diff --git a/CMakeLists.txt b/CMakeLists.txt index c75f3e4..e24be0c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,15 +1,21 @@ cmake_minimum_required(VERSION 2.8 FATAL_ERROR) -find_package(PCL 1.7 REQUIRED) - +set(PCL_DIR "/usr/local/share/pcl-1.8") +#find_package(PCL 1.9 REQUIRED HINTS "~/local/") +find_package(PCL 1.7 REQUIRED PATHS "./" NO_DEFAULT_PATH) +# find_package(PCL 1.7 REQUIRED PATHS "./") list(REMOVE_ITEM PCL_LIBRARIES "vtkproj4") -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fopenmp") -include_directories(${PCL_INCLUDE_DIRS} include) +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -O3 -DNDEBUG -fopenmp") + +message("\nPCL include: \n${PCL_INCLUDE_DIRS}\n") +include_directories("./pcl-1.7;/usr/include/eigen3;~/local/flann/include;" include) + link_directories(${PCL_LIBRARY_DIRS}) add_definitions(${PCL_DEFINITIONS} -O3 -DNDEBUG -DPCL_NO_PRECOMPILE) +add_executable (pc_pipeline src/modules.cpp src/utils.cpp src/read_config.cpp src/pc_pipeline.cpp) +target_link_libraries (pc_pipeline ${PCL_LIBRARIES}) -add_executable (pc-registration src/utils.cpp src/pc-registration.cpp) -target_link_libraries (pc-registration ${PCL_LIBRARIES}) +set_property(TARGET pc_pipeline PROPERTY CXX_STANDARD 11) -set_property(TARGET pc-registration PROPERTY CXX_STANDARD 11) +SET(EXECUTABLE_OUTPUT_PATH .././bin) \ No newline at end of file diff --git a/Makefile b/Makefile new file mode 100644 index 0000000..0469c8b --- /dev/null +++ b/Makefile @@ -0,0 +1,16 @@ +BUILD_DIR = ./build +BIN_DIR = ./bin + +.PHONY:build + +build: + mkdir $(BUILD_DIR); cd $(BUILD_DIR); cmake ..; make; + +clean: + rm -rf build/*; + +clean_result: + rm -rf result/result* + +run: + cd $(BIN_DIR); ./pc_pipeline \ No newline at end of file diff --git a/bin/config.txt b/bin/config.txt new file mode 100644 index 0000000..1fdf80e --- /dev/null +++ b/bin/config.txt @@ -0,0 +1,46 @@ +[File Directory Parameters] +Dataset_Directory: ../sample_data/ +Result_Directory: ../result/ + +[Normal Estimation Parameters] +Normal_Search_Radius: 0.75 +Normal_Use_Customized_KDTree: true +Normal_Max_Leaf_Size: 64 + + +[Key Point Detection Parameters] +Key_Point_Detection_Module: NARF + + +[Feature Description Parameters] +Feature_Search_Radius: 0.85 +Feature_Module: SHOT + + +[Correspondence Estimation Parameters] +Corr_Est_Use_Reciprocal_Search: true + + +[Correspondence Rejection Parameters] +Ransac_Threshold: 0.2 +Ransac_Max_Iteration: 10000 + + +[ICP Parameters] +ICP_Solver: SVD +ICP_Max_Iteration: 15 +ICP_Use_Ransac: true +ICP_Use_Reciprocal_Search: true + +ICP_Transformation_Epsilon: 1e-9 +ICP_Max_Correspondence_Distance: 1.2 +ICP_Euclidean_Fitness_Epsilon: 1e-6 +ICP_Ransac_Outlier_Rejection_Threshold: 120 + +ICP_Use_Customized_KDTree: true +ICP_Max_Leaf_Size: 32 + +[Approximation Search Parameters] +Approx_Radius_Search_Para: 0 +Approx_Nearest_Search_Para: 0 +Save_Approx_Data: false \ No newline at end of file diff --git a/build/run.py b/build/run.py deleted file mode 100755 index 03dd47c..0000000 --- a/build/run.py +++ /dev/null @@ -1,67 +0,0 @@ -#!/home/nile/anaconda3/bin/python -import os - -program = "./pc-registration" - -use_keypoint = str(0) - -normal_R = str(0.45) -FPFH_R = str(0.55) -ransac_threshold = str(0.20) -icp_transEps = str(1e-9) -icp_EuclFitEps = str(1e-6) -corrs_d=1.20 -out_mul=100 -icp_corresDist = str(float(corrs_d)) -icp_outlThresh = str(float(corrs_d * out_mul)) - -dataset = "../Kitti/Data/00/velodyne/" - -kernel_keyPoints = str('NARF') -kernel_descriptors = str('SHOT') -kernel_corrEst = str('corrEst') -kernel_corrRej = str('corrRej') - -flag_reciprocal = str('True') - -icp_solver = str("SVD") -icp_flag_ransac=str("True") -icp_flag_reciprocal= str("True") - -### mkdir -max_dir_num=0 -for i in os.listdir("../"): - # print(i) - if "result" in i: - if max_dir_num < int(i[6:]): - max_dir_num = int(i[6:]) -result_dir_num = max_dir_num + 1 -result_dir = "../result" + str(result_dir_num) + "/" - -# mkdir && create files -if not os.path.exists(result_dir): - print("mkdir " + result_dir) - os.mkdir(result_dir) - -result_file = result_dir + "pose_result_kitti.txt" -icp_delta_file = result_dir + "icp_delta.txt" -ransac_delta_file = result_dir + "ransac_delta.txt" -stage_time_file = result_dir + "stage_time.txt" -kdtree_time_file = result_dir + "kdtree_time.txt" - -### mkdir ends - -cmd = program + ' ' + normal_R + ' ' + FPFH_R + ' ' + \ -ransac_threshold + ' ' + icp_transEps + ' ' + icp_corresDist + ' ' + \ -icp_EuclFitEps + ' ' + icp_outlThresh + ' ' + result_file + ' ' + stage_time_file + \ -' ' + dataset + ' ' + ransac_delta_file + ' ' + icp_delta_file + ' ' + use_keypoint + \ -' ' + kernel_keyPoints + ' ' + kernel_descriptors + ' ' + kernel_corrEst + ' ' + kernel_corrRej + \ -' ' + flag_reciprocal + ' '+ icp_solver + ' ' + icp_flag_ransac + ' ' + icp_flag_reciprocal + \ -' ' + kdtree_time_file - -f = open(result_dir + "params.txt", "w+") -f.write(cmd) -f.close() - -print(cmd) -os.system(cmd) diff --git a/include/modules.h b/include/modules.h new file mode 100644 index 0000000..96a3212 --- /dev/null +++ b/include/modules.h @@ -0,0 +1,32 @@ +#ifndef MODULES_H +#define MODULES_H + +#include "typedefs.h" + +extern "C" { + +void filter(FeatureCloud &cloud); +void downSample(FeatureCloud &cloud, float gridsize); + +void keyPointsNARF(FeatureCloud &cloud); +void keyPointsSIFT(FeatureCloud &cloud); +void keyPointsHARRIS(FeatureCloud &cloud); + +void constructPointNormal(FeatureCloud &source_cloud, FeatureCloud &target_cloud); +void computeSurfaceNormals (FeatureCloud &cloud, std::vector &LF_points_counter, \ + std::vector &LF_operations_counter); + +void computeFeatures_FPFH (FeatureCloud &cloud, float R); +void computeFeatures_SHOT (FeatureCloud &cloud, float R); + +void estimateCorrespondence(FeatureCloud &source_cloud, FeatureCloud &target_cloud, \ + pcl::Correspondences &all_corres); +void rejectCorrespondences(FeatureCloud &source_cloud, FeatureCloud &target_cloud,\ + pcl::Correspondences &correspondences, pcl::Correspondences &inliers, \ + Result *result); +void iterativeClosestPoints(FeatureCloud &source_cloud, FeatureCloud &target_cloud, Result *result, \ + pcl::Correspondences &inliers, std::vector &LF_points_counter, std::vector &LF_operations_counter); + +} + +#endif \ No newline at end of file diff --git a/include/read_config.h b/include/read_config.h new file mode 100644 index 0000000..43db3ba --- /dev/null +++ b/include/read_config.h @@ -0,0 +1,93 @@ +#include +#include +#include +#include +#include +#include + +// configuration file class +class Config +{ + +protected: + // seperator between key and value + std::string m_Comment; + // seperator between value and comments + std::string m_Delimiter; + // extracted keys and values + std::map m_Contents; + // map iterator + typedef std::map::const_iterator mapci; + +public: + + Config(std::string filename, std::string delimiter = ":", std::string comment = "#"); + Config(); + + template + T Read(const std::string &in_key) const; + + template + T Read(const std::string &in_key, const T &in_value) const; + +private: + + friend std::istream &operator >> (std::istream &is, Config &cf); + + template + static T string_as_T(const mapci &p); + + static void Trim(std::string &inout_s); + + struct File_Not_Found + { + std::string filename; + File_Not_Found(const std::string &filename_ = std::string()) + :filename(filename_){} + }; + + struct Key_Not_Found + { + std::string key; + Key_Not_Found(const std::string &key_ = std::string()) + :key(key_){} + }; + +}; + +template +T Config::string_as_T(const mapci &p) +{ + T t; + std::istringstream ist(p->second); + + if (typeid(t) == typeid(bool)) // if key is bool type + { + ist >> std::boolalpha >> t; + std::cout << p->first << " : " << t << std::endl; + return t; + } + else if(ist >> t) // if key has a value + { + std::cout << p->first << " : " << t << std::endl; + return t; + } + else + { + std::cout << "Value For Key " << p->first << " Is Invalid!" << std::endl; + exit(-1); + } +} + +template +T Config::Read(const std::string &key, const T &value) const +{ + mapci p = m_Contents.find(key); + if (p == m_Contents.end()) + { + std::cout << "Key " << key << " Not Found!" << std::endl; + throw Key_Not_Found(key); + } + else + return string_as_T(p); +} \ No newline at end of file diff --git a/include/typedefs.h b/include/typedefs.h index e8faa8b..891229a 100755 --- a/include/typedefs.h +++ b/include/typedefs.h @@ -1,5 +1,3 @@ -/* */ - #ifndef TYPEDEFS_H #define TYPEDEFS_H @@ -12,6 +10,7 @@ #include #include #include +#include #include #include @@ -21,36 +20,25 @@ #include #include -//filters +// Filters #include #include #include -// key points -// #include +// Key-point modules #include #include #include +#include +#include #include #include #include -#include -#include -#include -#include -// #include #include -// #include - -//SIFT keypoints -#include - -//Harris keypoints -#include -// registration +// Registration modules #include #include @@ -66,9 +54,48 @@ #include #include -//visualizer -// #include -// #define pause printf("Press Enter key to continue..."); fgetc(stdin); +/** global variable definition**/ +extern std::string g_DATASET_DIR; // Dataset directory +extern std::string g_RESULT_DIR; // Result directory + +// Normal Estimation Parameters +extern float g_NORMAL_SEARCH_RADIUS; +extern bool g_NORMAL_USE_CUSTOMIZED_KDTREE; +extern int g_NORMAL_MAX_LEAF_SIZE; + +// Key Point Detection Parameters +extern std::string g_KEYPOINTS_MODULE; + +// Feature Description Parameters +extern float g_FEATURE_SEARCH_RADIUS; +extern std::string g_FEATURE_MODULE; + +// Correspondence Estimation Parameters +extern bool g_CORR_EST_USE_RECIPROCAL_SEARCH; + +// Correspondence Rejection Parameters +extern float g_RANSAC_THRESHOLD; +extern int g_RANSAC_MAX_ITERATION; + +// ICP Parameters +extern std::string g_ICP_SOLVER; +extern int g_ICP_MAX_ITERATION; +extern bool g_ICP_USE_RANSAC; +extern bool g_ICP_USE_RECIPROCAL_SEARCH; + +extern float g_ICP_TRANSFORMATION_EPSILON; +extern float g_ICP_MAX_CORRESPONDENCE_DISTANCE; +extern float g_ICP_EUCLIDEAN_FITNESS_EPSILON; +extern float g_ICP_RANSAC_OUTLIER_REJECTION_THRESHOLD; + +extern bool g_ICP_USE_CUSTOMIZED_KDTREE; +extern int g_ICP_MAX_LEAF_SIZE; + +extern float g_APPROX_RADIUS_SEARCH_PARA; +extern float g_APPROX_NEAREST_SEARCH_PARA; + +extern bool g_SAVE_APPROX_DATA; + typedef pcl::PointXYZ PointT; typedef pcl::PointCloud PointCloud; @@ -79,31 +106,16 @@ typedef pcl::PointNormal PointNormal; typedef pcl::PointCloud PointCloudNormal; typedef pcl::Correspondences Correspondences; - typedef pcl::PointCloud SurfaceNormals; typedef pcl::FPFHSignature33 FPFH_FeatureT; -typedef pcl::VFHSignature308 VFH_FeatureT; -typedef pcl::Histogram<153> SpinImage_FeatureT; -typedef pcl::ShapeContext1980 threeDSC_FeatureT; -// typedef pcl::UniqueShapeContext1960 USC_FeatureT; -typedef pcl::SHOT352 SHOT_FeatureT; -// typedef pcl::PrincipalRadiiRSD RSD_FeatureT; - - typedef pcl::PointCloud FPFH_Features; -typedef pcl::PointCloud VFH_Features; -typedef pcl::PointCloud> SpinImage_Features; -typedef pcl::PointCloud threeDSC_Features; -// typedef pcl::PointCloud USC_Features; + +typedef pcl::SHOT352 SHOT_FeatureT; typedef pcl::PointCloud SHOT_Features; -// typedef pcl::PointCloud RSD_Features; typedef pcl::search::KdTree SearchMethod; -typedef pcl::PFHSignature125 PFH_FeatureT; -typedef pcl::PointCloud PFH_Features; - // A struct for storing alignment results struct Result { @@ -115,266 +127,162 @@ struct Result // SIFT namespace pcl { - template<> - struct SIFTKeypointFieldSelector - { - inline float - operator () (const PointXYZ & p) const - { - return p.z; - } - }; + template<> + struct SIFTKeypointFieldSelector + { + inline float + operator () (const PointXYZ & p) const + { + return p.z; + } + }; } -/* - Representation of Point Cloud Data -*/ +/************************************* + Customized Point Cloud Data Structure +*************************************/ class FeatureCloud { public: - FeatureCloud () {} - - ~FeatureCloud () {} - - void - setInputCloud (PointCloud::Ptr xyz) - { - xyz_ = xyz; - } - - void - loadInputCloud (const std::string &pcd_file) - { - xyz_ = PointCloud::Ptr (new PointCloud); - pcl::io::loadPCDFile (pcd_file, *xyz_); - } - - // Return the pointer to the cloud (PointCloud Type). - PointCloud::Ptr - getPointCloud () const - { - return (xyz_); - } - - // Set key point cloud (PointCloud Type). - void - setKeyPoints (PointCloud::Ptr xyz_key) - { - xyz_key_ = xyz_key; - } - - // Return the pointer to the key point cloud (PointCloud Type). - PointCloud::Ptr - getKeyPoints () const - { - return (xyz_key_); - } - - // Set point cloud with normal(PointCloudNormal Type). - void - setPointCloudNormal (PointCloudNormal::Ptr xyzn) - { - xyzn_ = xyzn; - } - - // Return the pointer to the Point Cloud with Normal - // (PointCloudNormal Type). - PointCloudNormal::Ptr - getPointCloudNormal () const - { - return (xyzn_); - } - - // Set key point cloud (PointCloud Type). - void - setKeyPoint_indices (pcl::PointIndices::Ptr key_indices) - { - key_indices_ = key_indices; - } - - // Return the pointer to the key point cloud (PointCloud Type). - pcl::PointIndices::Ptr - getKeyPoint_indices () const - { - return (key_indices_); - } - - // Set initially aligned point cloud (PointCloud Type). - void - setTransformedCloud (PointCloud::Ptr xyz_transformed) - { - xyz_transformed_ = xyz_transformed; - } - // Return the pointer to initially aligned cloud. - PointCloud::Ptr - getTransformedCloud () const - { - return (xyz_transformed_); - } - - // Set Normals - void setSurfaceNormals (SurfaceNormals::Ptr normals) - { - normals_ = normals; - } - // Get the pointer to the cloud of 3D surface normals. - SurfaceNormals::Ptr - getSurfaceNormals () const - { - return (normals_); - } - - // Set FPFH features. - void setFeatures_FPFH (FPFH_Features::Ptr fpfh_features) - { - fpfh_features_ = fpfh_features; - } - - // Set PFH features. - void setFeatures_PFH (PFH_Features::Ptr pfh_features) - { - pfh_features_ = pfh_features; - } - - // Set VFH features. - void setFeatures_VFH (VFH_Features::Ptr vfh_features) - { - vfh_features_ = vfh_features; - } - - // Set SpinImage features. - void setFeatures_SpinImage (SpinImage_Features::Ptr spinimage_features) - { - spinimage_features_ = spinimage_features; - } - - // Set 3DSC features. - void setFeatures_3DSC (threeDSC_Features::Ptr threedsc_features) - { - threedsc_features_ = threedsc_features; - } - - // // Set USC features. - // void setFeatures_USC (USC_Features::Ptr usc_features) - // { - // usc_features_ = usc_features; - // } - - // Set SHOT features. - void setFeatures_SHOT (SHOT_Features::Ptr shot_features) - { - shot_features_ = shot_features; - } - - // // Set RSD features. - // void setFeatures_RSD (RSD_Features::Ptr rsd_features) - // { - // rsd_features_ = rsd_features; - // } - - // Get the pointer to the cloud of feature descriptors (FPFH). - FPFH_Features::Ptr - getFeatures_FPFH () const - { - return (fpfh_features_); - } - - // Get a pointer to the cloud of feature descriptors (PFH). - PFH_Features::Ptr - getFeatures_PFH () const - { - return (pfh_features_); - } - - // Get a pointer to the cloud of feature descriptors (VFH). - VFH_Features::Ptr - getFeatures_VFH () const - { - return (vfh_features_); - } - - // Get a pointer to the cloud of feature descriptors (SpinImage). - SpinImage_Features::Ptr - getFeatures_SpinImage () const - { - return (spinimage_features_); - } - - // Get a pointer to the cloud of feature descriptors (3DSC). - threeDSC_Features::Ptr - getFeatures_3DSC () const - { - return (threedsc_features_); - } - - // // Get a pointer to the cloud of feature descriptors (USC). - // USC_Features::Ptr - // getFeatures_USC () const - // { - // return (usc_features_); - // } - - // Get a pointer to the cloud of feature descriptors (SHOT). - SHOT_Features::Ptr - getFeatures_SHOT () const - { - return (shot_features_); - } - - // // Get a pointer to the cloud of feature descriptors (RSD). - // RSD_Features::Ptr - // getFeatures_RSD () const - // { - // return (rsd_features_); - // } + FeatureCloud () {} + + ~FeatureCloud () {} + + // Sets the pointer to the point cloud. + void setInputCloud (PointCloud::Ptr xyz) + { + xyz_ = xyz; + } + + // Loads Point Cloud from a PCD file. + void loadInputCloud (const std::string &pcd_file) + { + xyz_ = PointCloud::Ptr (new PointCloud); + pcl::io::loadPCDFile (pcd_file, *xyz_); + } + + // Returns the pointer to the cloud (PointCloud Type). + PointCloud::Ptr getPointCloud () const + { + return (xyz_); + } + + // Sets key point cloud (PointCloud Type). + void setKeyPoints (PointCloud::Ptr xyz_key) + { + xyz_key_ = xyz_key; + } + + // Returns the pointer to the key point cloud (PointCloud Type). + PointCloud::Ptr getKeyPoints () const + { + return (xyz_key_); + } + + // Sets the pointer to the PointCloudNormal Type. + void setPointCloudNormal (PointCloudNormal::Ptr xyzn) + { + xyzn_ = xyzn; + } + + // Returns the pointer to the PointCloudNormal Type + PointCloudNormal::Ptr getPointCloudNormal () const + { + return (xyzn_); + } + + // Sets the pointer to the key-point cloud (PointCloud Type). + void setKeyPoint_indices (pcl::PointIndices::Ptr key_indices) + { + key_indices_ = key_indices; + } + + // Returns the pointer to the key-point cloud (PointCloud Type). + pcl::PointIndices::Ptr getKeyPoint_indices () const + { + return (key_indices_); + } + + // Sets the pointer to the point cloud transformed by the initial + // tranformation matrix (PointCloud Type). + void setTransformedCloud (PointCloud::Ptr xyz_transformed) + { + xyz_transformed_ = xyz_transformed; + } + + // Returns the pointer to the point cloud transformed by the initial + // tranformation matrix (PointCloud Type). + PointCloud::Ptr getTransformedCloud () const + { + return (xyz_transformed_); + } + + // Sets pointer to Normals. + void setSurfaceNormals (SurfaceNormals::Ptr normals) + { + normals_ = normals; + } + // Gets the pointer to the cloud of 3D surface normals. + SurfaceNormals::Ptr getSurfaceNormals () const + { + return (normals_); + } + + // Sets a pointer to the feature descriptor data (FPFH type). + void setFeatures_FPFH (FPFH_Features::Ptr fpfh_features) + { + fpfh_features_ = fpfh_features; + } + + // Sets a pointer to the feature descriptor data (SHOT type). + void setFeatures_SHOT (SHOT_Features::Ptr shot_features) + { + shot_features_ = shot_features; + } + + // Gets the pointer to the feature descriptor data (FPFH type). + FPFH_Features::Ptr getFeatures_FPFH () const + { + return (fpfh_features_); + } + + // Gets a pointer to the feature descriptor data (SHOT type). + SHOT_Features::Ptr getFeatures_SHOT () const + { + return (shot_features_); + } private: - // Point Cloud Pointer - PointCloud::Ptr xyz_; - - // Point Cloud Pointer (Key Points) - PointCloud::Ptr xyz_key_; - - // Transformed Point Cloud (by the Initial Matrix) - PointCloud::Ptr xyz_transformed_; - - // Key point indices - pcl::PointIndices::Ptr key_indices_; - - // Point Cloud with Normal - PointCloudNormal::Ptr xyzn_; - - // Key points with Normal - PointCloudNormal::Ptr xyzn_key_; + // Pointer to the Original Point Cloud + PointCloud::Ptr xyz_; - /*Features*/ + // Pointer to the Key points + PointCloud::Ptr xyz_key_; - // Normals - SurfaceNormals::Ptr normals_; + // Pointer to the Point Cloud transformed by the Initial Matrix + PointCloud::Ptr xyz_transformed_; - // Feature: FPFH - FPFH_Features::Ptr fpfh_features_ ; + // PCL data structure: point indices (for key points) + pcl::PointIndices::Ptr key_indices_; - // Feature: PFH - PFH_Features::Ptr pfh_features_; + // PCL data structure: Point Cloud with Normal + PointCloudNormal::Ptr xyzn_; - //Feature: VFH - VFH_Features::Ptr vfh_features_; + // PCL data structure: Key points with Normal + PointCloudNormal::Ptr xyzn_key_; - //Feature: SpinImage - SpinImage_Features::Ptr spinimage_features_; + /* Features */ - //Feature: 3DSC - threeDSC_Features::Ptr threedsc_features_; + // Surface Normals + SurfaceNormals::Ptr normals_; - // //Feature: USC - // USC_Features::Ptr usc_features_; + // Feature Descriptor: FPFH + FPFH_Features::Ptr fpfh_features_ ; - //Feature: SHOT - SHOT_Features::Ptr shot_features_; + // Feature Descriptor: SHOT + SHOT_Features::Ptr shot_features_; - // //Feature: RSD - // RSD_Features::Ptr rsd_features_; + // Add more feature descriptors if needed }; -#endif +#endif \ No newline at end of file diff --git a/include/utils.h b/include/utils.h index 0f0eb4a..3d18d79 100755 --- a/include/utils.h +++ b/include/utils.h @@ -4,101 +4,77 @@ #include "typedefs.h" extern "C" { - -void filter(const PointCloud::Ptr cloud_src, const PointCloud::Ptr filtered, float &nn_time, float &bd_time); -void downSample(const PointCloud::Ptr cloud_src, const PointCloud::Ptr filtered, float gridsize); -void pointsNumberCheck(FeatureCloud &cloud); -void detectKeyPoints(std::string kernel_keyPoints, const PointCloud::Ptr cloud_ptr, const PointCloud::Ptr keyPoints_cal_ptr); -void describeFeatures(std::string kernel_descriptors, FeatureCloud &cloud, float R, float &nn_time, float &bd_time); +void readConfigFile(std::string file_name); +void makeResultFolder(std::string &result_dir); + +void detectKeyPoints(FeatureCloud &cloud); +void describeFeatures(FeatureCloud &cloud); +void removeNANFromNormal(FeatureCloud &cloud); void removeNANFromFPFH(FPFH_Features::Ptr descriptor, FPFH_Features::Ptr nanremoved, FeatureCloud &cloud); -void keyPointsNARF(const PointCloud::Ptr cloud_src, const PointCloud::Ptr keyPoints_NARF); -void keyPointsSIFT(const PointCloud::Ptr cloud_src, const PointCloud::Ptr keyPoints_SIFT); -void keyPointsHARRIS(const PointCloud::Ptr cloud_src, const PointCloud::Ptr keyPoints_Harris); - -// for parameters finetune only -void keyPointsSIFTtest(const PointCloud::Ptr cloud_src, const PointCloud::Ptr keyPoints_SIFT, float min_scale, int n_octaves, int n_scales_per_octave, float min_contrast); -void keyPointsHARRIStest(const PointCloud::Ptr cloud_src, const PointCloud::Ptr keyPoints_Harris, float radius, float threshold); -// void computeSurfaceNormals (FeatureCloud &cloud, int K); -// void computeFeatures_FPFH (FeatureCloud &cloud, int K); -// void computeFeatures (FeatureCloud &cloud, int normal_K, int FPFH_K); - -void computeSurfaceNormals (FeatureCloud &cloud, float R, float &nn_time, float &bd_time); -void computeFeatures_FPFH (FeatureCloud &cloud, float R, float &nn_time, float &bd_time); -void computeFeatures_VFH (FeatureCloud &cloud, float R); -void computeFeatures_SpinImage (FeatureCloud &cloud, float R); -void computeFeatures_3DSC (FeatureCloud &cloud, float R, float &nn_time, float &bd_time); -// void computeFeatures_USC (FeatureCloud &cloud, float R); -void computeFeatures_SHOT (FeatureCloud &cloud, float R, float &nn_time, float &bd_time); -// void computeFeatures_RSD (FeatureCloud &cloud, float R); - -void computeFeatures (FeatureCloud &cloud, float normal_R, float FPFH_R); -void construct_PointNormal(FeatureCloud &source_cloud, FeatureCloud &target_cloud, \ - int use_keypoints); - -void getIndices (PointCloud::Ptr cloudin, PointCloud::Ptr keypoints_cal, \ - PointCloud::Ptr keypoints_real, pcl::PointIndices::Ptr indices); - -void correspondence_estimation(std::string kernel_descriptors, std::string flag_reciprocal, FeatureCloud &source_cloud, FeatureCloud &target_cloud,\ - pcl::Correspondences &all_corres, float &nn_time, float &bd_time); -void correspondences_rejection(FeatureCloud &source_cloud, FeatureCloud &target_cloud,\ - pcl::Correspondences &correspondences, pcl::Correspondences &inliers, \ - Result *result, int N, float threshold, int use_keypoints); -void iterative_closest_points(std::string solver, std::string flag_reciprocal, std::string flag_ransac, FeatureCloud &source_cloud, FeatureCloud &target_cloud,\ - Result *result, float transEps, float corresDist, float EuclFitEps, float outlThresh, \ - int use_keypoints, pcl::Correspondences &inliers, float &nn_time, float &bd_time); - -void keyPoint_dist(FeatureCloud &source_cloud, FeatureCloud &target_cloud); - -bool string_sort (std::string i,std::string j); -void listdir(std::string path_dir, std::vector &files); -void load_bin(std::string infile, FeatureCloud &cloud); - -/* -boost::shared_ptr -visualize_correspondences (const PointCloudPtr points1, const PointCloudPtr keypoints1, - const PointCloudPtr points2, const PointCloudPtr keypoints2, - Correspondences &correspondences); -*/ +void keyPointsNARF(FeatureCloud &cloud); +void keyPointsSIFT(FeatureCloud &cloud); +void keyPointsHARRIS(FeatureCloud &cloud); + +void getIndices (FeatureCloud &cloud); + +bool sortString (std::string i,std::string j); +void listDir(std::string path_dir, std::vector &files); +void loadBINFile(std::string infile, FeatureCloud &cloud); +void loadTXTFile(std::string infile, FeatureCloud &cloud); +void writeMatrix(std::ofstream &stream_name, std::string file_name, Eigen::Matrix4f &stream_data); +void printMatrix(std::string matrix_name, Eigen::Matrix4f &matrix); + +} + +template +void writeVector(std::ofstream &stream_name, std::string file_name, std::vector &stream_data) +{ + stream_name.open (file_name, std::fstream::app); + + for(int i = 0; i < stream_data.size(); i ++) + { + stream_name << ("%lf", stream_data[i]); + stream_name << " "; + } + stream_name << "\n"; + stream_name.close(); + stream_data.clear(); } template void removeNANFromDescriptor(Feature_Descriptor& feature_descriptor, Feature_Descriptor& nanremoved, FeatureCloud &cloud) { - PointCloud::Ptr keyPoints_ptr_nanremoved(new PointCloud); - pcl::PointIndices::Ptr indices_ptr_nanremoved(new pcl::PointIndices); - - for (int i=0; ipoints.size();i++) - { - //std::cout << feature_descriptor->points[i].histogram[0] << std::endl; - //if (Feature_Descriptor == "SHOT") - float p = feature_descriptor->points[i].descriptor[0]; - //if (Feature_Descriptor == "FPFH") - // float p = feature_descriptor->points[i].histogram[0]; - if (p != p) - { - continue; - } - else - { - nanremoved->push_back(feature_descriptor->points[i]); - keyPoints_ptr_nanremoved->push_back(cloud.getKeyPoints()->points[i]); - indices_ptr_nanremoved->indices.push_back((cloud.getKeyPoint_indices())->indices[i]); - } - } - - if(feature_descriptor->points.size() != nanremoved->points.size()) - { - cloud.setKeyPoints(keyPoints_ptr_nanremoved); - cloud.setKeyPoint_indices(indices_ptr_nanremoved); - } - - std::cout << "Remove NAN From Feature Descriptors:" << std::endl; - std::cout << (feature_descriptor->points.size() - nanremoved->points.size()) << " Feature Descriptors Are Removed: " \ - << feature_descriptor->points.size() << "->" << nanremoved->points.size() << std::endl << std::endl; + PointCloud::Ptr keyPoints_ptr_nanremoved(new PointCloud); + pcl::PointIndices::Ptr indices_ptr_nanremoved(new pcl::PointIndices); + + for (int i=0; ipoints.size();i++) + { + + float p = feature_descriptor->points[i].descriptor[0]; + if (p != p) + { + continue; + } + else + { + nanremoved->push_back(feature_descriptor->points[i]); + keyPoints_ptr_nanremoved->push_back(cloud.getKeyPoints()->points[i]); + indices_ptr_nanremoved->indices.push_back((cloud.getKeyPoint_indices())->indices[i]); + } + } + + if(feature_descriptor->points.size() != nanremoved->points.size()) + { + cloud.setKeyPoints(keyPoints_ptr_nanremoved); + cloud.setKeyPoint_indices(indices_ptr_nanremoved); + } + + std::cout << "Remove NAN From Feature Descriptors:" << std::endl; + std::cout << (feature_descriptor->points.size() - nanremoved->points.size()) << " Feature Descriptors Are Removed: " \ + << feature_descriptor->points.size() << "->" << nanremoved->points.size() << std::endl << std::endl; } -#endif - +#endif \ No newline at end of file diff --git a/legacy/Registration-pipeline/CMakeLists.txt b/legacy/Registration-pipeline/CMakeLists.txt deleted file mode 100644 index cc6d8c5..0000000 --- a/legacy/Registration-pipeline/CMakeLists.txt +++ /dev/null @@ -1,12 +0,0 @@ -cmake_minimum_required(VERSION 2.8 FATAL_ERROR) - -find_package(PCL 1.7 REQUIRED) - -include_directories(${PCL_INCLUDE_DIRS} include) -link_directories(${PCL_LIBRARY_DIRS}) -add_definitions(${PCL_DEFINITIONS}) - -add_executable (registration src/utils.cpp src/registration.cpp) -target_link_libraries (registration ${PCL_LIBRARIES}) - -set_property(TARGET registration PROPERTY CXX_STANDARD 11) diff --git a/legacy/Registration-pipeline/README.md b/legacy/Registration-pipeline/README.md deleted file mode 100644 index e64c811..0000000 --- a/legacy/Registration-pipeline/README.md +++ /dev/null @@ -1,56 +0,0 @@ -### Point Cloud Registration -Pairwise registration of point cloud data using PCL. - -------------------------------- -#### Overview - -In the *src* directory are: -- *registration.cpp*: pairwise registration pipeline (in the main function); -- *utils.cpp*: implementation of individual modules (e.g. RANSAC, ICP) of the pipeline; - -In the *include* directory are function declarations and definitions. - -------------------------------- -### Usage -To run the pipeline:
-1. Compile: -``` -mkdir build -cmake.. -cd build && make -``` -2. Execute: -to execute, several parameters need to be passed in as arguments: -``` -./registration $[NORMAL SEARCH PARAMETER] $[FPFH SEARCH PARAMTER] $[RANSAC THRESHOLD] $[ICP TRANSFORMATION EPSILON] $[ICP CORRESPONDENCE DISTANCE] $[ICP EUCLIDEAN EPSILON] $[ICP OUTLIER THRESHOLD] $[POSE MATRIX FILE] $[PATH TO DATASET] -``` -It is convenient to invoke the executable using Python, below is an example: -``` -import os - -program='registration' - -normal_param = str(FLOAT) // Radius Search -fpfh_param = str(FLOAT) -// if you use K-search, the cpp source file needs to be modified and re-compiled - -ransac_threshold = str(FLOAT) -icp_trans=str(FLOAT) -icp_corresD=str(FLOAT) -icp_eucli=str(FLOAT) -icp_outlierT=str(FLOAT) - -pose_path=$PATH_TO_RESULT_FILE -dataset_path=$PATH_TO_DATASET - -cmd = './' + program + ' ' + normal_param + ' ' + fpfh_param + ' ' + ransac_threshold + ' ' \ -+ icp_trans + ' ' + icp_corresD + ' ' + icp_eucli + ' ' + icp_outlierT + ' ' + \ -pose_path + ' ' + dataset_path - -os.system(cmd) -``` - -------------------------------- -### To-do: -- [ ] Add more modules for different stages in the pipeline; -- [ ] Figure out a better way to pass the arguments; diff --git a/legacy/Registration-pipeline/include/typedefs.h b/legacy/Registration-pipeline/include/typedefs.h deleted file mode 100644 index 48771ae..0000000 --- a/legacy/Registration-pipeline/include/typedefs.h +++ /dev/null @@ -1,228 +0,0 @@ -/* - Libraries and Classes. -*/ - -#ifndef TYPEDEFS_H -#define TYPEDEFS_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include -#include - -//filters -#include -#include -#include - -// key points -#include -#include -#include -#include - -#include - -#include -#include - -//SIFT keypoints -#include - -// registration -#include - -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -//visualizer -#include -#define pause printf("Press Enter key to continue..."); fgetc(stdin); - -typedef pcl::PointXYZ PointT; -typedef pcl::PointCloud PointCloud; -typedef pcl::PointCloud::Ptr PointCloudPtr; -typedef pcl::PointCloud::ConstPtr PointCloudConstPtr; - -typedef pcl::Correspondences Correspondences; - -typedef pcl::PointCloud SurfaceNormals; - -typedef pcl::FPFHSignature33 FPFH_FeatureT; -typedef pcl::PointCloud FPFH_Features; - -typedef pcl::search::KdTree SearchMethod; - -typedef pcl::PFHSignature125 PFH_FeatureT; -typedef pcl::PointCloud PFH_Features; - -// A struct for storing alignment results -struct Result -{ - float fitness_score; - Eigen::Matrix4f final_transformation; - EIGEN_MAKE_ALIGNED_OPERATOR_NEW -}; - -// SIFT -namespace pcl -{ - template<> - struct SIFTKeypointFieldSelector - { - inline float - operator () (const PointXYZ & p) const - { - return p.z; - } - }; -} - -/* - Representation of Point Cloud Data -*/ -class FeatureCloud -{ - public: - FeatureCloud () {} - - ~FeatureCloud () {} - - void - setInputCloud (PointCloud::Ptr xyz) - { - xyz_ = xyz; - } - - void - loadInputCloud (const std::string &pcd_file) - { - xyz_ = PointCloud::Ptr (new PointCloud); - pcl::io::loadPCDFile (pcd_file, *xyz_); - } - - // Return the pointer to the cloud (PointCloud Type). - PointCloud::Ptr - getPointCloud () const - { - return (xyz_); - } - - // Set key point cloud (PointCloud Type). - void - setKeyPoints (PointCloud::Ptr xyz_key) - { - xyz_key_ = xyz_key; - } - - // Return the pointer to the key point cloud (PointCloud Type). - PointCloud::Ptr - getKeyPoints () const - { - return (xyz_key_); - } - - // Set key point cloud (PointCloud Type). - void - setKeyPoint_indices (pcl::PointIndices::Ptr key_indices) - { - key_indices_ = key_indices; - } - - // Return the pointer to the key point cloud (PointCloud Type). - pcl::PointIndices::Ptr - getKeyPoint_indices () const - { - return (key_indices_); - } - - // Set initially aligned point cloud (PointCloud Type). - void - setTransformedCloud (PointCloud::Ptr xyz_transformed) - { - xyz_transformed_ = xyz_transformed; - } - // Return the pointer to initially aligned cloud. - PointCloud::Ptr - getTransformedCloud () const - { - return (xyz_transformed_); - } - - // Set Normals - void setSurfaceNormals (SurfaceNormals::Ptr normals) - { - normals_ = normals; - } - // Get the pointer to the cloud of 3D surface normals. - SurfaceNormals::Ptr - getSurfaceNormals () const - { - return (normals_); - } - - // Set FPFH features. - void setFeatures_FPFH (FPFH_Features::Ptr fpfh_features) - { - fpfh_features_ = fpfh_features; - } - - // Get the pointer to the cloud of feature descriptors (FPFH). - FPFH_Features::Ptr - getFeatures_FPFH () const - { - return (fpfh_features_); - } - - // Get a pointer to the cloud of feature descriptors (PFH). - PFH_Features::Ptr - getFeatures_PFH () const - { - return (pfh_features_); - } - - private: - // Point Cloud Pointer - PointCloud::Ptr xyz_; - - // Point Cloud Pointer (Key Points) - PointCloud::Ptr xyz_key_; - - // Transformed Point Cloud (Initial Matrix) - PointCloud::Ptr xyz_transformed_; - - // Key point indices - pcl::PointIndices::Ptr key_indices_; - - /*Features*/ - // Normals - SurfaceNormals::Ptr normals_; - // Feature: FPFH - FPFH_Features::Ptr fpfh_features_ ; - // Feature: PFH - PFH_Features::Ptr pfh_features_; -}; - -#endif \ No newline at end of file diff --git a/legacy/Registration-pipeline/include/utils.h b/legacy/Registration-pipeline/include/utils.h deleted file mode 100644 index 9ff9b39..0000000 --- a/legacy/Registration-pipeline/include/utils.h +++ /dev/null @@ -1,44 +0,0 @@ -#ifndef UTILS_H -#define UTILS_H - -#include "typedefs.h" - -extern "C" { - -void filter(const PointCloud::Ptr cloud_src, const PointCloud::Ptr filtered); -void downSample(const PointCloud::Ptr cloud_src, const PointCloud::Ptr filtered, float gridsize); - -void narfKeyPoints(const PointCloud::Ptr cloud_src, const PointCloud::Ptr keyPoints_NARF); -void keyPointsSIFT(const PointCloud::Ptr cloud_src, const PointCloud::Ptr keyPoints_SIFT); -// void computeSurfaceNormals (FeatureCloud &cloud, int K); -// void computeFeatures_FPFH (FeatureCloud &cloud, int K); -// void computeFeatures (FeatureCloud &cloud, int normal_K, int FPFH_K); - -void computeSurfaceNormals (FeatureCloud &cloud, float R); -void computeFeatures_FPFH (FeatureCloud &cloud, float R); -void computeFeatures (FeatureCloud &cloud, float normal_R, float FPFH_R); - -void getIndices (PointCloud::Ptr cloudin, PointCloud::Ptr keypoints_cal, \ - PointCloud::Ptr keypoints_real, pcl::PointIndices::Ptr indices); - -void correspondence_estimation(FeatureCloud &source_cloud, FeatureCloud &target_cloud,\ - pcl::Correspondences &all_corres); -void correspondences_rejection(FeatureCloud &source_cloud, FeatureCloud &target_cloud,\ - pcl::Correspondences &correspondences, pcl::Correspondences &inliers, \ - Result *result, int N, float threshold); -void iterative_closest_points(FeatureCloud &source_cloud, FeatureCloud &target_cloud,\ - Result *result, float transEps, float corresDist, float EuclFitEps, float outlThresh); - -void keyPoint_dist(FeatureCloud &source_cloud, FeatureCloud &target_cloud); - -bool string_sort (std::string i,std::string j); -void listdir(std::string path_dir, std::vector &files); -void load_bin(std::string infile, FeatureCloud &cloud); - -boost::shared_ptr -visualize_correspondences (const PointCloudPtr points1, const PointCloudPtr keypoints1, - const PointCloudPtr points2, const PointCloudPtr keypoints2, - Correspondences &correspondences); - -} -#endif \ No newline at end of file diff --git a/legacy/Registration-pipeline/src/registration.cpp b/legacy/Registration-pipeline/src/registration.cpp deleted file mode 100644 index 29a4215..0000000 --- a/legacy/Registration-pipeline/src/registration.cpp +++ /dev/null @@ -1,134 +0,0 @@ -#include "typedefs.h" -#include "utils.h" - -int main(int argc, char **argv) -{ - std::vector path2bins; - std::queue clouds; // FeatureCloud is the class to represent Point Clouds - - // Taking module parameters from the arguments - std::vector arguments(argv, argv + argc); - // int normal_K = std::stoi(arguments[1]); - // int FPFH_K = std::stoi(arguments[2]); - float normal_R = std::stof(arguments[1]); - float FPFH_R = std::stof(arguments[2]); - - float ransac_threshold = std::stof(arguments[3]); - float icp_transEps = std::stof(arguments[4]); - float icp_corresDist = std::stof(arguments[5]); - float icp_EuclFitEps = std::stof(arguments[6]); - float icp_outlThresh = std::stof(arguments[7]); - - std::cout << "normal_R " << normal_R << std::endl; - std::cout << "FPFH_R " << FPFH_R << std::endl; - std::cout << "ransac_threshold " << ransac_threshold << std::endl; - std::cout << "icp_transEps " << icp_transEps << std::endl; - std::cout << "icp_corresDist " << icp_corresDist << std::endl; - std::cout << "icp_EuclFitEps " << icp_EuclFitEps << std::endl; - std::cout << "icp_outlThresh " << icp_outlThresh << std::endl; - - // Path to files where we store the results - const char * out_file2 = argv[8]; - // const char * dataset_dir = $PATH_TO_DATASET; - const char * dataset_dir = argv[9]; - - int index_start = 0; - // Initialize the final result matrix - Eigen::Matrix4f final_result_kitti = Eigen::Matrix4f::Identity(); - - // Start loading frame 0 - FeatureCloud cloud_; - listdir(dataset_dir, path2bins); // the path2bins contains frames (.bin) in a sorted order. - load_bin(path2bins[index_start], cloud_); - - clouds.push(cloud_); - - PointCloud::Ptr cloud_ptr = (clouds.front()).getPointCloud(); - PointCloud::Ptr keyPoints_ptr(new PointCloud); - PointCloud::Ptr keyPoints_cal_ptr(new PointCloud); - pcl::PointIndices::Ptr indices_ptr (new pcl::PointIndices); - - /* Modules in the pipeline are defined and implemented externally - (in a 'plug-and-play' fashion). - */ - filter(cloud_ptr, cloud_ptr); - // downSample(cloud_ptr, cloud_ptr, 0.1); - narfKeyPoints(cloud_ptr, keyPoints_cal_ptr); - // keyPointsSIFT(cloud_ptr, keyPoints_cal_ptr); - getIndices(cloud_ptr, keyPoints_cal_ptr, keyPoints_ptr, indices_ptr); - (clouds.front()).setKeyPoints(keyPoints_ptr); - (clouds.front()).setKeyPoint_indices(indices_ptr); - - computeFeatures((clouds.front()), normal_R, FPFH_R); - - for (int n=(index_start + 1); n < path2bins.size(); n++) - { - // Stage1: Load Point Clouds - FeatureCloud cloud_; - load_bin(path2bins[n], cloud_); - if (!(n == (index_start + 1))) - clouds.pop(); - clouds.push(cloud_); - - // Calculate normals and feature descriptors - PointCloud::Ptr cloud_ptr = (clouds.back()).getPointCloud(); - PointCloud::Ptr keyPoints_cal_ptr(new PointCloud); - PointCloud::Ptr keyPoints_ptr(new PointCloud); - pcl::PointIndices::Ptr indices_ (new pcl::PointIndices); - - filter(cloud_ptr, cloud_ptr); - // downSample(cloud_ptr, cloud_ptr, 0.1); - narfKeyPoints(cloud_ptr, keyPoints_cal_ptr); // calculate keypoint coordinates - // keyPointsSIFT(cloud_ptr, keyPoints_cal_ptr); - getIndices(cloud_ptr, keyPoints_cal_ptr, keyPoints_ptr, indices_); - // getIndices: match keypoint coordinates with points in the original point set - (clouds.back()).setKeyPoints(keyPoints_ptr); - (clouds.back()).setKeyPoint_indices(indices_); - computeFeatures(clouds.back(), normal_R, FPFH_R); // Compute normals and Fpfh - - // Stage3: Coorespondence Estimation - // (back, front): (source, target) - Correspondences all_correspondences; - Correspondences inliers; - - correspondence_estimation((clouds.back()), (clouds.front()), \ - all_correspondences); // (source, target) - - // Stage4: Coarse-alignment Correspondence Rejection - Result* init_result_ptr, init_result; - init_result_ptr = &init_result; - - // (source, target) - correspondences_rejection((clouds.back()), (clouds.front()), \ - all_correspondences, inliers, init_result_ptr, 1000, ransac_threshold); - // Stage5: Fine-alignment: Iterative Closest Point - Result* icp_result_ptr, icp_result; - icp_result_ptr = &icp_result; - - iterative_closest_points((clouds.back()), (clouds.front()), \ - icp_result_ptr, icp_transEps, icp_corresDist, \ - icp_EuclFitEps, icp_outlThresh); - - // Save results - Eigen::Matrix4f final_result = icp_result_ptr->final_transformation * \ - init_result_ptr->final_transformation; - final_result_kitti = final_result_kitti * final_result; - - ofstream myfile_kitti; - myfile_kitti.open (out_file2, fstream::app); - // Write the matrix into the pose file. - for(int i = 0; i < 3; i ++) - { - for(int j = 0; j < 4; j ++) - { - myfile_kitti << ("%lf", final_result_kitti(i,j)); - if (j != 4) - myfile_kitti << " "; - } - } - myfile_kitti << "\n"; - myfile_kitti.close(); - - } - return 0; -} \ No newline at end of file diff --git a/legacy/Registration-pipeline/src/utils.cpp b/legacy/Registration-pipeline/src/utils.cpp deleted file mode 100644 index c90586e..0000000 --- a/legacy/Registration-pipeline/src/utils.cpp +++ /dev/null @@ -1,367 +0,0 @@ -#include "typedefs.h" -#include "utils.h" - -void filter(const PointCloud::Ptr cloud_src, \ - const PointCloud::Ptr filtered) -{ - // std::cout << "Before Filtering:" << cloud_src->size() << std::endl; - pcl::StatisticalOutlierRemoval sor; - sor.setInputCloud(cloud_src); - sor.setMeanK(50); - sor.setStddevMulThresh(1.0); - sor.filter(*filtered); - // std::cout << "After Filtering:" << filtered->size() << std::endl; -} - -void downSample(const PointCloud::Ptr cloud_src, \ - const PointCloud::Ptr filtered, float gridsize) -{ - pcl::VoxelGrid grid; //VoxelGrid - grid.setLeafSize(gridsize, gridsize, gridsize); - // std::cout << "Before Downsampling:" << cloud_src->size() << std::endl; - grid.setInputCloud(cloud_src); - grid.filter(*filtered); - // std::cout << "After Downsampling: " << filtered->size() << std::endl; -} - -// Narf Key Point Detection -void narfKeyPoints(const PointCloud::Ptr cloud_src, \ - const PointCloud::Ptr keyPoints_NARF) -{ - //Parameters - float angular_resolution = 0.5f; - float support_size = 0.2f; - - PointCloud& point_cloud = *cloud_src; - pcl::PointCloud far_ranges; - pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME; - Eigen::Affine3f scene_sensor_pose (Eigen::Affine3f::Identity ()); - - angular_resolution = pcl::deg2rad (angular_resolution); - scene_sensor_pose = Eigen::Affine3f (Eigen::Translation3f (point_cloud.sensor_origin_[0], - point_cloud.sensor_origin_[1], - point_cloud.sensor_origin_[2])) * - Eigen::Affine3f (point_cloud.sensor_orientation_); - - // -----Create RangeImage from the PointCloud----- - float noise_level = 0.0; - float min_range = 0.0f; - int border_size = 1; - boost::shared_ptr range_image_ptr (new pcl::RangeImage); - - pcl::RangeImage& range_image = *range_image_ptr; - range_image.createFromPointCloud (point_cloud, angular_resolution, \ - pcl::deg2rad (360.0f), pcl::deg2rad (180.0f), \ - scene_sensor_pose, coordinate_frame, noise_level, min_range, border_size); - - range_image.integrateFarRanges (far_ranges); - - // -------------------------------- - // -----Extract NARF keypoints----- - // -------------------------------- - pcl::RangeImageBorderExtractor range_image_border_extractor; - pcl::NarfKeypoint narf_keypoint_detector (&range_image_border_extractor); - narf_keypoint_detector.setRangeImage (&range_image); - narf_keypoint_detector.getParameters ().support_size = support_size; - //narf_keypoint_detector.getParameters ().add_points_on_straight_edges = true; - //narf_keypoint_detector.getParameters ().distance_for_additional_points = 0.5; - - pcl::PointCloud keypoint_indices; - narf_keypoint_detector.compute (keypoint_indices); - std::cout << "Found "< sift; - pcl::PointCloud result; - - pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); - sift.setSearchMethod(tree); - sift.setScales(min_scale, n_octaves, n_scales_per_octave); - sift.setMinimumContrast(min_contrast); - - sift.setInputCloud(cloud_src); - sift.compute(result); - //std::cout << "Computing the SIFT points takes " << time.toc() / 1000 << "seconds" << std::endl; - std::cout << "No of SIFT points in the result are " << result.points.size() << std::endl; - - copyPointCloud(result, *keyPoints_SIFT); - std::cout << "SIFT points in the result are " << keyPoints_SIFT->points.size() << std::endl; -} - -// Compute the surface normals -void -computeSurfaceNormals (FeatureCloud &cloud, float R) -{ - SurfaceNormals::Ptr normals_ (new SurfaceNormals); - - pcl::NormalEstimation norm_est; - - norm_est.setInputCloud (cloud.getPointCloud()); - // norm_est.setIndices(cloud.getKeyPoint_indices()); - - pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); - norm_est.setSearchMethod(tree); - norm_est.setRadiusSearch(R); - // norm_est.setKSearch(35); - // norm_est.setKSearch(K); - norm_est.compute (*normals_); - - cloud.setSurfaceNormals(normals_); - // std::cout << "Normals:" << *normals_ << std::endl; -} - -// void -// computeFeatures_FPFH (FeatureCloud &cloud, int K) -// { - -// FPFH_Features::Ptr fpfh_features_ (new FPFH_Features); -// FPFH_Features::Ptr fpfh_features_key_ (new FPFH_Features); - -// pcl::FPFHEstimation fpfh_est; - -// fpfh_est.setInputCloud (cloud.getPointCloud()); -// fpfh_est.setInputNormals (cloud.getSurfaceNormals()); -// // fpfh_est.setIndices(cloud.getKeyPoint_indices()); -// // fpfh_est.setInputCloud (cloud.getKeyPoints()); -// // fpfh_est.setInputNormals (cloud.getSurfaceNormals()); - -// pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); -// fpfh_est.setSearchMethod(tree); -// fpfh_est.setKSearch(K); -// // fpfh_est.setRadiusSearch(0.05); - -// fpfh_est.compute (*fpfh_features_); - -// // cloud.setFeatures_FPFH(fpfh_features_); -// // std::cout << "fpfh size: " << fpfh_features_->points.size() << std::endl; - -// int key_index = 0; -// for (int i = 0; i < (cloud.getKeyPoint_indices())->indices.size(); i++) -// { -// key_index = (cloud.getKeyPoint_indices())->indices[i]; -// pcl::FPFHSignature33 descriptor = fpfh_features_->points[key_index]; -// (fpfh_features_key_->points).push_back(descriptor); -// } - -// // cloud.setFeatures_FPFH(fpfh_features_); - -// cloud.setFeatures_FPFH(fpfh_features_key_); -// // std::cout << "fpfh size: " << fpfh_features_key_->points.size() << std::endl; -// } - -/* New */ -void -computeFeatures_FPFH (FeatureCloud &cloud, float R) -{ - - FPFH_Features::Ptr fpfh_features_ (new FPFH_Features); - // FPFH_Features::Ptr fpfh_features_key_ (new FPFH_Features); - - pcl::FPFHEstimation fpfh_est; - - fpfh_est.setSearchSurface (cloud.getPointCloud()); - fpfh_est.setInputNormals (cloud.getSurfaceNormals()); - fpfh_est.setInputCloud (cloud.getKeyPoints()); - - pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); - fpfh_est.setSearchMethod(tree); - fpfh_est.setRadiusSearch(R); - // fpfh_est.setKSearch(K); - - fpfh_est.compute (*fpfh_features_); - - cloud.setFeatures_FPFH(fpfh_features_); -} - -// Compute the surface normals and local features. -void -computeFeatures (FeatureCloud &cloud, float normal_R, float FPFH_R) -{ - computeSurfaceNormals (cloud, normal_R); - computeFeatures_FPFH (cloud, FPFH_R); -} - -void getIndices (PointCloud::Ptr cloudin, PointCloud::Ptr keypoints_cal, \ - PointCloud::Ptr keypoints_real, pcl::PointIndices::Ptr indices) -{ - pcl::KdTreeFLANN kdtree; - kdtree.setInputCloud(cloudin); - std::vectorpointNKNSquareDistance; - std::vector pointIdxNKNSearch; - - int indice = 0; - for (size_t i =0; i < keypoints_cal->size();i++) - { - kdtree.nearestKSearch(keypoints_cal->points[i],1,pointIdxNKNSearch,pointNKNSquareDistance); - - indice = pointIdxNKNSearch[0]; - indices->indices.push_back(indice); - keypoints_real->points.push_back(cloudin->points[indice]); - } -} - -void correspondence_estimation(FeatureCloud &source_cloud, FeatureCloud &target_cloud,\ - pcl::Correspondences &all_corres) -{ - pcl::registration::CorrespondenceEstimation est; - est.setInputSource (source_cloud.getFeatures_FPFH()); - est.setInputTarget (target_cloud.getFeatures_FPFH()); - - est.determineReciprocalCorrespondences (all_corres); - std::cout << "corr size:" << all_corres.size() << std::endl; -} - -void correspondences_rejection(FeatureCloud &source_cloud, FeatureCloud &target_cloud,\ - pcl::Correspondences &correspondences, pcl::Correspondences &inliers, \ - Result *result, int N, float threshold) -{ - - pcl::registration::CorrespondenceRejectorSampleConsensus sac; - sac.setInputSource(source_cloud.getKeyPoints ()); - sac.setInputTarget(target_cloud.getKeyPoints ()); - // sac.setInputSource(source_cloud.getPointCloud ()); - // sac.setInputTarget(target_cloud.getPointCloud ()); - - /* Set the threshold for rejection iteration */ - sac.setInlierThreshold(threshold); - sac.setMaximumIterations(N); - - sac.getRemainingCorrespondences(correspondences, inliers); - Eigen::Matrix4f transformation = sac.getBestTransformation(); - - result->final_transformation = transformation; - - // std::cout << "ransac:" << std::endl; - // for(int i = 0; i < 3; i ++) - // { - // for(int j = 0; j < 4; j ++) - // { - // std::cout << ("%lf", transformation(i,j)); - // if (j != 4) - // std::cout << " "; - // } - // std::cout << std::endl; - // } - // std::cout << "corr size (after):" << inliers.size() << std::endl; - PointCloud::Ptr transformed_cloud (new PointCloud); - - //pcl::transformPointCloud (*(source_cloud.getKeyPoints ()), *transformed_cloud, transformation); - pcl::transformPointCloud (*(source_cloud.getPointCloud ()), *transformed_cloud, transformation); - source_cloud.setTransformedCloud(transformed_cloud); -} - -void iterative_closest_points(FeatureCloud &source_cloud, FeatureCloud &target_cloud,\ - Result *result, float transEps, float corresDist, float EuclFitEps, float outlThresh) -{ - pcl::IterativeClosestPoint icp; - - PointCloud Final; - - // icp.setInputSource(source_cloud.getTransformedCloud ()); - // icp.setInputTarget(target_cloud.getKeyPoints ()); - - icp.setInputSource(source_cloud.getTransformedCloud ()); - icp.setInputTarget(target_cloud.getPointCloud ()); - - icp.setUseReciprocalCorrespondences(true); - icp.setMaximumIterations (50); - icp.setTransformationEpsilon (transEps); - icp.setMaxCorrespondenceDistance (corresDist); - - icp.setEuclideanFitnessEpsilon (EuclFitEps); - icp.setRANSACOutlierRejectionThreshold (outlThresh); - - icp.align(Final); - - result->final_transformation = icp.getFinalTransformation(); - result->fitness_score = icp.getFitnessScore(); -} - -// Utils: helper functions to parse the Kitti odometry data -bool string_sort (std::string i,std::string j) -{ - // the part before '.bin' - std::string foo_i = i.substr(0,i.length()-4); - std::string foo_j = j.substr(0,i.length()-4); - return (foo_i &files) -{ - DIR* dirp = opendir(path_dir.c_str()); - - int file_num = 0; - if (!dirp) - { - std::cout << path_dir << endl; - return; - } - - struct dirent * dp; - while ((dp = readdir(dirp)) != NULL) { - - std::string str_d_name(dp->d_name); - - if (str_d_name == ".") - continue; - if (str_d_name == "..") - continue; - file_num += 1; - - if (*(path_dir.end() - 1) == '/') - files.push_back(path_dir + str_d_name); - else - files.push_back(path_dir + '/' + str_d_name); - - } - closedir(dirp); - std::cout << "total number of frames: " << file_num << std::endl; - - // sort - std::sort (files.begin(), files.end(), string_sort); -} - -void load_bin(std::string infile, FeatureCloud &cloud) -{ - std::cout << "Loading " << infile << std::endl; - - fstream input(infile.c_str(), ios::in | ios::binary); - - if(!input.good()){ - cerr << "Could not read file: " << infile << endl; - exit(EXIT_FAILURE); - } - input.seekg(0, ios::beg); - - /* convertion */ - PointCloud::Ptr points (new PointCloud); - - for (int j=0; input.good() && !input.eof(); j++) { - //PointXYZI point; - PointT point; - - input.read((char *) &point.x, 3*sizeof(float)); - input.seekg(sizeof(float), ios::cur); - - points->push_back(point); - } - - cloud.setInputCloud(points); - input.close(); -} \ No newline at end of file diff --git a/legacy/utils/plot-trajectory.py b/legacy/utils/plot-trajectory.py deleted file mode 100644 index fb3a39c..0000000 --- a/legacy/utils/plot-trajectory.py +++ /dev/null @@ -1,108 +0,0 @@ -import matplotlib.pyplot as plt -import sys -import time -import math - -fname="../Kitti/Ground-Truth/dataset/poses/00.txt" -gname='./result1/pose_result_kitti.txt' - -fig=plt.figure() -gt_xyz = fig.add_subplot(3,2,1) -ours_xyz = fig.add_subplot(3,2,2) -trajectory = fig.add_subplot(3,2,3) -y_com = fig.add_subplot(3,2,4) -x_com = fig.add_subplot(3,2,5) -z_com = fig.add_subplot(3,2,6) - -with open(fname) as f: - content = f.readlines() -# you may also want to remove whitespace characters like `\n` at the end of each line -content = [x.strip() for x in content] - -with open(gname) as f: - content2 = f.readlines() -# you may also want to remove whitespace characters like `\n` at the end of each line -content2 = [x.strip() for x in content2] - -x=[] -y=[] -z=[] -d = [] - -x1=[] -y1=[] -z1=[] -d1 =[] - -err=[] - -n=len(content2) -if len(sys.argv) == 3: - n = int(sys.argv[2]) -n= 2140 - -#groudtruth -for i, v in enumerate(content[:n]): - # print(i.split(' ')[3], i.split(' ')[7], i.split(' ')[11]) - d.append(i) - x_gt = float(v.split(' ')[3]) - y_gt = float(v.split(' ')[7]) - z_gt = float(v.split(' ')[11]) - x.append(x_gt) - y.append(y_gt) - z.append(z_gt) - - -#ours -for i, v in enumerate(content2[:n]): - d1.append(i) - x_ = float(v.split(' ')[3]) - y_ = float(v.split(' ')[7]) - z_ = float(v.split(' ')[11]) - - x1.append(x_) - y1.append(y_) - z1.append(z_) - - -ours_xyz.clear() -gt_xyz.clear() -trajectory.clear() - -# plt.subplot(221) -gt_xyz.set_title('Position(xyz) - Ground Truth') -gt_xyz.axis([0, n + 100, -200, 600]) -gt_xyz.plot(d, x, 'r', label='x') -gt_xyz.plot(d, y, 'g', label='y') -gt_xyz.plot(d, z,'b', label='z') -gt_xyz.legend(loc='upper right') - - -ours_xyz.set_title('Position(xyz) - Estimated Result') -ours_xyz.axis([0, n + 100, -200, 600]) -ours_xyz.plot(d1, x1, 'r', label='x') -ours_xyz.plot(d1, y1, 'g', label='y') -ours_xyz.plot(d1, z1,'b', label='z') -ours_xyz.legend(loc='upper right') - -trajectory.set_title("Trajectory") -trajectory.plot(z, x, 'r--', label='GT') -trajectory.plot(z1, x1, 'g--', label='EST') -trajectory.legend(loc='upper right') - -z_com.set_title("Z value comparison") -z_com.plot(d, z, 'r', label='z - GT') -z_com.plot(d1, z1, 'g', label='z - EST') -z_com.legend(loc='upper left') - -y_com.set_title("Y value comparison") -y_com.plot(d, y, 'r', label='y - GT') -y_com.plot(d1, y1, 'g', label='y - EST') -y_com.legend(loc='upper left') - -x_com.set_title("X value comparison") -x_com.plot(d, x, 'r', label='x - GT') -x_com.plot(d1, x1, 'g', label='x - EST') -x_com.legend(loc='upper left') - -plt.show() \ No newline at end of file diff --git a/legacy/utils/plotErrs-iterNumfixed.py b/legacy/utils/plotErrs-iterNumfixed.py deleted file mode 100644 index 1f9a343..0000000 --- a/legacy/utils/plotErrs-iterNumfixed.py +++ /dev/null @@ -1,282 +0,0 @@ -''' - Plot: - frame-wise translational and rotational error -''' - -import matplotlib.pyplot as plt -import numpy as np -import sys -import time -import math - -def load_and_transform(filename): - ''' - Load KITTI format ground-truth or pose estimation results. - Each line in the file represents a 3 * 4 matrix. - - Returns: - A list of numpy matrix - ''' - with open(filename) as f: - poses = f.readlines() - - poses = [x.strip().split(' ') for x in poses[:]] - poses_matrix = list() - - for mt in poses[:]: - ''' - Transform 3 * 4 into 4 * 4 (needed when calculating the inverse matrix). - ''' - list_ = [float(i) for i in mt] - - list_.append(.0) - list_.append(.0) - list_.append(.0) - list_.append(1.0) - - matrix_calcaulated = np.matrix(list_).reshape(4, 4) - poses_matrix.append(matrix_calcaulated) - - return poses_matrix - -def load_ests(filename): - ''' - Load ICP iteration results. (In this file stores the result of each icp iteration, instead of only the final result). - Example: - 3 * 4 (iter1, frame1-0) - 3 * 4 (iter2, frame1-0) - 3 * 4 (iter3, frame1-0) - ... - 3 * 4 (iter40, frame1-0) - 3 * 4 (iter1, frame2-1) - 3 * 4 (iter2, frame2-1) - 3 * 4 (iter3, frame2-1) - ... - 3 * 4 (iter40, frame2-1) - - Returns: - A list of numpy matrix list, each stores the matrix results after each iteration for the frame pairs. - Example: - [[m1, m2, ... m40], - [m1, m2, ... m40], - ... - ] - ''' - with open(filename) as f: - poses = f.readlines() - - total_est=list() # stores a list of icp result lists, i.e., frame_est - frame_est=list() # stores a list of icp results (tranformation matrix given by each iteration) - - for l_ in poses: - if l_ == '\n': - total_est.append(frame_est.copy()) - frame_est=list() - elif l_ == '-\n': - pass - else: - frame_est.append(l_.strip().split(' ')) - - ''' transform list into numpy matrix - ''' - total_est_matrix=list() - for est_ in total_est: - # est_: all the results for each pairwise registration - frame_est_matrix=list() - for mt in est_: - # mt: result of each icp iteration - list_ = [float(i) for i in mt] - list_.append(.0) - list_.append(.0) - list_.append(.0) - list_.append(1.0) - - matrix_calcaulated = np.matrix(list_).reshape(4, 4) - frame_est_matrix.append(matrix_calcaulated) - - total_est_matrix.append(frame_est_matrix) - - print(len(total_est)) - print(len(total_est_matrix)) - - return total_est_matrix - -def estimate_error(matrix_list_gt, total_est_matrix, pose_ransac_matrix): - ''' - ''' - dist = list() - dist.append(.0) - - tranlational_err_list = list() - rotational_err_list = list() - - ''' - Ground Truth - ''' - for i, m in enumerate(matrix_list_gt[:]): - ''' Calculate distance - ''' - if i > 0: - # the first line of gt is a identity matrix (of no use) - dx = m[2, 3] - matrix_list_gt[i-1][2,3] - dy = m[0, 3] - matrix_list_gt[i-1][0,3] - dz = m[1, 3] - matrix_list_gt[i-1][1,3] - - dist_delta = math.sqrt(dx*dx+dy*dy+dz*dz) - - dist.append(dist[i-1] + dist_delta) - - ''' - Estimated poses - ''' - translational_error_total = list() - rotational_error_total = list() - - for i0, frame_mts in enumerate(total_est_matrix[:]): - ''' frames - ''' - - # i0 == 1: 0 <- 1 registration result - - translational_error_frame = list() - rotational_error_frame = list() - - for i, m in enumerate(frame_mts): - # i + 1: iteration number - ''' 0 - 39 estimtated matrix - ''' - ''' Calculate rotational and translational error - ''' - if i0 > 0: - - pose_delta_gt = np.matmul(matrix_list_gt[i0 - 1].I, matrix_list_gt[i0]) - pose_delta_est = np.matmul(total_est_matrix[i0 - 1][i], pose_ransac_matrix[i0 - 1]) - - if i == len(frame_mts) - 1: - print("Frame: ", i0 - 1, "<---", i0) - print("delta gt\n", pose_delta_gt) - print("delta est\n", pose_delta_est) - print('\n\n') - - pose_error = np.matmul(pose_delta_est.I, pose_delta_gt) - - translational_error = math.sqrt( \ - pose_error[0, 3] * pose_error[0, 3] + \ - pose_error[1, 3] * pose_error[1, 3] + \ - pose_error[2, 3] * pose_error[2, 3]) - - translational_error_frame.append(translational_error) - - a = pose_error[0, 0] - b = pose_error[1, 1] - c = pose_error[2, 2] - d = 0.5 * (a + b + c - 1.0) - - rotational_error = math.acos(max(min(d, 1.0), -1.0)) - rotational_error_frame.append(rotational_error) - - if i0 > 0: - # ith in the error list: i + 1 ----> previous - translational_error_total.append(translational_error_frame) - rotational_error_total.append(rotational_error_frame) - - ''' Driving distance - ''' - return dist, translational_error_total, rotational_error_total - - -''' - plot -''' -def plot_errors_range(start, end): - for b_ in range(start, end, 5): - - fig=plt.figure(figsize=(15,5)) - - # trans_err = fig.add_subplot(3,2,1) - # rot_err = fig.add_subplot(3,2,2) - - # trans_err.set_title("Translational Error (Absolute)") - # rot_err.set_title("Rotational Error (Absolute)") - - # for f_ in [25,75,108,500,700,800,900]: - # trans_err.plot(range(40), translational_error_total[f_], '*-', label='#' + str(f_)) - # rot_err.plot(range(40), rotational_error_total[f_], '^-', label='#' + str(f_)) - # trans_err.legend(loc='upper right') - # rot_err.legend(loc='upper right') - - trans_err1 = fig.add_subplot(1,2,1) - rot_err1 = fig.add_subplot(1,2,2) - - trans_err1.set_title("Translational Error (Absolute)") - rot_err1.set_title("Rotational Error (Absolute)") - - for i in range(5): - trans_err1.plot(range(40), translational_error_total[b_ + i], '*-', label='#' + str(b_ + i)) - rot_err1.plot(range(40), rotational_error_total[b_ + i], '^-', label='#' + str(b_ + i)) - trans_err1.legend(loc='upper right') - rot_err1.legend(loc='upper right') - - trans_err1.set_ylim(.0, .5) - rot_err1.set_ylim(.0, .03) - - plt.show() - -if __name__ == '__main__': - ''' - Load pose ground truth && Transform to matrix - ''' - fname1="../Kitti/Ground-Truth/dataset/poses/00.txt" - pose_gt_matrix = load_and_transform(fname1) - - # ransac results - fransac='./result1/ransac_delta.txt' - pose_ransac_matrix = load_and_transform(fransac) - - # icp deltas - fname2='./icp_results.txt' - total_est_matrix = load_ests(fname2) - dist, translational_error_total, rotational_error_total = estimate_error(pose_gt_matrix, total_est_matrix, pose_ransac_matrix) - - ''' - plot - ''' - - fig=plt.figure() - - trans_err = fig.add_subplot(3,2,1) - rot_err = fig.add_subplot(3,2,2) - - trans_err.set_title("Translational Error (Absolute)") - rot_err.set_title("Rotational Error (Absolute)") - - for f_ in [25,75,108,500,700,800,900]: - trans_err.plot(range(40), translational_error_total[f_], '*-', label='#' + str(f_)) - rot_err.plot(range(40), rotational_error_total[f_], '^-', label='#' + str(f_)) - trans_err.legend(loc='upper right') - rot_err.legend(loc='upper right') - - trans_err1 = fig.add_subplot(3,2,3) - rot_err1 = fig.add_subplot(3,2,4) - - trans_err1.set_title("Translational Error (Absolute)") - rot_err1.set_title("Rotational Error (Absolute)") - for i in [1780,1781,1782,1783,1784]: - trans_err1.plot(range(40), translational_error_total[i], '*-', label='#' + str(i)) - rot_err1.plot(range(40), rotational_error_total[i], '^-', label='#' + str(i)) - trans_err1.legend(loc='upper right') - rot_err1.legend(loc='upper right') - - - trans_err2 = fig.add_subplot(3,2,5) - rot_err2 = fig.add_subplot(3,2,6) - - trans_err2.set_title("Translational Error (Absolute)") - rot_err2.set_title("Rotational Error (Absolute)") - for i in range(5): - trans_err2.plot(range(40), translational_error_total[i + 1795], '*-', label='#' + str(i + 1795)) - rot_err2.plot(range(40), rotational_error_total[i + 1795], '^-', label='#' + str(i + 1795)) - trans_err2.legend(loc='upper right') - rot_err2.legend(loc='upper right') - - plt.show() diff --git a/legacy/utils/plotErrs.py b/legacy/utils/plotErrs.py deleted file mode 100644 index 8b3ea72..0000000 --- a/legacy/utils/plotErrs.py +++ /dev/null @@ -1,277 +0,0 @@ -''' - Plot: - frame-wise translational and rotational error -''' - -import matplotlib.pyplot as plt -import numpy as np -import sys -import time -import math - -def load_and_transform(filename): - ''' - Load KITTI format ground-truth or pose estimation results. - Each line in the file represents a 3 * 4 matrix. - - Returns: - A list of numpy matrix - ''' - with open(filename) as f: - poses = f.readlines() - - poses = [x.strip().split(' ') for x in poses[:]] - poses_matrix = list() - - for mt in poses[:]: - ''' - Transform 3 * 4 into 4 * 4 (needed when calculating the inverse matrix). - ''' - list_ = [float(i) for i in mt] - - list_.append(.0) - list_.append(.0) - list_.append(.0) - list_.append(1.0) - - matrix_calcaulated = np.matrix(list_).reshape(4, 4) - poses_matrix.append(matrix_calcaulated) - - return poses_matrix - -def load_ests(filename): - ''' - Load ICP iteration results. (In this file stores the result of each icp iteration, instead of only the final result). - Example: - 3 * 4 (iter1, frame1-0) - 3 * 4 (iter2, frame1-0) - 3 * 4 (iter3, frame1-0) - ... - 3 * 4 (iter40, frame1-0) - 3 * 4 (iter1, frame2-1) - 3 * 4 (iter2, frame2-1) - 3 * 4 (iter3, frame2-1) - ... - 3 * 4 (iter40, frame2-1) - - Returns: - A list of numpy matrix list, each stores the matrix results after each iteration for the frame pairs. - Example: - [[m1, m2, ... m40], - [m1, m2, ... m40], - ... - ] - ''' - with open(filename) as f: - poses = f.readlines() - - total_est=list() # stores a list of icp result lists, i.e., frame_est - frame_est=list() # stores a list of icp results (tranformation matrix given by each iteration) - - for l_ in poses: - if l_ == '\n': - total_est.append(frame_est.copy()) - frame_est=list() - elif l_ == '-\n': - pass - else: - frame_est.append(l_.strip().split(' ')) - - ''' transform list into numpy matrix - ''' - total_est_matrix=list() - for est_ in total_est: - # est_: all the results for each pairwise registration - frame_est_matrix=list() - for mt in est_: - # mt: result of each icp iteration - list_ = [float(i) for i in mt] - list_.append(.0) - list_.append(.0) - list_.append(.0) - list_.append(1.0) - - matrix_calcaulated = np.matrix(list_).reshape(4, 4) - frame_est_matrix.append(matrix_calcaulated) - - total_est_matrix.append(frame_est_matrix) - - print(len(total_est)) - print(len(total_est_matrix)) - - return total_est_matrix - -def estimate_error(matrix_list_gt, total_est_matrix, pose_ransac_matrix): - ''' - Args: - total_est_matrix: icp results - ''' - dist = list() - dist.append(.0) - - tranlational_err_list = list() - rotational_err_list = list() - - ''' - Ground Truth - ''' - for i, m in enumerate(matrix_list_gt[:]): - ''' Calculate distance - ''' - if i > 0: - # the first line of gt is a identity matrix (of no use) - dx = m[2, 3] - matrix_list_gt[i-1][2,3] - dy = m[0, 3] - matrix_list_gt[i-1][0,3] - dz = m[1, 3] - matrix_list_gt[i-1][1,3] - - dist_delta = math.sqrt(dx*dx+dy*dy+dz*dz) - - dist.append(dist[i-1] + dist_delta) - - ''' - Estimated poses - ''' - translational_error_total = list() - rotational_error_total = list() - - for i0, frame_mts in enumerate(total_est_matrix[:]): - ''' frames - ''' - - # i0 == 1: 0 <---- 1 registration result - # i0 == n: (n-1) <---- n registration result - - translational_error_frame = list() - rotational_error_frame = list() - - previous_frame_mts = total_est_matrix[i0 - 1] - for i, m in enumerate(previous_frame_mts): - # i + 1: iteration number - ''' 0 - 39 estimtated matrix - ''' - ''' Calculate rotational and translational error - ''' - if i0 > 0: - - pose_delta_gt = np.matmul(matrix_list_gt[i0 - 1].I, matrix_list_gt[i0]) - pose_delta_est = np.matmul(previous_frame_mts[i], pose_ransac_matrix[i0 - 1]) - # m: total_est_matrix[i0][i] - # pose_delta_est = np.matmul(m, pose_ransac_matrix[i0 - 1]) - - if i == len(previous_frame_mts) - 1: - print("Frame: ", i0 - 1, "<---", i0) - print("Iteration Num:", i + 1) - print("delta gt\n", pose_delta_gt) - print("delta est\n", pose_delta_est) - print('\n\n') - - pose_error = np.matmul(pose_delta_est.I, pose_delta_gt) - - translational_error = math.sqrt( \ - pose_error[0, 3] * pose_error[0, 3] + \ - pose_error[1, 3] * pose_error[1, 3] + \ - pose_error[2, 3] * pose_error[2, 3]) - - translational_error_frame.append(translational_error) - - a = pose_error[0, 0] - b = pose_error[1, 1] - c = pose_error[2, 2] - d = 0.5 * (a + b + c - 1.0) - - rotational_error = math.acos(max(min(d, 1.0), -1.0)) - rotational_error_frame.append(rotational_error) - - if i0 > 0: - # ith in the error list: i + 1 ----> previous - translational_error_total.append(translational_error_frame) - rotational_error_total.append(rotational_error_frame) - - ''' Driving distance - ''' - return dist, translational_error_total, rotational_error_total - - -''' - plot -''' -def plot_errors_range(start, end): - for b_ in range(start, end, 5): - - fig=plt.figure(figsize=(15,5)) - - trans_err1 = fig.add_subplot(1,2,1) - rot_err1 = fig.add_subplot(1,2,2) - - trans_err1.set_title("Translational Error (Absolute)") - rot_err1.set_title("Rotational Error (Absolute)") - - for i in range(5): - trans_err1.plot(range(40), translational_error_total[b_ + i], '*-', label='#' + str(b_ + i)) - rot_err1.plot(range(40), rotational_error_total[b_ + i], '^-', label='#' + str(b_ + i)) - trans_err1.legend(loc='upper right') - rot_err1.legend(loc='upper right') - - trans_err1.set_ylim(.0, .5) - rot_err1.set_ylim(.0, .03) - - plt.show() - -if __name__ == '__main__': - ''' - Load pose ground truth && Transform to matrix - ''' - fname1="../Kitti/Ground-Truth/dataset/poses/00.txt" - pose_gt_matrix = load_and_transform(fname1) - - # ransac results - fransac='./result2/ransac_delta.txt' - pose_ransac_matrix = load_and_transform(fransac) - - # icp deltas - fname2='./icp_results.txt' - total_est_matrix = load_ests(fname2) - dist, translational_error_total, rotational_error_total = estimate_error(pose_gt_matrix, total_est_matrix, pose_ransac_matrix) - - ''' - plot - ''' - - fig=plt.figure() - - trans_err = fig.add_subplot(3,2,1) - rot_err = fig.add_subplot(3,2,2) - - trans_err.set_title("Translational Error (Absolute)") - rot_err.set_title("Rotational Error (Absolute)") - - for f_ in range(10): - trans_err.plot(range(len(translational_error_total[f_])), translational_error_total[f_], '*-', label='#' + str(f_)) - rot_err.plot(range(len(rotational_error_total[f_])), rotational_error_total[f_], '^-', label='#' + str(f_)) - trans_err.legend(loc='upper right') - rot_err.legend(loc='upper right') - - # trans_err1 = fig.add_subplot(3,2,3) - # rot_err1 = fig.add_subplot(3,2,4) - - # trans_err1.set_title("Translational Error (Absolute)") - # rot_err1.set_title("Rotational Error (Absolute)") - # for i in [1780,1781,1782,1783,1784]: - # trans_err1.plot(range(len(translational_error_total[i])), translational_error_total[i], '*-', label='#' + str(i)) - # rot_err1.plot(range(len(rotational_error_total[i])), rotational_error_total[i], '^-', label='#' + str(i)) - # trans_err1.legend(loc='upper right') - # rot_err1.legend(loc='upper right') - - - # trans_err2 = fig.add_subplot(3,2,5) - # rot_err2 = fig.add_subplot(3,2,6) - - # trans_err2.set_title("Translational Error (Absolute)") - # rot_err2.set_title("Rotational Error (Absolute)") - # for i in range(5): - # trans_err2.plot(range(len(translational_error_total[i + 1795])), translational_error_total[i + 1795], '*-', label='#' + str(i + 1795)) - # rot_err2.plot(range(len(rotational_error_total[i + 1795])), rotational_error_total[i + 1795], '^-', label='#' + str(i + 1795)) - # trans_err2.legend(loc='upper right') - # rot_err2.legend(loc='upper right') - - plt.show() diff --git a/pcl-1.7/pcl/ModelCoefficients.h b/pcl-1.7/pcl/ModelCoefficients.h new file mode 100644 index 0000000..e47a568 --- /dev/null +++ b/pcl-1.7/pcl/ModelCoefficients.h @@ -0,0 +1,46 @@ +#ifndef PCL_MESSAGE_MODELCOEFFICIENTS_H +#define PCL_MESSAGE_MODELCOEFFICIENTS_H +#include +#include +#include + +// Include the correct Header path here +#include + +namespace pcl +{ + struct ModelCoefficients + { + ModelCoefficients () : header (), values () + { + } + + ::pcl::PCLHeader header; + + std::vector values; + + public: + typedef boost::shared_ptr< ::pcl::ModelCoefficients> Ptr; + typedef boost::shared_ptr< ::pcl::ModelCoefficients const> ConstPtr; + }; // struct ModelCoefficients + + typedef boost::shared_ptr< ::pcl::ModelCoefficients> ModelCoefficientsPtr; + typedef boost::shared_ptr< ::pcl::ModelCoefficients const> ModelCoefficientsConstPtr; + + inline std::ostream& operator<<(std::ostream& s, const ::pcl::ModelCoefficients & v) + { + s << "header: " << std::endl; + s << v.header; + s << "values[]" << std::endl; + for (size_t i = 0; i < v.values.size (); ++i) + { + s << " values[" << i << "]: "; + s << " " << v.values[i] << std::endl; + } + return (s); + } + +} // namespace pcl + +#endif // PCL_MESSAGE_MODELCOEFFICIENTS_H + diff --git a/pcl-1.7/pcl/PCLHeader.h b/pcl-1.7/pcl/PCLHeader.h new file mode 100644 index 0000000..84a6407 --- /dev/null +++ b/pcl-1.7/pcl/PCLHeader.h @@ -0,0 +1,49 @@ +#ifndef PCL_ROSLIB_MESSAGE_HEADER_H +#define PCL_ROSLIB_MESSAGE_HEADER_H + +#ifdef USE_ROS + #error USE_ROS setup requires PCL to compile against ROS message headers, which is now deprecated +#endif + +#include +#include +#include +#include +#include + +namespace pcl +{ + struct PCLHeader + { + PCLHeader (): seq (0), stamp (), frame_id () + {} + + /** \brief Sequence number */ + pcl::uint32_t seq; + /** \brief A timestamp associated with the time when the data was acquired + * + * The value represents microseconds since 1970-01-01 00:00:00 (the UNIX epoch). + */ + pcl::uint64_t stamp; + /** \brief Coordinate frame ID */ + std::string frame_id; + + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + }; // struct PCLHeader + + typedef boost::shared_ptr HeaderPtr; + typedef boost::shared_ptr HeaderConstPtr; + + inline std::ostream& operator << (std::ostream& out, const PCLHeader &h) + { + out << "seq: " << h.seq; + out << " stamp: " << h.stamp; + out << " frame_id: " << h.frame_id << std::endl; + return (out); + } + +} // namespace pcl + +#endif // PCL_ROSLIB_MESSAGE_HEADER_H + diff --git a/pcl-1.7/pcl/PCLImage.h b/pcl-1.7/pcl/PCLImage.h new file mode 100644 index 0000000..8d55b5d --- /dev/null +++ b/pcl-1.7/pcl/PCLImage.h @@ -0,0 +1,65 @@ +#ifndef PCL_MESSAGE_IMAGE_H +#define PCL_MESSAGE_IMAGE_H +#include +#include +#include + +#ifdef USE_ROS + #error USE_ROS setup requires PCL to compile against ROS message headers, which is now deprecated +#endif + +// Include the correct Header path here +#include + +namespace pcl +{ + struct PCLImage + { + PCLImage () : header (), height (0), width (0), encoding (), + is_bigendian (0), step (0), data () + {} + + ::pcl::PCLHeader header; + + pcl::uint32_t height; + pcl::uint32_t width; + std::string encoding; + + pcl::uint8_t is_bigendian; + pcl::uint32_t step; + + std::vector data; + + typedef boost::shared_ptr< ::pcl::PCLImage> Ptr; + typedef boost::shared_ptr< ::pcl::PCLImage const> ConstPtr; + }; // struct PCLImage + + typedef boost::shared_ptr< ::pcl::PCLImage> PCLImagePtr; + typedef boost::shared_ptr< ::pcl::PCLImage const> PCLImageConstPtr; + + inline std::ostream& operator<<(std::ostream& s, const ::pcl::PCLImage & v) + { + s << "header: " << std::endl; + s << v.header; + s << "height: "; + s << " " << v.height << std::endl; + s << "width: "; + s << " " << v.width << std::endl; + s << "encoding: "; + s << " " << v.encoding << std::endl; + s << "is_bigendian: "; + s << " " << v.is_bigendian << std::endl; + s << "step: "; + s << " " << v.step << std::endl; + s << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size (); ++i) + { + s << " data[" << i << "]: "; + s << " " << v.data[i] << std::endl; + } + return (s); + } +} // namespace pcl + +#endif // PCL_MESSAGE_IMAGE_H + diff --git a/pcl-1.7/pcl/PCLPointCloud2.h b/pcl-1.7/pcl/PCLPointCloud2.h new file mode 100644 index 0000000..6a00c1f --- /dev/null +++ b/pcl-1.7/pcl/PCLPointCloud2.h @@ -0,0 +1,94 @@ +#ifndef PCL_SENSOR_MSGS_MESSAGE_POINTCLOUD2_H +#define PCL_SENSOR_MSGS_MESSAGE_POINTCLOUD2_H + +#ifdef USE_ROS + #error USE_ROS setup requires PCL to compile against ROS message headers, which is now deprecated +#endif + +#include +#include +#include +#include + +// Include the correct Header path here +#include +#include + +namespace pcl +{ + + struct PCLPointCloud2 + { + PCLPointCloud2 () : header (), height (0), width (0), fields (), + is_bigendian (false), point_step (0), row_step (0), + data (), is_dense (false) + { +#if defined(BOOST_BIG_ENDIAN) + is_bigendian = true; +#elif defined(BOOST_LITTLE_ENDIAN) + is_bigendian = false; +#else +#error "unable to determine system endianness" +#endif + } + + ::pcl::PCLHeader header; + + pcl::uint32_t height; + pcl::uint32_t width; + + std::vector< ::pcl::PCLPointField> fields; + + pcl::uint8_t is_bigendian; + pcl::uint32_t point_step; + pcl::uint32_t row_step; + + std::vector data; + + pcl::uint8_t is_dense; + + public: + typedef boost::shared_ptr< ::pcl::PCLPointCloud2> Ptr; + typedef boost::shared_ptr< ::pcl::PCLPointCloud2 const> ConstPtr; + }; // struct PCLPointCloud2 + + typedef boost::shared_ptr< ::pcl::PCLPointCloud2> PCLPointCloud2Ptr; + typedef boost::shared_ptr< ::pcl::PCLPointCloud2 const> PCLPointCloud2ConstPtr; + + inline std::ostream& operator<<(std::ostream& s, const ::pcl::PCLPointCloud2 &v) + { + s << "header: " << std::endl; + s << v.header; + s << "height: "; + s << " " << v.height << std::endl; + s << "width: "; + s << " " << v.width << std::endl; + s << "fields[]" << std::endl; + for (size_t i = 0; i < v.fields.size (); ++i) + { + s << " fields[" << i << "]: "; + s << std::endl; + s << " " << v.fields[i] << std::endl; + } + s << "is_bigendian: "; + s << " " << v.is_bigendian << std::endl; + s << "point_step: "; + s << " " << v.point_step << std::endl; + s << "row_step: "; + s << " " << v.row_step << std::endl; + s << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size (); ++i) + { + s << " data[" << i << "]: "; + s << " " << v.data[i] << std::endl; + } + s << "is_dense: "; + s << " " << v.is_dense << std::endl; + + return (s); + } + +} // namespace pcl + +#endif // PCL_SENSOR_MSGS_MESSAGE_POINTCLOUD2_H + diff --git a/pcl-1.7/pcl/PCLPointField.h b/pcl-1.7/pcl/PCLPointField.h new file mode 100644 index 0000000..835e353 --- /dev/null +++ b/pcl-1.7/pcl/PCLPointField.h @@ -0,0 +1,59 @@ +#ifndef PCL_SENSOR_MSGS_MESSAGE_POINTFIELD_H +#define PCL_SENSOR_MSGS_MESSAGE_POINTFIELD_H + +#ifdef USE_ROS + #error USE_ROS setup requires PCL to compile against ROS message headers, which is now deprecated +#endif + +#include +#include +#include +#include +#include + +namespace pcl +{ + struct PCLPointField + { + PCLPointField () : name (), offset (0), datatype (0), count (0) + {} + + std::string name; + + pcl::uint32_t offset; + pcl::uint8_t datatype; + pcl::uint32_t count; + + enum PointFieldTypes { INT8 = 1, + UINT8 = 2, + INT16 = 3, + UINT16 = 4, + INT32 = 5, + UINT32 = 6, + FLOAT32 = 7, + FLOAT64 = 8 }; + + public: + typedef boost::shared_ptr< ::pcl::PCLPointField> Ptr; + typedef boost::shared_ptr< ::pcl::PCLPointField const> ConstPtr; + }; // struct PCLPointField + + typedef boost::shared_ptr< ::pcl::PCLPointField> PCLPointFieldPtr; + typedef boost::shared_ptr< ::pcl::PCLPointField const> PCLPointFieldConstPtr; + + inline std::ostream& operator<<(std::ostream& s, const ::pcl::PCLPointField & v) + { + s << "name: "; + s << " " << v.name << std::endl; + s << "offset: "; + s << " " << v.offset << std::endl; + s << "datatype: "; + s << " " << v.datatype << std::endl; + s << "count: "; + s << " " << v.count << std::endl; + return (s); + } +} // namespace pcl + +#endif // PCL_SENSOR_MSGS_MESSAGE_POINTFIELD_H + diff --git a/pcl-1.7/pcl/PointIndices.h b/pcl-1.7/pcl/PointIndices.h new file mode 100644 index 0000000..f2de806 --- /dev/null +++ b/pcl-1.7/pcl/PointIndices.h @@ -0,0 +1,44 @@ +#ifndef PCL_MESSAGE_POINTINDICES_H +#define PCL_MESSAGE_POINTINDICES_H +#include +#include +#include + +// Include the correct Header path here +#include + +namespace pcl +{ + struct PointIndices + { + PointIndices () : header (), indices () + {} + + ::pcl::PCLHeader header; + + std::vector indices; + + public: + typedef boost::shared_ptr< ::pcl::PointIndices> Ptr; + typedef boost::shared_ptr< ::pcl::PointIndices const> ConstPtr; + }; // struct PointIndices + + typedef boost::shared_ptr< ::pcl::PointIndices> PointIndicesPtr; + typedef boost::shared_ptr< ::pcl::PointIndices const> PointIndicesConstPtr; + + inline std::ostream& operator << (std::ostream& s, const ::pcl::PointIndices &v) + { + s << "header: " << std::endl; + s << " " << v.header; + s << "indices[]" << std::endl; + for (size_t i = 0; i < v.indices.size (); ++i) + { + s << " indices[" << i << "]: "; + s << " " << v.indices[i] << std::endl; + } + return (s); + } +} // namespace pcl + +#endif // PCL_MESSAGE_POINTINDICES_H + diff --git a/pcl-1.7/pcl/PolygonMesh.h b/pcl-1.7/pcl/PolygonMesh.h new file mode 100644 index 0000000..06aa69e --- /dev/null +++ b/pcl-1.7/pcl/PolygonMesh.h @@ -0,0 +1,53 @@ +/* Auto-generated by genmsg_cpp for file /work/ros/pkgs-trunk/point_cloud_perception/pcl/msg/PolygonMesh.msg */ +#ifndef PCL_MESSAGE_POLYGONMESH_H +#define PCL_MESSAGE_POLYGONMESH_H +#include +#include +#include + +// Include the correct Header path here +#include +#include +#include + +namespace pcl +{ + struct PolygonMesh + { + PolygonMesh () : header (), cloud (), polygons () + {} + + ::pcl::PCLHeader header; + + ::pcl::PCLPointCloud2 cloud; + + std::vector< ::pcl::Vertices> polygons; + + + public: + typedef boost::shared_ptr< ::pcl::PolygonMesh> Ptr; + typedef boost::shared_ptr< ::pcl::PolygonMesh const> ConstPtr; + }; // struct PolygonMesh + + typedef boost::shared_ptr< ::pcl::PolygonMesh> PolygonMeshPtr; + typedef boost::shared_ptr< ::pcl::PolygonMesh const> PolygonMeshConstPtr; + + inline std::ostream& operator<<(std::ostream& s, const ::pcl::PolygonMesh &v) + { + s << "header: " << std::endl; + s << v.header; + s << "cloud: " << std::endl; + s << v.cloud; + s << "polygons[]" << std::endl; + for (size_t i = 0; i < v.polygons.size (); ++i) + { + s << " polygons[" << i << "]: " << std::endl; + s << v.polygons[i]; + } + return (s); + } + +} // namespace pcl + +#endif // PCL_MESSAGE_POLYGONMESH_H + diff --git a/pcl-1.7/pcl/TextureMesh.h b/pcl-1.7/pcl/TextureMesh.h new file mode 100644 index 0000000..4a7f673 --- /dev/null +++ b/pcl-1.7/pcl/TextureMesh.h @@ -0,0 +1,114 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_TEXTUREMESH_H_ +#define PCL_TEXTUREMESH_H_ + +#include +#include +#include +#include + +namespace pcl +{ + /** \author Khai Tran */ + struct TexMaterial + { + TexMaterial () : tex_name (), tex_file (), tex_Ka (), tex_Kd (), tex_Ks (), tex_d (), tex_Ns (), tex_illum () {} + + struct RGB + { + float r; + float g; + float b; + }; //RGB + + /** \brief Texture name. */ + std::string tex_name; + + /** \brief Texture file. */ + std::string tex_file; + + /** \brief Defines the ambient color of the material to be (r,g,b). */ + RGB tex_Ka; + + /** \brief Defines the diffuse color of the material to be (r,g,b). */ + RGB tex_Kd; + + /** \brief Defines the specular color of the material to be (r,g,b). This color shows up in highlights. */ + RGB tex_Ks; + + /** \brief Defines the transparency of the material to be alpha. */ + float tex_d; + + /** \brief Defines the shininess of the material to be s. */ + float tex_Ns; + + /** \brief Denotes the illumination model used by the material. + * + * illum = 1 indicates a flat material with no specular highlights, so the value of Ks is not used. + * illum = 2 denotes the presence of specular highlights, and so a specification for Ks is required. + */ + int tex_illum; + }; // TexMaterial + + /** \author Khai Tran */ + struct TextureMesh + { + TextureMesh () : + cloud (), tex_polygons (), tex_coordinates (), tex_materials () {} + + pcl::PCLPointCloud2 cloud; + pcl::PCLHeader header; + + + std::vector > tex_polygons; // polygon which is mapped with specific texture defined in TexMaterial + std::vector > tex_coordinates; // UV coordinates + std::vector tex_materials; // define texture material + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + }; // struct TextureMesh + + typedef boost::shared_ptr TextureMeshPtr; + typedef boost::shared_ptr TextureMeshConstPtr; +} // namespace pcl + +#endif /* PCL_TEXTUREMESH_H_ */ + diff --git a/pcl-1.7/pcl/Vertices.h b/pcl-1.7/pcl/Vertices.h new file mode 100644 index 0000000..631b8c0 --- /dev/null +++ b/pcl-1.7/pcl/Vertices.h @@ -0,0 +1,42 @@ +#ifndef PCL_MESSAGE_VERTICES_H +#define PCL_MESSAGE_VERTICES_H +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Describes a set of vertices in a polygon mesh, by basically + * storing an array of indices. + */ + struct Vertices + { + Vertices () : vertices () + {} + + std::vector vertices; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + }; // struct Vertices + + + typedef boost::shared_ptr VerticesPtr; + typedef boost::shared_ptr VerticesConstPtr; + + inline std::ostream& operator<<(std::ostream& s, const ::pcl::Vertices & v) + { + s << "vertices[]" << std::endl; + for (size_t i = 0; i < v.vertices.size (); ++i) + { + s << " vertices[" << i << "]: "; + s << " " << v.vertices[i] << std::endl; + } + return (s); + } +} // namespace pcl + +#endif // PCL_MESSAGE_VERTICES_H + diff --git a/pcl-1.7/pcl/apps/dominant_plane_segmentation.h b/pcl-1.7/pcl/apps/dominant_plane_segmentation.h new file mode 100644 index 0000000..cdb2730 --- /dev/null +++ b/pcl-1.7/pcl/apps/dominant_plane_segmentation.h @@ -0,0 +1,290 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef DOMINANT_PLANE_SEGMENTATION_H_ +#define DOMINANT_PLANE_SEGMENTATION_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace apps + { + /** \brief @b DominantPlaneSegmentation performs euclidean segmentation on a scene assuming that a dominant plane exists. + * \author Aitor Aldoma + * \ingroup apps + */ + + template + class PCL_EXPORTS DominantPlaneSegmentation + { + public: + typedef pcl::PointCloud Cloud; + typedef typename Cloud::Ptr CloudPtr; + typedef typename Cloud::ConstPtr CloudConstPtr; + typedef typename pcl::search::KdTree::Ptr KdTreePtr; + + DominantPlaneSegmentation () + { + min_z_bounds_ = 0; + max_z_bounds_ = 1.5; + object_min_height_ = 0.01; + object_max_height_ = 0.7; + object_cluster_tolerance_ = 0.05f; + object_cluster_min_size_ = 500; + k_ = 50; + sac_distance_threshold_ = 0.01; + downsample_leaf_ = 0.005f; + wsize_ = 5; + } + + /* \brief Extract the clusters. + * \param clusters Clusters extracted from the initial point cloud at the resolution size + * specified by downsample_leaf_ + */ + void + compute (std::vector & clusters); + + /* \brief Extract the clusters. + * \param clusters Clusters extracted from the initial point cloud. The returned + * clusters are not downsampled. + */ + void + compute_full (std::vector & clusters); + + /* \brief Extract clusters on a plane using connected components on an organized pointcloud. + * The method expects a the input cloud to have the is_dense attribute set to false. + * \param clusters Clusters extracted from the initial point cloud. The returned + * clusters are not downsampled. + */ + void + compute_fast (std::vector & clusters); + + /* \brief Computes the table plane. + */ + void + compute_table_plane(); + + /* \brief Sets the input point cloud. + * \param cloud_in The input point cloud. + */ + void + setInputCloud (CloudPtr & cloud_in) + { + input_ = cloud_in; + } + + /* \brief Returns the table coefficients after computation + * \param model represents the normal and the position of the plane (a,b,c,d) + */ + void + getTableCoefficients (Eigen::Vector4f & model) + { + model = table_coeffs_; + } + + /* \brief Sets minimum distance between clusters + * \param d distance (in meters) + */ + void + setDistanceBetweenClusters (float d) + { + object_cluster_tolerance_ = d; + } + + /* \brief Sets minimum size of the clusters. + * \param size number of points + */ + void + setMinClusterSize (int size) + { + object_cluster_min_size_ = size; + } + + /* \brief Sets the min height of the clusters in order to be considered. + * \param h minimum height (in meters) + */ + void + setObjectMinHeight (double h) + { + object_min_height_ = h; + } + + /* \brief Sets the max height of the clusters in order to be considered. + * \param h max height (in meters) + */ + void + setObjectMaxHeight (double h) + { + object_max_height_ = h; + } + + /* \brief Sets minimum distance from the camera for a point to be considered. + * \param z distance (in meters) + */ + void + setMinZBounds (double z) + { + min_z_bounds_ = z; + } + /* \brief Sets maximum distance from the camera for a point to be considered. + * \param z distance (in meters) + */ + void + setMaxZBounds (double z) + { + max_z_bounds_ = z; + } + + /* \brief Sets the number of neighbors used for normal estimation. + * \param k number of neighbors + */ + void setKNeighbors(int k) { + k_ = k; + } + + /* \brief Set threshold for SAC plane segmentation + * \param d threshold (in meters) + */ + void setSACThreshold(double d) { + sac_distance_threshold_ = d; + } + + /* \brief Set downsampling resolution. + * \param d resolution (in meters) + */ + void + setDownsamplingSize (float d) + { + downsample_leaf_ = d; + } + + /* \brief Set window size in pixels for CC used in compute_fast method + * \param w window size (in pixels) + */ + void setWSize(int w) { + wsize_ = w; + } + + /* \brief Returns the indices of the clusters found by the segmentation + * NOTE: This function returns only valid indices if the compute_fast method is used + * \param indices indices of the clusters + */ + void getIndicesClusters(std::vector & indices) { + indices = indices_clusters_; + } + + private: + + int + check (pcl::PointXYZI & p1, pcl::PointXYZI & p2, float, float max_dist) + { + if (p1.intensity == 0) //new label + return 1; + else + { + //compute distance and check aginst max_dist + if ((p1.getVector3fMap () - p2.getVector3fMap ()).norm () <= max_dist) + { + p2.intensity = p1.intensity; + return 0; + } + else //new label + return 1; + } + } + + //components needed for cluster segmentation and plane extraction + pcl::PassThrough pass_; + pcl::VoxelGrid grid_; + pcl::NormalEstimation n3d_; + pcl::SACSegmentationFromNormals seg_; + pcl::ProjectInliers proj_; + pcl::ProjectInliers bb_cluster_proj_; + pcl::ConvexHull hull_; + pcl::ExtractPolygonalPrismData prism_; + pcl::EuclideanClusterExtraction cluster_; + + /** \brief Input cloud from which to extract clusters */ + CloudPtr input_; + /** \brief Table coefficients (a,b,c,d) */ + Eigen::Vector4f table_coeffs_; + /** \brief Downsampling resolution. */ + float downsample_leaf_; + /** \brief Number of neighbors for normal estimation */ + int k_; + /** \brief Keep points farther away than min_z_bounds */ + double min_z_bounds_; + /** \brief Keep points closer than max_z_bounds */ + double max_z_bounds_; + /** \brief Threshold for SAC plane segmentation */ + double sac_distance_threshold_; + /** \brief Min height from the table plane object points will be considered from */ + double object_min_height_; + /** \brief Max height from the table plane */ + double object_max_height_; + /** \brief Tolerance between different clusters */ + float object_cluster_tolerance_; + /** \brief Minimum size for a cluster, clusters smaller than this won't be returned */ + int object_cluster_min_size_; + /** \brief Window size in pixels for CC in compute_fast method */ + int wsize_; + /** \brief Indices of the clusters to the main cloud found by the segmentation */ + std::vector indices_clusters_; + + }; + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif /* DOMINANT_PLANE_SEGMENTATION_H_ */ diff --git a/pcl-1.7/pcl/apps/impl/dominant_plane_segmentation.hpp b/pcl-1.7/pcl/apps/impl/dominant_plane_segmentation.hpp new file mode 100644 index 0000000..2a3fe5b --- /dev/null +++ b/pcl-1.7/pcl/apps/impl/dominant_plane_segmentation.hpp @@ -0,0 +1,859 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef Q_MOC_RUN +#pragma once +#include +#include +#endif + +#include +#include +#include +#include + +template void +pcl::apps::DominantPlaneSegmentation::compute_table_plane () +{ + // Has the input dataset been set already? + if (!input_) + { + PCL_WARN ("[pcl::apps::DominantPlaneSegmentation] No input dataset given!\n"); + return; + } + + CloudConstPtr cloud_; + CloudPtr cloud_filtered_ (new Cloud ()); + CloudPtr cloud_downsampled_ (new Cloud ()); + pcl::PointCloud::Ptr cloud_normals_ (new pcl::PointCloud ()); + pcl::PointIndices::Ptr table_inliers_ (new pcl::PointIndices ()); + pcl::ModelCoefficients::Ptr table_coefficients_ (new pcl::ModelCoefficients ()); + CloudPtr table_projected_ (new Cloud ()); + CloudPtr table_hull_ (new Cloud ()); + + typename pcl::search::KdTree::Ptr normals_tree_ (new pcl::search::KdTree); + + // Normal estimation parameters + n3d_.setKSearch (k_); + n3d_.setSearchMethod (normals_tree_); + + // Table model fitting parameters + seg_.setDistanceThreshold (sac_distance_threshold_); + seg_.setMaxIterations (2000); + seg_.setNormalDistanceWeight (0.1); + seg_.setOptimizeCoefficients (true); + seg_.setModelType (pcl::SACMODEL_NORMAL_PLANE); + seg_.setMethodType (pcl::SAC_RANSAC); + seg_.setProbability (0.99); + + proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE); + bb_cluster_proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE); + + // ---[ PassThroughFilter + pass_.setFilterLimits (float (min_z_bounds_), float (max_z_bounds_)); + pass_.setFilterFieldName ("z"); + pass_.setInputCloud (input_); + pass_.filter (*cloud_filtered_); + + if (int (cloud_filtered_->points.size ()) < k_) + { + PCL_WARN ("[DominantPlaneSegmentation] Filtering returned %lu points! Aborting.", + cloud_filtered_->points.size ()); + return; + } + + // Downsample the point cloud + grid_.setLeafSize (downsample_leaf_, downsample_leaf_, downsample_leaf_); + grid_.setDownsampleAllData (false); + grid_.setInputCloud (cloud_filtered_); + grid_.filter (*cloud_downsampled_); + + // ---[ Estimate the point normals + n3d_.setInputCloud (cloud_downsampled_); + n3d_.compute (*cloud_normals_); + + // ---[ Perform segmentation + seg_.setInputCloud (cloud_downsampled_); + seg_.setInputNormals (cloud_normals_); + seg_.segment (*table_inliers_, *table_coefficients_); + + if (table_inliers_->indices.size () == 0) + { + PCL_WARN ("[DominantPlaneSegmentation] No Plane Inliers points! Aborting."); + return; + } + + // ---[ Extract the plane + proj_.setInputCloud (cloud_downsampled_); + proj_.setIndices (table_inliers_); + proj_.setModelCoefficients (table_coefficients_); + proj_.filter (*table_projected_); + + // ---[ Estimate the convex hull + std::vector polygons; + CloudPtr table_hull (new Cloud ()); + hull_.setInputCloud (table_projected_); + hull_.reconstruct (*table_hull, polygons); + + // Compute the plane coefficients + Eigen::Vector4f model_coefficients; + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix; + + model_coefficients[0] = table_coefficients_->values[0]; + model_coefficients[1] = table_coefficients_->values[1]; + model_coefficients[2] = table_coefficients_->values[2]; + model_coefficients[3] = table_coefficients_->values[3]; + + // Need to flip the plane normal towards the viewpoint + Eigen::Vector4f vp (0, 0, 0, 0); + // See if we need to flip any plane normals + vp -= table_hull->points[0].getVector4fMap (); + vp[3] = 0; + // Dot product between the (viewpoint - point) and the plane normal + float cos_theta = vp.dot (model_coefficients); + // Flip the plane normal + if (cos_theta < 0) + { + model_coefficients *= -1; + model_coefficients[3] = 0; + // Hessian form (D = nc . p_plane (centroid here) + p) + model_coefficients[3] = -1 * (model_coefficients.dot (table_hull->points[0].getVector4fMap ())); + } + + //Set table_coeffs + table_coeffs_ = model_coefficients; +} + +template void +pcl::apps::DominantPlaneSegmentation::compute_fast (std::vector & clusters) +{ + // Has the input dataset been set already? + if (!input_) + { + PCL_WARN ("[pcl::apps::DominantPlaneSegmentation] No input dataset given!\n"); + return; + } + + // Is the input dataset organized? + if (input_->is_dense) + { + PCL_WARN ("[pcl::apps::DominantPlaneSegmentation] compute_fast can only be used with organized point clouds!\n"); + return; + } + + CloudConstPtr cloud_; + CloudPtr cloud_filtered_ (new Cloud ()); + CloudPtr cloud_downsampled_ (new Cloud ()); + pcl::PointCloud::Ptr cloud_normals_ (new pcl::PointCloud ()); + pcl::PointIndices::Ptr table_inliers_ (new pcl::PointIndices ()); + pcl::ModelCoefficients::Ptr table_coefficients_ (new pcl::ModelCoefficients ()); + CloudPtr table_projected_ (new Cloud ()); + CloudPtr table_hull_ (new Cloud ()); + CloudPtr cloud_objects_ (new Cloud ()); + CloudPtr cluster_object_ (new Cloud ()); + + typename pcl::search::KdTree::Ptr normals_tree_ (new pcl::search::KdTree); + typename pcl::search::KdTree::Ptr clusters_tree_ (new pcl::search::KdTree); + clusters_tree_->setEpsilon (1); + + // Normal estimation parameters + n3d_.setKSearch (k_); + n3d_.setSearchMethod (normals_tree_); + + // Table model fitting parameters + seg_.setDistanceThreshold (sac_distance_threshold_); + seg_.setMaxIterations (2000); + seg_.setNormalDistanceWeight (0.1); + seg_.setOptimizeCoefficients (true); + seg_.setModelType (pcl::SACMODEL_NORMAL_PLANE); + seg_.setMethodType (pcl::SAC_RANSAC); + seg_.setProbability (0.99); + + proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE); + bb_cluster_proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE); + + prism_.setHeightLimits (object_min_height_, object_max_height_); + + // Clustering parameters + cluster_.setClusterTolerance (object_cluster_tolerance_); + cluster_.setMinClusterSize (object_cluster_min_size_); + cluster_.setSearchMethod (clusters_tree_); + + // ---[ PassThroughFilter + pass_.setFilterLimits (float (min_z_bounds_), float (max_z_bounds_)); + pass_.setFilterFieldName ("z"); + pass_.setInputCloud (input_); + pass_.filter (*cloud_filtered_); + + if (int (cloud_filtered_->points.size ()) < k_) + { + PCL_WARN ("[DominantPlaneSegmentation] Filtering returned %lu points! Aborting.", + cloud_filtered_->points.size ()); + return; + } + + // Downsample the point cloud + grid_.setLeafSize (downsample_leaf_, downsample_leaf_, downsample_leaf_); + grid_.setDownsampleAllData (false); + grid_.setInputCloud (cloud_filtered_); + grid_.filter (*cloud_downsampled_); + + // ---[ Estimate the point normals + n3d_.setInputCloud (cloud_downsampled_); + n3d_.compute (*cloud_normals_); + + // ---[ Perform segmentation + seg_.setInputCloud (cloud_downsampled_); + seg_.setInputNormals (cloud_normals_); + seg_.segment (*table_inliers_, *table_coefficients_); + + if (table_inliers_->indices.size () == 0) + { + PCL_WARN ("[DominantPlaneSegmentation] No Plane Inliers points! Aborting."); + return; + } + + // ---[ Extract the plane + proj_.setInputCloud (cloud_downsampled_); + proj_.setIndices (table_inliers_); + proj_.setModelCoefficients (table_coefficients_); + proj_.filter (*table_projected_); + + // ---[ Estimate the convex hull + std::vector polygons; + CloudPtr table_hull (new Cloud ()); + hull_.setInputCloud (table_projected_); + hull_.reconstruct (*table_hull, polygons); + + // Compute the plane coefficients + Eigen::Vector4f model_coefficients; + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix; + + model_coefficients[0] = table_coefficients_->values[0]; + model_coefficients[1] = table_coefficients_->values[1]; + model_coefficients[2] = table_coefficients_->values[2]; + model_coefficients[3] = table_coefficients_->values[3]; + + // Need to flip the plane normal towards the viewpoint + Eigen::Vector4f vp (0, 0, 0, 0); + // See if we need to flip any plane normals + vp -= table_hull->points[0].getVector4fMap (); + vp[3] = 0; + // Dot product between the (viewpoint - point) and the plane normal + float cos_theta = vp.dot (model_coefficients); + // Flip the plane normal + if (cos_theta < 0) + { + model_coefficients *= -1; + model_coefficients[3] = 0; + // Hessian form (D = nc . p_plane (centroid here) + p) + model_coefficients[3] = -1 * (model_coefficients.dot (table_hull->points[0].getVector4fMap ())); + } + + //Set table_coeffs + table_coeffs_ = model_coefficients; + + // ---[ Get the objects on top of the table + pcl::PointIndices cloud_object_indices; + prism_.setInputCloud (input_); + prism_.setInputPlanarHull (table_hull); + prism_.segment (cloud_object_indices); + + pcl::ExtractIndices extract_object_indices; + extract_object_indices.setInputCloud (input_); + extract_object_indices.setIndices (boost::make_shared (cloud_object_indices)); + extract_object_indices.filter (*cloud_objects_); + + //create new binary pointcloud with intensity values (0 and 1), 0 for non-object pixels and 1 otherwise + pcl::PointCloud::Ptr binary_cloud (new pcl::PointCloud); + + { + binary_cloud->width = input_->width; + binary_cloud->height = input_->height; + binary_cloud->points.resize (input_->points.size ()); + binary_cloud->is_dense = input_->is_dense; + + size_t idx; + for (size_t i = 0; i < cloud_object_indices.indices.size (); ++i) + { + idx = cloud_object_indices.indices[i]; + binary_cloud->points[idx].getVector4fMap () = input_->points[idx].getVector4fMap (); + binary_cloud->points[idx].intensity = 1.0; + } + } + + //connected components on the binary image + + std::map connected_labels; + float c_intensity = 0.1f; + float intensity_incr = 0.1f; + + { + + int wsize = wsize_; + for (int i = 0; i < int (binary_cloud->width); i++) + { + for (int j = 0; j < int (binary_cloud->height); j++) + { + if (binary_cloud->at (i, j).intensity != 0) + { + //check neighboring pixels, first left and then top + //be aware of margins + + if ((i - 1) < 0 && (j - 1) < 0) + { + //top-left pixel + (*binary_cloud) (i, j).intensity = c_intensity; + } + else + { + if ((j - 1) < 0) + { + //top-row, check on the left of pixel to assign a new label or not + int left = check ((*binary_cloud) (i - 1, j), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_); + if (left) + { + //Nothing found on the left, check bigger window + + bool found = false; + for (int kk = 2; kk < wsize && !found; kk++) + { + if ((i - kk) < 0) + continue; + + int left = check ((*binary_cloud) (i - kk, j), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_); + if (left == 0) + { + found = true; + } + } + + if (!found) + { + c_intensity += intensity_incr; + (*binary_cloud) (i, j).intensity = c_intensity; + } + + } + } + else + { + if ((i - 1) == 0) + { + //check only top + int top = check ((*binary_cloud) (i, j - 1), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_); + if (top) + { + bool found = false; + for (int kk = 2; kk < wsize && !found; kk++) + { + if ((j - kk) < 0) + continue; + + int top = check ((*binary_cloud) (i, j - kk), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_); + if (top == 0) + { + found = true; + } + } + + if (!found) + { + c_intensity += intensity_incr; + (*binary_cloud) (i, j).intensity = c_intensity; + } + } + + } + else + { + //check left and top + int left = check ((*binary_cloud) (i - 1, j), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_); + int top = check ((*binary_cloud) (i, j - 1), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_); + + if (left == 0 && top == 0) + { + //both top and left had labels, check if they are different + //if they are, take the smallest one and mark labels to be connected.. + + if ((*binary_cloud) (i - 1, j).intensity != (*binary_cloud) (i, j - 1).intensity) + { + float smaller_intensity = (*binary_cloud) (i - 1, j).intensity; + float bigger_intensity = (*binary_cloud) (i, j - 1).intensity; + + if ((*binary_cloud) (i - 1, j).intensity > (*binary_cloud) (i, j - 1).intensity) + { + smaller_intensity = (*binary_cloud) (i, j - 1).intensity; + bigger_intensity = (*binary_cloud) (i - 1, j).intensity; + } + + connected_labels[bigger_intensity] = smaller_intensity; + (*binary_cloud) (i, j).intensity = smaller_intensity; + } + } + + if (left == 1 && top == 1) + { + //if none had labels, increment c_intensity + //search first on bigger window + bool found = false; + for (int dist = 2; dist < wsize && !found; dist++) + { + if (((i - dist) < 0) || ((j - dist) < 0)) + continue; + + int left = check ((*binary_cloud) (i - dist, j), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_); + int top = check ((*binary_cloud) (i, j - dist), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_); + + if (left == 0 && top == 0) + { + if ((*binary_cloud) (i - dist, j).intensity != (*binary_cloud) (i, j - dist).intensity) + { + float smaller_intensity = (*binary_cloud) (i - dist, j).intensity; + float bigger_intensity = (*binary_cloud) (i, j - dist).intensity; + + if ((*binary_cloud) (i - dist, j).intensity > (*binary_cloud) (i, j - dist).intensity) + { + smaller_intensity = (*binary_cloud) (i, j - dist).intensity; + bigger_intensity = (*binary_cloud) (i - dist, j).intensity; + } + + connected_labels[bigger_intensity] = smaller_intensity; + (*binary_cloud) (i, j).intensity = smaller_intensity; + found = true; + } + } + else if (left == 0 || top == 0) + { + //one had label + found = true; + } + } + + if (!found) + { + //none had label in the bigger window + c_intensity += intensity_incr; + (*binary_cloud) (i, j).intensity = c_intensity; + } + } + } + } + } + + } + } + } + } + + std::map clusters_map; + + { + std::map::iterator it; + + for (int i = 0; i < int (binary_cloud->width); i++) + { + for (int j = 0; j < int (binary_cloud->height); j++) + { + if (binary_cloud->at (i, j).intensity != 0) + { + //check if this is a root label... + it = connected_labels.find (binary_cloud->at (i, j).intensity); + while (it != connected_labels.end ()) + { + //the label is on the list, change pixel intensity until it has a root label + (*binary_cloud) (i, j).intensity = (*it).second; + it = connected_labels.find (binary_cloud->at (i, j).intensity); + } + + std::map::iterator it_indices; + it_indices = clusters_map.find (binary_cloud->at (i, j).intensity); + if (it_indices == clusters_map.end ()) + { + pcl::PointIndices indices; + clusters_map[binary_cloud->at (i, j).intensity] = indices; + } + + clusters_map[binary_cloud->at (i, j).intensity].indices.push_back (static_cast (j * binary_cloud->width + i)); + } + } + } + } + + clusters.resize (clusters_map.size ()); + + std::map::iterator it_indices; + int k = 0; + for (it_indices = clusters_map.begin (); it_indices != clusters_map.end (); it_indices++) + { + + if (int ((*it_indices).second.indices.size ()) >= object_cluster_min_size_) + { + + clusters[k] = CloudPtr (new Cloud ()); + pcl::copyPointCloud (*input_, (*it_indices).second.indices, *clusters[k]); + k++; + indices_clusters_.push_back((*it_indices).second); + } + } + + clusters.resize (k); + +} + +template void +pcl::apps::DominantPlaneSegmentation::compute (std::vector & clusters) +{ + + // Has the input dataset been set already? + if (!input_) + { + PCL_WARN ("[pcl::apps::DominantPlaneSegmentation] No input dataset given!\n"); + return; + } + + CloudConstPtr cloud_; + CloudPtr cloud_filtered_ (new Cloud ()); + CloudPtr cloud_downsampled_ (new Cloud ()); + pcl::PointCloud::Ptr cloud_normals_ (new pcl::PointCloud ()); + pcl::PointIndices::Ptr table_inliers_ (new pcl::PointIndices ()); + pcl::ModelCoefficients::Ptr table_coefficients_ (new pcl::ModelCoefficients ()); + CloudPtr table_projected_ (new Cloud ()); + CloudPtr table_hull_ (new Cloud ()); + CloudPtr cloud_objects_ (new Cloud ()); + CloudPtr cluster_object_ (new Cloud ()); + + typename pcl::search::KdTree::Ptr normals_tree_ (new pcl::search::KdTree); + typename pcl::search::KdTree::Ptr clusters_tree_ (new pcl::search::KdTree); + clusters_tree_->setEpsilon (1); + + // Normal estimation parameters + n3d_.setKSearch (k_); + n3d_.setSearchMethod (normals_tree_); + + // Table model fitting parameters + seg_.setDistanceThreshold (sac_distance_threshold_); + seg_.setMaxIterations (2000); + seg_.setNormalDistanceWeight (0.1); + seg_.setOptimizeCoefficients (true); + seg_.setModelType (pcl::SACMODEL_NORMAL_PLANE); + seg_.setMethodType (pcl::SAC_RANSAC); + seg_.setProbability (0.99); + + proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE); + bb_cluster_proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE); + + prism_.setHeightLimits (object_min_height_, object_max_height_); + + // Clustering parameters + cluster_.setClusterTolerance (object_cluster_tolerance_); + cluster_.setMinClusterSize (object_cluster_min_size_); + cluster_.setSearchMethod (clusters_tree_); + + // ---[ PassThroughFilter + pass_.setFilterLimits (float (min_z_bounds_), float (max_z_bounds_)); + pass_.setFilterFieldName ("z"); + pass_.setInputCloud (input_); + pass_.filter (*cloud_filtered_); + + if (int (cloud_filtered_->points.size ()) < k_) + { + PCL_WARN ("[DominantPlaneSegmentation] Filtering returned %lu points! Aborting.", + cloud_filtered_->points.size ()); + return; + } + + // Downsample the point cloud + grid_.setLeafSize (downsample_leaf_, downsample_leaf_, downsample_leaf_); + grid_.setDownsampleAllData (false); + grid_.setInputCloud (cloud_filtered_); + grid_.filter (*cloud_downsampled_); + + PCL_INFO ("[DominantPlaneSegmentation] Number of points left after filtering (%f -> %f): %lu out of %lu\n", + min_z_bounds_, max_z_bounds_, cloud_downsampled_->points.size (), input_->points.size ()); + + // ---[ Estimate the point normals + n3d_.setInputCloud (cloud_downsampled_); + n3d_.compute (*cloud_normals_); + + PCL_INFO ("[DominantPlaneSegmentation] %lu normals estimated. \n", cloud_normals_->points.size ()); + + // ---[ Perform segmentation + seg_.setInputCloud (cloud_downsampled_); + seg_.setInputNormals (cloud_normals_); + seg_.segment (*table_inliers_, *table_coefficients_); + + if (table_inliers_->indices.size () == 0) + { + PCL_WARN ("[DominantPlaneSegmentation] No Plane Inliers points! Aborting."); + return; + } + + // ---[ Extract the plane + proj_.setInputCloud (cloud_downsampled_); + proj_.setIndices (table_inliers_); + proj_.setModelCoefficients (table_coefficients_); + proj_.filter (*table_projected_); + + // ---[ Estimate the convex hull + std::vector polygons; + CloudPtr table_hull (new Cloud ()); + hull_.setInputCloud (table_projected_); + hull_.reconstruct (*table_hull, polygons); + + // Compute the plane coefficients + Eigen::Vector4f model_coefficients; + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix; + + model_coefficients[0] = table_coefficients_->values[0]; + model_coefficients[1] = table_coefficients_->values[1]; + model_coefficients[2] = table_coefficients_->values[2]; + model_coefficients[3] = table_coefficients_->values[3]; + + // Need to flip the plane normal towards the viewpoint + Eigen::Vector4f vp (0, 0, 0, 0); + // See if we need to flip any plane normals + vp -= table_hull->points[0].getVector4fMap (); + vp[3] = 0; + // Dot product between the (viewpoint - point) and the plane normal + float cos_theta = vp.dot (model_coefficients); + // Flip the plane normal + if (cos_theta < 0) + { + model_coefficients *= -1; + model_coefficients[3] = 0; + // Hessian form (D = nc . p_plane (centroid here) + p) + model_coefficients[3] = -1 * (model_coefficients.dot (table_hull->points[0].getVector4fMap ())); + } + + //Set table_coeffs + table_coeffs_ = model_coefficients; + + // ---[ Get the objects on top of the table + pcl::PointIndices cloud_object_indices; + prism_.setInputCloud (cloud_downsampled_); + prism_.setInputPlanarHull (table_hull); + prism_.segment (cloud_object_indices); + + pcl::ExtractIndices extract_object_indices; + extract_object_indices.setInputCloud (cloud_downsampled_); + extract_object_indices.setIndices (boost::make_shared (cloud_object_indices)); + extract_object_indices.filter (*cloud_objects_); + + if (cloud_objects_->points.size () == 0) + return; + + //down_.reset(new Cloud(*cloud_downsampled_)); + + // ---[ Split the objects into Euclidean clusters + std::vector clusters2; + cluster_.setInputCloud (cloud_downsampled_); + cluster_.setIndices (boost::make_shared (cloud_object_indices)); + cluster_.extract (clusters2); + + PCL_INFO ("[DominantPlaneSegmentation::compute()] Number of clusters found matching the given constraints: %lu.\n", + clusters2.size ()); + + clusters.resize (clusters2.size ()); + + for (size_t i = 0; i < clusters2.size (); ++i) + { + clusters[i] = CloudPtr (new Cloud ()); + pcl::copyPointCloud (*cloud_downsampled_, clusters2[i].indices, *clusters[i]); + } +} + +template +void +pcl::apps::DominantPlaneSegmentation::compute_full (std::vector & clusters) +{ + + // Has the input dataset been set already? + if (!input_) + { + PCL_WARN ("[pcl::apps::DominantPlaneSegmentation] No input dataset given!\n"); + return; + } + + CloudConstPtr cloud_; + CloudPtr cloud_filtered_ (new Cloud ()); + CloudPtr cloud_downsampled_ (new Cloud ()); + pcl::PointCloud::Ptr cloud_normals_ (new pcl::PointCloud ()); + pcl::PointIndices::Ptr table_inliers_ (new pcl::PointIndices ()); + pcl::ModelCoefficients::Ptr table_coefficients_ (new pcl::ModelCoefficients ()); + CloudPtr table_projected_ (new Cloud ()); + CloudPtr table_hull_ (new Cloud ()); + CloudPtr cloud_objects_ (new Cloud ()); + CloudPtr cluster_object_ (new Cloud ()); + + typename pcl::search::KdTree::Ptr normals_tree_ (new pcl::search::KdTree); + typename pcl::search::KdTree::Ptr clusters_tree_ (new pcl::search::KdTree); + clusters_tree_->setEpsilon (1); + + // Normal estimation parameters + n3d_.setKSearch (10); + n3d_.setSearchMethod (normals_tree_); + + // Table model fitting parameters + seg_.setDistanceThreshold (sac_distance_threshold_); + seg_.setMaxIterations (2000); + seg_.setNormalDistanceWeight (0.1); + seg_.setOptimizeCoefficients (true); + seg_.setModelType (pcl::SACMODEL_NORMAL_PLANE); + seg_.setMethodType (pcl::SAC_MSAC); + seg_.setProbability (0.98); + + proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE); + bb_cluster_proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE); + + prism_.setHeightLimits (object_min_height_, object_max_height_); + + // Clustering parameters + cluster_.setClusterTolerance (object_cluster_tolerance_); + cluster_.setMinClusterSize (object_cluster_min_size_); + cluster_.setSearchMethod (clusters_tree_); + + // ---[ PassThroughFilter + pass_.setFilterLimits (float (min_z_bounds_), float (max_z_bounds_)); + pass_.setFilterFieldName ("z"); + pass_.setInputCloud (input_); + pass_.filter (*cloud_filtered_); + + if (int (cloud_filtered_->points.size ()) < k_) + { + PCL_WARN ("[DominantPlaneSegmentation] Filtering returned %lu points! Aborting.", + cloud_filtered_->points.size ()); + return; + } + + // Downsample the point cloud + grid_.setLeafSize (downsample_leaf_, downsample_leaf_, downsample_leaf_); + grid_.setDownsampleAllData (false); + grid_.setInputCloud (cloud_filtered_); + grid_.filter (*cloud_downsampled_); + + PCL_INFO ("[DominantPlaneSegmentation] Number of points left after filtering&downsampling (%f -> %f): %lu out of %lu\n", + min_z_bounds_, max_z_bounds_, cloud_downsampled_->points.size (), input_->points.size ()); + + // ---[ Estimate the point normals + n3d_.setInputCloud (cloud_downsampled_); + n3d_.compute (*cloud_normals_); + + PCL_INFO ("[DominantPlaneSegmentation] %lu normals estimated. \n", cloud_normals_->points.size ()); + + // ---[ Perform segmentation + seg_.setInputCloud (cloud_downsampled_); + seg_.setInputNormals (cloud_normals_); + seg_.segment (*table_inliers_, *table_coefficients_); + + if (table_inliers_->indices.size () == 0) + { + PCL_WARN ("[DominantPlaneSegmentation] No Plane Inliers points! Aborting."); + return; + } + + // ---[ Extract the plane + proj_.setInputCloud (cloud_downsampled_); + proj_.setIndices (table_inliers_); + proj_.setModelCoefficients (table_coefficients_); + proj_.filter (*table_projected_); + + // ---[ Estimate the convex hull + std::vector polygons; + CloudPtr table_hull (new Cloud ()); + hull_.setInputCloud (table_projected_); + hull_.reconstruct (*table_hull, polygons); + + // Compute the plane coefficients + Eigen::Vector4f model_coefficients; + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix; + + model_coefficients[0] = table_coefficients_->values[0]; + model_coefficients[1] = table_coefficients_->values[1]; + model_coefficients[2] = table_coefficients_->values[2]; + model_coefficients[3] = table_coefficients_->values[3]; + + // Need to flip the plane normal towards the viewpoint + Eigen::Vector4f vp (0, 0, 0, 0); + // See if we need to flip any plane normals + vp -= table_hull->points[0].getVector4fMap (); + vp[3] = 0; + // Dot product between the (viewpoint - point) and the plane normal + float cos_theta = vp.dot (model_coefficients); + // Flip the plane normal + if (cos_theta < 0) + { + model_coefficients *= -1; + model_coefficients[3] = 0; + // Hessian form (D = nc . p_plane (centroid here) + p) + model_coefficients[3] = -1 * (model_coefficients.dot (table_hull->points[0].getVector4fMap ())); + } + + //Set table_coeffs + table_coeffs_ = model_coefficients; + + // ---[ Get the objects on top of the table + pcl::PointIndices cloud_object_indices; + prism_.setInputCloud (cloud_filtered_); + prism_.setInputPlanarHull (table_hull); + prism_.segment (cloud_object_indices); + + pcl::ExtractIndices extract_object_indices; + extract_object_indices.setInputCloud (cloud_downsampled_); + extract_object_indices.setIndices (boost::make_shared (cloud_object_indices)); + extract_object_indices.filter (*cloud_objects_); + + if (cloud_objects_->points.size () == 0) + return; + + // ---[ Split the objects into Euclidean clusters + std::vector clusters2; + cluster_.setInputCloud (cloud_filtered_); + cluster_.setIndices (boost::make_shared (cloud_object_indices)); + cluster_.extract (clusters2); + + PCL_INFO ("[DominantPlaneSegmentation::compute_full()] Number of clusters found matching the given constraints: %lu.\n", + clusters2.size ()); + + clusters.resize (clusters2.size ()); + + for (size_t i = 0; i < clusters2.size (); ++i) + { + clusters[i] = CloudPtr (new Cloud ()); + pcl::copyPointCloud (*cloud_filtered_, clusters2[i].indices, *clusters[i]); + } +} + +#define PCL_INSTANTIATE_DominantPlaneSegmentation(T) template class PCL_EXPORTS pcl::apps::DominantPlaneSegmentation; diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/cloud.h b/pcl-1.7/pcl/apps/point_cloud_editor/cloud.h new file mode 100644 index 0000000..f3bd909 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/cloud.h @@ -0,0 +1,472 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// +/// @file cloud.h +/// @details The declaration of the class representing the cloud data structure. +/// A cloud represents a single 3D set of points and associated attributes. +/// This class allows for the basic manipulation of the cloud as well as its +/// display. +/// @author Yue Li and Matthew Hielsberg + +#ifndef CLOUD_H_ +#define CLOUD_H_ + +#include +#include +#include + +/// @brief A wrapper which allows to use any implementation of cloud provided by +/// a third-party library. +/// @details This wrapper attempts to create a simple interface for displaying +/// and modifying point clouds. It is common for point clouds to have +/// coordinate values that are exceptionally large, especially when dealing +/// with the GIS community. As such this class shifts the stored point cloud +/// according to the minimum in each of the coordinate directions. The +/// interface presented by this class then serves the shifted points in order to +/// reduce any precision errors that may occur due to sums of large values. +/// Functions also exist for accessing the unshifted versions of the points, +/// however most operations performed on the cloud will expect it to live near +/// the origin. +// XXX - handle shifting upon setting of a Cloud3D +// XXX - add functions for retrieving an unshifted Cloud3D +// XXX - add functions for retrieveing unshifted points by index +// XXX - mark access functions below as returning shifted values +class Cloud : public Statistics +{ + public: + /// @brief Default Constructor + Cloud (); + + /// @brief Copy Constructor + /// @details This constructor creates a copy of the passed cloud. The + /// values of the member variables of the passed cloud are deep copied. + /// @param copy The cloud object to be used to initialize this cloud object. + Cloud (const Cloud& copy); + + /// @brief Construct a cloud from a Cloud3D. + /// @details This constructor creates a cloud object with the passed + /// cloud object stored with the internal representation. The member + /// variables of this object are initialized but not set. + Cloud (const Cloud3D& cloud, bool register_stats=false); + + /// @brief Destructor + ~Cloud (); + + /// @brief Equal Operator + /// @details Deep copies all the state of the passed cloud to this cloud. + /// @param cloud The cloud object whose status to be copied to this object + /// @return A reference to this cloud containing the new values. + Cloud& + operator= (const Cloud& cloud); + + /// @brief Subscript Operator + /// @details This operator returns a reference to the point with the + /// passed index in this cloud object. + /// @pre The index passed is expected to be within the limits of the cloud. + /// For debugging this is currently checked by an assert. + /// @param index The index of the point to be returned. + /// @return A reference to the indexed point. + Point3D& + operator[] (unsigned int index); + + /// @brief Subscript Operator + /// @details This operator returns a const reference to the point with the + /// passed index in this cloud object. + /// @pre The index passed is expected to be within the limits of the cloud. + /// For debugging this is currently checked by an assert. + /// @param index The index of the point to be returned. + /// @return A const reference to the indexed point. + const Point3D& + operator[] (unsigned int index) const; + + /// @brief Returns the center of the point cloud + /// @param x The x coordinate of the center (computed as the average point). + /// @param y The y coordinate of the center (computed as the average point). + /// @param z The z coordinate of the center (computed as the average point). + inline + void + getCenter (float &x, float &y, float &z) const + { + x = center_xyz_[X]; y = center_xyz_[Y]; z = center_xyz_[Z]; + } + + /// @brief Returns the scaling factor for the point cloud + /// @return The scaling factor + inline + float + getScalingFactor() const + { + return (display_scale_); + } + + /// @brief Gets the transform matrix. + /// @details The returned matrix is used to transform the cloud for + /// rendering only and does not affect the values of the points stored. + /// @return A 1-D array representing (4 x 4) matrix in + /// using OpenGL's column-major format. + inline + const float* + getMatrix () const + { + return (cloud_matrix_); + } + + /// @brief Sets the transform matrix for the cloud. + /// @details The passed matrix is used to transform the cloud for + /// rendering only and does not affect the values of the points stored. + /// @pre The passed pointer represents a matrix having valid memory of at + /// least MATRIX_SIZE elements. + /// @param matrix a 1-D array representing (4 x 4) matrix in + /// using OpenGL's column-major format. + void + loadMatrix (const float* matrix); + + /// @brief Right multiplies the cloud matrix with the passed matrix + /// @details The application of this matrix effectively transforms the + /// cloud from its current state. The passed matrix is used for display + /// only and does not affect the values of the points stored. + /// @pre The passed pointer represents a matrix having valid memory of at + /// least MATRIX_SIZE elements. + /// @param matrix a 1-D array representing (4 x 4) matrix in + /// using OpenGL's column-major format. + void + multMatrix (const float* matrix); + + /// @brief Sets the selection transform matrix to the one passed. + /// @details The selection matrix represents the local transformations + /// applied to the selected points. The matrix is used relative to the + /// cloud's state after the application of its own matrices which can be + /// modified by loadMatrix and multMatrix functions. + /// @pre The passed pointer represents a matrix having valid memory of at + /// least MATRIX_SIZE elements. + /// @param matrix a 1-D array representing (4 x 4) matrix in + /// using OpenGL's column-major format. + /// @sa loadMatrix multMatrix + void + setSelectionRotation (const float* matrix); + + void + setSelectionTranslation (float dx, float dy, float dz); + + /// @brief Sets the selected points. + /// @details The cloud object is responsible for its display. As we have + /// tried to adopt a lazy approach in the application of modifications to + /// the cloud, the cloud must be notified of the selected points. This is + /// required as the user may move the selected points and we do not wish for + /// the selected points to be drawn twice, once in the user-updated position + /// and another in the points original location. + /// @pre Assumes that the selection stores the selected indices of the + /// points sorted. + /// @param A pointer pointing to a selection object. + /// @remarks This has been implemented using a weak pointer to allow a lazy + /// update to occur. When a selection is destroyed we can switch to + /// a faster rendering mode; this also occurs if the selection object is + /// empty. + void + setSelection (SelectionPtr selection_ptr); + + /// @brief Sets the RGB values for coloring points in COLOR_BY_PURE mode. + /// @param r the value for red color + /// @param g the value for the green color + /// @param b the value for the blue color + void + setRGB (float r, float g, float b); + + /// @brief Sets the RGB values used for highlighting the selected points. + /// @param r the value for red color + /// @param g the value for the green color + /// @param b the value for the blue color + void + setHighlightColor (float r, float g, float b); + + /// @brief Renders the cloud and highlights any selected points. + /// @param disableHighlight Defaults to false. If true the selected points + /// will not be drawn. + /// @sa setColorRampAxis, setColorRamp + void + draw (bool disable_highlight = false) const; + + /// @brief Renders the cloud and highlights any selected points. + /// @details The colors of the non-selected points come from a 1D texture + /// which is implemented by a color ramp. + void + drawWithTexture () const; + + /// @brief Renders the cloud and highlights any selected points. + /// @details The colors of the non-selected points uses the native color + /// of the original points + /// @pre The cloud should be originally colored. + void + drawWithRGB () const; + + /// @brief Renders the cloud and highlights any selected points. + /// @details The non-selected points are in a single color + void + drawWithPureColor () const; + + /// @brief Renders the cloud with the color used for highlighting the + /// selected points. + void + drawWithHighlightColor () const; + + /// @brief Sets the axis along which the displyed points should have the + /// color ramp applied. + /// @param a The axis id describing which direction the ramp should be + /// applied. + inline + void + setColorRampAxis(Axis a) + { + color_ramp_axis_ = a; + } + + /// @brief Enables/Disables the use of the color ramp in display. + /// @details The color ramp aids in the visualization of the displayed + /// points by varying the color according to a linear ramp along one of the + /// axes. + /// @param onOff True enables the use of the color ramp and false disables. + inline + void + setColorRamp(bool on_off) + { + use_color_ramp_ = on_off; + } + + /// @brief Appends a new 3D point to the cloud. + /// @param point the new point to be added. + void + append (const Point3D& point); + + /// @brief Appends the points of the passed cloud to this cloud. + /// @param cloud the cloud to be appended to this cloud. + void + append (const Cloud& cloud); + + /// @brief Removes the points in selection from the cloud. + /// @details Each indexed point in the selection will be removed from this + /// container. + /// @pre The index of each point in the selection is expected to be within + /// the limits of the cloud. For debugging this is currently checked by an + /// assert. Also, it is expected that the selection indices are sorted. + /// @param selection a selection object which stores the indices of the + /// selected points. + /// @remarks This function requires the use of Selection::isSelected and its + /// complexity can vary based on the implementation of that function. + void + remove (const Selection& selection); + + /// @brief Gets the size of the cloud + inline + unsigned int + size () const + { + return (cloud_.size()); + } + + /// @brief Sets the size of the cloud of this object to the passed new size + /// @details If the size is smaller than the current size, only the first + /// new_size points will be kept, the rest being dropped. If new_size is + /// larger than the current size, the new points required to fill the + /// extended region are created with its default constructor. + /// @param new_size the new size of the cloud. + void + resize (unsigned int new_size); + + /// @brief Removes all points from the cloud and resets the object + void + clear (); + + /// @brief Set the sizes used for rendering the unselected points. + /// @param size The size, in pixels, used for rendering the points. + void + setPointSize (int size); + + /// @brief Set the sizes used for rendering the selected points. + /// @param size The size, in pixels, used for rendering the points. + void + setHighlightPointSize (int size); + + /// @brief Compute the transformed coordinates of the indexed point in the + /// cloud according to the object transform. + /// @details This applies the object rotation and translation of the + /// indexed point according to the user transforms. + /// @param index The index of the point whose coordinates are + /// transformed. + /// @return The transformed point. + Point3D + getObjectSpacePoint (unsigned int index) const; + + /// @brief Compute the transformed coordinates of the indexed point in the + /// cloud to match the display. + /// @details To save on computation, the points in the display are not + /// transformed on the cpu side, instead the gpu is allowed to manipulate + /// them for display. This function performs the same manipulation and + /// returns the transformed point. + /// @param index The index of the point whose coordinates are + /// transformed according to the display. + /// @return The transformed point. + Point3D + getDisplaySpacePoint (unsigned int index) const; + + /// @brief Compute the transformed coordinates of the all the points in the + /// cloud to match the display. + /// @details To save on computation, the points in the display are not + /// transformed on the cpu side, instead the gpu is allowed to manipulate + /// them for display. This function performs the same manipulation and + /// returns the transformed points. + /// @param pts a vector used to store the points whose coordinates are + /// transformed. + void + getDisplaySpacePoints (std::vector& pts) const; + + /// @brief Returns a const reference to the internal representation of this + /// object. + const Cloud3D& + getInternalCloud () const; + + /// @brief Places the points in the copy buffer into the cloud according + /// to the indices in the selection. + void + restore (const CopyBuffer& copy_buffer, const Selection& selection); + + /// @brief Get statistics of the selected points in string. + std::string + getStat () const; + + /// Default Point Size + static const float DEFAULT_POINT_DISPLAY_SIZE_; + /// Default Highlight Point Size + static const float DEFAULT_POINT_HIGHLIGHT_SIZE_; + /// Default Point Color - Red componenet + static const float DEFAULT_POINT_DISPLAY_COLOR_RED_; + /// Default Point Color - Green componenet + static const float DEFAULT_POINT_DISPLAY_COLOR_GREEN_; + /// Default Point Color - Blue componenet + static const float DEFAULT_POINT_DISPLAY_COLOR_BLUE_; + /// Default Point Highlight Color - Red componenet + static const float DEFAULT_POINT_HIGHLIGHT_COLOR_RED_; + /// Default Point Highlight Color - Green componenet + static const float DEFAULT_POINT_HIGHLIGHT_COLOR_GREEN_; + /// Default Point Highlight Color - Blue componenet + static const float DEFAULT_POINT_HIGHLIGHT_COLOR_BLUE_; + + private: + /// @brief Computes the point cloud related members. + /// @details The cloud keeps track of certain values related to the points + /// in the cloud. These include the minimum coordinates and the ranges in + /// the coordinate directions. + /// @pre Assumes that there is at least one dimension of the point cloud + /// that has non-zero range. + void + updateCloudMembers (); + + /// @brief Enable the texture used for rendering the cloud + void + enableTexture () const; + + /// @brief Disable the texture used for rendering the cloud + void + disableTexture() const; + + /// The internal representation of the cloud + Cloud3D cloud_; + + /// @breif A weak pointer pointing to the selection object. + /// @details This implementation uses the weak pointer to allow for a lazy + /// update of the cloud if the selection object is destroyed. + boost::weak_ptr selection_wk_ptr_; + + /// Flag that indicates whether a color ramp should be used (true) or not + /// (false) when displaying the cloud + bool use_color_ramp_; + + /// Flag that indicates whether the cloud should be colored with its own + /// color + bool use_native_color_; + + /// The axis which the color ramp is to be applied when drawing the cloud + Axis color_ramp_axis_; + + /// A scale value used to normalize the display of clouds. This is simply + /// one over the maximum of the range in each coordinate direction + float display_scale_; + + /// The center coordinate values in the point cloud. This is used for + /// display. + float center_xyz_[XYZ_SIZE]; + + /// The minimum coordinate values in the point cloud. This is used for + /// display. + float min_xyz_[XYZ_SIZE]; + + /// The maximum coordinate values in the point cloud. This is used for + /// display. + float max_xyz_[XYZ_SIZE]; + + /// A (4x4) OpenGL transform matrix for rendering the cloud + float cloud_matrix_[MATRIX_SIZE]; + + /// A (4x4) OpenGL transform matrix specifying the relative transformations + /// that are applied to the selected points in the cloud when drawing them + /// as highlighted. + float select_matrix_[MATRIX_SIZE]; + + /// A vector of indices for every point in the cloud. This vector is used + /// when a selection is set and sorted such that the selected indices + /// appear first in the vector. This is used during display to allow for + /// separate indexed drawing of the selection and the point cloud. Note + /// that this vector is partitioned according to selected and not-selected. + IndexVector partitioned_indices_; + + /// The size used for rendering the unselected points in the cloud + float point_size_; + + /// The size used for rendering the selected points in the cloud + float selected_point_size_; + + /// The R, G, B values used for coloring each points when the current + /// color scheme is COLOR_BY_PURE. + float color_[RGB]; + + /// The R, G, B values used for highlighting the selected points. + float highlight_color_[RGB]; + + /// The translations on x, y, and z axis on the selected points. + float select_translate_x_, select_translate_y_, select_translate_z_; +}; +#endif // CLOUD_H_ + + + + diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/cloudEditorWidget.h b/pcl-1.7/pcl/apps/point_cloud_editor/cloudEditorWidget.h new file mode 100644 index 0000000..e476e3b --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/cloudEditorWidget.h @@ -0,0 +1,316 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// +/// +/// @file cloudEditorWidget.h +/// @details the declaration of the class representing the widgets +/// which are used for viewing and editing point clouds +/// @author Yue Li and Matthew Hielsberg + +#ifndef CLOUD_EDITOR_WIDGET_H_ +#define CLOUD_EDITOR_WIDGET_H_ + +#include +#include +#include +#include +#include +#include +#include +#include + +/// @brief class declaration for the widget for editing and viewing +/// point clouds. +class CloudEditorWidget : public QGLWidget +{ + Q_OBJECT + public: + /// @brief Constructor + /// @param parent a pointer which points to the parent widget + CloudEditorWidget (QWidget *parent = 0); + + /// @brief Destructor + ~CloudEditorWidget (); + + /// @brief Attempts to load the point cloud designated by the passed file + /// name. + /// @param filename The name of the point cloud file to be loaded. + /// @remarks throws if the passed file can not be loaded. + void + loadFile(const std::string &filename); + + public slots: + /// @brief Loads a new cloud. + void + load (); + + /// @brief Saves a cloud to a .pcd file. The current format is ASCII. + void + save (); + + /// @brief Toggles the blend mode used to render the non-selected points + void + toggleBlendMode (); + + /// @brief Switches to the view mode. + void + view (); + + /// @brief Enters click selection mode. + void + select1D (); + + /// @brief Enters 2D selection mode. + void + select2D (); + + /// @brief Enters 3D selection mode. + void + select3D (); + + /// @brief Inverts the current selection. + void + invertSelect (); + + /// @brief Cancels the current selection. + void + cancelSelect (); + + /// @brief Copies the selected points. + void + copy (); + + /// @brief Pastes the copied points to the cloud. + void + paste (); + + /// @brief Removes the selected points. + void + remove (); + + /// @brief Copies and then removes the selected points. + void + cut (); + + /// @brief Enters the mode where users are able to translate the selecte + /// points. + void + transform (); + + /// @brief Denoises the current cloud. + void + denoise (); + + /// @brief Undoes last change. + void + undo (); + + /// @brief Increases the size of the unselected points. + void + increasePointSize (); + + /// @brief Decreases the size of the unselected points. + void + decreasePointSize (); + + /// @brief Increases the size of the selected points. + void + increaseSelectedPointSize (); + + /// @brief Decreases the size of the selected points. + void + decreaseSelectedPointSize (); + + /// @brief Sets the size of the unselected points. + void + setPointSize (int size); + + /// @brief Sets the size of the selected points. + void + setSelectedPointSize (int size); + + /// @brief Colors the unselected points by its native color. + void + colorByRGB (); + + /// @brief Colors the unselected points with a color ramp based on the X + /// values of the points + void + colorByX (); + + /// @brief Colors the unselected points with a color ramp based on the Y + /// values of the points + void + colorByY (); + + /// @brief Colors the unselected points with a color ramp based on the Z + /// values of the points + void + colorByZ (); + + /// @brief Colors the unselected points using an single color. + void + colorByPure (); + + /// @brief Turn on the dialog box showing the statistics of the cloud. + void + showStat (); + + //signals: + + protected: + /// initializes GL + void + initializeGL (); + + /// the rendering function. + void + paintGL (); + + /// resizes widget + void + resizeGL (int width, int height); + + /// mouse press control + void + mousePressEvent (QMouseEvent *event); + + /// mouse move control + void + mouseMoveEvent (QMouseEvent *event); + + /// mouse release control + void + mouseReleaseEvent (QMouseEvent *event); + + /// key press control + void + keyPressEvent (QKeyEvent *event); + + private: + + /// @brief Attempts to load a pcd file + /// @param filename The name of the pcd file to be loaded. + /// @remarks throws if the passed file can not be loaded. + void + loadFilePCD(const std::string &filename); + + /// @brief Adds all of our file loader functions to the extension map + void + initFileLoadMap(); + + /// @brief Returns true if the cloud stored in a file is colored + /// @param fileName a reference to a string storing the path of a cloud + bool + isColored (const std::string &fileName) const; + + /// @brief swap the values of r and b in each point of the cloud. + void + swapRBValues (); + + /// @brief initializes the map between key press events and the + /// corresponding functors. + void + initKeyMap(); + + struct ExtCompare + { + bool + operator()(std::string lhs, std::string rhs) const + { + stringToLower(lhs); + stringToLower(rhs); + return lhs.compare(rhs) < 0; + } + }; + typedef boost::function + FileLoadFunc; + typedef std::map FileLoadMap; + /// a map of file type extensions to loader functions. + FileLoadMap cloud_load_func_map_; + + /// a pointer to the cloud being edited. + CloudPtr cloud_ptr_; + + /// The display size, in pixels, of the cloud points + unsigned int point_size_; + + /// The display size, in pixels, of the selected cloud points + unsigned int selected_point_size_; + + /// The transformation tool being used. Either a cloud transform tool or + /// a selection transform tool is activated at a time. + boost::shared_ptr tool_ptr_; + + /// a pointer to the selection object + SelectionPtr selection_ptr_; + + /// a pointer to the copy buffer object. + CopyBufferPtr copy_buffer_ptr_; + + /// a pointer to the command queue object + CommandQueuePtr command_queue_ptr_; + + /// The camera field of view + double cam_fov_; + + /// The camera aspect ratio + double cam_aspect_; + + /// The camera near clipping plane + double cam_near_; + + /// The camera far clipping plane + double cam_far_; + + /// @brief Initialize the texture used for rendering the cloud + void + initTexture (); + + /// The current scheme used for coloring the whole cloud + ColorScheme color_scheme_; + + /// A flag indicates whether the cloud is initially colored or not. + bool is_colored_; + + typedef boost::function KeyMapFunc; + /// map between pressed key and the corresponding functor + std::map key_map_; + + /// a dialog displaying the statistics of the cloud editor + StatisticsDialog stat_dialog_; + + +}; +#endif // CLOUD_EDITOR_WIDGET_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/cloudTransformTool.h b/pcl-1.7/pcl/apps/point_cloud_editor/cloudTransformTool.h new file mode 100644 index 0000000..51ab68b --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/cloudTransformTool.h @@ -0,0 +1,149 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file cloudTransformTool.h +/// @details Provides a tool for changing the view of cloud through a simple +/// transformation matrix using inputs from the mouse. +/// @author Yue Li and Matthew Hielsberg + +#ifndef CLOUD_TRANSFORM_TOOL_H_ +#define CLOUD_TRANSFORM_TOOL_H_ + +#include +#include +#include + +/// @brief The cloud transform tool computes the transform matrix from user's +/// mouse operation. It then updates the cloud with the new transform matrices +/// to make the cloud be rendered appropriately. +class CloudTransformTool : public ToolInterface +{ + public: + /// @brief Constructor + /// @param cloud_ptr a shared pointer pointing to the cloud object. + CloudTransformTool (CloudPtr cloud_ptr); + + /// @brief Destructor + ~CloudTransformTool (); + + /// @brief Initialize the current transform with mouse screen coordinates + /// and key modifiers. + /// @param x the x value of the mouse screen coordinates. + /// @param y the y value of the mouse screen coordinates. + /// @param modifiers The keyboard modifiers. This function does not make + /// use of this parameter. + /// @param buttons The state of the mouse buttons. This function does not + /// make use of this parameter. + void + start (int x, int y, BitMask modifiers, BitMask buttons); + + /// @brief Updates the transform matrix of this object with mouse screen + /// coordinates and key modifiers. + /// @details When the LEFT mouse button is down the motion of the mouse is + /// used to compute various transforms for the cloud display. Depending on + /// the modifiers, the transformation matrix is computed correspondingly. + /// When shift is pressed, the motion of mouse indicates a scale. If + /// no key modifiers is pressed, the mouse move indicates a rotation. The + /// control key pans the display, and the alt key translates along the + /// z-axis. + /// @param x The x value of the mouse screen coordinates. + /// @param y The y value of the mouse screen coordinates. + /// @param modifiers the key modifier. SHIFT scales the point cloud + /// display. CONTROL pans the point cloud parallel to the view plane. ALT + /// moves the point cloud in/out along the z-axis (perpendicular to the + /// view plane). If no modifier is pressed then the cloud display is + /// rotated. + /// @param buttons The LEFT mouse button must be pressed for any transform + /// to be generated. All other buttons are ignored. + void + update (int x, int y, BitMask modifiers, BitMask buttons); + + /// @brief Updates the transform matrix of this object with mouse screen + /// coordinates and key modifiers. Then right multiplies the cloud_matrix_ + /// matrix of the cloud object with the transform matrix of this object. + /// @details This function is not required by this tool + void + end (int, int, BitMask, BitMask) + { + } + + /// @brief This function does nothing for this cloud transform tool. + void + draw() const + { + } + + private: + + /// generate translate matrix for the xy plane + void + getTranslateMatrix (int dx, int dy, float* matrix); + + /// generate translate matrix for the z direction + void + getZTranslateMatrix (int dy, float* matrix); + + /// generate scale matrix + void + getScaleMatrix (int dy, float* matrix); + + /// the transform matrix to be used for updating the coordinates of all + /// the points in the cloud + float transform_matrix_[MATRIX_SIZE]; + + /// a shared pointer pointing to the cloud object. + CloudPtr cloud_ptr_; + + /// the trackball associated with this transform + TrackBall trackball_; + + /// last recorded mouse positions + int x_, y_; + + /// scaling factor used to control the speed which the display scales the + /// point cloud + float scale_factor_; + + /// scaling factor used to control the speed which the display translates + /// the point cloud + float translate_factor_; + + /// default scaling factor + static const float DEFAULT_SCALE_FACTOR_; + + /// default translation factor + static const float DEFAULT_TRANSLATE_FACTOR_; +}; +#endif //CLOUD_TRANSFORM_TOOL_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/command.h b/pcl-1.7/pcl/apps/point_cloud_editor/command.h new file mode 100644 index 0000000..258df8c --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/command.h @@ -0,0 +1,104 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file command.h +/// @details The abstract parent class for each class implementing a specific +/// command of the cloud editor. This class is designed to be used with the +/// CommandQueue. +/// @author Yue Li and Matthew Hielsberg + +#ifndef COMMAND_H_ +#define COMMAND_H_ + +#include + +/// @brief The abstract parent class of all the command classes. Commands are +/// non-copyable. +class Command +{ + public: + /// @brief Destructor + virtual ~Command () + { + } + + protected: + /// Allows command queues to be the only objects which are able to execute + /// commands. + friend class CommandQueue; + + /// @brief The default constructor. + /// @details Derived commands are assumed to have undo by default. Each + /// is free to override this. + Command () : has_undo_(true) + { + } + + /// @brief Returns true if the command has an undo function. + inline + bool + hasUndo () const + { + return (has_undo_); + } + + /// @brief Executes the command. + virtual + void + execute () = 0; + + /// @brief Undos the command. + virtual + void + undo () = 0; + + /// @brief a flag indicates whether the command has an undo function. + bool has_undo_; + + private: + /// @brief Copy Constructor - object is non-copyable + Command (const Command&) + { + assert(false); + } + + /// @brief Equal Operator - object is non-copyable + Command& + operator= (const Command&) + { + assert(false); return (*this); + } +}; +#endif //COMMAND_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/commandQueue.h b/pcl-1.7/pcl/apps/point_cloud_editor/commandQueue.h new file mode 100644 index 0000000..199afad --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/commandQueue.h @@ -0,0 +1,122 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file commandQueue.h +/// @details This object provides a dequeue of commands as well as operations to +/// manipulate the deque. This class is designed to work with Command objects +/// in order to both execute them and undo them in the proper order. +/// @author Yue Li and Matthew Hielsberg + +#ifndef COMMAND_QUEUE_H_ +#define COMMAND_QUEUE_H_ + +#include +#include + +/// @brief A structure for managing commands +/// @details A command queue object provides a dequeue of commands as well as +/// operations to manipulate the commands in the queue. Operations include +/// executing and undoing the commands in the queue. A command queue object +/// is non-copyable. +class CommandQueue +{ + public: + /// @brief Defaut Constructor + /// @details Creates a command queue object and makes its depth limit + /// be the default value. + CommandQueue (); + + /// @brief Constructor + /// @details Create a command queue with specified depth limit. + /// @param max_size the value to be used to set the depth limit of this + /// object. + CommandQueue (unsigned int max_size); + + /// @brief Destructor + ~CommandQueue () + { + } + + /// @brief Executes a command. If the command has an undo function, then + /// adds the command to the queue. + /// @param command_ptr a shared pointer pointing to a command object whose + /// execute function will be invoked by this object. + void + execute (CommandPtr); + + /// @brief Undoes the last command by poping the tail of the queue, invoke + /// the undo function of the command. + void + undo (); + + /// @breif Changes the command history limit. + /// @details If the passed size is smaller than the current size then the + /// oldest commands are removed (their undo functions are not called). + /// @param size The new maximum number of commands that may exist in this + /// queue for undo purposes. + /// @return The actual maximum size set. It may happen that the passed + /// value is too large and cannot be set. + unsigned int + setMaxSize(unsigned int size); + + /// @brief The default maximal size of the depth limit + static const unsigned int DEFAULT_MAX_SIZE_ = 200; + + private: + /// @brief Copy constructor - object is non-copyable + CommandQueue(const CommandQueue&) + { + assert(false); + } + + /// @brief Equal operator - object is non-copyable + CommandQueue& + operator= (const CommandQueue&) + { + assert(false); return (*this); + } + + /// @brief Enforces the depth limit of the command queue. If the depth is + /// larger than the depth limit, a deque operation will be invoked. + void + enforceDequeLimit (); + + /// The internal representation of this object. + std::deque command_deque_; + + /// The depth limit of the command queue. + unsigned int depth_limit_; +}; +#endif // COMMAND_QUEUE_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/common.h b/pcl-1.7/pcl/apps/point_cloud_editor/common.h new file mode 100644 index 0000000..71851ce --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/common.h @@ -0,0 +1,87 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file common.h +/// @details The set of simple common operations used throughout the project. +/// @author Yue Li and Matthew Hielsberg + +#ifndef COMMON_H_ +#define COMMON_H_ + +#include + +/// @brief Sets an array representing a 4x4 matrix to the identity +/// @param matrix A pointer to memory representing at least MATRIX_SIZE +/// elements +/// @pre Assumes the pointer is valid. +void +setIdentity(float* matrix); + +/// @brief Performs result = left * right +/// @param left A pointer to memory representing at least MATRIX_SIZE +/// elements +/// @param right A pointer to memory representing at least MATRIX_SIZE +/// elements +/// @param result A pointer to memory representing at least MATRIX_SIZE +/// elements. The output of left * right is stored in this matrix +/// @pre Assumes all pointers are valid. +void +multMatrix(const float* left, const float* right, float* result); + +/// @brief Finds the inverse of a matrix +/// @param the input 4x4 column-major matrix following OpenGL's format +/// @param the output 4x4 column-major inverse matrix following OpenGL's format +bool +invertMatrix(const float* matrix, float* inverse); + +/// @brief Helper function for converting objects to strings (using operator<<) +/// @param input The object to be converted +/// @param result A reference to the string where the resulting string will be +/// stored. +template +void +toString(T input, std::string &result) +{ + std::stringstream ss; + ss << input; + result = ss.str(); +} + +/// @brief Converts the passed string to lowercase in place +/// @param s The string to be made lower. +void +stringToLower(std::string &s); + +#endif // COMMON_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/copyBuffer.h b/pcl-1.7/pcl/apps/point_cloud_editor/copyBuffer.h new file mode 100644 index 0000000..740e836 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/copyBuffer.h @@ -0,0 +1,117 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file copyBuffer.h +/// @details A CopyBuffer object provides a buffer to store the points +/// copied from the cloud. +/// @author Yue Li and Matthew Hielsberg + +#ifndef COPY_BUFFER_H_ +#define COPY_BUFFER_H_ + +#include +#include + +/// @brief a buffer holding the points being copied and a set of operations for +/// manipulating the buffer. +class CopyBuffer : public Statistics +{ + public: + /// @brief Default Constructor + /// @details This creates an empty buffer + CopyBuffer (bool register_stats=false) + { + if (register_stats) + registerStats(); + } + + /// @brief Copy Constructor + /// @details create a copy buffer by copying all the internal states of the + /// passed copy buffer. + /// @param copy the copy buffer object used to initialize this object + CopyBuffer (const CopyBuffer& copy); + + /// @brief Destructor + ~CopyBuffer () + { + } + + /// @brief Equal Operator + /// @details Copy all the internal states to the this copy buffer object. + /// @param copy_buffer the copy buffer object used to update the this object + /// @return A reference to this. + CopyBuffer& + operator= (const CopyBuffer& copy_buffer); + + /// @brief Sets the points in the copy buffer. + /// @details The passed selection pointer is used to get specified points + /// from the stored cloud pointer and copy them into the internal buffer. + /// Any points that currently exist in this buffer are removed and replaced + /// with those passed. Note that this buffer is cleared prior to any + /// checking of the state of the passed parameters. + /// @param cloud_ptr a pointer to a cloud object whose points are to be + /// copied + /// @param selection a const reference to the selected points object + void + set (ConstCloudPtr cloud_ptr, const Selection& selection); + + /// @brief Returns the points stored in the internal buffer as a const Cloud + const Cloud& + get() const; + + /// @brief Returns the points stored in the internal buffer as a Cloud + Cloud& + get(); + + /// @brief Removes all the points from the copy buffer. + void + clean (); + + /// @brief Get the statistics of the copied points in string. + std::string + getStat () const; + + /// @brief Returns true if the buffer is empty, false otherwise + bool + empty() const + { + return (buffer_.size() == 0); + } + + private: + /// a cloud object holding all the copied points. + Cloud buffer_; +}; +#endif // COPY_BUFFER_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/copyCommand.h b/pcl-1.7/pcl/apps/point_cloud_editor/copyCommand.h new file mode 100644 index 0000000..4ffc169 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/copyCommand.h @@ -0,0 +1,117 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file copyCommand.h +/// @details A CopyCommand object provides functionality for filling the copy +/// buffer with the current selection. The +/// @author Yue Li and Matthew Hielsberg + +#ifndef COPY_COMMAND_H_ +#define COPY_COMMAND_H_ + +#include +#include +#include + +class CopyCommand : public Command +{ + public: + /// @brief Constructor + /// @param copy_buffer_ptr a shared pointer pointing to the copy buffer. + /// @param selection_ptr a shared pointer pointing to the selection object. + /// @param cloud_ptr a shared pointer pointing to the cloud object. + CopyCommand (CopyBufferPtr copy_buffer_ptr, + ConstSelectionPtr selection_ptr, + ConstCloudPtr cloud_ptr) + : copy_buffer_ptr_(copy_buffer_ptr), selection_ptr_(selection_ptr), + cloud_ptr_(cloud_ptr) + { + has_undo_ = false; + } + + /// @brief Destructor + ~CopyCommand () + { + } + + protected: + /// @brief Copy the selected points into the copy buffer. + /// @pre Assumes the constructor was given appropriate pointers to the + /// required objects. + void + execute () + { + if (!cloud_ptr_) + return; + copy_buffer_ptr_ -> set(cloud_ptr_, *selection_ptr_); + } + + /// @brief undo is not supported for this command. + void + undo () + { + assert(false); + } + + private: + /// @brief Default constructor - object is not default constructable + CopyCommand () + { + assert(false); + } + + /// @brief Copy constructor - commands are non-copyable + CopyCommand (const CopyCommand&) + { + assert(false); + } + + /// @brief Equal operator - commands are non-copyable + CopyCommand& + operator= (const CopyCommand&) + { + assert(false); return (*this); + } + + /// a pointer to the copy buffer. + CopyBufferPtr copy_buffer_ptr_; + + /// a shared pointer pointing to the selection + ConstSelectionPtr selection_ptr_; + + /// a shared pointer pointing to the cloud + ConstCloudPtr cloud_ptr_; +}; +#endif //COPY_COMMAND_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/cutCommand.h b/pcl-1.7/pcl/apps/point_cloud_editor/cutCommand.h new file mode 100644 index 0000000..7c79e24 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/cutCommand.h @@ -0,0 +1,114 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file cutCommand.h +/// @details A CutCommand object provides functionality for removing selected +/// points from the cloud and filling the copy buffer. +/// @author Yue Li and Matthew Hielsberg + +#ifndef CUT_COMMAND_H_ +#define CUT_COMMAND_H_ + +#include +#include +#include +#include + +class CutCommand : public Command +{ + public: + /// @brief Constructor + /// @param copy_buffer_ptr a shared pointer pointing to the copy buffer. + /// @param selection_ptr a shared pointer pointing to the selection object. + /// @param cloud_ptr a shared pointer pointing to the cloud object. + CutCommand (CopyBufferPtr copy_buffer_ptr, + SelectionPtr selection_ptr, + CloudPtr cloud_ptr); + + /// @brief Destructor + ~CutCommand (); + + protected: + /// @brief Moves the selected points to the copy buffer and removes them + /// from the cloud. + /// @pre Assumes the constructor was given appropriate pointers to the + /// required objects. + void + execute (); + + /// @brief Returns the cut points to the cloud. This does not reconstruct + /// the original ordering of the point cloud. + void + undo (); + + private: + /// @brief Default constructor - object is not default constructable + CutCommand () : cut_selection_(CloudPtr()) + { + assert(false); + } + + /// @brief Copy constructor - commands are non-copyable + CutCommand (const CutCommand&) : cut_selection_(CloudPtr()) + { + assert(false); + } + + /// @brief Equal operator - commands are non-copyable + CutCommand& + operator= (const CutCommand&) + { + assert(false); return (*this); + } + + /// A shared pointer pointing to the selection object. + SelectionPtr selection_ptr_; + + /// a pointer pointing to the cloud + CloudPtr cloud_ptr_; + + /// a pointer pointing to the copy buffer. + CopyBufferPtr copy_buffer_ptr_; + + /// a selection which backs up the index of the points cut in the + /// original cloud. + Selection cut_selection_; + + /// The copy buffer which backs up the points removed from the cloud. + CopyBuffer cut_cloud_buffer_; + +}; + +#endif // CUT_COMMAND_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/deleteCommand.h b/pcl-1.7/pcl/apps/point_cloud_editor/deleteCommand.h new file mode 100644 index 0000000..e2a94a5 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/deleteCommand.h @@ -0,0 +1,106 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file deleteCommand.h +/// @details A Delete object provides the functionality for removing points +/// from the cloud as well as the ability to undo the removal. +/// @author Yue Li and Matthew Hielsberg + +#ifndef DELETE_COMMAND_H_ +#define DELETE_COMMAND_H_ + +#include +#include +#include +#include + +class DeleteCommand : public Command +{ + public: + /// @brief Constructor + /// @param selection_ptr A shared pointer pointing to the selection object. + /// @param cloud_ptr A shared pointer pointing to the cloud object. + DeleteCommand (SelectionPtr selection_ptr, CloudPtr cloud_ptr); + + /// @brief Destructor + ~DeleteCommand () + { + } + + protected: + /// @brief Removes the selected points and maintains a backup for undo. + void + execute (); + + /// @brief Returns the deleted points to the cloud, Order is not preserved. + void + undo (); + + private: + /// @brief Default constructor - object is not default constructable + DeleteCommand (): deleted_selection_(CloudPtr()) + { + assert(false); + } + + /// @brief Copy constructor - commands are non-copyable + DeleteCommand (const DeleteCommand& c) + : deleted_selection_(c.deleted_selection_) + { + assert(false); + } + + /// @brief Equal operator - commands are non-copyable + DeleteCommand& + operator= (const DeleteCommand&) + { + assert(false); return (*this); + } + + /// a pointer pointing to the cloud + CloudPtr cloud_ptr_; + + /// A shared pointer pointing to the selection object. + SelectionPtr selection_ptr_; + + /// a selection which backs up the index of the deleted points in the + /// original cloud. + Selection deleted_selection_; + + /// a copy buffer which backs up the points deleted from the cloud. + CopyBuffer deleted_cloud_buffer_; +}; + +#endif // DELETE_COMMAND_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/denoiseCommand.h b/pcl-1.7/pcl/apps/point_cloud_editor/denoiseCommand.h new file mode 100644 index 0000000..ea4d6bf --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/denoiseCommand.h @@ -0,0 +1,119 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file denoiseCommand.h +/// @details A DenoiseCommand object provides functionalities for removing the +/// outliers in the input cloud. This class also serves an example for developers +/// on extending the editors with cloud processing algorithms. See +/// http://pointclouds.org/documentation/tutorials/statistical_outlier.php +/// @author Yue Li and Matthew Hielsberg + +#ifndef DENOISE_COMMAND_H_ +#define DENOISE_COMMAND_H_ + +#include +#include +#include +#include + +class DenoiseCommand : public Command +{ +public: + /// @brief Constructor + /// @param selection_ptr a shared pointer pointing to the selection object. + /// @param cloud_ptr a shared pointer pointing to the cloud object. + /// @param mean the number of points to use for mean distance estimation. + /// @param threshold the standard deviation multiplier threshold + DenoiseCommand (SelectionPtr selection_ptr, CloudPtr cloud_ptr, + float mean, float threshold) + : selection_ptr_(selection_ptr), cloud_ptr_(cloud_ptr), mean_(mean), + threshold_(threshold), removed_indices_(cloud_ptr) + { + } + + /// @brief Destructor + ~DenoiseCommand () + { + } + +protected: + /// @brief Runs the denois algorithm to remove all the outliers. + void + execute (); + + /// @brief Adds the removed noisy points back to the cloud + void + undo (); + +private: + /// @brief Default Constructor + DenoiseCommand () : removed_indices_(CloudPtr()) + { + } + + /// @brief Copy constructor - commands are non-copyable + DenoiseCommand (const DenoiseCommand&) + : removed_indices_(CloudPtr()) + { + assert(false); + } + + /// @brief Equal operator - commands are non-copyable + DenoiseCommand& + operator= (const DenoiseCommand&) + { + assert(false); return (*this); + } + + /// A shared pointer pointing to the selection object of the widget + SelectionPtr selection_ptr_; + + /// A pointer pointing to the cloud of the widget + CloudPtr cloud_ptr_; + + /// The number of points to use for mean distance estimation. + float mean_; + + /// The standard deviation multiplier threshold + float threshold_; + + /// A copy buffer which backs up the noisy point removed after denoising. + CopyBuffer removed_points_; + + /// A selection object which backs up the indices of the noisy points removed. + Selection removed_indices_; +}; + +#endif // DENOISE_COMMAND_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/denoiseParameterForm.h b/pcl-1.7/pcl/apps/point_cloud_editor/denoiseParameterForm.h new file mode 100644 index 0000000..8ec5ea2 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/denoiseParameterForm.h @@ -0,0 +1,116 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// +/// +/// @file denoiseParameterForm.h +/// @details the class representing the dialog which accepts the parameters +/// to PCL's denoising filter. +/// @author Yue Li and Matthew Hielsberg + + +#ifndef DENOISE_PARAMETER_FORM_H_ +#define DENOISE_PARAMETER_FORM_H_ + +#include +#include +#include +#include +#include +#include + +class DenoiseParameterForm : public QDialog +{ + Q_OBJECT + + public: + /// @brief Default Constructor + DenoiseParameterForm(); + + /// @brief Destructor + ~DenoiseParameterForm (); + + /// @brief Returns the mean + inline + float + getMeanK () const + { + return (mean_k_); + } + + /// @brief Returns the standard deviation multiplier threshold + inline + float + getStdDevThresh () const + { + return (std_dev_thresh_); + } + + /// @brief Checks whether the OK button was pressed. + inline + bool + ok () const + { + return (ok_); + } + + private slots: + /// @brief Accepts and stores the current user inputs, and turns off the + /// dialog box. + void + accept (); + + /// @brief Rejects the current inputs, and turns off the dialog box. + void + reject (); + + private: + /// The line for entering the mean + QLineEdit *mean_K_line_; + /// The line for entering the standard deviation multiplier threshold + QLineEdit *std_dev_mul_thresh_line_; + /// The button box. + QDialogButtonBox *button_box_; + /// The layout of the two input QLineEdit objects + QFormLayout *layout_; + /// The main layout for the dialog + QVBoxLayout* main_layout_; + /// The mean + float mean_k_; + /// The standard deviation multiplier threshold + float std_dev_thresh_; + /// The flag indicating whether the OK button was pressed + bool ok_; +}; + +#endif // DENOISE_PARAMETER_FORM_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/localTypes.h b/pcl-1.7/pcl/apps/point_cloud_editor/localTypes.h new file mode 100644 index 0000000..f9cd41e --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/localTypes.h @@ -0,0 +1,194 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file localTypes.h +/// @details A set of useful typedefs, forward declarations and constants. +/// @author Yue Li and Matthew Hielsberg + + +#ifndef LOCAL_TYPES_H_ +#define LOCAL_TYPES_H_ + +#include +#include +#include +#include +#include + +// Forward declaration for commonly used objects +class Command; +class CommandQueue; +class Selection; +class CopyBuffer; +class Cloud; + +// Some helpful typedef's for commonly used objects + +/// The type for the 3D points in the point cloud. +typedef pcl::PointXYZRGBA Point3D; + +/// The type used as internal representation of a cloud object. +typedef pcl::PointCloud Cloud3D; + +/// The type for boost shared pointer pointing to a PCL cloud object. +typedef Cloud3D::Ptr PclCloudPtr; + +/// The type for boost shared pointer pointing to a cloud object +typedef boost::shared_ptr CloudPtr; + +/// The type for boost shared pointer pointing to a constant cloud +/// object +typedef boost::shared_ptr ConstCloudPtr; + +/// The type for boost shared pointer pointing to a selection buffer +typedef boost::shared_ptr SelectionPtr; + +/// The type for boost shared pointer pointing to a constant selection +/// buffer +typedef boost::shared_ptr ConstSelectionPtr; + +/// The type for boost shared pointer pointing to a copy buffer +typedef boost::shared_ptr CopyBufferPtr; + +/// The type for boost shared pointer pointing to a constant copy +/// buffer +typedef boost::shared_ptr ConstCopyBufferPtr; + +/// The type for boost shared pointer pointing to a command object +typedef boost::shared_ptr CommandPtr; + +/// The type used for vectors holding the indices of points in a cloud +typedef std::vector IndexVector; + +/// The type used for vectors holding the constant indices of points in +/// a cloud +typedef std::vector ConstIndexVector; + +/// The type for boost shared pointer pointing to a command queue +/// object +typedef boost::shared_ptr CommandQueuePtr; + +/// The type for bit masks used for recognizing key pressed by user. +typedef unsigned int BitMask; + +/// ID's for the key modifiers. +enum KeyModifier +{ + NONE = 0x00000000, + SHFT = 0x02000000, + CTRL = 0x04000000, + ALT = 0x08000000 +}; + +/// ID's for the mouse buttons. +enum MouseButton +{ + NOBUTTON, + LEFT, + RIGHT +}; + +/// Indices for the coordinate axes +/// It is assumed that the ColorScheme X,Y,Z match these values +enum Axis +{ + X, + Y, + Z +}; + +/// Indices for color components +enum Color +{ + RED, + GREEN, + BLUE, + RGB +}; + +/// Scheme used for coloring the whole cloud. +/// It is assumed that the Axiz X,Y,Z match the COLOR_BY_[X,Y,Z] values +enum ColorScheme +{ + COLOR_BY_X = 0, + COLOR_BY_Y, + COLOR_BY_Z, + COLOR_BY_RGB, + COLOR_BY_PURE +}; + +/// Simple functor that produces sequential integers from an initial value +struct IncIndex +{ + unsigned int val_; + IncIndex(int v=0) + { + val_ = v; + } + unsigned int operator()() + { + return (val_++); + } +}; + +/// A helpful const representing the number of elements in our vectors. +/// This is used for all operations that require the copying of the vector. +/// Although this is used in a fairly generic way, the display requires 3D. +const unsigned int XYZ_SIZE = 3; + +/// A helpful const representing the number of elements in each row/col in +/// our matrices. This is used for all operations that require the copying of +/// the matrix. +const unsigned int MATRIX_SIZE_DIM = 4; + +/// A helpful const representing the number of elements in our matrices. +/// This is used for all operations that require the copying of the matrix. +const unsigned int MATRIX_SIZE = MATRIX_SIZE_DIM * MATRIX_SIZE_DIM; + +/// The default window width +const unsigned int WINDOW_WIDTH = 1200; +/// The default window height +const unsigned int WINDOW_HEIGHT = 1000; + +/// The default z translation used to push the world origin in front of the +/// display +const float DISPLAY_Z_TRANSLATION = -2.0f; + +/// The radius of the trackball given as a percentage of the screen width +const float TRACKBALL_RADIUS_SCALE = 0.4f; + + + +#endif // LOCAL_TYPES_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/mainWindow.h b/pcl-1.7/pcl/apps/point_cloud_editor/mainWindow.h new file mode 100644 index 0000000..45a1887 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/mainWindow.h @@ -0,0 +1,237 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// +/// @file mainWindow.h +/// @details the declaration of the class representing the main window of the +/// point cloud editor +/// @author Yue Li and Matthew Hielsberg +/// + +#ifndef MAIN_WINDOW_H_ +#define MAIN_WINDOW_H_ + +#include +#include +#include + +// Forward declaration to prevent circular inclusion +class CloudEditorWidget; + +/// @brief the class for point cloud editor +class MainWindow : public QMainWindow +{ + Q_OBJECT + + public: + /// @brief Constructor + MainWindow (); + + /// @brief Constructor + /// @param argc The number of c-strings to be expected in argv + /// @param argv An array of c-strings. The zero entry is expected to be + /// the name of the appliation. Any additional strings will be interpreted + /// as filenames designating point clouds to be loaded. + MainWindow (int argc, char **argv); + + /// @brief Destructor + ~MainWindow (); + + /// @brief Increase the value of the spinbox by 1. + void + increaseSpinBoxValue (); + + /// @brief Decrease the value of the spinbox by 1. + void + decreaseSpinBoxValue (); + + /// @brief Gets the value of the spinbox. + int + getSpinBoxValue(); + + /// @brief Increase the value of the selected pts size spinbox by 1. + void + increaseSelectedSpinBoxValue (); + + /// @brief Decrease the value of the selected pts size spinbox by 1. + void + decreaseSelectedSpinBoxValue (); + + /// @brief Gets the value of the selected pts size spinbox. + int + getSelectedSpinBoxValue (); + + private slots: + void + about (); + + void + help (); + + private: + /// Initialization function. This handles the initialization of the widget, + /// menus, actions, etc. + void + initWindow (); + + /// create actions which are connected to file menus + void + createActions (); + + /// create menus such as file and help + void + createMenus (); + + /// create buttons in the tool bar + void + createToolBars (); + + /// create spin boxes used in the tool bar. + void + createSpinBoxes (); + + /// create sliders used in the tool bar. + void + createSliders (); + + /// the cloud editor GL widget + CloudEditorWidget *cloud_editor_widget_; + + /// the action group for making actions checkable. + QActionGroup* action_group_; + + /// action for exit the cloud editor + QAction *exit_action_; + + /// action for opening file + QAction *open_action_; + + /// action for saving file + QAction *save_action_; + + /// action for copying selected points + QAction *copy_action_; + + /// action for pasting copied points + QAction *paste_action_; + + /// action for cutting selected points + QAction *cut_action_; + + /// action for deleting selected points + QAction *delete_action_; + + /// action for viewing the software information + QAction *about_action_; + + /// action for viewing the software use/control information + QAction *help_action_; + + /// action for toggling the pseudo distance display + QAction *toggle_blend_action_; + + /// action for switching to view mode + QAction *view_action_; + + /// action for undo + QAction *undo_action_; + + /// action for point selection + QAction *select_action_; + + /// action for 2D point selection + QAction *select_2D_action_; + + /// action for 3D point selection + //QAction *select_3D_action_; + + /// action for box edit + QAction *box_edit_action_; + + /// action for invert selection + QAction *invert_select_action_; + + /// action for transforming the cloud + QAction *transform_action_; + + /// action for denoising the cloud + QAction *denoise_action_; + + /// action for showing the statistics of the editor + QAction *show_stat_action_; + + /// the file menu + QMenu *file_menu_; + + /// the menu for editing tools + QMenu *edit_menu_; + + /// the menu for display options + QMenu *display_menu_; + + /// the menu for visualization tools + QMenu *view_menu_; + + /// the menu for select tools + QMenu *select_menu_; + + /// the menu for other algorithmic tools + QMenu *tool_menu_; + + /// the help menu + QMenu *help_menu_; + + /// the spin box for adjusting point size. + QSpinBox *point_size_spin_box_; + + /// the spin box for adjusting the size of the selected point. + QSpinBox *selected_point_size_spin_box_; + + /// the tool bar containing all the cloud editing buttons. + QToolBar *edit_tool_bar_; + + /// the tool bar containing all the visualization function buttons + QToolBar *view_tool_bar_; + + /// the width of the main window. + int window_width_; + + /// the height of the main window. + int window_height_; + + /// the slider used for adjusting moving speed. + QSlider *move_speed_slider_; +}; +#endif //MAIN_WINDOW_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/pasteCommand.h b/pcl-1.7/pcl/apps/point_cloud_editor/pasteCommand.h new file mode 100644 index 0000000..5a87532 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/pasteCommand.h @@ -0,0 +1,109 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file pasteCommand.h +/// @details A PasteCommand object that allows the duplication of selected +/// points in a cloud object as well as undo. +/// @author Yue Li and Matthew Hielsberg + + +#ifndef PASTE_COMMAND_H_ +#define PASTE_COMMAND_H_ + +#include +#include + +class PasteCommand : public Command +{ + public: + /// @brief Constructor + /// @param copy_buffer_ptr a shared pointer pointing to the copy buffer. + /// @param selection_ptr a shared pointer pointing to the selection object. + /// @param cloud_ptr a shared pointer pointing to the cloud object. + PasteCommand (ConstCopyBufferPtr copy_buffer_ptr, + SelectionPtr selection_ptr, CloudPtr cloud_ptr); + // comment that the selection is updated (also resets the matrix in cloud) + + /// @brief Destructor + ~PasteCommand () + { + } + + protected: + /// @brief Appends the points in the copy buffer into the cloud. + /// @details After appending the points to the cloud, this function also + /// updates the selection object to point to the newly pasted points. This + /// also updates the selection object to point to the newly pasted points. + void + execute (); + + /// @brief Removes the points that were pasted to the cloud. + void + undo (); + + private: + /// @brief Default constructor - object is not default constructable + PasteCommand () + { + } + + /// @brief Copy constructor - commands are non-copyable + PasteCommand (const PasteCommand&) + { + assert(false); + } + + /// @brief Equal operator - commands are non-copyable + PasteCommand& + operator= (const PasteCommand&) + { + assert(false); return (*this); + } + + /// a pointer pointing to the copy buffer. + ConstCopyBufferPtr copy_buffer_ptr_; + + /// A shared pointer pointing to the selection object. + SelectionPtr selection_ptr_; + + /// a pointer pointing to the cloud + CloudPtr cloud_ptr_; + + /// The size of the cloud before new points are pasted. This value is used + /// to mark the point where points were added to the cloud. In order to + /// support undo, one only has to resize the cloud using this value. + unsigned int prev_cloud_size_; +}; +#endif // PASTE_COMMAND_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/select1DTool.h b/pcl-1.7/pcl/apps/point_cloud_editor/select1DTool.h new file mode 100644 index 0000000..8fe5535 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/select1DTool.h @@ -0,0 +1,110 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file select1DTool.h +/// @details Tool for selecting and deselecting individual points in the cloud. +/// @author Yue Li and Matthew Hielsberg + +#ifndef SELECT_1D_TOOL_H +#define SELECT_1D_TOOL_H + +#include +#include + +class Select1DTool : public ToolInterface +{ + public: + /// @brief Constructor + /// @param selection_ptr a shared pointer pointing to the selection object. + /// @param cloud_ptr a shared pointer pointing to the cloud object. + Select1DTool (SelectionPtr selection_ptr, CloudPtr cloud_ptr); + + /// @brief Destructor + ~Select1DTool () + { + } + + /// @brief Does nothing for 1D selection. + /// @sa end + void + start (int, int, BitMask, BitMask) + { + } + + /// @brief Does nothing for 1D selection. + /// @sa end + void + update (int, int, BitMask, BitMask) + { + } + + /// @brief Select or deselect the point under the mouse using GL's selection + /// facility. + /// @details If shift is pressed when the selection is made, the selected + /// point is appended to the existing selection. If instead ctrl is pressed, + /// the selected point will be removed from the existing selection. If + /// neither shift nor ctrl is pressed when the selection is made then the + /// selected point, if any, will replace any current selection. Note that + /// the ctrl key may be evaluated as the command key in OSX. + /// @param x the x value of the mouse screen coordinates. + /// @param y the y value of the mouse screen coordinates. + /// @param modifiers the key modifier. SHIFT adds selected points to the + /// selection. CTRL removes points and if neither are pressed then a new + /// selection is made. + /// @param buttons The state of the mouse buttons. All interaction with + /// this tool requires the LEFT mouse button. All others are ignored. + void + end (int x, int y, BitMask modifiers, BitMask buttons); + + /// @brief This function does nothing. + void + draw () const + { + } + + private: + /// @brief Default constructor - object is not default constructable + Select1DTool() + { + assert(false); + } + + /// a shared pointer pointing to the selection object + SelectionPtr selection_ptr_; + + /// a shared pointer pointing to the cloud object + CloudPtr cloud_ptr_; +}; +#endif // SELECT_1D_TOOL_H diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/select2DTool.h b/pcl-1.7/pcl/apps/point_cloud_editor/select2DTool.h new file mode 100644 index 0000000..1285375 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/select2DTool.h @@ -0,0 +1,152 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file select2DTool.h +/// @details the declaration of the 2D selection tool class providing +/// functionalities to enable 2D selection. +/// @author Yue Li and Matthew Hielsberg + +#ifndef SELECT_2D_TOOL_H_ +#define SELECT_2D_TOOL_H_ + +#include +#include +#include + +class Select2DTool : public ToolInterface +{ + public: + /// @brief Constructor + /// @param selection_ptr a shared pointer pointing to the selection object. + /// @param cloud_ptr a shared pointer pointing to the cloud object. + Select2DTool (SelectionPtr selection_ptr, CloudPtr cloud_ptr); + + /// @brief Destructor + ~Select2DTool (); + + /// @brief Initializes the selection tool with the initial mouse screen + /// coordinates and key modifiers. The passed coordinates are used for + /// determining the coordinates of the upper left corner of the rubber band. + /// @param x the x value of the mouse screen coordinates. + /// @param y the y value of the mouse screen coordinates. + /// @param modifiers the key modifier. There are three possible values for + /// modifiers: 1. shift key, 2. ctrl key, 3. no modifier is pressed. Note + /// that the ctrl key may be evaluated as the command key in OSX. + void + start (int x, int y, BitMask modifiers, BitMask mouseButton); + + /// @brief Update the selection tool from the current mouse screen + /// coordinates and key modifiers. + /// @details Creates a 2D rubberband. The coordinates of the lower right + /// corner of the rubberband is computed from the passed coordinates. + /// @param x the x value of the mouse screen coordinates. + /// @param y the y value of the mouse screen coordinates. + /// @param modifiers the key modifier. + void + update (int x, int y, BitMask modifiers, BitMask mouseButton); + + /// @brief Update the coordinates of the lower right corner of the rubber + /// band and process the points in the rubber band. + /// @details The points which fall into the selection region are processed + /// according to the value of the modifier: If shift is pressed, the + /// selected points are appended to the existing selection. If ctrl is + /// pressed, the points will be removed from the existing selection + /// if they were elected previously, otherwise nothing happens. + /// @param x the x value of the mouse screen coordinates. + /// @param y the y value of the mouse screen coordinates. + /// @param modifiers the key modifier. + void + end (int x, int y, BitMask modifiers, BitMask mouseButton); + + /// @brief Checks whether a point is inside the selection region. + /// @param pt the point to be checked against the selection region. + /// @param project the projection matrix obtained from GL. + /// @param viewport the current viewport obtained from GL. + bool + isInSelectBox (const Point3D& pt, const GLfloat* project, + const GLint* viewport) const; + + /// @brief Draws the rubber band as well as any highlighted points during + /// the 'update' phase (i.e. before the selection is made by a call to end). + void + draw () const; + + /// The default size in pixels of the rubberband tool outline + static const float DEFAULT_TOOL_DISPLAY_SIZE_; + + /// The default color of the rubberband tool - red component + static const float DEFAULT_TOOL_DISPLAY_COLOR_RED_; + /// The default color of the rubberband tool - green component + static const float DEFAULT_TOOL_DISPLAY_COLOR_GREEN_; + /// The default color of the rubberband tool - blue component + static const float DEFAULT_TOOL_DISPLAY_COLOR_BLUE_; + + + private: + /// @brief Default constructor - object is not default constructable + Select2DTool() + { + assert(false); + } + + /// @brief draw the 2D selection rubber band. + /// @param viewport the viewport obtained from GL + void + drawRubberBand (GLint* viewport) const; + + /// @brief highlight all the points in the rubber band. + /// @detail draw the cloud using a stencil buffer. During this time, the + /// points that are highlighted will not be recorded by the selecion object. + /// @param viewport the viewport obtained from GL + void + highlightPoints (GLint* viewport) const; + + /// a shared pointer pointing to the selection object + SelectionPtr selection_ptr_; + + /// a shared pointer pointing to the cloud object + CloudPtr cloud_ptr_; + + /// the original mouse screen coordinates + int origin_x_, origin_y_; + + /// the final mouse screen coordinates + int final_x_, final_y_; + + /// switch for selection box rendering + bool display_box_; + +}; +#endif // SELECT_2D_TOOL_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/selection.h b/pcl-1.7/pcl/apps/point_cloud_editor/selection.h new file mode 100644 index 0000000..baf6ad8 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/selection.h @@ -0,0 +1,206 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file selection.h +/// @details A Selection object maintains the set of indices of points from a +/// point cloud that have been identifed by the selection tools. +/// @author Yue Li and Matthew Hielsberg + + +#ifndef SELECTION_H_ +#define SELECTION_H_ + +#include +#include +#include + +/// @brief This class serves as a sort of mask for performing operations on a +/// point cloud. It keeps track of the indices of identified/selected points +/// and provides methods for accessing those indices and modifying them. +class Selection : public Statistics +{ + public: + /// @brief Constructor. + /// @param cloud_ptr A pointer to the const cloud object for which this + /// object is to maintain selections. + Selection (ConstCloudPtr cloud_ptr, bool register_stats=false) + : cloud_ptr_(cloud_ptr) + { + if (register_stats) + registerStats(); + } + + /// @brief Copy constructor + /// @param copy The selection object to be copied + Selection (const Selection& copy) + : cloud_ptr_(copy.cloud_ptr_), selected_indices_(copy.selected_indices_) + { + } + + /// @brief Destructor. + ~Selection () + { + } + + /// @brief Equal operator + /// @param selection a const reference to a selection object whose + /// properties will be copied. + Selection& + operator= (const Selection& selection); + + /// @brief Adds the index of the selected point to the selection table. + /// @param index The index of the point that is selected. + /// @pre Assumes the passed index is valid with respect to the current + /// cloud. + void + addIndex (unsigned int index); + + /// @brief Removes the index of a point from the selection table. + /// @param index The index of the point to be removed from the table. + void + removeIndex (unsigned int index); + + /// @brief Adds a vector of indices of the selected points to the table. + /// @param indices A vector of indices of points to be added to the table. + /// @pre Assumes the passed index is valid with respect to the current + /// cloud. + void + addIndex (const IndexVector &indices); + + /// @brief Removes a vector of indices from the table + /// @param indices A vector of indices of points to be removed from the + /// table. + void + removeIndex (const IndexVector &indices); + + /// @brief Adds a range of consecutive indices into the selection table. + /// @param start the first index in the range. + /// @param num the total number of indices in the range. + /// @pre Assumes the passed index is valid with respect to the current + /// cloud. + void + addIndexRange (unsigned int start, unsigned int num); + + /// @brief Removes a range of consecutive indices into the selection table. + /// @param start the first index in the range. + /// @param num the total number of indices in the range. + void + removeIndexRange (unsigned int start, unsigned int num); + + /// @brief Removes all the indices from the selection table. + void + clear () + { + selected_indices_.clear(); + } + + typedef std::set::iterator iterator; + typedef std::set::const_iterator const_iterator; + + /// @brief Get the begin iterator of the selection. + const_iterator + begin () const + { + return (selected_indices_.begin()); + } + + /// @brief Get the end iterator of the selection. + const_iterator + end () const + { + return (selected_indices_.end()); + } + + typedef std::set::const_reverse_iterator + const_reverse_iterator; + + /// @brief Get the begin iterator of the selection. + const_reverse_iterator + rbegin () const + { + return (selected_indices_.rbegin()); + } + + /// @brief Get the end iterator of the selection. + const_reverse_iterator + rend () const + { + return (selected_indices_.rend()); + } + + /// @brief Returns true if the passed index is selected. + bool + isSelected (unsigned int index) const; + + /// @brief Returns true if no point is selected. + inline + bool + empty () const + { + return (selected_indices_.empty()); + } + + /// @brief Returns the number of points in the selection + inline + unsigned int + size () const + { + return (selected_indices_.size()); + } + + /// @brief Invert selection + /// @details Make the unselected points selected and deselect the previously + /// selected points. + void + invertSelect (); + + /// @brief Get the statistics of the selected points in string. + std::string + getStat () const; + + private: + /// @brief Default constructor - object is not default constructable + Selection () + { + } + + /// a pointer to the cloud + ConstCloudPtr cloud_ptr_; + + /// A set of unique indices that have been selected in the cloud. + std::set selected_indices_; +}; + +#endif // SELECTION_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/selectionTransformTool.h b/pcl-1.7/pcl/apps/point_cloud_editor/selectionTransformTool.h new file mode 100644 index 0000000..78d7837 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/selectionTransformTool.h @@ -0,0 +1,165 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file selectionTransformTool.h +/// @details This tool provides the ability to transform the current selection. +/// @author Yue Li and Matthew Hielsberg + +#ifndef SELECTION_TRANSFORM_TOOL_H_ +#define SELECTION_TRANSFORM_TOOL_H_ + +#include +#include +#include + +/// @brief The selection transform tool computes the transform matrix from +/// mouse input. It then updates the cloud's transform matrix for the +/// selected points so that the transformed and selected points will be +/// rendered appropriately. Note that, the actual coordinates of the selected +/// points are not updated until the end of the mouse input. At the end of a +/// mouse input (i.e. when the mouse button is released), a transform command is +/// created to update the actual coordinates of the selected points. +class SelectionTransformTool : public ToolInterface +{ + public: + /// @brief Constructor + /// @param selection_ptr a shared pointer pointing to the selection object. + /// @param cloud_ptr a shared pointer pointing to the cloud object. + /// @param command_queue_ptr a shared pointer pointing to the command queue. + SelectionTransformTool (ConstSelectionPtr selection_ptr, + CloudPtr cloud_ptr, + CommandQueuePtr command_queue_ptr); + + /// @brief Destructor + ~SelectionTransformTool () + { + } + + /// @brief Initialize the transform tool with mouse screen coordinates + /// and key modifiers. + /// @param x the x value of the mouse screen coordinates. + /// @param y the y value of the mouse screen coordinates. + /// @param modifiers the key modifier. + void + start (int x, int y, BitMask modifiers, BitMask buttons); + + /// @brief Updates the transform matrix of this object with mouse screen + /// coordinates and key modifiers. Then the selection_matrix_ in the cloud + /// is further updated. + /// @details We first compute the changes between the initial and the current + /// mouse screen coordinates. Then depending on the passed modifiers, the + /// transformation matrix is computed correspondingly. If CONTROL is pressed + /// the selection will be translated (panned) parallel to the view plane. If + /// ALT is pressed the selection witll be translated along the z-axis + /// perpendicular to the view plane. If no key modifiers is pressed the + /// selection will be rotated. + /// @param x the x value of the mouse screen coordinates. + /// @param y the y value of the mouse screen coordinates. + /// @param modifiers the key modifier. CONTROL pans the selection parallel + /// to the view plane. ALT moves the selection in/out along the z-axis + /// (perpendicular to the view plane). If no modifier is pressed then the + /// selection is rotated. + void + update (int x, int y, BitMask modifiers, BitMask buttons); + + /// @brief Update the transform matrix for the selected points using the + /// final position of the mouse. To finalize the transformation, we then + /// create a transform command which computes the new coordinates of the + /// selected points after transformation. + /// @param x the x value of the mouse screen coordinates. + /// @param y the y value of the mouse screen coordinates. + /// @param modifiers the key modifier. + void + end (int x, int y, BitMask modifiers, BitMask buttons); + + /// @brief This does not do anything. + void + draw () const + { + } + + private: + /// @brief Computes the modelview matrix for rotation. + /// @param dx the distance between the x coordinates of the starting and + /// ending cursor position. + /// @param dy the distance between the y coordinates of the starting and + /// ending cursor position. + /// @param rotation_matrix_a a 4x4 matrix following OpenGL's format + /// implementing rotation along x-axis. + /// @param rotation_matrix_b a 4x4 matrix following OpenGL's format + /// implementing rotation along y or z-axis, which depens on which the mouse + /// button that is being pressed during the rotation operation. + void + getRotateMatrix (int dx, int dy, float* rotation_matrix_a, + float* rotation_matrix_b, BitMask buttons) const; + + /// @brief Computes the centroid of the selected points + void + findSelectionCenter (); + + /// a shared pointer pointing to the selection object + ConstSelectionPtr selection_ptr_; + + /// a shared pointer pointing to the cloud object + CloudPtr cloud_ptr_; + + /// a shared pointer pointing to the command queue of the widget. + CommandQueuePtr command_queue_ptr_; + + /// the trackball associated with this transform + TrackBall trackball_; + + /// last recorded mouse positions + int x_, y_; + + /// The centroid of the selected points. + float center_xyz_[XYZ_SIZE]; + + /// the transform matrix to be used for updating the coordinates of the + /// selected points in the cloud + float transform_matrix_[MATRIX_SIZE]; + + /// scaling factor used to control the speed which the display translates + /// the point cloud + float translate_factor_; + + /// default translation factor + static const float DEFAULT_TRANSLATE_FACTOR_; + + /// the copy of the modifiers passed in the start function. + BitMask modifiers_; + +}; +#endif // SELECTION_TRANSFORMER_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/statistics.h b/pcl-1.7/pcl/apps/point_cloud_editor/statistics.h new file mode 100644 index 0000000..4a82d37 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/statistics.h @@ -0,0 +1,98 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file statistics.h +/// @details The statistics of the current editing. These statistics will be +/// displayed in a pop-up dialog. +/// @author Yue Li and Matthew Hielsberg + +#ifndef STATISTICS_H_ +#define STATISTICS_H_ + +#include +#include +#include + +class Statistics +{ + public: + /// @brief Destructor + virtual ~Statistics () + { + } + + /// @brief Returns the strings of the statistics. + static + std::string + getStats(); + + static + void + clear(); + + protected: + /// @brief The default constructor. + Statistics () + { + } + + /// @brief Copy Constructor + Statistics (const Statistics&) + { + assert(false); + } + + /// @brief Equal Operator + virtual + Statistics& + operator= (const Statistics&) + { + assert(false); return (*this); + } + + /// @brief Returns the statistics in string. + virtual + std::string + getStat () const = 0; + + /// @brief Register a statistics + void + registerStats (); + + private: + static std::vector stat_vec_; +}; + +#endif // STATISTICS_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/statisticsDialog.h b/pcl-1.7/pcl/apps/point_cloud_editor/statisticsDialog.h new file mode 100644 index 0000000..ac2e026 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/statisticsDialog.h @@ -0,0 +1,81 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// +/// +/// @file statisticsDialog.h +/// @details the class representing the dialog which accepts the parameters +/// to PCL's denoising filter. +/// @author Yue Li and Matthew Hielsberg + +#ifndef STATISTICS_DIALOG_H_ +#define STATISTICS_DIALOG_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +class StatisticsDialog : public QDialog +{ + Q_OBJECT + + public: + /// @brief Default Constructor + StatisticsDialog(QWidget *parent = 0); + /// @brief Destructor + ~StatisticsDialog (); + + public slots: + /// @brief update the dialog box. + void update (); + + private slots: + void accept (); + + private: + /// The button box. + QDialogButtonBox *button_box_; + + QLabel *stat_label_; + + /// A timer used for periodically update the statistics in the dialog. + QTimer timer_; +}; + +#endif // STATISTICS_DIALOG_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/toolInterface.h b/pcl-1.7/pcl/apps/point_cloud_editor/toolInterface.h new file mode 100644 index 0000000..efe4715 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/toolInterface.h @@ -0,0 +1,123 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// +/// @file toolInterface.h +/// @details An abstract class that provides a single interface for all tools +/// in the editor. Objects inheriting from this class are assumed to be based +/// on mouse inputs from the user along with modifier keys (ALT, CTRL, SHIFT). +/// Note that the CTRL key may be evaluated as the Command key in OSX. +/// @author Yue Li and Matthew Hielsberg + +#ifndef TOOL_INTERFACE_H_ +#define TOOL_INTERFACE_H_ + +#include + +/// @brief the parent class of all the select and the transform tool classes +class ToolInterface +{ + public: + /// @brief Destructor. + virtual ~ToolInterface () + { + } + + /// @brief set the initial state of the tool from the screen coordinates + /// of the mouse as well as the value of the modifier. + /// @param x the x coordinate of the mouse screen coordinates. + /// @param y the y coordinate of the mouse screen coordinates. + /// @param modifiers The keyboard modifiers. We use modifier to change the + /// behavior of a tool. Values of a modifier can be control key, alt key + /// shift key, or no key is pressed. See the subclasses of this class + /// for specific usages of the modifiers. + /// @param buttons The state of the mouse buttons + virtual + void + start (int x, int y, BitMask modifiers, BitMask buttons) = 0; + + /// @brief update the state of the tool from the screen coordinates + /// of the mouse as well as the value of the modifier. + /// @param x the x coordinate of the mouse screen coordinates. + /// @param y the y coordinate of the mouse screen coordinates. + /// @param modifiers The keyboard modifiers. We use modifier to change the + /// behavior of a tool. Values of a modifier can be control key, alt key + /// shift key, or no key is pressed. See the subclasses of this class + /// for specific usages of the modifiers. + /// @param buttons The state of the mouse buttons + virtual + void + update (int x, int y, BitMask modifiers, BitMask buttons) = 0; + + /// @brief set final state of the tool from the screen coordinates + /// of the mouse as well as the value of the modifier. Also performs the + /// corresponding functionalities of the tool. + /// @param x the x coordinate of the mouse screen coordinates. + /// @param y the y coordinate of the mouse screen coordinates. + /// @param modifiers The keyboard modifiers. We use modifier to change the + /// behavior of a tool. Values of a modifier can be control key, alt key + /// shift key, or no key is pressed. See the subclasses of this class + /// for specific usages of the modifiers. + /// @param buttons The state of the mouse buttons + virtual + void + end (int x, int y, BitMask modifiers, BitMask buttons) = 0; + + /// @brief a rendering facility used by a tool. For instance, if this tool + /// is a selection tool, this function draws highlighted points as well as + /// selection region, e.g., rubberband, box, etc. + virtual + void + draw () const = 0; + + protected: + /// @brief Default constructor + ToolInterface () + { + } + + private: + /// @brief Copy constructor - tools are non-copyable + ToolInterface (const ToolInterface&) + { + assert(false); + } + + /// @brief Equal operator - tools are non-copyable + ToolInterface& + operator= (const ToolInterface&) + { + assert(false); return (*this); + } +}; +#endif // TOOL_INTERFACE_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/trackball.h b/pcl-1.7/pcl/apps/point_cloud_editor/trackball.h new file mode 100644 index 0000000..a718154 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/trackball.h @@ -0,0 +1,79 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file trackball.h +/// @details Generic object for generating rotations given mouse input. This +/// class has been based on +/// @author Matthew Hielsberg + +#ifndef TRACKBALL_H_ +#define TRACKBALL_H_ + +#include +#include + +class TrackBall +{ + public: + TrackBall(); + TrackBall(const TrackBall ©); + ~TrackBall(); + + TrackBall& operator=(const TrackBall &rhs); + + void start(int s_x, int s_y); + + void update(int s_x, int s_y); + + void getRotationMatrix(float (&rot)[MATRIX_SIZE]); + + void reset(); + + private: + + void getPointFromScreenPoint(int s_x, int s_y, float &x, float &y, float &z); + + /// the quaternion representing the current orientation of the trackball + boost::math::quaternion quat_; + + /// the original mouse screen coordinates converted to a 3d point + float origin_x_, origin_y_, origin_z_; + + /// the radius of the trackball squared + float radius_sqr_; + +}; // class TrackBall + +#endif // TRACKBALL_H_ diff --git a/pcl-1.7/pcl/apps/point_cloud_editor/transformCommand.h b/pcl-1.7/pcl/apps/point_cloud_editor/transformCommand.h new file mode 100644 index 0000000..12e6561 --- /dev/null +++ b/pcl-1.7/pcl/apps/point_cloud_editor/transformCommand.h @@ -0,0 +1,119 @@ +/// +/// Copyright (c) 2012, Texas A&M University +/// All rights reserved. +/// +/// Redistribution and use in source and binary forms, with or without +/// modification, are permitted provided that the following conditions +/// are met: +/// +/// * Redistributions of source code must retain the above copyright +/// notice, this list of conditions and the following disclaimer. +/// * Redistributions in binary form must reproduce the above +/// copyright notice, this list of conditions and the following +/// disclaimer in the documentation and/or other materials provided +/// with the distribution. +/// * Neither the name of Texas A&M University nor the names of its +/// contributors may be used to endorse or promote products derived +/// from this software without specific prior written permission. +/// +/// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +/// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +/// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +/// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +/// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +/// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +/// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +/// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +/// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +/// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +/// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +/// POSSIBILITY OF SUCH DAMAGE. +/// +/// The following software was written as part of a collaboration with the +/// University of South Carolina, Interdisciplinary Mathematics Institute. +/// + +/// @file transformCommand.h +/// @details a TransfromCommand object provides transformation and undo +/// functionalities. // XXX - transformation of what? +/// @author Yue Li and Matthew Hielsberg + +#ifndef TRANSFORM_COMMAND_H_ +#define TRANSFORM_COMMAND_H_ + +#include +#include +#include + + +class TransformCommand : public Command +{ + public: + /// @brief Constructor + /// @param selection_ptr a shared pointer pointing to the selection object. + /// @param cloud_ptr a shared pointer pointing to the cloud object. + /// @param matrix a (4x4) transform matrix following OpenGL's format. + /// @pre Assumes the selection_ptr is valid, non-NULL. + TransformCommand (ConstSelectionPtr selection_ptr, CloudPtr cloud_ptr, + const float* matrix, float translate_x, + float translate_y, float translate_z); + + /// @brief Destructor + ~TransformCommand () + { + } + + protected: + // Transforms the coorindates of the selected points according to the transform + // matrix. + void + execute (); + + // Restore the coordinates of the transformed points. + void + undo (); + + private: + /// @brief Copy constructor - object is not copy-constructable + TransformCommand (const TransformCommand&) + { + } + + /// @brief Equal operator - object is non-copyable + TransformCommand& + operator= (const TransformCommand&) + { + assert(false); return (*this); + } + + /// @brief Applies the transformation to the point values + /// @param sel_ptr A pointer to the selection object whose points are to be + /// transformed. + void + applyTransform(ConstSelectionPtr sel_ptr); + + /// pointers to constructor params + ConstSelectionPtr selection_ptr_; + + /// a pointer poiting to the cloud + CloudPtr cloud_ptr_; + + float translate_x_, translate_y_, translate_z_; + + /// An internal selection object used to perform undo + SelectionPtr internal_selection_ptr_; + + /// the transform matrix to be used to compute the new coordinates + /// of the selected points + float transform_matrix_[MATRIX_SIZE]; + + /// The transform matrix of the cloud used by this command + float cloud_matrix_[MATRIX_SIZE]; + /// The inverted transform matrix of the cloud used by this command + float cloud_matrix_inv_[MATRIX_SIZE]; + + /// The center of the cloud used by this command + float cloud_center_[XYZ_SIZE]; +}; + +#endif // TRANSFORM_COMMAND_H_ diff --git a/pcl-1.7/pcl/apps/render_views_tesselated_sphere.h b/pcl-1.7/pcl/apps/render_views_tesselated_sphere.h new file mode 100644 index 0000000..04a18d5 --- /dev/null +++ b/pcl-1.7/pcl/apps/render_views_tesselated_sphere.h @@ -0,0 +1,182 @@ +/* + * render_views_tesselated_sphere.h + * + * Created on: Dec 23, 2011 + * Author: aitor + */ + +#ifndef RENDER_VIEWS_TESSELATED_SPHERE_H_ +#define RENDER_VIEWS_TESSELATED_SPHERE_H_ + +#include +#include +#include +#include + +namespace pcl +{ + namespace apps + { + /** \brief @b Class to render synthetic views of a 3D mesh using a tesselated sphere + * NOTE: This class should replace renderViewTesselatedSphere from pcl::visualization. + * Some extensions are planned in the near future to this class like removal of duplicated views for + * symmetrical objects, generation of RGB synthetic clouds when RGB available on mesh, etc. + * \author Aitor Aldoma + * \ingroup apps + */ + class PCL_EXPORTS RenderViewsTesselatedSphere + { + private: + std::vector > poses_; + std::vector::Ptr> generated_views_; + std::vector entropies_; + int resolution_; + int tesselation_level_; + bool use_vertices_; + float view_angle_; + float radius_sphere_; + bool compute_entropy_; + vtkSmartPointer polydata_; + bool gen_organized_; + boost::function campos_constraints_func_; + + struct camPosConstraintsAllTrue + { + bool + operator() (const Eigen::Vector3f & /*pos*/) const + { + return true; + } + ; + }; + + public: + RenderViewsTesselatedSphere () + { + resolution_ = 150; + tesselation_level_ = 1; + use_vertices_ = false; + view_angle_ = 57; + radius_sphere_ = 1.f; + compute_entropy_ = false; + gen_organized_ = false; + campos_constraints_func_ = camPosConstraintsAllTrue (); + } + + void + setCamPosConstraints (boost::function & bb) + { + campos_constraints_func_ = bb; + } + + /* \brief Indicates wether to generate organized or unorganized data + * \param b organized/unorganized + */ + void + setGenOrganized (bool b) + { + gen_organized_ = b; + } + + /* \brief Sets the size of the render window + * \param res resolution size + */ + void + setResolution (int res) + { + resolution_ = res; + } + + /* \brief Wether to use the vertices or triangle centers of the tesselated sphere + * \param use true indicates to use vertices, false triangle centers + */ + + void + setUseVertices (bool use) + { + use_vertices_ = use; + } + + /* \brief Radius of the sphere where the virtual camera will be placed + * \param use true indicates to use vertices, false triangle centers + */ + void + setRadiusSphere (float radius) + { + radius_sphere_ = radius; + } + + /* \brief Wether to compute the entropies (level of occlusions for each view) + * \param compute true to compute entropies, false otherwise + */ + void + setComputeEntropies (bool compute) + { + compute_entropy_ = compute; + } + + /* \brief How many times the icosahedron should be tesselated. Results in more or less camera positions and generated views. + * \param level amount of tesselation + */ + void + setTesselationLevel (int level) + { + tesselation_level_ = level; + } + + /* \brief Sets the view angle of the virtual camera + * \param angle view angle in degrees + */ + void + setViewAngle (float angle) + { + view_angle_ = angle; + } + + /* \brief adds the mesh to be used as a vtkPolyData + * \param polydata vtkPolyData object + */ + void + addModelFromPolyData (vtkSmartPointer &polydata) + { + polydata_ = polydata; + } + + /* \brief performs the rendering and stores the generated information + */ + void + generateViews (); + + /* \brief Get the generated poses for the generated views + * \param poses 4x4 matrices representing the pose of the cloud relative to the model coordinate system + */ + void + getPoses (std::vector > & poses) + { + poses = poses_; + } + + /* \brief Get the generated views + * \param views generated pointclouds in camera coordinates + */ + void + getViews (std::vector::Ptr> & views) + { + views = generated_views_; + } + + /* \brief Get the entropies (level of occlusions) for the views + * \param entropies level of occlusions + */ + void + getEntropies (std::vector & entropies) + { + entropies = entropies_; + } + }; + + } +} + +#endif /* RENDER_VIEWS_TESSELATED_SPHERE_H_ */ diff --git a/pcl-1.7/pcl/apps/timer.h b/pcl-1.7/pcl/apps/timer.h new file mode 100644 index 0000000..00f6bf1 --- /dev/null +++ b/pcl-1.7/pcl/apps/timer.h @@ -0,0 +1,68 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: openni_viewer.cpp 5059 2012-03-14 02:12:17Z gedikli $ + * + */ + +#ifndef PCL_APPS_TIMER_H_ +#define PCL_APPS_TIMER_H_ + +#define MEASURE_FUNCTION_TIME +#include //fps calculations + +#if SHOW_FPS +#define FPS_CALC(_WHAT_) \ +do \ +{ \ + static unsigned count = 0;\ + static double last = pcl::getTime ();\ + double now = pcl::getTime (); \ + ++count; \ + if (now - last >= 1.0) \ + { \ + std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" << std::endl; \ + count = 0; \ + last = now; \ + } \ +}while(false) +#else +#define FPS_CALC(_WHAT_) \ +do \ +{ \ +}while(false) +#endif + +#endif // PCL_APPS_TIMER_H_ diff --git a/pcl-1.7/pcl/cloud_iterator.h b/pcl-1.7/pcl/cloud_iterator.h new file mode 100644 index 0000000..b7a0011 --- /dev/null +++ b/pcl-1.7/pcl/cloud_iterator.h @@ -0,0 +1,193 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_POINT_CLOUD_ITERATOR_H_ +#define PCL_POINT_CLOUD_ITERATOR_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief Iterator class for point clouds with or without given indices + * \author Suat Gedikli + */ + template + class CloudIterator + { + public: + CloudIterator (PointCloud& cloud); + + CloudIterator (PointCloud& cloud, const std::vector& indices); + + CloudIterator (PointCloud& cloud, const PointIndices& indices); + + CloudIterator (PointCloud& cloud, const Correspondences& corrs, bool source); + + ~CloudIterator (); + + void operator ++ (); + + void operator ++ (int); + + PointT& operator* () const; + + PointT* operator-> () const; + + unsigned getCurrentPointIndex () const; + + unsigned getCurrentIndex () const; + + /** \brief Size of the range the iterator is going through. Depending on how the CloudIterator was constructed this is the size of the cloud or indices/correspondences. */ + size_t size () const; + + void reset (); + + bool isValid () const; + + operator bool () const + { + return isValid (); + } + private: + + class Iterator + { + public: + virtual ~Iterator () {} + + virtual void operator ++ () = 0; + + virtual void operator ++ (int) = 0; + + virtual PointT& operator* () const = 0; + + virtual PointT* operator-> () const = 0; + + virtual unsigned getCurrentPointIndex () const = 0; + + virtual unsigned getCurrentIndex () const = 0; + + /** \brief Size of the range the iterator is going through. Depending on how the CloudIterator was constructed this is the size of the cloud or indices/correspondences. */ + virtual size_t size () const = 0; + + virtual void reset () = 0; + + virtual bool isValid () const = 0; + }; + Iterator* iterator_; + }; + + /** \brief Iterator class for point clouds with or without given indices + * \author Suat Gedikli + */ + template + class ConstCloudIterator + { + public: + ConstCloudIterator (const PointCloud& cloud); + + ConstCloudIterator (const PointCloud& cloud, const std::vector& indices); + + ConstCloudIterator (const PointCloud& cloud, const PointIndices& indices); + + ConstCloudIterator (const PointCloud& cloud, const Correspondences& corrs, bool source); + + ~ConstCloudIterator (); + + void operator ++ (); + + void operator ++ (int); + + const PointT& operator* () const; + + const PointT* operator-> () const; + + unsigned getCurrentPointIndex () const; + + unsigned getCurrentIndex () const; + + /** \brief Size of the range the iterator is going through. Depending on how the ConstCloudIterator was constructed this is the size of the cloud or indices/correspondences. */ + size_t size () const; + + void reset (); + + bool isValid () const; + + operator bool () const + { + return isValid (); + } + private: + + class Iterator + { + public: + virtual ~Iterator () {} + + virtual void operator ++ () = 0; + + virtual void operator ++ (int) = 0; + + virtual const PointT& operator* () const = 0; + + virtual const PointT* operator-> () const = 0; + + virtual unsigned getCurrentPointIndex () const = 0; + + virtual unsigned getCurrentIndex () const = 0; + + /** \brief Size of the range the iterator is going through. Depending on how the ConstCloudIterator was constructed this is the size of the cloud or indices/correspondences. */ + virtual size_t size () const = 0; + + virtual void reset () = 0; + + virtual bool isValid () const = 0; + }; + + class DefaultConstIterator; + class ConstIteratorIdx; + Iterator* iterator_; + }; + +} // namespace pcl + +#include + +#endif // PCL_POINT_CLOUD_ITERATOR_H_ diff --git a/pcl-1.7/pcl/common/angles.h b/pcl-1.7/pcl/common/angles.h new file mode 100644 index 0000000..619fe7c --- /dev/null +++ b/pcl-1.7/pcl/common/angles.h @@ -0,0 +1,89 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_COMMON_ANGLES_H_ +#define PCL_COMMON_ANGLES_H_ + +/** + * \file pcl/common/angles.h + * Define standard C methods to do angle calculations + * \ingroup common + */ + +/*@{*/ +namespace pcl +{ + /** \brief Convert an angle from radians to degrees + * \param alpha the input angle (in radians) + * \ingroup common + */ + inline float + rad2deg (float alpha); + + /** \brief Convert an angle from degrees to radians + * \param alpha the input angle (in degrees) + * \ingroup common + */ + inline float + deg2rad (float alpha); + + /** \brief Convert an angle from radians to degrees + * \param alpha the input angle (in radians) + * \ingroup common + */ + inline double + rad2deg (double alpha); + + /** \brief Convert an angle from degrees to radians + * \param alpha the input angle (in degrees) + * \ingroup common + */ + inline double + deg2rad (double alpha); + + /** \brief Normalize an angle to (-PI, PI] + * \param alpha the input angle (in radians) + * \ingroup common + */ + inline float + normAngle (float alpha); +} +/*@}*/ +#include + +#endif // PCL_COMMON_ANGLES_H_ diff --git a/pcl-1.7/pcl/common/bivariate_polynomial.h b/pcl-1.7/pcl/common/bivariate_polynomial.h new file mode 100644 index 0000000..ccb313f --- /dev/null +++ b/pcl-1.7/pcl/common/bivariate_polynomial.h @@ -0,0 +1,143 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef BIVARIATE_POLYNOMIAL_H +#define BIVARIATE_POLYNOMIAL_H + +#include +#include + +namespace pcl +{ + /** \brief This represents a bivariate polynomial and provides some functionality for it + * \author Bastian Steder + * \ingroup common + */ + template + class BivariatePolynomialT + { + public: + //-----CONSTRUCTOR&DESTRUCTOR----- + /** Constructor */ + BivariatePolynomialT (int new_degree=0); + /** Copy constructor */ + BivariatePolynomialT (const BivariatePolynomialT& other); + /** Destructor */ + ~BivariatePolynomialT (); + + //-----OPERATORS----- + /** = operator */ + BivariatePolynomialT& + operator= (const BivariatePolynomialT& other) { deepCopy (other); return *this;} + + //-----METHODS----- + /** Initialize members to default values */ + void + setDegree (int new_degree); + + /** How many parametes has a bivariate polynomial with this degree */ + unsigned int + getNoOfParameters () const { return getNoOfParametersFromDegree (degree);} + + /** Calculate the value of the polynomial at the given point */ + real + getValue (real x, real y) const; + + /** Calculate the gradient of this polynomial + * If forceRecalc is false, it will do nothing when the gradient already exists */ + void + calculateGradient (bool forceRecalc=false); + + /** Calculate the value of the gradient at the given point */ + void + getValueOfGradient (real x, real y, real& gradX, real& gradY); + + /** Returns critical points of the polynomial. type can be 0=maximum, 1=minimum, or 2=saddle point + * !!Currently only implemented for degree 2!! */ + void + findCriticalPoints (std::vector& x_values, std::vector& y_values, std::vector& types) const; + + /** write as binary to a stream */ + void + writeBinary (std::ostream& os) const; + + /** write as binary into a file */ + void + writeBinary (const char* filename) const; + + /** read binary from a stream */ + void + readBinary (std::istream& os); + + /** read binary from a file */ + void + readBinary (const char* filename); + + /** How many parametes has a bivariate polynomial of the given degree */ + static unsigned int + getNoOfParametersFromDegree (int n) { return ((n+2)* (n+1))/2;} + + //-----VARIABLES----- + int degree; + real* parameters; + BivariatePolynomialT* gradient_x, * gradient_y; + + protected: + //-----METHODS----- + /** Delete all members */ + void + memoryCleanUp (); + + /** Create a deep copy of the given polynomial */ + void + deepCopy (const BivariatePolynomialT& other); + //-----VARIABLES----- + }; + + template + std::ostream& + operator<< (std::ostream& os, const BivariatePolynomialT& p); + + typedef BivariatePolynomialT BivariatePolynomiald; + typedef BivariatePolynomialT BivariatePolynomial; + +} // end namespace + +#include + +#endif diff --git a/pcl-1.7/pcl/common/boost.h b/pcl-1.7/pcl/common/boost.h new file mode 100644 index 0000000..acc70af --- /dev/null +++ b/pcl-1.7/pcl/common/boost.h @@ -0,0 +1,62 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_COMMON_BOOST_H_ +#define PCL_COMMON_BOOST_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#ifndef Q_MOC_RUN +// Marking all Boost headers as system headers to remove warnings +#include +#include +#include +#include +#include +#include +//#include +#include +#include +#include +#include +#include +#endif + +#endif // PCL_COMMON_BOOST_H_ diff --git a/pcl-1.7/pcl/common/centroid.h b/pcl-1.7/pcl/common/centroid.h new file mode 100644 index 0000000..535ddf0 --- /dev/null +++ b/pcl-1.7/pcl/common/centroid.h @@ -0,0 +1,1134 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_COMMON_CENTROID_H_ +#define PCL_COMMON_CENTROID_H_ + +#include +#include +#include +#include + +/** + * \file pcl/common/centroid.h + * Define methods for centroid estimation and covariance matrix calculus + * \ingroup common + */ + +/*@{*/ +namespace pcl +{ + /** \brief Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector. + * \param[in] cloud_iterator an iterator over the input point cloud + * \param[out] centroid the output centroid + * \return number of valid point used to determine the centroid. In case of dense point clouds, this is the same as the size of input cloud. + * \note if return value is 0, the centroid is not changed, thus not valid. + * The last compononent of the vector is set to 1, this allow to transform the centroid vector with 4x4 matrices. + * \ingroup common + */ + template inline unsigned int + compute3DCentroid (ConstCloudIterator &cloud_iterator, + Eigen::Matrix ¢roid); + + template inline unsigned int + compute3DCentroid (ConstCloudIterator &cloud_iterator, + Eigen::Vector4f ¢roid) + { + return (compute3DCentroid (cloud_iterator, centroid)); + } + + template inline unsigned int + compute3DCentroid (ConstCloudIterator &cloud_iterator, + Eigen::Vector4d ¢roid) + { + return (compute3DCentroid (cloud_iterator, centroid)); + } + + /** \brief Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector. + * \param[in] cloud the input point cloud + * \param[out] centroid the output centroid + * \return number of valid point used to determine the centroid. In case of dense point clouds, this is the same as the size of input cloud. + * \note if return value is 0, the centroid is not changed, thus not valid. + * The last compononent of the vector is set to 1, this allow to transform the centroid vector with 4x4 matrices. + * \ingroup common + */ + template inline unsigned int + compute3DCentroid (const pcl::PointCloud &cloud, + Eigen::Matrix ¢roid); + + template inline unsigned int + compute3DCentroid (const pcl::PointCloud &cloud, + Eigen::Vector4f ¢roid) + { + return (compute3DCentroid (cloud, centroid)); + } + + template inline unsigned int + compute3DCentroid (const pcl::PointCloud &cloud, + Eigen::Vector4d ¢roid) + { + return (compute3DCentroid (cloud, centroid)); + } + + /** \brief Compute the 3D (X-Y-Z) centroid of a set of points using their indices and + * return it as a 3D vector. + * \param[in] cloud the input point cloud + * \param[in] indices the point cloud indices that need to be used + * \param[out] centroid the output centroid + * \return number of valid point used to determine the centroid. In case of dense point clouds, this is the same as the size of input cloud. + * \note if return value is 0, the centroid is not changed, thus not valid. + * The last compononent of the vector is set to 1, this allow to transform the centroid vector with 4x4 matrices. + * \ingroup common + */ + template inline unsigned int + compute3DCentroid (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::Matrix ¢roid); + + template inline unsigned int + compute3DCentroid (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::Vector4f ¢roid) + { + return (compute3DCentroid (cloud, indices, centroid)); + } + + template inline unsigned int + compute3DCentroid (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::Vector4d ¢roid) + { + return (compute3DCentroid (cloud, indices, centroid)); + } + + /** \brief Compute the 3D (X-Y-Z) centroid of a set of points using their indices and + * return it as a 3D vector. + * \param[in] cloud the input point cloud + * \param[in] indices the point cloud indices that need to be used + * \param[out] centroid the output centroid + * \return number of valid point used to determine the centroid. In case of dense point clouds, this is the same as the size of input cloud. + * \note if return value is 0, the centroid is not changed, thus not valid. + * The last compononent of the vector is set to 1, this allow to transform the centroid vector with 4x4 matrices. + * \ingroup common + */ + template inline unsigned int + compute3DCentroid (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::Matrix ¢roid); + + template inline unsigned int + compute3DCentroid (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::Vector4f ¢roid) + { + return (compute3DCentroid (cloud, indices, centroid)); + } + + template inline unsigned int + compute3DCentroid (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::Vector4d ¢roid) + { + return (compute3DCentroid (cloud, indices, centroid)); + } + + /** \brief Compute the 3x3 covariance matrix of a given set of points. + * The result is returned as a Eigen::Matrix3f. + * Note: the covariance matrix is not normalized with the number of + * points. For a normalized covariance, please use + * computeNormalizedCovarianceMatrix. + * \param[in] cloud the input point cloud + * \param[in] centroid the centroid of the set of points in the cloud + * \param[out] covariance_matrix the resultant 3x3 covariance matrix + * \return number of valid point used to determine the covariance matrix. + * In case of dense point clouds, this is the same as the size of input cloud. + * \note if return value is 0, the covariance matrix is not changed, thus not valid. + * \ingroup common + */ + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const Eigen::Matrix ¢roid, + Eigen::Matrix &covariance_matrix); + + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const Eigen::Vector4f ¢roid, + Eigen::Matrix3f &covariance_matrix) + { + return (computeCovarianceMatrix (cloud, centroid, covariance_matrix)); + } + + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const Eigen::Vector4d ¢roid, + Eigen::Matrix3d &covariance_matrix) + { + return (computeCovarianceMatrix (cloud, centroid, covariance_matrix)); + } + + /** \brief Compute normalized the 3x3 covariance matrix of a given set of points. + * The result is returned as a Eigen::Matrix3f. + * Normalized means that every entry has been divided by the number of points in the point cloud. + * For small number of points, or if you want explicitely the sample-variance, use computeCovarianceMatrix + * and scale the covariance matrix with 1 / (n-1), where n is the number of points used to calculate + * the covariance matrix and is returned by the computeCovarianceMatrix function. + * \param[in] cloud the input point cloud + * \param[in] centroid the centroid of the set of points in the cloud + * \param[out] covariance_matrix the resultant 3x3 covariance matrix + * \return number of valid point used to determine the covariance matrix. + * In case of dense point clouds, this is the same as the size of input cloud. + * \ingroup common + */ + template inline unsigned int + computeCovarianceMatrixNormalized (const pcl::PointCloud &cloud, + const Eigen::Matrix ¢roid, + Eigen::Matrix &covariance_matrix); + + template inline unsigned int + computeCovarianceMatrixNormalized (const pcl::PointCloud &cloud, + const Eigen::Vector4f ¢roid, + Eigen::Matrix3f &covariance_matrix) + { + return (computeCovarianceMatrixNormalized (cloud, centroid, covariance_matrix)); + } + + template inline unsigned int + computeCovarianceMatrixNormalized (const pcl::PointCloud &cloud, + const Eigen::Vector4d ¢roid, + Eigen::Matrix3d &covariance_matrix) + { + return (computeCovarianceMatrixNormalized (cloud, centroid, covariance_matrix)); + } + + /** \brief Compute the 3x3 covariance matrix of a given set of points using their indices. + * The result is returned as a Eigen::Matrix3f. + * Note: the covariance matrix is not normalized with the number of + * points. For a normalized covariance, please use + * computeNormalizedCovarianceMatrix. + * \param[in] cloud the input point cloud + * \param[in] indices the point cloud indices that need to be used + * \param[in] centroid the centroid of the set of points in the cloud + * \param[out] covariance_matrix the resultant 3x3 covariance matrix + * \return number of valid point used to determine the covariance matrix. + * In case of dense point clouds, this is the same as the size of input cloud. + * \ingroup common + */ + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const std::vector &indices, + const Eigen::Matrix ¢roid, + Eigen::Matrix &covariance_matrix); + + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const std::vector &indices, + const Eigen::Vector4f ¢roid, + Eigen::Matrix3f &covariance_matrix) + { + return (computeCovarianceMatrix (cloud, indices, centroid, covariance_matrix)); + } + + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const std::vector &indices, + const Eigen::Vector4d ¢roid, + Eigen::Matrix3d &covariance_matrix) + { + return (computeCovarianceMatrix (cloud, indices, centroid, covariance_matrix)); + } + + /** \brief Compute the 3x3 covariance matrix of a given set of points using their indices. + * The result is returned as a Eigen::Matrix3f. + * Note: the covariance matrix is not normalized with the number of + * points. For a normalized covariance, please use + * computeNormalizedCovarianceMatrix. + * \param[in] cloud the input point cloud + * \param[in] indices the point cloud indices that need to be used + * \param[in] centroid the centroid of the set of points in the cloud + * \param[out] covariance_matrix the resultant 3x3 covariance matrix + * \return number of valid point used to determine the covariance matrix. + * In case of dense point clouds, this is the same as the size of input cloud. + * \ingroup common + */ + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + const Eigen::Matrix ¢roid, + Eigen::Matrix &covariance_matrix); + + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + const Eigen::Vector4f ¢roid, + Eigen::Matrix3f &covariance_matrix) + { + return (computeCovarianceMatrix (cloud, indices, centroid, covariance_matrix)); + } + + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + const Eigen::Vector4d ¢roid, + Eigen::Matrix3d &covariance_matrix) + { + return (computeCovarianceMatrix (cloud, indices, centroid, covariance_matrix)); + } + + /** \brief Compute the normalized 3x3 covariance matrix of a given set of points using + * their indices. + * The result is returned as a Eigen::Matrix3f. + * Normalized means that every entry has been divided by the number of entries in indices. + * For small number of points, or if you want explicitely the sample-variance, use computeCovarianceMatrix + * and scale the covariance matrix with 1 / (n-1), where n is the number of points used to calculate + * the covariance matrix and is returned by the computeCovarianceMatrix function. + * \param[in] cloud the input point cloud + * \param[in] indices the point cloud indices that need to be used + * \param[in] centroid the centroid of the set of points in the cloud + * \param[out] covariance_matrix the resultant 3x3 covariance matrix + * \return number of valid point used to determine the covariance matrix. + * In case of dense point clouds, this is the same as the size of input cloud. + * \ingroup common + */ + template inline unsigned int + computeCovarianceMatrixNormalized (const pcl::PointCloud &cloud, + const std::vector &indices, + const Eigen::Matrix ¢roid, + Eigen::Matrix &covariance_matrix); + + template inline unsigned int + computeCovarianceMatrixNormalized (const pcl::PointCloud &cloud, + const std::vector &indices, + const Eigen::Vector4f ¢roid, + Eigen::Matrix3f &covariance_matrix) + { + return (computeCovarianceMatrixNormalized (cloud, indices, centroid, covariance_matrix)); + } + + template inline unsigned int + computeCovarianceMatrixNormalized (const pcl::PointCloud &cloud, + const std::vector &indices, + const Eigen::Vector4d ¢roid, + Eigen::Matrix3d &covariance_matrix) + { + return (computeCovarianceMatrixNormalized (cloud, indices, centroid, covariance_matrix)); + } + + /** \brief Compute the normalized 3x3 covariance matrix of a given set of points using + * their indices. The result is returned as a Eigen::Matrix3f. + * Normalized means that every entry has been divided by the number of entries in indices. + * For small number of points, or if you want explicitely the sample-variance, use computeCovarianceMatrix + * and scale the covariance matrix with 1 / (n-1), where n is the number of points used to calculate + * the covariance matrix and is returned by the computeCovarianceMatrix function. + * \param[in] cloud the input point cloud + * \param[in] indices the point cloud indices that need to be used + * \param[in] centroid the centroid of the set of points in the cloud + * \param[out] covariance_matrix the resultant 3x3 covariance matrix + * \return number of valid point used to determine the covariance matrix. + * In case of dense point clouds, this is the same as the size of input cloud. + * \ingroup common + */ + template inline unsigned int + computeCovarianceMatrixNormalized (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + const Eigen::Matrix ¢roid, + Eigen::Matrix &covariance_matrix); + + template inline unsigned int + computeCovarianceMatrixNormalized (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + const Eigen::Vector4f ¢roid, + Eigen::Matrix3f &covariance_matrix) + { + return (computeCovarianceMatrixNormalized (cloud, indices, centroid, covariance_matrix)); + } + + template inline unsigned int + computeCovarianceMatrixNormalized (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + const Eigen::Vector4d ¢roid, + Eigen::Matrix3d &covariance_matrix) + { + return (computeCovarianceMatrixNormalized (cloud, indices, centroid, covariance_matrix)); + } + + /** \brief Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop. + * Normalized means that every entry has been divided by the number of entries in indices. + * For small number of points, or if you want explicitely the sample-variance, scale the covariance matrix + * with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function. + * \note This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency. + * \param[in] cloud the input point cloud + * \param[out] covariance_matrix the resultant 3x3 covariance matrix + * \param[out] centroid the centroid of the set of points in the cloud + * \return number of valid point used to determine the covariance matrix. + * In case of dense point clouds, this is the same as the size of input cloud. + * \ingroup common + */ + template inline unsigned int + computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, + Eigen::Matrix &covariance_matrix, + Eigen::Matrix ¢roid); + + template inline unsigned int + computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, + Eigen::Matrix3f &covariance_matrix, + Eigen::Vector4f ¢roid) + { + return (computeMeanAndCovarianceMatrix (cloud, covariance_matrix, centroid)); + } + + template inline unsigned int + computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, + Eigen::Matrix3d &covariance_matrix, + Eigen::Vector4d ¢roid) + { + return (computeMeanAndCovarianceMatrix (cloud, covariance_matrix, centroid)); + } + + /** \brief Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop. + * Normalized means that every entry has been divided by the number of entries in indices. + * For small number of points, or if you want explicitely the sample-variance, scale the covariance matrix + * with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function. + * \note This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency. + * \param[in] cloud the input point cloud + * \param[in] indices subset of points given by their indices + * \param[out] covariance_matrix the resultant 3x3 covariance matrix + * \param[out] centroid the centroid of the set of points in the cloud + * \return number of valid point used to determine the covariance matrix. + * In case of dense point clouds, this is the same as the size of input cloud. + * \ingroup common + */ + template inline unsigned int + computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::Matrix &covariance_matrix, + Eigen::Matrix ¢roid); + + template inline unsigned int + computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::Matrix3f &covariance_matrix, + Eigen::Vector4f ¢roid) + { + return (computeMeanAndCovarianceMatrix (cloud, indices, covariance_matrix, centroid)); + } + + template inline unsigned int + computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::Matrix3d &covariance_matrix, + Eigen::Vector4d ¢roid) + { + return (computeMeanAndCovarianceMatrix (cloud, indices, covariance_matrix, centroid)); + } + + /** \brief Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop. + * Normalized means that every entry has been divided by the number of entries in indices. + * For small number of points, or if you want explicitely the sample-variance, scale the covariance matrix + * with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function. + * \note This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency. + * \param[in] cloud the input point cloud + * \param[in] indices subset of points given by their indices + * \param[out] centroid the centroid of the set of points in the cloud + * \param[out] covariance_matrix the resultant 3x3 covariance matrix + * \return number of valid point used to determine the covariance matrix. + * In case of dense point clouds, this is the same as the size of input cloud. + * \ingroup common + */ + template inline unsigned int + computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::Matrix &covariance_matrix, + Eigen::Matrix ¢roid); + + template inline unsigned int + computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::Matrix3f &covariance_matrix, + Eigen::Vector4f ¢roid) + { + return (computeMeanAndCovarianceMatrix (cloud, indices, covariance_matrix, centroid)); + } + + template inline unsigned int + computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::Matrix3d &covariance_matrix, + Eigen::Vector4d ¢roid) + { + return (computeMeanAndCovarianceMatrix (cloud, indices, covariance_matrix, centroid)); + } + + /** \brief Compute the normalized 3x3 covariance matrix for a already demeaned point cloud. + * Normalized means that every entry has been divided by the number of entries in indices. + * For small number of points, or if you want explicitely the sample-variance, scale the covariance matrix + * with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function. + * \note This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency. + * \param[in] cloud the input point cloud + * \param[out] covariance_matrix the resultant 3x3 covariance matrix + * \return number of valid point used to determine the covariance matrix. + * In case of dense point clouds, this is the same as the size of input cloud. + * \ingroup common + */ + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + Eigen::Matrix &covariance_matrix); + + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + Eigen::Matrix3f &covariance_matrix) + { + return (computeCovarianceMatrix (cloud, covariance_matrix)); + } + + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + Eigen::Matrix3d &covariance_matrix) + { + return (computeCovarianceMatrix (cloud, covariance_matrix)); + } + + /** \brief Compute the normalized 3x3 covariance matrix for a already demeaned point cloud. + * Normalized means that every entry has been divided by the number of entries in indices. + * For small number of points, or if you want explicitely the sample-variance, scale the covariance matrix + * with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function. + * \note This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency. + * \param[in] cloud the input point cloud + * \param[in] indices subset of points given by their indices + * \param[out] covariance_matrix the resultant 3x3 covariance matrix + * \return number of valid point used to determine the covariance matrix. + * In case of dense point clouds, this is the same as the size of input cloud. + * \ingroup common + */ + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::Matrix &covariance_matrix); + + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::Matrix3f &covariance_matrix) + { + return (computeCovarianceMatrix (cloud, indices, covariance_matrix)); + } + + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::Matrix3d &covariance_matrix) + { + return (computeCovarianceMatrix (cloud, indices, covariance_matrix)); + } + + /** \brief Compute the normalized 3x3 covariance matrix for a already demeaned point cloud. + * Normalized means that every entry has been divided by the number of entries in indices. + * For small number of points, or if you want explicitely the sample-variance, scale the covariance matrix + * with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function. + * \note This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency. + * \param[in] cloud the input point cloud + * \param[in] indices subset of points given by their indices + * \param[out] covariance_matrix the resultant 3x3 covariance matrix + * \return number of valid point used to determine the covariance matrix. + * In case of dense point clouds, this is the same as the size of input cloud. + * \ingroup common + */ + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::Matrix &covariance_matrix); + + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::Matrix3f &covariance_matrix) + { + return (computeCovarianceMatrix (cloud, indices, covariance_matrix)); + } + + template inline unsigned int + computeCovarianceMatrix (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::Matrix3d &covariance_matrix) + { + return (computeCovarianceMatrix (cloud, indices, covariance_matrix)); + } + + /** \brief Subtract a centroid from a point cloud and return the de-meaned representation + * \param[in] cloud_iterator an iterator over the input point cloud + * \param[in] centroid the centroid of the point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] npts the number of samples guaranteed to be left in the input cloud, accessible by the iterator. If not given, it will be calculated. + * \ingroup common + */ + template void + demeanPointCloud (ConstCloudIterator &cloud_iterator, + const Eigen::Matrix ¢roid, + pcl::PointCloud &cloud_out, + int npts = 0); + + template void + demeanPointCloud (ConstCloudIterator &cloud_iterator, + const Eigen::Vector4f ¢roid, + pcl::PointCloud &cloud_out, + int npts = 0) + { + return (demeanPointCloud (cloud_iterator, centroid, cloud_out, npts)); + } + + template void + demeanPointCloud (ConstCloudIterator &cloud_iterator, + const Eigen::Vector4d ¢roid, + pcl::PointCloud &cloud_out, + int npts = 0) + { + return (demeanPointCloud (cloud_iterator, centroid, cloud_out, npts)); + } + + /** \brief Subtract a centroid from a point cloud and return the de-meaned representation + * \param[in] cloud_in the input point cloud + * \param[in] centroid the centroid of the point cloud + * \param[out] cloud_out the resultant output point cloud + * \ingroup common + */ + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const Eigen::Matrix ¢roid, + pcl::PointCloud &cloud_out); + + template void + demeanPointCloud (ConstCloudIterator &cloud_iterator, + const Eigen::Vector4f ¢roid, + pcl::PointCloud &cloud_out) + { + return (demeanPointCloud (cloud_iterator, centroid, cloud_out)); + } + + template void + demeanPointCloud (ConstCloudIterator &cloud_iterator, + const Eigen::Vector4d ¢roid, + pcl::PointCloud &cloud_out) + { + return (demeanPointCloud (cloud_iterator, centroid, cloud_out)); + } + + /** \brief Subtract a centroid from a point cloud and return the de-meaned representation + * \param[in] cloud_in the input point cloud + * \param[in] indices the set of point indices to use from the input point cloud + * \param[out] centroid the centroid of the point cloud + * \param cloud_out the resultant output point cloud + * \ingroup common + */ + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + const Eigen::Matrix ¢roid, + pcl::PointCloud &cloud_out); + + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + const Eigen::Vector4f ¢roid, + pcl::PointCloud &cloud_out) + { + return (demeanPointCloud (cloud_in, indices, centroid, cloud_out)); + } + + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + const Eigen::Vector4d ¢roid, + pcl::PointCloud &cloud_out) + { + return (demeanPointCloud (cloud_in, indices, centroid, cloud_out)); + } + + /** \brief Subtract a centroid from a point cloud and return the de-meaned representation + * \param[in] cloud_in the input point cloud + * \param[in] indices the set of point indices to use from the input point cloud + * \param[out] centroid the centroid of the point cloud + * \param cloud_out the resultant output point cloud + * \ingroup common + */ + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const pcl::PointIndices& indices, + const Eigen::Matrix ¢roid, + pcl::PointCloud &cloud_out); + + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const pcl::PointIndices& indices, + const Eigen::Vector4f ¢roid, + pcl::PointCloud &cloud_out) + { + return (demeanPointCloud (cloud_in, indices, centroid, cloud_out)); + } + + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const pcl::PointIndices& indices, + const Eigen::Vector4d ¢roid, + pcl::PointCloud &cloud_out) + { + return (demeanPointCloud (cloud_in, indices, centroid, cloud_out)); + } + + /** \brief Subtract a centroid from a point cloud and return the de-meaned + * representation as an Eigen matrix + * \param[in] cloud_iterator an iterator over the input point cloud + * \param[in] centroid the centroid of the point cloud + * \param[out] cloud_out the resultant output XYZ0 dimensions of \a cloud_in as + * an Eigen matrix (4 rows, N pts columns) + * \param[in] npts the number of samples guaranteed to be left in the input cloud, accessible by the iterator. If not given, it will be calculated. + * \ingroup common + */ + template void + demeanPointCloud (ConstCloudIterator &cloud_iterator, + const Eigen::Matrix ¢roid, + Eigen::Matrix &cloud_out, + int npts = 0); + + template void + demeanPointCloud (ConstCloudIterator &cloud_iterator, + const Eigen::Vector4f ¢roid, + Eigen::MatrixXf &cloud_out, + int npts = 0) + { + return (demeanPointCloud (cloud_iterator, centroid, cloud_out, npts)); + } + + template void + demeanPointCloud (ConstCloudIterator &cloud_iterator, + const Eigen::Vector4d ¢roid, + Eigen::MatrixXd &cloud_out, + int npts = 0) + { + return (demeanPointCloud (cloud_iterator, centroid, cloud_out, npts)); + } + + /** \brief Subtract a centroid from a point cloud and return the de-meaned + * representation as an Eigen matrix + * \param[in] cloud_in the input point cloud + * \param[in] centroid the centroid of the point cloud + * \param[out] cloud_out the resultant output XYZ0 dimensions of \a cloud_in as + * an Eigen matrix (4 rows, N pts columns) + * \ingroup common + */ + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const Eigen::Matrix ¢roid, + Eigen::Matrix &cloud_out); + + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const Eigen::Vector4f ¢roid, + Eigen::MatrixXf &cloud_out) + { + return (demeanPointCloud (cloud_in, centroid, cloud_out)); + } + + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const Eigen::Vector4d ¢roid, + Eigen::MatrixXd &cloud_out) + { + return (demeanPointCloud (cloud_in, centroid, cloud_out)); + } + + /** \brief Subtract a centroid from a point cloud and return the de-meaned + * representation as an Eigen matrix + * \param[in] cloud_in the input point cloud + * \param[in] indices the set of point indices to use from the input point cloud + * \param[in] centroid the centroid of the point cloud + * \param[out] cloud_out the resultant output XYZ0 dimensions of \a cloud_in as + * an Eigen matrix (4 rows, N pts columns) + * \ingroup common + */ + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + const Eigen::Matrix ¢roid, + Eigen::Matrix &cloud_out); + + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + const Eigen::Vector4f ¢roid, + Eigen::MatrixXf &cloud_out) + { + return (demeanPointCloud (cloud_in, indices, centroid, cloud_out)); + } + + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + const Eigen::Vector4d ¢roid, + Eigen::MatrixXd &cloud_out) + { + return (demeanPointCloud (cloud_in, indices, centroid, cloud_out)); + } + + /** \brief Subtract a centroid from a point cloud and return the de-meaned + * representation as an Eigen matrix + * \param[in] cloud_in the input point cloud + * \param[in] indices the set of point indices to use from the input point cloud + * \param[in] centroid the centroid of the point cloud + * \param[out] cloud_out the resultant output XYZ0 dimensions of \a cloud_in as + * an Eigen matrix (4 rows, N pts columns) + * \ingroup common + */ + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const pcl::PointIndices& indices, + const Eigen::Matrix ¢roid, + Eigen::Matrix &cloud_out); + + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const pcl::PointIndices& indices, + const Eigen::Vector4f ¢roid, + Eigen::MatrixXf &cloud_out) + { + return (demeanPointCloud (cloud_in, indices, centroid, cloud_out)); + } + + template void + demeanPointCloud (const pcl::PointCloud &cloud_in, + const pcl::PointIndices& indices, + const Eigen::Vector4d ¢roid, + Eigen::MatrixXd &cloud_out) + { + return (demeanPointCloud (cloud_in, indices, centroid, cloud_out)); + } + + /** \brief Helper functor structure for n-D centroid estimation. */ + template + struct NdCentroidFunctor + { + typedef typename traits::POD::type Pod; + + NdCentroidFunctor (const PointT &p, Eigen::Matrix ¢roid) + : f_idx_ (0), + centroid_ (centroid), + p_ (reinterpret_cast(p)) { } + + template inline void operator() () + { + typedef typename pcl::traits::datatype::type T; + const uint8_t* raw_ptr = reinterpret_cast(&p_) + pcl::traits::offset::value; + const T* data_ptr = reinterpret_cast(raw_ptr); + + // Check if the value is invalid + if (!pcl_isfinite (*data_ptr)) + { + f_idx_++; + return; + } + + centroid_[f_idx_++] += *data_ptr; + } + + private: + int f_idx_; + Eigen::Matrix ¢roid_; + const Pod &p_; + }; + + /** \brief General, all purpose nD centroid estimation for a set of points using their + * indices. + * \param cloud the input point cloud + * \param centroid the output centroid + * \ingroup common + */ + template inline void + computeNDCentroid (const pcl::PointCloud &cloud, + Eigen::Matrix ¢roid); + + template inline void + computeNDCentroid (const pcl::PointCloud &cloud, + Eigen::VectorXf ¢roid) + { + return (computeNDCentroid (cloud, centroid)); + } + + template inline void + computeNDCentroid (const pcl::PointCloud &cloud, + Eigen::VectorXd ¢roid) + { + return (computeNDCentroid (cloud, centroid)); + } + + /** \brief General, all purpose nD centroid estimation for a set of points using their + * indices. + * \param cloud the input point cloud + * \param indices the point cloud indices that need to be used + * \param centroid the output centroid + * \ingroup common + */ + template inline void + computeNDCentroid (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::Matrix ¢roid); + + template inline void + computeNDCentroid (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::VectorXf ¢roid) + { + return (computeNDCentroid (cloud, indices, centroid)); + } + + template inline void + computeNDCentroid (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::VectorXd ¢roid) + { + return (computeNDCentroid (cloud, indices, centroid)); + } + + /** \brief General, all purpose nD centroid estimation for a set of points using their + * indices. + * \param cloud the input point cloud + * \param indices the point cloud indices that need to be used + * \param centroid the output centroid + * \ingroup common + */ + template inline void + computeNDCentroid (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::Matrix ¢roid); + + template inline void + computeNDCentroid (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::VectorXf ¢roid) + { + return (computeNDCentroid (cloud, indices, centroid)); + } + + template inline void + computeNDCentroid (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::VectorXd ¢roid) + { + return (computeNDCentroid (cloud, indices, centroid)); + } + +} + +#include + +namespace pcl +{ + + /** A generic class that computes the centroid of points fed to it. + * + * Here by "centroid" we denote not just the mean of 3D point coordinates, + * but also mean of values in the other data fields. The general-purpose + * \ref computeNDCentroid() function also implements this sort of + * functionality, however it does it in a "dumb" way, i.e. regardless of the + * semantics of the data inside a field it simply averages the values. In + * certain cases (e.g. for \c x, \c y, \c z, \c intensity fields) this + * behavior is reasonable, however in other cases (e.g. \c rgb, \c rgba, + * \c label fields) this does not lead to meaningful results. + * + * This class is capable of computing the centroid in a "smart" way, i.e. + * taking into account the meaning of the data inside fields. Currently the + * following fields are supported: + * + * - XYZ (\c x, \c y, \c z) + * + * Separate average for each field. + * + * - Normal (\c normal_x, \c normal_y, \c normal_z) + * + * Separate average for each field, and the resulting vector is normalized. + * + * - Curvature (\c curvature) + * + * Average. + * + * - RGB/RGBA (\c rgb or \c rgba) + * + * Separate average for R, G, B, and alpha channels. + * + * - Intensity (\c intensity) + * + * Average. + * + * - Label (\c label) + * + * Majority vote. If several labels have the same largest support then the + * smaller label wins. + * + * The template parameter defines the type of points that may be accumulated + * with this class. This may be an arbitrary PCL point type, and centroid + * computation will happen only for the fields that are present in it and are + * supported. + * + * Current centroid may be retrieved at any time using get(). Note that the + * function is templated on point type, so it is possible to fetch the + * centroid into a point type that differs from the type of points that are + * being accumulated. All the "extra" fields for which the centroid is not + * being calculated will be left untouched. + * + * Example usage: + * + * \code + * // Create and accumulate points + * CentroidPoint centroid; + * centroid.add (pcl::PointXYZ (1, 2, 3); + * centroid.add (pcl::PointXYZ (5, 6, 7); + * // Fetch centroid using `get()` + * pcl::PointXYZ c1; + * centroid.get (c1); + * // The expected result is: c1.x == 3, c1.y == 4, c1.z == 5 + * // It is also okay to use `get()` with a different point type + * pcl::PointXYZRGB c2; + * centroid.get (c2); + * // The expected result is: c2.x == 3, c2.y == 4, c2.z == 5, + * // and c2.rgb is left untouched + * \endcode + * + * \note Assumes that the points being inserted are valid. + * + * \note This class template can be successfully instantiated for *any* + * PCL point type. Of course, each of the field averages is computed only if + * the point type has the corresponding field. + * + * \ingroup common + * \author Sergey Alexandrov */ + template + class CentroidPoint + { + + public: + + CentroidPoint () + : num_points_ (0) + { + } + + /** Add a new point to the centroid computation. + * + * In this function only the accumulators and point counter are updated, + * actual centroid computation does not happen until get() is called. */ + void + add (const PointT& point) + { + // Invoke add point on each accumulator + boost::fusion::for_each (accumulators_, detail::AddPoint (point)); + ++num_points_; + } + + /** Retrieve the current centroid. + * + * Computation (division of accumulated values by the number of points + * and normalization where applicable) happens here. The result is not + * cached, so any subsequent call to this function will trigger + * re-computation. + * + * If the number of accumulated points is zero, then the point will be + * left untouched. */ + template void + get (PointOutT& point) const + { + if (num_points_ != 0) + { + // Filter accumulators so that only those that are compatible with + // both PointT and requested point type remain + typename pcl::detail::Accumulators::type ca (accumulators_); + // Invoke get point on each accumulator in filtered list + boost::fusion::for_each (ca, detail::GetPoint (point, num_points_)); + } + } + + /** Get the total number of points that were added. */ + size_t + getSize () const + { + return (num_points_); + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + private: + + size_t num_points_; + typename pcl::detail::Accumulators::type accumulators_; + + }; + + /** Compute the centroid of a set of points and return it as a point. + * + * Implementation leverages \ref CentroidPoint class and therefore behaves + * differently from \ref compute3DCentroid() and \ref computeNDCentroid(). + * See \ref CentroidPoint documentation for explanation. + * + * \param[in] cloud input point cloud + * \param[out] centroid output centroid + * + * \return number of valid points used to determine the centroid (will be the + * same as the size of the cloud if it is dense) + * + * \note If return value is \c 0, then the centroid is not changed, thus is + * not valid. + * + * \ingroup common */ + template size_t + computeCentroid (const pcl::PointCloud& cloud, + PointOutT& centroid); + + /** Compute the centroid of a set of points and return it as a point. + * \param[in] cloud + * \param[in] indices point cloud indices that need to be used + * \param[out] centroid + * This is an overloaded function provided for convenience. See the + * documentation for computeCentroid(). + * + * \ingroup common */ + template size_t + computeCentroid (const pcl::PointCloud& cloud, + const std::vector& indices, + PointOutT& centroid); + +} +/*@}*/ +#include + +#endif //#ifndef PCL_COMMON_CENTROID_H_ diff --git a/pcl-1.7/pcl/common/common.h b/pcl-1.7/pcl/common/common.h new file mode 100644 index 0000000..38e0b15 --- /dev/null +++ b/pcl-1.7/pcl/common/common.h @@ -0,0 +1,196 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_COMMON_H_ +#define PCL_COMMON_H_ + +#include +#include + +/** + * \file pcl/common/common.h + * Define standard C methods and C++ classes that are common to all methods + * \ingroup common + */ + +/*@{*/ +namespace pcl +{ + /** \brief Compute the smallest angle between two vectors in the [ 0, PI ) interval in 3D. + * \param v1 the first 3D vector (represented as a \a Eigen::Vector4f) + * \param v2 the second 3D vector (represented as a \a Eigen::Vector4f) + * \return the angle between v1 and v2 + * \ingroup common + */ + inline double + getAngle3D (const Eigen::Vector4f &v1, const Eigen::Vector4f &v2); + + /** \brief Compute both the mean and the standard deviation of an array of values + * \param values the array of values + * \param mean the resultant mean of the distribution + * \param stddev the resultant standard deviation of the distribution + * \ingroup common + */ + inline void + getMeanStd (const std::vector &values, double &mean, double &stddev); + + /** \brief Get a set of points residing in a box given its bounds + * \param cloud the point cloud data message + * \param min_pt the minimum bounds + * \param max_pt the maximum bounds + * \param indices the resultant set of point indices residing in the box + * \ingroup common + */ + template inline void + getPointsInBox (const pcl::PointCloud &cloud, Eigen::Vector4f &min_pt, + Eigen::Vector4f &max_pt, std::vector &indices); + + /** \brief Get the point at maximum distance from a given point and a given pointcloud + * \param cloud the point cloud data message + * \param pivot_pt the point from where to compute the distance + * \param max_pt the point in cloud that is the farthest point away from pivot_pt + * \ingroup common + */ + template inline void + getMaxDistance (const pcl::PointCloud &cloud, const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt); + + /** \brief Get the point at maximum distance from a given point and a given pointcloud + * \param cloud the point cloud data message + * \param pivot_pt the point from where to compute the distance + * \param indices the vector of point indices to use from \a cloud + * \param max_pt the point in cloud that is the farthest point away from pivot_pt + * \ingroup common + */ + template inline void + getMaxDistance (const pcl::PointCloud &cloud, const std::vector &indices, + const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt); + + /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud + * \param cloud the point cloud data message + * \param min_pt the resultant minimum bounds + * \param max_pt the resultant maximum bounds + * \ingroup common + */ + template inline void + getMinMax3D (const pcl::PointCloud &cloud, PointT &min_pt, PointT &max_pt); + + /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud + * \param cloud the point cloud data message + * \param min_pt the resultant minimum bounds + * \param max_pt the resultant maximum bounds + * \ingroup common + */ + template inline void + getMinMax3D (const pcl::PointCloud &cloud, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt); + + /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud + * \param cloud the point cloud data message + * \param indices the vector of point indices to use from \a cloud + * \param min_pt the resultant minimum bounds + * \param max_pt the resultant maximum bounds + * \ingroup common + */ + template inline void + getMinMax3D (const pcl::PointCloud &cloud, const std::vector &indices, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt); + + /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud + * \param cloud the point cloud data message + * \param indices the vector of point indices to use from \a cloud + * \param min_pt the resultant minimum bounds + * \param max_pt the resultant maximum bounds + * \ingroup common + */ + template inline void + getMinMax3D (const pcl::PointCloud &cloud, const pcl::PointIndices &indices, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt); + + /** \brief Compute the radius of a circumscribed circle for a triangle formed of three points pa, pb, and pc + * \param pa the first point + * \param pb the second point + * \param pc the third point + * \return the radius of the circumscribed circle + * \ingroup common + */ + template inline double + getCircumcircleRadius (const PointT &pa, const PointT &pb, const PointT &pc); + + /** \brief Get the minimum and maximum values on a point histogram + * \param histogram the point representing a multi-dimensional histogram + * \param len the length of the histogram + * \param min_p the resultant minimum + * \param max_p the resultant maximum + * \ingroup common + */ + template inline void + getMinMax (const PointT &histogram, int len, float &min_p, float &max_p); + + /** \brief Calculate the area of a polygon given a point cloud that defines the polygon + * \param polygon point cloud that contains those vertices that comprises the polygon. Vertices are stored in counterclockwise. + * \return the polygon area + * \ingroup common + */ + template inline float + calculatePolygonArea (const pcl::PointCloud &polygon); + + /** \brief Get the minimum and maximum values on a point histogram + * \param cloud the cloud containing multi-dimensional histograms + * \param idx point index representing the histogram that we need to compute min/max for + * \param field_name the field name containing the multi-dimensional histogram + * \param min_p the resultant minimum + * \param max_p the resultant maximum + * \ingroup common + */ + PCL_EXPORTS void + getMinMax (const pcl::PCLPointCloud2 &cloud, int idx, const std::string &field_name, + float &min_p, float &max_p); + + /** \brief Compute both the mean and the standard deviation of an array of values + * \param values the array of values + * \param mean the resultant mean of the distribution + * \param stddev the resultant standard deviation of the distribution + * \ingroup common + */ + PCL_EXPORTS void + getMeanStdDev (const std::vector &values, double &mean, double &stddev); + +} +/*@}*/ +#include + +#endif //#ifndef PCL_COMMON_H_ diff --git a/pcl-1.7/pcl/common/common_headers.h b/pcl-1.7/pcl/common/common_headers.h new file mode 100644 index 0000000..626f3b7 --- /dev/null +++ b/pcl-1.7/pcl/common/common_headers.h @@ -0,0 +1,46 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_COMMON_HEADERS_ +#define PCL_COMMON_HEADERS_ + +#include +#include +#include +#include +#include +#include + +#endif //#ifndef PCL_COMMON_HEADERS_ diff --git a/pcl-1.7/pcl/common/concatenate.h b/pcl-1.7/pcl/common/concatenate.h new file mode 100644 index 0000000..f1aa87e --- /dev/null +++ b/pcl-1.7/pcl/common/concatenate.h @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ +#ifndef PCL_COMMON_CONCATENATE_H_ +#define PCL_COMMON_CONCATENATE_H_ + +#include + +// We're doing a lot of black magic with Boost here, so disable warnings in Maintainer mode, as we will never +// be able to fix them anyway +#ifdef BUILD_Maintainer +# if defined __GNUC__ +# if __GNUC__ == 4 && __GNUC_MINOR__ > 3 +# pragma GCC diagnostic ignored "-Weffc++" +# pragma GCC diagnostic ignored "-pedantic" +# else +# pragma GCC system_header +# endif +# elif defined _MSC_VER +# pragma warning(push, 1) +# endif +#endif + +namespace pcl +{ + /** \brief Helper functor structure for concatenate. + * \ingroup common + */ + template + struct NdConcatenateFunctor + { + typedef typename traits::POD::type PodIn; + typedef typename traits::POD::type PodOut; + + NdConcatenateFunctor (const PointInT &p1, PointOutT &p2) + : p1_ (reinterpret_cast (p1)) + , p2_ (reinterpret_cast (p2)) { } + + template inline void + operator () () + { + // This sucks without Fusion :( + //boost::fusion::at_key (p2_) = boost::fusion::at_key (p1_); + typedef typename pcl::traits::datatype::type InT; + typedef typename pcl::traits::datatype::type OutT; + // Note: don't currently support different types for the same field (e.g. converting double to float) + BOOST_MPL_ASSERT_MSG ((boost::is_same::value), + POINT_IN_AND_POINT_OUT_HAVE_DIFFERENT_TYPES_FOR_FIELD, + (Key, PointInT&, InT, PointOutT&, OutT)); + memcpy (reinterpret_cast(&p2_) + pcl::traits::offset::value, + reinterpret_cast(&p1_) + pcl::traits::offset::value, + sizeof (InT)); + } + + private: + const PodIn &p1_; + PodOut &p2_; + }; +} + +#ifdef BUILD_Maintainer +# if defined __GNUC__ +# if __GNUC__ == 4 && __GNUC_MINOR__ > 3 +# pragma GCC diagnostic warning "-Weffc++" +# pragma GCC diagnostic warning "-pedantic" +# endif +# elif defined _MSC_VER +# pragma warning(pop) +# endif +#endif + +#endif // PCL_COMMON_CONCATENATE_H_ + diff --git a/pcl-1.7/pcl/common/conversions.h b/pcl-1.7/pcl/common/conversions.h new file mode 100644 index 0000000..a5bf20b --- /dev/null +++ b/pcl-1.7/pcl/common/conversions.h @@ -0,0 +1,349 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_CONVERSIONS_H_ +#define PCL_CONVERSIONS_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#ifndef Q_MOC_RUN +#include +#endif + +namespace pcl +{ + namespace detail + { + // For converting template point cloud to message. + template + struct FieldAdder + { + FieldAdder (std::vector& fields) : fields_ (fields) {}; + + template void operator() () + { + pcl::PCLPointField f; + f.name = traits::name::value; + f.offset = traits::offset::value; + f.datatype = traits::datatype::value; + f.count = traits::datatype::size; + fields_.push_back (f); + } + + std::vector& fields_; + }; + + // For converting message to template point cloud. + template + struct FieldMapper + { + FieldMapper (const std::vector& fields, + std::vector& map) + : fields_ (fields), map_ (map) + { + } + + template void + operator () () + { + BOOST_FOREACH (const pcl::PCLPointField& field, fields_) + { + if (FieldMatches()(field)) + { + FieldMapping mapping; + mapping.serialized_offset = field.offset; + mapping.struct_offset = traits::offset::value; + mapping.size = sizeof (typename traits::datatype::type); + map_.push_back (mapping); + return; + } + } + // Disable thrown exception per #595: http://dev.pointclouds.org/issues/595 + PCL_WARN ("Failed to find match for field '%s'.\n", traits::name::value); + //throw pcl::InvalidConversionException (ss.str ()); + } + + const std::vector& fields_; + std::vector& map_; + }; + + inline bool + fieldOrdering (const FieldMapping& a, const FieldMapping& b) + { + return (a.serialized_offset < b.serialized_offset); + } + + } //namespace detail + + template void + createMapping (const std::vector& msg_fields, MsgFieldMap& field_map) + { + // Create initial 1-1 mapping between serialized data segments and struct fields + detail::FieldMapper mapper (msg_fields, field_map); + for_each_type< typename traits::fieldList::type > (mapper); + + // Coalesce adjacent fields into single memcpy's where possible + if (field_map.size() > 1) + { + std::sort(field_map.begin(), field_map.end(), detail::fieldOrdering); + MsgFieldMap::iterator i = field_map.begin(), j = i + 1; + while (j != field_map.end()) + { + // This check is designed to permit padding between adjacent fields. + /// @todo One could construct a pathological case where the struct has a + /// field where the serialized data has padding + if (j->serialized_offset - i->serialized_offset == j->struct_offset - i->struct_offset) + { + i->size += (j->struct_offset + j->size) - (i->struct_offset + i->size); + j = field_map.erase(j); + } + else + { + ++i; + ++j; + } + } + } + } + + /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud object using a field_map. + * \param[in] msg the PCLPointCloud2 binary blob + * \param[out] cloud the resultant pcl::PointCloud + * \param[in] field_map a MsgFieldMap object + * + * \note Use fromPCLPointCloud2 (PCLPointCloud2, PointCloud) directly or create you + * own MsgFieldMap using: + * + * \code + * MsgFieldMap field_map; + * createMapping (msg.fields, field_map); + * \endcode + */ + template void + fromPCLPointCloud2 (const pcl::PCLPointCloud2& msg, pcl::PointCloud& cloud, + const MsgFieldMap& field_map) + { + // Copy info fields + cloud.header = msg.header; + cloud.width = msg.width; + cloud.height = msg.height; + cloud.is_dense = msg.is_dense == 1; + + // Copy point data + uint32_t num_points = msg.width * msg.height; + cloud.points.resize (num_points); + uint8_t* cloud_data = reinterpret_cast(&cloud.points[0]); + + // Check if we can copy adjacent points in a single memcpy + if (field_map.size() == 1 && + field_map[0].serialized_offset == 0 && + field_map[0].struct_offset == 0 && + msg.point_step == sizeof(PointT)) + { + uint32_t cloud_row_step = static_cast (sizeof (PointT) * cloud.width); + const uint8_t* msg_data = &msg.data[0]; + // Should usually be able to copy all rows at once + if (msg.row_step == cloud_row_step) + { + memcpy (cloud_data, msg_data, msg.data.size ()); + } + else + { + for (uint32_t i = 0; i < msg.height; ++i, cloud_data += cloud_row_step, msg_data += msg.row_step) + memcpy (cloud_data, msg_data, cloud_row_step); + } + + } + else + { + // If not, memcpy each group of contiguous fields separately + for (uint32_t row = 0; row < msg.height; ++row) + { + const uint8_t* row_data = &msg.data[row * msg.row_step]; + for (uint32_t col = 0; col < msg.width; ++col) + { + const uint8_t* msg_data = row_data + col * msg.point_step; + BOOST_FOREACH (const detail::FieldMapping& mapping, field_map) + { + memcpy (cloud_data + mapping.struct_offset, msg_data + mapping.serialized_offset, mapping.size); + } + cloud_data += sizeof (PointT); + } + } + } + } + + /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud object. + * \param[in] msg the PCLPointCloud2 binary blob + * \param[out] cloud the resultant pcl::PointCloud + */ + template void + fromPCLPointCloud2 (const pcl::PCLPointCloud2& msg, pcl::PointCloud& cloud) + { + MsgFieldMap field_map; + createMapping (msg.fields, field_map); + fromPCLPointCloud2 (msg, cloud, field_map); + } + + /** \brief Convert a pcl::PointCloud object to a PCLPointCloud2 binary data blob. + * \param[in] cloud the input pcl::PointCloud + * \param[out] msg the resultant PCLPointCloud2 binary blob + */ + template void + toPCLPointCloud2 (const pcl::PointCloud& cloud, pcl::PCLPointCloud2& msg) + { + // Ease the user's burden on specifying width/height for unorganized datasets + if (cloud.width == 0 && cloud.height == 0) + { + msg.width = static_cast(cloud.points.size ()); + msg.height = 1; + } + else + { + assert (cloud.points.size () == cloud.width * cloud.height); + msg.height = cloud.height; + msg.width = cloud.width; + } + + // Fill point cloud binary data (padding and all) + size_t data_size = sizeof (PointT) * cloud.points.size (); + msg.data.resize (data_size); + memcpy (&msg.data[0], &cloud.points[0], data_size); + + // Fill fields metadata + msg.fields.clear (); + for_each_type::type> (detail::FieldAdder(msg.fields)); + + msg.header = cloud.header; + msg.point_step = sizeof (PointT); + msg.row_step = static_cast (sizeof (PointT) * msg.width); + msg.is_dense = cloud.is_dense; + /// @todo msg.is_bigendian = ?; + } + + /** \brief Copy the RGB fields of a PointCloud into pcl::PCLImage format + * \param[in] cloud the point cloud message + * \param[out] msg the resultant pcl::PCLImage + * CloudT cloud type, CloudT should be akin to pcl::PointCloud + * \note will throw std::runtime_error if there is a problem + */ + template void + toPCLPointCloud2 (const CloudT& cloud, pcl::PCLImage& msg) + { + // Ease the user's burden on specifying width/height for unorganized datasets + if (cloud.width == 0 && cloud.height == 0) + throw std::runtime_error("Needs to be a dense like cloud!!"); + else + { + if (cloud.points.size () != cloud.width * cloud.height) + throw std::runtime_error("The width and height do not match the cloud size!"); + msg.height = cloud.height; + msg.width = cloud.width; + } + + // ensor_msgs::image_encodings::BGR8; + msg.encoding = "bgr8"; + msg.step = msg.width * sizeof (uint8_t) * 3; + msg.data.resize (msg.step * msg.height); + for (size_t y = 0; y < cloud.height; y++) + { + for (size_t x = 0; x < cloud.width; x++) + { + uint8_t * pixel = &(msg.data[y * msg.step + x * 3]); + memcpy (pixel, &cloud (x, y).rgb, 3 * sizeof(uint8_t)); + } + } + } + + /** \brief Copy the RGB fields of a PCLPointCloud2 msg into pcl::PCLImage format + * \param cloud the point cloud message + * \param msg the resultant pcl::PCLImage + * will throw std::runtime_error if there is a problem + */ + inline void + toPCLPointCloud2 (const pcl::PCLPointCloud2& cloud, pcl::PCLImage& msg) + { + int rgb_index = -1; + // Get the index we need + for (size_t d = 0; d < cloud.fields.size (); ++d) + if (cloud.fields[d].name == "rgb") + { + rgb_index = static_cast(d); + break; + } + + if(rgb_index == -1) + throw std::runtime_error ("No rgb field!!"); + if (cloud.width == 0 && cloud.height == 0) + throw std::runtime_error ("Needs to be a dense like cloud!!"); + else + { + msg.height = cloud.height; + msg.width = cloud.width; + } + int rgb_offset = cloud.fields[rgb_index].offset; + int point_step = cloud.point_step; + + // pcl::image_encodings::BGR8; + msg.encoding = "bgr8"; + msg.step = static_cast(msg.width * sizeof (uint8_t) * 3); + msg.data.resize (msg.step * msg.height); + + for (size_t y = 0; y < cloud.height; y++) + { + for (size_t x = 0; x < cloud.width; x++, rgb_offset += point_step) + { + uint8_t * pixel = &(msg.data[y * msg.step + x * 3]); + memcpy (pixel, &(cloud.data[rgb_offset]), 3 * sizeof (uint8_t)); + } + } + } +} + +#endif //#ifndef PCL_CONVERSIONS_H_ diff --git a/pcl-1.7/pcl/common/copy_point.h b/pcl-1.7/pcl/common/copy_point.h new file mode 100644 index 0000000..0e80cfe --- /dev/null +++ b/pcl-1.7/pcl/common/copy_point.h @@ -0,0 +1,62 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2014-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_COMMON_COPY_POINT_H_ +#define PCL_COMMON_COPY_POINT_H_ + +namespace pcl +{ + + /** \brief Copy the fields of a source point into a target point. + * + * If the source and the target point types are the same, then a complete + * copy is made. Otherwise only those fields that the two point types share + * in common are copied. + * + * \param[in] point_in the source point + * \param[out] point_out the target point + * + * \ingroup common */ + template void + copyPoint (const PointInT& point_in, PointOutT& point_out); + +} + +#include + +#endif // PCL_COMMON_COPY_POINT_H_ + diff --git a/pcl-1.7/pcl/common/distances.h b/pcl-1.7/pcl/common/distances.h new file mode 100644 index 0000000..3036e3a --- /dev/null +++ b/pcl-1.7/pcl/common/distances.h @@ -0,0 +1,203 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_DISTANCES_H_ +#define PCL_DISTANCES_H_ + +#include + +/** + * \file pcl/common/distances.h + * Define standard C methods to do distance calculations + * \ingroup common + */ + +/*@{*/ +namespace pcl +{ + /** \brief Get the shortest 3D segment between two 3D lines + * \param line_a the coefficients of the first line (point, direction) + * \param line_b the coefficients of the second line (point, direction) + * \param pt1_seg the first point on the line segment + * \param pt2_seg the second point on the line segment + * \ingroup common + */ + PCL_EXPORTS void + lineToLineSegment (const Eigen::VectorXf &line_a, const Eigen::VectorXf &line_b, + Eigen::Vector4f &pt1_seg, Eigen::Vector4f &pt2_seg); + + /** \brief Get the square distance from a point to a line (represented by a point and a direction) + * \param pt a point + * \param line_pt a point on the line (make sure that line_pt[3] = 0 as there are no internal checks!) + * \param line_dir the line direction + * \ingroup common + */ + double inline + sqrPointToLineDistance (const Eigen::Vector4f &pt, const Eigen::Vector4f &line_pt, const Eigen::Vector4f &line_dir) + { + // Calculate the distance from the point to the line + // D = ||(P2-P1) x (P1-P0)|| / ||P2-P1|| = norm (cross (p2-p1, p1-p0)) / norm(p2-p1) + return (line_dir.cross3 (line_pt - pt)).squaredNorm () / line_dir.squaredNorm (); + } + + /** \brief Get the square distance from a point to a line (represented by a point and a direction) + * \note This one is useful if one has to compute many distances to a fixed line, so the vector length can be pre-computed + * \param pt a point + * \param line_pt a point on the line (make sure that line_pt[3] = 0 as there are no internal checks!) + * \param line_dir the line direction + * \param sqr_length the squared norm of the line direction + * \ingroup common + */ + double inline + sqrPointToLineDistance (const Eigen::Vector4f &pt, const Eigen::Vector4f &line_pt, const Eigen::Vector4f &line_dir, const double sqr_length) + { + // Calculate the distance from the point to the line + // D = ||(P2-P1) x (P1-P0)|| / ||P2-P1|| = norm (cross (p2-p1, p1-p0)) / norm(p2-p1) + return (line_dir.cross3 (line_pt - pt)).squaredNorm () / sqr_length; + } + + /** \brief Obtain the maximum segment in a given set of points, and return the minimum and maximum points. + * \param[in] cloud the point cloud dataset + * \param[out] pmin the coordinates of the "minimum" point in \a cloud (one end of the segment) + * \param[out] pmax the coordinates of the "maximum" point in \a cloud (the other end of the segment) + * \return the length of segment length + * \ingroup common + */ + template double inline + getMaxSegment (const pcl::PointCloud &cloud, + PointT &pmin, PointT &pmax) + { + double max_dist = std::numeric_limits::min (); + int i_min = -1, i_max = -1; + + for (size_t i = 0; i < cloud.points.size (); ++i) + { + for (size_t j = i; j < cloud.points.size (); ++j) + { + // Compute the distance + double dist = (cloud.points[i].getVector4fMap () - + cloud.points[j].getVector4fMap ()).squaredNorm (); + if (dist <= max_dist) + continue; + + max_dist = dist; + i_min = i; + i_max = j; + } + } + + if (i_min == -1 || i_max == -1) + return (max_dist = std::numeric_limits::min ()); + + pmin = cloud.points[i_min]; + pmax = cloud.points[i_max]; + return (std::sqrt (max_dist)); + } + + /** \brief Obtain the maximum segment in a given set of points, and return the minimum and maximum points. + * \param[in] cloud the point cloud dataset + * \param[in] indices a set of point indices to use from \a cloud + * \param[out] pmin the coordinates of the "minimum" point in \a cloud (one end of the segment) + * \param[out] pmax the coordinates of the "maximum" point in \a cloud (the other end of the segment) + * \return the length of segment length + * \ingroup common + */ + template double inline + getMaxSegment (const pcl::PointCloud &cloud, const std::vector &indices, + PointT &pmin, PointT &pmax) + { + double max_dist = std::numeric_limits::min (); + int i_min = -1, i_max = -1; + + for (size_t i = 0; i < indices.size (); ++i) + { + for (size_t j = i; j < indices.size (); ++j) + { + // Compute the distance + double dist = (cloud.points[indices[i]].getVector4fMap () - + cloud.points[indices[j]].getVector4fMap ()).squaredNorm (); + if (dist <= max_dist) + continue; + + max_dist = dist; + i_min = i; + i_max = j; + } + } + + if (i_min == -1 || i_max == -1) + return (max_dist = std::numeric_limits::min ()); + + pmin = cloud.points[indices[i_min]]; + pmax = cloud.points[indices[i_max]]; + return (std::sqrt (max_dist)); + } + + /** \brief Calculate the squared euclidean distance between the two given points. + * \param[in] p1 the first point + * \param[in] p2 the second point + */ + template inline float + squaredEuclideanDistance (const PointType1& p1, const PointType2& p2) + { + float diff_x = p2.x - p1.x, diff_y = p2.y - p1.y, diff_z = p2.z - p1.z; + return (diff_x*diff_x + diff_y*diff_y + diff_z*diff_z); + } + + /** \brief Calculate the squared euclidean distance between the two given points. + * \param[in] p1 the first point + * \param[in] p2 the second point + */ + template<> inline float + squaredEuclideanDistance (const PointXY& p1, const PointXY& p2) + { + float diff_x = p2.x - p1.x, diff_y = p2.y - p1.y; + return (diff_x*diff_x + diff_y*diff_y); + } + + /** \brief Calculate the euclidean distance between the two given points. + * \param[in] p1 the first point + * \param[in] p2 the second point + */ + template inline float + euclideanDistance (const PointType1& p1, const PointType2& p2) + { + return (sqrtf (squaredEuclideanDistance (p1, p2))); + } +} +/*@*/ +#endif //#ifndef PCL_DISTANCES_H_ + diff --git a/pcl-1.7/pcl/common/eigen.h b/pcl-1.7/pcl/common/eigen.h new file mode 100644 index 0000000..9557f03 --- /dev/null +++ b/pcl-1.7/pcl/common/eigen.h @@ -0,0 +1,722 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (C) 2010 Gael Guennebaud + * Copyright (C) 2009 Hauke Heibel + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_COMMON_EIGEN_H_ +#define PCL_COMMON_EIGEN_H_ + +#ifndef NOMINMAX +#define NOMINMAX +#endif + +#if defined __GNUC__ +# pragma GCC system_header +#elif defined __SUNPRO_CC +# pragma disable_warn +#endif + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Compute the roots of a quadratic polynom x^2 + b*x + c = 0 + * \param[in] b linear parameter + * \param[in] c constant parameter + * \param[out] roots solutions of x^2 + b*x + c = 0 + */ + template void + computeRoots2 (const Scalar &b, const Scalar &c, Roots &roots); + + /** \brief computes the roots of the characteristic polynomial of the input matrix m, which are the eigenvalues + * \param[in] m input matrix + * \param[out] roots roots of the characteristic polynomial of the input matrix m, which are the eigenvalues + */ + template void + computeRoots (const Matrix &m, Roots &roots); + + /** \brief determine the smallest eigenvalue and its corresponding eigenvector + * \param[in] mat input matrix that needs to be symmetric and positive semi definite + * \param[out] eigenvalue the smallest eigenvalue of the input matrix + * \param[out] eigenvector the corresponding eigenvector to the smallest eigenvalue of the input matrix + * \ingroup common + */ + template void + eigen22 (const Matrix &mat, typename Matrix::Scalar &eigenvalue, Vector &eigenvector); + + /** \brief determine the smallest eigenvalue and its corresponding eigenvector + * \param[in] mat input matrix that needs to be symmetric and positive semi definite + * \param[out] eigenvectors the corresponding eigenvector to the smallest eigenvalue of the input matrix + * \param[out] eigenvalues the smallest eigenvalue of the input matrix + * \ingroup common + */ + template void + eigen22 (const Matrix &mat, Matrix &eigenvectors, Vector &eigenvalues); + + /** \brief determines the corresponding eigenvector to the given eigenvalue of the symmetric positive semi definite input matrix + * \param[in] mat symmetric positive semi definite input matrix + * \param[in] eigenvalue the eigenvalue which corresponding eigenvector is to be computed + * \param[out] eigenvector the corresponding eigenvector for the input eigenvalue + * \ingroup common + */ + template void + computeCorrespondingEigenVector (const Matrix &mat, const typename Matrix::Scalar &eigenvalue, Vector &eigenvector); + + /** \brief determines the eigenvector and eigenvalue of the smallest eigenvalue of the symmetric positive semi definite input matrix + * \param[in] mat symmetric positive semi definite input matrix + * \param[out] eigenvalue smallest eigenvalue of the input matrix + * \param[out] eigenvector the corresponding eigenvector for the input eigenvalue + * \note if the smallest eigenvalue is not unique, this function may return any eigenvector that is consistent to the eigenvalue. + * \ingroup common + */ + template void + eigen33 (const Matrix &mat, typename Matrix::Scalar &eigenvalue, Vector &eigenvector); + + /** \brief determines the eigenvalues of the symmetric positive semi definite input matrix + * \param[in] mat symmetric positive semi definite input matrix + * \param[out] evals resulting eigenvalues in ascending order + * \ingroup common + */ + template void + eigen33 (const Matrix &mat, Vector &evals); + + /** \brief determines the eigenvalues and corresponding eigenvectors of the symmetric positive semi definite input matrix + * \param[in] mat symmetric positive semi definite input matrix + * \param[out] evecs resulting eigenvalues in ascending order + * \param[out] evals corresponding eigenvectors in correct order according to eigenvalues + * \ingroup common + */ + template void + eigen33 (const Matrix &mat, Matrix &evecs, Vector &evals); + + /** \brief Calculate the inverse of a 2x2 matrix + * \param[in] matrix matrix to be inverted + * \param[out] inverse the resultant inverted matrix + * \note only the upper triangular part is taken into account => non symmetric matrices will give wrong results + * \return determinant of the original matrix => if 0 no inverse exists => result is invalid + * \ingroup common + */ + template typename Matrix::Scalar + invert2x2 (const Matrix &matrix, Matrix &inverse); + + /** \brief Calculate the inverse of a 3x3 symmetric matrix. + * \param[in] matrix matrix to be inverted + * \param[out] inverse the resultant inverted matrix + * \note only the upper triangular part is taken into account => non symmetric matrices will give wrong results + * \return determinant of the original matrix => if 0 no inverse exists => result is invalid + * \ingroup common + */ + template typename Matrix::Scalar + invert3x3SymMatrix (const Matrix &matrix, Matrix &inverse); + + /** \brief Calculate the inverse of a general 3x3 matrix. + * \param[in] matrix matrix to be inverted + * \param[out] inverse the resultant inverted matrix + * \return determinant of the original matrix => if 0 no inverse exists => result is invalid + * \ingroup common + */ + template typename Matrix::Scalar + invert3x3Matrix (const Matrix &matrix, Matrix &inverse); + + /** \brief Calculate the determinant of a 3x3 matrix. + * \param[in] matrix matrix + * \return determinant of the matrix + * \ingroup common + */ + template typename Matrix::Scalar + determinant3x3Matrix (const Matrix &matrix); + + /** \brief Get the unique 3D rotation that will rotate \a z_axis into (0,0,1) and \a y_direction into a vector + * with x=0 (or into (0,1,0) should \a y_direction be orthogonal to \a z_axis) + * \param[in] z_axis the z-axis + * \param[in] y_direction the y direction + * \param[out] transformation the resultant 3D rotation + * \ingroup common + */ + inline void + getTransFromUnitVectorsZY (const Eigen::Vector3f& z_axis, + const Eigen::Vector3f& y_direction, + Eigen::Affine3f& transformation); + + /** \brief Get the unique 3D rotation that will rotate \a z_axis into (0,0,1) and \a y_direction into a vector + * with x=0 (or into (0,1,0) should \a y_direction be orthogonal to \a z_axis) + * \param[in] z_axis the z-axis + * \param[in] y_direction the y direction + * \return the resultant 3D rotation + * \ingroup common + */ + inline Eigen::Affine3f + getTransFromUnitVectorsZY (const Eigen::Vector3f& z_axis, + const Eigen::Vector3f& y_direction); + + /** \brief Get the unique 3D rotation that will rotate \a x_axis into (1,0,0) and \a y_direction into a vector + * with z=0 (or into (0,1,0) should \a y_direction be orthogonal to \a z_axis) + * \param[in] x_axis the x-axis + * \param[in] y_direction the y direction + * \param[out] transformation the resultant 3D rotation + * \ingroup common + */ + inline void + getTransFromUnitVectorsXY (const Eigen::Vector3f& x_axis, + const Eigen::Vector3f& y_direction, + Eigen::Affine3f& transformation); + + /** \brief Get the unique 3D rotation that will rotate \a x_axis into (1,0,0) and \a y_direction into a vector + * with z=0 (or into (0,1,0) should \a y_direction be orthogonal to \a z_axis) + * \param[in] x_axis the x-axis + * \param[in] y_direction the y direction + * \return the resulting 3D rotation + * \ingroup common + */ + inline Eigen::Affine3f + getTransFromUnitVectorsXY (const Eigen::Vector3f& x_axis, + const Eigen::Vector3f& y_direction); + + /** \brief Get the unique 3D rotation that will rotate \a z_axis into (0,0,1) and \a y_direction into a vector + * with x=0 (or into (0,1,0) should \a y_direction be orthogonal to \a z_axis) + * \param[in] y_direction the y direction + * \param[in] z_axis the z-axis + * \param[out] transformation the resultant 3D rotation + * \ingroup common + */ + inline void + getTransformationFromTwoUnitVectors (const Eigen::Vector3f& y_direction, + const Eigen::Vector3f& z_axis, + Eigen::Affine3f& transformation); + + /** \brief Get the unique 3D rotation that will rotate \a z_axis into (0,0,1) and \a y_direction into a vector + * with x=0 (or into (0,1,0) should \a y_direction be orthogonal to \a z_axis) + * \param[in] y_direction the y direction + * \param[in] z_axis the z-axis + * \return transformation the resultant 3D rotation + * \ingroup common + */ + inline Eigen::Affine3f + getTransformationFromTwoUnitVectors (const Eigen::Vector3f& y_direction, + const Eigen::Vector3f& z_axis); + + /** \brief Get the transformation that will translate \a orign to (0,0,0) and rotate \a z_axis into (0,0,1) + * and \a y_direction into a vector with x=0 (or into (0,1,0) should \a y_direction be orthogonal to \a z_axis) + * \param[in] y_direction the y direction + * \param[in] z_axis the z-axis + * \param[in] origin the origin + * \param[in] transformation the resultant transformation matrix + * \ingroup common + */ + inline void + getTransformationFromTwoUnitVectorsAndOrigin (const Eigen::Vector3f& y_direction, + const Eigen::Vector3f& z_axis, + const Eigen::Vector3f& origin, + Eigen::Affine3f& transformation); + + /** \brief Extract the Euler angles (XYZ-convention) from the given transformation + * \param[in] t the input transformation matrix + * \param[in] roll the resulting roll angle + * \param[in] pitch the resulting pitch angle + * \param[in] yaw the resulting yaw angle + * \ingroup common + */ + template void + getEulerAngles (const Eigen::Transform &t, Scalar &roll, Scalar &pitch, Scalar &yaw); + + inline void + getEulerAngles (const Eigen::Affine3f &t, float &roll, float &pitch, float &yaw) + { + getEulerAngles (t, roll, pitch, yaw); + } + + inline void + getEulerAngles (const Eigen::Affine3d &t, double &roll, double &pitch, double &yaw) + { + getEulerAngles (t, roll, pitch, yaw); + } + + /** Extract x,y,z and the Euler angles (XYZ-convention) from the given transformation + * \param[in] t the input transformation matrix + * \param[out] x the resulting x translation + * \param[out] y the resulting y translation + * \param[out] z the resulting z translation + * \param[out] roll the resulting roll angle + * \param[out] pitch the resulting pitch angle + * \param[out] yaw the resulting yaw angle + * \ingroup common + */ + template void + getTranslationAndEulerAngles (const Eigen::Transform &t, + Scalar &x, Scalar &y, Scalar &z, + Scalar &roll, Scalar &pitch, Scalar &yaw); + + inline void + getTranslationAndEulerAngles (const Eigen::Affine3f &t, + float &x, float &y, float &z, + float &roll, float &pitch, float &yaw) + { + getTranslationAndEulerAngles (t, x, y, z, roll, pitch, yaw); + } + + inline void + getTranslationAndEulerAngles (const Eigen::Affine3d &t, + double &x, double &y, double &z, + double &roll, double &pitch, double &yaw) + { + getTranslationAndEulerAngles (t, x, y, z, roll, pitch, yaw); + } + + /** \brief Create a transformation from the given translation and Euler angles (XYZ-convention) + * \param[in] x the input x translation + * \param[in] y the input y translation + * \param[in] z the input z translation + * \param[in] roll the input roll angle + * \param[in] pitch the input pitch angle + * \param[in] yaw the input yaw angle + * \param[out] t the resulting transformation matrix + * \ingroup common + */ + template void + getTransformation (Scalar x, Scalar y, Scalar z, Scalar roll, Scalar pitch, Scalar yaw, + Eigen::Transform &t); + + inline void + getTransformation (float x, float y, float z, float roll, float pitch, float yaw, + Eigen::Affine3f &t) + { + return (getTransformation (x, y, z, roll, pitch, yaw, t)); + } + + inline void + getTransformation (double x, double y, double z, double roll, double pitch, double yaw, + Eigen::Affine3d &t) + { + return (getTransformation (x, y, z, roll, pitch, yaw, t)); + } + + /** \brief Create a transformation from the given translation and Euler angles (XYZ-convention) + * \param[in] x the input x translation + * \param[in] y the input y translation + * \param[in] z the input z translation + * \param[in] roll the input roll angle + * \param[in] pitch the input pitch angle + * \param[in] yaw the input yaw angle + * \return the resulting transformation matrix + * \ingroup common + */ + inline Eigen::Affine3f + getTransformation (float x, float y, float z, float roll, float pitch, float yaw) + { + Eigen::Affine3f t; + getTransformation (x, y, z, roll, pitch, yaw, t); + return (t); + } + + /** \brief Write a matrix to an output stream + * \param[in] matrix the matrix to output + * \param[out] file the output stream + * \ingroup common + */ + template void + saveBinary (const Eigen::MatrixBase& matrix, std::ostream& file); + + /** \brief Read a matrix from an input stream + * \param[out] matrix the resulting matrix, read from the input stream + * \param[in,out] file the input stream + * \ingroup common + */ + template void + loadBinary (Eigen::MatrixBase const& matrix, std::istream& file); + +// PCL_EIGEN_SIZE_MIN_PREFER_DYNAMIC gives the min between compile-time sizes. 0 has absolute priority, followed by 1, +// followed by Dynamic, followed by other finite values. The reason for giving Dynamic the priority over +// finite values is that min(3, Dynamic) should be Dynamic, since that could be anything between 0 and 3. +#define PCL_EIGEN_SIZE_MIN_PREFER_DYNAMIC(a,b) ((int (a) == 0 || int (b) == 0) ? 0 \ + : (int (a) == 1 || int (b) == 1) ? 1 \ + : (int (a) == Eigen::Dynamic || int (b) == Eigen::Dynamic) ? Eigen::Dynamic \ + : (int (a) <= int (b)) ? int (a) : int (b)) + + /** \brief Returns the transformation between two point sets. + * The algorithm is based on: + * "Least-squares estimation of transformation parameters between two point patterns", + * Shinji Umeyama, PAMI 1991, DOI: 10.1109/34.88573 + * + * It estimates parameters \f$ c, \mathbf{R}, \f$ and \f$ \mathbf{t} \f$ such that + * \f{align*} + * \frac{1}{n} \sum_{i=1}^n \vert\vert y_i - (c\mathbf{R}x_i + \mathbf{t}) \vert\vert_2^2 + * \f} + * is minimized. + * + * The algorithm is based on the analysis of the covariance matrix + * \f$ \Sigma_{\mathbf{x}\mathbf{y}} \in \mathbb{R}^{d \times d} \f$ + * of the input point sets \f$ \mathbf{x} \f$ and \f$ \mathbf{y} \f$ where + * \f$d\f$ is corresponding to the dimension (which is typically small). + * The analysis is involving the SVD having a complexity of \f$O(d^3)\f$ + * though the actual computational effort lies in the covariance + * matrix computation which has an asymptotic lower bound of \f$O(dm)\f$ when + * the input point sets have dimension \f$d \times m\f$. + * + * \param[in] src Source points \f$ \mathbf{x} = \left( x_1, \hdots, x_n \right) \f$ + * \param[in] dst Destination points \f$ \mathbf{y} = \left( y_1, \hdots, y_n \right) \f$. + * \param[in] with_scaling Sets \f$ c=1 \f$ when false is passed. (default: false) + * \return The homogeneous transformation + * \f{align*} + * T = \begin{bmatrix} c\mathbf{R} & \mathbf{t} \\ \mathbf{0} & 1 \end{bmatrix} + * \f} + * minimizing the resudiual above. This transformation is always returned as an + * Eigen::Matrix. + */ + template + typename Eigen::internal::umeyama_transform_matrix_type::type + umeyama (const Eigen::MatrixBase& src, const Eigen::MatrixBase& dst, bool with_scaling = false); + +/** \brief Transform a point using an affine matrix + * \param[in] point_in the vector to be transformed + * \param[out] point_out the transformed vector + * \param[in] transformation the transformation matrix + * + * \note Can be used with \c point_in = \c point_out + */ + template inline void + transformPoint (const Eigen::Matrix &point_in, + Eigen::Matrix &point_out, + const Eigen::Transform &transformation) + { + Eigen::Matrix point; + point << point_in, 1.0; + point_out = (transformation * point).template head<3> (); + } + + inline void + transformPoint (const Eigen::Vector3f &point_in, + Eigen::Vector3f &point_out, + const Eigen::Affine3f &transformation) + { + transformPoint (point_in, point_out, transformation); + } + + inline void + transformPoint (const Eigen::Vector3d &point_in, + Eigen::Vector3d &point_out, + const Eigen::Affine3d &transformation) + { + transformPoint (point_in, point_out, transformation); + } + +/** \brief Transform a vector using an affine matrix + * \param[in] vector_in the vector to be transformed + * \param[out] vector_out the transformed vector + * \param[in] transformation the transformation matrix + * + * \note Can be used with \c vector_in = \c vector_out + */ + template inline void + transformVector (const Eigen::Matrix &vector_in, + Eigen::Matrix &vector_out, + const Eigen::Transform &transformation) + { + vector_out = transformation.linear () * vector_in; + } + + inline void + transformVector (const Eigen::Vector3f &vector_in, + Eigen::Vector3f &vector_out, + const Eigen::Affine3f &transformation) + { + transformVector (vector_in, vector_out, transformation); + } + + inline void + transformVector (const Eigen::Vector3d &vector_in, + Eigen::Vector3d &vector_out, + const Eigen::Affine3d &transformation) + { + transformVector (vector_in, vector_out, transformation); + } + +/** \brief Transform a line using an affine matrix + * \param[in] line_in the line to be transformed + * \param[out] line_out the transformed line + * \param[in] transformation the transformation matrix + * + * Lines must be filled in this form:\n + * line[0-2] = Origin coordinates of the vector\n + * line[3-5] = Direction vector + * + * \note Can be used with \c line_in = \c line_out + */ + template bool + transformLine (const Eigen::Matrix &line_in, + Eigen::Matrix &line_out, + const Eigen::Transform &transformation); + + inline bool + transformLine (const Eigen::VectorXf &line_in, + Eigen::VectorXf &line_out, + const Eigen::Affine3f &transformation) + { + return (transformLine (line_in, line_out, transformation)); + } + + inline bool + transformLine (const Eigen::VectorXd &line_in, + Eigen::VectorXd &line_out, + const Eigen::Affine3d &transformation) + { + return (transformLine (line_in, line_out, transformation)); + } + +/** \brief Transform plane vectors using an affine matrix + * \param[in] plane_in the plane coefficients to be transformed + * \param[out] plane_out the transformed plane coefficients to fill + * \param[in] transformation the transformation matrix + * + * The plane vectors are filled in the form ax+by+cz+d=0 + * Can be used with non Hessian form planes coefficients + * Can be used with \c plane_in = \c plane_out + */ + template void + transformPlane (const Eigen::Matrix &plane_in, + Eigen::Matrix &plane_out, + const Eigen::Transform &transformation); + + inline void + transformPlane (const Eigen::Matrix &plane_in, + Eigen::Matrix &plane_out, + const Eigen::Transform &transformation) + { + transformPlane (plane_in, plane_out, transformation); + } + + inline void + transformPlane (const Eigen::Matrix &plane_in, + Eigen::Matrix &plane_out, + const Eigen::Transform &transformation) + { + transformPlane (plane_in, plane_out, transformation); + } + +/** \brief Transform plane vectors using an affine matrix + * \param[in] plane_in the plane coefficients to be transformed + * \param[out] plane_out the transformed plane coefficients to fill + * \param[in] transformation the transformation matrix + * + * The plane vectors are filled in the form ax+by+cz+d=0 + * Can be used with non Hessian form planes coefficients + * Can be used with \c plane_in = \c plane_out + * \warning ModelCoefficients stores floats only ! + */ + template void + transformPlane (const pcl::ModelCoefficients::Ptr plane_in, + pcl::ModelCoefficients::Ptr plane_out, + const Eigen::Transform &transformation); + + inline void + transformPlane (const pcl::ModelCoefficients::Ptr plane_in, + pcl::ModelCoefficients::Ptr plane_out, + const Eigen::Transform &transformation) + { + transformPlane (plane_in, plane_out, transformation); + } + + inline void + transformPlane (const pcl::ModelCoefficients::Ptr plane_in, + pcl::ModelCoefficients::Ptr plane_out, + const Eigen::Transform &transformation) + { + transformPlane (plane_in, plane_out, transformation); + } + +/** \brief Check coordinate system integrity + * \param[in] line_x the first axis + * \param[in] line_y the second axis + * \param[in] norm_limit the limit to ignore norm rounding errors + * \param[in] dot_limit the limit to ignore dot product rounding errors + * \return True if the coordinate system is consistent, false otherwise. + * + * Lines must be filled in this form:\n + * line[0-2] = Origin coordinates of the vector\n + * line[3-5] = Direction vector + * + * Can be used like this :\n + * line_x = X axis and line_y = Y axis\n + * line_x = Z axis and line_y = X axis\n + * line_x = Y axis and line_y = Z axis\n + * Because X^Y = Z, Z^X = Y and Y^Z = X. + * Do NOT invert line order ! + * + * Determine whether a coordinate system is consistent or not by checking :\n + * Line origins: They must be the same for the 2 lines\n + * Norm: The 2 lines must be normalized\n + * Dot products: Must be 0 or perpendicular vectors + */ + template bool + checkCoordinateSystem (const Eigen::Matrix &line_x, + const Eigen::Matrix &line_y, + const Scalar norm_limit = 1e-3, + const Scalar dot_limit = 1e-3); + + inline bool + checkCoordinateSystem (const Eigen::Matrix &line_x, + const Eigen::Matrix &line_y, + const double norm_limit = 1e-3, + const double dot_limit = 1e-3) + { + return (checkCoordinateSystem (line_x, line_y, norm_limit, dot_limit)); + } + + inline bool + checkCoordinateSystem (const Eigen::Matrix &line_x, + const Eigen::Matrix &line_y, + const float norm_limit = 1e-3, + const float dot_limit = 1e-3) + { + return (checkCoordinateSystem (line_x, line_y, norm_limit, dot_limit)); + } + +/** \brief Check coordinate system integrity + * \param[in] origin the origin of the coordinate system + * \param[in] x_direction the first axis + * \param[in] y_direction the second axis + * \param[in] norm_limit the limit to ignore norm rounding errors + * \param[in] dot_limit the limit to ignore dot product rounding errors + * \return True if the coordinate system is consistent, false otherwise. + * + * Read the other variant for more information + */ + template inline bool + checkCoordinateSystem (const Eigen::Matrix &origin, + const Eigen::Matrix &x_direction, + const Eigen::Matrix &y_direction, + const Scalar norm_limit = 1e-3, + const Scalar dot_limit = 1e-3) + { + Eigen::Matrix line_x; + Eigen::Matrix line_y; + line_x << origin, x_direction; + line_y << origin, y_direction; + return (checkCoordinateSystem (line_x, line_y, norm_limit, dot_limit)); + } + + inline bool + checkCoordinateSystem (const Eigen::Matrix &origin, + const Eigen::Matrix &x_direction, + const Eigen::Matrix &y_direction, + const double norm_limit = 1e-3, + const double dot_limit = 1e-3) + { + Eigen::Matrix line_x; + Eigen::Matrix line_y; + line_x.resize (6); + line_y.resize (6); + line_x << origin, x_direction; + line_y << origin, y_direction; + return (checkCoordinateSystem (line_x, line_y, norm_limit, dot_limit)); + } + + inline bool + checkCoordinateSystem (const Eigen::Matrix &origin, + const Eigen::Matrix &x_direction, + const Eigen::Matrix &y_direction, + const float norm_limit = 1e-3, + const float dot_limit = 1e-3) + { + Eigen::Matrix line_x; + Eigen::Matrix line_y; + line_x.resize (6); + line_y.resize (6); + line_x << origin, x_direction; + line_y << origin, y_direction; + return (checkCoordinateSystem (line_x, line_y, norm_limit, dot_limit)); + } + +/** \brief Compute the transformation between two coordinate systems + * \param[in] from_line_x X axis from the origin coordinate system + * \param[in] from_line_y Y axis from the origin coordinate system + * \param[in] to_line_x X axis from the destination coordinate system + * \param[in] to_line_y Y axis from the destination coordinate system + * \param[out] transformation the transformation matrix to fill + * \return true if transformation was filled, false otherwise. + * + * Line must be filled in this form:\n + * line[0-2] = Coordinate system origin coordinates \n + * line[3-5] = Direction vector (norm doesn't matter) + */ + template bool + transformBetween2CoordinateSystems (const Eigen::Matrix from_line_x, + const Eigen::Matrix from_line_y, + const Eigen::Matrix to_line_x, + const Eigen::Matrix to_line_y, + Eigen::Transform &transformation); + + inline bool + transformBetween2CoordinateSystems (const Eigen::Matrix from_line_x, + const Eigen::Matrix from_line_y, + const Eigen::Matrix to_line_x, + const Eigen::Matrix to_line_y, + Eigen::Transform &transformation) + { + return (transformBetween2CoordinateSystems (from_line_x, from_line_y, to_line_x, to_line_y, transformation)); + } + + inline bool + transformBetween2CoordinateSystems (const Eigen::Matrix from_line_x, + const Eigen::Matrix from_line_y, + const Eigen::Matrix to_line_x, + const Eigen::Matrix to_line_y, + Eigen::Transform &transformation) + { + return (transformBetween2CoordinateSystems (from_line_x, from_line_y, to_line_x, to_line_y, transformation)); + } + +} + +#include + +#if defined __SUNPRO_CC +# pragma enable_warn +#endif + +#endif //PCL_COMMON_EIGEN_H_ diff --git a/pcl-1.7/pcl/common/fft/_kiss_fft_guts.h b/pcl-1.7/pcl/common/fft/_kiss_fft_guts.h new file mode 100644 index 0000000..ba66144 --- /dev/null +++ b/pcl-1.7/pcl/common/fft/_kiss_fft_guts.h @@ -0,0 +1,164 @@ +/* +Copyright (c) 2003-2010, Mark Borgerding + +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + * Neither the author nor the names of any contributors may be used to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +/* kiss_fft.h + defines kiss_fft_scalar as either short or a float type + and defines + typedef struct { kiss_fft_scalar r; kiss_fft_scalar i; }kiss_fft_cpx; */ +#include "kiss_fft.h" +#include + +#define MAXFACTORS 32 +/* e.g. an fft of length 128 has 4 factors + as far as kissfft is concerned + 4*4*4*2 + */ + +struct kiss_fft_state{ + int nfft; + int inverse; + int factors[2*MAXFACTORS]; + kiss_fft_cpx twiddles[1]; +}; + +/* + Explanation of macros dealing with complex math: + + C_MUL(m,a,b) : m = a*b + C_FIXDIV( c , div ) : if a fixed point impl., c /= div. noop otherwise + C_SUB( res, a,b) : res = a - b + C_SUBFROM( res , a) : res -= a + C_ADDTO( res , a) : res += a + * */ +#ifdef FIXED_POINT +#if (FIXED_POINT==32) +# define FRACBITS 31 +# define SAMPPROD int64_t +#define SAMP_MAX 2147483647 +#else +# define FRACBITS 15 +# define SAMPPROD int32_t +#define SAMP_MAX 32767 +#endif + +#define SAMP_MIN -SAMP_MAX + +#if defined(CHECK_OVERFLOW) +# define CHECK_OVERFLOW_OP(a,op,b) \ + if ( (SAMPPROD)(a) op (SAMPPROD)(b) > SAMP_MAX || (SAMPPROD)(a) op (SAMPPROD)(b) < SAMP_MIN ) { \ + fprintf(stderr,"WARNING:overflow @ " __FILE__ "(%d): (%d " #op" %d) = %ld\n",__LINE__,(a),(b),(SAMPPROD)(a) op (SAMPPROD)(b) ); } +#endif + + +# define smul(a,b) ( (SAMPPROD)(a)*(b) ) +# define sround( x ) (kiss_fft_scalar)( ( (x) + (1<<(FRACBITS-1)) ) >> FRACBITS ) + +# define S_MUL(a,b) sround( smul(a,b) ) + +# define C_MUL(m,a,b) \ + do{ (m).r = sround( smul((a).r,(b).r) - smul((a).i,(b).i) ); \ + (m).i = sround( smul((a).r,(b).i) + smul((a).i,(b).r) ); }while(0) + +# define DIVSCALAR(x,k) \ + (x) = sround( smul( x, SAMP_MAX/k ) ) + +# define C_FIXDIV(c,div) \ + do { DIVSCALAR( (c).r , div); \ + DIVSCALAR( (c).i , div); }while (0) + +# define C_MULBYSCALAR( c, s ) \ + do{ (c).r = sround( smul( (c).r , s ) ) ;\ + (c).i = sround( smul( (c).i , s ) ) ; }while(0) + +#else /* not FIXED_POINT*/ + +# define S_MUL(a,b) ( (a)*(b) ) +#define C_MUL(m,a,b) \ + do{ (m).r = (a).r*(b).r - (a).i*(b).i;\ + (m).i = (a).r*(b).i + (a).i*(b).r; }while(0) +# define C_FIXDIV(c,div) /* NOOP */ +# define C_MULBYSCALAR( c, s ) \ + do{ (c).r *= (s);\ + (c).i *= (s); }while(0) +#endif + +#ifndef CHECK_OVERFLOW_OP +# define CHECK_OVERFLOW_OP(a,op,b) /* noop */ +#endif + +#define C_ADD( res, a,b)\ + do { \ + CHECK_OVERFLOW_OP((a).r,+,(b).r)\ + CHECK_OVERFLOW_OP((a).i,+,(b).i)\ + (res).r=(a).r+(b).r; (res).i=(a).i+(b).i; \ + }while(0) +#define C_SUB( res, a,b)\ + do { \ + CHECK_OVERFLOW_OP((a).r,-,(b).r)\ + CHECK_OVERFLOW_OP((a).i,-,(b).i)\ + (res).r=(a).r-(b).r; (res).i=(a).i-(b).i; \ + }while(0) +#define C_ADDTO( res , a)\ + do { \ + CHECK_OVERFLOW_OP((res).r,+,(a).r)\ + CHECK_OVERFLOW_OP((res).i,+,(a).i)\ + (res).r += (a).r; (res).i += (a).i;\ + }while(0) + +#define C_SUBFROM( res , a)\ + do {\ + CHECK_OVERFLOW_OP((res).r,-,(a).r)\ + CHECK_OVERFLOW_OP((res).i,-,(a).i)\ + (res).r -= (a).r; (res).i -= (a).i; \ + }while(0) + + +#ifdef FIXED_POINT +# define KISS_FFT_COS(phase) floor(.5+SAMP_MAX * cos (phase)) +# define KISS_FFT_SIN(phase) floor(.5+SAMP_MAX * sin (phase)) +# define HALF_OF(x) ((x)>>1) +#elif defined(USE_SIMD) +# define KISS_FFT_COS(phase) _mm_set1_ps( cos(phase) ) +# define KISS_FFT_SIN(phase) _mm_set1_ps( sin(phase) ) +# define HALF_OF(x) ((x)*_mm_set1_ps(.5)) +#else +# define KISS_FFT_COS(phase) (kiss_fft_scalar) cos(phase) +# define KISS_FFT_SIN(phase) (kiss_fft_scalar) sin(phase) +# define HALF_OF(x) ((x)*.5) +#endif + +#define kf_cexp(x,phase) \ + do{ \ + (x)->r = KISS_FFT_COS(phase);\ + (x)->i = KISS_FFT_SIN(phase);\ + }while(0) + + +/* a debugging function */ +#define pcpx(c)\ + fprintf(stderr,"%g + %gi\n",(double)((c)->r),(double)((c)->i) ) + + +#ifdef KISS_FFT_USE_ALLOCA +// define this to allow use of alloca instead of malloc for temporary buffers +// Temporary buffers are used in two case: +// 1. FFT sizes that have "bad" factors. i.e. not 2,3 and 5 +// 2. "in-place" FFTs. Notice the quotes, since kissfft does not really do an in-place transform. +#include +#define KISS_FFT_TMP_ALLOC(nbytes) alloca(nbytes) +#define KISS_FFT_TMP_FREE(ptr) +#else +#define KISS_FFT_TMP_ALLOC(nbytes) KISS_FFT_MALLOC(nbytes) +#define KISS_FFT_TMP_FREE(ptr) KISS_FFT_FREE(ptr) +#endif diff --git a/pcl-1.7/pcl/common/fft/kiss_fft.h b/pcl-1.7/pcl/common/fft/kiss_fft.h new file mode 100644 index 0000000..97487d2 --- /dev/null +++ b/pcl-1.7/pcl/common/fft/kiss_fft.h @@ -0,0 +1,134 @@ +#ifndef KISS_FFT_H +#define KISS_FFT_H + +#include +#include +#include +#include + +#if !defined(__APPLE__) +#include +#endif + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* + ATTENTION! + If you would like a : + -- a utility that will handle the caching of fft objects + -- real-only (no imaginary time component ) FFT + -- a multi-dimensional FFT + -- a command-line utility to perform ffts + -- a command-line utility to perform fast-convolution filtering + + Then see kfc.h kiss_fftr.h kiss_fftnd.h fftutil.c kiss_fastfir.c + in the tools/ directory. +*/ + +#ifdef USE_SIMD +# include +# define kiss_fft_scalar __m128 +#define KISS_FFT_MALLOC(nbytes) _mm_malloc(nbytes,16) +#define KISS_FFT_FREE _mm_free +#else +#define KISS_FFT_MALLOC malloc +#define KISS_FFT_FREE free +#endif + + +#ifdef FIXED_POINT +#include +# if (FIXED_POINT == 32) +# define kiss_fft_scalar int32_t +# else +# define kiss_fft_scalar int16_t +# endif +#else +# ifndef kiss_fft_scalar +/* default is float */ +# define kiss_fft_scalar float +# endif +#endif + +typedef struct { + kiss_fft_scalar r; + kiss_fft_scalar i; +}kiss_fft_cpx; + +typedef struct kiss_fft_state* kiss_fft_cfg; + +/* + * kiss_fft_alloc + * + * Initialize a FFT (or IFFT) algorithm's cfg/state buffer. + * + * typical usage: kiss_fft_cfg mycfg=kiss_fft_alloc(1024,0,NULL,NULL); + * + * The return value from fft_alloc is a cfg buffer used internally + * by the fft routine or NULL. + * + * If lenmem is NULL, then kiss_fft_alloc will allocate a cfg buffer using malloc. + * The returned value should be free()d when done to avoid memory leaks. + * + * The state can be placed in a user supplied buffer 'mem': + * If lenmem is not NULL and mem is not NULL and *lenmem is large enough, + * then the function places the cfg in mem and the size used in *lenmem + * and returns mem. + * + * If lenmem is not NULL and ( mem is NULL or *lenmem is not large enough), + * then the function returns NULL and places the minimum cfg + * buffer size in *lenmem. + * */ + +kiss_fft_cfg PCL_EXPORTS +kiss_fft_alloc(int nfft,int inverse_fft,void * mem,size_t * lenmem); + +/* + * kiss_fft(cfg,in_out_buf) + * + * Perform an FFT on a complex input buffer. + * for a forward FFT, + * fin should be f[0] , f[1] , ... ,f[nfft-1] + * fout will be F[0] , F[1] , ... ,F[nfft-1] + * Note that each element is complex and can be accessed like + f[k].r and f[k].i + * */ +void PCL_EXPORTS +kiss_fft(kiss_fft_cfg cfg,const kiss_fft_cpx *fin,kiss_fft_cpx *fout); + +/* + A more generic version of the above function. It reads its input from every Nth sample. + * */ +void PCL_EXPORTS +kiss_fft_stride(kiss_fft_cfg cfg,const kiss_fft_cpx *fin,kiss_fft_cpx *fout,int fin_stride); + +/* If kiss_fft_alloc allocated a buffer, it is one contiguous + buffer and can be simply free()d when no longer needed*/ +#define kiss_fft_free free + +/* + Cleans up some memory that gets managed internally. Not necessary to call, but it might clean up + your compiler output to call this before you exit. +*/ +void PCL_EXPORTS +kiss_fft_cleanup(void); + +/* + * Returns the smallest integer k, such that k>=n and k has only "fast" factors (2,3,5) + */ +int PCL_EXPORTS +kiss_fft_next_fast_size(int n); + +/* for real ffts, we need an even size */ +#define kiss_fftr_next_fast_size_real(n) \ + (kiss_fft_next_fast_size( ((n)+1)>>1)<<1) + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/pcl-1.7/pcl/common/fft/kiss_fftr.h b/pcl-1.7/pcl/common/fft/kiss_fftr.h new file mode 100644 index 0000000..810b6f5 --- /dev/null +++ b/pcl-1.7/pcl/common/fft/kiss_fftr.h @@ -0,0 +1,46 @@ +#ifndef KISS_FTR_H +#define KISS_FTR_H + +#include "kiss_fft.h" +#ifdef __cplusplus +extern "C" { +#endif + + +/* + + Real optimized version can save about 45% cpu time vs. complex fft of a real seq. + + + + */ + +typedef struct kiss_fftr_state *kiss_fftr_cfg; + + +kiss_fftr_cfg PCL_EXPORTS kiss_fftr_alloc(int nfft,int inverse_fft,void * mem, size_t * lenmem); +/* + nfft must be even + + If you don't care to allocate space, use mem = lenmem = NULL +*/ + + +void PCL_EXPORTS kiss_fftr(kiss_fftr_cfg cfg,const kiss_fft_scalar *timedata,kiss_fft_cpx *freqdata); +/* + input timedata has nfft scalar points + output freqdata has nfft/2+1 complex points +*/ + +void PCL_EXPORTS kiss_fftri(kiss_fftr_cfg cfg,const kiss_fft_cpx *freqdata,kiss_fft_scalar *timedata); +/* + input freqdata has nfft/2+1 complex points + output timedata has nfft scalar points +*/ + +#define kiss_fftr_free free + +#ifdef __cplusplus +} +#endif +#endif diff --git a/pcl-1.7/pcl/common/file_io.h b/pcl-1.7/pcl/common/file_io.h new file mode 100644 index 0000000..fb1ee18 --- /dev/null +++ b/pcl-1.7/pcl/common/file_io.h @@ -0,0 +1,91 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_COMMON_FILE_IO_H_ +#define PCL_COMMON_FILE_IO_H_ + +#include +#ifndef _WIN32 + #include +#endif +#include +#include + +/** + * \file pcl/common/file_io.h + * Define some helper functions for reading and writing files + * \ingroup common + * \todo move this to pcl::console + */ + +/*@{*/ +namespace pcl +{ + /** \brief Find all *.pcd files in the directory and return them sorted + * \param directory the directory to be searched + * \param file_names the resulting (sorted) list of .pcd files + */ + inline void + getAllPcdFilesInDirectory (const std::string& directory, std::vector& file_names); + + /** \brief Remove the path from the given string and return only the filename (the remaining string after the + * last '/') + * \param input the input filename (with full path) + * \return the resulting filename, stripped of the path + */ + inline std::string + getFilenameWithoutPath (const std::string& input); + + /** \brief Remove the extension from the given string and return only the filename (everything before the last '.') + * \param input the input filename (with the file extension) + * \return the resulting filename, stripped of its extension + */ + inline std::string + getFilenameWithoutExtension (const std::string& input); + + /** \brief Get the file extension from the given string (the remaining string after the last '.') + * \param input the input filename + * \return \a input 's file extension + */ + inline std::string + getFileExtension (const std::string& input); +} // namespace end +/*@}*/ +#include + +#endif //#ifndef PCL_FILE_IO_H_ diff --git a/pcl-1.7/pcl/common/gaussian.h b/pcl-1.7/pcl/common/gaussian.h new file mode 100644 index 0000000..2c38937 --- /dev/null +++ b/pcl-1.7/pcl/common/gaussian.h @@ -0,0 +1,266 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_GAUSSIAN_KERNEL +#define PCL_GAUSSIAN_KERNEL + +#include +#include +#include +#include + +namespace pcl +{ + /** Class GaussianKernel assembles all the method for computing, + * convolving, smoothing, gradients computing an image using + * a gaussian kernel. The image is stored in point cloud elements + * intensity member or rgb or... + * \author Nizar Sallem + * \ingroup common + */ + class PCL_EXPORTS GaussianKernel + { + public: + + GaussianKernel () {} + + static const unsigned MAX_KERNEL_WIDTH = 71; + /** Computes the gaussian kernel and dervative assiociated to sigma. + * The kernel and derivative width are adjusted according. + * \param[in] sigma + * \param[out] kernel the computed gaussian kernel + * \param[in] kernel_width the desired kernel width upper bond + * \throws pcl::KernelWidthTooSmallException + */ + void + compute (float sigma, + Eigen::VectorXf &kernel, + unsigned kernel_width = MAX_KERNEL_WIDTH) const; + + /** Computes the gaussian kernel and dervative assiociated to sigma. + * The kernel and derivative width are adjusted according. + * \param[in] sigma + * \param[out] kernel the computed gaussian kernel + * \param[out] derivative the computed kernel derivative + * \param[in] kernel_width the desired kernel width upper bond + * \throws pcl::KernelWidthTooSmallException + */ + void + compute (float sigma, + Eigen::VectorXf &kernel, + Eigen::VectorXf &derivative, + unsigned kernel_width = MAX_KERNEL_WIDTH) const; + + /** Convolve a float image rows by a given kernel. + * \param[in] kernel convolution kernel + * \param[in] input the image to convolve + * \param[out] output the convolved image + * \note if output doesn't fit in input i.e. output.rows () < input.rows () or + * output.cols () < input.cols () then output is resized to input sizes. + */ + void + convolveRows (const pcl::PointCloud &input, + const Eigen::VectorXf &kernel, + pcl::PointCloud &output) const; + + /** Convolve a float image rows by a given kernel. + * \param[in] input the image to convolve + * \param[in] field_accessor a field accessor + * \param[in] kernel convolution kernel + * \param[out] output the convolved image + * \note if output doesn't fit in input i.e. output.rows () < input.rows () or + * output.cols () < input.cols () then output is resized to input sizes. + */ + template void + convolveRows (const pcl::PointCloud &input, + boost::function field_accessor, + const Eigen::VectorXf &kernel, + pcl::PointCloud &output) const; + + /** Convolve a float image columns by a given kernel. + * \param[in] input the image to convolve + * \param[in] kernel convolution kernel + * \param[out] output the convolved image + * \note if output doesn't fit in input i.e. output.rows () < input.rows () or + * output.cols () < input.cols () then output is resized to input sizes. + */ + void + convolveCols (const pcl::PointCloud &input, + const Eigen::VectorXf &kernel, + pcl::PointCloud &output) const; + + /** Convolve a float image columns by a given kernel. + * \param[in] input the image to convolve + * \param[in] field_accessor a field accessor + * \param[in] kernel convolution kernel + * \param[out] output the convolved image + * \note if output doesn't fit in input i.e. output.rows () < input.rows () or + * output.cols () < input.cols () then output is resized to input sizes. + */ + template void + convolveCols (const pcl::PointCloud &input, + boost::function field_accessor, + const Eigen::VectorXf &kernel, + pcl::PointCloud &output) const; + + /** Convolve a float image in the 2 directions + * \param[in] horiz_kernel kernel for convolving rows + * \param[in] vert_kernel kernel for convolving columns + * \param[in] input image to convolve + * \param[out] output the convolved image + * \note if output doesn't fit in input i.e. output.rows () < input.rows () or + * output.cols () < input.cols () then output is resized to input sizes. + */ + inline void + convolve (const pcl::PointCloud &input, + const Eigen::VectorXf &horiz_kernel, + const Eigen::VectorXf &vert_kernel, + pcl::PointCloud &output) const + { + std::cout << ">>> convolve cpp" << std::endl; + pcl::PointCloud tmp (input.width, input.height) ; + convolveRows (input, horiz_kernel, tmp); + convolveCols (tmp, vert_kernel, output); + std::cout << "<<< convolve cpp" << std::endl; + } + + /** Convolve a float image in the 2 directions + * \param[in] input image to convolve + * \param[in] field_accessor a field accessor + * \param[in] horiz_kernel kernel for convolving rows + * \param[in] vert_kernel kernel for convolving columns + * \param[out] output the convolved image + * \note if output doesn't fit in input i.e. output.rows () < input.rows () or + * output.cols () < input.cols () then output is resized to input sizes. + */ + template inline void + convolve (const pcl::PointCloud &input, + boost::function field_accessor, + const Eigen::VectorXf &horiz_kernel, + const Eigen::VectorXf &vert_kernel, + pcl::PointCloud &output) const + { + std::cout << ">>> convolve hpp" << std::endl; + pcl::PointCloud tmp (input.width, input.height); + convolveRows(input, field_accessor, horiz_kernel, tmp); + convolveCols(tmp, vert_kernel, output); + std::cout << "<<< convolve hpp" << std::endl; + } + + /** Computes float image gradients using a gaussian kernel and gaussian kernel + * derivative. + * \param[in] input image to compute gardients for + * \param[in] gaussian_kernel the gaussian kernel to be used + * \param[in] gaussian_kernel_derivative the associated derivative + * \param[out] grad_x gradient along X direction + * \param[out] grad_y gradient along Y direction + * \note if output doesn't fit in input i.e. output.rows () < input.rows () or + * output.cols () < input.cols () then output is resized to input sizes. + */ + inline void + computeGradients (const pcl::PointCloud &input, + const Eigen::VectorXf &gaussian_kernel, + const Eigen::VectorXf &gaussian_kernel_derivative, + pcl::PointCloud &grad_x, + pcl::PointCloud &grad_y) const + { + convolve (input, gaussian_kernel_derivative, gaussian_kernel, grad_x); + convolve (input, gaussian_kernel, gaussian_kernel_derivative, grad_y); + } + + /** Computes float image gradients using a gaussian kernel and gaussian kernel + * derivative. + * \param[in] input image to compute gardients for + * \param[in] field_accessor a field accessor + * \param[in] gaussian_kernel the gaussian kernel to be used + * \param[in] gaussian_kernel_derivative the associated derivative + * \param[out] grad_x gradient along X direction + * \param[out] grad_y gradient along Y direction + * \note if output doesn't fit in input i.e. output.rows () < input.rows () or + * output.cols () < input.cols () then output is resized to input sizes. + */ + template inline void + computeGradients (const pcl::PointCloud &input, + boost::function field_accessor, + const Eigen::VectorXf &gaussian_kernel, + const Eigen::VectorXf &gaussian_kernel_derivative, + pcl::PointCloud &grad_x, + pcl::PointCloud &grad_y) const + { + convolve (input, field_accessor, gaussian_kernel_derivative, gaussian_kernel, grad_x); + convolve (input, field_accessor, gaussian_kernel, gaussian_kernel_derivative, grad_y); + } + + /** Smooth image using a gaussian kernel. + * \param[in] input image + * \param[in] gaussian_kernel the gaussian kernel to be used + * \param[out] output the smoothed image + * \note if output doesn't fit in input i.e. output.rows () < input.rows () or + * output.cols () < input.cols () then output is resized to input sizes. + */ + inline void + smooth (const pcl::PointCloud &input, + const Eigen::VectorXf &gaussian_kernel, + pcl::PointCloud &output) const + { + convolve (input, gaussian_kernel, gaussian_kernel, output); + } + + /** Smooth image using a gaussian kernel. + * \param[in] input image + * \param[in] field_accessor a field accessor + * \param[in] gaussian_kernel the gaussian kernel to be used + * \param[out] output the smoothed image + * \note if output doesn't fit in input i.e. output.rows () < input.rows () or + * output.cols () < input.cols () then output is resized to input sizes. + */ + template inline void + smooth (const pcl::PointCloud &input, + boost::function field_accessor, + const Eigen::VectorXf &gaussian_kernel, + pcl::PointCloud &output) const + { + convolve (input, field_accessor, gaussian_kernel, gaussian_kernel, output); + } + }; +} + +#include + +#endif // PCL_GAUSSIAN_KERNEL diff --git a/pcl-1.7/pcl/common/generate.h b/pcl-1.7/pcl/common/generate.h new file mode 100644 index 0000000..0929125 --- /dev/null +++ b/pcl-1.7/pcl/common/generate.h @@ -0,0 +1,189 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_COMMON_GENERATE_H_ +#define PCL_COMMON_GENERATE_H_ + +#include +#include +#include + +namespace pcl +{ + + namespace common + { + /** \brief CloudGenerator class generates a point cloud using some randoom number generator. + * Generators can be found in \file common/random.h and easily extensible. + * + * \ingroup common + * \author Nizar Sallem + */ + template + class CloudGenerator + { + public: + typedef typename GeneratorT::Parameters GeneratorParameters; + + /// Default constructor + CloudGenerator (); + + /** Consttructor with single generator to ensure all X, Y and Z values are within same range + * \param params paramteres for X, Y and Z values generation. Uniqueness is ensured through + * seed incrementation + */ + CloudGenerator (const GeneratorParameters& params); + + /** Constructor with independant generators per axis + * \param x_params parameters for x values generation + * \param y_params parameters for y values generation + * \param z_params parameters for z values generation + */ + CloudGenerator (const GeneratorParameters& x_params, + const GeneratorParameters& y_params, + const GeneratorParameters& z_params); + + /** Set parameters for x, y and z values. Uniqueness is ensured through seed incrementation. + * \param params parameteres for X, Y and Z values generation. + */ + void + setParameters (const GeneratorParameters& params); + + /** Set parameters for x values generation + * \param x_params paramters for x values generation + */ + void + setParametersForX (const GeneratorParameters& x_params); + + /** Set parameters for y values generation + * \param y_params paramters for y values generation + */ + void + setParametersForY (const GeneratorParameters& y_params); + + /** Set parameters for z values generation + * \param z_params paramters for z values generation + */ + void + setParametersForZ (const GeneratorParameters& z_params); + + /// \return x values generation parameters + const GeneratorParameters& + getParametersForX () const; + + /// \return y values generation parameters + const GeneratorParameters& + getParametersForY () const; + + /// \return z values generation parameters + const GeneratorParameters& + getParametersForZ () const; + + /// \return a single random generated point + PointT + get (); + + /** Generates a cloud with X Y Z picked within given ranges. This function assumes that + * cloud is properly defined else it raises errors and does nothing. + * \param[out] cloud cloud to generate coordinates for + * \return 0 if generation went well else -1. + */ + int + fill (pcl::PointCloud& cloud); + + /** Generates a cloud of specified dimensions with X Y Z picked within given ranges. + * \param[in] width width of generated cloud + * \param[in] height height of generated cloud + * \param[out] cloud output cloud + * \return 0 if generation went well else -1. + */ + int + fill (int width, int height, pcl::PointCloud& cloud); + + private: + GeneratorT x_generator_, y_generator_, z_generator_; + }; + + template + class CloudGenerator + { + public: + typedef typename GeneratorT::Parameters GeneratorParameters; + + CloudGenerator (); + + CloudGenerator (const GeneratorParameters& params); + + CloudGenerator (const GeneratorParameters& x_params, + const GeneratorParameters& y_params); + + void + setParameters (const GeneratorParameters& params); + + void + setParametersForX (const GeneratorParameters& x_params); + + void + setParametersForY (const GeneratorParameters& y_params); + + const GeneratorParameters& + getParametersForX () const; + + const GeneratorParameters& + getParametersForY () const; + + pcl::PointXY + get (); + + int + fill (pcl::PointCloud& cloud); + + int + fill (int width, int height, pcl::PointCloud& cloud); + + private: + GeneratorT x_generator_; + GeneratorT y_generator_; + }; + } +} + +#include + +#endif diff --git a/pcl-1.7/pcl/common/geometry.h b/pcl-1.7/pcl/common/geometry.h new file mode 100644 index 0000000..f40632e --- /dev/null +++ b/pcl-1.7/pcl/common/geometry.h @@ -0,0 +1,108 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_GEOMETRY_H_ +#define PCL_GEOMETRY_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include + +/** + * \file common/geometry.h + * Defines some geometrical functions and utility functions + * \ingroup common + */ + +/*@{*/ +namespace pcl +{ + namespace geometry + { + /** @return the euclidean distance between 2 points */ + template inline float + distance (const PointT& p1, const PointT& p2) + { + Eigen::Vector3f diff = p1 -p2; + return (diff.norm ()); + } + + /** @return the squared euclidean distance between 2 points */ + template inline float + squaredDistance (const PointT& p1, const PointT& p2) + { + Eigen::Vector3f diff = p1 -p2; + return (diff.squaredNorm ()); + } + + /** @return the point projection on a plane defined by its origin and normal vector + * \param[in] point Point to be projected + * \param[in] plane_origin The plane origin + * \param[in] plane_normal The plane normal + * \param[out] projected The returned projected point + */ + template inline void + project (const PointT& point, const PointT &plane_origin, + const NormalT& plane_normal, PointT& projected) + { + Eigen::Vector3f po = point - plane_origin; + const Eigen::Vector3f normal = plane_normal.getVector3fMapConst (); + float lambda = normal.dot(po); + projected.getVector3fMap () = point.getVector3fMapConst () - (lambda * normal); + } + + /** @return the point projection on a plane defined by its origin and normal vector + * \param[in] point Point to be projected + * \param[in] plane_origin The plane origin + * \param[in] plane_normal The plane normal + * \param[out] projected The returned projected point + */ + inline void + project (const Eigen::Vector3f& point, const Eigen::Vector3f &plane_origin, + const Eigen::Vector3f& plane_normal, Eigen::Vector3f& projected) + { + Eigen::Vector3f po = point - plane_origin; + float lambda = plane_normal.dot(po); + projected = point - (lambda * plane_normal); + } + } +} + +/*@}*/ +#endif //#ifndef PCL_GEOMETRY_H_ diff --git a/pcl-1.7/pcl/common/impl/accumulators.hpp b/pcl-1.7/pcl/common/impl/accumulators.hpp new file mode 100644 index 0000000..7c0b887 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/accumulators.hpp @@ -0,0 +1,296 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2014-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_COMMON_IMPL_DETAIL_ACCUMULATORS_HPP +#define PCL_COMMON_IMPL_DETAIL_ACCUMULATORS_HPP + +#include + +#include +#include +#include +#include + +#include + +namespace pcl +{ + + namespace detail + { + + /* Below are several helper accumulator structures that are used by the + * `CentroidPoint` class. Each of them is capable of accumulating + * information from a particular field(s) of a point. The points are + * inserted via `add()` and extracted via `get()` functions. Note that the + * accumulators are not templated on point type, so in principle it is + * possible to insert and extract points of different types. It is the + * responsibility of the user to make sure that points have corresponding + * fields. */ + + struct AccumulatorXYZ + { + + // Requires that point type has x, y, and z fields + typedef pcl::traits::has_xyz IsCompatible; + + // Storage + Eigen::Vector3f xyz; + + AccumulatorXYZ () : xyz (Eigen::Vector3f::Zero ()) { } + + template void + add (const PointT& t) { xyz += t.getVector3fMap (); } + + template void + get (PointT& t, size_t n) const { t.getVector3fMap () = xyz / n; } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + }; + + struct AccumulatorNormal + { + + // Requires that point type has normal_x, normal_y, and normal_z fields + typedef pcl::traits::has_normal IsCompatible; + + // Storage + Eigen::Vector4f normal; + + AccumulatorNormal () : normal (Eigen::Vector4f::Zero ()) { } + + // Requires that the normal of the given point is normalized, otherwise it + // does not make sense to sum it up with the accumulated value. + template void + add (const PointT& t) { normal += t.getNormalVector4fMap (); } + + template void + get (PointT& t, size_t) const + { + t.getNormalVector4fMap () = normal; + t.getNormalVector4fMap ().normalize (); + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + }; + + struct AccumulatorCurvature + { + + // Requires that point type has curvature field + typedef pcl::traits::has_curvature IsCompatible; + + // Storage + float curvature; + + AccumulatorCurvature () : curvature (0) { } + + template void + add (const PointT& t) { curvature += t.curvature; } + + template void + get (PointT& t, size_t n) const { t.curvature = curvature / n; } + + }; + + struct AccumulatorRGBA + { + + // Requires that point type has rgb or rgba field + typedef pcl::traits::has_color IsCompatible; + + // Storage + float r, g, b, a; + + AccumulatorRGBA () : r (0), g (0), b (0), a (0) { } + + template void + add (const PointT& t) + { + r += static_cast (t.r); + g += static_cast (t.g); + b += static_cast (t.b); + a += static_cast (t.a); + } + + template void + get (PointT& t, size_t n) const + { + t.rgba = static_cast (a / n) << 24 | + static_cast (r / n) << 16 | + static_cast (g / n) << 8 | + static_cast (b / n); + } + + }; + + struct AccumulatorIntensity + { + + // Requires that point type has intensity field + typedef pcl::traits::has_intensity IsCompatible; + + // Storage + float intensity; + + AccumulatorIntensity () : intensity (0) { } + + template void + add (const PointT& t) { intensity += t.intensity; } + + template void + get (PointT& t, size_t n) const { t.intensity = intensity / n; } + + }; + + struct AccumulatorLabel + { + + // Requires that point type has label field + typedef pcl::traits::has_label IsCompatible; + + // Storage + // A better performance may be achieved with a heap structure + std::map labels; + + AccumulatorLabel () { } + + template void + add (const PointT& t) + { + std::map::iterator itr = labels.find (t.label); + if (itr == labels.end ()) + labels.insert (std::make_pair (t.label, 1)); + else + ++itr->second; + } + + template void + get (PointT& t, size_t) const + { + size_t max = 0; + std::map::const_iterator itr; + for (itr = labels.begin (); itr != labels.end (); ++itr) + if (itr->second > max) + { + max = itr->second; + t.label = itr->first; + } + } + + }; + + /* This is a meta-function that may be used to create a Fusion vector of + * those accumulator types that are compatible with given point type(s). */ + + template + struct Accumulators + { + + // Check if a given accumulator type is compatible with a given point type + template + struct IsCompatible : boost::mpl::apply { }; + + // A Fusion vector with accumulator types that are compatible with given + // point types + typedef + typename boost::fusion::result_of::as_vector< + typename boost::mpl::filter_view< + boost::mpl::vector< + AccumulatorXYZ + , AccumulatorNormal + , AccumulatorCurvature + , AccumulatorRGBA + , AccumulatorIntensity + , AccumulatorLabel + > + , boost::mpl::and_< + IsCompatible + , IsCompatible + > + > + >::type + type; + }; + + /* Fusion function object to invoke point addition on every accumulator in + * a fusion sequence. */ + + template + struct AddPoint + { + + const PointT& p; + + AddPoint (const PointT& point) : p (point) { } + + template void + operator () (AccumulatorT& accumulator) const + { + accumulator.add (p); + } + + }; + + /* Fusion function object to invoke get point on every accumulator in a + * fusion sequence. */ + + template + struct GetPoint + { + + PointT& p; + size_t n; + + GetPoint (PointT& point, size_t num) : p (point), n (num) { } + + template void + operator () (AccumulatorT& accumulator) const + { + accumulator.get (p, n); + } + + }; + + } + +} + +#endif /* PCL_COMMON_IMPL_DETAIL_ACCUMULATORS_HPP */ + diff --git a/pcl-1.7/pcl/common/impl/angles.hpp b/pcl-1.7/pcl/common/impl/angles.hpp new file mode 100644 index 0000000..7235535 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/angles.hpp @@ -0,0 +1,86 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR a PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_COMMON_ANGLES_IMPL_HPP_ +#define PCL_COMMON_ANGLES_IMPL_HPP_ + +#include +#include + +namespace pcl +{ + inline float + normAngle (float alpha) + { + return (alpha >= 0 ? + fmodf (alpha + static_cast(M_PI), + 2.0f * static_cast(M_PI)) + - static_cast(M_PI) + : + -(fmodf (static_cast(M_PI) - alpha, + 2.0f * static_cast(M_PI)) + - static_cast(M_PI))); + } + + inline float + rad2deg (float alpha) + { + return (alpha * 57.29578f); + } + + inline float + deg2rad (float alpha) + { + return (alpha * 0.017453293f); + } + + inline double + rad2deg (double alpha) + { + return (alpha * 57.29578); + } + + inline double + deg2rad (double alpha) + { + return (alpha * 0.017453293); + } +} + +#endif // PCL_COMMON_ANGLES_IMPL_HPP_ + diff --git a/pcl-1.7/pcl/common/impl/bivariate_polynomial.hpp b/pcl-1.7/pcl/common/impl/bivariate_polynomial.hpp new file mode 100644 index 0000000..5a979d8 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/bivariate_polynomial.hpp @@ -0,0 +1,303 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef BIVARIATE_POLYNOMIAL_HPP +#define BIVARIATE_POLYNOMIAL_HPP + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::BivariatePolynomialT::BivariatePolynomialT (int new_degree) : + degree(0), parameters(NULL), gradient_x(NULL), gradient_y(NULL) +{ + setDegree(new_degree); +} + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::BivariatePolynomialT::BivariatePolynomialT (const BivariatePolynomialT& other) : + degree(0), parameters(NULL), gradient_x(NULL), gradient_y(NULL) +{ + deepCopy (other); +} + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::BivariatePolynomialT::~BivariatePolynomialT () +{ + memoryCleanUp (); +} + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BivariatePolynomialT::setDegree (int newDegree) +{ + if (newDegree <= 0) + { + degree = -1; + memoryCleanUp(); + return; + } + int oldDegree = degree; + degree = newDegree; + if (oldDegree != degree) + { + delete[] parameters; + parameters = new real[getNoOfParameters ()]; + } + delete gradient_x; gradient_x = NULL; + delete gradient_y; gradient_y = NULL; +} + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BivariatePolynomialT::memoryCleanUp () +{ + delete[] parameters; parameters = NULL; + delete gradient_x; gradient_x = NULL; + delete gradient_y; gradient_y = NULL; +} + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BivariatePolynomialT::deepCopy (const pcl::BivariatePolynomialT& other) +{ + if (this == &other) return; + if (degree != other.degree) + { + memoryCleanUp (); + degree = other.degree; + parameters = new real[getNoOfParameters ()]; + } + if (other.gradient_x == NULL) + { + delete gradient_x; gradient_x=NULL; + delete gradient_y; gradient_y=NULL; + } + else if (gradient_x==NULL) + { + gradient_x = new pcl::BivariatePolynomialT (); + gradient_y = new pcl::BivariatePolynomialT (); + } + real* tmpParameters1 = parameters; + const real* tmpParameters2 = other.parameters; + unsigned int noOfParameters = getNoOfParameters (); + for (unsigned int i=0; ideepCopy (*other.gradient_x); + gradient_y->deepCopy (*other.gradient_y); + } +} + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BivariatePolynomialT::calculateGradient (bool forceRecalc) +{ + if (gradient_x!=NULL && !forceRecalc) + + if (gradient_x == NULL) + gradient_x = new pcl::BivariatePolynomialT (degree-1); + if (gradient_y == NULL) + gradient_y = new pcl::BivariatePolynomialT (degree-1); + + unsigned int parameterPosDx=0, parameterPosDy=0; + for (int xDegree=degree; xDegree>=0; xDegree--) + { + for (int yDegree=degree-xDegree; yDegree>=0; yDegree--) + { + if (xDegree > 0) + { + gradient_x->parameters[parameterPosDx] = xDegree * parameters[parameterPosDx]; + parameterPosDx++; + } + if (yDegree > 0) + { + gradient_y->parameters[parameterPosDy] = yDegree * parameters[ ( (degree+2-xDegree)* (degree+1-xDegree))/2 - + yDegree - 1]; + parameterPosDy++; + } + } + } +} + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template real +pcl::BivariatePolynomialT::getValue (real x, real y) const +{ + unsigned int parametersSize = getNoOfParameters (); + real* tmpParameter = ¶meters[parametersSize-1]; + real tmpX=1.0, tmpY, ret=0; + for (int xDegree=0; xDegree<=degree; xDegree++) + { + tmpY = 1.0; + for (int yDegree=0; yDegree<=degree-xDegree; yDegree++) + { + ret += (*tmpParameter)*tmpX*tmpY; + tmpY *= y; + tmpParameter--; + } + tmpX *= x; + } + return ret; +} + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BivariatePolynomialT::getValueOfGradient (real x, real y, real& gradX, real& gradY) +{ + calculateGradient (); + gradX = gradient_x->getValue (x, y); + gradY = gradient_y->getValue (x, y); +} + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BivariatePolynomialT::findCriticalPoints (std::vector& x_values, std::vector& y_values, + std::vector& types) const +{ + x_values.clear (); + y_values.clear (); + types.clear (); + + if (degree == 2) + { + real x = (real(2)*parameters[2]*parameters[3] - parameters[1]*parameters[4]) / + (parameters[1]*parameters[1] - real(4)*parameters[0]*parameters[3]), + y = (real(-2)*parameters[0]*x - parameters[2]) / parameters[1]; + + if (!pcl_isfinite(x) || !pcl_isfinite(y)) + return; + + int type = 2; + real det_H = real(4)*parameters[0]*parameters[3] - parameters[1]*parameters[1]; + //std::cout << "det(H) = "< real(0)) // Check Hessian determinant + { + if (parameters[0]+parameters[3] < real(0)) // Check Hessian trace + type = 0; + else + type = 1; + } + x_values.push_back(x); + y_values.push_back(y); + types.push_back(type); + } + else + { + std::cerr << __PRETTY_FUNCTION__ << " is not implemented for polynomials of degree "< std::ostream& +pcl::operator<< (std::ostream& os, const pcl::BivariatePolynomialT& p) +{ + real* tmpParameter = p.parameters; + bool first = true; + real currentParameter; + for (int xDegree=p.degree; xDegree>=0; xDegree--) + { + for (int yDegree=p.degree-xDegree; yDegree>=0; yDegree--) + { + currentParameter = *tmpParameter; + if (!first) + { + os << (currentParameter<0.0?" - ":" + "); + currentParameter = fabs (currentParameter); + } + os << currentParameter; + if (xDegree>0) + { + os << "x"; + if (xDegree>1) + os<<"^"<0) + { + os << "y"; + if (yDegree>1) + os<<"^"< void +pcl::BivariatePolynomialT::writeBinary (std::ostream& os) const +{ + os.write (reinterpret_cast (°ree), sizeof (int)); + unsigned int paramCnt = getNoOfParametersFromDegree (this->degree); + os.write (reinterpret_cast (this->parameters), paramCnt * sizeof (real)); +} + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BivariatePolynomialT::writeBinary (const char* filename) const +{ + std::ofstream fout (filename); + writeBinary (fout); +} + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BivariatePolynomialT::readBinary (std::istream& os) +{ + memoryCleanUp (); + os.read (reinterpret_cast (&this->degree), sizeof (int)); + unsigned int paramCnt = getNoOfParametersFromDegree (this->degree); + parameters = new real[paramCnt]; + os.read (reinterpret_cast (&(*this->parameters)), paramCnt * sizeof (real)); +} + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BivariatePolynomialT::readBinary (const char* filename) +{ + std::ifstream fin (filename); + readBinary (fin); +} + +#endif + diff --git a/pcl-1.7/pcl/common/impl/centroid.hpp b/pcl-1.7/pcl/common/impl/centroid.hpp new file mode 100644 index 0000000..2c13eb1 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/centroid.hpp @@ -0,0 +1,902 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-present, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_COMMON_IMPL_CENTROID_H_ +#define PCL_COMMON_IMPL_CENTROID_H_ + +#include +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::compute3DCentroid (ConstCloudIterator &cloud_iterator, + Eigen::Matrix ¢roid) +{ + // Initialize to 0 + centroid.setZero (); + + unsigned cp = 0; + + // For each point in the cloud + // If the data is dense, we don't need to check for NaN + while (cloud_iterator.isValid ()) + { + // Check if the point is invalid + if (!pcl_isfinite (cloud_iterator->x) || + !pcl_isfinite (cloud_iterator->y) || + !pcl_isfinite (cloud_iterator->z)) + continue; + centroid[0] += cloud_iterator->x; + centroid[1] += cloud_iterator->y; + centroid[2] += cloud_iterator->z; + ++cp; + ++cloud_iterator; + } + centroid /= static_cast (cp); + centroid[3] = 1; + return (cp); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::compute3DCentroid (const pcl::PointCloud &cloud, + Eigen::Matrix ¢roid) +{ + if (cloud.empty ()) + return (0); + + // Initialize to 0 + centroid.setZero (); + // For each point in the cloud + // If the data is dense, we don't need to check for NaN + if (cloud.is_dense) + { + for (size_t i = 0; i < cloud.size (); ++i) + { + centroid[0] += cloud[i].x; + centroid[1] += cloud[i].y; + centroid[2] += cloud[i].z; + } + centroid /= static_cast (cloud.size ()); + centroid[3] = 1; + + return (static_cast (cloud.size ())); + } + // NaN or Inf values could exist => check for them + else + { + unsigned cp = 0; + for (size_t i = 0; i < cloud.size (); ++i) + { + // Check if the point is invalid + if (!isFinite (cloud [i])) + continue; + + centroid[0] += cloud[i].x; + centroid[1] += cloud[i].y; + centroid[2] += cloud[i].z; + ++cp; + } + centroid /= static_cast (cp); + centroid[3] = 1; + + return (cp); + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::compute3DCentroid (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::Matrix ¢roid) +{ + if (indices.empty ()) + return (0); + + // Initialize to 0 + centroid.setZero (); + // If the data is dense, we don't need to check for NaN + if (cloud.is_dense) + { + for (size_t i = 0; i < indices.size (); ++i) + { + centroid[0] += cloud[indices[i]].x; + centroid[1] += cloud[indices[i]].y; + centroid[2] += cloud[indices[i]].z; + } + centroid /= static_cast (indices.size ()); + centroid[3] = 1; + return (static_cast (indices.size ())); + } + // NaN or Inf values could exist => check for them + else + { + unsigned cp = 0; + for (size_t i = 0; i < indices.size (); ++i) + { + // Check if the point is invalid + if (!isFinite (cloud [indices[i]])) + continue; + + centroid[0] += cloud[indices[i]].x; + centroid[1] += cloud[indices[i]].y; + centroid[2] += cloud[indices[i]].z; + ++cp; + } + centroid /= static_cast (cp); + centroid[3] = 1; + return (cp); + } +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::compute3DCentroid (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::Matrix ¢roid) +{ + return (pcl::compute3DCentroid (cloud, indices.indices, centroid)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned +pcl::computeCovarianceMatrix (const pcl::PointCloud &cloud, + const Eigen::Matrix ¢roid, + Eigen::Matrix &covariance_matrix) +{ + if (cloud.empty ()) + return (0); + + // Initialize to 0 + covariance_matrix.setZero (); + + unsigned point_count; + // If the data is dense, we don't need to check for NaN + if (cloud.is_dense) + { + point_count = static_cast (cloud.size ()); + // For each point in the cloud + for (size_t i = 0; i < point_count; ++i) + { + Eigen::Matrix pt; + pt[0] = cloud[i].x - centroid[0]; + pt[1] = cloud[i].y - centroid[1]; + pt[2] = cloud[i].z - centroid[2]; + + covariance_matrix (1, 1) += pt.y () * pt.y (); + covariance_matrix (1, 2) += pt.y () * pt.z (); + + covariance_matrix (2, 2) += pt.z () * pt.z (); + + pt *= pt.x (); + covariance_matrix (0, 0) += pt.x (); + covariance_matrix (0, 1) += pt.y (); + covariance_matrix (0, 2) += pt.z (); + } + } + // NaN or Inf values could exist => check for them + else + { + point_count = 0; + // For each point in the cloud + for (size_t i = 0; i < cloud.size (); ++i) + { + // Check if the point is invalid + if (!isFinite (cloud [i])) + continue; + + Eigen::Matrix pt; + pt[0] = cloud[i].x - centroid[0]; + pt[1] = cloud[i].y - centroid[1]; + pt[2] = cloud[i].z - centroid[2]; + + covariance_matrix (1, 1) += pt.y () * pt.y (); + covariance_matrix (1, 2) += pt.y () * pt.z (); + + covariance_matrix (2, 2) += pt.z () * pt.z (); + + pt *= pt.x (); + covariance_matrix (0, 0) += pt.x (); + covariance_matrix (0, 1) += pt.y (); + covariance_matrix (0, 2) += pt.z (); + ++point_count; + } + } + covariance_matrix (1, 0) = covariance_matrix (0, 1); + covariance_matrix (2, 0) = covariance_matrix (0, 2); + covariance_matrix (2, 1) = covariance_matrix (1, 2); + + return (point_count); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud &cloud, + const Eigen::Matrix ¢roid, + Eigen::Matrix &covariance_matrix) +{ + unsigned point_count = pcl::computeCovarianceMatrix (cloud, centroid, covariance_matrix); + if (point_count != 0) + covariance_matrix /= static_cast (point_count); + return (point_count); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::computeCovarianceMatrix (const pcl::PointCloud &cloud, + const std::vector &indices, + const Eigen::Matrix ¢roid, + Eigen::Matrix &covariance_matrix) +{ + if (indices.empty ()) + return (0); + + // Initialize to 0 + covariance_matrix.setZero (); + + size_t point_count; + // If the data is dense, we don't need to check for NaN + if (cloud.is_dense) + { + point_count = indices.size (); + // For each point in the cloud + for (size_t i = 0; i < point_count; ++i) + { + Eigen::Matrix pt; + pt[0] = cloud[indices[i]].x - centroid[0]; + pt[1] = cloud[indices[i]].y - centroid[1]; + pt[2] = cloud[indices[i]].z - centroid[2]; + + covariance_matrix (1, 1) += pt.y () * pt.y (); + covariance_matrix (1, 2) += pt.y () * pt.z (); + + covariance_matrix (2, 2) += pt.z () * pt.z (); + + pt *= pt.x (); + covariance_matrix (0, 0) += pt.x (); + covariance_matrix (0, 1) += pt.y (); + covariance_matrix (0, 2) += pt.z (); + } + } + // NaN or Inf values could exist => check for them + else + { + point_count = 0; + // For each point in the cloud + for (size_t i = 0; i < indices.size (); ++i) + { + // Check if the point is invalid + if (!isFinite (cloud[indices[i]])) + continue; + + Eigen::Matrix pt; + pt[0] = cloud[indices[i]].x - centroid[0]; + pt[1] = cloud[indices[i]].y - centroid[1]; + pt[2] = cloud[indices[i]].z - centroid[2]; + + covariance_matrix (1, 1) += pt.y () * pt.y (); + covariance_matrix (1, 2) += pt.y () * pt.z (); + + covariance_matrix (2, 2) += pt.z () * pt.z (); + + pt *= pt.x (); + covariance_matrix (0, 0) += pt.x (); + covariance_matrix (0, 1) += pt.y (); + covariance_matrix (0, 2) += pt.z (); + ++point_count; + } + } + covariance_matrix (1, 0) = covariance_matrix (0, 1); + covariance_matrix (2, 0) = covariance_matrix (0, 2); + covariance_matrix (2, 1) = covariance_matrix (1, 2); + return (static_cast (point_count)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::computeCovarianceMatrix (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + const Eigen::Matrix ¢roid, + Eigen::Matrix &covariance_matrix) +{ + return (pcl::computeCovarianceMatrix (cloud, indices.indices, centroid, covariance_matrix)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud &cloud, + const std::vector &indices, + const Eigen::Matrix ¢roid, + Eigen::Matrix &covariance_matrix) +{ + unsigned point_count = pcl::computeCovarianceMatrix (cloud, indices, centroid, covariance_matrix); + if (point_count != 0) + covariance_matrix /= static_cast (point_count); + + return (point_count); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + const Eigen::Matrix ¢roid, + Eigen::Matrix &covariance_matrix) +{ + unsigned int point_count = pcl::computeCovarianceMatrix (cloud, indices.indices, centroid, covariance_matrix); + if (point_count != 0) + covariance_matrix /= static_cast (point_count); + + return point_count; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::computeCovarianceMatrix (const pcl::PointCloud &cloud, + Eigen::Matrix &covariance_matrix) +{ + // create the buffer on the stack which is much faster than using cloud[indices[i]] and centroid as a buffer + Eigen::Matrix accu = Eigen::Matrix::Zero (); + + unsigned int point_count; + if (cloud.is_dense) + { + point_count = static_cast (cloud.size ()); + // For each point in the cloud + for (size_t i = 0; i < point_count; ++i) + { + accu [0] += cloud[i].x * cloud[i].x; + accu [1] += cloud[i].x * cloud[i].y; + accu [2] += cloud[i].x * cloud[i].z; + accu [3] += cloud[i].y * cloud[i].y; + accu [4] += cloud[i].y * cloud[i].z; + accu [5] += cloud[i].z * cloud[i].z; + } + } + else + { + point_count = 0; + for (size_t i = 0; i < cloud.size (); ++i) + { + if (!isFinite (cloud[i])) + continue; + + accu [0] += cloud[i].x * cloud[i].x; + accu [1] += cloud[i].x * cloud[i].y; + accu [2] += cloud[i].x * cloud[i].z; + accu [3] += cloud[i].y * cloud[i].y; + accu [4] += cloud[i].y * cloud[i].z; + accu [5] += cloud[i].z * cloud[i].z; + ++point_count; + } + } + + if (point_count != 0) + { + accu /= static_cast (point_count); + covariance_matrix.coeffRef (0) = accu [0]; + covariance_matrix.coeffRef (1) = covariance_matrix.coeffRef (3) = accu [1]; + covariance_matrix.coeffRef (2) = covariance_matrix.coeffRef (6) = accu [2]; + covariance_matrix.coeffRef (4) = accu [3]; + covariance_matrix.coeffRef (5) = covariance_matrix.coeffRef (7) = accu [4]; + covariance_matrix.coeffRef (8) = accu [5]; + } + return (point_count); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::computeCovarianceMatrix (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::Matrix &covariance_matrix) +{ + // create the buffer on the stack which is much faster than using cloud[indices[i]] and centroid as a buffer + Eigen::Matrix accu = Eigen::Matrix::Zero (); + + unsigned int point_count; + if (cloud.is_dense) + { + point_count = static_cast (indices.size ()); + for (std::vector::const_iterator iIt = indices.begin (); iIt != indices.end (); ++iIt) + { + //const PointT& point = cloud[*iIt]; + accu [0] += cloud[*iIt].x * cloud[*iIt].x; + accu [1] += cloud[*iIt].x * cloud[*iIt].y; + accu [2] += cloud[*iIt].x * cloud[*iIt].z; + accu [3] += cloud[*iIt].y * cloud[*iIt].y; + accu [4] += cloud[*iIt].y * cloud[*iIt].z; + accu [5] += cloud[*iIt].z * cloud[*iIt].z; + } + } + else + { + point_count = 0; + for (std::vector::const_iterator iIt = indices.begin (); iIt != indices.end (); ++iIt) + { + if (!isFinite (cloud[*iIt])) + continue; + + ++point_count; + accu [0] += cloud[*iIt].x * cloud[*iIt].x; + accu [1] += cloud[*iIt].x * cloud[*iIt].y; + accu [2] += cloud[*iIt].x * cloud[*iIt].z; + accu [3] += cloud[*iIt].y * cloud[*iIt].y; + accu [4] += cloud[*iIt].y * cloud[*iIt].z; + accu [5] += cloud[*iIt].z * cloud[*iIt].z; + } + } + if (point_count != 0) + { + accu /= static_cast (point_count); + covariance_matrix.coeffRef (0) = accu [0]; + covariance_matrix.coeffRef (1) = covariance_matrix.coeffRef (3) = accu [1]; + covariance_matrix.coeffRef (2) = covariance_matrix.coeffRef (6) = accu [2]; + covariance_matrix.coeffRef (4) = accu [3]; + covariance_matrix.coeffRef (5) = covariance_matrix.coeffRef (7) = accu [4]; + covariance_matrix.coeffRef (8) = accu [5]; + } + return (point_count); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::computeCovarianceMatrix (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::Matrix &covariance_matrix) +{ + return (computeCovarianceMatrix (cloud, indices.indices, covariance_matrix)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, + Eigen::Matrix &covariance_matrix, + Eigen::Matrix ¢roid) +{ + // create the buffer on the stack which is much faster than using cloud[indices[i]] and centroid as a buffer + Eigen::Matrix accu = Eigen::Matrix::Zero (); + size_t point_count; + if (cloud.is_dense) + { + point_count = cloud.size (); + // For each point in the cloud + for (size_t i = 0; i < point_count; ++i) + { + accu [0] += cloud[i].x * cloud[i].x; + accu [1] += cloud[i].x * cloud[i].y; + accu [2] += cloud[i].x * cloud[i].z; + accu [3] += cloud[i].y * cloud[i].y; // 4 + accu [4] += cloud[i].y * cloud[i].z; // 5 + accu [5] += cloud[i].z * cloud[i].z; // 8 + accu [6] += cloud[i].x; + accu [7] += cloud[i].y; + accu [8] += cloud[i].z; + } + } + else + { + point_count = 0; + for (size_t i = 0; i < cloud.size (); ++i) + { + if (!isFinite (cloud[i])) + continue; + + accu [0] += cloud[i].x * cloud[i].x; + accu [1] += cloud[i].x * cloud[i].y; + accu [2] += cloud[i].x * cloud[i].z; + accu [3] += cloud[i].y * cloud[i].y; + accu [4] += cloud[i].y * cloud[i].z; + accu [5] += cloud[i].z * cloud[i].z; + accu [6] += cloud[i].x; + accu [7] += cloud[i].y; + accu [8] += cloud[i].z; + ++point_count; + } + } + accu /= static_cast (point_count); + if (point_count != 0) + { + //centroid.head<3> () = accu.tail<3> (); -- does not compile with Clang 3.0 + centroid[0] = accu[6]; centroid[1] = accu[7]; centroid[2] = accu[8]; + centroid[3] = 1; + covariance_matrix.coeffRef (0) = accu [0] - accu [6] * accu [6]; + covariance_matrix.coeffRef (1) = accu [1] - accu [6] * accu [7]; + covariance_matrix.coeffRef (2) = accu [2] - accu [6] * accu [8]; + covariance_matrix.coeffRef (4) = accu [3] - accu [7] * accu [7]; + covariance_matrix.coeffRef (5) = accu [4] - accu [7] * accu [8]; + covariance_matrix.coeffRef (8) = accu [5] - accu [8] * accu [8]; + covariance_matrix.coeffRef (3) = covariance_matrix.coeff (1); + covariance_matrix.coeffRef (6) = covariance_matrix.coeff (2); + covariance_matrix.coeffRef (7) = covariance_matrix.coeff (5); + } + return (static_cast (point_count)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::Matrix &covariance_matrix, + Eigen::Matrix ¢roid) +{ + // create the buffer on the stack which is much faster than using cloud[indices[i]] and centroid as a buffer + Eigen::Matrix accu = Eigen::Matrix::Zero (); + size_t point_count; + if (cloud.is_dense) + { + point_count = indices.size (); + for (std::vector::const_iterator iIt = indices.begin (); iIt != indices.end (); ++iIt) + { + //const PointT& point = cloud[*iIt]; + accu [0] += cloud[*iIt].x * cloud[*iIt].x; + accu [1] += cloud[*iIt].x * cloud[*iIt].y; + accu [2] += cloud[*iIt].x * cloud[*iIt].z; + accu [3] += cloud[*iIt].y * cloud[*iIt].y; + accu [4] += cloud[*iIt].y * cloud[*iIt].z; + accu [5] += cloud[*iIt].z * cloud[*iIt].z; + accu [6] += cloud[*iIt].x; + accu [7] += cloud[*iIt].y; + accu [8] += cloud[*iIt].z; + } + } + else + { + point_count = 0; + for (std::vector::const_iterator iIt = indices.begin (); iIt != indices.end (); ++iIt) + { + if (!isFinite (cloud[*iIt])) + continue; + + ++point_count; + accu [0] += cloud[*iIt].x * cloud[*iIt].x; + accu [1] += cloud[*iIt].x * cloud[*iIt].y; + accu [2] += cloud[*iIt].x * cloud[*iIt].z; + accu [3] += cloud[*iIt].y * cloud[*iIt].y; // 4 + accu [4] += cloud[*iIt].y * cloud[*iIt].z; // 5 + accu [5] += cloud[*iIt].z * cloud[*iIt].z; // 8 + accu [6] += cloud[*iIt].x; + accu [7] += cloud[*iIt].y; + accu [8] += cloud[*iIt].z; + } + } + + accu /= static_cast (point_count); + //Eigen::Vector3f vec = accu.tail<3> (); + //centroid.head<3> () = vec;//= accu.tail<3> (); + //centroid.head<3> () = accu.tail<3> (); -- does not compile with Clang 3.0 + centroid[0] = accu[6]; centroid[1] = accu[7]; centroid[2] = accu[8]; + centroid[3] = 1; + covariance_matrix.coeffRef (0) = accu [0] - accu [6] * accu [6]; + covariance_matrix.coeffRef (1) = accu [1] - accu [6] * accu [7]; + covariance_matrix.coeffRef (2) = accu [2] - accu [6] * accu [8]; + covariance_matrix.coeffRef (4) = accu [3] - accu [7] * accu [7]; + covariance_matrix.coeffRef (5) = accu [4] - accu [7] * accu [8]; + covariance_matrix.coeffRef (8) = accu [5] - accu [8] * accu [8]; + covariance_matrix.coeffRef (3) = covariance_matrix.coeff (1); + covariance_matrix.coeffRef (6) = covariance_matrix.coeff (2); + covariance_matrix.coeffRef (7) = covariance_matrix.coeff (5); + + return (static_cast (point_count)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::Matrix &covariance_matrix, + Eigen::Matrix ¢roid) +{ + return (computeMeanAndCovarianceMatrix (cloud, indices.indices, covariance_matrix, centroid)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::demeanPointCloud (ConstCloudIterator &cloud_iterator, + const Eigen::Matrix ¢roid, + pcl::PointCloud &cloud_out, + int npts) +{ + // Calculate the number of points if not given + if (npts == 0) + { + while (cloud_iterator.isValid ()) + { + ++npts; + ++cloud_iterator; + } + cloud_iterator.reset (); + } + + int i = 0; + cloud_out.resize (npts); + // Subtract the centroid from cloud_in + while (cloud_iterator.isValid ()) + { + cloud_out[i].x = cloud_iterator->x - centroid[0]; + cloud_out[i].y = cloud_iterator->y - centroid[1]; + cloud_out[i].z = cloud_iterator->z - centroid[2]; + ++i; + ++cloud_iterator; + } + cloud_out.width = cloud_out.size (); + cloud_out.height = 1; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::demeanPointCloud (const pcl::PointCloud &cloud_in, + const Eigen::Matrix ¢roid, + pcl::PointCloud &cloud_out) +{ + cloud_out = cloud_in; + + // Subtract the centroid from cloud_in + for (size_t i = 0; i < cloud_in.points.size (); ++i) + { + cloud_out[i].x -= static_cast (centroid[0]); + cloud_out[i].y -= static_cast (centroid[1]); + cloud_out[i].z -= static_cast (centroid[2]); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::demeanPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + const Eigen::Matrix ¢roid, + pcl::PointCloud &cloud_out) +{ + cloud_out.header = cloud_in.header; + cloud_out.is_dense = cloud_in.is_dense; + if (indices.size () == cloud_in.points.size ()) + { + cloud_out.width = cloud_in.width; + cloud_out.height = cloud_in.height; + } + else + { + cloud_out.width = static_cast (indices.size ()); + cloud_out.height = 1; + } + cloud_out.resize (indices.size ()); + + // Subtract the centroid from cloud_in + for (size_t i = 0; i < indices.size (); ++i) + { + cloud_out[i].x = static_cast (cloud_in[indices[i]].x - centroid[0]); + cloud_out[i].y = static_cast (cloud_in[indices[i]].y - centroid[1]); + cloud_out[i].z = static_cast (cloud_in[indices[i]].z - centroid[2]); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::demeanPointCloud (const pcl::PointCloud &cloud_in, + const pcl::PointIndices& indices, + const Eigen::Matrix ¢roid, + pcl::PointCloud &cloud_out) +{ + return (demeanPointCloud (cloud_in, indices.indices, centroid, cloud_out)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::demeanPointCloud (ConstCloudIterator &cloud_iterator, + const Eigen::Matrix ¢roid, + Eigen::Matrix &cloud_out, + int npts) +{ + // Calculate the number of points if not given + if (npts == 0) + { + while (cloud_iterator.isValid ()) + { + ++npts; + ++cloud_iterator; + } + cloud_iterator.reset (); + } + + cloud_out = Eigen::Matrix::Zero (4, npts); // keep the data aligned + + int i = 0; + while (cloud_iterator.isValid ()) + { + cloud_out (0, i) = cloud_iterator->x - centroid[0]; + cloud_out (1, i) = cloud_iterator->y - centroid[1]; + cloud_out (2, i) = cloud_iterator->z - centroid[2]; + ++i; + ++cloud_iterator; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::demeanPointCloud (const pcl::PointCloud &cloud_in, + const Eigen::Matrix ¢roid, + Eigen::Matrix &cloud_out) +{ + size_t npts = cloud_in.size (); + + cloud_out = Eigen::Matrix::Zero (4, npts); // keep the data aligned + + for (size_t i = 0; i < npts; ++i) + { + cloud_out (0, i) = cloud_in[i].x - centroid[0]; + cloud_out (1, i) = cloud_in[i].y - centroid[1]; + cloud_out (2, i) = cloud_in[i].z - centroid[2]; + // One column at a time + //cloud_out.block<4, 1> (0, i) = cloud_in.points[i].getVector4fMap () - centroid; + } + + // Make sure we zero the 4th dimension out (1 row, N columns) + //cloud_out.block (3, 0, 1, npts).setZero (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::demeanPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + const Eigen::Matrix ¢roid, + Eigen::Matrix &cloud_out) +{ + size_t npts = indices.size (); + + cloud_out = Eigen::Matrix::Zero (4, npts); // keep the data aligned + + for (size_t i = 0; i < npts; ++i) + { + cloud_out (0, i) = cloud_in[indices[i]].x - centroid[0]; + cloud_out (1, i) = cloud_in[indices[i]].y - centroid[1]; + cloud_out (2, i) = cloud_in[indices[i]].z - centroid[2]; + // One column at a time + //cloud_out.block<4, 1> (0, i) = cloud_in.points[indices[i]].getVector4fMap () - centroid; + } + + // Make sure we zero the 4th dimension out (1 row, N columns) + //cloud_out.block (3, 0, 1, npts).setZero (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::demeanPointCloud (const pcl::PointCloud &cloud_in, + const pcl::PointIndices &indices, + const Eigen::Matrix ¢roid, + Eigen::Matrix &cloud_out) +{ + return (pcl::demeanPointCloud (cloud_in, indices.indices, centroid, cloud_out)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::computeNDCentroid (const pcl::PointCloud &cloud, + Eigen::Matrix ¢roid) +{ + typedef typename pcl::traits::fieldList::type FieldList; + + // Get the size of the fields + centroid.setZero (boost::mpl::size::value); + + if (cloud.empty ()) + return; + // Iterate over each point + int size = static_cast (cloud.size ()); + for (int i = 0; i < size; ++i) + { + // Iterate over each dimension + pcl::for_each_type (NdCentroidFunctor (cloud[i], centroid)); + } + centroid /= static_cast (size); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::computeNDCentroid (const pcl::PointCloud &cloud, + const std::vector &indices, + Eigen::Matrix ¢roid) +{ + typedef typename pcl::traits::fieldList::type FieldList; + + // Get the size of the fields + centroid.setZero (boost::mpl::size::value); + + if (indices.empty ()) + return; + // Iterate over each point + int nr_points = static_cast (indices.size ()); + for (int i = 0; i < nr_points; ++i) + { + // Iterate over each dimension + pcl::for_each_type (NdCentroidFunctor (cloud[indices[i]], centroid)); + } + centroid /= static_cast (nr_points); +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::computeNDCentroid (const pcl::PointCloud &cloud, + const pcl::PointIndices &indices, + Eigen::Matrix ¢roid) +{ + return (pcl::computeNDCentroid (cloud, indices.indices, centroid)); +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template size_t +pcl::computeCentroid (const pcl::PointCloud& cloud, + PointOutT& centroid) +{ + pcl::CentroidPoint cp; + + if (cloud.is_dense) + for (size_t i = 0; i < cloud.size (); ++i) + cp.add (cloud[i]); + else + for (size_t i = 0; i < cloud.size (); ++i) + if (pcl::isFinite (cloud[i])) + cp.add (cloud[i]); + + cp.get (centroid); + return (cp.getSize ()); +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template size_t +pcl::computeCentroid (const pcl::PointCloud& cloud, + const std::vector& indices, + PointOutT& centroid) +{ + pcl::CentroidPoint cp; + + if (cloud.is_dense) + for (size_t i = 0; i < indices.size (); ++i) + cp.add (cloud[indices[i]]); + else + for (size_t i = 0; i < indices.size (); ++i) + if (pcl::isFinite (cloud[indices[i]])) + cp.add (cloud[indices[i]]); + + cp.get (centroid); + return (cp.getSize ()); +} + +#endif //#ifndef PCL_COMMON_IMPL_CENTROID_H_ + diff --git a/pcl-1.7/pcl/common/impl/common.hpp b/pcl-1.7/pcl/common/impl/common.hpp new file mode 100644 index 0000000..b994343 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/common.hpp @@ -0,0 +1,411 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_COMMON_IMPL_H_ +#define PCL_COMMON_IMPL_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +inline double +pcl::getAngle3D (const Eigen::Vector4f &v1, const Eigen::Vector4f &v2) +{ + // Compute the actual angle + double rad = v1.dot (v2) / sqrt (v1.squaredNorm () * v2.squaredNorm ()); + if (rad < -1.0) rad = -1.0; + if (rad > 1.0) rad = 1.0; + return (acos (rad)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +inline void +pcl::getMeanStd (const std::vector &values, double &mean, double &stddev) +{ + double sum = 0, sq_sum = 0; + + for (size_t i = 0; i < values.size (); ++i) + { + sum += values[i]; + sq_sum += values[i] * values[i]; + } + mean = sum / static_cast(values.size ()); + double variance = (sq_sum - sum * sum / static_cast(values.size ())) / (static_cast(values.size ()) - 1); + stddev = sqrt (variance); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::getPointsInBox (const pcl::PointCloud &cloud, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, + std::vector &indices) +{ + indices.resize (cloud.points.size ()); + int l = 0; + + // If the data is dense, we don't need to check for NaN + if (cloud.is_dense) + { + for (size_t i = 0; i < cloud.points.size (); ++i) + { + // Check if the point is inside bounds + if (cloud.points[i].x < min_pt[0] || cloud.points[i].y < min_pt[1] || cloud.points[i].z < min_pt[2]) + continue; + if (cloud.points[i].x > max_pt[0] || cloud.points[i].y > max_pt[1] || cloud.points[i].z > max_pt[2]) + continue; + indices[l++] = int (i); + } + } + // NaN or Inf values could exist => check for them + else + { + for (size_t i = 0; i < cloud.points.size (); ++i) + { + // Check if the point is invalid + if (!pcl_isfinite (cloud.points[i].x) || + !pcl_isfinite (cloud.points[i].y) || + !pcl_isfinite (cloud.points[i].z)) + continue; + // Check if the point is inside bounds + if (cloud.points[i].x < min_pt[0] || cloud.points[i].y < min_pt[1] || cloud.points[i].z < min_pt[2]) + continue; + if (cloud.points[i].x > max_pt[0] || cloud.points[i].y > max_pt[1] || cloud.points[i].z > max_pt[2]) + continue; + indices[l++] = int (i); + } + } + indices.resize (l); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::getMaxDistance (const pcl::PointCloud &cloud, const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt) +{ + float max_dist = -FLT_MAX; + int max_idx = -1; + float dist; + + // If the data is dense, we don't need to check for NaN + if (cloud.is_dense) + { + for (size_t i = 0; i < cloud.points.size (); ++i) + { + pcl::Vector4fMapConst pt = cloud.points[i].getVector4fMap (); + dist = (pivot_pt - pt).norm (); + if (dist > max_dist) + { + max_idx = int (i); + max_dist = dist; + } + } + } + // NaN or Inf values could exist => check for them + else + { + for (size_t i = 0; i < cloud.points.size (); ++i) + { + // Check if the point is invalid + if (!pcl_isfinite (cloud.points[i].x) || !pcl_isfinite (cloud.points[i].y) || !pcl_isfinite (cloud.points[i].z)) + continue; + pcl::Vector4fMapConst pt = cloud.points[i].getVector4fMap (); + dist = (pivot_pt - pt).norm (); + if (dist > max_dist) + { + max_idx = int (i); + max_dist = dist; + } + } + } + + if(max_idx != -1) + max_pt = cloud.points[max_idx].getVector4fMap (); + else + max_pt = Eigen::Vector4f(std::numeric_limits::quiet_NaN(),std::numeric_limits::quiet_NaN(),std::numeric_limits::quiet_NaN(),std::numeric_limits::quiet_NaN()); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::getMaxDistance (const pcl::PointCloud &cloud, const std::vector &indices, + const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt) +{ + float max_dist = -FLT_MAX; + int max_idx = -1; + float dist; + + // If the data is dense, we don't need to check for NaN + if (cloud.is_dense) + { + for (size_t i = 0; i < indices.size (); ++i) + { + pcl::Vector4fMapConst pt = cloud.points[indices[i]].getVector4fMap (); + dist = (pivot_pt - pt).norm (); + if (dist > max_dist) + { + max_idx = static_cast (i); + max_dist = dist; + } + } + } + // NaN or Inf values could exist => check for them + else + { + for (size_t i = 0; i < indices.size (); ++i) + { + // Check if the point is invalid + if (!pcl_isfinite (cloud.points[indices[i]].x) || !pcl_isfinite (cloud.points[indices[i]].y) + || + !pcl_isfinite (cloud.points[indices[i]].z)) + continue; + + pcl::Vector4fMapConst pt = cloud.points[indices[i]].getVector4fMap (); + dist = (pivot_pt - pt).norm (); + if (dist > max_dist) + { + max_idx = static_cast (i); + max_dist = dist; + } + } + } + + if(max_idx != -1) + max_pt = cloud.points[max_idx].getVector4fMap (); + else + max_pt = Eigen::Vector4f(std::numeric_limits::quiet_NaN(),std::numeric_limits::quiet_NaN(),std::numeric_limits::quiet_NaN(),std::numeric_limits::quiet_NaN()); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::getMinMax3D (const pcl::PointCloud &cloud, PointT &min_pt, PointT &max_pt) +{ + Eigen::Array4f min_p, max_p; + min_p.setConstant (FLT_MAX); + max_p.setConstant (-FLT_MAX); + + // If the data is dense, we don't need to check for NaN + if (cloud.is_dense) + { + for (size_t i = 0; i < cloud.points.size (); ++i) + { + pcl::Array4fMapConst pt = cloud.points[i].getArray4fMap (); + min_p = min_p.min (pt); + max_p = max_p.max (pt); + } + } + // NaN or Inf values could exist => check for them + else + { + for (size_t i = 0; i < cloud.points.size (); ++i) + { + // Check if the point is invalid + if (!pcl_isfinite (cloud.points[i].x) || + !pcl_isfinite (cloud.points[i].y) || + !pcl_isfinite (cloud.points[i].z)) + continue; + pcl::Array4fMapConst pt = cloud.points[i].getArray4fMap (); + min_p = min_p.min (pt); + max_p = max_p.max (pt); + } + } + min_pt.x = min_p[0]; min_pt.y = min_p[1]; min_pt.z = min_p[2]; + max_pt.x = max_p[0]; max_pt.y = max_p[1]; max_pt.z = max_p[2]; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::getMinMax3D (const pcl::PointCloud &cloud, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt) +{ + Eigen::Array4f min_p, max_p; + min_p.setConstant (FLT_MAX); + max_p.setConstant (-FLT_MAX); + + // If the data is dense, we don't need to check for NaN + if (cloud.is_dense) + { + for (size_t i = 0; i < cloud.points.size (); ++i) + { + pcl::Array4fMapConst pt = cloud.points[i].getArray4fMap (); + min_p = min_p.min (pt); + max_p = max_p.max (pt); + } + } + // NaN or Inf values could exist => check for them + else + { + for (size_t i = 0; i < cloud.points.size (); ++i) + { + // Check if the point is invalid + if (!pcl_isfinite (cloud.points[i].x) || + !pcl_isfinite (cloud.points[i].y) || + !pcl_isfinite (cloud.points[i].z)) + continue; + pcl::Array4fMapConst pt = cloud.points[i].getArray4fMap (); + min_p = min_p.min (pt); + max_p = max_p.max (pt); + } + } + min_pt = min_p; + max_pt = max_p; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::getMinMax3D (const pcl::PointCloud &cloud, const pcl::PointIndices &indices, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt) +{ + Eigen::Array4f min_p, max_p; + min_p.setConstant (FLT_MAX); + max_p.setConstant (-FLT_MAX); + + // If the data is dense, we don't need to check for NaN + if (cloud.is_dense) + { + for (size_t i = 0; i < indices.indices.size (); ++i) + { + pcl::Array4fMapConst pt = cloud.points[indices.indices[i]].getArray4fMap (); + min_p = min_p.min (pt); + max_p = max_p.max (pt); + } + } + // NaN or Inf values could exist => check for them + else + { + for (size_t i = 0; i < indices.indices.size (); ++i) + { + // Check if the point is invalid + if (!pcl_isfinite (cloud.points[indices.indices[i]].x) || + !pcl_isfinite (cloud.points[indices.indices[i]].y) || + !pcl_isfinite (cloud.points[indices.indices[i]].z)) + continue; + pcl::Array4fMapConst pt = cloud.points[indices.indices[i]].getArray4fMap (); + min_p = min_p.min (pt); + max_p = max_p.max (pt); + } + } + min_pt = min_p; + max_pt = max_p; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::getMinMax3D (const pcl::PointCloud &cloud, const std::vector &indices, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt) +{ + min_pt.setConstant (FLT_MAX); + max_pt.setConstant (-FLT_MAX); + + // If the data is dense, we don't need to check for NaN + if (cloud.is_dense) + { + for (size_t i = 0; i < indices.size (); ++i) + { + pcl::Array4fMapConst pt = cloud.points[indices[i]].getArray4fMap (); + min_pt = min_pt.array ().min (pt); + max_pt = max_pt.array ().max (pt); + } + } + // NaN or Inf values could exist => check for them + else + { + for (size_t i = 0; i < indices.size (); ++i) + { + // Check if the point is invalid + if (!pcl_isfinite (cloud.points[indices[i]].x) || + !pcl_isfinite (cloud.points[indices[i]].y) || + !pcl_isfinite (cloud.points[indices[i]].z)) + continue; + pcl::Array4fMapConst pt = cloud.points[indices[i]].getArray4fMap (); + min_pt = min_pt.array ().min (pt); + max_pt = max_pt.array ().max (pt); + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline double +pcl::getCircumcircleRadius (const PointT &pa, const PointT &pb, const PointT &pc) +{ + Eigen::Vector4f p1 (pa.x, pa.y, pa.z, 0); + Eigen::Vector4f p2 (pb.x, pb.y, pb.z, 0); + Eigen::Vector4f p3 (pc.x, pc.y, pc.z, 0); + + double p2p1 = (p2 - p1).norm (), p3p2 = (p3 - p2).norm (), p1p3 = (p1 - p3).norm (); + // Calculate the area of the triangle using Heron's formula + // (http://en.wikipedia.org/wiki/Heron's_formula) + double semiperimeter = (p2p1 + p3p2 + p1p3) / 2.0; + double area = sqrt (semiperimeter * (semiperimeter - p2p1) * (semiperimeter - p3p2) * (semiperimeter - p1p3)); + // Compute the radius of the circumscribed circle + return ((p2p1 * p3p2 * p1p3) / (4.0 * area)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::getMinMax (const PointT &histogram, int len, float &min_p, float &max_p) +{ + min_p = FLT_MAX; + max_p = -FLT_MAX; + + for (int i = 0; i < len; ++i) + { + min_p = (histogram[i] > min_p) ? min_p : histogram[i]; + max_p = (histogram[i] < max_p) ? max_p : histogram[i]; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline float +pcl::calculatePolygonArea (const pcl::PointCloud &polygon) +{ + float area = 0.0f; + int num_points = polygon.size (); + int j = 0; + Eigen::Vector3f va,vb,res; + + res(0) = res(1) = res(2) = 0.0f; + for (int i = 0; i < num_points; ++i) + { + j = (i + 1) % num_points; + va = polygon[i].getVector3fMap (); + vb = polygon[j].getVector3fMap (); + res += va.cross (vb); + } + area = res.norm (); + return (area*0.5); +} + +#endif //#ifndef PCL_COMMON_IMPL_H_ + diff --git a/pcl-1.7/pcl/common/impl/copy_point.hpp b/pcl-1.7/pcl/common/impl/copy_point.hpp new file mode 100644 index 0000000..b4070a0 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/copy_point.hpp @@ -0,0 +1,145 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2014-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_COMMON_IMPL_COPY_POINT_HPP_ +#define PCL_COMMON_IMPL_COPY_POINT_HPP_ + +#include +#include +#include +#include + +namespace pcl +{ + + namespace detail + { + + /* CopyPointHelper and its specializations copy the contents of a source + * point to a target point. There are three cases: + * + * - Points have the same type. + * In this case a single `memcpy` is used. + * + * - Points have different types and one of the following is true: + * * both have RGB fields; + * * both have RGBA fields; + * * one or both have no RGB/RGBA fields. + * In this case we find the list of common fields and copy their + * contents one by one with `NdConcatenateFunctor`. + * + * - Points have different types and one of these types has RGB field, and + * the other has RGBA field. + * In this case we also find the list of common fields and copy their + * contents. In order to account for the fact that RGB and RGBA do not + * match we have an additional `memcpy` to copy the contents of one into + * another. + * + * An appropriate version of CopyPointHelper is instantiated during + * compilation time automatically, so there is absolutely no run-time + * overhead. */ + + template + struct CopyPointHelper { }; + + template + struct CopyPointHelper >::type> + { + void operator () (const PointInT& point_in, PointOutT& point_out) const + { + memcpy (&point_out, &point_in, sizeof (PointInT)); + } + }; + + template + struct CopyPointHelper >, + boost::mpl::or_ >, + boost::mpl::not_ >, + boost::mpl::and_, + pcl::traits::has_field >, + boost::mpl::and_, + pcl::traits::has_field > > > >::type> + { + void operator () (const PointInT& point_in, PointOutT& point_out) const + { + typedef typename pcl::traits::fieldList::type FieldListInT; + typedef typename pcl::traits::fieldList::type FieldListOutT; + typedef typename pcl::intersect::type FieldList; + pcl::for_each_type (pcl::NdConcatenateFunctor (point_in, point_out)); + } + }; + + template + struct CopyPointHelper >, + boost::mpl::or_, + pcl::traits::has_field >, + boost::mpl::and_, + pcl::traits::has_field > > > >::type> + { + void operator () (const PointInT& point_in, PointOutT& point_out) const + { + typedef typename pcl::traits::fieldList::type FieldListInT; + typedef typename pcl::traits::fieldList::type FieldListOutT; + typedef typename pcl::intersect::type FieldList; + const uint32_t offset_in = boost::mpl::if_, + pcl::traits::offset, + pcl::traits::offset >::type::value; + const uint32_t offset_out = boost::mpl::if_, + pcl::traits::offset, + pcl::traits::offset >::type::value; + pcl::for_each_type (pcl::NdConcatenateFunctor (point_in, point_out)); + memcpy (reinterpret_cast (&point_out) + offset_out, + reinterpret_cast (&point_in) + offset_in, + 4); + } + }; + + } + +} + +template void +pcl::copyPoint (const PointInT& point_in, PointOutT& point_out) +{ + detail::CopyPointHelper copy; + copy (point_in, point_out); +} + +#endif //PCL_COMMON_IMPL_COPY_POINT_HPP_ + diff --git a/pcl-1.7/pcl/common/impl/eigen.hpp b/pcl-1.7/pcl/common/impl/eigen.hpp new file mode 100644 index 0000000..552224e --- /dev/null +++ b/pcl-1.7/pcl/common/impl/eigen.hpp @@ -0,0 +1,1001 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR a PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_COMMON_EIGEN_IMPL_HPP_ +#define PCL_COMMON_EIGEN_IMPL_HPP_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::computeRoots2 (const Scalar& b, const Scalar& c, Roots& roots) +{ + roots (0) = Scalar (0); + Scalar d = Scalar (b * b - 4.0 * c); + if (d < 0.0) // no real roots ! THIS SHOULD NOT HAPPEN! + d = 0.0; + + Scalar sd = ::std::sqrt (d); + + roots (2) = 0.5f * (b + sd); + roots (1) = 0.5f * (b - sd); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::computeRoots (const Matrix& m, Roots& roots) +{ + typedef typename Matrix::Scalar Scalar; + + // The characteristic equation is x^3 - c2*x^2 + c1*x - c0 = 0. The + // eigenvalues are the roots to this equation, all guaranteed to be + // real-valued, because the matrix is symmetric. + Scalar c0 = m (0, 0) * m (1, 1) * m (2, 2) + + Scalar (2) * m (0, 1) * m (0, 2) * m (1, 2) + - m (0, 0) * m (1, 2) * m (1, 2) + - m (1, 1) * m (0, 2) * m (0, 2) + - m (2, 2) * m (0, 1) * m (0, 1); + Scalar c1 = m (0, 0) * m (1, 1) - + m (0, 1) * m (0, 1) + + m (0, 0) * m (2, 2) - + m (0, 2) * m (0, 2) + + m (1, 1) * m (2, 2) - + m (1, 2) * m (1, 2); + Scalar c2 = m (0, 0) + m (1, 1) + m (2, 2); + + if (fabs (c0) < Eigen::NumTraits < Scalar > ::epsilon ()) // one root is 0 -> quadratic equation + computeRoots2 (c2, c1, roots); + else + { + const Scalar s_inv3 = Scalar (1.0 / 3.0); + const Scalar s_sqrt3 = std::sqrt (Scalar (3.0)); + // Construct the parameters used in classifying the roots of the equation + // and in solving the equation for the roots in closed form. + Scalar c2_over_3 = c2 * s_inv3; + Scalar a_over_3 = (c1 - c2 * c2_over_3) * s_inv3; + if (a_over_3 > Scalar (0)) + a_over_3 = Scalar (0); + + Scalar half_b = Scalar (0.5) * (c0 + c2_over_3 * (Scalar (2) * c2_over_3 * c2_over_3 - c1)); + + Scalar q = half_b * half_b + a_over_3 * a_over_3 * a_over_3; + if (q > Scalar (0)) + q = Scalar (0); + + // Compute the eigenvalues by solving for the roots of the polynomial. + Scalar rho = std::sqrt (-a_over_3); + Scalar theta = std::atan2 (std::sqrt (-q), half_b) * s_inv3; + Scalar cos_theta = std::cos (theta); + Scalar sin_theta = std::sin (theta); + roots (0) = c2_over_3 + Scalar (2) * rho * cos_theta; + roots (1) = c2_over_3 - rho * (cos_theta + s_sqrt3 * sin_theta); + roots (2) = c2_over_3 - rho * (cos_theta - s_sqrt3 * sin_theta); + + // Sort in increasing order. + if (roots (0) >= roots (1)) + std::swap (roots (0), roots (1)); + if (roots (1) >= roots (2)) + { + std::swap (roots (1), roots (2)); + if (roots (0) >= roots (1)) + std::swap (roots (0), roots (1)); + } + + if (roots (0) <= 0) // eigenval for symetric positive semi-definite matrix can not be negative! Set it to 0 + computeRoots2 (c2, c1, roots); + } +} + +////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::eigen22 (const Matrix& mat, typename Matrix::Scalar& eigenvalue, Vector& eigenvector) +{ + // if diagonal matrix, the eigenvalues are the diagonal elements + // and the eigenvectors are not unique, thus set to Identity + if (fabs (mat.coeff (1)) <= std::numeric_limits::min ()) + { + if (mat.coeff (0) < mat.coeff (2)) + { + eigenvalue = mat.coeff (0); + eigenvector[0] = 1.0; + eigenvector[1] = 0.0; + } + else + { + eigenvalue = mat.coeff (2); + eigenvector[0] = 0.0; + eigenvector[1] = 1.0; + } + return; + } + + // 0.5 to optimize further calculations + typename Matrix::Scalar trace = static_cast (0.5) * (mat.coeff (0) + mat.coeff (3)); + typename Matrix::Scalar determinant = mat.coeff (0) * mat.coeff (3) - mat.coeff (1) * mat.coeff (1); + + typename Matrix::Scalar temp = trace * trace - determinant; + + if (temp < 0) + temp = 0; + + eigenvalue = trace - ::std::sqrt (temp); + + eigenvector[0] = -mat.coeff (1); + eigenvector[1] = mat.coeff (0) - eigenvalue; + eigenvector.normalize (); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::eigen22 (const Matrix& mat, Matrix& eigenvectors, Vector& eigenvalues) +{ + // if diagonal matrix, the eigenvalues are the diagonal elements + // and the eigenvectors are not unique, thus set to Identity + if (fabs (mat.coeff (1)) <= std::numeric_limits::min ()) + { + if (mat.coeff (0) < mat.coeff (3)) + { + eigenvalues.coeffRef (0) = mat.coeff (0); + eigenvalues.coeffRef (1) = mat.coeff (3); + eigenvectors.coeffRef (0) = 1.0; + eigenvectors.coeffRef (1) = 0.0; + eigenvectors.coeffRef (2) = 0.0; + eigenvectors.coeffRef (3) = 1.0; + } + else + { + eigenvalues.coeffRef (0) = mat.coeff (3); + eigenvalues.coeffRef (1) = mat.coeff (0); + eigenvectors.coeffRef (0) = 0.0; + eigenvectors.coeffRef (1) = 1.0; + eigenvectors.coeffRef (2) = 1.0; + eigenvectors.coeffRef (3) = 0.0; + } + return; + } + + // 0.5 to optimize further calculations + typename Matrix::Scalar trace = static_cast (0.5) * (mat.coeff (0) + mat.coeff (3)); + typename Matrix::Scalar determinant = mat.coeff (0) * mat.coeff (3) - mat.coeff (1) * mat.coeff (1); + + typename Matrix::Scalar temp = trace * trace - determinant; + + if (temp < 0) + temp = 0; + else + temp = ::std::sqrt (temp); + + eigenvalues.coeffRef (0) = trace - temp; + eigenvalues.coeffRef (1) = trace + temp; + + // either this is in a row or column depending on RowMajor or ColumnMajor + eigenvectors.coeffRef (0) = -mat.coeff (1); + eigenvectors.coeffRef (2) = mat.coeff (0) - eigenvalues.coeff (0); + typename Matrix::Scalar norm = static_cast (1.0) + / static_cast (::std::sqrt (eigenvectors.coeffRef (0) * eigenvectors.coeffRef (0) + eigenvectors.coeffRef (2) * eigenvectors.coeffRef (2))); + eigenvectors.coeffRef (0) *= norm; + eigenvectors.coeffRef (2) *= norm; + eigenvectors.coeffRef (1) = eigenvectors.coeffRef (2); + eigenvectors.coeffRef (3) = -eigenvectors.coeffRef (0); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::computeCorrespondingEigenVector (const Matrix& mat, const typename Matrix::Scalar& eigenvalue, Vector& eigenvector) +{ + typedef typename Matrix::Scalar Scalar; + // Scale the matrix so its entries are in [-1,1]. The scaling is applied + // only when at least one matrix entry has magnitude larger than 1. + + Scalar scale = mat.cwiseAbs ().maxCoeff (); + if (scale <= std::numeric_limits < Scalar > ::min ()) + scale = Scalar (1.0); + + Matrix scaledMat = mat / scale; + + scaledMat.diagonal ().array () -= eigenvalue / scale; + + Vector vec1 = scaledMat.row (0).cross (scaledMat.row (1)); + Vector vec2 = scaledMat.row (0).cross (scaledMat.row (2)); + Vector vec3 = scaledMat.row (1).cross (scaledMat.row (2)); + + Scalar len1 = vec1.squaredNorm (); + Scalar len2 = vec2.squaredNorm (); + Scalar len3 = vec3.squaredNorm (); + + if (len1 >= len2 && len1 >= len3) + eigenvector = vec1 / std::sqrt (len1); + else if (len2 >= len1 && len2 >= len3) + eigenvector = vec2 / std::sqrt (len2); + else + eigenvector = vec3 / std::sqrt (len3); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::eigen33 (const Matrix& mat, typename Matrix::Scalar& eigenvalue, Vector& eigenvector) +{ + typedef typename Matrix::Scalar Scalar; + // Scale the matrix so its entries are in [-1,1]. The scaling is applied + // only when at least one matrix entry has magnitude larger than 1. + + Scalar scale = mat.cwiseAbs ().maxCoeff (); + if (scale <= std::numeric_limits < Scalar > ::min ()) + scale = Scalar (1.0); + + Matrix scaledMat = mat / scale; + + Vector eigenvalues; + computeRoots (scaledMat, eigenvalues); + + eigenvalue = eigenvalues (0) * scale; + + scaledMat.diagonal ().array () -= eigenvalues (0); + + Vector vec1 = scaledMat.row (0).cross (scaledMat.row (1)); + Vector vec2 = scaledMat.row (0).cross (scaledMat.row (2)); + Vector vec3 = scaledMat.row (1).cross (scaledMat.row (2)); + + Scalar len1 = vec1.squaredNorm (); + Scalar len2 = vec2.squaredNorm (); + Scalar len3 = vec3.squaredNorm (); + + if (len1 >= len2 && len1 >= len3) + eigenvector = vec1 / std::sqrt (len1); + else if (len2 >= len1 && len2 >= len3) + eigenvector = vec2 / std::sqrt (len2); + else + eigenvector = vec3 / std::sqrt (len3); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::eigen33 (const Matrix& mat, Vector& evals) +{ + typedef typename Matrix::Scalar Scalar; + Scalar scale = mat.cwiseAbs ().maxCoeff (); + if (scale <= std::numeric_limits < Scalar > ::min ()) + scale = Scalar (1.0); + + Matrix scaledMat = mat / scale; + computeRoots (scaledMat, evals); + evals *= scale; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::eigen33 (const Matrix& mat, Matrix& evecs, Vector& evals) +{ + typedef typename Matrix::Scalar Scalar; + // Scale the matrix so its entries are in [-1,1]. The scaling is applied + // only when at least one matrix entry has magnitude larger than 1. + + Scalar scale = mat.cwiseAbs ().maxCoeff (); + if (scale <= std::numeric_limits < Scalar > ::min ()) + scale = Scalar (1.0); + + Matrix scaledMat = mat / scale; + + // Compute the eigenvalues + computeRoots (scaledMat, evals); + + if ( (evals (2) - evals (0)) <= Eigen::NumTraits < Scalar > ::epsilon ()) + { + // all three equal + evecs.setIdentity (); + } + else if ( (evals (1) - evals (0)) <= Eigen::NumTraits < Scalar > ::epsilon ()) + { + // first and second equal + Matrix tmp; + tmp = scaledMat; + tmp.diagonal ().array () -= evals (2); + + Vector vec1 = tmp.row (0).cross (tmp.row (1)); + Vector vec2 = tmp.row (0).cross (tmp.row (2)); + Vector vec3 = tmp.row (1).cross (tmp.row (2)); + + Scalar len1 = vec1.squaredNorm (); + Scalar len2 = vec2.squaredNorm (); + Scalar len3 = vec3.squaredNorm (); + + if (len1 >= len2 && len1 >= len3) + evecs.col (2) = vec1 / std::sqrt (len1); + else if (len2 >= len1 && len2 >= len3) + evecs.col (2) = vec2 / std::sqrt (len2); + else + evecs.col (2) = vec3 / std::sqrt (len3); + + evecs.col (1) = evecs.col (2).unitOrthogonal (); + evecs.col (0) = evecs.col (1).cross (evecs.col (2)); + } + else if ( (evals (2) - evals (1)) <= Eigen::NumTraits < Scalar > ::epsilon ()) + { + // second and third equal + Matrix tmp; + tmp = scaledMat; + tmp.diagonal ().array () -= evals (0); + + Vector vec1 = tmp.row (0).cross (tmp.row (1)); + Vector vec2 = tmp.row (0).cross (tmp.row (2)); + Vector vec3 = tmp.row (1).cross (tmp.row (2)); + + Scalar len1 = vec1.squaredNorm (); + Scalar len2 = vec2.squaredNorm (); + Scalar len3 = vec3.squaredNorm (); + + if (len1 >= len2 && len1 >= len3) + evecs.col (0) = vec1 / std::sqrt (len1); + else if (len2 >= len1 && len2 >= len3) + evecs.col (0) = vec2 / std::sqrt (len2); + else + evecs.col (0) = vec3 / std::sqrt (len3); + + evecs.col (1) = evecs.col (0).unitOrthogonal (); + evecs.col (2) = evecs.col (0).cross (evecs.col (1)); + } + else + { + Matrix tmp; + tmp = scaledMat; + tmp.diagonal ().array () -= evals (2); + + Vector vec1 = tmp.row (0).cross (tmp.row (1)); + Vector vec2 = tmp.row (0).cross (tmp.row (2)); + Vector vec3 = tmp.row (1).cross (tmp.row (2)); + + Scalar len1 = vec1.squaredNorm (); + Scalar len2 = vec2.squaredNorm (); + Scalar len3 = vec3.squaredNorm (); +#ifdef _WIN32 + Scalar *mmax = new Scalar[3]; +#else + Scalar mmax[3]; +#endif + unsigned int min_el = 2; + unsigned int max_el = 2; + if (len1 >= len2 && len1 >= len3) + { + mmax[2] = len1; + evecs.col (2) = vec1 / std::sqrt (len1); + } + else if (len2 >= len1 && len2 >= len3) + { + mmax[2] = len2; + evecs.col (2) = vec2 / std::sqrt (len2); + } + else + { + mmax[2] = len3; + evecs.col (2) = vec3 / std::sqrt (len3); + } + + tmp = scaledMat; + tmp.diagonal ().array () -= evals (1); + + vec1 = tmp.row (0).cross (tmp.row (1)); + vec2 = tmp.row (0).cross (tmp.row (2)); + vec3 = tmp.row (1).cross (tmp.row (2)); + + len1 = vec1.squaredNorm (); + len2 = vec2.squaredNorm (); + len3 = vec3.squaredNorm (); + if (len1 >= len2 && len1 >= len3) + { + mmax[1] = len1; + evecs.col (1) = vec1 / std::sqrt (len1); + min_el = len1 <= mmax[min_el] ? 1 : min_el; + max_el = len1 > mmax[max_el] ? 1 : max_el; + } + else if (len2 >= len1 && len2 >= len3) + { + mmax[1] = len2; + evecs.col (1) = vec2 / std::sqrt (len2); + min_el = len2 <= mmax[min_el] ? 1 : min_el; + max_el = len2 > mmax[max_el] ? 1 : max_el; + } + else + { + mmax[1] = len3; + evecs.col (1) = vec3 / std::sqrt (len3); + min_el = len3 <= mmax[min_el] ? 1 : min_el; + max_el = len3 > mmax[max_el] ? 1 : max_el; + } + + tmp = scaledMat; + tmp.diagonal ().array () -= evals (0); + + vec1 = tmp.row (0).cross (tmp.row (1)); + vec2 = tmp.row (0).cross (tmp.row (2)); + vec3 = tmp.row (1).cross (tmp.row (2)); + + len1 = vec1.squaredNorm (); + len2 = vec2.squaredNorm (); + len3 = vec3.squaredNorm (); + if (len1 >= len2 && len1 >= len3) + { + mmax[0] = len1; + evecs.col (0) = vec1 / std::sqrt (len1); + min_el = len3 <= mmax[min_el] ? 0 : min_el; + max_el = len3 > mmax[max_el] ? 0 : max_el; + } + else if (len2 >= len1 && len2 >= len3) + { + mmax[0] = len2; + evecs.col (0) = vec2 / std::sqrt (len2); + min_el = len3 <= mmax[min_el] ? 0 : min_el; + max_el = len3 > mmax[max_el] ? 0 : max_el; + } + else + { + mmax[0] = len3; + evecs.col (0) = vec3 / std::sqrt (len3); + min_el = len3 <= mmax[min_el] ? 0 : min_el; + max_el = len3 > mmax[max_el] ? 0 : max_el; + } + + unsigned mid_el = 3 - min_el - max_el; + evecs.col (min_el) = evecs.col ( (min_el + 1) % 3).cross (evecs.col ( (min_el + 2) % 3)).normalized (); + evecs.col (mid_el) = evecs.col ( (mid_el + 1) % 3).cross (evecs.col ( (mid_el + 2) % 3)).normalized (); +#ifdef _WIN32 + delete [] mmax; +#endif + } + // Rescale back to the original size. + evals *= scale; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template inline typename Matrix::Scalar +pcl::invert2x2 (const Matrix& matrix, Matrix& inverse) +{ + typedef typename Matrix::Scalar Scalar; + Scalar det = matrix.coeff (0) * matrix.coeff (3) - matrix.coeff (1) * matrix.coeff (2); + + if (det != 0) + { + //Scalar inv_det = Scalar (1.0) / det; + inverse.coeffRef (0) = matrix.coeff (3); + inverse.coeffRef (1) = -matrix.coeff (1); + inverse.coeffRef (2) = -matrix.coeff (2); + inverse.coeffRef (3) = matrix.coeff (0); + inverse /= det; + } + return det; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template inline typename Matrix::Scalar +pcl::invert3x3SymMatrix (const Matrix& matrix, Matrix& inverse) +{ + typedef typename Matrix::Scalar Scalar; + // elements + // a b c + // b d e + // c e f + //| a b c |-1 | fd-ee ce-bf be-cd | + //| b d e | = 1/det * | ce-bf af-cc bc-ae | + //| c e f | | be-cd bc-ae ad-bb | + + //det = a(fd-ee) + b(ec-fb) + c(eb-dc) + + Scalar fd_ee = matrix.coeff (4) * matrix.coeff (8) - matrix.coeff (7) * matrix.coeff (5); + Scalar ce_bf = matrix.coeff (2) * matrix.coeff (5) - matrix.coeff (1) * matrix.coeff (8); + Scalar be_cd = matrix.coeff (1) * matrix.coeff (5) - matrix.coeff (2) * matrix.coeff (4); + + Scalar det = matrix.coeff (0) * fd_ee + matrix.coeff (1) * ce_bf + matrix.coeff (2) * be_cd; + + if (det != 0) + { + //Scalar inv_det = Scalar (1.0) / det; + inverse.coeffRef (0) = fd_ee; + inverse.coeffRef (1) = inverse.coeffRef (3) = ce_bf; + inverse.coeffRef (2) = inverse.coeffRef (6) = be_cd; + inverse.coeffRef (4) = (matrix.coeff (0) * matrix.coeff (8) - matrix.coeff (2) * matrix.coeff (2)); + inverse.coeffRef (5) = inverse.coeffRef (7) = (matrix.coeff (1) * matrix.coeff (2) - matrix.coeff (0) * matrix.coeff (5)); + inverse.coeffRef (8) = (matrix.coeff (0) * matrix.coeff (4) - matrix.coeff (1) * matrix.coeff (1)); + inverse /= det; + } + return det; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template inline typename Matrix::Scalar +pcl::invert3x3Matrix (const Matrix& matrix, Matrix& inverse) +{ + typedef typename Matrix::Scalar Scalar; + + //| a b c |-1 | ie-hf hc-ib fb-ec | + //| d e f | = 1/det * | gf-id ia-gc dc-fa | + //| g h i | | hd-ge gb-ha ea-db | + //det = a(ie-hf) + d(hc-ib) + g(fb-ec) + + Scalar ie_hf = matrix.coeff (8) * matrix.coeff (4) - matrix.coeff (7) * matrix.coeff (5); + Scalar hc_ib = matrix.coeff (7) * matrix.coeff (2) - matrix.coeff (8) * matrix.coeff (1); + Scalar fb_ec = matrix.coeff (5) * matrix.coeff (1) - matrix.coeff (4) * matrix.coeff (2); + Scalar det = matrix.coeff (0) * (ie_hf) + matrix.coeff (3) * (hc_ib) + matrix.coeff (6) * (fb_ec); + + if (det != 0) + { + inverse.coeffRef (0) = ie_hf; + inverse.coeffRef (1) = hc_ib; + inverse.coeffRef (2) = fb_ec; + inverse.coeffRef (3) = matrix.coeff (6) * matrix.coeff (5) - matrix.coeff (8) * matrix.coeff (3); + inverse.coeffRef (4) = matrix.coeff (8) * matrix.coeff (0) - matrix.coeff (6) * matrix.coeff (2); + inverse.coeffRef (5) = matrix.coeff (3) * matrix.coeff (2) - matrix.coeff (5) * matrix.coeff (0); + inverse.coeffRef (6) = matrix.coeff (7) * matrix.coeff (3) - matrix.coeff (6) * matrix.coeff (4); + inverse.coeffRef (7) = matrix.coeff (6) * matrix.coeff (1) - matrix.coeff (7) * matrix.coeff (0); + inverse.coeffRef (8) = matrix.coeff (4) * matrix.coeff (0) - matrix.coeff (3) * matrix.coeff (1); + + inverse /= det; + } + return det; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template inline typename Matrix::Scalar +pcl::determinant3x3Matrix (const Matrix& matrix) +{ + // result is independent of Row/Col Major storage! + return matrix.coeff (0) * (matrix.coeff (4) * matrix.coeff (8) - matrix.coeff (5) * matrix.coeff (7)) + + matrix.coeff (1) * (matrix.coeff (5) * matrix.coeff (6) - matrix.coeff (3) * matrix.coeff (8)) + + matrix.coeff (2) * (matrix.coeff (3) * matrix.coeff (7) - matrix.coeff (4) * matrix.coeff (6)) ; +} + +////////////////////////////////////////////////////////////////////////////////////////// +void +pcl::getTransFromUnitVectorsZY (const Eigen::Vector3f& z_axis, + const Eigen::Vector3f& y_direction, + Eigen::Affine3f& transformation) +{ + Eigen::Vector3f tmp0 = (y_direction.cross(z_axis)).normalized(); + Eigen::Vector3f tmp1 = (z_axis.cross(tmp0)).normalized(); + Eigen::Vector3f tmp2 = z_axis.normalized(); + + transformation(0,0)=tmp0[0]; transformation(0,1)=tmp0[1]; transformation(0,2)=tmp0[2]; transformation(0,3)=0.0f; + transformation(1,0)=tmp1[0]; transformation(1,1)=tmp1[1]; transformation(1,2)=tmp1[2]; transformation(1,3)=0.0f; + transformation(2,0)=tmp2[0]; transformation(2,1)=tmp2[1]; transformation(2,2)=tmp2[2]; transformation(2,3)=0.0f; + transformation(3,0)=0.0f; transformation(3,1)=0.0f; transformation(3,2)=0.0f; transformation(3,3)=1.0f; +} + +////////////////////////////////////////////////////////////////////////////////////////// +Eigen::Affine3f +pcl::getTransFromUnitVectorsZY (const Eigen::Vector3f& z_axis, + const Eigen::Vector3f& y_direction) +{ + Eigen::Affine3f transformation; + getTransFromUnitVectorsZY (z_axis, y_direction, transformation); + return (transformation); +} + +////////////////////////////////////////////////////////////////////////////////////////// +void +pcl::getTransFromUnitVectorsXY (const Eigen::Vector3f& x_axis, + const Eigen::Vector3f& y_direction, + Eigen::Affine3f& transformation) +{ + Eigen::Vector3f tmp2 = (x_axis.cross(y_direction)).normalized(); + Eigen::Vector3f tmp1 = (tmp2.cross(x_axis)).normalized(); + Eigen::Vector3f tmp0 = x_axis.normalized(); + + transformation(0,0)=tmp0[0]; transformation(0,1)=tmp0[1]; transformation(0,2)=tmp0[2]; transformation(0,3)=0.0f; + transformation(1,0)=tmp1[0]; transformation(1,1)=tmp1[1]; transformation(1,2)=tmp1[2]; transformation(1,3)=0.0f; + transformation(2,0)=tmp2[0]; transformation(2,1)=tmp2[1]; transformation(2,2)=tmp2[2]; transformation(2,3)=0.0f; + transformation(3,0)=0.0f; transformation(3,1)=0.0f; transformation(3,2)=0.0f; transformation(3,3)=1.0f; +} + +////////////////////////////////////////////////////////////////////////////////////////// +Eigen::Affine3f +pcl::getTransFromUnitVectorsXY (const Eigen::Vector3f& x_axis, + const Eigen::Vector3f& y_direction) +{ + Eigen::Affine3f transformation; + getTransFromUnitVectorsXY (x_axis, y_direction, transformation); + return (transformation); +} + +////////////////////////////////////////////////////////////////////////////////////////// +void +pcl::getTransformationFromTwoUnitVectors (const Eigen::Vector3f& y_direction, + const Eigen::Vector3f& z_axis, + Eigen::Affine3f& transformation) +{ + getTransFromUnitVectorsZY (z_axis, y_direction, transformation); +} + +////////////////////////////////////////////////////////////////////////////////////////// +Eigen::Affine3f +pcl::getTransformationFromTwoUnitVectors (const Eigen::Vector3f& y_direction, + const Eigen::Vector3f& z_axis) +{ + Eigen::Affine3f transformation; + getTransformationFromTwoUnitVectors (y_direction, z_axis, transformation); + return (transformation); +} + +void +pcl::getTransformationFromTwoUnitVectorsAndOrigin (const Eigen::Vector3f& y_direction, + const Eigen::Vector3f& z_axis, + const Eigen::Vector3f& origin, + Eigen::Affine3f& transformation) +{ + getTransformationFromTwoUnitVectors(y_direction, z_axis, transformation); + Eigen::Vector3f translation = transformation*origin; + transformation(0,3)=-translation[0]; transformation(1,3)=-translation[1]; transformation(2,3)=-translation[2]; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::getEulerAngles (const Eigen::Transform &t, Scalar &roll, Scalar &pitch, Scalar &yaw) +{ + roll = atan2 (t (2, 1), t (2, 2)); + pitch = asin (-t (2, 0)); + yaw = atan2 (t (1, 0), t (0, 0)); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::getTranslationAndEulerAngles (const Eigen::Transform &t, + Scalar &x, Scalar &y, Scalar &z, + Scalar &roll, Scalar &pitch, Scalar &yaw) +{ + x = t (0, 3); + y = t (1, 3); + z = t (2, 3); + roll = atan2 (t (2, 1), t (2, 2)); + pitch = asin (-t (2, 0)); + yaw = atan2 (t (1, 0), t (0, 0)); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::getTransformation (Scalar x, Scalar y, Scalar z, + Scalar roll, Scalar pitch, Scalar yaw, + Eigen::Transform &t) +{ + Scalar A = cos (yaw), B = sin (yaw), C = cos (pitch), D = sin (pitch), + E = cos (roll), F = sin (roll), DE = D*E, DF = D*F; + + t (0, 0) = A*C; t (0, 1) = A*DF - B*E; t (0, 2) = B*F + A*DE; t (0, 3) = x; + t (1, 0) = B*C; t (1, 1) = A*E + B*DF; t (1, 2) = B*DE - A*F; t (1, 3) = y; + t (2, 0) = -D; t (2, 1) = C*F; t (2, 2) = C*E; t (2, 3) = z; + t (3, 0) = 0; t (3, 1) = 0; t (3, 2) = 0; t (3, 3) = 1; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::saveBinary (const Eigen::MatrixBase& matrix, std::ostream& file) +{ + uint32_t rows = static_cast (matrix.rows ()), cols = static_cast (matrix.cols ()); + file.write (reinterpret_cast (&rows), sizeof (rows)); + file.write (reinterpret_cast (&cols), sizeof (cols)); + for (uint32_t i = 0; i < rows; ++i) + for (uint32_t j = 0; j < cols; ++j) + { + typename Derived::Scalar tmp = matrix(i,j); + file.write (reinterpret_cast (&tmp), sizeof (tmp)); + } +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::loadBinary (Eigen::MatrixBase const & matrix_, std::istream& file) +{ + Eigen::MatrixBase &matrix = const_cast &> (matrix_); + + uint32_t rows, cols; + file.read (reinterpret_cast (&rows), sizeof (rows)); + file.read (reinterpret_cast (&cols), sizeof (cols)); + if (matrix.rows () != static_cast(rows) || matrix.cols () != static_cast(cols)) + matrix.derived().resize(rows, cols); + + for (uint32_t i = 0; i < rows; ++i) + for (uint32_t j = 0; j < cols; ++j) + { + typename Derived::Scalar tmp; + file.read (reinterpret_cast (&tmp), sizeof (tmp)); + matrix (i, j) = tmp; + } +} + +////////////////////////////////////////////////////////////////////////////////////////// +template +typename Eigen::internal::umeyama_transform_matrix_type::type +pcl::umeyama (const Eigen::MatrixBase& src, const Eigen::MatrixBase& dst, bool with_scaling) +{ + typedef typename Eigen::internal::umeyama_transform_matrix_type::type TransformationMatrixType; + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename Derived::Index Index; + + EIGEN_STATIC_ASSERT (!Eigen::NumTraits::IsComplex, NUMERIC_TYPE_MUST_BE_REAL) + EIGEN_STATIC_ASSERT ((Eigen::internal::is_same::Scalar>::value), + YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) + + enum { Dimension = PCL_EIGEN_SIZE_MIN_PREFER_DYNAMIC (Derived::RowsAtCompileTime, OtherDerived::RowsAtCompileTime) }; + + typedef Eigen::Matrix VectorType; + typedef Eigen::Matrix MatrixType; + typedef typename Eigen::internal::plain_matrix_type_row_major::type RowMajorMatrixType; + + const Index m = src.rows (); // dimension + const Index n = src.cols (); // number of measurements + + // required for demeaning ... + const RealScalar one_over_n = 1 / static_cast (n); + + // computation of mean + const VectorType src_mean = src.rowwise ().sum () * one_over_n; + const VectorType dst_mean = dst.rowwise ().sum () * one_over_n; + + // demeaning of src and dst points + const RowMajorMatrixType src_demean = src.colwise () - src_mean; + const RowMajorMatrixType dst_demean = dst.colwise () - dst_mean; + + // Eq. (36)-(37) + const Scalar src_var = src_demean.rowwise ().squaredNorm ().sum () * one_over_n; + + // Eq. (38) + const MatrixType sigma (one_over_n * dst_demean * src_demean.transpose ()); + + Eigen::JacobiSVD svd (sigma, Eigen::ComputeFullU | Eigen::ComputeFullV); + + // Initialize the resulting transformation with an identity matrix... + TransformationMatrixType Rt = TransformationMatrixType::Identity (m + 1, m + 1); + + // Eq. (39) + VectorType S = VectorType::Ones (m); + if (sigma.determinant () < 0) + S (m - 1) = -1; + + // Eq. (40) and (43) + const VectorType& d = svd.singularValues (); + Index rank = 0; + for (Index i = 0; i < m; ++i) + if (!Eigen::internal::isMuchSmallerThan (d.coeff (i), d.coeff (0))) + ++rank; + if (rank == m - 1) + { + if (svd.matrixU ().determinant () * svd.matrixV ().determinant () > 0) + Rt.block (0, 0, m, m).noalias () = svd.matrixU () * svd.matrixV ().transpose (); + else + { + const Scalar s = S (m - 1); + S (m - 1) = -1; + Rt.block (0, 0, m, m).noalias () = svd.matrixU () * S.asDiagonal () * svd.matrixV ().transpose (); + S (m - 1) = s; + } + } + else + { + Rt.block (0, 0, m, m).noalias () = svd.matrixU () * S.asDiagonal () * svd.matrixV ().transpose (); + } + + // Eq. (42) + if (with_scaling) + { + // Eq. (42) + const Scalar c = 1 / src_var * svd.singularValues ().dot (S); + + // Eq. (41) + Rt.col (m).head (m) = dst_mean; + Rt.col (m).head (m).noalias () -= c * Rt.topLeftCorner (m, m) * src_mean; + Rt.block (0, 0, m, m) *= c; + } + else + { + Rt.col (m).head (m) = dst_mean; + Rt.col (m).head (m).noalias () -= Rt.topLeftCorner (m, m) * src_mean; + } + + return (Rt); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::transformLine (const Eigen::Matrix &line_in, + Eigen::Matrix &line_out, + const Eigen::Transform &transformation) +{ + if (line_in.innerSize () != 6 || line_out.innerSize () != 6) + { + PCL_DEBUG ("transformLine: lines size != 6\n"); + return (false); + } + + Eigen::Matrix point, vector; + point << line_in.template head<3> (); + vector << line_out.template tail<3> (); + + pcl::transformPoint (point, point, transformation); + pcl::transformVector (vector, vector, transformation); + line_out << point, vector; + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::transformPlane (const Eigen::Matrix &plane_in, + Eigen::Matrix &plane_out, + const Eigen::Transform &transformation) +{ + Eigen::Hyperplane < Scalar, 3 > plane; + plane.coeffs () << plane_in; + plane.transform (transformation); + plane_out << plane.coeffs (); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::transformPlane (const pcl::ModelCoefficients::Ptr plane_in, + pcl::ModelCoefficients::Ptr plane_out, + const Eigen::Transform &transformation) +{ + Eigen::Matrix < Scalar, 4, 1 > v_plane_in (std::vector < Scalar > (plane_in->values.begin (), plane_in->values.end ()).data ()); + pcl::transformPlane (v_plane_in, v_plane_in, transformation); + plane_out->values.resize (4); + for (int i = 0; i < 4; i++) + plane_in->values[i] = v_plane_in[i]; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::checkCoordinateSystem (const Eigen::Matrix &line_x, + const Eigen::Matrix &line_y, + const Scalar norm_limit, + const Scalar dot_limit) +{ + if (line_x.innerSize () != 6 || line_y.innerSize () != 6) + { + PCL_DEBUG ("checkCoordinateSystem: lines size != 6\n"); + return (false); + } + + if (line_x.template head<3> () != line_y.template head<3> ()) + { + PCL_DEBUG ("checkCoorZdinateSystem: vector origins are different !\n"); + return (false); + } + + // Make a copy of vector directions + // X^Y = Z | Y^Z = X | Z^X = Y + Eigen::Matrix v_line_x (line_x.template tail<3> ()), + v_line_y (line_y.template tail<3> ()), + v_line_z (v_line_x.cross (v_line_y)); + + // Check vectors norms + if (v_line_x.norm () < 1 - norm_limit || v_line_x.norm () > 1 + norm_limit) + { + PCL_DEBUG ("checkCoordinateSystem: line_x norm %d != 1\n", v_line_x.norm ()); + return (false); + } + + if (v_line_y.norm () < 1 - norm_limit || v_line_y.norm () > 1 + norm_limit) + { + PCL_DEBUG ("checkCoordinateSystem: line_y norm %d != 1\n", v_line_y.norm ()); + return (false); + } + + if (v_line_z.norm () < 1 - norm_limit || v_line_z.norm () > 1 + norm_limit) + { + PCL_DEBUG ("checkCoordinateSystem: line_z norm %d != 1\n", v_line_z.norm ()); + return (false); + } + + // Check vectors perendicularity + if (std::abs (v_line_x.dot (v_line_y)) > dot_limit) + { + PCL_DEBUG ("checkCSAxis: line_x dot line_y %e = > %e\n", v_line_x.dot (v_line_y), dot_limit); + return (false); + } + + if (std::abs (v_line_x.dot (v_line_z)) > dot_limit) + { + PCL_DEBUG ("checkCSAxis: line_x dot line_z = %e > %e\n", v_line_x.dot (v_line_z), dot_limit); + return (false); + } + + if (std::abs (v_line_y.dot (v_line_z)) > dot_limit) + { + PCL_DEBUG ("checkCSAxis: line_y dot line_z = %e > %e\n", v_line_y.dot (v_line_z), dot_limit); + return (false); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::transformBetween2CoordinateSystems (const Eigen::Matrix from_line_x, + const Eigen::Matrix from_line_y, + const Eigen::Matrix to_line_x, + const Eigen::Matrix to_line_y, + Eigen::Transform &transformation) +{ + if (from_line_x.innerSize () != 6 || from_line_y.innerSize () != 6 || to_line_x.innerSize () != 6 || to_line_y.innerSize () != 6) + { + PCL_DEBUG ("transformBetween2CoordinateSystems: lines size != 6\n"); + return (false); + } + + // Check if coordinate systems are valid + if (!pcl::checkCoordinateSystem (from_line_x, from_line_y) || !pcl::checkCoordinateSystem (to_line_x, to_line_y)) + { + PCL_DEBUG ("transformBetween2CoordinateSystems: coordinate systems invalid !\n"); + return (false); + } + + // Convert lines into Vector3 : + Eigen::Matrix fr0 (from_line_x.template head<3>()), + fr1 (from_line_x.template head<3>() + from_line_x.template tail<3>()), + fr2 (from_line_y.template head<3>() + from_line_y.template tail<3>()), + + to0 (to_line_x.template head<3>()), + to1 (to_line_x.template head<3>() + to_line_x.template tail<3>()), + to2 (to_line_y.template head<3>() + to_line_y.template tail<3>()); + + // Code is inspired from http://stackoverflow.com/a/15277421/1816078 + // Define matrices and points : + Eigen::Transform T2, T3 = Eigen::Transform::Identity (); + Eigen::Matrix x1, y1, z1, x2, y2, z2; + + // Axes of the coordinate system "fr" + x1 = (fr1 - fr0).normalized (); // the versor (unitary vector) of the (fr1-fr0) axis vector + y1 = (fr2 - fr0).normalized (); + + // Axes of the coordinate system "to" + x2 = (to1 - to0).normalized (); + y2 = (to2 - to0).normalized (); + + // Transform from CS1 to CS2 + // Note: if fr0 == (0,0,0) --> CS1 == CS2 --> T2 = Identity + T2.linear () << x1, y1, x1.cross (y1); + + // Transform from CS1 to CS3 + T3.linear () << x2, y2, x2.cross (y2); + + // Identity matrix = transform to CS2 to CS3 + // Note: if CS1 == CS2 --> transformation = T3 + transformation = Eigen::Transform::Identity (); + transformation.linear () = T3.linear () * T2.linear ().inverse (); + transformation.translation () = to0 - (transformation.linear () * fr0); + return (true); +} + +#endif //PCL_COMMON_EIGEN_IMPL_HPP_ + diff --git a/pcl-1.7/pcl/common/impl/file_io.hpp b/pcl-1.7/pcl/common/impl/file_io.hpp new file mode 100644 index 0000000..a7141ce --- /dev/null +++ b/pcl-1.7/pcl/common/impl/file_io.hpp @@ -0,0 +1,90 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR a PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_COMMON_FILE_IO_IMPL_HPP_ +#define PCL_COMMON_FILE_IO_IMPL_HPP_ + +namespace pcl +{ + +#ifndef _WIN32 + void getAllPcdFilesInDirectory(const std::string& directory, std::vector& file_names) + { + DIR *dp; + struct dirent *dirp; + if((dp = opendir(directory.c_str())) == NULL) { + std::cerr << "Could not open directory.\n"; + return; + } + while ((dirp = readdir(dp)) != NULL) { + if (dirp->d_type == DT_REG) // Only regular files + { + std::string file_name = dirp->d_name; + if (file_name.substr(file_name.size()-4, 4)==".pcd") + file_names.push_back(dirp->d_name); + } + } + closedir(dp); + std::sort(file_names.begin(), file_names.end()); + //for (unsigned int i=0; i(-1)) + 1; + return input.substr(filename_start, input.size()-filename_start); +} + +std::string getFilenameWithoutExtension(const std::string& input) +{ + size_t dot_position = input.find_last_of('.', input.size()); + return input.substr(0, dot_position); +} + +std::string getFileExtension(const std::string& input) +{ + size_t dot_position = input.find_last_of('.', input.size()); + return input.substr(dot_position+1, input.size()); +} + +} // namespace end + +#endif + diff --git a/pcl-1.7/pcl/common/impl/gaussian.hpp b/pcl-1.7/pcl/common/impl/gaussian.hpp new file mode 100644 index 0000000..ef09383 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/gaussian.hpp @@ -0,0 +1,113 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_GAUSSIAN_KERNEL_IMPL +#define PCL_GAUSSIAN_KERNEL_IMPL + +#include + +template void +pcl::GaussianKernel::convolveRows(const pcl::PointCloud &input, + boost::function field_accessor, + const Eigen::VectorXf& kernel, + pcl::PointCloud &output) const +{ + assert(kernel.size () % 2 == 1); + int kernel_width = kernel.size () -1; + int radius = kernel.size () / 2.0; + if(output.height < input.height || output.width < input.width) + { + output.width = input.width; + output.height = input.height; + output.points.resize (input.height * input.width); + } + + int i; + for(int j = 0; j < input.height; j++) + { + for (i = 0 ; i < radius ; i++) + output (i,j) = 0; + + for ( ; i < input.width - radius ; i++) { + output (i,j) = 0; + for (int k = kernel_width, l = i - radius; k >= 0 ; k--, l++) + output (i,j) += field_accessor (input (l,j)) * kernel[k]; + } + + for ( ; i < input.width ; i++) + output (i,j) = 0; + } +} + +template void +pcl::GaussianKernel::convolveCols(const pcl::PointCloud &input, + boost::function field_accessor, + const Eigen::VectorXf& kernel, + pcl::PointCloud &output) const +{ + assert(kernel.size () % 2 == 1); + int kernel_width = kernel.size () -1; + int radius = kernel.size () / 2.0; + if(output.height < input.height || output.width < input.width) + { + output.width = input.width; + output.height = input.height; + output.points.resize (input.height * input.width); + } + + int j; + for(int i = 0; i < input.width; i++) + { + for (j = 0 ; j < radius ; j++) + output (i,j) = 0; + + for ( ; j < input.height - radius ; j++) { + output (i,j) = 0; + for (int k = kernel_width, l = j - radius ; k >= 0 ; k--, l++) + { + output (i,j) += field_accessor (input (i,l)) * kernel[k]; + } + } + + for ( ; j < input.height ; j++) + output (i,j) = 0; + } +} + +#endif diff --git a/pcl-1.7/pcl/common/impl/generate.hpp b/pcl-1.7/pcl/common/impl/generate.hpp new file mode 100644 index 0000000..110b92a --- /dev/null +++ b/pcl-1.7/pcl/common/impl/generate.hpp @@ -0,0 +1,291 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_COMMON_GENERATE_HPP_ +#define PCL_COMMON_GENERATE_HPP_ + +#include + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::common::CloudGenerator::CloudGenerator () + : x_generator_ () + , y_generator_ () + , z_generator_ () +{} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::common::CloudGenerator::CloudGenerator (const GeneratorParameters& params) +{ + setParameters (params); +} + + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::common::CloudGenerator::CloudGenerator (const GeneratorParameters& x_params, + const GeneratorParameters& y_params, + const GeneratorParameters& z_params) + : x_generator_ (x_params) + , y_generator_ (y_params) + , z_generator_ (z_params) +{} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::common::CloudGenerator::setParameters (const GeneratorParameters& params) +{ + GeneratorParameters y_params = params; + y_params.seed += 1; + GeneratorParameters z_params = y_params; + z_params.seed += 1; + x_generator_.setParameters (params); + y_generator_.setParameters (y_params); + z_generator_.setParameters (z_params); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::common::CloudGenerator::setParametersForX (const GeneratorParameters& x_params) +{ + x_generator_.setParameters (x_params); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::common::CloudGenerator::setParametersForY (const GeneratorParameters& y_params) +{ + y_generator_.setParameters (y_params); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::common::CloudGenerator::setParametersForZ (const GeneratorParameters& z_params) +{ + z_generator_.setParameters (z_params); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template const typename pcl::common::CloudGenerator::GeneratorParameters& +pcl::common::CloudGenerator::getParametersForX () const +{ + x_generator_.getParameters (); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template const typename pcl::common::CloudGenerator::GeneratorParameters& +pcl::common::CloudGenerator::getParametersForY () const +{ + y_generator_.getParameters (); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template const typename pcl::common::CloudGenerator::GeneratorParameters& +pcl::common::CloudGenerator::getParametersForZ () const +{ + z_generator_.getParameters (); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template PointT +pcl::common::CloudGenerator::get () +{ + PointT p; + p.x = x_generator_.run (); + p.y = y_generator_.run (); + p.z = z_generator_.run (); + return (p); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::common::CloudGenerator::fill (pcl::PointCloud& cloud) +{ + return (fill (cloud.width, cloud.height, cloud)); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::common::CloudGenerator::fill (int width, int height, pcl::PointCloud& cloud) +{ + if (width < 1) + { + PCL_ERROR ("[pcl::common::CloudGenerator] Cloud width must be >= 1!\n"); + return (-1); + } + + if (height < 1) + { + PCL_ERROR ("[pcl::common::CloudGenerator] Cloud height must be >= 1!\n"); + return (-1); + } + + if (!cloud.empty ()) + { + PCL_WARN ("[pcl::common::CloudGenerator] Cloud data will be erased with new data!\n"); + } + + cloud.width = width; + cloud.height = height; + cloud.resize (cloud.width * cloud.height); + cloud.is_dense = true; + for (typename pcl::PointCloud::iterator points_it = cloud.begin (); + points_it != cloud.end (); + ++points_it) + { + points_it->x = x_generator_.run (); + points_it->y = y_generator_.run (); + points_it->z = z_generator_.run (); + } + return (0); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::common::CloudGenerator::CloudGenerator () + : x_generator_ () + , y_generator_ () +{} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::common::CloudGenerator::CloudGenerator (const GeneratorParameters& x_params, + const GeneratorParameters& y_params) + : x_generator_ (x_params) + , y_generator_ (y_params) +{} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::common::CloudGenerator::CloudGenerator (const GeneratorParameters& params) +{ + setParameters (params); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::common::CloudGenerator::setParameters (const GeneratorParameters& params) +{ + x_generator_.setParameters (params); + GeneratorParameters y_params = params; + y_params.seed += 1; + y_generator_.setParameters (y_params); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::common::CloudGenerator::setParametersForX (const GeneratorParameters& x_params) +{ + x_generator_.setParameters (x_params); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::common::CloudGenerator::setParametersForY (const GeneratorParameters& y_params) +{ + y_generator_.setParameters (y_params); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template const typename pcl::common::CloudGenerator::GeneratorParameters& +pcl::common::CloudGenerator::getParametersForX () const +{ + x_generator_.getParameters (); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template const typename pcl::common::CloudGenerator::GeneratorParameters& +pcl::common::CloudGenerator::getParametersForY () const +{ + y_generator_.getParameters (); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template pcl::PointXY +pcl::common::CloudGenerator::get () +{ + pcl::PointXY p; + p.x = x_generator_.run (); + p.y = y_generator_.run (); + return (p); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::common::CloudGenerator::fill (pcl::PointCloud& cloud) +{ + return (fill (cloud.width, cloud.height, cloud)); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::common::CloudGenerator::fill (int width, int height, pcl::PointCloud& cloud) +{ + if (width < 1) + { + PCL_ERROR ("[pcl::common::CloudGenerator] Cloud width must be >= 1\n!"); + return (-1); + } + + if (height < 1) + { + PCL_ERROR ("[pcl::common::CloudGenerator] Cloud height must be >= 1\n!"); + return (-1); + } + + if (!cloud.empty ()) + PCL_WARN ("[pcl::common::CloudGenerator] Cloud data will be erased with new data\n!"); + + cloud.width = width; + cloud.height = height; + cloud.resize (cloud.width * cloud.height); + cloud.is_dense = true; + + for (pcl::PointCloud::iterator points_it = cloud.begin (); + points_it != cloud.end (); + ++points_it) + { + points_it->x = x_generator_.run (); + points_it->y = y_generator_.run (); + } + return (0); +} + +#endif diff --git a/pcl-1.7/pcl/common/impl/intensity.hpp b/pcl-1.7/pcl/common/impl/intensity.hpp new file mode 100644 index 0000000..227c127 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/intensity.hpp @@ -0,0 +1,279 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_COMMON_INTENSITY_FIELD_ACCESSOR_IMPL_HPP +#define PCL_COMMON_INTENSITY_FIELD_ACCESSOR_IMPL_HPP + +#include +namespace pcl +{ + namespace common + { + template<> + struct IntensityFieldAccessor + { + inline float + operator () (const pcl::PointNormal &p) const + { + return (p.curvature); + } + + inline void + get (const pcl::PointNormal &p, float &intensity) const + { + intensity = p.curvature; + } + + inline void + set (pcl::PointNormal &p, float intensity) const + { + p.curvature = intensity; + } + + inline void + demean (pcl::PointNormal& p, float value) const + { + p.curvature -= value; + } + + inline void + add (pcl::PointNormal& p, float value) const + { + p.curvature += value; + } + }; + + template<> + struct IntensityFieldAccessor + { + inline float + operator () (const pcl::PointXYZ &p) const + { + return (p.z); + } + + inline void + get (const pcl::PointXYZ &p, float &intensity) const + { + intensity = p.z; + } + + inline void + set (pcl::PointXYZ &p, float intensity) const + { + p.z = intensity; + } + + inline void + demean (pcl::PointXYZ& p, float value) const + { + p.z -= value; + } + + inline void + add (pcl::PointXYZ& p, float value) const + { + p.z += value; + } + }; + + template<> + struct IntensityFieldAccessor + { + inline float + operator () (const pcl::PointXYZRGB &p) const + { + return (static_cast (299*p.r + 587*p.g + 114*p.b) * 0.001f); + } + + inline void + get (const pcl::PointXYZRGB &p, float& intensity) const + { + intensity = static_cast (299*p.r + 587*p.g + 114*p.b) * 0.001f; + } + + inline void + set (pcl::PointXYZRGB &p, float intensity) const + { + p.r = static_cast (intensity * 3.34448160535f); // 1000 / 299 + p.g = static_cast (intensity * 1.70357751278f); // 1000 / 587 + p.b = static_cast (intensity * 8.77192982456f); // 1000 / 114 + } + + inline void + demean (pcl::PointXYZRGB& p, float value) const + { + float intensity = this->operator () (p); + intensity -= value; + set (p, intensity); + } + + inline void + add (pcl::PointXYZRGB& p, float value) const + { + float intensity = this->operator () (p); + intensity += value; + set (p, intensity); + } + }; + + template<> + struct IntensityFieldAccessor + { + inline float + operator () (const pcl::PointXYZRGBA &p) const + { + return (static_cast (299*p.r + 587*p.g + 114*p.b) * 0.001f); + } + + inline void + get (const pcl::PointXYZRGBA &p, float& intensity) const + { + intensity = static_cast (299*p.r + 587*p.g + 114*p.b) * 0.001f; + } + + inline void + set (pcl::PointXYZRGBA &p, float intensity) const + { + p.r = static_cast (intensity * 3.34448160535f); // 1000 / 299 + p.g = static_cast (intensity * 1.70357751278f); // 1000 / 587 + p.b = static_cast (intensity * 8.77192982456f); // 1000 / 114 + } + + inline void + demean (pcl::PointXYZRGBA& p, float value) const + { + float intensity = this->operator () (p); + intensity -= value; + set (p, intensity); + } + + inline void + add (pcl::PointXYZRGBA& p, float value) const + { + float intensity = this->operator () (p); + intensity += value; + set (p, intensity); + } + }; + + template<> + struct IntensityFieldAccessor + { + inline float + operator () (const pcl::PointXYZRGBNormal &p) const + { + return (static_cast (299*p.r + 587*p.g + 114*p.b) * 0.001f); + } + + inline void + get (const pcl::PointXYZRGBNormal &p, float& intensity) const + { + intensity = static_cast (299*p.r + 587*p.g + 114*p.b) * 0.001f; + } + + inline void + set (pcl::PointXYZRGBNormal &p, float intensity) const + { + p.r = static_cast (intensity * 3.34448160535f); // 1000 / 299 + p.g = static_cast (intensity * 1.70357751278f); // 1000 / 587 + p.b = static_cast (intensity * 8.77192982456f); // 1000 / 114 + } + + inline void + demean (pcl::PointXYZRGBNormal &p, float value) const + { + float intensity = this->operator () (p); + intensity -= value; + set (p, intensity); + } + + inline void + add (pcl::PointXYZRGBNormal &p, float value) const + { + float intensity = this->operator () (p); + intensity += value; + set (p, intensity); + } + }; + + template<> + struct IntensityFieldAccessor + { + inline float + operator () (const pcl::PointXYZRGBL &p) const + { + return (static_cast (299*p.r + 587*p.g + 114*p.b) * 0.001f); + } + + inline void + get (const pcl::PointXYZRGBL &p, float& intensity) const + { + intensity = static_cast (299*p.r + 587*p.g + 114*p.b) * 0.001f; + } + + inline void + set (pcl::PointXYZRGBL &p, float intensity) const + { + p.r = static_cast (intensity * 3.34448160535f); // 1000 / 299 + p.g = static_cast (intensity * 1.70357751278f); // 1000 / 587 + p.b = static_cast (intensity * 8.77192982456f); // 1000 / 114 + } + + inline void + demean (pcl::PointXYZRGBL& p, float value) const + { + float intensity = this->operator () (p); + intensity -= value; + set (p, intensity); + } + + inline void + add (pcl::PointXYZRGBL& p, float value) const + { + float intensity = this->operator () (p); + intensity += value; + set (p, intensity); + } + }; + } +} + +#endif diff --git a/pcl-1.7/pcl/common/impl/intersections.hpp b/pcl-1.7/pcl/common/impl/intersections.hpp new file mode 100644 index 0000000..619a888 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/intersections.hpp @@ -0,0 +1,172 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_COMMON_INTERSECTIONS_IMPL_HPP_ +#define PCL_COMMON_INTERSECTIONS_IMPL_HPP_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////// + +bool +pcl::lineWithLineIntersection (const Eigen::VectorXf &line_a, + const Eigen::VectorXf &line_b, + Eigen::Vector4f &point, double sqr_eps) +{ + Eigen::Vector4f p1, p2; + lineToLineSegment (line_a, line_b, p1, p2); + + // If the segment size is smaller than a pre-given epsilon... + double sqr_dist = (p1 - p2).squaredNorm (); + if (sqr_dist < sqr_eps) + { + point = p1; + return (true); + } + point.setZero (); + return (false); +} + +bool +pcl::lineWithLineIntersection (const pcl::ModelCoefficients &line_a, + const pcl::ModelCoefficients &line_b, + Eigen::Vector4f &point, double sqr_eps) +{ + Eigen::VectorXf coeff1 = Eigen::VectorXf::Map (&line_a.values[0], line_a.values.size ()); + Eigen::VectorXf coeff2 = Eigen::VectorXf::Map (&line_b.values[0], line_b.values.size ()); + return (lineWithLineIntersection (coeff1, coeff2, point, sqr_eps)); +} + +template bool +pcl::planeWithPlaneIntersection (const Eigen::Matrix &plane_a, + const Eigen::Matrix &plane_b, + Eigen::Matrix &line, + double angular_tolerance) +{ + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix Vector4; + typedef Eigen::Matrix Vector5; + typedef Eigen::Matrix Matrix5; + + // Normalize plane normals + Vector3 plane_a_norm (plane_a.template head<3> ()); + Vector3 plane_b_norm (plane_b.template head<3> ()); + plane_a_norm.normalize (); + plane_b_norm.normalize (); + + // Test if planes are parallel (test_cos == 1) + double test_cos = plane_a_norm.dot (plane_b_norm); + double upper_limit = 1 + angular_tolerance; + double lower_limit = 1 - angular_tolerance; + + if ((test_cos > lower_limit) && (test_cos < upper_limit)) + { + PCL_DEBUG ("Plane A and Plane B are parallel.\n"); + return (false); + } + + Vector4 line_direction = plane_a.cross3 (plane_b); + line_direction.normalized(); + + // Construct system of equations using lagrange multipliers with one objective function and two constraints + Matrix5 langrange_coefs; + langrange_coefs << 2,0,0, plane_a[0], plane_b[0], + 0,2,0, plane_a[1], plane_b[1], + 0,0,2, plane_a[2], plane_b[2], + plane_a[0], plane_a[1], plane_a[2], 0, 0, + plane_b[0], plane_b[1], plane_b[2], 0, 0; + + Vector5 b; + b << 0, 0, 0, -plane_a[3], -plane_b[3]; + + line.resize(6); + // Solve for the lagrange multipliers + line.template head<3>() = langrange_coefs.colPivHouseholderQr().solve(b).template head<3> (); + line.template tail<3>() = line_direction.template head<3>(); + return (true); +} + +template bool +pcl::threePlanesIntersection (const Eigen::Matrix &plane_a, + const Eigen::Matrix &plane_b, + const Eigen::Matrix &plane_c, + Eigen::Matrix &intersection_point, + double determinant_tolerance) +{ + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix Matrix3; + + // TODO: Using Eigen::HyperPlanes is better to solve this problem + // Check if some planes are parallel + Matrix3 normals_in_lines; + + for (int i = 0; i < 3; i++) + { + normals_in_lines (i, 0) = plane_a[i]; + normals_in_lines (i, 1) = plane_b[i]; + normals_in_lines (i, 2) = plane_c[i]; + } + + Scalar determinant = normals_in_lines.determinant (); + if (fabs (determinant) < determinant_tolerance) + { + // det ~= 0 + PCL_DEBUG ("At least two planes are parralel.\n"); + return (false); + } + + // Left part of the 3 equations + Matrix3 left_member; + + for (int i = 0; i < 3; i++) + { + left_member (0, i) = plane_a[i]; + left_member (1, i) = plane_b[i]; + left_member (2, i) = plane_c[i]; + } + + // Right side of the 3 equations + Vector3 right_member; + right_member << -plane_a[3], -plane_b[3], -plane_c[3]; + + // Solve the system + intersection_point = left_member.fullPivLu ().solve (right_member); + return (true); +} + +#endif //PCL_COMMON_INTERSECTIONS_IMPL_HPP diff --git a/pcl-1.7/pcl/common/impl/io.hpp b/pcl-1.7/pcl/common/impl/io.hpp new file mode 100644 index 0000000..9ddd779 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/io.hpp @@ -0,0 +1,502 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_IO_IMPL_IO_HPP_ +#define PCL_IO_IMPL_IO_HPP_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::getFieldIndex (const pcl::PointCloud &, + const std::string &field_name, + std::vector &fields) +{ + fields.clear (); + // Get the fields list + pcl::for_each_type::type>(pcl::detail::FieldAdder(fields)); + for (size_t d = 0; d < fields.size (); ++d) + if (fields[d].name == field_name) + return (static_cast(d)); + return (-1); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::getFieldIndex (const std::string &field_name, + std::vector &fields) +{ + fields.clear (); + // Get the fields list + pcl::for_each_type::type>(pcl::detail::FieldAdder(fields)); + for (size_t d = 0; d < fields.size (); ++d) + if (fields[d].name == field_name) + return (static_cast(d)); + return (-1); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::getFields (const pcl::PointCloud &, std::vector &fields) +{ + fields.clear (); + // Get the fields list + pcl::for_each_type::type>(pcl::detail::FieldAdder(fields)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::getFields (std::vector &fields) +{ + fields.clear (); + // Get the fields list + pcl::for_each_type::type>(pcl::detail::FieldAdder(fields)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template std::string +pcl::getFieldsList (const pcl::PointCloud &) +{ + // Get the fields list + std::vector fields; + pcl::for_each_type::type>(pcl::detail::FieldAdder(fields)); + std::string result; + for (size_t i = 0; i < fields.size () - 1; ++i) + result += fields[i].name + " "; + result += fields[fields.size () - 1].name; + return (result); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::copyPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out) +{ + // Allocate enough space and copy the basics + cloud_out.header = cloud_in.header; + cloud_out.width = cloud_in.width; + cloud_out.height = cloud_in.height; + cloud_out.is_dense = cloud_in.is_dense; + cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_; + cloud_out.sensor_origin_ = cloud_in.sensor_origin_; + cloud_out.points.resize (cloud_in.points.size ()); + + if (isSamePointType ()) + // Copy the whole memory block + memcpy (&cloud_out.points[0], &cloud_in.points[0], cloud_in.points.size () * sizeof (PointInT)); + else + // Iterate over each point + for (size_t i = 0; i < cloud_in.points.size (); ++i) + copyPoint (cloud_in.points[i], cloud_out.points[i]); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::copyPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out) +{ + // Do we want to copy everything? + if (indices.size () == cloud_in.points.size ()) + { + cloud_out = cloud_in; + return; + } + + // Allocate enough space and copy the basics + cloud_out.points.resize (indices.size ()); + cloud_out.header = cloud_in.header; + cloud_out.width = static_cast(indices.size ()); + cloud_out.height = 1; + cloud_out.is_dense = cloud_in.is_dense; + cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_; + cloud_out.sensor_origin_ = cloud_in.sensor_origin_; + + // Iterate over each point + for (size_t i = 0; i < indices.size (); ++i) + cloud_out.points[i] = cloud_in.points[indices[i]]; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::copyPointCloud (const pcl::PointCloud &cloud_in, + const std::vector > &indices, + pcl::PointCloud &cloud_out) +{ + // Do we want to copy everything? + if (indices.size () == cloud_in.points.size ()) + { + cloud_out = cloud_in; + return; + } + + // Allocate enough space and copy the basics + cloud_out.points.resize (indices.size ()); + cloud_out.header = cloud_in.header; + cloud_out.width = static_cast (indices.size ()); + cloud_out.height = 1; + cloud_out.is_dense = cloud_in.is_dense; + cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_; + cloud_out.sensor_origin_ = cloud_in.sensor_origin_; + + // Iterate over each point + for (size_t i = 0; i < indices.size (); ++i) + cloud_out.points[i] = cloud_in.points[indices[i]]; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::copyPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out) +{ + // Allocate enough space and copy the basics + cloud_out.points.resize (indices.size ()); + cloud_out.header = cloud_in.header; + cloud_out.width = uint32_t (indices.size ()); + cloud_out.height = 1; + cloud_out.is_dense = cloud_in.is_dense; + cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_; + cloud_out.sensor_origin_ = cloud_in.sensor_origin_; + + // Iterate over each point + for (size_t i = 0; i < indices.size (); ++i) + copyPoint (cloud_in.points[indices[i]], cloud_out.points[i]); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::copyPointCloud (const pcl::PointCloud &cloud_in, + const std::vector > &indices, + pcl::PointCloud &cloud_out) +{ + // Allocate enough space and copy the basics + cloud_out.points.resize (indices.size ()); + cloud_out.header = cloud_in.header; + cloud_out.width = static_cast (indices.size ()); + cloud_out.height = 1; + cloud_out.is_dense = cloud_in.is_dense; + cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_; + cloud_out.sensor_origin_ = cloud_in.sensor_origin_; + + // Iterate over each point + for (size_t i = 0; i < indices.size (); ++i) + copyPoint (cloud_in.points[indices[i]], cloud_out.points[i]); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::copyPointCloud (const pcl::PointCloud &cloud_in, + const pcl::PointIndices &indices, + pcl::PointCloud &cloud_out) +{ + // Do we want to copy everything? + if (indices.indices.size () == cloud_in.points.size ()) + { + cloud_out = cloud_in; + return; + } + + // Allocate enough space and copy the basics + cloud_out.points.resize (indices.indices.size ()); + cloud_out.header = cloud_in.header; + cloud_out.width = indices.indices.size (); + cloud_out.height = 1; + cloud_out.is_dense = cloud_in.is_dense; + cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_; + cloud_out.sensor_origin_ = cloud_in.sensor_origin_; + + // Iterate over each point + for (size_t i = 0; i < indices.indices.size (); ++i) + cloud_out.points[i] = cloud_in.points[indices.indices[i]]; +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::copyPointCloud (const pcl::PointCloud &cloud_in, + const pcl::PointIndices &indices, + pcl::PointCloud &cloud_out) +{ + copyPointCloud (cloud_in, indices.indices, cloud_out); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::copyPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out) +{ + int nr_p = 0; + for (size_t i = 0; i < indices.size (); ++i) + nr_p += indices[i].indices.size (); + + // Do we want to copy everything? Remember we assume UNIQUE indices + if (nr_p == cloud_in.points.size ()) + { + cloud_out = cloud_in; + return; + } + + // Allocate enough space and copy the basics + cloud_out.points.resize (nr_p); + cloud_out.header = cloud_in.header; + cloud_out.width = nr_p; + cloud_out.height = 1; + cloud_out.is_dense = cloud_in.is_dense; + cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_; + cloud_out.sensor_origin_ = cloud_in.sensor_origin_; + + // Iterate over each cluster + int cp = 0; + for (size_t cc = 0; cc < indices.size (); ++cc) + { + // Iterate over each idx + for (size_t i = 0; i < indices[cc].indices.size (); ++i) + { + // Iterate over each dimension + cloud_out.points[cp] = cloud_in.points[indices[cc].indices[i]]; + cp++; + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::copyPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out) +{ + int nr_p = 0; + for (size_t i = 0; i < indices.size (); ++i) + nr_p += indices[i].indices.size (); + + // Do we want to copy everything? Remember we assume UNIQUE indices + if (nr_p == cloud_in.points.size ()) + { + copyPointCloud (cloud_in, cloud_out); + return; + } + + // Allocate enough space and copy the basics + cloud_out.points.resize (nr_p); + cloud_out.header = cloud_in.header; + cloud_out.width = nr_p; + cloud_out.height = 1; + cloud_out.is_dense = cloud_in.is_dense; + cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_; + cloud_out.sensor_origin_ = cloud_in.sensor_origin_; + + // Iterate over each cluster + int cp = 0; + for (size_t cc = 0; cc < indices.size (); ++cc) + { + // Iterate over each idx + for (size_t i = 0; i < indices[cc].indices.size (); ++i) + { + copyPoint (cloud_in.points[indices[cc].indices[i]], cloud_out.points[cp]); + ++cp; + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::concatenateFields (const pcl::PointCloud &cloud1_in, + const pcl::PointCloud &cloud2_in, + pcl::PointCloud &cloud_out) +{ + typedef typename pcl::traits::fieldList::type FieldList1; + typedef typename pcl::traits::fieldList::type FieldList2; + + if (cloud1_in.points.size () != cloud2_in.points.size ()) + { + PCL_ERROR ("[pcl::concatenateFields] The number of points in the two input datasets differs!\n"); + return; + } + + // Resize the output dataset + cloud_out.points.resize (cloud1_in.points.size ()); + cloud_out.header = cloud1_in.header; + cloud_out.width = cloud1_in.width; + cloud_out.height = cloud1_in.height; + if (!cloud1_in.is_dense || !cloud2_in.is_dense) + cloud_out.is_dense = false; + else + cloud_out.is_dense = true; + + // Iterate over each point + for (size_t i = 0; i < cloud_out.points.size (); ++i) + { + // Iterate over each dimension + pcl::for_each_type (pcl::NdConcatenateFunctor (cloud1_in.points[i], cloud_out.points[i])); + pcl::for_each_type (pcl::NdConcatenateFunctor (cloud2_in.points[i], cloud_out.points[i])); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::copyPointCloud (const pcl::PointCloud &cloud_in, pcl::PointCloud &cloud_out, + int top, int bottom, int left, int right, pcl::InterpolationType border_type, const PointT& value) +{ + if (top < 0 || left < 0 || bottom < 0 || right < 0) + { + std::string faulty = (top < 0) ? "top" : (left < 0) ? "left" : (bottom < 0) ? "bottom" : "right"; + PCL_THROW_EXCEPTION (pcl::BadArgumentException, "[pcl::copyPointCloud] error: " << faulty << " must be positive!"); + return; + } + + if (top == 0 && left == 0 && bottom == 0 && right == 0) + cloud_out = cloud_in; + else + { + // Allocate enough space and copy the basics + cloud_out.header = cloud_in.header; + cloud_out.width = cloud_in.width + left + right; + cloud_out.height = cloud_in.height + top + bottom; + if (cloud_out.size () != cloud_out.width * cloud_out.height) + cloud_out.resize (cloud_out.width * cloud_out.height); + cloud_out.is_dense = cloud_in.is_dense; + cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_; + cloud_out.sensor_origin_ = cloud_in.sensor_origin_; + + if (border_type == pcl::BORDER_TRANSPARENT) + { + const PointT* in = &(cloud_in.points[0]); + PointT* out = &(cloud_out.points[0]); + PointT* out_inner = out + cloud_out.width*top + left; + for (uint32_t i = 0; i < cloud_in.height; i++, out_inner += cloud_out.width, in += cloud_in.width) + { + if (out_inner != in) + memcpy (out_inner, in, cloud_in.width * sizeof (PointT)); + } + } + else + { + // Copy the data + if (border_type != pcl::BORDER_CONSTANT) + { + try + { + std::vector padding (cloud_out.width - cloud_in.width); + int right = cloud_out.width - cloud_in.width - left; + int bottom = cloud_out.height - cloud_in.height - top; + + for (int i = 0; i < left; i++) + padding[i] = pcl::interpolatePointIndex (i-left, cloud_in.width, border_type); + + for (int i = 0; i < right; i++) + padding[i+left] = pcl::interpolatePointIndex (cloud_in.width+i, cloud_in.width, border_type); + + const PointT* in = &(cloud_in.points[0]); + PointT* out = &(cloud_out.points[0]); + PointT* out_inner = out + cloud_out.width*top + left; + + for (uint32_t i = 0; i < cloud_in.height; i++, out_inner += cloud_out.width, in += cloud_in.width) + { + if (out_inner != in) + memcpy (out_inner, in, cloud_in.width * sizeof (PointT)); + + for (int j = 0; j < left; j++) + out_inner[j - left] = in[padding[j]]; + + for (int j = 0; j < right; j++) + out_inner[j + cloud_in.width] = in[padding[j + left]]; + } + + for (int i = 0; i < top; i++) + { + int j = pcl::interpolatePointIndex (i - top, cloud_in.height, border_type); + memcpy (out + i*cloud_out.width, + out + (j+top) * cloud_out.width, + sizeof (PointT) * cloud_out.width); + } + + for (int i = 0; i < bottom; i++) + { + int j = pcl::interpolatePointIndex (i + cloud_in.height, cloud_in.height, border_type); + memcpy (out + (i + cloud_in.height + top)*cloud_out.width, + out + (j+top)*cloud_out.width, + cloud_out.width * sizeof (PointT)); + } + } + catch (pcl::BadArgumentException &e) + { + PCL_ERROR ("[pcl::copyPointCloud] Unhandled interpolation type %d!\n", border_type); + } + } + else + { + int right = cloud_out.width - cloud_in.width - left; + int bottom = cloud_out.height - cloud_in.height - top; + std::vector buff (cloud_out.width, value); + PointT* buff_ptr = &(buff[0]); + const PointT* in = &(cloud_in.points[0]); + PointT* out = &(cloud_out.points[0]); + PointT* out_inner = out + cloud_out.width*top + left; + + for (uint32_t i = 0; i < cloud_in.height; i++, out_inner += cloud_out.width, in += cloud_in.width) + { + if (out_inner != in) + memcpy (out_inner, in, cloud_in.width * sizeof (PointT)); + + memcpy (out_inner - left, buff_ptr, left * sizeof (PointT)); + memcpy (out_inner + cloud_in.width, buff_ptr, right * sizeof (PointT)); + } + + for (int i = 0; i < top; i++) + { + memcpy (out + i*cloud_out.width, buff_ptr, cloud_out.width * sizeof (PointT)); + } + + for (int i = 0; i < bottom; i++) + { + memcpy (out + (i + cloud_in.height + top)*cloud_out.width, + buff_ptr, + cloud_out.width * sizeof (PointT)); + } + } + } + } +} + +#endif // PCL_IO_IMPL_IO_H_ + diff --git a/pcl-1.7/pcl/common/impl/norms.hpp b/pcl-1.7/pcl/common/impl/norms.hpp new file mode 100644 index 0000000..9d23116 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/norms.hpp @@ -0,0 +1,242 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR a PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_COMMON_NORMS_IMPL_HPP_ +#define PCL_COMMON_NORMS_IMPL_HPP_ + +#include +#include + +namespace pcl +{ + +template inline float +selectNorm (FloatVectorT a, FloatVectorT b, int dim, NormType norm_type) +{ + // {L1, L2_SQR, L2, LINF, JM, B, SUBLINEAR, CS, DIV, PF, K, KL, HIK}; + switch (norm_type) + { + case (L1): + return L1_Norm (a, b, dim); + case (L2_SQR): + return L2_Norm_SQR (a, b, dim); + case (L2): + return L2_Norm (a, b, dim); + case (LINF): + return Linf_Norm (a, b, dim); + case (JM): + return JM_Norm (a, b, dim); + case (B): + return B_Norm (a, b, dim); + case (SUBLINEAR): + return Sublinear_Norm (a, b, dim); + case (CS): + return CS_Norm (a, b, dim); + case (DIV): + return Div_Norm (a, b, dim); + case (KL): + return KL_Norm (a, b, dim); + case (HIK): + return HIK_Norm (a, b, dim); + + case (PF): + case (K): + default: + PCL_ERROR ("[pcl::selectNorm] For PF and K norms you have to explicitly call the method, as they need additional parameters\n"); + return -1; + } +} + + +template inline float +L1_Norm (FloatVectorT a, FloatVectorT b, int dim) +{ + float norm = 0.0f; + for (int i = 0; i < dim; ++i) + norm += fabsf(a[i] - b[i]); + return norm; +} + + +template inline float +L2_Norm_SQR (FloatVectorT a, FloatVectorT b, int dim) +{ + float norm = 0.0; + for (int i = 0; i < dim; ++i) + { + float diff = a[i] - b[i]; + norm += diff*diff; + } + return norm; +} + + +template inline float +L2_Norm (FloatVectorT a, FloatVectorT b, int dim) +{ + return sqrtf(L2_Norm_SQR(a, b, dim)); +} + + +template inline float +Linf_Norm (FloatVectorT a, FloatVectorT b, int dim) +{ + float norm = 0.0; + for (int i = 0; i < dim; ++i) + norm = (std::max)(fabsf(a[i] - b[i]), norm); + return norm; +} + + +template inline float +JM_Norm (FloatVectorT a, FloatVectorT b, int dim) +{ + float norm = 0.0; + + for (int i = 0; i < dim; ++i) + norm += (sqrtf (a[i]) - sqrtf (b[i])) * (sqrtf (a[i]) - sqrtf (b[i])); + + return sqrtf (norm); +} + + +template inline float +B_Norm (FloatVectorT a, FloatVectorT b, int dim) +{ + float norm = 0.0, result; + + for (int i = 0; i < dim; ++i) + norm += sqrtf (a[i] * b[i]); + + if (norm > 0) + result = -logf (norm); + else + result = 0; + + return result; +} + + +template inline float +Sublinear_Norm (FloatVectorT a, FloatVectorT b, int dim) +{ + float norm = 0.0; + + for (int i = 0; i < dim; ++i) + norm += sqrtf (fabsf (a[i] - b[i])); + + return norm; +} + + +template inline float +CS_Norm (FloatVectorT a, FloatVectorT b, int dim) +{ + float norm = 0.0; + + for (int i = 0; i < dim; ++i) + if ((a[i] + b[i]) != 0) + norm += (a[i] - b[i]) * (a[i] - b[i]) / (a[i] + b[i]); + else + norm += 0; + return norm; +} + + +template inline float +Div_Norm (FloatVectorT a, FloatVectorT b, int dim) +{ + float norm = 0.0; + + for (int i = 0; i < dim; ++i) + if ((a[i] / b[i]) > 0) + norm += (a[i] - b[i]) * logf (a[i] / b[i]); + else + norm += 0; + return norm; +} + + +template inline float +PF_Norm (FloatVectorT a, FloatVectorT b, int dim, float P1, float P2) +{ + float norm = 0.0; + + for (int i = 0; i < dim; ++i) + norm += (P1 * a[i] - P2 * b[i]) * (P1 * a[i] - P2 * b[i]); + return sqrtf (norm); +} + + +template inline float +K_Norm (FloatVectorT a, FloatVectorT b, int dim, float P1, float P2) +{ + float norm = 0.0; + + for (int i = 0; i < dim; ++i) + norm += fabsf (P1 * a[i] - P2 * b[i]); + return norm; +} + + +template inline float +KL_Norm (FloatVectorT a, FloatVectorT b, int dim) +{ + float norm = 0.0; + + for (int i = 0; i < dim; ++i) + if ( (b[i] != 0) && ((a[i] / b[i]) > 0) ) + norm += a[i] * logf (a[i] / b[i]); + else + norm += 0; + return norm; +} + + +template inline float +HIK_Norm(FloatVectorT a, FloatVectorT b, int dim) +{ + float norm = 0.0f; + for (int i = 0; i < dim; ++i) + norm += (std::min)(a[i], b[i]); + return norm; +} + +} +#endif + diff --git a/pcl-1.7/pcl/common/impl/pca.hpp b/pcl-1.7/pcl/common/impl/pca.hpp new file mode 100644 index 0000000..68d5b61 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/pca.hpp @@ -0,0 +1,257 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_PCA_IMPL_HPP +#define PCL_PCA_IMPL_HPP + +#include +#include +#include +#include +#include + +///////////////////////////////////////////////////////////////////////////////////////// +/** \brief Constructor with direct computation + * \param[in] cloud input m*n matrix (ie n vectors of R(m)) + * \param[in] basis_only flag to compute only the PCA basis + */ +template +pcl::PCA::PCA (const pcl::PointCloud &cloud, bool basis_only) +{ + Base (); + basis_only_ = basis_only; + setInputCloud (cloud.makeShared ()); + compute_done_ = initCompute (); +} + +///////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::PCA::initCompute () +{ + if(!Base::initCompute ()) + { + PCL_THROW_EXCEPTION (InitFailedException, "[pcl::PCA::initCompute] failed"); + return (false); + } + if(indices_->size () < 3) + { + PCL_THROW_EXCEPTION (InitFailedException, "[pcl::PCA::initCompute] number of points < 3"); + return (false); + } + + // Compute mean + mean_ = Eigen::Vector4f::Zero (); + compute3DCentroid (*input_, *indices_, mean_); + // Compute demeanished cloud + Eigen::MatrixXf cloud_demean; + demeanPointCloud (*input_, *indices_, mean_, cloud_demean); + assert (cloud_demean.cols () == int (indices_->size ())); + // Compute the product cloud_demean * cloud_demean^T + Eigen::Matrix3f alpha = static_cast (cloud_demean.topRows<3> () * cloud_demean.topRows<3> ().transpose ()); + + // Compute eigen vectors and values + Eigen::SelfAdjointEigenSolver evd (alpha); + // Organize eigenvectors and eigenvalues in ascendent order + for (int i = 0; i < 3; ++i) + { + eigenvalues_[i] = evd.eigenvalues () [2-i]; + eigenvectors_.col (i) = evd.eigenvectors ().col (2-i); + } + // If not basis only then compute the coefficients + + if (!basis_only_) + coefficients_ = eigenvectors_.transpose() * cloud_demean.topRows<3> (); + compute_done_ = true; + return (true); +} + +///////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::PCA::update (const PointT& input_point, FLAG flag) +{ + if (!compute_done_) + initCompute (); + if (!compute_done_) + PCL_THROW_EXCEPTION (InitFailedException, "[pcl::PCA::update] PCA initCompute failed"); + + Eigen::Vector3f input (input_point.x, input_point.y, input_point.z); + const size_t n = eigenvectors_.cols ();// number of eigen vectors + Eigen::VectorXf meanp = (float(n) * (mean_.head<3>() + input)) / float(n + 1); + Eigen::VectorXf a = eigenvectors_.transpose() * (input - mean_.head<3>()); + Eigen::VectorXf y = (eigenvectors_ * a) + mean_.head<3>(); + Eigen::VectorXf h = y - input; + if (h.norm() > 0) + h.normalize (); + else + h.setZero (); + float gamma = h.dot(input - mean_.head<3>()); + Eigen::MatrixXf D = Eigen::MatrixXf::Zero (a.size() + 1, a.size() + 1); + D.block(0,0,n,n) = a * a.transpose(); + D /= float(n)/float((n+1) * (n+1)); + for(std::size_t i=0; i < a.size(); i++) { + D(i,i)+= float(n)/float(n+1)*eigenvalues_(i); + D(D.rows()-1,i) = float(n) / float((n+1) * (n+1)) * gamma * a(i); + D(i,D.cols()-1) = D(D.rows()-1,i); + D(D.rows()-1,D.cols()-1) = float(n)/float((n+1) * (n+1)) * gamma * gamma; + } + + Eigen::MatrixXf R(D.rows(), D.cols()); + Eigen::EigenSolver D_evd (D, false); + Eigen::VectorXf alphap = D_evd.eigenvalues().real(); + eigenvalues_.resize(eigenvalues_.size() +1); + for(std::size_t i=0;i() = h; + eigenvectors_ = Up*R; + if (!basis_only_) { + Eigen::Vector3f etha = Up.transpose() * (mean_.head<3>() - meanp); + coefficients_.resize(coefficients_.rows()+1,coefficients_.cols()+1); + for(std::size_t i=0; i < (coefficients_.cols() - 1); i++) { + coefficients_(coefficients_.rows()-1,i) = 0; + coefficients_.col(i) = (R.transpose() * coefficients_.col(i)) + etha; + } + a.resize(a.size()+1); + a(a.size()-1) = 0; + coefficients_.col(coefficients_.cols()-1) = (R.transpose() * a) + etha; + } + mean_.head<3>() = meanp; + switch (flag) + { + case increase: + if (eigenvectors_.rows() >= eigenvectors_.cols()) + break; + case preserve: + if (!basis_only_) + coefficients_ = coefficients_.topRows(coefficients_.rows() - 1); + eigenvectors_ = eigenvectors_.leftCols(eigenvectors_.cols() - 1); + eigenvalues_.resize(eigenvalues_.size()-1); + break; + default: + PCL_ERROR("[pcl::PCA] unknown flag\n"); + } +} + +///////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::PCA::project (const PointT& input, PointT& projection) +{ + if(!compute_done_) + initCompute (); + if (!compute_done_) + PCL_THROW_EXCEPTION (InitFailedException, "[pcl::PCA::project] PCA initCompute failed"); + + Eigen::Vector3f demean_input = input.getVector3fMap () - mean_.head<3> (); + projection.getVector3fMap () = eigenvectors_.transpose() * demean_input; +} + +///////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::PCA::project (const PointCloud& input, PointCloud& projection) +{ + if(!compute_done_) + initCompute (); + if (!compute_done_) + PCL_THROW_EXCEPTION (InitFailedException, "[pcl::PCA::project] PCA initCompute failed"); + if (input.is_dense) + { + projection.resize (input.size ()); + for (size_t i = 0; i < input.size (); ++i) + project (input[i], projection[i]); + } + else + { + PointT p; + for (size_t i = 0; i < input.size (); ++i) + { + if (!pcl_isfinite (input[i].x) || + !pcl_isfinite (input[i].y) || + !pcl_isfinite (input[i].z)) + continue; + project (input[i], p); + projection.push_back (p); + } + } +} + +///////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::PCA::reconstruct (const PointT& projection, PointT& input) +{ + if(!compute_done_) + initCompute (); + if (!compute_done_) + PCL_THROW_EXCEPTION (InitFailedException, "[pcl::PCA::reconstruct] PCA initCompute failed"); + + input.getVector3fMap ()= eigenvectors_ * projection.getVector3fMap (); + input.getVector3fMap ()+= mean_.head<3> (); +} + +///////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::PCA::reconstruct (const PointCloud& projection, PointCloud& input) +{ + if(!compute_done_) + initCompute (); + if (!compute_done_) + PCL_THROW_EXCEPTION (InitFailedException, "[pcl::PCA::reconstruct] PCA initCompute failed"); + if (input.is_dense) + { + input.resize (projection.size ()); + for (size_t i = 0; i < projection.size (); ++i) + reconstruct (projection[i], input[i]); + } + else + { + PointT p; + for (size_t i = 0; i < input.size (); ++i) + { + if (!pcl_isfinite (input[i].x) || + !pcl_isfinite (input[i].y) || + !pcl_isfinite (input[i].z)) + continue; + reconstruct (projection[i], p); + input.push_back (p); + } + } +} + +#endif diff --git a/pcl-1.7/pcl/common/impl/piecewise_linear_function.hpp b/pcl-1.7/pcl/common/impl/piecewise_linear_function.hpp new file mode 100644 index 0000000..06b4eb6 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/piecewise_linear_function.hpp @@ -0,0 +1,56 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +/* \author Bastian Steder */ + + +namespace pcl { + +PiecewiseLinearFunction::PiecewiseLinearFunction(float factor, float offset) : factor_(factor), offset_(offset) +{ +} + +inline float PiecewiseLinearFunction::getValue(float point) const +{ + float vector_pos = factor_*point + offset_; + float floored_vector_pos = floor(vector_pos); + float interpolation_size = vector_pos-floored_vector_pos; + int data_point_before = (std::max)(0, (std::min)(int(data_points_.size())-2, int(lrint(floored_vector_pos)))); + //cout << "Interpolating between "< +pcl::PolynomialCalculationsT::PolynomialCalculationsT () +{ +} + +//////////////////////////////////// + +template +pcl::PolynomialCalculationsT:: ~PolynomialCalculationsT () +{ +} + +//////////////////////////////////// + +template +inline void + pcl::PolynomialCalculationsT::Parameters::setZeroValue (real new_zero_value) +{ + zero_value = new_zero_value; + sqr_zero_value = zero_value*zero_value; +} + +//////////////////////////////////// + +template +inline void + pcl::PolynomialCalculationsT::solveLinearEquation (real a, real b, std::vector& roots) const +{ + //cout << "Trying to solve "< +inline void + pcl::PolynomialCalculationsT::solveQuadraticEquation (real a, real b, real c, std::vector& roots) const +{ + //cout << "Trying to solve "< Calling solveLineaqrEquation.\n"; + solveLinearEquation (b, c, roots); + return; + } + + if (isNearlyZero (c)) + { + roots.push_back (0.0); + //cout << "Constant element is 0 => Adding root 0 and calling solveLinearEquation.\n"; + std::vector tmpRoots; + solveLinearEquation (a, b, tmpRoots); + for (unsigned int i=0; i0) + { + tmp = sqrt (tmp); + real tmp2 = 1.0/ (2*a); + roots.push_back ( (-b + tmp)*tmp2); + roots.push_back ( (-b - tmp)*tmp2); + } + else if (sqrtIsNearlyZero (tmp)) + { + roots.push_back (-b/ (2*a)); + } + +#if 0 + cout << __PRETTY_FUNCTION__ << ": Found "< +inline void + pcl::PolynomialCalculationsT::solveCubicEquation (real a, real b, real c, real d, std::vector& roots) const +{ + //cout << "Trying to solve "< Calling solveQuadraticEquation.\n"; + solveQuadraticEquation (b, c, d, roots); + return; + } + + if (isNearlyZero (d)) + { + roots.push_back (0.0); + //cout << "Constant element is 0 => Adding root 0 and calling solveQuadraticEquation.\n"; + std::vector tmpRoots; + solveQuadraticEquation (a, b, c, tmpRoots); + for (unsigned int i=0; i 0) + { + double sqrtDiscriminant = sqrt (discriminant); + double d1 = -0.5*beta + sqrtDiscriminant, + d2 = -0.5*beta - sqrtDiscriminant; + if (d1 < 0) + d1 = -pow (-d1, 1.0/3.0); + else + d1 = pow (d1, 1.0/3.0); + + if (d2 < 0) + d2 = -pow (-d2, 1.0/3.0); + else + d2 = pow (d2, 1.0/3.0); + + //cout << PVAR (d1)<<", "< 1e-4) + { + cout << "Something went wrong:\n"; + //roots.clear (); + } + cout << "Root "< +inline void + pcl::PolynomialCalculationsT::solveQuarticEquation (real a, real b, real c, real d, real e, + std::vector& roots) const +{ + //cout << "Trying to solve "< Calling solveCubicEquation.\n"; + solveCubicEquation (b, c, d, e, roots); + return; + } + + if (isNearlyZero (e)) + { + roots.push_back (0.0); + //cout << "Constant element is 0 => Adding root 0 and calling solveCubicEquation.\n"; + std::vector tmpRoots; + solveCubicEquation (a, b, c, d, tmpRoots); + for (unsigned int i=0; i tmpRoots; + solveQuadraticEquation (1.0, alpha, gamma, tmpRoots); + for (unsigned int i=0; i 0.0) + { + root1 = sqrt (qudraticRoot); + roots.push_back (root1 - resubValue); + roots.push_back (-root1 - resubValue); + } + } + } + else + { + //cout << "beta != 0\n"; + double alpha3 = alpha2*alpha, + beta2 = beta*beta, + p = (-alpha2/12.0)-gamma, + q = (-alpha3/108.0)+ ( (alpha*gamma)/3.0)- (beta2/8.0), + q2 = q*q, + p3 = p*p*p, + u = (0.5*q) + sqrt ( (0.25*q2)+ (p3/27.0)); + if (u > 0.0) + u = pow (u, 1.0/3.0); + else if (isNearlyZero (u)) + u = 0.0; + else + u = -pow (-u, 1.0/3.0); + + double y = (-5.0/6.0)*alpha - u; + if (!isNearlyZero (u)) + y += p/ (3.0*u); + + double w = alpha + 2.0*y; + + if (w > 0) + { + w = sqrt (w); + } + else if (isNearlyZero (w)) + { + w = 0; + } + else + { + //cout << "Found no roots\n"; + return; + } + + double tmp1 = - (3.0*alpha + 2.0*y + 2.0* (beta/w)), + tmp2 = - (3.0*alpha + 2.0*y - 2.0* (beta/w)); + + if (tmp1 > 0) + { + tmp1 = sqrt (tmp1); + root1 = - (b/ (4.0*a)) + 0.5* (w+tmp1); + root2 = - (b/ (4.0*a)) + 0.5* (w-tmp1); + roots.push_back (root1); + roots.push_back (root2); + } + else if (isNearlyZero (tmp1)) + { + root1 = - (b/ (4.0*a)) + 0.5*w; + roots.push_back (root1); + } + + if (tmp2 > 0) + { + tmp2 = sqrt (tmp2); + root3 = - (b/ (4.0*a)) + 0.5* (-w+tmp2); + root4 = - (b/ (4.0*a)) + 0.5* (-w-tmp2); + roots.push_back (root3); + roots.push_back (root4); + } + else if (isNearlyZero (tmp2)) + { + root3 = - (b/ (4.0*a)) - 0.5*w; + roots.push_back (root3); + } + + //cout << "Test: " << alpha<<", "< 1e-4) + { + cout << "Something went wrong:\n"; + //roots.clear (); + } + cout << "Root "< +inline pcl::BivariatePolynomialT + pcl::PolynomialCalculationsT::bivariatePolynomialApproximation ( + std::vector >& samplePoints, unsigned int polynomial_degree, bool& error) const +{ + pcl::BivariatePolynomialT ret; + error = bivariatePolynomialApproximation (samplePoints, polynomial_degree, ret); + return ret; +} + +//////////////////////////////////// + +template +inline bool + pcl::PolynomialCalculationsT::bivariatePolynomialApproximation ( + std::vector >& samplePoints, unsigned int polynomial_degree, + pcl::BivariatePolynomialT& ret) const +{ + //MEASURE_FUNCTION_TIME; + unsigned int parameters_size = BivariatePolynomialT::getNoOfParametersFromDegree (polynomial_degree); + //cout << PVARN (parameters_size); + + //cout << "Searching for the "< samplePoints.size ()) // Too many parameters for this number of equations (points)? + { + return false; + // Reduce degree of polynomial + //polynomial_degree = (unsigned int) (0.5f* (sqrtf (8*samplePoints.size ()+1) - 3)); + //parameters_size = BivariatePolynomialT::getNoOfParametersFromDegree (polynomial_degree); + //cout << "Not enough points, so degree of polynomial was decreased to "< "< A (parameters_size, parameters_size); + A.setZero(); + Eigen::Matrix b (parameters_size); + b.setZero(); + real currentX, currentY, currentZ; + real tmpX, tmpY; + real *tmpC = new real[parameters_size]; + real* tmpCEndPtr = &tmpC[parameters_size-1]; + for (typename std::vector >::const_iterator it=samplePoints.begin (); + it!=samplePoints.end (); ++it) + { + currentX= (*it)[0]; currentY= (*it)[1]; currentZ= (*it)[2]; + //cout << "current point: "< "<::outProd (tmpC); + //b += currentZ * tmpC; + } + //cout << "Calculating matrix A and vector b (size "< A (parameters_size, parameters_size); + //DVector b (parameters_size); + //real currentX, currentY, currentZ; + //unsigned int posInC; + //real tmpX, tmpY; + //DVector tmpC (parameters_size); + //for (typename std::vector >::const_iterator it=samplePoints.begin (); + // it!=samplePoints.end (); ++it) + //{ + //currentX= (*it)[0]; currentY= (*it)[1]; currentZ= (*it)[2]; + ////cout << "x="<::outProd (tmpC); + //b += currentZ * tmpC; + //} + //cout << "Calculating matrix A and vector b (size "< parameters; + //double choleskyStartTime=-get_time (); + //parameters = A.choleskySolve (b); + //cout << "Cholesky took "<< (choleskyStartTime+get_time ())*1000<<"ms.\n"; + + //double invStartTime=-get_time (); + parameters = A.inverse () * b; + //cout << "Inverse took "<< (invStartTime+get_time ())*1000<<"ms.\n"; + + //cout << PVARC (A)< 1e-5) + { + //cout << "Inversion result: "<< inversionCheckResult<<" for matrix "< + +/////////////////////////////////////////////////////////////////////////////////////////// +namespace pcl +{ + namespace common + { + namespace internal + { + template void + makeSymmetric (MatrixT& matrix, bool use_upper_triangular = true) + { + if (use_upper_triangular && (MatrixT::Flags & Eigen::RowMajorBit)) + { + matrix.coeffRef (4) = matrix.coeff (1); + matrix.coeffRef (8) = matrix.coeff (2); + matrix.coeffRef (9) = matrix.coeff (6); + matrix.coeffRef (12) = matrix.coeff (3); + matrix.coeffRef (13) = matrix.coeff (7); + matrix.coeffRef (14) = matrix.coeff (11); + } + else + { + matrix.coeffRef (1) = matrix.coeff (4); + matrix.coeffRef (2) = matrix.coeff (8); + matrix.coeffRef (6) = matrix.coeff (9); + matrix.coeffRef (3) = matrix.coeff (12); + matrix.coeffRef (7) = matrix.coeff (13); + matrix.coeffRef (11) = matrix.coeff (14); + } + } + } + } +} + +////////////////////////////////////////////////////////////////////////////// +template double +pcl::estimateProjectionMatrix ( + typename pcl::PointCloud::ConstPtr cloud, + Eigen::Matrix& projection_matrix, + const std::vector& indices) +{ + // internally we calculate with double but store the result into float matrices. + typedef double Scalar; + projection_matrix.setZero (); + if (cloud->height == 1 || cloud->width == 1) + { + PCL_ERROR ("[pcl::estimateProjectionMatrix] Input dataset is not organized!\n"); + return (-1.0); + } + + Eigen::Matrix A = Eigen::Matrix::Zero (); + Eigen::Matrix B = Eigen::Matrix::Zero (); + Eigen::Matrix C = Eigen::Matrix::Zero (); + Eigen::Matrix D = Eigen::Matrix::Zero (); + + pcl::ConstCloudIterator pointIt (*cloud, indices); + + while (pointIt) + { + unsigned yIdx = pointIt.getCurrentPointIndex () / cloud->width; + unsigned xIdx = pointIt.getCurrentPointIndex () % cloud->width; + + const PointT& point = *pointIt; + if (pcl_isfinite (point.x)) + { + Scalar xx = point.x * point.x; + Scalar xy = point.x * point.y; + Scalar xz = point.x * point.z; + Scalar yy = point.y * point.y; + Scalar yz = point.y * point.z; + Scalar zz = point.z * point.z; + Scalar xx_yy = xIdx * xIdx + yIdx * yIdx; + + A.coeffRef (0) += xx; + A.coeffRef (1) += xy; + A.coeffRef (2) += xz; + A.coeffRef (3) += point.x; + + A.coeffRef (5) += yy; + A.coeffRef (6) += yz; + A.coeffRef (7) += point.y; + + A.coeffRef (10) += zz; + A.coeffRef (11) += point.z; + A.coeffRef (15) += 1.0; + + B.coeffRef (0) -= xx * xIdx; + B.coeffRef (1) -= xy * xIdx; + B.coeffRef (2) -= xz * xIdx; + B.coeffRef (3) -= point.x * static_cast(xIdx); + + B.coeffRef (5) -= yy * xIdx; + B.coeffRef (6) -= yz * xIdx; + B.coeffRef (7) -= point.y * static_cast(xIdx); + + B.coeffRef (10) -= zz * xIdx; + B.coeffRef (11) -= point.z * static_cast(xIdx); + + B.coeffRef (15) -= xIdx; + + C.coeffRef (0) -= xx * yIdx; + C.coeffRef (1) -= xy * yIdx; + C.coeffRef (2) -= xz * yIdx; + C.coeffRef (3) -= point.x * static_cast(yIdx); + + C.coeffRef (5) -= yy * yIdx; + C.coeffRef (6) -= yz * yIdx; + C.coeffRef (7) -= point.y * static_cast(yIdx); + + C.coeffRef (10) -= zz * yIdx; + C.coeffRef (11) -= point.z * static_cast(yIdx); + + C.coeffRef (15) -= yIdx; + + D.coeffRef (0) += xx * xx_yy; + D.coeffRef (1) += xy * xx_yy; + D.coeffRef (2) += xz * xx_yy; + D.coeffRef (3) += point.x * xx_yy; + + D.coeffRef (5) += yy * xx_yy; + D.coeffRef (6) += yz * xx_yy; + D.coeffRef (7) += point.y * xx_yy; + + D.coeffRef (10) += zz * xx_yy; + D.coeffRef (11) += point.z * xx_yy; + + D.coeffRef (15) += xx_yy; + } + + ++pointIt; + } // while + + pcl::common::internal::makeSymmetric (A); + pcl::common::internal::makeSymmetric (B); + pcl::common::internal::makeSymmetric (C); + pcl::common::internal::makeSymmetric (D); + + Eigen::Matrix X = Eigen::Matrix::Zero (); + X.topLeftCorner<4,4> ().matrix () = A; + X.block<4,4> (0, 8).matrix () = B; + X.block<4,4> (8, 0).matrix () = B; + X.block<4,4> (4, 4).matrix () = A; + X.block<4,4> (4, 8).matrix () = C; + X.block<4,4> (8, 4).matrix () = C; + X.block<4,4> (8, 8).matrix () = D; + + Eigen::SelfAdjointEigenSolver > ei_symm (X); + Eigen::Matrix eigen_vectors = ei_symm.eigenvectors (); + + // check whether the residual MSE is low. If its high, the cloud was not captured from a projective device. + Eigen::Matrix residual_sqr = eigen_vectors.col (0).transpose () * X * eigen_vectors.col (0); + + double residual = residual_sqr.coeff (0); + + projection_matrix.coeffRef (0) = static_cast (eigen_vectors.coeff (0)); + projection_matrix.coeffRef (1) = static_cast (eigen_vectors.coeff (12)); + projection_matrix.coeffRef (2) = static_cast (eigen_vectors.coeff (24)); + projection_matrix.coeffRef (3) = static_cast (eigen_vectors.coeff (36)); + projection_matrix.coeffRef (4) = static_cast (eigen_vectors.coeff (48)); + projection_matrix.coeffRef (5) = static_cast (eigen_vectors.coeff (60)); + projection_matrix.coeffRef (6) = static_cast (eigen_vectors.coeff (72)); + projection_matrix.coeffRef (7) = static_cast (eigen_vectors.coeff (84)); + projection_matrix.coeffRef (8) = static_cast (eigen_vectors.coeff (96)); + projection_matrix.coeffRef (9) = static_cast (eigen_vectors.coeff (108)); + projection_matrix.coeffRef (10) = static_cast (eigen_vectors.coeff (120)); + projection_matrix.coeffRef (11) = static_cast (eigen_vectors.coeff (132)); + + if (projection_matrix.coeff (0) < 0) + projection_matrix *= -1.0; + + return (residual); +} + +#endif diff --git a/pcl-1.7/pcl/common/impl/random.hpp b/pcl-1.7/pcl/common/impl/random.hpp new file mode 100644 index 0000000..9a99e7c --- /dev/null +++ b/pcl-1.7/pcl/common/impl/random.hpp @@ -0,0 +1,189 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_COMMON_RANDOM_HPP_ +#define PCL_COMMON_RANDOM_HPP_ + +#include +#include + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::common::UniformGenerator::UniformGenerator(T min, T max, pcl::uint32_t seed) + : distribution_ (min, max) + , generator_ (rng_, distribution_) +{ + parameters_ = Parameters (min, max, seed); + if(parameters_.seed != -1) + rng_.seed (seed); +} + + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::common::UniformGenerator::UniformGenerator(const Parameters& parameters) + : parameters_ (parameters) + , distribution_ (parameters_.min, parameters_.max) + , generator_ (rng_, distribution_) +{ + if(parameters_.seed != -1) + rng_.seed (parameters_.seed); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::common::UniformGenerator::setSeed (pcl::uint32_t seed) +{ + if (seed != -1) + { + parameters_.seed = seed; + rng_.seed(parameters_.seed); + } +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::common::UniformGenerator::setParameters (T min, T max, pcl::uint32_t seed) +{ + parameters_.min = min; + parameters_.max = max; + parameters_.seed = seed; +#if BOOST_VERSION >= 104700 + typename DistributionType::param_type params (parameters_.min, parameters_.max); + distribution_.param (params); +#else + distribution_ = DistributionType (parameters_.min, parameters_.max); +#endif + distribution_.reset (); + generator_.distribution () = distribution_; + if (seed != -1) + { + parameters_.seed = seed; + rng_.seed (parameters_.seed); + } +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::common::UniformGenerator::setParameters (const Parameters& parameters) +{ + parameters_ = parameters; +#if BOOST_VERSION >= 104700 + typename DistributionType::param_type params (parameters_.min, parameters_.max); + distribution_.param (params); +#else + distribution_ = DistributionType (parameters_.min, parameters_.max); +#endif + distribution_.reset (); + generator_.distribution () = distribution_; + if (parameters_.seed != -1) + rng_.seed (parameters_.seed); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::common::NormalGenerator::NormalGenerator(T mean, T sigma, pcl::uint32_t seed) + : distribution_ (mean, sigma) + , generator_ (rng_, distribution_) +{ + parameters_ = Parameters (mean, sigma, seed); + if(parameters_.seed != -1) + rng_.seed (seed); +} + + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::common::NormalGenerator::NormalGenerator(const Parameters& parameters) + : parameters_ (parameters) + , distribution_ (parameters_.mean, parameters_.sigma) + , generator_ (rng_, distribution_) +{ + if(parameters_.seed != -1) + rng_.seed (parameters_.seed); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::common::NormalGenerator::setSeed (pcl::uint32_t seed) +{ + if (seed != -1) + { + parameters_.seed = seed; + rng_.seed(seed); + } +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::common::NormalGenerator::setParameters (T mean, T sigma, pcl::uint32_t seed) +{ + parameters_.mean = mean; + parameters_.sigma = sigma; + parameters_.seed = seed; +#if BOOST_VERSION >= 104700 + typename DistributionType::param_type params (parameters_.mean, parameters_.sigma); + distribution_.param (params); +#else + distribution_ = DistributionType (parameters_.mean, parameters_.sigma); +#endif + distribution_.reset (); + generator_.distribution () = distribution_; + if (seed != -1) + rng_.seed (parameters_.seed); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::common::NormalGenerator::setParameters (const Parameters& parameters) +{ + parameters_ = parameters; +#if BOOST_VERSION >= 104700 + typename DistributionType::param_type params (parameters_.mean, parameters_.sigma); + distribution_.param (params); +#else + distribution_ = DistributionType (parameters_.mean, parameters_.sigma); +#endif + distribution_.reset (); + generator_.distribution () = distribution_; + if (parameters_.seed != -1) + rng_.seed (parameters_.seed); +} + +#endif diff --git a/pcl-1.7/pcl/common/impl/spring.hpp b/pcl-1.7/pcl/common/impl/spring.hpp new file mode 100644 index 0000000..1751285 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/spring.hpp @@ -0,0 +1,261 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_POINT_CLOUD_SPRING_IMPL_HPP_ +#define PCL_POINT_CLOUD_SPRING_IMPL_HPP_ + +template void +pcl::common::expandColumns (const PointCloud& input, PointCloud& output, + const PointT& val, const size_t& amount) +{ + if (amount <= 0) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::common::expandColumns] error: amount must be ]0.." + << (input.width/2) << "] !"); + + if (!input.isOrganized () || amount > (input.width/2)) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::common::expandColumns] error: " + << "columns expansion requires organised point cloud"); + + uint32_t old_height = input.height; + uint32_t old_width = input.width; + uint32_t new_width = old_width + 2*amount; + if (&input != &output) + output = input; + output.reserve (new_width * old_height); + for (int j = 0; j < output.height; ++j) + { + typename PointCloud::iterator start = output.begin() + (j * new_width); + output.insert (start, amount, val); + start = output.begin() + (j * new_width) + old_width + amount; + output.insert (start, amount, val); + output.height = old_height; + } + output.width = new_width; + output.height = old_height; +} + +template void +pcl::common::expandRows (const PointCloud& input, PointCloud& output, + const PointT& val, const size_t& amount) +{ + if (amount <= 0) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::common::expandRows] error: amount must be ]0.." + << (input.height/2) << "] !"); + + uint32_t old_height = input.height; + uint32_t new_height = old_height + 2*amount; + uint32_t old_width = input.width; + if (&input != &output) + output = input; + output.reserve (new_height * old_width); + output.insert (output.begin (), amount * old_width, val); + output.insert (output.end (), amount * old_width, val); + output.width = old_width; + output.height = new_height; +} + +template void +pcl::common::duplicateColumns (const PointCloud& input, PointCloud& output, + const size_t& amount) +{ + if (amount <= 0) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::common::duplicateColumns] error: amount must be ]0.." + << (input.width/2) << "] !"); + + if (!input.isOrganized () || amount > (input.width/2)) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::common::duplicateColumns] error: " + << "columns expansion requires organised point cloud"); + + size_t old_height = input.height; + size_t old_width = input.width; + size_t new_width = old_width + 2*amount; + if (&input != &output) + output = input; + output.reserve (new_width * old_height); + for (size_t j = 0; j < old_height; ++j) + for(size_t i = 0; i < amount; ++i) + { + typename PointCloud::iterator start = output.begin () + (j * new_width); + output.insert (start, *start); + start = output.begin () + (j * new_width) + old_width + i; + output.insert (start, *start); + } + + output.width = new_width; + output.height = old_height; +} + +template void +pcl::common::duplicateRows (const PointCloud& input, PointCloud& output, + const size_t& amount) +{ + if (amount <= 0 || amount > (input.height/2)) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::common::duplicateRows] error: amount must be ]0.." + << (input.height/2) << "] !"); + + uint32_t old_height = input.height; + uint32_t new_height = old_height + 2*amount; + uint32_t old_width = input.width; + if (&input != &output) + output = input; + output.reserve (new_height * old_width); + for(size_t i = 0; i < amount; ++i) + { + output.insert (output.begin (), output.begin (), output.begin () + old_width); + output.insert (output.end (), output.end () - old_width, output.end ()); + } + + output.width = old_width; + output.height = new_height; +} + +template void +pcl::common::mirrorColumns (const PointCloud& input, PointCloud& output, + const size_t& amount) +{ + if (amount <= 0) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::common::mirrorColumns] error: amount must be ]0.." + << (input.width/2) << "] !"); + + if (!input.isOrganized () || amount > (input.width/2)) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::common::mirrorColumns] error: " + << "columns expansion requires organised point cloud"); + + size_t old_height = input.height; + size_t old_width = input.width; + size_t new_width = old_width + 2*amount; + if (&input != &output) + output = input; + output.reserve (new_width * old_height); + for (size_t j = 0; j < old_height; ++j) + for(size_t i = 0; i < amount; ++i) + { + typename PointCloud::iterator start = output.begin () + (j * new_width); + output.insert (start, *(start + 2*i)); + start = output.begin () + (j * new_width) + old_width + 2*i; + output.insert (start+1, *(start - 2*i)); + } + output.width = new_width; + output.height = old_height; +} + +template void +pcl::common::mirrorRows (const PointCloud& input, PointCloud& output, + const size_t& amount) +{ + if (amount <= 0 || amount > (input.height/2)) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::common::mirrorRows] error: amount must be ]0.." + << (input.height/2) << "] !"); + + uint32_t old_height = input.height; + uint32_t new_height = old_height + 2*amount; + uint32_t old_width = input.width; + if (&input != &output) + output = input; + output.reserve (new_height * old_width); + for(size_t i = 0; i < amount; i++) + { + typename PointCloud::iterator up; + if (output.height % 2 == 0) + up = output.begin () + (2*i) * old_width; + else + up = output.begin () + (2*i+1) * old_width; + output.insert (output.begin (), up, up + old_width); + typename PointCloud::iterator bottom = output.end () - (2*i+1) * old_width; + output.insert (output.end (), bottom, bottom + old_width); + } + output.width = old_width; + output.height = new_height; +} + +template void +pcl::common::deleteRows (const PointCloud& input, PointCloud& output, + const size_t& amount) +{ + if (amount <= 0 || amount > (input.height/2)) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::common::deleteRows] error: amount must be ]0.." + << (input.height/2) << "] !"); + + uint32_t old_height = input.height; + uint32_t old_width = input.width; + output.erase (output.begin (), output.begin () + amount * old_width); + output.erase (output.end () - amount * old_width, output.end ()); + output.height = old_height - 2*amount; + output.width = old_width; +} + +template void +pcl::common::deleteCols (const PointCloud& input, PointCloud& output, + const size_t& amount) +{ + if (amount <= 0 || amount > (input.width/2)) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::common::deleteCols] error: amount must be in ]0.." + << (input.width/2) << "] !"); + + if (!input.isOrganized ()) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::common::deleteCols] error: " + << "columns delete requires organised point cloud"); + + uint32_t old_height = input.height; + uint32_t old_width = input.width; + uint32_t new_width = old_width - 2 * amount; + for(size_t j = 0; j < old_height; j++) + { + typename PointCloud::iterator start = output.begin () + j * new_width; + output.erase (start, start + amount); + start = output.begin () + (j+1) * new_width; + output.erase (start, start + amount); + } + output.height = old_height; + output.width = new_width; +} + +#endif diff --git a/pcl-1.7/pcl/common/impl/transformation_from_correspondences.hpp b/pcl-1.7/pcl/common/impl/transformation_from_correspondences.hpp new file mode 100644 index 0000000..4067a5b --- /dev/null +++ b/pcl-1.7/pcl/common/impl/transformation_from_correspondences.hpp @@ -0,0 +1,93 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +inline void +pcl::TransformationFromCorrespondences::reset () +{ + no_of_samples_ = 0; + accumulated_weight_ = 0.0; + mean1_.fill(0); + mean2_.fill(0); + covariance_.fill(0); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +inline void +pcl::TransformationFromCorrespondences::add (const Eigen::Vector3f& point, const Eigen::Vector3f& corresponding_point, + float weight) +{ + if (weight==0.0f) + return; + + ++no_of_samples_; + accumulated_weight_ += weight; + float alpha = weight/accumulated_weight_; + + Eigen::Vector3f diff1 = point - mean1_, diff2 = corresponding_point - mean2_; + covariance_ = (1.0f-alpha)*(covariance_ + alpha * (diff2 * diff1.transpose())); + + mean1_ += alpha*(diff1); + mean2_ += alpha*(diff2); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +inline Eigen::Affine3f +pcl::TransformationFromCorrespondences::getTransformation () +{ + //Eigen::JacobiSVD > svd (covariance_, Eigen::ComputeFullU | Eigen::ComputeFullV); + Eigen::JacobiSVD > svd (covariance_, Eigen::ComputeFullU | Eigen::ComputeFullV); + const Eigen::Matrix& u = svd.matrixU(), + & v = svd.matrixV(); + Eigen::Matrix s; + s.setIdentity(); + if (u.determinant()*v.determinant() < 0.0f) + s(2,2) = -1.0f; + + Eigen::Matrix r = u * s * v.transpose(); + Eigen::Vector3f t = mean2_ - r*mean1_; + + Eigen::Affine3f ret; + ret(0,0)=r(0,0); ret(0,1)=r(0,1); ret(0,2)=r(0,2); ret(0,3)=t(0); + ret(1,0)=r(1,0); ret(1,1)=r(1,1); ret(1,2)=r(1,2); ret(1,3)=t(1); + ret(2,0)=r(2,0); ret(2,1)=r(2,1); ret(2,2)=r(2,2); ret(2,3)=t(2); + ret(3,0)=0.0f; ret(3,1)=0.0f; ret(3,2)=0.0f; ret(3,3)=1.0f; + + return (ret); +} diff --git a/pcl-1.7/pcl/common/impl/transforms.hpp b/pcl-1.7/pcl/common/impl/transforms.hpp new file mode 100644 index 0000000..c686da5 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/transforms.hpp @@ -0,0 +1,329 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::transformPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Transform &transform) +{ + if (&cloud_in != &cloud_out) + { + // Note: could be replaced by cloud_out = cloud_in + cloud_out.header = cloud_in.header; + cloud_out.is_dense = cloud_in.is_dense; + cloud_out.width = cloud_in.width; + cloud_out.height = cloud_in.height; + cloud_out.points.reserve (cloud_out.points.size ()); + cloud_out.points.assign (cloud_in.points.begin (), cloud_in.points.end ()); + cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_; + cloud_out.sensor_origin_ = cloud_in.sensor_origin_; + } + + if (cloud_in.is_dense) + { + // If the dataset is dense, simply transform it! + for (size_t i = 0; i < cloud_out.points.size (); ++i) + { + //cloud_out.points[i].getVector3fMap () = transform * cloud_in.points[i].getVector3fMap (); + Eigen::Matrix pt (cloud_in[i].x, cloud_in[i].y, cloud_in[i].z); + cloud_out[i].x = static_cast (transform (0, 0) * pt.coeffRef (0) + transform (0, 1) * pt.coeffRef (1) + transform (0, 2) * pt.coeffRef (2) + transform (0, 3)); + cloud_out[i].y = static_cast (transform (1, 0) * pt.coeffRef (0) + transform (1, 1) * pt.coeffRef (1) + transform (1, 2) * pt.coeffRef (2) + transform (1, 3)); + cloud_out[i].z = static_cast (transform (2, 0) * pt.coeffRef (0) + transform (2, 1) * pt.coeffRef (1) + transform (2, 2) * pt.coeffRef (2) + transform (2, 3)); + } + } + else + { + // Dataset might contain NaNs and Infs, so check for them first, + // otherwise we get errors during the multiplication (?) + for (size_t i = 0; i < cloud_out.points.size (); ++i) + { + if (!pcl_isfinite (cloud_in.points[i].x) || + !pcl_isfinite (cloud_in.points[i].y) || + !pcl_isfinite (cloud_in.points[i].z)) + continue; + //cloud_out.points[i].getVector3fMap () = transform * cloud_in.points[i].getVector3fMap (); + Eigen::Matrix pt (cloud_in[i].x, cloud_in[i].y, cloud_in[i].z); + cloud_out[i].x = static_cast (transform (0, 0) * pt.coeffRef (0) + transform (0, 1) * pt.coeffRef (1) + transform (0, 2) * pt.coeffRef (2) + transform (0, 3)); + cloud_out[i].y = static_cast (transform (1, 0) * pt.coeffRef (0) + transform (1, 1) * pt.coeffRef (1) + transform (1, 2) * pt.coeffRef (2) + transform (1, 3)); + cloud_out[i].z = static_cast (transform (2, 0) * pt.coeffRef (0) + transform (2, 1) * pt.coeffRef (1) + transform (2, 2) * pt.coeffRef (2) + transform (2, 3)); + } + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::transformPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out, + const Eigen::Transform &transform) +{ + size_t npts = indices.size (); + // In order to transform the data, we need to remove NaNs + cloud_out.is_dense = cloud_in.is_dense; + cloud_out.header = cloud_in.header; + cloud_out.width = static_cast (npts); + cloud_out.height = 1; + cloud_out.points.resize (npts); + cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_; + cloud_out.sensor_origin_ = cloud_in.sensor_origin_; + + if (cloud_in.is_dense) + { + // If the dataset is dense, simply transform it! + for (size_t i = 0; i < npts; ++i) + { + // Copy fields first, then transform xyz data + //cloud_out.points[i] = cloud_in.points[indices[i]]; + //cloud_out.points[i].getVector3fMap () = transform*cloud_out.points[i].getVector3fMap (); + Eigen::Matrix pt (cloud_in[indices[i]].x, cloud_in[indices[i]].y, cloud_in[indices[i]].z); + cloud_out[i].x = static_cast (transform (0, 0) * pt.coeffRef (0) + transform (0, 1) * pt.coeffRef (1) + transform (0, 2) * pt.coeffRef (2) + transform (0, 3)); + cloud_out[i].y = static_cast (transform (1, 0) * pt.coeffRef (0) + transform (1, 1) * pt.coeffRef (1) + transform (1, 2) * pt.coeffRef (2) + transform (1, 3)); + cloud_out[i].z = static_cast (transform (2, 0) * pt.coeffRef (0) + transform (2, 1) * pt.coeffRef (1) + transform (2, 2) * pt.coeffRef (2) + transform (2, 3)); + } + } + else + { + // Dataset might contain NaNs and Infs, so check for them first, + // otherwise we get errors during the multiplication (?) + for (size_t i = 0; i < npts; ++i) + { + if (!pcl_isfinite (cloud_in.points[indices[i]].x) || + !pcl_isfinite (cloud_in.points[indices[i]].y) || + !pcl_isfinite (cloud_in.points[indices[i]].z)) + continue; + //cloud_out.points[i] = cloud_in.points[indices[i]]; + //cloud_out.points[i].getVector3fMap () = transform*cloud_out.points[i].getVector3fMap (); + Eigen::Matrix pt (cloud_in[indices[i]].x, cloud_in[indices[i]].y, cloud_in[indices[i]].z); + cloud_out[i].x = static_cast (transform (0, 0) * pt.coeffRef (0) + transform (0, 1) * pt.coeffRef (1) + transform (0, 2) * pt.coeffRef (2) + transform (0, 3)); + cloud_out[i].y = static_cast (transform (1, 0) * pt.coeffRef (0) + transform (1, 1) * pt.coeffRef (1) + transform (1, 2) * pt.coeffRef (2) + transform (1, 3)); + cloud_out[i].z = static_cast (transform (2, 0) * pt.coeffRef (0) + transform (2, 1) * pt.coeffRef (1) + transform (2, 2) * pt.coeffRef (2) + transform (2, 3)); + } + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Transform &transform) +{ + if (&cloud_in != &cloud_out) + { + // Note: could be replaced by cloud_out = cloud_in + cloud_out.header = cloud_in.header; + cloud_out.width = cloud_in.width; + cloud_out.height = cloud_in.height; + cloud_out.is_dense = cloud_in.is_dense; + cloud_out.points.reserve (cloud_out.points.size ()); + cloud_out.points.assign (cloud_in.points.begin (), cloud_in.points.end ()); + cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_; + cloud_out.sensor_origin_ = cloud_in.sensor_origin_; + } + + // If the data is dense, we don't need to check for NaN + if (cloud_in.is_dense) + { + for (size_t i = 0; i < cloud_out.points.size (); ++i) + { + //cloud_out.points[i].getVector3fMap() = transform * cloud_in.points[i].getVector3fMap (); + Eigen::Matrix pt (cloud_in[i].x, cloud_in[i].y, cloud_in[i].z); + cloud_out[i].x = static_cast (transform (0, 0) * pt.coeffRef (0) + transform (0, 1) * pt.coeffRef (1) + transform (0, 2) * pt.coeffRef (2) + transform (0, 3)); + cloud_out[i].y = static_cast (transform (1, 0) * pt.coeffRef (0) + transform (1, 1) * pt.coeffRef (1) + transform (1, 2) * pt.coeffRef (2) + transform (1, 3)); + cloud_out[i].z = static_cast (transform (2, 0) * pt.coeffRef (0) + transform (2, 1) * pt.coeffRef (1) + transform (2, 2) * pt.coeffRef (2) + transform (2, 3)); + + // Rotate normals (WARNING: transform.rotation () uses SVD internally!) + //cloud_out.points[i].getNormalVector3fMap() = transform.rotation () * cloud_in.points[i].getNormalVector3fMap (); + Eigen::Matrix nt (cloud_in[i].normal_x, cloud_in[i].normal_y, cloud_in[i].normal_z); + cloud_out[i].normal_x = static_cast (transform (0, 0) * nt.coeffRef (0) + transform (0, 1) * nt.coeffRef (1) + transform (0, 2) * nt.coeffRef (2)); + cloud_out[i].normal_y = static_cast (transform (1, 0) * nt.coeffRef (0) + transform (1, 1) * nt.coeffRef (1) + transform (1, 2) * nt.coeffRef (2)); + cloud_out[i].normal_z = static_cast (transform (2, 0) * nt.coeffRef (0) + transform (2, 1) * nt.coeffRef (1) + transform (2, 2) * nt.coeffRef (2)); + } + } + // Dataset might contain NaNs and Infs, so check for them first. + else + { + for (size_t i = 0; i < cloud_out.points.size (); ++i) + { + if (!pcl_isfinite (cloud_in.points[i].x) || + !pcl_isfinite (cloud_in.points[i].y) || + !pcl_isfinite (cloud_in.points[i].z)) + continue; + + //cloud_out.points[i].getVector3fMap() = transform * cloud_in.points[i].getVector3fMap (); + Eigen::Matrix pt (cloud_in[i].x, cloud_in[i].y, cloud_in[i].z); + cloud_out[i].x = static_cast (transform (0, 0) * pt.coeffRef (0) + transform (0, 1) * pt.coeffRef (1) + transform (0, 2) * pt.coeffRef (2) + transform (0, 3)); + cloud_out[i].y = static_cast (transform (1, 0) * pt.coeffRef (0) + transform (1, 1) * pt.coeffRef (1) + transform (1, 2) * pt.coeffRef (2) + transform (1, 3)); + cloud_out[i].z = static_cast (transform (2, 0) * pt.coeffRef (0) + transform (2, 1) * pt.coeffRef (1) + transform (2, 2) * pt.coeffRef (2) + transform (2, 3)); + + // Rotate normals + //cloud_out.points[i].getNormalVector3fMap() = transform.rotation () * cloud_in.points[i].getNormalVector3fMap (); + Eigen::Matrix nt (cloud_in[i].normal_x, cloud_in[i].normal_y, cloud_in[i].normal_z); + cloud_out[i].normal_x = static_cast (transform (0, 0) * nt.coeffRef (0) + transform (0, 1) * nt.coeffRef (1) + transform (0, 2) * nt.coeffRef (2)); + cloud_out[i].normal_y = static_cast (transform (1, 0) * nt.coeffRef (0) + transform (1, 1) * nt.coeffRef (1) + transform (1, 2) * nt.coeffRef (2)); + cloud_out[i].normal_z = static_cast (transform (2, 0) * nt.coeffRef (0) + transform (2, 1) * nt.coeffRef (1) + transform (2, 2) * nt.coeffRef (2)); + } + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out, + const Eigen::Transform &transform) +{ + size_t npts = indices.size (); + // In order to transform the data, we need to remove NaNs + cloud_out.is_dense = cloud_in.is_dense; + cloud_out.header = cloud_in.header; + cloud_out.width = static_cast (npts); + cloud_out.height = 1; + cloud_out.points.resize (npts); + cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_; + cloud_out.sensor_origin_ = cloud_in.sensor_origin_; + + // If the data is dense, we don't need to check for NaN + if (cloud_in.is_dense) + { + for (size_t i = 0; i < cloud_out.points.size (); ++i) + { + //cloud_out.points[i].getVector3fMap() = transform * cloud_in.points[i].getVector3fMap (); + Eigen::Matrix pt (cloud_in[indices[i]].x, cloud_in[indices[i]].y, cloud_in[indices[i]].z); + cloud_out[i].x = static_cast (transform (0, 0) * pt.coeffRef (0) + transform (0, 1) * pt.coeffRef (1) + transform (0, 2) * pt.coeffRef (2) + transform (0, 3)); + cloud_out[i].y = static_cast (transform (1, 0) * pt.coeffRef (0) + transform (1, 1) * pt.coeffRef (1) + transform (1, 2) * pt.coeffRef (2) + transform (1, 3)); + cloud_out[i].z = static_cast (transform (2, 0) * pt.coeffRef (0) + transform (2, 1) * pt.coeffRef (1) + transform (2, 2) * pt.coeffRef (2) + transform (2, 3)); + + // Rotate normals + //cloud_out.points[i].getNormalVector3fMap() = transform.rotation () * cloud_in.points[i].getNormalVector3fMap (); + Eigen::Matrix nt (cloud_in[indices[i]].normal_x, cloud_in[indices[i]].normal_y, cloud_in[indices[i]].normal_z); + cloud_out[i].normal_x = static_cast (transform (0, 0) * nt.coeffRef (0) + transform (0, 1) * nt.coeffRef (1) + transform (0, 2) * nt.coeffRef (2)); + cloud_out[i].normal_y = static_cast (transform (1, 0) * nt.coeffRef (0) + transform (1, 1) * nt.coeffRef (1) + transform (1, 2) * nt.coeffRef (2)); + cloud_out[i].normal_z = static_cast (transform (2, 0) * nt.coeffRef (0) + transform (2, 1) * nt.coeffRef (1) + transform (2, 2) * nt.coeffRef (2)); + } + } + // Dataset might contain NaNs and Infs, so check for them first. + else + { + for (size_t i = 0; i < cloud_out.points.size (); ++i) + { + if (!pcl_isfinite (cloud_in.points[indices[i]].x) || + !pcl_isfinite (cloud_in.points[indices[i]].y) || + !pcl_isfinite (cloud_in.points[indices[i]].z)) + continue; + + //cloud_out.points[i].getVector3fMap() = transform * cloud_in.points[i].getVector3fMap (); + Eigen::Matrix pt (cloud_in[indices[i]].x, cloud_in[indices[i]].y, cloud_in[indices[i]].z); + cloud_out[i].x = static_cast (transform (0, 0) * pt.coeffRef (0) + transform (0, 1) * pt.coeffRef (1) + transform (0, 2) * pt.coeffRef (2) + transform (0, 3)); + cloud_out[i].y = static_cast (transform (1, 0) * pt.coeffRef (0) + transform (1, 1) * pt.coeffRef (1) + transform (1, 2) * pt.coeffRef (2) + transform (1, 3)); + cloud_out[i].z = static_cast (transform (2, 0) * pt.coeffRef (0) + transform (2, 1) * pt.coeffRef (1) + transform (2, 2) * pt.coeffRef (2) + transform (2, 3)); + + // Rotate normals + //cloud_out.points[i].getNormalVector3fMap() = transform.rotation () * cloud_in.points[i].getNormalVector3fMap (); + Eigen::Matrix nt (cloud_in[indices[i]].normal_x, cloud_in[indices[i]].normal_y, cloud_in[indices[i]].normal_z); + cloud_out[i].normal_x = static_cast (transform (0, 0) * nt.coeffRef (0) + transform (0, 1) * nt.coeffRef (1) + transform (0, 2) * nt.coeffRef (2)); + cloud_out[i].normal_y = static_cast (transform (1, 0) * nt.coeffRef (0) + transform (1, 1) * nt.coeffRef (1) + transform (1, 2) * nt.coeffRef (2)); + cloud_out[i].normal_z = static_cast (transform (2, 0) * nt.coeffRef (0) + transform (2, 1) * nt.coeffRef (1) + transform (2, 2) * nt.coeffRef (2)); + } + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::transformPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Matrix &offset, + const Eigen::Quaternion &rotation) +{ + Eigen::Translation translation (offset); + // Assemble an Eigen Transform + Eigen::Transform t (translation * rotation); + transformPointCloud (cloud_in, cloud_out, t); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Matrix &offset, + const Eigen::Quaternion &rotation) +{ + Eigen::Translation translation (offset); + // Assemble an Eigen Transform + Eigen::Transform t (translation * rotation); + transformPointCloudWithNormals (cloud_in, cloud_out, t); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline PointT +pcl::transformPoint (const PointT &point, + const Eigen::Transform &transform) +{ + PointT ret = point; + //ret.getVector3fMap () = transform * point.getVector3fMap (); + ret.x = static_cast (transform (0, 0) * point.x + transform (0, 1) * point.y + transform (0, 2) * point.z + transform (0, 3)); + ret.y = static_cast (transform (1, 0) * point.x + transform (1, 1) * point.y + transform (1, 2) * point.z + transform (1, 3)); + ret.z = static_cast (transform (2, 0) * point.x + transform (2, 1) * point.y + transform (2, 2) * point.z + transform (2, 3)); + + return (ret); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::getPrincipalTransformation (const pcl::PointCloud &cloud, + Eigen::Transform &transform) +{ + EIGEN_ALIGN16 Eigen::Matrix covariance_matrix; + Eigen::Matrix centroid; + + pcl::computeMeanAndCovarianceMatrix (cloud, covariance_matrix, centroid); + + EIGEN_ALIGN16 Eigen::Matrix eigen_vects; + Eigen::Matrix eigen_vals; + pcl::eigen33 (covariance_matrix, eigen_vects, eigen_vals); + + double rel1 = eigen_vals.coeff (0) / eigen_vals.coeff (1); + double rel2 = eigen_vals.coeff (1) / eigen_vals.coeff (2); + + transform.translation () = centroid.head (3); + transform.linear () = eigen_vects; + + return (std::min (rel1, rel2)); +} + diff --git a/pcl-1.7/pcl/common/impl/vector_average.hpp b/pcl-1.7/pcl/common/impl/vector_average.hpp new file mode 100644 index 0000000..0b1e383 --- /dev/null +++ b/pcl-1.7/pcl/common/impl/vector_average.hpp @@ -0,0 +1,204 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_COMMON_VECTOR_AVERAGE_IMPL_HPP_ +#define PCL_COMMON_VECTOR_AVERAGE_IMPL_HPP_ + +namespace pcl +{ + template + VectorAverage::VectorAverage () : + noOfSamples_ (0), accumulatedWeight_ (0), + mean_ (Eigen::Matrix::Identity ()), + covariance_ (Eigen::Matrix::Identity ()) + { + reset(); + } + + template + inline void VectorAverage::reset() + { + noOfSamples_ = 0; + accumulatedWeight_ = 0.0; + mean_.fill(0); + covariance_.fill(0); + } + + template + inline void VectorAverage::add(const Eigen::Matrix& sample, real weight) { + if (weight == 0.0f) + return; + + ++noOfSamples_; + accumulatedWeight_ += weight; + real alpha = weight/accumulatedWeight_; + + Eigen::Matrix diff = sample - mean_; + covariance_ = (covariance_ + (diff * diff.transpose())*alpha)*(1.0f-alpha); + + mean_ += (diff)*alpha; + + //if (pcl_isnan(covariance_(0,0))) + //{ + //cout << PVARN(weight); + //exit(0); + //} + } + + template + inline void VectorAverage::doPCA(Eigen::Matrix& eigen_values, Eigen::Matrix& eigen_vector1, + Eigen::Matrix& eigen_vector2, Eigen::Matrix& eigen_vector3) const + { + // The following step is necessary for cases where the values in the covariance matrix are small + // In this case float accuracy is nor enough to calculate the eigenvalues and eigenvectors. + //Eigen::Matrix tmp_covariance = covariance_.template cast(); + //Eigen::SelfAdjointEigenSolver > ei_symm(tmp_covariance); + //eigen_values = ei_symm.eigenvalues().template cast(); + //Eigen::Matrix eigen_vectors = ei_symm.eigenvectors().template cast(); + + //cout << "My covariance is \n"< > ei_symm(covariance_); + eigen_values = ei_symm.eigenvalues(); + Eigen::Matrix eigen_vectors = ei_symm.eigenvectors(); + + eigen_vector1 = eigen_vectors.col(0); + eigen_vector2 = eigen_vectors.col(1); + eigen_vector3 = eigen_vectors.col(2); + } + + template + inline void VectorAverage::doPCA(Eigen::Matrix& eigen_values) const + { + // The following step is necessary for cases where the values in the covariance matrix are small + // In this case float accuracy is nor enough to calculate the eigenvalues and eigenvectors. + //Eigen::Matrix tmp_covariance = covariance_.template cast(); + //Eigen::SelfAdjointEigenSolver > ei_symm(tmp_covariance, false); + //eigen_values = ei_symm.eigenvalues().template cast(); + + Eigen::SelfAdjointEigenSolver > ei_symm(covariance_, false); + eigen_values = ei_symm.eigenvalues(); + } + + template + inline void VectorAverage::getEigenVector1(Eigen::Matrix& eigen_vector1) const + { + // The following step is necessary for cases where the values in the covariance matrix are small + // In this case float accuracy is nor enough to calculate the eigenvalues and eigenvectors. + //Eigen::Matrix tmp_covariance = covariance_.template cast(); + //Eigen::SelfAdjointEigenSolver > ei_symm(tmp_covariance); + //eigen_values = ei_symm.eigenvalues().template cast(); + //Eigen::Matrix eigen_vectors = ei_symm.eigenvectors().template cast(); + + //cout << "My covariance is \n"< > ei_symm(covariance_); + Eigen::Matrix eigen_vectors = ei_symm.eigenvectors(); + eigen_vector1 = eigen_vectors.col(0); + } + + + ///////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Special cases for real=float & dimension=3 -> Partial specialization does not work with class templates. :( // + ///////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /////////// + // float // + /////////// + template <> + inline void VectorAverage::doPCA(Eigen::Matrix& eigen_values, Eigen::Matrix& eigen_vector1, + Eigen::Matrix& eigen_vector2, Eigen::Matrix& eigen_vector3) const + { + //cout << "Using specialized 3x3 version of doPCA!\n"; + Eigen::Matrix eigen_vectors; + eigen33(covariance_, eigen_vectors, eigen_values); + eigen_vector1 = eigen_vectors.col(0); + eigen_vector2 = eigen_vectors.col(1); + eigen_vector3 = eigen_vectors.col(2); + } + template <> + inline void VectorAverage::doPCA(Eigen::Matrix& eigen_values) const + { + //cout << "Using specialized 3x3 version of doPCA!\n"; + computeRoots (covariance_, eigen_values); + } + template <> + inline void VectorAverage::getEigenVector1(Eigen::Matrix& eigen_vector1) const + { + //cout << "Using specialized 3x3 version of doPCA!\n"; + Eigen::Vector3f::Scalar eigen_value; + Eigen::Vector3f eigen_vector; + eigen33(covariance_, eigen_value, eigen_vector); + eigen_vector1 = eigen_vector; + } + + //////////// + // double // + //////////// + template <> + inline void VectorAverage::doPCA(Eigen::Matrix& eigen_values, Eigen::Matrix& eigen_vector1, + Eigen::Matrix& eigen_vector2, Eigen::Matrix& eigen_vector3) const + { + //cout << "Using specialized 3x3 version of doPCA!\n"; + Eigen::Matrix eigen_vectors; + eigen33(covariance_, eigen_vectors, eigen_values); + eigen_vector1 = eigen_vectors.col(0); + eigen_vector2 = eigen_vectors.col(1); + eigen_vector3 = eigen_vectors.col(2); + } + template <> + inline void VectorAverage::doPCA(Eigen::Matrix& eigen_values) const + { + //cout << "Using specialized 3x3 version of doPCA!\n"; + computeRoots (covariance_, eigen_values); + } + template <> + inline void VectorAverage::getEigenVector1(Eigen::Matrix& eigen_vector1) const + { + //cout << "Using specialized 3x3 version of doPCA!\n"; + Eigen::Vector3d::Scalar eigen_value; + Eigen::Vector3d eigen_vector; + eigen33(covariance_, eigen_value, eigen_vector); + eigen_vector1 = eigen_vector; + } +} // END namespace + +#endif + diff --git a/pcl-1.7/pcl/common/intensity.h b/pcl-1.7/pcl/common/intensity.h new file mode 100644 index 0000000..673cfe1 --- /dev/null +++ b/pcl-1.7/pcl/common/intensity.h @@ -0,0 +1,104 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_COMMON_INTENSITY_FIELD_SELECTOR_H +#define PCL_COMMON_INTENSITY_FIELD_SELECTOR_H + +namespace pcl +{ + namespace common + { + /** \brief Intensity field accessor provides access to the inetnsity filed of a PoinT + * implementation for specific types should be done in \file pcl/common/impl/intensity.hpp + */ + template + struct IntensityFieldAccessor + { + /** \brief get intensity field + * \param[in] p point + * \return p.intensity + */ + inline float + operator () (const PointT &p) const + { + return p.intensity; + } + /** \brief gets the intensity value of a point + * \param p point for which intensity to be get + * \param[in] intensity value of the intensity field + */ + inline void + get (const PointT &p, float &intensity) const + { + intensity = p.intensity; + } + /** \brief sets the intensity value of a point + * \param p point for which intensity to be set + * \param[in] intensity value of the intensity field + */ + inline void + set (PointT &p, float intensity) const + { + p.intensity = intensity; + } + /** \brief subtract value from intensity field + * \param p point for which to modify inetnsity + * \param[in] value value to be subtracted from point intensity + */ + inline void + demean (PointT& p, float value) const + { + p.intensity -= value; + } + /** \brief add value to intensity field + * \param p point for which to modify inetnsity + * \param[in] value value to be added to point intensity + */ + inline void + add (PointT& p, float value) const + { + p.intensity += value; + } + }; + } +} + +#include + +#endif diff --git a/pcl-1.7/pcl/common/intersections.h b/pcl-1.7/pcl/common/intersections.h new file mode 100644 index 0000000..7cf30b1 --- /dev/null +++ b/pcl-1.7/pcl/common/intersections.h @@ -0,0 +1,160 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_INTERSECTIONS_H_ +#define PCL_INTERSECTIONS_H_ + +#include +#include +#include + +/** + * \file pcl/common/intersections.h + * Define line with line intersection functions + * \ingroup common + */ + +/*@{*/ +namespace pcl +{ + /** \brief Get the intersection of a two 3D lines in space as a 3D point + * \param[in] line_a the coefficients of the first line (point, direction) + * \param[in] line_b the coefficients of the second line (point, direction) + * \param[out] point holder for the computed 3D point + * \param[in] sqr_eps maximum allowable squared distance to the true solution + * \ingroup common + */ + PCL_EXPORTS inline bool + lineWithLineIntersection (const Eigen::VectorXf &line_a, + const Eigen::VectorXf &line_b, + Eigen::Vector4f &point, + double sqr_eps = 1e-4); + + /** \brief Get the intersection of a two 3D lines in space as a 3D point + * \param[in] line_a the coefficients of the first line (point, direction) + * \param[in] line_b the coefficients of the second line (point, direction) + * \param[out] point holder for the computed 3D point + * \param[in] sqr_eps maximum allowable squared distance to the true solution + * \ingroup common + */ + + PCL_EXPORTS inline bool + lineWithLineIntersection (const pcl::ModelCoefficients &line_a, + const pcl::ModelCoefficients &line_b, + Eigen::Vector4f &point, + double sqr_eps = 1e-4); + + /** \brief Determine the line of intersection of two non-parallel planes using lagrange multipliers + * \note Described in: "Intersection of Two Planes, John Krumm, Microsoft Research, Redmond, WA, USA" + * \param[in] plane_a coefficients of plane A and plane B in the form ax + by + cz + d = 0 + * \param[in] plane_b coefficients of line where line.tail<3>() = direction vector and + * line.head<3>() the point on the line clossest to (0, 0, 0) + * \param[out] line the intersected line to be filled + * \param[in] angular_tolerance tolerance in radians + * \return true if succeeded/planes aren't parallel + */ + PCL_EXPORTS template bool + planeWithPlaneIntersection (const Eigen::Matrix &plane_a, + const Eigen::Matrix &plane_b, + Eigen::Matrix &line, + double angular_tolerance = 0.1); + + PCL_EXPORTS inline bool + planeWithPlaneIntersection (const Eigen::Vector4f &plane_a, + const Eigen::Vector4f &plane_b, + Eigen::VectorXf &line, + double angular_tolerance = 0.1) + { + return (planeWithPlaneIntersection (plane_a, plane_b, line, angular_tolerance)); + } + + PCL_EXPORTS inline bool + planeWithPlaneIntersection (const Eigen::Vector4d &plane_a, + const Eigen::Vector4d &plane_b, + Eigen::VectorXd &line, + double angular_tolerance = 0.1) + { + return (planeWithPlaneIntersection (plane_a, plane_b, line, angular_tolerance)); + } + + /** \brief Determine the point of intersection of three non-parallel planes by solving the equations. + * \note If using nearly parralel planes you can lower the determinant_tolerance value. This can + * lead to inconsistent results. + * If the three planes intersects in a line the point will be anywhere on the line. + * \param[in] plane_a are the coefficients of the first plane in the form ax + by + cz + d = 0 + * \param[in] plane_b are the coefficients of the second plane + * \param[in] plane_c are the coefficients of the third plane + * \param[in] determinant_tolerance is a limit to determine whether planes are parallel or not + * \param[out] intersection_point the three coordinates x, y, z of the intersection point + * \return true if succeeded/planes aren't parallel + */ + PCL_EXPORTS template bool + threePlanesIntersection (const Eigen::Matrix &plane_a, + const Eigen::Matrix &plane_b, + const Eigen::Matrix &plane_c, + Eigen::Matrix &intersection_point, + double determinant_tolerance = 1e-6); + + + PCL_EXPORTS inline bool + threePlanesIntersection (const Eigen::Vector4f &plane_a, + const Eigen::Vector4f &plane_b, + const Eigen::Vector4f &plane_c, + Eigen::Vector3f &intersection_point, + double determinant_tolerance = 1e-6) + { + return (threePlanesIntersection (plane_a, plane_b, plane_c, + intersection_point, determinant_tolerance)); + } + + PCL_EXPORTS inline bool + threePlanesIntersection (const Eigen::Vector4d &plane_a, + const Eigen::Vector4d &plane_b, + const Eigen::Vector4d &plane_c, + Eigen::Vector3d &intersection_point, + double determinant_tolerance = 1e-6) + { + return (threePlanesIntersection (plane_a, plane_b, plane_c, + intersection_point, determinant_tolerance)); + } + +} +/*@}*/ + +#include + +#endif //#ifndef PCL_INTERSECTIONS_H_ diff --git a/pcl-1.7/pcl/common/io.h b/pcl-1.7/pcl/common/io.h new file mode 100644 index 0000000..ec72fed --- /dev/null +++ b/pcl-1.7/pcl/common/io.h @@ -0,0 +1,534 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_COMMON_IO_H_ +#define PCL_COMMON_IO_H_ + +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Get the index of a specified field (i.e., dimension/channel) + * \param[in] cloud the the point cloud message + * \param[in] field_name the string defining the field name + * \ingroup common + */ + inline int + getFieldIndex (const pcl::PCLPointCloud2 &cloud, const std::string &field_name) + { + // Get the index we need + for (size_t d = 0; d < cloud.fields.size (); ++d) + if (cloud.fields[d].name == field_name) + return (static_cast(d)); + return (-1); + } + + /** \brief Get the index of a specified field (i.e., dimension/channel) + * \param[in] cloud the the point cloud message + * \param[in] field_name the string defining the field name + * \param[out] fields a vector to the original \a PCLPointField vector that the raw PointCloud message contains + * \ingroup common + */ + template inline int + getFieldIndex (const pcl::PointCloud &cloud, const std::string &field_name, + std::vector &fields); + + /** \brief Get the index of a specified field (i.e., dimension/channel) + * \param[in] field_name the string defining the field name + * \param[out] fields a vector to the original \a PCLPointField vector that the raw PointCloud message contains + * \ingroup common + */ + template inline int + getFieldIndex (const std::string &field_name, + std::vector &fields); + + /** \brief Get the list of available fields (i.e., dimension/channel) + * \param[in] cloud the point cloud message + * \param[out] fields a vector to the original \a PCLPointField vector that the raw PointCloud message contains + * \ingroup common + */ + template inline void + getFields (const pcl::PointCloud &cloud, std::vector &fields); + + /** \brief Get the list of available fields (i.e., dimension/channel) + * \param[out] fields a vector to the original \a PCLPointField vector that the raw PointCloud message contains + * \ingroup common + */ + template inline void + getFields (std::vector &fields); + + /** \brief Get the list of all fields available in a given cloud + * \param[in] cloud the the point cloud message + * \ingroup common + */ + template inline std::string + getFieldsList (const pcl::PointCloud &cloud); + + /** \brief Get the available point cloud fields as a space separated string + * \param[in] cloud a pointer to the PointCloud message + * \ingroup common + */ + inline std::string + getFieldsList (const pcl::PCLPointCloud2 &cloud) + { + std::string result; + for (size_t i = 0; i < cloud.fields.size () - 1; ++i) + result += cloud.fields[i].name + " "; + result += cloud.fields[cloud.fields.size () - 1].name; + return (result); + } + + /** \brief Obtains the size of a specific field data type in bytes + * \param[in] datatype the field data type (see PCLPointField.h) + * \ingroup common + */ + inline int + getFieldSize (const int datatype) + { + switch (datatype) + { + case pcl::PCLPointField::INT8: + case pcl::PCLPointField::UINT8: + return (1); + + case pcl::PCLPointField::INT16: + case pcl::PCLPointField::UINT16: + return (2); + + case pcl::PCLPointField::INT32: + case pcl::PCLPointField::UINT32: + case pcl::PCLPointField::FLOAT32: + return (4); + + case pcl::PCLPointField::FLOAT64: + return (8); + + default: + return (0); + } + } + + /** \brief Obtain a vector with the sizes of all valid fields (e.g., not "_") + * \param[in] fields the input vector containing the fields + * \param[out] field_sizes the resultant field sizes in bytes + */ + PCL_EXPORTS void + getFieldsSizes (const std::vector &fields, + std::vector &field_sizes); + + /** \brief Obtains the type of the PCLPointField from a specific size and type + * \param[in] size the size in bytes of the data field + * \param[in] type a char describing the type of the field ('F' = float, 'I' = signed, 'U' = unsigned) + * \ingroup common + */ + inline int + getFieldType (const int size, char type) + { + type = std::toupper (type, std::locale::classic ()); + switch (size) + { + case 1: + if (type == 'I') + return (pcl::PCLPointField::INT8); + if (type == 'U') + return (pcl::PCLPointField::UINT8); + + case 2: + if (type == 'I') + return (pcl::PCLPointField::INT16); + if (type == 'U') + return (pcl::PCLPointField::UINT16); + + case 4: + if (type == 'I') + return (pcl::PCLPointField::INT32); + if (type == 'U') + return (pcl::PCLPointField::UINT32); + if (type == 'F') + return (pcl::PCLPointField::FLOAT32); + + case 8: + return (pcl::PCLPointField::FLOAT64); + + default: + return (-1); + } + } + + /** \brief Obtains the type of the PCLPointField from a specific PCLPointField as a char + * \param[in] type the PCLPointField field type + * \ingroup common + */ + inline char + getFieldType (const int type) + { + switch (type) + { + case pcl::PCLPointField::INT8: + case pcl::PCLPointField::INT16: + case pcl::PCLPointField::INT32: + return ('I'); + + case pcl::PCLPointField::UINT8: + case pcl::PCLPointField::UINT16: + case pcl::PCLPointField::UINT32: + return ('U'); + + case pcl::PCLPointField::FLOAT32: + case pcl::PCLPointField::FLOAT64: + return ('F'); + default: + return ('?'); + } + } + + typedef enum + { + BORDER_CONSTANT = 0, BORDER_REPLICATE = 1, + BORDER_REFLECT = 2, BORDER_WRAP = 3, + BORDER_REFLECT_101 = 4, BORDER_TRANSPARENT = 5, + BORDER_DEFAULT = BORDER_REFLECT_101 + } InterpolationType; + + /** \brief \return the right index according to the interpolation type. + * \note this is adapted from OpenCV + * \param p the index of point to interpolate + * \param length the top/bottom row or left/right column index + * \param type the requested interpolation + * \throws pcl::BadArgumentException if type is unknown + */ + PCL_EXPORTS int + interpolatePointIndex (int p, int length, InterpolationType type); + + /** \brief Concatenate two pcl::PCLPointCloud2. + * \param[in] cloud1 the first input point cloud dataset + * \param[in] cloud2 the second input point cloud dataset + * \param[out] cloud_out the resultant output point cloud dataset + * \return true if successful, false if failed (e.g., name/number of fields differs) + * \ingroup common + */ + PCL_EXPORTS bool + concatenatePointCloud (const pcl::PCLPointCloud2 &cloud1, + const pcl::PCLPointCloud2 &cloud2, + pcl::PCLPointCloud2 &cloud_out); + + /** \brief Extract the indices of a given point cloud as a new point cloud + * \param[in] cloud_in the input point cloud dataset + * \param[in] indices the vector of indices representing the points to be copied from \a cloud_in + * \param[out] cloud_out the resultant output point cloud dataset + * \note Assumes unique indices. + * \ingroup common + */ + PCL_EXPORTS void + copyPointCloud (const pcl::PCLPointCloud2 &cloud_in, + const std::vector &indices, + pcl::PCLPointCloud2 &cloud_out); + + /** \brief Extract the indices of a given point cloud as a new point cloud + * \param[in] cloud_in the input point cloud dataset + * \param[in] indices the vector of indices representing the points to be copied from \a cloud_in + * \param[out] cloud_out the resultant output point cloud dataset + * \note Assumes unique indices. + * \ingroup common + */ + PCL_EXPORTS void + copyPointCloud (const pcl::PCLPointCloud2 &cloud_in, + const std::vector > &indices, + pcl::PCLPointCloud2 &cloud_out); + + /** \brief Copy fields and point cloud data from \a cloud_in to \a cloud_out + * \param[in] cloud_in the input point cloud dataset + * \param[out] cloud_out the resultant output point cloud dataset + * \ingroup common + */ + PCL_EXPORTS void + copyPointCloud (const pcl::PCLPointCloud2 &cloud_in, + pcl::PCLPointCloud2 &cloud_out); + + /** \brief Check if two given point types are the same or not. */ + template inline bool + isSamePointType () + { + return (typeid (Point1T) == typeid (Point2T)); + } + + /** \brief Extract the indices of a given point cloud as a new point cloud + * \param[in] cloud_in the input point cloud dataset + * \param[in] indices the vector of indices representing the points to be copied from \a cloud_in + * \param[out] cloud_out the resultant output point cloud dataset + * \note Assumes unique indices. + * \ingroup common + */ + template void + copyPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out); + + /** \brief Extract the indices of a given point cloud as a new point cloud + * \param[in] cloud_in the input point cloud dataset + * \param[in] indices the vector of indices representing the points to be copied from \a cloud_in + * \param[out] cloud_out the resultant output point cloud dataset + * \note Assumes unique indices. + * \ingroup common + */ + template void + copyPointCloud (const pcl::PointCloud &cloud_in, + const std::vector > &indices, + pcl::PointCloud &cloud_out); + + /** \brief Extract the indices of a given point cloud as a new point cloud + * \param[in] cloud_in the input point cloud dataset + * \param[in] indices the PointIndices structure representing the points to be copied from cloud_in + * \param[out] cloud_out the resultant output point cloud dataset + * \note Assumes unique indices. + * \ingroup common + */ + template void + copyPointCloud (const pcl::PointCloud &cloud_in, + const PointIndices &indices, + pcl::PointCloud &cloud_out); + + /** \brief Extract the indices of a given point cloud as a new point cloud + * \param[in] cloud_in the input point cloud dataset + * \param[in] indices the vector of indices representing the points to be copied from \a cloud_in + * \param[out] cloud_out the resultant output point cloud dataset + * \note Assumes unique indices. + * \ingroup common + */ + template void + copyPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out); + + /** \brief Copy all the fields from a given point cloud into a new point cloud + * \param[in] cloud_in the input point cloud dataset + * \param[out] cloud_out the resultant output point cloud dataset + * \ingroup common + */ + template void + copyPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out); + + /** \brief Extract the indices of a given point cloud as a new point cloud + * \param[in] cloud_in the input point cloud dataset + * \param[in] indices the vector of indices representing the points to be copied from \a cloud_in + * \param[out] cloud_out the resultant output point cloud dataset + * \note Assumes unique indices. + * \ingroup common + */ + template void + copyPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out); + + /** \brief Extract the indices of a given point cloud as a new point cloud + * \param[in] cloud_in the input point cloud dataset + * \param[in] indices the vector of indices representing the points to be copied from \a cloud_in + * \param[out] cloud_out the resultant output point cloud dataset + * \note Assumes unique indices. + * \ingroup common + */ + template void + copyPointCloud (const pcl::PointCloud &cloud_in, + const std::vector > &indices, + pcl::PointCloud &cloud_out); + + /** \brief Extract the indices of a given point cloud as a new point cloud + * \param[in] cloud_in the input point cloud dataset + * \param[in] indices the PointIndices structure representing the points to be copied from cloud_in + * \param[out] cloud_out the resultant output point cloud dataset + * \note Assumes unique indices. + * \ingroup common + */ + template void + copyPointCloud (const pcl::PointCloud &cloud_in, + const PointIndices &indices, + pcl::PointCloud &cloud_out); + + /** \brief Extract the indices of a given point cloud as a new point cloud + * \param[in] cloud_in the input point cloud dataset + * \param[in] indices the vector of indices representing the points to be copied from cloud_in + * \param[out] cloud_out the resultant output point cloud dataset + * \note Assumes unique indices. + * \ingroup common + */ + template void + copyPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out); + + /** \brief Copy a point cloud inside a larger one interpolating borders. + * \param[in] cloud_in the input point cloud dataset + * \param[out] cloud_out the resultant output point cloud dataset + * \param top + * \param bottom + * \param left + * \param right + * Position of cloud_in inside cloud_out is given by \a top, \a left, \a bottom \a right. + * \param[in] border_type the interpolating method (pcl::BORDER_XXX) + * BORDER_REPLICATE: aaaaaa|abcdefgh|hhhhhhh + * BORDER_REFLECT: fedcba|abcdefgh|hgfedcb + * BORDER_REFLECT_101: gfedcb|abcdefgh|gfedcba + * BORDER_WRAP: cdefgh|abcdefgh|abcdefg + * BORDER_CONSTANT: iiiiii|abcdefgh|iiiiiii with some specified 'i' + * BORDER_TRANSPARENT: mnopqr|abcdefgh|tuvwxyz where m-r and t-z are orignal values of cloud_out + * \param value + * \throw pcl::BadArgumentException if any of top, bottom, left or right is negative. + * \ingroup common + */ + template void + copyPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + int top, int bottom, int left, int right, + pcl::InterpolationType border_type, const PointT& value); + + /** \brief Concatenate two datasets representing different fields. + * + * \note If the input datasets have overlapping fields (i.e., both contain + * the same fields), then the data in the second cloud (cloud2_in) will + * overwrite the data in the first (cloud1_in). + * + * \param[in] cloud1_in the first input dataset + * \param[in] cloud2_in the second input dataset (overwrites the fields of the first dataset for those that are shared) + * \param[out] cloud_out the resultant output dataset created by the concatenation of all the fields in the input datasets + * \ingroup common + */ + template void + concatenateFields (const pcl::PointCloud &cloud1_in, + const pcl::PointCloud &cloud2_in, + pcl::PointCloud &cloud_out); + + /** \brief Concatenate two datasets representing different fields. + * + * \note If the input datasets have overlapping fields (i.e., both contain + * the same fields), then the data in the second cloud (cloud2_in) will + * overwrite the data in the first (cloud1_in). + * + * \param[in] cloud1_in the first input dataset + * \param[in] cloud2_in the second input dataset (overwrites the fields of the first dataset for those that are shared) + * \param[out] cloud_out the output dataset created by concatenating all the fields in the input datasets + * \ingroup common + */ + PCL_EXPORTS bool + concatenateFields (const pcl::PCLPointCloud2 &cloud1_in, + const pcl::PCLPointCloud2 &cloud2_in, + pcl::PCLPointCloud2 &cloud_out); + + /** \brief Copy the XYZ dimensions of a pcl::PCLPointCloud2 into Eigen format + * \param[in] in the point cloud message + * \param[out] out the resultant Eigen MatrixXf format containing XYZ0 / point + * \ingroup common + */ + PCL_EXPORTS bool + getPointCloudAsEigen (const pcl::PCLPointCloud2 &in, Eigen::MatrixXf &out); + + /** \brief Copy the XYZ dimensions from an Eigen MatrixXf into a pcl::PCLPointCloud2 message + * \param[in] in the Eigen MatrixXf format containing XYZ0 / point + * \param[out] out the resultant point cloud message + * \note the method assumes that the PCLPointCloud2 message already has the fields set up properly ! + * \ingroup common + */ + PCL_EXPORTS bool + getEigenAsPointCloud (Eigen::MatrixXf &in, pcl::PCLPointCloud2 &out); + + namespace io + { + /** \brief swap bytes order of a char array of length N + * \param bytes char array to swap + * \ingroup common + */ + template void + swapByte (char* bytes); + + /** \brief specialization of swapByte for dimension 1 + * \param bytes char array to swap + */ + template <> inline void + swapByte<1> (char* bytes) { bytes[0] = bytes[0]; } + + + /** \brief specialization of swapByte for dimension 2 + * \param bytes char array to swap + */ + template <> inline void + swapByte<2> (char* bytes) { std::swap (bytes[0], bytes[1]); } + + /** \brief specialization of swapByte for dimension 4 + * \param bytes char array to swap + */ + template <> inline void + swapByte<4> (char* bytes) + { + std::swap (bytes[0], bytes[3]); + std::swap (bytes[1], bytes[2]); + } + + /** \brief specialization of swapByte for dimension 8 + * \param bytes char array to swap + */ + template <> inline void + swapByte<8> (char* bytes) + { + std::swap (bytes[0], bytes[7]); + std::swap (bytes[1], bytes[6]); + std::swap (bytes[2], bytes[5]); + std::swap (bytes[3], bytes[4]); + } + + /** \brief swaps byte of an arbitrary type T casting it to char* + * \param value the data you want its bytes swapped + */ + template void + swapByte (T& value) + { + pcl::io::swapByte (reinterpret_cast (&value)); + } + } +} + +#include + +#endif //#ifndef PCL_COMMON_IO_H_ + diff --git a/pcl-1.7/pcl/common/norms.h b/pcl-1.7/pcl/common/norms.h new file mode 100644 index 0000000..d4fb82c --- /dev/null +++ b/pcl-1.7/pcl/common/norms.h @@ -0,0 +1,201 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_COMMON_NORMS_H_ +#define PCL_COMMON_NORMS_H_ + +/** + * \file norms.h + * Define standard C methods to calculate different norms + * \ingroup common + */ + +/*@{*/ +namespace pcl +{ + /** \brief Enum that defines all the types of norms available. + * \note Any new norm type should have its own enum value and its own case in the selectNorm () method + * \ingroup common + */ + enum NormType {L1, L2_SQR, L2, LINF, JM, B, SUBLINEAR, CS, DIV, PF, K, KL, HIK}; + + /** \brief Method that calculates any norm type available, based on the norm_type variable + * \note FloatVectorT is any type of vector with its values accessible via [ ] + * \ingroup common + * */ + template inline float + selectNorm (FloatVectorT A, FloatVectorT B, int dim, NormType norm_type); + + /** \brief Compute the L1 norm of the vector between two points + * \param A the first point + * \param B the second point + * \param dim the number of dimensions in \a A and \a B (dimensions must match) + * \note FloatVectorT is any type of vector with its values accessible via [ ] + * \ingroup common + */ + template inline float + L1_Norm (FloatVectorT A, FloatVectorT B, int dim); + + /** \brief Compute the squared L2 norm of the vector between two points + * \param A the first point + * \param B the second point + * \param dim the number of dimensions in \a A and \a B (dimensions must match) + * \note FloatVectorT is any type of vector with its values accessible via [ ] + * \ingroup common + */ + template inline float + L2_Norm_SQR (FloatVectorT A, FloatVectorT B, int dim); + + /** \brief Compute the L2 norm of the vector between two points + * \param A the first point + * \param B the second point + * \param dim the number of dimensions in \a A and \a B (dimensions must match) + * \note FloatVectorT is any type of vector with its values accessible via [ ] + * \ingroup common + */ + template inline float + L2_Norm (FloatVectorT A, FloatVectorT B, int dim); + + /** \brief Compute the L-infinity norm of the vector between two points + * \param A the first point + * \param B the second point + * \param dim the number of dimensions in \a A and \a B (dimensions must match) + * \note FloatVectorT is any type of vector with its values accessible via [ ] + * \ingroup common + */ + template inline float + Linf_Norm (FloatVectorT A, FloatVectorT B, int dim); + + /** \brief Compute the JM norm of the vector between two points + * \param A the first point + * \param B the second point + * \param dim the number of dimensions in \a A and \a B (dimensions must match) + * \note FloatVectorT is any type of vector with its values accessible via [ ] + * \ingroup common + */ + template inline float + JM_Norm (FloatVectorT A, FloatVectorT B, int dim); + + /** \brief Compute the B norm of the vector between two points + * \param A the first point + * \param B the second point + * \param dim the number of dimensions in \a A and \a B (dimensions must match) + * \note FloatVectorT is any type of vector with its values accessible via [ ] + * \ingroup common + */ + template inline float + B_Norm (FloatVectorT A, FloatVectorT B, int dim); + + /** \brief Compute the sublinear norm of the vector between two points + * \param A the first point + * \param B the second point + * \param dim the number of dimensions in \a A and \a B (dimensions must match) + * \note FloatVectorT is any type of vector with its values accessible via [ ] + * \ingroup common + */ + template inline float + Sublinear_Norm (FloatVectorT A, FloatVectorT B, int dim); + + /** \brief Compute the CS norm of the vector between two points + * \param A the first point + * \param B the second point + * \param dim the number of dimensions in \a A and \a B (dimensions must match) + * \note FloatVectorT is any type of vector with its values accessible via [ ] + * \ingroup common + */ + template inline float + CS_Norm (FloatVectorT A, FloatVectorT B, int dim); + + /** \brief Compute the div norm of the vector between two points + * \param A the first point + * \param B the second point + * \param dim the number of dimensions in \a A and \a B (dimensions must match) + * \note FloatVectorT is any type of vector with its values accessible via [ ] + * \ingroup common + */ + template inline float + Div_Norm (FloatVectorT A, FloatVectorT B, int dim); + + /** \brief Compute the PF norm of the vector between two points + * \param A the first point + * \param B the second point + * \param dim the number of dimensions in \a A and \a B (dimensions must match) + * \param P1 the first parameter + * \param P2 the second parameter + * \note FloatVectorT is any type of vector with its values accessible via [ ] + * \ingroup common + */ + template inline float + PF_Norm (FloatVectorT A, FloatVectorT B, int dim, float P1, float P2); + + /** \brief Compute the K norm of the vector between two points + * \param A the first point + * \param B the second point + * \param dim the number of dimensions in \a A and \a B (dimensions must match) + * \param P1 the first parameter + * \param P2 the second parameter + * \note FloatVectorT is any type of vector with its values accessible via [ ] + * \ingroup common + */ + template inline float + K_Norm (FloatVectorT A, FloatVectorT B, int dim, float P1, float P2); + + /** \brief Compute the KL between two discrete probability density functions + * \param A the first discrete PDF + * \param B the second discrete PDF + * \param dim the number of dimensions in \a A and \a B (dimensions must match) + * \note FloatVectorT is any type of vector with its values accessible via [ ] + * \ingroup common + */ + template inline float + KL_Norm (FloatVectorT A, FloatVectorT B, int dim); + + /** \brief Compute the HIK norm of the vector between two points + * \param A the first point + * \param B the second point + * \param dim the number of dimensions in \a A and \a B (dimensions must match) + * \note FloatVectorT is any type of vector with its values accessible via [ ] + * \ingroup common + */ + template inline float + HIK_Norm (FloatVectorT A, FloatVectorT B, int dim); +} +/*@}*/ +#include + +#endif //#ifndef PCL_NORMS_H_ diff --git a/pcl-1.7/pcl/common/pca.h b/pcl-1.7/pcl/common/pca.h new file mode 100644 index 0000000..509cbdc --- /dev/null +++ b/pcl-1.7/pcl/common/pca.h @@ -0,0 +1,252 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_PCA_H +#define PCL_PCA_H + +#include +#include + +namespace pcl +{ + /** Principal Component analysis (PCA) class.\n + * Principal components are extracted by singular values decomposition on the + * covariance matrix of the centered input cloud. Available data after pca computation + * are the mean of the input data, the eigenvalues (in descending order) and + * corresponding eigenvectors.\n + * Other methods allow projection in the eigenspace, reconstruction from eigenspace and + * update of the eigenspace with a new datum (according Matej Artec, Matjaz Jogan and + * Ales Leonardis: "Incremental PCA for On-line Visual Learning and Recognition"). + * + * \author Nizar Sallem + * \ingroup common + */ + template + class PCA : public pcl::PCLBase + { + public: + typedef pcl::PCLBase Base; + typedef typename Base::PointCloud PointCloud; + typedef typename Base::PointCloudPtr PointCloudPtr; + typedef typename Base::PointCloudConstPtr PointCloudConstPtr; + typedef typename Base::PointIndicesPtr PointIndicesPtr; + typedef typename Base::PointIndicesConstPtr PointIndicesConstPtr; + + using Base::input_; + using Base::indices_; + using Base::initCompute; + using Base::setInputCloud; + + /** Updating method flag */ + enum FLAG + { + /** keep the new basis vectors if possible */ + increase, + /** preserve subspace dimension */ + preserve + }; + + /** \brief Default Constructor + * \param basis_only flag to compute only the PCA basis + */ + PCA (bool basis_only = false) + : Base () + , compute_done_ (false) + , basis_only_ (basis_only) + , eigenvectors_ () + , coefficients_ () + , mean_ () + , eigenvalues_ () + {} + + /** \brief Constructor with direct computation + * X input m*n matrix (ie n vectors of R(m)) + * basis_only flag to compute only the PCA basis + */ + PCL_DEPRECATED ("Use PCA (bool basis_only); setInputCloud (X.makeShared ()); instead") + PCA (const pcl::PointCloud& X, bool basis_only = false); + + /** Copy Constructor + * \param[in] pca PCA object + */ + PCA (PCA const & pca) + : Base (pca) + , compute_done_ (pca.compute_done_) + , basis_only_ (pca.basis_only_) + , eigenvectors_ (pca.eigenvectors_) + , coefficients_ (pca.coefficients_) + , mean_ (pca.mean_) + , eigenvalues_ (pca.eigenvalues_) + {} + + /** Assignment operator + * \param[in] pca PCA object + */ + inline PCA& + operator= (PCA const & pca) + { + eigenvectors_ = pca.eigenvectors; + coefficients_ = pca.coefficients; + eigenvalues_ = pca.eigenvalues; + mean_ = pca.mean; + return (*this); + } + + /** \brief Provide a pointer to the input dataset + * \param cloud the const boost shared pointer to a PointCloud message + */ + inline void + setInputCloud (const PointCloudConstPtr &cloud) + { + Base::setInputCloud (cloud); + compute_done_ = false; + } + + /** \brief Mean accessor + * \throw InitFailedException + */ + inline Eigen::Vector4f& + getMean () + { + if (!compute_done_) + initCompute (); + if (!compute_done_) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::PCA::getMean] PCA initCompute failed"); + return (mean_); + } + + /** Eigen Vectors accessor + * \throw InitFailedException + */ + inline Eigen::Matrix3f& + getEigenVectors () + { + if (!compute_done_) + initCompute (); + if (!compute_done_) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::PCA::getEigenVectors] PCA initCompute failed"); + return (eigenvectors_); + } + + /** Eigen Values accessor + * \throw InitFailedException + */ + inline Eigen::Vector3f& + getEigenValues () + { + if (!compute_done_) + initCompute (); + if (!compute_done_) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::PCA::getEigenVectors] PCA getEigenValues failed"); + return (eigenvalues_); + } + + /** Coefficients accessor + * \throw InitFailedException + */ + inline Eigen::MatrixXf& + getCoefficients () + { + if (!compute_done_) + initCompute (); + if (!compute_done_) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::PCA::getEigenVectors] PCA getCoefficients failed"); + return (coefficients_); + } + + /** update PCA with a new point + * \param[in] input input point + * \param[in] flag update flag + * \throw InitFailedException + */ + inline void + update (const PointT& input, FLAG flag = preserve); + + /** Project point on the eigenspace. + * \param[in] input point from original dataset + * \param[out] projection the point in eigen vectors space + * \throw InitFailedException + */ + inline void + project (const PointT& input, PointT& projection); + + /** Project cloud on the eigenspace. + * \param[in] input cloud from original dataset + * \param[out] projection the cloud in eigen vectors space + * \throw InitFailedException + */ + inline void + project (const PointCloud& input, PointCloud& projection); + + /** Reconstruct point from its projection + * \param[in] projection point from eigenvector space + * \param[out] input reconstructed point + * \throw InitFailedException + */ + inline void + reconstruct (const PointT& projection, PointT& input); + + /** Reconstruct cloud from its projection + * \param[in] projection cloud from eigenvector space + * \param[out] input reconstructed cloud + * \throw InitFailedException + */ + inline void + reconstruct (const PointCloud& projection, PointCloud& input); + + private: + inline bool + initCompute (); + + bool compute_done_; + bool basis_only_; + Eigen::Matrix3f eigenvectors_; + Eigen::MatrixXf coefficients_; + Eigen::Vector4f mean_; + Eigen::Vector3f eigenvalues_; + }; // class PCA +} // namespace pcl + +#include + +#endif // PCL_PCA_H + diff --git a/pcl-1.7/pcl/common/piecewise_linear_function.h b/pcl-1.7/pcl/common/piecewise_linear_function.h new file mode 100644 index 0000000..1be4eb0 --- /dev/null +++ b/pcl-1.7/pcl/common/piecewise_linear_function.h @@ -0,0 +1,81 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +/* \author Bastian Steder */ + +#ifndef PCL_PIECEWISE_LINEAR_FUNCTION_H_ +#define PCL_PIECEWISE_LINEAR_FUNCTION_H_ + +#include + +namespace pcl +{ + /** + * \brief This provides functionalities to efficiently return values for piecewise linear function + * \ingroup common + */ + class PiecewiseLinearFunction + { + public: + // =====CONSTRUCTOR & DESTRUCTOR===== + //! Constructor + PiecewiseLinearFunction (float factor, float offset); + + // =====PUBLIC METHODS===== + //! Get the list of known data points + std::vector& + getDataPoints () + { + return data_points_; + } + + //! Get the value of the function at the given point + inline float + getValue (float point) const; + + // =====PUBLIC MEMBER VARIABLES===== + + protected: + // =====PROTECTED MEMBER VARIABLES===== + std::vector data_points_; + float factor_; + float offset_; + }; + +} // end namespace pcl + +#include + +#endif //#ifndef PCL_PIECEWISE_LINEAR_FUNCTION_H_ diff --git a/pcl-1.7/pcl/common/point_operators.h b/pcl-1.7/pcl/common/point_operators.h new file mode 100644 index 0000000..a28397f --- /dev/null +++ b/pcl-1.7/pcl/common/point_operators.h @@ -0,0 +1,44 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_COMMON_POINT_OPERATORS_H +#define PCL_COMMON_POINT_OPERATORS_H + +#endif diff --git a/pcl-1.7/pcl/common/point_tests.h b/pcl-1.7/pcl/common/point_tests.h new file mode 100644 index 0000000..f202af7 --- /dev/null +++ b/pcl-1.7/pcl/common/point_tests.h @@ -0,0 +1,111 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: point_types.hpp 6415 2012-07-16 20:11:47Z rusu $ + * + */ + +#ifndef PCL_COMMON_POINT_TESTS_H_ +#define PCL_COMMON_POINT_TESTS_H_ + +#ifdef _MSC_VER +#include +#endif + +namespace pcl +{ + /** Tests if the 3D components of a point are all finite + * param[in] pt point to be tested + */ + template inline bool + isFinite (const PointT &pt) + { + return (pcl_isfinite (pt.x) && pcl_isfinite (pt.y) && pcl_isfinite (pt.z)); + } + +#ifdef _MSC_VER + template inline bool + isFinite (const Eigen::internal::workaround_msvc_stl_support &pt) + { + return isFinite (static_cast (pt)); + } +#endif + + template<> inline bool isFinite (const pcl::RGB&) { return (true); } + template<> inline bool isFinite (const pcl::Label&) { return (true); } + template<> inline bool isFinite (const pcl::Axis&) { return (true); } + template<> inline bool isFinite (const pcl::Intensity&) { return (true); } + template<> inline bool isFinite (const pcl::MomentInvariants&) { return (true); } + template<> inline bool isFinite (const pcl::PrincipalRadiiRSD&) { return (true); } + template<> inline bool isFinite (const pcl::Boundary&) { return (true); } + template<> inline bool isFinite (const pcl::PrincipalCurvatures&) { return (true); } + template<> inline bool isFinite (const pcl::SHOT352&) { return (true); } + template<> inline bool isFinite (const pcl::SHOT1344&) { return (true); } + template<> inline bool isFinite (const pcl::ReferenceFrame&) { return (true); } + template<> inline bool isFinite (const pcl::ShapeContext1980&) { return (true); } + template<> inline bool isFinite (const pcl::PFHSignature125&) { return (true); } + template<> inline bool isFinite (const pcl::PFHRGBSignature250&) { return (true); } + template<> inline bool isFinite (const pcl::PPFSignature&) { return (true); } + template<> inline bool isFinite (const pcl::PPFRGBSignature&) { return (true); } + template<> inline bool isFinite (const pcl::NormalBasedSignature12&) { return (true); } + template<> inline bool isFinite (const pcl::FPFHSignature33&) { return (true); } + template<> inline bool isFinite (const pcl::VFHSignature308&) { return (true); } + template<> inline bool isFinite (const pcl::ESFSignature640&) { return (true); } + template<> inline bool isFinite (const pcl::IntensityGradient&) { return (true); } + + // specification for pcl::PointXY + template <> inline bool + isFinite (const pcl::PointXY &p) + { + return (pcl_isfinite (p.x) && pcl_isfinite (p.y)); + } + + // specification for pcl::BorderDescription + template <> inline bool + isFinite (const pcl::BorderDescription &p) + { + return (pcl_isfinite (p.x) && pcl_isfinite (p.y)); + } + + // specification for pcl::Normal + template <> inline bool + isFinite (const pcl::Normal &n) + { + return (pcl_isfinite (n.normal_x) && pcl_isfinite (n.normal_y) && pcl_isfinite (n.normal_z)); + } +} + +#endif // PCL_COMMON_POINT_TESTS_H_ + diff --git a/pcl-1.7/pcl/common/polynomial_calculations.h b/pcl-1.7/pcl/common/polynomial_calculations.h new file mode 100644 index 0000000..9312731 --- /dev/null +++ b/pcl-1.7/pcl/common/polynomial_calculations.h @@ -0,0 +1,135 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_POLYNOMIAL_CALCULATIONS_H_ +#define PCL_POLYNOMIAL_CALCULATIONS_H_ + +#include +#include + +namespace pcl +{ + /** \brief This provides some functionality for polynomials, + * like finding roots or approximating bivariate polynomials + * \author Bastian Steder + * \ingroup common + */ + template + class PolynomialCalculationsT + { + public: + // =====CONSTRUCTOR & DESTRUCTOR===== + PolynomialCalculationsT (); + ~PolynomialCalculationsT (); + + // =====PUBLIC STRUCTS===== + //! Parameters used in this class + struct Parameters + { + Parameters () : zero_value (), sqr_zero_value () { setZeroValue (1e-6);} + //! Set zero_value + void + setZeroValue (real new_zero_value); + + real zero_value; //!< Every value below this is considered to be zero + real sqr_zero_value; //!< sqr of the above + }; + + // =====PUBLIC METHODS===== + /** Solves an equation of the form ax^4 + bx^3 + cx^2 +dx + e = 0 + * See http://en.wikipedia.org/wiki/Quartic_equation#Summary_of_Ferrari.27s_method */ + inline void + solveQuarticEquation (real a, real b, real c, real d, real e, std::vector& roots) const; + + /** Solves an equation of the form ax^3 + bx^2 + cx + d = 0 + * See http://en.wikipedia.org/wiki/Cubic_equation */ + inline void + solveCubicEquation (real a, real b, real c, real d, std::vector& roots) const; + + /** Solves an equation of the form ax^2 + bx + c = 0 + * See http://en.wikipedia.org/wiki/Quadratic_equation */ + inline void + solveQuadraticEquation (real a, real b, real c, std::vector& roots) const; + + /** Solves an equation of the form ax + b = 0 */ + inline void + solveLinearEquation (real a, real b, std::vector& roots) const; + + /** Get the bivariate polynomial approximation for Z(X,Y) from the given sample points. + * The parameters a,b,c,... for the polynom are returned. + * The order is, e.g., for degree 1: ax+by+c and for degree 2: ax²+bxy+cx+dy²+ey+f. + * error is set to true if the approximation did not work for any reason + * (not enough points, matrix not invertible, etc.) */ + inline BivariatePolynomialT + bivariatePolynomialApproximation (std::vector >& samplePoints, + unsigned int polynomial_degree, bool& error) const; + + //! Same as above, using a reference for the return value + inline bool + bivariatePolynomialApproximation (std::vector >& samplePoints, + unsigned int polynomial_degree, BivariatePolynomialT& ret) const; + + //! Set the minimum value under which values are considered zero + inline void + setZeroValue (real new_zero_value) { parameters_.setZeroValue(new_zero_value); } + + protected: + // =====PROTECTED METHODS===== + //! check if fabs(d) PolynomialCalculationsd; + typedef PolynomialCalculationsT PolynomialCalculations; + +} // end namespace + +#include + +#endif diff --git a/pcl-1.7/pcl/common/poses_from_matches.h b/pcl-1.7/pcl/common/poses_from_matches.h new file mode 100644 index 0000000..fa5c4c9 --- /dev/null +++ b/pcl-1.7/pcl/common/poses_from_matches.h @@ -0,0 +1,132 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_POSES_FROM_MATCHES_H_ +#define PCL_POSES_FROM_MATCHES_H_ + +#include +#include + +namespace pcl +{ + /** + * \brief calculate 3D transformation based on point correspondencdes + * \author Bastian Steder + * \ingroup common + */ + class PCL_EXPORTS PosesFromMatches + { + public: + // =====CONSTRUCTOR & DESTRUCTOR===== + //! Constructor + PosesFromMatches(); + //! Destructor + ~PosesFromMatches(); + + // =====STRUCTS===== + //! Parameters used in this class + struct PCL_EXPORTS Parameters + { + Parameters() : max_correspondence_distance_error(0.2f) {} + float max_correspondence_distance_error; // As a fraction + }; + + //! A result of the pose estimation process + struct PoseEstimate + { + PoseEstimate () : + transformation (Eigen::Affine3f::Identity ()), + score (0), + correspondence_indices (0) + {} + + Eigen::Affine3f transformation; //!< The estimated transformation between the two coordinate systems + float score; //!< An estimate in [0,1], how good the estimated pose is + std::vector correspondence_indices; //!< The indices of the used correspondences + + struct IsBetter + { + bool operator()(const PoseEstimate& pe1, const PoseEstimate& pe2) const { return pe1.score>pe2.score;} + }; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + // =====TYPEDEFS===== + typedef std::vector > PoseEstimatesVector; + + + // =====STATIC METHODS===== + + // =====PUBLIC METHODS===== + /** Use single 6DOF correspondences to estimate transformations between the coordinate systems. + * Use max_no_of_results=-1 to use all. + * It is assumed, that the correspondences are sorted from good to bad. */ + void + estimatePosesUsing1Correspondence ( + const PointCorrespondences6DVector& correspondences, + int max_no_of_results, PoseEstimatesVector& pose_estimates) const; + + /** Use pairs of 6DOF correspondences to estimate transformations between the coordinate systems. + * It is assumed, that the correspondences are sorted from good to bad. */ + void + estimatePosesUsing2Correspondences ( + const PointCorrespondences6DVector& correspondences, + int max_no_of_tested_combinations, int max_no_of_results, + PoseEstimatesVector& pose_estimates) const; + + /** Use triples of 6DOF correspondences to estimate transformations between the coordinate systems. + * It is assumed, that the correspondences are sorted from good to bad. */ + void + estimatePosesUsing3Correspondences ( + const PointCorrespondences6DVector& correspondences, + int max_no_of_tested_combinations, int max_no_of_results, + PoseEstimatesVector& pose_estimates) const; + + /// Get a reference to the parameters struct + Parameters& + getParameters () { return parameters_; } + + protected: + // =====PROTECTED MEMBER VARIABLES===== + Parameters parameters_; + + }; + +} // end namespace pcl + +#endif //#ifndef PCL_POSES_FROM_MATCHES_H_ diff --git a/pcl-1.7/pcl/common/projection_matrix.h b/pcl-1.7/pcl/common/projection_matrix.h new file mode 100644 index 0000000..616e2d4 --- /dev/null +++ b/pcl-1.7/pcl/common/projection_matrix.h @@ -0,0 +1,80 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef __PCL_ORGANIZED_PROJECTION_MATRIX_H__ +#define __PCL_ORGANIZED_PROJECTION_MATRIX_H__ + +#include +#include + +/** + * \file common/geometry.h + * Defines some geometrical functions and utility functions + * \ingroup common + */ + +/*@{*/ +namespace pcl +{ + template class PointCloud; + + /** \brief Estimates the projection matrix P = K * (R|-R*t) from organized point clouds, with + * K = [[fx, s, cx], [0, fy, cy], [0, 0, 1]] + * R = rotation matrix and + * t = translation vector + * + * \param[in] cloud input cloud. Must be organized and from a projective device. e.g. stereo or kinect, ... + * \param[out] projection_matrix output projection matrix + * \param[in] indices The indices to be used to determine the projection matrix + * \return the resudial error. A high residual indicates, that the point cloud was not from a projective device. + */ + template double + estimateProjectionMatrix (typename pcl::PointCloud::ConstPtr cloud, Eigen::Matrix& projection_matrix, const std::vector& indices = std::vector ()); + + /** \brief Determines the camera matrix from the given projection matrix. + * \note This method does NOT use a RQ decomposition, but uses the fact that the left 3x3 matrix P' of P squared eliminates the rotational part. + * P' = K * R -> P' * P'^T = K * R * R^T * K = K * K^T + * \param[in] projection_matrix + * \param[out] camera_matrix + */ + PCL_EXPORTS void + getCameraMatrixFromProjectionMatrix (const Eigen::Matrix& projection_matrix, Eigen::Matrix3f& camera_matrix); +} + +#include + +#endif // __PCL_ORGANIZED_PROJECTION_MATRIX_H__ diff --git a/pcl-1.7/pcl/common/random.h b/pcl-1.7/pcl/common/random.h new file mode 100644 index 0000000..da44608 --- /dev/null +++ b/pcl-1.7/pcl/common/random.h @@ -0,0 +1,233 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_COMMON_RANDOM_H_ +#define PCL_COMMON_RANDOM_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace common + { + /// uniform distribution dummy struct + template struct uniform_distribution; + /// uniform distribution int specialized + template<> + struct uniform_distribution + { + typedef boost::uniform_int type; + }; + /// uniform distribution float specialized + template<> + struct uniform_distribution + { + typedef boost::uniform_real type; + }; + /// normal distribution + template + struct normal_distribution + { + typedef boost::normal_distribution type; + }; + + /** \brief UniformGenerator class generates a random number from range [min, max] at each run picked + * according to a uniform distribution i.e eaach number within [min, max] has almost the same + * probability of being drawn. + * + * \author Nizar Sallem + */ + template + class UniformGenerator + { + public: + struct Parameters + { + Parameters (T _min = 0, T _max = 1, pcl::uint32_t _seed = 1) + : min (_min) + , max (_max) + , seed (_seed) + {} + + T min; + T max; + pcl::uint32_t seed; + }; + + /** Constructor + * \param min: included lower bound + * \param max: included higher bound + * \param seed: seeding value + */ + UniformGenerator(T min = 0, T max = 1, pcl::uint32_t seed = -1); + + /** Constructor + * \param parameters uniform distribution parameters and generator seed + */ + UniformGenerator(const Parameters& parameters); + + /** Change seed value + * \param[in] seed new generator seed value + */ + void + setSeed (pcl::uint32_t seed); + + /** Set the uniform number generator parameters + * \param[in] min minimum allowed value + * \param[in] max maximum allowed value + * \param[in] seed random number generator seed (applied if != -1) + */ + void + setParameters (T min, T max, pcl::uint32_t seed = -1); + + /** Set generator parameters + * \param parameters uniform distribution parameters and generator seed + */ + void + setParameters (const Parameters& parameters); + + /// \return uniform distribution parameters and generator seed + const Parameters& + getParameters () { return (parameters_); } + + /// \return a randomly generated number in the interval [min, max] + inline T + run () { return (generator_ ()); } + + private: + typedef boost::mt19937 EngineType; + typedef typename uniform_distribution::type DistributionType; + /// parameters + Parameters parameters_; + /// uniform distribution + DistributionType distribution_; + /// random number generator + EngineType rng_; + /// generator of random number from a uniform distribution + boost::variate_generator generator_; + }; + + /** \brief NormalGenerator class generates a random number from a normal distribution specified + * by (mean, sigma). + * + * \author Nizar Sallem + */ + template + class NormalGenerator + { + public: + struct Parameters + { + Parameters (T _mean = 0, T _sigma = 1, pcl::uint32_t _seed = 1) + : mean (_mean) + , sigma (_sigma) + , seed (_seed) + {} + + T mean; + T sigma; + pcl::uint32_t seed; + }; + + /** Constructor + * \param[in] mean normal mean + * \param[in] sigma normal variation + * \param[in] seed seeding value + */ + NormalGenerator(T mean = 0, T sigma = 1, pcl::uint32_t seed = -1); + + /** Constructor + * \param parameters normal distribution parameters and seed + */ + NormalGenerator(const Parameters& parameters); + + /** Change seed value + * \param[in] seed new seed value + */ + void + setSeed (pcl::uint32_t seed); + + /** Set the normal number generator parameters + * \param[in] mean mean of the normal distribution + * \param[in] sigma standard variation of the normal distribution + * \param[in] seed random number generator seed (applied if != -1) + */ + void + setParameters (T mean, T sigma, pcl::uint32_t seed = -1); + + /** Set generator parameters + * \param parameters normal distribution parameters and seed + */ + void + setParameters (const Parameters& parameters); + + /// \return normal distribution parameters and generator seed + const Parameters& + getParameters () { return (parameters_); } + + /// \return a randomly generated number in the normal distribution (mean, sigma) + inline T + run () { return (generator_ ()); } + + typedef boost::mt19937 EngineType; + typedef typename normal_distribution::type DistributionType; + /// parameters + Parameters parameters_; + /// normal distribution + DistributionType distribution_; + /// random number generator + EngineType rng_; + /// generator of random number from a normal distribution + boost::variate_generator generator_; + }; + } +} + +#include + +#endif diff --git a/pcl-1.7/pcl/common/register_point_struct.h b/pcl-1.7/pcl/common/register_point_struct.h new file mode 100644 index 0000000..57a0e42 --- /dev/null +++ b/pcl-1.7/pcl/common/register_point_struct.h @@ -0,0 +1,367 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTER_POINT_STRUCT_H_ +#define PCL_REGISTER_POINT_STRUCT_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#if defined _MSC_VER + #pragma warning (push, 2) + // 4244 : conversion from 'type1' to 'type2', possible loss of data + #pragma warning (disable: 4244) +#endif + +//https://bugreports.qt-project.org/browse/QTBUG-22829 +#ifndef Q_MOC_RUN +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#endif +#include //offsetof + +// Must be used in global namespace with name fully qualified +#define POINT_CLOUD_REGISTER_POINT_STRUCT(name, fseq) \ + POINT_CLOUD_REGISTER_POINT_STRUCT_I(name, \ + BOOST_PP_CAT(POINT_CLOUD_REGISTER_POINT_STRUCT_X fseq, 0)) \ + /***/ + +#define POINT_CLOUD_REGISTER_POINT_WRAPPER(wrapper, pod) \ + BOOST_MPL_ASSERT_MSG(sizeof(wrapper) == sizeof(pod), POINT_WRAPPER_AND_POD_TYPES_HAVE_DIFFERENT_SIZES, (wrapper&, pod&)); \ + namespace pcl { \ + namespace traits { \ + template<> struct POD { typedef pod type; }; \ + } \ + } \ + /***/ + +// These macros help transform the unusual data structure (type, name, tag)(type, name, tag)... +// into a proper preprocessor sequence of 3-tuples ((type, name, tag))((type, name, tag))... +#define POINT_CLOUD_REGISTER_POINT_STRUCT_X(type, name, tag) \ + ((type, name, tag)) POINT_CLOUD_REGISTER_POINT_STRUCT_Y +#define POINT_CLOUD_REGISTER_POINT_STRUCT_Y(type, name, tag) \ + ((type, name, tag)) POINT_CLOUD_REGISTER_POINT_STRUCT_X +#define POINT_CLOUD_REGISTER_POINT_STRUCT_X0 +#define POINT_CLOUD_REGISTER_POINT_STRUCT_Y0 + +namespace pcl +{ + namespace traits + { + template inline + typename boost::disable_if_c::value>::type + plus (T &l, const T &r) + { + l += r; + } + + template inline + typename boost::enable_if_c::value>::type + plus (typename boost::remove_const::type &l, const T &r) + { + typedef typename boost::remove_all_extents::type type; + static const uint32_t count = sizeof (T) / sizeof (type); + for (int i = 0; i < count; ++i) + l[i] += r[i]; + } + + template inline + typename boost::disable_if_c::value>::type + plusscalar (T1 &p, const T2 &scalar) + { + p += scalar; + } + + template inline + typename boost::enable_if_c::value>::type + plusscalar (T1 &p, const T2 &scalar) + { + typedef typename boost::remove_all_extents::type type; + static const uint32_t count = sizeof (T1) / sizeof (type); + for (int i = 0; i < count; ++i) + p[i] += scalar; + } + + template inline + typename boost::disable_if_c::value>::type + minus (T &l, const T &r) + { + l -= r; + } + + template inline + typename boost::enable_if_c::value>::type + minus (typename boost::remove_const::type &l, const T &r) + { + typedef typename boost::remove_all_extents::type type; + static const uint32_t count = sizeof (T) / sizeof (type); + for (int i = 0; i < count; ++i) + l[i] -= r[i]; + } + + template inline + typename boost::disable_if_c::value>::type + minusscalar (T1 &p, const T2 &scalar) + { + p -= scalar; + } + + template inline + typename boost::enable_if_c::value>::type + minusscalar (T1 &p, const T2 &scalar) + { + typedef typename boost::remove_all_extents::type type; + static const uint32_t count = sizeof (T1) / sizeof (type); + for (int i = 0; i < count; ++i) + p[i] -= scalar; + } + + template inline + typename boost::disable_if_c::value>::type + mulscalar (T1 &p, const T2 &scalar) + { + p *= scalar; + } + + template inline + typename boost::enable_if_c::value>::type + mulscalar (T1 &p, const T2 &scalar) + { + typedef typename boost::remove_all_extents::type type; + static const uint32_t count = sizeof (T1) / sizeof (type); + for (int i = 0; i < count; ++i) + p[i] *= scalar; + } + + template inline + typename boost::disable_if_c::value>::type + divscalar (T1 &p, const T2 &scalar) + { + p /= scalar; + } + + template inline + typename boost::enable_if_c::value>::type + divscalar (T1 &p, const T2 &scalar) + { + typedef typename boost::remove_all_extents::type type; + static const uint32_t count = sizeof (T1) / sizeof (type); + for (int i = 0; i < count; ++i) + p[i] /= scalar; + } + } +} + +// Point operators +#define PCL_PLUSEQ_POINT_TAG(r, data, elem) \ + pcl::traits::plus (lhs.BOOST_PP_TUPLE_ELEM(3, 1, elem), \ + rhs.BOOST_PP_TUPLE_ELEM(3, 1, elem)); \ + /***/ + +#define PCL_PLUSEQSC_POINT_TAG(r, data, elem) \ + pcl::traits::plusscalar (p.BOOST_PP_TUPLE_ELEM(3, 1, elem), \ + scalar); \ + /***/ + //p.BOOST_PP_TUPLE_ELEM(3, 1, elem) += scalar; \ + +#define PCL_MINUSEQ_POINT_TAG(r, data, elem) \ + pcl::traits::minus (lhs.BOOST_PP_TUPLE_ELEM(3, 1, elem), \ + rhs.BOOST_PP_TUPLE_ELEM(3, 1, elem)); \ + /***/ + +#define PCL_MINUSEQSC_POINT_TAG(r, data, elem) \ + pcl::traits::minusscalar (p.BOOST_PP_TUPLE_ELEM(3, 1, elem), \ + scalar); \ + /***/ + //p.BOOST_PP_TUPLE_ELEM(3, 1, elem) -= scalar; \ + +#define PCL_MULEQSC_POINT_TAG(r, data, elem) \ + pcl::traits::mulscalar (p.BOOST_PP_TUPLE_ELEM(3, 1, elem), \ + scalar); \ + /***/ + +#define PCL_DIVEQSC_POINT_TAG(r, data, elem) \ + pcl::traits::divscalar (p.BOOST_PP_TUPLE_ELEM(3, 1, elem), \ + scalar); \ + /***/ + +// Construct type traits given full sequence of (type, name, tag) triples +// BOOST_MPL_ASSERT_MSG(boost::is_pod::value, +// REGISTERED_POINT_TYPE_MUST_BE_PLAIN_OLD_DATA, (name)); +#define POINT_CLOUD_REGISTER_POINT_STRUCT_I(name, seq) \ + namespace pcl \ + { \ + namespace fields \ + { \ + BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_TAG, name, seq) \ + } \ + namespace traits \ + { \ + BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_NAME, name, seq) \ + BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_OFFSET, name, seq) \ + BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_DATATYPE, name, seq) \ + POINT_CLOUD_REGISTER_POINT_FIELD_LIST(name, POINT_CLOUD_EXTRACT_TAGS(seq)) \ + } \ + namespace common \ + { \ + inline const name& \ + operator+= (name& lhs, const name& rhs) \ + { \ + BOOST_PP_SEQ_FOR_EACH(PCL_PLUSEQ_POINT_TAG, _, seq) \ + return (lhs); \ + } \ + inline const name& \ + operator+= (name& p, const float& scalar) \ + { \ + BOOST_PP_SEQ_FOR_EACH(PCL_PLUSEQSC_POINT_TAG, _, seq) \ + return (p); \ + } \ + inline const name operator+ (const name& lhs, const name& rhs) \ + { name result = lhs; result += rhs; return (result); } \ + inline const name operator+ (const float& scalar, const name& p) \ + { name result = p; result += scalar; return (result); } \ + inline const name operator+ (const name& p, const float& scalar) \ + { name result = p; result += scalar; return (result); } \ + inline const name& \ + operator-= (name& lhs, const name& rhs) \ + { \ + BOOST_PP_SEQ_FOR_EACH(PCL_MINUSEQ_POINT_TAG, _, seq) \ + return (lhs); \ + } \ + inline const name& \ + operator-= (name& p, const float& scalar) \ + { \ + BOOST_PP_SEQ_FOR_EACH(PCL_MINUSEQSC_POINT_TAG, _, seq) \ + return (p); \ + } \ + inline const name operator- (const name& lhs, const name& rhs) \ + { name result = lhs; result -= rhs; return (result); } \ + inline const name operator- (const float& scalar, const name& p) \ + { name result = p; result -= scalar; return (result); } \ + inline const name operator- (const name& p, const float& scalar) \ + { name result = p; result -= scalar; return (result); } \ + inline const name& \ + operator*= (name& p, const float& scalar) \ + { \ + BOOST_PP_SEQ_FOR_EACH(PCL_MULEQSC_POINT_TAG, _, seq) \ + return (p); \ + } \ + inline const name operator* (const float& scalar, const name& p) \ + { name result = p; result *= scalar; return (result); } \ + inline const name operator* (const name& p, const float& scalar) \ + { name result = p; result *= scalar; return (result); } \ + inline const name& \ + operator/= (name& p, const float& scalar) \ + { \ + BOOST_PP_SEQ_FOR_EACH(PCL_DIVEQSC_POINT_TAG, _, seq) \ + return (p); \ + } \ + inline const name operator/ (const float& scalar, const name& p) \ + { name result = p; result /= scalar; return (result); } \ + inline const name operator/ (const name& p, const float& scalar) \ + { name result = p; result /= scalar; return (result); } \ + } \ + } \ + /***/ + +#define POINT_CLOUD_REGISTER_FIELD_TAG(r, name, elem) \ + struct BOOST_PP_TUPLE_ELEM(3, 2, elem); \ + /***/ + +#define POINT_CLOUD_REGISTER_FIELD_NAME(r, point, elem) \ + template \ + struct name \ + { \ + static const char value[]; \ + }; \ + \ + template \ + const char name::value[] = \ + BOOST_PP_STRINGIZE(BOOST_PP_TUPLE_ELEM(3, 2, elem)); \ + /***/ + +#define POINT_CLOUD_REGISTER_FIELD_OFFSET(r, name, elem) \ + template<> struct offset \ + { \ + static const size_t value = offsetof(name, BOOST_PP_TUPLE_ELEM(3, 1, elem)); \ + }; \ + /***/ + +// \note: the mpl::identity weirdness is to support array types without requiring the +// user to wrap them. The basic problem is: +// typedef float[81] type; // SYNTAX ERROR! +// typedef float type[81]; // OK, can now use "type" as a synonym for float[81] +#define POINT_CLOUD_REGISTER_FIELD_DATATYPE(r, name, elem) \ + template<> struct datatype \ + { \ + typedef boost::mpl::identity::type type; \ + typedef decomposeArray decomposed; \ + static const uint8_t value = asEnum::value; \ + static const uint32_t size = decomposed::value; \ + }; \ + /***/ + +#define POINT_CLOUD_TAG_OP(s, data, elem) pcl::fields::BOOST_PP_TUPLE_ELEM(3, 2, elem) + +#define POINT_CLOUD_EXTRACT_TAGS(seq) BOOST_PP_SEQ_TRANSFORM(POINT_CLOUD_TAG_OP, _, seq) + +#define POINT_CLOUD_REGISTER_POINT_FIELD_LIST(name, seq) \ + template<> struct fieldList \ + { \ + typedef boost::mpl::vector type; \ + }; \ + /***/ + +#if defined _MSC_VER + #pragma warning (pop) +#endif + +#endif //#ifndef PCL_REGISTER_POINT_STRUCT_H_ diff --git a/pcl-1.7/pcl/common/spring.h b/pcl-1.7/pcl/common/spring.h new file mode 100644 index 0000000..db7268d --- /dev/null +++ b/pcl-1.7/pcl/common/spring.h @@ -0,0 +1,132 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_POINT_CLOUD_SPRING_H_ +#define PCL_POINT_CLOUD_SPRING_H_ + +#include + +namespace pcl +{ + namespace common + { + /** expand point cloud inserting \a amount rows at the + * top and the bottom of a point cloud and filling them with + * custom values. + * \param[in] input the input point cloud + * \param[out] output the output point cloud + * \param[in] val the point value to be insterted + * \param[in] amount the amount of rows to be added + */ + template void + expandRows (const PointCloud& input, PointCloud& output, + const PointT& val, const size_t& amount); + + /** expand point cloud inserting \a amount columns at + * the right and the left of a point cloud and filling them with + * custom values. + * \param[in] input the input point cloud + * \param[out] output the output point cloud + * \param[in] val the point value to be insterted + * \param[in] amount the amount of columns to be added + */ + template void + expandColumns (const PointCloud& input, PointCloud& output, + const PointT& val, const size_t& amount); + + /** expand point cloud duplicating the \a amount top and bottom rows times. + * \param[in] input the input point cloud + * \param[out] output the output point cloud + * \param[in] amount the amount of rows to be added + */ + template void + duplicateRows (const PointCloud& input, PointCloud& output, + const size_t& amount); + + /** expand point cloud duplicating the \a amount right and left columns + * times. + * \param[in] input the input point cloud + * \param[out] output the output point cloud + * \param[in] amount the amount of cilumns to be added + */ + template void + duplicateColumns (const PointCloud& input, PointCloud& output, + const size_t& amount); + + /** expand point cloud mirroring \a amount top and bottom rows. + * \param[in] input the input point cloud + * \param[out] output the output point cloud + * \param[in] amount the amount of rows to be added + */ + template void + mirrorRows (const PointCloud& input, PointCloud& output, + const size_t& amount); + + /** expand point cloud mirroring \a amount right and left columns. + * \param[in] input the input point cloud + * \param[out] output the output point cloud + * \param[in] amount the amount of rows to be added + */ + template void + mirrorColumns (const PointCloud& input, PointCloud& output, + const size_t& amount); + + /** delete \a amount rows in top and bottom of point cloud + * \param[in] input the input point cloud + * \param[out] output the output point cloud + * \param[in] amount the amount of rows to be added + */ + template void + deleteRows (const PointCloud& input, PointCloud& output, + const size_t& amount); + + /** delete \a amount columns in top and bottom of point cloud + * \param[in] input the input point cloud + * \param[out] output the output point cloud + * \param[in] amount the amount of rows to be added + */ + template void + deleteCols (const PointCloud& input, PointCloud& output, + const size_t& amount); + }; +} + +#include + +#endif diff --git a/pcl-1.7/pcl/common/synchronizer.h b/pcl-1.7/pcl/common/synchronizer.h new file mode 100644 index 0000000..49dc8ae --- /dev/null +++ b/pcl-1.7/pcl/common/synchronizer.h @@ -0,0 +1,178 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * Author: Nico Blodow (blodow@in.tum.de), Suat Gedikli (gedikli@willowgarage.com) + */ +#ifndef __PCL_SYNCHRONIZER__ +#define __PCL_SYNCHRONIZER__ + +namespace pcl +{ + /** /brief This template class synchronizes two data streams of different types. + * The data can be added using add0 and add1 methods which expects also a timestamp of type unsigned long. + * If two matching data objects are found, registered callback functions are invoked with the objects and the time stamps. + * The only assumption of the timestamp is, that they are in the same unit, linear and strictly monotonic increasing. + * If filtering is desired, e.g. thresholding of time differences, the user can do that in the callback method. + * This class is thread safe. + * /ingroup common + */ + template + class Synchronizer + { + typedef std::pair T1Stamped; + typedef std::pair T2Stamped; + boost::mutex mutex1_; + boost::mutex mutex2_; + boost::mutex publish_mutex_; + std::deque queueT1; + std::deque queueT2; + + typedef boost::function CallbackFunction; + + std::map cb_; + int callback_counter; + public: + + Synchronizer () : mutex1_ (), mutex2_ (), publish_mutex_ (), queueT1 (), queueT2 (), cb_ (), callback_counter (0) { }; + + int + addCallback (const CallbackFunction& callback) + { + boost::unique_lock publish_lock (publish_mutex_); + cb_[callback_counter] = callback; + return callback_counter++; + } + + void + removeCallback (int i) + { + boost::unique_lock publish_lock (publish_mutex_); + cb_.erase (i); + } + + void + add0 (const T1& t, unsigned long time) + { + mutex1_.lock (); + queueT1.push_back (T1Stamped (time, t)); + mutex1_.unlock (); + publish (); + } + + void + add1 (const T2& t, unsigned long time) + { + mutex2_.lock (); + queueT2.push_back (T2Stamped (time, t)); + mutex2_.unlock (); + publish (); + } + + private: + + void + publishData () + { + boost::unique_lock lock1 (mutex1_); + boost::unique_lock lock2 (mutex2_); + + for (typename std::map::iterator cb = cb_.begin (); cb != cb_.end (); ++cb) + { + if (!cb->second.empty ()) + { + cb->second.operator()(queueT1.front ().second, queueT2.front ().second, queueT1.front ().first, queueT2.front ().first); + } + } + + queueT1.pop_front (); + queueT2.pop_front (); + } + + void + publish () + { + // only one publish call at once allowed + boost::unique_lock publish_lock (publish_mutex_); + + boost::unique_lock lock1 (mutex1_); + if (queueT1.empty ()) + return; + T1Stamped t1 = queueT1.front (); + lock1.unlock (); + + boost::unique_lock lock2 (mutex2_); + if (queueT2.empty ()) + return; + T2Stamped t2 = queueT2.front (); + lock2.unlock (); + + bool do_publish = false; + + if (t1.first <= t2.first) + { // iterate over queue1 + lock1.lock (); + while (queueT1.size () > 1 && queueT1[1].first <= t2.first) + queueT1.pop_front (); + + if (queueT1.size () > 1) + { // we have at least 2 measurements; first in past and second in future -> find out closer one! + if ( (t2.first << 1) > (queueT1[0].first + queueT1[1].first) ) + queueT1.pop_front (); + + do_publish = true; + } + lock1.unlock (); + } + else + { // iterate over queue2 + lock2.lock (); + while (queueT2.size () > 1 && (queueT2[1].first <= t1.first) ) + queueT2.pop_front (); + + if (queueT2.size () > 1) + { // we have at least 2 measurements; first in past and second in future -> find out closer one! + if ( (t1.first << 1) > queueT2[0].first + queueT2[1].first ) + queueT2.pop_front (); + + do_publish = true; + } + lock2.unlock (); + } + + if (do_publish) + publishData (); + } + } ; +} // namespace + +#endif // __PCL_SYNCHRONIZER__ + diff --git a/pcl-1.7/pcl/common/time.h b/pcl-1.7/pcl/common/time.h new file mode 100644 index 0000000..7dab8b2 --- /dev/null +++ b/pcl-1.7/pcl/common/time.h @@ -0,0 +1,180 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_TIME_H_ +#define PCL_TIME_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#include +#include +#ifndef Q_MOC_RUN +#include +#endif + +/** + * \file pcl/common/time.h + * Define methods for measuring time spent in code blocks + * \ingroup common + */ + +/*@{*/ +namespace pcl +{ + /** \brief Simple stopwatch. + * \ingroup common + */ + class StopWatch + { + public: + /** \brief Constructor. */ + StopWatch () : start_time_ (boost::posix_time::microsec_clock::local_time ()) + { + } + + /** \brief Destructor. */ + virtual ~StopWatch () {} + + /** \brief Retrieve the time in milliseconds spent since the last call to \a reset(). */ + inline double + getTime () + { + boost::posix_time::ptime end_time = boost::posix_time::microsec_clock::local_time (); + return (static_cast (((end_time - start_time_).total_milliseconds ()))); + } + + /** \brief Retrieve the time in seconds spent since the last call to \a reset(). */ + inline double + getTimeSeconds () + { + return (getTime () * 0.001f); + } + + /** \brief Reset the stopwatch to 0. */ + inline void + reset () + { + start_time_ = boost::posix_time::microsec_clock::local_time (); + } + + protected: + boost::posix_time::ptime start_time_; + }; + + /** \brief Class to measure the time spent in a scope + * + * To use this class, e.g. to measure the time spent in a function, + * just create an instance at the beginning of the function. Example: + * + * \code + * { + * pcl::ScopeTime t1 ("calculation"); + * + * // ... perform calculation here + * } + * \endcode + * + * \ingroup common + */ + class ScopeTime : public StopWatch + { + public: + inline ScopeTime (const char* title) : + title_ (std::string (title)) + { + start_time_ = boost::posix_time::microsec_clock::local_time (); + } + + inline ScopeTime () : + title_ (std::string ("")) + { + start_time_ = boost::posix_time::microsec_clock::local_time (); + } + + inline ~ScopeTime () + { + double val = this->getTime (); + std::cerr << title_ << " took " << val << "ms.\n"; + } + + private: + std::string title_; + }; + + +#ifndef MEASURE_FUNCTION_TIME +#define MEASURE_FUNCTION_TIME \ + ScopeTime scopeTime(__func__) +#endif + +inline double +getTime () +{ + boost::posix_time::ptime epoch_time (boost::gregorian::date (1970, 1, 1)); + boost::posix_time::ptime current_time = boost::posix_time::microsec_clock::local_time (); + return (static_cast((current_time - epoch_time).total_nanoseconds ()) * 1.0e-9); +} + +/// Executes code, only if secs are gone since last exec. +#ifndef DO_EVERY_TS +#define DO_EVERY_TS(secs, currentTime, code) \ +if (1) {\ + static double s_lastDone_ = 0.0; \ + double s_now_ = (currentTime); \ + if (s_lastDone_ > s_now_) \ + s_lastDone_ = s_now_; \ + if ((s_now_ - s_lastDone_) > (secs)) { \ + code; \ + s_lastDone_ = s_now_; \ + }\ +} else \ + (void)0 +#endif + +/// Executes code, only if secs are gone since last exec. +#ifndef DO_EVERY +#define DO_EVERY(secs, code) \ + DO_EVERY_TS(secs, pcl::getTime(), code) +#endif + +} // end namespace +/*@}*/ + +#endif //#ifndef PCL_NORMS_H_ diff --git a/pcl-1.7/pcl/common/time_trigger.h b/pcl-1.7/pcl/common/time_trigger.h new file mode 100644 index 0000000..941f96b --- /dev/null +++ b/pcl-1.7/pcl/common/time_trigger.h @@ -0,0 +1,108 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_COMMON_TIME_TRIGGER_H_ +#define PCL_COMMON_TIME_TRIGGER_H_ + +#include +#ifndef Q_MOC_RUN +#include +#include +#include +#endif + +namespace pcl +{ + /** \brief Timer class that invokes registered callback methods periodically. + * \ingroup common + */ + class PCL_EXPORTS TimeTrigger + { + public: + typedef boost::function callback_type; + + /** \brief Timer class that calls a callback method periodically. Due to possible blocking calls, only one callback method can be registered per instance. + * \param[in] interval_seconds interval in seconds + * \param[in] callback callback to be invoked periodically + */ + TimeTrigger (double interval_seconds, const callback_type& callback); + + /** \brief Timer class that calls a callback method periodically. Due to possible blocking calls, only one callback method can be registered per instance. + * \param[in] interval_seconds interval in seconds + */ + TimeTrigger (double interval_seconds = 1.0); + + /** \brief Destructor. */ + ~TimeTrigger (); + + /** \brief registeres a callback + * \param[in] callback callback function to the list of callbacks. signature has to be boost::function + * \return connection the connection, which can be used to disable/enable and remove callback from list + */ + boost::signals2::connection registerCallback (const callback_type& callback); + + /** \brief Resets the timer interval + * \param[in] interval_seconds interval in seconds + */ + void + setInterval (double interval_seconds); + + /** \brief Start the Trigger. */ + void + start (); + + /** \brief Stop the Trigger. */ + void + stop (); + private: + void + thread_function (); + boost::signals2::signal callbacks_; + + double interval_; + + bool quit_; + bool running_; + + boost::thread timer_thread_; + boost::condition_variable condition_; + boost::mutex condition_mutex_; + }; +} + +#endif diff --git a/pcl-1.7/pcl/common/transformation_from_correspondences.h b/pcl-1.7/pcl/common/transformation_from_correspondences.h new file mode 100644 index 0000000..8d4ca51 --- /dev/null +++ b/pcl-1.7/pcl/common/transformation_from_correspondences.h @@ -0,0 +1,101 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_TRANSFORMATION_FROM_CORRESPONDENCES_H +#define PCL_TRANSFORMATION_FROM_CORRESPONDENCES_H + +#include + +namespace pcl +{ + /** + * \brief Calculates a transformation based on corresponding 3D points + * \author Bastian Steder + * \ingroup common + */ + class TransformationFromCorrespondences + { + public: + //-----CONSTRUCTOR&DESTRUCTOR----- + /** Constructor - dimension gives the size of the vectors to work with. */ + TransformationFromCorrespondences () : + no_of_samples_ (0), accumulated_weight_ (0), + mean1_ (Eigen::Vector3f::Identity ()), + mean2_ (Eigen::Vector3f::Identity ()), + covariance_ (Eigen::Matrix::Identity ()) + { reset (); } + + /** Destructor */ + ~TransformationFromCorrespondences () { }; + + //-----METHODS----- + /** Reset the object to work with a new data set */ + inline void + reset (); + + /** Get the summed up weight of all added vectors */ + inline float + getAccumulatedWeight () const { return accumulated_weight_;} + + /** Get the number of added vectors */ + inline unsigned int + getNoOfSamples () { return no_of_samples_;} + + /** Add a new sample */ + inline void + add (const Eigen::Vector3f& point, const Eigen::Vector3f& corresponding_point, float weight=1.0); + + /** Calculate the transformation that will best transform the points into their correspondences */ + inline Eigen::Affine3f + getTransformation (); + + //-----VARIABLES----- + + protected: + //-----METHODS----- + //-----VARIABLES----- + unsigned int no_of_samples_; + float accumulated_weight_; + Eigen::Vector3f mean1_, mean2_; + Eigen::Matrix covariance_; + }; + +} // END namespace + +#include + +#endif // #ifndef PCL_TRANSFORMATION_FROM_CORRESPONDENCES_H + diff --git a/pcl-1.7/pcl/common/transforms.h b/pcl-1.7/pcl/common/transforms.h new file mode 100644 index 0000000..1f0a85a --- /dev/null +++ b/pcl-1.7/pcl/common/transforms.h @@ -0,0 +1,420 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ +#ifndef PCL_TRANSFORMS_H_ +#define PCL_TRANSFORMS_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Apply an affine transform defined by an Eigen Transform + * \param[in] cloud_in the input point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] transform an affine transformation (typically a rigid transformation) + * \note Can be used with cloud_in equal to cloud_out + * \ingroup common + */ + template void + transformPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Transform &transform); + + template void + transformPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Affine3f &transform) + { + return (transformPointCloud (cloud_in, cloud_out, transform)); + } + + /** \brief Apply an affine transform defined by an Eigen Transform + * \param[in] cloud_in the input point cloud + * \param[in] indices the set of point indices to use from the input point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] transform an affine transformation (typically a rigid transformation) + * \ingroup common + */ + template void + transformPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out, + const Eigen::Transform &transform); + + template void + transformPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out, + const Eigen::Affine3f &transform) + { + return (transformPointCloud (cloud_in, indices, cloud_out, transform)); + } + + /** \brief Apply an affine transform defined by an Eigen Transform + * \param[in] cloud_in the input point cloud + * \param[in] indices the set of point indices to use from the input point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] transform an affine transformation (typically a rigid transformation) + * \ingroup common + */ + template void + transformPointCloud (const pcl::PointCloud &cloud_in, + const pcl::PointIndices &indices, + pcl::PointCloud &cloud_out, + const Eigen::Transform &transform) + { + return (transformPointCloud (cloud_in, indices.indices, cloud_out, transform)); + } + + template void + transformPointCloud (const pcl::PointCloud &cloud_in, + const pcl::PointIndices &indices, + pcl::PointCloud &cloud_out, + const Eigen::Affine3f &transform) + { + return (transformPointCloud (cloud_in, indices, cloud_out, transform)); + } + + /** \brief Transform a point cloud and rotate its normals using an Eigen transform. + * \param[in] cloud_in the input point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] transform an affine transformation (typically a rigid transformation) + * \note Can be used with cloud_in equal to cloud_out + */ + template void + transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Transform &transform); + + template void + transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Affine3f &transform) + { + return (transformPointCloudWithNormals (cloud_in, cloud_out, transform)); + } + + /** \brief Transform a point cloud and rotate its normals using an Eigen transform. + * \param[in] cloud_in the input point cloud + * \param[in] indices the set of point indices to use from the input point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] transform an affine transformation (typically a rigid transformation) + */ + template void + transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out, + const Eigen::Transform &transform); + + template void + transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out, + const Eigen::Affine3f &transform) + { + return (transformPointCloudWithNormals (cloud_in, indices, cloud_out, transform)); + } + + /** \brief Transform a point cloud and rotate its normals using an Eigen transform. + * \param[in] cloud_in the input point cloud + * \param[in] indices the set of point indices to use from the input point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] transform an affine transformation (typically a rigid transformation) + */ + template void + transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + const pcl::PointIndices &indices, + pcl::PointCloud &cloud_out, + const Eigen::Transform &transform) + { + return (transformPointCloudWithNormals (cloud_in, indices.indices, cloud_out, transform)); + } + + + template void + transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + const pcl::PointIndices &indices, + pcl::PointCloud &cloud_out, + const Eigen::Affine3f &transform) + { + return (transformPointCloudWithNormals (cloud_in, indices, cloud_out, transform)); + } + + /** \brief Apply a rigid transform defined by a 4x4 matrix + * \param[in] cloud_in the input point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] transform a rigid transformation + * \note Can be used with cloud_in equal to cloud_out + * \ingroup common + */ + template void + transformPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Matrix &transform) + { + Eigen::Transform t (transform); + return (transformPointCloud (cloud_in, cloud_out, t)); + } + + template void + transformPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Matrix4f &transform) + { + return (transformPointCloud (cloud_in, cloud_out, transform)); + } + + /** \brief Apply a rigid transform defined by a 4x4 matrix + * \param[in] cloud_in the input point cloud + * \param[in] indices the set of point indices to use from the input point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] transform a rigid transformation + * \ingroup common + */ + template void + transformPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out, + const Eigen::Matrix &transform) + { + Eigen::Transform t (transform); + return (transformPointCloud (cloud_in, indices, cloud_out, t)); + } + + template void + transformPointCloud (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out, + const Eigen::Matrix4f &transform) + { + return (transformPointCloud (cloud_in, indices, cloud_out, transform)); + } + + /** \brief Apply a rigid transform defined by a 4x4 matrix + * \param[in] cloud_in the input point cloud + * \param[in] indices the set of point indices to use from the input point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] transform a rigid transformation + * \ingroup common + */ + template void + transformPointCloud (const pcl::PointCloud &cloud_in, + const pcl::PointIndices &indices, + pcl::PointCloud &cloud_out, + const Eigen::Matrix &transform) + { + return (transformPointCloud (cloud_in, indices.indices, cloud_out, transform)); + } + + template void + transformPointCloud (const pcl::PointCloud &cloud_in, + const pcl::PointIndices &indices, + pcl::PointCloud &cloud_out, + const Eigen::Matrix4f &transform) + { + return (transformPointCloud (cloud_in, indices, cloud_out, transform)); + } + + /** \brief Transform a point cloud and rotate its normals using an Eigen transform. + * \param[in] cloud_in the input point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] transform an affine transformation (typically a rigid transformation) + * \note Can be used with cloud_in equal to cloud_out + * \ingroup common + */ + template void + transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Matrix &transform) + { + Eigen::Transform t (transform); + return (transformPointCloudWithNormals (cloud_in, cloud_out, t)); + } + + + template void + transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Matrix4f &transform) + { + return (transformPointCloudWithNormals (cloud_in, cloud_out, transform)); + } + + /** \brief Transform a point cloud and rotate its normals using an Eigen transform. + * \param[in] cloud_in the input point cloud + * \param[in] indices the set of point indices to use from the input point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] transform an affine transformation (typically a rigid transformation) + * \note Can be used with cloud_in equal to cloud_out + * \ingroup common + */ + template void + transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out, + const Eigen::Matrix &transform) + { + Eigen::Transform t (transform); + return (transformPointCloudWithNormals (cloud_in, indices, cloud_out, t)); + } + + + template void + transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + const std::vector &indices, + pcl::PointCloud &cloud_out, + const Eigen::Matrix4f &transform) + { + return (transformPointCloudWithNormals (cloud_in, indices, cloud_out, transform)); + } + + /** \brief Transform a point cloud and rotate its normals using an Eigen transform. + * \param[in] cloud_in the input point cloud + * \param[in] indices the set of point indices to use from the input point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] transform an affine transformation (typically a rigid transformation) + * \note Can be used with cloud_in equal to cloud_out + * \ingroup common + */ + template void + transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + const pcl::PointIndices &indices, + pcl::PointCloud &cloud_out, + const Eigen::Matrix &transform) + { + Eigen::Transform t (transform); + return (transformPointCloudWithNormals (cloud_in, indices, cloud_out, t)); + } + + + template void + transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + const pcl::PointIndices &indices, + pcl::PointCloud &cloud_out, + const Eigen::Matrix4f &transform) + { + return (transformPointCloudWithNormals (cloud_in, indices, cloud_out, transform)); + } + + /** \brief Apply a rigid transform defined by a 3D offset and a quaternion + * \param[in] cloud_in the input point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] offset the translation component of the rigid transformation + * \param[in] rotation the rotation component of the rigid transformation + * \ingroup common + */ + template inline void + transformPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Matrix &offset, + const Eigen::Quaternion &rotation); + + template inline void + transformPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Vector3f &offset, + const Eigen::Quaternionf &rotation) + { + return (transformPointCloud (cloud_in, cloud_out, offset, rotation)); + } + + /** \brief Transform a point cloud and rotate its normals using an Eigen transform. + * \param[in] cloud_in the input point cloud + * \param[out] cloud_out the resultant output point cloud + * \param[in] offset the translation component of the rigid transformation + * \param[in] rotation the rotation component of the rigid transformation + * \ingroup common + */ + template inline void + transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Matrix &offset, + const Eigen::Quaternion &rotation); + + template void + transformPointCloudWithNormals (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + const Eigen::Vector3f &offset, + const Eigen::Quaternionf &rotation) + { + return (transformPointCloudWithNormals (cloud_in, cloud_out, offset, rotation)); + } + + /** \brief Transform a point with members x,y,z + * \param[in] point the point to transform + * \param[out] transform the transformation to apply + * \return the transformed point + * \ingroup common + */ + template inline PointT + transformPoint (const PointT &point, + const Eigen::Transform &transform); + + template inline PointT + transformPoint (const PointT &point, + const Eigen::Affine3f &transform) + { + return (transformPoint (point, transform)); + } + + /** \brief Calculates the principal (PCA-based) alignment of the point cloud + * \param[in] cloud the input point cloud + * \param[out] transform the resultant transform + * \return the ratio lambda1/lambda2 or lambda2/lambda3, whatever is closer to 1. + * \note If the return value is close to one then the transformation might be not unique -> two principal directions have + * almost same variance (extend) + */ + template inline double + getPrincipalTransformation (const pcl::PointCloud &cloud, + Eigen::Transform &transform); + + template inline double + getPrincipalTransformation (const pcl::PointCloud &cloud, + Eigen::Affine3f &transform) + { + return (getPrincipalTransformation (cloud, transform)); + } +} + +#include + +#endif // PCL_TRANSFORMS_H_ diff --git a/pcl-1.7/pcl/common/utils.h b/pcl-1.7/pcl/common/utils.h new file mode 100644 index 0000000..179a4bf --- /dev/null +++ b/pcl-1.7/pcl/common/utils.h @@ -0,0 +1,62 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_UTILS +#define PCL_UTILS + +#include + +namespace pcl +{ + namespace utils + { + /** \brief Check if val1 and val2 are equals to an epsilon extent + * \param[in] val1 first number to check + * \param[in] val2 second number to check + * \param[in] eps epsilon + * \return true if val1 is equal to val2, false otherwise. + */ + template bool + equal (T val1, T val2, T eps = std::numeric_limits::min ()) + { + return (fabs (val1 - val2) < eps); + } + } +} + +#endif diff --git a/pcl-1.7/pcl/common/vector_average.h b/pcl-1.7/pcl/common/vector_average.h new file mode 100644 index 0000000..678f26f --- /dev/null +++ b/pcl-1.7/pcl/common/vector_average.h @@ -0,0 +1,119 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_COMMON_VECTOR_AVERAGE_H +#define PCL_COMMON_VECTOR_AVERAGE_H + +#include + +namespace pcl +{ + /** \brief Calculates the weighted average and the covariance matrix + * + * A class to calculate the weighted average and the covariance matrix of a set of vectors with given weights. + * The original data is not saved. Mean and covariance are calculated iteratively. + * \author Bastian Steder + * \ingroup common + */ + template + class VectorAverage + { + public: + //-----CONSTRUCTOR&DESTRUCTOR----- + /** Constructor - dimension gives the size of the vectors to work with. */ + VectorAverage (); + /** Destructor */ + ~VectorAverage () {} + + //-----METHODS----- + /** Reset the object to work with a new data set */ + inline void + reset (); + + /** Get the mean of the added vectors */ + inline const + Eigen::Matrix& getMean () const { return mean_;} + + /** Get the covariance matrix of the added vectors */ + inline const + Eigen::Matrix& getCovariance () const { return covariance_;} + + /** Get the summed up weight of all added vectors */ + inline real + getAccumulatedWeight () const { return accumulatedWeight_;} + + /** Get the number of added vectors */ + inline unsigned int + getNoOfSamples () { return noOfSamples_;} + + /** Add a new sample */ + inline void + add (const Eigen::Matrix& sample, real weight=1.0); + + /** Do Principal component analysis */ + inline void + doPCA (Eigen::Matrix& eigen_values, Eigen::Matrix& eigen_vector1, + Eigen::Matrix& eigen_vector2, Eigen::Matrix& eigen_vector3) const; + + /** Do Principal component analysis */ + inline void + doPCA (Eigen::Matrix& eigen_values) const; + + /** Get the eigenvector corresponding to the smallest eigenvalue */ + inline void + getEigenVector1 (Eigen::Matrix& eigen_vector1) const; + + //-----VARIABLES----- + + protected: + //-----METHODS----- + //-----VARIABLES----- + unsigned int noOfSamples_; + real accumulatedWeight_; + Eigen::Matrix mean_; + Eigen::Matrix covariance_; + }; + + typedef VectorAverage VectorAverage2f; + typedef VectorAverage VectorAverage3f; + typedef VectorAverage VectorAverage4f; +} // END namespace + +#include + +#endif // #ifndef PCL_VECTOR_AVERAGE_H + diff --git a/pcl-1.7/pcl/compression/color_coding.h b/pcl-1.7/pcl/compression/color_coding.h new file mode 100644 index 0000000..382d33a --- /dev/null +++ b/pcl-1.7/pcl/compression/color_coding.h @@ -0,0 +1,420 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef COLOR_COMPRESSION_H +#define COLOR_COMPRESSION_H + +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace octree + { + using namespace std; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b ColorCoding class + * \note This class encodes 8-bit color information for octree-based point cloud compression. + * \note + * \note typename: PointT: type of point used in pointcloud + * \author Julius Kammerl (julius@kammerl.de) + */ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template + class ColorCoding + { + + // public typedefs + typedef pcl::PointCloud PointCloud; + typedef boost::shared_ptr PointCloudPtr; + typedef boost::shared_ptr PointCloudConstPtr; + + public: + + /** \brief Constructor. + * + * */ + ColorCoding () : + output_ (), pointAvgColorDataVector_ (), pointAvgColorDataVector_Iterator_ (), + pointDiffColorDataVector_ (), pointDiffColorDataVector_Iterator_ (), colorBitReduction_ (0) + { + } + + /** \brief Empty class constructor. */ + virtual + ~ColorCoding () + { + } + + /** \brief Define color bit depth of encoded color information. + * \param bitDepth_arg: amounts of bits for representing one color component + */ + inline + void + setBitDepth (unsigned char bitDepth_arg) + { + colorBitReduction_ = static_cast (8 - bitDepth_arg); + } + + /** \brief Retrieve color bit depth of encoded color information. + * \return amounts of bits for representing one color component + */ + inline unsigned char + getBitDepth () + { + return (static_cast (8 - colorBitReduction_)); + } + + /** \brief Set amount of voxels containing point color information and reserve memory + * \param voxelCount_arg: amounts of voxels + */ + inline void + setVoxelCount (unsigned int voxelCount_arg) + { + pointAvgColorDataVector_.reserve (voxelCount_arg * 3); + } + + /** \brief Set amount of points within point cloud to be encoded and reserve memory + * \param pointCount_arg: amounts of points within point cloud + * */ + inline + void + setPointCount (unsigned int pointCount_arg) + { + pointDiffColorDataVector_.reserve (pointCount_arg * 3); + } + + /** \brief Initialize encoding of color information + * */ + void + initializeEncoding () + { + pointAvgColorDataVector_.clear (); + + pointDiffColorDataVector_.clear (); + } + + /** \brief Initialize decoding of color information + * */ + void + initializeDecoding () + { + pointAvgColorDataVector_Iterator_ = pointAvgColorDataVector_.begin (); + + pointDiffColorDataVector_Iterator_ = pointDiffColorDataVector_.begin (); + } + + /** \brief Get reference to vector containing averaged color data + * */ + std::vector& + getAverageDataVector () + { + return pointAvgColorDataVector_; + } + + /** \brief Get reference to vector containing differential color data + * */ + std::vector& + getDifferentialDataVector () + { + return pointDiffColorDataVector_; + } + + /** \brief Encode averaged color information for a subset of points from point cloud + * \param indexVector_arg indices defining a subset of points from points cloud + * \param rgba_offset_arg offset to color information + * \param inputCloud_arg input point cloud + * */ + void + encodeAverageOfPoints (const typename std::vector& indexVector_arg, unsigned char rgba_offset_arg, PointCloudConstPtr inputCloud_arg) + { + std::size_t i, len; + + unsigned int avgRed; + unsigned int avgGreen; + unsigned int avgBlue; + + // initialize + avgRed = avgGreen = avgBlue = 0; + + // iterate over points + len = indexVector_arg.size (); + for (i = 0; i < len; i++) + { + // get color information from points + const int& idx = indexVector_arg[i]; + const char* idxPointPtr = reinterpret_cast (&inputCloud_arg->points[idx]); + const int& colorInt = *reinterpret_cast (idxPointPtr+rgba_offset_arg); + + // add color information + avgRed += (colorInt >> 0) & 0xFF; + avgGreen += (colorInt >> 8) & 0xFF; + avgBlue += (colorInt >> 16) & 0xFF; + + } + + // calculated average color information + if (len > 1) + { + avgRed /= static_cast (len); + avgGreen /= static_cast (len); + avgBlue /= static_cast (len); + } + + // remove least significant bits + avgRed >>= colorBitReduction_; + avgGreen >>= colorBitReduction_; + avgBlue >>= colorBitReduction_; + + // add to average color vector + pointAvgColorDataVector_.push_back (static_cast (avgRed)); + pointAvgColorDataVector_.push_back (static_cast (avgGreen)); + pointAvgColorDataVector_.push_back (static_cast (avgBlue)); + } + + /** \brief Encode color information of a subset of points from point cloud + * \param indexVector_arg indices defining a subset of points from points cloud + * \param rgba_offset_arg offset to color information + * \param inputCloud_arg input point cloud + * */ + void + encodePoints (const typename std::vector& indexVector_arg, unsigned char rgba_offset_arg, PointCloudConstPtr inputCloud_arg) + { + std::size_t i, len; + + unsigned int avgRed; + unsigned int avgGreen; + unsigned int avgBlue; + + // initialize + avgRed = avgGreen = avgBlue = 0; + + // iterate over points + len = indexVector_arg.size (); + for (i = 0; i < len; i++) + { + // get color information from point + const int& idx = indexVector_arg[i]; + const char* idxPointPtr = reinterpret_cast (&inputCloud_arg->points[idx]); + const int& colorInt = *reinterpret_cast (idxPointPtr+rgba_offset_arg); + + // add color information + avgRed += (colorInt >> 0) & 0xFF; + avgGreen += (colorInt >> 8) & 0xFF; + avgBlue += (colorInt >> 16) & 0xFF; + + } + + if (len > 1) + { + unsigned char diffRed; + unsigned char diffGreen; + unsigned char diffBlue; + + // calculated average color information + avgRed /= static_cast (len); + avgGreen /= static_cast (len); + avgBlue /= static_cast (len); + + // iterate over points for differential encoding + for (i = 0; i < len; i++) + { + const int& idx = indexVector_arg[i]; + const char* idxPointPtr = reinterpret_cast (&inputCloud_arg->points[idx]); + const int& colorInt = *reinterpret_cast (idxPointPtr+rgba_offset_arg); + + // extract color components and do XOR encoding with predicted average color + diffRed = (static_cast (avgRed)) ^ static_cast (((colorInt >> 0) & 0xFF)); + diffGreen = (static_cast (avgGreen)) ^ static_cast (((colorInt >> 8) & 0xFF)); + diffBlue = (static_cast (avgBlue)) ^ static_cast (((colorInt >> 16) & 0xFF)); + + // remove least significant bits + diffRed = static_cast (diffRed >> colorBitReduction_); + diffGreen = static_cast (diffGreen >> colorBitReduction_); + diffBlue = static_cast (diffBlue >> colorBitReduction_); + + // add to differential color vector + pointDiffColorDataVector_.push_back (static_cast (diffRed)); + pointDiffColorDataVector_.push_back (static_cast (diffGreen)); + pointDiffColorDataVector_.push_back (static_cast (diffBlue)); + } + } + + // remove least significant bits from average color information + avgRed >>= colorBitReduction_; + avgGreen >>= colorBitReduction_; + avgBlue >>= colorBitReduction_; + + // add to differential color vector + pointAvgColorDataVector_.push_back (static_cast (avgRed)); + pointAvgColorDataVector_.push_back (static_cast (avgGreen)); + pointAvgColorDataVector_.push_back (static_cast (avgBlue)); + + } + + /** \brief Decode color information + * \param outputCloud_arg output point cloud + * \param beginIdx_arg index indicating first point to be assiged with color information + * \param endIdx_arg index indicating last point to be assiged with color information + * \param rgba_offset_arg offset to color information + */ + void + decodePoints (PointCloudPtr outputCloud_arg, std::size_t beginIdx_arg, std::size_t endIdx_arg, unsigned char rgba_offset_arg) + { + std::size_t i; + unsigned int pointCount; + unsigned int colorInt; + + assert (beginIdx_arg <= endIdx_arg); + + // amount of points to be decoded + pointCount = static_cast (endIdx_arg - beginIdx_arg); + + // get averaged color information for current voxel + unsigned char avgRed = *(pointAvgColorDataVector_Iterator_++); + unsigned char avgGreen = *(pointAvgColorDataVector_Iterator_++); + unsigned char avgBlue = *(pointAvgColorDataVector_Iterator_++); + + // invert bit shifts during encoding + avgRed = static_cast (avgRed << colorBitReduction_); + avgGreen = static_cast (avgGreen << colorBitReduction_); + avgBlue = static_cast (avgBlue << colorBitReduction_); + + // iterate over points + for (i = 0; i < pointCount; i++) + { + if (pointCount > 1) + { + // get differential color information from input vector + unsigned char diffRed = static_cast (*(pointDiffColorDataVector_Iterator_++)); + unsigned char diffGreen = static_cast (*(pointDiffColorDataVector_Iterator_++)); + unsigned char diffBlue = static_cast (*(pointDiffColorDataVector_Iterator_++)); + + // invert bit shifts during encoding + diffRed = static_cast (diffRed << colorBitReduction_); + diffGreen = static_cast (diffGreen << colorBitReduction_); + diffBlue = static_cast (diffBlue << colorBitReduction_); + + // decode color information + colorInt = ((avgRed ^ diffRed) << 0) | + ((avgGreen ^ diffGreen) << 8) | + ((avgBlue ^ diffBlue) << 16); + } + else + { + // decode color information + colorInt = (avgRed << 0) | (avgGreen << 8) | (avgBlue << 16); + } + + char* idxPointPtr = reinterpret_cast (&outputCloud_arg->points[beginIdx_arg + i]); + int& pointColor = *reinterpret_cast (idxPointPtr+rgba_offset_arg); + // assign color to point from point cloud + pointColor=colorInt; + } + } + + /** \brief Set default color to points + * \param outputCloud_arg output point cloud + * \param beginIdx_arg index indicating first point to be assiged with color information + * \param endIdx_arg index indicating last point to be assiged with color information + * \param rgba_offset_arg offset to color information + * */ + void + setDefaultColor (PointCloudPtr outputCloud_arg, std::size_t beginIdx_arg, std::size_t endIdx_arg, unsigned char rgba_offset_arg) + { + std::size_t i; + unsigned int pointCount; + + assert (beginIdx_arg <= endIdx_arg); + + // amount of points to be decoded + pointCount = static_cast (endIdx_arg - beginIdx_arg); + + // iterate over points + for (i = 0; i < pointCount; i++) + { + char* idxPointPtr = reinterpret_cast (&outputCloud_arg->points[beginIdx_arg + i]); + int& pointColor = *reinterpret_cast (idxPointPtr+rgba_offset_arg); + // assign color to point from point cloud + pointColor = defaultColor_; + } + } + + + protected: + + /** \brief Pointer to output point cloud dataset. */ + PointCloudPtr output_; + + /** \brief Vector for storing average color information */ + std::vector pointAvgColorDataVector_; + + /** \brief Iterator on average color information vector */ + std::vector::const_iterator pointAvgColorDataVector_Iterator_; + + /** \brief Vector for storing differential color information */ + std::vector pointDiffColorDataVector_; + + /** \brief Iterator on differential color information vector */ + std::vector::const_iterator pointDiffColorDataVector_Iterator_; + + /** \brief Amount of bits to be removed from color components before encoding */ + unsigned char colorBitReduction_; + + // frame header identifier + static const int defaultColor_; + + }; + + // define default color + template + const int ColorCoding::defaultColor_ = ((255) << 0) | + ((255) << 8) | + ((255) << 16); + + } +} + +#define PCL_INSTANTIATE_ColorCoding(T) template class PCL_EXPORTS pcl::octree::ColorCoding; + +#endif diff --git a/pcl-1.7/pcl/compression/compression_profiles.h b/pcl-1.7/pcl/compression/compression_profiles.h new file mode 100644 index 0000000..b0feb4f --- /dev/null +++ b/pcl-1.7/pcl/compression/compression_profiles.h @@ -0,0 +1,185 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Julius Kammerl (julius@kammerl.de) + */ + +#ifndef OCTREE_COMPRESSION_PROFILES_H +#define OCTREE_COMPRESSION_PROFILES_H + +namespace pcl +{ + namespace io + { + + enum compression_Profiles_e + { + LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR, + LOW_RES_ONLINE_COMPRESSION_WITH_COLOR, + + MED_RES_ONLINE_COMPRESSION_WITHOUT_COLOR, + MED_RES_ONLINE_COMPRESSION_WITH_COLOR, + + HIGH_RES_ONLINE_COMPRESSION_WITHOUT_COLOR, + HIGH_RES_ONLINE_COMPRESSION_WITH_COLOR, + + LOW_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR, + LOW_RES_OFFLINE_COMPRESSION_WITH_COLOR, + + MED_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR, + MED_RES_OFFLINE_COMPRESSION_WITH_COLOR, + + HIGH_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR, + HIGH_RES_OFFLINE_COMPRESSION_WITH_COLOR, + + COMPRESSION_PROFILE_COUNT, + MANUAL_CONFIGURATION + }; + + // compression configuration profile + struct configurationProfile_t + { + double pointResolution; + const double octreeResolution; + bool doVoxelGridDownSampling; + unsigned int iFrameRate; + const unsigned char colorBitResolution; + bool doColorEncoding; + }; + + // predefined configuration parameters + const struct configurationProfile_t compressionProfiles_[COMPRESSION_PROFILE_COUNT] = { + { + // PROFILE: LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR + 0.01, /* pointResolution = */ + 0.01, /* octreeResolution = */ + true, /* doVoxelGridDownDownSampling = */ + 50, /* iFrameRate = */ + 4, /* colorBitResolution = */ + false /* doColorEncoding = */ + }, { + // PROFILE: LOW_RES_ONLINE_COMPRESSION_WITH_COLOR + 0.01, /* pointResolution = */ + 0.01, /* octreeResolution = */ + true, /* doVoxelGridDownDownSampling = */ + 50, /* iFrameRate = */ + 4, /* colorBitResolution = */ + true /* doColorEncoding = */ + }, { + // PROFILE: MED_RES_ONLINE_COMPRESSION_WITHOUT_COLOR + 0.005, /* pointResolution = */ + 0.01, /* octreeResolution = */ + false, /* doVoxelGridDownDownSampling = */ + 40, /* iFrameRate = */ + 5, /* colorBitResolution = */ + false /* doColorEncoding = */ + }, { + // PROFILE: MED_RES_ONLINE_COMPRESSION_WITH_COLOR + 0.005, /* pointResolution = */ + 0.01, /* octreeResolution = */ + false, /* doVoxelGridDownDownSampling = */ + 40, /* iFrameRate = */ + 5, /* colorBitResolution = */ + true /* doColorEncoding = */ + }, { + // PROFILE: HIGH_RES_ONLINE_COMPRESSION_WITHOUT_COLOR + 0.0001, /* pointResolution = */ + 0.01, /* octreeResolution = */ + false, /* doVoxelGridDownDownSampling = */ + 30, /* iFrameRate = */ + 7, /* colorBitResolution = */ + false /* doColorEncoding = */ + }, { + // PROFILE: HIGH_RES_ONLINE_COMPRESSION_WITH_COLOR + 0.0001, /* pointResolution = */ + 0.01, /* octreeResolution = */ + false, /* doVoxelGridDownDownSampling = */ + 30, /* iFrameRate = */ + 7, /* colorBitResolution = */ + true /* doColorEncoding = */ + }, { + // PROFILE: LOW_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR + 0.01, /* pointResolution = */ + 0.01, /* octreeResolution = */ + true, /* doVoxelGridDownDownSampling = */ + 100, /* iFrameRate = */ + 4, /* colorBitResolution = */ + false /* doColorEncoding = */ + }, { + // PROFILE: LOW_RES_OFFLINE_COMPRESSION_WITH_COLOR + 0.01, /* pointResolution = */ + 0.01, /* octreeResolution = */ + true, /* doVoxelGridDownDownSampling = */ + 100, /* iFrameRate = */ + 4, /* colorBitResolution = */ + true /* doColorEncoding = */ + }, { + // PROFILE: MED_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR + 0.005, /* pointResolution = */ + 0.005, /* octreeResolution = */ + true, /* doVoxelGridDownDownSampling = */ + 100, /* iFrameRate = */ + 5, /* colorBitResolution = */ + false /* doColorEncoding = */ + }, { + // PROFILE: MED_RES_OFFLINE_COMPRESSION_WITH_COLOR + 0.005, /* pointResolution = */ + 0.01, /* octreeResolution = */ + false, /* doVoxelGridDownDownSampling = */ + 100, /* iFrameRate = */ + 5, /* colorBitResolution = */ + true /* doColorEncoding = */ + }, { + // PROFILE: HIGH_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR + 0.0001, /* pointResolution = */ + 0.0001, /* octreeResolution = */ + true, /* doVoxelGridDownDownSampling = */ + 100, /* iFrameRate = */ + 8, /* colorBitResolution = */ + false /* doColorEncoding = */ + }, { + // PROFILE: HIGH_RES_OFFLINE_COMPRESSION_WITH_COLOR + 0.0001, /* pointResolution = */ + 0.01, /* octreeResolution = */ + false, /* doVoxelGridDownDownSampling = */ + 100, /* iFrameRate = */ + 8, /* colorBitResolution = */ + true /* doColorEncoding = */ + }}; + + } +} + + +#endif + diff --git a/pcl-1.7/pcl/compression/entropy_range_coder.h b/pcl-1.7/pcl/compression/entropy_range_coder.h new file mode 100644 index 0000000..6b922e9 --- /dev/null +++ b/pcl-1.7/pcl/compression/entropy_range_coder.h @@ -0,0 +1,192 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + * Range Coder based on Dmitry Subbotin's carry-less implementation (http://www.compression.ru/ds/) + * Added optimized symbol lookup and added implementation for static range coding (uses fixed precomputed frequency table) + * + * Author: Julius Kammerl (julius@kammerl.de) + */ + +#ifndef __PCL_IO_RANGECODING__ +#define __PCL_IO_RANGECODING__ + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + + using boost::uint8_t; + using boost::uint32_t; + using boost::uint64_t; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b AdaptiveRangeCoder compression class + * \note This class provides adaptive range coding functionality. + * \note Its symbol probability/frequency table is adaptively updated during encoding + * \note + * \author Julius Kammerl (julius@kammerl.de) + */ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + class AdaptiveRangeCoder + { + + public: + + /** \brief Empty constructor. */ + AdaptiveRangeCoder () : outputCharVector_ () + { + } + + /** \brief Empty deconstructor. */ + virtual + ~AdaptiveRangeCoder () + { + } + + /** \brief Encode char vector to output stream + * \param inputByteVector_arg input vector + * \param outputByteStream_arg output stream containing compressed data + * \return amount of bytes written to output stream + */ + unsigned long + encodeCharVectorToStream (const std::vector& inputByteVector_arg, std::ostream& outputByteStream_arg); + + /** \brief Decode char stream to output vector + * \param inputByteStream_arg input stream of compressed data + * \param outputByteVector_arg decompressed output vector + * \return amount of bytes read from input stream + */ + unsigned long + decodeStreamToCharVector (std::istream& inputByteStream_arg, std::vector& outputByteVector_arg); + + protected: + typedef boost::uint32_t DWord; // 4 bytes + + private: + /** vector containing compressed data + */ + std::vector outputCharVector_; + + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b StaticRangeCoder compression class + * \note This class provides static range coding functionality. + * \note Its symbol probability/frequency table is precomputed and encoded to the output stream + * \note + * \author Julius Kammerl (julius@kammerl.de) + */ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + class StaticRangeCoder + { + public: + /** \brief Constructor. */ + StaticRangeCoder () : + cFreqTable_ (65537), outputCharVector_ () + { + } + + /** \brief Empty deconstructor. */ + virtual + ~StaticRangeCoder () + { + } + + /** \brief Encode integer vector to output stream + * \param[in] inputIntVector_arg input vector + * \param[out] outputByterStream_arg output stream containing compressed data + * \return amount of bytes written to output stream + */ + unsigned long + encodeIntVectorToStream (std::vector& inputIntVector_arg, std::ostream& outputByterStream_arg); + + /** \brief Decode stream to output integer vector + * \param inputByteStream_arg input stream of compressed data + * \param outputIntVector_arg decompressed output vector + * \return amount of bytes read from input stream + */ + unsigned long + decodeStreamToIntVector (std::istream& inputByteStream_arg, std::vector& outputIntVector_arg); + + /** \brief Encode char vector to output stream + * \param inputByteVector_arg input vector + * \param outputByteStream_arg output stream containing compressed data + * \return amount of bytes written to output stream + */ + unsigned long + encodeCharVectorToStream (const std::vector& inputByteVector_arg, std::ostream& outputByteStream_arg); + + /** \brief Decode char stream to output vector + * \param inputByteStream_arg input stream of compressed data + * \param outputByteVector_arg decompressed output vector + * \return amount of bytes read from input stream + */ + unsigned long + decodeStreamToCharVector (std::istream& inputByteStream_arg, std::vector& outputByteVector_arg); + + protected: + typedef boost::uint32_t DWord; // 4 bytes + + /** \brief Helper function to calculate the binary logarithm + * \param n_arg: some value + * \return binary logarithm (log2) of argument n_arg + */ + inline double + Log2 (double n_arg) + { + return log (n_arg) / log (2.0); + } + + private: + /** \brief Vector containing cumulative symbol frequency table. */ + std::vector cFreqTable_; + + /** \brief Vector containing compressed data. */ + std::vector outputCharVector_; + + }; +} + + +//#include "impl/entropy_range_coder.hpp" + +#endif + diff --git a/pcl-1.7/pcl/compression/libpng_wrapper.h b/pcl-1.7/pcl/compression/libpng_wrapper.h new file mode 100644 index 0000000..f56cc9d --- /dev/null +++ b/pcl-1.7/pcl/compression/libpng_wrapper.h @@ -0,0 +1,142 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Julius Kammerl (julius@kammerl.de) + */ + +#ifndef __PCL_IO_LIBPNG_WRAPPER__ +#define __PCL_IO_LIBPNG_WRAPPER__ + +#include +#include +#include + +namespace pcl +{ + namespace io + { + /** \brief Encodes 8-bit mono image to PNG format. + * \param[in] image_arg input image data + * \param[in] width_arg image width + * \param[in] height_arg image height + * \param[out] pngData_arg PNG compressed image data + * \param[in] png_level_arg zLib compression level (default level: -1) + * \ingroup io + */ + PCL_EXPORTS void + encodeMonoImageToPNG (std::vector& image_arg, + size_t width_arg, + size_t height_arg, + std::vector& pngData_arg, + int png_level_arg = -1); + + /** \brief Encodes 16-bit mono image to PNG format. + * \param[in] image_arg input image data + * \param[in] width_arg image width + * \param[in] height_arg image height + * \param[out] pngData_arg PNG compressed image data + * \param[in] png_level_arg zLib compression level (default level: -1) + * \ingroup io + */ + PCL_EXPORTS void + encodeMonoImageToPNG (std::vector& image_arg, + size_t width_arg, + size_t height_arg, + std::vector& pngData_arg, + int png_level_arg = -1); + + /** \brief Encodes 8-bit RGB image to PNG format. + * \param[in] image_arg input image data + * \param[in] width_arg image width + * \param[in] height_arg image height + * \param[out] pngData_arg PNG compressed image data + * \param[in] png_level_arg zLib compression level (default level: -1) + * \ingroup io + */ + PCL_EXPORTS void + encodeRGBImageToPNG (std::vector& image_arg, + size_t width_arg, + size_t height_arg, + std::vector& pngData_arg, + int png_level_arg = -1); + + /** \brief Encodes 16-bit RGB image to PNG format. + * \param[in] image_arg input image data + * \param[in] width_arg image width + * \param[in] height_arg image height + * \param[out] pngData_arg PNG compressed image data + * \param[in] png_level_arg zLib compression level (default level: -1) + * \ingroup io + */ + PCL_EXPORTS void + encodeRGBImageToPNG (std::vector& image_arg, + size_t width_arg, + size_t height_arg, + std::vector& pngData_arg, + int png_level_arg = -1); + + /** \brief Decode compressed PNG to 8-bit image + * \param[in] pngData_arg PNG compressed input data + * \param[in] imageData_arg image output data + * \param[out] width_arg image width + * \param[out] heigh_argt image height + * \param[out] channels_arg number of channels + * \ingroup io + */ + PCL_EXPORTS void + decodePNGToImage (std::vector& pngData_arg, + std::vector& imageData_arg, + size_t& width_arg, + size_t& heigh_argt, + unsigned int& channels_arg); + + /** \brief Decode compressed PNG to 16-bit image + * \param[in] pngData_arg PNG compressed input data + * \param[in] imageData_arg image output data + * \param[out] width_arg image width + * \param[out] height_arg image height + * \param[out] channels_arg number of channels + * \ingroup io + */ + PCL_EXPORTS void + decodePNGToImage (std::vector& pngData_arg, + std::vector& imageData_arg, + size_t& width_arg, + size_t& height_arg, + unsigned int& channels_arg); + } +} + + +#endif + diff --git a/pcl-1.7/pcl/compression/octree_pointcloud_compression.h b/pcl-1.7/pcl/compression/octree_pointcloud_compression.h new file mode 100644 index 0000000..de16904 --- /dev/null +++ b/pcl-1.7/pcl/compression/octree_pointcloud_compression.h @@ -0,0 +1,324 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef OCTREE_COMPRESSION_H +#define OCTREE_COMPRESSION_H + +#include +#include +#include +#include +#include "entropy_range_coder.h" +#include "color_coding.h" +#include "point_coding.h" + +#include "compression_profiles.h" + +#include +#include +#include +#include +#include +#include +#include + +using namespace pcl::octree; + +namespace pcl +{ + namespace io + { + /** \brief @b Octree pointcloud compression class + * \note This class enables compression and decompression of point cloud data based on octree data structures. + * \note + * \note typename: PointT: type of point used in pointcloud + * \author Julius Kammerl (julius@kammerl.de) + */ + template > + class OctreePointCloudCompression : public OctreePointCloud + { + public: + // public typedefs + typedef typename OctreePointCloud::PointCloud PointCloud; + typedef typename OctreePointCloud::PointCloudPtr PointCloudPtr; + typedef typename OctreePointCloud::PointCloudConstPtr PointCloudConstPtr; + + // Boost shared pointers + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename OctreeT::LeafNode LeafNode; + typedef typename OctreeT::BranchNode BranchNode; + + typedef OctreePointCloudCompression > RealTimeStreamCompression; + typedef OctreePointCloudCompression > SinglePointCloudCompressionLowMemory; + + + /** \brief Constructor + * \param compressionProfile_arg: define compression profile + * \param octreeResolution_arg: octree resolution at lowest octree level + * \param pointResolution_arg: precision of point coordinates + * \param doVoxelGridDownDownSampling_arg: voxel grid filtering + * \param iFrameRate_arg: i-frame encoding rate + * \param doColorEncoding_arg: enable/disable color coding + * \param colorBitResolution_arg: color bit depth + * \param showStatistics_arg: output compression statistics + */ + OctreePointCloudCompression (compression_Profiles_e compressionProfile_arg = MED_RES_ONLINE_COMPRESSION_WITH_COLOR, + bool showStatistics_arg = false, + const double pointResolution_arg = 0.001, + const double octreeResolution_arg = 0.01, + bool doVoxelGridDownDownSampling_arg = false, + const unsigned int iFrameRate_arg = 30, + bool doColorEncoding_arg = true, + const unsigned char colorBitResolution_arg = 6) : + OctreePointCloud (octreeResolution_arg), + output_ (PointCloudPtr ()), + binary_tree_data_vector_ (), + binary_color_tree_vector_ (), + point_count_data_vector_ (), + point_count_data_vector_iterator_ (), + color_coder_ (), + point_coder_ (), + entropy_coder_ (), + do_voxel_grid_enDecoding_ (doVoxelGridDownDownSampling_arg), i_frame_rate_ (iFrameRate_arg), + i_frame_counter_ (0), frame_ID_ (0), point_count_ (0), i_frame_ (true), + do_color_encoding_ (doColorEncoding_arg), cloud_with_color_ (false), data_with_color_ (false), + point_color_offset_ (0), b_show_statistics_ (showStatistics_arg), + compressed_point_data_len_ (), compressed_color_data_len_ (), selected_profile_(compressionProfile_arg), + point_resolution_(pointResolution_arg), octree_resolution_(octreeResolution_arg), + color_bit_resolution_(colorBitResolution_arg), + object_count_(0) + { + initialization(); + } + + /** \brief Empty deconstructor. */ + virtual + ~OctreePointCloudCompression () + { + } + + /** \brief Initialize globals */ + void initialization () { + if (selected_profile_ != MANUAL_CONFIGURATION) + { + // apply selected compression profile + + // retrieve profile settings + const configurationProfile_t selectedProfile = compressionProfiles_[selected_profile_]; + + // apply profile settings + i_frame_rate_ = selectedProfile.iFrameRate; + do_voxel_grid_enDecoding_ = selectedProfile.doVoxelGridDownSampling; + this->setResolution (selectedProfile.octreeResolution); + point_coder_.setPrecision (static_cast (selectedProfile.pointResolution)); + do_color_encoding_ = selectedProfile.doColorEncoding; + color_coder_.setBitDepth (selectedProfile.colorBitResolution); + + } + else + { + // configure point & color coder + point_coder_.setPrecision (static_cast (point_resolution_)); + color_coder_.setBitDepth (color_bit_resolution_); + } + + if (point_coder_.getPrecision () == this->getResolution ()) + //disable differential point colding + do_voxel_grid_enDecoding_ = true; + + } + + /** \brief Add point at index from input pointcloud dataset to octree + * \param[in] pointIdx_arg the index representing the point in the dataset given by \a setInputCloud to be added + */ + virtual void + addPointIdx (const int pointIdx_arg) + { + ++object_count_; + OctreePointCloud::addPointIdx(pointIdx_arg); + } + + /** \brief Provide a pointer to the output data set. + * \param cloud_arg: the boost shared pointer to a PointCloud message + */ + inline void + setOutputCloud (const PointCloudPtr &cloud_arg) + { + if (output_ != cloud_arg) + { + output_ = cloud_arg; + } + } + + /** \brief Get a pointer to the output point cloud dataset. + * \return pointer to pointcloud output class. + */ + inline PointCloudPtr + getOutputCloud () const + { + return (output_); + } + + /** \brief Encode point cloud to output stream + * \param cloud_arg: point cloud to be compressed + * \param compressed_tree_data_out_arg: binary output stream containing compressed data + */ + void + encodePointCloud (const PointCloudConstPtr &cloud_arg, std::ostream& compressed_tree_data_out_arg); + + /** \brief Decode point cloud from input stream + * \param compressed_tree_data_in_arg: binary input stream containing compressed data + * \param cloud_arg: reference to decoded point cloud + */ + void + decodePointCloud (std::istream& compressed_tree_data_in_arg, PointCloudPtr &cloud_arg); + + protected: + + /** \brief Write frame information to output stream + * \param compressed_tree_data_out_arg: binary output stream + */ + void + writeFrameHeader (std::ostream& compressed_tree_data_out_arg); + + /** \brief Read frame information to output stream + * \param compressed_tree_data_in_arg: binary input stream + */ + void + readFrameHeader (std::istream& compressed_tree_data_in_arg); + + /** \brief Synchronize to frame header + * \param compressed_tree_data_in_arg: binary input stream + */ + void + syncToHeader (std::istream& compressed_tree_data_in_arg); + + /** \brief Apply entropy encoding to encoded information and output to binary stream + * \param compressed_tree_data_out_arg: binary output stream + */ + void + entropyEncoding (std::ostream& compressed_tree_data_out_arg); + + /** \brief Entropy decoding of input binary stream and output to information vectors + * \param compressed_tree_data_in_arg: binary input stream + */ + void + entropyDecoding (std::istream& compressed_tree_data_in_arg); + + /** \brief Encode leaf node information during serialization + * \param leaf_arg: reference to new leaf node + * \param key_arg: octree key of new leaf node + */ + virtual void + serializeTreeCallback (LeafT &leaf_arg, const OctreeKey& key_arg); + + /** \brief Decode leaf nodes information during deserialization + * \param key_arg octree key of new leaf node + */ + // param leaf_arg reference to new leaf node + virtual void + deserializeTreeCallback (LeafT&, const OctreeKey& key_arg); + + + /** \brief Pointer to output point cloud dataset. */ + PointCloudPtr output_; + + /** \brief Vector for storing binary tree structure */ + std::vector binary_tree_data_vector_; + + /** \brief Interator on binary tree structure vector */ + std::vector binary_color_tree_vector_; + + /** \brief Vector for storing points per voxel information */ + std::vector point_count_data_vector_; + + /** \brief Interator on points per voxel vector */ + std::vector::const_iterator point_count_data_vector_iterator_; + + /** \brief Color coding instance */ + ColorCoding color_coder_; + + /** \brief Point coding instance */ + PointCoding point_coder_; + + /** \brief Static range coder instance */ + StaticRangeCoder entropy_coder_; + + bool do_voxel_grid_enDecoding_; + uint32_t i_frame_rate_; + uint32_t i_frame_counter_; + uint32_t frame_ID_; + uint64_t point_count_; + bool i_frame_; + + bool do_color_encoding_; + bool cloud_with_color_; + bool data_with_color_; + unsigned char point_color_offset_; + + //bool activating statistics + bool b_show_statistics_; + uint64_t compressed_point_data_len_; + uint64_t compressed_color_data_len_; + + // frame header identifier + static const char* frame_header_identifier_; + + const compression_Profiles_e selected_profile_; + const double point_resolution_; + const double octree_resolution_; + const unsigned char color_bit_resolution_; + + std::size_t object_count_; + + }; + + // define frame identifier + template + const char* OctreePointCloudCompression::frame_header_identifier_ = ""; + } + +} + + +#endif + diff --git a/pcl-1.7/pcl/compression/organized_pointcloud_compression.h b/pcl-1.7/pcl/compression/organized_pointcloud_compression.h new file mode 100644 index 0000000..5485ae3 --- /dev/null +++ b/pcl-1.7/pcl/compression/organized_pointcloud_compression.h @@ -0,0 +1,155 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_ORGANIZED_POINT_COMPRESSION_H_ +#define PCL_ORGANIZED_POINT_COMPRESSION_H_ + +#include +#include + +#include +#include +#include +#include + +#include + +#include + +namespace pcl +{ + namespace io + { + /** \author Julius Kammerl (julius@kammerl.de) + */ + template + class OrganizedPointCloudCompression + { + public: + typedef pcl::PointCloud PointCloud; + typedef boost::shared_ptr PointCloudPtr; + typedef boost::shared_ptr PointCloudConstPtr; + + /** \brief Empty Constructor. */ + OrganizedPointCloudCompression () + { + } + + /** \brief Empty deconstructor. */ + virtual ~OrganizedPointCloudCompression () + { + } + + /** \brief Encode point cloud to output stream + * \param[in] cloud_arg: point cloud to be compressed + * \param[out] compressedDataOut_arg: binary output stream containing compressed data + * \param[in] doColorEncoding: encode color information (if available) + * \param[in] convertToMono: convert rgb to mono + * \param[in] pngLevel_arg: png compression level (default compression: -1) + * \param[in] bShowStatistics_arg: show statistics + */ + void encodePointCloud (const PointCloudConstPtr &cloud_arg, + std::ostream& compressedDataOut_arg, + bool doColorEncoding = false, + bool convertToMono = false, + bool bShowStatistics_arg = true, + int pngLevel_arg = -1); + + /** \brief Encode raw disparity map and color image. + * \note Default values are configured according to the kinect/asus device specifications + * \param[in] disparityMap_arg: pointer to raw 16-bit disparity map + * \param[in] colorImage_arg: pointer to raw 8-bit rgb color image + * \param[in] width_arg: width of disparity map/color image + * \param[in] height_arg: height of disparity map/color image + * \param[out] compressedDataOut_arg: binary output stream containing compressed data + * \param[in] doColorEncoding: encode color information (if available) + * \param[in] convertToMono: convert rgb to mono + * \param[in] pngLevel_arg: png compression level (default compression: -1) + * \param[in] bShowStatistics_arg: show statistics + * \param[in] focalLength_arg focal length + * \param[in] disparityShift_arg disparity shift + * \param[in] disparityScale_arg disparity scaling + */ + void encodeRawDisparityMapWithColorImage ( std::vector& disparityMap_arg, + std::vector& colorImage_arg, + uint32_t width_arg, + uint32_t height_arg, + std::ostream& compressedDataOut_arg, + bool doColorEncoding = false, + bool convertToMono = false, + bool bShowStatistics_arg = true, + int pngLevel_arg = -1, + float focalLength_arg = 525.0f, + float disparityShift_arg = 174.825f, + float disparityScale_arg = -0.161175f); + + /** \brief Decode point cloud from input stream + * \param[in] compressedDataIn_arg: binary input stream containing compressed data + * \param[out] cloud_arg: reference to decoded point cloud + * \param[in] bShowStatistics_arg: show compression statistics during decoding + * \return false if an I/O error occured. + */ + bool decodePointCloud (std::istream& compressedDataIn_arg, + PointCloudPtr &cloud_arg, + bool bShowStatistics_arg = true); + + protected: + /** \brief Analyze input point cloud and calculate the maximum depth and focal length + * \param[in] cloud_arg: input point cloud + * \param[out] maxDepth_arg: calculated maximum depth + * \param[out] focalLength_arg: estimated focal length + */ + void analyzeOrganizedCloud (PointCloudConstPtr cloud_arg, + float& maxDepth_arg, + float& focalLength_arg) const; + + private: + // frame header identifier + static const char* frameHeaderIdentifier_; + + // + openni_wrapper::ShiftToDepthConverter sd_converter_; + }; + + // define frame identifier + template + const char* OrganizedPointCloudCompression::frameHeaderIdentifier_ = ""; + } +} + +#endif diff --git a/pcl-1.7/pcl/compression/organized_pointcloud_conversion.h b/pcl-1.7/pcl/compression/organized_pointcloud_conversion.h new file mode 100644 index 0000000..d646927 --- /dev/null +++ b/pcl-1.7/pcl/compression/organized_pointcloud_conversion.h @@ -0,0 +1,616 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * Authors: Julius Kammerl (julius@kammerl.de) + */ + +#ifndef PCL_ORGANIZED_CONVERSION_H_ +#define PCL_ORGANIZED_CONVERSION_H_ + +#include +#include + +#include +#include +#include + +namespace pcl +{ + namespace io + { + + template struct CompressionPointTraits + { + static const bool hasColor = false; + static const unsigned int channels = 1; + static const size_t bytesPerPoint = 3 * sizeof(float); + }; + + template<> + struct CompressionPointTraits + { + static const bool hasColor = true; + static const unsigned int channels = 4; + static const size_t bytesPerPoint = 3 * sizeof(float) + 3 * sizeof(uint8_t); + }; + + template<> + struct CompressionPointTraits + { + static const bool hasColor = true; + static const unsigned int channels = 4; + static const size_t bytesPerPoint = 3 * sizeof(float) + 3 * sizeof(uint8_t); + }; + + ////////////////////////////////////////////////////////////////////////////////////////////// + template ::hasColor > + struct OrganizedConversion; + + ////////////////////////////////////////////////////////////////////////////////////////////// + // Uncolored point cloud specialization + ////////////////////////////////////////////////////////////////////////////////////////////// + template + struct OrganizedConversion + { + /** \brief Convert point cloud to disparity image + * \param[in] cloud_arg input point cloud + * \param[in] focalLength_arg focal length + * \param[in] disparityShift_arg disparity shift + * \param[in] disparityScale_arg disparity scaling + * \param[out] disparityData_arg output disparity image + * \ingroup io + */ + static void convert(const pcl::PointCloud& cloud_arg, + float focalLength_arg, + float disparityShift_arg, + float disparityScale_arg, + bool , + typename std::vector& disparityData_arg, + typename std::vector&) + { + size_t cloud_size, i; + + cloud_size = cloud_arg.points.size (); + + // Clear image data + disparityData_arg.clear (); + + disparityData_arg.reserve (cloud_size); + + for (i = 0; i < cloud_size; ++i) + { + // Get point from cloud + const PointT& point = cloud_arg.points[i]; + + if (pcl::isFinite (point)) + { + // Inverse depth quantization + uint16_t disparity = static_cast ( focalLength_arg / (disparityScale_arg * point.z) + disparityShift_arg / disparityScale_arg); + disparityData_arg.push_back (disparity); + } + else + { + // Non-valid points are encoded with zeros + disparityData_arg.push_back (0); + } + } + } + + /** \brief Convert disparity image to point cloud + * \param[in] disparityData_arg input depth image + * \param[in] width_arg width of disparity image + * \param[in] height_arg height of disparity image + * \param[in] focalLength_arg focal length + * \param[in] disparityShift_arg disparity shift + * \param[in] disparityScale_arg disparity scaling + * \param[out] cloud_arg output point cloud + * \ingroup io + */ + static void convert(typename std::vector& disparityData_arg, + typename std::vector&, + bool, + size_t width_arg, + size_t height_arg, + float focalLength_arg, + float disparityShift_arg, + float disparityScale_arg, + pcl::PointCloud& cloud_arg) + { + size_t i; + size_t cloud_size = width_arg * height_arg; + int x, y, centerX, centerY; + + assert(disparityData_arg.size()==cloud_size); + + // Reset point cloud + cloud_arg.points.clear (); + cloud_arg.points.reserve (cloud_size); + + // Define point cloud parameters + cloud_arg.width = static_cast (width_arg); + cloud_arg.height = static_cast (height_arg); + cloud_arg.is_dense = false; + + // Calculate center of disparity image + centerX = static_cast (width_arg / 2); + centerY = static_cast (height_arg / 2); + + const float fl_const = 1.0f / focalLength_arg; + static const float bad_point = std::numeric_limits::quiet_NaN (); + + i = 0; + for (y = -centerY; y < +centerY; ++y) + for (x = -centerX; x < +centerX; ++x) + { + PointT newPoint; + const uint16_t& pixel_disparity = disparityData_arg[i]; + ++i; + + if (pixel_disparity) + { + // Inverse depth decoding + float depth = focalLength_arg / (static_cast (pixel_disparity) * disparityScale_arg + disparityShift_arg); + + // Generate new points + newPoint.x = static_cast (x) * depth * fl_const; + newPoint.y = static_cast (y) * depth * fl_const; + newPoint.z = depth; + + } + else + { + // Generate bad point + newPoint.x = newPoint.y = newPoint.z = bad_point; + } + + cloud_arg.points.push_back (newPoint); + } + + } + + + /** \brief Convert disparity image to point cloud + * \param[in] depthData_arg input depth image + * \param[in] width_arg width of disparity image + * \param[in] height_arg height of disparity image + * \param[in] focalLength_arg focal length + * \param[out] cloud_arg output point cloud + * \ingroup io + */ + static void convert(typename std::vector& depthData_arg, + typename std::vector&, + bool, + size_t width_arg, + size_t height_arg, + float focalLength_arg, + pcl::PointCloud& cloud_arg) + { + size_t i; + size_t cloud_size = width_arg * height_arg; + int x, y, centerX, centerY; + + assert(depthData_arg.size()==cloud_size); + + // Reset point cloud + cloud_arg.points.clear (); + cloud_arg.points.reserve (cloud_size); + + // Define point cloud parameters + cloud_arg.width = static_cast (width_arg); + cloud_arg.height = static_cast (height_arg); + cloud_arg.is_dense = false; + + // Calculate center of disparity image + centerX = static_cast (width_arg / 2); + centerY = static_cast (height_arg / 2); + + const float fl_const = 1.0f / focalLength_arg; + static const float bad_point = std::numeric_limits::quiet_NaN (); + + i = 0; + for (y = -centerY; y < +centerY; ++y) + for (x = -centerX; x < +centerX; ++x) + { + PointT newPoint; + const float& pixel_depth = depthData_arg[i]; + ++i; + + if (pixel_depth) + { + // Inverse depth decoding + float depth = focalLength_arg / pixel_depth; + + // Generate new points + newPoint.x = static_cast (x) * depth * fl_const; + newPoint.y = static_cast (y) * depth * fl_const; + newPoint.z = depth; + + } + else + { + // Generate bad point + newPoint.x = newPoint.y = newPoint.z = bad_point; + } + + cloud_arg.points.push_back (newPoint); + } + + } + + }; + + ////////////////////////////////////////////////////////////////////////////////////////////// + // Colored point cloud specialization + ////////////////////////////////////////////////////////////////////////////////////////////// + template + struct OrganizedConversion + { + /** \brief Convert point cloud to disparity image and rgb image + * \param[in] cloud_arg input point cloud + * \param[in] focalLength_arg focal length + * \param[in] disparityShift_arg disparity shift + * \param[in] disparityScale_arg disparity scaling + * \param[in] convertToMono convert color to mono/grayscale + * \param[out] disparityData_arg output disparity image + * \param[out] rgbData_arg output rgb image + * \ingroup io + */ + static void convert(const pcl::PointCloud& cloud_arg, + float focalLength_arg, + float disparityShift_arg, + float disparityScale_arg, + bool convertToMono, + typename std::vector& disparityData_arg, + typename std::vector& rgbData_arg) + { + size_t cloud_size, i; + + cloud_size = cloud_arg.points.size (); + + // Reset output vectors + disparityData_arg.clear (); + rgbData_arg.clear (); + + // Allocate memory + disparityData_arg.reserve (cloud_size); + if (convertToMono) + { + rgbData_arg.reserve (cloud_size); + } else + { + rgbData_arg.reserve (cloud_size * 3); + } + + + for (i = 0; i < cloud_size; ++i) + { + const PointT& point = cloud_arg.points[i]; + + if (pcl::isFinite (point)) + { + if (convertToMono) + { + // Encode point color + const uint32_t rgb = *reinterpret_cast (&point.rgb); + uint8_t grayvalue = static_cast(0.2989 * static_cast((rgb >> 16) & 0x0000ff) + + 0.5870 * static_cast((rgb >> 8) & 0x0000ff) + + 0.1140 * static_cast((rgb >> 0) & 0x0000ff)); + + rgbData_arg.push_back (grayvalue); + } else + { + // Encode point color + const uint32_t rgb = *reinterpret_cast (&point.rgb); + + rgbData_arg.push_back ( (rgb >> 16) & 0x0000ff); + rgbData_arg.push_back ( (rgb >> 8) & 0x0000ff); + rgbData_arg.push_back ( (rgb >> 0) & 0x0000ff); + } + + + // Inverse depth quantization + uint16_t disparity = static_cast (focalLength_arg / (disparityScale_arg * point.z) + disparityShift_arg / disparityScale_arg); + + // Encode disparity + disparityData_arg.push_back (disparity); + } + else + { + + // Encode black point + if (convertToMono) + { + rgbData_arg.push_back (0); + } else + { + rgbData_arg.push_back (0); + rgbData_arg.push_back (0); + rgbData_arg.push_back (0); + } + + // Encode bad point + disparityData_arg.push_back (0); + } + } + + } + + /** \brief Convert disparity image to point cloud + * \param[in] disparityData_arg output disparity image + * \param[in] rgbData_arg output rgb image + * \param[in] monoImage_arg input image is a single-channel mono image + * \param[in] width_arg width of disparity image + * \param[in] height_arg height of disparity image + * \param[in] focalLength_arg focal length + * \param[in] disparityShift_arg disparity shift + * \param[in] disparityScale_arg disparity scaling + * \param[out] cloud_arg output point cloud + * \ingroup io + */ + static void convert(typename std::vector& disparityData_arg, + typename std::vector& rgbData_arg, + bool monoImage_arg, + size_t width_arg, + size_t height_arg, + float focalLength_arg, + float disparityShift_arg, + float disparityScale_arg, + pcl::PointCloud& cloud_arg) + { + size_t i; + size_t cloud_size = width_arg*height_arg; + bool hasColor = (rgbData_arg.size () > 0); + + // Check size of input data + assert (disparityData_arg.size()==cloud_size); + if (hasColor) + { + if (monoImage_arg) + { + assert (rgbData_arg.size()==cloud_size); + } else + { + assert (rgbData_arg.size()==cloud_size*3); + } + } + + int x, y, centerX, centerY; + + // Reset point cloud + cloud_arg.points.clear(); + cloud_arg.points.reserve(cloud_size); + + // Define point cloud parameters + cloud_arg.width = static_cast(width_arg); + cloud_arg.height = static_cast(height_arg); + cloud_arg.is_dense = false; + + // Calculate center of disparity image + centerX = static_cast(width_arg/2); + centerY = static_cast(height_arg/2); + + const float fl_const = 1.0f/focalLength_arg; + static const float bad_point = std::numeric_limits::quiet_NaN (); + + i = 0; + for (y=-centerY; y<+centerY; ++y ) + for (x=-centerX; x<+centerX; ++x ) + { + PointT newPoint; + + const uint16_t& pixel_disparity = disparityData_arg[i]; + + if (pixel_disparity && (pixel_disparity!=0x7FF)) + { + float depth = focalLength_arg / (static_cast (pixel_disparity) * disparityScale_arg + disparityShift_arg); + + // Define point location + newPoint.z = depth; + newPoint.x = static_cast (x) * depth * fl_const; + newPoint.y = static_cast (y) * depth * fl_const; + + if (hasColor) + { + if (monoImage_arg) + { + const uint8_t& pixel_r = rgbData_arg[i]; + const uint8_t& pixel_g = rgbData_arg[i]; + const uint8_t& pixel_b = rgbData_arg[i]; + + // Define point color + uint32_t rgb = (static_cast(pixel_r) << 16 + | static_cast(pixel_g) << 8 + | static_cast(pixel_b)); + newPoint.rgb = *reinterpret_cast(&rgb); + } else + { + const uint8_t& pixel_r = rgbData_arg[i*3+0]; + const uint8_t& pixel_g = rgbData_arg[i*3+1]; + const uint8_t& pixel_b = rgbData_arg[i*3+2]; + + // Define point color + uint32_t rgb = (static_cast(pixel_r) << 16 + | static_cast(pixel_g) << 8 + | static_cast(pixel_b)); + newPoint.rgb = *reinterpret_cast(&rgb); + } + + } else + { + // Set white point color + uint32_t rgb = (static_cast(255) << 16 + | static_cast(255) << 8 + | static_cast(255)); + newPoint.rgb = *reinterpret_cast(&rgb); + } + } else + { + // Define bad point + newPoint.x = newPoint.y = newPoint.z = bad_point; + newPoint.rgb = 0.0f; + } + + // Add point to cloud + cloud_arg.points.push_back(newPoint); + // Increment point iterator + ++i; + } + } + + /** \brief Convert disparity image to point cloud + * \param[in] depthData_arg output disparity image + * \param[in] rgbData_arg output rgb image + * \param[in] monoImage_arg input image is a single-channel mono image + * \param[in] width_arg width of disparity image + * \param[in] height_arg height of disparity image + * \param[in] focalLength_arg focal length + * \param[out] cloud_arg output point cloud + * \ingroup io + */ + static void convert(typename std::vector& depthData_arg, + typename std::vector& rgbData_arg, + bool monoImage_arg, + size_t width_arg, + size_t height_arg, + float focalLength_arg, + pcl::PointCloud& cloud_arg) + { + size_t i; + size_t cloud_size = width_arg*height_arg; + bool hasColor = (rgbData_arg.size () > 0); + + // Check size of input data + assert (depthData_arg.size()==cloud_size); + if (hasColor) + { + if (monoImage_arg) + { + assert (rgbData_arg.size()==cloud_size); + } else + { + assert (rgbData_arg.size()==cloud_size*3); + } + } + + int x, y, centerX, centerY; + + // Reset point cloud + cloud_arg.points.clear(); + cloud_arg.points.reserve(cloud_size); + + // Define point cloud parameters + cloud_arg.width = static_cast(width_arg); + cloud_arg.height = static_cast(height_arg); + cloud_arg.is_dense = false; + + // Calculate center of disparity image + centerX = static_cast(width_arg/2); + centerY = static_cast(height_arg/2); + + const float fl_const = 1.0f/focalLength_arg; + static const float bad_point = std::numeric_limits::quiet_NaN (); + + i = 0; + for (y=-centerY; y<+centerY; ++y ) + for (x=-centerX; x<+centerX; ++x ) + { + PointT newPoint; + + const float& pixel_depth = depthData_arg[i]; + + if (pixel_depth==pixel_depth) + { + float depth = focalLength_arg / pixel_depth; + + // Define point location + newPoint.z = depth; + newPoint.x = static_cast (x) * depth * fl_const; + newPoint.y = static_cast (y) * depth * fl_const; + + if (hasColor) + { + if (monoImage_arg) + { + const uint8_t& pixel_r = rgbData_arg[i]; + const uint8_t& pixel_g = rgbData_arg[i]; + const uint8_t& pixel_b = rgbData_arg[i]; + + // Define point color + uint32_t rgb = (static_cast(pixel_r) << 16 + | static_cast(pixel_g) << 8 + | static_cast(pixel_b)); + newPoint.rgb = *reinterpret_cast(&rgb); + } else + { + const uint8_t& pixel_r = rgbData_arg[i*3+0]; + const uint8_t& pixel_g = rgbData_arg[i*3+1]; + const uint8_t& pixel_b = rgbData_arg[i*3+2]; + + // Define point color + uint32_t rgb = (static_cast(pixel_r) << 16 + | static_cast(pixel_g) << 8 + | static_cast(pixel_b)); + newPoint.rgb = *reinterpret_cast(&rgb); + } + + } else + { + // Set white point color + uint32_t rgb = (static_cast(255) << 16 + | static_cast(255) << 8 + | static_cast(255)); + newPoint.rgb = *reinterpret_cast(&rgb); + } + } else + { + // Define bad point + newPoint.x = newPoint.y = newPoint.z = bad_point; + newPoint.rgb = 0.0f; + } + + // Add point to cloud + cloud_arg.points.push_back(newPoint); + // Increment point iterator + ++i; + } + } + }; + + } +} + + +#endif diff --git a/pcl-1.7/pcl/compression/point_coding.h b/pcl-1.7/pcl/compression/point_coding.h new file mode 100644 index 0000000..2c77350 --- /dev/null +++ b/pcl-1.7/pcl/compression/point_coding.h @@ -0,0 +1,215 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef POINT_COMPRESSION_H +#define POINT_COMPRESSION_H + +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace octree + { + /** \brief @b PointCoding class + * \note This class encodes 8-bit differential point information for octree-based point cloud compression. + * \note typename: PointT: type of point used in pointcloud + * \author Julius Kammerl (julius@kammerl.de) + */ + template + class PointCoding + { + // public typedefs + typedef pcl::PointCloud PointCloud; + typedef boost::shared_ptr PointCloudPtr; + typedef boost::shared_ptr PointCloudConstPtr; + + public: + /** \brief Constructor. */ + PointCoding () : + output_ (), pointDiffDataVector_ (), pointDiffDataVectorIterator_ (), + pointCompressionResolution_ (0.001f) // 1mm + { + } + + /** \brief Empty class constructor. */ + virtual + ~PointCoding () + { + } + + /** \brief Define precision of point information + * \param precision_arg: precision + */ + inline void + setPrecision (float precision_arg) + { + pointCompressionResolution_ = precision_arg; + } + + /** \brief Retrieve precision of point information + * \return precision + */ + inline float + getPrecision () + { + return (pointCompressionResolution_); + } + + /** \brief Set amount of points within point cloud to be encoded and reserve memory + * \param pointCount_arg: amounts of points within point cloud + */ + inline void + setPointCount (unsigned int pointCount_arg) + { + pointDiffDataVector_.reserve (pointCount_arg * 3); + } + + /** \brief Initialize encoding of differential point */ + void + initializeEncoding () + { + pointDiffDataVector_.clear (); + } + + /** \brief Initialize decoding of differential point */ + void + initializeDecoding () + { + pointDiffDataVectorIterator_ = pointDiffDataVector_.begin (); + } + + /** \brief Get reference to vector containing differential color data */ + std::vector& + getDifferentialDataVector () + { + return (pointDiffDataVector_); + } + + /** \brief Encode differential point information for a subset of points from point cloud + * \param indexVector_arg indices defining a subset of points from points cloud + * \param referencePoint_arg coordinates of reference point + * \param inputCloud_arg input point cloud + */ + void + encodePoints (const typename std::vector& indexVector_arg, const double* referencePoint_arg, + PointCloudConstPtr inputCloud_arg) + { + std::size_t i, len; + + len = indexVector_arg.size (); + + // iterate over points within current voxel + for (i = 0; i < len; i++) + { + unsigned char diffX, diffY, diffZ; + + // retrieve point from cloud + const int& idx = indexVector_arg[i]; + const PointT& idxPoint = inputCloud_arg->points[idx]; + + // differentially encode point coordinates and truncate overflow + diffX = static_cast (max (-127, min(127, static_cast ((idxPoint.x - referencePoint_arg[0]) / pointCompressionResolution_)))); + diffY = static_cast (max (-127, min(127, static_cast ((idxPoint.y - referencePoint_arg[1]) / pointCompressionResolution_)))); + diffZ = static_cast (max (-127, min(127, static_cast ((idxPoint.z - referencePoint_arg[2]) / pointCompressionResolution_)))); + + // store information in differential point vector + pointDiffDataVector_.push_back (diffX); + pointDiffDataVector_.push_back (diffY); + pointDiffDataVector_.push_back (diffZ); + } + } + + /** \brief Decode differential point information + * \param outputCloud_arg output point cloud + * \param referencePoint_arg coordinates of reference point + * \param beginIdx_arg index indicating first point to be assiged with color information + * \param endIdx_arg index indicating last point to be assiged with color information + */ + void + decodePoints (PointCloudPtr outputCloud_arg, const double* referencePoint_arg, std::size_t beginIdx_arg, + std::size_t endIdx_arg) + { + std::size_t i; + unsigned int pointCount; + + assert (beginIdx_arg <= endIdx_arg); + + pointCount = static_cast (endIdx_arg - beginIdx_arg); + + // iterate over points within current voxel + for (i = 0; i < pointCount; i++) + { + // retrieve differential point information + const unsigned char& diffX = static_cast (*(pointDiffDataVectorIterator_++)); + const unsigned char& diffY = static_cast (*(pointDiffDataVectorIterator_++)); + const unsigned char& diffZ = static_cast (*(pointDiffDataVectorIterator_++)); + + // retrieve point from point cloud + PointT& point = outputCloud_arg->points[beginIdx_arg + i]; + + // decode point position + point.x = static_cast (referencePoint_arg[0] + diffX * pointCompressionResolution_); + point.y = static_cast (referencePoint_arg[1] + diffY * pointCompressionResolution_); + point.z = static_cast (referencePoint_arg[2] + diffZ * pointCompressionResolution_); + } + } + + protected: + /** \brief Pointer to output point cloud dataset. */ + PointCloudPtr output_; + + /** \brief Vector for storing differential point information */ + std::vector pointDiffDataVector_; + + /** \brief Iterator on differential point information vector */ + std::vector::const_iterator pointDiffDataVectorIterator_; + + /** \brief Precision of point coding*/ + float pointCompressionResolution_; + }; + } +} + +#define PCL_INSTANTIATE_ColorCoding(T) template class PCL_EXPORTS pcl::octree::ColorCoding; + +#endif diff --git a/pcl-1.7/pcl/console/parse.h b/pcl-1.7/pcl/console/parse.h new file mode 100644 index 0000000..0015875 --- /dev/null +++ b/pcl-1.7/pcl/console/parse.h @@ -0,0 +1,363 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_CONSOLE_PARSE_H_ +#define PCL_CONSOLE_PARSE_H_ + +#include +#include +#include + +namespace pcl +{ + namespace console + { + /** \brief Finds whether the argument with name "argument_name" is in the argument list "argv". + * An example for a widely used switch argument is the "-r" flag for unix commands that indicates whether + * the command should run recursively or not. + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] argument_name the string value to search for + * \return true if argument was found, false otherwise + * \note find_switch is simply returning find_argument != -1. + */ + PCL_EXPORTS bool + find_switch (int argc, char** argv, const char* argument_name); + + /** \brief Finds the position of the argument with name "argument_name" in the argument list "argv" + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] argument_name the string value to search for + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + find_argument (int argc, char** argv, const char* argument_name); + + /** \brief Template version for parsing arguments. Template parameter needs to have input stream operator overloaded! + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] argument_name the name of the argument to search for + * \param[out] value The value of the argument + * \return index of found argument or -1 if arguments do not appear in list + */ + template int + parse (int argc, char** argv, const char* argument_name, Type& value) + { + int index = find_argument (argc, argv, argument_name) + 1; + + if (index > 0 && index < argc) + { + std::istringstream stream; + stream.clear (); + stream.str (argv[index]); + stream >> value; + } + + return (index - 1); + } + + /** \brief Parse for a specific given command line argument. + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the string value to search for + * \param[out] val the resultant value + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_argument (int argc, char** argv, const char* str, std::string &val); + + /** \brief Parse for a specific given command line argument. + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the string value to search for + * \param[out] val the resultant value + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_argument (int argc, char** argv, const char* str, bool &val); + + /** \brief Parse for a specific given command line argument. + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the string value to search for + * \param[out] val the resultant value + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_argument (int argc, char** argv, const char* str, float &val); + + /** \brief Parse for a specific given command line argument. + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the string value to search for + * \param[out] val the resultant value + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_argument (int argc, char** argv, const char* str, double &val); + + /** \brief Parse for a specific given command line argument. + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the string value to search for + * \param[out] val the resultant value + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_argument (int argc, char** argv, const char* str, int &val); + + /** \brief Parse for a specific given command line argument. + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the string value to search for + * \param[out] val the resultant value + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_argument (int argc, char** argv, const char* str, unsigned int &val); + + /** \brief Parse for a specific given command line argument. + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the string value to search for + * \param[out] val the resultant value + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_argument (int argc, char** argv, const char* str, char &val); + + /** \brief Parse for specific given command line arguments (2x values comma + * separated). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the command line argument to search for + * \param[out] f the first output value + * \param[out] s the second output value + * \param[in] debug whether to print debug info or not + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_2x_arguments (int argc, char** argv, const char* str, float &f, float &s, bool debug = true); + + /** \brief Parse for specific given command line arguments (2x values comma + * separated). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the command line argument to search for + * \param[out] f the first output value + * \param[out] s the second output value + * \param[in] debug whether to print debug info or not + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_2x_arguments (int argc, char** argv, const char* str, double &f, double &s, bool debug = true); + + /** \brief Parse for specific given command line arguments (2x values comma + * separated). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the command line argument to search for + * \param[out] f the first output value + * \param[out] s the second output value + * \param[in] debug whether to print debug info or not + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_2x_arguments (int argc, char** argv, const char* str, int &f, int &s, bool debug = true); + + /** \brief Parse for specific given command line arguments (3x values comma + * separated). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the command line argument to search for + * \param[out] f the first output value + * \param[out] s the second output value + * \param[out] t the third output value + * \param[in] debug whether to print debug info or not + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_3x_arguments (int argc, char** argv, const char* str, float &f, float &s, float &t, bool debug = true); + + /** \brief Parse for specific given command line arguments (3x values comma + * separated). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the command line argument to search for + * \param[out] f the first output value + * \param[out] s the second output value + * \param[out] t the third output value + * \param[in] debug whether to print debug info or not + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_3x_arguments (int argc, char** argv, const char* str, double &f, double &s, double &t, bool debug = true); + + /** \brief Parse for specific given command line arguments (3x values comma + * separated). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the command line argument to search for + * \param[out] f the first output value + * \param[out] s the second output value + * \param[out] t the third output value + * \param[in] debug whether to print debug info or not + * return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_3x_arguments (int argc, char** argv, const char* str, int &f, int &s, int &t, bool debug = true); + + /** \brief Parse for specific given command line arguments (3x values comma + * separated). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the command line argument to search for + * \param[out] v the vector into which the parsed values will be copied + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_x_arguments (int argc, char** argv, const char* str, std::vector& v); + + /** \brief Parse for specific given command line arguments (N values comma + * separated). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the command line argument to search for + * \param[out] v the vector into which the parsed values will be copied + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_x_arguments (int argc, char** argv, const char* str, std::vector& v); + + /** \brief Parse for specific given command line arguments (N values comma + * separated). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the command line argument to search for + * \param[out] v the vector into which the parsed values will be copied + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS int + parse_x_arguments (int argc, char** argv, const char* str, std::vector& v); + + /** \brief Parse for specific given command line arguments (multiple occurences + * of the same command line parameter). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the command line argument to search for + * \param[out] values the resultant output values + * \return index of found argument or -1 if arguments do not appear in list + */ + PCL_EXPORTS bool + parse_multiple_arguments (int argc, char** argv, const char* str, std::vector &values); + + /** \brief Parse for specific given command line arguments (multiple occurences + * of the same command line parameter). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the command line argument to search for + * \param[out] values the resultant output values + * \return true if found, false otherwise + */ + PCL_EXPORTS bool + parse_multiple_arguments (int argc, char** argv, const char* str, std::vector &values); + + /** \brief Parse for specific given command line arguments (multiple occurences + * of the same command line parameter). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the command line argument to search for + * \param[out] values the resultant output values + * \return true if found, false otherwise + */ + PCL_EXPORTS bool + parse_multiple_arguments (int argc, char** argv, const char* str, std::vector &values); + + /** \brief Parse for a specific given command line argument (multiple occurences + * of the same command line parameter). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the string value to search for + * \param[out] values the resultant output values + * \return true if found, false otherwise + */ + PCL_EXPORTS bool + parse_multiple_arguments (int argc, char** argv, const char* str, std::vector &values); + + /** \brief Parse command line arguments for file names with given extension (multiple occurences + * of 2x argument groups, separated by commas). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the command line argument to search for + * \param[out] values_f the first vector of output values + * \param[out] values_s the second vector of output values + * \return true if found, false otherwise + */ + PCL_EXPORTS bool + parse_multiple_2x_arguments (int argc, char** argv, const char* str, + std::vector &values_f, + std::vector &values_s); + + /** \brief Parse command line arguments for file names with given extension (multiple occurences + * of 3x argument groups, separated by commas). + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] str the command line argument to search for + * \param[out] values_f the first vector of output values + * \param[out] values_s the second vector of output values + * \param[out] values_t the third vector of output values + * \return true if found, false otherwise + */ + PCL_EXPORTS bool + parse_multiple_3x_arguments (int argc, char** argv, const char* str, + std::vector &values_f, + std::vector &values_s, + std::vector &values_t); + + /** \brief Parse command line arguments for file names with given extension + * \param[in] argc the number of command line arguments + * \param[in] argv the command line arguments + * \param[in] ext the extension to search for + * \return a vector with file names indices + */ + PCL_EXPORTS std::vector + parse_file_extension_argument (int argc, char** argv, const std::string &ext); + } +} + +#endif // PCL_CONSOLE_PARSE_H_ + diff --git a/pcl-1.7/pcl/console/print.h b/pcl-1.7/pcl/console/print.h new file mode 100644 index 0000000..2c2cd8c --- /dev/null +++ b/pcl-1.7/pcl/console/print.h @@ -0,0 +1,251 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef TERMINAL_TOOLS_PRINT_H_ +#define TERMINAL_TOOLS_PRINT_H_ + +#include +#include + +#include +#include + +#define PCL_ALWAYS(...) pcl::console::print (pcl::console::L_ALWAYS, __VA_ARGS__) +#define PCL_ERROR(...) pcl::console::print (pcl::console::L_ERROR, __VA_ARGS__) +#define PCL_WARN(...) pcl::console::print (pcl::console::L_WARN, __VA_ARGS__) +#define PCL_INFO(...) pcl::console::print (pcl::console::L_INFO, __VA_ARGS__) +#define PCL_DEBUG(...) pcl::console::print (pcl::console::L_DEBUG, __VA_ARGS__) +#define PCL_VERBOSE(...) pcl::console::print (pcl::console::L_VERBOSE, __VA_ARGS__) + +#define PCL_ASSERT_ERROR_PRINT_CHECK(pred, msg) \ + do \ + { \ + if (!(pred)) \ + { \ + PCL_ERROR(msg); \ + PCL_ERROR("In File %s, in line %d\n" __FILE__, __LINE__); \ + } \ + } while (0) + +#define PCL_ASSERT_ERROR_PRINT_RETURN(pred, msg, err) \ + do \ + { \ + PCL_ASSERT_ERROR_PRINT_CHECK(pred, msg); \ + if (!(pred)) return err; \ + } while (0) + +namespace pcl +{ + namespace console + { + enum TT_ATTIBUTES + { + TT_RESET = 0, + TT_BRIGHT = 1, + TT_DIM = 2, + TT_UNDERLINE = 3, + TT_BLINK = 4, + TT_REVERSE = 7, + TT_HIDDEN = 8 + }; + + enum TT_COLORS + { + TT_BLACK, + TT_RED, + TT_GREEN, + TT_YELLOW, + TT_BLUE, + TT_MAGENTA, + TT_CYAN, + TT_WHITE + }; + + enum VERBOSITY_LEVEL + { + L_ALWAYS, + L_ERROR, + L_WARN, + L_INFO, + L_DEBUG, + L_VERBOSE + }; + + /** set the verbosity level */ + PCL_EXPORTS void + setVerbosityLevel (VERBOSITY_LEVEL level); + + /** get the verbosity level. */ + PCL_EXPORTS VERBOSITY_LEVEL + getVerbosityLevel (); + + /** initialize verbosity level. */ + PCL_EXPORTS bool + initVerbosityLevel (); + + /** is verbosity level enabled? */ + PCL_EXPORTS bool + isVerbosityLevelEnabled (VERBOSITY_LEVEL severity); + + /** \brief Change the text color (on either stdout or stderr) with an attr:fg:bg + * \param stream the output stream (stdout, stderr, etc) + * \param attribute the text attribute + * \param fg the foreground color + * \param bg the background color + */ + PCL_EXPORTS void + change_text_color (FILE *stream, int attribute, int fg, int bg); + + /** \brief Change the text color (on either stdout or stderr) with an attr:fg + * \param stream the output stream (stdout, stderr, etc) + * \param attribute the text attribute + * \param fg the foreground color + */ + PCL_EXPORTS void + change_text_color (FILE *stream, int attribute, int fg); + + /** \brief Reset the text color (on either stdout or stderr) to its original state + * \param stream the output stream (stdout, stderr, etc) + */ + PCL_EXPORTS void + reset_text_color (FILE *stream); + + /** \brief Print a message on stream with colors + * \param stream the output stream (stdout, stderr, etc) + * \param attr the text attribute + * \param fg the foreground color + * \param format the message + */ + PCL_EXPORTS void + print_color (FILE *stream, int attr, int fg, const char *format, ...); + + /** \brief Print an info message on stream with colors + * \param format the message + */ + PCL_EXPORTS void + print_info (const char *format, ...); + + /** \brief Print an info message on stream with colors + * \param stream the output stream (stdout, stderr, etc) + * \param format the message + */ + PCL_EXPORTS void + print_info (FILE *stream, const char *format, ...); + + /** \brief Print a highlighted info message on stream with colors + * \param format the message + */ + PCL_EXPORTS void + print_highlight (const char *format, ...); + + /** \brief Print a highlighted info message on stream with colors + * \param stream the output stream (stdout, stderr, etc) + * \param format the message + */ + PCL_EXPORTS void + print_highlight (FILE *stream, const char *format, ...); + + /** \brief Print an error message on stream with colors + * \param format the message + */ + PCL_EXPORTS void + print_error (const char *format, ...); + + /** \brief Print an error message on stream with colors + * \param stream the output stream (stdout, stderr, etc) + * \param format the message + */ + PCL_EXPORTS void + print_error (FILE *stream, const char *format, ...); + + /** \brief Print a warning message on stream with colors + * \param format the message + */ + PCL_EXPORTS void + print_warn (const char *format, ...); + + /** \brief Print a warning message on stream with colors + * \param stream the output stream (stdout, stderr, etc) + * \param format the message + */ + PCL_EXPORTS void + print_warn (FILE *stream, const char *format, ...); + + /** \brief Print a debug message on stream with colors + * \param format the message + */ + PCL_EXPORTS void + print_debug (const char *format, ...); + + /** \brief Print a debug message on stream with colors + * \param stream the output stream (stdout, stderr, etc) + * \param format the message + */ + PCL_EXPORTS void + print_debug (FILE *stream, const char *format, ...); + + + /** \brief Print a value message on stream with colors + * \param format the message + */ + PCL_EXPORTS void + print_value (const char *format, ...); + + /** \brief Print a value message on stream with colors + * \param stream the output stream (stdout, stderr, etc) + * \param format the message + */ + PCL_EXPORTS void + print_value (FILE *stream, const char *format, ...); + + /** \brief Print a message on stream + * \param level the verbosity level + * \param stream the output stream (stdout, stderr, etc) + * \param format the message + */ + PCL_EXPORTS void + print (VERBOSITY_LEVEL level, FILE *stream, const char *format, ...); + + /** \brief Print a message + * \param level the verbosity level + * \param format the message + */ + PCL_EXPORTS void + print (VERBOSITY_LEVEL level, const char *format, ...); + } +} + +#endif // TERMINAL_TOOLS_PRINT_H_ diff --git a/pcl-1.7/pcl/console/time.h b/pcl-1.7/pcl/console/time.h new file mode 100644 index 0000000..b5a91c3 --- /dev/null +++ b/pcl-1.7/pcl/console/time.h @@ -0,0 +1,95 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef TERMINAL_TOOLS_TIME_H_ +#define TERMINAL_TOOLS_TIME_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#ifndef Q_MOC_RUN +#include +#endif +#include + +namespace pcl +{ + namespace console + { + class TicToc + { + public: + + TicToc () : tictic (), toctoc () {} + + void + tic () + { + tictic = boost::posix_time::microsec_clock::local_time (); + }; + + inline double + toc () + { + toctoc = boost::posix_time::microsec_clock::local_time (); + return (static_cast ((toctoc - tictic).total_milliseconds ())); + }; + + inline void + toc_print () + { + double milliseconds = toc (); + //int minutes = (int) floor ( seconds / 60.0 ); + //seconds -= minutes * 60.0; + //if (minutes != 0) + //{ + // print_value ("%i", minutes); + // print_info (" minutes, "); + //} + print_value ("%g", milliseconds); + print_info (" ms\n"); + }; + + private: + boost::posix_time::ptime tictic; + boost::posix_time::ptime toctoc; + }; + } +} + +#endif diff --git a/pcl-1.7/pcl/conversions.h b/pcl-1.7/pcl/conversions.h new file mode 100644 index 0000000..a5bf20b --- /dev/null +++ b/pcl-1.7/pcl/conversions.h @@ -0,0 +1,349 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_CONVERSIONS_H_ +#define PCL_CONVERSIONS_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#ifndef Q_MOC_RUN +#include +#endif + +namespace pcl +{ + namespace detail + { + // For converting template point cloud to message. + template + struct FieldAdder + { + FieldAdder (std::vector& fields) : fields_ (fields) {}; + + template void operator() () + { + pcl::PCLPointField f; + f.name = traits::name::value; + f.offset = traits::offset::value; + f.datatype = traits::datatype::value; + f.count = traits::datatype::size; + fields_.push_back (f); + } + + std::vector& fields_; + }; + + // For converting message to template point cloud. + template + struct FieldMapper + { + FieldMapper (const std::vector& fields, + std::vector& map) + : fields_ (fields), map_ (map) + { + } + + template void + operator () () + { + BOOST_FOREACH (const pcl::PCLPointField& field, fields_) + { + if (FieldMatches()(field)) + { + FieldMapping mapping; + mapping.serialized_offset = field.offset; + mapping.struct_offset = traits::offset::value; + mapping.size = sizeof (typename traits::datatype::type); + map_.push_back (mapping); + return; + } + } + // Disable thrown exception per #595: http://dev.pointclouds.org/issues/595 + PCL_WARN ("Failed to find match for field '%s'.\n", traits::name::value); + //throw pcl::InvalidConversionException (ss.str ()); + } + + const std::vector& fields_; + std::vector& map_; + }; + + inline bool + fieldOrdering (const FieldMapping& a, const FieldMapping& b) + { + return (a.serialized_offset < b.serialized_offset); + } + + } //namespace detail + + template void + createMapping (const std::vector& msg_fields, MsgFieldMap& field_map) + { + // Create initial 1-1 mapping between serialized data segments and struct fields + detail::FieldMapper mapper (msg_fields, field_map); + for_each_type< typename traits::fieldList::type > (mapper); + + // Coalesce adjacent fields into single memcpy's where possible + if (field_map.size() > 1) + { + std::sort(field_map.begin(), field_map.end(), detail::fieldOrdering); + MsgFieldMap::iterator i = field_map.begin(), j = i + 1; + while (j != field_map.end()) + { + // This check is designed to permit padding between adjacent fields. + /// @todo One could construct a pathological case where the struct has a + /// field where the serialized data has padding + if (j->serialized_offset - i->serialized_offset == j->struct_offset - i->struct_offset) + { + i->size += (j->struct_offset + j->size) - (i->struct_offset + i->size); + j = field_map.erase(j); + } + else + { + ++i; + ++j; + } + } + } + } + + /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud object using a field_map. + * \param[in] msg the PCLPointCloud2 binary blob + * \param[out] cloud the resultant pcl::PointCloud + * \param[in] field_map a MsgFieldMap object + * + * \note Use fromPCLPointCloud2 (PCLPointCloud2, PointCloud) directly or create you + * own MsgFieldMap using: + * + * \code + * MsgFieldMap field_map; + * createMapping (msg.fields, field_map); + * \endcode + */ + template void + fromPCLPointCloud2 (const pcl::PCLPointCloud2& msg, pcl::PointCloud& cloud, + const MsgFieldMap& field_map) + { + // Copy info fields + cloud.header = msg.header; + cloud.width = msg.width; + cloud.height = msg.height; + cloud.is_dense = msg.is_dense == 1; + + // Copy point data + uint32_t num_points = msg.width * msg.height; + cloud.points.resize (num_points); + uint8_t* cloud_data = reinterpret_cast(&cloud.points[0]); + + // Check if we can copy adjacent points in a single memcpy + if (field_map.size() == 1 && + field_map[0].serialized_offset == 0 && + field_map[0].struct_offset == 0 && + msg.point_step == sizeof(PointT)) + { + uint32_t cloud_row_step = static_cast (sizeof (PointT) * cloud.width); + const uint8_t* msg_data = &msg.data[0]; + // Should usually be able to copy all rows at once + if (msg.row_step == cloud_row_step) + { + memcpy (cloud_data, msg_data, msg.data.size ()); + } + else + { + for (uint32_t i = 0; i < msg.height; ++i, cloud_data += cloud_row_step, msg_data += msg.row_step) + memcpy (cloud_data, msg_data, cloud_row_step); + } + + } + else + { + // If not, memcpy each group of contiguous fields separately + for (uint32_t row = 0; row < msg.height; ++row) + { + const uint8_t* row_data = &msg.data[row * msg.row_step]; + for (uint32_t col = 0; col < msg.width; ++col) + { + const uint8_t* msg_data = row_data + col * msg.point_step; + BOOST_FOREACH (const detail::FieldMapping& mapping, field_map) + { + memcpy (cloud_data + mapping.struct_offset, msg_data + mapping.serialized_offset, mapping.size); + } + cloud_data += sizeof (PointT); + } + } + } + } + + /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud object. + * \param[in] msg the PCLPointCloud2 binary blob + * \param[out] cloud the resultant pcl::PointCloud + */ + template void + fromPCLPointCloud2 (const pcl::PCLPointCloud2& msg, pcl::PointCloud& cloud) + { + MsgFieldMap field_map; + createMapping (msg.fields, field_map); + fromPCLPointCloud2 (msg, cloud, field_map); + } + + /** \brief Convert a pcl::PointCloud object to a PCLPointCloud2 binary data blob. + * \param[in] cloud the input pcl::PointCloud + * \param[out] msg the resultant PCLPointCloud2 binary blob + */ + template void + toPCLPointCloud2 (const pcl::PointCloud& cloud, pcl::PCLPointCloud2& msg) + { + // Ease the user's burden on specifying width/height for unorganized datasets + if (cloud.width == 0 && cloud.height == 0) + { + msg.width = static_cast(cloud.points.size ()); + msg.height = 1; + } + else + { + assert (cloud.points.size () == cloud.width * cloud.height); + msg.height = cloud.height; + msg.width = cloud.width; + } + + // Fill point cloud binary data (padding and all) + size_t data_size = sizeof (PointT) * cloud.points.size (); + msg.data.resize (data_size); + memcpy (&msg.data[0], &cloud.points[0], data_size); + + // Fill fields metadata + msg.fields.clear (); + for_each_type::type> (detail::FieldAdder(msg.fields)); + + msg.header = cloud.header; + msg.point_step = sizeof (PointT); + msg.row_step = static_cast (sizeof (PointT) * msg.width); + msg.is_dense = cloud.is_dense; + /// @todo msg.is_bigendian = ?; + } + + /** \brief Copy the RGB fields of a PointCloud into pcl::PCLImage format + * \param[in] cloud the point cloud message + * \param[out] msg the resultant pcl::PCLImage + * CloudT cloud type, CloudT should be akin to pcl::PointCloud + * \note will throw std::runtime_error if there is a problem + */ + template void + toPCLPointCloud2 (const CloudT& cloud, pcl::PCLImage& msg) + { + // Ease the user's burden on specifying width/height for unorganized datasets + if (cloud.width == 0 && cloud.height == 0) + throw std::runtime_error("Needs to be a dense like cloud!!"); + else + { + if (cloud.points.size () != cloud.width * cloud.height) + throw std::runtime_error("The width and height do not match the cloud size!"); + msg.height = cloud.height; + msg.width = cloud.width; + } + + // ensor_msgs::image_encodings::BGR8; + msg.encoding = "bgr8"; + msg.step = msg.width * sizeof (uint8_t) * 3; + msg.data.resize (msg.step * msg.height); + for (size_t y = 0; y < cloud.height; y++) + { + for (size_t x = 0; x < cloud.width; x++) + { + uint8_t * pixel = &(msg.data[y * msg.step + x * 3]); + memcpy (pixel, &cloud (x, y).rgb, 3 * sizeof(uint8_t)); + } + } + } + + /** \brief Copy the RGB fields of a PCLPointCloud2 msg into pcl::PCLImage format + * \param cloud the point cloud message + * \param msg the resultant pcl::PCLImage + * will throw std::runtime_error if there is a problem + */ + inline void + toPCLPointCloud2 (const pcl::PCLPointCloud2& cloud, pcl::PCLImage& msg) + { + int rgb_index = -1; + // Get the index we need + for (size_t d = 0; d < cloud.fields.size (); ++d) + if (cloud.fields[d].name == "rgb") + { + rgb_index = static_cast(d); + break; + } + + if(rgb_index == -1) + throw std::runtime_error ("No rgb field!!"); + if (cloud.width == 0 && cloud.height == 0) + throw std::runtime_error ("Needs to be a dense like cloud!!"); + else + { + msg.height = cloud.height; + msg.width = cloud.width; + } + int rgb_offset = cloud.fields[rgb_index].offset; + int point_step = cloud.point_step; + + // pcl::image_encodings::BGR8; + msg.encoding = "bgr8"; + msg.step = static_cast(msg.width * sizeof (uint8_t) * 3); + msg.data.resize (msg.step * msg.height); + + for (size_t y = 0; y < cloud.height; y++) + { + for (size_t x = 0; x < cloud.width; x++, rgb_offset += point_step) + { + uint8_t * pixel = &(msg.data[y * msg.step + x * 3]); + memcpy (pixel, &(cloud.data[rgb_offset]), 3 * sizeof (uint8_t)); + } + } + } +} + +#endif //#ifndef PCL_CONVERSIONS_H_ diff --git a/pcl-1.7/pcl/correspondence.h b/pcl-1.7/pcl/correspondence.h new file mode 100644 index 0000000..4dfb53c --- /dev/null +++ b/pcl-1.7/pcl/correspondence.h @@ -0,0 +1,163 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_COMMON_CORRESPONDENCE_H_ +#define PCL_COMMON_CORRESPONDENCE_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Correspondence represents a match between two entities (e.g., points, descriptors, etc). This is + * represesented via the indices of a \a source point and a \a target point, and the distance between them. + * + * \author Dirk Holz, Radu B. Rusu, Bastian Steder + * \ingroup common + */ + struct Correspondence + { + /** \brief Index of the query (source) point. */ + int index_query; + /** \brief Index of the matching (target) point. Set to -1 if no correspondence found. */ + int index_match; + /** \brief Distance between the corresponding points, or the weight denoting the confidence in correspondence estimation */ + union + { + float distance; + float weight; + }; + + /** \brief Standard constructor. + * Sets \ref index_query to 0, \ref index_match to -1, and \ref distance to FLT_MAX. + */ + inline Correspondence () : index_query (0), index_match (-1), + distance (std::numeric_limits::max ()) + {} + + /** \brief Constructor. */ + inline Correspondence (int _index_query, int _index_match, float _distance) : + index_query (_index_query), index_match (_index_match), distance (_distance) + {} + + /** \brief Empty destructor. */ + virtual ~Correspondence () {} + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + /** \brief overloaded << operator */ + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Correspondence& c); + + typedef std::vector< pcl::Correspondence, Eigen::aligned_allocator > Correspondences; + typedef boost::shared_ptr CorrespondencesPtr; + typedef boost::shared_ptr CorrespondencesConstPtr; + + /** + * \brief Get the query points of correspondences that are present in + * one correspondence vector but not in the other, e.g., to compare + * correspondences before and after rejection. + * \param[in] correspondences_before Vector of correspondences before rejection + * \param[in] correspondences_after Vector of correspondences after rejection + * \param[out] indices Query point indices of correspondences that have been rejected + * \param[in] presorting_required Enable/disable internal sorting of vectors. + * By default (true), vectors are internally sorted before determining their difference. + * If the order of correspondences in \a correspondences_after is not different (has not been changed) + * from the order in \b correspondences_before this pre-processing step can be disabled + * in order to gain efficiency. In order to disable pre-sorting set \a presorting_requered to false. + */ + void + getRejectedQueryIndices (const pcl::Correspondences &correspondences_before, + const pcl::Correspondences &correspondences_after, + std::vector& indices, + bool presorting_required = true); + + /** + * \brief Representation of a (possible) correspondence between two 3D points in two different coordinate frames + * (e.g. from feature matching) + * \ingroup common + */ + struct PointCorrespondence3D : public Correspondence + { + Eigen::Vector3f point1; //!< The 3D position of the point in the first coordinate frame + Eigen::Vector3f point2; //!< The 3D position of the point in the second coordinate frame + + /** \brief Empty constructor. */ + PointCorrespondence3D () : point1 (), point2 () {} + + /** \brief Empty destructor. */ + virtual ~PointCorrespondence3D () {} + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + typedef std::vector > PointCorrespondences3DVector; + + /** + * \brief Representation of a (possible) correspondence between two points (e.g. from feature matching), + * that encode complete 6DOF transoformations. + * \ingroup common + */ + struct PointCorrespondence6D : public PointCorrespondence3D + { + Eigen::Affine3f transformation; //!< The transformation to go from the coordinate system + //!< of point2 to the coordinate system of point1 + /** \brief Empty destructor. */ + virtual ~PointCorrespondence6D () {} + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + typedef std::vector > PointCorrespondences6DVector; + + /** + * \brief Comparator to enable us to sort a vector of PointCorrespondences according to their scores using + * std::sort (begin(), end(), isBetterCorrespondence); + * \ingroup common + */ + inline bool + isBetterCorrespondence (const Correspondence &pc1, const Correspondence &pc2) + { + return (pc1.distance > pc2.distance); + } +} + +#endif /* PCL_COMMON_CORRESPONDENCE_H_ */ diff --git a/pcl-1.7/pcl/exceptions.h b/pcl-1.7/pcl/exceptions.h new file mode 100644 index 0000000..b3462da --- /dev/null +++ b/pcl-1.7/pcl/exceptions.h @@ -0,0 +1,270 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_EXCEPTIONS_H_ +#define PCL_EXCEPTIONS_H_ + +#include +#include +#include +#include + +/** PCL_THROW_EXCEPTION a helper macro to be used for throwing exceptions. + * This is an example on how to use: + * PCL_THROW_EXCEPTION(IOException, + * "encountered an error while opening " << filename << " PCD file"); + */ +#define PCL_THROW_EXCEPTION(ExceptionName, message) \ +{ \ + std::ostringstream s; \ + s << message; \ + s.flush (); \ + throw ExceptionName(s.str(), __FILE__, BOOST_CURRENT_FUNCTION, __LINE__); \ +} + +namespace pcl +{ + + /** \class PCLException + * \brief A base class for all pcl exceptions which inherits from std::runtime_error + * \author Eitan Marder-Eppstein, Suat Gedikli, Nizar Sallem + */ + class PCLException : public std::runtime_error + { + public: + + PCLException (const std::string& error_description, + const std::string& file_name = "", + const std::string& function_name = "" , + unsigned line_number = 0) throw () + : std::runtime_error (error_description) + , file_name_ (file_name) + , function_name_ (function_name) + , message_ (error_description) + , line_number_ (line_number) + { + message_ = detailedMessage (); + } + + virtual ~PCLException () throw () + {} + + const std::string& + getFileName () const throw () + { + return (file_name_); + } + + const std::string& + getFunctionName () const throw () + { + return (function_name_); + } + + unsigned + getLineNumber () const throw () + { + return (line_number_); + } + + std::string + detailedMessage () const throw () + { + std::stringstream sstream; + if (function_name_ != "") + sstream << function_name_ << " "; + + if (file_name_ != "") + { + sstream << "in " << file_name_ << " "; + if (line_number_ != 0) + sstream << "@ " << line_number_ << " "; + } + sstream << ": " << what (); + + return (sstream.str ()); + } + + char const* + what () const throw () + { + return (message_.c_str ()); + } + + protected: + std::string file_name_; + std::string function_name_; + std::string message_; + unsigned line_number_; + } ; + + /** \class InvalidConversionException + * \brief An exception that is thrown when a PCLPointCloud2 message cannot be converted into a PCL type + */ + class InvalidConversionException : public PCLException + { + public: + + InvalidConversionException (const std::string& error_description, + const std::string& file_name = "", + const std::string& function_name = "" , + unsigned line_number = 0) throw () + : pcl::PCLException (error_description, file_name, function_name, line_number) { } + } ; + + /** \class IsNotDenseException + * \brief An exception that is thrown when a PointCloud is not dense but is attemped to be used as dense + */ + class IsNotDenseException : public PCLException + { + public: + + IsNotDenseException (const std::string& error_description, + const std::string& file_name = "", + const std::string& function_name = "" , + unsigned line_number = 0) throw () + : pcl::PCLException (error_description, file_name, function_name, line_number) { } + } ; + + /** \class InvalidSACModelTypeException + * \brief An exception that is thrown when a sample consensus model doesn't + * have the correct number of samples defined in model_types.h + */ + class InvalidSACModelTypeException : public PCLException + { + public: + + InvalidSACModelTypeException (const std::string& error_description, + const std::string& file_name = "", + const std::string& function_name = "" , + unsigned line_number = 0) throw () + : pcl::PCLException (error_description, file_name, function_name, line_number) { } + } ; + + /** \class IOException + * \brief An exception that is thrown during an IO error (typical read/write errors) + */ + class IOException : public PCLException + { + public: + + IOException (const std::string& error_description, + const std::string& file_name = "", + const std::string& function_name = "" , + unsigned line_number = 0) throw () + : pcl::PCLException (error_description, file_name, function_name, line_number) { } + } ; + + /** \class InitFailedException + * \brief An exception thrown when init can not be performed should be used in all the + * PCLBase class inheritants. + */ + class InitFailedException : public PCLException + { + public: + InitFailedException (const std::string& error_description = "", + const std::string& file_name = "", + const std::string& function_name = "" , + unsigned line_number = 0) throw () + : pcl::PCLException (error_description, file_name, function_name, line_number) { } + } ; + + /** \class UnorganizedPointCloudException + * \brief An exception that is thrown when an organized point cloud is needed + * but not provided. + */ + class UnorganizedPointCloudException : public PCLException + { + public: + + UnorganizedPointCloudException (const std::string& error_description, + const std::string& file_name = "", + const std::string& function_name = "" , + unsigned line_number = 0) throw () + : pcl::PCLException (error_description, file_name, function_name, line_number) { } + } ; + + /** \class KernelWidthTooSmallException + * \brief An exception that is thrown when the kernel size is too small + */ + class KernelWidthTooSmallException : public PCLException + { + public: + + KernelWidthTooSmallException (const std::string& error_description, + const std::string& file_name = "", + const std::string& function_name = "" , + unsigned line_number = 0) throw () + : pcl::PCLException (error_description, file_name, function_name, line_number) { } + } ; + + class UnhandledPointTypeException : public PCLException + { + public: + UnhandledPointTypeException (const std::string& error_description, + const std::string& file_name = "", + const std::string& function_name = "" , + unsigned line_number = 0) throw () + : pcl::PCLException (error_description, file_name, function_name, line_number) { } + }; + + class ComputeFailedException : public PCLException + { + public: + ComputeFailedException (const std::string& error_description, + const std::string& file_name = "", + const std::string& function_name = "" , + unsigned line_number = 0) throw () + : pcl::PCLException (error_description, file_name, function_name, line_number) { } + }; + + /** \class BadArgumentException + * \brief An exception that is thrown when the argments number or type is wrong/unhandled. + */ + class BadArgumentException : public PCLException + { + public: + BadArgumentException (const std::string& error_description, + const std::string& file_name = "", + const std::string& function_name = "" , + unsigned line_number = 0) throw () + : pcl::PCLException (error_description, file_name, function_name, line_number) { } + }; +} + + + +#endif diff --git a/pcl-1.7/pcl/features/3dsc.h b/pcl-1.7/pcl/features/3dsc.h new file mode 100644 index 0000000..00d396e --- /dev/null +++ b/pcl-1.7/pcl/features/3dsc.h @@ -0,0 +1,243 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_3DSC_H_ +#define PCL_FEATURES_3DSC_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief ShapeContext3DEstimation implements the 3D shape context descriptor as + * described in: + * - Andrea Frome, Daniel Huber, Ravi Kolluri and Thomas Bülow, Jitendra Malik + * Recognizing Objects in Range Data Using Regional Point Descriptors, + * In proceedings of the 8th European Conference on Computer Vision (ECCV), + * Prague, May 11-14, 2004 + * + * The suggested PointOutT is pcl::ShapeContext1980 + * + * \attention + * The convention for a 3D shape context descriptor is: + * - if a query point's nearest neighbors cannot be estimated, the feature descriptor will be set to NaN (not a number), and the RF to 0 + * - it is impossible to estimate a 3D shape context descriptor for a + * point that doesn't have finite 3D coordinates. Therefore, any point + * that contains NaN data on x, y, or z, will have its boundary feature + * property set to NaN. + * + * \author Alessandro Franchi, Samuele Salti, Federico Tombari (original code) + * \author Nizar Sallem (port to PCL) + * \ingroup features + */ + template + class ShapeContext3DEstimation : public FeatureFromNormals + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::search_parameter_; + using Feature::search_radius_; + using Feature::surface_; + using Feature::input_; + using Feature::searchForNeighbors; + using FeatureFromNormals::normals_; + + typedef typename Feature::PointCloudOut PointCloudOut; + typedef typename Feature::PointCloudIn PointCloudIn; + + /** \brief Constructor. + * \param[in] random If true the random seed is set to current time, else it is + * set to 12345 prior to computing the descriptor (used to select X axis) + */ + ShapeContext3DEstimation (bool random = false) : + radii_interval_(0), + theta_divisions_(0), + phi_divisions_(0), + volume_lut_(0), + azimuth_bins_(12), + elevation_bins_(11), + radius_bins_(15), + min_radius_(0.1), + point_density_radius_(0.2), + descriptor_length_ (), + rng_alg_ (), + rng_ (new boost::uniform_01 (rng_alg_)) + { + feature_name_ = "ShapeContext3DEstimation"; + search_radius_ = 2.5; + + // Create a random number generator object + if (random) + rng_->base ().seed (static_cast (std::time(0))); + else + rng_->base ().seed (12345u); + } + + virtual ~ShapeContext3DEstimation() {} + + //inline void + //setAzimuthBins (size_t bins) { azimuth_bins_ = bins; } + + /** \return the number of bins along the azimuth */ + inline size_t + getAzimuthBins () { return (azimuth_bins_); } + + //inline void + //setElevationBins (size_t bins) { elevation_bins_ = bins; } + + /** \return The number of bins along the elevation */ + inline size_t + getElevationBins () { return (elevation_bins_); } + + //inline void + //setRadiusBins (size_t bins) { radius_bins_ = bins; } + + /** \return The number of bins along the radii direction */ + inline size_t + getRadiusBins () { return (radius_bins_); } + + /** \brief The minimal radius value for the search sphere (rmin) in the original paper + * \param[in] radius the desired minimal radius + */ + inline void + setMinimalRadius (double radius) { min_radius_ = radius; } + + /** \return The minimal sphere radius */ + inline double + getMinimalRadius () { return (min_radius_); } + + /** \brief This radius is used to compute local point density + * density = number of points within this radius + * \param[in] radius value of the point density search radius + */ + inline void + setPointDensityRadius (double radius) { point_density_radius_ = radius; } + + /** \return The point density search radius */ + inline double + getPointDensityRadius () { return (point_density_radius_); } + + protected: + /** \brief Initialize computation by allocating all the intervals and the volume lookup table. */ + bool + initCompute (); + + /** \brief Estimate a descriptor for a given point. + * \param[in] index the index of the point to estimate a descriptor for + * \param[in] normals a pointer to the set of normals + * \param[in] rf the reference frame + * \param[out] desc the resultant estimated descriptor + * \return true if the descriptor was computed successfully, false if there was an error + * (e.g. the nearest neighbor didn't return any neighbors) + */ + bool + computePoint (size_t index, const pcl::PointCloud &normals, float rf[9], std::vector &desc); + + /** \brief Estimate the actual feature. + * \param[out] output the resultant feature + */ + void + computeFeature (PointCloudOut &output); + + /** \brief Values of the radii interval */ + std::vector radii_interval_; + + /** \brief Theta divisions interval */ + std::vector theta_divisions_; + + /** \brief Phi divisions interval */ + std::vector phi_divisions_; + + /** \brief Volumes look up table */ + std::vector volume_lut_; + + /** \brief Bins along the azimuth dimension */ + size_t azimuth_bins_; + + /** \brief Bins along the elevation dimension */ + size_t elevation_bins_; + + /** \brief Bins along the radius dimension */ + size_t radius_bins_; + + /** \brief Minimal radius value */ + double min_radius_; + + /** \brief Point density radius */ + double point_density_radius_; + + /** \brief Descriptor length */ + size_t descriptor_length_; + + /** \brief Boost-based random number generator algorithm. */ + boost::mt19937 rng_alg_; + + /** \brief Boost-based random number generator distribution. */ + boost::shared_ptr > rng_; + + /* \brief Shift computed descriptor "L" times along the azimuthal direction + * \param[in] block_size the size of each azimuthal block + * \param[in] desc at input desc == original descriptor and on output it contains + * shifted descriptor resized descriptor_length_ * azimuth_bins_ + */ + //void + //shiftAlongAzimuth (size_t block_size, std::vector& desc); + + /** \brief Boost-based random number generator. */ + inline double + rnd () + { + return ((*rng_) ()); + } + + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_3DSC_H_ diff --git a/pcl-1.7/pcl/features/board.h b/pcl-1.7/pcl/features/board.h new file mode 100644 index 0000000..a9e1b49 --- /dev/null +++ b/pcl-1.7/pcl/features/board.h @@ -0,0 +1,369 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_BOARD_H_ +#define PCL_BOARD_H_ + +#include +#include + +namespace pcl +{ + /** \brief BOARDLocalReferenceFrameEstimation implements the BOrder Aware Repeatable Directions algorithm + * for local reference frame estimation as described here: + * + * - A. Petrelli, L. Di Stefano, + * "On the repeatability of the local reference frame for partial shape matching", + * 13th International Conference on Computer Vision (ICCV), 2011 + * + * \author Alioscia Petrelli (original), Tommaso Cavallari (PCL port) + * \ingroup features + */ + template + class BOARDLocalReferenceFrameEstimation : public FeatureFromNormals + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + BOARDLocalReferenceFrameEstimation () : + tangent_radius_ (0.0f), + find_holes_ (false), + margin_thresh_ (0.85f), + check_margin_array_size_ (24), + hole_size_prob_thresh_ (0.2f), + steep_thresh_ (0.1f), + check_margin_array_ (), + margin_array_min_angle_ (), + margin_array_max_angle_ (), + margin_array_min_angle_normal_ (), + margin_array_max_angle_normal_ () + { + feature_name_ = "BOARDLocalReferenceFrameEstimation"; + setCheckMarginArraySize (check_margin_array_size_); + } + + /** \brief Empty destructor */ + virtual ~BOARDLocalReferenceFrameEstimation () {} + + //Getters/Setters + + /** \brief Set the maximum distance of the points used to estimate the x_axis and y_axis of the BOARD Reference Frame for a given point. + * + * \param[in] radius The search radius for x and y axes. If not set or set to 0 the parameter given with setRadiusSearch is used. + */ + inline void + setTangentRadius (float radius) + { + tangent_radius_ = radius; + } + + /** \brief Get the maximum distance of the points used to estimate the x_axis and y_axis of the BOARD Reference Frame for a given point. + * + * \return The search radius for x and y axes. If set to 0 the parameter given with setRadiusSearch is used. + */ + inline float + getTangentRadius () const + { + return (tangent_radius_); + } + + /** \brief Sets whether holes in the margin of the support, for each point, are searched and accounted for in the estimation of the + * Reference Frame or not. + * + * \param[in] find_holes Enable/Disable the search for holes in the support. + */ + inline void + setFindHoles (bool find_holes) + { + find_holes_ = find_holes; + } + + /** \brief Gets whether holes in the margin of the support, for each point, are searched and accounted for in the estimation of the + * Reference Frame or not. + * + * \return The search for holes in the support is enabled/disabled. + */ + inline bool + getFindHoles () const + { + return (find_holes_); + } + + /** \brief Sets the percentage of the search radius (or tangent radius if set) after which a point is considered part of the support margin. + * + * \param[in] margin_thresh the percentage of the search radius after which a point is considered a margin point. + */ + inline void + setMarginThresh (float margin_thresh) + { + margin_thresh_ = margin_thresh; + } + + /** \brief Gets the percentage of the search radius (or tangent radius if set) after which a point is considered part of the support margin. + * + * \return The percentage of the search radius after which a point is considered a margin point. + */ + inline float + getMarginThresh () const + { + return (margin_thresh_); + } + + /** \brief Sets the number of slices in which is divided the margin for the search of missing regions. + * + * \param[in] size the number of margin slices. + */ + void + setCheckMarginArraySize (int size) + { + check_margin_array_size_ = size; + + check_margin_array_.clear (); + check_margin_array_.resize (check_margin_array_size_); + + margin_array_min_angle_.clear (); + margin_array_min_angle_.resize (check_margin_array_size_); + + margin_array_max_angle_.clear (); + margin_array_max_angle_.resize (check_margin_array_size_); + + margin_array_min_angle_normal_.clear (); + margin_array_min_angle_normal_.resize (check_margin_array_size_); + + margin_array_max_angle_normal_.clear (); + margin_array_max_angle_normal_.resize (check_margin_array_size_); + } + + /** \brief Gets the number of slices in which is divided the margin for the search of missing regions. + * + * \return the number of margin slices. + */ + inline int + getCheckMarginArraySize () const + { + return (check_margin_array_size_); + } + + /** \brief Given the angle width of a hole in the support margin, sets the minimum percentage of a circumference this angle + * must cover to be considered a missing region in the support and hence used for the estimation of the Reference Frame. + * + * \param[in] prob_thresh the minimum percentage of a circumference after which a hole is considered in the calculation + */ + inline void + setHoleSizeProbThresh (float prob_thresh) + { + hole_size_prob_thresh_ = prob_thresh; + } + + /** \brief Given the angle width of a hole in the support margin, gets the minimum percentage of a circumference this angle + * must cover to be considered a missing region in the support and hence used for the estimation of the Reference Frame. + * + * \return the minimum percentage of a circumference after which a hole is considered in the calculation + */ + inline float + getHoleSizeProbThresh () const + { + return (hole_size_prob_thresh_); + } + + /** \brief Sets the minimum steepness that the normals of the points situated on the borders of the hole, with reference + * to the normal of the best point found by the algorithm, must have in order to be considered in the calculation of the Reference Frame. + * + * \param[in] steep_thresh threshold that defines if a missing region contains a point with the most different normal. + */ + inline void + setSteepThresh (float steep_thresh) + { + steep_thresh_ = steep_thresh; + } + + /** \brief Gets the minimum steepness that the normals of the points situated on the borders of the hole, with reference + * to the normal of the best point found by the algorithm, must have in order to be considered in the calculation of the Reference Frame. + * + * \return threshold that defines if a missing region contains a point with the most different normal. + */ + inline float + getSteepThresh () const + { + return (steep_thresh_); + } + + protected: + using Feature::feature_name_; + using Feature::getClassName; + using Feature::input_; + using Feature::indices_; + using Feature::surface_; + using Feature::tree_; + using Feature::search_parameter_; + using FeatureFromNormals::normals_; + + typedef typename Feature::PointCloudIn PointCloudIn; + typedef typename Feature::PointCloudOut PointCloudOut; + + void + resetData () + { + setCheckMarginArraySize (check_margin_array_size_); + } + + /** \brief Estimate the LRF descriptor for a given point based on its spatial neighborhood of 3D points with normals + * \param[in] index the index of the point in input_ + * \param[out] lrf the resultant local reference frame + */ + float + computePointLRF (const int &index, Eigen::Matrix3f &lrf); + + /** \brief Abstract feature estimation method. + * \param[out] output the resultant features + */ + virtual void + computeFeature (PointCloudOut &output); + + /** \brief Given an axis (with origin axis_origin), return the orthogonal axis directed to point. + * + * \note axis must be normalized. + * + * \param[in] axis the axis + * \param[in] axis_origin the axis_origin + * \param[in] point the point towards which the resulting axis is directed + * \param[out] directed_ortho_axis the directed orthogonal axis calculated + */ + void + directedOrthogonalAxis (Eigen::Vector3f const &axis, Eigen::Vector3f const &axis_origin, + Eigen::Vector3f const &point, Eigen::Vector3f &directed_ortho_axis); + + /** \brief return the angle (in radians) that rotate v1 to v2 with respect to axis . + * + * \param[in] v1 the first vector + * \param[in] v2 the second vector + * \param[in] axis the rotation axis. Axis must be normalized and orthogonal to plane defined by v1 and v2. + * \return angle + */ + float + getAngleBetweenUnitVectors (Eigen::Vector3f const &v1, Eigen::Vector3f const &v2, Eigen::Vector3f const &axis); + + /** \brief Disambiguates a normal direction using adjacent normals + * + * \param[in] normals_cloud a cloud of normals used for the calculation + * \param[in] normal_indices the indices of the normals in the cloud that should to be used for the calculation + * \param[in,out] normal the normal to disambiguate, the calculation is performed in place + */ + void + normalDisambiguation (pcl::PointCloud const &normals_cloud, std::vector const &normal_indices, + Eigen::Vector3f &normal); + + /** \brief Compute Least Square Plane Fitting in a set of 3D points + * + * \param[in] points Matrix(nPoints,3) of 3D points coordinates + * \param[out] center centroid of the distribution of points that belongs to the fitted plane + * \param[out] norm normal to the fitted plane + */ + void + planeFitting (Eigen::Matrix const &points, Eigen::Vector3f ¢er, + Eigen::Vector3f &norm); + + /** \brief Given a plane (origin and normal) and a point, return the projection of x on plane + * + * Equivalent to vtkPlane::ProjectPoint() + * + * \param[in] point the point to project + * \param[in] origin_point a point belonging to the plane + * \param[in] plane_normal normal of the plane + * \param[out] projected_point the projection of the point on the plane + */ + void + projectPointOnPlane (Eigen::Vector3f const &point, Eigen::Vector3f const &origin_point, + Eigen::Vector3f const &plane_normal, Eigen::Vector3f &projected_point); + + /** \brief Given an axis, return a random orthogonal axis + * + * \param[in] axis input axis + * \param[out] rand_ortho_axis an axis orthogonal to the input axis and whose direction is random + */ + void + randomOrthogonalAxis (Eigen::Vector3f const &axis, Eigen::Vector3f &rand_ortho_axis); + + /** \brief Check if val1 and val2 are equals. + * + * \param[in] val1 first number to check. + * \param[in] val2 second number to check. + * \param[in] zero_float_eps epsilon + * \return true if val1 is equal to val2, false otherwise. + */ + inline bool + areEquals (float val1, float val2, float zero_float_eps = 1E-8f) const + { + return (std::abs (val1 - val2) < zero_float_eps); + } + + private: + /** \brief Radius used to find tangent axis. */ + float tangent_radius_; + + /** \brief If true, check if support is complete or has missing regions because it is too near to mesh borders. */ + bool find_holes_; + + /** \brief Threshold that define if a support point is near the margins. */ + float margin_thresh_; + + /** \brief Number of slices that divide the support in order to determine if a missing region is present. */ + int check_margin_array_size_; + + /** \brief Threshold used to determine a missing region */ + float hole_size_prob_thresh_; + + /** \brief Threshold that defines if a missing region contains a point with the most different normal. */ + float steep_thresh_; + + std::vector check_margin_array_; + std::vector margin_array_min_angle_; + std::vector margin_array_max_angle_; + std::vector margin_array_min_angle_normal_; + std::vector margin_array_max_angle_normal_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_BOARD_H_ diff --git a/pcl-1.7/pcl/features/boost.h b/pcl-1.7/pcl/features/boost.h new file mode 100644 index 0000000..1ff4720 --- /dev/null +++ b/pcl-1.7/pcl/features/boost.h @@ -0,0 +1,55 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $ + * + */ + +#ifndef PCL_FEATURES_BOOST_H_ +#define PCL_FEATURES_BOOST_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include +#include +#include +#include +//#include +//#include + +#endif // PCL_FEATURES_BOOST_H_ diff --git a/pcl-1.7/pcl/features/boundary.h b/pcl-1.7/pcl/features/boundary.h new file mode 100644 index 0000000..10fb3fe --- /dev/null +++ b/pcl-1.7/pcl/features/boundary.h @@ -0,0 +1,187 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_BOUNDARY_H_ +#define PCL_BOUNDARY_H_ + +#include +#include + +namespace pcl +{ + /** \brief BoundaryEstimation estimates whether a set of points is lying on surface boundaries using an angle + * criterion. The code makes use of the estimated surface normals at each point in the input dataset. + * + * Here's an example for estimating boundary points for a PointXYZ point cloud: + * \code + * pcl::PointCloud::Ptr cloud (new pcl::PointCloud); + * // fill in the cloud data here + * + * pcl::PointCloud::Ptr normals (new pcl::PointCloud); + * // estimate normals and fill in \a normals + * + * pcl::PointCloud boundaries; + * pcl::BoundaryEstimation est; + * est.setInputCloud (cloud); + * est.setInputNormals (normals); + * est.setRadiusSearch (0.02); // 2cm radius + * est.setSearchMethod (typename pcl::search::KdTree::Ptr (new pcl::search::KdTree) + * est.compute (boundaries); + * \endcode + * + * \attention + * The convention for Boundary features is: + * - if a query point's nearest neighbors cannot be estimated, the boundary feature will be set to NaN + * (not a number) + * - it is impossible to estimate a boundary property for a point that + * doesn't have finite 3D coordinates. Therefore, any point that contains + * NaN data on x, y, or z, will have its boundary feature property set to NaN. + * + * \author Radu B. Rusu + * \ingroup features + */ + template + class BoundaryEstimation: public FeatureFromNormals + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using Feature::feature_name_; + using Feature::getClassName; + using Feature::input_; + using Feature::indices_; + using Feature::k_; + using Feature::tree_; + using Feature::search_radius_; + using Feature::search_parameter_; + using Feature::surface_; + using FeatureFromNormals::normals_; + + typedef typename Feature::PointCloudOut PointCloudOut; + + public: + /** \brief Empty constructor. + * The angular threshold \a angle_threshold_ is set to M_PI / 2.0 + */ + BoundaryEstimation () : angle_threshold_ (static_cast (M_PI) / 2.0f) + { + feature_name_ = "BoundaryEstimation"; + }; + + /** \brief Check whether a point is a boundary point in a planar patch of projected points given by indices. + * \note A coordinate system u-v-n must be computed a-priori using \a getCoordinateSystemOnPlane + * \param[in] cloud a pointer to the input point cloud + * \param[in] q_idx the index of the query point in \a cloud + * \param[in] indices the estimated point neighbors of the query point + * \param[in] u the u direction + * \param[in] v the v direction + * \param[in] angle_threshold the threshold angle (default \f$\pi / 2.0\f$) + */ + bool + isBoundaryPoint (const pcl::PointCloud &cloud, + int q_idx, const std::vector &indices, + const Eigen::Vector4f &u, const Eigen::Vector4f &v, const float angle_threshold); + + /** \brief Check whether a point is a boundary point in a planar patch of projected points given by indices. + * \note A coordinate system u-v-n must be computed a-priori using \a getCoordinateSystemOnPlane + * \param[in] cloud a pointer to the input point cloud + * \param[in] q_point a pointer to the querry point + * \param[in] indices the estimated point neighbors of the query point + * \param[in] u the u direction + * \param[in] v the v direction + * \param[in] angle_threshold the threshold angle (default \f$\pi / 2.0\f$) + */ + bool + isBoundaryPoint (const pcl::PointCloud &cloud, + const PointInT &q_point, + const std::vector &indices, + const Eigen::Vector4f &u, const Eigen::Vector4f &v, const float angle_threshold); + + /** \brief Set the decision boundary (angle threshold) that marks points as boundary or regular. + * (default \f$\pi / 2.0\f$) + * \param[in] angle the angle threshold + */ + inline void + setAngleThreshold (float angle) + { + angle_threshold_ = angle; + } + + /** \brief Get the decision boundary (angle threshold) as set by the user. */ + inline float + getAngleThreshold () + { + return (angle_threshold_); + } + + /** \brief Get a u-v-n coordinate system that lies on a plane defined by its normal + * \param[in] p_coeff the plane coefficients (containing the plane normal) + * \param[out] u the resultant u direction + * \param[out] v the resultant v direction + */ + inline void + getCoordinateSystemOnPlane (const PointNT &p_coeff, + Eigen::Vector4f &u, Eigen::Vector4f &v) + { + pcl::Vector4fMapConst p_coeff_v = p_coeff.getNormalVector4fMap (); + v = p_coeff_v.unitOrthogonal (); + u = p_coeff_v.cross3 (v); + } + + protected: + /** \brief Estimate whether a set of points is lying on surface boundaries using an angle criterion for all points + * given in using the surface in setSearchSurface () and the spatial locator in + * setSearchMethod () + * \param[out] output the resultant point cloud model dataset that contains boundary point estimates + */ + void + computeFeature (PointCloudOut &output); + + /** \brief The decision boundary (angle threshold) that marks points as boundary or regular. (default \f$\pi / 2.0\f$) */ + float angle_threshold_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_BOUNDARY_H_ diff --git a/pcl-1.7/pcl/features/cppf.h b/pcl-1.7/pcl/features/cppf.h new file mode 100644 index 0000000..4f44aaf --- /dev/null +++ b/pcl-1.7/pcl/features/cppf.h @@ -0,0 +1,120 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2013, Martin Szarski + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_CPPF_H_ +#define PCL_CPPF_H_ + +#include +#include + +namespace pcl +{ + /** \brief + * \param[in] p1 + * \param[in] n1 + * \param[in] p2 + * \param[in] n2 + * \param[in] c1 + * \param[in] c2 + * \param[out] f1 + * \param[out] f2 + * \param[out] f3 + * \param[out] f4 + * \param[out] f5 + * \param[out] f6 + * \param[out] f7 + * \param[out] f8 + * \param[out] f9 + * \param[out] f10 + */ + PCL_EXPORTS bool + computeCPPFPairFeature (const Eigen::Vector4f &p1, const Eigen::Vector4f &n1, const Eigen::Vector4i &c1, + const Eigen::Vector4f &p2, const Eigen::Vector4f &n2, const Eigen::Vector4i &c2, + float &f1, float &f2, float &f3, float &f4, float &f5, float &f6, float &f7, float &f8, float &f9, float &f10); + + + + /** \brief Class that calculates the "surflet" features for each pair in the given + * pointcloud. Please refer to the following publication for more details: + * C. Choi, Henrik Christensen + * 3D Pose Estimation of Daily Objects Using an RGB-D Camera + * Proceedings of IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS) + * 2012 + * + * PointOutT is meant to be pcl::CPPFSignature - contains the 10 values of the Surflet + * feature and in addition, alpha_m for the respective pair - optimization proposed by + * the authors (see above) + * + * \author Martin Szarski, Alexandru-Eugen Ichim + */ + + template + class CPPFEstimation : public FeatureFromNormals + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using PCLBase::indices_; + using Feature::input_; + using Feature::feature_name_; + using Feature::getClassName; + using FeatureFromNormals::normals_; + + typedef pcl::PointCloud PointCloudOut; + + /** \brief Empty Constructor. */ + CPPFEstimation (); + + + private: + /** \brief The method called for actually doing the computations + * \param[out] output the resulting point cloud (which should be of type pcl::CPPFSignature); + * its size is the size of the input cloud, squared (i.e., one point for each pair in + * the input cloud); + */ + void + computeFeature (PointCloudOut &output); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_CPPF_H_ diff --git a/pcl-1.7/pcl/features/crh.h b/pcl-1.7/pcl/features/crh.h new file mode 100644 index 0000000..8feebe0 --- /dev/null +++ b/pcl-1.7/pcl/features/crh.h @@ -0,0 +1,145 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: cvfh.h 4936 2012-03-07 11:12:45Z aaldoma $ + * + */ + +#ifndef PCL_FEATURES_CRH_H_ +#define PCL_FEATURES_CRH_H_ + +#include + +namespace pcl +{ + /** \brief CRHEstimation estimates the Camera Roll Histogram (CRH) descriptor for a given + * point cloud dataset containing XYZ data and normals, as presented in: + * - CAD-Model Recognition and 6 DOF Pose Estimation + * A. Aldoma, N. Blodow, D. Gossow, S. Gedikli, R.B. Rusu, M. Vincze and G. Bradski + * ICCV 2011, 3D Representation and Recognition (3dRR11) workshop + * Barcelona, Spain, (2011) + * + * The suggested PointOutT is pcl::Histogram<90>. //dc (real) + 44 complex numbers (real, imaginary) + nyquist (real) + * + * \author Aitor Aldoma + * \ingroup features + */ + template > + class CRHEstimation : public FeatureFromNormals + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::k_; + using Feature::search_radius_; + using Feature::surface_; + using FeatureFromNormals::normals_; + + typedef typename Feature::PointCloudOut PointCloudOut; + + /** \brief Constructor. */ + CRHEstimation () : + vpx_ (0), vpy_ (0), vpz_ (0), nbins_ (90) + { + k_ = 1; + feature_name_ = "CRHEstimation"; + } + ; + + /** \brief Set the viewpoint. + * \param[in] vpx the X coordinate of the viewpoint + * \param[in] vpy the Y coordinate of the viewpoint + * \param[in] vpz the Z coordinate of the viewpoint + */ + inline void + setViewPoint (float vpx, float vpy, float vpz) + { + vpx_ = vpx; + vpy_ = vpy; + vpz_ = vpz; + } + + /** \brief Get the viewpoint. + * \param[out] vpx the X coordinate of the viewpoint + * \param[out] vpy the Y coordinate of the viewpoint + * \param[out] vpz the Z coordinate of the viewpoint + */ + inline void + getViewPoint (float &vpx, float &vpy, float &vpz) + { + vpx = vpx_; + vpy = vpy_; + vpz = vpz_; + } + + inline void + setCentroid (Eigen::Vector4f & centroid) + { + centroid_ = centroid; + } + + private: + /** \brief Values describing the viewpoint ("pinhole" camera model assumed). + * By default, the viewpoint is set to 0,0,0. + */ + float vpx_, vpy_, vpz_; + + /** \brief Number of bins, this should match the Output type */ + int nbins_; + + /** \brief Centroid to be used */ + Eigen::Vector4f centroid_; + + /** \brief Estimate the CRH histogram at + * a set of points given by using the surface in + * setSearchSurface () + * + * \param[out] output the resultant point cloud with a CRH histogram + */ + void + computeFeature (PointCloudOut &output); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FEATURES_CRH_H_ diff --git a/pcl-1.7/pcl/features/cvfh.h b/pcl-1.7/pcl/features/cvfh.h new file mode 100644 index 0000000..95334de --- /dev/null +++ b/pcl-1.7/pcl/features/cvfh.h @@ -0,0 +1,293 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_CVFH_H_ +#define PCL_FEATURES_CVFH_H_ + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief CVFHEstimation estimates the Clustered Viewpoint Feature Histogram (CVFH) descriptor for a given + * point cloud dataset containing XYZ data and normals, as presented in: + * - CAD-Model Recognition and 6 DOF Pose Estimation + * A. Aldoma, N. Blodow, D. Gossow, S. Gedikli, R.B. Rusu, M. Vincze and G. Bradski + * ICCV 2011, 3D Representation and Recognition (3dRR11) workshop + * Barcelona, Spain, (2011) + * + * The suggested PointOutT is pcl::VFHSignature308. + * + * \author Aitor Aldoma + * \ingroup features + */ + template + class CVFHEstimation : public FeatureFromNormals + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::k_; + using Feature::search_radius_; + using Feature::surface_; + using FeatureFromNormals::normals_; + + typedef typename Feature::PointCloudOut PointCloudOut; + typedef typename pcl::search::Search::Ptr KdTreePtr; + typedef typename pcl::VFHEstimation VFHEstimator; + + /** \brief Empty constructor. */ + CVFHEstimation () : + vpx_ (0), vpy_ (0), vpz_ (0), + leaf_size_ (0.005f), + normalize_bins_ (false), + curv_threshold_ (0.03f), + cluster_tolerance_ (leaf_size_ * 3), + eps_angle_threshold_ (0.125f), + min_points_ (50), + radius_normals_ (leaf_size_ * 3), + centroids_dominant_orientations_ (), + dominant_normals_ () + { + search_radius_ = 0; + k_ = 1; + feature_name_ = "CVFHEstimation"; + } + ; + + /** \brief Removes normals with high curvature caused by real edges or noisy data + * \param[in] cloud pointcloud to be filtered + * \param[in] indices_to_use the indices to use + * \param[out] indices_out the indices of the points with higher curvature than threshold + * \param[out] indices_in the indices of the remaining points after filtering + * \param[in] threshold threshold value for curvature + */ + void + filterNormalsWithHighCurvature (const pcl::PointCloud & cloud, std::vector & indices_to_use, std::vector &indices_out, + std::vector &indices_in, float threshold); + + /** \brief Set the viewpoint. + * \param[in] vpx the X coordinate of the viewpoint + * \param[in] vpy the Y coordinate of the viewpoint + * \param[in] vpz the Z coordinate of the viewpoint + */ + inline void + setViewPoint (float vpx, float vpy, float vpz) + { + vpx_ = vpx; + vpy_ = vpy; + vpz_ = vpz; + } + + /** \brief Set the radius used to compute normals + * \param[in] radius_normals the radius + */ + inline void + setRadiusNormals (float radius_normals) + { + radius_normals_ = radius_normals; + } + + /** \brief Get the viewpoint. + * \param[out] vpx the X coordinate of the viewpoint + * \param[out] vpy the Y coordinate of the viewpoint + * \param[out] vpz the Z coordinate of the viewpoint + */ + inline void + getViewPoint (float &vpx, float &vpy, float &vpz) + { + vpx = vpx_; + vpy = vpy_; + vpz = vpz_; + } + + /** \brief Get the centroids used to compute different CVFH descriptors + * \param[out] centroids vector to hold the centroids + */ + inline void + getCentroidClusters (std::vector & centroids) + { + for (size_t i = 0; i < centroids_dominant_orientations_.size (); ++i) + centroids.push_back (centroids_dominant_orientations_[i]); + } + + /** \brief Get the normal centroids used to compute different CVFH descriptors + * \param[out] centroids vector to hold the normal centroids + */ + inline void + getCentroidNormalClusters (std::vector & centroids) + { + for (size_t i = 0; i < dominant_normals_.size (); ++i) + centroids.push_back (dominant_normals_[i]); + } + + /** \brief Sets max. Euclidean distance between points to be added to the cluster + * \param[in] d the maximum Euclidean distance + */ + + inline void + setClusterTolerance (float d) + { + cluster_tolerance_ = d; + } + + /** \brief Sets max. deviation of the normals between two points so they can be clustered together + * \param[in] d the maximum deviation + */ + inline void + setEPSAngleThreshold (float d) + { + eps_angle_threshold_ = d; + } + + /** \brief Sets curvature threshold for removing normals + * \param[in] d the curvature threshold + */ + inline void + setCurvatureThreshold (float d) + { + curv_threshold_ = d; + } + + /** \brief Set minimum amount of points for a cluster to be considered + * \param[in] min the minimum amount of points to be set + */ + inline void + setMinPoints (size_t min) + { + min_points_ = min; + } + + /** \brief Sets wether if the CVFH signatures should be normalized or not + * \param[in] normalize true if normalization is required, false otherwise + */ + inline void + setNormalizeBins (bool normalize) + { + normalize_bins_ = normalize; + } + + /** \brief Overloaded computed method from pcl::Feature. + * \param[out] output the resultant point cloud model dataset containing the estimated features + */ + void + compute (PointCloudOut &output); + + private: + /** \brief Values describing the viewpoint ("pinhole" camera model assumed). + * By default, the viewpoint is set to 0,0,0. + */ + float vpx_, vpy_, vpz_; + + /** \brief Size of the voxels after voxel gridding. IMPORTANT: Must match the voxel + * size of the training data or the normalize_bins_ flag must be set to true. + */ + float leaf_size_; + + /** \brief Wether to normalize the signatures or not. Default: false. */ + bool normalize_bins_; + + /** \brief Curvature threshold for removing normals. */ + float curv_threshold_; + + /** \brief allowed Euclidean distance between points to be added to the cluster. */ + float cluster_tolerance_; + + /** \brief deviation of the normals between two points so they can be clustered together. */ + float eps_angle_threshold_; + + /** \brief Minimum amount of points in a clustered region to be considered stable for CVFH + * computation. + */ + size_t min_points_; + + /** \brief Radius for the normals computation. */ + float radius_normals_; + + /** \brief Estimate the Clustered Viewpoint Feature Histograms (CVFH) descriptors at + * a set of points given by using the surface in + * setSearchSurface () + * + * \param[out] output the resultant point cloud model dataset that contains the CVFH + * feature estimates + */ + void + computeFeature (PointCloudOut &output); + + /** \brief Region growing method using Euclidean distances and neighbors normals to + * add points to a region. + * \param[in] cloud point cloud to split into regions + * \param[in] normals are the normals of cloud + * \param[in] tolerance is the allowed Euclidean distance between points to be added to + * the cluster + * \param[in] tree is the spatial search structure for nearest neighbour search + * \param[out] clusters vector of indices representing the clustered regions + * \param[in] eps_angle deviation of the normals between two points so they can be + * clustered together + * \param[in] min_pts_per_cluster minimum cluster size. (default: 1 point) + * \param[in] max_pts_per_cluster maximum cluster size. (default: all the points) + */ + void + extractEuclideanClustersSmooth (const pcl::PointCloud &cloud, + const pcl::PointCloud &normals, float tolerance, + const pcl::search::Search::Ptr &tree, + std::vector &clusters, double eps_angle, + unsigned int min_pts_per_cluster = 1, + unsigned int max_pts_per_cluster = (std::numeric_limits::max) ()); + + protected: + /** \brief Centroids that were used to compute different CVFH descriptors */ + std::vector centroids_dominant_orientations_; + /** \brief Normal centroids that were used to compute different CVFH descriptors */ + std::vector dominant_normals_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FEATURES_CVFH_H_ diff --git a/pcl-1.7/pcl/features/don.h b/pcl-1.7/pcl/features/don.h new file mode 100644 index 0000000..4ebdd7b --- /dev/null +++ b/pcl-1.7/pcl/features/don.h @@ -0,0 +1,145 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Yani Ioannou + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_FILTERS_DON_H_ +#define PCL_FILTERS_DON_H_ + +#include + +namespace pcl +{ + /** \brief A Difference of Normals (DoN) scale filter implementation for point cloud data. + * + * For each point in the point cloud two normals estimated with a differing search radius (sigma_s, sigma_l) + * are subtracted, the difference of these normals provides a scale-based feature which + * can be further used to filter the point cloud, somewhat like the Difference of Guassians + * in image processing, but instead on surfaces. Best results are had when the two search + * radii are related as sigma_l=10*sigma_s, the octaves between the two search radii + * can be though of as a filter bandwidth. For appropriate values and thresholds it + * can be used for surface edge extraction. + * + * \attention The input normals given by setInputNormalsSmall and setInputNormalsLarge have + * to match the input point cloud given by setInputCloud. This behavior is different than + * feature estimation methods that extend FeatureFromNormals, which match the normals + * with the search surface. + * + * \note For more information please see + * Yani Ioannou. Automatic Urban Modelling using Mobile Urban LIDAR Data. + * Thesis (Master, Computing), Queen's University, March, 2010. + * + * \author Yani Ioannou. + * \ingroup features + */ + template + class DifferenceOfNormalsEstimation : public Feature + { + using Feature::getClassName; + using Feature::feature_name_; + using PCLBase::input_; + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + typedef typename Feature::PointCloudOut PointCloudOut; + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** + * Creates a new Difference of Normals filter. + */ + DifferenceOfNormalsEstimation () + { + feature_name_ = "DifferenceOfNormalsEstimation"; + } + + virtual ~DifferenceOfNormalsEstimation () + { + // + } + + /** + * Set the normals calculated using a smaller search radius (scale) for the DoN operator. + * @param normals the smaller radius (scale) of the DoN filter. + */ + inline void + setNormalScaleSmall (const PointCloudNConstPtr &normals) + { + input_normals_small_ = normals; + } + + /** + * Set the normals calculated using a larger search radius (scale) for the DoN operator. + * @param normals the larger radius (scale) of the DoN filter. + */ + inline void + setNormalScaleLarge (const PointCloudNConstPtr &normals) + { + input_normals_large_ = normals; + } + + /** + * Computes the DoN vector for each point in the input point cloud and outputs the vector cloud to the given output. + * @param output the cloud to output the DoN vector cloud to. + */ + virtual void + computeFeature (PointCloudOut &output); + + /** + * Initialize for computation of features. + * @return true if parameters (input normals, input) are sufficient to perform computation. + */ + virtual bool + initCompute (); + private: + /** \brief Make the compute (&PointCloudOut); inaccessible from outside the class + * \param[out] output the output point cloud + */ + void + compute (PointCloudOut &) {} + + ///The smallest radius (scale) used in the DoN filter. + PointCloudNConstPtr input_normals_small_; + ///The largest radius (scale) used in the DoN filter. + PointCloudNConstPtr input_normals_large_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_FILTERS_DON_H_ diff --git a/pcl-1.7/pcl/features/eigen.h b/pcl-1.7/pcl/features/eigen.h new file mode 100644 index 0000000..49f3b0f --- /dev/null +++ b/pcl-1.7/pcl/features/eigen.h @@ -0,0 +1,51 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $ + * + */ + +#ifndef PCL_FEATURES_EIGEN_H_ +#define PCL_FEATURES_EIGEN_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include +#include + +#endif // PCL_FEATURES_EIGEN_H_ diff --git a/pcl-1.7/pcl/features/esf.h b/pcl-1.7/pcl/features/esf.h new file mode 100644 index 0000000..8a840fa --- /dev/null +++ b/pcl-1.7/pcl/features/esf.h @@ -0,0 +1,143 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: pfh.hpp 5027 2012-03-12 03:10:45Z rusu $ + * + */ +#ifndef PCL_ESF_H_ +#define PCL_ESF_H_ + +#include +#define GRIDSIZE 64 +#define GRIDSIZE_H GRIDSIZE/2 +#include + +namespace pcl +{ + /** \brief @b ESFEstimation estimates the ensemble of shape functions descriptors for a given point cloud + * dataset containing points. Shape functions are D2, D3, A3. For more information about the ESF descriptor, see: + * Walter Wohlkinger and Markus Vincze, "Ensemble of Shape Functions for 3D Object Classification", + * IEEE International Conference on Robotics and Biomimetics (IEEE-ROBIO), 2011 + * \author Walter Wohlkinger + * \ingroup features + */ + + template + class ESFEstimation: public Feature + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::k_; + using Feature::search_radius_; + using Feature::input_; + using Feature::surface_; + + typedef typename pcl::PointCloud PointCloudIn; + typedef typename Feature::PointCloudOut PointCloudOut; + + /** \brief Empty constructor. */ + ESFEstimation () : lut_ (), local_cloud_ () + { + feature_name_ = "ESFEstimation"; + lut_.resize (GRIDSIZE); + for (int i = 0; i < GRIDSIZE; ++i) + { + lut_[i].resize (GRIDSIZE); + for (int j = 0; j < GRIDSIZE; ++j) + lut_[i][j].resize (GRIDSIZE); + } + //lut_.resize (boost::extents[GRIDSIZE][GRIDSIZE][GRIDSIZE]); + search_radius_ = 0; + k_ = 5; + } + + /** \brief Overloaded computed method from pcl::Feature. + * \param[out] output the resultant point cloud model dataset containing the estimated features + */ + void + compute (PointCloudOut &output); + + protected: + + /** \brief Estimate the Ensebmel of Shape Function (ESF) descriptors at a set of points given by + * &hist); + + /** \brief ... */ + void + voxelize9 (PointCloudIn &cluster); + + /** \brief ... */ + void + cleanup9 (PointCloudIn &cluster); + + /** \brief ... */ + void + scale_points_unit_sphere (const pcl::PointCloud &pc, float scalefactor, Eigen::Vector4f& centroid); + + private: + + /** \brief ... */ + std::vector > > lut_; + + /** \brief ... */ + PointCloudIn local_cloud_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // # diff --git a/pcl-1.7/pcl/features/feature.h b/pcl-1.7/pcl/features/feature.h new file mode 100644 index 0000000..3bf2f60 --- /dev/null +++ b/pcl-1.7/pcl/features/feature.h @@ -0,0 +1,557 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURE_H_ +#define PCL_FEATURE_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +namespace pcl +{ + /** \brief Solve the eigenvalues and eigenvectors of a given 3x3 covariance matrix, and estimate the least-squares + * plane normal and surface curvature. + * \param covariance_matrix the 3x3 covariance matrix + * \param point a point lying on the least-squares plane (SSE aligned) + * \param plane_parameters the resultant plane parameters as: a, b, c, d (ax + by + cz + d = 0) + * \param curvature the estimated surface curvature as a measure of + * \f[ + * \lambda_0 / (\lambda_0 + \lambda_1 + \lambda_2) + * \f] + * \ingroup features + */ + inline void + solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix, + const Eigen::Vector4f &point, + Eigen::Vector4f &plane_parameters, float &curvature); + + /** \brief Solve the eigenvalues and eigenvectors of a given 3x3 covariance matrix, and estimate the least-squares + * plane normal and surface curvature. + * \param covariance_matrix the 3x3 covariance matrix + * \param nx the resultant X component of the plane normal + * \param ny the resultant Y component of the plane normal + * \param nz the resultant Z component of the plane normal + * \param curvature the estimated surface curvature as a measure of + * \f[ + * \lambda_0 / (\lambda_0 + \lambda_1 + \lambda_2) + * \f] + * \ingroup features + */ + inline void + solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix, + float &nx, float &ny, float &nz, float &curvature); + + //////////////////////////////////////////////////////////////////////////////////////////// + //////////////////////////////////////////////////////////////////////////////////////////// + //////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Feature represents the base feature class. Some generic 3D operations that + * are applicable to all features are defined here as static methods. + * + * \attention + * The convention for a feature descriptor is: + * - if the nearest neighbors for the query point at which the descriptor is to be computed cannot be + * determined, the descriptor values will be set to NaN (not a number) + * - it is impossible to estimate a feature descriptor for a point that doesn't have finite 3D coordinates. + * Therefore, any point that has NaN data on x, y, or z, will most likely have its descriptor set to NaN. + * + * \author Radu B. Rusu + * \ingroup features + */ + template + class Feature : public PCLBase + { + public: + using PCLBase::indices_; + using PCLBase::input_; + + typedef PCLBase BaseClass; + + typedef boost::shared_ptr< Feature > Ptr; + typedef boost::shared_ptr< const Feature > ConstPtr; + + typedef typename pcl::search::Search KdTree; + typedef typename pcl::search::Search::Ptr KdTreePtr; + + typedef pcl::PointCloud PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + typedef pcl::PointCloud PointCloudOut; + + typedef boost::function &, std::vector &)> SearchMethod; + typedef boost::function &, std::vector &)> SearchMethodSurface; + + public: + /** \brief Empty constructor. */ + Feature () : + feature_name_ (), search_method_surface_ (), + surface_(), tree_(), + search_parameter_(0), search_radius_(0), k_(0), + fake_surface_(false), + points_target_ptr_ (NULL), + index_target_ptr_ (NULL), + treeH_target_ (NULL), + max_leaf_size_ (64), + use_customized_tree_ (false), + approx_radius_para_ (0.0), + approx_nn_para_ (0.0) + {} + + /** \brief Empty destructor */ + virtual ~Feature () + { + } + + /** \brief Provide a pointer to a dataset to add additional information + * to estimate the features for every point in the input dataset. This + * is optional, if this is not set, it will only use the data in the + * input cloud to estimate the features. This is useful when you only + * need to compute the features for a downsampled cloud. + * \param[in] cloud a pointer to a PointCloud message + */ + inline void + setSearchSurface (const PointCloudInConstPtr &cloud) + { + surface_ = cloud; + fake_surface_ = false; + //use_surface_ = true; + } + + /** \brief Get a pointer to the surface point cloud dataset. */ + inline PointCloudInConstPtr + getSearchSurface () const + { + return (surface_); + } + + /** \brief Provide a pointer to the search object. + * \param[in] tree a pointer to the spatial search object. + */ + inline void + setSearchMethod (const KdTreePtr &tree) { tree_ = tree; } + + /** \brief Get a pointer to the search method used. */ + inline KdTreePtr + getSearchMethod () const + { + return (tree_); + } + + /** \brief Get the internal search parameter. */ + inline double + getSearchParameter () const + { + return (search_parameter_); + } + + /** \brief Set the number of k nearest neighbors to use for the feature estimation. + * \param[in] k the number of k-nearest neighbors + */ + inline void + setKSearch (int k) { k_ = k; } + + /** \brief get the number of k nearest neighbors used for the feature estimation. */ + inline int + getKSearch () const + { + return (k_); + } + + /** \brief Set the sphere radius that is to be used for determining the nearest neighbors used for the feature + * estimation. + * \param[in] radius the sphere radius used as the maximum distance to consider a point a neighbor + */ + inline void + setRadiusSearch (double radius) + { + search_radius_ = radius; + } + + /** \brief Get the sphere radius used for determining the neighbors. */ + inline double + getRadiusSearch () const + { + return (search_radius_); + } + + /** \brief Base method for feature estimation for all points given in + * using the surface in setSearchSurface () + * and the spatial locator in setSearchMethod () + * \param[out] output the resultant point cloud model dataset containing the estimated features + */ + void + compute (PointCloudOut &output); + + inline void setApproxRadiusPara(float approx_radius_para) + { + approx_radius_para_ = approx_radius_para; + } + + protected: + /** To store the points and indices in the target point cloud. **/ + std::vector points_target_; + std::vector * points_target_ptr_; + + std::vector index_target_; + std::vector * index_target_ptr_; + + /** Parameter for Approximate Radius Search **/ + float approx_radius_para_; + + /** Parameter for Approximate NN Search **/ + float approx_nn_para_; + + /** Whether to use the customized KD-Tree data structure. **/ + bool use_customized_tree_; + + /** Pointer to the customized KD-Tree data structure. **/ + KdTreeH * treeH_target_; + + /** Maximum number of points in each leaf node (of the searching KDTree). **/ + int max_leaf_size_; + + /** \brief The feature name. */ + std::string feature_name_; + + /** \brief The search method template for points. */ + SearchMethodSurface search_method_surface_; + + /** \brief An input point cloud describing the surface that is to be used + * for nearest neighbors estimation. + */ + PointCloudInConstPtr surface_; + + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + + /** \brief The actual search parameter (from either \a search_radius_ or \a k_). */ + double search_parameter_; + + /** \brief The nearest neighbors search radius for each point. */ + double search_radius_; + + /** \brief The number of K nearest neighbors to use for each point. */ + int k_; + + /** \brief Get a string representation of the name of this class. */ + inline const std::string& + getClassName () const { return (feature_name_); } + + /** \brief This method should get called before starting the actual computation. */ + virtual bool + initCompute (); + + /** \brief This method should get called after ending the actual computation. */ + virtual bool + deinitCompute (); + + /** \brief If no surface is given, we use the input PointCloud as the surface. */ + bool fake_surface_; + + /** \brief Search for k-nearest neighbors using the spatial locator from + * \a setSearchmethod, and the given surface from \a setSearchSurface. + * \param[in] index the index of the query point + * \param[in] parameter the search parameter (either k or radius) + * \param[out] indices the resultant vector of indices representing the k-nearest neighbors + * \param[out] distances the resultant vector of distances representing the distances from the query point to the + * k-nearest neighbors + * + * \return the number of neighbors found. If no neighbors are found or an error occurred, return 0. + */ + inline int + searchForNeighbors (size_t index, double parameter, + std::vector &indices, std::vector &distances) const + { + return (search_method_surface_ (*input_, index, parameter, indices, distances)); + } + + /** \brief Search for k-nearest neighbors using the spatial locator from + * \a setSearchmethod, and the given surface from \a setSearchSurface. + * \param[in] cloud the query point cloud + * \param[in] index the index of the query point in \a cloud + * \param[in] parameter the search parameter (either k or radius) + * \param[out] indices the resultant vector of indices representing the k-nearest neighbors + * \param[out] distances the resultant vector of distances representing the distances from the query point to the + * k-nearest neighbors + * + * \return the number of neighbors found. If no neighbors are found or an error occurred, return 0. + */ + inline int + searchForNeighbors (const PointCloudIn &cloud, size_t index, double parameter, + std::vector &indices, std::vector &distances) const + { + return (search_method_surface_ (cloud, index, parameter, indices, distances)); + } + + /** Set maximum leaf size. **/ + void setMaxLeafSize (int size) { max_leaf_size_ = size; } + + /** Build the customized KD-Tree. **/ + void buildHKdTree_target() + { + treeH_target_ = new KdTreeH(points_target_ptr_, \ + index_target_ptr_, max_leaf_size_, approx_radius_para_, approx_nn_para_); + + treeH_target_->buildKDTree(); + } + + private: + /** \brief Abstract feature estimation method. + * \param[out] output the resultant features + */ + virtual void + computeFeature (PointCloudOut &output) = 0; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + + //////////////////////////////////////////////////////////////////////////////////////////// + //////////////////////////////////////////////////////////////////////////////////////////// + //////////////////////////////////////////////////////////////////////////////////////////// + template + class FeatureFromNormals : public Feature + { + typedef typename Feature::PointCloudIn PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + typedef typename Feature::PointCloudOut PointCloudOut; + + public: + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + + typedef boost::shared_ptr< FeatureFromNormals > Ptr; + typedef boost::shared_ptr< const FeatureFromNormals > ConstPtr; + + // Members derived from the base class + using Feature::input_; + using Feature::surface_; + using Feature::getClassName; + + /** \brief Empty constructor. */ + FeatureFromNormals () : normals_ () {} + + /** \brief Empty destructor */ + virtual ~FeatureFromNormals () {} + + /** \brief Provide a pointer to the input dataset that contains the point normals of + * the XYZ dataset. + * In case of search surface is set to be different from the input cloud, + * normals should correspond to the search surface, not the input cloud! + * \param[in] normals the const boost shared pointer to a PointCloud of normals. + * By convention, L2 norm of each normal should be 1. + */ + inline void + setInputNormals (const PointCloudNConstPtr &normals) { normals_ = normals; } + + /** \brief Get a pointer to the normals of the input XYZ point cloud dataset. */ + inline PointCloudNConstPtr + getInputNormals () const { return (normals_); } + + protected: + /** \brief A pointer to the input dataset that contains the point normals of the XYZ + * dataset. + */ + PointCloudNConstPtr normals_; + + /** \brief This method should get called before starting the actual computation. */ + virtual bool + initCompute (); + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + //////////////////////////////////////////////////////////////////////////////////////////// + //////////////////////////////////////////////////////////////////////////////////////////// + //////////////////////////////////////////////////////////////////////////////////////////// + template + class FeatureFromLabels : public Feature + { + typedef typename Feature::PointCloudIn PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + typedef typename pcl::PointCloud PointCloudL; + typedef typename PointCloudL::Ptr PointCloudNPtr; + typedef typename PointCloudL::ConstPtr PointCloudLConstPtr; + + typedef typename Feature::PointCloudOut PointCloudOut; + + public: + typedef boost::shared_ptr< FeatureFromLabels > Ptr; + typedef boost::shared_ptr< const FeatureFromLabels > ConstPtr; + + // Members derived from the base class + using Feature::input_; + using Feature::surface_; + using Feature::getClassName; + using Feature::k_; + + /** \brief Empty constructor. */ + FeatureFromLabels () : labels_ () + { + k_ = 1; // Search tree is not always used here. + } + + /** \brief Empty destructor */ + virtual ~FeatureFromLabels () {} + + /** \brief Provide a pointer to the input dataset that contains the point labels of + * the XYZ dataset. + * In case of search surface is set to be different from the input cloud, + * labels should correspond to the search surface, not the input cloud! + * \param[in] labels the const boost shared pointer to a PointCloud of labels. + */ + inline void + setInputLabels (const PointCloudLConstPtr &labels) + { + labels_ = labels; + } + + /** \brief Get a pointer to the labels of the input XYZ point cloud dataset. */ + inline PointCloudLConstPtr + getInputLabels () const + { + return (labels_); + } + + protected: + /** \brief A pointer to the input dataset that contains the point labels of the XYZ + * dataset. + */ + PointCloudLConstPtr labels_; + + /** \brief This method should get called before starting the actual computation. */ + virtual bool + initCompute (); + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + //////////////////////////////////////////////////////////////////////////////////////////// + //////////////////////////////////////////////////////////////////////////////////////////// + //////////////////////////////////////////////////////////////////////////////////////////// + /** \brief FeatureWithLocalReferenceFrames provides a public interface for descriptor + * extractor classes which need a local reference frame at each input keypoint. + * + * \attention + * This interface is for backward compatibility with existing code and in the future it could be + * merged with pcl::Feature. Subclasses should call the protected method initLocalReferenceFrames () + * to correctly initialize the frames_ member. + * + * \author Nicola Fioraio + * \ingroup features + */ + template + class FeatureWithLocalReferenceFrames + { + public: + typedef pcl::PointCloud PointCloudLRF; + typedef typename PointCloudLRF::Ptr PointCloudLRFPtr; + typedef typename PointCloudLRF::ConstPtr PointCloudLRFConstPtr; + + /** \brief Empty constructor. */ + FeatureWithLocalReferenceFrames () : frames_ (), frames_never_defined_ (true) {} + + /** \brief Empty destructor. */ + virtual ~FeatureWithLocalReferenceFrames () {} + + /** \brief Provide a pointer to the input dataset that contains the local + * reference frames of the XYZ dataset. + * In case of search surface is set to be different from the input cloud, + * local reference frames should correspond to the input cloud, not the search surface! + * \param[in] frames the const boost shared pointer to a PointCloud of reference frames. + */ + inline void + setInputReferenceFrames (const PointCloudLRFConstPtr &frames) + { + frames_ = frames; + frames_never_defined_ = false; + } + + /** \brief Get a pointer to the local reference frames. */ + inline PointCloudLRFConstPtr + getInputReferenceFrames () const + { + return (frames_); + } + + protected: + /** \brief A boost shared pointer to the local reference frames. */ + PointCloudLRFConstPtr frames_; + /** \brief The user has never set the frames. */ + bool frames_never_defined_; + + /** \brief Check if frames_ has been correctly initialized and compute it if needed. + * \param input the subclass' input cloud dataset. + * \param lrf_estimation a pointer to a local reference frame estimation class to be used as default. + * \return true if frames_ has been correctly initialized. + */ + typedef typename Feature::Ptr LRFEstimationPtr; + virtual bool + initLocalReferenceFrames (const size_t& indices_size, + const LRFEstimationPtr& lrf_estimation = LRFEstimationPtr()); + }; +} + +#include + +#endif //#ifndef PCL_FEATURE_H_ diff --git a/pcl-1.7/pcl/features/fpfh.h b/pcl-1.7/pcl/features/fpfh.h new file mode 100644 index 0000000..b53103b --- /dev/null +++ b/pcl-1.7/pcl/features/fpfh.h @@ -0,0 +1,226 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FPFH_H_ +#define PCL_FPFH_H_ + +#include +#include + +namespace pcl +{ + /** \brief FPFHEstimation estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point + * cloud dataset containing points and normals. + * + * A commonly used type for PointOutT is pcl::FPFHSignature33. + * + * \note If you use this code in any academic work, please cite: + * + * - R.B. Rusu, N. Blodow, M. Beetz. + * Fast Point Feature Histograms (FPFH) for 3D Registration. + * In Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), + * Kobe, Japan, May 12-17 2009. + * - R.B. Rusu, A. Holzbach, N. Blodow, M. Beetz. + * Fast Geometric Point Labeling using Conditional Random Fields. + * In Proceedings of the 22nd IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), + * St. Louis, MO, USA, October 11-15 2009. + * + * \attention + * The convention for FPFH features is: + * - if a query point's nearest neighbors cannot be estimated, the FPFH feature will be set to NaN + * (not a number) + * - it is impossible to estimate a FPFH descriptor for a point that + * doesn't have finite 3D coordinates. Therefore, any point that contains + * NaN data on x, y, or z, will have its FPFH feature property set to NaN. + * + * \note The code is stateful as we do not expect this class to be multicore parallelized. Please look at + * \ref FPFHEstimationOMP for examples on parallel implementations of the FPFH (Fast Point Feature Histogram). + * + * \author Radu B. Rusu + * \ingroup features + */ + template + class FPFHEstimation : public FeatureFromNormals + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::k_; + using Feature::search_parameter_; + using Feature::input_; + using Feature::surface_; + using FeatureFromNormals::normals_; + + typedef typename Feature::PointCloudOut PointCloudOut; + + /** \brief Empty constructor. */ + FPFHEstimation () : + nr_bins_f1_ (11), nr_bins_f2_ (11), nr_bins_f3_ (11), + hist_f1_ (), hist_f2_ (), hist_f3_ (), fpfh_histogram_ (), + d_pi_ (1.0f / (2.0f * static_cast (M_PI))) + { + feature_name_ = "FPFHEstimation"; + }; + + /** \brief Compute the 4-tuple representation containing the three angles and one distance between two points + * represented by Cartesian coordinates and normals. + * \note For explanations about the features, please see the literature mentioned above (the order of the + * features might be different). + * \param[in] cloud the dataset containing the XYZ Cartesian coordinates of the two points + * \param[in] normals the dataset containing the surface normals (assuming normalized vectors) at each point in cloud + * \param[in] p_idx the index of the first point (source) + * \param[in] q_idx the index of the second point (target) + * \param[out] f1 the first angular feature (angle between the projection of nq_idx and u) + * \param[out] f2 the second angular feature (angle between nq_idx and v) + * \param[out] f3 the third angular feature (angle between np_idx and |p_idx - q_idx|) + * \param[out] f4 the distance feature (p_idx - q_idx) + */ + bool + computePairFeatures (const pcl::PointCloud &cloud, const pcl::PointCloud &normals, + int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4); + + /** \brief Estimate the SPFH (Simple Point Feature Histograms) individual signatures of the three angular + * (f1, f2, f3) features for a given point based on its spatial neighborhood of 3D points with normals + * \param[in] cloud the dataset containing the XYZ Cartesian coordinates of the two points + * \param[in] normals the dataset containing the surface normals at each point in \a cloud + * \param[in] p_idx the index of the query point (source) + * \param[in] row the index row in feature histogramms + * \param[in] indices the k-neighborhood point indices in the dataset + * \param[out] hist_f1 the resultant SPFH histogram for feature f1 + * \param[out] hist_f2 the resultant SPFH histogram for feature f2 + * \param[out] hist_f3 the resultant SPFH histogram for feature f3 + */ + void + computePointSPFHSignature (const pcl::PointCloud &cloud, + const pcl::PointCloud &normals, int p_idx, int row, + const std::vector &indices, + Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3); + + /** \brief Weight the SPFH (Simple Point Feature Histograms) individual histograms to create the final FPFH + * (Fast Point Feature Histogram) for a given point based on its 3D spatial neighborhood + * \param[in] hist_f1 the histogram feature vector of \a f1 values over the given patch + * \param[in] hist_f2 the histogram feature vector of \a f2 values over the given patch + * \param[in] hist_f3 the histogram feature vector of \a f3 values over the given patch + * \param[in] indices the point indices of p_idx's k-neighborhood in the point cloud + * \param[in] dists the distances from p_idx to all its k-neighbors + * \param[out] fpfh_histogram the resultant FPFH histogram representing the feature at the query point + */ + void + weightPointSPFHSignature (const Eigen::MatrixXf &hist_f1, + const Eigen::MatrixXf &hist_f2, + const Eigen::MatrixXf &hist_f3, + const std::vector &indices, + const std::vector &dists, + Eigen::VectorXf &fpfh_histogram); + + /** \brief Set the number of subdivisions for each angular feature interval. + * \param[in] nr_bins_f1 number of subdivisions for the first angular feature + * \param[in] nr_bins_f2 number of subdivisions for the second angular feature + * \param[in] nr_bins_f3 number of subdivisions for the third angular feature + */ + inline void + setNrSubdivisions (int nr_bins_f1, int nr_bins_f2, int nr_bins_f3) + { + nr_bins_f1_ = nr_bins_f1; + nr_bins_f2_ = nr_bins_f2; + nr_bins_f3_ = nr_bins_f3; + } + + /** \brief Get the number of subdivisions for each angular feature interval. + * \param[out] nr_bins_f1 number of subdivisions for the first angular feature + * \param[out] nr_bins_f2 number of subdivisions for the second angular feature + * \param[out] nr_bins_f3 number of subdivisions for the third angular feature + */ + inline void + getNrSubdivisions (int &nr_bins_f1, int &nr_bins_f2, int &nr_bins_f3) + { + nr_bins_f1 = nr_bins_f1_; + nr_bins_f2 = nr_bins_f2_; + nr_bins_f3 = nr_bins_f3_; + } + + protected: + + /** \brief Estimate the set of all SPFH (Simple Point Feature Histograms) signatures for the input cloud + * \param[out] spf_hist_lookup a lookup table for all the SPF feature indices + * \param[out] hist_f1 the resultant SPFH histogram for feature f1 + * \param[out] hist_f2 the resultant SPFH histogram for feature f2 + * \param[out] hist_f3 the resultant SPFH histogram for feature f3 + */ + void + computeSPFHSignatures (std::vector &spf_hist_lookup, + Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3); + + /** \brief Estimate the Fast Point Feature Histograms (FPFH) descriptors at a set of points given by + * using the surface in setSearchSurface () and the spatial locator in + * setSearchMethod () + * \param[out] output the resultant point cloud model dataset that contains the FPFH feature estimates + */ + void + computeFeature (PointCloudOut &output); + + /** \brief The number of subdivisions for each angular feature interval. */ + int nr_bins_f1_, nr_bins_f2_, nr_bins_f3_; + + /** \brief Placeholder for the f1 histogram. */ + Eigen::MatrixXf hist_f1_; + + /** \brief Placeholder for the f2 histogram. */ + Eigen::MatrixXf hist_f2_; + + /** \brief Placeholder for the f3 histogram. */ + Eigen::MatrixXf hist_f3_; + + /** \brief Placeholder for a point's FPFH signature. */ + Eigen::VectorXf fpfh_histogram_; + + /** \brief Float constant = 1.0 / (2.0 * M_PI) */ + float d_pi_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FPFH_H_ diff --git a/pcl-1.7/pcl/features/fpfh_omp.h b/pcl-1.7/pcl/features/fpfh_omp.h new file mode 100644 index 0000000..9d56c9d --- /dev/null +++ b/pcl-1.7/pcl/features/fpfh_omp.h @@ -0,0 +1,140 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FPFH_OMP_H_ +#define PCL_FPFH_OMP_H_ + +#include +#include + +namespace pcl +{ + /** \brief FPFHEstimationOMP estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud + * dataset containing points and normals, in parallel, using the OpenMP standard. + * + * \note If you use this code in any academic work, please cite: + * + * - R.B. Rusu, N. Blodow, M. Beetz. + * Fast Point Feature Histograms (FPFH) for 3D Registration. + * In Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), + * Kobe, Japan, May 12-17 2009. + * - R.B. Rusu, A. Holzbach, N. Blodow, M. Beetz. + * Fast Geometric Point Labeling using Conditional Random Fields. + * In Proceedings of the 22nd IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), + * St. Louis, MO, USA, October 11-15 2009. + * + * \attention + * The convention for FPFH features is: + * - if a query point's nearest neighbors cannot be estimated, the FPFH feature will be set to NaN + * (not a number) + * - it is impossible to estimate a FPFH descriptor for a point that + * doesn't have finite 3D coordinates. Therefore, any point that contains + * NaN data on x, y, or z, will have its FPFH feature property set to NaN. + * + * \author Radu B. Rusu + * \ingroup features + */ + template + class FPFHEstimationOMP : public FPFHEstimation + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::k_; + using Feature::search_parameter_; + using Feature::input_; + using Feature::surface_; + using FeatureFromNormals::normals_; + using FPFHEstimation::hist_f1_; + using FPFHEstimation::hist_f2_; + using FPFHEstimation::hist_f3_; + using FPFHEstimation::weightPointSPFHSignature; + + typedef typename Feature::PointCloudOut PointCloudOut; + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param[in] nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + FPFHEstimationOMP (unsigned int nr_threads = 0) : nr_bins_f1_ (11), + nr_bins_f2_ (11), nr_bins_f3_ (11), threads_ (nr_threads), nn_time_(0.0) + { + feature_name_ = "FPFHEstimationOMP"; + } + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param[in] nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + + void getNnTime(float &nn_time) + { + nn_time = nn_time_; + } + + protected: + float nn_time_; + + private: + /** \brief Estimate the Fast Point Feature Histograms (FPFH) descriptors at a set of points given by + * using the surface in setSearchSurface () and the spatial locator in + * setSearchMethod () + * \param[out] output the resultant point cloud model dataset that contains the FPFH feature estimates + */ + void + computeFeature (PointCloudOut &output); + + public: + /** \brief The number of subdivisions for each angular feature interval. */ + int nr_bins_f1_, nr_bins_f2_, nr_bins_f3_; + private: + /** \brief The number of threads the scheduler should use. */ + unsigned int threads_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FPFH_OMP_H_ diff --git a/pcl-1.7/pcl/features/gfpfh.h b/pcl-1.7/pcl/features/gfpfh.h new file mode 100644 index 0000000..9eaa40b --- /dev/null +++ b/pcl-1.7/pcl/features/gfpfh.h @@ -0,0 +1,179 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: gfpfh.h 1423 2011-06-21 09:51:32Z bouffa $ + * + */ + +#ifndef PCL_GFPFH_H_ +#define PCL_GFPFH_H_ + +#include + +namespace pcl +{ + /** \brief @b GFPFHEstimation estimates the Global Fast Point Feature Histogram (GFPFH) descriptor for a given point + * cloud dataset containing points and labels. + * + * @note If you use this code in any academic work, please cite: + * + *
    + *
  • R.B. Rusu, A. Holzbach, M. Beetz. + * Detecting and Segmenting Objects for Mobile Manipulation. + * In the S3DV Workshop of the 12th International Conference on Computer Vision (ICCV), + * 2009. + *
  • + *
+ * + * \author Radu B. Rusu + * \ingroup features + */ + template + class GFPFHEstimation : public FeatureFromLabels + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using FeatureFromLabels::feature_name_; + using FeatureFromLabels::getClassName; + using FeatureFromLabels::indices_; + using FeatureFromLabels::k_; + using FeatureFromLabels::search_parameter_; + using FeatureFromLabels::surface_; + + using FeatureFromLabels::input_; + using FeatureFromLabels::labels_; + + typedef typename Feature::PointCloudOut PointCloudOut; + typedef typename Feature::PointCloudIn PointCloudIn; + + /** \brief Empty constructor. */ + GFPFHEstimation () : + octree_leaf_size_ (0.01), + number_of_classes_ (16), + descriptor_size_ (PointOutT::descriptorSize ()) + { + feature_name_ = "GFPFHEstimation"; + } + + /** \brief Set the size of the octree leaves. + */ + inline void + setOctreeLeafSize (double size) { octree_leaf_size_ = size; } + + /** \brief Get the sphere radius used for determining the neighbors. */ + inline double + getOctreeLeafSize () { return (octree_leaf_size_); } + + /** \brief Return the empty label value. */ + inline uint32_t + emptyLabel () const { return 0; } + + /** \brief Return the number of different classes. */ + inline uint32_t + getNumberOfClasses () const { return number_of_classes_; } + + /** \brief Set the number of different classes. + * \param n number of different classes. + */ + inline void + setNumberOfClasses (uint32_t n) { number_of_classes_ = n; } + + /** \brief Return the size of the descriptor. */ + inline int + descriptorSize () const { return descriptor_size_; } + + /** \brief Overloaded computed method from pcl::Feature. + * \param[out] output the resultant point cloud model dataset containing the estimated features + */ + void + compute (PointCloudOut &output); + + protected: + + /** \brief Estimate the Point Feature Histograms (PFH) descriptors at a set of points given by + * using the surface in setSearchSurface () and the spatial locator in + * setSearchMethod () + * \param output the resultant point cloud model dataset that contains the PFH feature estimates + */ + void + computeFeature (PointCloudOut &output); + + /** \brief Return the dominant label of a set of points. */ + uint32_t + getDominantLabel (const std::vector& indices); + + /** \brief Compute the fixed-length histograms of transitions. */ + void computeTransitionHistograms (const std::vector< std::vector >& label_histograms, + std::vector< std::vector >& transition_histograms); + + /** \brief Compute the distance of each transition histogram to the mean. */ + void + computeDistancesToMean (const std::vector< std::vector >& transition_histograms, + std::vector& distances); + + /** \brief Return the Intersection Kernel distance between two histograms. */ + float + computeHIKDistance (const std::vector& histogram, + const std::vector& mean_histogram); + + /** \brief Compute the binned histogram of distance values. */ + void + computeDistanceHistogram (const std::vector& distances, + std::vector& histogram); + + /** \brief Compute the mean histogram of the given set of histograms. */ + void + computeMeanHistogram (const std::vector< std::vector >& histograms, + std::vector& mean_histogram); + + private: + /** \brief Size of octree leaves. */ + double octree_leaf_size_; + + /** \brief Number of possible classes/labels. */ + uint32_t number_of_classes_; + + /** \brief Dimension of the descriptors. */ + int descriptor_size_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_GFPFH_H_ diff --git a/pcl-1.7/pcl/features/impl/3dsc.hpp b/pcl-1.7/pcl/features/impl/3dsc.hpp new file mode 100644 index 0000000..517a707 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/3dsc.hpp @@ -0,0 +1,314 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_IMPL_3DSC_HPP_ +#define PCL_FEATURES_IMPL_3DSC_HPP_ + +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::ShapeContext3DEstimation::initCompute () +{ + if (!FeatureFromNormals::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + if (search_radius_< min_radius_) + { + PCL_ERROR ("[pcl::%s::initCompute] search_radius_ must be GREATER than min_radius_.\n", getClassName ().c_str ()); + return (false); + } + + // Update descriptor length + descriptor_length_ = elevation_bins_ * azimuth_bins_ * radius_bins_; + + // Compute radial, elevation and azimuth divisions + float azimuth_interval = 360.0f / static_cast (azimuth_bins_); + float elevation_interval = 180.0f / static_cast (elevation_bins_); + + // Reallocate divisions and volume lut + radii_interval_.clear (); + phi_divisions_.clear (); + theta_divisions_.clear (); + volume_lut_.clear (); + + // Fills radii interval based on formula (1) in section 2.1 of Frome's paper + radii_interval_.resize (radius_bins_ + 1); + for (size_t j = 0; j < radius_bins_ + 1; j++) + radii_interval_[j] = static_cast (exp (log (min_radius_) + ((static_cast (j) / static_cast (radius_bins_)) * log (search_radius_ / min_radius_)))); + + // Fill theta divisions of elevation + theta_divisions_.resize (elevation_bins_ + 1); + for (size_t k = 0; k < elevation_bins_ + 1; k++) + theta_divisions_[k] = static_cast (k) * elevation_interval; + + // Fill phi didvisions of elevation + phi_divisions_.resize (azimuth_bins_ + 1); + for (size_t l = 0; l < azimuth_bins_ + 1; l++) + phi_divisions_[l] = static_cast (l) * azimuth_interval; + + // LookUp Table that contains the volume of all the bins + // "phi" term of the volume integral + // "integr_phi" has always the same value so we compute it only one time + float integr_phi = pcl::deg2rad (phi_divisions_[1]) - pcl::deg2rad (phi_divisions_[0]); + // exponential to compute the cube root using pow + float e = 1.0f / 3.0f; + // Resize volume look up table + volume_lut_.resize (radius_bins_ * elevation_bins_ * azimuth_bins_); + // Fill volumes look up table + for (size_t j = 0; j < radius_bins_; j++) + { + // "r" term of the volume integral + float integr_r = (radii_interval_[j+1] * radii_interval_[j+1] * radii_interval_[j+1] / 3.0f) - (radii_interval_[j] * radii_interval_[j] * radii_interval_[j] / 3.0f); + + for (size_t k = 0; k < elevation_bins_; k++) + { + // "theta" term of the volume integral + float integr_theta = cosf (pcl::deg2rad (theta_divisions_[k])) - cosf (pcl::deg2rad (theta_divisions_[k+1])); + // Volume + float V = integr_phi * integr_theta * integr_r; + // Compute cube root of the computed volume commented for performance but left + // here for clarity + // float cbrt = pow(V, e); + // cbrt = 1 / cbrt; + + for (size_t l = 0; l < azimuth_bins_; l++) + { + // Store in lut 1/cbrt + //volume_lut_[ (l*elevation_bins_*radius_bins_) + k*radius_bins_ + j ] = cbrt; + volume_lut_[(l*elevation_bins_*radius_bins_) + k*radius_bins_ + j] = 1.0f / powf (V, e); + } + } + } + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::ShapeContext3DEstimation::computePoint ( + size_t index, const pcl::PointCloud &normals, float rf[9], std::vector &desc) +{ + // The RF is formed as this x_axis | y_axis | normal + Eigen::Map x_axis (rf); + Eigen::Map y_axis (rf + 3); + Eigen::Map normal (rf + 6); + + // Find every point within specified search_radius_ + std::vector nn_indices; + std::vector nn_dists; + + const size_t neighb_cnt = searchForNeighbors ((*indices_)[index], search_radius_, nn_indices, nn_dists); + + if (neighb_cnt == 0) + { + for (size_t i = 0; i < desc.size (); ++i) + desc[i] = std::numeric_limits::quiet_NaN (); + + memset (rf, 0, sizeof (rf[0]) * 9); + return (false); + } + + float minDist = std::numeric_limits::max (); + int minIndex = -1; + for (size_t i = 0; i < nn_indices.size (); i++) + { + if (nn_dists[i] < minDist) + { + minDist = nn_dists[i]; + minIndex = nn_indices[i]; + } + } + + // Get origin point + Vector3fMapConst origin = input_->points[(*indices_)[index]].getVector3fMap (); + // Get origin normal + // Use pre-computed normals + normal = normals[minIndex].getNormalVector3fMap (); + + // Compute and store the RF direction + x_axis[0] = static_cast (rnd ()); + x_axis[1] = static_cast (rnd ()); + x_axis[2] = static_cast (rnd ()); + if (!pcl::utils::equal (normal[2], 0.0f)) + x_axis[2] = - (normal[0]*x_axis[0] + normal[1]*x_axis[1]) / normal[2]; + else if (!pcl::utils::equal (normal[1], 0.0f)) + x_axis[1] = - (normal[0]*x_axis[0] + normal[2]*x_axis[2]) / normal[1]; + else if (!pcl::utils::equal (normal[0], 0.0f)) + x_axis[0] = - (normal[1]*x_axis[1] + normal[2]*x_axis[2]) / normal[0]; + + x_axis.normalize (); + + // Check if the computed x axis is orthogonal to the normal + assert (pcl::utils::equal (x_axis[0]*normal[0] + x_axis[1]*normal[1] + x_axis[2]*normal[2], 0.0f, 1E-6f)); + + // Store the 3rd frame vector + y_axis.matrix () = normal.cross (x_axis); + + // For each point within radius + for (size_t ne = 0; ne < neighb_cnt; ne++) + { + if (pcl::utils::equal (nn_dists[ne], 0.0f)) + continue; + // Get neighbours coordinates + Eigen::Vector3f neighbour = surface_->points[nn_indices[ne]].getVector3fMap (); + + /// ----- Compute current neighbour polar coordinates ----- + /// Get distance between the neighbour and the origin + float r = sqrtf (nn_dists[ne]); + + /// Project point into the tangent plane + Eigen::Vector3f proj; + pcl::geometry::project (neighbour, origin, normal, proj); + proj -= origin; + + /// Normalize to compute the dot product + proj.normalize (); + + /// Compute the angle between the projection and the x axis in the interval [0,360] + Eigen::Vector3f cross = x_axis.cross (proj); + float phi = pcl::rad2deg (std::atan2 (cross.norm (), x_axis.dot (proj))); + phi = cross.dot (normal) < 0.f ? (360.0f - phi) : phi; + /// Compute the angle between the neighbour and the z axis (normal) in the interval [0, 180] + Eigen::Vector3f no = neighbour - origin; + no.normalize (); + float theta = normal.dot (no); + theta = pcl::rad2deg (acosf (std::min (1.0f, std::max (-1.0f, theta)))); + + // Bin (j, k, l) + size_t j = 0; + size_t k = 0; + size_t l = 0; + + // Compute the Bin(j, k, l) coordinates of current neighbour + for (size_t rad = 1; rad < radius_bins_+1; rad++) + { + if (r <= radii_interval_[rad]) + { + j = rad-1; + break; + } + } + + for (size_t ang = 1; ang < elevation_bins_+1; ang++) + { + if (theta <= theta_divisions_[ang]) + { + k = ang-1; + break; + } + } + + for (size_t ang = 1; ang < azimuth_bins_+1; ang++) + { + if (phi <= phi_divisions_[ang]) + { + l = ang-1; + break; + } + } + + // Local point density = number of points in a sphere of radius "point_density_radius_" around the current neighbour + std::vector neighbour_indices; + std::vector neighbour_distances; + + int point_density = searchForNeighbors (*surface_, nn_indices[ne], point_density_radius_, neighbour_indices, neighbour_distances); + + // point_density is NOT always bigger than 0 (on error, searchForNeighbors returns 0), so we must check for that + if (point_density == 0) + continue; + + float w = (1.0f / static_cast (point_density)) * + volume_lut_[(l*elevation_bins_*radius_bins_) + (k*radius_bins_) + j]; + + assert (w >= 0.0); + if (w == std::numeric_limits::infinity ()) + PCL_ERROR ("Shape Context Error INF!\n"); + if (w != w) + PCL_ERROR ("Shape Context Error IND!\n"); + /// Accumulate w into correspondant Bin(j,k,l) + desc[(l*elevation_bins_*radius_bins_) + (k*radius_bins_) + j] += w; + + assert (desc[(l*elevation_bins_*radius_bins_) + (k*radius_bins_) + j] >= 0); + } // end for each neighbour + + // 3DSC does not define a repeatable local RF, we set it to zero to signal it to the user + memset (rf, 0, sizeof (rf[0]) * 9); + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ShapeContext3DEstimation::computeFeature (PointCloudOut &output) +{ + assert (descriptor_length_ == 1980); + + output.is_dense = true; + // Iterate over all points and compute the descriptors + for (size_t point_index = 0; point_index < indices_->size (); point_index++) + { + //output[point_index].descriptor.resize (descriptor_length_); + + // If the point is not finite, set the descriptor to NaN and continue + if (!isFinite ((*input_)[(*indices_)[point_index]])) + { + for (size_t i = 0; i < descriptor_length_; ++i) + output[point_index].descriptor[i] = std::numeric_limits::quiet_NaN (); + + memset (output[point_index].rf, 0, sizeof (output[point_index].rf[0]) * 9); + output.is_dense = false; + continue; + } + + std::vector descriptor (descriptor_length_); + if (!computePoint (point_index, *normals_, output[point_index].rf, descriptor)) + output.is_dense = false; + for (size_t j = 0; j < descriptor_length_; ++j) + output[point_index].descriptor[j] = descriptor[j]; + } +} + +#define PCL_INSTANTIATE_ShapeContext3DEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::ShapeContext3DEstimation; + +#endif diff --git a/pcl-1.7/pcl/features/impl/board.hpp b/pcl-1.7/pcl/features/impl/board.hpp new file mode 100644 index 0000000..bb3e468 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/board.hpp @@ -0,0 +1,631 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_FEATURES_IMPL_BOARD_H_ +#define PCL_FEATURES_IMPL_BOARD_H_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BOARDLocalReferenceFrameEstimation::directedOrthogonalAxis ( + Eigen::Vector3f const &axis, + Eigen::Vector3f const &axis_origin, + Eigen::Vector3f const &point, + Eigen::Vector3f &directed_ortho_axis) +{ + Eigen::Vector3f projection; + projectPointOnPlane (point, axis_origin, axis, projection); + directed_ortho_axis = projection - axis_origin; + + directed_ortho_axis.normalize (); + + // check if the computed x axis is orthogonal to the normal + //assert(areEquals((float)(directed_ortho_axis.dot(axis)), 0.0f, 1E-3f)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BOARDLocalReferenceFrameEstimation::projectPointOnPlane ( + Eigen::Vector3f const &point, + Eigen::Vector3f const &origin_point, + Eigen::Vector3f const &plane_normal, + Eigen::Vector3f &projected_point) +{ + float t; + Eigen::Vector3f xo; + + xo = point - origin_point; + t = plane_normal.dot (xo); + + projected_point = point - (t * plane_normal); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::BOARDLocalReferenceFrameEstimation::getAngleBetweenUnitVectors ( + Eigen::Vector3f const &v1, + Eigen::Vector3f const &v2, + Eigen::Vector3f const &axis) +{ + Eigen::Vector3f angle_orientation; + angle_orientation = v1.cross (v2); + float angle_radians = acosf (std::max (-1.0f, std::min (1.0f, v1.dot (v2)))); + + angle_radians = angle_orientation.dot (axis) < 0.f ? (2 * static_cast (M_PI) - angle_radians) : angle_radians; + + return (angle_radians); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BOARDLocalReferenceFrameEstimation::randomOrthogonalAxis ( + Eigen::Vector3f const &axis, + Eigen::Vector3f &rand_ortho_axis) +{ + if (!areEquals (axis.z (), 0.0f)) + { + rand_ortho_axis.x () = (static_cast (rand ()) / static_cast (RAND_MAX)) * 2.0f - 1.0f; + rand_ortho_axis.y () = (static_cast (rand ()) / static_cast (RAND_MAX)) * 2.0f - 1.0f; + rand_ortho_axis.z () = -(axis.x () * rand_ortho_axis.x () + axis.y () * rand_ortho_axis.y ()) / axis.z (); + } + else if (!areEquals (axis.y (), 0.0f)) + { + rand_ortho_axis.x () = (static_cast (rand ()) / static_cast (RAND_MAX)) * 2.0f - 1.0f; + rand_ortho_axis.z () = (static_cast (rand ()) / static_cast (RAND_MAX)) * 2.0f - 1.0f; + rand_ortho_axis.y () = -(axis.x () * rand_ortho_axis.x () + axis.z () * rand_ortho_axis.z ()) / axis.y (); + } + else if (!areEquals (axis.x (), 0.0f)) + { + rand_ortho_axis.y () = (static_cast (rand ()) / static_cast (RAND_MAX)) * 2.0f - 1.0f; + rand_ortho_axis.z () = (static_cast (rand ()) / static_cast (RAND_MAX)) * 2.0f - 1.0f; + rand_ortho_axis.x () = -(axis.y () * rand_ortho_axis.y () + axis.z () * rand_ortho_axis.z ()) / axis.x (); + } + + rand_ortho_axis.normalize (); + + // check if the computed x axis is orthogonal to the normal + //assert(areEquals(rand_ortho_axis.dot(axis), 0.0f, 1E-6f)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BOARDLocalReferenceFrameEstimation::planeFitting ( + Eigen::Matrix const &points, + Eigen::Vector3f ¢er, + Eigen::Vector3f &norm) +{ + // ----------------------------------------------------- + // Plane Fitting using Singular Value Decomposition (SVD) + // ----------------------------------------------------- + + int n_points = static_cast (points.rows ()); + if (n_points == 0) + { + return; + } + + //find the center by averaging the points positions + center.setZero (); + + for (int i = 0; i < n_points; ++i) + { + center += points.row (i); + } + + center /= static_cast (n_points); + + //copy points - average (center) + Eigen::Matrix A (n_points, 3); //PointData + for (int i = 0; i < n_points; ++i) + { + A (i, 0) = points (i, 0) - center.x (); + A (i, 1) = points (i, 1) - center.y (); + A (i, 2) = points (i, 2) - center.z (); + } + + Eigen::JacobiSVD svd (A, Eigen::ComputeFullV); + norm = svd.matrixV ().col (2); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BOARDLocalReferenceFrameEstimation::normalDisambiguation ( + pcl::PointCloud const &normal_cloud, + std::vector const &normal_indices, + Eigen::Vector3f &normal) +{ + Eigen::Vector3f normal_mean; + normal_mean.setZero (); + + for (size_t i = 0; i < normal_indices.size (); ++i) + { + const PointNT& curPt = normal_cloud[normal_indices[i]]; + + normal_mean += curPt.getNormalVector3fMap (); + } + + normal_mean.normalize (); + + if (normal.dot (normal_mean) < 0) + { + normal = -normal; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::BOARDLocalReferenceFrameEstimation::computePointLRF (const int &index, + Eigen::Matrix3f &lrf) +{ + //find Z axis + + //extract support points for Rz radius + std::vector neighbours_indices; + std::vector neighbours_distances; + int n_neighbours = this->searchForNeighbors (index, search_parameter_, neighbours_indices, neighbours_distances); + + //check if there are enough neighbor points, otherwise compute a random X axis and use normal as Z axis + if (n_neighbours < 6) + { + //PCL_WARN( + // "[pcl::%s::computePointLRF] Warning! Neighborhood has less than 6 vertices. Aborting description of point with index %d\n", + // getClassName().c_str(), index); + + //setting lrf to NaN + lrf.setConstant (std::numeric_limits::quiet_NaN ()); + + return (std::numeric_limits::max ()); + } + + //copy neighbours coordinates into eigen matrix + Eigen::Matrix neigh_points_mat (n_neighbours, 3); + for (int i = 0; i < n_neighbours; ++i) + { + neigh_points_mat.row (i) = (*surface_)[neighbours_indices[i]].getVector3fMap (); + } + + Eigen::Vector3f x_axis, y_axis; + //plane fitting to find direction of Z axis + Eigen::Vector3f fitted_normal; //z_axis + Eigen::Vector3f centroid; + planeFitting (neigh_points_mat, centroid, fitted_normal); + + //disambiguate Z axis with normal mean + normalDisambiguation (*normals_, neighbours_indices, fitted_normal); + + //setting LRF Z axis + lrf.row (2).matrix () = fitted_normal; + + ///////////////////////////////////////////////////////////////////////////////////////// + //find X axis + + //extract support points for Rx radius + if (tangent_radius_ != 0.0f && search_parameter_ != tangent_radius_) + { + n_neighbours = this->searchForNeighbors (index, tangent_radius_, neighbours_indices, neighbours_distances); + } + + //find point with the "most different" normal (with respect to fittedNormal) + + float min_normal_cos = std::numeric_limits::max (); + int min_normal_index = -1; + + bool margin_point_found = false; + Eigen::Vector3f best_margin_point; + bool best_point_found_on_margins = false; + + float radius2 = tangent_radius_ * tangent_radius_; + + float margin_distance2 = margin_thresh_ * margin_thresh_ * radius2; + + float max_boundary_angle = 0; + + if (find_holes_) + { + randomOrthogonalAxis (fitted_normal, x_axis); + + lrf.row (0).matrix () = x_axis; + + for (int i = 0; i < check_margin_array_size_; i++) + { + check_margin_array_[i] = false; + margin_array_min_angle_[i] = std::numeric_limits::max (); + margin_array_max_angle_[i] = -std::numeric_limits::max (); + margin_array_min_angle_normal_[i] = -1.0; + margin_array_max_angle_normal_[i] = -1.0; + } + max_boundary_angle = (2 * static_cast (M_PI)) / static_cast (check_margin_array_size_); + } + + for (int curr_neigh = 0; curr_neigh < n_neighbours; ++curr_neigh) + { + const int& curr_neigh_idx = neighbours_indices[curr_neigh]; + const float& neigh_distance_sqr = neighbours_distances[curr_neigh]; + if (neigh_distance_sqr <= margin_distance2) + { + continue; + } + + //point normalIndex is inside the ring between marginThresh and Radius + margin_point_found = true; + + Eigen::Vector3f normal_mean = normals_->at (curr_neigh_idx).getNormalVector3fMap (); + + float normal_cos = fitted_normal.dot (normal_mean); + if (normal_cos < min_normal_cos) + { + min_normal_index = curr_neigh_idx; + min_normal_cos = normal_cos; + best_point_found_on_margins = false; + } + + if (find_holes_) + { + //find angle with respect to random axis previously calculated + Eigen::Vector3f indicating_normal_vect; + directedOrthogonalAxis (fitted_normal, input_->at (index).getVector3fMap (), + surface_->at (curr_neigh_idx).getVector3fMap (), indicating_normal_vect); + float angle = getAngleBetweenUnitVectors (x_axis, indicating_normal_vect, fitted_normal); + + int check_margin_array_idx = std::min (static_cast (floor (angle / max_boundary_angle)), check_margin_array_size_ - 1); + check_margin_array_[check_margin_array_idx] = true; + + if (angle < margin_array_min_angle_[check_margin_array_idx]) + { + margin_array_min_angle_[check_margin_array_idx] = angle; + margin_array_min_angle_normal_[check_margin_array_idx] = normal_cos; + } + if (angle > margin_array_max_angle_[check_margin_array_idx]) + { + margin_array_max_angle_[check_margin_array_idx] = angle; + margin_array_max_angle_normal_[check_margin_array_idx] = normal_cos; + } + } + + } //for each neighbor + + if (!margin_point_found) + { + //find among points with neighDistance <= marginThresh*radius + for (int curr_neigh = 0; curr_neigh < n_neighbours; curr_neigh++) + { + const int& curr_neigh_idx = neighbours_indices[curr_neigh]; + const float& neigh_distance_sqr = neighbours_distances[curr_neigh]; + + if (neigh_distance_sqr > margin_distance2) + continue; + + Eigen::Vector3f normal_mean = normals_->at (curr_neigh_idx).getNormalVector3fMap (); + + float normal_cos = fitted_normal.dot (normal_mean); + + if (normal_cos < min_normal_cos) + { + min_normal_index = curr_neigh_idx; + min_normal_cos = normal_cos; + } + }//for each neighbor + + // Check if we are not in a degenerate case (all the neighboring normals are NaNs) + if (min_normal_index == -1) + { + lrf.setConstant (std::numeric_limits::quiet_NaN ()); + return (std::numeric_limits::max ()); + } + //find orthogonal axis directed to minNormalIndex point projection on plane with fittedNormal as axis + directedOrthogonalAxis (fitted_normal, input_->at (index).getVector3fMap (), + surface_->at (min_normal_index).getVector3fMap (), x_axis); + y_axis = fitted_normal.cross (x_axis); + + lrf.row (0).matrix () = x_axis; + lrf.row (1).matrix () = y_axis; + //z axis already set + + + return (min_normal_cos); + } + + if (!find_holes_) + { + if (best_point_found_on_margins) + { + //if most inclined normal is on support margin + directedOrthogonalAxis (fitted_normal, input_->at (index).getVector3fMap (), best_margin_point, x_axis); + y_axis = fitted_normal.cross (x_axis); + + lrf.row (0).matrix () = x_axis; + lrf.row (1).matrix () = y_axis; + //z axis already set + + return (min_normal_cos); + } + + // Check if we are not in a degenerate case (all the neighboring normals are NaNs) + if (min_normal_index == -1) + { + lrf.setConstant (std::numeric_limits::quiet_NaN ()); + return (std::numeric_limits::max ()); + } + + directedOrthogonalAxis (fitted_normal, input_->at (index).getVector3fMap (), + surface_->at (min_normal_index).getVector3fMap (), x_axis); + y_axis = fitted_normal.cross (x_axis); + + lrf.row (0).matrix () = x_axis; + lrf.row (1).matrix () = y_axis; + //z axis already set + + return (min_normal_cos); + }// if(!find_holes_) + + //check if there is at least a hole + bool is_hole_present = false; + for (int i = 0; i < check_margin_array_size_; i++) + { + if (!check_margin_array_[i]) + { + is_hole_present = true; + break; + } + } + + if (!is_hole_present) + { + if (best_point_found_on_margins) + { + //if most inclined normal is on support margin + directedOrthogonalAxis (fitted_normal, input_->at (index).getVector3fMap (), best_margin_point, x_axis); + y_axis = fitted_normal.cross (x_axis); + + lrf.row (0).matrix () = x_axis; + lrf.row (1).matrix () = y_axis; + //z axis already set + + return (min_normal_cos); + } + + // Check if we are not in a degenerate case (all the neighboring normals are NaNs) + if (min_normal_index == -1) + { + lrf.setConstant (std::numeric_limits::quiet_NaN ()); + return (std::numeric_limits::max ()); + } + + //find orthogonal axis directed to minNormalIndex point projection on plane with fittedNormal as axis + directedOrthogonalAxis (fitted_normal, input_->at (index).getVector3fMap (), + surface_->at (min_normal_index).getVector3fMap (), x_axis); + y_axis = fitted_normal.cross (x_axis); + + lrf.row (0).matrix () = x_axis; + lrf.row (1).matrix () = y_axis; + //z axis already set + + return (min_normal_cos); + }//if (!is_hole_present) + + //case hole found + //find missing region + float angle = 0.0; + int hole_end; + int hole_first; + + //find first no border pie + int first_no_border = -1; + if (check_margin_array_[check_margin_array_size_ - 1]) + { + first_no_border = 0; + } + else + { + for (int i = 0; i < check_margin_array_size_; i++) + { + if (check_margin_array_[i]) + { + first_no_border = i; + break; + } + } + } + + //float steep_prob = 0.0; + float max_hole_prob = -std::numeric_limits::max (); + + //find holes + for (int ch = first_no_border; ch < check_margin_array_size_; ch++) + { + if (!check_margin_array_[ch]) + { + //border beginning found + hole_first = ch; + hole_end = hole_first + 1; + while (!check_margin_array_[hole_end % check_margin_array_size_]) + { + ++hole_end; + } + //border end found, find angle + + if ((hole_end - hole_first) > 0) + { + //check if hole can be a shapeness hole + int previous_hole = (((hole_first - 1) < 0) ? (hole_first - 1) + check_margin_array_size_ : (hole_first - 1)) + % check_margin_array_size_; + int following_hole = (hole_end) % check_margin_array_size_; + float normal_begin = margin_array_max_angle_normal_[previous_hole]; + float normal_end = margin_array_min_angle_normal_[following_hole]; + normal_begin -= min_normal_cos; + normal_end -= min_normal_cos; + normal_begin = normal_begin / (1.0f - min_normal_cos); + normal_end = normal_end / (1.0f - min_normal_cos); + normal_begin = 1.0f - normal_begin; + normal_end = 1.0f - normal_end; + + //evaluate P(Hole); + float hole_width = 0.0f; + if (following_hole < previous_hole) + { + hole_width = margin_array_min_angle_[following_hole] + 2 * static_cast (M_PI) + - margin_array_max_angle_[previous_hole]; + } + else + { + hole_width = margin_array_min_angle_[following_hole] - margin_array_max_angle_[previous_hole]; + } + float hole_prob = hole_width / (2 * static_cast (M_PI)); + + //evaluate P(zmin|Hole) + float steep_prob = (normal_end + normal_begin) / 2.0f; + + //check hole prob and after that, check steepThresh + + if (hole_prob > hole_size_prob_thresh_) + { + if (steep_prob > steep_thresh_) + { + if (hole_prob > max_hole_prob) + { + max_hole_prob = hole_prob; + + float angle_weight = ((normal_end - normal_begin) + 1.0f) / 2.0f; + if (following_hole < previous_hole) + { + angle = margin_array_max_angle_[previous_hole] + (margin_array_min_angle_[following_hole] + 2 + * static_cast (M_PI) - margin_array_max_angle_[previous_hole]) * angle_weight; + } + else + { + angle = margin_array_max_angle_[previous_hole] + (margin_array_min_angle_[following_hole] + - margin_array_max_angle_[previous_hole]) * angle_weight; + } + } + } + } + } //(hole_end-hole_first) > 0 + + if (hole_end >= check_margin_array_size_) + { + break; + } + else + { + ch = hole_end - 1; + } + } + } + + if (max_hole_prob > -std::numeric_limits::max ()) + { + //hole found + Eigen::AngleAxisf rotation = Eigen::AngleAxisf (angle, fitted_normal); + x_axis = rotation * x_axis; + + min_normal_cos -= 10.0f; + } + else + { + if (best_point_found_on_margins) + { + //if most inclined normal is on support margin + directedOrthogonalAxis (fitted_normal, input_->at (index).getVector3fMap (), best_margin_point, x_axis); + } + else + { + // Check if we are not in a degenerate case (all the neighboring normals are NaNs) + if (min_normal_index == -1) + { + lrf.setConstant (std::numeric_limits::quiet_NaN ()); + return (std::numeric_limits::max ()); + } + + //find orthogonal axis directed to minNormalIndex point projection on plane with fittedNormal as axis + directedOrthogonalAxis (fitted_normal, input_->at (index).getVector3fMap (), + surface_->at (min_normal_index).getVector3fMap (), x_axis); + } + } + + y_axis = fitted_normal.cross (x_axis); + + lrf.row (0).matrix () = x_axis; + lrf.row (1).matrix () = y_axis; + //z axis already set + + return (min_normal_cos); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BOARDLocalReferenceFrameEstimation::computeFeature (PointCloudOut &output) +{ + //check whether used with search radius or search k-neighbors + if (this->getKSearch () != 0) + { + PCL_ERROR( + "[pcl::%s::computeFeature] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n", + getClassName().c_str()); + return; + } + + this->resetData (); + for (size_t point_idx = 0; point_idx < indices_->size (); ++point_idx) + { + Eigen::Matrix3f currentLrf; + PointOutT &rf = output[point_idx]; + + //rf.confidence = computePointLRF (*indices_[point_idx], currentLrf); + //if (rf.confidence == std::numeric_limits::max ()) + if (computePointLRF ((*indices_)[point_idx], currentLrf) == std::numeric_limits::max ()) + { + output.is_dense = false; + } + + for (int d = 0; d < 3; ++d) + { + rf.x_axis[d] = currentLrf (0, d); + rf.y_axis[d] = currentLrf (1, d); + rf.z_axis[d] = currentLrf (2, d); + } + } +} + +#define PCL_INSTANTIATE_BOARDLocalReferenceFrameEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::BOARDLocalReferenceFrameEstimation; + +#endif // PCL_FEATURES_IMPL_BOARD_H_ diff --git a/pcl-1.7/pcl/features/impl/boundary.hpp b/pcl-1.7/pcl/features/impl/boundary.hpp new file mode 100644 index 0000000..0bcdf9e --- /dev/null +++ b/pcl-1.7/pcl/features/impl/boundary.hpp @@ -0,0 +1,176 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_IMPL_BOUNDARY_H_ +#define PCL_FEATURES_IMPL_BOUNDARY_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::BoundaryEstimation::isBoundaryPoint ( + const pcl::PointCloud &cloud, int q_idx, + const std::vector &indices, + const Eigen::Vector4f &u, const Eigen::Vector4f &v, + const float angle_threshold) +{ + return (isBoundaryPoint (cloud, cloud.points[q_idx], indices, u, v, angle_threshold)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::BoundaryEstimation::isBoundaryPoint ( + const pcl::PointCloud &cloud, const PointInT &q_point, + const std::vector &indices, + const Eigen::Vector4f &u, const Eigen::Vector4f &v, + const float angle_threshold) +{ + if (indices.size () < 3) + return (false); + + if (!pcl_isfinite (q_point.x) || !pcl_isfinite (q_point.y) || !pcl_isfinite (q_point.z)) + return (false); + + // Compute the angles between each neighboring point and the query point itself + std::vector angles (indices.size ()); + float max_dif = FLT_MIN, dif; + int cp = 0; + + for (size_t i = 0; i < indices.size (); ++i) + { + if (!pcl_isfinite (cloud.points[indices[i]].x) || + !pcl_isfinite (cloud.points[indices[i]].y) || + !pcl_isfinite (cloud.points[indices[i]].z)) + continue; + + Eigen::Vector4f delta = cloud.points[indices[i]].getVector4fMap () - q_point.getVector4fMap (); + if (delta == Eigen::Vector4f::Zero()) + continue; + + angles[cp++] = atan2f (v.dot (delta), u.dot (delta)); // the angles are fine between -PI and PI too + } + if (cp == 0) + return (false); + + angles.resize (cp); + std::sort (angles.begin (), angles.end ()); + + // Compute the maximal angle difference between two consecutive angles + for (size_t i = 0; i < angles.size () - 1; ++i) + { + dif = angles[i + 1] - angles[i]; + if (max_dif < dif) + max_dif = dif; + } + // Get the angle difference between the last and the first + dif = 2 * static_cast (M_PI) - angles[angles.size () - 1] + angles[0]; + if (max_dif < dif) + max_dif = dif; + + // Check results + if (max_dif > angle_threshold) + return (true); + else + return (false); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BoundaryEstimation::computeFeature (PointCloudOut &output) +{ + // Allocate enough space to hold the results + // \note This resize is irrelevant for a radiusSearch (). + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + Eigen::Vector4f u = Eigen::Vector4f::Zero (), v = Eigen::Vector4f::Zero (); + + output.is_dense = true; + // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense + if (input_->is_dense) + { + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) + { + output.points[idx].boundary_point = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + continue; + } + + // Obtain a coordinate system on the least-squares plane + //v = normals_->points[(*indices_)[idx]].getNormalVector4fMap ().unitOrthogonal (); + //u = normals_->points[(*indices_)[idx]].getNormalVector4fMap ().cross3 (v); + getCoordinateSystemOnPlane (normals_->points[(*indices_)[idx]], u, v); + + // Estimate whether the point is lying on a boundary surface or not + output.points[idx].boundary_point = isBoundaryPoint (*surface_, input_->points[(*indices_)[idx]], nn_indices, u, v, angle_threshold_); + } + } + else + { + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + if (!isFinite ((*input_)[(*indices_)[idx]]) || + this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) + { + output.points[idx].boundary_point = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + continue; + } + + // Obtain a coordinate system on the least-squares plane + //v = normals_->points[(*indices_)[idx]].getNormalVector4fMap ().unitOrthogonal (); + //u = normals_->points[(*indices_)[idx]].getNormalVector4fMap ().cross3 (v); + getCoordinateSystemOnPlane (normals_->points[(*indices_)[idx]], u, v); + + // Estimate whether the point is lying on a boundary surface or not + output.points[idx].boundary_point = isBoundaryPoint (*surface_, input_->points[(*indices_)[idx]], nn_indices, u, v, angle_threshold_); + } + } +} + +#define PCL_INSTANTIATE_BoundaryEstimation(PointInT,PointNT,PointOutT) template class PCL_EXPORTS pcl::BoundaryEstimation; + +#endif // PCL_FEATURES_IMPL_BOUNDARY_H_ + diff --git a/pcl-1.7/pcl/features/impl/cppf.hpp b/pcl-1.7/pcl/features/impl/cppf.hpp new file mode 100644 index 0000000..5e2174c --- /dev/null +++ b/pcl-1.7/pcl/features/impl/cppf.hpp @@ -0,0 +1,124 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2013, Martin Szarski + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_FEATURES_IMPL_CPPF_H_ +#define PCL_FEATURES_IMPL_CPPF_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::CPPFEstimation::CPPFEstimation () + : FeatureFromNormals () +{ + feature_name_ = "CPPFEstimation"; + // Slight hack in order to pass the check for the presence of a search method in Feature::initCompute () + Feature::tree_.reset (new pcl::search::KdTree ()); + Feature::search_radius_ = 1.0f; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::CPPFEstimation::computeFeature (PointCloudOut &output) +{ + // Initialize output container - overwrite the sizes done by Feature::initCompute () + output.points.resize (indices_->size () * input_->points.size ()); + output.height = 1; + output.width = static_cast (output.points.size ()); + output.is_dense = true; + + // Compute point pair features for every pair of points in the cloud + for (size_t index_i = 0; index_i < indices_->size (); ++index_i) + { + size_t i = (*indices_)[index_i]; + for (size_t j = 0 ; j < input_->points.size (); ++j) + { + PointOutT p; + if (i != j) + { + if ( + pcl::computeCPPFPairFeature (input_->points[i].getVector4fMap (), + normals_->points[i].getNormalVector4fMap (), + input_->points[i].getRGBVector4i (), + input_->points[j].getVector4fMap (), + normals_->points[j].getNormalVector4fMap (), + input_->points[j].getRGBVector4i (), + p.f1, p.f2, p.f3, p.f4, p.f5, p.f6, p.f7, p.f8, p.f9, p.f10)) + { + // Calculate alpha_m angle + Eigen::Vector3f model_reference_point = input_->points[i].getVector3fMap (), + model_reference_normal = normals_->points[i].getNormalVector3fMap (), + model_point = input_->points[j].getVector3fMap (); + Eigen::AngleAxisf rotation_mg (acosf (model_reference_normal.dot (Eigen::Vector3f::UnitX ())), + model_reference_normal.cross (Eigen::Vector3f::UnitX ()).normalized ()); + Eigen::Affine3f transform_mg = Eigen::Translation3f ( rotation_mg * ((-1) * model_reference_point)) * rotation_mg; + + Eigen::Vector3f model_point_transformed = transform_mg * model_point; + float angle = atan2f ( -model_point_transformed(2), model_point_transformed(1)); + if (sin (angle) * model_point_transformed(2) < 0.0f) + angle *= (-1); + p.alpha_m = -angle; + } + else + { + PCL_ERROR ("[pcl::%s::computeFeature] Computing pair feature vector between points %lu and %lu went wrong.\n", getClassName ().c_str (), i, j); + p.f1 = p.f2 = p.f3 = p.f4 = p.f5 = p.f6 = p.f7 = p.f8 = p.f9 = p.f10 = p.alpha_m = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + } + } + // Do not calculate the feature for identity pairs (i, i) as they are not used + // in the following computations + else + { + p.f1 = p.f2 = p.f3 = p.f4 = p.f5 = p.f6 = p.f7 = p.f8 = p.f9 = p.f10 = p.alpha_m = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + } + + output.points[index_i*input_->points.size () + j] = p; + } + } +} + +#define PCL_INSTANTIATE_CPPFEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::CPPFEstimation; + + +#endif // PCL_FEATURES_IMPL_CPPF_H_ diff --git a/pcl-1.7/pcl/features/impl/crh.hpp b/pcl-1.7/pcl/features/impl/crh.hpp new file mode 100644 index 0000000..8af466c --- /dev/null +++ b/pcl-1.7/pcl/features/impl/crh.hpp @@ -0,0 +1,136 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: cvfh.hpp 5311 2012-03-26 22:02:04Z aaldoma $ + * + */ + +#ifndef PCL_FEATURES_IMPL_CRH_H_ +#define PCL_FEATURES_IMPL_CRH_H_ + +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::CRHEstimation::computeFeature (PointCloudOut &output) +{ + // Check if input was set + if (!normals_) + { + PCL_ERROR ("[pcl::%s::computeFeature] No input dataset containing normals was given!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + if (normals_->points.size () != surface_->points.size ()) + { + PCL_ERROR ("[pcl::%s::computeFeature] The number of points in the input dataset differs from the number of points in the dataset containing the normals!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + Eigen::Vector3f plane_normal; + plane_normal[0] = -centroid_[0]; + plane_normal[1] = -centroid_[1]; + plane_normal[2] = -centroid_[2]; + Eigen::Vector3f z_vector = Eigen::Vector3f::UnitZ (); + plane_normal.normalize (); + Eigen::Vector3f axis = plane_normal.cross (z_vector); + double rotation = -asin (axis.norm ()); + axis.normalize (); + + int nbins = nbins_; + int bin_angle = 360 / nbins; + + Eigen::Affine3f transformPC (Eigen::AngleAxisf (static_cast (rotation), axis)); + + pcl::PointCloud grid; + grid.points.resize (indices_->size ()); + + for (size_t i = 0; i < indices_->size (); i++) + { + grid.points[i].getVector4fMap () = surface_->points[(*indices_)[i]].getVector4fMap (); + grid.points[i].getNormalVector4fMap () = normals_->points[(*indices_)[i]].getNormalVector4fMap (); + } + + pcl::transformPointCloudWithNormals (grid, grid, transformPC); + + //fill spatial data vector + kiss_fft_scalar * spatial_data = new kiss_fft_scalar[nbins]; + float sum_w = 0, w = 0; + int bin = 0; + for (size_t i = 0; i < grid.points.size (); ++i) + { + bin = static_cast ((((atan2 (grid.points[i].normal_y, grid.points[i].normal_x) + M_PI) * 180 / M_PI) / bin_angle)) % nbins; + w = sqrtf (grid.points[i].normal_y * grid.points[i].normal_y + grid.points[i].normal_x * grid.points[i].normal_x); + sum_w += w; + spatial_data[bin] += w; + } + + for (int i = 0; i < nbins; ++i) + spatial_data[i] /= sum_w; + + kiss_fft_cpx * freq_data = new kiss_fft_cpx[nbins / 2 + 1]; + kiss_fftr_cfg mycfg = kiss_fftr_alloc (nbins, 0, NULL, NULL); + kiss_fftr (mycfg, spatial_data, freq_data); + + output.points.resize (1); + output.width = output.height = 1; + + output.points[0].histogram[0] = freq_data[0].r / freq_data[0].r; //dc + int k = 1; + for (int i = 1; i < (nbins / 2); i++, k += 2) + { + output.points[0].histogram[k] = freq_data[i].r / freq_data[0].r; + output.points[0].histogram[k + 1] = freq_data[i].i / freq_data[0].r; + } + + output.points[0].histogram[nbins - 1] = freq_data[nbins / 2].r / freq_data[0].r; //nyquist + + delete[] spatial_data; + delete[] freq_data; + +} + +#define PCL_INSTANTIATE_CRHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::CRHEstimation; + +#endif // PCL_FEATURES_IMPL_CRH_H_ diff --git a/pcl-1.7/pcl/features/impl/cvfh.hpp b/pcl-1.7/pcl/features/impl/cvfh.hpp new file mode 100644 index 0000000..45fa76f --- /dev/null +++ b/pcl-1.7/pcl/features/impl/cvfh.hpp @@ -0,0 +1,339 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_IMPL_CVFH_H_ +#define PCL_FEATURES_IMPL_CVFH_H_ + +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::CVFHEstimation::compute (PointCloudOut &output) +{ + if (!Feature::initCompute ()) + { + output.width = output.height = 0; + output.points.clear (); + return; + } + // Resize the output dataset + // Important! We should only allocate precisely how many elements we will need, otherwise + // we risk at pre-allocating too much memory which could lead to bad_alloc + // (see http://dev.pointclouds.org/issues/657) + output.width = output.height = 1; + output.points.resize (1); + + // Perform the actual feature computation + computeFeature (output); + + Feature::deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::CVFHEstimation::extractEuclideanClustersSmooth ( + const pcl::PointCloud &cloud, + const pcl::PointCloud &normals, + float tolerance, + const pcl::search::Search::Ptr &tree, + std::vector &clusters, + double eps_angle, + unsigned int min_pts_per_cluster, + unsigned int max_pts_per_cluster) +{ + if (tree->getInputCloud ()->points.size () != cloud.points.size ()) + { + PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset (%lu) than the input cloud (%lu)!\n", tree->getInputCloud ()->points.size (), cloud.points.size ()); + return; + } + if (cloud.points.size () != normals.points.size ()) + { + PCL_ERROR ("[pcl::extractEuclideanClusters] Number of points in the input point cloud (%lu) different than normals (%lu)!\n", cloud.points.size (), normals.points.size ()); + return; + } + + // Create a bool vector of processed point indices, and initialize it to false + std::vector processed (cloud.points.size (), false); + + std::vector nn_indices; + std::vector nn_distances; + // Process all points in the indices vector + for (int i = 0; i < static_cast (cloud.points.size ()); ++i) + { + if (processed[i]) + continue; + + std::vector seed_queue; + int sq_idx = 0; + seed_queue.push_back (i); + + processed[i] = true; + + while (sq_idx < static_cast (seed_queue.size ())) + { + // Search for sq_idx + if (!tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances)) + { + sq_idx++; + continue; + } + + for (size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx + { + if (processed[nn_indices[j]]) // Has this point been processed before ? + continue; + + //processed[nn_indices[j]] = true; + // [-1;1] + + double dot_p = normals.points[seed_queue[sq_idx]].normal[0] * normals.points[nn_indices[j]].normal[0] + + normals.points[seed_queue[sq_idx]].normal[1] * normals.points[nn_indices[j]].normal[1] + + normals.points[seed_queue[sq_idx]].normal[2] * normals.points[nn_indices[j]].normal[2]; + + if (fabs (acos (dot_p)) < eps_angle) + { + processed[nn_indices[j]] = true; + seed_queue.push_back (nn_indices[j]); + } + } + + sq_idx++; + } + + // If this queue is satisfactory, add to the clusters + if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster) + { + pcl::PointIndices r; + r.indices.resize (seed_queue.size ()); + for (size_t j = 0; j < seed_queue.size (); ++j) + r.indices[j] = seed_queue[j]; + + std::sort (r.indices.begin (), r.indices.end ()); + r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ()); + + r.header = cloud.header; + clusters.push_back (r); // We could avoid a copy by working directly in the vector + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::CVFHEstimation::filterNormalsWithHighCurvature ( + const pcl::PointCloud & cloud, + std::vector &indices_to_use, + std::vector &indices_out, + std::vector &indices_in, + float threshold) +{ + indices_out.resize (cloud.points.size ()); + indices_in.resize (cloud.points.size ()); + + size_t in, out; + in = out = 0; + + for (int i = 0; i < static_cast (indices_to_use.size ()); i++) + { + if (cloud.points[indices_to_use[i]].curvature > threshold) + { + indices_out[out] = indices_to_use[i]; + out++; + } + else + { + indices_in[in] = indices_to_use[i]; + in++; + } + } + + indices_out.resize (out); + indices_in.resize (in); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::CVFHEstimation::computeFeature (PointCloudOut &output) +{ + // Check if input was set + if (!normals_) + { + PCL_ERROR ("[pcl::%s::computeFeature] No input dataset containing normals was given!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + if (normals_->points.size () != surface_->points.size ()) + { + PCL_ERROR ("[pcl::%s::computeFeature] The number of points in the input dataset differs from the number of points in the dataset containing the normals!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + centroids_dominant_orientations_.clear (); + + // ---[ Step 0: remove normals with high curvature + std::vector indices_out; + std::vector indices_in; + filterNormalsWithHighCurvature (*normals_, *indices_, indices_out, indices_in, curv_threshold_); + + pcl::PointCloud::Ptr normals_filtered_cloud (new pcl::PointCloud ()); + normals_filtered_cloud->width = static_cast (indices_in.size ()); + normals_filtered_cloud->height = 1; + normals_filtered_cloud->points.resize (normals_filtered_cloud->width); + + for (size_t i = 0; i < indices_in.size (); ++i) + { + normals_filtered_cloud->points[i].x = surface_->points[indices_in[i]].x; + normals_filtered_cloud->points[i].y = surface_->points[indices_in[i]].y; + normals_filtered_cloud->points[i].z = surface_->points[indices_in[i]].z; + } + + std::vector clusters; + + if(normals_filtered_cloud->points.size() >= min_points_) + { + //recompute normals and use them for clustering + KdTreePtr normals_tree_filtered (new pcl::search::KdTree (false)); + normals_tree_filtered->setInputCloud (normals_filtered_cloud); + + + pcl::NormalEstimation n3d; + n3d.setRadiusSearch (radius_normals_); + n3d.setSearchMethod (normals_tree_filtered); + n3d.setInputCloud (normals_filtered_cloud); + n3d.compute (*normals_filtered_cloud); + + KdTreePtr normals_tree (new pcl::search::KdTree (false)); + normals_tree->setInputCloud (normals_filtered_cloud); + + extractEuclideanClustersSmooth (*normals_filtered_cloud, + *normals_filtered_cloud, + cluster_tolerance_, + normals_tree, + clusters, + eps_angle_threshold_, + static_cast (min_points_)); + + } + + VFHEstimator vfh; + vfh.setInputCloud (surface_); + vfh.setInputNormals (normals_); + vfh.setIndices(indices_); + vfh.setSearchMethod (this->tree_); + vfh.setUseGivenNormal (true); + vfh.setUseGivenCentroid (true); + vfh.setNormalizeBins (normalize_bins_); + vfh.setNormalizeDistance (true); + vfh.setFillSizeComponent (true); + output.height = 1; + + // ---[ Step 1b : check if any dominant cluster was found + if (clusters.size () > 0) + { // ---[ Step 1b.1 : If yes, compute CVFH using the cluster information + + for (size_t i = 0; i < clusters.size (); ++i) //for each cluster + { + Eigen::Vector4f avg_normal = Eigen::Vector4f::Zero (); + Eigen::Vector4f avg_centroid = Eigen::Vector4f::Zero (); + + for (size_t j = 0; j < clusters[i].indices.size (); j++) + { + avg_normal += normals_filtered_cloud->points[clusters[i].indices[j]].getNormalVector4fMap (); + avg_centroid += normals_filtered_cloud->points[clusters[i].indices[j]].getVector4fMap (); + } + + avg_normal /= static_cast (clusters[i].indices.size ()); + avg_centroid /= static_cast (clusters[i].indices.size ()); + + Eigen::Vector4f centroid_test; + pcl::compute3DCentroid (*normals_filtered_cloud, centroid_test); + avg_normal.normalize (); + + Eigen::Vector3f avg_norm (avg_normal[0], avg_normal[1], avg_normal[2]); + Eigen::Vector3f avg_dominant_centroid (avg_centroid[0], avg_centroid[1], avg_centroid[2]); + + //append normal and centroid for the clusters + dominant_normals_.push_back (avg_norm); + centroids_dominant_orientations_.push_back (avg_dominant_centroid); + } + + //compute modified VFH for all dominant clusters and add them to the list! + output.points.resize (dominant_normals_.size ()); + output.width = static_cast (dominant_normals_.size ()); + + for (size_t i = 0; i < dominant_normals_.size (); ++i) + { + //configure VFH computation for CVFH + vfh.setNormalToUse (dominant_normals_[i]); + vfh.setCentroidToUse (centroids_dominant_orientations_[i]); + pcl::PointCloud vfh_signature; + vfh.compute (vfh_signature); + output.points[i] = vfh_signature.points[0]; + } + } + else + { // ---[ Step 1b.1 : If no, compute CVFH using all the object points + Eigen::Vector4f avg_centroid; + pcl::compute3DCentroid (*surface_, avg_centroid); + Eigen::Vector3f cloud_centroid (avg_centroid[0], avg_centroid[1], avg_centroid[2]); + centroids_dominant_orientations_.push_back (cloud_centroid); + + //configure VFH computation for CVFH using all object points + vfh.setCentroidToUse (cloud_centroid); + vfh.setUseGivenNormal (false); + + pcl::PointCloud vfh_signature; + vfh.compute (vfh_signature); + + output.points.resize (1); + output.width = 1; + + output.points[0] = vfh_signature.points[0]; + } +} + +#define PCL_INSTANTIATE_CVFHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::CVFHEstimation; + +#endif // PCL_FEATURES_IMPL_VFH_H_ diff --git a/pcl-1.7/pcl/features/impl/don.hpp b/pcl-1.7/pcl/features/impl/don.hpp new file mode 100644 index 0000000..4ac6f51 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/don.hpp @@ -0,0 +1,104 @@ + /* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Yani Ioannou + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_FILTERS_DON_IMPL_H_ +#define PCL_FILTERS_DON_IMPL_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::DifferenceOfNormalsEstimation::initCompute () +{ + // Check if input normals are set + if (!input_normals_small_) + { + PCL_ERROR ("[pcl::%s::initCompute] No input dataset containing small support radius normals was given!\n", getClassName().c_str ()); + Feature::deinitCompute(); + return (false); + } + + if (!input_normals_large_) + { + PCL_ERROR ("[pcl::%s::initCompute] No input dataset containing large support radius normals was given!\n", getClassName().c_str ()); + Feature::deinitCompute(); + return (false); + } + + // Check if the size of normals is the same as the size of the surface + if (input_normals_small_->points.size () != input_->points.size ()) + { + PCL_ERROR ("[pcl::%s::initCompute] ", getClassName().c_str ()); + PCL_ERROR ("The number of points in the input dataset differs from "); + PCL_ERROR ("the number of points in the dataset containing the small support radius normals!\n"); + Feature::deinitCompute (); + return (false); + } + + if (input_normals_large_->points.size () != input_->points.size ()) + { + PCL_ERROR ("[pcl::%s::initCompute] ", getClassName().c_str ()); + PCL_ERROR ("The number of points in the input dataset differs from "); + PCL_ERROR ("the number of points in the dataset containing the large support radius normals!\n"); + Feature::deinitCompute (); + return (false); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::DifferenceOfNormalsEstimation::computeFeature (PointCloudOut &output) +{ + //perform DoN subtraction and return results + for (size_t point_id = 0; point_id < input_->points.size (); ++point_id) + { + output.points[point_id].getNormalVector3fMap () = (input_normals_small_->points[point_id].getNormalVector3fMap () + - input_normals_large_->points[point_id].getNormalVector3fMap ()) / 2.0; + if(!pcl_isfinite (output.points[point_id].normal_x) || + !pcl_isfinite (output.points[point_id].normal_y) || + !pcl_isfinite (output.points[point_id].normal_z)){ + output.points[point_id].getNormalVector3fMap () = Eigen::Vector3f(0,0,0); + } + output.points[point_id].curvature = output.points[point_id].getNormalVector3fMap ().norm(); + } +} + + +#define PCL_INSTANTIATE_DifferenceOfNormalsEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::DifferenceOfNormalsEstimation; + +#endif // PCL_FILTERS_DON_H_ diff --git a/pcl-1.7/pcl/features/impl/esf.hpp b/pcl-1.7/pcl/features/impl/esf.hpp new file mode 100644 index 0000000..f36ab4b --- /dev/null +++ b/pcl-1.7/pcl/features/impl/esf.hpp @@ -0,0 +1,554 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: pfh.hpp 5027 2012-03-12 03:10:45Z rusu $ + * + */ + +#ifndef PCL_FEATURES_IMPL_ESF_H_ +#define PCL_FEATURES_IMPL_ESF_H_ + +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ESFEstimation::computeESF ( + PointCloudIn &pc, std::vector &hist) +{ + const int binsize = 64; + unsigned int sample_size = 20000; + srand (static_cast (time (0))); + int maxindex = static_cast (pc.points.size ()); + + int index1, index2, index3; + std::vector d2v, d1v, d3v, wt_d3; + std::vector wt_d2; + d1v.reserve (sample_size); + d2v.reserve (sample_size * 3); + d3v.reserve (sample_size); + wt_d2.reserve (sample_size * 3); + wt_d3.reserve (sample_size); + + float h_in[binsize] = {0}; + float h_out[binsize] = {0}; + float h_mix[binsize] = {0}; + float h_mix_ratio[binsize] = {0}; + + float h_a3_in[binsize] = {0}; + float h_a3_out[binsize] = {0}; + float h_a3_mix[binsize] = {0}; + + float h_d3_in[binsize] = {0}; + float h_d3_out[binsize] = {0}; + float h_d3_mix[binsize] = {0}; + + float ratio=0.0; + float pih = static_cast(M_PI) / 2.0f; + float a,b,c,s; + int th1,th2,th3; + int vxlcnt = 0; + int pcnt1,pcnt2,pcnt3; + for (size_t nn_idx = 0; nn_idx < sample_size; ++nn_idx) + { + // get a new random point + index1 = rand()%maxindex; + index2 = rand()%maxindex; + index3 = rand()%maxindex; + + if (index1==index2 || index1 == index3 || index2 == index3) + { + nn_idx--; + continue; + } + + Eigen::Vector4f p1 = pc.points[index1].getVector4fMap (); + Eigen::Vector4f p2 = pc.points[index2].getVector4fMap (); + Eigen::Vector4f p3 = pc.points[index3].getVector4fMap (); + + // A3 + Eigen::Vector4f v21 (p2 - p1); + Eigen::Vector4f v31 (p3 - p1); + Eigen::Vector4f v23 (p2 - p3); + a = v21.norm (); b = v31.norm (); c = v23.norm (); s = (a+b+c) * 0.5f; + if (s * (s-a) * (s-b) * (s-c) <= 0.001f) + continue; + + v21.normalize (); + v31.normalize (); + v23.normalize (); + + //TODO: .dot gives nan's + th1 = static_cast (pcl_round (acos (fabs (v21.dot (v31))) / pih * (binsize-1))); + th2 = static_cast (pcl_round (acos (fabs (v23.dot (v31))) / pih * (binsize-1))); + th3 = static_cast (pcl_round (acos (fabs (v23.dot (v21))) / pih * (binsize-1))); + if (th1 < 0 || th1 >= binsize) + { + nn_idx--; + continue; + } + if (th2 < 0 || th2 >= binsize) + { + nn_idx--; + continue; + } + if (th3 < 0 || th3 >= binsize) + { + nn_idx--; + continue; + } + + // D2 + d2v.push_back (pcl::euclideanDistance (pc.points[index1], pc.points[index2])); + d2v.push_back (pcl::euclideanDistance (pc.points[index1], pc.points[index3])); + d2v.push_back (pcl::euclideanDistance (pc.points[index2], pc.points[index3])); + + int vxlcnt_sum = 0; + int p_cnt = 0; + // IN, OUT, MIXED, Ratio line tracing, index1->index2 + { + const int xs = p1[0] < 0.0? static_cast(floor(p1[0])+GRIDSIZE_H): static_cast(ceil(p1[0])+GRIDSIZE_H-1); + const int ys = p1[1] < 0.0? static_cast(floor(p1[1])+GRIDSIZE_H): static_cast(ceil(p1[1])+GRIDSIZE_H-1); + const int zs = p1[2] < 0.0? static_cast(floor(p1[2])+GRIDSIZE_H): static_cast(ceil(p1[2])+GRIDSIZE_H-1); + const int xt = p2[0] < 0.0? static_cast(floor(p2[0])+GRIDSIZE_H): static_cast(ceil(p2[0])+GRIDSIZE_H-1); + const int yt = p2[1] < 0.0? static_cast(floor(p2[1])+GRIDSIZE_H): static_cast(ceil(p2[1])+GRIDSIZE_H-1); + const int zt = p2[2] < 0.0? static_cast(floor(p2[2])+GRIDSIZE_H): static_cast(ceil(p2[2])+GRIDSIZE_H-1); + wt_d2.push_back (this->lci (xs, ys, zs, xt, yt, zt, ratio, vxlcnt, pcnt1)); + if (wt_d2.back () == 2) + h_mix_ratio[static_cast (pcl_round (ratio * (binsize-1)))]++; + vxlcnt_sum += vxlcnt; + p_cnt += pcnt1; + } + // IN, OUT, MIXED, Ratio line tracing, index1->index3 + { + const int xs = p1[0] < 0.0? static_cast(floor(p1[0])+GRIDSIZE_H): static_cast(ceil(p1[0])+GRIDSIZE_H-1); + const int ys = p1[1] < 0.0? static_cast(floor(p1[1])+GRIDSIZE_H): static_cast(ceil(p1[1])+GRIDSIZE_H-1); + const int zs = p1[2] < 0.0? static_cast(floor(p1[2])+GRIDSIZE_H): static_cast(ceil(p1[2])+GRIDSIZE_H-1); + const int xt = p3[0] < 0.0? static_cast(floor(p3[0])+GRIDSIZE_H): static_cast(ceil(p3[0])+GRIDSIZE_H-1); + const int yt = p3[1] < 0.0? static_cast(floor(p3[1])+GRIDSIZE_H): static_cast(ceil(p3[1])+GRIDSIZE_H-1); + const int zt = p3[2] < 0.0? static_cast(floor(p3[2])+GRIDSIZE_H): static_cast(ceil(p3[2])+GRIDSIZE_H-1); + wt_d2.push_back (this->lci (xs, ys, zs, xt, yt, zt, ratio, vxlcnt, pcnt2)); + if (wt_d2.back () == 2) + h_mix_ratio[static_cast(pcl_round (ratio * (binsize-1)))]++; + vxlcnt_sum += vxlcnt; + p_cnt += pcnt2; + } + // IN, OUT, MIXED, Ratio line tracing, index2->index3 + { + const int xs = p2[0] < 0.0? static_cast(floor(p2[0])+GRIDSIZE_H): static_cast(ceil(p2[0])+GRIDSIZE_H-1); + const int ys = p2[1] < 0.0? static_cast(floor(p2[1])+GRIDSIZE_H): static_cast(ceil(p2[1])+GRIDSIZE_H-1); + const int zs = p2[2] < 0.0? static_cast(floor(p2[2])+GRIDSIZE_H): static_cast(ceil(p2[2])+GRIDSIZE_H-1); + const int xt = p3[0] < 0.0? static_cast(floor(p3[0])+GRIDSIZE_H): static_cast(ceil(p3[0])+GRIDSIZE_H-1); + const int yt = p3[1] < 0.0? static_cast(floor(p3[1])+GRIDSIZE_H): static_cast(ceil(p3[1])+GRIDSIZE_H-1); + const int zt = p3[2] < 0.0? static_cast(floor(p3[2])+GRIDSIZE_H): static_cast(ceil(p3[2])+GRIDSIZE_H-1); + wt_d2.push_back (this->lci (xs,ys,zs,xt,yt,zt,ratio,vxlcnt,pcnt3)); + if (wt_d2.back () == 2) + h_mix_ratio[static_cast(pcl_round(ratio * (binsize-1)))]++; + vxlcnt_sum += vxlcnt; + p_cnt += pcnt3; + } + + // D3 ( herons formula ) + d3v.push_back (sqrtf (sqrtf (s * (s-a) * (s-b) * (s-c)))); + if (vxlcnt_sum <= 21) + { + wt_d3.push_back (0); + h_a3_out[th1] += static_cast (pcnt3) / 32.0f; + h_a3_out[th2] += static_cast (pcnt1) / 32.0f; + h_a3_out[th3] += static_cast (pcnt2) / 32.0f; + } + else + if (p_cnt - vxlcnt_sum < 4) + { + h_a3_in[th1] += static_cast (pcnt3) / 32.0f; + h_a3_in[th2] += static_cast (pcnt1) / 32.0f; + h_a3_in[th3] += static_cast (pcnt2) / 32.0f; + wt_d3.push_back (1); + } + else + { + h_a3_mix[th1] += static_cast (pcnt3) / 32.0f; + h_a3_mix[th2] += static_cast (pcnt1) / 32.0f; + h_a3_mix[th3] += static_cast (pcnt2) / 32.0f; + wt_d3.push_back (static_cast (vxlcnt_sum) / static_cast (p_cnt)); + } + } + // Normalizing, get max + float maxd2 = 0; + float maxd3 = 0; + + for (size_t nn_idx = 0; nn_idx < sample_size; ++nn_idx) + { + // get max of Dx + if (d2v[nn_idx] > maxd2) + maxd2 = d2v[nn_idx]; + if (d2v[sample_size + nn_idx] > maxd2) + maxd2 = d2v[sample_size + nn_idx]; + if (d2v[sample_size*2 +nn_idx] > maxd2) + maxd2 = d2v[sample_size*2 +nn_idx]; + if (d3v[nn_idx] > maxd3) + maxd3 = d3v[nn_idx]; + } + + // Normalize and create histogram + int index; + for (size_t nn_idx = 0; nn_idx < sample_size; ++nn_idx) + { + if (wt_d3[nn_idx] >= 0.999) // IN + { + index = static_cast(pcl_round (d3v[nn_idx] / maxd3 * (binsize-1))); + if (index >= 0 && index < binsize) + h_d3_in[index]++; + } + else + { + if (wt_d3[nn_idx] <= 0.001) // OUT + { + index = static_cast(pcl_round (d3v[nn_idx] / maxd3 * (binsize-1))); + if (index >= 0 && index < binsize) + h_d3_out[index]++ ; + } + else + { + index = static_cast(pcl_round (d3v[nn_idx] / maxd3 * (binsize-1))); + if (index >= 0 && index < binsize) + h_d3_mix[index]++; + } + } + } + //normalize and create histogram + for (size_t nn_idx = 0; nn_idx < d2v.size(); ++nn_idx ) + { + if (wt_d2[nn_idx] == 0) + h_in[static_cast(pcl_round (d2v[nn_idx] / maxd2 * (binsize-1)))]++ ; + if (wt_d2[nn_idx] == 1) + h_out[static_cast(pcl_round (d2v[nn_idx] / maxd2 * (binsize-1)))]++; + if (wt_d2[nn_idx] == 2) + h_mix[static_cast(pcl_round (d2v[nn_idx] / maxd2 * (binsize-1)))]++ ; + } + + //float weights[10] = {1, 1, 1, 1, 1, 1, 1, 1 , 1 , 1}; + float weights[10] = {0.5f, 0.5f, 0.5f, 0.5f, 0.5f, 1.0f, 1.0f, 2.0f, 2.0f, 2.0f}; + + hist.reserve (binsize * 10); + for (int i = 0; i < binsize; i++) + hist.push_back (h_a3_in[i] * weights[0]); + for (int i = 0; i < binsize; i++) + hist.push_back (h_a3_out[i] * weights[1]); + for (int i = 0; i < binsize; i++) + hist.push_back (h_a3_mix[i] * weights[2]); + + for (int i = 0; i < binsize; i++) + hist.push_back (h_d3_in[i] * weights[3]); + for (int i = 0; i < binsize; i++) + hist.push_back (h_d3_out[i] * weights[4]); + for (int i = 0; i < binsize; i++) + hist.push_back (h_d3_mix[i] * weights[5]); + + for (int i = 0; i < binsize; i++) + hist.push_back (h_in[i]*0.5f * weights[6]); + for (int i = 0; i < binsize; i++) + hist.push_back (h_out[i] * weights[7]); + for (int i = 0; i < binsize; i++) + hist.push_back (h_mix[i] * weights[8]); + for (int i = 0; i < binsize; i++) + hist.push_back (h_mix_ratio[i]*0.5f * weights[9]); + + float sm = 0; + for (size_t i = 0; i < hist.size (); i++) + sm += hist[i]; + + for (size_t i = 0; i < hist.size (); i++) + hist[i] /= sm; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::ESFEstimation::lci ( + const int x1, const int y1, const int z1, + const int x2, const int y2, const int z2, + float &ratio, int &incnt, int &pointcount) +{ + int voxelcount = 0; + int voxel_in = 0; + int act_voxel[3]; + act_voxel[0] = x1; + act_voxel[1] = y1; + act_voxel[2] = z1; + int x_inc, y_inc, z_inc; + int dx = x2 - x1; + int dy = y2 - y1; + int dz = z2 - z1; + if (dx < 0) + x_inc = -1; + else + x_inc = 1; + int l = abs (dx); + if (dy < 0) + y_inc = -1 ; + else + y_inc = 1; + int m = abs (dy); + if (dz < 0) + z_inc = -1 ; + else + z_inc = 1; + int n = abs (dz); + int dx2 = 2 * l; + int dy2 = 2 * m; + int dz2 = 2 * n; + if ((l >= m) & (l >= n)) + { + int err_1 = dy2 - l; + int err_2 = dz2 - l; + for (int i = 1; i(lut_[act_voxel[0]][act_voxel[1]][act_voxel[2]] == 1); + if (err_1 > 0) + { + act_voxel[1] += y_inc; + err_1 -= dx2; + } + if (err_2 > 0) + { + act_voxel[2] += z_inc; + err_2 -= dx2; + } + err_1 += dy2; + err_2 += dz2; + act_voxel[0] += x_inc; + } + } + else if ((m >= l) & (m >= n)) + { + int err_1 = dx2 - m; + int err_2 = dz2 - m; + for (int i=1; i(lut_[act_voxel[0]][act_voxel[1]][act_voxel[2]] == 1); + if (err_1 > 0) + { + act_voxel[0] += x_inc; + err_1 -= dy2; + } + if (err_2 > 0) + { + act_voxel[2] += z_inc; + err_2 -= dy2; + } + err_1 += dx2; + err_2 += dz2; + act_voxel[1] += y_inc; + } + } + else + { + int err_1 = dy2 - n; + int err_2 = dx2 - n; + for (int i=1; i(lut_[act_voxel[0]][act_voxel[1]][act_voxel[2]] == 1); + if (err_1 > 0) + { + act_voxel[1] += y_inc; + err_1 -= dz2; + } + if (err_2 > 0) + { + act_voxel[0] += x_inc; + err_2 -= dz2; + } + err_1 += dy2; + err_2 += dx2; + act_voxel[2] += z_inc; + } + } + voxelcount++; + voxel_in += static_cast(lut_[act_voxel[0]][act_voxel[1]][act_voxel[2]] == 1); + incnt = voxel_in; + pointcount = voxelcount; + + if (voxel_in >= voxelcount-1) + return (0); + + if (voxel_in <= 7) + return (1); + + ratio = static_cast(voxel_in) / static_cast(voxelcount); + return (2); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ESFEstimation::voxelize9 (PointCloudIn &cluster) +{ + int xi,yi,zi,xx,yy,zz; + for (size_t i = 0; i < cluster.points.size (); ++i) + { + xx = cluster.points[i].x<0.0? static_cast(floor(cluster.points[i].x)+GRIDSIZE_H) : static_cast(ceil(cluster.points[i].x)+GRIDSIZE_H-1); + yy = cluster.points[i].y<0.0? static_cast(floor(cluster.points[i].y)+GRIDSIZE_H) : static_cast(ceil(cluster.points[i].y)+GRIDSIZE_H-1); + zz = cluster.points[i].z<0.0? static_cast(floor(cluster.points[i].z)+GRIDSIZE_H) : static_cast(ceil(cluster.points[i].z)+GRIDSIZE_H-1); + + for (int x = -1; x < 2; x++) + for (int y = -1; y < 2; y++) + for (int z = -1; z < 2; z++) + { + xi = xx + x; + yi = yy + y; + zi = zz + z; + + if (yi >= GRIDSIZE || xi >= GRIDSIZE || zi>=GRIDSIZE || yi < 0 || xi < 0 || zi < 0) + { + ; + } + else + this->lut_[xi][yi][zi] = 1; + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ESFEstimation::cleanup9 (PointCloudIn &cluster) +{ + int xi,yi,zi,xx,yy,zz; + for (size_t i = 0; i < cluster.points.size (); ++i) + { + xx = cluster.points[i].x<0.0? static_cast(floor(cluster.points[i].x)+GRIDSIZE_H) : static_cast(ceil(cluster.points[i].x)+GRIDSIZE_H-1); + yy = cluster.points[i].y<0.0? static_cast(floor(cluster.points[i].y)+GRIDSIZE_H) : static_cast(ceil(cluster.points[i].y)+GRIDSIZE_H-1); + zz = cluster.points[i].z<0.0? static_cast(floor(cluster.points[i].z)+GRIDSIZE_H) : static_cast(ceil(cluster.points[i].z)+GRIDSIZE_H-1); + + for (int x = -1; x < 2; x++) + for (int y = -1; y < 2; y++) + for (int z = -1; z < 2; z++) + { + xi = xx + x; + yi = yy + y; + zi = zz + z; + + if (yi >= GRIDSIZE || xi >= GRIDSIZE || zi>=GRIDSIZE || yi < 0 || xi < 0 || zi < 0) + { + ; + } + else + this->lut_[xi][yi][zi] = 0; + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ESFEstimation::scale_points_unit_sphere ( + const pcl::PointCloud &pc, float scalefactor, Eigen::Vector4f& centroid) +{ + pcl::compute3DCentroid (pc, centroid); + pcl::demeanPointCloud (pc, centroid, local_cloud_); + + float max_distance = 0, d; + pcl::PointXYZ cog (0, 0, 0); + + for (size_t i = 0; i < local_cloud_.points.size (); ++i) + { + d = pcl::euclideanDistance(cog,local_cloud_.points[i]); + if (d > max_distance) + max_distance = d; + } + + float scale_factor = 1.0f / max_distance * scalefactor; + + Eigen::Affine3f matrix = Eigen::Affine3f::Identity(); + matrix.scale (scale_factor); + pcl::transformPointCloud (local_cloud_, local_cloud_, matrix); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ESFEstimation::compute (PointCloudOut &output) +{ + if (!Feature::initCompute ()) + { + output.width = output.height = 0; + output.points.clear (); + return; + } + // Copy the header + output.header = input_->header; + + // Resize the output dataset + // Important! We should only allocate precisely how many elements we will need, otherwise + // we risk at pre-allocating too much memory which could lead to bad_alloc + // (see http://dev.pointclouds.org/issues/657) + output.width = output.height = 1; + output.is_dense = input_->is_dense; + output.points.resize (1); + + // Perform the actual feature computation + computeFeature (output); + + Feature::deinitCompute (); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ESFEstimation::computeFeature (PointCloudOut &output) +{ + Eigen::Vector4f xyz_centroid; + std::vector hist; + scale_points_unit_sphere (*surface_, static_cast(GRIDSIZE_H), xyz_centroid); + this->voxelize9 (local_cloud_); + this->computeESF (local_cloud_, hist); + this->cleanup9 (local_cloud_); + + // We only output _1_ signature + output.points.resize (1); + output.width = 1; + output.height = 1; + + for (size_t d = 0; d < hist.size (); ++d) + output.points[0].histogram[d] = hist[d]; +} + +#define PCL_INSTANTIATE_ESFEstimation(T,OutT) template class PCL_EXPORTS pcl::ESFEstimation; + +#endif // PCL_FEATURES_IMPL_ESF_H_ + diff --git a/pcl-1.7/pcl/features/impl/feature.hpp b/pcl-1.7/pcl/features/impl/feature.hpp new file mode 100644 index 0000000..3354839 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/feature.hpp @@ -0,0 +1,335 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_IMPL_FEATURE_H_ +#define PCL_FEATURES_IMPL_FEATURE_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +inline void +pcl::solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix, + const Eigen::Vector4f &point, + Eigen::Vector4f &plane_parameters, float &curvature) +{ + solvePlaneParameters (covariance_matrix, plane_parameters [0], plane_parameters [1], plane_parameters [2], curvature); + + plane_parameters[3] = 0; + // Hessian form (D = nc . p_plane (centroid here) + p) + plane_parameters[3] = -1 * plane_parameters.dot (point); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +inline void +pcl::solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix, + float &nx, float &ny, float &nz, float &curvature) +{ + // Avoid getting hung on Eigen's optimizers +// for (int i = 0; i < 9; ++i) +// if (!pcl_isfinite (covariance_matrix.coeff (i))) +// { +// //PCL_WARN ("[pcl::solvePlaneParameteres] Covariance matrix has NaN/Inf values!\n"); +// nx = ny = nz = curvature = std::numeric_limits::quiet_NaN (); +// return; +// } + // Extract the smallest eigenvalue and its eigenvector + EIGEN_ALIGN16 Eigen::Vector3f::Scalar eigen_value; + EIGEN_ALIGN16 Eigen::Vector3f eigen_vector; + pcl::eigen33 (covariance_matrix, eigen_value, eigen_vector); + + nx = eigen_vector [0]; + ny = eigen_vector [1]; + nz = eigen_vector [2]; + + // Compute the curvature surface change + float eig_sum = covariance_matrix.coeff (0) + covariance_matrix.coeff (4) + covariance_matrix.coeff (8); + if (eig_sum != 0) + curvature = fabsf (eigen_value / eig_sum); + else + curvature = 0; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::Feature::initCompute () +{ + if (!PCLBase::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + // If the dataset is empty, just return + if (input_->points.empty ()) + { + PCL_ERROR ("[pcl::%s::compute] input_ is empty!\n", getClassName ().c_str ()); + // Cleanup + deinitCompute (); + return (false); + } + + // If no search surface has been defined, use the input dataset as the search surface itself + if (!surface_) + { + fake_surface_ = true; + surface_ = input_; + } + + // Check if a space search locator was given + if (!tree_) + { + if (surface_->isOrganized () && input_->isOrganized ()) + tree_.reset (new pcl::search::OrganizedNeighbor ()); + else + tree_.reset (new pcl::search::KdTree (false)); + } + + // PCL_ERROR ("[pcl::%s::compute] \n", getClassName ().c_str ()); + if (tree_->getInputCloud () != surface_) // Make sure the tree searches the surface + tree_->setInputCloud (surface_); + + // Do a fast check to see if the search parameters are well defined + if (search_radius_ != 0.0) + { + if (k_ != 0) + { + PCL_ERROR ("[pcl::%s::compute] ", getClassName ().c_str ()); + PCL_ERROR ("Both radius (%f) and K (%d) defined! ", search_radius_, k_); + PCL_ERROR ("Set one of them to zero first and then re-run compute ().\n"); + // Cleanup + deinitCompute (); + return (false); + } + else // Use the radiusSearch () function + { + search_parameter_ = search_radius_; + // Declare the search locator definition + int (KdTree::*radiusSearchSurface)(const PointCloudIn &cloud, int index, double radius, + std::vector &k_indices, std::vector &k_distances, + unsigned int max_nn) const = &pcl::search::Search::radiusSearch; + search_method_surface_ = boost::bind (radiusSearchSurface, boost::ref (tree_), _1, _2, _3, _4, _5, 0); + } + } + else + { + if (k_ != 0) // Use the nearestKSearch () function + { + search_parameter_ = k_; + // Declare the search locator definition + int (KdTree::*nearestKSearchSurface)(const PointCloudIn &cloud, int index, int k, std::vector &k_indices, + std::vector &k_distances) const = &KdTree::nearestKSearch; + search_method_surface_ = boost::bind (nearestKSearchSurface, boost::ref (tree_), _1, _2, _3, _4, _5); + } + else + { + PCL_ERROR ("[pcl::%s::compute] Neither radius nor K defined! ", getClassName ().c_str ()); + PCL_ERROR ("Set one of them to a positive number first and then re-run compute ().\n"); + // Cleanup + deinitCompute (); + return (false); + } + } + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::Feature::deinitCompute () +{ + // Reset the surface + if (fake_surface_) + { + surface_.reset (); + fake_surface_ = false; + } + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::Feature::compute (PointCloudOut &output) +{ + if (!initCompute ()) + { + output.width = output.height = 0; + output.points.clear (); + return; + } + + // Copy the header + output.header = input_->header; + + // Resize the output dataset + if (output.points.size () != indices_->size ()) + output.points.resize (indices_->size ()); + + // Check if the output will be computed for all points or only a subset + // If the input width or height are not set, set output width as size + if (indices_->size () != input_->points.size () || input_->width * input_->height == 0) + { + output.width = static_cast (indices_->size ()); + output.height = 1; + } + else + { + output.width = input_->width; + output.height = input_->height; + } + output.is_dense = input_->is_dense; + + // Perform the actual feature computation + computeFeature (output); + + deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::FeatureFromNormals::initCompute () +{ + if (!Feature::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + // Check if input normals are set + if (!normals_) + { + PCL_ERROR ("[pcl::%s::initCompute] No input dataset containing normals was given!\n", getClassName ().c_str ()); + Feature::deinitCompute (); + return (false); + } + + // Check if the size of normals is the same as the size of the surface + if (normals_->points.size () != surface_->points.size ()) + { + PCL_ERROR ("[pcl::%s::initCompute] ", getClassName ().c_str ()); + PCL_ERROR ("The number of points in the input dataset (%u) differs from ", surface_->points.size ()); + PCL_ERROR ("the number of points in the dataset containing the normals (%u)!\n", normals_->points.size ()); + Feature::deinitCompute (); + return (false); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::FeatureFromLabels::initCompute () +{ + if (!Feature::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + // Check if input normals are set + if (!labels_) + { + PCL_ERROR ("[pcl::%s::initCompute] No input dataset containing labels was given!\n", getClassName ().c_str ()); + Feature::deinitCompute (); + return (false); + } + + // Check if the size of normals is the same as the size of the surface + if (labels_->points.size () != surface_->points.size ()) + { + PCL_ERROR ("[pcl::%s::initCompute] The number of points in the input dataset differs from the number of points in the dataset containing the labels!\n", getClassName ().c_str ()); + Feature::deinitCompute (); + return (false); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::FeatureWithLocalReferenceFrames::initLocalReferenceFrames (const size_t& indices_size, + const LRFEstimationPtr& lrf_estimation) +{ + if (frames_never_defined_) + frames_.reset (); + + // Check if input frames are set + if (!frames_) + { + if (!lrf_estimation) + { + PCL_ERROR ("[initLocalReferenceFrames] No input dataset containing reference frames was given!\n"); + return (false); + } else + { + //PCL_WARN ("[initLocalReferenceFrames] No input dataset containing reference frames was given! Proceed using default\n"); + PointCloudLRFPtr default_frames (new PointCloudLRF()); + lrf_estimation->compute (*default_frames); + frames_ = default_frames; + } + } + + // Check if the size of frames is the same as the size of the input cloud + if (frames_->points.size () != indices_size) + { + if (!lrf_estimation) + { + PCL_ERROR ("[initLocalReferenceFrames] The number of points in the input dataset differs from the number of points in the dataset containing the reference frames!\n"); + return (false); + } else + { + //PCL_WARN ("[initLocalReferenceFrames] The number of points in the input dataset differs from the number of points in the dataset containing the reference frames! Proceed using default\n"); + PointCloudLRFPtr default_frames (new PointCloudLRF()); + lrf_estimation->compute (*default_frames); + frames_ = default_frames; + } + } + + return (true); +} + +#endif //#ifndef PCL_FEATURES_IMPL_FEATURE_H_ + diff --git a/pcl-1.7/pcl/features/impl/fpfh.hpp b/pcl-1.7/pcl/features/impl/fpfh.hpp new file mode 100644 index 0000000..eb96993 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/fpfh.hpp @@ -0,0 +1,383 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_IMPL_FPFH_H_ +#define PCL_FEATURES_IMPL_FPFH_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::FPFHEstimation::computePairFeatures ( + const pcl::PointCloud &cloud, const pcl::PointCloud &normals, + int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4) +{ + pcl::computePairFeatures (cloud.points[p_idx].getVector4fMap (), normals.points[p_idx].getNormalVector4fMap (), + cloud.points[q_idx].getVector4fMap (), normals.points[q_idx].getNormalVector4fMap (), + f1, f2, f3, f4); + return (true); + + // mannually added + // PCL_ERROR("compute pair feature\n"); + // Eigen::Vector4f p1 = cloud.points[p_idx].getVector4fMap (); + // Eigen::Vector4f n1 = normals.points[p_idx].getNormalVector4fMap (); + // Eigen::Vector4f p2 = cloud.points[q_idx].getVector4fMap (); + // Eigen::Vector4f n2 = normals.points[q_idx].getNormalVector4fMap (); + + // Eigen::Vector4f dp2p1 = p2 - p1; + // dp2p1[3] = 0.0f; + // f4 = dp2p1.norm (); + + // if (f4 == 0.0f) + // { + // PCL_DEBUG ("[pcl::computePairFeatures] Euclidean distance between points is 0!\n"); + // f1 = f2 = f3 = f4 = 0.0f; + // return (false); + // } + + // Eigen::Vector4f n1_copy = n1, + // n2_copy = n2; + // n1_copy[3] = n2_copy[3] = 0.0f; + // float angle1 = n1_copy.dot (dp2p1) / f4; + + // // Make sure the same point is selected as 1 and 2 for each pair + // float angle2 = n2_copy.dot (dp2p1) / f4; + // if (acos (fabs (angle1)) > acos (fabs (angle2))) + // { + // // switch p1 and p2 + // n1_copy = n2; + // n2_copy = n1; + // n1_copy[3] = n2_copy[3] = 0.0f; + // dp2p1 *= (-1); + // f3 = -angle2; + // } + // else + // f3 = angle1; + + // // Create a Darboux frame coordinate system u-v-w + // // u = n1; v = (p_idx - q_idx) x u / || (p_idx - q_idx) x u ||; w = u x v + // Eigen::Vector4f v = dp2p1.cross3 (n1_copy); + // v[3] = 0.0f; + // float v_norm = v.norm (); + // if (v_norm == 0.0f) + // { + // PCL_DEBUG ("[pcl::computePairFeatures] Norm of Delta x U is 0!\n"); + // f1 = f2 = f3 = f4 = 0.0f; + // return (false); + // } + // // Normalize v + // v /= v_norm; + + // Eigen::Vector4f w = n1_copy.cross3 (v); + // // Do not have to normalize w - it is a unit vector by construction + + // v[3] = 0.0f; + // f2 = v.dot (n2_copy); + // w[3] = 0.0f; + // // Compute f1 = arctan (w * n2, u * n2) i.e. angle of n2 in the x=u, y=w coordinate system + // f1 = atan2f (w.dot (n2_copy), n1_copy.dot (n2_copy)); // @todo optimize this + + // return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::FPFHEstimation::computePointSPFHSignature ( + const pcl::PointCloud &cloud, const pcl::PointCloud &normals, + int p_idx, int row, const std::vector &indices, + Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3) +{ + Eigen::Vector4f pfh_tuple; + // Get the number of bins from the histograms size + int nr_bins_f1 = static_cast (hist_f1.cols ()); + int nr_bins_f2 = static_cast (hist_f2.cols ()); + int nr_bins_f3 = static_cast (hist_f3.cols ()); + + // Factorization constant + float hist_incr = 100.0f / static_cast(indices.size () - 1); + + // Iterate over all the points in the neighborhood + for (size_t idx = 0; idx < indices.size (); ++idx) + { + // Avoid unnecessary returns + if (p_idx == indices[idx]) + continue; + + // Compute the pair P to NNi + if (!computePairFeatures (cloud, normals, p_idx, indices[idx], pfh_tuple[0], pfh_tuple[1], pfh_tuple[2], pfh_tuple[3])) + continue; + + // Normalize the f1, f2, f3 features and push them in the histogram + int h_index = static_cast (floor (nr_bins_f1 * ((pfh_tuple[0] + M_PI) * d_pi_))); + if (h_index < 0) h_index = 0; + if (h_index >= nr_bins_f1) h_index = nr_bins_f1 - 1; + hist_f1 (row, h_index) += hist_incr; + + h_index = static_cast (floor (nr_bins_f2 * ((pfh_tuple[1] + 1.0) * 0.5))); + if (h_index < 0) h_index = 0; + if (h_index >= nr_bins_f2) h_index = nr_bins_f2 - 1; + hist_f2 (row, h_index) += hist_incr; + + h_index = static_cast (floor (nr_bins_f3 * ((pfh_tuple[2] + 1.0) * 0.5))); + if (h_index < 0) h_index = 0; + if (h_index >= nr_bins_f3) h_index = nr_bins_f3 - 1; + hist_f3 (row, h_index) += hist_incr; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::FPFHEstimation::weightPointSPFHSignature ( + const Eigen::MatrixXf &hist_f1, const Eigen::MatrixXf &hist_f2, const Eigen::MatrixXf &hist_f3, + const std::vector &indices, const std::vector &dists, Eigen::VectorXf &fpfh_histogram) +{ + assert (indices.size () == dists.size ()); + double sum_f1 = 0.0, sum_f2 = 0.0, sum_f3 = 0.0; + float weight = 0.0, val_f1, val_f2, val_f3; + + // Get the number of bins from the histograms size + int nr_bins_f1 = static_cast (hist_f1.cols ()); + int nr_bins_f2 = static_cast (hist_f2.cols ()); + int nr_bins_f3 = static_cast (hist_f3.cols ()); + int nr_bins_f12 = nr_bins_f1 + nr_bins_f2; + + // Clear the histogram + fpfh_histogram.setZero (nr_bins_f1 + nr_bins_f2 + nr_bins_f3); + + // Use the entire patch + for (size_t idx = 0, data_size = indices.size (); idx < data_size; ++idx) + { + // Minus the query point itself + if (dists[idx] == 0) + continue; + + // Standard weighting function used + weight = 1.0f / dists[idx]; + + // Weight the SPFH of the query point with the SPFH of its neighbors + for (int f1_i = 0; f1_i < nr_bins_f1; ++f1_i) + { + val_f1 = hist_f1 (indices[idx], f1_i) * weight; + sum_f1 += val_f1; + fpfh_histogram[f1_i] += val_f1; + } + + for (int f2_i = 0; f2_i < nr_bins_f2; ++f2_i) + { + val_f2 = hist_f2 (indices[idx], f2_i) * weight; + sum_f2 += val_f2; + fpfh_histogram[f2_i + nr_bins_f1] += val_f2; + } + + for (int f3_i = 0; f3_i < nr_bins_f3; ++f3_i) + { + val_f3 = hist_f3 (indices[idx], f3_i) * weight; + sum_f3 += val_f3; + fpfh_histogram[f3_i + nr_bins_f12] += val_f3; + } + } + + if (sum_f1 != 0) + sum_f1 = 100.0 / sum_f1; // histogram values sum up to 100 + if (sum_f2 != 0) + sum_f2 = 100.0 / sum_f2; // histogram values sum up to 100 + if (sum_f3 != 0) + sum_f3 = 100.0 / sum_f3; // histogram values sum up to 100 + + // Adjust final FPFH values + for (int f1_i = 0; f1_i < nr_bins_f1; ++f1_i) + fpfh_histogram[f1_i] *= static_cast (sum_f1); + for (int f2_i = 0; f2_i < nr_bins_f2; ++f2_i) + fpfh_histogram[f2_i + nr_bins_f1] *= static_cast (sum_f2); + for (int f3_i = 0; f3_i < nr_bins_f3; ++f3_i) + fpfh_histogram[f3_i + nr_bins_f12] *= static_cast (sum_f3); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::FPFHEstimation::computeSPFHSignatures (std::vector &spfh_hist_lookup, + Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3) +{ + + // Allocate enough space to hold the NN search results + // \note This resize is irrelevant for a radiusSearch (). + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + std::set spfh_indices; + spfh_hist_lookup.resize (surface_->points.size ()); + spfh_hist_lookup.resize (indices_->size ()); + // PCL_ERROR("computeSPFHSignatures: %d\n", surface_->points.size()); + + // Build a list of (unique) indices for which we will need to compute SPFH signatures + // (We need an SPFH signature for every point that is a neighbor of any point in input_[indices_]) + if (surface_ != input_ || + indices_->size () != surface_->points.size ()) + { + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + int p_idx = (*indices_)[idx]; + + if (this->searchForNeighbors (p_idx, search_parameter_, nn_indices, nn_dists) == 0) + continue; + + spfh_indices.insert (nn_indices.begin (), nn_indices.end ()); + } + // PCL_ERROR("computeSPFHSignatures: %d\n", indices_->size()); + } + else + { + // Special case: When a feature must be computed at every point, there is no need for a neighborhood search + for (size_t idx = 0; idx < indices_->size (); ++idx) + spfh_indices.insert (static_cast (idx)); + } + + // Initialize the arrays that will store the SPFH signatures + size_t data_size = spfh_indices.size (); + hist_f1.setZero (data_size, nr_bins_f1_); + hist_f2.setZero (data_size, nr_bins_f2_); + hist_f3.setZero (data_size, nr_bins_f3_); + + // Compute SPFH signatures for every point that needs them + std::set::iterator spfh_indices_itr = spfh_indices.begin (); + for (int i = 0; i < static_cast (spfh_indices.size ()); ++i) + { + // Get the next point index + int p_idx = *spfh_indices_itr; + ++spfh_indices_itr; + + // Find the neighborhood around p_idx + if (this->searchForNeighbors (*surface_, p_idx, search_parameter_, nn_indices, nn_dists) == 0) + continue; + + // Estimate the SPFH signature around p_idx + computePointSPFHSignature (*surface_, *normals_, p_idx, i, nn_indices, hist_f1, hist_f2, hist_f3); + + // Populate a lookup table for converting a point index to its corresponding row in the spfh_hist_* matrices + spfh_hist_lookup[p_idx] = i; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::FPFHEstimation::computeFeature (PointCloudOut &output) +{ + // Allocate enough space to hold the NN search results + // \note This resize is irrelevant for a radiusSearch (). + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + int search_state = 0; + + std::vector spfh_hist_lookup; + computeSPFHSignatures (spfh_hist_lookup, hist_f1_, hist_f2_, hist_f3_); + + // PCL_ERROR("computeFeature (FPFH): %d\n", spfh_hist_lookup.size ()); + // number of points + + output.is_dense = true; + // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense + if (input_->is_dense) + { + + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + search_state = this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists); + + if (search_state == 0) + { + for (int d = 0; d < fpfh_histogram_.size (); ++d) + output.points[idx].histogram[d] = std::numeric_limits::quiet_NaN (); + + output.is_dense = false; + continue; + } + + // ... and remap the nn_indices values so that they represent row indices in the spfh_hist_* matrices + // instead of indices into surface_->points + for (size_t i = 0; i < nn_indices.size (); ++i) + nn_indices[i] = spfh_hist_lookup[nn_indices[i]]; + + // Compute the FPFH signature (i.e. compute a weighted combination of local SPFH signatures) ... + // no neighbouring search inside + weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_); + + // ...and copy it into the output cloud + for (int d = 0; d < fpfh_histogram_.size (); ++d) + output.points[idx].histogram[d] = fpfh_histogram_[d]; + } + } + else + { + // Iterate over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + search_state = this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists); + + if (!isFinite ((*input_)[(*indices_)[idx]]) || search_state == 0) + { + for (int d = 0; d < fpfh_histogram_.size (); ++d) + output.points[idx].histogram[d] = std::numeric_limits::quiet_NaN (); + + output.is_dense = false; + continue; + } + + // ... and remap the nn_indices values so that they represent row indices in the spfh_hist_* matrices + // instead of indices into surface_->points + for (size_t i = 0; i < nn_indices.size (); ++i) + nn_indices[i] = spfh_hist_lookup[nn_indices[i]]; + + // Compute the FPFH signature (i.e. compute a weighted combination of local SPFH signatures) ... + weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_); + + // ...and copy it into the output cloud + for (int d = 0; d < fpfh_histogram_.size (); ++d) + output.points[idx].histogram[d] = fpfh_histogram_[d]; + } + } + +} + +#define PCL_INSTANTIATE_FPFHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::FPFHEstimation; + +#endif // PCL_FEATURES_IMPL_FPFH_H_ + diff --git a/pcl-1.7/pcl/features/impl/fpfh_omp.hpp b/pcl-1.7/pcl/features/impl/fpfh_omp.hpp new file mode 100644 index 0000000..a3624a7 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/fpfh_omp.hpp @@ -0,0 +1,162 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_IMPL_FPFH_OMP_H_ +#define PCL_FEATURES_IMPL_FPFH_OMP_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::FPFHEstimationOMP::computeFeature (PointCloudOut &output) +{ + + int search_state = 0; + + std::vector spfh_indices_vec; + std::vector spfh_hist_lookup (surface_->points.size ()); + + // Build a list of (unique) indices for which we will need to compute SPFH signatures + // (We need an SPFH signature for every point that is a neighbor of any point in input_[indices_]) + if (surface_ != input_ || + indices_->size () != surface_->points.size ()) + { + std::vector nn_indices (k_); // \note These resizes are irrelevant for a radiusSearch (). + std::vector nn_dists (k_); + + std::set spfh_indices_set; + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + int p_idx = (*indices_)[idx]; + + if (this->searchForNeighbors (p_idx, search_parameter_, nn_indices, nn_dists) == 0) + continue; + + spfh_indices_set.insert (nn_indices.begin (), nn_indices.end ()); + } + spfh_indices_vec.resize (spfh_indices_set.size ()); + std::copy (spfh_indices_set.begin (), spfh_indices_set.end (), spfh_indices_vec.begin ()); + } + else + { + // Special case: When a feature must be computed at every point, there is no need for a neighborhood search + spfh_indices_vec.resize (indices_->size ()); + for (int idx = 0; idx < static_cast (indices_->size ()); ++idx) + spfh_indices_vec[idx] = idx; + } + + // Initialize the arrays that will store the SPFH signatures + size_t data_size = spfh_indices_vec.size (); + hist_f1_.setZero (data_size, nr_bins_f1_); + hist_f2_.setZero (data_size, nr_bins_f2_); + hist_f3_.setZero (data_size, nr_bins_f3_); + + std::vector nn_indices (k_); // \note These resizes are irrelevant for a radiusSearch (). + std::vector nn_dists (k_); + + // Compute SPFH signatures for every point that needs them + +#ifdef _OPENMP +#pragma omp parallel for shared (spfh_hist_lookup) private (nn_indices, nn_dists) num_threads(threads_) +#endif + for (int i = 0; i < static_cast (spfh_indices_vec.size ()); ++i) + { + // Get the next point index + int p_idx = spfh_indices_vec[i]; + + // Find the neighborhood around p_idx + if (this->searchForNeighbors (*surface_, p_idx, search_parameter_, nn_indices, nn_dists) == 0) + continue; + + // Estimate the SPFH signature around p_idx + this->computePointSPFHSignature (*surface_, *normals_, p_idx, i, nn_indices, hist_f1_, hist_f2_, hist_f3_); + + // Populate a lookup table for converting a point index to its corresponding row in the spfh_hist_* matrices + spfh_hist_lookup[p_idx] = i; + } + + // Intialize the array that will store the FPFH signature + int nr_bins = nr_bins_f1_ + nr_bins_f2_ + nr_bins_f3_; + + nn_indices.clear(); + nn_dists.clear(); + + // Iterate over the entire index vector +#ifdef _OPENMP +#pragma omp parallel for shared (output) private (nn_indices, nn_dists) num_threads(threads_) +#endif + + for (int idx = 0; idx < static_cast (indices_->size ()); ++idx) + { + + search_state = this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists); + + // Find the indices of point idx's neighbors... + if (!isFinite ((*input_)[(*indices_)[idx]]) || + search_state == 0) + { + for (int d = 0; d < nr_bins; ++d) + output.points[idx].histogram[d] = std::numeric_limits::quiet_NaN (); + + output.is_dense = false; + continue; + } + + + // ... and remap the nn_indices values so that they represent row indices in the spfh_hist_* matrices + // instead of indices into surface_->points + for (size_t i = 0; i < nn_indices.size (); ++i) + nn_indices[i] = spfh_hist_lookup[nn_indices[i]]; + + // Compute the FPFH signature (i.e. compute a weighted combination of local SPFH signatures) ... + Eigen::VectorXf fpfh_histogram = Eigen::VectorXf::Zero (nr_bins); + weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram); + + // ...and copy it into the output cloud + for (int d = 0; d < nr_bins; ++d) + output.points[idx].histogram[d] = fpfh_histogram[d]; + } + +} + +#define PCL_INSTANTIATE_FPFHEstimationOMP(T,NT,OutT) template class PCL_EXPORTS pcl::FPFHEstimationOMP; + +#endif // PCL_FEATURES_IMPL_FPFH_OMP_H_ + diff --git a/pcl-1.7/pcl/features/impl/gfpfh.hpp b/pcl-1.7/pcl/features/impl/gfpfh.hpp new file mode 100644 index 0000000..6d05f66 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/gfpfh.hpp @@ -0,0 +1,272 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: gfpfh.hpp 2218 2011-08-25 20:27:15Z rusu $ + * + */ + +#ifndef PCL_FEATURES_IMPL_GFPFH_H_ +#define PCL_FEATURES_IMPL_GFPFH_H_ + +#include +#include +#include +#include + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GFPFHEstimation::compute (PointCloudOut &output) +{ + if (!Feature::initCompute ()) + { + output.width = output.height = 0; + output.points.clear (); + return; + } + // Copy the header + output.header = input_->header; + + // Resize the output dataset + // Important! We should only allocate precisely how many elements we will need, otherwise + // we risk at pre-allocating too much memory which could lead to bad_alloc + // (see http://dev.pointclouds.org/issues/657) + output.width = output.height = 1; + output.is_dense = input_->is_dense; + output.points.resize (1); + + // Perform the actual feature computation + computeFeature (output); + + Feature::deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GFPFHEstimation::computeFeature (PointCloudOut &output) +{ + pcl::octree::OctreePointCloudSearch octree (octree_leaf_size_); + octree.setInputCloud (input_); + octree.addPointsFromInputCloud (); + + typename pcl::PointCloud::VectorType occupied_cells; + octree.getOccupiedVoxelCenters (occupied_cells); + + // Determine the voxels crosses along the line segments + // formed by every pair of occupied cells. + std::vector< std::vector > line_histograms; + for (size_t i = 0; i < occupied_cells.size (); ++i) + { + Eigen::Vector3f origin = occupied_cells[i].getVector3fMap (); + + for (size_t j = i+1; j < occupied_cells.size (); ++j) + { + typename pcl::PointCloud::VectorType intersected_cells; + Eigen::Vector3f end = occupied_cells[j].getVector3fMap (); + octree.getApproxIntersectedVoxelCentersBySegment (origin, end, intersected_cells, 0.5f); + + // Intersected cells are ordered from closest to furthest w.r.t. the origin. + std::vector histogram; + for (size_t k = 0; k < intersected_cells.size (); ++k) + { + std::vector indices; + octree.voxelSearch (intersected_cells[k], indices); + int label = emptyLabel (); + if (indices.size () != 0) + { + label = getDominantLabel (indices); + } + histogram.push_back (label); + } + + line_histograms.push_back(histogram); + } + } + + std::vector< std::vector > transition_histograms; + computeTransitionHistograms (line_histograms, transition_histograms); + + std::vector distances; + computeDistancesToMean (transition_histograms, distances); + + std::vector gfpfh_histogram; + computeDistanceHistogram (distances, gfpfh_histogram); + + output.clear (); + output.width = 1; + output.height = 1; + output.points.resize (1); + std::copy (gfpfh_histogram.begin (), gfpfh_histogram.end (), output.points[0].histogram); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GFPFHEstimation::computeTransitionHistograms (const std::vector< std::vector >& label_histograms, + std::vector< std::vector >& transition_histograms) +{ + transition_histograms.resize (label_histograms.size ()); + + for (size_t i = 0; i < label_histograms.size (); ++i) + { + transition_histograms[i].resize ((getNumberOfClasses () + 2) * (getNumberOfClasses () + 1) / 2, 0); + + std::vector< std::vector > transitions (getNumberOfClasses () + 1); + for (size_t k = 0; k < transitions.size (); ++k) + { + transitions[k].resize (getNumberOfClasses () + 1, 0); + } + + for (size_t k = 1; k < label_histograms[i].size (); ++k) + { + uint32_t first_class = label_histograms[i][k-1]; + uint32_t second_class = label_histograms[i][k]; + // Order has no influence. + if (second_class < first_class) + std::swap (first_class, second_class); + + transitions[first_class][second_class] += 1; + } + + // Build a one-dimension histogram out of it. + int flat_index = 0; + for (int m = 0; m < static_cast (transitions.size ()); ++m) + for (int n = m; n < static_cast (transitions[m].size ()); ++n) + { + transition_histograms[i][flat_index] = transitions[m][n]; + ++flat_index; + } + + assert (flat_index == static_cast (transition_histograms[i].size ())); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GFPFHEstimation::computeDistancesToMean (const std::vector< std::vector >& transition_histograms, + std::vector& distances) +{ + distances.resize (transition_histograms.size ()); + + std::vector mean_histogram; + computeMeanHistogram (transition_histograms, mean_histogram); + + for (size_t i = 0; i < transition_histograms.size (); ++i) + { + float d = computeHIKDistance (transition_histograms[i], mean_histogram); + distances[i] = d; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GFPFHEstimation::computeDistanceHistogram (const std::vector& distances, + std::vector& histogram) +{ + std::vector::const_iterator min_it = std::min_element (distances.begin (), distances.end ()); + assert (min_it != distances.end ()); + const float min_value = *min_it; + + std::vector::const_iterator max_it = std::max_element (distances.begin (), distances.end ()); + assert (max_it != distances.end()); + const float max_value = *max_it; + + histogram.resize (descriptorSize (), 0); + + const float range = max_value - min_value; + const int max_bin = descriptorSize () - 1; + for (size_t i = 0; i < distances.size (); ++i) + { + const float raw_bin = static_cast (descriptorSize ()) * (distances[i] - min_value) / range; + int bin = std::min (max_bin, static_cast (floor (raw_bin))); + histogram[bin] += 1; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GFPFHEstimation::computeMeanHistogram (const std::vector< std::vector >& histograms, + std::vector& mean_histogram) +{ + assert (histograms.size () > 0); + + mean_histogram.resize (histograms[0].size (), 0); + for (size_t i = 0; i < histograms.size (); ++i) + for (size_t j = 0; j < histograms[i].size (); ++j) + mean_histogram[j] += static_cast (histograms[i][j]); + + for (size_t i = 0; i < mean_histogram.size (); ++i) + mean_histogram[i] /= static_cast (histograms.size ()); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::GFPFHEstimation::computeHIKDistance (const std::vector& histogram, + const std::vector& mean_histogram) +{ + assert (histogram.size () == mean_histogram.size ()); + + float norm = 0.f; + for (size_t i = 0; i < histogram.size (); ++i) + norm += std::min (static_cast (histogram[i]), mean_histogram[i]); + + norm /= static_cast (histogram.size ()); + return (norm); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template boost::uint32_t +pcl::GFPFHEstimation::getDominantLabel (const std::vector& indices) +{ + std::vector counts (getNumberOfClasses () + 1, 0); + for (size_t i = 0; i < indices.size (); ++i) + { + uint32_t label = labels_->points[indices[i]].label; + counts[label] += 1; + } + + std::vector::const_iterator max_it; + max_it = std::max_element (counts.begin (), counts.end ()); + if (max_it == counts.end ()) + return (emptyLabel ()); + + return (static_cast (max_it - counts.begin ())); +} + +#define PCL_INSTANTIATE_GFPFHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::GFPFHEstimation; + +#endif // PCL_FEATURES_IMPL_GFPFH_H_ diff --git a/pcl-1.7/pcl/features/impl/integral_image2D.hpp b/pcl-1.7/pcl/features/impl/integral_image2D.hpp new file mode 100644 index 0000000..d4e9a94 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/integral_image2D.hpp @@ -0,0 +1,385 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: feature.h 2784 2011-10-15 22:05:38Z aichim $ + */ + +#ifndef PCL_INTEGRAL_IMAGE2D_IMPL_H_ +#define PCL_INTEGRAL_IMAGE2D_IMPL_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImage2D::setSecondOrderComputation (bool compute_second_order_integral_images) +{ + compute_second_order_integral_images_ = compute_second_order_integral_images; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImage2D::setInput (const DataType * data, unsigned width,unsigned height, unsigned element_stride, unsigned row_stride) +{ + if ((width + 1) * (height + 1) > first_order_integral_image_.size () ) + { + width_ = width; + height_ = height; + first_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) ); + finite_values_integral_image_.resize ( (width_ + 1) * (height_ + 1) ); + if (compute_second_order_integral_images_) + second_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) ); + } + computeIntegralImages (data, row_stride, element_stride); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::IntegralImage2D::ElementType +pcl::IntegralImage2D::getFirstOrderSum ( + unsigned start_x, unsigned start_y, unsigned width, unsigned height) const +{ + const unsigned upper_left_idx = start_y * (width_ + 1) + start_x; + const unsigned upper_right_idx = upper_left_idx + width; + const unsigned lower_left_idx = (start_y + height) * (width_ + 1) + start_x; + const unsigned lower_right_idx = lower_left_idx + width; + + return (first_order_integral_image_[lower_right_idx] + first_order_integral_image_[upper_left_idx] - + first_order_integral_image_[upper_right_idx] - first_order_integral_image_[lower_left_idx] ); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::IntegralImage2D::SecondOrderType +pcl::IntegralImage2D::getSecondOrderSum ( + unsigned start_x, unsigned start_y, unsigned width, unsigned height) const +{ + const unsigned upper_left_idx = start_y * (width_ + 1) + start_x; + const unsigned upper_right_idx = upper_left_idx + width; + const unsigned lower_left_idx = (start_y + height) * (width_ + 1) + start_x; + const unsigned lower_right_idx = lower_left_idx + width; + + return (second_order_integral_image_[lower_right_idx] + second_order_integral_image_[upper_left_idx] - + second_order_integral_image_[upper_right_idx] - second_order_integral_image_[lower_left_idx] ); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template unsigned +pcl::IntegralImage2D::getFiniteElementsCount ( + unsigned start_x, unsigned start_y, unsigned width, unsigned height) const +{ + const unsigned upper_left_idx = start_y * (width_ + 1) + start_x; + const unsigned upper_right_idx = upper_left_idx + width; + const unsigned lower_left_idx = (start_y + height) * (width_ + 1) + start_x; + const unsigned lower_right_idx = lower_left_idx + width; + + return (finite_values_integral_image_[lower_right_idx] + finite_values_integral_image_[upper_left_idx] - + finite_values_integral_image_[upper_right_idx] - finite_values_integral_image_[lower_left_idx] ); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::IntegralImage2D::ElementType +pcl::IntegralImage2D::getFirstOrderSumSE ( + unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const +{ + const unsigned upper_left_idx = start_y * (width_ + 1) + start_x; + const unsigned upper_right_idx = start_y * (width_ + 1) + end_x; + const unsigned lower_left_idx = end_y * (width_ + 1) + start_x; + const unsigned lower_right_idx = end_y * (width_ + 1) + end_x; + + return (first_order_integral_image_[lower_right_idx] + first_order_integral_image_[upper_left_idx] - + first_order_integral_image_[upper_right_idx] - first_order_integral_image_[lower_left_idx] ); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::IntegralImage2D::SecondOrderType +pcl::IntegralImage2D::getSecondOrderSumSE ( + unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const +{ + const unsigned upper_left_idx = start_y * (width_ + 1) + start_x; + const unsigned upper_right_idx = start_y * (width_ + 1) + end_x; + const unsigned lower_left_idx = end_y * (width_ + 1) + start_x; + const unsigned lower_right_idx = end_y * (width_ + 1) + end_x; + + return (second_order_integral_image_[lower_right_idx] + second_order_integral_image_[upper_left_idx] - + second_order_integral_image_[upper_right_idx] - second_order_integral_image_[lower_left_idx] ); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template unsigned +pcl::IntegralImage2D::getFiniteElementsCountSE ( + unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const +{ + const unsigned upper_left_idx = start_y * (width_ + 1) + start_x; + const unsigned upper_right_idx = start_y * (width_ + 1) + end_x; + const unsigned lower_left_idx = end_y * (width_ + 1) + start_x; + const unsigned lower_right_idx = end_y * (width_ + 1) + end_x; + + return (finite_values_integral_image_[lower_right_idx] + finite_values_integral_image_[upper_left_idx] - + finite_values_integral_image_[upper_right_idx] - finite_values_integral_image_[lower_left_idx] ); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImage2D::computeIntegralImages ( + const DataType *data, unsigned row_stride, unsigned element_stride) +{ + ElementType* previous_row = &first_order_integral_image_[0]; + ElementType* current_row = previous_row + (width_ + 1); + memset (previous_row, 0, sizeof (ElementType) * (width_ + 1)); + + unsigned* count_previous_row = &finite_values_integral_image_[0]; + unsigned* count_current_row = count_previous_row + (width_ + 1); + memset (count_previous_row, 0, sizeof (unsigned) * (width_ + 1)); + + if (!compute_second_order_integral_images_) + { + for (unsigned rowIdx = 0; rowIdx < height_; ++rowIdx, data += row_stride, + previous_row = current_row, current_row += (width_ + 1), + count_previous_row = count_current_row, count_current_row += (width_ + 1)) + { + current_row [0].setZero (); + count_current_row [0] = 0; + for (unsigned colIdx = 0, valIdx = 0; colIdx < width_; ++colIdx, valIdx += element_stride) + { + current_row [colIdx + 1] = previous_row [colIdx + 1] + current_row [colIdx] - previous_row [colIdx]; + count_current_row [colIdx + 1] = count_previous_row [colIdx + 1] + count_current_row [colIdx] - count_previous_row [colIdx]; + const InputType* element = reinterpret_cast (&data [valIdx]); + if (pcl_isfinite (element->sum ())) + { + current_row [colIdx + 1] += element->template cast::IntegralType>(); + ++(count_current_row [colIdx + 1]); + } + } + } + } + else + { + SecondOrderType* so_previous_row = &second_order_integral_image_[0]; + SecondOrderType* so_current_row = so_previous_row + (width_ + 1); + memset (so_previous_row, 0, sizeof (SecondOrderType) * (width_ + 1)); + + SecondOrderType so_element; + for (unsigned rowIdx = 0; rowIdx < height_; ++rowIdx, data += row_stride, + previous_row = current_row, current_row += (width_ + 1), + count_previous_row = count_current_row, count_current_row += (width_ + 1), + so_previous_row = so_current_row, so_current_row += (width_ + 1)) + { + current_row [0].setZero (); + so_current_row [0].setZero (); + count_current_row [0] = 0; + for (unsigned colIdx = 0, valIdx = 0; colIdx < width_; ++colIdx, valIdx += element_stride) + { + current_row [colIdx + 1] = previous_row [colIdx + 1] + current_row [colIdx] - previous_row [colIdx]; + so_current_row [colIdx + 1] = so_previous_row [colIdx + 1] + so_current_row [colIdx] - so_previous_row [colIdx]; + count_current_row [colIdx + 1] = count_previous_row [colIdx + 1] + count_current_row [colIdx] - count_previous_row [colIdx]; + + const InputType* element = reinterpret_cast (&data [valIdx]); + if (pcl_isfinite (element->sum ())) + { + current_row [colIdx + 1] += element->template cast::IntegralType>(); + ++(count_current_row [colIdx + 1]); + for (unsigned myIdx = 0, elIdx = 0; myIdx < Dimension; ++myIdx) + for (unsigned mxIdx = myIdx; mxIdx < Dimension; ++mxIdx, ++elIdx) + so_current_row [colIdx + 1][elIdx] += (*element)[myIdx] * (*element)[mxIdx]; + } + } + } + } +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + +template void +pcl::IntegralImage2D::setInput (const DataType * data, unsigned width,unsigned height, unsigned element_stride, unsigned row_stride) +{ + if ((width + 1) * (height + 1) > first_order_integral_image_.size () ) + { + width_ = width; + height_ = height; + first_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) ); + finite_values_integral_image_.resize ( (width_ + 1) * (height_ + 1) ); + if (compute_second_order_integral_images_) + second_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) ); + } + computeIntegralImages (data, row_stride, element_stride); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::IntegralImage2D::ElementType +pcl::IntegralImage2D::getFirstOrderSum ( + unsigned start_x, unsigned start_y, unsigned width, unsigned height) const +{ + const unsigned upper_left_idx = start_y * (width_ + 1) + start_x; + const unsigned upper_right_idx = upper_left_idx + width; + const unsigned lower_left_idx = (start_y + height) * (width_ + 1) + start_x; + const unsigned lower_right_idx = lower_left_idx + width; + + return (first_order_integral_image_[lower_right_idx] + first_order_integral_image_[upper_left_idx] - + first_order_integral_image_[upper_right_idx] - first_order_integral_image_[lower_left_idx] ); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::IntegralImage2D::SecondOrderType +pcl::IntegralImage2D::getSecondOrderSum ( + unsigned start_x, unsigned start_y, unsigned width, unsigned height) const +{ + const unsigned upper_left_idx = start_y * (width_ + 1) + start_x; + const unsigned upper_right_idx = upper_left_idx + width; + const unsigned lower_left_idx = (start_y + height) * (width_ + 1) + start_x; + const unsigned lower_right_idx = lower_left_idx + width; + + return (second_order_integral_image_[lower_right_idx] + second_order_integral_image_[upper_left_idx] - + second_order_integral_image_[upper_right_idx] - second_order_integral_image_[lower_left_idx] ); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template unsigned +pcl::IntegralImage2D::getFiniteElementsCount ( + unsigned start_x, unsigned start_y, unsigned width, unsigned height) const +{ + const unsigned upper_left_idx = start_y * (width_ + 1) + start_x; + const unsigned upper_right_idx = upper_left_idx + width; + const unsigned lower_left_idx = (start_y + height) * (width_ + 1) + start_x; + const unsigned lower_right_idx = lower_left_idx + width; + + return (finite_values_integral_image_[lower_right_idx] + finite_values_integral_image_[upper_left_idx] - + finite_values_integral_image_[upper_right_idx] - finite_values_integral_image_[lower_left_idx] ); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::IntegralImage2D::ElementType +pcl::IntegralImage2D::getFirstOrderSumSE ( + unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const +{ + const unsigned upper_left_idx = start_y * (width_ + 1) + start_x; + const unsigned upper_right_idx = start_y * (width_ + 1) + end_x; + const unsigned lower_left_idx = end_y * (width_ + 1) + start_x; + const unsigned lower_right_idx = end_y * (width_ + 1) + end_x; + + return (first_order_integral_image_[lower_right_idx] + first_order_integral_image_[upper_left_idx] - + first_order_integral_image_[upper_right_idx] - first_order_integral_image_[lower_left_idx] ); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::IntegralImage2D::SecondOrderType +pcl::IntegralImage2D::getSecondOrderSumSE ( + unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const +{ + const unsigned upper_left_idx = start_y * (width_ + 1) + start_x; + const unsigned upper_right_idx = start_y * (width_ + 1) + end_x; + const unsigned lower_left_idx = end_y * (width_ + 1) + start_x; + const unsigned lower_right_idx = end_y * (width_ + 1) + end_x; + + return (second_order_integral_image_[lower_right_idx] + second_order_integral_image_[upper_left_idx] - + second_order_integral_image_[upper_right_idx] - second_order_integral_image_[lower_left_idx] ); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template unsigned +pcl::IntegralImage2D::getFiniteElementsCountSE ( + unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const +{ + const unsigned upper_left_idx = start_y * (width_ + 1) + start_x; + const unsigned upper_right_idx = start_y * (width_ + 1) + end_x; + const unsigned lower_left_idx = end_y * (width_ + 1) + start_x; + const unsigned lower_right_idx = end_y * (width_ + 1) + end_x; + + return (finite_values_integral_image_[lower_right_idx] + finite_values_integral_image_[upper_left_idx] - + finite_values_integral_image_[upper_right_idx] - finite_values_integral_image_[lower_left_idx] ); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImage2D::computeIntegralImages ( + const DataType *data, unsigned row_stride, unsigned element_stride) +{ + ElementType* previous_row = &first_order_integral_image_[0]; + ElementType* current_row = previous_row + (width_ + 1); + memset (previous_row, 0, sizeof (ElementType) * (width_ + 1)); + + unsigned* count_previous_row = &finite_values_integral_image_[0]; + unsigned* count_current_row = count_previous_row + (width_ + 1); + memset (count_previous_row, 0, sizeof (unsigned) * (width_ + 1)); + + if (!compute_second_order_integral_images_) + { + for (unsigned rowIdx = 0; rowIdx < height_; ++rowIdx, data += row_stride, + previous_row = current_row, current_row += (width_ + 1), + count_previous_row = count_current_row, count_current_row += (width_ + 1)) + { + current_row [0] = 0.0; + count_current_row [0] = 0; + for (unsigned colIdx = 0, valIdx = 0; colIdx < width_; ++colIdx, valIdx += element_stride) + { + current_row [colIdx + 1] = previous_row [colIdx + 1] + current_row [colIdx] - previous_row [colIdx]; + count_current_row [colIdx + 1] = count_previous_row [colIdx + 1] + count_current_row [colIdx] - count_previous_row [colIdx]; + if (pcl_isfinite (data [valIdx])) + { + current_row [colIdx + 1] += data [valIdx]; + ++(count_current_row [colIdx + 1]); + } + } + } + } + else + { + SecondOrderType* so_previous_row = &second_order_integral_image_[0]; + SecondOrderType* so_current_row = so_previous_row + (width_ + 1); + memset (so_previous_row, 0, sizeof (SecondOrderType) * (width_ + 1)); + + for (unsigned rowIdx = 0; rowIdx < height_; ++rowIdx, data += row_stride, + previous_row = current_row, current_row += (width_ + 1), + count_previous_row = count_current_row, count_current_row += (width_ + 1), + so_previous_row = so_current_row, so_current_row += (width_ + 1)) + { + current_row [0] = 0.0; + so_current_row [0] = 0.0; + count_current_row [0] = 0; + for (unsigned colIdx = 0, valIdx = 0; colIdx < width_; ++colIdx, valIdx += element_stride) + { + current_row [colIdx + 1] = previous_row [colIdx + 1] + current_row [colIdx] - previous_row [colIdx]; + so_current_row [colIdx + 1] = so_previous_row [colIdx + 1] + so_current_row [colIdx] - so_previous_row [colIdx]; + count_current_row [colIdx + 1] = count_previous_row [colIdx + 1] + count_current_row [colIdx] - count_previous_row [colIdx]; + if (pcl_isfinite (data[valIdx])) + { + current_row [colIdx + 1] += data[valIdx]; + so_current_row [colIdx + 1] += data[valIdx] * data[valIdx]; + ++(count_current_row [colIdx + 1]); + } + } + } + } +} +#endif // PCL_INTEGRAL_IMAGE2D_IMPL_H_ + diff --git a/pcl-1.7/pcl/features/impl/integral_image_normal.hpp b/pcl-1.7/pcl/features/impl/integral_image_normal.hpp new file mode 100644 index 0000000..9b23e5c --- /dev/null +++ b/pcl-1.7/pcl/features/impl/integral_image_normal.hpp @@ -0,0 +1,1196 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_INTEGRALIMAGE_BASED_IMPL_NORMAL_ESTIMATOR_H_ +#define PCL_FEATURES_INTEGRALIMAGE_BASED_IMPL_NORMAL_ESTIMATOR_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::IntegralImageNormalEstimation::~IntegralImageNormalEstimation () +{ + if (diff_x_ != NULL) delete[] diff_x_; + if (diff_y_ != NULL) delete[] diff_y_; + if (depth_data_ != NULL) delete[] depth_data_; + if (distance_map_ != NULL) delete[] distance_map_; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImageNormalEstimation::initData () +{ + if (border_policy_ != BORDER_POLICY_IGNORE && + border_policy_ != BORDER_POLICY_MIRROR) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::IntegralImageNormalEstimation::initData] unknown border policy."); + + if (normal_estimation_method_ != COVARIANCE_MATRIX && + normal_estimation_method_ != AVERAGE_3D_GRADIENT && + normal_estimation_method_ != AVERAGE_DEPTH_CHANGE && + normal_estimation_method_ != SIMPLE_3D_GRADIENT) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::IntegralImageNormalEstimation::initData] unknown normal estimation method."); + + // compute derivatives + if (diff_x_ != NULL) delete[] diff_x_; + if (diff_y_ != NULL) delete[] diff_y_; + if (depth_data_ != NULL) delete[] depth_data_; + if (distance_map_ != NULL) delete[] distance_map_; + diff_x_ = NULL; + diff_y_ = NULL; + depth_data_ = NULL; + distance_map_ = NULL; + + if (normal_estimation_method_ == COVARIANCE_MATRIX) + initCovarianceMatrixMethod (); + else if (normal_estimation_method_ == AVERAGE_3D_GRADIENT) + initAverage3DGradientMethod (); + else if (normal_estimation_method_ == AVERAGE_DEPTH_CHANGE) + initAverageDepthChangeMethod (); + else if (normal_estimation_method_ == SIMPLE_3D_GRADIENT) + initSimple3DGradientMethod (); +} + + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImageNormalEstimation::setRectSize (const int width, const int height) +{ + rect_width_ = width; + rect_width_2_ = width/2; + rect_width_4_ = width/4; + rect_height_ = height; + rect_height_2_ = height/2; + rect_height_4_ = height/4; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImageNormalEstimation::initSimple3DGradientMethod () +{ + // number of DataType entries per element (equal or bigger than dimensions) + int element_stride = sizeof (PointInT) / sizeof (float); + // number of DataType entries per row (equal or bigger than element_stride number of elements per row) + int row_stride = element_stride * input_->width; + + const float *data_ = reinterpret_cast (&input_->points[0]); + + integral_image_XYZ_.setSecondOrderComputation (false); + integral_image_XYZ_.setInput (data_, input_->width, input_->height, element_stride, row_stride); + + init_simple_3d_gradient_ = true; + init_covariance_matrix_ = init_average_3d_gradient_ = init_depth_change_ = false; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImageNormalEstimation::initCovarianceMatrixMethod () +{ + // number of DataType entries per element (equal or bigger than dimensions) + int element_stride = sizeof (PointInT) / sizeof (float); + // number of DataType entries per row (equal or bigger than element_stride number of elements per row) + int row_stride = element_stride * input_->width; + + const float *data_ = reinterpret_cast (&input_->points[0]); + + integral_image_XYZ_.setSecondOrderComputation (true); + integral_image_XYZ_.setInput (data_, input_->width, input_->height, element_stride, row_stride); + + init_covariance_matrix_ = true; + init_average_3d_gradient_ = init_depth_change_ = init_simple_3d_gradient_ = false; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImageNormalEstimation::initAverage3DGradientMethod () +{ + size_t data_size = (input_->points.size () << 2); + diff_x_ = new float[data_size]; + diff_y_ = new float[data_size]; + + memset (diff_x_, 0, sizeof(float) * data_size); + memset (diff_y_, 0, sizeof(float) * data_size); + + // x u x + // l x r + // x d x + const PointInT* point_up = &(input_->points [1]); + const PointInT* point_dn = point_up + (input_->width << 1);//&(input_->points [1 + (input_->width << 1)]); + const PointInT* point_lf = &(input_->points [input_->width]); + const PointInT* point_rg = point_lf + 2; //&(input_->points [input_->width + 2]); + float* diff_x_ptr = diff_x_ + ((input_->width + 1) << 2); + float* diff_y_ptr = diff_y_ + ((input_->width + 1) << 2); + unsigned diff_skip = 8; // skip last element in row and the first in the next row + + for (size_t ri = 1; ri < input_->height - 1; ++ri + , point_up += input_->width + , point_dn += input_->width + , point_lf += input_->width + , point_rg += input_->width + , diff_x_ptr += diff_skip + , diff_y_ptr += diff_skip) + { + for (size_t ci = 0; ci < input_->width - 2; ++ci, diff_x_ptr += 4, diff_y_ptr += 4) + { + diff_x_ptr[0] = point_rg[ci].x - point_lf[ci].x; + diff_x_ptr[1] = point_rg[ci].y - point_lf[ci].y; + diff_x_ptr[2] = point_rg[ci].z - point_lf[ci].z; + + diff_y_ptr[0] = point_dn[ci].x - point_up[ci].x; + diff_y_ptr[1] = point_dn[ci].y - point_up[ci].y; + diff_y_ptr[2] = point_dn[ci].z - point_up[ci].z; + } + } + + // Compute integral images + integral_image_DX_.setInput (diff_x_, input_->width, input_->height, 4, input_->width << 2); + integral_image_DY_.setInput (diff_y_, input_->width, input_->height, 4, input_->width << 2); + init_covariance_matrix_ = init_depth_change_ = init_simple_3d_gradient_ = false; + init_average_3d_gradient_ = true; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImageNormalEstimation::initAverageDepthChangeMethod () +{ + // number of DataType entries per element (equal or bigger than dimensions) + int element_stride = sizeof (PointInT) / sizeof (float); + // number of DataType entries per row (equal or bigger than element_stride number of elements per row) + int row_stride = element_stride * input_->width; + + const float *data_ = reinterpret_cast (&input_->points[0]); + + // integral image over the z - value + integral_image_depth_.setInput (&(data_[2]), input_->width, input_->height, element_stride, row_stride); + init_depth_change_ = true; + init_covariance_matrix_ = init_average_3d_gradient_ = init_simple_3d_gradient_ = false; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImageNormalEstimation::computePointNormal ( + const int pos_x, const int pos_y, const unsigned point_index, PointOutT &normal) +{ + float bad_point = std::numeric_limits::quiet_NaN (); + + if (normal_estimation_method_ == COVARIANCE_MATRIX) + { + if (!init_covariance_matrix_) + initCovarianceMatrixMethod (); + + unsigned count = integral_image_XYZ_.getFiniteElementsCount (pos_x - (rect_width_2_), pos_y - (rect_height_2_), rect_width_, rect_height_); + + // no valid points within the rectangular reagion? + if (count == 0) + { + normal.normal_x = normal.normal_y = normal.normal_z = normal.curvature = bad_point; + return; + } + + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix; + Eigen::Vector3f center; + typename IntegralImage2D::SecondOrderType so_elements; + center = integral_image_XYZ_.getFirstOrderSum(pos_x - rect_width_2_, pos_y - rect_height_2_, rect_width_, rect_height_).template cast (); + so_elements = integral_image_XYZ_.getSecondOrderSum(pos_x - rect_width_2_, pos_y - rect_height_2_, rect_width_, rect_height_); + + covariance_matrix.coeffRef (0) = static_cast (so_elements [0]); + covariance_matrix.coeffRef (1) = covariance_matrix.coeffRef (3) = static_cast (so_elements [1]); + covariance_matrix.coeffRef (2) = covariance_matrix.coeffRef (6) = static_cast (so_elements [2]); + covariance_matrix.coeffRef (4) = static_cast (so_elements [3]); + covariance_matrix.coeffRef (5) = covariance_matrix.coeffRef (7) = static_cast (so_elements [4]); + covariance_matrix.coeffRef (8) = static_cast (so_elements [5]); + covariance_matrix -= (center * center.transpose ()) / static_cast (count); + float eigen_value; + Eigen::Vector3f eigen_vector; + pcl::eigen33 (covariance_matrix, eigen_value, eigen_vector); + flipNormalTowardsViewpoint (input_->points[point_index], vpx_, vpy_, vpz_, eigen_vector[0], eigen_vector[1], eigen_vector[2]); + normal.getNormalVector3fMap () = eigen_vector; + + // Compute the curvature surface change + if (eigen_value > 0.0) + normal.curvature = fabsf (eigen_value / (covariance_matrix.coeff (0) + covariance_matrix.coeff (4) + covariance_matrix.coeff (8))); + else + normal.curvature = 0; + + return; + } + else if (normal_estimation_method_ == AVERAGE_3D_GRADIENT) + { + if (!init_average_3d_gradient_) + initAverage3DGradientMethod (); + + unsigned count_x = integral_image_DX_.getFiniteElementsCount (pos_x - rect_width_2_, pos_y - rect_height_2_, rect_width_, rect_height_); + unsigned count_y = integral_image_DY_.getFiniteElementsCount (pos_x - rect_width_2_, pos_y - rect_height_2_, rect_width_, rect_height_); + if (count_x == 0 || count_y == 0) + { + normal.normal_x = normal.normal_y = normal.normal_z = normal.curvature = bad_point; + return; + } + Eigen::Vector3d gradient_x = integral_image_DX_.getFirstOrderSum (pos_x - rect_width_2_, pos_y - rect_height_2_, rect_width_, rect_height_); + Eigen::Vector3d gradient_y = integral_image_DY_.getFirstOrderSum (pos_x - rect_width_2_, pos_y - rect_height_2_, rect_width_, rect_height_); + + Eigen::Vector3d normal_vector = gradient_y.cross (gradient_x); + double normal_length = normal_vector.squaredNorm (); + if (normal_length == 0.0f) + { + normal.getNormalVector3fMap ().setConstant (bad_point); + normal.curvature = bad_point; + return; + } + + normal_vector /= sqrt (normal_length); + + float nx = static_cast (normal_vector [0]); + float ny = static_cast (normal_vector [1]); + float nz = static_cast (normal_vector [2]); + + flipNormalTowardsViewpoint (input_->points[point_index], vpx_, vpy_, vpz_, nx, ny, nz); + + normal.normal_x = nx; + normal.normal_y = ny; + normal.normal_z = nz; + normal.curvature = bad_point; + return; + } + else if (normal_estimation_method_ == AVERAGE_DEPTH_CHANGE) + { + if (!init_depth_change_) + initAverageDepthChangeMethod (); + + // width and height are at least 3 x 3 + unsigned count_L_z = integral_image_depth_.getFiniteElementsCount (pos_x - rect_width_2_, pos_y - rect_height_4_, rect_width_2_, rect_height_2_); + unsigned count_R_z = integral_image_depth_.getFiniteElementsCount (pos_x + 1 , pos_y - rect_height_4_, rect_width_2_, rect_height_2_); + unsigned count_U_z = integral_image_depth_.getFiniteElementsCount (pos_x - rect_width_4_, pos_y - rect_height_2_, rect_width_2_, rect_height_2_); + unsigned count_D_z = integral_image_depth_.getFiniteElementsCount (pos_x - rect_width_4_, pos_y + 1 , rect_width_2_, rect_height_2_); + + if (count_L_z == 0 || count_R_z == 0 || count_U_z == 0 || count_D_z == 0) + { + normal.normal_x = normal.normal_y = normal.normal_z = normal.curvature = bad_point; + return; + } + + float mean_L_z = static_cast (integral_image_depth_.getFirstOrderSum (pos_x - rect_width_2_, pos_y - rect_height_4_, rect_width_2_, rect_height_2_) / count_L_z); + float mean_R_z = static_cast (integral_image_depth_.getFirstOrderSum (pos_x + 1 , pos_y - rect_height_4_, rect_width_2_, rect_height_2_) / count_R_z); + float mean_U_z = static_cast (integral_image_depth_.getFirstOrderSum (pos_x - rect_width_4_, pos_y - rect_height_2_, rect_width_2_, rect_height_2_) / count_U_z); + float mean_D_z = static_cast (integral_image_depth_.getFirstOrderSum (pos_x - rect_width_4_, pos_y + 1 , rect_width_2_, rect_height_2_) / count_D_z); + + PointInT pointL = input_->points[point_index - rect_width_4_ - 1]; + PointInT pointR = input_->points[point_index + rect_width_4_ + 1]; + PointInT pointU = input_->points[point_index - rect_height_4_ * input_->width - 1]; + PointInT pointD = input_->points[point_index + rect_height_4_ * input_->width + 1]; + + const float mean_x_z = mean_R_z - mean_L_z; + const float mean_y_z = mean_D_z - mean_U_z; + + const float mean_x_x = pointR.x - pointL.x; + const float mean_x_y = pointR.y - pointL.y; + const float mean_y_x = pointD.x - pointU.x; + const float mean_y_y = pointD.y - pointU.y; + + float normal_x = mean_x_y * mean_y_z - mean_x_z * mean_y_y; + float normal_y = mean_x_z * mean_y_x - mean_x_x * mean_y_z; + float normal_z = mean_x_x * mean_y_y - mean_x_y * mean_y_x; + + const float normal_length = (normal_x * normal_x + normal_y * normal_y + normal_z * normal_z); + + if (normal_length == 0.0f) + { + normal.getNormalVector3fMap ().setConstant (bad_point); + normal.curvature = bad_point; + return; + } + + flipNormalTowardsViewpoint (input_->points[point_index], vpx_, vpy_, vpz_, normal_x, normal_y, normal_z); + + const float scale = 1.0f / sqrtf (normal_length); + + normal.normal_x = normal_x * scale; + normal.normal_y = normal_y * scale; + normal.normal_z = normal_z * scale; + normal.curvature = bad_point; + + return; + } + else if (normal_estimation_method_ == SIMPLE_3D_GRADIENT) + { + if (!init_simple_3d_gradient_) + initSimple3DGradientMethod (); + + // this method does not work if lots of NaNs are in the neighborhood of the point + Eigen::Vector3d gradient_x = integral_image_XYZ_.getFirstOrderSum (pos_x + rect_width_2_, pos_y - rect_height_2_, 1, rect_height_) - + integral_image_XYZ_.getFirstOrderSum (pos_x - rect_width_2_, pos_y - rect_height_2_, 1, rect_height_); + + Eigen::Vector3d gradient_y = integral_image_XYZ_.getFirstOrderSum (pos_x - rect_width_2_, pos_y + rect_height_2_, rect_width_, 1) - + integral_image_XYZ_.getFirstOrderSum (pos_x - rect_width_2_, pos_y - rect_height_2_, rect_width_, 1); + Eigen::Vector3d normal_vector = gradient_y.cross (gradient_x); + double normal_length = normal_vector.squaredNorm (); + if (normal_length == 0.0f) + { + normal.getNormalVector3fMap ().setConstant (bad_point); + normal.curvature = bad_point; + return; + } + + normal_vector /= sqrt (normal_length); + + float nx = static_cast (normal_vector [0]); + float ny = static_cast (normal_vector [1]); + float nz = static_cast (normal_vector [2]); + + flipNormalTowardsViewpoint (input_->points[point_index], vpx_, vpy_, vpz_, nx, ny, nz); + + normal.normal_x = nx; + normal.normal_y = ny; + normal.normal_z = nz; + normal.curvature = bad_point; + return; + } + + normal.getNormalVector3fMap ().setConstant (bad_point); + normal.curvature = bad_point; + return; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template +void +sumArea (int start_x, int start_y, int end_x, int end_y, const int width, const int height, + const boost::function &f, + T & result) +{ + if (start_x < 0) + { + if (start_y < 0) + { + result += f (0, 0, end_x, end_y); + result += f (0, 0, -start_x, -start_y); + result += f (0, 0, -start_x, end_y); + result += f (0, 0, end_x, -start_y); + } + else if (end_y >= height) + { + result += f (0, start_y, end_x, height-1); + result += f (0, start_y, -start_x, height-1); + result += f (0, height-(end_y-(height-1)), end_x, height-1); + result += f (0, height-(end_y-(height-1)), -start_x, height-1); + } + else + { + result += f (0, start_y, end_x, end_y); + result += f (0, start_y, -start_x, end_y); + } + } + else if (start_y < 0) + { + if (end_x >= width) + { + result += f (start_x, 0, width-1, end_y); + result += f (start_x, 0, width-1, -start_y); + result += f (width-(end_x-(width-1)), 0, width-1, end_y); + result += f (width-(end_x-(width-1)), 0, width-1, -start_y); + } + else + { + result += f (start_x, 0, end_x, end_y); + result += f (start_x, 0, end_x, -start_y); + } + } + else if (end_x >= width) + { + if (end_y >= height) + { + result += f (start_x, start_y, width-1, height-1); + result += f (start_x, height-(end_y-(height-1)), width-1, height-1); + result += f (width-(end_x-(width-1)), start_y, width-1, height-1); + result += f (width-(end_x-(width-1)), height-(end_y-(height-1)), width-1, height-1); + } + else + { + result += f (start_x, start_y, width-1, end_y); + result += f (width-(end_x-(width-1)), start_y, width-1, end_y); + } + } + else if (end_y >= height) + { + result += f (start_x, start_y, end_x, height-1); + result += f (start_x, height-(end_y-(height-1)), end_x, height-1); + } + else + { + result += f (start_x, start_y, end_x, end_y); + } +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImageNormalEstimation::computePointNormalMirror ( + const int pos_x, const int pos_y, const unsigned point_index, PointOutT &normal) +{ + float bad_point = std::numeric_limits::quiet_NaN (); + + const int width = input_->width; + const int height = input_->height; + + // ============================================================== + if (normal_estimation_method_ == COVARIANCE_MATRIX) + { + if (!init_covariance_matrix_) + initCovarianceMatrixMethod (); + + const int start_x = pos_x - rect_width_2_; + const int start_y = pos_y - rect_height_2_; + const int end_x = start_x + rect_width_; + const int end_y = start_y + rect_height_; + + unsigned count = 0; + sumArea(start_x, start_y, end_x, end_y, width, height, boost::bind(&IntegralImage2D::getFiniteElementsCountSE, &integral_image_XYZ_, _1, _2, _3, _4), count); + + // no valid points within the rectangular reagion? + if (count == 0) + { + normal.normal_x = normal.normal_y = normal.normal_z = normal.curvature = bad_point; + return; + } + + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix; + Eigen::Vector3f center; + typename IntegralImage2D::SecondOrderType so_elements; + typename IntegralImage2D::ElementType tmp_center; + typename IntegralImage2D::SecondOrderType tmp_so_elements; + + center[0] = 0; + center[1] = 0; + center[2] = 0; + tmp_center[0] = 0; + tmp_center[1] = 0; + tmp_center[2] = 0; + so_elements[0] = 0; + so_elements[1] = 0; + so_elements[2] = 0; + so_elements[3] = 0; + so_elements[4] = 0; + so_elements[5] = 0; + + sumArea::ElementType>(start_x, start_y, end_x, end_y, width, height, boost::bind(&IntegralImage2D::getFirstOrderSumSE, &integral_image_XYZ_, _1, _2, _3, _4), tmp_center); + sumArea::SecondOrderType>(start_x, start_y, end_x, end_y, width, height, boost::bind(&IntegralImage2D::getSecondOrderSumSE, &integral_image_XYZ_, _1, _2, _3, _4), so_elements); + + center[0] = float (tmp_center[0]); + center[1] = float (tmp_center[1]); + center[2] = float (tmp_center[2]); + + covariance_matrix.coeffRef (0) = static_cast (so_elements [0]); + covariance_matrix.coeffRef (1) = covariance_matrix.coeffRef (3) = static_cast (so_elements [1]); + covariance_matrix.coeffRef (2) = covariance_matrix.coeffRef (6) = static_cast (so_elements [2]); + covariance_matrix.coeffRef (4) = static_cast (so_elements [3]); + covariance_matrix.coeffRef (5) = covariance_matrix.coeffRef (7) = static_cast (so_elements [4]); + covariance_matrix.coeffRef (8) = static_cast (so_elements [5]); + covariance_matrix -= (center * center.transpose ()) / static_cast (count); + float eigen_value; + Eigen::Vector3f eigen_vector; + pcl::eigen33 (covariance_matrix, eigen_value, eigen_vector); + flipNormalTowardsViewpoint (input_->points[point_index], vpx_, vpy_, vpz_, eigen_vector[0], eigen_vector[1], eigen_vector[2]); + normal.getNormalVector3fMap () = eigen_vector; + + // Compute the curvature surface change + if (eigen_value > 0.0) + normal.curvature = fabsf (eigen_value / (covariance_matrix.coeff (0) + covariance_matrix.coeff (4) + covariance_matrix.coeff (8))); + else + normal.curvature = 0; + + return; + } + // ======================================================= + else if (normal_estimation_method_ == AVERAGE_3D_GRADIENT) + { + if (!init_average_3d_gradient_) + initAverage3DGradientMethod (); + + const int start_x = pos_x - rect_width_2_; + const int start_y = pos_y - rect_height_2_; + const int end_x = start_x + rect_width_; + const int end_y = start_y + rect_height_; + + unsigned count_x = 0; + unsigned count_y = 0; + + sumArea(start_x, start_y, end_x, end_y, width, height, boost::bind(&IntegralImage2D::getFiniteElementsCountSE, &integral_image_DX_, _1, _2, _3, _4), count_x); + sumArea(start_x, start_y, end_x, end_y, width, height, boost::bind(&IntegralImage2D::getFiniteElementsCountSE, &integral_image_DY_, _1, _2, _3, _4), count_y); + + + if (count_x == 0 || count_y == 0) + { + normal.normal_x = normal.normal_y = normal.normal_z = normal.curvature = bad_point; + return; + } + Eigen::Vector3d gradient_x (0, 0, 0); + Eigen::Vector3d gradient_y (0, 0, 0); + + sumArea::ElementType>(start_x, start_y, end_x, end_y, width, height, boost::bind(&IntegralImage2D::getFirstOrderSumSE, &integral_image_DX_, _1, _2, _3, _4), gradient_x); + sumArea::ElementType>(start_x, start_y, end_x, end_y, width, height, boost::bind(&IntegralImage2D::getFirstOrderSumSE, &integral_image_DY_, _1, _2, _3, _4), gradient_y); + + + Eigen::Vector3d normal_vector = gradient_y.cross (gradient_x); + double normal_length = normal_vector.squaredNorm (); + if (normal_length == 0.0f) + { + normal.getNormalVector3fMap ().setConstant (bad_point); + normal.curvature = bad_point; + return; + } + + normal_vector /= sqrt (normal_length); + + float nx = static_cast (normal_vector [0]); + float ny = static_cast (normal_vector [1]); + float nz = static_cast (normal_vector [2]); + + flipNormalTowardsViewpoint (input_->points[point_index], vpx_, vpy_, vpz_, nx, ny, nz); + + normal.normal_x = nx; + normal.normal_y = ny; + normal.normal_z = nz; + normal.curvature = bad_point; + return; + } + // ====================================================== + else if (normal_estimation_method_ == AVERAGE_DEPTH_CHANGE) + { + if (!init_depth_change_) + initAverageDepthChangeMethod (); + + int point_index_L_x = pos_x - rect_width_4_ - 1; + int point_index_L_y = pos_y; + int point_index_R_x = pos_x + rect_width_4_ + 1; + int point_index_R_y = pos_y; + int point_index_U_x = pos_x - 1; + int point_index_U_y = pos_y - rect_height_4_; + int point_index_D_x = pos_x + 1; + int point_index_D_y = pos_y + rect_height_4_; + + if (point_index_L_x < 0) + point_index_L_x = -point_index_L_x; + if (point_index_U_x < 0) + point_index_U_x = -point_index_U_x; + if (point_index_U_y < 0) + point_index_U_y = -point_index_U_y; + + if (point_index_R_x >= width) + point_index_R_x = width-(point_index_R_x-(width-1)); + if (point_index_D_x >= width) + point_index_D_x = width-(point_index_D_x-(width-1)); + if (point_index_D_y >= height) + point_index_D_y = height-(point_index_D_y-(height-1)); + + const int start_x_L = pos_x - rect_width_2_; + const int start_y_L = pos_y - rect_height_4_; + const int end_x_L = start_x_L + rect_width_2_; + const int end_y_L = start_y_L + rect_height_2_; + + const int start_x_R = pos_x + 1; + const int start_y_R = pos_y - rect_height_4_; + const int end_x_R = start_x_R + rect_width_2_; + const int end_y_R = start_y_R + rect_height_2_; + + const int start_x_U = pos_x - rect_width_4_; + const int start_y_U = pos_y - rect_height_2_; + const int end_x_U = start_x_U + rect_width_2_; + const int end_y_U = start_y_U + rect_height_2_; + + const int start_x_D = pos_x - rect_width_4_; + const int start_y_D = pos_y + 1; + const int end_x_D = start_x_D + rect_width_2_; + const int end_y_D = start_y_D + rect_height_2_; + + unsigned count_L_z = 0; + unsigned count_R_z = 0; + unsigned count_U_z = 0; + unsigned count_D_z = 0; + + sumArea(start_x_L, start_y_L, end_x_L, end_y_L, width, height, boost::bind(&IntegralImage2D::getFiniteElementsCountSE, &integral_image_depth_, _1, _2, _3, _4), count_L_z); + sumArea(start_x_R, start_y_R, end_x_R, end_y_R, width, height, boost::bind(&IntegralImage2D::getFiniteElementsCountSE, &integral_image_depth_, _1, _2, _3, _4), count_R_z); + sumArea(start_x_U, start_y_U, end_x_U, end_y_U, width, height, boost::bind(&IntegralImage2D::getFiniteElementsCountSE, &integral_image_depth_, _1, _2, _3, _4), count_U_z); + sumArea(start_x_D, start_y_D, end_x_D, end_y_D, width, height, boost::bind(&IntegralImage2D::getFiniteElementsCountSE, &integral_image_depth_, _1, _2, _3, _4), count_D_z); + + if (count_L_z == 0 || count_R_z == 0 || count_U_z == 0 || count_D_z == 0) + { + normal.normal_x = normal.normal_y = normal.normal_z = normal.curvature = bad_point; + return; + } + + float mean_L_z = 0; + float mean_R_z = 0; + float mean_U_z = 0; + float mean_D_z = 0; + + sumArea(start_x_L, start_y_L, end_x_L, end_y_L, width, height, boost::bind(&IntegralImage2D::getFirstOrderSumSE, &integral_image_depth_, _1, _2, _3, _4), mean_L_z); + sumArea(start_x_R, start_y_R, end_x_R, end_y_R, width, height, boost::bind(&IntegralImage2D::getFirstOrderSumSE, &integral_image_depth_, _1, _2, _3, _4), mean_R_z); + sumArea(start_x_U, start_y_U, end_x_U, end_y_U, width, height, boost::bind(&IntegralImage2D::getFirstOrderSumSE, &integral_image_depth_, _1, _2, _3, _4), mean_U_z); + sumArea(start_x_D, start_y_D, end_x_D, end_y_D, width, height, boost::bind(&IntegralImage2D::getFirstOrderSumSE, &integral_image_depth_, _1, _2, _3, _4), mean_D_z); + + mean_L_z /= float (count_L_z); + mean_R_z /= float (count_R_z); + mean_U_z /= float (count_U_z); + mean_D_z /= float (count_D_z); + + + PointInT pointL = input_->points[point_index_L_y*width + point_index_L_x]; + PointInT pointR = input_->points[point_index_R_y*width + point_index_R_x]; + PointInT pointU = input_->points[point_index_U_y*width + point_index_U_x]; + PointInT pointD = input_->points[point_index_D_y*width + point_index_D_x]; + + const float mean_x_z = mean_R_z - mean_L_z; + const float mean_y_z = mean_D_z - mean_U_z; + + const float mean_x_x = pointR.x - pointL.x; + const float mean_x_y = pointR.y - pointL.y; + const float mean_y_x = pointD.x - pointU.x; + const float mean_y_y = pointD.y - pointU.y; + + float normal_x = mean_x_y * mean_y_z - mean_x_z * mean_y_y; + float normal_y = mean_x_z * mean_y_x - mean_x_x * mean_y_z; + float normal_z = mean_x_x * mean_y_y - mean_x_y * mean_y_x; + + const float normal_length = (normal_x * normal_x + normal_y * normal_y + normal_z * normal_z); + + if (normal_length == 0.0f) + { + normal.getNormalVector3fMap ().setConstant (bad_point); + normal.curvature = bad_point; + return; + } + + flipNormalTowardsViewpoint (input_->points[point_index], vpx_, vpy_, vpz_, normal_x, normal_y, normal_z); + + const float scale = 1.0f / sqrtf (normal_length); + + normal.normal_x = normal_x * scale; + normal.normal_y = normal_y * scale; + normal.normal_z = normal_z * scale; + normal.curvature = bad_point; + + return; + } + // ======================================================== + else if (normal_estimation_method_ == SIMPLE_3D_GRADIENT) + { + PCL_THROW_EXCEPTION (PCLException, "BORDER_POLICY_MIRROR not supported for normal estimation method SIMPLE_3D_GRADIENT"); + } + + normal.getNormalVector3fMap ().setConstant (bad_point); + normal.curvature = bad_point; + return; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImageNormalEstimation::computeFeature (PointCloudOut &output) +{ + output.sensor_origin_ = input_->sensor_origin_; + output.sensor_orientation_ = input_->sensor_orientation_; + + float bad_point = std::numeric_limits::quiet_NaN (); + + // compute depth-change map + unsigned char * depthChangeMap = new unsigned char[input_->points.size ()]; + memset (depthChangeMap, 255, input_->points.size ()); + + unsigned index = 0; + for (unsigned int ri = 0; ri < input_->height-1; ++ri) + { + for (unsigned int ci = 0; ci < input_->width-1; ++ci, ++index) + { + index = ri * input_->width + ci; + + const float depth = input_->points [index].z; + const float depthR = input_->points [index + 1].z; + const float depthD = input_->points [index + input_->width].z; + + //const float depthDependendDepthChange = (max_depth_change_factor_ * (fabs(depth)+1.0f))/(500.0f*0.001f); + const float depthDependendDepthChange = (max_depth_change_factor_ * (fabsf (depth) + 1.0f) * 2.0f); + + if (fabs (depth - depthR) > depthDependendDepthChange + || !pcl_isfinite (depth) || !pcl_isfinite (depthR)) + { + depthChangeMap[index] = 0; + depthChangeMap[index+1] = 0; + } + if (fabs (depth - depthD) > depthDependendDepthChange + || !pcl_isfinite (depth) || !pcl_isfinite (depthD)) + { + depthChangeMap[index] = 0; + depthChangeMap[index + input_->width] = 0; + } + } + } + + // compute distance map + //float *distanceMap = new float[input_->points.size ()]; + if (distance_map_ != NULL) delete[] distance_map_; + distance_map_ = new float[input_->points.size ()]; + float *distanceMap = distance_map_; + for (size_t index = 0; index < input_->points.size (); ++index) + { + if (depthChangeMap[index] == 0) + distanceMap[index] = 0.0f; + else + distanceMap[index] = static_cast (input_->width + input_->height); + } + + // first pass + float* previous_row = distanceMap; + float* current_row = previous_row + input_->width; + for (size_t ri = 1; ri < input_->height; ++ri) + { + for (size_t ci = 1; ci < input_->width; ++ci) + { + const float upLeft = previous_row [ci - 1] + 1.4f; //distanceMap[(ri-1)*input_->width + ci-1] + 1.4f; + const float up = previous_row [ci] + 1.0f; //distanceMap[(ri-1)*input_->width + ci] + 1.0f; + const float upRight = previous_row [ci + 1] + 1.4f; //distanceMap[(ri-1)*input_->width + ci+1] + 1.4f; + const float left = current_row [ci - 1] + 1.0f; //distanceMap[ri*input_->width + ci-1] + 1.0f; + const float center = current_row [ci]; //distanceMap[ri*input_->width + ci]; + + const float minValue = std::min (std::min (upLeft, up), std::min (left, upRight)); + + if (minValue < center) + current_row [ci] = minValue; //distanceMap[ri * input_->width + ci] = minValue; + } + previous_row = current_row; + current_row += input_->width; + } + + float* next_row = distanceMap + input_->width * (input_->height - 1); + current_row = next_row - input_->width; + // second pass + for (int ri = input_->height-2; ri >= 0; --ri) + { + for (int ci = input_->width-2; ci >= 0; --ci) + { + const float lowerLeft = next_row [ci - 1] + 1.4f; //distanceMap[(ri+1)*input_->width + ci-1] + 1.4f; + const float lower = next_row [ci] + 1.0f; //distanceMap[(ri+1)*input_->width + ci] + 1.0f; + const float lowerRight = next_row [ci + 1] + 1.4f; //distanceMap[(ri+1)*input_->width + ci+1] + 1.4f; + const float right = current_row [ci + 1] + 1.0f; //distanceMap[ri*input_->width + ci+1] + 1.0f; + const float center = current_row [ci]; //distanceMap[ri*input_->width + ci]; + + const float minValue = std::min (std::min (lowerLeft, lower), std::min (right, lowerRight)); + + if (minValue < center) + current_row [ci] = minValue; //distanceMap[ri*input_->width + ci] = minValue; + } + next_row = current_row; + current_row -= input_->width; + } + + if (indices_->size () < input_->size ()) + computeFeaturePart (distanceMap, bad_point, output); + else + computeFeatureFull (distanceMap, bad_point, output); + + delete[] depthChangeMap; +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImageNormalEstimation::computeFeatureFull (const float *distanceMap, + const float &bad_point, + PointCloudOut &output) +{ + unsigned index = 0; + + if (border_policy_ == BORDER_POLICY_IGNORE) + { + // Set all normals that we do not touch to NaN + // top and bottom borders + // That sets the output density to false! + output.is_dense = false; + unsigned border = int(normal_smoothing_size_); + PointOutT* vec1 = &output [0]; + PointOutT* vec2 = vec1 + input_->width * (input_->height - border); + + size_t count = border * input_->width; + for (size_t idx = 0; idx < count; ++idx) + { + vec1 [idx].getNormalVector3fMap ().setConstant (bad_point); + vec1 [idx].curvature = bad_point; + vec2 [idx].getNormalVector3fMap ().setConstant (bad_point); + vec2 [idx].curvature = bad_point; + } + + // left and right borders actually columns + vec1 = &output [border * input_->width]; + vec2 = vec1 + input_->width - border; + for (size_t ri = border; ri < input_->height - border; ++ri, vec1 += input_->width, vec2 += input_->width) + { + for (size_t ci = 0; ci < border; ++ci) + { + vec1 [ci].getNormalVector3fMap ().setConstant (bad_point); + vec1 [ci].curvature = bad_point; + vec2 [ci].getNormalVector3fMap ().setConstant (bad_point); + vec2 [ci].curvature = bad_point; + } + } + + if (use_depth_dependent_smoothing_) + { + index = border + input_->width * border; + unsigned skip = (border << 1); + for (unsigned ri = border; ri < input_->height - border; ++ri, index += skip) + { + for (unsigned ci = border; ci < input_->width - border; ++ci, ++index) + { + index = ri * input_->width + ci; + + const float depth = input_->points[index].z; + if (!pcl_isfinite (depth)) + { + output[index].getNormalVector3fMap ().setConstant (bad_point); + output[index].curvature = bad_point; + continue; + } + + float smoothing = (std::min)(distanceMap[index], normal_smoothing_size_ + static_cast(depth)/10.0f); + + if (smoothing > 2.0f) + { + setRectSize (static_cast (smoothing), static_cast (smoothing)); + computePointNormal (ci, ri, index, output [index]); + } + else + { + output[index].getNormalVector3fMap ().setConstant (bad_point); + output[index].curvature = bad_point; + } + } + } + } + else + { + float smoothing_constant = normal_smoothing_size_; + + index = border + input_->width * border; + unsigned skip = (border << 1); + for (unsigned ri = border; ri < input_->height - border; ++ri, index += skip) + { + for (unsigned ci = border; ci < input_->width - border; ++ci, ++index) + { + index = ri * input_->width + ci; + + if (!pcl_isfinite (input_->points[index].z)) + { + output [index].getNormalVector3fMap ().setConstant (bad_point); + output [index].curvature = bad_point; + continue; + } + + float smoothing = (std::min)(distanceMap[index], smoothing_constant); + + if (smoothing > 2.0f) + { + setRectSize (static_cast (smoothing), static_cast (smoothing)); + computePointNormal (ci, ri, index, output [index]); + } + else + { + output [index].getNormalVector3fMap ().setConstant (bad_point); + output [index].curvature = bad_point; + } + } + } + } + } + else if (border_policy_ == BORDER_POLICY_MIRROR) + { + output.is_dense = false; + + if (use_depth_dependent_smoothing_) + { + //index = 0; + //unsigned skip = 0; + //for (unsigned ri = 0; ri < input_->height; ++ri, index += skip) + for (unsigned ri = 0; ri < input_->height; ++ri) + { + //for (unsigned ci = 0; ci < input_->width; ++ci, ++index) + for (unsigned ci = 0; ci < input_->width; ++ci) + { + index = ri * input_->width + ci; + + const float depth = input_->points[index].z; + if (!pcl_isfinite (depth)) + { + output[index].getNormalVector3fMap ().setConstant (bad_point); + output[index].curvature = bad_point; + continue; + } + + float smoothing = (std::min)(distanceMap[index], normal_smoothing_size_ + static_cast(depth)/10.0f); + + if (smoothing > 2.0f) + { + setRectSize (static_cast (smoothing), static_cast (smoothing)); + computePointNormalMirror (ci, ri, index, output [index]); + } + else + { + output[index].getNormalVector3fMap ().setConstant (bad_point); + output[index].curvature = bad_point; + } + } + } + } + else + { + float smoothing_constant = normal_smoothing_size_; + + //index = border + input_->width * border; + //unsigned skip = (border << 1); + //for (unsigned ri = border; ri < input_->height - border; ++ri, index += skip) + for (unsigned ri = 0; ri < input_->height; ++ri) + { + //for (unsigned ci = border; ci < input_->width - border; ++ci, ++index) + for (unsigned ci = 0; ci < input_->width; ++ci) + { + index = ri * input_->width + ci; + + if (!pcl_isfinite (input_->points[index].z)) + { + output [index].getNormalVector3fMap ().setConstant (bad_point); + output [index].curvature = bad_point; + continue; + } + + float smoothing = (std::min)(distanceMap[index], smoothing_constant); + + if (smoothing > 2.0f) + { + setRectSize (static_cast (smoothing), static_cast (smoothing)); + computePointNormalMirror (ci, ri, index, output [index]); + } + else + { + output [index].getNormalVector3fMap ().setConstant (bad_point); + output [index].curvature = bad_point; + } + } + } + } + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntegralImageNormalEstimation::computeFeaturePart (const float *distanceMap, + const float &bad_point, + PointCloudOut &output) +{ + if (border_policy_ == BORDER_POLICY_IGNORE) + { + output.is_dense = false; + unsigned border = int(normal_smoothing_size_); + unsigned bottom = input_->height > border ? input_->height - border : 0; + unsigned right = input_->width > border ? input_->width - border : 0; + if (use_depth_dependent_smoothing_) + { + // Iterating over the entire index vector + for (std::size_t idx = 0; idx < indices_->size (); ++idx) + { + unsigned pt_index = (*indices_)[idx]; + unsigned u = pt_index % input_->width; + unsigned v = pt_index / input_->width; + if (v < border || v > bottom) + { + output.points[idx].getNormalVector3fMap ().setConstant (bad_point); + output.points[idx].curvature = bad_point; + continue; + } + + if (u < border || v > right) + { + output.points[idx].getNormalVector3fMap ().setConstant (bad_point); + output.points[idx].curvature = bad_point; + continue; + } + + const float depth = input_->points[pt_index].z; + if (!pcl_isfinite (depth)) + { + output.points[idx].getNormalVector3fMap ().setConstant (bad_point); + output.points[idx].curvature = bad_point; + continue; + } + + float smoothing = (std::min)(distanceMap[pt_index], normal_smoothing_size_ + static_cast(depth)/10.0f); + if (smoothing > 2.0f) + { + setRectSize (static_cast (smoothing), static_cast (smoothing)); + computePointNormal (u, v, pt_index, output [idx]); + } + else + { + output[idx].getNormalVector3fMap ().setConstant (bad_point); + output[idx].curvature = bad_point; + } + } + } + else + { + float smoothing_constant = normal_smoothing_size_; + // Iterating over the entire index vector + for (std::size_t idx = 0; idx < indices_->size (); ++idx) + { + unsigned pt_index = (*indices_)[idx]; + unsigned u = pt_index % input_->width; + unsigned v = pt_index / input_->width; + if (v < border || v > bottom) + { + output.points[idx].getNormalVector3fMap ().setConstant (bad_point); + output.points[idx].curvature = bad_point; + continue; + } + + if (u < border || v > right) + { + output.points[idx].getNormalVector3fMap ().setConstant (bad_point); + output.points[idx].curvature = bad_point; + continue; + } + + if (!pcl_isfinite (input_->points[pt_index].z)) + { + output [idx].getNormalVector3fMap ().setConstant (bad_point); + output [idx].curvature = bad_point; + continue; + } + + float smoothing = (std::min)(distanceMap[pt_index], smoothing_constant); + + if (smoothing > 2.0f) + { + setRectSize (static_cast (smoothing), static_cast (smoothing)); + computePointNormal (u, v, pt_index, output [idx]); + } + else + { + output [pt_index].getNormalVector3fMap ().setConstant (bad_point); + output [pt_index].curvature = bad_point; + } + } + } + }// border_policy_ == BORDER_POLICY_IGNORE + else if (border_policy_ == BORDER_POLICY_MIRROR) + { + output.is_dense = false; + + if (use_depth_dependent_smoothing_) + { + for (std::size_t idx = 0; idx < indices_->size (); ++idx) + { + unsigned pt_index = (*indices_)[idx]; + unsigned u = pt_index % input_->width; + unsigned v = pt_index / input_->width; + + const float depth = input_->points[pt_index].z; + if (!pcl_isfinite (depth)) + { + output[idx].getNormalVector3fMap ().setConstant (bad_point); + output[idx].curvature = bad_point; + continue; + } + + float smoothing = (std::min)(distanceMap[pt_index], normal_smoothing_size_ + static_cast(depth)/10.0f); + + if (smoothing > 2.0f) + { + setRectSize (static_cast (smoothing), static_cast (smoothing)); + computePointNormalMirror (u, v, pt_index, output [idx]); + } + else + { + output[idx].getNormalVector3fMap ().setConstant (bad_point); + output[idx].curvature = bad_point; + } + } + } + else + { + float smoothing_constant = normal_smoothing_size_; + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + unsigned pt_index = (*indices_)[idx]; + unsigned u = pt_index % input_->width; + unsigned v = pt_index / input_->width; + + if (!pcl_isfinite (input_->points[pt_index].z)) + { + output [idx].getNormalVector3fMap ().setConstant (bad_point); + output [idx].curvature = bad_point; + continue; + } + + float smoothing = (std::min)(distanceMap[pt_index], smoothing_constant); + + if (smoothing > 2.0f) + { + setRectSize (static_cast (smoothing), static_cast (smoothing)); + computePointNormalMirror (u, v, pt_index, output [idx]); + } + else + { + output [idx].getNormalVector3fMap ().setConstant (bad_point); + output [idx].curvature = bad_point; + } + } + } + } // border_policy_ == BORDER_POLICY_MIRROR +} + +////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::IntegralImageNormalEstimation::initCompute () +{ + if (!input_->isOrganized ()) + { + PCL_ERROR ("[pcl::IntegralImageNormalEstimation::initCompute] Input dataset is not organized (height = 1).\n"); + return (false); + } + return (Feature::initCompute ()); +} + +#define PCL_INSTANTIATE_IntegralImageNormalEstimation(T,NT) template class PCL_EXPORTS pcl::IntegralImageNormalEstimation; + +#endif + diff --git a/pcl-1.7/pcl/features/impl/intensity_gradient.hpp b/pcl-1.7/pcl/features/impl/intensity_gradient.hpp new file mode 100644 index 0000000..cd1a520 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/intensity_gradient.hpp @@ -0,0 +1,237 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_IMPL_INTENSITY_GRADIENT_H_ +#define PCL_FEATURES_IMPL_INTENSITY_GRADIENT_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntensityGradientEstimation ::computePointIntensityGradient ( + const pcl::PointCloud &cloud, const std::vector &indices, + const Eigen::Vector3f &point, float mean_intensity, const Eigen::Vector3f &normal, Eigen::Vector3f &gradient) +{ + if (indices.size () < 3) + { + gradient[0] = gradient[1] = gradient[2] = std::numeric_limits::quiet_NaN (); + return; + } + + Eigen::Matrix3f A = Eigen::Matrix3f::Zero (); + Eigen::Vector3f b = Eigen::Vector3f::Zero (); + + for (size_t i_point = 0; i_point < indices.size (); ++i_point) + { + PointInT p = cloud.points[indices[i_point]]; + if (!pcl_isfinite (p.x) || + !pcl_isfinite (p.y) || + !pcl_isfinite (p.z) || + !pcl_isfinite (intensity_ (p))) + continue; + + p.x -= point[0]; + p.y -= point[1]; + p.z -= point[2]; + intensity_.demean (p, mean_intensity); + + A (0, 0) += p.x * p.x; + A (0, 1) += p.x * p.y; + A (0, 2) += p.x * p.z; + + A (1, 1) += p.y * p.y; + A (1, 2) += p.y * p.z; + + A (2, 2) += p.z * p.z; + + b[0] += p.x * intensity_ (p); + b[1] += p.y * intensity_ (p); + b[2] += p.z * intensity_ (p); + } + // Fill in the lower triangle of A + A (1, 0) = A (0, 1); + A (2, 0) = A (0, 2); + A (2, 1) = A (1, 2); + +//* + Eigen::Vector3f x = A.colPivHouseholderQr ().solve (b); +/*/ + + Eigen::Vector3f eigen_values; + Eigen::Matrix3f eigen_vectors; + eigen33 (A, eigen_vectors, eigen_values); + + b = eigen_vectors.transpose () * b; + + if ( eigen_values (0) != 0) + b (0) /= eigen_values (0); + else + b (0) = 0; + + if ( eigen_values (1) != 0) + b (1) /= eigen_values (1); + else + b (1) = 0; + + if ( eigen_values (2) != 0) + b (2) /= eigen_values (2); + else + b (2) = 0; + + + Eigen::Vector3f x = eigen_vectors * b; + +// if (A.col (0).squaredNorm () != 0) +// x [0] /= A.col (0).squaredNorm (); +// b -= x [0] * A.col (0); +// +// +// if (A.col (1).squaredNorm () != 0) +// x [1] /= A.col (1).squaredNorm (); +// b -= x[1] * A.col (1); +// +// x [2] = b.dot (A.col (2)); +// if (A.col (2).squaredNorm () != 0) +// x[2] /= A.col (2).squaredNorm (); + // Fit a hyperplane to the data + +//*/ +// std::cout << A << "\n*\n" << bb << "\n=\n" << x << "\nvs.\n" << x2 << "\n\n"; +// std::cout << A * x << "\nvs.\n" << A * x2 << "\n\n------\n"; + // Project the gradient vector, x, onto the tangent plane + gradient = (Eigen::Matrix3f::Identity () - normal*normal.transpose ()) * x; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntensityGradientEstimation::computeFeature (PointCloudOut &output) +{ + // Allocate enough space to hold the results + // \note This resize is irrelevant for a radiusSearch (). + std::vector nn_indices (k_); + std::vector nn_dists (k_); + output.is_dense = true; + + // If the data is dense, we don't need to check for NaN + if (surface_->is_dense) + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) private (nn_indices, nn_dists) num_threads(threads_) +#endif + // Iterating over the entire index vector + for (int idx = 0; idx < static_cast (indices_->size ()); ++idx) + { + PointOutT &p_out = output.points[idx]; + + if (!this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists)) + { + p_out.gradient[0] = p_out.gradient[1] = p_out.gradient[2] = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + continue; + } + + Eigen::Vector3f centroid; + float mean_intensity = 0; + // Initialize to 0 + centroid.setZero (); + for (size_t i = 0; i < nn_indices.size (); ++i) + { + centroid += surface_->points[nn_indices[i]].getVector3fMap (); + mean_intensity += intensity_ (surface_->points[nn_indices[i]]); + } + centroid /= static_cast (nn_indices.size ()); + mean_intensity /= static_cast (nn_indices.size ()); + + Eigen::Vector3f normal = Eigen::Vector3f::Map (normals_->points[(*indices_) [idx]].normal); + Eigen::Vector3f gradient; + computePointIntensityGradient (*surface_, nn_indices, centroid, mean_intensity, normal, gradient); + + p_out.gradient[0] = gradient[0]; + p_out.gradient[1] = gradient[1]; + p_out.gradient[2] = gradient[2]; + } + } + else + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) private (nn_indices, nn_dists) num_threads(threads_) +#endif + // Iterating over the entire index vector + for (int idx = 0; idx < static_cast (indices_->size ()); ++idx) + { + PointOutT &p_out = output.points[idx]; + if (!isFinite ((*surface_) [(*indices_)[idx]]) || + !this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists)) + { + p_out.gradient[0] = p_out.gradient[1] = p_out.gradient[2] = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + continue; + } + Eigen::Vector3f centroid; + float mean_intensity = 0; + // Initialize to 0 + centroid.setZero (); + unsigned cp = 0; + for (size_t i = 0; i < nn_indices.size (); ++i) + { + // Check if the point is invalid + if (!isFinite ((*surface_) [nn_indices[i]])) + continue; + + centroid += surface_->points [nn_indices[i]].getVector3fMap (); + mean_intensity += intensity_ (surface_->points [nn_indices[i]]); + ++cp; + } + centroid /= static_cast (cp); + mean_intensity /= static_cast (cp); + Eigen::Vector3f normal = Eigen::Vector3f::Map (normals_->points[(*indices_) [idx]].normal); + Eigen::Vector3f gradient; + computePointIntensityGradient (*surface_, nn_indices, centroid, mean_intensity, normal, gradient); + + p_out.gradient[0] = gradient[0]; + p_out.gradient[1] = gradient[1]; + p_out.gradient[2] = gradient[2]; + } + } +} + +#define PCL_INSTANTIATE_IntensityGradientEstimation(InT,NT,OutT) template class PCL_EXPORTS pcl::IntensityGradientEstimation; + +#endif // PCL_FEATURES_IMPL_INTENSITY_GRADIENT_H_ diff --git a/pcl-1.7/pcl/features/impl/intensity_spin.hpp b/pcl-1.7/pcl/features/impl/intensity_spin.hpp new file mode 100644 index 0000000..669c101 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/intensity_spin.hpp @@ -0,0 +1,174 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_IMPL_INTENSITY_SPIN_H_ +#define PCL_FEATURES_IMPL_INTENSITY_SPIN_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntensitySpinEstimation::computeIntensitySpinImage ( + const PointCloudIn &cloud, float radius, float sigma, + int k, + const std::vector &indices, + const std::vector &squared_distances, + Eigen::MatrixXf &intensity_spin_image) +{ + // Determine the number of bins to use based on the size of intensity_spin_image + int nr_distance_bins = static_cast (intensity_spin_image.cols ()); + int nr_intensity_bins = static_cast (intensity_spin_image.rows ()); + + // Find the min and max intensity values in the given neighborhood + float min_intensity = std::numeric_limits::max (); + float max_intensity = -std::numeric_limits::max (); + for (int idx = 0; idx < k; ++idx) + { + min_intensity = (std::min) (min_intensity, cloud.points[indices[idx]].intensity); + max_intensity = (std::max) (max_intensity, cloud.points[indices[idx]].intensity); + } + + float constant = 1.0f / (2.0f * sigma_ * sigma_); + // Compute the intensity spin image + intensity_spin_image.setZero (); + for (int idx = 0; idx < k; ++idx) + { + // Normalize distance and intensity values to: 0.0 <= d,i < nr_distance_bins,nr_intensity_bins + const float eps = std::numeric_limits::epsilon (); + float d = static_cast (nr_distance_bins) * sqrtf (squared_distances[idx]) / (radius + eps); + float i = static_cast (nr_intensity_bins) * + (cloud.points[indices[idx]].intensity - min_intensity) / (max_intensity - min_intensity + eps); + + if (sigma == 0) + { + // If sigma is zero, update the histogram with no smoothing kernel + int d_idx = static_cast (d); + int i_idx = static_cast (i); + intensity_spin_image (i_idx, d_idx) += 1; + } + else + { + // Compute the bin indices that need to be updated (+/- 3 standard deviations) + int d_idx_min = (std::max)(static_cast (floor (d - 3*sigma)), 0); + int d_idx_max = (std::min)(static_cast (ceil (d + 3*sigma)), nr_distance_bins - 1); + int i_idx_min = (std::max)(static_cast (floor (i - 3*sigma)), 0); + int i_idx_max = (std::min)(static_cast (ceil (i + 3*sigma)), nr_intensity_bins - 1); + + // Update the appropriate bins of the histogram + for (int i_idx = i_idx_min; i_idx <= i_idx_max; ++i_idx) + { + for (int d_idx = d_idx_min; d_idx <= d_idx_max; ++d_idx) + { + // Compute a "soft" update weight based on the distance between the point and the bin + float w = expf (-powf (d - static_cast (d_idx), 2.0f) * constant - powf (i - static_cast (i_idx), 2.0f) * constant); + intensity_spin_image (i_idx, d_idx) += w; + } + } + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IntensitySpinEstimation::computeFeature (PointCloudOut &output) +{ + // Make sure a search radius is set + if (search_radius_ == 0.0) + { + PCL_ERROR ("[pcl::%s::computeFeature] The search radius must be set before computing the feature!\n", + getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + // Make sure the spin image has valid dimensions + if (nr_intensity_bins_ <= 0) + { + PCL_ERROR ("[pcl::%s::computeFeature] The number of intensity bins must be greater than zero!\n", + getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + if (nr_distance_bins_ <= 0) + { + PCL_ERROR ("[pcl::%s::computeFeature] The number of distance bins must be greater than zero!\n", + getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + Eigen::MatrixXf intensity_spin_image (nr_intensity_bins_, nr_distance_bins_); + // Allocate enough space to hold the radiusSearch results + std::vector nn_indices (surface_->points.size ()); + std::vector nn_dist_sqr (surface_->points.size ()); + + output.is_dense = true; + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + // Find neighbors within the search radius + // TODO: do we want to use searchForNeigbors instead? + int k = tree_->radiusSearch ((*indices_)[idx], search_radius_, nn_indices, nn_dist_sqr); + if (k == 0) + { + for (int bin = 0; bin < nr_intensity_bins_ * nr_distance_bins_; ++bin) + output.points[idx].histogram[bin] = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + continue; + } + + // Compute the intensity spin image + computeIntensitySpinImage (*surface_, static_cast (search_radius_), sigma_, k, nn_indices, nn_dist_sqr, intensity_spin_image); + + // Copy into the resultant cloud + int bin = 0; + for (int bin_j = 0; bin_j < intensity_spin_image.cols (); ++bin_j) + for (int bin_i = 0; bin_i < intensity_spin_image.rows (); ++bin_i) + output.points[idx].histogram[bin++] = intensity_spin_image (bin_i, bin_j); + } +} + +#define PCL_INSTANTIATE_IntensitySpinEstimation(T,NT) template class PCL_EXPORTS pcl::IntensitySpinEstimation; + +#endif // PCL_FEATURES_IMPL_INTENSITY_SPIN_H_ + diff --git a/pcl-1.7/pcl/features/impl/linear_least_squares_normal.hpp b/pcl-1.7/pcl/features/impl/linear_least_squares_normal.hpp new file mode 100644 index 0000000..ff1d38b --- /dev/null +++ b/pcl-1.7/pcl/features/impl/linear_least_squares_normal.hpp @@ -0,0 +1,270 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_LINEAR_LEAST_SQUARES_NORMAL_HPP_ +#define PCL_FEATURES_LINEAR_LEAST_SQUARES_NORMAL_HPP_ +#define EIGEN_II_METHOD 1 + +#include +#include +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::LinearLeastSquaresNormalEstimation::~LinearLeastSquaresNormalEstimation () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LinearLeastSquaresNormalEstimation::computePointNormal ( + const int pos_x, const int pos_y, PointOutT &normal) +{ + const float bad_point = std::numeric_limits::quiet_NaN (); + + const int width = input_->width; + const int height = input_->height; + + const int x = pos_x; + const int y = pos_y; + + const int index = y * width + x; + + const float px = input_->points[index].x; + const float py = input_->points[index].y; + const float pz = input_->points[index].z; + + if (pcl_isnan (px)) + { + normal.normal_x = bad_point; + normal.normal_y = bad_point; + normal.normal_z = bad_point; + normal.curvature = bad_point; + + return; + } + + float smoothingSize = normal_smoothing_size_; + if (use_depth_dependent_smoothing_) smoothingSize = smoothingSize*(pz+0.5f); + + const int smoothingSizeInt = static_cast (smoothingSize); + + float matA0 = 0.0f; + float matA1 = 0.0f; + float matA3 = 0.0f; + + float vecb0 = 0.0f; + float vecb1 = 0.0f; + + for (int v = y - smoothingSizeInt; v <= y + smoothingSizeInt; v += smoothingSizeInt) + { + for (int u = x - smoothingSizeInt; u <= x + smoothingSizeInt; u += smoothingSizeInt) + { + if (u < 0 || u >= width || v < 0 || v >= height) continue; + + const int index2 = v * width + u; + + const float qx = input_->points[index2].x; + const float qy = input_->points[index2].y; + const float qz = input_->points[index2].z; + + if (pcl_isnan (qx)) continue; + + const float delta = qz - pz; + const float i = qx - px; + const float j = qy - py; + + float depthChangeThreshold = pz*pz * 0.05f * max_depth_change_factor_; + if (use_depth_dependent_smoothing_) depthChangeThreshold *= pz; + + const float f = fabs (delta) > depthChangeThreshold ? 0 : 1; + + matA0 += f * i * i; + matA1 += f * i * j; + matA3 += f * j * j; + vecb0 += f * i * delta; + vecb1 += f * j * delta; + } + } + + const float det = matA0 * matA3 - matA1 * matA1; + const float ddx = matA3 * vecb0 - matA1 * vecb1; + const float ddy = -matA1 * vecb0 + matA0 * vecb1; + + const float nx = ddx; + const float ny = ddy; + const float nz = -det * pz; + + const float length = nx * nx + ny * ny + nz * nz; + + if (length <= 0.01f) + { + normal.normal_x = bad_point; + normal.normal_y = bad_point; + normal.normal_z = bad_point; + normal.curvature = bad_point; + } + else + { + const float normInv = 1.0f / sqrtf (length); + + normal.normal_x = -nx * normInv; + normal.normal_y = -ny * normInv; + normal.normal_z = -nz * normInv; + normal.curvature = bad_point; + } + + return; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LinearLeastSquaresNormalEstimation::computeFeature (PointCloudOut &output) +{ + const float bad_point = std::numeric_limits::quiet_NaN (); + + const int width = input_->width; + const int height = input_->height; + + // we compute the normals as follows: + // ---------------------------------- + // + // for the depth-gradient you can make the following first-order Taylor approximation: + // D(x + dx) - D(x) = dx^T \Delta D + h.o.t. + // + // build linear system by stacking up equation for 8 neighbor points: + // Y = X \Delta D + // + // => \Delta D = (X^T X)^{-1} X^T Y + // => \Delta D = (A)^{-1} b + + //const float smoothingSize = 30.0f; + for (int y = 0; y < height; ++y) + { + for (int x = 0; x < width; ++x) + { + const int index = y * width + x; + + const float px = input_->points[index].x; + const float py = input_->points[index].y; + const float pz = input_->points[index].z; + + if (pcl_isnan(px)) continue; + + //float depthDependentSmoothingSize = smoothingSize + pz / 10.0f; + + float smoothingSize = normal_smoothing_size_; + //if (use_depth_dependent_smoothing_) smoothingSize *= pz; + //if (use_depth_dependent_smoothing_) smoothingSize += pz*5; + //if (smoothingSize < 1.0f) smoothingSize += 1.0f; + + const int smoothingSizeInt = static_cast(smoothingSize); + + float matA0 = 0.0f; + float matA1 = 0.0f; + float matA3 = 0.0f; + + float vecb0 = 0.0f; + float vecb1 = 0.0f; + + for (int v = y - smoothingSizeInt; v <= y + smoothingSizeInt; v += smoothingSizeInt) + { + for (int u = x - smoothingSizeInt; u <= x + smoothingSizeInt; u += smoothingSizeInt) + { + if (u < 0 || u >= width || v < 0 || v >= height) continue; + + const int index2 = v * width + u; + + const float qx = input_->points[index2].x; + const float qy = input_->points[index2].y; + const float qz = input_->points[index2].z; + + if (pcl_isnan(qx)) continue; + + const float delta = qz - pz; + const float i = qx - px; + const float j = qy - py; + + const float depthDependendDepthChange = (max_depth_change_factor_ * (fabsf (pz) + 1.0f) * 2.0f); + const float f = fabs(delta) > depthDependendDepthChange ? 0 : 1; + + //float f = fabs(delta) > (pz * 0.05f - 0.3f) ? 0 : 1; + //const float f = fabs(delta) > (pz*pz * 0.05f * max_depth_change_factor_) ? 0 : 1; + //float f = Math.Abs(delta) > (depth * Math.Log(depth + 1.0) * 0.02f - 0.2f) ? 0 : 1; + + matA0 += f * i * i; + matA1 += f * i * j; + matA3 += f * j * j; + vecb0 += f * i * delta; + vecb1 += f * j * delta; + } + } + + const float det = matA0 * matA3 - matA1 * matA1; + const float ddx = matA3 * vecb0 - matA1 * vecb1; + const float ddy = -matA1 * vecb0 + matA0 * vecb1; + + const float nx = ddx; + const float ny = ddy; + const float nz = -det * pz; + + const float length = nx * nx + ny * ny + nz * nz; + + if (length <= 0.0f) + { + output.points[index].normal_x = bad_point; + output.points[index].normal_y = bad_point; + output.points[index].normal_z = bad_point; + output.points[index].curvature = bad_point; + } + else + { + const float normInv = 1.0f / sqrtf (length); + + output.points[index].normal_x = nx * normInv; + output.points[index].normal_y = ny * normInv; + output.points[index].normal_z = nz * normInv; + output.points[index].curvature = bad_point; + } + } + } +} + +#define PCL_INSTANTIATE_LinearLeastSquaresNormalEstimation(T,NT) template class PCL_EXPORTS pcl::LinearLeastSquaresNormalEstimation; +//#define LinearLeastSquaresNormalEstimation(T,NT) template class PCL_EXPORTS pcl::LinearLeastSquaresNormalEstimation; + +#endif + diff --git a/pcl-1.7/pcl/features/impl/moment_invariants.hpp b/pcl-1.7/pcl/features/impl/moment_invariants.hpp new file mode 100644 index 0000000..639b278 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/moment_invariants.hpp @@ -0,0 +1,163 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_IMPL_MOMENT_INVARIANTS_H_ +#define PCL_FEATURES_IMPL_MOMENT_INVARIANTS_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentInvariantsEstimation::computePointMomentInvariants ( + const pcl::PointCloud &cloud, const std::vector &indices, + float &j1, float &j2, float &j3) +{ + // Estimate the XYZ centroid + compute3DCentroid (cloud, indices, xyz_centroid_); + + // Initalize the centralized moments + float mu200 = 0, mu020 = 0, mu002 = 0, mu110 = 0, mu101 = 0, mu011 = 0; + + // Iterate over the nearest neighbors set + for (size_t nn_idx = 0; nn_idx < indices.size (); ++nn_idx) + { + // Demean the points + temp_pt_[0] = cloud.points[indices[nn_idx]].x - xyz_centroid_[0]; + temp_pt_[1] = cloud.points[indices[nn_idx]].y - xyz_centroid_[1]; + temp_pt_[2] = cloud.points[indices[nn_idx]].z - xyz_centroid_[2]; + + mu200 += temp_pt_[0] * temp_pt_[0]; + mu020 += temp_pt_[1] * temp_pt_[1]; + mu002 += temp_pt_[2] * temp_pt_[2]; + mu110 += temp_pt_[0] * temp_pt_[1]; + mu101 += temp_pt_[0] * temp_pt_[2]; + mu011 += temp_pt_[1] * temp_pt_[2]; + } + + // Save the moment invariants + j1 = mu200 + mu020 + mu002; + j2 = mu200*mu020 + mu200*mu002 + mu020*mu002 - mu110*mu110 - mu101*mu101 - mu011*mu011; + j3 = mu200*mu020*mu002 + 2*mu110*mu101*mu011 - mu002*mu110*mu110 - mu020*mu101*mu101 - mu200*mu011*mu011; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentInvariantsEstimation::computePointMomentInvariants ( + const pcl::PointCloud &cloud, float &j1, float &j2, float &j3) +{ + // Estimate the XYZ centroid + compute3DCentroid (cloud, xyz_centroid_); + + // Initalize the centralized moments + float mu200 = 0, mu020 = 0, mu002 = 0, mu110 = 0, mu101 = 0, mu011 = 0; + + // Iterate over the nearest neighbors set + for (size_t nn_idx = 0; nn_idx < cloud.points.size (); ++nn_idx ) + { + // Demean the points + temp_pt_[0] = cloud.points[nn_idx].x - xyz_centroid_[0]; + temp_pt_[1] = cloud.points[nn_idx].y - xyz_centroid_[1]; + temp_pt_[2] = cloud.points[nn_idx].z - xyz_centroid_[2]; + + mu200 += temp_pt_[0] * temp_pt_[0]; + mu020 += temp_pt_[1] * temp_pt_[1]; + mu002 += temp_pt_[2] * temp_pt_[2]; + mu110 += temp_pt_[0] * temp_pt_[1]; + mu101 += temp_pt_[0] * temp_pt_[2]; + mu011 += temp_pt_[1] * temp_pt_[2]; + } + + // Save the moment invariants + j1 = mu200 + mu020 + mu002; + j2 = mu200*mu020 + mu200*mu002 + mu020*mu002 - mu110*mu110 - mu101*mu101 - mu011*mu011; + j3 = mu200*mu020*mu002 + 2*mu110*mu101*mu011 - mu002*mu110*mu110 - mu020*mu101*mu101 - mu200*mu011*mu011; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentInvariantsEstimation::computeFeature (PointCloudOut &output) +{ + // Allocate enough space to hold the results + // \note This resize is irrelevant for a radiusSearch (). + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + output.is_dense = true; + // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense + if (input_->is_dense) + { + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) + { + output.points[idx].j1 = output.points[idx].j2 = output.points[idx].j3 = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + continue; + } + + computePointMomentInvariants (*surface_, nn_indices, + output.points[idx].j1, output.points[idx].j2, output.points[idx].j3); + } + } + else + { + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + if (!isFinite ((*input_)[(*indices_)[idx]]) || + this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) + { + output.points[idx].j1 = output.points[idx].j2 = output.points[idx].j3 = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + continue; + } + + computePointMomentInvariants (*surface_, nn_indices, + output.points[idx].j1, output.points[idx].j2, output.points[idx].j3); + } + } +} + +#define PCL_INSTANTIATE_MomentInvariantsEstimation(T,NT) template class PCL_EXPORTS pcl::MomentInvariantsEstimation; + +#endif // PCL_FEATURES_IMPL_MOMENT_INVARIANTS_H_ + diff --git a/pcl-1.7/pcl/features/impl/moment_of_inertia_estimation.hpp b/pcl-1.7/pcl/features/impl/moment_of_inertia_estimation.hpp new file mode 100644 index 0000000..c00670c --- /dev/null +++ b/pcl-1.7/pcl/features/impl/moment_of_inertia_estimation.hpp @@ -0,0 +1,649 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : Sergey Ushakov + * Email : sergey.s.ushakov@mail.ru + * + */ + +#ifndef PCL_MOMENT_OF_INERTIA_ESTIMATION_HPP_ +#define PCL_MOMENT_OF_INERTIA_ESTIMATION_HPP_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::MomentOfInertiaEstimation::MomentOfInertiaEstimation () : + is_valid_ (false), + step_ (10.0f), + point_mass_ (0.0001f), + normalize_ (true), + mean_value_ (0.0f, 0.0f, 0.0f), + major_axis_ (0.0f, 0.0f, 0.0f), + middle_axis_ (0.0f, 0.0f, 0.0f), + minor_axis_ (0.0f, 0.0f, 0.0f), + major_value_ (0.0f), + middle_value_ (0.0f), + minor_value_ (0.0f), + moment_of_inertia_ (), + eccentricity_ (), + aabb_min_point_ (), + aabb_max_point_ (), + obb_min_point_ (), + obb_max_point_ (), + obb_position_ (0.0f, 0.0f, 0.0f), + obb_rotational_matrix_ () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::MomentOfInertiaEstimation::~MomentOfInertiaEstimation () +{ + moment_of_inertia_.clear (); + eccentricity_.clear (); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::setAngleStep (const float step) +{ + if (step <= 0.0f) + return; + + step_ = step; + + is_valid_ = false; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::MomentOfInertiaEstimation::getAngleStep () const +{ + return (step_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::setNormalizePointMassFlag (bool need_to_normalize) +{ + normalize_ = need_to_normalize; + + is_valid_ = false; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::MomentOfInertiaEstimation::getNormalizePointMassFlag () const +{ + return (normalize_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::setPointMass (const float point_mass) +{ + if (point_mass <= 0.0f) + return; + + point_mass_ = point_mass; + + is_valid_ = false; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::MomentOfInertiaEstimation::getPointMass () const +{ + return (point_mass_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::compute () +{ + moment_of_inertia_.clear (); + eccentricity_.clear (); + + if (!initCompute ()) + { + deinitCompute (); + return; + } + + if (normalize_) + { + if (indices_->size () > 0) + point_mass_ = 1.0f / static_cast (indices_->size () * indices_->size ()); + else + point_mass_ = 1.0f; + } + + computeMeanValue (); + + Eigen::Matrix covariance_matrix; + covariance_matrix.setZero (); + computeCovarianceMatrix (covariance_matrix); + + computeEigenVectors (covariance_matrix, major_axis_, middle_axis_, minor_axis_, major_value_, middle_value_, minor_value_); + + float theta = 0.0f; + while (theta <= 90.0f) + { + float phi = 0.0f; + Eigen::Vector3f rotated_vector; + rotateVector (major_axis_, middle_axis_, theta, rotated_vector); + while (phi <= 360.0f) + { + Eigen::Vector3f current_axis; + rotateVector (rotated_vector, minor_axis_, phi, current_axis); + current_axis.normalize (); + + //compute moment of inertia for the current axis + float current_moment_of_inertia = calculateMomentOfInertia (current_axis, mean_value_); + moment_of_inertia_.push_back (current_moment_of_inertia); + + //compute eccentricity for the current plane + typename pcl::PointCloud::Ptr projected_cloud (new pcl::PointCloud ()); + getProjectedCloud (current_axis, mean_value_, projected_cloud); + Eigen::Matrix covariance_matrix; + covariance_matrix.setZero (); + computeCovarianceMatrix (projected_cloud, covariance_matrix); + projected_cloud.reset (); + float current_eccentricity = computeEccentricity (covariance_matrix, current_axis); + eccentricity_.push_back (current_eccentricity); + + phi += step_; + } + theta += step_; + } + + computeOBB (); + + is_valid_ = true; + + deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::MomentOfInertiaEstimation::getAABB (PointT& min_point, PointT& max_point) const +{ + min_point = aabb_min_point_; + max_point = aabb_max_point_; + + return (is_valid_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::MomentOfInertiaEstimation::getOBB (PointT& min_point, PointT& max_point, PointT& position, Eigen::Matrix3f& rotational_matrix) const +{ + min_point = obb_min_point_; + max_point = obb_max_point_; + position.x = obb_position_ (0); + position.y = obb_position_ (1); + position.z = obb_position_ (2); + rotational_matrix = obb_rotational_matrix_; + + return (is_valid_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::computeOBB () +{ + obb_min_point_.x = std::numeric_limits ::max (); + obb_min_point_.y = std::numeric_limits ::max (); + obb_min_point_.z = std::numeric_limits ::max (); + + obb_max_point_.x = std::numeric_limits ::min (); + obb_max_point_.y = std::numeric_limits ::min (); + obb_max_point_.z = std::numeric_limits ::min (); + + unsigned int number_of_points = static_cast (indices_->size ()); + for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + { + float x = (input_->points[(*indices_)[i_point]].x - mean_value_ (0)) * major_axis_ (0) + + (input_->points[(*indices_)[i_point]].y - mean_value_ (1)) * major_axis_ (1) + + (input_->points[(*indices_)[i_point]].z - mean_value_ (2)) * major_axis_ (2); + float y = (input_->points[(*indices_)[i_point]].x - mean_value_ (0)) * middle_axis_ (0) + + (input_->points[(*indices_)[i_point]].y - mean_value_ (1)) * middle_axis_ (1) + + (input_->points[(*indices_)[i_point]].z - mean_value_ (2)) * middle_axis_ (2); + float z = (input_->points[(*indices_)[i_point]].x - mean_value_ (0)) * minor_axis_ (0) + + (input_->points[(*indices_)[i_point]].y - mean_value_ (1)) * minor_axis_ (1) + + (input_->points[(*indices_)[i_point]].z - mean_value_ (2)) * minor_axis_ (2); + + if (x <= obb_min_point_.x) obb_min_point_.x = x; + if (y <= obb_min_point_.y) obb_min_point_.y = y; + if (z <= obb_min_point_.z) obb_min_point_.z = z; + + if (x >= obb_max_point_.x) obb_max_point_.x = x; + if (y >= obb_max_point_.y) obb_max_point_.y = y; + if (z >= obb_max_point_.z) obb_max_point_.z = z; + } + + obb_rotational_matrix_ << major_axis_ (0), middle_axis_ (0), minor_axis_ (0), + major_axis_ (1), middle_axis_ (1), minor_axis_ (1), + major_axis_ (2), middle_axis_ (2), minor_axis_ (2); + + Eigen::Vector3f shift ( + (obb_max_point_.x + obb_min_point_.x) / 2.0f, + (obb_max_point_.y + obb_min_point_.y) / 2.0f, + (obb_max_point_.z + obb_min_point_.z) / 2.0f); + + obb_min_point_.x -= shift (0); + obb_min_point_.y -= shift (1); + obb_min_point_.z -= shift (2); + + obb_max_point_.x -= shift (0); + obb_max_point_.y -= shift (1); + obb_max_point_.z -= shift (2); + + obb_position_ = mean_value_ + obb_rotational_matrix_ * shift; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::MomentOfInertiaEstimation::getEigenValues (float& major, float& middle, float& minor) const +{ + major = major_value_; + middle = middle_value_; + minor = minor_value_; + + return (is_valid_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::MomentOfInertiaEstimation::getEigenVectors (Eigen::Vector3f& major, Eigen::Vector3f& middle, Eigen::Vector3f& minor) const +{ + major = major_axis_; + middle = middle_axis_; + minor = minor_axis_; + + return (is_valid_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::MomentOfInertiaEstimation::getMomentOfInertia (std::vector & moment_of_inertia) const +{ + moment_of_inertia.resize (moment_of_inertia_.size (), 0.0f); + std::copy (moment_of_inertia_.begin (), moment_of_inertia_.end (), moment_of_inertia.begin ()); + + return (is_valid_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::MomentOfInertiaEstimation::getEccentricity (std::vector & eccentricity) const +{ + eccentricity.resize (eccentricity_.size (), 0.0f); + std::copy (eccentricity_.begin (), eccentricity_.end (), eccentricity.begin ()); + + return (is_valid_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::computeMeanValue () +{ + mean_value_ (0) = 0.0f; + mean_value_ (1) = 0.0f; + mean_value_ (2) = 0.0f; + + aabb_min_point_.x = std::numeric_limits ::max (); + aabb_min_point_.y = std::numeric_limits ::max (); + aabb_min_point_.z = std::numeric_limits ::max (); + + aabb_max_point_.x = -std::numeric_limits ::max (); + aabb_max_point_.y = -std::numeric_limits ::max (); + aabb_max_point_.z = -std::numeric_limits ::max (); + + unsigned int number_of_points = static_cast (indices_->size ()); + for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + { + mean_value_ (0) += input_->points[(*indices_)[i_point]].x; + mean_value_ (1) += input_->points[(*indices_)[i_point]].y; + mean_value_ (2) += input_->points[(*indices_)[i_point]].z; + + if (input_->points[(*indices_)[i_point]].x <= aabb_min_point_.x) aabb_min_point_.x = input_->points[(*indices_)[i_point]].x; + if (input_->points[(*indices_)[i_point]].y <= aabb_min_point_.y) aabb_min_point_.y = input_->points[(*indices_)[i_point]].y; + if (input_->points[(*indices_)[i_point]].z <= aabb_min_point_.z) aabb_min_point_.z = input_->points[(*indices_)[i_point]].z; + + if (input_->points[(*indices_)[i_point]].x >= aabb_max_point_.x) aabb_max_point_.x = input_->points[(*indices_)[i_point]].x; + if (input_->points[(*indices_)[i_point]].y >= aabb_max_point_.y) aabb_max_point_.y = input_->points[(*indices_)[i_point]].y; + if (input_->points[(*indices_)[i_point]].z >= aabb_max_point_.z) aabb_max_point_.z = input_->points[(*indices_)[i_point]].z; + } + + if (number_of_points == 0) + number_of_points = 1; + + mean_value_ (0) /= number_of_points; + mean_value_ (1) /= number_of_points; + mean_value_ (2) /= number_of_points; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::computeCovarianceMatrix (Eigen::Matrix & covariance_matrix) const +{ + covariance_matrix.setZero (); + + unsigned int number_of_points = static_cast (indices_->size ()); + float factor = 1.0f / static_cast ((number_of_points - 1 > 0)?(number_of_points - 1):1); + for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + { + Eigen::Vector3f current_point (0.0f, 0.0f, 0.0f); + current_point (0) = input_->points[(*indices_)[i_point]].x - mean_value_ (0); + current_point (1) = input_->points[(*indices_)[i_point]].y - mean_value_ (1); + current_point (2) = input_->points[(*indices_)[i_point]].z - mean_value_ (2); + + covariance_matrix += current_point * current_point.transpose (); + } + + covariance_matrix *= factor; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::computeCovarianceMatrix (PointCloudConstPtr cloud, Eigen::Matrix & covariance_matrix) const +{ + covariance_matrix.setZero (); + + unsigned int number_of_points = static_cast (cloud->points.size ()); + float factor = 1.0f / static_cast ((number_of_points - 1 > 0)?(number_of_points - 1):1); + Eigen::Vector3f current_point; + for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + { + current_point (0) = cloud->points[i_point].x - mean_value_ (0); + current_point (1) = cloud->points[i_point].y - mean_value_ (1); + current_point (2) = cloud->points[i_point].z - mean_value_ (2); + + covariance_matrix += current_point * current_point.transpose (); + } + + covariance_matrix *= factor; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::computeEigenVectors (const Eigen::Matrix & covariance_matrix, + Eigen::Vector3f& major_axis, Eigen::Vector3f& middle_axis, Eigen::Vector3f& minor_axis, float& major_value, + float& middle_value, float& minor_value) +{ + Eigen::EigenSolver > eigen_solver; + eigen_solver.compute (covariance_matrix); + + Eigen::EigenSolver >::EigenvectorsType eigen_vectors; + Eigen::EigenSolver >::EigenvalueType eigen_values; + eigen_vectors = eigen_solver.eigenvectors (); + eigen_values = eigen_solver.eigenvalues (); + + unsigned int temp = 0; + unsigned int major_index = 0; + unsigned int middle_index = 1; + unsigned int minor_index = 2; + + if (eigen_values.real () (major_index) < eigen_values.real () (middle_index)) + { + temp = major_index; + major_index = middle_index; + middle_index = temp; + } + + if (eigen_values.real () (major_index) < eigen_values.real () (minor_index)) + { + temp = major_index; + major_index = minor_index; + minor_index = temp; + } + + if (eigen_values.real () (middle_index) < eigen_values.real () (minor_index)) + { + temp = minor_index; + minor_index = middle_index; + middle_index = temp; + } + + major_value = eigen_values.real () (major_index); + middle_value = eigen_values.real () (middle_index); + minor_value = eigen_values.real () (minor_index); + + major_axis = eigen_vectors.col (major_index).real (); + middle_axis = eigen_vectors.col (middle_index).real (); + minor_axis = eigen_vectors.col (minor_index).real (); + + major_axis.normalize (); + middle_axis.normalize (); + minor_axis.normalize (); + + float det = major_axis.dot (middle_axis.cross (minor_axis)); + if (det <= 0.0f) + { + major_axis (0) = -major_axis (0); + major_axis (1) = -major_axis (1); + major_axis (2) = -major_axis (2); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::rotateVector (const Eigen::Vector3f& vector, const Eigen::Vector3f& axis, const float angle, Eigen::Vector3f& rotated_vector) const +{ + Eigen::Matrix rotation_matrix; + const float x = axis (0); + const float y = axis (1); + const float z = axis (2); + const float rad = M_PI / 180.0f; + const float cosine = cos (angle * rad); + const float sine = sin (angle * rad); + rotation_matrix << cosine + (1 - cosine) * x * x, (1 - cosine) * x * y - sine * z, (1 - cosine) * x * z + sine * y, + (1 - cosine) * y * x + sine * z, cosine + (1 - cosine) * y * y, (1 - cosine) * y * z - sine * x, + (1 - cosine) * z * x - sine * y, (1 - cosine) * z * y + sine * x, cosine + (1 - cosine) * z * z; + + rotated_vector = rotation_matrix * vector; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::MomentOfInertiaEstimation::calculateMomentOfInertia (const Eigen::Vector3f& current_axis, const Eigen::Vector3f& mean_value) const +{ + float moment_of_inertia = 0.0f; + unsigned int number_of_points = static_cast (indices_->size ()); + for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + { + Eigen::Vector3f vector; + vector (0) = mean_value (0) - input_->points[(*indices_)[i_point]].x; + vector (1) = mean_value (1) - input_->points[(*indices_)[i_point]].y; + vector (2) = mean_value (2) - input_->points[(*indices_)[i_point]].z; + + Eigen::Vector3f product = vector.cross (current_axis); + + float distance = product (0) * product (0) + product (1) * product (1) + product (2) * product (2); + + moment_of_inertia += distance; + } + + return (point_mass_ * moment_of_inertia); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::getProjectedCloud (const Eigen::Vector3f& normal_vector, const Eigen::Vector3f& point, typename pcl::PointCloud ::Ptr projected_cloud) const +{ + const float D = - normal_vector.dot (point); + + unsigned int number_of_points = static_cast (indices_->size ()); + projected_cloud->points.resize (number_of_points, PointT ()); + + for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + { + const unsigned int index = (*indices_)[i_point]; + float K = - (D + normal_vector (0) * input_->points[index].x + normal_vector (1) * input_->points[index].y + normal_vector (2) * input_->points[index].z); + PointT projected_point; + projected_point.x = input_->points[index].x + K * normal_vector (0); + projected_point.y = input_->points[index].y + K * normal_vector (1); + projected_point.z = input_->points[index].z + K * normal_vector (2); + projected_cloud->points[i_point] = projected_point; + } + projected_cloud->width = number_of_points; + projected_cloud->height = 1; + projected_cloud->header = input_->header; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::MomentOfInertiaEstimation::computeEccentricity (const Eigen::Matrix & covariance_matrix, const Eigen::Vector3f& normal_vector) +{ + Eigen::Vector3f major_axis (0.0f, 0.0f, 0.0f); + Eigen::Vector3f middle_axis (0.0f, 0.0f, 0.0f); + Eigen::Vector3f minor_axis (0.0f, 0.0f, 0.0f); + float major_value = 0.0f; + float middle_value = 0.0f; + float minor_value = 0.0f; + computeEigenVectors (covariance_matrix, major_axis, middle_axis, minor_axis, major_value, middle_value, minor_value); + + float major = abs (major_axis.dot (normal_vector)); + float middle = abs (middle_axis.dot (normal_vector)); + float minor = abs (minor_axis.dot (normal_vector)); + + float eccentricity = 0.0f; + + if (major >= middle && major >= minor && middle_value != 0.0f) + eccentricity = pow (1.0f - (minor_value * minor_value) / (middle_value * middle_value), 0.5f); + + if (middle >= major && middle >= minor && major_value != 0.0f) + eccentricity = pow (1.0f - (minor_value * minor_value) / (major_value * major_value), 0.5f); + + if (minor >= major && minor >= middle && major_value != 0.0f) + eccentricity = pow (1.0f - (middle_value * middle_value) / (major_value * major_value), 0.5f); + + return (eccentricity); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::MomentOfInertiaEstimation::getMassCenter (Eigen::Vector3f& mass_center) const +{ + mass_center = mean_value_; + + return (is_valid_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::setInputCloud (const PointCloudConstPtr& cloud) +{ + input_ = cloud; + + is_valid_ = false; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::setIndices (const IndicesPtr& indices) +{ + indices_ = indices; + fake_indices_ = false; + use_indices_ = true; + + is_valid_ = false; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::setIndices (const IndicesConstPtr& indices) +{ + indices_.reset (new std::vector (*indices)); + fake_indices_ = false; + use_indices_ = true; + + is_valid_ = false; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::setIndices (const PointIndicesConstPtr& indices) +{ + indices_.reset (new std::vector (indices->indices)); + fake_indices_ = false; + use_indices_ = true; + + is_valid_ = false; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MomentOfInertiaEstimation::setIndices (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols) +{ + if ((nb_rows > input_->height) || (row_start > input_->height)) + { + PCL_ERROR ("[PCLBase::setIndices] cloud is only %d height", input_->height); + return; + } + + if ((nb_cols > input_->width) || (col_start > input_->width)) + { + PCL_ERROR ("[PCLBase::setIndices] cloud is only %d width", input_->width); + return; + } + + size_t row_end = row_start + nb_rows; + if (row_end > input_->height) + { + PCL_ERROR ("[PCLBase::setIndices] %d is out of rows range %d", row_end, input_->height); + return; + } + + size_t col_end = col_start + nb_cols; + if (col_end > input_->width) + { + PCL_ERROR ("[PCLBase::setIndices] %d is out of columns range %d", col_end, input_->width); + return; + } + + indices_.reset (new std::vector); + indices_->reserve (nb_cols * nb_rows); + for(size_t i = row_start; i < row_end; i++) + for(size_t j = col_start; j < col_end; j++) + indices_->push_back (static_cast ((i * input_->width) + j)); + fake_indices_ = false; + use_indices_ = true; + + is_valid_ = false; +} + +#endif // PCL_MOMENT_OF_INERTIA_ESTIMATION_HPP_ diff --git a/pcl-1.7/pcl/features/impl/multiscale_feature_persistence.hpp b/pcl-1.7/pcl/features/impl/multiscale_feature_persistence.hpp new file mode 100644 index 0000000..a4c560c --- /dev/null +++ b/pcl-1.7/pcl/features/impl/multiscale_feature_persistence.hpp @@ -0,0 +1,252 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_FEATURES_IMPL_MULTISCALE_FEATURE_PERSISTENCE_H_ +#define PCL_FEATURES_IMPL_MULTISCALE_FEATURE_PERSISTENCE_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::MultiscaleFeaturePersistence::MultiscaleFeaturePersistence () : + scale_values_ (), + alpha_ (0), + distance_metric_ (L1), + feature_estimator_ (), + features_at_scale_ (), + features_at_scale_vectorized_ (), + mean_feature_ (), + feature_representation_ (), + unique_features_indices_ (), + unique_features_table_ () +{ + feature_representation_.reset (new DefaultPointRepresentation); + // No input is needed, hack around the initCompute () check from PCLBase + input_.reset (new pcl::PointCloud ()); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::MultiscaleFeaturePersistence::initCompute () +{ + if (!PCLBase::initCompute ()) + { + PCL_ERROR ("[pcl::MultiscaleFeaturePersistence::initCompute] PCLBase::initCompute () failed - no input cloud was given.\n"); + return false; + } + if (!feature_estimator_) + { + PCL_ERROR ("[pcl::MultiscaleFeaturePersistence::initCompute] No feature estimator was set\n"); + return false; + } + if (scale_values_.empty ()) + { + PCL_ERROR ("[pcl::MultiscaleFeaturePersistence::initCompute] No scale values were given\n"); + return false; + } + + mean_feature_.resize (feature_representation_->getNumberOfDimensions ()); + + return true; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MultiscaleFeaturePersistence::computeFeaturesAtAllScales () +{ + features_at_scale_.resize (scale_values_.size ()); + features_at_scale_vectorized_.resize (scale_values_.size ()); + for (size_t scale_i = 0; scale_i < scale_values_.size (); ++scale_i) + { + FeatureCloudPtr feature_cloud (new FeatureCloud ()); + computeFeatureAtScale (scale_values_[scale_i], feature_cloud); + features_at_scale_[scale_i] = feature_cloud; + + // Vectorize each feature and insert it into the vectorized feature storage + std::vector > feature_cloud_vectorized (feature_cloud->points.size ()); + for (size_t feature_i = 0; feature_i < feature_cloud->points.size (); ++feature_i) + { + std::vector feature_vectorized (feature_representation_->getNumberOfDimensions ()); + feature_representation_->vectorize (feature_cloud->points[feature_i], feature_vectorized); + feature_cloud_vectorized[feature_i] = feature_vectorized; + } + features_at_scale_vectorized_[scale_i] = feature_cloud_vectorized; + } +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MultiscaleFeaturePersistence::computeFeatureAtScale (float &scale, + FeatureCloudPtr &features) +{ + feature_estimator_->setRadiusSearch (scale); + feature_estimator_->compute (*features); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::MultiscaleFeaturePersistence::distanceBetweenFeatures (const std::vector &a, + const std::vector &b) +{ + return (pcl::selectNorm > (a, b, static_cast (a.size ()), distance_metric_)); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MultiscaleFeaturePersistence::calculateMeanFeature () +{ + // Reset mean feature + for (int i = 0; i < feature_representation_->getNumberOfDimensions (); ++i) + mean_feature_[i] = 0.0f; + + float normalization_factor = 0.0f; + for (std::vector > >::iterator scale_it = features_at_scale_vectorized_.begin (); scale_it != features_at_scale_vectorized_.end(); ++scale_it) { + normalization_factor += static_cast (scale_it->size ()); + for (std::vector >::iterator feature_it = scale_it->begin (); feature_it != scale_it->end (); ++feature_it) + for (int dim_i = 0; dim_i < feature_representation_->getNumberOfDimensions (); ++dim_i) + mean_feature_[dim_i] += (*feature_it)[dim_i]; + } + + for (int dim_i = 0; dim_i < feature_representation_->getNumberOfDimensions (); ++dim_i) + mean_feature_[dim_i] /= normalization_factor; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MultiscaleFeaturePersistence::extractUniqueFeatures () +{ + unique_features_indices_.resize (scale_values_.size ()); + unique_features_table_.resize (scale_values_.size ()); + for (size_t scale_i = 0; scale_i < features_at_scale_vectorized_.size (); ++scale_i) + { + // Calculate standard deviation within the scale + float standard_dev = 0.0; + std::vector diff_vector (features_at_scale_vectorized_[scale_i].size ()); + for (size_t point_i = 0; point_i < features_at_scale_vectorized_[scale_i].size (); ++point_i) + { + float diff = distanceBetweenFeatures (features_at_scale_vectorized_[scale_i][point_i], mean_feature_); + standard_dev += diff * diff; + diff_vector[point_i] = diff; + } + standard_dev = sqrtf (standard_dev / static_cast (features_at_scale_vectorized_[scale_i].size ())); + PCL_DEBUG ("[pcl::MultiscaleFeaturePersistence::extractUniqueFeatures] Standard deviation for scale %f is %f\n", scale_values_[scale_i], standard_dev); + + // Select only points outside (mean +/- alpha * standard_dev) + std::list indices_per_scale; + std::vector indices_table_per_scale (features_at_scale_[scale_i]->points.size (), false); + for (size_t point_i = 0; point_i < features_at_scale_[scale_i]->points.size (); ++point_i) + { + if (diff_vector[point_i] > alpha_ * standard_dev) + { + indices_per_scale.push_back (point_i); + indices_table_per_scale[point_i] = true; + } + } + unique_features_indices_[scale_i] = indices_per_scale; + unique_features_table_[scale_i] = indices_table_per_scale; + } +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MultiscaleFeaturePersistence::determinePersistentFeatures (FeatureCloud &output_features, + boost::shared_ptr > &output_indices) +{ + if (!initCompute ()) + return; + + // Compute the features for all scales with the given feature estimator + PCL_DEBUG ("[pcl::MultiscaleFeaturePersistence::determinePersistentFeatures] Computing features ...\n"); + computeFeaturesAtAllScales (); + + // Compute mean feature + PCL_DEBUG ("[pcl::MultiscaleFeaturePersistence::determinePersistentFeatures] Calculating mean feature ...\n"); + calculateMeanFeature (); + + // Get the 'unique' features at each scale + PCL_DEBUG ("[pcl::MultiscaleFeaturePersistence::determinePersistentFeatures] Extracting unique features ...\n"); + extractUniqueFeatures (); + + PCL_DEBUG ("[pcl::MultiscaleFeaturePersistence::determinePersistentFeatures] Determining persistent features between scales ...\n"); + // Determine persistent features between scales + +/* + // Method 1: a feature is considered persistent if it is 'unique' in at least 2 different scales + for (size_t scale_i = 0; scale_i < features_at_scale_vectorized_.size () - 1; ++scale_i) + for (std::list::iterator feature_it = unique_features_indices_[scale_i].begin (); feature_it != unique_features_indices_[scale_i].end (); ++feature_it) + { + if (unique_features_table_[scale_i][*feature_it] == true) + { + output_features.points.push_back (features_at_scale[scale_i]->points[*feature_it]); + output_indices->push_back (feature_estimator_->getIndices ()->at (*feature_it)); + } + } +*/ + // Method 2: a feature is considered persistent if it is 'unique' in all the scales + for (std::list::iterator feature_it = unique_features_indices_.front ().begin (); feature_it != unique_features_indices_.front ().end (); ++feature_it) + { + bool present_in_all = true; + for (size_t scale_i = 0; scale_i < features_at_scale_.size (); ++scale_i) + present_in_all = present_in_all && unique_features_table_[scale_i][*feature_it]; + + if (present_in_all) + { + output_features.points.push_back (features_at_scale_.front ()->points[*feature_it]); + output_indices->push_back (feature_estimator_->getIndices ()->at (*feature_it)); + } + } + + // Consider that output cloud is unorganized + output_features.header = feature_estimator_->getInputCloud ()->header; + output_features.is_dense = feature_estimator_->getInputCloud ()->is_dense; + output_features.width = static_cast (output_features.points.size ()); + output_features.height = 1; +} + + +#define PCL_INSTANTIATE_MultiscaleFeaturePersistence(InT, Feature) template class PCL_EXPORTS pcl::MultiscaleFeaturePersistence; + +#endif /* PCL_FEATURES_IMPL_MULTISCALE_FEATURE_PERSISTENCE_H_ */ diff --git a/pcl-1.7/pcl/features/impl/narf.hpp b/pcl-1.7/pcl/features/impl/narf.hpp new file mode 100644 index 0000000..33ccdd3 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/narf.hpp @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#include +#include + +namespace pcl { + +inline float +Narf::getDescriptorDistance(const Narf& other) const +{ + float ret = L1_Norm(descriptor_, other.descriptor_, descriptor_size_); + //float ret = Sublinear_Norm(descriptor_, other.descriptor_, descriptor_size_); + ret /= static_cast (descriptor_size_); + return (ret); +} + +inline void Narf::copyToNarf36(Narf36& narf36) const +{ + if (descriptor_size_ != 36) + { + std::cerr << __PRETTY_FUNCTION__ << ": descriptor size is not 36!\n"; + return; + } + getTranslationAndEulerAngles(transformation_.inverse (), narf36.x, narf36.y, narf36.z, narf36.roll, narf36.pitch, narf36.yaw); + memcpy(narf36.descriptor, descriptor_, 36*sizeof(*descriptor_)); +} + +//inline float Narf::getDescriptorDistance(const Narf& other) const +//{ + //float middle_value = 0.1f; + //float normalization_factor1 = 1.0f/middle_value, + //normalization_factor2 = 1.0f/(1.0f-middle_value); + //const float* descriptor1_ptr = descriptor_; + //const float* descriptor2_ptr = other.getDescriptor(); + //float ret = 0; + //for (int i=0; i + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::NormalEstimation::computeFeature (PointCloudOut &output) +{ + /** If using the Customized KD-Tree data structure **/ + if (use_customized_tree_) + { + points_target_.clear(); + for(size_t i = 0; i < surface_->size(); i++) + { + // points + Point point; + point.x = (*surface_)[i].data[0]; + point.y = (*surface_)[i].data[1]; + point.z = (*surface_)[i].data[2]; + points_target_.push_back(point); + } + points_target_ptr_ = &points_target_; + + // indices + index_target_.clear(); + for(size_t i = 0; i < surface_->size(); i++) + index_target_.push_back(i); + index_target_ptr_ = &index_target_; + + buildHKdTree_target(); + + std::vector nn_indices (0); + std::vector nn_dists (0); + + int search_state = 0; + + output.is_dense = true; + // Save a few cycles by not checking every point for\ + // NaN/Inf values if the cloud is set to dense + if (input_->is_dense) + { + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + // flann's + // search_state = this->searchForNeighbors \ + ((*indices_)[idx], search_parameter_, nn_indices, nn_dists); + Point query; + query.x = (input_->points[ (*indices_)[idx] ]).data[0]; + query.y = (input_->points[ (*indices_)[idx] ]).data[1]; + query.z = (input_->points[ (*indices_)[idx] ]).data[2]; + + // !Remember to add resize(0) or clear() + nn_indices.resize(0); + nn_dists.resize(0); + + treeH_target_->radiusSearchApprox(query, \ + search_parameter_, nn_indices, nn_dists); + + if (nn_indices.size() == 0) + { + output.points[idx].normal[0] = \ + output.points[idx].normal[1] = \ + output.points[idx].normal[2] = \ + output.points[idx].curvature = \ + std::numeric_limits::quiet_NaN (); + output.is_dense = false; + continue; + } + + computePointNormal (*surface_, nn_indices, + output.points[idx].normal[0], \ + output.points[idx].normal[1], \ + output.points[idx].normal[2], \ + output.points[idx].curvature); + + flipNormalTowardsViewpoint (input_->points[(*indices_)[idx]], \ + vpx_, vpy_, vpz_, + output.points[idx].normal[0], \ + output.points[idx].normal[1], \ + output.points[idx].normal[2]); + + } + } + else + { + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + // flann's + // search_state = this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists); + Point query; + query.x = (input_->points[ (*indices_)[idx] ]).data[0]; + query.y = (input_->points[ (*indices_)[idx] ]).data[1]; + query.z = (input_->points[ (*indices_)[idx] ]).data[2]; + + nn_indices.resize(0); + nn_dists.resize(0); + + treeH_target_->radiusSearchApprox(query, search_parameter_, nn_indices, nn_dists); + + if (!isFinite ((*input_)[(*indices_)[idx]]) || nn_indices.size() == 0 ) //search_state == 0) + { + output.points[idx].normal[0] = \ + output.points[idx].normal[1] = \ + output.points[idx].normal[2] = \ + output.points[idx].curvature = std::numeric_limits::quiet_NaN (); + + output.is_dense = false; + continue; + } + + computePointNormal (*surface_, nn_indices, + output.points[idx].normal[0], \ + output.points[idx].normal[1], \ + output.points[idx].normal[2], \ + output.points[idx].curvature); + + flipNormalTowardsViewpoint (input_->points[(*indices_)[idx]], vpx_, vpy_, vpz_, + output.points[idx].normal[0], \ + output.points[idx].normal[1], \ + output.points[idx].normal[2]); + + } + } + if (save_approx_data_) + { + approx_radius_ops_num_ = treeH_target_->approx_radius_ops_num_; + approx_leaders_num_ = treeH_target_->approx_leaders_num_; + approx_followers_num_ = treeH_target_->approx_followers_num_; + } + } + + // Use Flann's implementation + else + { + // Allocate enough space to hold the results + // \note This resize is irrelevant for a radiusSearch (). + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + int search_state = 0; + output.is_dense = true; + // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense + if (input_->is_dense) + { + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + // flann's + search_state = this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists); + + if (search_state == 0) + { + output.points[idx].normal[0] = output.points[idx].normal[1] = output.points[idx].normal[2] = output.points[idx].curvature = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + continue; + } + + computePointNormal (*surface_, nn_indices, + output.points[idx].normal[0], \ + output.points[idx].normal[1], \ + output.points[idx].normal[2], \ + output.points[idx].curvature); + + flipNormalTowardsViewpoint (input_->points[(*indices_)[idx]], vpx_, vpy_, vpz_, + output.points[idx].normal[0], \ + output.points[idx].normal[1], \ + output.points[idx].normal[2]); + } + } + else + { + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + // flann's + search_state = this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists); + + if (search_state == 0) + { + output.points[idx].normal[0] = \ + output.points[idx].normal[1] = \ + output.points[idx].normal[2] = \ + output.points[idx].curvature = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + continue; + } + + computePointNormal (*surface_, nn_indices, + output.points[idx].normal[0], \ + output.points[idx].normal[1], \ + output.points[idx].normal[2], \ + output.points[idx].curvature); + + flipNormalTowardsViewpoint (input_->points[(*indices_)[idx]], vpx_, vpy_, vpz_, + output.points[idx].normal[0], \ + output.points[idx].normal[1], \ + output.points[idx].normal[2]); + } + } + } +} + +#define PCL_INSTANTIATE_NormalEstimation(T,NT) template class PCL_EXPORTS pcl::NormalEstimation; + +#endif // PCL_FEATURES_IMPL_NORMAL_3D_H_ diff --git a/pcl-1.7/pcl/features/impl/normal_3d_omp.hpp b/pcl-1.7/pcl/features/impl/normal_3d_omp.hpp new file mode 100644 index 0000000..429985d --- /dev/null +++ b/pcl-1.7/pcl/features/impl/normal_3d_omp.hpp @@ -0,0 +1,134 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_IMPL_NORMAL_3D_OMP_H_ +#define PCL_FEATURES_IMPL_NORMAL_3D_OMP_H_ + +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::NormalEstimationOMP::computeFeature (PointCloudOut &output) +{ + // Allocate enough space to hold the results + // \note This resize is irrelevant for a radiusSearch (). + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + output.is_dense = true; + + int search_state = 0; + + // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense + if (input_->is_dense) + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) private (nn_indices, nn_dists) num_threads(threads_) +#endif + + // Iterating over the entire index vector + for (int idx = 0; idx < static_cast (indices_->size ()); ++idx) + { + + search_state = this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists); + + if (search_state == 0) + { + output.points[idx].normal[0] = output.points[idx].normal[1] = output.points[idx].normal[2] = output.points[idx].curvature = std::numeric_limits::quiet_NaN (); + + output.is_dense = false; + continue; + } + + Eigen::Vector4f n; + pcl::computePointNormal (*surface_, nn_indices, + n, + output.points[idx].curvature); + + output.points[idx].normal_x = n[0]; + output.points[idx].normal_y = n[1]; + output.points[idx].normal_z = n[2]; + + flipNormalTowardsViewpoint (input_->points[(*indices_)[idx]], vpx_, vpy_, vpz_, + output.points[idx].normal[0], + output.points[idx].normal[1], + output.points[idx].normal[2]); + } + } + else + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) private (nn_indices, nn_dists) num_threads(threads_) +#endif + + // Iterating over the entire index vector + for (int idx = 0; idx < static_cast (indices_->size ()); ++idx) + { + + search_state = this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists); + + if (!isFinite ((*input_)[(*indices_)[idx]]) || + search_state == 0) + { + output.points[idx].normal[0] = output.points[idx].normal[1] = output.points[idx].normal[2] = output.points[idx].curvature = std::numeric_limits::quiet_NaN (); + + output.is_dense = false; + continue; + } + + Eigen::Vector4f n; + pcl::computePointNormal (*surface_, nn_indices, + n, + output.points[idx].curvature); + + output.points[idx].normal_x = n[0]; + output.points[idx].normal_y = n[1]; + output.points[idx].normal_z = n[2]; + + flipNormalTowardsViewpoint (input_->points[(*indices_)[idx]], vpx_, vpy_, vpz_, + output.points[idx].normal[0], output.points[idx].normal[1], output.points[idx].normal[2]); + } + } +} + +#define PCL_INSTANTIATE_NormalEstimationOMP(T,NT) template class PCL_EXPORTS pcl::NormalEstimationOMP; + +#endif // PCL_FEATURES_IMPL_NORMAL_3D_OMP_H_ + diff --git a/pcl-1.7/pcl/features/impl/normal_based_signature.hpp b/pcl-1.7/pcl/features/impl/normal_based_signature.hpp new file mode 100644 index 0000000..0f89176 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/normal_based_signature.hpp @@ -0,0 +1,191 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_FEATURES_IMPL_NORMAL_BASED_SIGNATURE_H_ +#define PCL_FEATURES_IMPL_NORMAL_BASED_SIGNATURE_H_ + +#include + +template void +pcl::NormalBasedSignatureEstimation::computeFeature (FeatureCloud &output) +{ + // do a few checks before starting the computations + + PointFeature test_feature; + (void)test_feature; + if (N_prime_ * M_prime_ != sizeof (test_feature.values) / sizeof (float)) + { + PCL_ERROR ("NormalBasedSignatureEstimation: not using the proper signature size: %u vs %u\n", N_prime_ * M_prime_, sizeof (test_feature.values) / sizeof (float)); + return; + } + + std::vector k_indices; + std::vector k_sqr_distances; + + tree_->setInputCloud (input_); + output.points.resize (indices_->size ()); + + for (size_t index_i = 0; index_i < indices_->size (); ++index_i) + { + size_t point_i = (*indices_)[index_i]; + Eigen::MatrixXf s_matrix (N_, M_); + + Eigen::Vector4f center_point = input_->points[point_i].getVector4fMap (); + + for (size_t k = 0; k < N_; ++k) + { + Eigen::VectorXf s_row (M_); + + for (size_t l = 0; l < M_; ++l) + { + Eigen::Vector4f normal = normals_->points[point_i].getNormalVector4fMap (); + Eigen::Vector4f normal_u = Eigen::Vector4f::Zero (); + Eigen::Vector4f normal_v = Eigen::Vector4f::Zero (); + + if (fabs (normal.x ()) > 0.0001f) + { + normal_u.x () = - normal.y () / normal.x (); + normal_u.y () = 1.0f; + normal_u.z () = 0.0f; + normal_u.normalize (); + + } + else if (fabs (normal.y ()) > 0.0001f) + { + normal_u.x () = 1.0f; + normal_u.y () = - normal.x () / normal.y (); + normal_u.z () = 0.0f; + normal_u.normalize (); + } + else + { + normal_u.x () = 0.0f; + normal_u.y () = 1.0f; + normal_u.z () = - normal.y () / normal.z (); + } + normal_v = normal.cross3 (normal_u); + + Eigen::Vector4f zeta_point = 2.0f * static_cast (l + 1) * scale_h_ / static_cast (M_) * + (cosf (2.0f * static_cast (M_PI) * static_cast ((k + 1) / N_)) * normal_u + + sinf (2.0f * static_cast (M_PI) * static_cast ((k + 1) / N_)) * normal_v); + + // Compute normal by using the neighbors + Eigen::Vector4f zeta_point_plus_center = zeta_point + center_point; + PointT zeta_point_pcl; + zeta_point_pcl.x = zeta_point_plus_center.x (); zeta_point_pcl.y = zeta_point_plus_center.y (); zeta_point_pcl.z = zeta_point_plus_center.z (); + + tree_->radiusSearch (zeta_point_pcl, search_radius_, k_indices, k_sqr_distances); + + // Do k nearest search if there are no neighbors nearby + if (k_indices.size () == 0) + { + k_indices.resize (5); + k_sqr_distances.resize (5); + tree_->nearestKSearch (zeta_point_pcl, 5, k_indices, k_sqr_distances); + } + + Eigen::Vector4f average_normal = Eigen::Vector4f::Zero (); + + float average_normalization_factor = 0.0f; + + // Normals weighted by 1/squared_distances + for (size_t nn_i = 0; nn_i < k_indices.size (); ++nn_i) + { + if (k_sqr_distances[nn_i] < 1e-7f) + { + average_normal = normals_->points[k_indices[nn_i]].getNormalVector4fMap (); + average_normalization_factor = 1.0f; + break; + } + average_normal += normals_->points[k_indices[nn_i]].getNormalVector4fMap () / k_sqr_distances[nn_i]; + average_normalization_factor += 1.0f / k_sqr_distances[nn_i]; + } + average_normal /= average_normalization_factor; + float s = zeta_point.dot (average_normal) / zeta_point.norm (); + s_row[l] = s; + } + + // do DCT on the s_matrix row-wise + Eigen::VectorXf dct_row (M_); + for (int m = 0; m < s_row.size (); ++m) + { + float Xk = 0.0f; + for (int n = 0; n < s_row.size (); ++n) + Xk += static_cast (s_row[n] * cos (M_PI / (static_cast (M_ * n) + 0.5) * static_cast (k))); + dct_row[m] = Xk; + } + s_row = dct_row; + s_matrix.row (k).matrix () = dct_row; + } + + // do DFT on the s_matrix column-wise + Eigen::MatrixXf dft_matrix (N_, M_); + for (size_t column_i = 0; column_i < M_; ++column_i) + { + Eigen::VectorXf dft_col (N_); + for (size_t k = 0; k < N_; ++k) + { + float Xk_real = 0.0f, Xk_imag = 0.0f; + for (size_t n = 0; n < N_; ++n) + { + Xk_real += static_cast (s_matrix (n, column_i) * cos (2.0f * M_PI / static_cast (N_ * k * n))); + Xk_imag += static_cast (s_matrix (n, column_i) * sin (2.0f * M_PI / static_cast (N_ * k * n))); + } + dft_col[k] = sqrtf (Xk_real*Xk_real + Xk_imag*Xk_imag); + } + dft_matrix.col (column_i).matrix () = dft_col; + } + + Eigen::MatrixXf final_matrix = dft_matrix.block (0, 0, N_prime_, M_prime_); + + PointFeature feature_point; + for (size_t i = 0; i < N_prime_; ++i) + for (size_t j = 0; j < M_prime_; ++j) + feature_point.values[i*M_prime_ + j] = final_matrix (i, j); + + output.points[index_i] = feature_point; + } +} + + + +#define PCL_INSTANTIATE_NormalBasedSignatureEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::NormalBasedSignatureEstimation; + + +#endif /* PCL_FEATURES_IMPL_NORMAL_BASED_SIGNATURE_H_ */ diff --git a/pcl-1.7/pcl/features/impl/our_cvfh.hpp b/pcl-1.7/pcl/features/impl/our_cvfh.hpp new file mode 100644 index 0000000..7ddd84c --- /dev/null +++ b/pcl-1.7/pcl/features/impl/our_cvfh.hpp @@ -0,0 +1,743 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: cvfh.hpp 5311 2012-03-26 22:02:04Z aaldoma $ + * + */ + +#ifndef PCL_FEATURES_IMPL_OURCVFH_H_ +#define PCL_FEATURES_IMPL_OURCVFH_H_ + +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OURCVFHEstimation::compute (PointCloudOut &output) +{ + if (!Feature::initCompute ()) + { + output.width = output.height = 0; + output.points.clear (); + return; + } + // Resize the output dataset + // Important! We should only allocate precisely how many elements we will need, otherwise + // we risk at pre-allocating too much memory which could lead to bad_alloc + // (see http://dev.pointclouds.org/issues/657) + output.width = output.height = 1; + output.points.resize (1); + + // Perform the actual feature computation + computeFeature (output); + + Feature::deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OURCVFHEstimation::extractEuclideanClustersSmooth (const pcl::PointCloud &cloud, + const pcl::PointCloud &normals, + float tolerance, + const pcl::search::Search::Ptr &tree, + std::vector &clusters, double eps_angle, + unsigned int min_pts_per_cluster, + unsigned int max_pts_per_cluster) +{ + if (tree->getInputCloud ()->points.size () != cloud.points.size ()) + { + PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset (%lu) than the input cloud (%lu)!\n", tree->getInputCloud ()->points.size (), cloud.points.size ()); + return; + } + if (cloud.points.size () != normals.points.size ()) + { + PCL_ERROR ("[pcl::extractEuclideanClusters] Number of points in the input point cloud (%lu) different than normals (%lu)!\n", cloud.points.size (), normals.points.size ()); + return; + } + + // Create a bool vector of processed point indices, and initialize it to false + std::vector processed (cloud.points.size (), false); + + std::vector nn_indices; + std::vector nn_distances; + // Process all points in the indices vector + for (int i = 0; i < static_cast (cloud.points.size ()); ++i) + { + if (processed[i]) + continue; + + std::vector seed_queue; + int sq_idx = 0; + seed_queue.push_back (i); + + processed[i] = true; + + while (sq_idx < static_cast (seed_queue.size ())) + { + // Search for sq_idx + if (!tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances)) + { + sq_idx++; + continue; + } + + for (size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx + { + if (processed[nn_indices[j]]) // Has this point been processed before ? + continue; + + //processed[nn_indices[j]] = true; + // [-1;1] + + double dot_p = normals.points[seed_queue[sq_idx]].normal[0] * normals.points[nn_indices[j]].normal[0] + + normals.points[seed_queue[sq_idx]].normal[1] * normals.points[nn_indices[j]].normal[1] + normals.points[seed_queue[sq_idx]].normal[2] + * normals.points[nn_indices[j]].normal[2]; + + if (fabs (acos (dot_p)) < eps_angle) + { + processed[nn_indices[j]] = true; + seed_queue.push_back (nn_indices[j]); + } + } + + sq_idx++; + } + + // If this queue is satisfactory, add to the clusters + if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster) + { + pcl::PointIndices r; + r.indices.resize (seed_queue.size ()); + for (size_t j = 0; j < seed_queue.size (); ++j) + r.indices[j] = seed_queue[j]; + + std::sort (r.indices.begin (), r.indices.end ()); + r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ()); + + r.header = cloud.header; + clusters.push_back (r); // We could avoid a copy by working directly in the vector + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OURCVFHEstimation::filterNormalsWithHighCurvature (const pcl::PointCloud & cloud, + std::vector &indices_to_use, + std::vector &indices_out, std::vector &indices_in, + float threshold) +{ + indices_out.resize (cloud.points.size ()); + indices_in.resize (cloud.points.size ()); + + size_t in, out; + in = out = 0; + + for (int i = 0; i < static_cast (indices_to_use.size ()); i++) + { + if (cloud.points[indices_to_use[i]].curvature > threshold) + { + indices_out[out] = indices_to_use[i]; + out++; + } + else + { + indices_in[in] = indices_to_use[i]; + in++; + } + } + + indices_out.resize (out); + indices_in.resize (in); +} + +template bool +pcl::OURCVFHEstimation::sgurf (Eigen::Vector3f & centroid, Eigen::Vector3f & normal_centroid, + PointInTPtr & processed, std::vector > & transformations, + PointInTPtr & grid, pcl::PointIndices & indices) +{ + + Eigen::Vector3f plane_normal; + plane_normal[0] = -centroid[0]; + plane_normal[1] = -centroid[1]; + plane_normal[2] = -centroid[2]; + Eigen::Vector3f z_vector = Eigen::Vector3f::UnitZ (); + plane_normal.normalize (); + Eigen::Vector3f axis = plane_normal.cross (z_vector); + double rotation = -asin (axis.norm ()); + axis.normalize (); + + Eigen::Affine3f transformPC (Eigen::AngleAxisf (static_cast (rotation), axis)); + + grid->points.resize (processed->points.size ()); + for (size_t k = 0; k < processed->points.size (); k++) + grid->points[k].getVector4fMap () = processed->points[k].getVector4fMap (); + + pcl::transformPointCloud (*grid, *grid, transformPC); + + Eigen::Vector4f centroid4f (centroid[0], centroid[1], centroid[2], 0); + Eigen::Vector4f normal_centroid4f (normal_centroid[0], normal_centroid[1], normal_centroid[2], 0); + + centroid4f = transformPC * centroid4f; + normal_centroid4f = transformPC * normal_centroid4f; + + Eigen::Vector3f centroid3f (centroid4f[0], centroid4f[1], centroid4f[2]); + + Eigen::Vector4f farthest_away; + pcl::getMaxDistance (*grid, indices.indices, centroid4f, farthest_away); + farthest_away[3] = 0; + + float max_dist = (farthest_away - centroid4f).norm (); + + pcl::demeanPointCloud (*grid, centroid4f, *grid); + + Eigen::Matrix4f center_mat; + center_mat.setIdentity (4, 4); + center_mat (0, 3) = -centroid4f[0]; + center_mat (1, 3) = -centroid4f[1]; + center_mat (2, 3) = -centroid4f[2]; + + Eigen::Matrix3f scatter; + scatter.setZero (); + float sum_w = 0.f; + + //for (int k = 0; k < static_castpoints[k].getVector3fMap ();> (grid->points.size ()); k++) + for (int k = 0; k < static_cast (indices.indices.size ()); k++) + { + Eigen::Vector3f pvector = grid->points[indices.indices[k]].getVector3fMap (); + float d_k = (pvector).norm (); + float w = (max_dist - d_k); + Eigen::Vector3f diff = (pvector); + Eigen::Matrix3f mat = diff * diff.transpose (); + scatter = scatter + mat * w; + sum_w += w; + } + + scatter /= sum_w; + + Eigen::JacobiSVD svd (scatter, Eigen::ComputeFullV); + Eigen::Vector3f evx = svd.matrixV ().col (0); + Eigen::Vector3f evy = svd.matrixV ().col (1); + Eigen::Vector3f evz = svd.matrixV ().col (2); + Eigen::Vector3f evxminus = evx * -1; + Eigen::Vector3f evyminus = evy * -1; + Eigen::Vector3f evzminus = evz * -1; + + float s_xplus, s_xminus, s_yplus, s_yminus; + s_xplus = s_xminus = s_yplus = s_yminus = 0.f; + + //disambiguate rf using all points + for (int k = 0; k < static_cast (grid->points.size ()); k++) + { + Eigen::Vector3f pvector = grid->points[k].getVector3fMap (); + float dist_x, dist_y; + dist_x = std::abs (evx.dot (pvector)); + dist_y = std::abs (evy.dot (pvector)); + + if ((pvector).dot (evx) >= 0) + s_xplus += dist_x; + else + s_xminus += dist_x; + + if ((pvector).dot (evy) >= 0) + s_yplus += dist_y; + else + s_yminus += dist_y; + + } + + if (s_xplus < s_xminus) + evx = evxminus; + + if (s_yplus < s_yminus) + evy = evyminus; + + //select the axis that could be disambiguated more easily + float fx, fy; + float max_x = static_cast (std::max (s_xplus, s_xminus)); + float min_x = static_cast (std::min (s_xplus, s_xminus)); + float max_y = static_cast (std::max (s_yplus, s_yminus)); + float min_y = static_cast (std::min (s_yplus, s_yminus)); + + fx = (min_x / max_x); + fy = (min_y / max_y); + + Eigen::Vector3f normal3f = Eigen::Vector3f (normal_centroid4f[0], normal_centroid4f[1], normal_centroid4f[2]); + if (normal3f.dot (evz) < 0) + evz = evzminus; + + //if fx/y close to 1, it was hard to disambiguate + //what if both are equally easy or difficult to disambiguate, namely fy == fx or very close + + float max_axis = std::max (fx, fy); + float min_axis = std::min (fx, fy); + + if ((min_axis / max_axis) > axis_ratio_) + { + PCL_WARN ("Both axes are equally easy/difficult to disambiguate\n"); + + Eigen::Vector3f evy_copy = evy; + Eigen::Vector3f evxminus = evx * -1; + Eigen::Vector3f evyminus = evy * -1; + + if (min_axis > min_axis_value_) + { + //combination of all possibilities + evy = evx.cross (evz); + Eigen::Matrix4f trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat); + transformations.push_back (trans); + + evx = evxminus; + evy = evx.cross (evz); + trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat); + transformations.push_back (trans); + + evx = evy_copy; + evy = evx.cross (evz); + trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat); + transformations.push_back (trans); + + evx = evyminus; + evy = evx.cross (evz); + trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat); + transformations.push_back (trans); + + } + else + { + //1-st case (evx selected) + evy = evx.cross (evz); + Eigen::Matrix4f trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat); + transformations.push_back (trans); + + //2-nd case (evy selected) + evx = evy_copy; + evy = evx.cross (evz); + trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat); + transformations.push_back (trans); + } + } + else + { + if (fy < fx) + { + evx = evy; + fx = fy; + } + + evy = evx.cross (evz); + Eigen::Matrix4f trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat); + transformations.push_back (trans); + + } + + return true; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OURCVFHEstimation::computeRFAndShapeDistribution (PointInTPtr & processed, PointCloudOut & output, + std::vector & cluster_indices) +{ + PointCloudOut ourcvfh_output; + + cluster_axes_.clear (); + cluster_axes_.resize (centroids_dominant_orientations_.size ()); + + for (size_t i = 0; i < centroids_dominant_orientations_.size (); i++) + { + + std::vector < Eigen::Matrix4f, Eigen::aligned_allocator > transformations; + PointInTPtr grid (new pcl::PointCloud); + sgurf (centroids_dominant_orientations_[i], dominant_normals_[i], processed, transformations, grid, cluster_indices[i]); + + // Make a note of how many transformations correspond to each cluster + cluster_axes_[i] = transformations.size (); + + for (size_t t = 0; t < transformations.size (); t++) + { + + pcl::transformPointCloud (*processed, *grid, transformations[t]); + transforms_.push_back (transformations[t]); + valid_transforms_.push_back (true); + + std::vector < Eigen::VectorXf > quadrants (8); + int size_hists = 13; + int num_hists = 8; + for (int k = 0; k < num_hists; k++) + quadrants[k].setZero (size_hists); + + Eigen::Vector4f centroid_p; + centroid_p.setZero (); + Eigen::Vector4f max_pt; + pcl::getMaxDistance (*grid, centroid_p, max_pt); + max_pt[3] = 0; + double distance_normalization_factor = (centroid_p - max_pt).norm (); + + float hist_incr; + if (normalize_bins_) + hist_incr = 100.0f / static_cast (grid->points.size () - 1); + else + hist_incr = 1.0f; + + float * weights = new float[num_hists]; + float sigma = 0.01f; //1cm + float sigma_sq = sigma * sigma; + + for (int k = 0; k < static_cast (grid->points.size ()); k++) + { + Eigen::Vector4f p = grid->points[k].getVector4fMap (); + p[3] = 0.f; + float d = p.norm (); + + //compute weight for all octants + float wx = 1.f - std::exp (-((p[0] * p[0]) / (2.f * sigma_sq))); //how is the weight distributed among two semi-cubes + float wy = 1.f - std::exp (-((p[1] * p[1]) / (2.f * sigma_sq))); + float wz = 1.f - std::exp (-((p[2] * p[2]) / (2.f * sigma_sq))); + + //distribute the weights using the x-coordinate + if (p[0] >= 0) + { + for (size_t ii = 0; ii <= 3; ii++) + weights[ii] = 0.5f - wx * 0.5f; + + for (size_t ii = 4; ii <= 7; ii++) + weights[ii] = 0.5f + wx * 0.5f; + } + else + { + for (size_t ii = 0; ii <= 3; ii++) + weights[ii] = 0.5f + wx * 0.5f; + + for (size_t ii = 4; ii <= 7; ii++) + weights[ii] = 0.5f - wx * 0.5f; + } + + //distribute the weights using the y-coordinate + if (p[1] >= 0) + { + for (size_t ii = 0; ii <= 1; ii++) + weights[ii] *= 0.5f - wy * 0.5f; + for (size_t ii = 4; ii <= 5; ii++) + weights[ii] *= 0.5f - wy * 0.5f; + + for (size_t ii = 2; ii <= 3; ii++) + weights[ii] *= 0.5f + wy * 0.5f; + + for (size_t ii = 6; ii <= 7; ii++) + weights[ii] *= 0.5f + wy * 0.5f; + } + else + { + for (size_t ii = 0; ii <= 1; ii++) + weights[ii] *= 0.5f + wy * 0.5f; + for (size_t ii = 4; ii <= 5; ii++) + weights[ii] *= 0.5f + wy * 0.5f; + + for (size_t ii = 2; ii <= 3; ii++) + weights[ii] *= 0.5f - wy * 0.5f; + + for (size_t ii = 6; ii <= 7; ii++) + weights[ii] *= 0.5f - wy * 0.5f; + } + + //distribute the weights using the z-coordinate + if (p[2] >= 0) + { + for (size_t ii = 0; ii <= 7; ii += 2) + weights[ii] *= 0.5f - wz * 0.5f; + + for (size_t ii = 1; ii <= 7; ii += 2) + weights[ii] *= 0.5f + wz * 0.5f; + + } + else + { + for (size_t ii = 0; ii <= 7; ii += 2) + weights[ii] *= 0.5f + wz * 0.5f; + + for (size_t ii = 1; ii <= 7; ii += 2) + weights[ii] *= 0.5f - wz * 0.5f; + } + + int h_index = (d <= 0) ? 0 : std::ceil (size_hists * (d / distance_normalization_factor)) - 1; + for (int j = 0; j < num_hists; j++) + quadrants[j][h_index] += hist_incr * weights[j]; + + } + + //copy to the cvfh signature + PointCloudOut vfh_signature; + vfh_signature.points.resize (1); + vfh_signature.width = vfh_signature.height = 1; + for (int d = 0; d < 308; ++d) + vfh_signature.points[0].histogram[d] = output.points[i].histogram[d]; + + int pos = 45 * 3; + for (int k = 0; k < num_hists; k++) + { + for (int ii = 0; ii < size_hists; ii++, pos++) + { + vfh_signature.points[0].histogram[pos] = quadrants[k][ii]; + } + } + + ourcvfh_output.points.push_back (vfh_signature.points[0]); + ourcvfh_output.width = ourcvfh_output.points.size (); + delete[] weights; + } + } + + if (ourcvfh_output.points.size ()) + { + ourcvfh_output.height = 1; + } + output = ourcvfh_output; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OURCVFHEstimation::computeFeature (PointCloudOut &output) +{ + if (refine_clusters_ <= 0.f) + refine_clusters_ = 1.f; + + // Check if input was set + if (!normals_) + { + PCL_ERROR ("[pcl::%s::computeFeature] No input dataset containing normals was given!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + if (normals_->points.size () != surface_->points.size ()) + { + PCL_ERROR ("[pcl::%s::computeFeature] The number of points in the input dataset differs from the number of points in the dataset containing the normals!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + centroids_dominant_orientations_.clear (); + clusters_.clear (); + transforms_.clear (); + dominant_normals_.clear (); + + // ---[ Step 0: remove normals with high curvature + std::vector indices_out; + std::vector indices_in; + filterNormalsWithHighCurvature (*normals_, *indices_, indices_out, indices_in, curv_threshold_); + + pcl::PointCloud::Ptr normals_filtered_cloud (new pcl::PointCloud ()); + normals_filtered_cloud->width = static_cast (indices_in.size ()); + normals_filtered_cloud->height = 1; + normals_filtered_cloud->points.resize (normals_filtered_cloud->width); + + std::vector indices_from_nfc_to_indices; + indices_from_nfc_to_indices.resize (indices_in.size ()); + + for (size_t i = 0; i < indices_in.size (); ++i) + { + normals_filtered_cloud->points[i].x = surface_->points[indices_in[i]].x; + normals_filtered_cloud->points[i].y = surface_->points[indices_in[i]].y; + normals_filtered_cloud->points[i].z = surface_->points[indices_in[i]].z; + //normals_filtered_cloud->points[i].getNormalVector4fMap() = normals_->points[indices_in[i]].getNormalVector4fMap(); + indices_from_nfc_to_indices[i] = indices_in[i]; + } + + std::vector clusters; + + if (normals_filtered_cloud->points.size () >= min_points_) + { + //recompute normals and use them for clustering + { + KdTreePtr normals_tree_filtered (new pcl::search::KdTree (false)); + normals_tree_filtered->setInputCloud (normals_filtered_cloud); + pcl::NormalEstimation n3d; + n3d.setRadiusSearch (radius_normals_); + n3d.setSearchMethod (normals_tree_filtered); + n3d.setInputCloud (normals_filtered_cloud); + n3d.compute (*normals_filtered_cloud); + } + + KdTreePtr normals_tree (new pcl::search::KdTree (false)); + normals_tree->setInputCloud (normals_filtered_cloud); + + extractEuclideanClustersSmooth (*normals_filtered_cloud, *normals_filtered_cloud, cluster_tolerance_, normals_tree, clusters, + eps_angle_threshold_, static_cast (min_points_)); + + std::vector clusters_filtered; + int cluster_filtered_idx = 0; + for (size_t i = 0; i < clusters.size (); i++) + { + + pcl::PointIndices pi; + pcl::PointIndices pi_cvfh; + pcl::PointIndices pi_filtered; + + clusters_.push_back (pi); + clusters_filtered.push_back (pi_filtered); + + Eigen::Vector4f avg_normal = Eigen::Vector4f::Zero (); + Eigen::Vector4f avg_centroid = Eigen::Vector4f::Zero (); + + for (size_t j = 0; j < clusters[i].indices.size (); j++) + { + avg_normal += normals_filtered_cloud->points[clusters[i].indices[j]].getNormalVector4fMap (); + avg_centroid += normals_filtered_cloud->points[clusters[i].indices[j]].getVector4fMap (); + } + + avg_normal /= static_cast (clusters[i].indices.size ()); + avg_centroid /= static_cast (clusters[i].indices.size ()); + avg_normal.normalize (); + + Eigen::Vector3f avg_norm (avg_normal[0], avg_normal[1], avg_normal[2]); + Eigen::Vector3f avg_dominant_centroid (avg_centroid[0], avg_centroid[1], avg_centroid[2]); + + for (size_t j = 0; j < clusters[i].indices.size (); j++) + { + //decide if normal should be added + double dot_p = avg_normal.dot (normals_filtered_cloud->points[clusters[i].indices[j]].getNormalVector4fMap ()); + if (fabs (acos (dot_p)) < (eps_angle_threshold_ * refine_clusters_)) + { + clusters_[cluster_filtered_idx].indices.push_back (indices_from_nfc_to_indices[clusters[i].indices[j]]); + clusters_filtered[cluster_filtered_idx].indices.push_back (clusters[i].indices[j]); + } + } + + //remove last cluster if no points found... + if (clusters_[cluster_filtered_idx].indices.size () == 0) + { + clusters_.pop_back (); + clusters_filtered.pop_back (); + } + else + cluster_filtered_idx++; + } + + clusters = clusters_filtered; + + } + + pcl::VFHEstimation vfh; + vfh.setInputCloud (surface_); + vfh.setInputNormals (normals_); + vfh.setIndices (indices_); + vfh.setSearchMethod (this->tree_); + vfh.setUseGivenNormal (true); + vfh.setUseGivenCentroid (true); + vfh.setNormalizeBins (normalize_bins_); + output.height = 1; + + // ---[ Step 1b : check if any dominant cluster was found + if (clusters.size () > 0) + { // ---[ Step 1b.1 : If yes, compute CVFH using the cluster information + + for (size_t i = 0; i < clusters.size (); ++i) //for each cluster + + { + Eigen::Vector4f avg_normal = Eigen::Vector4f::Zero (); + Eigen::Vector4f avg_centroid = Eigen::Vector4f::Zero (); + + for (size_t j = 0; j < clusters[i].indices.size (); j++) + { + avg_normal += normals_filtered_cloud->points[clusters[i].indices[j]].getNormalVector4fMap (); + avg_centroid += normals_filtered_cloud->points[clusters[i].indices[j]].getVector4fMap (); + } + + avg_normal /= static_cast (clusters[i].indices.size ()); + avg_centroid /= static_cast (clusters[i].indices.size ()); + avg_normal.normalize (); + + Eigen::Vector3f avg_norm (avg_normal[0], avg_normal[1], avg_normal[2]); + Eigen::Vector3f avg_dominant_centroid (avg_centroid[0], avg_centroid[1], avg_centroid[2]); + + //append normal and centroid for the clusters + dominant_normals_.push_back (avg_norm); + centroids_dominant_orientations_.push_back (avg_dominant_centroid); + } + + //compute modified VFH for all dominant clusters and add them to the list! + output.points.resize (dominant_normals_.size ()); + output.width = static_cast (dominant_normals_.size ()); + + for (size_t i = 0; i < dominant_normals_.size (); ++i) + { + //configure VFH computation for CVFH + vfh.setNormalToUse (dominant_normals_[i]); + vfh.setCentroidToUse (centroids_dominant_orientations_[i]); + pcl::PointCloud vfh_signature; + vfh.compute (vfh_signature); + output.points[i] = vfh_signature.points[0]; + } + + //finish filling the descriptor with the shape distribution + PointInTPtr cloud_input (new pcl::PointCloud); + pcl::copyPointCloud (*surface_, *indices_, *cloud_input); + computeRFAndShapeDistribution (cloud_input, output, clusters_); //this will set transforms_ + } + else + { // ---[ Step 1b.1 : If no, compute a VFH using all the object points + + PCL_WARN("No clusters were found in the surface... using VFH...\n"); + Eigen::Vector4f avg_centroid; + pcl::compute3DCentroid (*surface_, avg_centroid); + Eigen::Vector3f cloud_centroid (avg_centroid[0], avg_centroid[1], avg_centroid[2]); + centroids_dominant_orientations_.push_back (cloud_centroid); + + //configure VFH computation using all object points + vfh.setCentroidToUse (cloud_centroid); + vfh.setUseGivenNormal (false); + + pcl::PointCloud vfh_signature; + vfh.compute (vfh_signature); + + output.points.resize (1); + output.width = 1; + + output.points[0] = vfh_signature.points[0]; + Eigen::Matrix4f id = Eigen::Matrix4f::Identity (); + transforms_.push_back (id); + valid_transforms_.push_back (false); + } +} + +#define PCL_INSTANTIATE_OURCVFHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::OURCVFHEstimation; + +#endif // PCL_FEATURES_IMPL_OURCVFH_H_ diff --git a/pcl-1.7/pcl/features/impl/pfh.hpp b/pcl-1.7/pcl/features/impl/pfh.hpp new file mode 100644 index 0000000..278e898 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/pfh.hpp @@ -0,0 +1,287 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_IMPL_PFH_H_ +#define PCL_FEATURES_IMPL_PFH_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::PFHEstimation::computePairFeatures ( + const pcl::PointCloud &cloud, const pcl::PointCloud &normals, + int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4) +{ + pcl::computePairFeatures (cloud.points[p_idx].getVector4fMap (), normals.points[p_idx].getNormalVector4fMap (), + cloud.points[q_idx].getVector4fMap (), normals.points[q_idx].getNormalVector4fMap (), + f1, f2, f3, f4); + + return (true); + + // mannually added + // PCL_ERROR("compute pair feature\n"); + // Eigen::Vector4f p1 = cloud.points[p_idx].getVector4fMap (); + // Eigen::Vector4f n1 = normals.points[p_idx].getNormalVector4fMap (); + // Eigen::Vector4f p2 = cloud.points[q_idx].getVector4fMap (); + // Eigen::Vector4f n2 = normals.points[q_idx].getNormalVector4fMap (); + + // Eigen::Vector4f dp2p1 = p2 - p1; + // dp2p1[3] = 0.0f; + // f4 = dp2p1.norm (); + + // if (f4 == 0.0f) + // { + // PCL_DEBUG ("[pcl::computePairFeatures] Euclidean distance between points is 0!\n"); + // f1 = f2 = f3 = f4 = 0.0f; + // return (false); + // } + + // Eigen::Vector4f n1_copy = n1, + // n2_copy = n2; + // n1_copy[3] = n2_copy[3] = 0.0f; + // float angle1 = n1_copy.dot (dp2p1) / f4; + + // // Make sure the same point is selected as 1 and 2 for each pair + // float angle2 = n2_copy.dot (dp2p1) / f4; + // if (acos (fabs (angle1)) > acos (fabs (angle2))) + // { + // // switch p1 and p2 + // n1_copy = n2; + // n2_copy = n1; + // n1_copy[3] = n2_copy[3] = 0.0f; + // dp2p1 *= (-1); + // f3 = -angle2; + // } + // else + // f3 = angle1; + + // // Create a Darboux frame coordinate system u-v-w + // // u = n1; v = (p_idx - q_idx) x u / || (p_idx - q_idx) x u ||; w = u x v + // Eigen::Vector4f v = dp2p1.cross3 (n1_copy); + // v[3] = 0.0f; + // float v_norm = v.norm (); + // if (v_norm == 0.0f) + // { + // PCL_DEBUG ("[pcl::computePairFeatures] Norm of Delta x U is 0!\n"); + // f1 = f2 = f3 = f4 = 0.0f; + // return (false); + // } + // // Normalize v + // v /= v_norm; + + // Eigen::Vector4f w = n1_copy.cross3 (v); + // // Do not have to normalize w - it is a unit vector by construction + + // v[3] = 0.0f; + // f2 = v.dot (n2_copy); + // w[3] = 0.0f; + // // Compute f1 = arctan (w * n2, u * n2) i.e. angle of n2 in the x=u, y=w coordinate system + // f1 = atan2f (w.dot (n2_copy), n1_copy.dot (n2_copy)); // @todo optimize this + + // return (true); + +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PFHEstimation::computePointPFHSignature ( + const pcl::PointCloud &cloud, const pcl::PointCloud &normals, + const std::vector &indices, int nr_split, Eigen::VectorXf &pfh_histogram) +{ + int h_index, h_p; + + // Clear the resultant point histogram + pfh_histogram.setZero (); + + // Factorization constant + float hist_incr = 100.0f / static_cast (indices.size () * (indices.size () - 1) / 2); + + std::pair key; + // Iterate over all the points in the neighborhood + for (size_t i_idx = 0; i_idx < indices.size (); ++i_idx) + { + for (size_t j_idx = 0; j_idx < i_idx; ++j_idx) + { + // If the 3D points are invalid, don't bother estimating, just continue + if (!isFinite (cloud.points[indices[i_idx]]) || !isFinite (cloud.points[indices[j_idx]])) + continue; + + if (use_cache_) + { + // In order to create the key, always use the smaller index as the first key pair member + int p1, p2; + // if (indices[i_idx] >= indices[j_idx]) + // { + p1 = indices[i_idx]; + p2 = indices[j_idx]; + // } + // else + // { + // p1 = indices[j_idx]; + // p2 = indices[i_idx]; + // } + key = std::pair (p1, p2); + + // Check to see if we already estimated this pair in the global hashmap + std::map, Eigen::Vector4f, std::less >, Eigen::aligned_allocator >::iterator fm_it = feature_map_.find (key); + if (fm_it != feature_map_.end ()) + pfh_tuple_ = fm_it->second; + else + { + // Compute the pair NNi to NNj + if (!computePairFeatures (cloud, normals, indices[i_idx], indices[j_idx], + pfh_tuple_[0], pfh_tuple_[1], pfh_tuple_[2], pfh_tuple_[3])) + continue; + } + } + else + if (!computePairFeatures (cloud, normals, indices[i_idx], indices[j_idx], + pfh_tuple_[0], pfh_tuple_[1], pfh_tuple_[2], pfh_tuple_[3])) + continue; + + // Normalize the f1, f2, f3 features and push them in the histogram + f_index_[0] = static_cast (floor (nr_split * ((pfh_tuple_[0] + M_PI) * d_pi_))); + if (f_index_[0] < 0) f_index_[0] = 0; + if (f_index_[0] >= nr_split) f_index_[0] = nr_split - 1; + + f_index_[1] = static_cast (floor (nr_split * ((pfh_tuple_[1] + 1.0) * 0.5))); + if (f_index_[1] < 0) f_index_[1] = 0; + if (f_index_[1] >= nr_split) f_index_[1] = nr_split - 1; + + f_index_[2] = static_cast (floor (nr_split * ((pfh_tuple_[2] + 1.0) * 0.5))); + if (f_index_[2] < 0) f_index_[2] = 0; + if (f_index_[2] >= nr_split) f_index_[2] = nr_split - 1; + + // Copy into the histogram + h_index = 0; + h_p = 1; + for (int d = 0; d < 3; ++d) + { + h_index += h_p * f_index_[d]; + h_p *= nr_split; + } + pfh_histogram[h_index] += hist_incr; + + if (use_cache_) + { + // Save the value in the hashmap + feature_map_[key] = pfh_tuple_; + + // Use a maximum cache so that we don't go overboard on RAM usage + key_list_.push (key); + // Check to see if we need to remove an element due to exceeding max_size + if (key_list_.size () > max_cache_size_) + { + // Remove the last element. + feature_map_.erase (key_list_.back ()); + key_list_.pop (); + } + } + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PFHEstimation::computeFeature (PointCloudOut &output) +{ + // Clear the feature map + feature_map_.clear (); + std::queue > empty; + std::swap (key_list_, empty); + + pfh_histogram_.setZero (nr_subdiv_ * nr_subdiv_ * nr_subdiv_); + + // Allocate enough space to hold the results + // \note This resize is irrelevant for a radiusSearch (). + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + output.is_dense = true; + // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense + if (input_->is_dense) + { + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) + { + for (int d = 0; d < pfh_histogram_.size (); ++d) + output.points[idx].histogram[d] = std::numeric_limits::quiet_NaN (); + + output.is_dense = false; + continue; + } + + // Estimate the PFH signature at each patch + computePointPFHSignature (*surface_, *normals_, nn_indices, nr_subdiv_, pfh_histogram_); + + // Copy into the resultant cloud + for (int d = 0; d < pfh_histogram_.size (); ++d) + output.points[idx].histogram[d] = pfh_histogram_[d]; + } + } + else + { + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + if (!isFinite ((*input_)[(*indices_)[idx]]) || + this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) + { + for (int d = 0; d < pfh_histogram_.size (); ++d) + output.points[idx].histogram[d] = std::numeric_limits::quiet_NaN (); + + output.is_dense = false; + continue; + } + + // Estimate the PFH signature at each patch + computePointPFHSignature (*surface_, *normals_, nn_indices, nr_subdiv_, pfh_histogram_); + + // Copy into the resultant cloud + for (int d = 0; d < pfh_histogram_.size (); ++d) + output.points[idx].histogram[d] = pfh_histogram_[d]; + } + } +} + +#define PCL_INSTANTIATE_PFHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::PFHEstimation; + +#endif // PCL_FEATURES_IMPL_PFH_H_ + diff --git a/pcl-1.7/pcl/features/impl/pfhrgb.hpp b/pcl-1.7/pcl/features/impl/pfhrgb.hpp new file mode 100644 index 0000000..dbe5918 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/pfhrgb.hpp @@ -0,0 +1,173 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_FEATURES_IMPL_PFHRGB_H_ +#define PCL_FEATURES_IMPL_PFHRGB_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::PFHRGBEstimation::computeRGBPairFeatures ( + const pcl::PointCloud &cloud, const pcl::PointCloud &normals, + int p_idx, int q_idx, + float &f1, float &f2, float &f3, float &f4, float &f5, float &f6, float &f7) +{ + Eigen::Vector4i colors1 (cloud.points[p_idx].r, cloud.points[p_idx].g, cloud.points[p_idx].b, 0), + colors2 (cloud.points[q_idx].r, cloud.points[q_idx].g, cloud.points[q_idx].b, 0); + pcl::computeRGBPairFeatures (cloud.points[p_idx].getVector4fMap (), normals.points[p_idx].getNormalVector4fMap (), + colors1, + cloud.points[q_idx].getVector4fMap (), normals.points[q_idx].getNormalVector4fMap (), + colors2, + f1, f2, f3, f4, f5, f6, f7); + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PFHRGBEstimation::computePointPFHRGBSignature ( + const pcl::PointCloud &cloud, const pcl::PointCloud &normals, + const std::vector &indices, int nr_split, Eigen::VectorXf &pfhrgb_histogram) +{ + int h_index, h_p; + + // Clear the resultant point histogram + pfhrgb_histogram.setZero (); + + // Factorization constant + float hist_incr = 100.0f / static_cast (indices.size () * indices.size () - 1); + + // Iterate over all the points in the neighborhood + for (size_t i_idx = 0; i_idx < indices.size (); ++i_idx) + { + for (size_t j_idx = 0; j_idx < indices.size (); ++j_idx) + { + // Avoid unnecessary returns + if (i_idx == j_idx) + continue; + + // Compute the pair NNi to NNj + if (!computeRGBPairFeatures (cloud, normals, indices[i_idx], indices[j_idx], + pfhrgb_tuple_[0], pfhrgb_tuple_[1], pfhrgb_tuple_[2], pfhrgb_tuple_[3], + pfhrgb_tuple_[4], pfhrgb_tuple_[5], pfhrgb_tuple_[6])) + continue; + + // Normalize the f1, f2, f3, f5, f6, f7 features and push them in the histogram + f_index_[0] = static_cast (floor (nr_split * ((pfhrgb_tuple_[0] + M_PI) * d_pi_))); + if (f_index_[0] < 0) f_index_[0] = 0; + if (f_index_[0] >= nr_split) f_index_[0] = nr_split - 1; + + f_index_[1] = static_cast (floor (nr_split * ((pfhrgb_tuple_[1] + 1.0) * 0.5))); + if (f_index_[1] < 0) f_index_[1] = 0; + if (f_index_[1] >= nr_split) f_index_[1] = nr_split - 1; + + f_index_[2] = static_cast (floor (nr_split * ((pfhrgb_tuple_[2] + 1.0) * 0.5))); + if (f_index_[2] < 0) f_index_[2] = 0; + if (f_index_[2] >= nr_split) f_index_[2] = nr_split - 1; + + // color ratios are in [-1, 1] + f_index_[4] = static_cast (floor (nr_split * ((pfhrgb_tuple_[4] + 1.0) * 0.5))); + if (f_index_[4] < 0) f_index_[4] = 0; + if (f_index_[4] >= nr_split) f_index_[4] = nr_split - 1; + + f_index_[5] = static_cast (floor (nr_split * ((pfhrgb_tuple_[5] + 1.0) * 0.5))); + if (f_index_[5] < 0) f_index_[5] = 0; + if (f_index_[5] >= nr_split) f_index_[5] = nr_split - 1; + + f_index_[6] = static_cast (floor (nr_split * ((pfhrgb_tuple_[6] + 1.0) * 0.5))); + if (f_index_[6] < 0) f_index_[6] = 0; + if (f_index_[6] >= nr_split) f_index_[6] = nr_split - 1; + + + // Copy into the histogram + h_index = 0; + h_p = 1; + for (int d = 0; d < 3; ++d) + { + h_index += h_p * f_index_[d]; + h_p *= nr_split; + } + pfhrgb_histogram[h_index] += hist_incr; + + // and the colors + h_index = 125; + h_p = 1; + for (int d = 4; d < 7; ++d) + { + h_index += h_p * f_index_[d]; + h_p *= nr_split; + } + pfhrgb_histogram[h_index] += hist_incr; + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PFHRGBEstimation::computeFeature (PointCloudOut &output) +{ + /// nr_subdiv^3 for RGB and nr_subdiv^3 for the angular features + pfhrgb_histogram_.setZero (2 * nr_subdiv_ * nr_subdiv_ * nr_subdiv_); + pfhrgb_tuple_.setZero (7); + + // Allocate enough space to hold the results + // \note This resize is irrelevant for a radiusSearch (). + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists); + + // Estimate the PFH signature at each patch + computePointPFHRGBSignature (*surface_, *normals_, nn_indices, nr_subdiv_, pfhrgb_histogram_); + + // Copy into the resultant cloud + for (int d = 0; d < pfhrgb_histogram_.size (); ++d) { + output.points[idx].histogram[d] = pfhrgb_histogram_[d]; +// PCL_INFO ("%f ", pfhrgb_histogram_[d]); + } +// PCL_INFO ("\n"); + } +} + +#define PCL_INSTANTIATE_PFHRGBEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::PFHRGBEstimation; + +#endif /* PCL_FEATURES_IMPL_PFHRGB_H_ */ diff --git a/pcl-1.7/pcl/features/impl/ppf.hpp b/pcl-1.7/pcl/features/impl/ppf.hpp new file mode 100644 index 0000000..e1a5872 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/ppf.hpp @@ -0,0 +1,123 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_FEATURES_IMPL_PPF_H_ +#define PCL_FEATURES_IMPL_PPF_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::PPFEstimation::PPFEstimation () + : FeatureFromNormals () +{ + feature_name_ = "PPFEstimation"; + // Slight hack in order to pass the check for the presence of a search method in Feature::initCompute () + Feature::tree_.reset (new pcl::search::KdTree ()); + Feature::search_radius_ = 1.0f; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PPFEstimation::computeFeature (PointCloudOut &output) +{ + // Initialize output container - overwrite the sizes done by Feature::initCompute () + output.points.resize (indices_->size () * input_->points.size ()); + output.height = 1; + output.width = static_cast (output.points.size ()); + output.is_dense = true; + + // Compute point pair features for every pair of points in the cloud + for (size_t index_i = 0; index_i < indices_->size (); ++index_i) + { + size_t i = (*indices_)[index_i]; + for (size_t j = 0 ; j < input_->points.size (); ++j) + { + PointOutT p; + if (i != j) + { + if (//pcl::computePPFPairFeature + pcl::computePairFeatures (input_->points[i].getVector4fMap (), + normals_->points[i].getNormalVector4fMap (), + input_->points[j].getVector4fMap (), + normals_->points[j].getNormalVector4fMap (), + p.f1, p.f2, p.f3, p.f4)) + { + // Calculate alpha_m angle + Eigen::Vector3f model_reference_point = input_->points[i].getVector3fMap (), + model_reference_normal = normals_->points[i].getNormalVector3fMap (), + model_point = input_->points[j].getVector3fMap (); + float rotation_angle = acosf (model_reference_normal.dot (Eigen::Vector3f::UnitX ())); + bool parallel_to_x = (model_reference_normal.y() == 0.0f && model_reference_normal.z() == 0.0f); + Eigen::Vector3f rotation_axis = (parallel_to_x)?(Eigen::Vector3f::UnitY ()):(model_reference_normal.cross (Eigen::Vector3f::UnitX ()). normalized()); + Eigen::AngleAxisf rotation_mg (rotation_angle, rotation_axis); + Eigen::Affine3f transform_mg (Eigen::Translation3f ( rotation_mg * ((-1) * model_reference_point)) * rotation_mg); + + Eigen::Vector3f model_point_transformed = transform_mg * model_point; + float angle = atan2f ( -model_point_transformed(2), model_point_transformed(1)); + if (sin (angle) * model_point_transformed(2) < 0.0f) + angle *= (-1); + p.alpha_m = -angle; + } + else + { + PCL_ERROR ("[pcl::%s::computeFeature] Computing pair feature vector between points %u and %u went wrong.\n", getClassName ().c_str (), i, j); + p.f1 = p.f2 = p.f3 = p.f4 = p.alpha_m = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + } + } + // Do not calculate the feature for identity pairs (i, i) as they are not used + // in the following computations + else + { + p.f1 = p.f2 = p.f3 = p.f4 = p.alpha_m = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + } + + output.points[index_i*input_->points.size () + j] = p; + } + } +} + +#define PCL_INSTANTIATE_PPFEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::PPFEstimation; + + +#endif // PCL_FEATURES_IMPL_PPF_H_ diff --git a/pcl-1.7/pcl/features/impl/ppfrgb.hpp b/pcl-1.7/pcl/features/impl/ppfrgb.hpp new file mode 100644 index 0000000..d351c10 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/ppfrgb.hpp @@ -0,0 +1,181 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_IMPL_PPFRGB_H_ +#define PCL_FEATURES_IMPL_PPFRGB_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::PPFRGBEstimation::PPFRGBEstimation () +: FeatureFromNormals () +{ + feature_name_ = "PPFRGBEstimation"; + // Slight hack in order to pass the check for the presence of a search method in Feature::initCompute () + Feature::tree_.reset (new pcl::search::KdTree ()); + Feature::search_radius_ = 1.0f; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PPFRGBEstimation::computeFeature (PointCloudOut &output) +{ + // Initialize output container - overwrite the sizes done by Feature::initCompute () + output.points.resize (indices_->size () * input_->points.size ()); + output.height = 1; + output.width = static_cast (output.points.size ()); + + // Compute point pair features for every pair of points in the cloud + for (size_t index_i = 0; index_i < indices_->size (); ++index_i) + { + size_t i = (*indices_)[index_i]; + for (size_t j = 0 ; j < input_->points.size (); ++j) + { + PointOutT p; + if (i != j) + { + if (pcl::computeRGBPairFeatures + (input_->points[i].getVector4fMap (), normals_->points[i].getNormalVector4fMap (), input_->points[i].getRGBVector4i (), + input_->points[j].getVector4fMap (), normals_->points[j].getNormalVector4fMap (), input_->points[j].getRGBVector4i (), + p.f1, p.f2, p.f3, p.f4, p.r_ratio, p.g_ratio, p.b_ratio)) + { + // Calculate alpha_m angle + Eigen::Vector3f model_reference_point = input_->points[i].getVector3fMap (), + model_reference_normal = normals_->points[i].getNormalVector3fMap (), + model_point = input_->points[j].getVector3fMap (); + Eigen::AngleAxisf rotation_mg (acosf (model_reference_normal.dot (Eigen::Vector3f::UnitX ())), + model_reference_normal.cross (Eigen::Vector3f::UnitX ()).normalized ()); + Eigen::Affine3f transform_mg = Eigen::Translation3f ( rotation_mg * ((-1) * model_reference_point)) * rotation_mg; + + Eigen::Vector3f model_point_transformed = transform_mg * model_point; + float angle = atan2f ( -model_point_transformed(2), model_point_transformed(1)); + if (sin (angle) * model_point_transformed(2) < 0.0f) + angle *= (-1); + p.alpha_m = -angle; + } + else + { + PCL_ERROR ("[pcl::%s::computeFeature] Computing pair feature vector between points %lu and %lu went wrong.\n", getClassName ().c_str (), i, j); + p.f1 = p.f2 = p.f3 = p.f4 = p.alpha_m = p.r_ratio = p.g_ratio = p.b_ratio = 0.f; + } + } + // Do not calculate the feature for identity pairs (i, i) as they are not used + // in the following computations + else + p.f1 = p.f2 = p.f3 = p.f4 = p.alpha_m = p.r_ratio = p.g_ratio = p.b_ratio = 0.f; + + output.points[index_i*input_->points.size () + j] = p; + } + } +} + + + +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::PPFRGBRegionEstimation::PPFRGBRegionEstimation () +: FeatureFromNormals () +{ + feature_name_ = "PPFRGBEstimation"; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PPFRGBRegionEstimation::computeFeature (PointCloudOut &output) +{ + PCL_INFO ("before computing output size: %u\n", output.size ()); + output.resize (indices_->size ()); + for (int index_i = 0; index_i < static_cast (indices_->size ()); ++index_i) + { + int i = (*indices_)[index_i]; + std::vector nn_indices; + std::vector nn_distances; + tree_->radiusSearch (i, static_cast (search_radius_), nn_indices, nn_distances); + + PointOutT average_feature_nn; + average_feature_nn.alpha_m = 0; + average_feature_nn.f1 = average_feature_nn.f2 = average_feature_nn.f3 = average_feature_nn.f4 = + average_feature_nn.r_ratio = average_feature_nn.g_ratio = average_feature_nn.b_ratio = 0.0f; + + for (std::vector::iterator nn_it = nn_indices.begin (); nn_it != nn_indices.end (); ++nn_it) + { + int j = *nn_it; + if (i != j) + { + float f1, f2, f3, f4, r_ratio, g_ratio, b_ratio; + if (pcl::computeRGBPairFeatures + (input_->points[i].getVector4fMap (), normals_->points[i].getNormalVector4fMap (), input_->points[i].getRGBVector4i (), + input_->points[j].getVector4fMap (), normals_->points[j].getNormalVector4fMap (), input_->points[j].getRGBVector4i (), + f1, f2, f3, f4, r_ratio, g_ratio, b_ratio)) + { + average_feature_nn.f1 += f1; + average_feature_nn.f2 += f2; + average_feature_nn.f3 += f3; + average_feature_nn.f4 += f4; + average_feature_nn.r_ratio += r_ratio; + average_feature_nn.g_ratio += g_ratio; + average_feature_nn.b_ratio += b_ratio; + } + else + { + PCL_ERROR ("[pcl::%s::computeFeature] Computing pair feature vector between points %lu and %lu went wrong.\n", getClassName ().c_str (), i, j); + } + } + } + + float normalization_factor = static_cast (nn_indices.size ()); + average_feature_nn.f1 /= normalization_factor; + average_feature_nn.f2 /= normalization_factor; + average_feature_nn.f3 /= normalization_factor; + average_feature_nn.f4 /= normalization_factor; + average_feature_nn.r_ratio /= normalization_factor; + average_feature_nn.g_ratio /= normalization_factor; + average_feature_nn.b_ratio /= normalization_factor; + output.points[index_i] = average_feature_nn; + } + PCL_INFO ("Output size: %u\n", output.points.size ()); +} + + +#define PCL_INSTANTIATE_PPFRGBEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::PPFRGBEstimation; +#define PCL_INSTANTIATE_PPFRGBRegionEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::PPFRGBRegionEstimation; + +#endif // PCL_FEATURES_IMPL_PPFRGB_H_ diff --git a/pcl-1.7/pcl/features/impl/principal_curvatures.hpp b/pcl-1.7/pcl/features/impl/principal_curvatures.hpp new file mode 100644 index 0000000..fe1e5c6 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/principal_curvatures.hpp @@ -0,0 +1,166 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_IMPL_PRINCIPAL_CURVATURES_H_ +#define PCL_FEATURES_IMPL_PRINCIPAL_CURVATURES_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PrincipalCurvaturesEstimation::computePointPrincipalCurvatures ( + const pcl::PointCloud &normals, int p_idx, const std::vector &indices, + float &pcx, float &pcy, float &pcz, float &pc1, float &pc2) +{ + EIGEN_ALIGN16 Eigen::Matrix3f I = Eigen::Matrix3f::Identity (); + Eigen::Vector3f n_idx (normals.points[p_idx].normal[0], normals.points[p_idx].normal[1], normals.points[p_idx].normal[2]); + EIGEN_ALIGN16 Eigen::Matrix3f M = I - n_idx * n_idx.transpose (); // projection matrix (into tangent plane) + + // Project normals into the tangent plane + Eigen::Vector3f normal; + projected_normals_.resize (indices.size ()); + xyz_centroid_.setZero (); + for (size_t idx = 0; idx < indices.size(); ++idx) + { + normal[0] = normals.points[indices[idx]].normal[0]; + normal[1] = normals.points[indices[idx]].normal[1]; + normal[2] = normals.points[indices[idx]].normal[2]; + + projected_normals_[idx] = M * normal; + xyz_centroid_ += projected_normals_[idx]; + } + + // Estimate the XYZ centroid + xyz_centroid_ /= static_cast (indices.size ()); + + // Initialize to 0 + covariance_matrix_.setZero (); + + double demean_xy, demean_xz, demean_yz; + // For each point in the cloud + for (size_t idx = 0; idx < indices.size (); ++idx) + { + demean_ = projected_normals_[idx] - xyz_centroid_; + + demean_xy = demean_[0] * demean_[1]; + demean_xz = demean_[0] * demean_[2]; + demean_yz = demean_[1] * demean_[2]; + + covariance_matrix_(0, 0) += demean_[0] * demean_[0]; + covariance_matrix_(0, 1) += static_cast (demean_xy); + covariance_matrix_(0, 2) += static_cast (demean_xz); + + covariance_matrix_(1, 0) += static_cast (demean_xy); + covariance_matrix_(1, 1) += demean_[1] * demean_[1]; + covariance_matrix_(1, 2) += static_cast (demean_yz); + + covariance_matrix_(2, 0) += static_cast (demean_xz); + covariance_matrix_(2, 1) += static_cast (demean_yz); + covariance_matrix_(2, 2) += demean_[2] * demean_[2]; + } + + // Extract the eigenvalues and eigenvectors + pcl::eigen33 (covariance_matrix_, eigenvalues_); + pcl::computeCorrespondingEigenVector (covariance_matrix_, eigenvalues_ [2], eigenvector_); + + pcx = eigenvector_ [0]; + pcy = eigenvector_ [1]; + pcz = eigenvector_ [2]; + float indices_size = 1.0f / static_cast (indices.size ()); + pc1 = eigenvalues_ [2] * indices_size; + pc2 = eigenvalues_ [1] * indices_size; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PrincipalCurvaturesEstimation::computeFeature (PointCloudOut &output) +{ + // Allocate enough space to hold the results + // \note This resize is irrelevant for a radiusSearch (). + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + output.is_dense = true; + // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense + if (input_->is_dense) + { + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) + { + output.points[idx].principal_curvature[0] = output.points[idx].principal_curvature[1] = output.points[idx].principal_curvature[2] = + output.points[idx].pc1 = output.points[idx].pc2 = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + continue; + } + + // Estimate the principal curvatures at each patch + computePointPrincipalCurvatures (*normals_, (*indices_)[idx], nn_indices, + output.points[idx].principal_curvature[0], output.points[idx].principal_curvature[1], output.points[idx].principal_curvature[2], + output.points[idx].pc1, output.points[idx].pc2); + } + } + else + { + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + if (!isFinite ((*input_)[(*indices_)[idx]]) || + this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) + { + output.points[idx].principal_curvature[0] = output.points[idx].principal_curvature[1] = output.points[idx].principal_curvature[2] = + output.points[idx].pc1 = output.points[idx].pc2 = std::numeric_limits::quiet_NaN (); + output.is_dense = false; + continue; + } + + // Estimate the principal curvatures at each patch + computePointPrincipalCurvatures (*normals_, (*indices_)[idx], nn_indices, + output.points[idx].principal_curvature[0], output.points[idx].principal_curvature[1], output.points[idx].principal_curvature[2], + output.points[idx].pc1, output.points[idx].pc2); + } + } +} + +#define PCL_INSTANTIATE_PrincipalCurvaturesEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::PrincipalCurvaturesEstimation; + +#endif // PCL_FEATURES_IMPL_PRINCIPAL_CURVATURES_H_ diff --git a/pcl-1.7/pcl/features/impl/range_image_border_extractor.hpp b/pcl-1.7/pcl/features/impl/range_image_border_extractor.hpp new file mode 100644 index 0000000..bb68a18 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/range_image_border_extractor.hpp @@ -0,0 +1,404 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Bastian Steder + */ + +#include + +namespace pcl { + +////////// STATIC ////////// +float RangeImageBorderExtractor::getObstacleBorderAngle(const BorderTraits& border_traits) +{ + float x=0.0f, y=0.0f; + if (border_traits[BORDER_TRAIT__OBSTACLE_BORDER_RIGHT]) + ++x; + if (border_traits[BORDER_TRAIT__OBSTACLE_BORDER_LEFT]) + --x; + if (border_traits[BORDER_TRAIT__OBSTACLE_BORDER_TOP]) + --y; + if (border_traits[BORDER_TRAIT__OBSTACLE_BORDER_BOTTOM]) + ++y; + + return atan2f(y, x); +} + +inline std::ostream& operator << (std::ostream& os, const RangeImageBorderExtractor::Parameters& p) +{ + os << PVARC(p.pixel_radius_borders)<getPoint(x, y); + PointWithRange neighbor; + range_image_->get1dPointAverage(x+offset_x, y+offset_y, offset_x, offset_y, pixel_radius, neighbor); + if (pcl_isinf(neighbor.range)) + { + if (neighbor.range < 0.0f) + return 0.0f; + else + { + //cout << "INF edge -> Setting to 1.0\n"; + return 1.0f; // TODO: Something more intelligent + } + } + + float neighbor_distance_squared = squaredEuclideanDistance(neighbor, point); + if (neighbor_distance_squared <= local_surface.max_neighbor_distance_squared) + return 0.0f; + float ret = 1.0f - sqrtf(local_surface.max_neighbor_distance_squared / neighbor_distance_squared); + if (neighbor.range < point.range) + ret = -ret; + return ret; +} + +//float RangeImageBorderExtractor::getNormalBasedBorderScore(const RangeImageBorderExtractor::LocalSurface& local_surface, + //int x, int y, int offset_x, int offset_y) const +//{ + //PointWithRange neighbor; + //range_image_->get1dPointAverage(x+offset_x, y+offset_y, offset_x, offset_y, parameters_.pixel_radius_borders, neighbor); + //if (pcl_isinf(neighbor.range)) + //{ + //if (neighbor.range < 0.0f) + //return 0.0f; + //else + //return 1.0f; // TODO: Something more intelligent (Compare normal with viewing direction) + //} + + //float normal_distance_to_plane_squared = local_surface.smallest_eigenvalue_no_jumps; + //float distance_to_plane = local_surface.normal_no_jumps.dot(local_surface.neighborhood_mean_no_jumps-neighbor.getVector3fMap()); + //bool shadow_side = distance_to_plane < 0.0f; + //float distance_to_plane_squared = pow(distance_to_plane, 2); + //if (distance_to_plane_squared <= normal_distance_to_plane_squared) + //return 0.0f; + //float ret = 1.0f - (normal_distance_to_plane_squared/distance_to_plane_squared); + //if (shadow_side) + //ret = -ret; + ////cout << PVARC(normal_distance_to_plane_squared)< "<getPoint(x, y); + Eigen::Vector3f neighbor_point; + range_image_->calculate3DPoint(static_cast (x+delta_x), static_cast (y+delta_y), point.range, neighbor_point); + //cout << "Neighborhood point is "<getSensorPos(), + viewing_direction = neighbor_point-sensor_pos; + + float lambda = (local_surface->normal_no_jumps.dot(local_surface->neighborhood_mean_no_jumps-sensor_pos)/ + local_surface->normal_no_jumps.dot(viewing_direction)); + neighbor_point = lambda*viewing_direction + sensor_pos; + //cout << "Neighborhood point projected onto plane is "< "<< direction[0]<<","<< direction[1]<<","<< direction[2]<<"\n"; + direction = neighbor_point-point.getVector3fMap(); + direction.normalize(); + + return true; +} + +void RangeImageBorderExtractor::calculateBorderDirection(int x, int y) +{ + int index = y*range_image_->width + x; + Eigen::Vector3f*& border_direction = border_directions_[index]; + border_direction = NULL; + const BorderDescription& border_description = border_descriptions_->points[index]; + const BorderTraits& border_traits = border_description.traits; + if (!border_traits[BORDER_TRAIT__OBSTACLE_BORDER]) + return; + border_direction = new Eigen::Vector3f(0.0f, 0.0f, 0.0f); + if (!get3dDirection(border_description, *border_direction, surface_structure_[index])) + { + delete border_direction; + border_direction = NULL; + return; + } +} + +bool RangeImageBorderExtractor::changeScoreAccordingToShadowBorderValue(int x, int y, int offset_x, int offset_y, float* border_scores, + float* border_scores_other_direction, int& shadow_border_idx) const +{ + float& border_score = border_scores[y*range_image_->width+x]; + + shadow_border_idx = -1; + if (border_scoreisMaxRange(x+offset_x, y+offset_y)) + { + shadow_border_idx = (y+offset_y)*range_image_->width + x+offset_x; + return true; + } + } + + float best_shadow_border_score = 0.0f; + + for (int neighbor_distance=1; neighbor_distance<=parameters_.pixel_radius_borders; ++neighbor_distance) + { + int neighbor_x=x+neighbor_distance*offset_x, neighbor_y=y+neighbor_distance*offset_y; + if (!range_image_->isInImage(neighbor_x, neighbor_y)) + continue; + float neighbor_shadow_border_score = border_scores_other_direction[neighbor_y*range_image_->width+neighbor_x]; + + if (neighbor_shadow_border_score < best_shadow_border_score) + { + shadow_border_idx = neighbor_y*range_image_->width + neighbor_x; + best_shadow_border_score = neighbor_shadow_border_score; + } + } + if (shadow_border_idx >= 0) + { + //cout << PVARC(border_score)<=parameters_.minimum_border_probability) + return true; + } + shadow_border_idx = -1; + border_score = 0.0f; // Since there was no shadow border found we set this value to zero, so that it does not influence the maximum search + return false; +} + +float RangeImageBorderExtractor::updatedScoreAccordingToNeighborValues(int x, int y, const float* border_scores) const +{ + float max_score_bonus = 0.5f; + + float border_score = border_scores[y*range_image_->width+x]; + + // Check if an update can bring the score to a value higher than the minimum + if (border_score + max_score_bonus*(1.0f-border_score) < parameters_.minimum_border_probability) + return border_score; + + float average_neighbor_score=0.0f, weight_sum=0.0f; + for (int y2=y-1; y2<=y+1; ++y2) + { + for (int x2=x-1; x2<=x+1; ++x2) + { + if (!range_image_->isInImage(x2, y2) || (x2==x&&y2==y)) + continue; + average_neighbor_score += border_scores[y2*range_image_->width+x2]; + weight_sum += 1.0f; + } + } + average_neighbor_score /=weight_sum; + + if (average_neighbor_score*border_score < 0.0f) + return border_score; + + float new_border_score = border_score + max_score_bonus * average_neighbor_score * (1.0f-fabsf(border_score)); + + //std::cout << PVARC(border_score)<width+x]; + if (border_scoreisInImage(neighbor_x, neighbor_y)) + continue; + float neighbor_shadow_border_score = border_scores_other_direction[neighbor_y*range_image_->width+neighbor_x]; + + if (neighbor_shadow_border_score < best_shadow_border_score) + { + shadow_border_idx = neighbor_y*range_image_->width + neighbor_x; + best_shadow_border_score = neighbor_shadow_border_score; + } + } + if (shadow_border_idx >= 0) + { + return true; + } + border_score = 0.0f; // Since there was no shadow border found we set this value to zero, so that it does not influence the maximum search + return false; +} + +bool RangeImageBorderExtractor::checkIfMaximum(int x, int y, int offset_x, int offset_y, float* border_scores, int shadow_border_idx) const +{ + float border_score = border_scores[y*range_image_->width+x]; + int neighbor_x=x-offset_x, neighbor_y=y-offset_y; + if (range_image_->isInImage(neighbor_x, neighbor_y) && border_scores[neighbor_y*range_image_->width+neighbor_x] > border_score) + return false; + + for (int neighbor_distance=1; neighbor_distance<=parameters_.pixel_radius_borders; ++neighbor_distance) + { + neighbor_x=x+neighbor_distance*offset_x; neighbor_y=y+neighbor_distance*offset_y; + if (!range_image_->isInImage(neighbor_x, neighbor_y)) + continue; + int neighbor_index = neighbor_y*range_image_->width + neighbor_x; + if (neighbor_index==shadow_border_idx) + return true; + + float neighbor_border_score = border_scores[neighbor_index]; + if (neighbor_border_score > border_score) + return false; + } + return true; +} + +bool RangeImageBorderExtractor::calculateMainPrincipalCurvature(int x, int y, int radius, float& magnitude, + Eigen::Vector3f& main_direction) const +{ + magnitude = 0.0f; + int index = y*range_image_->width+x; + LocalSurface* local_surface = surface_structure_[index]; + if (local_surface==NULL) + return false; + //const PointWithRange& point = range_image_->getPointNoCheck(x,y); + + //Eigen::Vector3f& normal = local_surface->normal_no_jumps; + //Eigen::Matrix3f to_tangent_plane = Eigen::Matrix3f::Identity() - normal*normal.transpose(); + + VectorAverage3f vector_average; + bool beams_valid[9]; + for (int step=1; step<=radius; ++step) + { + int beam_idx = 0; + for (int y2=y-step; y2<=y+step; y2+=step) + { + for (int x2=x-step; x2<=x+step; x2+=step) + { + bool& beam_valid = beams_valid[beam_idx++]; + if (step==1) + { + if (x2==x && y2==y) + beam_valid = false; + else + beam_valid = true; + } + else + if (!beam_valid) + continue; + //std::cout << x2-x<<","<isValid(x2,y2)) + continue; + + int index2 = y2*range_image_->width + x2; + + const BorderTraits& border_traits = border_descriptions_->points[index2].traits; + if (border_traits[BORDER_TRAIT__VEIL_POINT] || border_traits[BORDER_TRAIT__SHADOW_BORDER]) + { + beam_valid = false; + continue; + } + + //const PointWithRange& point2 = range_image_->getPoint(index2); + LocalSurface* local_surface2 = surface_structure_[index2]; + if (local_surface2==NULL) + continue; + Eigen::Vector3f& normal2 = local_surface2->normal_no_jumps; + //float distance_squared = squaredEuclideanDistance(point, point2); + //vector_average.add(to_tangent_plane*normal2); + vector_average.add(normal2); + } + } + } + //std::cout << "\n"; + if (vector_average.getNoOfSamples() < 3) + return false; + + Eigen::Vector3f eigen_values, eigen_vector1, eigen_vector2; + vector_average.doPCA(eigen_values, eigen_vector1, eigen_vector2, main_direction); + magnitude = sqrtf(eigen_values[2]); + //magnitude = eigen_values[2]; + //magnitude = 1.0f - powf(1.0f-magnitude, 5); + //magnitude = 1.0f - powf(1.0f-magnitude, 10); + //magnitude += magnitude - powf(magnitude,2); + //magnitude += magnitude - powf(magnitude,2); + + //magnitude = sqrtf(local_surface->eigen_values[0]/local_surface->eigen_values.sum()); + //magnitude = sqrtf(local_surface->eigen_values_no_jumps[0]/local_surface->eigen_values_no_jumps.sum()); + + //if (surface_structure_[y*range_image_->width+x+1]==NULL||surface_structure_[y*range_image_->width+x-1]==NULL) + //{ + //magnitude = -std::numeric_limits::infinity (); + //return false; + //} + //float angle2 = acosf(surface_structure_[y*range_image_->width+x+1]->normal.dot(local_surface->normal)), + //angle1 = acosf(surface_structure_[y*range_image_->width+x-1]->normal.dot(local_surface->normal)); + //magnitude = angle2-angle1; + + if (!pcl_isfinite(magnitude)) + return false; + + return true; +} + +} // namespace end diff --git a/pcl-1.7/pcl/features/impl/rift.hpp b/pcl-1.7/pcl/features/impl/rift.hpp new file mode 100644 index 0000000..4d167ab --- /dev/null +++ b/pcl-1.7/pcl/features/impl/rift.hpp @@ -0,0 +1,184 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_IMPL_RIFT_H_ +#define PCL_FEATURES_IMPL_RIFT_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RIFTEstimation::computeRIFT ( + const PointCloudIn &cloud, const PointCloudGradient &gradient, + int p_idx, float radius, const std::vector &indices, + const std::vector &sqr_distances, Eigen::MatrixXf &rift_descriptor) +{ + if (indices.empty ()) + { + PCL_ERROR ("[pcl::RIFTEstimation] Null indices points passed!\n"); + return; + } + + // Determine the number of bins to use based on the size of rift_descriptor + int nr_distance_bins = static_cast (rift_descriptor.rows ()); + int nr_gradient_bins = static_cast (rift_descriptor.cols ()); + + // Get the center point + pcl::Vector3fMapConst p0 = cloud.points[p_idx].getVector3fMap (); + + // Compute the RIFT descriptor + rift_descriptor.setZero (); + for (size_t idx = 0; idx < indices.size (); ++idx) + { + // Compute the gradient magnitude and orientation (relative to the center point) + pcl::Vector3fMapConst point = cloud.points[indices[idx]].getVector3fMap (); + Eigen::Map gradient_vector (& (gradient.points[indices[idx]].gradient[0])); + + float gradient_magnitude = gradient_vector.norm (); + float gradient_angle_from_center = acosf (gradient_vector.dot ((point - p0).normalized ()) / gradient_magnitude); + if (!pcl_isfinite (gradient_angle_from_center)) + gradient_angle_from_center = 0.0; + + // Normalize distance and angle values to: 0.0 <= d,g < nr_distances_bins,nr_gradient_bins + const float eps = std::numeric_limits::epsilon (); + float d = static_cast (nr_distance_bins) * sqrtf (sqr_distances[idx]) / (radius + eps); + float g = static_cast (nr_gradient_bins) * gradient_angle_from_center / (static_cast (M_PI) + eps); + + // Compute the bin indices that need to be updated + int d_idx_min = (std::max)(static_cast (ceil (d - 1)), 0); + int d_idx_max = (std::min)(static_cast (floor (d + 1)), nr_distance_bins - 1); + int g_idx_min = static_cast (ceil (g - 1)); + int g_idx_max = static_cast (floor (g + 1)); + + // Update the appropriate bins of the histogram + for (int g_idx = g_idx_min; g_idx <= g_idx_max; ++g_idx) + { + // Because gradient orientation is cyclical, out-of-bounds values must wrap around + int g_idx_wrapped = ((g_idx + nr_gradient_bins) % nr_gradient_bins); + + for (int d_idx = d_idx_min; d_idx <= d_idx_max; ++d_idx) + { + // To avoid boundary effects, use linear interpolation when updating each bin + float w = (1.0f - fabsf (d - static_cast (d_idx))) * (1.0f - fabsf (g - static_cast (g_idx))); + + rift_descriptor (d_idx, g_idx_wrapped) += w * gradient_magnitude; + } + } + } + + // Normalize the RIFT descriptor to unit magnitude + rift_descriptor.normalize (); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RIFTEstimation::computeFeature (PointCloudOut &output) +{ + // Make sure a search radius is set + if (search_radius_ == 0.0) + { + PCL_ERROR ("[pcl::%s::computeFeature] The search radius must be set before computing the feature!\n", + getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + // Make sure the RIFT descriptor has valid dimensions + if (nr_gradient_bins_ <= 0) + { + PCL_ERROR ("[pcl::%s::computeFeature] The number of gradient bins must be greater than zero!\n", + getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + if (nr_distance_bins_ <= 0) + { + PCL_ERROR ("[pcl::%s::computeFeature] The number of distance bins must be greater than zero!\n", + getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + // Check for valid input gradient + if (!gradient_) + { + PCL_ERROR ("[pcl::%s::computeFeature] No input gradient was given!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + if (gradient_->points.size () != surface_->points.size ()) + { + PCL_ERROR ("[pcl::%s::computeFeature] ", getClassName ().c_str ()); + PCL_ERROR ("The number of points in the input dataset differs from the number of points in the gradient!\n"); + output.width = output.height = 0; + output.points.clear (); + return; + } + + Eigen::MatrixXf rift_descriptor (nr_distance_bins_, nr_gradient_bins_); + std::vector nn_indices; + std::vector nn_dist_sqr; + + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + // Find neighbors within the search radius + tree_->radiusSearch ((*indices_)[idx], search_radius_, nn_indices, nn_dist_sqr); + + // Compute the RIFT descriptor + computeRIFT (*surface_, *gradient_, (*indices_)[idx], static_cast (search_radius_), nn_indices, nn_dist_sqr, rift_descriptor); + + // Copy into the resultant cloud + int bin = 0; + for (int g_bin = 0; g_bin < rift_descriptor.cols (); ++g_bin) + for (int d_bin = 0; d_bin < rift_descriptor.rows (); ++d_bin) + output.points[idx].histogram[bin++] = rift_descriptor (d_bin, g_bin); + } +} + +#define PCL_INSTANTIATE_RIFTEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::RIFTEstimation; + +#endif // PCL_FEATURES_IMPL_RIFT_H_ + diff --git a/pcl-1.7/pcl/features/impl/rops_estimation.hpp b/pcl-1.7/pcl/features/impl/rops_estimation.hpp new file mode 100644 index 0000000..5befcdb --- /dev/null +++ b/pcl-1.7/pcl/features/impl/rops_estimation.hpp @@ -0,0 +1,537 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : Sergey Ushakov + * Email : sergey.s.ushakov@mail.ru + * + */ + +#ifndef PCL_ROPS_ESTIMATION_HPP_ +#define PCL_ROPS_ESTIMATION_HPP_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::ROPSEstimation ::ROPSEstimation () : + number_of_bins_ (5), + number_of_rotations_ (3), + support_radius_ (1.0f), + sqr_support_radius_ (1.0f), + step_ (30.0f), + triangles_ (0), + triangles_of_the_point_ (0) +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::ROPSEstimation ::~ROPSEstimation () +{ + triangles_.clear (); + triangles_of_the_point_.clear (); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ROPSEstimation ::setNumberOfPartitionBins (unsigned int number_of_bins) +{ + if (number_of_bins != 0) + number_of_bins_ = number_of_bins; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template unsigned int +pcl::ROPSEstimation ::getNumberOfPartitionBins () const +{ + return (number_of_bins_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ROPSEstimation ::setNumberOfRotations (unsigned int number_of_rotations) +{ + if (number_of_rotations != 0) + { + number_of_rotations_ = number_of_rotations; + step_ = 90.0f / static_cast (number_of_rotations_ + 1); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template unsigned int +pcl::ROPSEstimation ::getNumberOfRotations () const +{ + return (number_of_rotations_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ROPSEstimation ::setSupportRadius (float support_radius) +{ + if (support_radius > 0.0f) + { + support_radius_ = support_radius; + sqr_support_radius_ = support_radius * support_radius; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::ROPSEstimation ::getSupportRadius () const +{ + return (support_radius_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ROPSEstimation ::setTriangles (const std::vector & triangles) +{ + triangles_ = triangles; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ROPSEstimation ::getTriangles (std::vector & triangles) const +{ + triangles = triangles_; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ROPSEstimation ::computeFeature (PointCloudOut &output) +{ + if (triangles_.size () == 0) + { + output.points.clear (); + return; + } + + buildListOfPointsTriangles (); + + //feature size = number_of_rotations * number_of_axis_to_rotate_around * number_of_projections * number_of_central_moments + unsigned int feature_size = number_of_rotations_ * 3 * 3 * 5; + unsigned int number_of_points = static_cast (indices_->size ()); + output.points.resize (number_of_points, PointOutT ()); + + for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + { + std::set local_triangles; + std::vector local_points; + getLocalSurface (input_->points[(*indices_)[i_point]], local_triangles, local_points); + + Eigen::Matrix3f lrf_matrix; + computeLRF (input_->points[(*indices_)[i_point]], local_triangles, lrf_matrix); + + PointCloudIn transformed_cloud; + transformCloud (input_->points[(*indices_)[i_point]], lrf_matrix, local_points, transformed_cloud); + + PointInT axis[3]; + axis[0].x = 1.0f; axis[0].y = 0.0f; axis[0].z = 0.0f; + axis[1].x = 0.0f; axis[1].y = 1.0f; axis[1].z = 0.0f; + axis[2].x = 0.0f; axis[2].y = 0.0f; axis[2].z = 1.0f; + std::vector feature; + for (unsigned int i_axis = 0; i_axis < 3; i_axis++) + { + float theta = step_; + do + { + //rotate local surface and get bounding box + PointCloudIn rotated_cloud; + Eigen::Vector3f min, max; + rotateCloud (axis[i_axis], theta, transformed_cloud, rotated_cloud, min, max); + + //for each projection (XY, XZ and YZ) compute distribution matrix and central moments + for (unsigned int i_proj = 0; i_proj < 3; i_proj++) + { + Eigen::MatrixXf distribution_matrix; + distribution_matrix.resize (number_of_bins_, number_of_bins_); + getDistributionMatrix (i_proj, min, max, rotated_cloud, distribution_matrix); + + std::vector moments; + computeCentralMoments (distribution_matrix, moments); + + feature.insert (feature.end (), moments.begin (), moments.end ()); + } + + theta += step_; + } while (theta < 90.0f); + } + + float norm = 0.0f; + for (unsigned int i_dim = 0; i_dim < feature_size; i_dim++) + norm += feature[i_dim]; + if (abs (norm) < std::numeric_limits ::epsilon ()) + norm = 1.0f / norm; + else + norm = 1.0f; + + for (unsigned int i_dim = 0; i_dim < feature_size; i_dim++) + output.points[i_point].histogram[i_dim] = feature[i_dim] * norm; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ROPSEstimation ::buildListOfPointsTriangles () +{ + triangles_of_the_point_.clear (); + + const unsigned int number_of_triangles = static_cast (triangles_.size ()); + + std::vector dummy; + dummy.reserve (100); + triangles_of_the_point_.resize (surface_->points. size (), dummy); + + for (unsigned int i_triangle = 0; i_triangle < number_of_triangles; i_triangle++) + for (unsigned int i_vertex = 0; i_vertex < 3; i_vertex++) + triangles_of_the_point_[triangles_[i_triangle].vertices[i_vertex]].push_back (i_triangle); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ROPSEstimation ::getLocalSurface (const PointInT& point, std::set & local_triangles, std::vector & local_points) const +{ + std::vector distances; + tree_->radiusSearch (point, support_radius_, local_points, distances); + + const unsigned int number_of_indices = static_cast (local_points.size ()); + for (unsigned int i = 0; i < number_of_indices; i++) + local_triangles.insert (triangles_of_the_point_[local_points[i]].begin (), triangles_of_the_point_[local_points[i]].end ()); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ROPSEstimation ::computeLRF (const PointInT& point, const std::set & local_triangles, Eigen::Matrix3f& lrf_matrix) const +{ + const unsigned int number_of_triangles = static_cast (local_triangles.size ()); + + std::vector scatter_matrices (number_of_triangles); + std::vector triangle_area (number_of_triangles); + std::vector distance_weight (number_of_triangles); + + float total_area = 0.0f; + const float coeff = 1.0f / 12.0f; + const float coeff_1_div_3 = 1.0f / 3.0f; + + Eigen::Vector3f feature_point (point.x, point.y, point.z); + + std::set ::const_iterator it; + unsigned int i_triangle = 0; + for (it = local_triangles.begin (), i_triangle = 0; it != local_triangles.end (); it++, i_triangle++) + { + Eigen::Vector3f pt[3]; + for (unsigned int i_vertex = 0; i_vertex < 3; i_vertex++) + { + const unsigned int index = triangles_[*it].vertices[i_vertex]; + pt[i_vertex] (0) = surface_->points[index].x; + pt[i_vertex] (1) = surface_->points[index].y; + pt[i_vertex] (2) = surface_->points[index].z; + } + + const float curr_area = ((pt[1] - pt[0]).cross (pt[2] - pt[0])).norm (); + triangle_area[i_triangle] = curr_area; + total_area += curr_area; + + distance_weight[i_triangle] = pow (support_radius_ - (feature_point - (pt[0] + pt[1] + pt[2]) * coeff_1_div_3).norm (), 2.0f); + + Eigen::Matrix3f curr_scatter_matrix; + curr_scatter_matrix.setZero (); + for (unsigned int i_pt = 0; i_pt < 3; i_pt++) + { + Eigen::Vector3f vec = pt[i_pt] - feature_point; + curr_scatter_matrix += vec * (vec.transpose ()); + for (unsigned int j_pt = 0; j_pt < 3; j_pt++) + curr_scatter_matrix += vec * ((pt[j_pt] - feature_point).transpose ()); + } + scatter_matrices[i_triangle] = coeff * curr_scatter_matrix; + } + + if (abs (total_area) < std::numeric_limits ::epsilon ()) + total_area = 1.0f / total_area; + else + total_area = 1.0f; + + Eigen::Matrix3f overall_scatter_matrix; + overall_scatter_matrix.setZero (); + std::vector total_weight (number_of_triangles); + const float denominator = 1.0f / 6.0f; + for (unsigned int i_triangle = 0; i_triangle < number_of_triangles; i_triangle++) + { + float factor = distance_weight[i_triangle] * triangle_area[i_triangle] * total_area; + overall_scatter_matrix += factor * scatter_matrices[i_triangle]; + total_weight[i_triangle] = factor * denominator; + } + + Eigen::Vector3f v1, v2, v3; + computeEigenVectors (overall_scatter_matrix, v1, v2, v3); + + float h1 = 0.0f; + float h3 = 0.0f; + for (it = local_triangles.begin (), i_triangle = 0; it != local_triangles.end (); it++, i_triangle++) + { + Eigen::Vector3f pt[3]; + for (unsigned int i_vertex = 0; i_vertex < 3; i_vertex++) + { + const unsigned int index = triangles_[*it].vertices[i_vertex]; + pt[i_vertex] (0) = surface_->points[index].x; + pt[i_vertex] (1) = surface_->points[index].y; + pt[i_vertex] (2) = surface_->points[index].z; + } + + float factor1 = 0.0f; + float factor3 = 0.0f; + for (unsigned int i_pt = 0; i_pt < 3; i_pt++) + { + Eigen::Vector3f vec = pt[i_pt] - feature_point; + factor1 += vec.dot (v1); + factor3 += vec.dot (v3); + } + h1 += total_weight[i_triangle] * factor1; + h3 += total_weight[i_triangle] * factor3; + } + + if (h1 < 0.0f) v1 = -v1; + if (h3 < 0.0f) v3 = -v3; + + v2 = v3.cross (v1); + + lrf_matrix.row (0) = v1; + lrf_matrix.row (1) = v2; + lrf_matrix.row (2) = v3; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ROPSEstimation ::computeEigenVectors (const Eigen::Matrix3f& matrix, + Eigen::Vector3f& major_axis, Eigen::Vector3f& middle_axis, Eigen::Vector3f& minor_axis) const +{ + Eigen::EigenSolver eigen_solver; + eigen_solver.compute (matrix); + + Eigen::EigenSolver ::EigenvectorsType eigen_vectors; + Eigen::EigenSolver ::EigenvalueType eigen_values; + eigen_vectors = eigen_solver.eigenvectors (); + eigen_values = eigen_solver.eigenvalues (); + + unsigned int temp = 0; + unsigned int major_index = 0; + unsigned int middle_index = 1; + unsigned int minor_index = 2; + + if (eigen_values.real () (major_index) < eigen_values.real () (middle_index)) + { + temp = major_index; + major_index = middle_index; + middle_index = temp; + } + + if (eigen_values.real () (major_index) < eigen_values.real () (minor_index)) + { + temp = major_index; + major_index = minor_index; + minor_index = temp; + } + + if (eigen_values.real () (middle_index) < eigen_values.real () (minor_index)) + { + temp = minor_index; + minor_index = middle_index; + middle_index = temp; + } + + major_axis = eigen_vectors.col (major_index).real (); + middle_axis = eigen_vectors.col (middle_index).real (); + minor_axis = eigen_vectors.col (minor_index).real (); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ROPSEstimation ::transformCloud (const PointInT& point, const Eigen::Matrix3f& matrix, const std::vector & local_points, PointCloudIn& transformed_cloud) const +{ + const unsigned int number_of_points = static_cast (local_points.size ()); + transformed_cloud.points.resize (number_of_points, PointInT ()); + + for (unsigned int i = 0; i < number_of_points; i++) + { + Eigen::Vector3f transformed_point ( + surface_->points[local_points[i]].x - point.x, + surface_->points[local_points[i]].y - point.y, + surface_->points[local_points[i]].z - point.z); + + transformed_point = matrix * transformed_point; + + PointInT new_point; + new_point.x = transformed_point (0); + new_point.y = transformed_point (1); + new_point.z = transformed_point (2); + transformed_cloud.points[i] = new_point; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ROPSEstimation ::rotateCloud (const PointInT& axis, const float angle, const PointCloudIn& cloud, PointCloudIn& rotated_cloud, Eigen::Vector3f& min, Eigen::Vector3f& max) const +{ + Eigen::Matrix3f rotation_matrix; + const float x = axis.x; + const float y = axis.y; + const float z = axis.z; + const float rad = M_PI / 180.0f; + const float cosine = cos (angle * rad); + const float sine = sin (angle * rad); + rotation_matrix << cosine + (1 - cosine) * x * x, (1 - cosine) * x * y - sine * z, (1 - cosine) * x * z + sine * y, + (1 - cosine) * y * x + sine * z, cosine + (1 - cosine) * y * y, (1 - cosine) * y * z - sine * x, + (1 - cosine) * z * x - sine * y, (1 - cosine) * z * y + sine * x, cosine + (1 - cosine) * z * z; + + const unsigned int number_of_points = static_cast (cloud.points.size ()); + + rotated_cloud.header = cloud.header; + rotated_cloud.width = number_of_points; + rotated_cloud.height = 1; + rotated_cloud.points.resize (number_of_points, PointInT ()); + + min (0) = std::numeric_limits ::max (); + min (1) = std::numeric_limits ::max (); + min (2) = std::numeric_limits ::max (); + max (0) = -std::numeric_limits ::max (); + max (1) = -std::numeric_limits ::max (); + max (2) = -std::numeric_limits ::max (); + + for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + { + Eigen::Vector3f point ( + cloud.points[i_point].x, + cloud.points[i_point].y, + cloud.points[i_point].z); + + point = rotation_matrix * point; + PointInT rotated_point; + rotated_point.x = point (0); + rotated_point.y = point (1); + rotated_point.z = point (2); + rotated_cloud.points[i_point] = rotated_point; + + if (min (0) > rotated_point.x) min (0) = rotated_point.x; + if (min (1) > rotated_point.y) min (1) = rotated_point.y; + if (min (2) > rotated_point.z) min (2) = rotated_point.z; + + if (max (0) < rotated_point.x) max (0) = rotated_point.x; + if (max (1) < rotated_point.y) max (1) = rotated_point.y; + if (max (2) < rotated_point.z) max (2) = rotated_point.z; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ROPSEstimation ::getDistributionMatrix (const unsigned int projection, const Eigen::Vector3f& min, const Eigen::Vector3f& max, const PointCloudIn& cloud, Eigen::MatrixXf& matrix) const +{ + matrix.setZero (); + + const unsigned int number_of_points = static_cast (cloud.points.size ()); + + const unsigned int coord[3][2] = { + {0, 1}, + {0, 2}, + {1, 2}}; + + const float u_bin_length = (max (coord[projection][0]) - min (coord[projection][0])) / number_of_bins_; + const float v_bin_length = (max (coord[projection][1]) - min (coord[projection][1])) / number_of_bins_; + + for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + { + Eigen::Vector3f point ( + cloud.points[i_point].x, + cloud.points[i_point].y, + cloud.points[i_point].z); + + const float u_length = point (coord[projection][0]) - min[coord[projection][0]]; + const float v_length = point (coord[projection][1]) - min[coord[projection][1]]; + + const float u_ratio = u_length / u_bin_length; + unsigned int row = static_cast (u_ratio); + if (row == number_of_bins_) row--; + + const float v_ratio = v_length / v_bin_length; + unsigned int col = static_cast (v_ratio); + if (col == number_of_bins_) col--; + + matrix (row, col) += 1.0f; + } + + matrix /= static_cast (number_of_points); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ROPSEstimation ::computeCentralMoments (const Eigen::MatrixXf& matrix, std::vector & moments) const +{ + float mean_i = 0.0f; + float mean_j = 0.0f; + + for (unsigned int i = 0; i < number_of_bins_; i++) + for (unsigned int j = 0; j < number_of_bins_; j++) + { + const float m = matrix (i, j); + mean_i += static_cast (i + 1) * m; + mean_j += static_cast (j + 1) * m; + } + + const unsigned int number_of_moments_to_compute = 4; + const float power[number_of_moments_to_compute][2] = { + {1.0f, 1.0f}, + {2.0f, 1.0f}, + {1.0f, 2.0f}, + {2.0f, 2.0f}}; + + float entropy = 0.0f; + moments.resize (number_of_moments_to_compute + 1, 0.0f); + for (unsigned int i = 0; i < number_of_bins_; i++) + { + const float i_factor = static_cast (i + 1) - mean_i; + for (unsigned int j = 0; j < number_of_bins_; j++) + { + const float j_factor = static_cast (j + 1) - mean_j; + const float m = matrix (i, j); + if (m > 0.0f) + entropy -= m * log (m); + for (unsigned int i_moment = 0; i_moment < number_of_moments_to_compute; i_moment++) + moments[i_moment] += pow (i_factor, power[i_moment][0]) * pow (j_factor, power[i_moment][1]) * m; + } + } + + moments[number_of_moments_to_compute] = entropy; +} + +#endif // PCL_ROPS_ESTIMATION_HPP_ diff --git a/pcl-1.7/pcl/features/impl/shot.hpp b/pcl-1.7/pcl/features/impl/shot.hpp new file mode 100644 index 0000000..ca46285 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/shot.hpp @@ -0,0 +1,910 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_FEATURES_IMPL_SHOT_H_ +#define PCL_FEATURES_IMPL_SHOT_H_ + +#include +#include +#include + +// Useful constants. +#define PST_PI 3.1415926535897932384626433832795 +#define PST_RAD_45 0.78539816339744830961566084581988 +#define PST_RAD_90 1.5707963267948966192313216916398 +#define PST_RAD_135 2.3561944901923449288469825374596 +#define PST_RAD_180 PST_PI +#define PST_RAD_360 6.283185307179586476925286766558 +#define PST_RAD_PI_7_8 2.7488935718910690836548129603691 + +const double zeroDoubleEps15 = 1E-15; +const float zeroFloatEps8 = 1E-8f; + +////////////////////////////////////////////////////////////////////////////////////////////// +/** \brief Check if val1 and val2 are equals. + * + * \param[in] val1 first number to check. + * \param[in] val2 second number to check. + * \param[in] zeroDoubleEps epsilon + * \return true if val1 is equal to val2, false otherwise. + */ +inline bool +areEquals (double val1, double val2, double zeroDoubleEps = zeroDoubleEps15) +{ + return (fabs (val1 - val2) float +pcl::SHOTColorEstimation::sRGB_LUT[256] = {- 1}; + +////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::SHOTColorEstimation::sXYZ_LUT[4000] = {- 1}; + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTColorEstimation::RGB2CIELAB (unsigned char R, unsigned char G, + unsigned char B, float &L, float &A, + float &B2) +{ + if (sRGB_LUT[0] < 0) + { + for (int i = 0; i < 256; i++) + { + float f = static_cast (i) / 255.0f; + if (f > 0.04045) + sRGB_LUT[i] = powf ((f + 0.055f) / 1.055f, 2.4f); + else + sRGB_LUT[i] = f / 12.92f; + } + + for (int i = 0; i < 4000; i++) + { + float f = static_cast (i) / 4000.0f; + if (f > 0.008856) + sXYZ_LUT[i] = static_cast (powf (f, 0.3333f)); + else + sXYZ_LUT[i] = static_cast((7.787 * f) + (16.0 / 116.0)); + } + } + + float fr = sRGB_LUT[R]; + float fg = sRGB_LUT[G]; + float fb = sRGB_LUT[B]; + + // Use white = D65 + const float x = fr * 0.412453f + fg * 0.357580f + fb * 0.180423f; + const float y = fr * 0.212671f + fg * 0.715160f + fb * 0.072169f; + const float z = fr * 0.019334f + fg * 0.119193f + fb * 0.950227f; + + float vx = x / 0.95047f; + float vy = y; + float vz = z / 1.08883f; + + vx = sXYZ_LUT[int(vx*4000)]; + vy = sXYZ_LUT[int(vy*4000)]; + vz = sXYZ_LUT[int(vz*4000)]; + + L = 116.0f * vy - 16.0f; + if (L > 100) + L = 100.0f; + + A = 500.0f * (vx - vy); + if (A > 120) + A = 120.0f; + else if (A <- 120) + A = -120.0f; + + B2 = 200.0f * (vy - vz); + if (B2 > 120) + B2 = 120.0f; + else if (B2<- 120) + B2 = -120.0f; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SHOTEstimationBase::initCompute () +{ + if (!FeatureFromNormals::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + // SHOT cannot work with k-search + if (this->getKSearch () != 0) + { + PCL_ERROR( + "[pcl::%s::initCompute] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n", + getClassName().c_str ()); + return (false); + } + + // Default LRF estimation alg: SHOTLocalReferenceFrameEstimation + typename SHOTLocalReferenceFrameEstimation::Ptr lrf_estimator(new SHOTLocalReferenceFrameEstimation()); + lrf_estimator->setRadiusSearch ((lrf_radius_ > 0 ? lrf_radius_ : search_radius_)); + lrf_estimator->setInputCloud (input_); + lrf_estimator->setIndices (indices_); + if (!fake_surface_) + lrf_estimator->setSearchSurface(surface_); + + if (!FeatureWithLocalReferenceFrames::initLocalReferenceFrames (indices_->size (), lrf_estimator)) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTEstimationBase::createBinDistanceShape ( + int index, + const std::vector &indices, + std::vector &bin_distance_shape) +{ + bin_distance_shape.resize (indices.size ()); + + const PointRFT& current_frame = frames_->points[index]; + //if (!pcl_isfinite (current_frame.rf[0]) || !pcl_isfinite (current_frame.rf[4]) || !pcl_isfinite (current_frame.rf[11])) + //return; + + Eigen::Vector4f current_frame_z (current_frame.z_axis[0], current_frame.z_axis[1], current_frame.z_axis[2], 0); + + unsigned nan_counter = 0; + for (size_t i_idx = 0; i_idx < indices.size (); ++i_idx) + { + // check NaN normal + const Eigen::Vector4f& normal_vec = normals_->points[indices[i_idx]].getNormalVector4fMap (); + if (!pcl_isfinite (normal_vec[0]) || + !pcl_isfinite (normal_vec[1]) || + !pcl_isfinite (normal_vec[2])) + { + bin_distance_shape[i_idx] = std::numeric_limits::quiet_NaN (); + ++nan_counter; + } else + { + //double cosineDesc = feat[i].rf[6]*normal[0] + feat[i].rf[7]*normal[1] + feat[i].rf[8]*normal[2]; + double cosineDesc = normal_vec.dot (current_frame_z); + + if (cosineDesc > 1.0) + cosineDesc = 1.0; + if (cosineDesc < - 1.0) + cosineDesc = - 1.0; + + bin_distance_shape[i_idx] = ((1.0 + cosineDesc) * nr_shape_bins_) / 2; + } + } + if (nan_counter > 0) + PCL_WARN ("[pcl::%s::createBinDistanceShape] Point %d has %d (%f%%) NaN normals in its neighbourhood\n", + getClassName ().c_str (), index, nan_counter, (static_cast(nan_counter)*100.f/static_cast(indices.size ()))); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTEstimationBase::normalizeHistogram ( + Eigen::VectorXf &shot, int desc_length) +{ + // Normalization is performed by considering the L2 norm + // and not the sum of bins, as reported in the ECCV paper. + // This is due to additional experiments performed by the authors after its pubblication, + // where L2 normalization turned out better at handling point density variations. + double acc_norm = 0; + for (int j = 0; j < desc_length; j++) + acc_norm += shot[j] * shot[j]; + acc_norm = sqrt (acc_norm); + for (int j = 0; j < desc_length; j++) + shot[j] /= static_cast (acc_norm); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTEstimationBase::interpolateSingleChannel ( + const std::vector &indices, + const std::vector &sqr_dists, + const int index, + std::vector &binDistance, + const int nr_bins, + Eigen::VectorXf &shot) +{ + const Eigen::Vector4f& central_point = (*input_)[(*indices_)[index]].getVector4fMap (); + const PointRFT& current_frame = (*frames_)[index]; + + Eigen::Vector4f current_frame_x (current_frame.x_axis[0], current_frame.x_axis[1], current_frame.x_axis[2], 0); + Eigen::Vector4f current_frame_y (current_frame.y_axis[0], current_frame.y_axis[1], current_frame.y_axis[2], 0); + Eigen::Vector4f current_frame_z (current_frame.z_axis[0], current_frame.z_axis[1], current_frame.z_axis[2], 0); + + for (size_t i_idx = 0; i_idx < indices.size (); ++i_idx) + { + if (!pcl_isfinite(binDistance[i_idx])) + continue; + + Eigen::Vector4f delta = surface_->points[indices[i_idx]].getVector4fMap () - central_point; + delta[3] = 0; + + // Compute the Euclidean norm + double distance = sqrt (sqr_dists[i_idx]); + + if (areEquals (distance, 0.0)) + continue; + + double xInFeatRef = delta.dot (current_frame_x); + double yInFeatRef = delta.dot (current_frame_y); + double zInFeatRef = delta.dot (current_frame_z); + + // To avoid numerical problems afterwards + if (fabs (yInFeatRef) < 1E-30) + yInFeatRef = 0; + if (fabs (xInFeatRef) < 1E-30) + xInFeatRef = 0; + if (fabs (zInFeatRef) < 1E-30) + zInFeatRef = 0; + + + unsigned char bit4 = ((yInFeatRef > 0) || ((yInFeatRef == 0.0) && (xInFeatRef < 0))) ? 1 : 0; + unsigned char bit3 = static_cast (((xInFeatRef > 0) || ((xInFeatRef == 0.0) && (yInFeatRef > 0))) ? !bit4 : bit4); + + assert (bit3 == 0 || bit3 == 1); + + int desc_index = (bit4<<3) + (bit3<<2); + + desc_index = desc_index << 1; + + if ((xInFeatRef * yInFeatRef > 0) || (xInFeatRef == 0.0)) + desc_index += (fabs (xInFeatRef) >= fabs (yInFeatRef)) ? 0 : 4; + else + desc_index += (fabs (xInFeatRef) > fabs (yInFeatRef)) ? 4 : 0; + + desc_index += zInFeatRef > 0 ? 1 : 0; + + // 2 RADII + desc_index += (distance > radius1_2_) ? 2 : 0; + + int step_index = static_cast(floor (binDistance[i_idx] +0.5)); + int volume_index = desc_index * (nr_bins+1); + + //Interpolation on the cosine (adjacent bins in the histogram) + binDistance[i_idx] -= step_index; + double intWeight = (1- fabs (binDistance[i_idx])); + + if (binDistance[i_idx] > 0) + shot[volume_index + ((step_index+1) % nr_bins)] += static_cast (binDistance[i_idx]); + else + shot[volume_index + ((step_index - 1 + nr_bins) % nr_bins)] += - static_cast (binDistance[i_idx]); + + //Interpolation on the distance (adjacent husks) + + if (distance > radius1_2_) //external sphere + { + double radiusDistance = (distance - radius3_4_) / radius1_2_; + + if (distance > radius3_4_) //most external sector, votes only for itself + intWeight += 1 - radiusDistance; //peso=1-d + else //3/4 of radius, votes also for the internal sphere + { + intWeight += 1 + radiusDistance; + shot[(desc_index - 2) * (nr_bins+1) + step_index] -= static_cast (radiusDistance); + } + } + else //internal sphere + { + double radiusDistance = (distance - radius1_4_) / radius1_2_; + + if (distance < radius1_4_) //most internal sector, votes only for itself + intWeight += 1 + radiusDistance; //weight=1-d + else //3/4 of radius, votes also for the external sphere + { + intWeight += 1 - radiusDistance; + shot[(desc_index + 2) * (nr_bins+1) + step_index] += static_cast (radiusDistance); + } + } + + //Interpolation on the inclination (adjacent vertical volumes) + double inclinationCos = zInFeatRef / distance; + if (inclinationCos < - 1.0) + inclinationCos = - 1.0; + if (inclinationCos > 1.0) + inclinationCos = 1.0; + + double inclination = acos (inclinationCos); + + assert (inclination >= 0.0 && inclination <= PST_RAD_180); + + if (inclination > PST_RAD_90 || (fabs (inclination - PST_RAD_90) < 1e-30 && zInFeatRef <= 0)) + { + double inclinationDistance = (inclination - PST_RAD_135) / PST_RAD_90; + if (inclination > PST_RAD_135) + intWeight += 1 - inclinationDistance; + else + { + intWeight += 1 + inclinationDistance; + assert ((desc_index + 1) * (nr_bins+1) + step_index >= 0 && (desc_index + 1) * (nr_bins+1) + step_index < descLength_); + shot[(desc_index + 1) * (nr_bins+1) + step_index] -= static_cast (inclinationDistance); + } + } + else + { + double inclinationDistance = (inclination - PST_RAD_45) / PST_RAD_90; + if (inclination < PST_RAD_45) + intWeight += 1 + inclinationDistance; + else + { + intWeight += 1 - inclinationDistance; + assert ((desc_index - 1) * (nr_bins+1) + step_index >= 0 && (desc_index - 1) * (nr_bins+1) + step_index < descLength_); + shot[(desc_index - 1) * (nr_bins+1) + step_index] += static_cast (inclinationDistance); + } + } + + if (yInFeatRef != 0.0 || xInFeatRef != 0.0) + { + //Interpolation on the azimuth (adjacent horizontal volumes) + double azimuth = atan2 (yInFeatRef, xInFeatRef); + + int sel = desc_index >> 2; + double angularSectorSpan = PST_RAD_45; + double angularSectorStart = - PST_RAD_PI_7_8; + + double azimuthDistance = (azimuth - (angularSectorStart + angularSectorSpan*sel)) / angularSectorSpan; + + assert ((azimuthDistance < 0.5 || areEquals (azimuthDistance, 0.5)) && (azimuthDistance > - 0.5 || areEquals (azimuthDistance, - 0.5))); + + azimuthDistance = (std::max)(- 0.5, std::min (azimuthDistance, 0.5)); + + if (azimuthDistance > 0) + { + intWeight += 1 - azimuthDistance; + int interp_index = (desc_index + 4) % maxAngularSectors_; + assert (interp_index * (nr_bins+1) + step_index >= 0 && interp_index * (nr_bins+1) + step_index < descLength_); + shot[interp_index * (nr_bins+1) + step_index] += static_cast (azimuthDistance); + } + else + { + int interp_index = (desc_index - 4 + maxAngularSectors_) % maxAngularSectors_; + assert (interp_index * (nr_bins+1) + step_index >= 0 && interp_index * (nr_bins+1) + step_index < descLength_); + intWeight += 1 + azimuthDistance; + shot[interp_index * (nr_bins+1) + step_index] -= static_cast (azimuthDistance); + } + + } + + assert (volume_index + step_index >= 0 && volume_index + step_index < descLength_); + shot[volume_index + step_index] += static_cast (intWeight); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTColorEstimation::interpolateDoubleChannel ( + const std::vector &indices, + const std::vector &sqr_dists, + const int index, + std::vector &binDistanceShape, + std::vector &binDistanceColor, + const int nr_bins_shape, + const int nr_bins_color, + Eigen::VectorXf &shot) +{ + const Eigen::Vector4f ¢ral_point = (*input_)[(*indices_)[index]].getVector4fMap (); + const PointRFT& current_frame = (*frames_)[index]; + + int shapeToColorStride = nr_grid_sector_*(nr_bins_shape+1); + + Eigen::Vector4f current_frame_x (current_frame.x_axis[0], current_frame.x_axis[1], current_frame.x_axis[2], 0); + Eigen::Vector4f current_frame_y (current_frame.y_axis[0], current_frame.y_axis[1], current_frame.y_axis[2], 0); + Eigen::Vector4f current_frame_z (current_frame.z_axis[0], current_frame.z_axis[1], current_frame.z_axis[2], 0); + + for (size_t i_idx = 0; i_idx < indices.size (); ++i_idx) + { + if (!pcl_isfinite(binDistanceShape[i_idx])) + continue; + + Eigen::Vector4f delta = surface_->points[indices[i_idx]].getVector4fMap () - central_point; + delta[3] = 0; + + // Compute the Euclidean norm + double distance = sqrt (sqr_dists[i_idx]); + + if (areEquals (distance, 0.0)) + continue; + + double xInFeatRef = delta.dot (current_frame_x); + double yInFeatRef = delta.dot (current_frame_y); + double zInFeatRef = delta.dot (current_frame_z); + + // To avoid numerical problems afterwards + if (fabs (yInFeatRef) < 1E-30) + yInFeatRef = 0; + if (fabs (xInFeatRef) < 1E-30) + xInFeatRef = 0; + if (fabs (zInFeatRef) < 1E-30) + zInFeatRef = 0; + + unsigned char bit4 = ((yInFeatRef > 0) || ((yInFeatRef == 0.0) && (xInFeatRef < 0))) ? 1 : 0; + unsigned char bit3 = static_cast (((xInFeatRef > 0) || ((xInFeatRef == 0.0) && (yInFeatRef > 0))) ? !bit4 : bit4); + + assert (bit3 == 0 || bit3 == 1); + + int desc_index = (bit4<<3) + (bit3<<2); + + desc_index = desc_index << 1; + + if ((xInFeatRef * yInFeatRef > 0) || (xInFeatRef == 0.0)) + desc_index += (fabs (xInFeatRef) >= fabs (yInFeatRef)) ? 0 : 4; + else + desc_index += (fabs (xInFeatRef) > fabs (yInFeatRef)) ? 4 : 0; + + desc_index += zInFeatRef > 0 ? 1 : 0; + + // 2 RADII + desc_index += (distance > radius1_2_) ? 2 : 0; + + int step_index_shape = static_cast(floor (binDistanceShape[i_idx] +0.5)); + int step_index_color = static_cast(floor (binDistanceColor[i_idx] +0.5)); + + int volume_index_shape = desc_index * (nr_bins_shape+1); + int volume_index_color = shapeToColorStride + desc_index * (nr_bins_color+1); + + //Interpolation on the cosine (adjacent bins in the histrogram) + binDistanceShape[i_idx] -= step_index_shape; + binDistanceColor[i_idx] -= step_index_color; + + double intWeightShape = (1- fabs (binDistanceShape[i_idx])); + double intWeightColor = (1- fabs (binDistanceColor[i_idx])); + + if (binDistanceShape[i_idx] > 0) + shot[volume_index_shape + ((step_index_shape + 1) % nr_bins_shape)] += static_cast (binDistanceShape[i_idx]); + else + shot[volume_index_shape + ((step_index_shape - 1 + nr_bins_shape) % nr_bins_shape)] -= static_cast (binDistanceShape[i_idx]); + + if (binDistanceColor[i_idx] > 0) + shot[volume_index_color + ((step_index_color+1) % nr_bins_color)] += static_cast (binDistanceColor[i_idx]); + else + shot[volume_index_color + ((step_index_color - 1 + nr_bins_color) % nr_bins_color)] -= static_cast (binDistanceColor[i_idx]); + + //Interpolation on the distance (adjacent husks) + + if (distance > radius1_2_) //external sphere + { + double radiusDistance = (distance - radius3_4_) / radius1_2_; + + if (distance > radius3_4_) //most external sector, votes only for itself + { + intWeightShape += 1 - radiusDistance; //weight=1-d + intWeightColor += 1 - radiusDistance; //weight=1-d + } + else //3/4 of radius, votes also for the internal sphere + { + intWeightShape += 1 + radiusDistance; + intWeightColor += 1 + radiusDistance; + shot[(desc_index - 2) * (nr_bins_shape+1) + step_index_shape] -= static_cast (radiusDistance); + shot[shapeToColorStride + (desc_index - 2) * (nr_bins_color+1) + step_index_color] -= static_cast (radiusDistance); + } + } + else //internal sphere + { + double radiusDistance = (distance - radius1_4_) / radius1_2_; + + if (distance < radius1_4_) //most internal sector, votes only for itself + { + intWeightShape += 1 + radiusDistance; + intWeightColor += 1 + radiusDistance; //weight=1-d + } + else //3/4 of radius, votes also for the external sphere + { + intWeightShape += 1 - radiusDistance; //weight=1-d + intWeightColor += 1 - radiusDistance; //weight=1-d + shot[(desc_index + 2) * (nr_bins_shape+1) + step_index_shape] += static_cast (radiusDistance); + shot[shapeToColorStride + (desc_index + 2) * (nr_bins_color+1) + step_index_color] += static_cast (radiusDistance); + } + } + + //Interpolation on the inclination (adjacent vertical volumes) + double inclinationCos = zInFeatRef / distance; + if (inclinationCos < - 1.0) + inclinationCos = - 1.0; + if (inclinationCos > 1.0) + inclinationCos = 1.0; + + double inclination = acos (inclinationCos); + + assert (inclination >= 0.0 && inclination <= PST_RAD_180); + + if (inclination > PST_RAD_90 || (fabs (inclination - PST_RAD_90) < 1e-30 && zInFeatRef <= 0)) + { + double inclinationDistance = (inclination - PST_RAD_135) / PST_RAD_90; + if (inclination > PST_RAD_135) + { + intWeightShape += 1 - inclinationDistance; + intWeightColor += 1 - inclinationDistance; + } + else + { + intWeightShape += 1 + inclinationDistance; + intWeightColor += 1 + inclinationDistance; + assert ((desc_index + 1) * (nr_bins_shape+1) + step_index_shape >= 0 && (desc_index + 1) * (nr_bins_shape+1) + step_index_shape < descLength_); + assert (shapeToColorStride + (desc_index + 1) * (nr_bins_color+ 1) + step_index_color >= 0 && shapeToColorStride + (desc_index + 1) * (nr_bins_color+1) + step_index_color < descLength_); + shot[(desc_index + 1) * (nr_bins_shape+1) + step_index_shape] -= static_cast (inclinationDistance); + shot[shapeToColorStride + (desc_index + 1) * (nr_bins_color+1) + step_index_color] -= static_cast (inclinationDistance); + } + } + else + { + double inclinationDistance = (inclination - PST_RAD_45) / PST_RAD_90; + if (inclination < PST_RAD_45) + { + intWeightShape += 1 + inclinationDistance; + intWeightColor += 1 + inclinationDistance; + } + else + { + intWeightShape += 1 - inclinationDistance; + intWeightColor += 1 - inclinationDistance; + assert ((desc_index - 1) * (nr_bins_shape+1) + step_index_shape >= 0 && (desc_index - 1) * (nr_bins_shape+1) + step_index_shape < descLength_); + assert (shapeToColorStride + (desc_index - 1) * (nr_bins_color+ 1) + step_index_color >= 0 && shapeToColorStride + (desc_index - 1) * (nr_bins_color+1) + step_index_color < descLength_); + shot[(desc_index - 1) * (nr_bins_shape+1) + step_index_shape] += static_cast (inclinationDistance); + shot[shapeToColorStride + (desc_index - 1) * (nr_bins_color+1) + step_index_color] += static_cast (inclinationDistance); + } + } + + if (yInFeatRef != 0.0 || xInFeatRef != 0.0) + { + //Interpolation on the azimuth (adjacent horizontal volumes) + double azimuth = atan2 (yInFeatRef, xInFeatRef); + + int sel = desc_index >> 2; + double angularSectorSpan = PST_RAD_45; + double angularSectorStart = - PST_RAD_PI_7_8; + + double azimuthDistance = (azimuth - (angularSectorStart + angularSectorSpan*sel)) / angularSectorSpan; + assert ((azimuthDistance < 0.5 || areEquals (azimuthDistance, 0.5)) && (azimuthDistance > - 0.5 || areEquals (azimuthDistance, - 0.5))); + azimuthDistance = (std::max)(- 0.5, std::min (azimuthDistance, 0.5)); + + if (azimuthDistance > 0) + { + intWeightShape += 1 - azimuthDistance; + intWeightColor += 1 - azimuthDistance; + int interp_index = (desc_index + 4) % maxAngularSectors_; + assert (interp_index * (nr_bins_shape+1) + step_index_shape >= 0 && interp_index * (nr_bins_shape+1) + step_index_shape < descLength_); + assert (shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color >= 0 && shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color < descLength_); + shot[interp_index * (nr_bins_shape+1) + step_index_shape] += static_cast (azimuthDistance); + shot[shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color] += static_cast (azimuthDistance); + } + else + { + int interp_index = (desc_index - 4 + maxAngularSectors_) % maxAngularSectors_; + intWeightShape += 1 + azimuthDistance; + intWeightColor += 1 + azimuthDistance; + assert (interp_index * (nr_bins_shape+1) + step_index_shape >= 0 && interp_index * (nr_bins_shape+1) + step_index_shape < descLength_); + assert (shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color >= 0 && shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color < descLength_); + shot[interp_index * (nr_bins_shape+1) + step_index_shape] -= static_cast (azimuthDistance); + shot[shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color] -= static_cast (azimuthDistance); + } + } + + assert (volume_index_shape + step_index_shape >= 0 && volume_index_shape + step_index_shape < descLength_); + assert (volume_index_color + step_index_color >= 0 && volume_index_color + step_index_color < descLength_); + shot[volume_index_shape + step_index_shape] += static_cast (intWeightShape); + shot[volume_index_color + step_index_color] += static_cast (intWeightColor); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTColorEstimation::computePointSHOT ( + const int index, const std::vector &indices, const std::vector &sqr_dists, Eigen::VectorXf &shot) +{ + // Clear the resultant shot + shot.setZero (); + std::vector binDistanceShape; + std::vector binDistanceColor; + size_t nNeighbors = indices.size (); + //Skip the current feature if the number of its neighbors is not sufficient for its description + if (nNeighbors < 5) + { + PCL_WARN ("[pcl::%s::computePointSHOT] Warning! Neighborhood has less than 5 vertexes. Aborting description of point with index %d\n", + getClassName ().c_str (), (*indices_)[index]); + + shot.setConstant(descLength_, 1, std::numeric_limits::quiet_NaN () ); + + return; + } + + //If shape description is enabled, compute the bins activated by each neighbor of the current feature in the shape histogram + if (b_describe_shape_) + { + this->createBinDistanceShape (index, indices, binDistanceShape); + } + + //If color description is enabled, compute the bins activated by each neighbor of the current feature in the color histogram + if (b_describe_color_) + { + binDistanceColor.resize (nNeighbors); + + //unsigned char redRef = input_->points[(*indices_)[index]].rgba >> 16 & 0xFF; + //unsigned char greenRef = input_->points[(*indices_)[index]].rgba >> 8& 0xFF; + //unsigned char blueRef = input_->points[(*indices_)[index]].rgba & 0xFF; + unsigned char redRef = input_->points[(*indices_)[index]].r; + unsigned char greenRef = input_->points[(*indices_)[index]].g; + unsigned char blueRef = input_->points[(*indices_)[index]].b; + + float LRef, aRef, bRef; + + RGB2CIELAB (redRef, greenRef, blueRef, LRef, aRef, bRef); + LRef /= 100.0f; + aRef /= 120.0f; + bRef /= 120.0f; //normalized LAB components (0points[indices[i_idx]].rgba >> 16 & 0xFF; + //unsigned char green = surface_->points[indices[i_idx]].rgba >> 8 & 0xFF; + //unsigned char blue = surface_->points[indices[i_idx]].rgba & 0xFF; + unsigned char red = surface_->points[indices[i_idx]].r; + unsigned char green = surface_->points[indices[i_idx]].g; + unsigned char blue = surface_->points[indices[i_idx]].b; + + float L, a, b; + + RGB2CIELAB (red, green, blue, L, a, b); + L /= 100.0f; + a /= 120.0f; + b /= 120.0f; //normalized LAB components (0 1.0) + colorDistance = 1.0; + if (colorDistance < 0.0) + colorDistance = 0.0; + + binDistanceColor[i_idx] = colorDistance * nr_color_bins_; + } + } + + //Apply quadrilinear interpolation on the activated bins in the shape and/or color histogram(s) + + if (b_describe_shape_ && b_describe_color_) + interpolateDoubleChannel (indices, sqr_dists, index, binDistanceShape, binDistanceColor, + nr_shape_bins_, nr_color_bins_, + shot); + else if (b_describe_color_) + interpolateSingleChannel (indices, sqr_dists, index, binDistanceColor, nr_color_bins_, shot); + else + interpolateSingleChannel (indices, sqr_dists, index, binDistanceShape, nr_shape_bins_, shot); + + // Normalize the final histogram + this->normalizeHistogram (shot, descLength_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTEstimation::computePointSHOT ( + const int index, const std::vector &indices, const std::vector &sqr_dists, Eigen::VectorXf &shot) +{ + //Skip the current feature if the number of its neighbors is not sufficient for its description + if (indices.size () < 5) + { + PCL_WARN ("[pcl::%s::computePointSHOT] Warning! Neighborhood has less than 5 vertexes. Aborting description of point with index %d\n", + getClassName ().c_str (), (*indices_)[index]); + + shot.setConstant(descLength_, 1, std::numeric_limits::quiet_NaN () ); + + return; + } + + // Clear the resultant shot + std::vector binDistanceShape; + this->createBinDistanceShape (index, indices, binDistanceShape); + + // Interpolate + shot.setZero (); + interpolateSingleChannel (indices, sqr_dists, index, binDistanceShape, nr_shape_bins_, shot); + + // Normalize the final histogram + this->normalizeHistogram (shot, descLength_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTEstimation::computeFeature (pcl::PointCloud &output) +{ + descLength_ = nr_grid_sector_ * (nr_shape_bins_+1); + + sqradius_ = search_radius_ * search_radius_; + radius3_4_ = (search_radius_*3) / 4; + radius1_4_ = search_radius_ / 4; + radius1_2_ = search_radius_ / 2; + + assert(descLength_ == 352); + + shot_.setZero (descLength_); + + // Allocate enough space to hold the results + // \note This resize is irrelevant for a radiusSearch (). + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + int search_state = 0; + + output.is_dense = true; + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + bool lrf_is_nan = false; + const PointRFT& current_frame = (*frames_)[idx]; + if (!pcl_isfinite (current_frame.x_axis[0]) || + !pcl_isfinite (current_frame.y_axis[0]) || + !pcl_isfinite (current_frame.z_axis[0])) + { + PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n", + getClassName ().c_str (), (*indices_)[idx]); + lrf_is_nan = true; + } + + search_state = this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists); + + if (!isFinite ((*input_)[(*indices_)[idx]]) || + lrf_is_nan || + search_state == 0) + { + // Copy into the resultant cloud + for (int d = 0; d < descLength_; ++d) + output.points[idx].descriptor[d] = std::numeric_limits::quiet_NaN (); + for (int d = 0; d < 9; ++d) + output.points[idx].rf[d] = std::numeric_limits::quiet_NaN (); + + output.is_dense = false; + continue; + } + + // Estimate the SHOT descriptor at each patch + computePointSHOT (static_cast (idx), nn_indices, nn_dists, shot_); + + // Copy into the resultant cloud + for (int d = 0; d < descLength_; ++d) + output.points[idx].descriptor[d] = shot_[d]; + for (int d = 0; d < 3; ++d) + { + output.points[idx].rf[d + 0] = frames_->points[idx].x_axis[d]; + output.points[idx].rf[d + 3] = frames_->points[idx].y_axis[d]; + output.points[idx].rf[d + 6] = frames_->points[idx].z_axis[d]; + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTColorEstimation::computeFeature (pcl::PointCloud &output) +{ + // Compute the current length of the descriptor + descLength_ = (b_describe_shape_) ? nr_grid_sector_*(nr_shape_bins_+1) : 0; + descLength_ += (b_describe_color_) ? nr_grid_sector_*(nr_color_bins_+1) : 0; + + assert( (!b_describe_color_ && b_describe_shape_ && descLength_ == 352) || + (b_describe_color_ && !b_describe_shape_ && descLength_ == 992) || + (b_describe_color_ && b_describe_shape_ && descLength_ == 1344) + ); + + // Useful values + sqradius_ = search_radius_*search_radius_; + radius3_4_ = (search_radius_*3) / 4; + radius1_4_ = search_radius_ / 4; + radius1_2_ = search_radius_ / 2; + + shot_.setZero (descLength_); + + // Allocate enough space to hold the results + // \note This resize is irrelevant for a radiusSearch (). + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + int search_state = 0; + + output.is_dense = true; + // Iterating over the entire index vector + for (size_t idx = 0; idx < indices_->size (); ++idx) + { + bool lrf_is_nan = false; + const PointRFT& current_frame = (*frames_)[idx]; + if (!pcl_isfinite (current_frame.x_axis[0]) || + !pcl_isfinite (current_frame.y_axis[0]) || + !pcl_isfinite (current_frame.z_axis[0])) + { + PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n", + getClassName ().c_str (), (*indices_)[idx]); + lrf_is_nan = true; + } + + search_state = this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists); + + if (!isFinite ((*input_)[(*indices_)[idx]]) || + lrf_is_nan || + search_state == 0) + { + // Copy into the resultant cloud + for (int d = 0; d < descLength_; ++d) + output.points[idx].descriptor[d] = std::numeric_limits::quiet_NaN (); + for (int d = 0; d < 9; ++d) + output.points[idx].rf[d] = std::numeric_limits::quiet_NaN (); + + output.is_dense = false; + continue; + } + + // Compute the SHOT descriptor for the current 3D feature + computePointSHOT (static_cast (idx), nn_indices, nn_dists, shot_); + + // Copy into the resultant cloud + for (int d = 0; d < descLength_; ++d) + output.points[idx].descriptor[d] = shot_[d]; + for (int d = 0; d < 3; ++d) + { + output.points[idx].rf[d + 0] = frames_->points[idx].x_axis[d]; + output.points[idx].rf[d + 3] = frames_->points[idx].y_axis[d]; + output.points[idx].rf[d + 6] = frames_->points[idx].z_axis[d]; + } + } +} + +#define PCL_INSTANTIATE_SHOTEstimationBase(T,NT,OutT,RFT) template class PCL_EXPORTS pcl::SHOTEstimationBase; +#define PCL_INSTANTIATE_SHOTEstimation(T,NT,OutT,RFT) template class PCL_EXPORTS pcl::SHOTEstimation; +#define PCL_INSTANTIATE_SHOTColorEstimation(T,NT,OutT,RFT) template class PCL_EXPORTS pcl::SHOTColorEstimation; + +#endif // PCL_FEATURES_IMPL_SHOT_H_ diff --git a/pcl-1.7/pcl/features/impl/shot_lrf.hpp b/pcl-1.7/pcl/features/impl/shot_lrf.hpp new file mode 100644 index 0000000..96626b0 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/shot_lrf.hpp @@ -0,0 +1,206 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_FEATURES_IMPL_SHOT_LRF_H_ +#define PCL_FEATURES_IMPL_SHOT_LRF_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +// Compute a local Reference Frame for a 3D feature; the output is stored in the "rf" matrix +template float +pcl::SHOTLocalReferenceFrameEstimation::getLocalRF (const int& current_point_idx, Eigen::Matrix3f &rf) +{ + const Eigen::Vector4f& central_point = (*input_)[current_point_idx].getVector4fMap (); + std::vector n_indices; + std::vector n_sqr_distances; + + this->searchForNeighbors (current_point_idx, search_parameter_, n_indices, n_sqr_distances); + + Eigen::Matrix vij (n_indices.size (), 4); + + Eigen::Matrix3d cov_m = Eigen::Matrix3d::Zero (); + + double distance = 0.0; + double sum = 0.0; + + int valid_nn_points = 0; + + for (size_t i_idx = 0; i_idx < n_indices.size (); ++i_idx) + { + Eigen::Vector4f pt = surface_->points[n_indices[i_idx]].getVector4fMap (); + if (pt.head<3> () == central_point.head<3> ()) + continue; + + // Difference between current point and origin + vij.row (valid_nn_points).matrix () = (pt - central_point).cast (); + vij (valid_nn_points, 3) = 0; + + distance = search_parameter_ - sqrt (n_sqr_distances[i_idx]); + + // Multiply vij * vij' + cov_m += distance * (vij.row (valid_nn_points).head<3> ().transpose () * vij.row (valid_nn_points).head<3> ()); + + sum += distance; + valid_nn_points++; + } + + if (valid_nn_points < 5) + { + //PCL_ERROR ("[pcl::%s::getLocalRF] Warning! Neighborhood has less than 5 vertexes. Aborting Local RF computation of feature point (%lf, %lf, %lf)\n", "SHOTLocalReferenceFrameEstimation", central_point[0], central_point[1], central_point[2]); + rf.setConstant (std::numeric_limits::quiet_NaN ()); + + return (std::numeric_limits::max ()); + } + + cov_m /= sum; + + Eigen::SelfAdjointEigenSolver solver (cov_m); + + const double& e1c = solver.eigenvalues ()[0]; + const double& e2c = solver.eigenvalues ()[1]; + const double& e3c = solver.eigenvalues ()[2]; + + if (!pcl_isfinite (e1c) || !pcl_isfinite (e2c) || !pcl_isfinite (e3c)) + { + //PCL_ERROR ("[pcl::%s::getLocalRF] Warning! Eigenvectors are NaN. Aborting Local RF computation of feature point (%lf, %lf, %lf)\n", "SHOTLocalReferenceFrameEstimation", central_point[0], central_point[1], central_point[2]); + rf.setConstant (std::numeric_limits::quiet_NaN ()); + + return (std::numeric_limits::max ()); + } + + // Disambiguation + Eigen::Vector4d v1 = Eigen::Vector4d::Zero (); + Eigen::Vector4d v3 = Eigen::Vector4d::Zero (); + v1.head<3> ().matrix () = solver.eigenvectors ().col (2); + v3.head<3> ().matrix () = solver.eigenvectors ().col (0); + + int plusNormal = 0, plusTangentDirection1=0; + for (int ne = 0; ne < valid_nn_points; ne++) + { + double dp = vij.row (ne).dot (v1); + if (dp >= 0) + plusTangentDirection1++; + + dp = vij.row (ne).dot (v3); + if (dp >= 0) + plusNormal++; + } + + //TANGENT + plusTangentDirection1 = 2*plusTangentDirection1 - valid_nn_points; + if (plusTangentDirection1 == 0) + { + int points = 5; //std::min(valid_nn_points*2/2+1, 11); + int medianIndex = valid_nn_points/2; + + for (int i = -points/2; i <= points/2; i++) + if ( vij.row (medianIndex - i).dot (v1) > 0) + plusTangentDirection1 ++; + + if (plusTangentDirection1 < points/2+1) + v1 *= - 1; + } + else if (plusTangentDirection1 < 0) + v1 *= - 1; + + //Normal + plusNormal = 2*plusNormal - valid_nn_points; + if (plusNormal == 0) + { + int points = 5; //std::min(valid_nn_points*2/2+1, 11); + int medianIndex = valid_nn_points/2; + + for (int i = -points/2; i <= points/2; i++) + if ( vij.row (medianIndex - i).dot (v3) > 0) + plusNormal ++; + + if (plusNormal < points/2+1) + v3 *= - 1; + } else if (plusNormal < 0) + v3 *= - 1; + + rf.row (0).matrix () = v1.head<3> ().cast (); + rf.row (2).matrix () = v3.head<3> ().cast (); + rf.row (1).matrix () = rf.row (2).cross (rf.row (0)); + + return (0.0f); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTLocalReferenceFrameEstimation::computeFeature (PointCloudOut &output) +{ + //check whether used with search radius or search k-neighbors + if (this->getKSearch () != 0) + { + PCL_ERROR( + "[pcl::%s::computeFeature] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n", + getClassName().c_str ()); + return; + } + tree_->setSortedResults (true); + + for (size_t i = 0; i < indices_->size (); ++i) + { + // point result + Eigen::Matrix3f rf; + PointOutT& output_rf = output[i]; + + //output_rf.confidence = getLocalRF ((*indices_)[i], rf); + //if (output_rf.confidence == std::numeric_limits::max ()) + if (getLocalRF ((*indices_)[i], rf) == std::numeric_limits::max ()) + { + output.is_dense = false; + } + + for (int d = 0; d < 3; ++d) + { + output_rf.x_axis[d] = rf.row (0)[d]; + output_rf.y_axis[d] = rf.row (1)[d]; + output_rf.z_axis[d] = rf.row (2)[d]; + } + } +} + +#define PCL_INSTANTIATE_SHOTLocalReferenceFrameEstimation(T,OutT) template class PCL_EXPORTS pcl::SHOTLocalReferenceFrameEstimation; + +#endif // PCL_FEATURES_IMPL_SHOT_LRF_H_ + diff --git a/pcl-1.7/pcl/features/impl/shot_lrf_omp.hpp b/pcl-1.7/pcl/features/impl/shot_lrf_omp.hpp new file mode 100644 index 0000000..42a3c9e --- /dev/null +++ b/pcl-1.7/pcl/features/impl/shot_lrf_omp.hpp @@ -0,0 +1,94 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_FEATURES_IMPL_SHOT_LRF_OMP_H_ +#define PCL_FEATURES_IMPL_SHOT_LRF_OMP_H_ + +#include +#include +#include + +template +void +pcl::SHOTLocalReferenceFrameEstimationOMP::computeFeature (PointCloudOut &output) +{ + //check whether used with search radius or search k-neighbors + if (this->getKSearch () != 0) + { + PCL_ERROR( + "[pcl::%s::computeFeature] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n", + getClassName().c_str ()); + return; + } + tree_->setSortedResults (true); + + int data_size = static_cast (indices_->size ()); +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int i = 0; i < data_size; ++i) + { + // point result + Eigen::Matrix3f rf; + PointOutT& output_rf = output[i]; + + //output_rf.confidence = getLocalRF ((*indices_)[i], rf); + //if (output_rf.confidence == std::numeric_limits::max ()) + + std::vector n_indices; + std::vector n_sqr_distances; + this->searchForNeighbors ((*indices_)[i], search_parameter_, n_indices, n_sqr_distances); + if (getLocalRF ((*indices_)[i], rf) == std::numeric_limits::max ()) + { + output.is_dense = false; + } + + for (int d = 0; d < 3; ++d) + { + output_rf.x_axis[d] = rf.row (0)[d]; + output_rf.y_axis[d] = rf.row (1)[d]; + output_rf.z_axis[d] = rf.row (2)[d]; + } + } + +} + +#define PCL_INSTANTIATE_SHOTLocalReferenceFrameEstimationOMP(T,OutT) template class PCL_EXPORTS pcl::SHOTLocalReferenceFrameEstimationOMP; + +#endif // PCL_FEATURES_IMPL_SHOT_LRF_H_ diff --git a/pcl-1.7/pcl/features/impl/shot_omp.hpp b/pcl-1.7/pcl/features/impl/shot_omp.hpp new file mode 100644 index 0000000..16215c3 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/shot_omp.hpp @@ -0,0 +1,269 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_FEATURES_IMPL_SHOT_OMP_H_ +#define PCL_FEATURES_IMPL_SHOT_OMP_H_ + +#include +#include +#include + +template bool +pcl::SHOTEstimationOMP::initCompute () +{ + if (!FeatureFromNormals::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + // SHOT cannot work with k-search + if (this->getKSearch () != 0) + { + PCL_ERROR( + "[pcl::%s::initCompute] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n", + getClassName().c_str ()); + return (false); + } + + // Default LRF estimation alg: SHOTLocalReferenceFrameEstimationOMP + typename boost::shared_ptr > lrf_estimator(new SHOTLocalReferenceFrameEstimationOMP()); + lrf_estimator->setRadiusSearch ((lrf_radius_ > 0 ? lrf_radius_ : search_radius_)); + lrf_estimator->setInputCloud (input_); + lrf_estimator->setIndices (indices_); + lrf_estimator->setNumberOfThreads(threads_); + + if (!fake_surface_) + lrf_estimator->setSearchSurface(surface_); + + if (!FeatureWithLocalReferenceFrames::initLocalReferenceFrames (indices_->size (), lrf_estimator)) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SHOTColorEstimationOMP::initCompute () +{ + if (!FeatureFromNormals::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + // SHOT cannot work with k-search + if (this->getKSearch () != 0) + { + PCL_ERROR( + "[pcl::%s::initCompute] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n", + getClassName().c_str ()); + return (false); + } + + // Default LRF estimation alg: SHOTLocalReferenceFrameEstimationOMP + typename boost::shared_ptr > lrf_estimator(new SHOTLocalReferenceFrameEstimationOMP()); + lrf_estimator->setRadiusSearch ((lrf_radius_ > 0 ? lrf_radius_ : search_radius_)); + lrf_estimator->setInputCloud (input_); + lrf_estimator->setIndices (indices_); + lrf_estimator->setNumberOfThreads(threads_); + + if (!fake_surface_) + lrf_estimator->setSearchSurface(surface_); + + if (!FeatureWithLocalReferenceFrames::initLocalReferenceFrames (indices_->size (), lrf_estimator)) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTEstimationOMP::computeFeature (PointCloudOut &output) +{ + descLength_ = nr_grid_sector_ * (nr_shape_bins_ + 1); + + sqradius_ = search_radius_ * search_radius_; + radius3_4_ = (search_radius_ * 3) / 4; + radius1_4_ = search_radius_ / 4; + radius1_2_ = search_radius_ / 2; + + assert(descLength_ == 352); + + int data_size = static_cast (indices_->size ()); + + output.is_dense = true; + // Iterating over the entire index vector +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int idx = 0; idx < data_size; ++idx) + { + + Eigen::VectorXf shot; + shot.setZero (descLength_); + + bool lrf_is_nan = false; + const PointRFT& current_frame = (*frames_)[idx]; + if (!pcl_isfinite (current_frame.x_axis[0]) || + !pcl_isfinite (current_frame.y_axis[0]) || + !pcl_isfinite (current_frame.z_axis[0])) + { + PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n", + getClassName ().c_str (), (*indices_)[idx]); + lrf_is_nan = true; + } + + // Allocate enough space to hold the results + // \note This resize is irrelevant for a radiusSearch (). + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + if (!isFinite ((*input_)[(*indices_)[idx]]) || lrf_is_nan || this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, + nn_dists) == 0) + { + // Copy into the resultant cloud + for (int d = 0; d < shot.size (); ++d) + output.points[idx].descriptor[d] = std::numeric_limits::quiet_NaN (); + for (int d = 0; d < 9; ++d) + output.points[idx].rf[d] = std::numeric_limits::quiet_NaN (); + + output.is_dense = false; + continue; + } + + // Estimate the SHOT at each patch + this->computePointSHOT (idx, nn_indices, nn_dists, shot); + + // Copy into the resultant cloud + for (int d = 0; d < shot.size (); ++d) + output.points[idx].descriptor[d] = shot[d]; + for (int d = 0; d < 3; ++d) + { + output.points[idx].rf[d + 0] = frames_->points[idx].x_axis[d]; + output.points[idx].rf[d + 3] = frames_->points[idx].y_axis[d]; + output.points[idx].rf[d + 6] = frames_->points[idx].z_axis[d]; + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTColorEstimationOMP::computeFeature (PointCloudOut &output) +{ + descLength_ = (b_describe_shape_) ? nr_grid_sector_ * (nr_shape_bins_ + 1) : 0; + descLength_ += (b_describe_color_) ? nr_grid_sector_ * (nr_color_bins_ + 1) : 0; + + assert( (!b_describe_color_ && b_describe_shape_ && descLength_ == 352) || + (b_describe_color_ && !b_describe_shape_ && descLength_ == 992) || + (b_describe_color_ && b_describe_shape_ && descLength_ == 1344) + ); + + sqradius_ = search_radius_ * search_radius_; + radius3_4_ = (search_radius_ * 3) / 4; + radius1_4_ = search_radius_ / 4; + radius1_2_ = search_radius_ / 2; + + int data_size = static_cast (indices_->size ()); + + output.is_dense = true; + // Iterating over the entire index vector +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int idx = 0; idx < data_size; ++idx) + { + Eigen::VectorXf shot; + shot.setZero (descLength_); + + // Allocate enough space to hold the results + // \note This resize is irrelevant for a radiusSearch (). + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + bool lrf_is_nan = false; + const PointRFT& current_frame = (*frames_)[idx]; + if (!pcl_isfinite (current_frame.x_axis[0]) || + !pcl_isfinite (current_frame.y_axis[0]) || + !pcl_isfinite (current_frame.z_axis[0])) + { + PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n", + getClassName ().c_str (), (*indices_)[idx]); + lrf_is_nan = true; + } + + if (!isFinite ((*input_)[(*indices_)[idx]]) || + lrf_is_nan || + this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) + { + // Copy into the resultant cloud + for (int d = 0; d < shot.size (); ++d) + output.points[idx].descriptor[d] = std::numeric_limits::quiet_NaN (); + for (int d = 0; d < 9; ++d) + output.points[idx].rf[d] = std::numeric_limits::quiet_NaN (); + + output.is_dense = false; + continue; + } + + // Estimate the SHOT at each patch + this->computePointSHOT (idx, nn_indices, nn_dists, shot); + + // Copy into the resultant cloud + for (int d = 0; d < shot.size (); ++d) + output.points[idx].descriptor[d] = shot[d]; + for (int d = 0; d < 3; ++d) + { + output.points[idx].rf[d + 0] = frames_->points[idx].x_axis[d]; + output.points[idx].rf[d + 3] = frames_->points[idx].y_axis[d]; + output.points[idx].rf[d + 6] = frames_->points[idx].z_axis[d]; + } + } +} + +#define PCL_INSTANTIATE_SHOTEstimationOMP(T,NT,OutT,RFT) template class PCL_EXPORTS pcl::SHOTEstimationOMP; +#define PCL_INSTANTIATE_SHOTColorEstimationOMP(T,NT,OutT,RFT) template class PCL_EXPORTS pcl::SHOTColorEstimationOMP; + +#endif // PCL_FEATURES_IMPL_SHOT_OMP_H_ diff --git a/pcl-1.7/pcl/features/impl/spin_image.hpp b/pcl-1.7/pcl/features/impl/spin_image.hpp new file mode 100644 index 0000000..6d10089 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/spin_image.hpp @@ -0,0 +1,344 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_IMPL_SPIN_IMAGE_H_ +#define PCL_FEATURES_IMPL_SPIN_IMAGE_H_ + +#include +#include +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::SpinImageEstimation::SpinImageEstimation ( + unsigned int image_width, double support_angle_cos, unsigned int min_pts_neighb) : + input_normals_ (), rotation_axes_cloud_ (), + is_angular_ (false), rotation_axis_ (), use_custom_axis_(false), use_custom_axes_cloud_ (false), + is_radial_ (false), image_width_ (image_width), support_angle_cos_ (support_angle_cos), + min_pts_neighb_ (min_pts_neighb) +{ + assert (support_angle_cos_ <= 1.0 && support_angle_cos_ >= 0.0); // may be permit negative cosine? + + feature_name_ = "SpinImageEstimation"; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template Eigen::ArrayXXd +pcl::SpinImageEstimation::computeSiForPoint (int index) const +{ + assert (image_width_ > 0); + assert (support_angle_cos_ <= 1.0 && support_angle_cos_ >= 0.0); // may be permit negative cosine? + + const Eigen::Vector3f origin_point (input_->points[index].getVector3fMap ()); + + Eigen::Vector3f origin_normal; + origin_normal = + input_normals_ ? + input_normals_->points[index].getNormalVector3fMap () : + Eigen::Vector3f (); // just a placeholder; should never be used! + + const Eigen::Vector3f rotation_axis = use_custom_axis_ ? + rotation_axis_.getNormalVector3fMap () : + use_custom_axes_cloud_ ? + rotation_axes_cloud_->points[index].getNormalVector3fMap () : + origin_normal; + + Eigen::ArrayXXd m_matrix (Eigen::ArrayXXd::Zero (image_width_+1, 2*image_width_+1)); + Eigen::ArrayXXd m_averAngles (Eigen::ArrayXXd::Zero (image_width_+1, 2*image_width_+1)); + + // OK, we are interested in the points of the cylinder of height 2*r and + // base radius r, where r = m_dBinSize * in_iImageWidth + // it can be embedded to the sphere of radius sqrt(2) * m_dBinSize * in_iImageWidth + // suppose that points are uniformly distributed, so we lose ~40% + // according to the volumes ratio + double bin_size = 0.0; + if (is_radial_) + bin_size = search_radius_ / image_width_; + else + bin_size = search_radius_ / image_width_ / sqrt(2.0); + + std::vector nn_indices; + std::vector nn_sqr_dists; + const int neighb_cnt = this->searchForNeighbors (index, search_radius_, nn_indices, nn_sqr_dists); + if (neighb_cnt < static_cast (min_pts_neighb_)) + { + throw PCLException ( + "Too few points for spin image, use setMinPointCountInNeighbourhood() to decrease the threshold or use larger feature radius", + "spin_image.hpp", "computeSiForPoint"); + } + + // for all neighbor points + for (int i_neigh = 0; i_neigh < neighb_cnt ; i_neigh++) + { + // first, skip the points with distant normals + double cos_between_normals = -2.0; // should be initialized if used + if (support_angle_cos_ > 0.0 || is_angular_) // not bogus + { + cos_between_normals = origin_normal.dot (input_normals_->points[nn_indices[i_neigh]].getNormalVector3fMap ()); + if (fabs (cos_between_normals) > (1.0 + 10*std::numeric_limits::epsilon ())) // should be okay for numeric stability + { + PCL_ERROR ("[pcl::%s::computeSiForPoint] Normal for the point %d and/or the point %d are not normalized, dot ptoduct is %f.\n", + getClassName ().c_str (), nn_indices[i_neigh], index, cos_between_normals); + throw PCLException ("Some normals are not normalized", + "spin_image.hpp", "computeSiForPoint"); + } + cos_between_normals = std::max (-1.0, std::min (1.0, cos_between_normals)); + + if (fabs (cos_between_normals) < support_angle_cos_ ) // allow counter-directed normals + { + continue; + } + + if (cos_between_normals < 0.0) + { + cos_between_normals = -cos_between_normals; // the normal is not used explicitly from now + } + } + + // now compute the coordinate in cylindric coordinate system associated with the origin point + const Eigen::Vector3f direction ( + surface_->points[nn_indices[i_neigh]].getVector3fMap () - origin_point); + const double direction_norm = direction.norm (); + if (fabs(direction_norm) < 10*std::numeric_limits::epsilon ()) + continue; // ignore the point itself; it does not contribute really + assert (direction_norm > 0.0); + + // the angle between the normal vector and the direction to the point + double cos_dir_axis = direction.dot(rotation_axis) / direction_norm; + if (fabs(cos_dir_axis) > (1.0 + 10*std::numeric_limits::epsilon())) // should be okay for numeric stability + { + PCL_ERROR ("[pcl::%s::computeSiForPoint] Rotation axis for the point %d are not normalized, dot ptoduct is %f.\n", + getClassName ().c_str (), index, cos_dir_axis); + throw PCLException ("Some rotation axis is not normalized", + "spin_image.hpp", "computeSiForPoint"); + } + cos_dir_axis = std::max (-1.0, std::min (1.0, cos_dir_axis)); + + // compute coordinates w.r.t. the reference frame + double beta = std::numeric_limits::signaling_NaN (); + double alpha = std::numeric_limits::signaling_NaN (); + if (is_radial_) // radial spin image structure + { + beta = asin (cos_dir_axis); // yes, arc sine! to get the angle against tangent, not normal! + alpha = direction_norm; + } + else // rectangular spin-image structure + { + beta = direction_norm * cos_dir_axis; + alpha = direction_norm * sqrt (1.0 - cos_dir_axis*cos_dir_axis); + + if (fabs (beta) >= bin_size * image_width_ || alpha >= bin_size * image_width_) + { + continue; // outside the cylinder + } + } + + assert (alpha >= 0.0); + assert (alpha <= bin_size * image_width_ + 20 * std::numeric_limits::epsilon () ); + + + // bilinear interpolation + double beta_bin_size = is_radial_ ? (M_PI / 2 / image_width_) : bin_size; + int beta_bin = int(std::floor (beta / beta_bin_size)) + int(image_width_); + assert (0 <= beta_bin && beta_bin < m_matrix.cols ()); + int alpha_bin = int(std::floor (alpha / bin_size)); + assert (0 <= alpha_bin && alpha_bin < m_matrix.rows ()); + + if (alpha_bin == static_cast (image_width_)) // border points + { + alpha_bin--; + // HACK: to prevent a > 1 + alpha = bin_size * (alpha_bin + 1) - std::numeric_limits::epsilon (); + } + if (beta_bin == int(2*image_width_) ) // border points + { + beta_bin--; + // HACK: to prevent b > 1 + beta = beta_bin_size * (beta_bin - int(image_width_) + 1) - std::numeric_limits::epsilon (); + } + + double a = alpha/bin_size - double(alpha_bin); + double b = beta/beta_bin_size - double(beta_bin-int(image_width_)); + + assert (0 <= a && a <= 1); + assert (0 <= b && b <= 1); + + m_matrix (alpha_bin, beta_bin) += (1-a) * (1-b); + m_matrix (alpha_bin+1, beta_bin) += a * (1-b); + m_matrix (alpha_bin, beta_bin+1) += (1-a) * b; + m_matrix (alpha_bin+1, beta_bin+1) += a * b; + + if (is_angular_) + { + m_averAngles (alpha_bin, beta_bin) += (1-a) * (1-b) * acos (cos_between_normals); + m_averAngles (alpha_bin+1, beta_bin) += a * (1-b) * acos (cos_between_normals); + m_averAngles (alpha_bin, beta_bin+1) += (1-a) * b * acos (cos_between_normals); + m_averAngles (alpha_bin+1, beta_bin+1) += a * b * acos (cos_between_normals); + } + } + + if (is_angular_) + { + // transform sum to average + m_matrix = m_averAngles / (m_matrix + std::numeric_limits::epsilon ()); // +eps to avoid division by zero + } + else if (neighb_cnt > 1) // to avoid division by zero, also no need to divide by 1 + { + // normalization + m_matrix /= m_matrix.sum(); + } + + return m_matrix; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SpinImageEstimation::initCompute () +{ + if (!Feature::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + // Check if input normals are set + if (!input_normals_) + { + PCL_ERROR ("[pcl::%s::initCompute] No input dataset containing normals was given!\n", getClassName ().c_str ()); + Feature::deinitCompute (); + return (false); + } + + // Check if the size of normals is the same as the size of the surface + if (input_normals_->points.size () != input_->points.size ()) + { + PCL_ERROR ("[pcl::%s::initCompute] ", getClassName ().c_str ()); + PCL_ERROR ("The number of points in the input dataset differs from "); + PCL_ERROR ("the number of points in the dataset containing the normals!\n"); + Feature::deinitCompute (); + return (false); + } + + // We need a positive definite search radius to continue + if (search_radius_ == 0) + { + PCL_ERROR ("[pcl::%s::initCompute] Need a search radius different than 0!\n", getClassName ().c_str ()); + Feature::deinitCompute (); + return (false); + } + if (k_ != 0) + { + PCL_ERROR ("[pcl::%s::initCompute] K-nearest neighbor search for spin images not implemented. Used a search radius instead!\n", getClassName ().c_str ()); + Feature::deinitCompute (); + return (false); + } + // If the surface won't be set, make fake surface and fake surface normals + // if we wouldn't do it here, the following method would alarm that no surface normals is given + if (!surface_) + { + surface_ = input_; + fake_surface_ = true; + } + + //if (fake_surface_ && !input_normals_) + // input_normals_ = normals_; // normals_ is set, as checked earlier + + assert(!(use_custom_axis_ && use_custom_axes_cloud_)); + + if (!use_custom_axis_ && !use_custom_axes_cloud_ // use input normals as rotation axes + && !input_normals_) + { + PCL_ERROR ("[pcl::%s::initCompute] No normals for input cloud were given!\n", getClassName ().c_str ()); + // Cleanup + Feature::deinitCompute (); + return (false); + } + + if ((is_angular_ || support_angle_cos_ > 0.0) // support angle is not bogus NOTE this is for randomly-flipped normals + && !input_normals_) + { + PCL_ERROR ("[pcl::%s::initCompute] No normals for input cloud were given!\n", getClassName ().c_str ()); + // Cleanup + Feature::deinitCompute (); + return (false); + } + + if (use_custom_axes_cloud_ + && rotation_axes_cloud_->size () == input_->size ()) + { + PCL_ERROR ("[pcl::%s::initCompute] Rotation axis cloud have different size from input!\n", getClassName ().c_str ()); + // Cleanup + Feature::deinitCompute (); + return (false); + } + + return (true); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SpinImageEstimation::computeFeature (PointCloudOut &output) +{ + for (int i_input = 0; i_input < static_cast (indices_->size ()); ++i_input) + { + Eigen::ArrayXXd res = computeSiForPoint (indices_->at (i_input)); + + // Copy into the resultant cloud + for (int iRow = 0; iRow < res.rows () ; iRow++) + { + for (int iCol = 0; iCol < res.cols () ; iCol++) + { + output.points[i_input].histogram[ iRow*res.cols () + iCol ] = static_cast (res (iRow, iCol)); + } + } + } +} + +#define PCL_INSTANTIATE_SpinImageEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::SpinImageEstimation; + +#endif // PCL_FEATURES_IMPL_SPIN_IMAGE_H_ + diff --git a/pcl-1.7/pcl/features/impl/statistical_multiscale_interest_region_extraction.hpp b/pcl-1.7/pcl/features/impl/statistical_multiscale_interest_region_extraction.hpp new file mode 100644 index 0000000..1a91dd0 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/statistical_multiscale_interest_region_extraction.hpp @@ -0,0 +1,253 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_FEATURES_IMPL_STATISTICAL_MULTISCALE_INTEREST_REGION_EXTRACTION_H_ +#define PCL_FEATURES_IMPL_STATISTICAL_MULTISCALE_INTEREST_REGION_EXTRACTION_H_ + +#include +#include +#include +#include +#include +#include + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::StatisticalMultiscaleInterestRegionExtraction::generateCloudGraph () +{ + // generate a K-NNG (K-nearest neighbors graph) + pcl::KdTreeFLANN kdtree; + kdtree.setInputCloud (input_); + + using namespace boost; + typedef property Weight; + typedef adjacency_list Graph; + Graph cloud_graph; + + for (size_t point_i = 0; point_i < input_->points.size (); ++point_i) + { + std::vector k_indices (16); + std::vector k_distances (16); + kdtree.nearestKSearch (static_cast (point_i), 16, k_indices, k_distances); + + for (int k_i = 0; k_i < static_cast (k_indices.size ()); ++k_i) + add_edge (point_i, k_indices[k_i], Weight (sqrtf (k_distances[k_i])), cloud_graph); + } + + const size_t E = num_edges (cloud_graph), + V = num_vertices (cloud_graph); + PCL_INFO ("The graph has %lu vertices and %lu edges.\n", V, E); + geodesic_distances_.clear (); + for (size_t i = 0; i < V; ++i) + { + std::vector aux (V); + geodesic_distances_.push_back (aux); + } + johnson_all_pairs_shortest_paths (cloud_graph, geodesic_distances_); + + PCL_INFO ("Done generating the graph\n"); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::StatisticalMultiscaleInterestRegionExtraction::initCompute () +{ + if (!PCLBase::initCompute ()) + { + PCL_ERROR ("[pcl::StatisticalMultiscaleInterestRegionExtraction::initCompute] PCLBase::initCompute () failed - no input cloud was given.\n"); + return (false); + } + if (scale_values_.empty ()) + { + PCL_ERROR ("[pcl::StatisticalMultiscaleInterestRegionExtraction::initCompute] No scale values were given\n"); + return (false); + } + + return (true); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::StatisticalMultiscaleInterestRegionExtraction::geodesicFixedRadiusSearch (size_t &query_index, + float &radius, + std::vector &result_indices) +{ + for (size_t i = 0; i < geodesic_distances_[query_index].size (); ++i) + if (i != query_index && geodesic_distances_[query_index][i] < radius) + result_indices.push_back (static_cast (i)); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::StatisticalMultiscaleInterestRegionExtraction::computeRegionsOfInterest (std::list &rois) +{ + if (!initCompute ()) + { + PCL_ERROR ("StatisticalMultiscaleInterestRegionExtraction: not completely initialized\n"); + return; + } + + generateCloudGraph (); + + computeF (); + + extractExtrema (rois); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::StatisticalMultiscaleInterestRegionExtraction::computeF () +{ + PCL_INFO ("Calculating statistical information\n"); + + // declare and initialize data structure + F_scales_.resize (scale_values_.size ()); + std::vector point_density (input_->points.size ()), + F (input_->points.size ()); + std::vector > phi (input_->points.size ()); + std::vector phi_row (input_->points.size ()); + + for (size_t scale_i = 0; scale_i < scale_values_.size (); ++scale_i) + { + float scale_squared = scale_values_[scale_i] * scale_values_[scale_i]; + + // calculate point density for each point x_i + for (size_t point_i = 0; point_i < input_->points.size (); ++point_i) + { + float point_density_i = 0.0; + for (size_t point_j = 0; point_j < input_->points.size (); ++point_j) + { + float d_g = geodesic_distances_[point_i][point_j]; + float phi_i_j = 1.0f / sqrtf (2.0f * static_cast (M_PI) * scale_squared) * expf ( (-1) * d_g*d_g / (2.0f * scale_squared)); + + point_density_i += phi_i_j; + phi_row[point_j] = phi_i_j; + } + point_density[point_i] = point_density_i; + phi[point_i] = phi_row; + } + + // compute weights for each pair (x_i, x_j), evaluate the operator A_hat + for (size_t point_i = 0; point_i < input_->points.size (); ++point_i) + { + float A_hat_normalization = 0.0; + PointT A_hat; A_hat.x = A_hat.y = A_hat.z = 0.0; + for (size_t point_j = 0; point_j < input_->points.size (); ++point_j) + { + float phi_hat_i_j = phi[point_i][point_j] / (point_density[point_i] * point_density[point_j]); + A_hat_normalization += phi_hat_i_j; + + PointT aux = input_->points[point_j]; + aux.x *= phi_hat_i_j; aux.y *= phi_hat_i_j; aux.z *= phi_hat_i_j; + + A_hat.x += aux.x; A_hat.y += aux.y; A_hat.z += aux.z; + } + A_hat.x /= A_hat_normalization; A_hat.y /= A_hat_normalization; A_hat.z /= A_hat_normalization; + + // compute the invariant F + float aux = 2.0f / scale_values_[scale_i] * euclideanDistance (A_hat, input_->points[point_i]); + F[point_i] = aux * expf (-aux); + } + + F_scales_[scale_i] = F; + } +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::StatisticalMultiscaleInterestRegionExtraction::extractExtrema (std::list &rois) +{ + std::vector > is_min (scale_values_.size ()), + is_max (scale_values_.size ()); + + // for each point, check if it is a local extrema on each scale + for (size_t scale_i = 0; scale_i < scale_values_.size (); ++scale_i) + { + std::vector is_min_scale (input_->points.size ()), + is_max_scale (input_->points.size ()); + for (size_t point_i = 0; point_i < input_->points.size (); ++point_i) + { + std::vector nn_indices; + geodesicFixedRadiusSearch (point_i, scale_values_[scale_i], nn_indices); + bool is_max_point = true, is_min_point = true; + for (std::vector::iterator nn_it = nn_indices.begin (); nn_it != nn_indices.end (); ++nn_it) + if (F_scales_[scale_i][point_i] < F_scales_[scale_i][*nn_it]) + is_max_point = false; + else + is_min_point = false; + + is_min_scale[point_i] = is_min_point; + is_max_scale[point_i] = is_max_point; + } + + is_min[scale_i] = is_min_scale; + is_max[scale_i] = is_max_scale; + } + + // look for points that are min/max over three consecutive scales + for (size_t scale_i = 1; scale_i < scale_values_.size () - 1; ++scale_i) + { + for (size_t point_i = 0; point_i < input_->points.size (); ++point_i) + if ((is_min[scale_i - 1][point_i] && is_min[scale_i][point_i] && is_min[scale_i + 1][point_i]) || + (is_max[scale_i - 1][point_i] && is_max[scale_i][point_i] && is_max[scale_i + 1][point_i])) + { + // add the point to the result vector + IndicesPtr region (new std::vector); + region->push_back (static_cast (point_i)); + + // and also add its scale-sized geodesic neighborhood + std::vector nn_indices; + geodesicFixedRadiusSearch (point_i, scale_values_[scale_i], nn_indices); + region->insert (region->end (), nn_indices.begin (), nn_indices.end ()); + rois.push_back (region); + } + } +} + + +#define PCL_INSTANTIATE_StatisticalMultiscaleInterestRegionExtraction(T) template class PCL_EXPORTS pcl::StatisticalMultiscaleInterestRegionExtraction; + +#endif /* PCL_FEATURES_IMPL_STATISTICAL_MULTISCALE_INTEREST_REGION_EXTRACTION_H_ */ + diff --git a/pcl-1.7/pcl/features/impl/usc.hpp b/pcl-1.7/pcl/features/impl/usc.hpp new file mode 100644 index 0000000..7fbc493 --- /dev/null +++ b/pcl-1.7/pcl/features/impl/usc.hpp @@ -0,0 +1,288 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_IMPL_USC_HPP_ +#define PCL_FEATURES_IMPL_USC_HPP_ + +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::UniqueShapeContext::initCompute () +{ + if (!Feature::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + // Default LRF estimation alg: SHOTLocalReferenceFrameEstimation + typename SHOTLocalReferenceFrameEstimation::Ptr lrf_estimator(new SHOTLocalReferenceFrameEstimation()); + lrf_estimator->setRadiusSearch (local_radius_); + lrf_estimator->setInputCloud (input_); + lrf_estimator->setIndices (indices_); + if (!fake_surface_) + lrf_estimator->setSearchSurface(surface_); + + if (!FeatureWithLocalReferenceFrames::initLocalReferenceFrames (indices_->size (), lrf_estimator)) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + if (search_radius_< min_radius_) + { + PCL_ERROR ("[pcl::%s::initCompute] search_radius_ must be GREATER than min_radius_.\n", getClassName ().c_str ()); + return (false); + } + + // Update descriptor length + descriptor_length_ = elevation_bins_ * azimuth_bins_ * radius_bins_; + + // Compute radial, elevation and azimuth divisions + float azimuth_interval = 360.0f / static_cast (azimuth_bins_); + float elevation_interval = 180.0f / static_cast (elevation_bins_); + + // Reallocate divisions and volume lut + radii_interval_.clear (); + phi_divisions_.clear (); + theta_divisions_.clear (); + volume_lut_.clear (); + + // Fills radii interval based on formula (1) in section 2.1 of Frome's paper + radii_interval_.resize (radius_bins_ + 1); + for (size_t j = 0; j < radius_bins_ + 1; j++) + radii_interval_[j] = static_cast (exp (log (min_radius_) + ((static_cast (j) / static_cast (radius_bins_)) * log (search_radius_/min_radius_)))); + + // Fill theta didvisions of elevation + theta_divisions_.resize (elevation_bins_+1); + for (size_t k = 0; k < elevation_bins_+1; k++) + theta_divisions_[k] = static_cast (k) * elevation_interval; + + // Fill phi didvisions of elevation + phi_divisions_.resize (azimuth_bins_+1); + for (size_t l = 0; l < azimuth_bins_+1; l++) + phi_divisions_[l] = static_cast (l) * azimuth_interval; + + // LookUp Table that contains the volume of all the bins + // "phi" term of the volume integral + // "integr_phi" has always the same value so we compute it only one time + float integr_phi = pcl::deg2rad (phi_divisions_[1]) - pcl::deg2rad (phi_divisions_[0]); + // exponential to compute the cube root using pow + float e = 1.0f / 3.0f; + // Resize volume look up table + volume_lut_.resize (radius_bins_ * elevation_bins_ * azimuth_bins_); + // Fill volumes look up table + for (size_t j = 0; j < radius_bins_; j++) + { + // "r" term of the volume integral + float integr_r = (radii_interval_[j+1]*radii_interval_[j+1]*radii_interval_[j+1] / 3) - (radii_interval_[j]*radii_interval_[j]*radii_interval_[j]/ 3); + + for (size_t k = 0; k < elevation_bins_; k++) + { + // "theta" term of the volume integral + float integr_theta = cosf (deg2rad (theta_divisions_[k])) - cosf (deg2rad (theta_divisions_[k+1])); + // Volume + float V = integr_phi * integr_theta * integr_r; + // Compute cube root of the computed volume commented for performance but left + // here for clarity + // float cbrt = pow(V, e); + // cbrt = 1 / cbrt; + + for (size_t l = 0; l < azimuth_bins_; l++) + // Store in lut 1/cbrt + //volume_lut_[ (l*elevation_bins_*radius_bins_) + k*radius_bins_ + j ] = cbrt; + volume_lut_[(l*elevation_bins_*radius_bins_) + k*radius_bins_ + j] = 1.0f / powf (V, e); + } + } + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::UniqueShapeContext::computePointDescriptor (size_t index, /*float rf[9],*/ std::vector &desc) +{ + pcl::Vector3fMapConst origin = input_->points[(*indices_)[index]].getVector3fMap (); + + const Eigen::Vector3f x_axis (frames_->points[index].x_axis[0], + frames_->points[index].x_axis[1], + frames_->points[index].x_axis[2]); + //const Eigen::Vector3f& y_axis = frames_->points[index].y_axis.getNormalVector3fMap (); + const Eigen::Vector3f normal (frames_->points[index].z_axis[0], + frames_->points[index].z_axis[1], + frames_->points[index].z_axis[2]); + + // Find every point within specified search_radius_ + std::vector nn_indices; + std::vector nn_dists; + const size_t neighb_cnt = searchForNeighbors ((*indices_)[index], search_radius_, nn_indices, nn_dists); + // For each point within radius + for (size_t ne = 0; ne < neighb_cnt; ne++) + { + if (pcl::utils::equal(nn_dists[ne], 0.0f)) + continue; + // Get neighbours coordinates + Eigen::Vector3f neighbour = surface_->points[nn_indices[ne]].getVector3fMap (); + + // ----- Compute current neighbour polar coordinates ----- + + // Get distance between the neighbour and the origin + float r = sqrtf (nn_dists[ne]); + + // Project point into the tangent plane + Eigen::Vector3f proj; + pcl::geometry::project (neighbour, origin, normal, proj); + proj -= origin; + + // Normalize to compute the dot product + proj.normalize (); + + // Compute the angle between the projection and the x axis in the interval [0,360] + Eigen::Vector3f cross = x_axis.cross (proj); + float phi = rad2deg (std::atan2 (cross.norm (), x_axis.dot (proj))); + phi = cross.dot (normal) < 0.f ? (360.0f - phi) : phi; + /// Compute the angle between the neighbour and the z axis (normal) in the interval [0, 180] + Eigen::Vector3f no = neighbour - origin; + no.normalize (); + float theta = normal.dot (no); + theta = pcl::rad2deg (acosf (std::min (1.0f, std::max (-1.0f, theta)))); + + /// Bin (j, k, l) + size_t j = 0; + size_t k = 0; + size_t l = 0; + + /// Compute the Bin(j, k, l) coordinates of current neighbour + for (size_t rad = 1; rad < radius_bins_ + 1; rad++) + { + if (r <= radii_interval_[rad]) + { + j = rad - 1; + break; + } + } + + for (size_t ang = 1; ang < elevation_bins_ + 1; ang++) + { + if (theta <= theta_divisions_[ang]) + { + k = ang - 1; + break; + } + } + + for (size_t ang = 1; ang < azimuth_bins_ + 1; ang++) + { + if (phi <= phi_divisions_[ang]) + { + l = ang - 1; + break; + } + } + + /// Local point density = number of points in a sphere of radius "point_density_radius_" around the current neighbour + std::vector neighbour_indices; + std::vector neighbour_didtances; + float point_density = static_cast (searchForNeighbors (*surface_, nn_indices[ne], point_density_radius_, neighbour_indices, neighbour_didtances)); + /// point_density is always bigger than 0 because FindPointsWithinRadius returns at least the point itself + float w = (1.0f / point_density) * volume_lut_[(l*elevation_bins_*radius_bins_) + + (k*radius_bins_) + + j]; + + assert (w >= 0.0); + if (w == std::numeric_limits::infinity ()) + PCL_ERROR ("Shape Context Error INF!\n"); + if (w != w) + PCL_ERROR ("Shape Context Error IND!\n"); + /// Accumulate w into correspondant Bin(j,k,l) + desc[(l*elevation_bins_*radius_bins_) + (k*radius_bins_) + j] += w; + + assert (desc[(l*elevation_bins_*radius_bins_) + (k*radius_bins_) + j] >= 0); + } // end for each neighbour +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::UniqueShapeContext::computeFeature (PointCloudOut &output) +{ + assert (descriptor_length_ == 1980); + + output.is_dense = true; + + for (size_t point_index = 0; point_index < indices_->size (); ++point_index) + { + //output[point_index].descriptor.resize (descriptor_length_); + + // If the point is not finite, set the descriptor to NaN and continue + const PointRFT& current_frame = (*frames_)[point_index]; + if (!isFinite ((*input_)[(*indices_)[point_index]]) || + !pcl_isfinite (current_frame.x_axis[0]) || + !pcl_isfinite (current_frame.y_axis[0]) || + !pcl_isfinite (current_frame.z_axis[0]) ) + { + for (size_t i = 0; i < descriptor_length_; ++i) + output[point_index].descriptor[i] = std::numeric_limits::quiet_NaN (); + + memset (output[point_index].rf, 0, sizeof (output[point_index].rf[0]) * 9); + output.is_dense = false; + continue; + } + + for (int d = 0; d < 3; ++d) + { + output.points[point_index].rf[0 + d] = current_frame.x_axis[d]; + output.points[point_index].rf[3 + d] = current_frame.y_axis[d]; + output.points[point_index].rf[6 + d] = current_frame.z_axis[d]; + } + + std::vector descriptor (descriptor_length_); + computePointDescriptor (point_index, descriptor); + for (size_t j = 0; j < descriptor_length_; ++j) + output [point_index].descriptor[j] = descriptor[j]; + } +} + +#define PCL_INSTANTIATE_UniqueShapeContext(T,OutT,RFT) template class PCL_EXPORTS pcl::UniqueShapeContext; + +#endif diff --git a/pcl-1.7/pcl/features/impl/vfh.hpp b/pcl-1.7/pcl/features/impl/vfh.hpp new file mode 100644 index 0000000..bca6edd --- /dev/null +++ b/pcl-1.7/pcl/features/impl/vfh.hpp @@ -0,0 +1,288 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_IMPL_VFH_H_ +#define PCL_FEATURES_IMPL_VFH_H_ + +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::VFHEstimation::initCompute () +{ + if (input_->points.size () < 2 || (surface_ && surface_->points.size () < 2)) + { + PCL_ERROR ("[pcl::VFHEstimation::initCompute] Input dataset must have at least 2 points!\n"); + return (false); + } + if (search_radius_ == 0 && k_ == 0) + k_ = 1; + return (Feature::initCompute ()); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::VFHEstimation::compute (PointCloudOut &output) +{ + if (!initCompute ()) + { + output.width = output.height = 0; + output.points.clear (); + return; + } + // Copy the header + output.header = input_->header; + + // Resize the output dataset + // Important! We should only allocate precisely how many elements we will need, otherwise + // we risk at pre-allocating too much memory which could lead to bad_alloc + // (see http://dev.pointclouds.org/issues/657) + output.width = output.height = 1; + output.is_dense = input_->is_dense; + output.points.resize (1); + + // Perform the actual feature computation + computeFeature (output); + + Feature::deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::VFHEstimation::computePointSPFHSignature (const Eigen::Vector4f ¢roid_p, + const Eigen::Vector4f ¢roid_n, + const pcl::PointCloud &cloud, + const pcl::PointCloud &normals, + const std::vector &indices) +{ + Eigen::Vector4f pfh_tuple; + // Reset the whole thing + hist_f1_.setZero (nr_bins_f1_); + hist_f2_.setZero (nr_bins_f2_); + hist_f3_.setZero (nr_bins_f3_); + hist_f4_.setZero (nr_bins_f4_); + + // Get the bounding box of the current cluster + //Eigen::Vector4f min_pt, max_pt; + //pcl::getMinMax3D (cloud, indices, min_pt, max_pt); + //double distance_normalization_factor = (std::max)((centroid_p - min_pt).norm (), (centroid_p - max_pt).norm ()); + + //Instead of using the bounding box to normalize the VFH distance component, it is better to use the max_distance + //from any point to centroid. VFH is invariant to rotation about the roll axis but the bounding box is not, + //resulting in different normalization factors for point clouds that are just rotated about that axis. + + double distance_normalization_factor = 1.0; + if (normalize_distances_) + { + Eigen::Vector4f max_pt; + pcl::getMaxDistance (cloud, indices, centroid_p, max_pt); + max_pt[3] = 0; + distance_normalization_factor = (centroid_p - max_pt).norm (); + } + + // Factorization constant + float hist_incr; + if (normalize_bins_) + hist_incr = 100.0f / static_cast (indices.size () - 1); + else + hist_incr = 1.0f; + + float hist_incr_size_component; + if (size_component_) + hist_incr_size_component = hist_incr; + else + hist_incr_size_component = 0.0; + + // Iterate over all the points in the neighborhood + for (size_t idx = 0; idx < indices.size (); ++idx) + { + // Compute the pair P to NNi + if (!computePairFeatures (centroid_p, centroid_n, cloud.points[indices[idx]].getVector4fMap (), + normals.points[indices[idx]].getNormalVector4fMap (), pfh_tuple[0], pfh_tuple[1], + pfh_tuple[2], pfh_tuple[3])) + continue; + + // Normalize the f1, f2, f3, f4 features and push them in the histogram + int h_index = static_cast (floor (nr_bins_f1_ * ((pfh_tuple[0] + M_PI) * d_pi_))); + if (h_index < 0) + h_index = 0; + if (h_index >= nr_bins_f1_) + h_index = nr_bins_f1_ - 1; + hist_f1_ (h_index) += hist_incr; + + h_index = static_cast (floor (nr_bins_f2_ * ((pfh_tuple[1] + 1.0) * 0.5))); + if (h_index < 0) + h_index = 0; + if (h_index >= nr_bins_f2_) + h_index = nr_bins_f2_ - 1; + hist_f2_ (h_index) += hist_incr; + + h_index = static_cast (floor (nr_bins_f3_ * ((pfh_tuple[2] + 1.0) * 0.5))); + if (h_index < 0) + h_index = 0; + if (h_index >= nr_bins_f3_) + h_index = nr_bins_f3_ - 1; + hist_f3_ (h_index) += hist_incr; + + if (normalize_distances_) + h_index = static_cast (floor (nr_bins_f4_ * (pfh_tuple[3] / distance_normalization_factor))); + else + h_index = static_cast (pcl_round (pfh_tuple[3] * 100)); + + if (h_index < 0) + h_index = 0; + if (h_index >= nr_bins_f4_) + h_index = nr_bins_f4_ - 1; + + hist_f4_ (h_index) += hist_incr_size_component; + } +} +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::VFHEstimation::computeFeature (PointCloudOut &output) +{ + // ---[ Step 1a : compute the centroid in XYZ space + Eigen::Vector4f xyz_centroid; + + if (use_given_centroid_) + xyz_centroid = centroid_to_use_; + else + compute3DCentroid (*surface_, *indices_, xyz_centroid); // Estimate the XYZ centroid + + // ---[ Step 1b : compute the centroid in normal space + Eigen::Vector4f normal_centroid = Eigen::Vector4f::Zero (); + int cp = 0; + + // If the data is dense, we don't need to check for NaN + if (use_given_normal_) + normal_centroid = normal_to_use_; + else + { + if (normals_->is_dense) + { + for (size_t i = 0; i < indices_->size (); ++i) + { + normal_centroid += normals_->points[(*indices_)[i]].getNormalVector4fMap (); + cp++; + } + } + // NaN or Inf values could exist => check for them + else + { + for (size_t i = 0; i < indices_->size (); ++i) + { + if (!pcl_isfinite (normals_->points[(*indices_)[i]].normal[0]) + || + !pcl_isfinite (normals_->points[(*indices_)[i]].normal[1]) + || + !pcl_isfinite (normals_->points[(*indices_)[i]].normal[2])) + continue; + normal_centroid += normals_->points[(*indices_)[i]].getNormalVector4fMap (); + cp++; + } + } + normal_centroid /= static_cast (cp); + } + + // Compute the direction of view from the viewpoint to the centroid + Eigen::Vector4f viewpoint (vpx_, vpy_, vpz_, 0); + Eigen::Vector4f d_vp_p = viewpoint - xyz_centroid; + d_vp_p.normalize (); + + // Estimate the SPFH at nn_indices[0] using the entire cloud + computePointSPFHSignature (xyz_centroid, normal_centroid, *surface_, *normals_, *indices_); + + // We only output _1_ signature + output.points.resize (1); + output.width = 1; + output.height = 1; + + // Estimate the FPFH at nn_indices[0] using the entire cloud and copy the resultant signature + for (int d = 0; d < hist_f1_.size (); ++d) + output.points[0].histogram[d + 0] = hist_f1_[d]; + + size_t data_size = hist_f1_.size (); + for (int d = 0; d < hist_f2_.size (); ++d) + output.points[0].histogram[d + data_size] = hist_f2_[d]; + + data_size += hist_f2_.size (); + for (int d = 0; d < hist_f3_.size (); ++d) + output.points[0].histogram[d + data_size] = hist_f3_[d]; + + data_size += hist_f3_.size (); + for (int d = 0; d < hist_f4_.size (); ++d) + output.points[0].histogram[d + data_size] = hist_f4_[d]; + + // ---[ Step 2 : obtain the viewpoint component + hist_vp_.setZero (nr_bins_vp_); + + double hist_incr; + if (normalize_bins_) + hist_incr = 100.0 / static_cast (indices_->size ()); + else + hist_incr = 1.0; + + for (size_t i = 0; i < indices_->size (); ++i) + { + Eigen::Vector4f normal (normals_->points[(*indices_)[i]].normal[0], + normals_->points[(*indices_)[i]].normal[1], + normals_->points[(*indices_)[i]].normal[2], 0); + // Normalize + double alpha = (normal.dot (d_vp_p) + 1.0) * 0.5; + int fi = static_cast (floor (alpha * static_cast (hist_vp_.size ()))); + if (fi < 0) + fi = 0; + if (fi > (static_cast (hist_vp_.size ()) - 1)) + fi = static_cast (hist_vp_.size ()) - 1; + // Bin into the histogram + hist_vp_ [fi] += static_cast (hist_incr); + } + data_size += hist_f4_.size (); + // Copy the resultant signature + for (int d = 0; d < hist_vp_.size (); ++d) + output.points[0].histogram[d + data_size] = hist_vp_[d]; +} + +#define PCL_INSTANTIATE_VFHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::VFHEstimation; + +#endif // PCL_FEATURES_IMPL_VFH_H_ diff --git a/pcl-1.7/pcl/features/integral_image2D.h b/pcl-1.7/pcl/features/integral_image2D.h new file mode 100644 index 0000000..33a3f10 --- /dev/null +++ b/pcl-1.7/pcl/features/integral_image2D.h @@ -0,0 +1,346 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: feature.h 2784 2011-10-15 22:05:38Z aichim $ + */ + +#ifndef PCL_INTEGRAL_IMAGE2D_H_ +#define PCL_INTEGRAL_IMAGE2D_H_ + +#include + +namespace pcl +{ + template + struct IntegralImageTypeTraits + { + typedef DataType Type; + typedef DataType IntegralType; + }; + + template <> + struct IntegralImageTypeTraits + { + typedef float Type; + typedef double IntegralType; + }; + + template <> + struct IntegralImageTypeTraits + { + typedef char Type; + typedef int IntegralType; + }; + + template <> + struct IntegralImageTypeTraits + { + typedef short Type; + typedef long IntegralType; + }; + + template <> + struct IntegralImageTypeTraits + { + typedef unsigned short Type; + typedef unsigned long IntegralType; + }; + + template <> + struct IntegralImageTypeTraits + { + typedef unsigned char Type; + typedef unsigned int IntegralType; + }; + + template <> + struct IntegralImageTypeTraits + { + typedef int Type; + typedef long IntegralType; + }; + + template <> + struct IntegralImageTypeTraits + { + typedef unsigned int Type; + typedef unsigned long IntegralType; + }; + + /** \brief Determines an integral image representation for a given organized data array + * \author Suat Gedikli + */ + template + class IntegralImage2D + { + public: + static const unsigned second_order_size = (Dimension * (Dimension + 1)) >> 1; + typedef Eigen::Matrix::IntegralType, Dimension, 1> ElementType; + typedef Eigen::Matrix::IntegralType, second_order_size, 1> SecondOrderType; + + /** \brief Constructor for an Integral Image + * \param[in] compute_second_order_integral_images set to true if we want to compute a second order image + */ + IntegralImage2D (bool compute_second_order_integral_images) : + first_order_integral_image_ (), + second_order_integral_image_ (), + finite_values_integral_image_ (), + width_ (1), + height_ (1), + compute_second_order_integral_images_ (compute_second_order_integral_images) + { + } + + /** \brief Destructor */ + virtual + ~IntegralImage2D () { } + + /** \brief sets the computation for second order integral images on or off. + * \param compute_second_order_integral_images + */ + void + setSecondOrderComputation (bool compute_second_order_integral_images); + + /** \brief Set the input data to compute the integral image for + * \param[in] data the input data + * \param[in] width the width of the data + * \param[in] height the height of the data + * \param[in] element_stride the element stride of the data + * \param[in] row_stride the row stride of the data + */ + void + setInput (const DataType * data, + unsigned width, unsigned height, unsigned element_stride, unsigned row_stride); + + /** \brief Compute the first order sum within a given rectangle + * \param[in] start_x x position of rectangle + * \param[in] start_y y position of rectangle + * \param[in] width width of rectangle + * \param[in] height height of rectangle + */ + inline ElementType + getFirstOrderSum (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const; + + /** \brief Compute the first order sum within a given rectangle + * \param[in] start_x x position of the start of the rectangle + * \param[in] start_y x position of the start of the rectangle + * \param[in] end_x x position of the end of the rectangle + * \param[in] end_y x position of the end of the rectangle + */ + inline ElementType + getFirstOrderSumSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const; + + /** \brief Compute the second order sum within a given rectangle + * \param[in] start_x x position of rectangle + * \param[in] start_y y position of rectangle + * \param[in] width width of rectangle + * \param[in] height height of rectangle + */ + inline SecondOrderType + getSecondOrderSum (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const; + + /** \brief Compute the second order sum within a given rectangle + * \param[in] start_x x position of the start of the rectangle + * \param[in] start_y x position of the start of the rectangle + * \param[in] end_x x position of the end of the rectangle + * \param[in] end_y x position of the end of the rectangle + */ + inline SecondOrderType + getSecondOrderSumSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const; + + /** \brief Compute the number of finite elements within a given rectangle + * \param[in] start_x x position of rectangle + * \param[in] start_y y position of rectangle + * \param[in] width width of rectangle + * \param[in] height height of rectangle + */ + inline unsigned + getFiniteElementsCount (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const; + + /** \brief Compute the number of finite elements within a given rectangle + * \param[in] start_x x position of the start of the rectangle + * \param[in] start_y x position of the start of the rectangle + * \param[in] end_x x position of the end of the rectangle + * \param[in] end_y x position of the end of the rectangle + */ + inline unsigned + getFiniteElementsCountSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const; + + private: + typedef Eigen::Matrix::Type, Dimension, 1> InputType; + + /** \brief Compute the actual integral image data + * \param[in] data the input data + * \param[in] element_stride the element stride of the data + * \param[in] row_stride the row stride of the data + */ + void + computeIntegralImages (const DataType * data, unsigned row_stride, unsigned element_stride); + + std::vector > first_order_integral_image_; + std::vector > second_order_integral_image_; + std::vector finite_values_integral_image_; + + /** \brief The width of the 2d input data array */ + unsigned width_; + /** \brief The height of the 2d input data array */ + unsigned height_; + + /** \brief Indicates whether second order integral images are available **/ + bool compute_second_order_integral_images_; + }; + + /** + * \brief partial template specialization for integral images with just one channel. + */ + template + class IntegralImage2D + { + public: + static const unsigned second_order_size = 1; + typedef typename IntegralImageTypeTraits::IntegralType ElementType; + typedef typename IntegralImageTypeTraits::IntegralType SecondOrderType; + + /** \brief Constructor for an Integral Image + * \param[in] compute_second_order_integral_images set to true if we want to compute a second order image + */ + IntegralImage2D (bool compute_second_order_integral_images) : + first_order_integral_image_ (), + second_order_integral_image_ (), + finite_values_integral_image_ (), + width_ (1), height_ (1), + compute_second_order_integral_images_ (compute_second_order_integral_images) + { + } + + /** \brief Destructor */ + virtual + ~IntegralImage2D () { } + + /** \brief Set the input data to compute the integral image for + * \param[in] data the input data + * \param[in] width the width of the data + * \param[in] height the height of the data + * \param[in] element_stride the element stride of the data + * \param[in] row_stride the row stride of the data + */ + void + setInput (const DataType * data, + unsigned width, unsigned height, unsigned element_stride, unsigned row_stride); + + /** \brief Compute the first order sum within a given rectangle + * \param[in] start_x x position of rectangle + * \param[in] start_y y position of rectangle + * \param[in] width width of rectangle + * \param[in] height height of rectangle + */ + inline ElementType + getFirstOrderSum (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const; + + /** \brief Compute the first order sum within a given rectangle + * \param[in] start_x x position of the start of the rectangle + * \param[in] start_y x position of the start of the rectangle + * \param[in] end_x x position of the end of the rectangle + * \param[in] end_y x position of the end of the rectangle + */ + inline ElementType + getFirstOrderSumSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const; + + /** \brief Compute the second order sum within a given rectangle + * \param[in] start_x x position of rectangle + * \param[in] start_y y position of rectangle + * \param[in] width width of rectangle + * \param[in] height height of rectangle + */ + inline SecondOrderType + getSecondOrderSum (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const; + + /** \brief Compute the second order sum within a given rectangle + * \param[in] start_x x position of the start of the rectangle + * \param[in] start_y x position of the start of the rectangle + * \param[in] end_x x position of the end of the rectangle + * \param[in] end_y x position of the end of the rectangle + */ + inline SecondOrderType + getSecondOrderSumSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const; + + /** \brief Compute the number of finite elements within a given rectangle + * \param[in] start_x x position of rectangle + * \param[in] start_y y position of rectangle + * \param[in] width width of rectangle + * \param[in] height height of rectangle + */ + inline unsigned + getFiniteElementsCount (unsigned start_x, unsigned start_y, unsigned width, unsigned height) const; + + /** \brief Compute the number of finite elements within a given rectangle + * \param[in] start_x x position of the start of the rectangle + * \param[in] start_y x position of the start of the rectangle + * \param[in] end_x x position of the end of the rectangle + * \param[in] end_y x position of the end of the rectangle + */ + inline unsigned + getFiniteElementsCountSE (unsigned start_x, unsigned start_y, unsigned end_x, unsigned end_y) const; + + private: + // typedef typename IntegralImageTypeTraits::Type InputType; + + /** \brief Compute the actual integral image data + * \param[in] data the input data + * \param[in] element_stride the element stride of the data + * \param[in] row_stride the row stride of the data + */ + void + computeIntegralImages (const DataType * data, unsigned row_stride, unsigned element_stride); + + std::vector > first_order_integral_image_; + std::vector > second_order_integral_image_; + std::vector finite_values_integral_image_; + + /** \brief The width of the 2d input data array */ + unsigned width_; + /** \brief The height of the 2d input data array */ + unsigned height_; + + /** \brief Indicates whether second order integral images are available **/ + bool compute_second_order_integral_images_; + }; + } + +#include + +#endif // PCL_INTEGRAL_IMAGE2D_H_ + diff --git a/pcl-1.7/pcl/features/integral_image_normal.h b/pcl-1.7/pcl/features/integral_image_normal.h new file mode 100644 index 0000000..4404f29 --- /dev/null +++ b/pcl-1.7/pcl/features/integral_image_normal.h @@ -0,0 +1,483 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_INTEGRALIMAGE_BASED_NORMAL_ESTIMATOR_H_ +#define PCL_INTEGRALIMAGE_BASED_NORMAL_ESTIMATOR_H_ + +#include +#include +#include +#include + +#if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 +#pragma GCC diagnostic ignored "-Weffc++" +#endif +namespace pcl +{ + /** \brief Surface normal estimation on organized data using integral images. + * + * For detailed information about this method see: + * + * S. Holzer and R. B. Rusu and M. Dixon and S. Gedikli and N. Navab, + * Adaptive Neighborhood Selection for Real-Time Surface Normal Estimation + * from Organized Point Cloud Data Using Integral Images, IROS 2012. + * + * D. Holz, S. Holzer, R. B. Rusu, and S. Behnke (2011, July). + * Real-Time Plane Segmentation using RGB-D Cameras. In Proceedings of + * the 15th RoboCup International Symposium, Istanbul, Turkey. + * http://www.ais.uni-bonn.de/~holz/papers/holz_2011_robocup.pdf + * + * \author Stefan Holzer + */ + template + class IntegralImageNormalEstimation: public Feature + { + using Feature::input_; + using Feature::feature_name_; + using Feature::tree_; + using Feature::k_; + using Feature::indices_; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Different types of border handling. */ + enum BorderPolicy + { + BORDER_POLICY_IGNORE, + BORDER_POLICY_MIRROR + }; + + /** \brief Different normal estimation methods. + *
    + *
  • COVARIANCE_MATRIX - creates 9 integral images to compute the normal for a specific point + * from the covariance matrix of its local neighborhood.
  • + *
  • AVERAGE_3D_GRADIENT - creates 6 integral images to compute smoothed versions of + * horizontal and vertical 3D gradients and computes the normals using the cross-product between these + * two gradients. + *
  • AVERAGE_DEPTH_CHANGE - creates only a single integral image and computes the normals + * from the average depth changes. + *
+ */ + enum NormalEstimationMethod + { + COVARIANCE_MATRIX, + AVERAGE_3D_GRADIENT, + AVERAGE_DEPTH_CHANGE, + SIMPLE_3D_GRADIENT + }; + + typedef typename Feature::PointCloudIn PointCloudIn; + typedef typename Feature::PointCloudOut PointCloudOut; + + /** \brief Constructor */ + IntegralImageNormalEstimation () + : normal_estimation_method_(AVERAGE_3D_GRADIENT) + , border_policy_ (BORDER_POLICY_IGNORE) + , rect_width_ (0), rect_width_2_ (0), rect_width_4_ (0) + , rect_height_ (0), rect_height_2_ (0), rect_height_4_ (0) + , distance_threshold_ (0) + , integral_image_DX_ (false) + , integral_image_DY_ (false) + , integral_image_depth_ (false) + , integral_image_XYZ_ (true) + , diff_x_ (NULL) + , diff_y_ (NULL) + , depth_data_ (NULL) + , distance_map_ (NULL) + , use_depth_dependent_smoothing_ (false) + , max_depth_change_factor_ (20.0f*0.001f) + , normal_smoothing_size_ (10.0f) + , init_covariance_matrix_ (false) + , init_average_3d_gradient_ (false) + , init_simple_3d_gradient_ (false) + , init_depth_change_ (false) + , vpx_ (0.0f) + , vpy_ (0.0f) + , vpz_ (0.0f) + , use_sensor_origin_ (true) + { + feature_name_ = "IntegralImagesNormalEstimation"; + tree_.reset (); + k_ = 1; + } + + /** \brief Destructor **/ + virtual ~IntegralImageNormalEstimation (); + + /** \brief Set the regions size which is considered for normal estimation. + * \param[in] width the width of the search rectangle + * \param[in] height the height of the search rectangle + */ + void + setRectSize (const int width, const int height); + + /** \brief Sets the policy for handling borders. + * \param[in] border_policy the border policy. + */ + void + setBorderPolicy (const BorderPolicy border_policy) + { + border_policy_ = border_policy; + } + + /** \brief Computes the normal at the specified position. + * \param[in] pos_x x position (pixel) + * \param[in] pos_y y position (pixel) + * \param[in] point_index the position index of the point + * \param[out] normal the output estimated normal + */ + void + computePointNormal (const int pos_x, const int pos_y, const unsigned point_index, PointOutT &normal); + + /** \brief Computes the normal at the specified position with mirroring for border handling. + * \param[in] pos_x x position (pixel) + * \param[in] pos_y y position (pixel) + * \param[in] point_index the position index of the point + * \param[out] normal the output estimated normal + */ + void + computePointNormalMirror (const int pos_x, const int pos_y, const unsigned point_index, PointOutT &normal); + + /** \brief The depth change threshold for computing object borders + * \param[in] max_depth_change_factor the depth change threshold for computing object borders based on + * depth changes + */ + void + setMaxDepthChangeFactor (float max_depth_change_factor) + { + max_depth_change_factor_ = max_depth_change_factor; + } + + /** \brief Set the normal smoothing size + * \param[in] normal_smoothing_size factor which influences the size of the area used to smooth normals + * (depth dependent if useDepthDependentSmoothing is true) + */ + void + setNormalSmoothingSize (float normal_smoothing_size) + { + if (normal_smoothing_size <= 0) + { + PCL_ERROR ("[pcl::%s::setNormalSmoothingSize] Invalid normal smoothing size given! (%f). Allowed ranges are: 0 < N. Defaulting to %f.\n", + feature_name_.c_str (), normal_smoothing_size, normal_smoothing_size_); + return; + } + normal_smoothing_size_ = normal_smoothing_size; + } + + /** \brief Set the normal estimation method. The current implemented algorithms are: + *
    + *
  • COVARIANCE_MATRIX - creates 9 integral images to compute the normal for a specific point + * from the covariance matrix of its local neighborhood.
  • + *
  • AVERAGE_3D_GRADIENT - creates 6 integral images to compute smoothed versions of + * horizontal and vertical 3D gradients and computes the normals using the cross-product between these + * two gradients. + *
  • AVERAGE_DEPTH_CHANGE - creates only a single integral image and computes the normals + * from the average depth changes. + *
+ * \param[in] normal_estimation_method the method used for normal estimation + */ + void + setNormalEstimationMethod (NormalEstimationMethod normal_estimation_method) + { + normal_estimation_method_ = normal_estimation_method; + } + + /** \brief Set whether to use depth depending smoothing or not + * \param[in] use_depth_dependent_smoothing decides whether the smoothing is depth dependent + */ + void + setDepthDependentSmoothing (bool use_depth_dependent_smoothing) + { + use_depth_dependent_smoothing_ = use_depth_dependent_smoothing; + } + + /** \brief Provide a pointer to the input dataset (overwrites the PCLBase::setInputCloud method) + * \param[in] cloud the const boost shared pointer to a PointCloud message + */ + virtual inline void + setInputCloud (const typename PointCloudIn::ConstPtr &cloud) + { + input_ = cloud; + if (!cloud->isOrganized ()) + { + PCL_ERROR ("[pcl::IntegralImageNormalEstimation::setInputCloud] Input dataset is not organized (height = 1).\n"); + return; + } + + init_covariance_matrix_ = init_average_3d_gradient_ = init_depth_change_ = false; + + if (use_sensor_origin_) + { + vpx_ = input_->sensor_origin_.coeff (0); + vpy_ = input_->sensor_origin_.coeff (1); + vpz_ = input_->sensor_origin_.coeff (2); + } + + // Initialize the correct data structure based on the normal estimation method chosen + initData (); + } + + /** \brief Returns a pointer to the distance map which was computed internally + */ + inline float* + getDistanceMap () + { + return (distance_map_); + } + + /** \brief Set the viewpoint. + * \param vpx the X coordinate of the viewpoint + * \param vpy the Y coordinate of the viewpoint + * \param vpz the Z coordinate of the viewpoint + */ + inline void + setViewPoint (float vpx, float vpy, float vpz) + { + vpx_ = vpx; + vpy_ = vpy; + vpz_ = vpz; + use_sensor_origin_ = false; + } + + /** \brief Get the viewpoint. + * \param [out] vpx x-coordinate of the view point + * \param [out] vpy y-coordinate of the view point + * \param [out] vpz z-coordinate of the view point + * \note this method returns the currently used viewpoint for normal flipping. + * If the viewpoint is set manually using the setViewPoint method, this method will return the set view point coordinates. + * If an input cloud is set, it will return the sensor origin otherwise it will return the origin (0, 0, 0) + */ + inline void + getViewPoint (float &vpx, float &vpy, float &vpz) + { + vpx = vpx_; + vpy = vpy_; + vpz = vpz_; + } + + /** \brief sets whether the sensor origin or a user given viewpoint should be used. After this method, the + * normal estimation method uses the sensor origin of the input cloud. + * to use a user defined view point, use the method setViewPoint + */ + inline void + useSensorOriginAsViewPoint () + { + use_sensor_origin_ = true; + if (input_) + { + vpx_ = input_->sensor_origin_.coeff (0); + vpy_ = input_->sensor_origin_.coeff (1); + vpz_ = input_->sensor_origin_.coeff (2); + } + else + { + vpx_ = 0; + vpy_ = 0; + vpz_ = 0; + } + } + + protected: + + /** \brief Computes the normal for the complete cloud or only \a indices_ if provided. + * \param[out] output the resultant normals + */ + void + computeFeature (PointCloudOut &output); + + /** \brief Computes the normal for the complete cloud. + * \param[in] distance_map distance map + * \param[in] bad_point constant given to invalid normal components + * \param[out] output the resultant normals + */ + void + computeFeatureFull (const float* distance_map, const float& bad_point, PointCloudOut& output); + + /** \brief Computes the normal for part of the cloud specified by \a indices_ + * \param[in] distance_map distance map + * \param[in] bad_point constant given to invalid normal components + * \param[out] output the resultant normals + */ + void + computeFeaturePart (const float* distance_map, const float& bad_point, PointCloudOut& output); + + /** \brief Initialize the data structures, based on the normal estimation method chosen. */ + void + initData (); + + private: + + /** \brief Flip (in place) the estimated normal of a point towards a given viewpoint + * \param point a given point + * \param vp_x the X coordinate of the viewpoint + * \param vp_y the X coordinate of the viewpoint + * \param vp_z the X coordinate of the viewpoint + * \param nx the resultant X component of the plane normal + * \param ny the resultant Y component of the plane normal + * \param nz the resultant Z component of the plane normal + * \ingroup features + */ + inline void + flipNormalTowardsViewpoint (const PointInT &point, + float vp_x, float vp_y, float vp_z, + float &nx, float &ny, float &nz) + { + // See if we need to flip any plane normals + vp_x -= point.x; + vp_y -= point.y; + vp_z -= point.z; + + // Dot product between the (viewpoint - point) and the plane normal + float cos_theta = (vp_x * nx + vp_y * ny + vp_z * nz); + + // Flip the plane normal + if (cos_theta < 0) + { + nx *= -1; + ny *= -1; + nz *= -1; + } + } + + /** \brief The normal estimation method to use. Currently, 3 implementations are provided: + * + * - COVARIANCE_MATRIX + * - AVERAGE_3D_GRADIENT + * - AVERAGE_DEPTH_CHANGE + */ + NormalEstimationMethod normal_estimation_method_; + + /** \brief The policy for handling borders. */ + BorderPolicy border_policy_; + + /** The width of the neighborhood region used for computing the normal. */ + int rect_width_; + int rect_width_2_; + int rect_width_4_; + /** The height of the neighborhood region used for computing the normal. */ + int rect_height_; + int rect_height_2_; + int rect_height_4_; + + /** the threshold used to detect depth discontinuities */ + float distance_threshold_; + + /** integral image in x-direction */ + IntegralImage2D integral_image_DX_; + /** integral image in y-direction */ + IntegralImage2D integral_image_DY_; + /** integral image */ + IntegralImage2D integral_image_depth_; + /** integral image xyz */ + IntegralImage2D integral_image_XYZ_; + + /** derivatives in x-direction */ + float *diff_x_; + /** derivatives in y-direction */ + float *diff_y_; + + /** depth data */ + float *depth_data_; + + /** distance map */ + float *distance_map_; + + /** \brief Smooth data based on depth (true/false). */ + bool use_depth_dependent_smoothing_; + + /** \brief Threshold for detecting depth discontinuities */ + float max_depth_change_factor_; + + /** \brief */ + float normal_smoothing_size_; + + /** \brief True when a dataset has been received and the covariance_matrix data has been initialized. */ + bool init_covariance_matrix_; + + /** \brief True when a dataset has been received and the average 3d gradient data has been initialized. */ + bool init_average_3d_gradient_; + + /** \brief True when a dataset has been received and the simple 3d gradient data has been initialized. */ + bool init_simple_3d_gradient_; + + /** \brief True when a dataset has been received and the depth change data has been initialized. */ + bool init_depth_change_; + + /** \brief Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit + * from NormalEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0. */ + float vpx_, vpy_, vpz_; + + /** whether the sensor origin of the input cloud or a user given viewpoint should be used.*/ + bool use_sensor_origin_; + + /** \brief This method should get called before starting the actual computation. */ + bool + initCompute (); + + /** \brief Internal initialization method for COVARIANCE_MATRIX estimation. */ + void + initCovarianceMatrixMethod (); + + /** \brief Internal initialization method for AVERAGE_3D_GRADIENT estimation. */ + void + initAverage3DGradientMethod (); + + /** \brief Internal initialization method for AVERAGE_DEPTH_CHANGE estimation. */ + void + initAverageDepthChangeMethod (); + + /** \brief Internal initialization method for SIMPLE_3D_GRADIENT estimation. */ + void + initSimple3DGradientMethod (); + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} +#if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 +#pragma GCC diagnostic warning "-Weffc++" +#endif + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif + diff --git a/pcl-1.7/pcl/features/intensity_gradient.h b/pcl-1.7/pcl/features/intensity_gradient.h new file mode 100644 index 0000000..7f14ea8 --- /dev/null +++ b/pcl-1.7/pcl/features/intensity_gradient.h @@ -0,0 +1,119 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_INTENSITY_GRADIENT_H_ +#define PCL_INTENSITY_GRADIENT_H_ + +#include +#include + +namespace pcl +{ + /** \brief IntensityGradientEstimation estimates the intensity gradient for a point cloud that contains position + * and intensity values. The intensity gradient at a given point will be a vector orthogonal to the surface + * normal and pointing in the direction of the greatest increase in local intensity; the vector's magnitude + * indicates the rate of intensity change. + * \author Michael Dixon + * \ingroup features + */ + template > + class IntensityGradientEstimation : public FeatureFromNormals + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::surface_; + using Feature::k_; + using Feature::search_parameter_; + using FeatureFromNormals::normals_; + + typedef typename Feature::PointCloudOut PointCloudOut; + + /** \brief Empty constructor. */ + IntensityGradientEstimation () : intensity_ (), threads_ (0) + { + feature_name_ = "IntensityGradientEstimation"; + }; + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + + protected: + /** \brief Estimate the intensity gradients for a set of points given in using + * the surface in setSearchSurface () and the spatial locator in setSearchMethod (). + * \param output the resultant point cloud that contains the intensity gradient vectors + */ + void + computeFeature (PointCloudOut &output); + + /** \brief Estimate the intensity gradient around a given point based on its spatial neighborhood of points + * \param cloud a point cloud dataset containing XYZI coordinates (Cartesian coordinates + intensity) + * \param indices the indices of the neighoring points in the dataset + * \param point the 3D Cartesian coordinates of the point at which to estimate the gradient + * \param mean_intensity + * \param normal the 3D surface normal of the given point + * \param gradient the resultant 3D gradient vector + */ + void + computePointIntensityGradient (const pcl::PointCloud &cloud, + const std::vector &indices, + const Eigen::Vector3f &point, + float mean_intensity, + const Eigen::Vector3f &normal, + Eigen::Vector3f &gradient); + + protected: + ///intensity field accessor structure + IntensitySelectorT intensity_; + ///number of threads to be used, default 0 (auto) + unsigned int threads_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // #ifndef PCL_INTENSITY_GRADIENT_H_ diff --git a/pcl-1.7/pcl/features/intensity_spin.h b/pcl-1.7/pcl/features/intensity_spin.h new file mode 100644 index 0000000..715db9e --- /dev/null +++ b/pcl-1.7/pcl/features/intensity_spin.h @@ -0,0 +1,152 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_INTENSITY_SPIN_H_ +#define PCL_INTENSITY_SPIN_H_ + +#include + +namespace pcl +{ + /** \brief IntensitySpinEstimation estimates the intensity-domain spin image descriptors for a given point cloud + * dataset containing points and intensity. For more information about the intensity-domain spin image descriptor, + * see: + * + * Svetlana Lazebnik, Cordelia Schmid, and Jean Ponce. + * A sparse texture representation using local affine regions. + * In IEEE Transactions on Pattern Analysis and Machine Intelligence, volume 27, pages 1265-1278, August 2005. + * \author Michael Dixon + * \ingroup features + */ + template + class IntensitySpinEstimation: public Feature + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using Feature::feature_name_; + using Feature::getClassName; + + using Feature::input_; + using Feature::indices_; + using Feature::surface_; + + using Feature::tree_; + using Feature::search_radius_; + + typedef typename pcl::PointCloud PointCloudIn; + typedef typename Feature::PointCloudOut PointCloudOut; + + /** \brief Empty constructor. */ + IntensitySpinEstimation () : nr_distance_bins_ (4), nr_intensity_bins_ (5), sigma_ (1.0) + { + feature_name_ = "IntensitySpinEstimation"; + }; + + /** \brief Estimate the intensity-domain spin image descriptor for a given point based on its spatial + * neighborhood of 3D points and their intensities. + * \param[in] cloud the dataset containing the Cartesian coordinates and intensity values of the points + * \param[in] radius the radius of the feature + * \param[in] sigma the standard deviation of the Gaussian smoothing kernel to use during the soft histogram update + * \param[in] k the number of neighbors to use from \a indices and \a squared_distances + * \param[in] indices the indices of the points that comprise the query point's neighborhood + * \param[in] squared_distances the squared distances from the query point to each point in the neighborhood + * \param[out] intensity_spin_image the resultant intensity-domain spin image descriptor + */ + void + computeIntensitySpinImage (const PointCloudIn &cloud, + float radius, float sigma, int k, + const std::vector &indices, + const std::vector &squared_distances, + Eigen::MatrixXf &intensity_spin_image); + + /** \brief Set the number of bins to use in the distance dimension of the spin image + * \param[in] nr_distance_bins the number of bins to use in the distance dimension of the spin image + */ + inline void + setNrDistanceBins (size_t nr_distance_bins) { nr_distance_bins_ = static_cast (nr_distance_bins); }; + + /** \brief Returns the number of bins in the distance dimension of the spin image. */ + inline int + getNrDistanceBins () { return (nr_distance_bins_); }; + + /** \brief Set the number of bins to use in the intensity dimension of the spin image. + * \param[in] nr_intensity_bins the number of bins to use in the intensity dimension of the spin image + */ + inline void + setNrIntensityBins (size_t nr_intensity_bins) { nr_intensity_bins_ = static_cast (nr_intensity_bins); }; + + /** \brief Returns the number of bins in the intensity dimension of the spin image. */ + inline int + getNrIntensityBins () { return (nr_intensity_bins_); }; + + /** \brief Set the standard deviation of the Gaussian smoothing kernel to use when constructing the spin images. + * \param[in] sigma the standard deviation of the Gaussian smoothing kernel to use when constructing the spin images + */ + inline void + setSmoothingBandwith (float sigma) { sigma_ = sigma; }; + + /** \brief Returns the standard deviation of the Gaussian smoothing kernel used to construct the spin images. */ + inline float + getSmoothingBandwith () { return (sigma_); }; + + + /** \brief Estimate the intensity-domain descriptors at a set of points given by + * using the surface in setSearchSurface (), and the spatial locator in setSearchMethod (). + * \param[out] output the resultant point cloud model dataset that contains the intensity-domain spin image features + */ + void + computeFeature (PointCloudOut &output); + + /** \brief The number of distance bins in the descriptor. */ + int nr_distance_bins_; + + /** \brief The number of intensity bins in the descriptor. */ + int nr_intensity_bins_; + + /** \brief The standard deviation of the Gaussian smoothing kernel used to construct the spin images. */ + float sigma_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // #ifndef PCL_INTENSITY_SPIN_H_ diff --git a/pcl-1.7/pcl/features/linear_least_squares_normal.h b/pcl-1.7/pcl/features/linear_least_squares_normal.h new file mode 100644 index 0000000..dbe5ca2 --- /dev/null +++ b/pcl-1.7/pcl/features/linear_least_squares_normal.h @@ -0,0 +1,152 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_LINEAR_LEAST_SQUARES_NORMAL_H_ +#define PCL_FEATURES_LINEAR_LEAST_SQUARES_NORMAL_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief Surface normal estimation on dense data using a least-squares estimation based on a first-order Taylor approximation. + * \author Stefan Holzer, Cedric Cagniart + */ + template + class LinearLeastSquaresNormalEstimation : public Feature + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + typedef typename Feature::PointCloudIn PointCloudIn; + typedef typename Feature::PointCloudOut PointCloudOut; + using Feature::input_; + using Feature::feature_name_; + using Feature::tree_; + using Feature::k_; + + /** \brief Constructor */ + LinearLeastSquaresNormalEstimation () : + use_depth_dependent_smoothing_(false), + max_depth_change_factor_(1.0f), + normal_smoothing_size_(9.0f) + { + feature_name_ = "LinearLeastSquaresNormalEstimation"; + tree_.reset (); + k_ = 1; + }; + + /** \brief Destructor */ + virtual ~LinearLeastSquaresNormalEstimation (); + + /** \brief Computes the normal at the specified position. + * \param[in] pos_x x position (pixel) + * \param[in] pos_y y position (pixel) + * \param[out] normal the output estimated normal + */ + void + computePointNormal (const int pos_x, const int pos_y, PointOutT &normal); + + /** \brief Set the normal smoothing size + * \param[in] normal_smoothing_size factor which influences the size of the area used to smooth normals + * (depth dependent if useDepthDependentSmoothing is true) + */ + void + setNormalSmoothingSize (float normal_smoothing_size) + { + normal_smoothing_size_ = normal_smoothing_size; + } + + /** \brief Set whether to use depth depending smoothing or not + * \param[in] use_depth_dependent_smoothing decides whether the smoothing is depth dependent + */ + void + setDepthDependentSmoothing (bool use_depth_dependent_smoothing) + { + use_depth_dependent_smoothing_ = use_depth_dependent_smoothing; + } + + /** \brief The depth change threshold for computing object borders + * \param[in] max_depth_change_factor the depth change threshold for computing object borders based on + * depth changes + */ + void + setMaxDepthChangeFactor (float max_depth_change_factor) + { + max_depth_change_factor_ = max_depth_change_factor; + } + + /** \brief Provide a pointer to the input dataset (overwrites the PCLBase::setInputCloud method) + * \param[in] cloud the const boost shared pointer to a PointCloud message + */ + virtual inline void + setInputCloud (const typename PointCloudIn::ConstPtr &cloud) + { + input_ = cloud; + } + + protected: + /** \brief Computes the normal for the complete cloud. + * \param[out] output the resultant normals + */ + void + computeFeature (PointCloudOut &output); + + private: + + /** the threshold used to detect depth discontinuities */ + //float distance_threshold_; + + /** \brief Smooth data based on depth (true/false). */ + bool use_depth_dependent_smoothing_; + + /** \brief Threshold for detecting depth discontinuities */ + float max_depth_change_factor_; + + /** \brief */ + float normal_smoothing_size_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif + diff --git a/pcl-1.7/pcl/features/moment_invariants.h b/pcl-1.7/pcl/features/moment_invariants.h new file mode 100644 index 0000000..047e27d --- /dev/null +++ b/pcl-1.7/pcl/features/moment_invariants.h @@ -0,0 +1,121 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_MOMENT_INVARIANTS_H_ +#define PCL_MOMENT_INVARIANTS_H_ + +#include + +namespace pcl +{ + /** \brief MomentInvariantsEstimation estimates the 3 moment invariants (j1, j2, j3) at each 3D point. + * + * \note The code is stateful as we do not expect this class to be multicore parallelized. Please look at + * \ref NormalEstimationOMP for an example on how to extend this to parallel implementations. + * \author Radu B. Rusu + * \ingroup features + */ + template + class MomentInvariantsEstimation: public Feature + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::k_; + using Feature::search_parameter_; + using Feature::surface_; + using Feature::input_; + + typedef typename Feature::PointCloudOut PointCloudOut; + + /** \brief Empty constructor. */ + MomentInvariantsEstimation () : xyz_centroid_ (), temp_pt_ () + { + feature_name_ = "MomentInvariantsEstimation"; + }; + + /** \brief Compute the 3 moment invariants (j1, j2, j3) for a given set of points, using their indices. + * \param[in] cloud the input point cloud + * \param[in] indices the point cloud indices that need to be used + * \param[out] j1 the resultant first moment invariant + * \param[out] j2 the resultant second moment invariant + * \param[out] j3 the resultant third moment invariant + */ + void + computePointMomentInvariants (const pcl::PointCloud &cloud, + const std::vector &indices, + float &j1, float &j2, float &j3); + + /** \brief Compute the 3 moment invariants (j1, j2, j3) for a given set of points, using their indices. + * \param[in] cloud the input point cloud + * \param[out] j1 the resultant first moment invariant + * \param[out] j2 the resultant second moment invariant + * \param[out] j3 the resultant third moment invariant + */ + void + computePointMomentInvariants (const pcl::PointCloud &cloud, + float &j1, float &j2, float &j3); + + protected: + + /** \brief Estimate moment invariants for all points given in using the surface + * in setSearchSurface () and the spatial locator in setSearchMethod () + * \param[out] output the resultant point cloud model dataset that contains the moment invariants + */ + void + computeFeature (PointCloudOut &output); + + private: + /** \brief 16-bytes aligned placeholder for the XYZ centroid of a surface patch. */ + Eigen::Vector4f xyz_centroid_; + + /** \brief Internal data vector. */ + Eigen::Vector4f temp_pt_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_MOMENT_INVARIANTS_H_ diff --git a/pcl-1.7/pcl/features/moment_of_inertia_estimation.h b/pcl-1.7/pcl/features/moment_of_inertia_estimation.h new file mode 100644 index 0000000..e36c128 --- /dev/null +++ b/pcl-1.7/pcl/features/moment_of_inertia_estimation.h @@ -0,0 +1,362 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : Sergey Ushakov + * Email : sergey.s.ushakov@mail.ru + * + */ + +#ifndef PCL_MOMENT_OF_INERTIA_ESIMATION_H_ +#define PCL_MOMENT_OF_INERTIA_ESIMATION_H_ + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief + * Implements the method for extracting features based on moment of inertia. It also + * calculates AABB, OBB and eccentricity of the projected cloud. + */ + template + class PCL_EXPORTS MomentOfInertiaEstimation : public pcl::PCLBase + { + public: + + using PCLBase ::input_; + using PCLBase ::indices_; + using PCLBase ::fake_indices_; + using PCLBase ::use_indices_; + using PCLBase ::initCompute; + using PCLBase ::deinitCompute; + + typedef typename pcl::PCLBase ::PointCloudConstPtr PointCloudConstPtr; + typedef typename pcl::PCLBase ::PointIndicesConstPtr PointIndicesConstPtr; + + public: + + /** \brief Provide a pointer to the input dataset + * \param[in] cloud the const boost shared pointer to a PointCloud message + */ + virtual void + setInputCloud (const PointCloudConstPtr& cloud); + + /** \brief Provide a pointer to the vector of indices that represents the input data. + * \param[in] indices a pointer to the vector of indices that represents the input data. + */ + virtual void + setIndices (const IndicesPtr& indices); + + /** \brief Provide a pointer to the vector of indices that represents the input data. + * \param[in] indices a pointer to the vector of indices that represents the input data. + */ + virtual void + setIndices (const IndicesConstPtr& indices); + + /** \brief Provide a pointer to the vector of indices that represents the input data. + * \param[in] indices a pointer to the vector of indices that represents the input data. + */ + virtual void + setIndices (const PointIndicesConstPtr& indices); + + /** \brief Set the indices for the points laying within an interest region of + * the point cloud. + * \note you shouldn't call this method on unorganized point clouds! + * \param[in] row_start the offset on rows + * \param[in] col_start the offset on columns + * \param[in] nb_rows the number of rows to be considered row_start included + * \param[in] nb_cols the number of columns to be considered col_start included + */ + virtual void + setIndices (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols); + + /** \brief Constructor that sets default values for member variables. */ + MomentOfInertiaEstimation (); + + /** \brief Virtual destructor which frees the memory. */ + virtual + ~MomentOfInertiaEstimation (); + + /** \brief This method allows to set the angle step. It is used for the rotation + * of the axis which is used for moment of inertia/eccentricity calculation. + * \param[in] step angle step + */ + void + setAngleStep (const float step); + + /** \brief Returns the angle step. */ + float + getAngleStep () const; + + /** \brief This method allows to set the normalize_ flag. If set to false, then + * point_mass_ will be used to scale the moment of inertia values. Otherwise, + * point_mass_ will be set to 1 / number_of_points. Default value is true. + * \param[in] need_to_normalize desired value + */ + void + setNormalizePointMassFlag (bool need_to_normalize); + + /** \brief Returns the normalize_ flag. */ + bool + getNormalizePointMassFlag () const; + + /** \brief This method allows to set point mass that will be used for + * moment of inertia calculation. It is needed to scale moment of inertia values. + * default value is 0.0001. + * \param[in] point_mass point mass + */ + void + setPointMass (const float point_mass); + + /** \brief Returns the mass of point. */ + float + getPointMass () const; + + /** \brief This method launches the computation of all features. After execution + * it sets is_valid_ flag to true and each feature can be accessed with the + * corresponding get method. + */ + void + compute (); + + /** \brief This method gives access to the computed axis aligned bounding box. It returns true + * if the current values (eccentricity, moment of inertia etc) are valid and false otherwise. + * \param[out] min_point min point of the AABB + * \param[out] max_point max point of the AABB + */ + bool + getAABB (PointT& min_point, PointT& max_point) const; + + /** \brief This method gives access to the computed oriented bounding box. It returns true + * if the current values (eccentricity, moment of inertia etc) are valid and false otherwise. + * Note that in order to get the OBB, each vertex of the given AABB (specified with min_point and max_point) + * must be rotated with the given rotational matrix (rotation transform) and then positioned. + * Also pay attention to the fact that this is not the minimal possible bounding box. This is the bounding box + * which is oriented in accordance with the eigen vectors. + * \param[out] min_point min point of the OBB + * \param[out] max_point max point of the OBB + * \param[out] position position of the OBB + * \param[out] rotational_matrix this matrix represents the rotation transform + */ + bool + getOBB (PointT& min_point, PointT& max_point, PointT& position, Eigen::Matrix3f& rotational_matrix) const; + + /** \brief This method gives access to the computed eigen values. It returns true + * if the current values (eccentricity, moment of inertia etc) are valid and false otherwise. + * \param[out] major major eigen value + * \param[out] middle middle eigen value + * \param[out] minor minor eigen value + */ + bool + getEigenValues (float& major, float& middle, float& minor) const; + + /** \brief This method gives access to the computed eigen vectors. It returns true + * if the current values (eccentricity, moment of inertia etc) are valid and false otherwise. + * \param[out] major axis which corresponds to the eigen vector with the major eigen value + * \param[out] middle axis which corresponds to the eigen vector with the middle eigen value + * \param[out] minor axis which corresponds to the eigen vector with the minor eigen value + */ + bool + getEigenVectors (Eigen::Vector3f& major, Eigen::Vector3f& middle, Eigen::Vector3f& minor) const; + + /** \brief This method gives access to the computed moments of inertia. It returns true + * if the current values (eccentricity, moment of inertia etc) are valid and false otherwise. + * \param[out] moment_of_inertia computed moments of inertia + */ + bool + getMomentOfInertia (std::vector & moment_of_inertia) const; + + /** \brief This method gives access to the computed ecentricities. It returns true + * if the current values (eccentricity, moment of inertia etc) are valid and false otherwise. + * \param[out] eccentricity computed eccentricities + */ + bool + getEccentricity (std::vector & eccentricity) const; + + /** \brief This method gives access to the computed mass center. It returns true + * if the current values (eccentricity, moment of inertia etc) are valid and false otherwise. + * Note that when mass center of a cloud is computed, mass point is always considered equal 1. + * \param[out] mass_center computed mass center + */ + bool + getMassCenter (Eigen::Vector3f& mass_center) const; + + private: + + /** \brief This method rotates the given vector around the given axis. + * \param[in] vector vector that must be rotated + * \param[in] axis axis around which vector must be rotated + * \param[in] angle angle in degrees + * \param[out] rotated_vector resultant vector + */ + void + rotateVector (const Eigen::Vector3f& vector, const Eigen::Vector3f& axis, const float angle, Eigen::Vector3f& rotated_vector) const; + + /** \brief This method computes center of mass and axis aligned bounding box. */ + void + computeMeanValue (); + + /** \brief This method computes the oriented bounding box. */ + void + computeOBB (); + + /** \brief This method computes the covariance matrix for the input_ cloud. + * \param[out] covariance_matrix stores the computed covariance matrix + */ + void + computeCovarianceMatrix (Eigen::Matrix & covariance_matrix) const; + + /** \brief This method computes the covariance matrix for the given cloud. + * It uses all points in the cloud, unlike the previous method that uses indices. + * \param[in] cloud cloud for which covariance matrix will be computed + * \param[out] covariance_matrix stores the computed covariance matrix + */ + void + computeCovarianceMatrix (PointCloudConstPtr cloud, Eigen::Matrix & covariance_matrix) const; + + /** \brief This method calculates the eigen values and eigen vectors + * for the given covariance matrix. Note that it returns normalized eigen + * vectors that always form the right-handed coordinate system. + * \param[in] covariance_matrix covariance matrix + * \param[out] major_axis eigen vector which corresponds to a major eigen value + * \param[out] middle_axis eigen vector which corresponds to a middle eigen value + * \param[out] minor_axis eigen vector which corresponds to a minor eigen value + * \param[out] major_value major eigen value + * \param[out] middle_value middle eigen value + * \param[out] minor_value minor eigen value + */ + void + computeEigenVectors (const Eigen::Matrix & covariance_matrix, Eigen::Vector3f& major_axis, + Eigen::Vector3f& middle_axis, Eigen::Vector3f& minor_axis, float& major_value, float& middle_value, + float& minor_value); + + /** \brief This method returns the moment of inertia of a given input_ cloud. + * Note that when moment of inertia is computed it is multiplied by the point mass. + * Point mass can be accessed with the corresponding get/set methods. + * \param[in] current_axis axis that will be used in moment of inertia computation + * \param[in] mean_value mean value(center of mass) of the cloud + */ + float + calculateMomentOfInertia (const Eigen::Vector3f& current_axis, const Eigen::Vector3f& mean_value) const; + + /** \brief This method simply projects the given input_ cloud on the plane specified with + * the normal vector. + * \param[in] normal_vector nrmal vector of the plane + * \param[in] point point belonging to the plane + * \param[out] projected_cloud projected cloud + */ + void + getProjectedCloud (const Eigen::Vector3f& normal_vector, const Eigen::Vector3f& point, typename pcl::PointCloud ::Ptr projected_cloud) const; + + /** \brief This method returns the eccentricity of the projected cloud. + * \param[in] covariance_matrix covariance matrix of the projected cloud + * \param[in] normal_vector normal vector of the plane, it is used to discard the + * third eigen vector and eigen value*/ + float + computeEccentricity (const Eigen::Matrix & covariance_matrix, const Eigen::Vector3f& normal_vector); + + private: + + /** \brief Indicates if the stored values (eccentricity, moment of inertia, AABB etc.) + * are valid when accessed with the get methods. */ + bool is_valid_; + + /** \brief Stores the angle step */ + float step_; + + /** \brief Stores the mass of point in the cloud */ + float point_mass_; + + /** \brief Stores the flag for mass normalization */ + bool normalize_; + + /** \brief Stores the mean value (center of mass) of the cloud */ + Eigen::Vector3f mean_value_; + + /** \brief Major eigen vector */ + Eigen::Vector3f major_axis_; + + /** \brief Middle eigen vector */ + Eigen::Vector3f middle_axis_; + + /** \brief Minor eigen vector */ + Eigen::Vector3f minor_axis_; + + /** \brief Major eigen value */ + float major_value_; + + /** \brief Middle eigen value */ + float middle_value_; + + /** \brief Minor eigen value */ + float minor_value_; + + /** \brief Stores calculated moments of inertia */ + std::vector moment_of_inertia_; + + /** \brief Stores calculated eccentricities */ + std::vector eccentricity_; + + /** \brief Min point of the axis aligned bounding box */ + PointT aabb_min_point_; + + /** \brief Max point of the axis aligned bounding box */ + PointT aabb_max_point_; + + /** \brief Min point of the oriented bounding box */ + PointT obb_min_point_; + + /** \brief Max point of the oriented bounding box */ + PointT obb_max_point_; + + /** \brief Stores position of the oriented bounding box */ + Eigen::Vector3f obb_position_; + + /** \brief Stores the rotational matrix of the oriented bounding box */ + Eigen::Matrix3f obb_rotational_matrix_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#define PCL_INSTANTIATE_MomentOfInertiaEstimation(T) template class pcl::MomentOfInertiaEstimation; + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/features/multiscale_feature_persistence.h b/pcl-1.7/pcl/features/multiscale_feature_persistence.h new file mode 100644 index 0000000..0beea6b --- /dev/null +++ b/pcl-1.7/pcl/features/multiscale_feature_persistence.h @@ -0,0 +1,209 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_MULTISCALE_FEATURE_PERSISTENCE_H_ +#define PCL_MULTISCALE_FEATURE_PERSISTENCE_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Generic class for extracting the persistent features from an input point cloud + * It can be given any Feature estimator instance and will compute the features of the input + * over a multiscale representation of the cloud and output the unique ones over those scales. + * + * Please refer to the following publication for more details: + * Radu Bogdan Rusu, Zoltan Csaba Marton, Nico Blodow, and Michael Beetz + * Persistent Point Feature Histograms for 3D Point Clouds + * Proceedings of the 10th International Conference on Intelligent Autonomous Systems (IAS-10) + * 2008, Baden-Baden, Germany + * + * \author Alexandru-Eugen Ichim + */ + template + class MultiscaleFeaturePersistence : public PCLBase + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + typedef pcl::PointCloud FeatureCloud; + typedef typename pcl::PointCloud::Ptr FeatureCloudPtr; + typedef typename pcl::Feature::Ptr FeatureEstimatorPtr; + typedef boost::shared_ptr > FeatureRepresentationConstPtr; + + using pcl::PCLBase::input_; + + /** \brief Empty constructor */ + MultiscaleFeaturePersistence (); + + /** \brief Empty destructor */ + virtual ~MultiscaleFeaturePersistence () {} + + /** \brief Method that calls computeFeatureAtScale () for each scale parameter */ + void + computeFeaturesAtAllScales (); + + /** \brief Central function that computes the persistent features + * \param output_features a cloud containing the persistent features + * \param output_indices vector containing the indices of the points in the input cloud + * that have persistent features, under a one-to-one correspondence with the output_features cloud + */ + void + determinePersistentFeatures (FeatureCloud &output_features, + boost::shared_ptr > &output_indices); + + /** \brief Method for setting the scale parameters for the algorithm + * \param scale_values vector of scales to determine the characteristic of each scaling step + */ + inline void + setScalesVector (std::vector &scale_values) { scale_values_ = scale_values; } + + /** \brief Method for getting the scale parameters vector */ + inline std::vector + getScalesVector () { return scale_values_; } + + /** \brief Setter method for the feature estimator + * \param feature_estimator pointer to the feature estimator instance that will be used + * \note the feature estimator instance should already have the input data given beforehand + * and everything set, ready to be given the compute () command + */ + inline void + setFeatureEstimator (FeatureEstimatorPtr feature_estimator) { feature_estimator_ = feature_estimator; }; + + /** \brief Getter method for the feature estimator */ + inline FeatureEstimatorPtr + getFeatureEstimator () { return feature_estimator_; } + + /** \brief Provide a pointer to the feature representation to use to convert features to k-D vectors. + * \param feature_representation the const boost shared pointer to a PointRepresentation + */ + inline void + setPointRepresentation (const FeatureRepresentationConstPtr& feature_representation) { feature_representation_ = feature_representation; } + + /** \brief Get a pointer to the feature representation used when converting features into k-D vectors. */ + inline FeatureRepresentationConstPtr const + getPointRepresentation () { return feature_representation_; } + + /** \brief Sets the alpha parameter + * \param alpha value to replace the current alpha with + */ + inline void + setAlpha (float alpha) { alpha_ = alpha; } + + /** \brief Get the value of the alpha parameter */ + inline float + getAlpha () { return alpha_; } + + /** \brief Method for setting the distance metric that will be used for computing the difference between feature vectors + * \param distance_metric the new distance metric chosen from the NormType enum + */ + inline void + setDistanceMetric (NormType distance_metric) { distance_metric_ = distance_metric; } + + /** \brief Returns the distance metric that is currently used to calculate the difference between feature vectors */ + inline NormType + getDistanceMetric () { return distance_metric_; } + + + private: + /** \brief Checks if all the necessary input was given and the computations can successfully start */ + bool + initCompute (); + + + /** \brief Method to compute the features for the point cloud at the given scale */ + virtual void + computeFeatureAtScale (float &scale, + FeatureCloudPtr &features); + + + /** \brief Function that calculates the scalar difference between two features + * \return the difference as a floating point type + */ + float + distanceBetweenFeatures (const std::vector &a, + const std::vector &b); + + /** \brief Method that averages all the features at all scales in order to obtain the global mean feature; + * this value is stored in the mean_feature field + */ + void + calculateMeanFeature (); + + /** \brief Selects the so-called 'unique' features from the cloud of features at each level. + * These features are the ones that fall outside the standard deviation * alpha_ + */ + void + extractUniqueFeatures (); + + + /** \brief The general parameter for determining each scale level */ + std::vector scale_values_; + + /** \brief Parameter that determines if a feature is to be considered unique or not */ + float alpha_; + + /** \brief Parameter that determines which distance metric is to be usedto calculate the difference between feature vectors */ + NormType distance_metric_; + + /** \brief the feature estimator that will be used to determine the feature set at each scale level */ + FeatureEstimatorPtr feature_estimator_; + + std::vector features_at_scale_; + std::vector > > features_at_scale_vectorized_; + std::vector mean_feature_; + FeatureRepresentationConstPtr feature_representation_; + + /** \brief Two structures in which to hold the results of the unique feature extraction process. + * They are superfluous with respect to each other, but improve the time performance of the algorithm + */ + std::vector > unique_features_indices_; + std::vector > unique_features_table_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif /* PCL_MULTISCALE_FEATURE_PERSISTENCE_H_ */ diff --git a/pcl-1.7/pcl/features/narf.h b/pcl-1.7/pcl/features/narf.h new file mode 100644 index 0000000..335c44f --- /dev/null +++ b/pcl-1.7/pcl/features/narf.h @@ -0,0 +1,293 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_NARF_H_ +#define PCL_NARF_H_ + +#include +#include +#include + +namespace pcl +{ + // Forward declarations + class RangeImage; + struct InterestPoint; + +#define NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE 10 + + /** + * \brief NARF (Normal Aligned Radial Features) is a point feature descriptor type for 3D data. + * Please refer to pcl/features/narf_descriptor.h if you want the class derived from pcl Feature. + * See B. Steder, R. B. Rusu, K. Konolige, and W. Burgard + * Point Feature Extraction on 3D Range Scans Taking into Account Object Boundaries + * In Proc. of the IEEE Int. Conf. on Robotics &Automation (ICRA). 2011. + * \author Bastian Steder + * \ingroup features + */ + class PCL_EXPORTS Narf + { + public: + // =====CONSTRUCTOR & DESTRUCTOR===== + //! Constructor + Narf(); + //! Copy Constructor + Narf(const Narf& other); + //! Destructor + ~Narf(); + + // =====Operators===== + //! Assignment operator + const Narf& operator=(const Narf& other); + + // =====STATIC===== + /** The maximum number of openmp threads that can be used in this class */ + static int max_no_of_threads; + + /** Add features extracted at the given interest point and add them to the list */ + static void + extractFromRangeImageAndAddToList (const RangeImage& range_image, const Eigen::Vector3f& interest_point, int descriptor_size, + float support_size, bool rotation_invariant, std::vector& feature_list); + /** Same as above */ + static void + extractFromRangeImageAndAddToList (const RangeImage& range_image, float image_x, float image_y, int descriptor_size, + float support_size, bool rotation_invariant, std::vector& feature_list); + /** Get a list of features from the given interest points. */ + static void + extractForInterestPoints (const RangeImage& range_image, const PointCloud& interest_points, + int descriptor_size, float support_size, bool rotation_invariant, std::vector& feature_list); + /** Extract an NARF for every point in the range image. */ + static void + extractForEveryRangeImagePointAndAddToList (const RangeImage& range_image, int descriptor_size, float support_size, + bool rotation_invariant, std::vector& feature_list); + + // =====PUBLIC METHODS===== + /** Method to extract a NARF feature from a certain 3D point using a range image. + * pose determines the coordinate system of the feature, whereas it transforms a point from the world into the feature system. + * This means the interest point at which the feature is extracted will be the inverse application of pose onto (0,0,0). + * descriptor_size_ determines the size of the descriptor, + * support_size determines the support size of the feature, meaning the size in the world it covers */ + bool + extractFromRangeImage (const RangeImage& range_image, const Eigen::Affine3f& pose, int descriptor_size, float support_size, + int surface_patch_world_size=NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE); + + //! Same as above, but determines the transformation from the surface in the range image + bool + extractFromRangeImage (const RangeImage& range_image, float x, float y, int descriptor_size, float support_size); + + //! Same as above + bool + extractFromRangeImage (const RangeImage& range_image, const InterestPoint& interest_point, int descriptor_size, float support_size); + + //! Same as above + bool + extractFromRangeImage (const RangeImage& range_image, const Eigen::Vector3f& interest_point, int descriptor_size, float support_size); + + /** Same as above, but using the rotational invariant version by choosing the best extracted rotation around the normal. + * Use extractFromRangeImageAndAddToList if you want to enable the system to return multiple features with different rotations. */ + bool + extractFromRangeImageWithBestRotation (const RangeImage& range_image, const Eigen::Vector3f& interest_point, + int descriptor_size, float support_size); + + /* Get the dominant rotations of the current descriptor + * \param rotations the returned rotations + * \param strength values describing how pronounced the corresponding rotations are + */ + void + getRotations (std::vector& rotations, std::vector& strengths) const; + + /* Get the feature with a different rotation around the normal + * You are responsible for deleting the new features! + * \param range_image the source from which the feature is extracted + * \param rotations list of angles (in radians) + * \param rvps returned features + */ + void + getRotatedVersions (const RangeImage& range_image, const std::vector& rotations, std::vector& features) const; + + //! Calculate descriptor distance, value in [0,1] with 0 meaning identical and 1 every cell above maximum distance + inline float + getDescriptorDistance (const Narf& other) const; + + //! How many points on each beam of the gradient star are used to calculate the descriptor? + inline int + getNoOfBeamPoints () const { return (static_cast (pcl_lrint (ceil (0.5f * float (surface_patch_pixel_size_))))); } + + //! Copy the descriptor and pose to the point struct Narf36 + inline void + copyToNarf36 (Narf36& narf36) const; + + /** Write to file */ + void + saveBinary (const std::string& filename) const; + /** Write to output stream */ + void + saveBinary (std::ostream& file) const; + + /** Read from file */ + void + loadBinary (const std::string& filename); + /** Read from input stream */ + void + loadBinary (std::istream& file); + + //! Create the descriptor from the already set other members + bool + extractDescriptor (int descriptor_size); + + // =====GETTERS===== + //! Getter (const) for the descriptor + inline const float* + getDescriptor () const { return descriptor_;} + //! Getter for the descriptor + inline float* + getDescriptor () { return descriptor_;} + //! Getter (const) for the descriptor length + inline const int& + getDescriptorSize () const { return descriptor_size_;} + //! Getter for the descriptor length + inline int& + getDescriptorSize () { return descriptor_size_;} + //! Getter (const) for the position + inline const Eigen::Vector3f& + getPosition () const { return position_;} + //! Getter for the position + inline Eigen::Vector3f& + getPosition () { return position_;} + //! Getter (const) for the 6DoF pose + inline const Eigen::Affine3f& + getTransformation () const { return transformation_;} + //! Getter for the 6DoF pose + inline Eigen::Affine3f& + getTransformation () { return transformation_;} + //! Getter (const) for the pixel size of the surface patch (only one dimension) + inline const int& + getSurfacePatchPixelSize () const { return surface_patch_pixel_size_;} + //! Getter for the pixel size of the surface patch (only one dimension) + inline int& + getSurfacePatchPixelSize () { return surface_patch_pixel_size_;} + //! Getter (const) for the world size of the surface patch + inline const float& + getSurfacePatchWorldSize () const { return surface_patch_world_size_;} + //! Getter for the world size of the surface patch + inline float& + getSurfacePatchWorldSize () { return surface_patch_world_size_;} + //! Getter (const) for the rotation of the surface patch + inline const float& + getSurfacePatchRotation () const { return surface_patch_rotation_;} + //! Getter for the rotation of the surface patch + inline float& + getSurfacePatchRotation () { return surface_patch_rotation_;} + //! Getter (const) for the surface patch + inline const float* + getSurfacePatch () const { return surface_patch_;} + //! Getter for the surface patch + inline float* + getSurfacePatch () { return surface_patch_;} + //! Method to erase the surface patch and free the memory + inline void + freeSurfacePatch () { delete[] surface_patch_; surface_patch_=NULL; surface_patch_pixel_size_=0; } + + // =====SETTERS===== + //! Setter for the descriptor + inline void + setDescriptor (float* descriptor) { descriptor_ = descriptor;} + //! Setter for the surface patch + inline void + setSurfacePatch (float* surface_patch) { surface_patch_ = surface_patch;} + + // =====PUBLIC MEMBER VARIABLES===== + + // =====PUBLIC STRUCTS===== + struct FeaturePointRepresentation : public PointRepresentation + { + typedef Narf* PointT; + FeaturePointRepresentation(int nr_dimensions) { this->nr_dimensions_ = nr_dimensions; } + /** \brief Empty destructor */ + virtual ~FeaturePointRepresentation () {} + virtual void copyToFloatArray (const PointT& p, float* out) const { memcpy(out, p->getDescriptor(), sizeof(*p->getDescriptor())*this->nr_dimensions_); } + }; + + protected: + // =====PROTECTED METHODS===== + //! Reset al members to default values and free allocated memory + void + reset (); + //! Create a deep copy of other + void + deepCopy (const Narf& other); + //! Get the surface patch with a blur on it + float* + getBlurredSurfacePatch (int new_pixel_size, int blur_radius) const; + + /** Write header to output stream */ + void + saveHeader (std::ostream& file) const; + /** Read header from input stream */ + int + loadHeader (std::istream& file) const; + + // =====PROTECTED STATIC METHODS===== + static const std::string + getHeaderKeyword () { return "NARF"; } + + // =====PROTECTED STATIC VARIABLES===== + const static int VERSION = 1; + + // =====PROTECTED MEMBER VARIABLES===== + Eigen::Vector3f position_; + Eigen::Affine3f transformation_; + float* surface_patch_; + int surface_patch_pixel_size_; + float surface_patch_world_size_; + float surface_patch_rotation_; + float* descriptor_; + int descriptor_size_; + + // =====STATIC PROTECTED===== + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +#undef NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE + +} // end namespace pcl + +#include + +#endif //#ifndef PCL_NARF_H_ diff --git a/pcl-1.7/pcl/features/narf_descriptor.h b/pcl-1.7/pcl/features/narf_descriptor.h new file mode 100644 index 0000000..7c9ebd4 --- /dev/null +++ b/pcl-1.7/pcl/features/narf_descriptor.h @@ -0,0 +1,111 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_NARF_DESCRIPTOR_H_ +#define PCL_NARF_DESCRIPTOR_H_ + +#include +#include + +#if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 +#pragma GCC diagnostic ignored "-Weffc++" +#endif +namespace pcl +{ + // Forward declarations + class RangeImage; + + /** @b Computes NARF feature descriptors for points in a range image + * See B. Steder, R. B. Rusu, K. Konolige, and W. Burgard + * Point Feature Extraction on 3D Range Scans Taking into Account Object Boundaries + * In Proc. of the IEEE Int. Conf. on Robotics &Automation (ICRA). 2011. + * \author Bastian Steder + * \ingroup features + */ + class PCL_EXPORTS NarfDescriptor : public Feature + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + // =====TYPEDEFS===== + typedef Feature BaseClass; + + // =====STRUCTS/CLASSES===== + struct Parameters + { + Parameters() : support_size(-1.0f), rotation_invariant(true) {} + float support_size; + bool rotation_invariant; + }; + + // =====CONSTRUCTOR & DESTRUCTOR===== + /** Constructor */ + NarfDescriptor (const RangeImage* range_image=NULL, const std::vector* indices=NULL); + /** Destructor */ + virtual ~NarfDescriptor(); + + // =====METHODS===== + //! Set input data + void + setRangeImage (const RangeImage* range_image, const std::vector* indices=NULL); + + //! Overwrite the compute function of the base class + void + compute (PointCloudOut& output); + + // =====GETTER===== + //! Get a reference to the parameters struct + Parameters& + getParameters () { return parameters_;} + + protected: + // =====PROTECTED MEMBER VARIABLES===== + const RangeImage* range_image_; + Parameters parameters_; + + // =====PROTECTED METHODS===== + /** Implementation of abstract derived function */ + virtual void + computeFeature (PointCloudOut& output); + }; + +} // namespace end +#if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 +#pragma GCC diagnostic warning "-Weffc++" +#endif + +#endif //#ifndef PCL_NARF_DESCRIPTOR_H_ diff --git a/pcl-1.7/pcl/features/normal_3d.h b/pcl-1.7/pcl/features/normal_3d.h new file mode 100644 index 0000000..a311ed1 --- /dev/null +++ b/pcl-1.7/pcl/features/normal_3d.h @@ -0,0 +1,427 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_NORMAL_3D_H_ +#define PCL_NORMAL_3D_H_ + +#include +#include + +#include + +namespace pcl +{ + /** \brief Compute the Least-Squares plane fit for a given set of points, and return the estimated plane + * parameters together with the surface curvature. + * \param cloud the input point cloud + * \param plane_parameters the plane parameters as: a, b, c, d (ax + by + cz + d = 0) + * \param curvature the estimated surface curvature as a measure of + * \f[ + * \lambda_0 / (\lambda_0 + \lambda_1 + \lambda_2) + * \f] + * \ingroup features + */ + template inline void + computePointNormal (const pcl::PointCloud &cloud, + Eigen::Vector4f &plane_parameters, float &curvature) + { + // Placeholder for the 3x3 covariance matrix at each surface patch + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix; + // 16-bytes aligned placeholder for the XYZ centroid of a surface patch + Eigen::Vector4f xyz_centroid; + + if (cloud.size () < 3 || + computeMeanAndCovarianceMatrix (cloud, covariance_matrix, xyz_centroid) == 0) + { + plane_parameters.setConstant (std::numeric_limits::quiet_NaN ()); + curvature = std::numeric_limits::quiet_NaN (); + return; + } + + // Get the plane normal and surface curvature + solvePlaneParameters (covariance_matrix, xyz_centroid, plane_parameters, curvature); + } + + /** \brief Compute the Least-Squares plane fit for a given set of points, using their indices, + * and return the estimated plane parameters together with the surface curvature. + * \param cloud the input point cloud + * \param indices the point cloud indices that need to be used + * \param plane_parameters the plane parameters as: a, b, c, d (ax + by + cz + d = 0) + * \param curvature the estimated surface curvature as a measure of + * \f[ + * \lambda_0 / (\lambda_0 + \lambda_1 + \lambda_2) + * \f] + * \ingroup features + */ + template inline void + computePointNormal (const pcl::PointCloud &cloud, const std::vector &indices, + Eigen::Vector4f &plane_parameters, float &curvature) + { + // Placeholder for the 3x3 covariance matrix at each surface patch + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix; + // 16-bytes aligned placeholder for the XYZ centroid of a surface patch + Eigen::Vector4f xyz_centroid; + if (indices.size () < 3 || + computeMeanAndCovarianceMatrix (cloud, indices, covariance_matrix, xyz_centroid) == 0) + { + plane_parameters.setConstant (std::numeric_limits::quiet_NaN ()); + curvature = std::numeric_limits::quiet_NaN (); + return; + } + // Get the plane normal and surface curvature + solvePlaneParameters (covariance_matrix, xyz_centroid, plane_parameters, curvature); + } + + /** \brief Flip (in place) the estimated normal of a point towards a given viewpoint + * \param point a given point + * \param vp_x the X coordinate of the viewpoint + * \param vp_y the X coordinate of the viewpoint + * \param vp_z the X coordinate of the viewpoint + * \param normal the plane normal to be flipped + * \ingroup features + */ + template inline void + flipNormalTowardsViewpoint (const PointT &point, float vp_x, float vp_y, float vp_z, + Eigen::Matrix& normal) + { + Eigen::Matrix vp (vp_x - point.x, vp_y - point.y, vp_z - point.z, 0); + + // Dot product between the (viewpoint - point) and the plane normal + float cos_theta = vp.dot (normal); + + // Flip the plane normal + if (cos_theta < 0) + { + normal *= -1; + normal[3] = 0.0f; + // Hessian form (D = nc . p_plane (centroid here) + p) + normal[3] = -1 * normal.dot (point.getVector4fMap ()); + } + } + + /** \brief Flip (in place) the estimated normal of a point towards a given viewpoint + * \param point a given point + * \param vp_x the X coordinate of the viewpoint + * \param vp_y the X coordinate of the viewpoint + * \param vp_z the X coordinate of the viewpoint + * \param normal the plane normal to be flipped + * \ingroup features + */ + template inline void + flipNormalTowardsViewpoint (const PointT &point, float vp_x, float vp_y, float vp_z, + Eigen::Matrix& normal) + { + Eigen::Matrix vp (vp_x - point.x, vp_y - point.y, vp_z - point.z); + + // Flip the plane normal + if (vp.dot (normal) < 0) + normal *= -1; + } + + /** \brief Flip (in place) the estimated normal of a point towards a given viewpoint + * \param point a given point + * \param vp_x the X coordinate of the viewpoint + * \param vp_y the X coordinate of the viewpoint + * \param vp_z the X coordinate of the viewpoint + * \param nx the resultant X component of the plane normal + * \param ny the resultant Y component of the plane normal + * \param nz the resultant Z component of the plane normal + * \ingroup features + */ + template inline void + flipNormalTowardsViewpoint (const PointT &point, float vp_x, float vp_y, float vp_z, + float &nx, float &ny, float &nz) + { + // See if we need to flip any plane normals + vp_x -= point.x; + vp_y -= point.y; + vp_z -= point.z; + + // Dot product between the (viewpoint - point) and the plane normal + float cos_theta = (vp_x * nx + vp_y * ny + vp_z * nz); + + // Flip the plane normal + if (cos_theta < 0) + { + nx *= -1; + ny *= -1; + nz *= -1; + } + } + + /** \brief NormalEstimation estimates local surface properties (surface normals and curvatures)at each + * 3D point. If PointOutT is specified as pcl::Normal, the normal is stored in the first 3 components (0-2), + * and the curvature is stored in component 3. + * + * \note The code is stateful as we do not expect this class to be multicore parallelized. Please look at + * \ref NormalEstimationOMP for a parallel implementation. + * \author Radu B. Rusu + * \ingroup features + */ + template + class NormalEstimation: public Feature + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::input_; + using Feature::surface_; + using Feature::k_; + using Feature::search_radius_; + using Feature::search_parameter_; + + typedef typename Feature::PointCloudOut PointCloudOut; + typedef typename Feature::PointCloudConstPtr PointCloudConstPtr; + + using Feature::points_target_; // target + using Feature::points_target_ptr_; // target + using Feature::index_target_; + using Feature::index_target_ptr_; + + using Feature::treeH_target_; // pointer to tree + using Feature::max_leaf_size_; // max leaf size + using Feature::setMaxLeafSize; + using Feature::buildHKdTree_target; + + /** \brief Empty constructor. */ + NormalEstimation () + : vpx_ (0) + , vpy_ (0) + , vpz_ (0) + , covariance_matrix_ () + , xyz_centroid_ () + , use_sensor_origin_ (true) + , use_customized_tree_ (false) + , approx_radius_ops_num_(0) + , approx_leaders_num_(0) + , approx_followers_num_(0) + , save_approx_data_(false) + { + feature_name_ = "NormalEstimation"; + }; + + /** \brief Empty destructor */ + virtual ~NormalEstimation () + { + delete treeH_target_; + } + + /** \brief Compute the Least-Squares plane fit for a given set of points, using their indices, + * and return the estimated plane parameters together with the surface curvature. + * \param cloud the input point cloud + * \param indices the point cloud indices that need to be used + * \param plane_parameters the plane parameters as: a, b, c, d (ax + by + cz + d = 0) + * \param curvature the estimated surface curvature as a measure of + * \f[ + * \lambda_0 / (\lambda_0 + \lambda_1 + \lambda_2) + * \f] + */ + inline void + computePointNormal (const pcl::PointCloud &cloud, const std::vector &indices, + Eigen::Vector4f &plane_parameters, float &curvature) + { + if (indices.size () < 3 || + computeMeanAndCovarianceMatrix (cloud, indices, covariance_matrix_, xyz_centroid_) == 0) + { + plane_parameters.setConstant (std::numeric_limits::quiet_NaN ()); + curvature = std::numeric_limits::quiet_NaN (); + return; + } + + // Get the plane normal and surface curvature + solvePlaneParameters (covariance_matrix_, xyz_centroid_, plane_parameters, curvature); + } + + /** \brief Compute the Least-Squares plane fit for a given set of points, using their indices, + * and return the estimated plane parameters together with the surface curvature. + * \param cloud the input point cloud + * \param indices the point cloud indices that need to be used + * \param nx the resultant X component of the plane normal + * \param ny the resultant Y component of the plane normal + * \param nz the resultant Z component of the plane normal + * \param curvature the estimated surface curvature as a measure of + * \f[ + * \lambda_0 / (\lambda_0 + \lambda_1 + \lambda_2) + * \f] + */ + inline void + computePointNormal (const pcl::PointCloud &cloud, const std::vector &indices, + float &nx, float &ny, float &nz, float &curvature) + { + if (indices.size () < 3 || + computeMeanAndCovarianceMatrix (cloud, indices, covariance_matrix_, xyz_centroid_) == 0) + { + nx = ny = nz = curvature = std::numeric_limits::quiet_NaN (); + return; + } + + // Get the plane normal and surface curvature + solvePlaneParameters (covariance_matrix_, nx, ny, nz, curvature); + } + + /** \brief Provide a pointer to the input dataset + * \param cloud the const boost shared pointer to a PointCloud message + */ + virtual inline void + setInputCloud (const PointCloudConstPtr &cloud) + { + input_ = cloud; + if (use_sensor_origin_) + { + vpx_ = input_->sensor_origin_.coeff (0); + vpy_ = input_->sensor_origin_.coeff (1); + vpz_ = input_->sensor_origin_.coeff (2); + } + + } + + /** \brief Set the viewpoint. + * \param vpx the X coordinate of the viewpoint + * \param vpy the Y coordinate of the viewpoint + * \param vpz the Z coordinate of the viewpoint + */ + inline void + setViewPoint (float vpx, float vpy, float vpz) + { + vpx_ = vpx; + vpy_ = vpy; + vpz_ = vpz; + use_sensor_origin_ = false; + } + + /** \brief Get the viewpoint. + * \param [out] vpx x-coordinate of the view point + * \param [out] vpy y-coordinate of the view point + * \param [out] vpz z-coordinate of the view point + * \note this method returns the currently used viewpoint for normal flipping. + * If the viewpoint is set manually using the setViewPoint method, this method will return the set view point coordinates. + * If an input cloud is set, it will return the sensor origin otherwise it will return the origin (0, 0, 0) + */ + inline void + getViewPoint (float &vpx, float &vpy, float &vpz) + { + vpx = vpx_; + vpy = vpy_; + vpz = vpz_; + } + + /** \brief sets whether the sensor origin or a user given viewpoint should be used. After this method, the + * normal estimation method uses the sensor origin of the input cloud. + * to use a user defined view point, use the method setViewPoint + */ + inline void + useSensorOriginAsViewPoint () + { + use_sensor_origin_ = true; + if (input_) + { + vpx_ = input_->sensor_origin_.coeff (0); + vpy_ = input_->sensor_origin_.coeff (1); + vpz_ = input_->sensor_origin_.coeff (2); + } + else + { + vpx_ = 0; + vpy_ = 0; + vpz_ = 0; + } + } + + /** To decide whether to use the customized KD-Tree data structure. **/ + inline void setUseCustomizedKDTree(bool use) { use_customized_tree_ = use;} + + inline void setSaveApproxData(bool save) { save_approx_data_ = save;} + + /** To get approximate search statistics. **/ + inline int getApproxRadiusOpsNum() { return approx_radius_ops_num_; } + inline int getApproxLeadersNum() { return approx_leaders_num_; } + inline int getApproxFollowersNum() { return approx_followers_num_; } + + protected: + /** \brief Estimate normals for all points given in using the surface in + * setSearchSurface () and the spatial locator in setSearchMethod () + * \note In situations where not enough neighbors are found, the normal and curvature values are set to -1. + * \param output the resultant point cloud model dataset that contains surface normals and curvatures + */ + void + computeFeature (PointCloudOut &output); + + /** \brief Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit + * from NormalEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0. */ + float vpx_, vpy_, vpz_; + + /** \brief Placeholder for the 3x3 covariance matrix at each surface patch. */ + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix_; + + /** \brief 16-bytes aligned placeholder for the XYZ centroid of a surface patch. */ + Eigen::Vector4f xyz_centroid_; + + /** whether the sensor origin of the input cloud or a user given viewpoint should be used.*/ + bool use_sensor_origin_; + + /** Whether to use the customized KD-Tree data structure. **/ + bool use_customized_tree_; + + /** Number of operations in the approximation search **/ + int approx_radius_ops_num_; + + /** Number of leaders in the approximation search **/ + int approx_leaders_num_; + + /** Number of leaders in the approximation search **/ + int approx_followers_num_; + + /** Whether save the operations, leaders and followers in approx search**/ + bool save_approx_data_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_NORMAL_3D_H_ + diff --git a/pcl-1.7/pcl/features/normal_3d_omp.h b/pcl-1.7/pcl/features/normal_3d_omp.h new file mode 100644 index 0000000..a7f1771 --- /dev/null +++ b/pcl-1.7/pcl/features/normal_3d_omp.h @@ -0,0 +1,115 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_NORMAL_3D_OMP_H_ +#define PCL_NORMAL_3D_OMP_H_ + +#include + +namespace pcl +{ + /** \brief NormalEstimationOMP estimates local surface properties at each 3D point, such as surface normals and + * curvatures, in parallel, using the OpenMP standard. + * \author Radu Bogdan Rusu + * \ingroup features + */ + template + class NormalEstimationOMP: public NormalEstimation + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using NormalEstimation::feature_name_; + using NormalEstimation::getClassName; + using NormalEstimation::indices_; + using NormalEstimation::input_; + using NormalEstimation::k_; + using NormalEstimation::vpx_; + using NormalEstimation::vpy_; + using NormalEstimation::vpz_; + using NormalEstimation::search_parameter_; + using NormalEstimation::surface_; + using NormalEstimation::getViewPoint; + + typedef typename NormalEstimation::PointCloudOut PointCloudOut; + + public: + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + NormalEstimationOMP (unsigned int nr_threads = 0) : threads_ (nr_threads), + nn_time_ (0.0) + { + feature_name_ = "NormalEstimationOMP"; + } + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + + void getNnTime(float &nn_time) + { + nn_time = nn_time_; + } + + protected: + /** \brief The number of threads the scheduler should use. */ + unsigned int threads_; + + // neighbouring search time + float nn_time_; + + private: + /** \brief Estimate normals for all points given in using the surface in + * setSearchSurface () and the spatial locator in setSearchMethod () + * \param output the resultant point cloud model dataset that contains surface normals and curvatures + */ + void + computeFeature (PointCloudOut &output); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_NORMAL_3D_OMP_H_ diff --git a/pcl-1.7/pcl/features/normal_based_signature.h b/pcl-1.7/pcl/features/normal_based_signature.h new file mode 100644 index 0000000..f5773df --- /dev/null +++ b/pcl-1.7/pcl/features/normal_based_signature.h @@ -0,0 +1,165 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_NORMAL_BASED_SIGNATURE_H_ +#define PCL_NORMAL_BASED_SIGNATURE_H_ + +#include + +namespace pcl +{ + /** \brief Normal-based feature signature estimation class. Obtains the feature vector by applying Discrete Cosine and + * Fourier Transforms on an NxM array of real numbers representing the projection distances of the points in the input + * cloud to a disc around the point of interest. + * Please consult the following publication for more details: + * Xinju Li and Igor Guskov + * Multi-scale features for approximate alignment of point-based surfaces + * Proceedings of the third Eurographics symposium on Geometry processing + * July 2005, Vienna, Austria + * + * \note These features were meant to be used at keypoints detected by a detector using different smoothing radii + * (e.g., SmoothedSurfacesKeypoint) + * \author Alexandru-Eugen Ichim + */ + template + class NormalBasedSignatureEstimation : public FeatureFromNormals + { + public: + using Feature::input_; + using Feature::tree_; + using Feature::search_radius_; + using PCLBase::indices_; + using FeatureFromNormals::normals_; + + typedef pcl::PointCloud FeatureCloud; + typedef typename boost::shared_ptr > Ptr; + typedef typename boost::shared_ptr > ConstPtr; + + + + /** \brief Empty constructor, initializes the internal parameters to the default values + */ + NormalBasedSignatureEstimation () + : FeatureFromNormals (), + scale_h_ (), + N_ (36), + M_ (8), + N_prime_ (4), + M_prime_ (3) + { + } + + /** \brief Setter method for the N parameter - the length of the columns used for the Discrete Fourier Transform. + * \param[in] n the length of the columns used for the Discrete Fourier Transform. + */ + inline void + setN (size_t n) { N_ = n; } + + /** \brief Returns the N parameter - the length of the columns used for the Discrete Fourier Transform. */ + inline size_t + getN () { return N_; } + + /** \brief Setter method for the M parameter - the length of the rows used for the Discrete Cosine Transform. + * \param[in] m the length of the rows used for the Discrete Cosine Transform. + */ + inline void + setM (size_t m) { M_ = m; } + + /** \brief Returns the M parameter - the length of the rows used for the Discrete Cosine Transform */ + inline size_t + getM () { return M_; } + + /** \brief Setter method for the N' parameter - the number of columns to be taken from the matrix of DFT and DCT + * values that will be contained in the output feature vector + * \note This value directly influences the dimensions of the type of output points (PointFeature) + * \param[in] n_prime the number of columns from the matrix of DFT and DCT that will be contained in the output + */ + inline void + setNPrime (size_t n_prime) { N_prime_ = n_prime; } + + /** \brief Returns the N' parameter - the number of rows to be taken from the matrix of DFT and DCT + * values that will be contained in the output feature vector + * \note This value directly influences the dimensions of the type of output points (PointFeature) + */ + inline size_t + getNPrime () { return N_prime_; } + + /** \brief Setter method for the M' parameter - the number of rows to be taken from the matrix of DFT and DCT + * values that will be contained in the output feature vector + * \note This value directly influences the dimensions of the type of output points (PointFeature) + * \param[in] m_prime the number of rows from the matrix of DFT and DCT that will be contained in the output + */ + inline void + setMPrime (size_t m_prime) { M_prime_ = m_prime; } + + /** \brief Returns the M' parameter - the number of rows to be taken from the matrix of DFT and DCT + * values that will be contained in the output feature vector + * \note This value directly influences the dimensions of the type of output points (PointFeature) + */ + inline size_t + getMPrime () { return M_prime_; } + + /** \brief Setter method for the scale parameter - used to determine the radius of the sampling disc around the + * point of interest - linked to the smoothing scale of the input cloud + */ + inline void + setScale (float scale) { scale_h_ = scale; } + + /** \brief Returns the scale parameter - used to determine the radius of the sampling disc around the + * point of interest - linked to the smoothing scale of the input cloud + */ + inline float + getScale () { return scale_h_; } + + + protected: + void + computeFeature (FeatureCloud &output); + + private: + float scale_h_; + size_t N_, M_, N_prime_, M_prime_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif /* PCL_NORMAL_BASED_SIGNATURE_H_ */ diff --git a/pcl-1.7/pcl/features/our_cvfh.h b/pcl-1.7/pcl/features/our_cvfh.h new file mode 100644 index 0000000..5d5bc15 --- /dev/null +++ b/pcl-1.7/pcl/features/our_cvfh.h @@ -0,0 +1,412 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: cvfh.h 4936 2012-03-07 11:12:45Z aaldoma $ + * + */ + +#ifndef PCL_FEATURES_OURCVFH_H_ +#define PCL_FEATURES_OURCVFH_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief OURCVFHEstimation estimates the Oriented, Unique and Repetable Clustered Viewpoint Feature Histogram (CVFH) descriptor for a given + * point cloud dataset given XYZ data and normals, as presented in: + * - OUR-CVFH – Oriented, Unique and Repeatable Clustered Viewpoint Feature Histogram for Object Recognition and 6DOF Pose Estimation + * A. Aldoma, F. Tombari, R.B. Rusu and M. Vincze + * DAGM-OAGM 2012 + * Graz, Austria + * The suggested PointOutT is pcl::VFHSignature308. + * + * \author Aitor Aldoma + * \ingroup features + */ + template + class OURCVFHEstimation : public FeatureFromNormals + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::k_; + using Feature::search_radius_; + using Feature::surface_; + using FeatureFromNormals::normals_; + + typedef typename Feature::PointCloudOut PointCloudOut; + typedef typename pcl::search::Search::Ptr KdTreePtr; + typedef typename pcl::PointCloud::Ptr PointInTPtr; + /** \brief Empty constructor. */ + OURCVFHEstimation () : + vpx_ (0), vpy_ (0), vpz_ (0), leaf_size_ (0.005f), normalize_bins_ (false), curv_threshold_ (0.03f), cluster_tolerance_ (leaf_size_ * 3), + eps_angle_threshold_ (0.125f), min_points_ (50), radius_normals_ (leaf_size_ * 3), centroids_dominant_orientations_ (), + dominant_normals_ () + { + search_radius_ = 0; + k_ = 1; + feature_name_ = "OURCVFHEstimation"; + refine_clusters_ = 1.f; + min_axis_value_ = 0.925f; + axis_ratio_ = 0.8f; + } + ; + + /** \brief Creates an affine transformation from the RF axes + * \param[in] evx the x-axis + * \param[in] evy the y-axis + * \param[in] evz the z-axis + * \param[out] transformPC the resulting transformation + * \param[in] center_mat 4x4 matrix concatenated to the resulting transformation + */ + inline Eigen::Matrix4f + createTransFromAxes (Eigen::Vector3f & evx, Eigen::Vector3f & evy, Eigen::Vector3f & evz, Eigen::Affine3f & transformPC, + Eigen::Matrix4f & center_mat) + { + Eigen::Matrix4f trans; + trans.setIdentity (4, 4); + trans (0, 0) = evx (0, 0); + trans (1, 0) = evx (1, 0); + trans (2, 0) = evx (2, 0); + trans (0, 1) = evy (0, 0); + trans (1, 1) = evy (1, 0); + trans (2, 1) = evy (2, 0); + trans (0, 2) = evz (0, 0); + trans (1, 2) = evz (1, 0); + trans (2, 2) = evz (2, 0); + + Eigen::Matrix4f homMatrix = Eigen::Matrix4f (); + homMatrix.setIdentity (4, 4); + homMatrix = transformPC.matrix (); + + Eigen::Matrix4f trans_copy = trans.inverse (); + trans = trans_copy * center_mat * homMatrix; + return trans; + } + + /** \brief Computes SGURF and the shape distribution based on the selected SGURF + * \param[in] processed the input cloud + * \param[out] output the resulting signature + * \param[in] cluster_indices the indices of the stable cluster + */ + void + computeRFAndShapeDistribution (PointInTPtr & processed, PointCloudOut &output, std::vector & cluster_indices); + + /** \brief Computes SGURF + * \param[in] centroid the centroid of the cluster + * \param[in] normal_centroid the average of the normals + * \param[in] processed the input cloud + * \param[out] transformations the transformations aligning the cloud to the SGURF axes + * \param[out] grid the cloud transformed internally + * \param[in] indices the indices of the stable cluster + */ + bool + sgurf (Eigen::Vector3f & centroid, Eigen::Vector3f & normal_centroid, PointInTPtr & processed, std::vector > & transformations, + PointInTPtr & grid, pcl::PointIndices & indices); + + /** \brief Removes normals with high curvature caused by real edges or noisy data + * \param[in] cloud pointcloud to be filtered + * \param[in] indices_to_use + * \param[out] indices_out the indices of the points with higher curvature than threshold + * \param[out] indices_in the indices of the remaining points after filtering + * \param[in] threshold threshold value for curvature + */ + void + filterNormalsWithHighCurvature (const pcl::PointCloud & cloud, std::vector & indices_to_use, std::vector &indices_out, + std::vector &indices_in, float threshold); + + /** \brief Set the viewpoint. + * \param[in] vpx the X coordinate of the viewpoint + * \param[in] vpy the Y coordinate of the viewpoint + * \param[in] vpz the Z coordinate of the viewpoint + */ + inline void + setViewPoint (float vpx, float vpy, float vpz) + { + vpx_ = vpx; + vpy_ = vpy; + vpz_ = vpz; + } + + /** \brief Set the radius used to compute normals + * \param[in] radius_normals the radius + */ + inline void + setRadiusNormals (float radius_normals) + { + radius_normals_ = radius_normals; + } + + /** \brief Get the viewpoint. + * \param[out] vpx the X coordinate of the viewpoint + * \param[out] vpy the Y coordinate of the viewpoint + * \param[out] vpz the Z coordinate of the viewpoint + */ + inline void + getViewPoint (float &vpx, float &vpy, float &vpz) + { + vpx = vpx_; + vpy = vpy_; + vpz = vpz_; + } + + /** \brief Get the centroids used to compute different CVFH descriptors + * \param[out] centroids vector to hold the centroids + */ + inline void + getCentroidClusters (std::vector & centroids) + { + for (size_t i = 0; i < centroids_dominant_orientations_.size (); ++i) + centroids.push_back (centroids_dominant_orientations_[i]); + } + + /** \brief Get the normal centroids used to compute different CVFH descriptors + * \param[out] centroids vector to hold the normal centroids + */ + inline void + getCentroidNormalClusters (std::vector & centroids) + { + for (size_t i = 0; i < dominant_normals_.size (); ++i) + centroids.push_back (dominant_normals_[i]); + } + + /** \brief Sets max. Euclidean distance between points to be added to the cluster + * \param[in] d the maximum Euclidean distance + */ + + inline void + setClusterTolerance (float d) + { + cluster_tolerance_ = d; + } + + /** \brief Sets max. deviation of the normals between two points so they can be clustered together + * \param[in] d the maximum deviation + */ + inline void + setEPSAngleThreshold (float d) + { + eps_angle_threshold_ = d; + } + + /** \brief Sets curvature threshold for removing normals + * \param[in] d the curvature threshold + */ + inline void + setCurvatureThreshold (float d) + { + curv_threshold_ = d; + } + + /** \brief Set minimum amount of points for a cluster to be considered + * \param[in] min the minimum amount of points to be set + */ + inline void + setMinPoints (size_t min) + { + min_points_ = min; + } + + /** \brief Sets wether if the signatures should be normalized or not + * \param[in] normalize true if normalization is required, false otherwise + */ + inline void + setNormalizeBins (bool normalize) + { + normalize_bins_ = normalize; + } + + /** \brief Gets the indices of the original point cloud used to compute the signatures + * \param[out] indices vector of point indices + */ + inline void + getClusterIndices (std::vector & indices) + { + indices = clusters_; + } + + /** \brief Gets the number of non-disambiguable axes that correspond to each centroid + * \param[out] cluster_axes vector mapping each centroid to the number of signatures + */ + inline void + getClusterAxes (std::vector & cluster_axes) + { + cluster_axes = cluster_axes_; + } + + /** \brief Sets the refinement factor for the clusters + * \param[in] rc the factor used to decide if a point is used to estimate a stable cluster + */ + void + setRefineClusters (float rc) + { + refine_clusters_ = rc; + } + + /** \brief Returns the transformations aligning the point cloud to the corresponding SGURF + * \param[out] trans vector of transformations + */ + void + getTransforms (std::vector > & trans) + { + trans = transforms_; + } + + /** \brief Returns a boolean vector indicating of the transformation obtained by getTransforms() represents + * a valid SGURF + * \param[out] valid vector of booleans + */ + void + getValidTransformsVec (std::vector & valid) + { + valid = valid_transforms_; + } + + /** \brief Sets the min axis ratio between the SGURF axes to decide if disambiguition is feasible + * \param[in] f the ratio between axes + */ + void + setAxisRatio (float f) + { + axis_ratio_ = f; + } + + /** \brief Sets the min disambiguition axis value to generate several SGURFs for the cluster when disambiguition is difficult + * \param[in] f the min axis value + */ + void + setMinAxisValue (float f) + { + min_axis_value_ = f; + } + + /** \brief Overloaded computed method from pcl::Feature. + * \param[out] output the resultant point cloud model dataset containing the estimated features + */ + void + compute (PointCloudOut &output); + + private: + /** \brief Values describing the viewpoint ("pinhole" camera model assumed). + * By default, the viewpoint is set to 0,0,0. + */ + float vpx_, vpy_, vpz_; + + /** \brief Size of the voxels after voxel gridding. IMPORTANT: Must match the voxel + * size of the training data or the normalize_bins_ flag must be set to true. + */ + float leaf_size_; + + /** \brief Wether to normalize the signatures or not. Default: false. */ + bool normalize_bins_; + + /** \brief Curvature threshold for removing normals. */ + float curv_threshold_; + + /** \brief allowed Euclidean distance between points to be added to the cluster. */ + float cluster_tolerance_; + + /** \brief deviation of the normals between two points so they can be clustered together. */ + float eps_angle_threshold_; + + /** \brief Minimum amount of points in a clustered region to be considered stable for CVFH + * computation. + */ + size_t min_points_; + + /** \brief Radius for the normals computation. */ + float radius_normals_; + + /** \brief Factor for the cluster refinement */ + float refine_clusters_; + + std::vector > transforms_; + std::vector valid_transforms_; + + float axis_ratio_; + float min_axis_value_; + + /** \brief Estimate the OUR-CVFH descriptors at + * a set of points given by using the surface in + * setSearchSurface () + * + * \param[out] output the resultant point cloud model dataset that contains the OUR-CVFH + * feature estimates + */ + void + computeFeature (PointCloudOut &output); + + /** \brief Region growing method using Euclidean distances and neighbors normals to + * add points to a region. + * \param[in] cloud point cloud to split into regions + * \param[in] normals are the normals of cloud + * \param[in] tolerance is the allowed Euclidean distance between points to be added to + * the cluster + * \param[in] tree is the spatial search structure for nearest neighbour search + * \param[out] clusters vector of indices representing the clustered regions + * \param[in] eps_angle deviation of the normals between two points so they can be + * clustered together + * \param[in] min_pts_per_cluster minimum cluster size. (default: 1 point) + * \param[in] max_pts_per_cluster maximum cluster size. (default: all the points) + */ + void + extractEuclideanClustersSmooth (const pcl::PointCloud &cloud, const pcl::PointCloud &normals, + float tolerance, const pcl::search::Search::Ptr &tree, + std::vector &clusters, double eps_angle, unsigned int min_pts_per_cluster = 1, + unsigned int max_pts_per_cluster = (std::numeric_limits::max) ()); + + protected: + /** \brief Centroids that were used to compute different OUR-CVFH descriptors */ + std::vector centroids_dominant_orientations_; + /** \brief Normal centroids that were used to compute different OUR-CVFH descriptors */ + std::vector dominant_normals_; + /** \brief Indices to the points representing the stable clusters */ + std::vector clusters_; + /** \brief Mapping from clusters to OUR-CVFH descriptors */ + std::vector cluster_axes_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FEATURES_VFH_H_ diff --git a/pcl-1.7/pcl/features/pfh.h b/pcl-1.7/pcl/features/pfh.h new file mode 100644 index 0000000..70bd20c --- /dev/null +++ b/pcl-1.7/pcl/features/pfh.h @@ -0,0 +1,229 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_PFH_H_ +#define PCL_PFH_H_ + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief PFHEstimation estimates the Point Feature Histogram (PFH) descriptor for a given point cloud dataset + * containing points and normals. + * + * A commonly used type for PointOutT is pcl::PFHSignature125. + * + * \note If you use this code in any academic work, please cite: + * + * - R.B. Rusu, N. Blodow, Z.C. Marton, M. Beetz. + * Aligning Point Cloud Views using Persistent Feature Histograms. + * In Proceedings of the 21st IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), + * Nice, France, September 22-26 2008. + * - R.B. Rusu, Z.C. Marton, N. Blodow, M. Beetz. + * Learning Informative Point Classes for the Acquisition of Object Model Maps. + * In Proceedings of the 10th International Conference on Control, Automation, Robotics and Vision (ICARCV), + * Hanoi, Vietnam, December 17-20 2008. + * + * \attention + * The convention for PFH features is: + * - if a query point's nearest neighbors cannot be estimated, the PFH feature will be set to NaN + * (not a number) + * - it is impossible to estimate a PFH descriptor for a point that + * doesn't have finite 3D coordinates. Therefore, any point that contains + * NaN data on x, y, or z, will have its PFH feature property set to NaN. + * + * \note The code is stateful as we do not expect this class to be multicore parallelized. Please look at + * \ref FPFHEstimationOMP for examples on parallel implementations of the FPFH (Fast Point Feature Histogram). + * + * \author Radu B. Rusu + * \ingroup features + */ + template + class PFHEstimation : public FeatureFromNormals + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::k_; + using Feature::search_parameter_; + using Feature::surface_; + using Feature::input_; + using FeatureFromNormals::normals_; + + typedef typename Feature::PointCloudOut PointCloudOut; + typedef typename Feature::PointCloudIn PointCloudIn; + + /** \brief Empty constructor. + * Sets \a use_cache_ to false, \a nr_subdiv_ to 5, and the internal maximum cache size to 1GB. + */ + PFHEstimation () : + nr_subdiv_ (5), + pfh_histogram_ (), + pfh_tuple_ (), + d_pi_ (1.0f / (2.0f * static_cast (M_PI))), + feature_map_ (), + key_list_ (), + // Default 1GB memory size. Need to set it to something more conservative. + max_cache_size_ ((1ul*1024ul*1024ul*1024ul) / sizeof (std::pair, Eigen::Vector4f>)), + use_cache_ (false) + { + feature_name_ = "PFHEstimation"; + }; + + /** \brief Set the maximum internal cache size. Defaults to 2GB worth of entries. + * \param[in] cache_size maximum cache size + */ + inline void + setMaximumCacheSize (unsigned int cache_size) + { + max_cache_size_ = cache_size; + } + + /** \brief Get the maximum internal cache size. */ + inline unsigned int + getMaximumCacheSize () + { + return (max_cache_size_); + } + + /** \brief Set whether to use an internal cache mechanism for removing redundant calculations or not. + * + * \note Depending on how the point cloud is ordered and how the nearest + * neighbors are estimated, using a cache could have a positive or a + * negative influence. Please test with and without a cache on your + * data, and choose whatever works best! + * + * See \ref setMaximumCacheSize for setting the maximum cache size + * + * \param[in] use_cache set to true to use the internal cache, false otherwise + */ + inline void + setUseInternalCache (bool use_cache) + { + use_cache_ = use_cache; + } + + /** \brief Get whether the internal cache is used or not for computing the PFH features. */ + inline bool + getUseInternalCache () + { + return (use_cache_); + } + + /** \brief Compute the 4-tuple representation containing the three angles and one distance between two points + * represented by Cartesian coordinates and normals. + * \note For explanations about the features, please see the literature mentioned above (the order of the + * features might be different). + * \param[in] cloud the dataset containing the XYZ Cartesian coordinates of the two points + * \param[in] normals the dataset containing the surface normals (assuming normalized vectors) at each point in cloud + * \param[in] p_idx the index of the first point (source) + * \param[in] q_idx the index of the second point (target) + * \param[out] f1 the first angular feature (angle between the projection of nq_idx and u) + * \param[out] f2 the second angular feature (angle between nq_idx and v) + * \param[out] f3 the third angular feature (angle between np_idx and |p_idx - q_idx|) + * \param[out] f4 the distance feature (p_idx - q_idx) + * \note For efficiency reasons, we assume that the point data passed to the method is finite. + */ + bool + computePairFeatures (const pcl::PointCloud &cloud, const pcl::PointCloud &normals, + int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4); + + /** \brief Estimate the PFH (Point Feature Histograms) individual signatures of the three angular (f1, f2, f3) + * features for a given point based on its spatial neighborhood of 3D points with normals + * \param[in] cloud the dataset containing the XYZ Cartesian coordinates of the two points + * \param[in] normals the dataset containing the surface normals at each point in \a cloud + * \param[in] indices the k-neighborhood point indices in the dataset + * \param[in] nr_split the number of subdivisions for each angular feature interval + * \param[out] pfh_histogram the resultant (combinatorial) PFH histogram representing the feature at the query point + */ + void + computePointPFHSignature (const pcl::PointCloud &cloud, const pcl::PointCloud &normals, + const std::vector &indices, int nr_split, Eigen::VectorXf &pfh_histogram); + + protected: + /** \brief Estimate the Point Feature Histograms (PFH) descriptors at a set of points given by + * using the surface in setSearchSurface () and the spatial locator in + * setSearchMethod () + * \param[out] output the resultant point cloud model dataset that contains the PFH feature estimates + */ + void + computeFeature (PointCloudOut &output); + + /** \brief The number of subdivisions for each angular feature interval. */ + int nr_subdiv_; + + /** \brief Placeholder for a point's PFH signature. */ + Eigen::VectorXf pfh_histogram_; + + /** \brief Placeholder for a PFH 4-tuple. */ + Eigen::Vector4f pfh_tuple_; + + /** \brief Placeholder for a histogram index. */ + int f_index_[3]; + + /** \brief Float constant = 1.0 / (2.0 * M_PI) */ + float d_pi_; + + /** \brief Internal hashmap, used to optimize efficiency of redundant computations. */ + std::map, Eigen::Vector4f, std::less >, Eigen::aligned_allocator > feature_map_; + + /** \brief Queue of pairs saved, used to constrain memory usage. */ + std::queue > key_list_; + + /** \brief Maximum size of internal cache memory. */ + unsigned int max_cache_size_; + + /** \brief Set to true to use the internal cache for removing redundant computations. */ + bool use_cache_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_PFH_H_ + diff --git a/pcl-1.7/pcl/features/pfh_tools.h b/pcl-1.7/pcl/features/pfh_tools.h new file mode 100644 index 0000000..9a9923f --- /dev/null +++ b/pcl-1.7/pcl/features/pfh_tools.h @@ -0,0 +1,79 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_PFH_TOOLS_H_ +#define PCL_FEATURES_PFH_TOOLS_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include + +namespace pcl +{ + // * \brief Compute the 4-tuple representation containing the three angles and one distance between two points + // * represented by Cartesian coordinates and normals. + // * \note For explanations about the features, please see the literature mentioned above (the order of the + // * features might be different). + // * \param[in] p1 the first XYZ point + // * \param[in] n1 the first surface normal + // * \param[in] p2 the second XYZ point + // * \param[in] n2 the second surface normal + // * \param[out] f1 the first angular feature (angle between the projection of nq_idx and u) + // * \param[out] f2 the second angular feature (angle between nq_idx and v) + // * \param[out] f3 the third angular feature (angle between np_idx and |p_idx - q_idx|) + // * \param[out] f4 the distance feature (p_idx - q_idx) + // * + // * \note For efficiency reasons, we assume that the point data passed to the method is finite. + // * \ingroup features + + PCL_EXPORTS bool + computePairFeatures (const Eigen::Vector4f &p1, const Eigen::Vector4f &n1, + const Eigen::Vector4f &p2, const Eigen::Vector4f &n2, + float &f1, float &f2, float &f3, float &f4); + + PCL_EXPORTS bool + computeRGBPairFeatures (const Eigen::Vector4f &p1, const Eigen::Vector4f &n1, const Eigen::Vector4i &colors1, + const Eigen::Vector4f &p2, const Eigen::Vector4f &n2, const Eigen::Vector4i &colors2, + float &f1, float &f2, float &f3, float &f4, float &f5, float &f6, float &f7); + +} + +#endif //#ifndef PCL_FEATURES_PFH_TOOLS_H_ + diff --git a/pcl-1.7/pcl/features/pfhrgb.h b/pcl-1.7/pcl/features/pfhrgb.h new file mode 100644 index 0000000..0222bcc --- /dev/null +++ b/pcl-1.7/pcl/features/pfhrgb.h @@ -0,0 +1,104 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_PFHRGB_H_ +#define PCL_PFHRGB_H_ + +#include +#include + +namespace pcl +{ + template + class PFHRGBEstimation : public FeatureFromNormals + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using PCLBase::indices_; + using Feature::feature_name_; + using Feature::surface_; + using Feature::k_; + using Feature::search_parameter_; + using FeatureFromNormals::normals_; + typedef typename Feature::PointCloudOut PointCloudOut; + + + PFHRGBEstimation () + : nr_subdiv_ (5), pfhrgb_histogram_ (), pfhrgb_tuple_ (), d_pi_ (1.0f / (2.0f * static_cast (M_PI))) + { + feature_name_ = "PFHRGBEstimation"; + } + + bool + computeRGBPairFeatures (const pcl::PointCloud &cloud, const pcl::PointCloud &normals, + int p_idx, int q_idx, + float &f1, float &f2, float &f3, float &f4, float &f5, float &f6, float &f7); + + void + computePointPFHRGBSignature (const pcl::PointCloud &cloud, const pcl::PointCloud &normals, + const std::vector &indices, int nr_split, Eigen::VectorXf &pfhrgb_histogram); + + protected: + void + computeFeature (PointCloudOut &output); + + private: + /** \brief The number of subdivisions for each angular feature interval. */ + int nr_subdiv_; + + /** \brief Placeholder for a point's PFHRGB signature. */ + Eigen::VectorXf pfhrgb_histogram_; + + /** \brief Placeholder for a PFHRGB 7-tuple. */ + Eigen::VectorXf pfhrgb_tuple_; + + /** \brief Placeholder for a histogram index. */ + int f_index_[7]; + + /** \brief Float constant = 1.0 / (2.0 * M_PI) */ + float d_pi_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif /* PCL_PFHRGB_H_ */ diff --git a/pcl-1.7/pcl/features/ppf.h b/pcl-1.7/pcl/features/ppf.h new file mode 100644 index 0000000..fb898c2 --- /dev/null +++ b/pcl-1.7/pcl/features/ppf.h @@ -0,0 +1,109 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_PPF_H_ +#define PCL_PPF_H_ + +#include +#include + +namespace pcl +{ + /** \brief + * \param[in] p1 + * \param[in] n1 + * \param[in] p2 + * \param[in] n2 + * \param[out] f1 + * \param[out] f2 + * \param[out] f3 + * \param[out] f4 + */ + PCL_EXPORTS bool + computePPFPairFeature (const Eigen::Vector4f &p1, const Eigen::Vector4f &n1, + const Eigen::Vector4f &p2, const Eigen::Vector4f &n2, + float &f1, float &f2, float &f3, float &f4); + + + /** \brief Class that calculates the "surflet" features for each pair in the given + * pointcloud. Please refer to the following publication for more details: + * B. Drost, M. Ulrich, N. Navab, S. Ilic + * Model Globally, Match Locally: Efficient and Robust 3D Object Recognition + * 2010 IEEE Conference on Computer Vision and Pattern Recognition (CVPR) + * 13-18 June 2010, San Francisco, CA + * + * PointOutT is meant to be pcl::PPFSignature - contains the 4 values of the Surflet + * feature and in addition, alpha_m for the respective pair - optimization proposed by + * the authors (see above) + * + * \author Alexandru-Eugen Ichim + */ + template + class PPFEstimation : public FeatureFromNormals + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using PCLBase::indices_; + using Feature::input_; + using Feature::feature_name_; + using Feature::getClassName; + using FeatureFromNormals::normals_; + + typedef pcl::PointCloud PointCloudOut; + + /** \brief Empty Constructor. */ + PPFEstimation (); + + + private: + /** \brief The method called for actually doing the computations + * \param[out] output the resulting point cloud (which should be of type pcl::PPFSignature); + * its size is the size of the input cloud, squared (i.e., one point for each pair in + * the input cloud); + */ + void + computeFeature (PointCloudOut &output); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_PPF_H_ diff --git a/pcl-1.7/pcl/features/ppfrgb.h b/pcl-1.7/pcl/features/ppfrgb.h new file mode 100644 index 0000000..34f59be --- /dev/null +++ b/pcl-1.7/pcl/features/ppfrgb.h @@ -0,0 +1,100 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_PPFRGB_H_ +#define PCL_PPFRGB_H_ + +#include +#include + +namespace pcl +{ + template + class PPFRGBEstimation : public FeatureFromNormals + { + public: + using PCLBase::indices_; + using Feature::input_; + using Feature::feature_name_; + using Feature::getClassName; + using FeatureFromNormals::normals_; + + typedef pcl::PointCloud PointCloudOut; + + /** + * \brief Empty Constructor + */ + PPFRGBEstimation (); + + + private: + /** \brief The method called for actually doing the computations + * \param output the resulting point cloud (which should be of type pcl::PPFRGBSignature); + */ + void + computeFeature (PointCloudOut &output); + }; + + template + class PPFRGBRegionEstimation : public FeatureFromNormals + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using PCLBase::indices_; + using Feature::input_; + using Feature::feature_name_; + using Feature::search_radius_; + using Feature::tree_; + using Feature::getClassName; + using FeatureFromNormals::normals_; + + typedef pcl::PointCloud PointCloudOut; + + PPFRGBRegionEstimation (); + + private: + void + computeFeature (PointCloudOut &output); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_PPFRGB_H_ diff --git a/pcl-1.7/pcl/features/principal_curvatures.h b/pcl-1.7/pcl/features/principal_curvatures.h new file mode 100644 index 0000000..73c0892 --- /dev/null +++ b/pcl-1.7/pcl/features/principal_curvatures.h @@ -0,0 +1,141 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_PRINCIPAL_CURVATURES_H_ +#define PCL_PRINCIPAL_CURVATURES_H_ + +#include +#include + +namespace pcl +{ + /** \brief PrincipalCurvaturesEstimation estimates the directions (eigenvectors) and magnitudes (eigenvalues) of + * principal surface curvatures for a given point cloud dataset containing points and normals. + * + * The recommended PointOutT is pcl::PrincipalCurvatures. + * + * \note The code is stateful as we do not expect this class to be multicore parallelized. Please look at + * \ref NormalEstimationOMP for an example on how to extend this to parallel implementations. + * + * \author Radu B. Rusu, Jared Glover + * \ingroup features + */ + template + class PrincipalCurvaturesEstimation : public FeatureFromNormals + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::k_; + using Feature::search_parameter_; + using Feature::surface_; + using Feature::input_; + using FeatureFromNormals::normals_; + + typedef typename Feature::PointCloudOut PointCloudOut; + typedef pcl::PointCloud PointCloudIn; + + /** \brief Empty constructor. */ + PrincipalCurvaturesEstimation () : + projected_normals_ (), + xyz_centroid_ (Eigen::Vector3f::Zero ()), + demean_ (Eigen::Vector3f::Zero ()), + covariance_matrix_ (Eigen::Matrix3f::Zero ()), + eigenvector_ (Eigen::Vector3f::Zero ()), + eigenvalues_ (Eigen::Vector3f::Zero ()) + { + feature_name_ = "PrincipalCurvaturesEstimation"; + }; + + /** \brief Perform Principal Components Analysis (PCA) on the point normals of a surface patch in the tangent + * plane of the given point normal, and return the principal curvature (eigenvector of the max eigenvalue), + * along with both the max (pc1) and min (pc2) eigenvalues + * \param[in] normals the point cloud normals + * \param[in] p_idx the query point at which the least-squares plane was estimated + * \param[in] indices the point cloud indices that need to be used + * \param[out] pcx the principal curvature X direction + * \param[out] pcy the principal curvature Y direction + * \param[out] pcz the principal curvature Z direction + * \param[out] pc1 the max eigenvalue of curvature + * \param[out] pc2 the min eigenvalue of curvature + */ + void + computePointPrincipalCurvatures (const pcl::PointCloud &normals, + int p_idx, const std::vector &indices, + float &pcx, float &pcy, float &pcz, float &pc1, float &pc2); + + protected: + + /** \brief Estimate the principal curvature (eigenvector of the max eigenvalue), along with both the max (pc1) + * and min (pc2) eigenvalues for all points given in using the surface in + * setSearchSurface () and the spatial locator in setSearchMethod () + * \param[out] output the resultant point cloud model dataset that contains the principal curvature estimates + */ + void + computeFeature (PointCloudOut &output); + + private: + /** \brief A pointer to the input dataset that contains the point normals of the XYZ dataset. */ + std::vector projected_normals_; + + /** \brief SSE aligned placeholder for the XYZ centroid of a surface patch. */ + Eigen::Vector3f xyz_centroid_; + + /** \brief Temporary point placeholder. */ + Eigen::Vector3f demean_; + + /** \brief Placeholder for the 3x3 covariance matrix at each surface patch. */ + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix_; + + /** \brief SSE aligned eigenvectors placeholder for a covariance matrix. */ + Eigen::Vector3f eigenvector_; + /** \brief eigenvalues placeholder for a covariance matrix. */ + Eigen::Vector3f eigenvalues_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_PRINCIPAL_CURVATURES_H_ diff --git a/pcl-1.7/pcl/features/range_image_border_extractor.h b/pcl-1.7/pcl/features/range_image_border_extractor.h new file mode 100644 index 0000000..9f55cb7 --- /dev/null +++ b/pcl-1.7/pcl/features/range_image_border_extractor.h @@ -0,0 +1,363 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_RANGE_IMAGE_BORDER_EXTRACTOR_H_ +#define PCL_RANGE_IMAGE_BORDER_EXTRACTOR_H_ + +#include +#include + +#if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 +#pragma GCC diagnostic ignored "-Weffc++" +#endif +namespace pcl +{ + // FORWARD DECLARATIONS: + class RangeImage; + template + class PointCloud; + + /** \brief @b Extract obstacle borders from range images, meaning positions where there is a transition from foreground + * to background. + * \author Bastian Steder + * \ingroup features + */ + class PCL_EXPORTS RangeImageBorderExtractor : public Feature + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + // =====TYPEDEFS===== + typedef Feature BaseClass; + + // =====PUBLIC STRUCTS===== + //! Stores some information extracted from the neighborhood of a point + struct LocalSurface + { + LocalSurface () : + normal (), neighborhood_mean (), eigen_values (), normal_no_jumps (), + neighborhood_mean_no_jumps (), eigen_values_no_jumps (), max_neighbor_distance_squared () {} + + Eigen::Vector3f normal; + Eigen::Vector3f neighborhood_mean; + Eigen::Vector3f eigen_values; + Eigen::Vector3f normal_no_jumps; + Eigen::Vector3f neighborhood_mean_no_jumps; + Eigen::Vector3f eigen_values_no_jumps; + float max_neighbor_distance_squared; + }; + + //! Stores the indices of the shadow border corresponding to obstacle borders + struct ShadowBorderIndices + { + ShadowBorderIndices () : left (-1), right (-1), top (-1), bottom (-1) {} + int left, right, top, bottom; + }; + + //! Parameters used in this class + struct Parameters + { + Parameters () : max_no_of_threads(1), pixel_radius_borders (3), pixel_radius_plane_extraction (2), pixel_radius_border_direction (2), + minimum_border_probability (0.8f), pixel_radius_principal_curvature (2) {} + int max_no_of_threads; + int pixel_radius_borders; + int pixel_radius_plane_extraction; + int pixel_radius_border_direction; + float minimum_border_probability; + int pixel_radius_principal_curvature; + }; + + // =====STATIC METHODS===== + /** \brief Take the information from BorderTraits to calculate the local direction of the border + * \param border_traits contains the information needed to calculate the border angle + */ + static inline float + getObstacleBorderAngle (const BorderTraits& border_traits); + + // =====CONSTRUCTOR & DESTRUCTOR===== + /** Constructor */ + RangeImageBorderExtractor (const RangeImage* range_image=NULL); + /** Destructor */ + virtual ~RangeImageBorderExtractor (); + + // =====METHODS===== + /** \brief Provide a pointer to the range image + * \param range_image a pointer to the range_image + */ + void + setRangeImage (const RangeImage* range_image); + + /** \brief Erase all data calculated for the current range image */ + void + clearData (); + + /** \brief Get the 2D directions in the range image from the border directions - probably mainly useful for + * visualization + */ + float* + getAnglesImageForBorderDirections (); + + /** \brief Get the 2D directions in the range image from the surface change directions - probably mainly useful for + * visualization + */ + float* + getAnglesImageForSurfaceChangeDirections (); + + /** Overwrite the compute function of the base class */ + void + compute (PointCloudOut& output); + + // =====GETTER===== + Parameters& + getParameters () { return (parameters_); } + + bool + hasRangeImage () const { return range_image_ != NULL; } + + const RangeImage& + getRangeImage () const { return *range_image_; } + + float* + getBorderScoresLeft () { extractBorderScoreImages (); return border_scores_left_; } + + float* + getBorderScoresRight () { extractBorderScoreImages (); return border_scores_right_; } + + float* + getBorderScoresTop () { extractBorderScoreImages (); return border_scores_top_; } + + float* + getBorderScoresBottom () { extractBorderScoreImages (); return border_scores_bottom_; } + + LocalSurface** + getSurfaceStructure () { extractLocalSurfaceStructure (); return surface_structure_; } + + PointCloudOut& + getBorderDescriptions () { classifyBorders (); return *border_descriptions_; } + + ShadowBorderIndices** + getShadowBorderInformations () { findAndEvaluateShadowBorders (); return shadow_border_informations_; } + + Eigen::Vector3f** + getBorderDirections () { calculateBorderDirections (); return border_directions_; } + + float* + getSurfaceChangeScores () { calculateSurfaceChanges (); return surface_change_scores_; } + + Eigen::Vector3f* + getSurfaceChangeDirections () { calculateSurfaceChanges (); return surface_change_directions_; } + + + protected: + // =====PROTECTED MEMBER VARIABLES===== + Parameters parameters_; + const RangeImage* range_image_; + int range_image_size_during_extraction_; + float* border_scores_left_, * border_scores_right_, * border_scores_top_, * border_scores_bottom_; + LocalSurface** surface_structure_; + PointCloudOut* border_descriptions_; + ShadowBorderIndices** shadow_border_informations_; + Eigen::Vector3f** border_directions_; + + float* surface_change_scores_; + Eigen::Vector3f* surface_change_directions_; + + + // =====PROTECTED METHODS===== + /** \brief Calculate a border score based on how distant the neighbor is, compared to the closest neighbors + * /param local_surface + * /param x + * /param y + * /param offset_x + * /param offset_y + * /param pixel_radius (defaults to 1) + * /return the resulting border score + */ + inline float + getNeighborDistanceChangeScore (const LocalSurface& local_surface, int x, int y, + int offset_x, int offset_y, int pixel_radius=1) const; + + /** \brief Calculate a border score based on how much the neighbor is away from the local surface plane + * \param local_surface + * \param x + * \param y + * \param offset_x + * \param offset_y + * \return the resulting border score + */ + inline float + getNormalBasedBorderScore (const LocalSurface& local_surface, int x, int y, + int offset_x, int offset_y) const; + + /** \brief Find the best corresponding shadow border and lower score according to the shadow borders value + * \param x + * \param y + * \param offset_x + * \param offset_y + * \param border_scores + * \param border_scores_other_direction + * \param shadow_border_idx + * \return + */ + inline bool + changeScoreAccordingToShadowBorderValue (int x, int y, int offset_x, int offset_y, float* border_scores, + float* border_scores_other_direction, int& shadow_border_idx) const; + + /** \brief Returns a new score for the given pixel that is >= the original value, based on the neighbors values + * \param x the x-coordinate of the input pixel + * \param y the y-coordinate of the input pixel + * \param border_scores the input border scores + * \return the resulting updated border score + */ + inline float + updatedScoreAccordingToNeighborValues (int x, int y, const float* border_scores) const; + + /** \brief For all pixels, returns a new score that is >= the original value, based on the neighbors values + * \param border_scores the input border scores + * \return a pointer to the resulting array of updated scores + */ + float* + updatedScoresAccordingToNeighborValues (const float* border_scores) const; + + /** \brief Replace all border score values with updates according to \a updatedScoreAccordingToNeighborValues */ + void + updateScoresAccordingToNeighborValues (); + + /** \brief Check if a potential border point has a corresponding shadow border + * \param x the x-coordinate of the input point + * \param y the y-coordinate of the input point + * \param offset_x + * \param offset_y + * \param border_scores_left + * \param border_scores_right + * \param shadow_border_idx + * \return a boolean value indicating whether or not the point has a corresponding shadow border + */ + inline bool + checkPotentialBorder (int x, int y, int offset_x, int offset_y, float* border_scores_left, + float* border_scores_right, int& shadow_border_idx) const; + + /** \brief Check if a potential border point is a maximum regarding the border score + * \param x the x-coordinate of the input point + * \param y the y-coordinate of the input point + * \param offset_x + * \param offset_y + * \param border_scores + * \param shadow_border_idx + * \result a boolean value indicating whether or not the point is a maximum + */ + inline bool + checkIfMaximum (int x, int y, int offset_x, int offset_y, float* border_scores, int shadow_border_idx) const; + + /** \brief Find the best corresponding shadow border and lower score according to the shadow borders value */ + void + findAndEvaluateShadowBorders (); + + /** \brief Extract local plane information in every point (see getSurfaceStructure ()) */ + void + extractLocalSurfaceStructure (); + + /** \brief Get images representing the probability that the corresponding pixels are borders in that direction + * (see getBorderScores... ()) + */ + void + extractBorderScoreImages (); + + /** \brief Classify the pixels in the range image according to the different classes defined below in + * enum BorderClass. minImpactAngle (in radians) defines how flat the angle at which a surface was seen can be. + */ + void + classifyBorders (); + + /** \brief Calculate the 3D direction of the border just using the border traits at this position (facing away from + * the obstacle) + * \param x the x-coordinate of the input position + * \param y the y-coordinate of the input position + */ + inline void + calculateBorderDirection (int x, int y); + + /** \brief Call \a calculateBorderDirection for every point and average the result over + * parameters_.pixel_radius_border_direction + */ + void + calculateBorderDirections (); + + /** \brief Calculate a 3d direction from a border point by projecting the direction in the range image - returns + * false if direction could not be calculated + * \param border_description + * \param direction + * \param local_surface + * \return a boolean value indicating whether or not a direction could be calculated + */ + inline bool + get3dDirection (const BorderDescription& border_description, Eigen::Vector3f& direction, + const LocalSurface* local_surface=NULL); + + /** \brief Calculate the main principal curvature (the largest eigenvalue and corresponding eigenvector for the + * normals in the area) in the given point + * \param x the x-coordinate of the input point + * \param y the y-coordinate of the input point + * \param radius the pixel radius that is used to find neighboring points + * \param magnitude the resulting magnitude + * \param main_direction the resulting direction + */ + inline bool + calculateMainPrincipalCurvature (int x, int y, int radius, float& magnitude, + Eigen::Vector3f& main_direction) const; + + /** \brief Uses either the border or principal curvature to define a score how much the surface changes in a point + (1 for a border) and what the main direction of that change is */ + void + calculateSurfaceChanges (); + + /** \brief Apply a blur to the surface change images */ + void + blurSurfaceChanges (); + + /** \brief Implementation of abstract derived function */ + virtual void + computeFeature (PointCloudOut &output); + }; +} // namespace end +#if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 +#pragma GCC diagnostic warning "-Weffc++" +#endif + +#include // Definitions of templated and inline functions + +#endif //#ifndef PCL_RANGE_IMAGE_BORDER_EXTRACTOR_H_ diff --git a/pcl-1.7/pcl/features/rift.h b/pcl-1.7/pcl/features/rift.h new file mode 100644 index 0000000..f21f09c --- /dev/null +++ b/pcl-1.7/pcl/features/rift.h @@ -0,0 +1,159 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_RIFT_H_ +#define PCL_RIFT_H_ + +#include + +namespace pcl +{ + /** \brief RIFTEstimation estimates the Rotation Invariant Feature Transform descriptors for a given point cloud + * dataset containing points and intensity. For more information about the RIFT descriptor, see: + * + * Svetlana Lazebnik, Cordelia Schmid, and Jean Ponce. + * A sparse texture representation using local affine regions. + * In IEEE Transactions on Pattern Analysis and Machine Intelligence, volume 27, pages 1265-1278, August 2005. + * + * \author Michael Dixon + * \ingroup features + */ + + template + class RIFTEstimation: public Feature + { + public: + using Feature::feature_name_; + using Feature::getClassName; + + using Feature::surface_; + using Feature::indices_; + + using Feature::tree_; + using Feature::search_radius_; + + typedef typename pcl::PointCloud PointCloudIn; + typedef typename Feature::PointCloudOut PointCloudOut; + + typedef typename pcl::PointCloud PointCloudGradient; + typedef typename PointCloudGradient::Ptr PointCloudGradientPtr; + typedef typename PointCloudGradient::ConstPtr PointCloudGradientConstPtr; + + typedef typename boost::shared_ptr > Ptr; + typedef typename boost::shared_ptr > ConstPtr; + + + /** \brief Empty constructor. */ + RIFTEstimation () : gradient_ (), nr_distance_bins_ (4), nr_gradient_bins_ (8) + { + feature_name_ = "RIFTEstimation"; + }; + + /** \brief Provide a pointer to the input gradient data + * \param[in] gradient a pointer to the input gradient data + */ + inline void + setInputGradient (const PointCloudGradientConstPtr &gradient) { gradient_ = gradient; }; + + /** \brief Returns a shared pointer to the input gradient data */ + inline PointCloudGradientConstPtr + getInputGradient () const { return (gradient_); }; + + /** \brief Set the number of bins to use in the distance dimension of the RIFT descriptor + * \param[in] nr_distance_bins the number of bins to use in the distance dimension of the RIFT descriptor + */ + inline void + setNrDistanceBins (int nr_distance_bins) { nr_distance_bins_ = nr_distance_bins; }; + + /** \brief Returns the number of bins in the distance dimension of the RIFT descriptor. */ + inline int + getNrDistanceBins () const { return (nr_distance_bins_); }; + + /** \brief Set the number of bins to use in the gradient orientation dimension of the RIFT descriptor + * \param[in] nr_gradient_bins the number of bins to use in the gradient orientation dimension of the RIFT descriptor + */ + inline void + setNrGradientBins (int nr_gradient_bins) { nr_gradient_bins_ = nr_gradient_bins; }; + + /** \brief Returns the number of bins in the gradient orientation dimension of the RIFT descriptor. */ + inline int + getNrGradientBins () const { return (nr_gradient_bins_); }; + + /** \brief Estimate the Rotation Invariant Feature Transform (RIFT) descriptor for a given point based on its + * spatial neighborhood of 3D points and the corresponding intensity gradient vector field + * \param[in] cloud the dataset containing the Cartesian coordinates of the points + * \param[in] gradient the dataset containing the intensity gradient at each point in \a cloud + * \param[in] p_idx the index of the query point in \a cloud (i.e. the center of the neighborhood) + * \param[in] radius the radius of the RIFT feature + * \param[in] indices the indices of the points that comprise \a p_idx's neighborhood in \a cloud + * \param[in] squared_distances the squared distances from the query point to each point in the neighborhood + * \param[out] rift_descriptor the resultant RIFT descriptor + */ + void + computeRIFT (const PointCloudIn &cloud, const PointCloudGradient &gradient, int p_idx, float radius, + const std::vector &indices, const std::vector &squared_distances, + Eigen::MatrixXf &rift_descriptor); + + protected: + + /** \brief Estimate the Rotation Invariant Feature Transform (RIFT) descriptors at a set of points given by + * using the surface in setSearchSurface (), the gradient in + * setInputGradient (), and the spatial locator in setSearchMethod () + * \param[out] output the resultant point cloud model dataset that contains the RIFT feature estimates + */ + void + computeFeature (PointCloudOut &output); + + /** \brief The intensity gradient of the input point cloud data*/ + PointCloudGradientConstPtr gradient_; + + /** \brief The number of distance bins in the descriptor. */ + int nr_distance_bins_; + + /** \brief The number of gradient orientation bins in the descriptor. */ + int nr_gradient_bins_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // #ifndef PCL_RIFT_H_ diff --git a/pcl-1.7/pcl/features/rops_estimation.h b/pcl-1.7/pcl/features/rops_estimation.h new file mode 100644 index 0000000..4e27095 --- /dev/null +++ b/pcl-1.7/pcl/features/rops_estimation.h @@ -0,0 +1,236 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : Sergey Ushakov + * Email : sergey.s.ushakov@mail.ru + * + */ + +#ifndef PCL_ROPS_ESIMATION_H_ +#define PCL_ROPS_ESIMATION_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief + * This class implements the method for extracting RoPS features presented in the article + * "Rotational Projection Statistics for 3D Local Surface Description and Object Recognition" by + * Yulan Guo, Ferdous Sohel, Mohammed Bennamoun, Min Lu and Jianwei Wan. + */ + template + class PCL_EXPORTS ROPSEstimation : public pcl::Feature + { + public: + + using Feature ::input_; + using Feature ::indices_; + using Feature ::surface_; + using Feature ::tree_; + + typedef typename pcl::Feature ::PointCloudOut PointCloudOut; + typedef typename pcl::Feature ::PointCloudIn PointCloudIn; + + public: + + /** \brief Simple constructor. */ + ROPSEstimation (); + + /** \brief Virtual destructor. */ + virtual + ~ROPSEstimation (); + + /** \brief Allows to set the number of partition bins that is used for distribution matrix calculation. + * \param[in] number_of_bins number of partition bins + */ + void + setNumberOfPartitionBins (unsigned int number_of_bins); + + /** \brief Returns the nmber of partition bins. */ + unsigned int + getNumberOfPartitionBins () const; + + /** \brief This method sets the number of rotations. + * \param[in] number_of_rotations number of rotations + */ + void + setNumberOfRotations (unsigned int number_of_rotations); + + /** \brief returns the number of rotations. */ + unsigned int + getNumberOfRotations () const; + + /** \brief Allows to set the support radius that is used to crop the local surface of the point. + * \param[in] support_radius support radius + */ + void + setSupportRadius (float support_radius); + + /** \brief Returns the support radius. */ + float + getSupportRadius () const; + + /** \brief This method sets the triangles of the mesh. + * \param[in] triangles list of triangles of the mesh + */ + void + setTriangles (const std::vector & triangles); + + /** \brief Returns the triangles of the mesh. + * \param[out] triangles triangles of tthe mesh + */ + void + getTriangles (std::vector & triangles) const; + + private: + + /** \brief Abstract feature estimation method. + * \param[out] output the resultant features + */ + virtual void + computeFeature (PointCloudOut& output); + + /** \brief This method simply builds the list of triangles for every point. + * The list of triangles for each point consists of indices of triangles it belongs to. + * The only purpose of this method is to improve perfomance of the algorithm. + */ + void + buildListOfPointsTriangles (); + + /** \brief This method crops all the triangles within the given radius of the given point. + * \param[in] point point for which the local surface is computed + * \param[out] local_triangles strores the indices of the triangles that belong to the local surface + * \param[out] local_points stores the indices of the points that belong to the local surface + */ + void + getLocalSurface (const PointInT& point, std::set & local_triangles, std::vector & local_points) const; + + /** \brief This method computes LRF (Local Reference Frame) matrix for the given point. + * \param[in] point point for which the LRF is computed + * \param[in] local_triangles list of triangles that represents the local surface of the point + * \paran[out] lrf_matrix strores computed LRF matrix for the given point + */ + void + computeLRF (const PointInT& point, const std::set & local_triangles, Eigen::Matrix3f& lrf_matrix) const; + + /** \brief This method calculates the eigen values and eigen vectors + * for the given covariance matrix. Note that it returns normalized eigen + * vectors that always form the right-handed coordinate system. + * \param[in] matrix covariance matrix of the cloud + * \param[out] major_axis eigen vector which corresponds to a major eigen value + * \param[out] middle_axis eigen vector which corresponds to a middle eigen value + * \param[out] minor_axis eigen vector which corresponds to a minor eigen value + */ + void + computeEigenVectors (const Eigen::Matrix3f& matrix, Eigen::Vector3f& major_axis, Eigen::Vector3f& middle_axis, + Eigen::Vector3f& minor_axis) const; + + /** \brief This method translates the cloud so that the given point becomes the origin. + * After that the cloud is rotated with the help of the given matrix. + * \param[in] point point which stores the translation information + * \param[in] matrix rotation matrix + * \param[in] local_points point to transform + * \param[out] transformed_cloud stores the transformed cloud + */ + void + transformCloud (const PointInT& point, const Eigen::Matrix3f& matrix, const std::vector & local_points, PointCloudIn& transformed_cloud) const; + + /** \brief This method rotates the cloud around the given axis and computes AABB of the rotated cloud. + * \param[in] axis axis around which cloud must be rotated + * \param[in] angle angle in degrees + * \param[in] cloud cloud to rotate + * \param[out] rotated_cloud stores the rotated cloud + * \param[out] min stores the min point of the AABB + * \param[out] max stores the max point of the AABB + */ + void + rotateCloud (const PointInT& axis, const float angle, const PointCloudIn& cloud, PointCloudIn& rotated_cloud, + Eigen::Vector3f& min, Eigen::Vector3f& max) const; + + /** \brief This method projects the local surface onto the XY, XZ or YZ plane + * and computes the distribution matrix. + * \param[in] projection represents the case of projection. 1 - XY, 2 - XZ, 3 - YZ + * \param[in] min min point of the AABB + * \param[in] max max point of the AABB + * \param[in] cloud cloud containing the points of the local surface + * \param[out] matrix stores computed distribution matrix + */ + void + getDistributionMatrix (const unsigned int projection, const Eigen::Vector3f& min, const Eigen::Vector3f& max, const PointCloudIn& cloud, Eigen::MatrixXf& matrix) const; + + /** \brief This method computes the set ofcentral moments for the given matrix. + * \param[in] matrix input matrix + * \param[out] moments set of computed moments + */ + void + computeCentralMoments (const Eigen::MatrixXf& matrix, std::vector & moments) const; + + private: + + /** \brief Stores the number of partition bins that is used for distribution matrix calculation. */ + unsigned int number_of_bins_; + + /** \brief Stores number of rotations. Central moments are calculated for every rotation. */ + unsigned int number_of_rotations_; + + /** \brief Support radius that is used to crop the local surface of the point. */ + float support_radius_; + + /** \brief Stores the squared support radius. Used to improve performance. */ + float sqr_support_radius_; + + /** \brief Stores the angle step. Step is calculated with respect to number of rotations. */ + float step_; + + /** \brief Stores the set of triangles reprsenting the mesh. */ + std::vector triangles_; + + /** \brief Stores the set of triangles for each point. Its purpose is to improve perfomance. */ + std::vector > triangles_of_the_point_; + + public: + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#define PCL_INSTANTIATE_ROPSEstimation(InT, OutT) template class pcl::ROPSEstimation; + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/features/shot.h b/pcl-1.7/pcl/features/shot.h new file mode 100644 index 0000000..2bb8188 --- /dev/null +++ b/pcl-1.7/pcl/features/shot.h @@ -0,0 +1,416 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_SHOT_H_ +#define PCL_SHOT_H_ + +#include +#include + +namespace pcl +{ + /** \brief SHOTEstimation estimates the Signature of Histograms of OrienTations (SHOT) descriptor for + * a given point cloud dataset containing points and normals. + * + * The suggested PointOutT is pcl::SHOT352. + * + * \note If you use this code in any academic work, please cite: + * + * - F. Tombari, S. Salti, L. Di Stefano + * Unique Signatures of Histograms for Local Surface Description. + * In Proceedings of the 11th European Conference on Computer Vision (ECCV), + * Heraklion, Greece, September 5-11 2010. + * - F. Tombari, S. Salti, L. Di Stefano + * A Combined Texture-Shape Descriptor For Enhanced 3D Feature Matching. + * In Proceedings of the 18th International Conference on Image Processing (ICIP), + * Brussels, Belgium, September 11-14 2011. + * + * \author Samuele Salti, Federico Tombari + * \ingroup features + */ + template + class SHOTEstimationBase : public FeatureFromNormals, + public FeatureWithLocalReferenceFrames + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using Feature::feature_name_; + using Feature::getClassName; + using Feature::input_; + using Feature::indices_; + using Feature::k_; + using Feature::search_parameter_; + using Feature::search_radius_; + using Feature::surface_; + using Feature::fake_surface_; + using FeatureFromNormals::normals_; + using FeatureWithLocalReferenceFrames::frames_; + + typedef typename Feature::PointCloudIn PointCloudIn; + + protected: + /** \brief Empty constructor. + * \param[in] nr_shape_bins the number of bins in the shape histogram + */ + SHOTEstimationBase (int nr_shape_bins = 10) : + nr_shape_bins_ (nr_shape_bins), + shot_ (), lrf_radius_ (0), + sqradius_ (0), radius3_4_ (0), radius1_4_ (0), radius1_2_ (0), + nr_grid_sector_ (32), + maxAngularSectors_ (28), + descLength_ (0) + { + feature_name_ = "SHOTEstimation"; + }; + + + public: + + /** \brief Empty destructor */ + virtual ~SHOTEstimationBase () {} + + /** \brief Estimate the SHOT descriptor for a given point based on its spatial neighborhood of 3D points with normals + * \param[in] index the index of the point in indices_ + * \param[in] indices the k-neighborhood point indices in surface_ + * \param[in] sqr_dists the k-neighborhood point distances in surface_ + * \param[out] shot the resultant SHOT descriptor representing the feature at the query point + */ + virtual void + computePointSHOT (const int index, + const std::vector &indices, + const std::vector &sqr_dists, + Eigen::VectorXf &shot) = 0; + + /** \brief Set the radius used for local reference frame estimation if the frames are not set by the user */ + virtual void + setLRFRadius (float radius) { lrf_radius_ = radius; } + + /** \brief Get the radius used for local reference frame estimation */ + virtual float + getLRFRadius () const { return lrf_radius_; } + + protected: + + /** \brief This method should get called before starting the actual computation. */ + virtual bool + initCompute (); + + /** \brief Quadrilinear interpolation used when color and shape descriptions are NOT activated simultaneously + * + * \param[in] indices the neighborhood point indices + * \param[in] sqr_dists the neighborhood point distances + * \param[in] index the index of the point in indices_ + * \param[out] binDistance the resultant distance shape histogram + * \param[in] nr_bins the number of bins in the shape histogram + * \param[out] shot the resultant SHOT histogram + */ + void + interpolateSingleChannel (const std::vector &indices, + const std::vector &sqr_dists, + const int index, + std::vector &binDistance, + const int nr_bins, + Eigen::VectorXf &shot); + + /** \brief Normalize the SHOT histogram. + * \param[in,out] shot the SHOT histogram + * \param[in] desc_length the length of the histogram + */ + void + normalizeHistogram (Eigen::VectorXf &shot, int desc_length); + + + /** \brief Create a binned distance shape histogram + * \param[in] index the index of the point in indices_ + * \param[in] indices the k-neighborhood point indices in surface_ + * \param[out] bin_distance_shape the resultant histogram + */ + void + createBinDistanceShape (int index, const std::vector &indices, + std::vector &bin_distance_shape); + + /** \brief The number of bins in each shape histogram. */ + int nr_shape_bins_; + + /** \brief Placeholder for a point's SHOT. */ + Eigen::VectorXf shot_; + + /** \brief The radius used for the LRF computation */ + float lrf_radius_; + + /** \brief The squared search radius. */ + double sqradius_; + + /** \brief 3/4 of the search radius. */ + double radius3_4_; + + /** \brief 1/4 of the search radius. */ + double radius1_4_; + + /** \brief 1/2 of the search radius. */ + double radius1_2_; + + /** \brief Number of azimuthal sectors. */ + const int nr_grid_sector_; + + /** \brief ... */ + const int maxAngularSectors_; + + /** \brief One SHOT length. */ + int descLength_; + }; + + /** \brief SHOTEstimation estimates the Signature of Histograms of OrienTations (SHOT) descriptor for + * a given point cloud dataset containing points and normals. + * + * The suggested PointOutT is pcl::SHOT352 + * + * \note If you use this code in any academic work, please cite: + * + * - F. Tombari, S. Salti, L. Di Stefano + * Unique Signatures of Histograms for Local Surface Description. + * In Proceedings of the 11th European Conference on Computer Vision (ECCV), + * Heraklion, Greece, September 5-11 2010. + * - F. Tombari, S. Salti, L. Di Stefano + * A Combined Texture-Shape Descriptor For Enhanced 3D Feature Matching. + * In Proceedings of the 18th International Conference on Image Processing (ICIP), + * Brussels, Belgium, September 11-14 2011. + * + * \author Samuele Salti, Federico Tombari + * \ingroup features + */ + template + class SHOTEstimation : public SHOTEstimationBase + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using SHOTEstimationBase::feature_name_; + using SHOTEstimationBase::getClassName; + using SHOTEstimationBase::indices_; + using SHOTEstimationBase::k_; + using SHOTEstimationBase::search_parameter_; + using SHOTEstimationBase::search_radius_; + using SHOTEstimationBase::surface_; + using SHOTEstimationBase::input_; + using SHOTEstimationBase::normals_; + using SHOTEstimationBase::descLength_; + using SHOTEstimationBase::nr_grid_sector_; + using SHOTEstimationBase::nr_shape_bins_; + using SHOTEstimationBase::sqradius_; + using SHOTEstimationBase::radius3_4_; + using SHOTEstimationBase::radius1_4_; + using SHOTEstimationBase::radius1_2_; + using SHOTEstimationBase::maxAngularSectors_; + using SHOTEstimationBase::interpolateSingleChannel; + using SHOTEstimationBase::shot_; + using FeatureWithLocalReferenceFrames::frames_; + + typedef typename Feature::PointCloudIn PointCloudIn; + + /** \brief Empty constructor. */ + SHOTEstimation () : SHOTEstimationBase (10) + { + feature_name_ = "SHOTEstimation"; + }; + + /** \brief Empty destructor */ + virtual ~SHOTEstimation () {} + + /** \brief Estimate the SHOT descriptor for a given point based on its spatial neighborhood of 3D points with normals + * \param[in] index the index of the point in indices_ + * \param[in] indices the k-neighborhood point indices in surface_ + * \param[in] sqr_dists the k-neighborhood point distances in surface_ + * \param[out] shot the resultant SHOT descriptor representing the feature at the query point + */ + virtual void + computePointSHOT (const int index, + const std::vector &indices, + const std::vector &sqr_dists, + Eigen::VectorXf &shot); + + protected: + /** \brief Estimate the Signatures of Histograms of OrienTations (SHOT) descriptors at a set of points given by + * using the surface in setSearchSurface () and the spatial locator in + * setSearchMethod () + * \param output the resultant point cloud model dataset that contains the SHOT feature estimates + */ + + void + computeFeature (pcl::PointCloud &output); + }; + + /** \brief SHOTColorEstimation estimates the Signature of Histograms of OrienTations (SHOT) descriptor for a given point cloud dataset + * containing points, normals and colors. + * + * The suggested PointOutT is pcl::SHOT1344 + * + * \note If you use this code in any academic work, please cite: + * + * - F. Tombari, S. Salti, L. Di Stefano + * Unique Signatures of Histograms for Local Surface Description. + * In Proceedings of the 11th European Conference on Computer Vision (ECCV), + * Heraklion, Greece, September 5-11 2010. + * - F. Tombari, S. Salti, L. Di Stefano + * A Combined Texture-Shape Descriptor For Enhanced 3D Feature Matching. + * In Proceedings of the 18th International Conference on Image Processing (ICIP), + * Brussels, Belgium, September 11-14 2011. + * + * \author Samuele Salti, Federico Tombari + * \ingroup features + */ + template + class SHOTColorEstimation : public SHOTEstimationBase + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using SHOTEstimationBase::feature_name_; + using SHOTEstimationBase::getClassName; + using SHOTEstimationBase::indices_; + using SHOTEstimationBase::k_; + using SHOTEstimationBase::search_parameter_; + using SHOTEstimationBase::search_radius_; + using SHOTEstimationBase::surface_; + using SHOTEstimationBase::input_; + using SHOTEstimationBase::normals_; + using SHOTEstimationBase::descLength_; + using SHOTEstimationBase::nr_grid_sector_; + using SHOTEstimationBase::nr_shape_bins_; + using SHOTEstimationBase::sqradius_; + using SHOTEstimationBase::radius3_4_; + using SHOTEstimationBase::radius1_4_; + using SHOTEstimationBase::radius1_2_; + using SHOTEstimationBase::maxAngularSectors_; + using SHOTEstimationBase::interpolateSingleChannel; + using SHOTEstimationBase::shot_; + using FeatureWithLocalReferenceFrames::frames_; + + typedef typename Feature::PointCloudIn PointCloudIn; + + /** \brief Empty constructor. + * \param[in] describe_shape + * \param[in] describe_color + */ + SHOTColorEstimation (bool describe_shape = true, + bool describe_color = true) + : SHOTEstimationBase (10), + b_describe_shape_ (describe_shape), + b_describe_color_ (describe_color), + nr_color_bins_ (30) + { + feature_name_ = "SHOTColorEstimation"; + }; + + /** \brief Empty destructor */ + virtual ~SHOTColorEstimation () {} + + /** \brief Estimate the SHOT descriptor for a given point based on its spatial neighborhood of 3D points with normals + * \param[in] index the index of the point in indices_ + * \param[in] indices the k-neighborhood point indices in surface_ + * \param[in] sqr_dists the k-neighborhood point distances in surface_ + * \param[out] shot the resultant SHOT descriptor representing the feature at the query point + */ + virtual void + computePointSHOT (const int index, + const std::vector &indices, + const std::vector &sqr_dists, + Eigen::VectorXf &shot); + + protected: + /** \brief Estimate the Signatures of Histograms of OrienTations (SHOT) descriptors at a set of points given by + * using the surface in setSearchSurface () and the spatial locator in + * setSearchMethod () + * \param output the resultant point cloud model dataset that contains the SHOT feature estimates + */ + void + computeFeature (pcl::PointCloud &output); + + /** \brief Quadrilinear interpolation; used when color and shape descriptions are both activated + * \param[in] indices the neighborhood point indices + * \param[in] sqr_dists the neighborhood point distances + * \param[in] index the index of the point in indices_ + * \param[out] binDistanceShape the resultant distance shape histogram + * \param[out] binDistanceColor the resultant color shape histogram + * \param[in] nr_bins_shape the number of bins in the shape histogram + * \param[in] nr_bins_color the number of bins in the color histogram + * \param[out] shot the resultant SHOT histogram + */ + void + interpolateDoubleChannel (const std::vector &indices, + const std::vector &sqr_dists, + const int index, + std::vector &binDistanceShape, + std::vector &binDistanceColor, + const int nr_bins_shape, + const int nr_bins_color, + Eigen::VectorXf &shot); + + /** \brief Compute shape descriptor. */ + bool b_describe_shape_; + + /** \brief Compute color descriptor. */ + bool b_describe_color_; + + /** \brief The number of bins in each color histogram. */ + int nr_color_bins_; + + public: + /** \brief Converts RGB triplets to CIELab space. + * \param[in] R the red channel + * \param[in] G the green channel + * \param[in] B the blue channel + * \param[out] L the lightness + * \param[out] A the first color-opponent dimension + * \param[out] B2 the second color-opponent dimension + */ + static void + RGB2CIELAB (unsigned char R, unsigned char G, unsigned char B, float &L, float &A, float &B2); + + static float sRGB_LUT[256]; + static float sXYZ_LUT[4000]; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SHOT_H_ diff --git a/pcl-1.7/pcl/features/shot_lrf.h b/pcl-1.7/pcl/features/shot_lrf.h new file mode 100644 index 0000000..ecc1f2c --- /dev/null +++ b/pcl-1.7/pcl/features/shot_lrf.h @@ -0,0 +1,113 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_FEATURES_SHOT_LRF_H_ +#define PCL_FEATURES_SHOT_LRF_H_ + +#include +#include + +namespace pcl +{ + /** \brief SHOTLocalReferenceFrameEstimation estimates the Local Reference Frame used in the calculation + * of the (SHOT) descriptor. + * + * \note If you use this code in any academic work, please cite: + * + * - F. Tombari, S. Salti, L. Di Stefano + * Unique Signatures of Histograms for Local Surface Description. + * In Proceedings of the 11th European Conference on Computer Vision (ECCV), + * Heraklion, Greece, September 5-11 2010. + * - F. Tombari, S. Salti, L. Di Stefano + * A Combined Texture-Shape Descriptor For Enhanced 3D Feature Matching. + * In Proceedings of the 18th International Conference on Image Processing (ICIP), + * Brussels, Belgium, September 11-14 2011. + * + * \author Samuele Salti, Federico Tombari + * \ingroup features + */ + template + class SHOTLocalReferenceFrameEstimation : public Feature + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + /** \brief Constructor */ + SHOTLocalReferenceFrameEstimation () + { + feature_name_ = "SHOTLocalReferenceFrameEstimation"; + } + + /** \brief Empty destructor */ + virtual ~SHOTLocalReferenceFrameEstimation () {} + + protected: + using Feature::feature_name_; + using Feature::getClassName; + //using Feature::searchForNeighbors; + using Feature::input_; + using Feature::indices_; + using Feature::surface_; + using Feature::tree_; + using Feature::search_parameter_; + + typedef typename Feature::PointCloudIn PointCloudIn; + typedef typename Feature::PointCloudOut PointCloudOut; + + /** \brief Computes disambiguated local RF for a point index + * \param[in] index the index + * \param[out] rf reference frame to compute + */ + float + getLocalRF (const int &index, Eigen::Matrix3f &rf); + + /** \brief Feature estimation method. + * \param[out] output the resultant features + */ + virtual void + computeFeature (PointCloudOut &output); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_FEATURES_SHOT_LRF_H_ + diff --git a/pcl-1.7/pcl/features/shot_lrf_omp.h b/pcl-1.7/pcl/features/shot_lrf_omp.h new file mode 100644 index 0000000..958b8b7 --- /dev/null +++ b/pcl-1.7/pcl/features/shot_lrf_omp.h @@ -0,0 +1,117 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_FEATURES_SHOT_LRF_OMP_H_ +#define PCL_FEATURES_SHOT_LRF_OMP_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief SHOTLocalReferenceFrameEstimation estimates the Local Reference Frame used in the calculation + * of the (SHOT) descriptor. + * + * \note If you use this code in any academic work, please cite: + * + * - F. Tombari, S. Salti, L. Di Stefano + * Unique Signatures of Histograms for Local Surface Description. + * In Proceedings of the 11th European Conference on Computer Vision (ECCV), + * Heraklion, Greece, September 5-11 2010. + * - F. Tombari, S. Salti, L. Di Stefano + * A Combined Texture-Shape Descriptor For Enhanced 3D Feature Matching. + * In Proceedings of the 18th International Conference on Image Processing (ICIP), + * Brussels, Belgium, September 11-14 2011. + * + * \author Samuele Salti, Federico Tombari + * \ingroup features + */ + template + class SHOTLocalReferenceFrameEstimationOMP : public SHOTLocalReferenceFrameEstimation + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + /** \brief Constructor */ + SHOTLocalReferenceFrameEstimationOMP () : threads_ (0) + { + feature_name_ = "SHOTLocalReferenceFrameEstimationOMP"; + } + + /** \brief Empty destructor */ + virtual ~SHOTLocalReferenceFrameEstimationOMP () {} + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + + protected: + using Feature::feature_name_; + using Feature::getClassName; + //using Feature::searchForNeighbors; + using Feature::input_; + using Feature::indices_; + using Feature::surface_; + using Feature::tree_; + using Feature::search_parameter_; + using SHOTLocalReferenceFrameEstimation::getLocalRF; + typedef typename Feature::PointCloudIn PointCloudIn; + typedef typename Feature::PointCloudOut PointCloudOut; + + /** \brief Feature estimation method. + * \param[out] output the resultant features + */ + virtual void + computeFeature (PointCloudOut &output); + + /** \brief The number of threads the scheduler should use. */ + unsigned int threads_; + + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_FEATURES_SHOT_LRF_H_ + diff --git a/pcl-1.7/pcl/features/shot_omp.h b/pcl-1.7/pcl/features/shot_omp.h new file mode 100644 index 0000000..7fc34b4 --- /dev/null +++ b/pcl-1.7/pcl/features/shot_omp.h @@ -0,0 +1,215 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_SHOT_OMP_H_ +#define PCL_SHOT_OMP_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief SHOTEstimationOMP estimates the Signature of Histograms of OrienTations (SHOT) descriptor for a given point cloud dataset + * containing points and normals, in parallel, using the OpenMP standard. + * + * The suggested PointOutT is pcl::SHOT352. + * + * \note If you use this code in any academic work, please cite: + * + * - F. Tombari, S. Salti, L. Di Stefano + * Unique Signatures of Histograms for Local Surface Description. + * In Proceedings of the 11th European Conference on Computer Vision (ECCV), + * Heraklion, Greece, September 5-11 2010. + * - F. Tombari, S. Salti, L. Di Stefano + * A Combined Texture-Shape Descriptor For Enhanced 3D Feature Matching. + * In Proceedings of the 18th International Conference on Image Processing (ICIP), + * Brussels, Belgium, September 11-14 2011. + * + * \author Samuele Salti + * \ingroup features + */ + + template + class SHOTEstimationOMP : public SHOTEstimation + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using Feature::feature_name_; + using Feature::getClassName; + using Feature::input_; + using Feature::indices_; + using Feature::k_; + using Feature::search_parameter_; + using Feature::search_radius_; + using Feature::surface_; + using Feature::fake_surface_; + using FeatureFromNormals::normals_; + using FeatureWithLocalReferenceFrames::frames_; + using SHOTEstimationBase::lrf_radius_; + using SHOTEstimation::descLength_; + using SHOTEstimation::nr_grid_sector_; + using SHOTEstimation::nr_shape_bins_; + using SHOTEstimation::sqradius_; + using SHOTEstimation::radius3_4_; + using SHOTEstimation::radius1_4_; + using SHOTEstimation::radius1_2_; + + typedef typename Feature::PointCloudOut PointCloudOut; + typedef typename Feature::PointCloudIn PointCloudIn; + + /** \brief Empty constructor. */ + SHOTEstimationOMP (unsigned int nr_threads = 0) : SHOTEstimation (), threads_ (nr_threads) + { }; + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + + protected: + + /** \brief Estimate the Signatures of Histograms of OrienTations (SHOT) descriptors at a set of points given by + * using the surface in setSearchSurface () and the spatial locator in + * setSearchMethod () + * \param output the resultant point cloud model dataset that contains the SHOT feature estimates + */ + void + computeFeature (PointCloudOut &output); + + /** \brief This method should get called before starting the actual computation. */ + bool + initCompute (); + + /** \brief The number of threads the scheduler should use. */ + unsigned int threads_; + }; + + /** \brief SHOTColorEstimationOMP estimates the Signature of Histograms of OrienTations (SHOT) descriptor for a given point cloud dataset + * containing points, normals and colors, in parallel, using the OpenMP standard. + * + * The suggested PointOutT is pcl::SHOT1344. + * + * \note If you use this code in any academic work, please cite: + * + * - F. Tombari, S. Salti, L. Di Stefano + * Unique Signatures of Histograms for Local Surface Description. + * In Proceedings of the 11th European Conference on Computer Vision (ECCV), + * Heraklion, Greece, September 5-11 2010. + * - F. Tombari, S. Salti, L. Di Stefano + * A Combined Texture-Shape Descriptor For Enhanced 3D Feature Matching. + * In Proceedings of the 18th International Conference on Image Processing (ICIP), + * Brussels, Belgium, September 11-14 2011. + * + * \author Samuele Salti + * \ingroup features + */ + + template + class SHOTColorEstimationOMP : public SHOTColorEstimation + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using Feature::feature_name_; + using Feature::getClassName; + using Feature::input_; + using Feature::indices_; + using Feature::k_; + using Feature::search_parameter_; + using Feature::search_radius_; + using Feature::surface_; + using Feature::fake_surface_; + using FeatureFromNormals::normals_; + using FeatureWithLocalReferenceFrames::frames_; + using SHOTEstimationBase::lrf_radius_; + using SHOTColorEstimation::descLength_; + using SHOTColorEstimation::nr_grid_sector_; + using SHOTColorEstimation::nr_shape_bins_; + using SHOTColorEstimation::sqradius_; + using SHOTColorEstimation::radius3_4_; + using SHOTColorEstimation::radius1_4_; + using SHOTColorEstimation::radius1_2_; + using SHOTColorEstimation::b_describe_shape_; + using SHOTColorEstimation::b_describe_color_; + using SHOTColorEstimation::nr_color_bins_; + + typedef typename Feature::PointCloudOut PointCloudOut; + typedef typename Feature::PointCloudIn PointCloudIn; + + /** \brief Empty constructor. */ + SHOTColorEstimationOMP (bool describe_shape = true, + bool describe_color = true, + unsigned int nr_threads = 0) + : SHOTColorEstimation (describe_shape, describe_color), threads_ (nr_threads) + { + } + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + + protected: + + /** \brief Estimate the Signatures of Histograms of OrienTations (SHOT) descriptors at a set of points given by + * using the surface in setSearchSurface () and the spatial locator in + * setSearchMethod () + * \param output the resultant point cloud model dataset that contains the SHOT feature estimates + */ + void + computeFeature (PointCloudOut &output); + + /** \brief This method should get called before starting the actual computation. */ + bool + initCompute (); + + /** \brief The number of threads the scheduler should use. */ + unsigned int threads_; + }; + +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SHOT_OMP_H_ diff --git a/pcl-1.7/pcl/features/spin_image.h b/pcl-1.7/pcl/features/spin_image.h new file mode 100644 index 0000000..79e9140 --- /dev/null +++ b/pcl-1.7/pcl/features/spin_image.h @@ -0,0 +1,288 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_SPIN_IMAGE_H_ +#define PCL_SPIN_IMAGE_H_ + +#include +#include + +namespace pcl +{ + /** \brief Estimates spin-image descriptors in the given input points. + * + * This class represents spin image descriptor. Spin image is + * a histogram of point locations summed along the bins of the image. + * A 2D accumulator indexed by a and b is created. Next, + * the coordinates (a, b) are computed for a vertex in + * the surface mesh that is within the support of the spin image + * (explained below). The bin indexed by (a, b) in + * the accumulator is then incremented; bilinear interpolation is used + * to smooth the contribution of the vertex. This procedure is repeated + * for all vertices within the support of the spin image. + * The resulting accumulator can be thought of as an image; + * dark areas in the image correspond to bins that contain many projected points. + * As long as the size of the bins in the accumulator is greater + * than the median distance between vertices in the mesh + * (the definition of mesh resolution), the position of individual + * vertices will be averaged out during spin image generation. + * + * \attention The input normals given by \ref setInputNormals have to match + * the input point cloud given by \ref setInputCloud. This behavior is + * different than feature estimation methods that extend \ref + * FeatureFromNormals, which match the normals with the search surface. + * + * With the default paramters, pcl::Histogram<153> is a good choice for PointOutT. + * Of course the dimension of this descriptor must change to match the number + * of bins set by the parameters. + * + * For further information please see: + * + * - Johnson, A. E., & Hebert, M. (1998). Surface Matching for Object + * Recognition in Complex 3D Scenes. Image and Vision Computing, 16, + * 635-651. + * + * The class also implements radial spin images and spin-images in angular domain + * (or both). + * + * \author Roman Shapovalov, Alexander Velizhev + * \ingroup features + */ + template + class SpinImageEstimation : public Feature + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::search_radius_; + using Feature::k_; + using Feature::surface_; + using Feature::fake_surface_; + using PCLBase::input_; + + typedef typename Feature::PointCloudOut PointCloudOut; + + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + + typedef typename pcl::PointCloud PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + /** \brief Constructs empty spin image estimator. + * + * \param[in] image_width spin-image resolution, number of bins along one dimension + * \param[in] support_angle_cos minimal allowed cosine of the angle between + * the normals of input point and search surface point for the point + * to be retained in the support + * \param[in] min_pts_neighb min number of points in the support to correctly estimate + * spin-image. If at some point the support contains less points, exception is thrown + */ + SpinImageEstimation (unsigned int image_width = 8, + double support_angle_cos = 0.0, // when 0, this is bogus, so not applied + unsigned int min_pts_neighb = 0); + + /** \brief Empty destructor */ + virtual ~SpinImageEstimation () {} + + /** \brief Sets spin-image resolution. + * + * \param[in] bin_count spin-image resolution, number of bins along one dimension + */ + void + setImageWidth (unsigned int bin_count) + { + image_width_ = bin_count; + } + + /** \brief Sets the maximum angle for the point normal to get to support region. + * + * \param[in] support_angle_cos minimal allowed cosine of the angle between + * the normals of input point and search surface point for the point + * to be retained in the support + */ + void + setSupportAngle (double support_angle_cos) + { + if (0.0 > support_angle_cos || support_angle_cos > 1.0) // may be permit negative cosine? + { + throw PCLException ("Cosine of support angle should be between 0 and 1", + "spin_image.h", "setSupportAngle"); + } + + support_angle_cos_ = support_angle_cos; + } + + /** \brief Sets minimal points count for spin image computation. + * + * \param[in] min_pts_neighb min number of points in the support to correctly estimate + * spin-image. If at some point the support contains less points, exception is thrown + */ + void + setMinPointCountInNeighbourhood (unsigned int min_pts_neighb) + { + min_pts_neighb_ = min_pts_neighb; + } + + /** \brief Provide a pointer to the input dataset that contains the point normals of + * the input XYZ dataset given by \ref setInputCloud + * + * \attention The input normals given by \ref setInputNormals have to match + * the input point cloud given by \ref setInputCloud. This behavior is + * different than feature estimation methods that extend \ref + * FeatureFromNormals, which match the normals with the search surface. + * \param[in] normals the const boost shared pointer to a PointCloud of normals. + * By convention, L2 norm of each normal should be 1. + */ + inline void + setInputNormals (const PointCloudNConstPtr &normals) + { + input_normals_ = normals; + } + + /** \brief Sets single vector a rotation axis for all input points. + * + * It could be useful e.g. when the vertical axis is known. + * \param[in] axis unit-length vector that serves as rotation axis for reference frame + */ + void + setRotationAxis (const PointNT& axis) + { + rotation_axis_ = axis; + use_custom_axis_ = true; + use_custom_axes_cloud_ = false; + } + + /** \brief Sets array of vectors as rotation axes for input points. + * + * Useful e.g. when one wants to use tangents instead of normals as rotation axes + * \param[in] axes unit-length vectors that serves as rotation axes for + * the corresponding input points' reference frames + */ + void + setInputRotationAxes (const PointCloudNConstPtr& axes) + { + rotation_axes_cloud_ = axes; + + use_custom_axes_cloud_ = true; + use_custom_axis_ = false; + } + + /** \brief Sets input normals as rotation axes (default setting). */ + void + useNormalsAsRotationAxis () + { + use_custom_axis_ = false; + use_custom_axes_cloud_ = false; + } + + /** \brief Sets/unsets flag for angular spin-image domain. + * + * Angular spin-image differs from the vanilla one in the way that not + * the points are collected in the bins but the angles between their + * normals and the normal to the reference point. For further + * information please see + * Endres, F., Plagemann, C., Stachniss, C., & Burgard, W. (2009). + * Unsupervised Discovery of Object Classes from Range Data using Latent Dirichlet Allocation. + * In Robotics: Science and Systems. Seattle, USA. + * \param[in] is_angular true for angular domain, false for point domain + */ + void + setAngularDomain (bool is_angular = true) { is_angular_ = is_angular; } + + /** \brief Sets/unsets flag for radial spin-image structure. + * + * Instead of rectangular coordinate system for reference frame + * polar coordinates are used. Binning is done depending on the distance and + * inclination angle from the reference point + * \param[in] is_radial true for radial spin-image structure, false for rectangular + */ + void + setRadialStructure (bool is_radial = true) { is_radial_ = is_radial; } + + protected: + /** \brief Estimate the Spin Image descriptors at a set of points given by + * setInputWithNormals() using the surface in setSearchSurfaceWithNormals() and the spatial locator + * \param[out] output the resultant point cloud that contains the Spin Image feature estimates + */ + virtual void + computeFeature (PointCloudOut &output); + + /** \brief initializes computations specific to spin-image. + * + * \return true iff input data and initialization are correct + */ + virtual bool + initCompute (); + + /** \brief Computes a spin-image for the point of the scan. + * \param[in] index the index of the reference point in the input cloud + * \return estimated spin-image (or its variant) as a matrix + */ + Eigen::ArrayXXd + computeSiForPoint (int index) const; + + private: + PointCloudNConstPtr input_normals_; + PointCloudNConstPtr rotation_axes_cloud_; + + bool is_angular_; + + PointNT rotation_axis_; + bool use_custom_axis_; + bool use_custom_axes_cloud_; + + bool is_radial_; + + unsigned int image_width_; + double support_angle_cos_; + unsigned int min_pts_neighb_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SPIN_IMAGE_H_ + diff --git a/pcl-1.7/pcl/features/statistical_multiscale_interest_region_extraction.h b/pcl-1.7/pcl/features/statistical_multiscale_interest_region_extraction.h new file mode 100644 index 0000000..6bf91e8 --- /dev/null +++ b/pcl-1.7/pcl/features/statistical_multiscale_interest_region_extraction.h @@ -0,0 +1,130 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef STATISTICAL_MULTISCALE_INTEREST_REGION_EXTRACTION_H_ +#define STATISTICAL_MULTISCALE_INTEREST_REGION_EXTRACTION_H_ + +#include +#include + +namespace pcl +{ + /** \brief Class for extracting interest regions from unstructured point clouds, based on a multi scale + * statistical approach. + * Please refer to the following publications for more details: + * Ranjith Unnikrishnan and Martial Hebert + * Multi-Scale Interest Regions from Unorganized Point Clouds + * Workshop on Search in 3D (S3D), IEEE Conf. on Computer Vision and Pattern Recognition (CVPR) + * June, 2008 + * + * Statistical Approaches to Multi-scale Point Cloud Processing + * Ranjith Unnikrishnan + * PhD Thesis + * The Robotics Institute Carnegie Mellon University + * May, 2008 + * + * \author Alexandru-Eugen Ichim + */ + template + class StatisticalMultiscaleInterestRegionExtraction : public PCLBase + { + public: + typedef boost::shared_ptr > IndicesPtr; + typedef typename boost::shared_ptr > Ptr; + typedef typename boost::shared_ptr > ConstPtr; + + + /** \brief Empty constructor */ + StatisticalMultiscaleInterestRegionExtraction () : + scale_values_ (), geodesic_distances_ (), F_scales_ () + {}; + + /** \brief Method that generates the underlying nearest neighbor graph based on the + * input point cloud + */ + void + generateCloudGraph (); + + /** \brief The method to be called in order to run the algorithm and produce the resulting + * set of regions of interest + */ + void + computeRegionsOfInterest (std::list& rois); + + /** \brief Method for setting the scale parameters for the algorithm + * \param scale_values vector of scales to determine the size of each scaling step + */ + inline void + setScalesVector (std::vector &scale_values) { scale_values_ = scale_values; } + + /** \brief Method for getting the scale parameters vector */ + inline std::vector + getScalesVector () { return scale_values_; } + + + private: + /** \brief Checks if all the necessary input was given and the computations can successfully start */ + bool + initCompute (); + + void + geodesicFixedRadiusSearch (size_t &query_index, + float &radius, + std::vector &result_indices); + + void + computeF (); + + void + extractExtrema (std::list& rois); + + using PCLBase::initCompute; + using PCLBase::input_; + std::vector scale_values_; + std::vector > geodesic_distances_; + std::vector > F_scales_; + }; +} + + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif /* STATISTICAL_MULTISCALE_INTEREST_REGION_EXTRACTION_H_ */ diff --git a/pcl-1.7/pcl/features/usc.h b/pcl-1.7/pcl/features/usc.h new file mode 100644 index 0000000..4fe7966 --- /dev/null +++ b/pcl-1.7/pcl/features/usc.h @@ -0,0 +1,206 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_USC_H_ +#define PCL_FEATURES_USC_H_ + +#include +#include + +namespace pcl +{ + /** \brief UniqueShapeContext implements the Unique Shape Context Descriptor + * described here: + * + * - F. Tombari, S. Salti, L. Di Stefano, + * "Unique Shape Context for 3D data description", + * International Workshop on 3D Object Retrieval (3DOR 10) - + * in conjuction with ACM Multimedia 2010 + * + * The suggested PointOutT is pcl::ShapeContext1980 + * + * \author Alessandro Franchi, Federico Tombari, Samuele Salti (original code) + * \author Nizar Sallem (port to PCL) + * \ingroup features + */ + template + class UniqueShapeContext : public Feature, + public FeatureWithLocalReferenceFrames + { + public: + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::search_parameter_; + using Feature::search_radius_; + using Feature::surface_; + using Feature::fake_surface_; + using Feature::input_; + using Feature::searchForNeighbors; + using FeatureWithLocalReferenceFrames::frames_; + + typedef typename Feature::PointCloudOut PointCloudOut; + typedef typename Feature::PointCloudIn PointCloudIn; + typedef typename boost::shared_ptr > Ptr; + typedef typename boost::shared_ptr > ConstPtr; + + + /** \brief Constructor. */ + UniqueShapeContext () : + radii_interval_(0), theta_divisions_(0), phi_divisions_(0), volume_lut_(0), + azimuth_bins_(12), elevation_bins_(11), radius_bins_(15), + min_radius_(0.1), point_density_radius_(0.2), descriptor_length_ (), local_radius_ (2.5) + { + feature_name_ = "UniqueShapeContext"; + search_radius_ = 2.5; + } + + virtual ~UniqueShapeContext() { } + + //inline void + //setAzimuthBins (size_t bins) { azimuth_bins_ = bins; } + + /** \return The number of bins along the azimuth. */ + inline size_t + getAzimuthBins () const { return (azimuth_bins_); } + + //inline void + //setElevationBins (size_t bins) { elevation_bins_ = bins; } + + /** \return The number of bins along the elevation */ + inline size_t + getElevationBins () const { return (elevation_bins_); } + + //inline void + //setRadiusBins (size_t bins) { radius_bins_ = bins; } + + /** \return The number of bins along the radii direction. */ + inline size_t + getRadiusBins () const { return (radius_bins_); } + + /** The minimal radius value for the search sphere (rmin) in the original paper + * \param[in] radius the desired minimal radius + */ + inline void + setMinimalRadius (double radius) { min_radius_ = radius; } + + /** \return The minimal sphere radius. */ + inline double + getMinimalRadius () const { return (min_radius_); } + + /** This radius is used to compute local point density + * density = number of points within this radius + * \param[in] radius Value of the point density search radius + */ + inline void + setPointDensityRadius (double radius) { point_density_radius_ = radius; } + + /** \return The point density search radius. */ + inline double + getPointDensityRadius () const { return (point_density_radius_); } + + /** Set the local RF radius value + * \param[in] radius the desired local RF radius + */ + inline void + setLocalRadius (double radius) { local_radius_ = radius; } + + /** \return The local RF radius. */ + inline double + getLocalRadius () const { return (local_radius_); } + + protected: + /** Compute 3D shape context feature descriptor + * \param[in] index point index in input_ + * \param[out] desc descriptor to compute + */ + void + computePointDescriptor (size_t index, std::vector &desc); + + /** \brief Initialize computation by allocating all the intervals and the volume lookup table. */ + virtual bool + initCompute (); + + /** \brief The actual feature computation. + * \param[out] output the resultant features + */ + virtual void + computeFeature (PointCloudOut &output); + + /** \brief values of the radii interval. */ + std::vector radii_interval_; + + /** \brief Theta divisions interval. */ + std::vector theta_divisions_; + + /** \brief Phi divisions interval. */ + std::vector phi_divisions_; + + /** \brief Volumes look up table. */ + std::vector volume_lut_; + + /** \brief Bins along the azimuth dimension. */ + size_t azimuth_bins_; + + /** \brief Bins along the elevation dimension. */ + size_t elevation_bins_; + + /** \brief Bins along the radius dimension. */ + size_t radius_bins_; + + /** \brief Minimal radius value. */ + double min_radius_; + + /** \brief Point density radius. */ + double point_density_radius_; + + /** \brief Descriptor length. */ + size_t descriptor_length_; + + /** \brief Radius to compute local RF. */ + double local_radius_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_USC_H_ diff --git a/pcl-1.7/pcl/features/vfh.h b/pcl-1.7/pcl/features/vfh.h new file mode 100644 index 0000000..ec7501e --- /dev/null +++ b/pcl-1.7/pcl/features/vfh.h @@ -0,0 +1,276 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FEATURES_VFH_H_ +#define PCL_FEATURES_VFH_H_ + +#include +#include + +namespace pcl +{ + /** \brief VFHEstimation estimates the Viewpoint Feature Histogram (VFH) descriptor for a given point cloud + * dataset containing points and normals. The default VFH implementation uses 45 binning subdivisions for each of + * the three extended FPFH values, plus another 45 binning subdivisions for the distances between each point and + * the centroid and 128 binning subdivisions for the viewpoint component, which results in a + * 308-byte array of float values. These are stored in a pcl::VFHSignature308 point type. + * A major difference between the PFH/FPFH descriptors and VFH, is that for a given point cloud dataset, only a + * single VFH descriptor will be estimated (vfhs->points.size() should be 1), while the resultant PFH/FPFH data + * will have the same number of entries as the number of points in the cloud. + * + * \note If you use this code in any academic work, please cite: + * + * - R.B. Rusu, G. Bradski, R. Thibaux, J. Hsu. + * Fast 3D Recognition and Pose Using the Viewpoint Feature Histogram. + * In Proceedings of International Conference on Intelligent Robots and Systems (IROS) + * Taipei, Taiwan, October 18-22 2010. + * + * \note The code is stateful as we do not expect this class to be multicore parallelized. Please look at + * \ref FPFHEstimationOMP for an example of a parallel implementation of the FPFH (Fast Point Feature Histogram). + * \author Radu B. Rusu + * \ingroup features + */ + template + class VFHEstimation : public FeatureFromNormals + { + public: + using Feature::feature_name_; + using Feature::getClassName; + using Feature::indices_; + using Feature::k_; + using Feature::search_radius_; + using Feature::input_; + using Feature::surface_; + using FeatureFromNormals::normals_; + + typedef typename Feature::PointCloudOut PointCloudOut; + typedef typename boost::shared_ptr > Ptr; + typedef typename boost::shared_ptr > ConstPtr; + + + /** \brief Empty constructor. */ + VFHEstimation () : + nr_bins_f1_ (45), nr_bins_f2_ (45), nr_bins_f3_ (45), nr_bins_f4_ (45), nr_bins_vp_ (128), + vpx_ (0), vpy_ (0), vpz_ (0), + hist_f1_ (), hist_f2_ (), hist_f3_ (), hist_f4_ (), hist_vp_ (), + normal_to_use_ (), centroid_to_use_ (), use_given_normal_ (false), use_given_centroid_ (false), + normalize_bins_ (true), normalize_distances_ (false), size_component_ (false), + d_pi_ (1.0f / (2.0f * static_cast (M_PI))) + { + hist_f1_.setZero (nr_bins_f1_); + hist_f2_.setZero (nr_bins_f2_); + hist_f3_.setZero (nr_bins_f3_); + hist_f4_.setZero (nr_bins_f4_); + search_radius_ = 0; + k_ = 0; + feature_name_ = "VFHEstimation"; + } + + /** \brief Estimate the SPFH (Simple Point Feature Histograms) signatures of the angular + * (f1, f2, f3) and distance (f4) features for a given point from its neighborhood + * \param[in] centroid_p the centroid point + * \param[in] centroid_n the centroid normal + * \param[in] cloud the dataset containing the XYZ Cartesian coordinates of the two points + * \param[in] normals the dataset containing the surface normals at each point in \a cloud + * \param[in] indices the k-neighborhood point indices in the dataset + */ + void + computePointSPFHSignature (const Eigen::Vector4f ¢roid_p, const Eigen::Vector4f ¢roid_n, + const pcl::PointCloud &cloud, const pcl::PointCloud &normals, + const std::vector &indices); + + /** \brief Set the viewpoint. + * \param[in] vpx the X coordinate of the viewpoint + * \param[in] vpy the Y coordinate of the viewpoint + * \param[in] vpz the Z coordinate of the viewpoint + */ + inline void + setViewPoint (float vpx, float vpy, float vpz) + { + vpx_ = vpx; + vpy_ = vpy; + vpz_ = vpz; + } + + /** \brief Get the viewpoint. */ + inline void + getViewPoint (float &vpx, float &vpy, float &vpz) + { + vpx = vpx_; + vpy = vpy_; + vpz = vpz_; + } + + /** \brief Set use_given_normal_ + * \param[in] use Set to true if you want to use the normal passed to setNormalUse(normal) + */ + inline void + setUseGivenNormal (bool use) + { + use_given_normal_ = use; + } + + /** \brief Set the normal to use + * \param[in] normal Sets the normal to be used in the VFH computation. It is is used + * to build the Darboux Coordinate system. + */ + inline void + setNormalToUse (const Eigen::Vector3f &normal) + { + normal_to_use_ = Eigen::Vector4f (normal[0], normal[1], normal[2], 0); + } + + /** \brief Set use_given_centroid_ + * \param[in] use Set to true if you want to use the centroid passed through setCentroidToUse(centroid) + */ + inline void + setUseGivenCentroid (bool use) + { + use_given_centroid_ = use; + } + + /** \brief Set centroid_to_use_ + * \param[in] centroid Centroid to be used in the VFH computation. It is used to compute the distances + * from all points to this centroid. + */ + inline void + setCentroidToUse (const Eigen::Vector3f ¢roid) + { + centroid_to_use_ = Eigen::Vector4f (centroid[0], centroid[1], centroid[2], 0); + } + + /** \brief set normalize_bins_ + * \param[in] normalize If true, the VFH bins are normalized using the total number of points + */ + inline void + setNormalizeBins (bool normalize) + { + normalize_bins_ = normalize; + } + + /** \brief set normalize_distances_ + * \param[in] normalize If true, the 4th component of VFH (shape distribution component) get normalized + * by the maximum size between the centroid and the point cloud + */ + inline void + setNormalizeDistance (bool normalize) + { + normalize_distances_ = normalize; + } + + /** \brief set size_component_ + * \param[in] fill_size True if the 4th component of VFH (shape distribution component) needs to be filled. + * Otherwise, it is set to zero. + */ + inline void + setFillSizeComponent (bool fill_size) + { + size_component_ = fill_size; + } + + /** \brief Overloaded computed method from pcl::Feature. + * \param[out] output the resultant point cloud model dataset containing the estimated features + */ + void + compute (PointCloudOut &output); + + private: + + /** \brief The number of subdivisions for each feature interval. */ + int nr_bins_f1_, nr_bins_f2_, nr_bins_f3_, nr_bins_f4_, nr_bins_vp_; + + /** \brief Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit + * from VFHEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0. + */ + float vpx_, vpy_, vpz_; + + /** \brief Estimate the Viewpoint Feature Histograms (VFH) descriptors at a set of points given by + * using the surface in setSearchSurface () and the spatial locator in + * setSearchMethod () + * \param[out] output the resultant point cloud model dataset that contains the VFH feature estimates + */ + void + computeFeature (PointCloudOut &output); + + protected: + /** \brief This method should get called before starting the actual computation. */ + bool + initCompute (); + + /** \brief Placeholder for the f1 histogram. */ + Eigen::VectorXf hist_f1_; + /** \brief Placeholder for the f2 histogram. */ + Eigen::VectorXf hist_f2_; + /** \brief Placeholder for the f3 histogram. */ + Eigen::VectorXf hist_f3_; + /** \brief Placeholder for the f4 histogram. */ + Eigen::VectorXf hist_f4_; + /** \brief Placeholder for the vp histogram. */ + Eigen::VectorXf hist_vp_; + + /** \brief Normal to be used to computed VFH. Default, the average normal of the whole point cloud */ + Eigen::Vector4f normal_to_use_; + /** \brief Centroid to be used to computed VFH. Default, the centroid of the whole point cloud */ + Eigen::Vector4f centroid_to_use_; + + // VFH configuration parameters because CVFH instantiates it. See constructor for default values. + + /** \brief Use the normal_to_use_ */ + bool use_given_normal_; + /** \brief Use the centroid_to_use_ */ + bool use_given_centroid_; + /** \brief Normalize bins by the number the total number of points. */ + bool normalize_bins_; + /** \brief Normalize the shape distribution component of VFH */ + bool normalize_distances_; + /** \brief Activate or deactivate the size component of VFH */ + bool size_component_; + + private: + /** \brief Float constant = 1.0 / (2.0 * M_PI) */ + float d_pi_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FEATURES_VFH_H_ diff --git a/pcl-1.7/pcl/filters/approximate_voxel_grid.h b/pcl-1.7/pcl/filters/approximate_voxel_grid.h new file mode 100644 index 0000000..06210ac --- /dev/null +++ b/pcl-1.7/pcl/filters/approximate_voxel_grid.h @@ -0,0 +1,250 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: voxel_grid.h 1374 2011-06-19 02:29:56Z bouffa $ + * + */ + +#ifndef PCL_FILTERS_APPROXIMATE_VOXEL_GRID_MAP_H_ +#define PCL_FILTERS_APPROXIMATE_VOXEL_GRID_MAP_H_ + +#include +#include + +namespace pcl +{ + /** \brief Helper functor structure for copying data between an Eigen::VectorXf and a PointT. */ + template + struct xNdCopyEigenPointFunctor + { + typedef typename traits::POD::type Pod; + + xNdCopyEigenPointFunctor (const Eigen::VectorXf &p1, PointT &p2) + : p1_ (p1), + p2_ (reinterpret_cast(p2)), + f_idx_ (0) { } + + template inline void operator() () + { + //boost::fusion::at_key (p2_) = p1_[f_idx_++]; + typedef typename pcl::traits::datatype::type T; + uint8_t* data_ptr = reinterpret_cast(&p2_) + pcl::traits::offset::value; + *reinterpret_cast(data_ptr) = static_cast (p1_[f_idx_++]); + } + + private: + const Eigen::VectorXf &p1_; + Pod &p2_; + int f_idx_; + }; + + /** \brief Helper functor structure for copying data between an Eigen::VectorXf and a PointT. */ + template + struct xNdCopyPointEigenFunctor + { + typedef typename traits::POD::type Pod; + + xNdCopyPointEigenFunctor (const PointT &p1, Eigen::VectorXf &p2) + : p1_ (reinterpret_cast(p1)), p2_ (p2), f_idx_ (0) { } + + template inline void operator() () + { + //p2_[f_idx_++] = boost::fusion::at_key (p1_); + typedef typename pcl::traits::datatype::type T; + const uint8_t* data_ptr = reinterpret_cast(&p1_) + pcl::traits::offset::value; + p2_[f_idx_++] = static_cast (*reinterpret_cast(data_ptr)); + } + + private: + const Pod &p1_; + Eigen::VectorXf &p2_; + int f_idx_; + }; + + /** \brief ApproximateVoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. + * + * \author James Bowman, Radu B. Rusu + * \ingroup filters + */ + template + class ApproximateVoxelGrid: public Filter + { + using Filter::filter_name_; + using Filter::getClassName; + using Filter::input_; + using Filter::indices_; + + typedef typename Filter::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + private: + struct he + { + he () : ix (), iy (), iz (), count (0), centroid () {} + int ix, iy, iz; + int count; + Eigen::VectorXf centroid; + }; + + public: + + typedef boost::shared_ptr< ApproximateVoxelGrid > Ptr; + typedef boost::shared_ptr< const ApproximateVoxelGrid > ConstPtr; + + + /** \brief Empty constructor. */ + ApproximateVoxelGrid () : + pcl::Filter (), + leaf_size_ (Eigen::Vector3f::Ones ()), + inverse_leaf_size_ (Eigen::Array3f::Ones ()), + downsample_all_data_ (true), histsize_ (512), + history_ (new he[histsize_]) + { + filter_name_ = "ApproximateVoxelGrid"; + } + + /** \brief Copy constructor. + * \param[in] src the approximate voxel grid to copy into this. + */ + ApproximateVoxelGrid (const ApproximateVoxelGrid &src) : + pcl::Filter (), + leaf_size_ (src.leaf_size_), + inverse_leaf_size_ (src.inverse_leaf_size_), + downsample_all_data_ (src.downsample_all_data_), + histsize_ (src.histsize_), + history_ () + { + history_ = new he[histsize_]; + for (size_t i = 0; i < histsize_; i++) + history_[i] = src.history_[i]; + } + + + /** \brief Destructor. + */ + ~ApproximateVoxelGrid () + { + delete [] history_; + } + + + /** \brief Copy operator. + * \param[in] src the approximate voxel grid to copy into this. + */ + inline ApproximateVoxelGrid& + operator = (const ApproximateVoxelGrid &src) + { + leaf_size_ = src.leaf_size_; + inverse_leaf_size_ = src.inverse_leaf_size_; + downsample_all_data_ = src.downsample_all_data_; + histsize_ = src.histsize_; + history_ = new he[histsize_]; + for (size_t i = 0; i < histsize_; i++) + history_[i] = src.history_[i]; + return (*this); + } + + /** \brief Set the voxel grid leaf size. + * \param[in] leaf_size the voxel grid leaf size + */ + inline void + setLeafSize (const Eigen::Vector3f &leaf_size) + { + leaf_size_ = leaf_size; + inverse_leaf_size_ = Eigen::Array3f::Ones () / leaf_size_.array (); + } + + /** \brief Set the voxel grid leaf size. + * \param[in] lx the leaf size for X + * \param[in] ly the leaf size for Y + * \param[in] lz the leaf size for Z + */ + inline void + setLeafSize (float lx, float ly, float lz) + { + setLeafSize (Eigen::Vector3f (lx, ly, lz)); + } + + /** \brief Get the voxel grid leaf size. */ + inline Eigen::Vector3f + getLeafSize () const { return (leaf_size_); } + + /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. + * \param downsample the new value (true/false) + */ + inline void + setDownsampleAllData (bool downsample) { downsample_all_data_ = downsample; } + + /** \brief Get the state of the internal downsampling parameter (true if + * all fields need to be downsampled, false if just XYZ). + */ + inline bool + getDownsampleAllData () const { return (downsample_all_data_); } + + protected: + /** \brief The size of a leaf. */ + Eigen::Vector3f leaf_size_; + + /** \brief Compute 1/leaf_size_ to avoid division later */ + Eigen::Array3f inverse_leaf_size_; + + /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. */ + bool downsample_all_data_; + + /** \brief history buffer size, power of 2 */ + size_t histsize_; + + /** \brief history buffer */ + struct he* history_; + + typedef typename pcl::traits::fieldList::type FieldList; + + /** \brief Downsample a Point Cloud using a voxelized grid approach + * \param output the resultant point cloud message + */ + void + applyFilter (PointCloud &output); + + /** \brief Write a single point from the hash to the output cloud + */ + void + flush (PointCloud &output, size_t op, he *hhe, int rgba_index, int centroid_size); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FILTERS_VOXEL_GRID_MAP_H_ diff --git a/pcl-1.7/pcl/filters/bilateral.h b/pcl-1.7/pcl/filters/bilateral.h new file mode 100644 index 0000000..9341d78 --- /dev/null +++ b/pcl-1.7/pcl/filters/bilateral.h @@ -0,0 +1,150 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_BILATERAL_H_ +#define PCL_FILTERS_BILATERAL_H_ + +#include +#include + +namespace pcl +{ + /** \brief A bilateral filter implementation for point cloud data. Uses the intensity data channel. + * \note For more information please see + * C. Tomasi and R. Manduchi. Bilateral Filtering for Gray and Color Images. + * In Proceedings of the IEEE International Conference on Computer Vision, + * 1998. + * \author Luca Penasa + * \ingroup filters + */ + template + class BilateralFilter : public Filter + { + using Filter::input_; + using Filter::indices_; + typedef typename Filter::PointCloud PointCloud; + typedef typename pcl::search::Search::Ptr KdTreePtr; + + public: + + typedef boost::shared_ptr< BilateralFilter > Ptr; + typedef boost::shared_ptr< const BilateralFilter > ConstPtr; + + + /** \brief Constructor. + * Sets sigma_s_ to 0 and sigma_r_ to MAXDBL + */ + BilateralFilter () : sigma_s_ (0), + sigma_r_ (std::numeric_limits::max ()), + tree_ () + { + } + + + /** \brief Filter the input data and store the results into output + * \param[out] output the resultant point cloud message + */ + void + applyFilter (PointCloud &output); + + /** \brief Compute the intensity average for a single point + * \param[in] pid the point index to compute the weight for + * \param[in] indices the set of nearest neighor indices + * \param[in] distances the set of nearest neighbor distances + * \return the intensity average at a given point index + */ + double + computePointWeight (const int pid, const std::vector &indices, const std::vector &distances); + + /** \brief Set the half size of the Gaussian bilateral filter window. + * \param[in] sigma_s the half size of the Gaussian bilateral filter window to use + */ + inline void + setHalfSize (const double sigma_s) + { sigma_s_ = sigma_s; } + + /** \brief Get the half size of the Gaussian bilateral filter window as set by the user. */ + inline double + getHalfSize () const + { return (sigma_s_); } + + /** \brief Set the standard deviation parameter + * \param[in] sigma_r the new standard deviation parameter + */ + inline void + setStdDev (const double sigma_r) + { sigma_r_ = sigma_r;} + + /** \brief Get the value of the current standard deviation parameter of the bilateral filter. */ + inline double + getStdDev () const + { return (sigma_r_); } + + /** \brief Provide a pointer to the search object. + * \param[in] tree a pointer to the spatial search object. + */ + inline void + setSearchMethod (const KdTreePtr &tree) + { tree_ = tree; } + + private: + + /** \brief The bilateral filter Gaussian distance kernel. + * \param[in] x the spatial distance (distance or intensity) + * \param[in] sigma standard deviation + */ + inline double + kernel (double x, double sigma) + { return (exp (- (x*x)/(2*sigma*sigma))); } + + /** \brief The half size of the Gaussian bilateral filter window (e.g., spatial extents in Euclidean). */ + double sigma_s_; + /** \brief The standard deviation of the bilateral filter (e.g., standard deviation in intensity). */ + double sigma_r_; + + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_FILTERS_BILATERAL_H_ diff --git a/pcl-1.7/pcl/filters/boost.h b/pcl-1.7/pcl/filters/boost.h new file mode 100644 index 0000000..47c274a --- /dev/null +++ b/pcl-1.7/pcl/filters/boost.h @@ -0,0 +1,61 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: io.h 5850 2012-06-06 14:04:59Z stfox88 $ + * + */ + +#ifndef PCL_FILTERS_BOOST_H_ +#define PCL_FILTERS_BOOST_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +// Marking all Boost headers as system headers to remove warnings +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#endif // PCL_FILTERS_BOOST_H_ diff --git a/pcl-1.7/pcl/filters/box_clipper3D.h b/pcl-1.7/pcl/filters/box_clipper3D.h new file mode 100644 index 0000000..b133d36 --- /dev/null +++ b/pcl-1.7/pcl/filters/box_clipper3D.h @@ -0,0 +1,127 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_BOX_CLIPPER3D_H_ +#define PCL_BOX_CLIPPER3D_H_ +#include "clipper3D.h" + +namespace pcl +{ + /** + * \author Suat Gedikli + * \brief Implementation of a box clipper in 3D. Actually it allows affine transformations, thus any parallelepiped in general pose. + * The affine transformation is used to transform the point before clipping it using the unit cube centered at origin and with an extend of -1 to +1 in each dimension + * \ingroup filters + */ + template + class BoxClipper3D : public Clipper3D + { + public: + + typedef boost::shared_ptr< BoxClipper3D > Ptr; + typedef boost::shared_ptr< const BoxClipper3D > ConstPtr; + + + /** + * \author Suat Gedikli + * \brief Constructor taking an affine transformation matrix, which allows also shearing of the clipping area + * \param[in] transformation the 3x3 affine transformation matrix that is used to describe the unit cube + */ + BoxClipper3D (const Eigen::Affine3f& transformation); + + /** + * \brief creates a BoxClipper object with a scaled box in general pose + * \param[in] rodrigues the rotation axis and angle given by the vector direction and length respectively + * \param[in] translation the position of the box center + * \param[in] box_size the size of the box for each dimension + */ + BoxClipper3D (const Eigen::Vector3f& rodrigues, const Eigen::Vector3f& translation, const Eigen::Vector3f& box_size); + + /** + * \brief Set the affine transformation + * \param[in] transformation + */ + void setTransformation (const Eigen::Affine3f& transformation); + + /** + * \brief sets the box in general pose given by the orientation position and size + * \param[in] rodrigues the rotation axis and angle given by the vector direction and length respectively + * \param[in] translation the position of the box center + * \param[in] box_size the size of the box for each dimension + */ + void setTransformation (const Eigen::Vector3f& rodrigues, const Eigen::Vector3f& translation, const Eigen::Vector3f& box_size); + + /** + * \brief virtual destructor + */ + virtual ~BoxClipper3D () throw (); + + virtual bool + clipPoint3D (const PointT& point) const; + + virtual bool + clipLineSegment3D (PointT& from, PointT& to) const; + + virtual void + clipPlanarPolygon3D (std::vector >& polygon) const; + + virtual void + clipPlanarPolygon3D (const std::vector >& polygon, std::vector& clipped_polygon) const; + + virtual void + clipPointCloud3D (const pcl::PointCloud &cloud_in, std::vector& clipped, const std::vector& indices = std::vector ()) const; + + virtual Clipper3D* + clone () const; + + protected: + float getDistance (const PointT& point) const; + void transformPoint (const PointT& pointIn, PointT& pointOut) const; + private: + /** + * \brief the affine transformation that is applied before clipping is done on the unit cube. + */ + Eigen::Affine3f transformation_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#include + +#endif // PCL_BOX_CLIPPER3D_H_ diff --git a/pcl-1.7/pcl/filters/clipper3D.h b/pcl-1.7/pcl/filters/clipper3D.h new file mode 100644 index 0000000..ddd9ab0 --- /dev/null +++ b/pcl-1.7/pcl/filters/clipper3D.h @@ -0,0 +1,115 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_CLIPPER3D_H_ +#define PCL_CLIPPER3D_H_ +#include +#include +#include + +namespace pcl +{ + /** + * \brief Base class for 3D clipper objects + * \author Suat Gedikli + * \ingroup filters + */ + template + class Clipper3D + { + public: + typedef boost::shared_ptr< Clipper3D > Ptr; + typedef boost::shared_ptr< const Clipper3D > ConstPtr; + + /** + * \brief virtual destructor. Never throws an exception. + */ + virtual ~Clipper3D () throw () {} + + /** + * \brief interface to clip a single point + * \param[in] point the point to check against + * \return true, it point still exists, false if its clipped + */ + virtual bool + clipPoint3D (const PointT& point) const = 0; + + /** + * \brief interface to clip a line segment given by two end points. The order of the end points is unimportant and will sty the same after clipping. + * This means basically, that the direction of the line will not flip after clipping. + * \param[in,out] pt1 start point of the line + * \param[in,out] pt2 end point of the line + * \return true if the clipped line is not empty, thus the parameters are still valid, false if line completely outside clipping space + */ + virtual bool + clipLineSegment3D (PointT& pt1, PointT& pt2) const = 0; + + /** + * \brief interface to clip a planar polygon given by an ordered list of points + * \param[in,out] polygon the polygon in any direction (ccw or cw) but ordered, thus two neighboring points define an edge of the polygon + */ + virtual void + clipPlanarPolygon3D (std::vector >& polygon) const = 0; + + /** + * \brief interface to clip a planar polygon given by an ordered list of points + * \param[in] polygon the polygon in any direction (ccw or cw) but ordered, thus two neighboring points define an edge of the polygon + * \param[out] clipped_polygon the clipped polygon + */ + virtual void + clipPlanarPolygon3D (const std::vector >& polygon, std::vector >& clipped_polygon) const = 0; + + /** + * \brief interface to clip a point cloud + * \param[in] cloud_in input point cloud + * \param[out] clipped indices of points that remain after clipping the input cloud + * \param[in] indices the indices of points in the point cloud to be clipped. + * \return list of indices of remaining points after clipping. + */ + virtual void + clipPointCloud3D (const pcl::PointCloud &cloud_in, std::vector& clipped, const std::vector& indices = std::vector ()) const = 0; + + /** + * \brief polymorphic method to clone the underlying clipper with its parameters. + * \return the new clipper object from the specific subclass with all its parameters. + */ + virtual Clipper3D* + clone () const = 0; + }; +} + +#endif // PCL_CLIPPER3D_H_ diff --git a/pcl-1.7/pcl/filters/conditional_removal.h b/pcl-1.7/pcl/filters/conditional_removal.h new file mode 100644 index 0000000..50f8a78 --- /dev/null +++ b/pcl-1.7/pcl/filters/conditional_removal.h @@ -0,0 +1,709 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTER_FIELD_VAL_CONDITION_H_ +#define PCL_FILTER_FIELD_VAL_CONDITION_H_ +#include +#include + +namespace pcl +{ + ////////////////////////////////////////////////////////////////////////////////////////// + namespace ComparisonOps + { + /** \brief The kind of comparison operations that are possible within a + * comparison object + */ + typedef enum + { + GT, GE, LT, LE, EQ + } CompareOp; + } + + ////////////////////////////////////////////////////////////////////////////////////////// + /** \brief A datatype that enables type-correct comparisons. */ + template + class PointDataAtOffset + { + public: + /** \brief Constructor. */ + PointDataAtOffset (uint8_t datatype, uint32_t offset) : + datatype_ (datatype), offset_ (offset) + { + } + + /** \brief Compare function. + * \param p the point to compare + * \param val the value to compare the point to + */ + int + compare (const PointT& p, const double& val); + protected: + /** \brief The type of data. */ + uint8_t datatype_; + + /** \brief The data offset. */ + uint32_t offset_; + private: + PointDataAtOffset () : datatype_ (), offset_ () {} + }; + + ////////////////////////////////////////////////////////////////////////////////////////// + /** \brief The (abstract) base class for the comparison object. */ + template + class ComparisonBase + { + public: + typedef boost::shared_ptr< ComparisonBase > Ptr; + typedef boost::shared_ptr< const ComparisonBase > ConstPtr; + + /** \brief Constructor. */ + ComparisonBase () : capable_ (false), field_name_ (), offset_ (), op_ () {} + + /** \brief Destructor. */ + virtual ~ComparisonBase () {} + + /** \brief Return if the comparison is capable. */ + inline bool + isCapable () const + { + return (capable_); + } + + /** \brief Evaluate function. */ + virtual bool + evaluate (const PointT &point) const = 0; + + protected: + /** \brief True if capable. */ + bool capable_; + + /** \brief Field name to compare data on. */ + std::string field_name_; + + /** \brief The data offset. */ + uint32_t offset_; + + /** \brief The comparison operator type. */ + ComparisonOps::CompareOp op_; + }; + + ////////////////////////////////////////////////////////////////////////////////////////// + /** \brief The field-based specialization of the comparison object. */ + template + class FieldComparison : public ComparisonBase + { + using ComparisonBase::field_name_; + using ComparisonBase::op_; + using ComparisonBase::capable_; + + public: + typedef boost::shared_ptr< FieldComparison > Ptr; + typedef boost::shared_ptr< const FieldComparison > ConstPtr; + + + /** \brief Construct a FieldComparison + * \param field_name the name of the field that contains the data we want to compare + * \param op the operator to use when making the comparison + * \param compare_val the constant value to compare the field value too + */ + FieldComparison (std::string field_name, ComparisonOps::CompareOp op, double compare_val); + + /** \brief Copy constructor. + * \param[in] src the field comparison object to copy into this + */ + FieldComparison (const FieldComparison &src) + : ComparisonBase () + , compare_val_ (src.compare_val_), point_data_ (src.point_data_) + { + } + + /** \brief Copy operator. + * \param[in] src the field comparison object to copy into this + */ + inline FieldComparison& + operator = (const FieldComparison &src) + { + compare_val_ = src.compare_val_; + point_data_ = src.point_data_; + return (*this); + } + + /** \brief Destructor. */ + virtual ~FieldComparison (); + + /** \brief Determine the result of this comparison. + * \param point the point to evaluate + * \return the result of this comparison. + */ + virtual bool + evaluate (const PointT &point) const; + + protected: + /** \brief All types (that we care about) can be represented as a double. */ + double compare_val_; + + /** \brief The point data to compare. */ + PointDataAtOffset* point_data_; + + private: + FieldComparison () : + compare_val_ (), point_data_ () + { + } // not allowed + }; + + ////////////////////////////////////////////////////////////////////////////////////////// + /** \brief A packed rgb specialization of the comparison object. */ + template + class PackedRGBComparison : public ComparisonBase + { + using ComparisonBase::capable_; + using ComparisonBase::op_; + + public: + typedef boost::shared_ptr< PackedRGBComparison > Ptr; + typedef boost::shared_ptr< const PackedRGBComparison > ConstPtr; + + /** \brief Construct a PackedRGBComparison + * \param component_name either "r", "g" or "b" + * \param op the operator to use when making the comparison + * \param compare_val the constant value to compare the component value too + */ + PackedRGBComparison (std::string component_name, ComparisonOps::CompareOp op, double compare_val); + + /** \brief Destructor. */ + virtual ~PackedRGBComparison () {} + + /** \brief Determine the result of this comparison. + * \param point the point to evaluate + * \return the result of this comparison. + */ + virtual bool + evaluate (const PointT &point) const; + + protected: + /** \brief The name of the component. */ + std::string component_name_; + + /** \brief The offset of the component */ + uint32_t component_offset_; + + /** \brief All types (that we care about) can be represented as a double. */ + double compare_val_; + + private: + PackedRGBComparison () : + component_name_ (), component_offset_ (), compare_val_ () + { + } // not allowed + + }; + + ////////////////////////////////////////////////////////////////////////////////////////// + /** \brief A packed HSI specialization of the comparison object. */ + template + class PackedHSIComparison : public ComparisonBase + { + using ComparisonBase::capable_; + using ComparisonBase::op_; + + public: + typedef boost::shared_ptr< PackedHSIComparison > Ptr; + typedef boost::shared_ptr< const PackedHSIComparison > ConstPtr; + + /** \brief Construct a PackedHSIComparison + * \param component_name either "h", "s" or "i" + * \param op the operator to use when making the comparison + * \param compare_val the constant value to compare the component value too + */ + PackedHSIComparison (std::string component_name, ComparisonOps::CompareOp op, double compare_val); + + /** \brief Destructor. */ + virtual ~PackedHSIComparison () {} + + /** \brief Determine the result of this comparison. + * \param point the point to evaluate + * \return the result of this comparison. + */ + virtual bool + evaluate (const PointT &point) const; + + typedef enum + { + H, // -128 to 127 corresponds to -pi to pi + S, // 0 to 255 + I // 0 to 255 + } ComponentId; + + protected: + /** \brief The name of the component. */ + std::string component_name_; + + /** \brief The ID of the component. */ + ComponentId component_id_; + + /** \brief All types (that we care about) can be represented as a double. */ + double compare_val_; + + /** \brief The offset of the component */ + uint32_t rgb_offset_; + + private: + PackedHSIComparison () : + component_name_ (), component_id_ (), compare_val_ (), rgb_offset_ () + { + } // not allowed + }; + + ////////////////////////////////////////////////////////////////////////////////////////// + /**\brief A comparison whether the (x,y,z) components of a given point satisfy (p'Ap + 2v'p + c [OP] 0). + * Here [OP] stands for the defined pcl::ComparisonOps, i.e. for GT, GE, LT, LE or EQ; + * p = (x,y,z) is a point of the point cloud; A is 3x3 matrix; v is the 3x1 vector; c is a scalar. + * + * One can also use TfQuadraticXYZComparison for simpler geometric shapes by defining the + * quadratic parts (i.e. the matrix A) to be zero. By combining different instances of + * TfQuadraticXYZComparison one can get more complex shapes. For example, to have a simple + * cylinder (along the x-axis) of specific length one needs three comparisons combined as AND condition: + * 1. The cylinder: A = [0 0 0, 0 1 0, 0 0 1]; v = [0, 0, 0]; c = radius²; OP = LT (meaning "<") + * 2. X-min limit: A = 0; v = [1, 0, 0]; c = x_min; OP = GT + * 3. X-max ... + * + * \author Julian Löchner + */ + template + class TfQuadraticXYZComparison : public pcl::ComparisonBase + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW //needed whenever there is a fixed size Eigen:: vector or matrix in a class + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. + */ + TfQuadraticXYZComparison (); + + /** \brief Empty destructor */ + virtual ~TfQuadraticXYZComparison () {} + + /** \brief Constructor. + * \param op the operator "[OP]" of the comparison "p'Ap + 2v'p + c [OP] 0". + * \param comparison_matrix the matrix "A" of the comparison "p'Ap + 2v'p + c [OP] 0". + * \param comparison_vector the vector "v" of the comparison "p'Ap + 2v'p + c [OP] 0". + * \param comparison_scalar the scalar "c" of the comparison "p'Ap + 2v'p + c [OP] 0". + * \param comparison_transform the transformation of the comparison. + */ + TfQuadraticXYZComparison (const pcl::ComparisonOps::CompareOp op, const Eigen::Matrix3f &comparison_matrix, + const Eigen::Vector3f &comparison_vector, const float &comparison_scalar, + const Eigen::Affine3f &comparison_transform = Eigen::Affine3f::Identity ()); + + /** \brief set the operator "[OP]" of the comparison "p'Ap + 2v'p + c [OP] 0". + */ + inline void + setComparisonOperator (const pcl::ComparisonOps::CompareOp op) + { + op_ = op; + } + + /** \brief set the matrix "A" of the comparison "p'Ap + 2v'p + c [OP] 0". + */ + inline void + setComparisonMatrix (const Eigen::Matrix3f &matrix) + { + //define comp_matr_ as an homogeneous matrix of the given matrix + comp_matr_.block<3, 3> (0, 0) = matrix; + comp_matr_.col (3) << 0, 0, 0, 1; + comp_matr_.block<1, 3> (3, 0) << 0, 0, 0; + tf_comp_matr_ = comp_matr_; + } + + /** \brief set the matrix "A" of the comparison "p'Ap + 2v'p + c [OP] 0". + */ + inline void + setComparisonMatrix (const Eigen::Matrix4f &homogeneousMatrix) + { + comp_matr_ = homogeneousMatrix; + tf_comp_matr_ = comp_matr_; + } + + /** \brief set the vector "v" of the comparison "p'Ap + 2v'p + c [OP] 0". + */ + inline void + setComparisonVector (const Eigen::Vector3f &vector) + { + comp_vect_ = vector.homogeneous (); + tf_comp_vect_ = comp_vect_; + } + + /** \brief set the vector "v" of the comparison "p'Ap + 2v'p + c [OP] 0". + */ + inline void + setComparisonVector (const Eigen::Vector4f &homogeneousVector) + { + comp_vect_ = homogeneousVector; + tf_comp_vect_ = comp_vect_; + } + + /** \brief set the scalar "c" of the comparison "p'Ap + 2v'p + c [OP] 0". + */ + inline void + setComparisonScalar (const float &scalar) + { + comp_scalar_ = scalar; + } + + /** \brief transform the coordinate system of the comparison. If you think of + * the transformation to be a translation and rotation of the comparison in the + * same coordinate system, you have to provide the inverse transformation. + * This function does not change the original definition of the comparison. Thus, + * each call of this function will assume the original definition of the comparison + * as starting point for the transformation. + * + * @param transform the transformation (rotation and translation) as an affine matrix. + */ + inline void + transformComparison (const Eigen::Matrix4f &transform) + { + tf_comp_matr_ = transform.transpose () * comp_matr_ * transform; + tf_comp_vect_ = comp_vect_.transpose () * transform; + } + + /** \brief transform the coordinate system of the comparison. If you think of + * the transformation to be a translation and rotation of the comparison in the + * same coordinate system, you have to provide the inverse transformation. + * This function does not change the original definition of the comparison. Thus, + * each call of this function will assume the original definition of the comparison + * as starting point for the transformation. + * + * @param transform the transformation (rotation and translation) as an affine matrix. + */ + inline void + transformComparison (const Eigen::Affine3f &transform) + { + transformComparison (transform.matrix ()); + } + + /** \brief Determine the result of this comparison. + * \param point the point to evaluate + * \return the result of this comparison. + */ + virtual bool + evaluate (const PointT &point) const; + + protected: + using pcl::ComparisonBase::capable_; + using pcl::ComparisonBase::op_; + + Eigen::Matrix4f comp_matr_; + Eigen::Vector4f comp_vect_; + + float comp_scalar_; + + private: + Eigen::Matrix4f tf_comp_matr_; + Eigen::Vector4f tf_comp_vect_; + }; + + ////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Base condition class. */ + template + class ConditionBase + { + public: + typedef typename pcl::ComparisonBase ComparisonBase; + typedef typename ComparisonBase::Ptr ComparisonBasePtr; + typedef typename ComparisonBase::ConstPtr ComparisonBaseConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + ConditionBase () : capable_ (true), comparisons_ (), conditions_ () + { + } + + /** \brief Destructor. */ + virtual ~ConditionBase () + { + // comparisons are boost::shared_ptr.will take care of themselves + comparisons_.clear (); + + // conditions are boost::shared_ptr. will take care of themselves + conditions_.clear (); + } + + /** \brief Add a new comparison + * \param comparison the comparison operator to add + */ + void + addComparison (ComparisonBaseConstPtr comparison); + + /** \brief Add a nested condition to this condition. + * \param condition the nested condition to be added + */ + void + addCondition (Ptr condition); + + /** \brief Check if evaluation requirements are met. */ + inline bool + isCapable () const + { + return (capable_); + } + + /** \brief Determine if a point meets this condition. + * \return whether the point meets this condition. + */ + virtual bool + evaluate (const PointT &point) const = 0; + + protected: + /** \brief True if capable. */ + bool capable_; + + /** \brief The collection of all comparisons that need to be verified. */ + std::vector comparisons_; + + /** \brief The collection of all conditions that need to be verified. */ + std::vector conditions_; + }; + + ////////////////////////////////////////////////////////////////////////////////////////// + /** \brief AND condition. */ + template + class ConditionAnd : public ConditionBase + { + using ConditionBase::conditions_; + using ConditionBase::comparisons_; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + ConditionAnd () : + ConditionBase () + { + } + + /** \brief Determine if a point meets this condition. + * \return whether the point meets this condition. + * + * The ConditionAnd evaluates to true when ALL + * comparisons and nested conditions evaluate to true + */ + virtual bool + evaluate (const PointT &point) const; + }; + + ////////////////////////////////////////////////////////////////////////////////////////// + /** \brief OR condition. */ + template + class ConditionOr : public ConditionBase + { + using ConditionBase::conditions_; + using ConditionBase::comparisons_; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + ConditionOr () : + ConditionBase () + { + } + + /** \brief Determine if a point meets this condition. + * \return whether the point meets this condition. + * + * The ConditionOr evaluates to true when ANY + * comparisons or nested conditions evaluate to true + */ + virtual bool + evaluate (const PointT &point) const; + }; + + ////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b ConditionalRemoval filters data that satisfies certain conditions. + * + * A ConditionalRemoval must be provided a condition. There are two types of + * conditions: ConditionAnd and ConditionOr. Conditions require one or more + * comparisons and/or other conditions. A comparison has a name, a + * comparison operator, and a value. + * + * An ConditionAnd will evaluate to true when ALL of its encapsulated + * comparisons and conditions are true. + * + * An ConditionOr will evaluate to true when ANY of its encapsulated + * comparisons and conditions are true. + * + * Depending on the derived type of the comparison, the name can correspond + * to a PointCloud field name, or a color component in rgb color space or + * hsi color space. + * + * Here is an example usage: + * // Build the condition + * pcl::ConditionAnd::Ptr range_cond (new pcl::ConditionAnd ()); + * range_cond->addComparison (pcl::FieldComparison::Ptr (new pcl::FieldComparison("z", pcl::ComparisonOps::LT, 2.0))); + * range_cond->addComparison (pcl::FieldComparison::Ptr (new pcl::FieldComparison("z", pcl::ComparisonOps::GT, 0.0))); + * // Build the filter + * pcl::ConditionalRemoval range_filt; + * range_filt.setCondition (range_cond); + * range_filt.setKeepOrganized (false); + * + * \author Louis LeGrand, Intel Labs Seattle + * \ingroup filters + */ + template + class ConditionalRemoval : public Filter + { + using Filter::input_; + using Filter::filter_name_; + using Filter::getClassName; + + using Filter::removed_indices_; + using Filter::extract_removed_indices_; + + typedef typename Filter::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + typedef typename pcl::ConditionBase ConditionBase; + typedef typename ConditionBase::Ptr ConditionBasePtr; + typedef typename ConditionBase::ConstPtr ConditionBaseConstPtr; + + /** \brief the default constructor. + * + * All ConditionalRemovals require a condition which can be set + * using the setCondition method + * \param extract_removed_indices extract filtered indices from indices vector + */ + ConditionalRemoval (int extract_removed_indices = false) : + Filter::Filter (extract_removed_indices), capable_ (false), keep_organized_ (false), condition_ (), + user_filter_value_ (std::numeric_limits::quiet_NaN ()) + { + filter_name_ = "ConditionalRemoval"; + } + + /** \brief a constructor that includes the condition. + * \param condition the condition that each point must satisfy to avoid + * being removed by the filter + * \param extract_removed_indices extract filtered indices from indices vector + */ + PCL_DEPRECATED ("ConditionalRemoval(ConditionBasePtr condition, bool extract_removed_indices = false) is deprecated, " + "please use the setCondition (ConditionBasePtr condition) function instead.") + ConditionalRemoval (ConditionBasePtr condition, bool extract_removed_indices = false) : + Filter::Filter (extract_removed_indices), capable_ (false), keep_organized_ (false), condition_ (), + user_filter_value_ (std::numeric_limits::quiet_NaN ()) + { + filter_name_ = "ConditionalRemoval"; + setCondition (condition); + } + + /** \brief Set whether the filtered points should be kept and set to the + * value given through \a setUserFilterValue (default: NaN), or removed + * from the PointCloud, thus potentially breaking its organized + * structure. By default, points are removed. + * + * \param val set to true whether the filtered points should be kept and + * set to a given user value (default: NaN) + */ + inline void + setKeepOrganized (bool val) + { + keep_organized_ = val; + } + + inline bool + getKeepOrganized () const + { + return (keep_organized_); + } + + /** \brief Provide a value that the filtered points should be set to + * instead of removing them. Used in conjunction with \a + * setKeepOrganized (). + * \param val the user given value that the filtered point dimensions should be set to + */ + inline void + setUserFilterValue (float val) + { + user_filter_value_ = val; + } + + /** \brief Set the condition that the filter will use. + * \param condition each point must satisfy this condition to avoid + * being removed by the filter + * + * All ConditionalRemovals require a condition + */ + void + setCondition (ConditionBasePtr condition); + + protected: + /** \brief Filter a Point Cloud. + * \param output the resultant point cloud message + */ + void + applyFilter (PointCloud &output); + + /** \brief True if capable. */ + bool capable_; + + /** \brief Keep the structure of the data organized, by setting the + * filtered points to the a user given value (NaN by default). + */ + bool keep_organized_; + + /** \brief The condition to use for filtering */ + ConditionBasePtr condition_; + + /** \brief User given value to be set to any filtered point. Casted to + * the correct field type. + */ + float user_filter_value_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/filters/convolution.h b/pcl-1.7/pcl/filters/convolution.h new file mode 100644 index 0000000..d96dea6 --- /dev/null +++ b/pcl-1.7/pcl/filters/convolution.h @@ -0,0 +1,239 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_CONVOLUTION_H_ +#define PCL_FILTERS_CONVOLUTION_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace filters + { + /** Convolution is a mathematical operation on two functions f and g, + * producing a third function that is typically viewed as a modified + * version of one of the original functions. + * see http://en.wikipedia.org/wiki/Convolution. + * + * The class provides rows, column and separate convolving operations + * of a point cloud. + * Columns and separate convolution is only allowed on organised + * point clouds. + * + * When convolving, computing the rows and cols elements at 1/2 kernel + * width distance from the borders is not defined. We allow for 3 + * policies: + * - Ignoring: elements at special locations are filled with zero + * (default behaviour) + * - Mirroring: the missing rows or columns are obtained throug mirroring + * - Duplicating: the missing rows or columns are obtained throug + * duplicating + * + * \author Nizar Sallem + * \ingroup filters + */ + + template + class Convolution + { + public: + typedef typename pcl::PointCloud PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + typedef typename pcl::PointCloud PointCloudOut; + typedef boost::shared_ptr< Convolution > Ptr; + typedef boost::shared_ptr< const Convolution > ConstPtr; + + + /// The borders policy available + enum BORDERS_POLICY + { + BORDERS_POLICY_IGNORE = -1, + BORDERS_POLICY_MIRROR = 0, + BORDERS_POLICY_DUPLICATE = 1 + }; + /// Constructor + Convolution (); + /// Empty destructor + ~Convolution () {} + /** \brief Provide a pointer to the input dataset + * \param cloud the const boost shared pointer to a PointCloud message + * \remark Will perform a deep copy + */ + inline void + setInputCloud (const PointCloudInConstPtr& cloud) { input_ = cloud; } + /** Set convolving kernel + * \param[in] kernel convolving element + */ + inline void + setKernel (const Eigen::ArrayXf& kernel) { kernel_ = kernel; } + /// Set the borders policy + void + setBordersPolicy (int policy) { borders_policy_ = policy; } + /// Get the borders policy + int + getBordersPolicy () { return (borders_policy_); } + /** \remark this is critical so please read it carefully. + * In 3D the next point in (u,v) coordinate can be really far so a distance + * threshold is used to keep us from ghost points. + * The value you set here is strongly related to the sensor. A good value for + * kinect data is 0.001. Default is std::numeric::infinity () + * \param[in] threshold maximum allowed distance between 2 juxtaposed points + */ + inline void + setDistanceThreshold (const float& threshold) { distance_threshold_ = threshold; } + /// \return the distance threshold + inline const float & + getDistanceThreshold () const { return (distance_threshold_); } + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + /** Convolve a float image rows by a given kernel. + * \param[out] output the convolved cloud + * \note if output doesn't fit in input i.e. output.rows () < input.rows () or + * output.cols () < input.cols () then output is resized to input sizes. + */ + inline void + convolveRows (PointCloudOut& output); + /** Convolve a float image columns by a given kernel. + * \param[out] output the convolved image + * \note if output doesn't fit in input i.e. output.rows () < input.rows () or + * output.cols () < input.cols () then output is resized to input sizes. + */ + inline void + convolveCols (PointCloudOut& output); + /** Convolve point cloud with an horizontal kernel along rows + * then vertical kernel along columns : convolve separately. + * \param[in] h_kernel kernel for convolving rows + * \param[in] v_kernel kernel for convolving columns + * \param[out] output the convolved cloud + * \note if output doesn't fit in input i.e. output.rows () < input.rows () or + * output.cols () < input.cols () then output is resized to input sizes. + */ + inline void + convolve (const Eigen::ArrayXf& h_kernel, const Eigen::ArrayXf& v_kernel, PointCloudOut& output); + /** Convolve point cloud with same kernel along rows and columns separately. + * \param[out] output the convolved cloud + * \note if output doesn't fit in input i.e. output.rows () < input.rows () or + * output.cols () < input.cols () then output is resized to input sizes. + */ + inline void + convolve (PointCloudOut& output); + + protected: + /// \brief convolve rows and ignore borders + void + convolve_rows (PointCloudOut& output); + /// \brief convolve cols and ignore borders + void + convolve_cols (PointCloudOut& output); + /// \brief convolve rows and mirror borders + void + convolve_rows_mirror (PointCloudOut& output); + /// \brief convolve cols and mirror borders + void + convolve_cols_mirror (PointCloudOut& output); + /// \brief convolve rows and duplicate borders + void + convolve_rows_duplicate (PointCloudOut& output); + /// \brief convolve cols and duplicate borders + void + convolve_cols_duplicate (PointCloudOut& output); + /** init compute is an internal method called before computation + * \param[in] output + * \throw pcl::InitFailedException + */ + void + initCompute (PointCloudOut& output); + private: + /** \return the result of convolution of point at (\ai, \aj) + * \note no test on finity is performed + */ + inline PointOut + convolveOneRowDense (int i, int j); + /** \return the result of convolution of point at (\ai, \aj) + * \note no test on finity is performed + */ + inline PointOut + convolveOneColDense (int i, int j); + /** \return the result of convolution of point at (\ai, \aj) + * \note only finite points within \a distance_threshold_ are accounted + */ + inline PointOut + convolveOneRowNonDense (int i, int j); + /** \return the result of convolution of point at (\ai, \aj) + * \note only finite points within \a distance_threshold_ are accounted + */ + inline PointOut + convolveOneColNonDense (int i, int j); + + /// Border policy + int borders_policy_; + /// Threshold distance between adjacent points + float distance_threshold_; + /// Pointer to the input cloud + PointCloudInConstPtr input_; + /// convolution kernel + Eigen::ArrayXf kernel_; + /// half kernel size + int half_width_; + /// kernel size - 1 + int kernel_width_; + protected: + /** \brief The number of threads the scheduler should use. */ + unsigned int threads_; + + void + makeInfinite (PointOut& p) + { + p.x = p.y = p.z = std::numeric_limits::quiet_NaN (); + } + }; + } +} + +#include + +#endif diff --git a/pcl-1.7/pcl/filters/convolution_3d.h b/pcl-1.7/pcl/filters/convolution_3d.h new file mode 100644 index 0000000..1931673 --- /dev/null +++ b/pcl-1.7/pcl/filters/convolution_3d.h @@ -0,0 +1,292 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_CONVOLUTION_3D_H +#define PCL_FILTERS_CONVOLUTION_3D_H + +#include +#include +#include + +namespace pcl +{ + namespace filters + { + /** \brief Class ConvolvingKernel base class for all convolving kernels + * \ingroup filters + */ + template + class ConvolvingKernel + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename PointCloud::ConstPtr PointCloudInConstPtr; + + /// \brief empty constructor + ConvolvingKernel () {} + + /// \brief empty destructor + virtual ~ConvolvingKernel () {} + + /** \brief Set input cloud + * \param[in] input source point cloud + */ + void + setInputCloud (const PointCloudInConstPtr& input) { input_ = input; } + + /** \brief Convolve point at the center of this local information + * \param[in] indices indices of the point in the source point cloud + * \param[in] distances euclidean distance squared from the query point + * \return the convolved point + */ + virtual PointOutT + operator() (const std::vector& indices, const std::vector& distances) = 0; + + /** \brief Must call this methode before doing any computation + * \note make sure to override this with at least + * \code + * bool initCompute () + * { + * return (true); + * } + * \endcode + * in your kernel interface, else you are going nowhere! + */ + virtual bool + initCompute () { return false; } + + /** \brief Utility function that annihilates a point making it fail the \ref pcl::isFinite test + * \param p point to annihilate + */ + static void + makeInfinite (PointOutT& p) + { + p.x = p.y = p.z = std::numeric_limits::quiet_NaN (); + } + + protected: + /// source cloud + PointCloudInConstPtr input_; + }; + + /** \brief Gaussian kernel implementation interface + * Use this as implementation reference + * \ingroup filters + */ + template + class GaussianKernel : public ConvolvingKernel + { + public: + using ConvolvingKernel::initCompute; + using ConvolvingKernel::input_; + using ConvolvingKernel::operator (); + using ConvolvingKernel::makeInfinite; + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** Default constructor */ + GaussianKernel () + : ConvolvingKernel () + , sigma_ (0) + , threshold_ (std::numeric_limits::infinity ()) + {} + + virtual ~GaussianKernel () {} + + /** Set the sigma parameter of the Gaussian + * \param[in] sigma + */ + inline void + setSigma (float sigma) { sigma_ = sigma; } + + /** Set the distance threshold relative to a sigma factor i.e. points such as + * ||pi - q|| > sigma_coefficient^2 * sigma^2 are not considered. + */ + inline void + setThresholdRelativeToSigma (float sigma_coefficient) + { + sigma_coefficient_.reset (sigma_coefficient); + } + + /** Set the distance threshold such as pi, ||pi - q|| > threshold are not considered. */ + inline void + setThreshold (float threshold) { threshold_ = threshold; } + + /** Must call this methode before doing any computation */ + bool initCompute (); + + virtual PointOutT + operator() (const std::vector& indices, const std::vector& distances); + + protected: + float sigma_; + float sigma_sqr_; + float threshold_; + boost::optional sigma_coefficient_; + }; + + /** \brief Gaussian kernel implementation interface with RGB channel handling + * Use this as implementation reference + * \ingroup filters + */ + template + class GaussianKernelRGB : public GaussianKernel + { + public: + using GaussianKernel::initCompute; + using GaussianKernel::input_; + using GaussianKernel::operator (); + using GaussianKernel::makeInfinite; + using GaussianKernel::sigma_sqr_; + using GaussianKernel::threshold_; + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** Default constructor */ + GaussianKernelRGB () + : GaussianKernel () + {} + + ~GaussianKernelRGB () {} + + PointOutT + operator() (const std::vector& indices, const std::vector& distances); + }; + + /** Convolution3D handles the non organized case where width and height are unknown or if you + * are only interested in convolving based on local neighborhood information. + * The convolving kernel MUST be a radial symmetric and implement \ref ConvolvingKernel + * interface. + */ + template + class Convolution3D : public pcl::PCLBase + { + public: + typedef typename pcl::PointCloud PointCloudIn; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + typedef typename pcl::search::Search KdTree; + typedef typename pcl::search::Search::Ptr KdTreePtr; + typedef typename pcl::PointCloud PointCloudOut; + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using pcl::PCLBase::indices_; + using pcl::PCLBase::input_; + + /** \brief Constructor */ + Convolution3D (); + + /** \brief Empty destructor */ + ~Convolution3D () {} + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + + /** \brief Set convolving kernel + * \param[in] kernel convolving element + */ + inline void + setKernel (const KernelT& kernel) { kernel_ = kernel; } + + /** \brief Provide a pointer to the input dataset that we need to estimate features at every point for. + * \param cloud the const boost shared pointer to a PointCloud message + */ + inline void + setSearchSurface (const PointCloudInConstPtr &cloud) { surface_ = cloud; } + + /** \brief Get a pointer to the surface point cloud dataset. */ + inline PointCloudInConstPtr + getSearchSurface () { return (surface_); } + + /** \brief Provide a pointer to the search object. + * \param tree a pointer to the spatial search object. + */ + inline void + setSearchMethod (const KdTreePtr &tree) { tree_ = tree; } + + /** \brief Get a pointer to the search method used. */ + inline KdTreePtr + getSearchMethod () { return (tree_); } + + /** \brief Set the sphere radius that is to be used for determining the nearest neighbors + * \param radius the sphere radius used as the maximum distance to consider a point a neighbor + */ + inline void + setRadiusSearch (double radius) { search_radius_ = radius; } + + /** \brief Get the sphere radius used for determining the neighbors. */ + inline double + getRadiusSearch () { return (search_radius_); } + + /** Convolve point cloud. + * \param[out] output the convolved cloud + */ + void + convolve (PointCloudOut& output); + + protected: + /** \brief initialize computation */ + bool initCompute (); + + /** \brief An input point cloud describing the surface that is to be used for nearest neighbors estimation. */ + PointCloudInConstPtr surface_; + + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + + /** \brief The nearest neighbors search radius for each point. */ + double search_radius_; + + /** \brief number of threads */ + unsigned int threads_; + + /** \brief convlving kernel */ + KernelT kernel_; + }; + } +} + +#include + +#endif // PCL_FILTERS_CONVOLUTION_3D_H diff --git a/pcl-1.7/pcl/filters/covariance_sampling.h b/pcl-1.7/pcl/filters/covariance_sampling.h new file mode 100644 index 0000000..6d41efc --- /dev/null +++ b/pcl-1.7/pcl/filters/covariance_sampling.h @@ -0,0 +1,172 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + + * All rights reserved. + + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + + +#ifndef PCL_FILTERS_COVARIANCE_SAMPLING_H_ +#define PCL_FILTERS_COVARIANCE_SAMPLING_H_ + +#include + +namespace pcl +{ + /** \brief Point Cloud sampling based on the 6D covariances. It selects the points such that the resulting cloud is + * as stable as possible for being registered (against a copy of itself) with ICP. The algorithm adds points to the + * resulting cloud incrementally, while trying to keep all the 6 eigenvalues of the covariance matrix as close to each + * other as possible. + * This class also comes with the \a computeConditionNumber method that returns a number which shows how stable a point + * cloud will be when used as input for ICP (the closer the value it is to 1.0, the better). + * + * Based on the following publication: + * * "Geometrically Stable Sampling for the ICP Algorithm" - N. Gelfand, L. Ikemoto, S. Rusinkiewicz, M. Levoy + * + * \author Alexandru E. Ichim, alex.e.ichim@gmail.com + */ + template + class CovarianceSampling : public FilterIndices + { + using FilterIndices::filter_name_; + using FilterIndices::getClassName; + using FilterIndices::indices_; + using FilterIndices::input_; + using FilterIndices::initCompute; + + typedef typename FilterIndices::PointCloud Cloud; + typedef typename Cloud::Ptr CloudPtr; + typedef typename Cloud::ConstPtr CloudConstPtr; + typedef typename pcl::PointCloud::ConstPtr NormalsConstPtr; + + public: + typedef boost::shared_ptr< CovarianceSampling > Ptr; + typedef boost::shared_ptr< const CovarianceSampling > ConstPtr; + + /** \brief Empty constructor. */ + CovarianceSampling () + { filter_name_ = "CovarianceSampling"; } + + /** \brief Set number of indices to be sampled. + * \param[in] samples the number of sample indices + */ + inline void + setNumberOfSamples (unsigned int samples) + { num_samples_ = samples; } + + /** \brief Get the value of the internal \a num_samples_ parameter. */ + inline unsigned int + getNumberOfSamples () const + { return (num_samples_); } + + /** \brief Set the normals computed on the input point cloud + * \param[in] normals the normals computed for the input cloud + */ + inline void + setNormals (const NormalsConstPtr &normals) + { input_normals_ = normals; } + + /** \brief Get the normals computed on the input point cloud */ + inline NormalsConstPtr + getNormals () const + { return (input_normals_); } + + + + /** \brief Compute the condition number of the input point cloud. The condition number is the ratio between the + * largest and smallest eigenvalues of the 6x6 covariance matrix of the cloud. The closer this number is to 1.0, + * the more stable the cloud is for ICP registration. + * \return the condition number + */ + double + computeConditionNumber (); + + /** \brief Compute the condition number of the input point cloud. The condition number is the ratio between the + * largest and smallest eigenvalues of the 6x6 covariance matrix of the cloud. The closer this number is to 1.0, + * the more stable the cloud is for ICP registration. + * \param[in] covariance_matrix user given covariance matrix + * \return the condition number + */ + static double + computeConditionNumber (const Eigen::Matrix &covariance_matrix); + + /** \brief Computes the covariance matrix of the input cloud. + * \param[out] covariance_matrix the computed covariance matrix. + * \return whether the computation succeeded or not + */ + bool + computeCovarianceMatrix (Eigen::Matrix &covariance_matrix); + + protected: + /** \brief Number of indices that will be returned. */ + unsigned int num_samples_; + + /** \brief The normals computed at each point in the input cloud */ + NormalsConstPtr input_normals_; + + std::vector scaled_points_; + + bool + initCompute (); + + /** \brief Sample of point indices into a separate PointCloud + * \param[out] output the resultant point cloud + */ + void + applyFilter (Cloud &output); + + /** \brief Sample of point indices + * \param[out] indices the resultant point cloud indices + */ + void + applyFilter (std::vector &indices); + + static bool + sort_dot_list_function (std::pair a, + std::pair b) + { return (a.second > b.second); } + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + + +#endif /* PCL_FILTERS_COVARIANCE_SAMPLING_H_ */ diff --git a/pcl-1.7/pcl/filters/crop_box.h b/pcl-1.7/pcl/filters/crop_box.h new file mode 100644 index 0000000..e632c63 --- /dev/null +++ b/pcl-1.7/pcl/filters/crop_box.h @@ -0,0 +1,349 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: crop_box.h 1370 2011-06-19 01:06:01Z jspricke $ + * + */ + +#ifndef PCL_FILTERS_CROP_BOX_H_ +#define PCL_FILTERS_CROP_BOX_H_ + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief CropBox is a filter that allows the user to filter all the data + * inside of a given box. + * + * \author Justin Rosen + * \ingroup filters + */ + template + class CropBox : public FilterIndices + { + using Filter::getClassName; + + typedef typename Filter::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + + typedef boost::shared_ptr< CropBox > Ptr; + typedef boost::shared_ptr< const CropBox > ConstPtr; + + /** \brief Constructor. + * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false). + */ + CropBox (bool extract_removed_indices = false) : + FilterIndices::FilterIndices (extract_removed_indices), + min_pt_ (Eigen::Vector4f (-1, -1, -1, 1)), + max_pt_ (Eigen::Vector4f (1, 1, 1, 1)), + rotation_ (Eigen::Vector3f::Zero ()), + translation_ (Eigen::Vector3f::Zero ()), + transform_ (Eigen::Affine3f::Identity ()) + { + filter_name_ = "CropBox"; + } + + /** \brief Set the minimum point of the box + * \param[in] min_pt the minimum point of the box + */ + inline void + setMin (const Eigen::Vector4f &min_pt) + { + min_pt_ = min_pt; + } + + /** \brief Get the value of the minimum point of the box, as set by the user + * \return the value of the internal \a min_pt parameter. + */ + inline Eigen::Vector4f + getMin () const + { + return (min_pt_); + } + + /** \brief Set the maximum point of the box + * \param[in] max_pt the maximum point of the box + */ + inline void + setMax (const Eigen::Vector4f &max_pt) + { + max_pt_ = max_pt; + } + + /** \brief Get the value of the maxiomum point of the box, as set by the user + * \return the value of the internal \a max_pt parameter. + */ + inline Eigen::Vector4f + getMax () const + { + return (max_pt_); + } + + /** \brief Set a translation value for the box + * \param[in] translation the (tx,ty,tz) values that the box should be translated by + */ + inline void + setTranslation (const Eigen::Vector3f &translation) + { + translation_ = translation; + } + + /** \brief Get the value of the box translation parameter as set by the user. */ + Eigen::Vector3f + getTranslation () const + { + return (translation_); + } + + /** \brief Set a rotation value for the box + * \param[in] rotation the (rx,ry,rz) values that the box should be rotated by + */ + inline void + setRotation (const Eigen::Vector3f &rotation) + { + rotation_ = rotation; + } + + /** \brief Get the value of the box rotatation parameter, as set by the user. */ + inline Eigen::Vector3f + getRotation () const + { + return (rotation_); + } + + /** \brief Set a transformation that should be applied to the cloud before filtering + * \param[in] transform an affine transformation that needs to be applied to the cloud before filtering + */ + inline void + setTransform (const Eigen::Affine3f &transform) + { + transform_ = transform; + } + + /** \brief Get the value of the transformation parameter, as set by the user. */ + inline Eigen::Affine3f + getTransform () const + { + return (transform_); + } + + protected: + using PCLBase::input_; + using PCLBase::indices_; + using Filter::filter_name_; + using FilterIndices::negative_; + using FilterIndices::keep_organized_; + using FilterIndices::user_filter_value_; + using FilterIndices::extract_removed_indices_; + using FilterIndices::removed_indices_; + + /** \brief Sample of point indices into a separate PointCloud + * \param[out] output the resultant point cloud + */ + void + applyFilter (PointCloud &output); + + /** \brief Sample of point indices + * \param[out] indices the resultant point cloud indices + */ + void + applyFilter (std::vector &indices); + + private: + /** \brief The minimum point of the box. */ + Eigen::Vector4f min_pt_; + /** \brief The maximum point of the box. */ + Eigen::Vector4f max_pt_; + /** \brief The 3D rotation for the box. */ + Eigen::Vector3f rotation_; + /** \brief The 3D translation for the box. */ + Eigen::Vector3f translation_; + /** \brief The affine transform applied to the cloud. */ + Eigen::Affine3f transform_; + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief CropBox is a filter that allows the user to filter all the data + * inside of a given box. + * + * \author Justin Rosen + * \ingroup filters + */ + template<> + class PCL_EXPORTS CropBox : public FilterIndices + { + using Filter::filter_name_; + using Filter::getClassName; + + typedef pcl::PCLPointCloud2 PCLPointCloud2; + typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr; + typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr; + + public: + /** \brief Constructor. + * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false). + */ + CropBox (bool extract_removed_indices = false) : + FilterIndices::FilterIndices (extract_removed_indices), + min_pt_(Eigen::Vector4f (-1, -1, -1, 1)), + max_pt_(Eigen::Vector4f (1, 1, 1, 1)), + translation_ (Eigen::Vector3f::Zero ()), + rotation_ (Eigen::Vector3f::Zero ()), + transform_(Eigen::Affine3f::Identity ()) + { + filter_name_ = "CropBox"; + } + + /** \brief Set the minimum point of the box + * \param[in] min_pt the minimum point of the box + */ + inline void + setMin (const Eigen::Vector4f& min_pt) + { + min_pt_ = min_pt; + } + + /** \brief Get the value of the minimum point of the box, as set by the user + * \return the value of the internal \a min_pt parameter. + */ + inline Eigen::Vector4f + getMin () const + { + return (min_pt_); + } + + /** \brief Set the maximum point of the box + * \param[in] max_pt the maximum point of the box + */ + inline void + setMax (const Eigen::Vector4f &max_pt) + { + max_pt_ = max_pt; + } + + /** \brief Get the value of the maxiomum point of the box, as set by the user + * \return the value of the internal \a max_pt parameter. + */ + inline Eigen::Vector4f + getMax () const + { + return (max_pt_); + } + + /** \brief Set a translation value for the box + * \param[in] translation the (tx,ty,tz) values that the box should be translated by + */ + inline void + setTranslation (const Eigen::Vector3f &translation) + { + translation_ = translation; + } + + /** \brief Get the value of the box translation parameter as set by the user. */ + inline Eigen::Vector3f + getTranslation () const + { + return (translation_); + } + + /** \brief Set a rotation value for the box + * \param[in] rotation the (rx,ry,rz) values that the box should be rotated by + */ + inline void + setRotation (const Eigen::Vector3f &rotation) + { + rotation_ = rotation; + } + + /** \brief Get the value of the box rotatation parameter, as set by the user. */ + inline Eigen::Vector3f + getRotation () const + { + return (rotation_); + } + + /** \brief Set a transformation that should be applied to the cloud before filtering + * \param[in] transform an affine transformation that needs to be applied to the cloud before filtering + */ + inline void + setTransform (const Eigen::Affine3f &transform) + { + transform_ = transform; + } + + /** \brief Get the value of the transformation parameter, as set by the user. */ + inline Eigen::Affine3f + getTransform () const + { + return (transform_); + } + + protected: + /** \brief Sample of point indices into a separate PointCloud + * \param output the resultant point cloud + */ + void + applyFilter (PCLPointCloud2 &output); + + /** \brief Sample of point indices + * \param indices the resultant point cloud indices + */ + void + applyFilter (std::vector &indices); + + /** \brief The minimum point of the box. */ + Eigen::Vector4f min_pt_; + /** \brief The maximum point of the box. */ + Eigen::Vector4f max_pt_; + /** \brief The 3D translation for the box. */ + Eigen::Vector3f translation_; + /** \brief The 3D rotation for the box. */ + Eigen::Vector3f rotation_; + /** \brief The affine transform applied to the cloud. */ + Eigen::Affine3f transform_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_FILTERS_CROP_BOX_H_ diff --git a/pcl-1.7/pcl/filters/crop_hull.h b/pcl-1.7/pcl/filters/crop_hull.h new file mode 100644 index 0000000..7cd60a0 --- /dev/null +++ b/pcl-1.7/pcl/filters/crop_hull.h @@ -0,0 +1,243 @@ + /* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FILTERS_CROP_HULL_H_ +#define PCL_FILTERS_CROP_HULL_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief Filter points that lie inside or outside a 3D closed surface or 2D + * closed polygon, as generated by the ConvexHull or ConcaveHull classes. + * \author James Crosby + * \ingroup filters + */ + template + class CropHull: public FilterIndices + { + using Filter::filter_name_; + using Filter::indices_; + using Filter::input_; + + typedef typename Filter::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + + typedef boost::shared_ptr< CropHull > Ptr; + typedef boost::shared_ptr< const CropHull > ConstPtr; + + /** \brief Empty Constructor. */ + CropHull () : + hull_polygons_(), + hull_cloud_(), + dim_(3), + crop_outside_(true) + { + filter_name_ = "CropHull"; + } + + /** \brief Set the vertices of the hull used to filter points. + * \param[in] polygons Vector of polygons (Vertices structures) forming + * the hull used for filtering points. + */ + inline void + setHullIndices (const std::vector& polygons) + { + hull_polygons_ = polygons; + } + + /** \brief Get the vertices of the hull used to filter points. + */ + std::vector + getHullIndices () const + { + return (hull_polygons_); + } + + /** \brief Set the point cloud that the hull indices refer to + * \param[in] points the point cloud that the hull indices refer to + */ + inline void + setHullCloud (PointCloudPtr points) + { + hull_cloud_ = points; + } + + /** \brief Get the point cloud that the hull indices refer to. */ + PointCloudPtr + getHullCloud () const + { + return (hull_cloud_); + } + + /** \brief Set the dimensionality of the hull to be used. + * This should be set to correspond to the dimensionality of the + * convex/concave hull produced by the pcl::ConvexHull and + * pcl::ConcaveHull classes. + * \param[in] dim Dimensionailty of the hull used to filter points. + */ + inline void + setDim (int dim) + { + dim_ = dim; + } + + /** \brief Remove points outside the hull (default), or those inside the hull. + * \param[in] crop_outside If true, the filter will remove points + * outside the hull. If false, those inside will be removed. + */ + inline void + setCropOutside(bool crop_outside) + { + crop_outside_ = crop_outside; + } + + protected: + /** \brief Filter the input points using the 2D or 3D polygon hull. + * \param[out] output The set of points that passed the filter + */ + void + applyFilter (PointCloud &output); + + /** \brief Filter the input points using the 2D or 3D polygon hull. + * \param[out] indices the indices of the set of points that passed the filter. + */ + void + applyFilter (std::vector &indices); + + private: + /** \brief Return the size of the hull point cloud in line with coordinate axes. + * This is used to choose the 2D projection to use when cropping to a 2d + * polygon. + */ + Eigen::Vector3f + getHullCloudRange (); + + /** \brief Apply the two-dimensional hull filter. + * All points are assumed to lie in the same plane as the 2D hull, an + * axis-aligned 2D coordinate system using the two dimensions specified + * (PlaneDim1, PlaneDim2) is used for calculations. + * \param[out] output The set of points that pass the 2D polygon filter. + */ + template void + applyFilter2D (PointCloud &output); + + /** \brief Apply the two-dimensional hull filter. + * All points are assumed to lie in the same plane as the 2D hull, an + * axis-aligned 2D coordinate system using the two dimensions specified + * (PlaneDim1, PlaneDim2) is used for calculations. + * \param[out] indices The indices of the set of points that pass the + * 2D polygon filter. + */ + template void + applyFilter2D (std::vector &indices); + + /** \brief Apply the three-dimensional hull filter. + * Polygon-ray crossings are used for three rays cast from each point + * being tested, and a majority vote of the resulting + * polygon-crossings is used to decide whether the point lies inside + * or outside the hull. + * \param[out] output The set of points that pass the 3D polygon hull + * filter. + */ + void + applyFilter3D (PointCloud &output); + + /** \brief Apply the three-dimensional hull filter. + * Polygon-ray crossings are used for three rays cast from each point + * being tested, and a majority vote of the resulting + * polygon-crossings is used to decide whether the point lies inside + * or outside the hull. + * \param[out] indices The indices of the set of points that pass the 3D + * polygon hull filter. + */ + void + applyFilter3D (std::vector &indices); + + /** \brief Test an individual point against a 2D polygon. + * PlaneDim1 and PlaneDim2 specify the x/y/z coordinate axes to use. + * \param[in] point Point to test against the polygon. + * \param[in] verts Vertex indices of polygon. + * \param[in] cloud Cloud from which the vertex indices are drawn. + */ + template inline static bool + isPointIn2DPolyWithVertIndices (const PointT& point, + const Vertices& verts, + const PointCloud& cloud); + + /** \brief Does a ray cast from a point intersect with an arbitrary + * triangle in 3D? + * See: http://softsurfer.com/Archive/algorithm_0105/algorithm_0105.htm#intersect_RayTriangle() + * \param[in] point Point from which the ray is cast. + * \param[in] ray Vector in direction of ray. + * \param[in] verts Indices of vertices making the polygon. + * \param[in] cloud Cloud from which the vertex indices are drawn. + */ + inline static bool + rayTriangleIntersect (const PointT& point, + const Eigen::Vector3f& ray, + const Vertices& verts, + const PointCloud& cloud); + + + /** \brief The vertices of the hull used to filter points. */ + std::vector hull_polygons_; + + /** \brief The point cloud that the hull indices refer to. */ + PointCloudPtr hull_cloud_; + + /** \brief The dimensionality of the hull to be used. */ + int dim_; + + /** \brief If true, the filter will remove points outside the hull. If + * false, those inside will be removed. + */ + bool crop_outside_; + }; + +} // namespace pcl + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // ifndef PCL_FILTERS_CROP_HULL_H_ diff --git a/pcl-1.7/pcl/filters/extract_indices.h b/pcl-1.7/pcl/filters/extract_indices.h new file mode 100644 index 0000000..dbadbcd --- /dev/null +++ b/pcl-1.7/pcl/filters/extract_indices.h @@ -0,0 +1,204 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_EXTRACT_INDICES_H_ +#define PCL_FILTERS_EXTRACT_INDICES_H_ + +#include + +namespace pcl +{ + /** \brief @b ExtractIndices extracts a set of indices from a point cloud. + * \details Usage example: + * \code + * pcl::ExtractIndices eifilter (true); // Initializing with true will allow us to extract the removed indices + * eifilter.setInputCloud (cloud_in); + * eifilter.setIndices (indices_in); + * eifilter.filter (*cloud_out); + * // The resulting cloud_out contains all points of cloud_in that are indexed by indices_in + * indices_rem = eifilter.getRemovedIndices (); + * // The indices_rem array indexes all points of cloud_in that are not indexed by indices_in + * eifilter.setNegative (true); + * eifilter.filter (*indices_out); + * // Alternatively: the indices_out array is identical to indices_rem + * eifilter.setNegative (false); + * eifilter.setUserFilterValue (1337.0); + * eifilter.filterDirectly (cloud_in); + * // This will directly modify cloud_in instead of creating a copy of the cloud + * // It will overwrite all fields of the filtered points by the user value: 1337 + * \endcode + * \author Radu Bogdan Rusu + * \ingroup filters + */ + template + class ExtractIndices : public FilterIndices + { + protected: + typedef typename FilterIndices::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + typedef typename pcl::traits::fieldList::type FieldList; + + public: + + typedef boost::shared_ptr< ExtractIndices > Ptr; + typedef boost::shared_ptr< const ExtractIndices > ConstPtr; + + /** \brief Constructor. + * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false). + */ + ExtractIndices (bool extract_removed_indices = false) : + FilterIndices::FilterIndices (extract_removed_indices) + { + use_indices_ = true; + filter_name_ = "ExtractIndices"; + } + + /** \brief Apply the filter and store the results directly in the input cloud. + * \details This method will save the time and memory copy of an output cloud but can not alter the original size of the input cloud: + * It operates as though setKeepOrganized() is true and will overwrite the filtered points instead of remove them. + * All fields of filtered points are replaced with the value set by setUserFilterValue() (default = NaN). + * This method also automatically alters the input cloud set via setInputCloud(). + * It does not alter the value of the internal keep organized boolean as set by setKeepOrganized(). + * \param cloud The point cloud used for input and output. + */ + void + filterDirectly (PointCloudPtr &cloud); + + protected: + using PCLBase::input_; + using PCLBase::indices_; + using PCLBase::use_indices_; + using Filter::filter_name_; + using Filter::getClassName; + using FilterIndices::negative_; + using FilterIndices::keep_organized_; + using FilterIndices::user_filter_value_; + using FilterIndices::extract_removed_indices_; + using FilterIndices::removed_indices_; + + /** \brief Filtered results are stored in a separate point cloud. + * \param[out] output The resultant point cloud. + */ + void + applyFilter (PointCloud &output); + + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. + */ + void + applyFilter (std::vector &indices) + { + applyFilterIndices (indices); + } + + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. + */ + void + applyFilterIndices (std::vector &indices); + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b ExtractIndices extracts a set of indices from a point cloud. + *
+ * Usage examples: + * \code + * pcl::ExtractIndices filter; + * filter.setInputCloud (cloud_in); + * filter.setIndices (indices_in); + * // Extract the points in cloud_in referenced by indices_in as a separate point cloud: + * filter.filter (*cloud_out); + * // Retrieve indices to all points in cloud_in except those referenced by indices_in: + * filter.setNegative (true); + * filter.filter (*indices_out); + * // The resulting cloud_out is identical to cloud_in, but all points referenced by indices_in are made NaN: + * filter.setNegative (true); + * filter.setKeepOrganized (true); + * filter.filter (*cloud_out); + * \endcode + * \note Does not inherently remove NaNs from results, hence the \a extract_removed_indices_ system is not used. + * \author Radu Bogdan Rusu + * \ingroup filters + */ + template<> + class PCL_EXPORTS ExtractIndices : public FilterIndices + { + public: + typedef pcl::PCLPointCloud2 PCLPointCloud2; + typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr; + typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr; + + /** \brief Empty constructor. */ + ExtractIndices () + { + use_indices_ = true; + filter_name_ = "ExtractIndices"; + } + + protected: + using PCLBase::input_; + using PCLBase::indices_; + using PCLBase::use_indices_; + using Filter::filter_name_; + using Filter::getClassName; + using FilterIndices::negative_; + using FilterIndices::keep_organized_; + using FilterIndices::user_filter_value_; + + /** \brief Extract point indices into a separate PointCloud + * \param[out] output the resultant point cloud + */ + void + applyFilter (PCLPointCloud2 &output); + + /** \brief Extract point indices + * \param indices the resultant indices + */ + void + applyFilter (std::vector &indices); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_FILTERS_EXTRACT_INDICES_H_ + diff --git a/pcl-1.7/pcl/filters/fast_bilateral.h b/pcl-1.7/pcl/filters/fast_bilateral.h new file mode 100644 index 0000000..84f818c --- /dev/null +++ b/pcl-1.7/pcl/filters/fast_bilateral.h @@ -0,0 +1,199 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2004, Sylvain Paris and Francois Sillion + + * All rights reserved. + + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + + +#ifndef PCL_FILTERS_FAST_BILATERAL_H_ +#define PCL_FILTERS_FAST_BILATERAL_H_ + +#include + +namespace pcl +{ + /** \brief Implementation of a fast bilateral filter for smoothing depth information in organized point clouds + * Based on the following paper: + * * Sylvain Paris and FrŽdo Durand + * "A Fast Approximation of the Bilateral Filter using a Signal Processing Approach" + * European Conference on Computer Vision (ECCV'06) + * + * More details on the webpage: http://people.csail.mit.edu/sparis/bf/ + */ + template + class FastBilateralFilter : public Filter + { + protected: + using Filter::input_; + typedef typename Filter::PointCloud PointCloud; + + public: + + typedef boost::shared_ptr< FastBilateralFilter > Ptr; + typedef boost::shared_ptr< const FastBilateralFilter > ConstPtr; + + /** \brief Empty constructor. */ + FastBilateralFilter () + : sigma_s_ (15.0f) + , sigma_r_ (0.05f) + , early_division_ (false) + { } + + /** \brief Empty destructor */ + virtual ~FastBilateralFilter () {} + + /** \brief Set the standard deviation of the Gaussian used by the bilateral filter for + * the spatial neighborhood/window. + * \param[in] sigma_s the size of the Gaussian bilateral filter window to use + */ + inline void + setSigmaS (float sigma_s) + { sigma_s_ = sigma_s; } + + /** \brief Get the size of the Gaussian bilateral filter window as set by the user. */ + inline float + getSigmaS () const + { return sigma_s_; } + + + /** \brief Set the standard deviation of the Gaussian used to control how much an adjacent + * pixel is downweighted because of the intensity difference (depth in our case). + * \param[in] sigma_r the standard deviation of the Gaussian for the intensity difference + */ + inline void + setSigmaR (float sigma_r) + { sigma_r_ = sigma_r; } + + /** \brief Get the standard deviation of the Gaussian for the intensity difference */ + inline float + getSigmaR () const + { return sigma_r_; } + + /** \brief Filter the input data and store the results into output. + * \param[out] output the resultant point cloud + */ + virtual void + applyFilter (PointCloud &output); + + protected: + float sigma_s_; + float sigma_r_; + bool early_division_; + + class Array3D + { + public: + Array3D (const size_t width, const size_t height, const size_t depth) + { + x_dim_ = width; + y_dim_ = height; + z_dim_ = depth; + v_ = std::vector (width*height*depth, Eigen::Vector2f (0.0f, 0.0f)); + } + + inline Eigen::Vector2f& + operator () (const size_t x, const size_t y, const size_t z) + { return v_[(x * y_dim_ + y) * z_dim_ + z]; } + + inline const Eigen::Vector2f& + operator () (const size_t x, const size_t y, const size_t z) const + { return v_[(x * y_dim_ + y) * z_dim_ + z]; } + + inline void + resize (const size_t width, const size_t height, const size_t depth) + { + x_dim_ = width; + y_dim_ = height; + z_dim_ = depth; + v_.resize (x_dim_ * y_dim_ * z_dim_); + } + + Eigen::Vector2f + trilinear_interpolation (const float x, + const float y, + const float z); + + static inline size_t + clamp (const size_t min_value, + const size_t max_value, + const size_t x); + + inline size_t + x_size () const + { return x_dim_; } + + inline size_t + y_size () const + { return y_dim_; } + + inline size_t + z_size () const + { return z_dim_; } + + inline std::vector::iterator + begin () + { return v_.begin (); } + + inline std::vector::iterator + end () + { return v_.end (); } + + inline std::vector::const_iterator + begin () const + { return v_.begin (); } + + inline std::vector::const_iterator + end () const + { return v_.end (); } + + private: + std::vector v_; + size_t x_dim_, y_dim_, z_dim_; + }; + + + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#else +#define PCL_INSTANTIATE_FastBilateralFilter(T) template class PCL_EXPORTS pcl::FastBilateralFilter; +#endif + + +#endif /* PCL_FILTERS_FAST_BILATERAL_H_ */ diff --git a/pcl-1.7/pcl/filters/fast_bilateral_omp.h b/pcl-1.7/pcl/filters/fast_bilateral_omp.h new file mode 100644 index 0000000..a93c184 --- /dev/null +++ b/pcl-1.7/pcl/filters/fast_bilateral_omp.h @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2004, Sylvain Paris and Francois Sillion + + * All rights reserved. + + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: fast_bilateral_omp.h 8379 2013-01-02 23:12:21Z sdmiller $ + * + */ + + +#ifndef PCL_FILTERS_FAST_BILATERAL_OMP_H_ +#define PCL_FILTERS_FAST_BILATERAL_OMP_H_ + +#include +#include + +namespace pcl +{ + /** \brief Implementation of a fast bilateral filter for smoothing depth information in organized point clouds + * Based on the following paper: + * * Sylvain Paris and FrÂŽdo Durand + * "A Fast Approximation of the Bilateral Filter using a Signal Processing Approach" + * European Conference on Computer Vision (ECCV'06) + * + * More details on the webpage: http://people.csail.mit.edu/sparis/bf/ + */ + template + class FastBilateralFilterOMP : public FastBilateralFilter + { + protected: + using FastBilateralFilter::input_; + using FastBilateralFilter::sigma_s_; + using FastBilateralFilter::sigma_r_; + using FastBilateralFilter::early_division_; + typedef typename FastBilateralFilter::Array3D Array3D; + + typedef typename Filter::PointCloud PointCloud; + + public: + + typedef boost::shared_ptr< FastBilateralFilterOMP > Ptr; + typedef boost::shared_ptr< const FastBilateralFilterOMP > ConstPtr; + + /** \brief Empty constructor. */ + FastBilateralFilterOMP (unsigned int nr_threads = 0) + : threads_ (nr_threads) + { } + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + + /** \brief Filter the input data and store the results into output. + * \param[out] output the resultant point cloud + */ + void + applyFilter (PointCloud &output); + + protected: + /** \brief The number of threads the scheduler should use. */ + unsigned int threads_; + + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#else +#define PCL_INSTANTIATE_FastBilateralFilterOMP(T) template class PCL_EXPORTS pcl::FastBilateralFilterOMP; +#endif + + +#endif /* PCL_FILTERS_FAST_BILATERAL_OMP_H_ */ + diff --git a/pcl-1.7/pcl/filters/filter.h b/pcl-1.7/pcl/filters/filter.h new file mode 100644 index 0000000..c6fd846 --- /dev/null +++ b/pcl-1.7/pcl/filters/filter.h @@ -0,0 +1,267 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTER_H_ +#define PCL_FILTER_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Removes points with x, y, or z equal to NaN + * \param[in] cloud_in the input point cloud + * \param[out] cloud_out the input point cloud + * \param[out] index the mapping (ordered): cloud_out.points[i] = cloud_in.points[index[i]] + * \note The density of the point cloud is lost. + * \note Can be called with cloud_in == cloud_out + * \ingroup filters + */ + template void + removeNaNFromPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + std::vector &index); + + /** \brief Removes points that have their normals invalid (i.e., equal to NaN) + * \param[in] cloud_in the input point cloud + * \param[out] cloud_out the input point cloud + * \param[out] index the mapping (ordered): cloud_out.points[i] = cloud_in.points[index[i]] + * \note The density of the point cloud is lost. + * \note Can be called with cloud_in == cloud_out + * \ingroup filters + */ + template void + removeNaNNormalsFromPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + std::vector &index); + + //////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Filter represents the base filter class. All filters must inherit from this interface. + * \author Radu B. Rusu + * \ingroup filters + */ + template + class Filter : public PCLBase + { + public: + using PCLBase::indices_; + using PCLBase::input_; + + typedef boost::shared_ptr< Filter > Ptr; + typedef boost::shared_ptr< const Filter > ConstPtr; + + + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + /** \brief Empty constructor. + * \param[in] extract_removed_indices set to true if the filtered data indices should be saved in a + * separate list. Default: false. + */ + Filter (bool extract_removed_indices = false) : + removed_indices_ (new std::vector), + filter_name_ (), + extract_removed_indices_ (extract_removed_indices) + { + } + + /** \brief Empty destructor */ + virtual ~Filter () {} + + /** \brief Get the point indices being removed */ + inline IndicesConstPtr const + getRemovedIndices () + { + return (removed_indices_); + } + + /** \brief Get the point indices being removed + * \param[out] pi the resultant point indices that have been removed + */ + inline void + getRemovedIndices (PointIndices &pi) + { + pi.indices = *removed_indices_; + } + + /** \brief Calls the filtering method and returns the filtered dataset in output. + * \param[out] output the resultant filtered point cloud dataset + */ + inline void + filter (PointCloud &output) + { + if (!initCompute ()) + return; + + // Resize the output dataset + //if (output.points.size () != indices_->size ()) + // output.points.resize (indices_->size ()); + + // Copy header at a minimum + output.header = input_->header; + output.sensor_origin_ = input_->sensor_origin_; + output.sensor_orientation_ = input_->sensor_orientation_; + + // Apply the actual filter + applyFilter (output); + + deinitCompute (); + } + + protected: + + using PCLBase::initCompute; + using PCLBase::deinitCompute; + + /** \brief Indices of the points that are removed */ + IndicesPtr removed_indices_; + + /** \brief The filter name. */ + std::string filter_name_; + + /** \brief Set to true if we want to return the indices of the removed points. */ + bool extract_removed_indices_; + + /** \brief Abstract filter method. + * + * The implementation needs to set output.{points, width, height, is_dense}. + * + * \param[out] output the resultant filtered point cloud + */ + virtual void + applyFilter (PointCloud &output) = 0; + + /** \brief Get a string representation of the name of this class. */ + inline const std::string& + getClassName () const + { + return (filter_name_); + } + }; + + //////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Filter represents the base filter class. All filters must inherit from this interface. + * \author Radu B. Rusu + * \ingroup filters + */ + template<> + class PCL_EXPORTS Filter : public PCLBase + { + public: + typedef boost::shared_ptr< Filter > Ptr; + typedef boost::shared_ptr< const Filter > ConstPtr; + + typedef pcl::PCLPointCloud2 PCLPointCloud2; + typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr; + typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr; + + /** \brief Empty constructor. + * \param[in] extract_removed_indices set to true if the filtered data indices should be saved in a + * separate list. Default: false. + */ + Filter (bool extract_removed_indices = false) : + removed_indices_ (new std::vector), + extract_removed_indices_ (extract_removed_indices), + filter_name_ () + { + } + + /** \brief Empty destructor */ + virtual ~Filter () {} + + /** \brief Get the point indices being removed */ + inline IndicesConstPtr const + getRemovedIndices () + { + return (removed_indices_); + } + + /** \brief Get the point indices being removed + * \param[out] pi the resultant point indices that have been removed + */ + inline void + getRemovedIndices (PointIndices &pi) + { + pi.indices = *removed_indices_; + } + + /** \brief Calls the filtering method and returns the filtered dataset in output. + * \param[out] output the resultant filtered point cloud dataset + */ + void + filter (PCLPointCloud2 &output); + + protected: + + /** \brief Indices of the points that are removed */ + IndicesPtr removed_indices_; + + /** \brief Set to true if we want to return the indices of the removed points. */ + bool extract_removed_indices_; + + /** \brief The filter name. */ + std::string filter_name_; + + /** \brief Abstract filter method. + * + * The implementation needs to set output.{data, row_step, point_step, width, height, is_dense}. + * + * \param[out] output the resultant filtered point cloud + */ + virtual void + applyFilter (PCLPointCloud2 &output) = 0; + + /** \brief Get a string representation of the name of this class. */ + inline const std::string& + getClassName () const + { + return (filter_name_); + } + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FILTER_H_ diff --git a/pcl-1.7/pcl/filters/filter_indices.h b/pcl-1.7/pcl/filters/filter_indices.h new file mode 100644 index 0000000..5bba9e8 --- /dev/null +++ b/pcl-1.7/pcl/filters/filter_indices.h @@ -0,0 +1,313 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: filter_indices.h 4707 2012-02-23 10:34:17Z florentinus $ + * + */ + +#ifndef PCL_FILTERS_FILTER_INDICES_H_ +#define PCL_FILTERS_FILTER_INDICES_H_ + +#include + +namespace pcl +{ + /** \brief Removes points with x, y, or z equal to NaN (dry run). + * + * This function only computes the mapping between the points in the input + * cloud and the cloud that would result from filtering. It does not + * actually construct and output the filtered cloud. + * + * \note This function does not modify the input point cloud! + * + * \param cloud_in the input point cloud + * \param index the mapping (ordered): filtered_cloud.points[i] = cloud_in.points[index[i]] + * + * \see removeNaNFromPointCloud + * \ingroup filters + */ + template void + removeNaNFromPointCloud (const pcl::PointCloud &cloud_in, std::vector &index); + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b FilterIndices represents the base class for filters that are about binary point removal. + *
+ * All derived classes have to implement the \a filter (PointCloud &output) and the \a filter (std::vector &indices) methods. + * Ideally they also make use of the \a negative_, \a keep_organized_ and \a extract_removed_indices_ systems. + * The distinguishment between the \a negative_ and \a extract_removed_indices_ systems only makes sense if the class automatically + * filters non-finite entries in the filtering methods (recommended). + * \author Justin Rosen + * \ingroup filters + */ + template + class FilterIndices : public Filter + { + public: + using Filter::extract_removed_indices_; + typedef pcl::PointCloud PointCloud; + + typedef boost::shared_ptr< FilterIndices > Ptr; + typedef boost::shared_ptr< const FilterIndices > ConstPtr; + + + /** \brief Constructor. + * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false). + */ + FilterIndices (bool extract_removed_indices = false) : + negative_ (false), + keep_organized_ (false), + user_filter_value_ (std::numeric_limits::quiet_NaN ()) + { + extract_removed_indices_ = extract_removed_indices; + } + + /** \brief Empty virtual destructor. */ + virtual + ~FilterIndices () + { + } + + inline void + filter (PointCloud &output) + { + pcl::Filter::filter (output); + } + + /** \brief Calls the filtering method and returns the filtered point cloud indices. + * \param[out] indices the resultant filtered point cloud indices + */ + inline void + filter (std::vector &indices) + { + if (!initCompute ()) + return; + + // Apply the actual filter + applyFilter (indices); + + deinitCompute (); + } + + /** \brief Set whether the regular conditions for points filtering should apply, or the inverted conditions. + * \param[in] negative false = normal filter behavior (default), true = inverted behavior. + */ + inline void + setNegative (bool negative) + { + negative_ = negative; + } + + /** \brief Get whether the regular conditions for points filtering should apply, or the inverted conditions. + * \return The value of the internal \a negative_ parameter; false = normal filter behavior (default), true = inverted behavior. + */ + inline bool + getNegative () + { + return (negative_); + } + + /** \brief Set whether the filtered points should be kept and set to the value given through \a setUserFilterValue (default: NaN), + * or removed from the PointCloud, thus potentially breaking its organized structure. + * \param[in] keep_organized false = remove points (default), true = redefine points, keep structure. + */ + inline void + setKeepOrganized (bool keep_organized) + { + keep_organized_ = keep_organized; + } + + /** \brief Get whether the filtered points should be kept and set to the value given through \a setUserFilterValue (default = NaN), + * or removed from the PointCloud, thus potentially breaking its organized structure. + * \return The value of the internal \a keep_organized_ parameter; false = remove points (default), true = redefine points, keep structure. + */ + inline bool + getKeepOrganized () + { + return (keep_organized_); + } + + /** \brief Provide a value that the filtered points should be set to instead of removing them. + * Used in conjunction with \a setKeepOrganized (). + * \param[in] value the user given value that the filtered point dimensions should be set to (default = NaN). + */ + inline void + setUserFilterValue (float value) + { + user_filter_value_ = value; + } + + protected: + + using Filter::initCompute; + using Filter::deinitCompute; + + /** \brief False = normal filter behavior (default), true = inverted behavior. */ + bool negative_; + + /** \brief False = remove points (default), true = redefine points, keep structure. */ + bool keep_organized_; + + /** \brief The user given value that the filtered point dimensions should be set to (default = NaN). */ + float user_filter_value_; + + /** \brief Abstract filter method for point cloud indices. */ + virtual void + applyFilter (std::vector &indices) = 0; + + /** \brief Abstract filter method for point cloud. */ + virtual void + applyFilter (PointCloud &output) = 0; + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b FilterIndices represents the base class for filters that are about binary point removal. + *
+ * All derived classes have to implement the \a filter (PointCloud &output) and the \a filter (std::vector &indices) methods. + * Ideally they also make use of the \a negative_, \a keep_organized_ and \a extract_removed_indices_ systems. + * The distinguishment between the \a negative_ and \a extract_removed_indices_ systems only makes sense if the class automatically + * filters non-finite entries in the filtering methods (recommended). + * \author Justin Rosen + * \ingroup filters + */ + template<> + class PCL_EXPORTS FilterIndices : public Filter + { + public: + typedef pcl::PCLPointCloud2 PCLPointCloud2; + + /** \brief Constructor. + * \param[in] extract_removed_indices Set to true if you want to extract the indices of points being removed (default = false). + */ + FilterIndices (bool extract_removed_indices = false) : + negative_ (false), + keep_organized_ (false), + user_filter_value_ (std::numeric_limits::quiet_NaN ()) + { + extract_removed_indices_ = extract_removed_indices; + } + + /** \brief Empty virtual destructor. */ + virtual + ~FilterIndices () + { + } + + virtual void + filter (PCLPointCloud2 &output) + { + pcl::Filter::filter (output); + } + + /** \brief Calls the filtering method and returns the filtered point cloud indices. + * \param[out] indices the resultant filtered point cloud indices + */ + void + filter (std::vector &indices); + + /** \brief Set whether the regular conditions for points filtering should apply, or the inverted conditions. + * \param[in] negative false = normal filter behavior (default), true = inverted behavior. + */ + inline void + setNegative (bool negative) + { + negative_ = negative; + } + + /** \brief Get whether the regular conditions for points filtering should apply, or the inverted conditions. + * \return The value of the internal \a negative_ parameter; false = normal filter behavior (default), true = inverted behavior. + */ + inline bool + getNegative () + { + return (negative_); + } + + /** \brief Set whether the filtered points should be kept and set to the value given through \a setUserFilterValue (default: NaN), + * or removed from the PointCloud, thus potentially breaking its organized structure. + * \param[in] keep_organized false = remove points (default), true = redefine points, keep structure. + */ + inline void + setKeepOrganized (bool keep_organized) + { + keep_organized_ = keep_organized; + } + + /** \brief Get whether the filtered points should be kept and set to the value given through \a setUserFilterValue (default = NaN), + * or removed from the PointCloud, thus potentially breaking its organized structure. + * \return The value of the internal \a keep_organized_ parameter; false = remove points (default), true = redefine points, keep structure. + */ + inline bool + getKeepOrganized () + { + return (keep_organized_); + } + + /** \brief Provide a value that the filtered points should be set to instead of removing them. + * Used in conjunction with \a setKeepOrganized (). + * \param[in] value the user given value that the filtered point dimensions should be set to (default = NaN). + */ + inline void + setUserFilterValue (float value) + { + user_filter_value_ = value; + } + + protected: + + /** \brief False = normal filter behavior (default), true = inverted behavior. */ + bool negative_; + + /** \brief False = remove points (default), true = redefine points, keep structure. */ + bool keep_organized_; + + /** \brief The user given value that the filtered point dimensions should be set to (default = NaN). */ + float user_filter_value_; + + /** \brief Abstract filter method for point cloud indices. */ + virtual void + applyFilter (std::vector &indices) = 0; + + /** \brief Abstract filter method for point cloud. */ + virtual void + applyFilter (PCLPointCloud2 &output) = 0; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FILTERS_FILTER_INDICES_H_ + diff --git a/pcl-1.7/pcl/filters/frustum_culling.h b/pcl-1.7/pcl/filters/frustum_culling.h new file mode 100644 index 0000000..9069a6d --- /dev/null +++ b/pcl-1.7/pcl/filters/frustum_culling.h @@ -0,0 +1,242 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + + +#ifndef PCL_FILTERS_FRUSTUM_CULLING_H_ +#define PCL_FILTERS_FRUSTUM_CULLING_H_ + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief FrustumCulling filters points inside a frustum + * given by pose and field of view of the camera. + * + * Code example: + * + * \code + * pcl::PointCloud ::Ptr source; + * // .. read or fill the source cloud + * + * pcl::FrustumCulling fc; + * fc.setInputCloud (source); + * fc.setVerticalFOV (45); + * fc.setHorizontalFOV (60); + * fc.setNearPlaneDistance (5.0); + * fc.setFarPlaneDistance (15); + * + * Eigen::Matrix4f camera_pose; + * // .. read or input the camera pose from a registration algorithm. + * fc.setCameraPose (camera_pose); + * + * pcl::PointCloud target; + * fc.filter (target); + * \endcode + * + * + * \author Aravindhan K Krishnan + * \ingroup filters + */ + template + class FrustumCulling : public FilterIndices + { + typedef typename Filter::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + + typedef boost::shared_ptr< FrustumCulling > Ptr; + typedef boost::shared_ptr< const FrustumCulling > ConstPtr; + + + using Filter::getClassName; + + FrustumCulling (bool extract_removed_indices = false) + : FilterIndices::FilterIndices (extract_removed_indices) + , camera_pose_ (Eigen::Matrix4f::Identity ()) + , hfov_ (60.0f) + , vfov_ (60.0f) + , np_dist_ (0.1f) + , fp_dist_ (5.0f) + { + filter_name_ = "FrustumCulling"; + } + + /** \brief Set the pose of the camera w.r.t the origin + * \param[in] camera_pose the camera pose + * + * Note: This assumes a coordinate system where X is forward, + * Y is up, and Z is right. To convert from the traditional camera + * coordinate system (X right, Y down, Z forward), one can use: + * + * \code + * Eigen::Matrix4f pose_orig = //pose in camera coordinates + * Eigen::Matrix4f cam2robot; + * cam2robot << 0, 0, 1, 0 + * 0,-1, 0, 0 + * 1, 0, 0, 0 + * 0, 0, 0, 1; + * Eigen::Matrix4f pose_new = pose_orig * cam2robot; + * fc.setCameraPose (pose_new); + * \endcode + */ + void + setCameraPose (const Eigen::Matrix4f& camera_pose) + { + camera_pose_ = camera_pose; + } + + /** \brief Get the pose of the camera w.r.t the origin */ + Eigen::Matrix4f + getCameraPose () const + { + return (camera_pose_); + } + + /** \brief Set the horizontal field of view for the camera in degrees + * \param[in] hfov the field of view + */ + void + setHorizontalFOV (float hfov) + { + hfov_ = hfov; + } + + /** \brief Get the horizontal field of view for the camera in degrees */ + float + getHorizontalFOV () const + { + return (hfov_); + } + + /** \brief Set the vertical field of view for the camera in degrees + * \param[in] vfov the field of view + */ + void + setVerticalFOV (float vfov) + { + vfov_ = vfov; + } + + /** \brief Get the vertical field of view for the camera in degrees */ + float + getVerticalFOV () const + { + return (vfov_); + } + + /** \brief Set the near plane distance + * \param[in] np_dist the near plane distance + */ + void + setNearPlaneDistance (float np_dist) + { + np_dist_ = np_dist; + } + + /** \brief Get the near plane distance. */ + float + getNearPlaneDistance () const + { + return (np_dist_); + } + + /** \brief Set the far plane distance + * \param[in] fp_dist the far plane distance + */ + void + setFarPlaneDistance (float fp_dist) + { + fp_dist_ = fp_dist; + } + + /** \brief Get the far plane distance */ + float + getFarPlaneDistance () const + { + return (fp_dist_); + } + + protected: + using PCLBase::input_; + using PCLBase::indices_; + using Filter::filter_name_; + using FilterIndices::negative_; + using FilterIndices::keep_organized_; + using FilterIndices::user_filter_value_; + using FilterIndices::extract_removed_indices_; + using FilterIndices::removed_indices_; + + /** \brief Sample of point indices into a separate PointCloud + * \param[out] output the resultant point cloud + */ + void + applyFilter (PointCloud &output); + + /** \brief Sample of point indices + * \param[out] indices the resultant point cloud indices + */ + void + applyFilter (std::vector &indices); + + private: + + /** \brief The camera pose */ + Eigen::Matrix4f camera_pose_; + /** \brief Horizontal field of view */ + float hfov_; + /** \brief Vertical field of view */ + float vfov_; + /** \brief Near plane distance */ + float np_dist_; + /** \brief Far plane distance */ + float fp_dist_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/filters/grid_minimum.h b/pcl-1.7/pcl/filters/grid_minimum.h new file mode 100644 index 0000000..5d4a599 --- /dev/null +++ b/pcl-1.7/pcl/filters/grid_minimum.h @@ -0,0 +1,137 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2014, RadiantBlue Technologies, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_VOXEL_GRID_MINIMUM_H_ +#define PCL_FILTERS_VOXEL_GRID_MINIMUM_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief GridMinimum assembles a local 2D grid over a given PointCloud, and downsamples the data. + * + * The GridMinimum class creates a *2D grid* over the input point cloud + * data. Then, in each *cell* (i.e., 2D grid element), all the points + * present will be *downsampled* with the minimum z value. This grid minimum + * can be useful in a number of topographic processing tasks such as crudely + * estimating ground returns, especially under foliage. + * + * \author Bradley J Chambers + * \ingroup filters + */ + template + class GridMinimum: public FilterIndices + { + protected: + using Filter::filter_name_; + using Filter::getClassName; + using Filter::input_; + using Filter::indices_; + + typedef typename FilterIndices::PointCloud PointCloud; + + public: + /** \brief Empty constructor. */ + GridMinimum (const float resolution) + { + setResolution (resolution); + filter_name_ = "GridMinimum"; + } + + /** \brief Destructor. */ + virtual ~GridMinimum () + { + } + + /** \brief Set the grid resolution. + * \param[in] resolution the grid resolution + */ + inline void + setResolution (const float resolution) + { + resolution_ = resolution; + // Use multiplications instead of divisions + inverse_resolution_ = 1.0f / resolution_; + } + + /** \brief Get the grid resolution. */ + inline float + getResolution () { return (resolution_); } + + protected: + /** \brief The resolution. */ + float resolution_; + + /** \brief Internal resolution stored as 1/resolution_ for efficiency reasons. */ + float inverse_resolution_; + + /** \brief Downsample a Point Cloud using a 2D grid approach + * \param[out] output the resultant point cloud message + */ + void + applyFilter (PointCloud &output); + + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. + */ + void + applyFilter (std::vector &indices) + { + applyFilterIndices (indices); + } + + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. + */ + void + applyFilterIndices (std::vector &indices); + + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FILTERS_VOXEL_GRID_MINIMUM_H_ + diff --git a/pcl-1.7/pcl/filters/impl/approximate_voxel_grid.hpp b/pcl-1.7/pcl/filters/impl/approximate_voxel_grid.hpp new file mode 100644 index 0000000..7bff0a7 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/approximate_voxel_grid.hpp @@ -0,0 +1,138 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: voxel_grid.hpp 1600 2011-07-07 16:55:51Z shapovalov $ + * + */ + +#ifndef PCL_FILTERS_IMPL_FAST_VOXEL_GRID_H_ +#define PCL_FILTERS_IMPL_FAST_VOXEL_GRID_H_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ApproximateVoxelGrid::flush (PointCloud &output, size_t op, he *hhe, int rgba_index, int centroid_size) +{ + hhe->centroid /= static_cast (hhe->count); + pcl::for_each_type (pcl::xNdCopyEigenPointFunctor (hhe->centroid, output.points[op])); + // ---[ RGB special case + if (rgba_index >= 0) + { + // pack r/g/b into rgb + float r = hhe->centroid[centroid_size-3], + g = hhe->centroid[centroid_size-2], + b = hhe->centroid[centroid_size-1]; + int rgb = (static_cast (r)) << 16 | (static_cast (g)) << 8 | (static_cast (b)); + memcpy (reinterpret_cast (&output.points[op]) + rgba_index, &rgb, sizeof (float)); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ApproximateVoxelGrid::applyFilter (PointCloud &output) +{ + int centroid_size = 4; + if (downsample_all_data_) + centroid_size = boost::mpl::size::value; + + // ---[ RGB special case + std::vector fields; + int rgba_index = -1; + rgba_index = pcl::getFieldIndex (*input_, "rgb", fields); + if (rgba_index == -1) + rgba_index = pcl::getFieldIndex (*input_, "rgba", fields); + if (rgba_index >= 0) + { + rgba_index = fields[rgba_index].offset; + centroid_size += 3; + } + + for (size_t i = 0; i < histsize_; i++) + { + history_[i].count = 0; + history_[i].centroid = Eigen::VectorXf::Zero (centroid_size); + } + Eigen::VectorXf scratch = Eigen::VectorXf::Zero (centroid_size); + + output.points.resize (input_->points.size ()); // size output for worst case + size_t op = 0; // output pointer + for (size_t cp = 0; cp < input_->points.size (); ++cp) + { + int ix = static_cast (floor (input_->points[cp].x * inverse_leaf_size_[0])); + int iy = static_cast (floor (input_->points[cp].y * inverse_leaf_size_[1])); + int iz = static_cast (floor (input_->points[cp].z * inverse_leaf_size_[2])); + unsigned int hash = static_cast ((ix * 7171 + iy * 3079 + iz * 4231) & (histsize_ - 1)); + he *hhe = &history_[hash]; + if (hhe->count && ((ix != hhe->ix) || (iy != hhe->iy) || (iz != hhe->iz))) + { + flush (output, op++, hhe, rgba_index, centroid_size); + hhe->count = 0; + hhe->centroid.setZero ();// = Eigen::VectorXf::Zero (centroid_size); + } + hhe->ix = ix; + hhe->iy = iy; + hhe->iz = iz; + hhe->count++; + + // Unpack the point into scratch, then accumulate + // ---[ RGB special case + if (rgba_index >= 0) + { + // fill r/g/b data + pcl::RGB rgb; + memcpy (&rgb, (reinterpret_cast (&input_->points[cp])) + rgba_index, sizeof (RGB)); + scratch[centroid_size-3] = rgb.r; + scratch[centroid_size-2] = rgb.g; + scratch[centroid_size-1] = rgb.b; + } + pcl::for_each_type (xNdCopyPointEigenFunctor (input_->points[cp], scratch)); + hhe->centroid += scratch; + } + for (size_t i = 0; i < histsize_; i++) + { + he *hhe = &history_[i]; + if (hhe->count) + flush (output, op++, hhe, rgba_index, centroid_size); + } + output.points.resize (op); + output.width = static_cast (output.points.size ()); + output.height = 1; // downsampling breaks the organized structure + output.is_dense = false; // we filter out invalid points +} + +#define PCL_INSTANTIATE_ApproximateVoxelGrid(T) template class PCL_EXPORTS pcl::ApproximateVoxelGrid; + +#endif // PCL_FILTERS_IMPL_FAST_VOXEL_GRID_H_ diff --git a/pcl-1.7/pcl/filters/impl/bilateral.hpp b/pcl-1.7/pcl/filters/impl/bilateral.hpp new file mode 100644 index 0000000..30295fb --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/bilateral.hpp @@ -0,0 +1,113 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_BILATERAL_IMPL_H_ +#define PCL_FILTERS_BILATERAL_IMPL_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::BilateralFilter::computePointWeight (const int pid, + const std::vector &indices, + const std::vector &distances) +{ + double BF = 0, W = 0; + + // For each neighbor + for (size_t n_id = 0; n_id < indices.size (); ++n_id) + { + int id = indices[n_id]; + // Compute the difference in intensity + double intensity_dist = fabs (input_->points[pid].intensity - input_->points[id].intensity); + + // Compute the Gaussian intensity weights both in Euclidean and in intensity space + double dist = std::sqrt (distances[n_id]); + double weight = kernel (dist, sigma_s_) * kernel (intensity_dist, sigma_r_); + + // Calculate the bilateral filter response + BF += weight * input_->points[id].intensity; + W += weight; + } + return (BF / W); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BilateralFilter::applyFilter (PointCloud &output) +{ + // Check if sigma_s has been given by the user + if (sigma_s_ == 0) + { + PCL_ERROR ("[pcl::BilateralFilter::applyFilter] Need a sigma_s value given before continuing.\n"); + return; + } + // In case a search method has not been given, initialize it using some defaults + if (!tree_) + { + // For organized datasets, use an OrganizedDataIndex + if (input_->isOrganized ()) + tree_.reset (new pcl::search::OrganizedNeighbor ()); + // For unorganized data, use a FLANN kdtree + else + tree_.reset (new pcl::search::KdTree (false)); + } + tree_->setInputCloud (input_); + + std::vector k_indices; + std::vector k_distances; + + // Copy the input data into the output + output = *input_; + + // For all the indices given (equal to the entire cloud if none given) + for (size_t i = 0; i < indices_->size (); ++i) + { + // Perform a radius search to find the nearest neighbors + tree_->radiusSearch ((*indices_)[i], sigma_s_ * 2, k_indices, k_distances); + + // Overwrite the intensity value with the computed average + output.points[(*indices_)[i]].intensity = static_cast (computePointWeight ((*indices_)[i], k_indices, k_distances)); + } +} + +#define PCL_INSTANTIATE_BilateralFilter(T) template class PCL_EXPORTS pcl::BilateralFilter; + +#endif // PCL_FILTERS_BILATERAL_H_ + diff --git a/pcl-1.7/pcl/filters/impl/box_clipper3D.hpp b/pcl-1.7/pcl/filters/impl/box_clipper3D.hpp new file mode 100644 index 0000000..9f0bb24 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/box_clipper3D.hpp @@ -0,0 +1,222 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_FILTERS_IMPL_BOX_CLIPPER3D_HPP +#define PCL_FILTERS_IMPL_BOX_CLIPPER3D_HPP + +#include + +template +pcl::BoxClipper3D::BoxClipper3D (const Eigen::Affine3f& transformation) +: transformation_ (transformation) +{ + //inverse_transformation_ = transformation_.inverse (); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::BoxClipper3D::BoxClipper3D (const Eigen::Vector3f& rodrigues, const Eigen::Vector3f& translation, const Eigen::Vector3f& box_size) +{ + setTransformation (rodrigues, translation, box_size); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::BoxClipper3D::~BoxClipper3D () throw () +{ +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BoxClipper3D::setTransformation (const Eigen::Affine3f& transformation) +{ + transformation_ = transformation; + //inverse_transformation_ = transformation_.inverse (); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BoxClipper3D::setTransformation (const Eigen::Vector3f& rodrigues, const Eigen::Vector3f& translation, const Eigen::Vector3f& box_size) +{ + transformation_ = Eigen::Translation3f (translation) * Eigen::AngleAxisf(rodrigues.norm (), rodrigues.normalized ()) * Eigen::Scaling (box_size); + //inverse_transformation_ = transformation_.inverse (); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template pcl::Clipper3D* +pcl::BoxClipper3D::clone () const +{ + return new BoxClipper3D (transformation_); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BoxClipper3D::transformPoint (const PointT& pointIn, PointT& pointOut) const +{ + const Eigen::Vector4f& point = pointIn.getVector4fMap (); + pointOut.getVector4fMap () = transformation_ * point; + + // homogeneous value might not be 1 + if (point [3] != 1) + { + // homogeneous component might be uninitialized -> invalid + if (point [3] != 0) + { + pointOut.x += (1 - point [3]) * transformation_.data () [ 9]; + pointOut.y += (1 - point [3]) * transformation_.data () [10]; + pointOut.z += (1 - point [3]) * transformation_.data () [11]; + } + else + { + pointOut.x += transformation_.data () [ 9]; + pointOut.y += transformation_.data () [10]; + pointOut.z += transformation_.data () [11]; + } + } +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +// ToDo use product on point.getVector3fMap () and transformatio_.col (i) to use the SSE advantages of eigen +template bool +pcl::BoxClipper3D::clipPoint3D (const PointT& point) const +{ + return (fabs(transformation_.data () [ 0] * point.x + + transformation_.data () [ 3] * point.y + + transformation_.data () [ 6] * point.z + + transformation_.data () [ 9]) <= 1 && + fabs(transformation_.data () [ 1] * point.x + + transformation_.data () [ 4] * point.y + + transformation_.data () [ 7] * point.z + + transformation_.data () [10]) <= 1 && + fabs(transformation_.data () [ 2] * point.x + + transformation_.data () [ 5] * point.y + + transformation_.data () [ 8] * point.z + + transformation_.data () [11]) <= 1 ); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +/** + * @attention untested code + */ +template bool +pcl::BoxClipper3D::clipLineSegment3D (PointT& point1, PointT& point2) const +{ + /* + PointT pt1, pt2; + transformPoint (point1, pt1); + transformPoint (point2, pt2); + + // + bool pt1InBox = (fabs(pt1.x) <= 1.0 && fabs (pt1.y) <= 1.0 && fabs (pt1.z) <= 1.0); + bool pt2InBox = (fabs(pt2.x) <= 1.0 && fabs (pt2.y) <= 1.0 && fabs (pt2.z) <= 1.0); + + // one is outside the other one inside the box + //if (pt1InBox ^ pt2InBox) + if (pt1InBox && !pt2InBox) + { + PointT diff; + PointT lambda; + diff.getVector3fMap () = pt2.getVector3fMap () - pt1.getVector3fMap (); + + if (diff.x > 0) + lambda.x = (1.0 - pt1.x) / diff.x; + else + lambda.x = (-1.0 - pt1.x) / diff.x; + + if (diff.y > 0) + lambda.y = (1.0 - pt1.y) / diff.y; + else + lambda.y = (-1.0 - pt1.y) / diff.y; + + if (diff.z > 0) + lambda.z = (1.0 - pt1.z) / diff.z; + else + lambda.z = (-1.0 - pt1.z) / diff.z; + + pt2 = pt1 + std::min(std::min(lambda.x, lambda.y), lambda.z) * diff; + + // inverse transformation + inverseTransformPoint (pt2, point2); + return true; + } + else if (!pt1InBox && pt2InBox) + { + return true; + } + */ + return false; +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +/** + * @attention untested code + */ +template void +pcl::BoxClipper3D::clipPlanarPolygon3D (const std::vector >& polygon, std::vector >& clipped_polygon) const +{ + // not implemented -> clip everything + clipped_polygon.clear (); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +/** + * @attention untested code + */ +template void +pcl::BoxClipper3D::clipPlanarPolygon3D (std::vector >& polygon) const +{ + // not implemented -> clip everything + polygon.clear (); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +// /ToDo: write fast version using eigen map and single matrix vector multiplication, that uses advantages of eigens SSE operations. +template void +pcl::BoxClipper3D::clipPointCloud3D (const pcl::PointCloud& cloud_in, std::vector& clipped, const std::vector& indices) const +{ + if (indices.empty ()) + { + clipped.reserve (cloud_in.size ()); + for (register unsigned pIdx = 0; pIdx < cloud_in.size (); ++pIdx) + if (clipPoint3D (cloud_in[pIdx])) + clipped.push_back (pIdx); + } + else + { + for (std::vector::const_iterator iIt = indices.begin (); iIt != indices.end (); ++iIt) + if (clipPoint3D (cloud_in[*iIt])) + clipped.push_back (*iIt); + } +} +#endif //PCL_FILTERS_IMPL_BOX_CLIPPER3D_HPP \ No newline at end of file diff --git a/pcl-1.7/pcl/filters/impl/conditional_removal.hpp b/pcl-1.7/pcl/filters/impl/conditional_removal.hpp new file mode 100644 index 0000000..9a20bef --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/conditional_removal.hpp @@ -0,0 +1,802 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTER_IMPL_FIELD_VAL_CONDITION_H_ +#define PCL_FILTER_IMPL_FIELD_VAL_CONDITION_H_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +template +pcl::FieldComparison::FieldComparison ( + std::string field_name, ComparisonOps::CompareOp op, double compare_val) + : ComparisonBase () + , compare_val_ (compare_val), point_data_ (NULL) +{ + field_name_ = field_name; + op_ = op; + + // Get all fields + std::vector point_fields; + // Use a dummy cloud to get the field types in a clever way + PointCloud dummyCloud; + pcl::getFields (dummyCloud, point_fields); + + // Find field_name + if (point_fields.empty ()) + { + PCL_WARN ("[pcl::FieldComparison::FieldComparison] no fields found!\n"); + capable_ = false; + return; + } + + // Get the field index + size_t d; + for (d = 0; d < point_fields.size (); ++d) + { + if (point_fields[d].name == field_name) + break; + } + + if (d == point_fields.size ()) + { + PCL_WARN ("[pcl::FieldComparison::FieldComparison] field not found!\n"); + capable_ = false; + return; + } + uint8_t datatype = point_fields[d].datatype; + uint32_t offset = point_fields[d].offset; + + point_data_ = new PointDataAtOffset(datatype, offset); + capable_ = true; +} + +////////////////////////////////////////////////////////////////////////// +template +pcl::FieldComparison::~FieldComparison () +{ + if (point_data_ != NULL) + { + delete point_data_; + point_data_ = NULL; + } +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::FieldComparison::evaluate (const PointT &point) const +{ + if (!this->capable_) + { + PCL_WARN ("[pcl::FieldComparison::evaluate] invalid compariosn!\n"); + return (false); + } + + // if p(data) > val then compare_result = 1 + // if p(data) == val then compare_result = 0 + // if p(data) < ival then compare_result = -1 + int compare_result = point_data_->compare (point, compare_val_); + + switch (this->op_) + { + case pcl::ComparisonOps::GT : + return (compare_result > 0); + case pcl::ComparisonOps::GE : + return (compare_result >= 0); + case pcl::ComparisonOps::LT : + return (compare_result < 0); + case pcl::ComparisonOps::LE : + return (compare_result <= 0); + case pcl::ComparisonOps::EQ : + return (compare_result == 0); + default: + PCL_WARN ("[pcl::FieldComparison::evaluate] unrecognized op_!\n"); + return (false); + } +} + +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +template +pcl::PackedRGBComparison::PackedRGBComparison ( + std::string component_name, ComparisonOps::CompareOp op, double compare_val) : + component_name_ (component_name), component_offset_ (), compare_val_ (compare_val) +{ + // get all the fields + std::vector point_fields; + // Use a dummy cloud to get the field types in a clever way + PointCloud dummyCloud; + pcl::getFields (dummyCloud, point_fields); + + // Locate the "rgb" field + size_t d; + for (d = 0; d < point_fields.size (); ++d) + { + if (point_fields[d].name == "rgb" || point_fields[d].name == "rgba") + break; + } + if (d == point_fields.size ()) + { + PCL_WARN ("[pcl::PackedRGBComparison::PackedRGBComparison] rgb field not found!\n"); + capable_ = false; + return; + } + + // Verify the datatype + uint8_t datatype = point_fields[d].datatype; + if (datatype != pcl::PCLPointField::FLOAT32 && + datatype != pcl::PCLPointField::UINT32 && + datatype != pcl::PCLPointField::INT32) + { + PCL_WARN ("[pcl::PackedRGBComparison::PackedRGBComparison] has unusable type!\n"); + capable_ = false; + return; + } + + // Verify the component name + if (component_name == "r") + { + component_offset_ = point_fields[d].offset + 2; + } + else if (component_name == "g") + { + component_offset_ = point_fields[d].offset + 1; + } + else if (component_name == "b") + { + component_offset_ = point_fields[d].offset; + } + else + { + PCL_WARN ("[pcl::PackedRGBComparison::PackedRGBComparison] unrecognized component name!\n"); + capable_ = false; + return; + } + + // save the rest of the context + capable_ = true; + op_ = op; +} + + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::PackedRGBComparison::evaluate (const PointT &point) const +{ + // extract the component value + const uint8_t* pt_data = reinterpret_cast (&point); + uint8_t my_val = *(pt_data + component_offset_); + + // now do the comparison + switch (this->op_) + { + case pcl::ComparisonOps::GT : + return (my_val > this->compare_val_); + case pcl::ComparisonOps::GE : + return (my_val >= this->compare_val_); + case pcl::ComparisonOps::LT : + return (my_val < this->compare_val_); + case pcl::ComparisonOps::LE : + return (my_val <= this->compare_val_); + case pcl::ComparisonOps::EQ : + return (my_val == this->compare_val_); + default: + PCL_WARN ("[pcl::PackedRGBComparison::evaluate] unrecognized op_!\n"); + return (false); + } +} + +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +template +pcl::PackedHSIComparison::PackedHSIComparison ( + std::string component_name, ComparisonOps::CompareOp op, double compare_val) : + component_name_ (component_name), component_id_ (), compare_val_ (compare_val), rgb_offset_ () +{ + // Get all the fields + std::vector point_fields; + // Use a dummy cloud to get the field types in a clever way + PointCloud dummyCloud; + pcl::getFields (dummyCloud, point_fields); + + // Locate the "rgb" field + size_t d; + for (d = 0; d < point_fields.size (); ++d) + if (point_fields[d].name == "rgb" || point_fields[d].name == "rgba") + break; + if (d == point_fields.size ()) + { + PCL_WARN ("[pcl::PackedHSIComparison::PackedHSIComparison] rgb field not found!\n"); + capable_ = false; + return; + } + + // Verify the datatype + uint8_t datatype = point_fields[d].datatype; + if (datatype != pcl::PCLPointField::FLOAT32 && + datatype != pcl::PCLPointField::UINT32 && + datatype != pcl::PCLPointField::INT32) + { + PCL_WARN ("[pcl::PackedHSIComparison::PackedHSIComparison] has unusable type!\n"); + capable_ = false; + return; + } + + // verify the offset + uint32_t offset = point_fields[d].offset; + if (offset % 4 != 0) + { + PCL_WARN ("[pcl::PackedHSIComparison::PackedHSIComparison] rgb field is not 32 bit aligned!\n"); + capable_ = false; + return; + } + rgb_offset_ = point_fields[d].offset; + + // verify the component name + if (component_name == "h" ) + { + component_id_ = H; + } + else if (component_name == "s") + { + component_id_ = S; + } + else if (component_name == "i") + { + component_id_ = I; + } + else + { + PCL_WARN ("[pcl::PackedRGBComparison::PackedRGBComparison] unrecognized component name!\n"); + capable_ = false; + return; + } + + // Save the context + capable_ = true; + op_ = op; +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::PackedHSIComparison::evaluate (const PointT &point) const +{ + // Since this is a const function, we can't make these data members because we change them here + static uint32_t rgb_val_ = 0; + static uint8_t r_ = 0; + static uint8_t g_ = 0; + static uint8_t b_ = 0; + static int8_t h_ = 0; + static uint8_t s_ = 0; + static uint8_t i_ = 0; + + // We know that rgb data is 32 bit aligned (verified in the ctor) so... + const uint8_t* pt_data = reinterpret_cast (&point); + const uint32_t* rgb_data = reinterpret_cast (pt_data + rgb_offset_); + uint32_t new_rgb_val = *rgb_data; + + if (rgb_val_ != new_rgb_val) + { // avoid having to redo this calc, if possible + rgb_val_ = new_rgb_val; + // extract r,g,b + r_ = static_cast (rgb_val_ >> 16); + g_ = static_cast (rgb_val_ >> 8); + b_ = static_cast (rgb_val_); + + // definitions taken from http://en.wikipedia.org/wiki/HSL_and_HSI + float hx = (2.0f * r_ - g_ - b_) / 4.0f; // hue x component -127 to 127 + float hy = static_cast (g_ - b_) * 111.0f / 255.0f; // hue y component -111 to 111 + h_ = static_cast (atan2(hy, hx) * 128.0f / M_PI); + + int32_t i = (r_+g_+b_)/3; // 0 to 255 + i_ = static_cast (i); + + int32_t m; // min(r,g,b) + m = (r_ < g_) ? r_ : g_; + m = (m < b_) ? m : b_; + + s_ = static_cast ((i == 0) ? 0 : 255 - (m * 255) / i); // saturation 0 to 255 + } + + float my_val = 0; + + switch (component_id_) + { + case H: + my_val = static_cast (h_); + break; + case S: + my_val = static_cast (s_); + break; + case I: + my_val = static_cast (i_); + break; + default: + assert (false); + } + + // now do the comparison + switch (this->op_) + { + case pcl::ComparisonOps::GT : + return (my_val > this->compare_val_); + case pcl::ComparisonOps::GE : + return (my_val >= this->compare_val_); + case pcl::ComparisonOps::LT : + return (my_val < this->compare_val_); + case pcl::ComparisonOps::LE : + return (my_val <= this->compare_val_); + case pcl::ComparisonOps::EQ : + return (my_val == this->compare_val_); + default: + PCL_WARN ("[pcl::PackedHSIComparison::evaluate] unrecognized op_!\n"); + return (false); + } +} + + +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +template +pcl::TfQuadraticXYZComparison::TfQuadraticXYZComparison () : + comp_matr_ (), comp_vect_ (), comp_scalar_ (0.0) +{ + // get all the fields + std::vector point_fields; + // Use a dummy cloud to get the field types in a clever way + PointCloud dummyCloud; + pcl::getFields (dummyCloud, point_fields); + + // Locate the "x" field + size_t dX; + for (dX = 0; dX < point_fields.size (); ++dX) + { + if (point_fields[dX].name == "x") + break; + } + if (dX == point_fields.size ()) + { + PCL_WARN ("[pcl::TfQuadraticXYZComparison::TfQuadraticXYZComparison] x field not found!\n"); + capable_ = false; + return; + } + + // Locate the "y" field + size_t dY; + for (dY = 0; dY < point_fields.size (); ++dY) + { + if (point_fields[dY].name == "y") + break; + } + if (dY == point_fields.size ()) + { + PCL_WARN ("[pcl::TfQuadraticXYZComparison::TfQuadraticXYZComparison] y field not found!\n"); + capable_ = false; + return; + } + + // Locate the "z" field + size_t dZ; + for (dZ = 0; dZ < point_fields.size (); ++dZ) + { + if (point_fields[dZ].name == "z") + break; + } + if (dZ == point_fields.size ()) + { + PCL_WARN ("[pcl::TfQuadraticXYZComparison::TfQuadraticXYZComparison] z field not found!\n"); + capable_ = false; + return; + } + + comp_matr_ << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0; + comp_vect_ << 0.0, 0.0, 0.0, 1.0; + tf_comp_matr_ = comp_matr_; + tf_comp_vect_ = comp_vect_; + op_ = pcl::ComparisonOps::EQ; + capable_ = true; +} + +////////////////////////////////////////////////////////////////////////// +template +pcl::TfQuadraticXYZComparison::TfQuadraticXYZComparison (const pcl::ComparisonOps::CompareOp op, + const Eigen::Matrix3f &comparison_matrix, + const Eigen::Vector3f &comparison_vector, + const float &comparison_scalar, + const Eigen::Affine3f &comparison_transform) : + comp_matr_ (), comp_vect_ (), comp_scalar_ (comparison_scalar) +{ + // get all the fields + std::vector point_fields; + // Use a dummy cloud to get the field types in a clever way + PointCloud dummyCloud; + pcl::getFields (dummyCloud, point_fields); + + // Locate the "x" field + size_t dX; + for (dX = 0; dX < point_fields.size (); ++dX) + { + if (point_fields[dX].name == "x") + break; + } + if (dX == point_fields.size ()) + { + PCL_WARN ("[pcl::TfQuadraticXYZComparison::TfQuadraticXYZComparison] x field not found!\n"); + capable_ = false; + return; + } + + // Locate the "y" field + size_t dY; + for (dY = 0; dY < point_fields.size (); ++dY) + { + if (point_fields[dY].name == "y") + break; + } + if (dY == point_fields.size ()) + { + PCL_WARN ("[pcl::TfQuadraticXYZComparison::TfQuadraticXYZComparison] y field not found!\n"); + capable_ = false; + return; + } + + // Locate the "z" field + size_t dZ; + for (dZ = 0; dZ < point_fields.size (); ++dZ) + { + if (point_fields[dZ].name == "z") + break; + } + if (dZ == point_fields.size ()) + { + PCL_WARN ("[pcl::TfQuadraticXYZComparison::TfQuadraticXYZComparison] z field not found!\n"); + capable_ = false; + return; + } + + capable_ = true; + op_ = op; + setComparisonMatrix (comparison_matrix); + setComparisonVector (comparison_vector); + if (!comparison_transform.matrix ().isIdentity ()) + transformComparison (comparison_transform); +} + +////////////////////////////////////////////////////////////////////////// +template +bool +pcl::TfQuadraticXYZComparison::evaluate (const PointT &point) const +{ + Eigen::Vector4f pointAffine; + pointAffine << point.x, point.y, point.z, 1; + + float myVal = static_cast(2.0f * tf_comp_vect_.transpose () * pointAffine) + static_cast(pointAffine.transpose () * tf_comp_matr_ * pointAffine) + comp_scalar_ - 3.0f; + + // now do the comparison + switch (this->op_) + { + case pcl::ComparisonOps::GT: + return (myVal > 0); + case pcl::ComparisonOps::GE: + return (myVal >= 0); + case pcl::ComparisonOps::LT: + return (myVal < 0); + case pcl::ComparisonOps::LE: + return (myVal <= 0); + case pcl::ComparisonOps::EQ: + return (myVal == 0); + default: + PCL_WARN ("[pcl::transformableQuadricXYZComparison::evaluate] unrecognized op_!\n"); + return (false); + } +} + +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +template int +pcl::PointDataAtOffset::compare (const PointT& p, const double& val) +{ + // if p(data) > val return 1 + // if p(data) == val return 0 + // if p(data) < val return -1 + + const uint8_t* pt_data = reinterpret_cast (&p); + + switch (datatype_) + { + case pcl::PCLPointField::INT8 : + { + int8_t pt_val; + memcpy (&pt_val, pt_data + this->offset_, sizeof (int8_t)); + return (pt_val > static_cast(val)) - (pt_val < static_cast (val)); + } + case pcl::PCLPointField::UINT8 : + { + uint8_t pt_val; + memcpy (&pt_val, pt_data + this->offset_, sizeof (uint8_t)); + return (pt_val > static_cast(val)) - (pt_val < static_cast (val)); + } + case pcl::PCLPointField::INT16 : + { + int16_t pt_val; + memcpy (&pt_val, pt_data + this->offset_, sizeof (int16_t)); + return (pt_val > static_cast(val)) - (pt_val < static_cast (val)); + } + case pcl::PCLPointField::UINT16 : + { + uint16_t pt_val; + memcpy (&pt_val, pt_data + this->offset_, sizeof (uint16_t)); + return (pt_val > static_cast (val)) - (pt_val < static_cast (val)); + } + case pcl::PCLPointField::INT32 : + { + int32_t pt_val; + memcpy (&pt_val, pt_data + this->offset_, sizeof (int32_t)); + return (pt_val > static_cast (val)) - (pt_val < static_cast (val)); + } + case pcl::PCLPointField::UINT32 : + { + uint32_t pt_val; + memcpy (&pt_val, pt_data + this->offset_, sizeof (uint32_t)); + return (pt_val > static_cast (val)) - (pt_val < static_cast (val)); + } + case pcl::PCLPointField::FLOAT32 : + { + float pt_val; + memcpy (&pt_val, pt_data + this->offset_, sizeof (float)); + return (pt_val > static_cast (val)) - (pt_val < static_cast (val)); + } + case pcl::PCLPointField::FLOAT64 : + { + double pt_val; + memcpy (&pt_val, pt_data + this->offset_, sizeof (double)); + return (pt_val > val) - (pt_val < val); + } + default : + PCL_WARN ("[pcl::pcl::PointDataAtOffset::compare] unknown data_type!\n"); + return (0); + } +} + +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConditionBase::addComparison (ComparisonBaseConstPtr comparison) +{ + if (!comparison->isCapable ()) + capable_ = false; + comparisons_.push_back (comparison); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConditionBase::addCondition (Ptr condition) +{ + if (!condition->isCapable ()) + capable_ = false; + conditions_.push_back (condition); +} + +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +template bool +pcl::ConditionAnd::evaluate (const PointT &point) const +{ + for (size_t i = 0; i < comparisons_.size (); ++i) + if (!comparisons_[i]->evaluate (point)) + return (false); + + for (size_t i = 0; i < conditions_.size (); ++i) + if (!conditions_[i]->evaluate (point)) + return (false); + + return (true); +} + +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +template bool +pcl::ConditionOr::evaluate (const PointT &point) const +{ + if (comparisons_.empty () && conditions_.empty ()) + return (true); + for (size_t i = 0; i < comparisons_.size (); ++i) + if (comparisons_[i]->evaluate(point)) + return (true); + + for (size_t i = 0; i < conditions_.size (); ++i) + if (conditions_[i]->evaluate (point)) + return (true); + + return (false); +} + +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConditionalRemoval::setCondition (ConditionBasePtr condition) +{ + condition_ = condition; + capable_ = condition_->isCapable (); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConditionalRemoval::applyFilter (PointCloud &output) +{ + if (capable_ == false) + { + PCL_WARN ("[pcl::%s::applyFilter] not capable!\n", getClassName ().c_str ()); + return; + } + // Has the input dataset been set already? + if (!input_) + { + PCL_WARN ("[pcl::%s::applyFilter] No input dataset given!\n", getClassName ().c_str ()); + return; + } + + if (condition_.get () == NULL) + { + PCL_WARN ("[pcl::%s::applyFilter] No filtering condition given!\n", getClassName ().c_str ()); + return; + } + + // Copy the header (and thus the frame_id) + allocate enough space for points + output.header = input_->header; + if (!keep_organized_) + { + output.height = 1; // filtering breaks the organized structure + output.is_dense = true; + } + else + { + output.height = this->input_->height; + output.width = this->input_->width; + output.is_dense = this->input_->is_dense; + } + output.points.resize (input_->points.size ()); + removed_indices_->resize (input_->points.size ()); + + int nr_p = 0; + int nr_removed_p = 0; + + if (!keep_organized_) + { + for (size_t cp = 0; cp < Filter::indices_->size (); ++cp) + { + // Check if the point is invalid + if (!pcl_isfinite (input_->points[(*Filter < PointT > ::indices_)[cp]].x) + || !pcl_isfinite (input_->points[(*Filter < PointT > ::indices_)[cp]].y) + || !pcl_isfinite (input_->points[(*Filter < PointT > ::indices_)[cp]].z)) + { + if (extract_removed_indices_) + { + (*removed_indices_)[nr_removed_p] = (*Filter::indices_)[cp]; + nr_removed_p++; + } + continue; + } + + if (condition_->evaluate (input_->points[(*Filter < PointT > ::indices_)[cp]])) + { + copyPoint (input_->points[(*Filter < PointT > ::indices_)[cp]], output.points[nr_p]); + nr_p++; + } + else + { + if (extract_removed_indices_) + { + (*removed_indices_)[nr_removed_p] = (*Filter::indices_)[cp]; + nr_removed_p++; + } + } + } + + output.width = nr_p; + output.points.resize (nr_p); + } + else + { + std::vector indices = *Filter::indices_; + std::sort (indices.begin (), indices.end ()); //TODO: is this necessary or can we assume the indices to be sorted? + bool removed_p = false; + size_t ci = 0; + for (size_t cp = 0; cp < input_->points.size (); ++cp) + { + if (cp == static_cast (indices[ci])) + { + if (ci < indices.size () - 1) + { + ci++; + if (cp == static_cast (indices[ci])) //check whether the next index will have the same value. TODO: necessary? + continue; + } + + // copy all the fields + copyPoint (input_->points[cp], output.points[cp]); + + if (!condition_->evaluate (input_->points[cp])) + { + output.points[cp].getVector4fMap ().setConstant (user_filter_value_); + removed_p = true; + + if (extract_removed_indices_) + { + (*removed_indices_)[nr_removed_p] = static_cast (cp); + nr_removed_p++; + } + } + } + else + { + output.points[cp].getVector4fMap ().setConstant (user_filter_value_); + removed_p = true; + //as for !keep_organized_: removed points due to setIndices are not considered as removed_indices_ + } + } + + if (removed_p && !pcl_isfinite (user_filter_value_)) + output.is_dense = false; + } + removed_indices_->resize (nr_removed_p); +} + +#define PCL_INSTANTIATE_PointDataAtOffset(T) template class PCL_EXPORTS pcl::PointDataAtOffset; +#define PCL_INSTANTIATE_ComparisonBase(T) template class PCL_EXPORTS pcl::ComparisonBase; +#define PCL_INSTANTIATE_FieldComparison(T) template class PCL_EXPORTS pcl::FieldComparison; +#define PCL_INSTANTIATE_PackedRGBComparison(T) template class PCL_EXPORTS pcl::PackedRGBComparison; +#define PCL_INSTANTIATE_PackedHSIComparison(T) template class PCL_EXPORTS pcl::PackedHSIComparison; +#define PCL_INSTANTIATE_TfQuadraticXYZComparison(T) template class PCL_EXPORTS pcl::TfQuadraticXYZComparison; +#define PCL_INSTANTIATE_ConditionBase(T) template class PCL_EXPORTS pcl::ConditionBase; +#define PCL_INSTANTIATE_ConditionAnd(T) template class PCL_EXPORTS pcl::ConditionAnd; +#define PCL_INSTANTIATE_ConditionOr(T) template class PCL_EXPORTS pcl::ConditionOr; +#define PCL_INSTANTIATE_ConditionalRemoval(T) template class PCL_EXPORTS pcl::ConditionalRemoval; + +#endif diff --git a/pcl-1.7/pcl/filters/impl/convolution.hpp b/pcl-1.7/pcl/filters/impl/convolution.hpp new file mode 100644 index 0000000..bc13b3a --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/convolution.hpp @@ -0,0 +1,672 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_CONVOLUTION_IMPL_HPP +#define PCL_FILTERS_CONVOLUTION_IMPL_HPP + +#include +#include + +template +pcl::filters::Convolution::Convolution () + : borders_policy_ (BORDERS_POLICY_IGNORE) + , distance_threshold_ (std::numeric_limits::infinity ()) + , input_ () + , kernel_ () + , half_width_ () + , kernel_width_ () + , threads_ (1) +{} + +template void +pcl::filters::Convolution::initCompute (PointCloud& output) +{ + if (borders_policy_ != BORDERS_POLICY_IGNORE && + borders_policy_ != BORDERS_POLICY_MIRROR && + borders_policy_ != BORDERS_POLICY_DUPLICATE) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::filters::Convolution::initCompute] unknown borders policy."); + + if(kernel_.size () % 2 == 0) + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::filters::Convolution::initCompute] convolving element width must be odd."); + + if (distance_threshold_ != std::numeric_limits::infinity ()) + distance_threshold_ *= static_cast (kernel_.size () % 2) * distance_threshold_; + + half_width_ = static_cast (kernel_.size ()) / 2; + kernel_width_ = static_cast (kernel_.size () - 1); + + if (&(*input_) != &output) + { + if (output.height != input_->height || output.width != input_->width) + { + output.resize (input_->width * input_->height); + output.width = input_->width; + output.height = input_->height; + } + } + output.is_dense = input_->is_dense; +} + +template inline void +pcl::filters::Convolution::convolveRows (PointCloudOut& output) +{ + try + { + initCompute (output); + switch (borders_policy_) + { + case BORDERS_POLICY_MIRROR : convolve_rows_mirror (output); + case BORDERS_POLICY_DUPLICATE : convolve_rows_duplicate (output); + case BORDERS_POLICY_IGNORE : convolve_rows (output); + } + } + catch (InitFailedException& e) + { + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::filters::Convolution::convolveRows] init failed " << e.what ()); + } +} + +template inline void +pcl::filters::Convolution::convolveCols (PointCloudOut& output) +{ + try + { + initCompute (output); + switch (borders_policy_) + { + case BORDERS_POLICY_MIRROR : convolve_cols_mirror (output); + case BORDERS_POLICY_DUPLICATE : convolve_cols_duplicate (output); + case BORDERS_POLICY_IGNORE : convolve_cols (output); + } + } + catch (InitFailedException& e) + { + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::filters::Convolution::convolveCols] init failed " << e.what ()); + } +} + +template inline void +pcl::filters::Convolution::convolve (const Eigen::ArrayXf& h_kernel, + const Eigen::ArrayXf& v_kernel, + PointCloud& output) +{ + try + { + PointCloudInPtr tmp (new PointCloud ()); + setKernel (h_kernel); + convolveRows (*tmp); + setInputCloud (tmp); + setKernel (v_kernel); + convolveCols (output); + } + catch (InitFailedException& e) + { + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::filters::Convolution::convolve] init failed " << e.what ()); + } +} + +template inline void +pcl::filters::Convolution::convolve (PointCloud& output) +{ + try + { + PointCloudInPtr tmp (new PointCloud ()); + convolveRows (*tmp); + setInputCloud (tmp); + convolveCols (output); + } + catch (InitFailedException& e) + { + PCL_THROW_EXCEPTION (InitFailedException, + "[pcl::filters::Convolution::convolve] init failed " << e.what ()); + } +} + +template inline PointOut +pcl::filters::Convolution::convolveOneRowDense (int i, int j) +{ + using namespace pcl::common; + PointOut result; + for (int k = kernel_width_, l = i - half_width_; k > -1; --k, ++l) + result+= (*input_) (l,j) * kernel_[k]; + return (result); +} + +template inline PointOut +pcl::filters::Convolution::convolveOneColDense (int i, int j) +{ + using namespace pcl::common; + PointOut result; + for (int k = kernel_width_, l = j - half_width_; k > -1; --k, ++l) + result+= (*input_) (i,l) * kernel_[k]; + return (result); +} + +template inline PointOut +pcl::filters::Convolution::convolveOneRowNonDense (int i, int j) +{ + using namespace pcl::common; + PointOut result; + float weight = 0; + for (int k = kernel_width_, l = i - half_width_; k > -1; --k, ++l) + { + if (!isFinite ((*input_) (l,j))) + continue; + if (pcl::squaredEuclideanDistance ((*input_) (i,j), (*input_) (l,j)) < distance_threshold_) + { + result+= (*input_) (l,j) * kernel_[k]; + weight += kernel_[k]; + } + } + if (weight == 0) + result.x = result.y = result.z = std::numeric_limits::quiet_NaN (); + else + { + weight = 1.f/weight; + result*= weight; + } + return (result); +} + +template inline PointOut +pcl::filters::Convolution::convolveOneColNonDense (int i, int j) +{ + using namespace pcl::common; + PointOut result; + float weight = 0; + for (int k = kernel_width_, l = j - half_width_; k > -1; --k, ++l) + { + if (!isFinite ((*input_) (i,l))) + continue; + if (pcl::squaredEuclideanDistance ((*input_) (i,j), (*input_) (i,l)) < distance_threshold_) + { + result+= (*input_) (i,l) * kernel_[k]; + weight += kernel_[k]; + } + } + if (weight == 0) + result.x = result.y = result.z = std::numeric_limits::quiet_NaN (); + else + { + weight = 1.f/weight; + result*= weight; + } + return (result); +} + +namespace pcl +{ + namespace filters + { + template<> pcl::PointXYZRGB + Convolution::convolveOneRowDense (int i, int j) + { + pcl::PointXYZRGB result; + float r = 0, g = 0, b = 0; + for (int k = kernel_width_, l = i - half_width_; k > -1; --k, ++l) + { + result.x += (*input_) (l,j).x * kernel_[k]; + result.y += (*input_) (l,j).y * kernel_[k]; + result.z += (*input_) (l,j).z * kernel_[k]; + r += kernel_[k] * static_cast ((*input_) (l,j).r); + g += kernel_[k] * static_cast ((*input_) (l,j).g); + b += kernel_[k] * static_cast ((*input_) (l,j).b); + } + result.r = static_cast (r); + result.g = static_cast (g); + result.b = static_cast (b); + return (result); + } + + template<> pcl::PointXYZRGB + Convolution::convolveOneColDense (int i, int j) + { + pcl::PointXYZRGB result; + float r = 0, g = 0, b = 0; + for (int k = kernel_width_, l = j - half_width_; k > -1; --k, ++l) + { + result.x += (*input_) (i,l).x * kernel_[k]; + result.y += (*input_) (i,l).y * kernel_[k]; + result.z += (*input_) (i,l).z * kernel_[k]; + r += kernel_[k] * static_cast ((*input_) (i,l).r); + g += kernel_[k] * static_cast ((*input_) (i,l).g); + b += kernel_[k] * static_cast ((*input_) (i,l).b); + } + result.r = static_cast (r); + result.g = static_cast (g); + result.b = static_cast (b); + return (result); + } + + template<> pcl::PointXYZRGB + Convolution::convolveOneRowNonDense (int i, int j) + { + pcl::PointXYZRGB result; + float weight = 0; + float r = 0, g = 0, b = 0; + for (int k = kernel_width_, l = i - half_width_; k > -1; --k, ++l) + { + if (!isFinite ((*input_) (l,j))) + continue; + if (pcl::squaredEuclideanDistance ((*input_) (i,j), (*input_) (l,j)) < distance_threshold_) + { + result.x += (*input_) (l,j).x * kernel_[k]; result.y += (*input_) (l,j).y * kernel_[k]; result.z += (*input_) (l,j).z * kernel_[k]; + r+= kernel_[k] * static_cast ((*input_) (l,j).r); + g+= kernel_[k] * static_cast ((*input_) (l,j).g); + b+= kernel_[k] * static_cast ((*input_) (l,j).b); + weight += kernel_[k]; + } + } + + if (weight == 0) + result.x = result.y = result.z = std::numeric_limits::quiet_NaN (); + else + { + weight = 1.f/weight; + r*= weight; g*= weight; b*= weight; + result.x*= weight; result.y*= weight; result.z*= weight; + result.r = static_cast (r); + result.g = static_cast (g); + result.b = static_cast (b); + } + return (result); + } + + template<> pcl::PointXYZRGB + Convolution::convolveOneColNonDense (int i, int j) + { + pcl::PointXYZRGB result; + float weight = 0; + float r = 0, g = 0, b = 0; + for (int k = kernel_width_, l = j - half_width_; k > -1; --k, ++l) + { + if (!isFinite ((*input_) (i,l))) + continue; + if (pcl::squaredEuclideanDistance ((*input_) (i,j), (*input_) (i,l)) < distance_threshold_) + { + result.x += (*input_) (i,l).x * kernel_[k]; result.y += (*input_) (i,l).y * kernel_[k]; result.z += (*input_) (i,l).z * kernel_[k]; + r+= kernel_[k] * static_cast ((*input_) (i,l).r); + g+= kernel_[k] * static_cast ((*input_) (i,l).g); + b+= kernel_[k] * static_cast ((*input_) (i,l).b); + weight+= kernel_[k]; + } + } + if (weight == 0) + result.x = result.y = result.z = std::numeric_limits::quiet_NaN (); + else + { + weight = 1.f/weight; + r*= weight; g*= weight; b*= weight; + result.x*= weight; result.y*= weight; result.z*= weight; + result.r = static_cast (r); + result.g = static_cast (g); + result.b = static_cast (b); + } + return (result); + } + + /////////////////////////////////////////////////////////////////////////////////////////////// + template<> pcl::RGB + Convolution::convolveOneRowDense (int i, int j) + { + pcl::RGB result; + float r = 0, g = 0, b = 0; + for (int k = kernel_width_, l = i - half_width_; k > -1; --k, ++l) + { + r += kernel_[k] * static_cast ((*input_) (l,j).r); + g += kernel_[k] * static_cast ((*input_) (l,j).g); + b += kernel_[k] * static_cast ((*input_) (l,j).b); + } + result.r = static_cast (r); + result.g = static_cast (g); + result.b = static_cast (b); + return (result); + } + + template<> pcl::RGB + Convolution::convolveOneColDense (int i, int j) + { + pcl::RGB result; + float r = 0, g = 0, b = 0; + for (int k = kernel_width_, l = j - half_width_; k > -1; --k, ++l) + { + r += kernel_[k] * static_cast ((*input_) (i,l).r); + g += kernel_[k] * static_cast ((*input_) (i,l).g); + b += kernel_[k] * static_cast ((*input_) (i,l).b); + } + result.r = static_cast (r); + result.g = static_cast (g); + result.b = static_cast (b); + return (result); + } + + template<> pcl::RGB + Convolution::convolveOneRowNonDense (int i, int j) + { + return (convolveOneRowDense (i,j)); + } + + template<> pcl::RGB + Convolution::convolveOneColNonDense (int i, int j) + { + return (convolveOneColDense (i,j)); + } + + template<> void + Convolution::makeInfinite (pcl::RGB& p) + { + p.r = 0; p.g = 0; p.b = 0; + } + } +} + +template void +pcl::filters::Convolution::convolve_rows (PointCloudOut& output) +{ + using namespace pcl::common; + + int width = input_->width; + int height = input_->height; + int last = input_->width - half_width_; + if (input_->is_dense) + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads (threads_) +#endif + for(int j = 0; j < height; ++j) + { + for (int i = 0; i < half_width_; ++i) + makeInfinite (output (i,j)); + + for (int i = half_width_; i < last; ++i) + output (i,j) = convolveOneRowDense (i,j); + + for (int i = last; i < width; ++i) + makeInfinite (output (i,j)); + } + } + else + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads (threads_) +#endif + for(int j = 0; j < height; ++j) + { + for (int i = 0; i < half_width_; ++i) + makeInfinite (output (i,j)); + + for (int i = half_width_; i < last; ++i) + output (i,j) = convolveOneRowNonDense (i,j); + + for (int i = last; i < width; ++i) + makeInfinite (output (i,j)); + } + } +} + +template void +pcl::filters::Convolution::convolve_rows_duplicate (PointCloudOut& output) +{ + using namespace pcl::common; + + int width = input_->width; + int height = input_->height; + int last = input_->width - half_width_; + int w = last - 1; + if (input_->is_dense) + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads (threads_) +#endif + for(int j = 0; j < height; ++j) + { + for (int i = half_width_; i < last; ++i) + output (i,j) = convolveOneRowDense (i,j); + + for (int i = last; i < width; ++i) + output (i,j) = output (w, j); + + for (int i = 0; i < half_width_; ++i) + output (i,j) = output (half_width_, j); + } + } + else + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads (threads_) +#endif + for(int j = 0; j < height; ++j) + { + for (int i = half_width_; i < last; ++i) + output (i,j) = convolveOneRowNonDense (i,j); + + for (int i = last; i < width; ++i) + output (i,j) = output (w, j); + + for (int i = 0; i < half_width_; ++i) + output (i,j) = output (half_width_, j); + } + } +} + +template void +pcl::filters::Convolution::convolve_rows_mirror (PointCloudOut& output) +{ + using namespace pcl::common; + + int width = input_->width; + int height = input_->height; + int last = input_->width - half_width_; + int w = last - 1; + if (input_->is_dense) + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads (threads_) +#endif + for(int j = 0; j < height; ++j) + { + for (int i = half_width_; i < last; ++i) + output (i,j) = convolveOneRowDense (i,j); + + for (int i = last, l = 0; i < width; ++i, ++l) + output (i,j) = output (w-l, j); + + for (int i = 0; i < half_width_; ++i) + output (i,j) = output (half_width_+1-i, j); + } + } + else + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads (threads_) +#endif + for(int j = 0; j < height; ++j) + { + for (int i = half_width_; i < last; ++i) + output (i,j) = convolveOneRowNonDense (i,j); + + for (int i = last, l = 0; i < width; ++i, ++l) + output (i,j) = output (w-l, j); + + for (int i = 0; i < half_width_; ++i) + output (i,j) = output (half_width_+1-i, j); + } + } +} + +template void +pcl::filters::Convolution::convolve_cols (PointCloudOut& output) +{ + using namespace pcl::common; + + int width = input_->width; + int height = input_->height; + int last = input_->height - half_width_; + if (input_->is_dense) + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads (threads_) +#endif + for(int i = 0; i < width; ++i) + { + for (int j = 0; j < half_width_; ++j) + makeInfinite (output (i,j)); + + for (int j = half_width_; j < last; ++j) + output (i,j) = convolveOneColDense (i,j); + + for (int j = last; j < height; ++j) + makeInfinite (output (i,j)); + } + } + else + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads (threads_) +#endif + for(int i = 0; i < width; ++i) + { + for (int j = 0; j < half_width_; ++j) + makeInfinite (output (i,j)); + + for (int j = half_width_; j < last; ++j) + output (i,j) = convolveOneColNonDense (i,j); + + for (int j = last; j < height; ++j) + makeInfinite (output (i,j)); + } + } +} + +template void +pcl::filters::Convolution::convolve_cols_duplicate (PointCloudOut& output) +{ + using namespace pcl::common; + + int width = input_->width; + int height = input_->height; + int last = input_->height - half_width_; + int h = last -1; + if (input_->is_dense) + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads (threads_) +#endif + for(int i = 0; i < width; ++i) + { + for (int j = half_width_; j < last; ++j) + output (i,j) = convolveOneColDense (i,j); + + for (int j = last; j < height; ++j) + output (i,j) = output (i,h); + + for (int j = 0; j < half_width_; ++j) + output (i,j) = output (i, half_width_); + } + } + else + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads (threads_) +#endif + for(int i = 0; i < width; ++i) + { + for (int j = half_width_; j < last; ++j) + output (i,j) = convolveOneColNonDense (i,j); + + for (int j = last; j < height; ++j) + output (i,j) = output (i,h); + + for (int j = 0; j < half_width_; ++j) + output (i,j) = output (i,half_width_); + } + } +} + +template void +pcl::filters::Convolution::convolve_cols_mirror (PointCloudOut& output) +{ + using namespace pcl::common; + + int width = input_->width; + int height = input_->height; + int last = input_->height - half_width_; + int h = last -1; + if (input_->is_dense) + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads (threads_) +#endif + for(int i = 0; i < width; ++i) + { + for (int j = half_width_; j < last; ++j) + output (i,j) = convolveOneColDense (i,j); + + for (int j = last, l = 0; j < height; ++j, ++l) + output (i,j) = output (i,h-l); + + for (int j = 0; j < half_width_; ++j) + output (i,j) = output (i, half_width_+1-j); + } + } + else + { +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads (threads_) +#endif + for(int i = 0; i < width; ++i) + { + for (int j = half_width_; j < last; ++j) + output (i,j) = convolveOneColNonDense (i,j); + + for (int j = last, l = 0; j < height; ++j, ++l) + output (i,j) = output (i,h-l); + + for (int j = 0; j < half_width_; ++j) + output (i,j) = output (i,half_width_+1-j); + } + } +} + +#endif //PCL_FILTERS_CONVOLUTION_IMPL_HPP diff --git a/pcl-1.7/pcl/filters/impl/convolution_3d.hpp b/pcl-1.7/pcl/filters/impl/convolution_3d.hpp new file mode 100644 index 0000000..dbc585c --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/convolution_3d.hpp @@ -0,0 +1,260 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_CONVOLUTION_3D_IMPL_HPP +#define PCL_FILTERS_CONVOLUTION_3D_IMPL_HPP + +#include +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////////////// +namespace pcl +{ + namespace filters + { + template + class ConvolvingKernel + { + void + makeInfinite (pcl::Normal& n) + { + n.normal_x = n.normal_y = n.normal_z = std::numeric_limits::quiet_NaN (); + } + }; + + template class + ConvolvingKernel + { + void + makeInfinite (pcl::PointXY& p) + { + p.x = p.y = std::numeric_limits::quiet_NaN (); + } + }; + } +} + +/////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::filters::GaussianKernel::initCompute () +{ + if (sigma_ == 0) + { + PCL_ERROR ("Sigma is not set or equal to 0!\n", sigma_); + return (false); + } + sigma_sqr_ = sigma_ * sigma_; + + if (sigma_coefficient_) + { + if ((*sigma_coefficient_) > 6 || (*sigma_coefficient_) < 3) + { + PCL_ERROR ("Sigma coefficient (%f) out of [3..6]!\n", (*sigma_coefficient_)); + return (false); + } + else + threshold_ = (*sigma_coefficient_) * (*sigma_coefficient_) * sigma_sqr_; + } + + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////////////// +template PointOutT +pcl::filters::GaussianKernel::operator() (const std::vector& indices, + const std::vector& distances) +{ + using namespace pcl::common; + PointOutT result; + float total_weight = 0; + std::vector::const_iterator dist_it = distances.begin (); + + for (std::vector::const_iterator idx_it = indices.begin (); + idx_it != indices.end (); + ++idx_it, ++dist_it) + { + if (*dist_it <= threshold_ && isFinite ((*input_) [*idx_it])) + { + float weight = expf (-0.5f * (*dist_it) / sigma_sqr_); + result += weight * (*input_) [*idx_it]; + total_weight += weight; + } + } + if (total_weight != 0) + result /= total_weight; + else + makeInfinite (result); + + return (result); +} + +/////////////////////////////////////////////////////////////////////////////////////////////////////// +template PointOutT +pcl::filters::GaussianKernelRGB::operator() (const std::vector& indices, const std::vector& distances) +{ + using namespace pcl::common; + PointOutT result; + float total_weight = 0; + float r = 0, g = 0, b = 0; + std::vector::const_iterator dist_it = distances.begin (); + + for (std::vector::const_iterator idx_it = indices.begin (); + idx_it != indices.end (); + ++idx_it, ++dist_it) + { + if (*dist_it <= threshold_ && isFinite ((*input_) [*idx_it])) + { + float weight = expf (-0.5f * (*dist_it) / sigma_sqr_); + result.x += weight * (*input_) [*idx_it].x; + result.y += weight * (*input_) [*idx_it].y; + result.z += weight * (*input_) [*idx_it].z; + r += weight * static_cast ((*input_) [*idx_it].r); + g += weight * static_cast ((*input_) [*idx_it].g); + b += weight * static_cast ((*input_) [*idx_it].b); + total_weight += weight; + } + } + if (total_weight != 0) + { + total_weight = 1.f/total_weight; + r*= total_weight; g*= total_weight; b*= total_weight; + result.x*= total_weight; result.y*= total_weight; result.z*= total_weight; + result.r = static_cast (r); + result.g = static_cast (g); + result.b = static_cast (b); + } + else + makeInfinite (result); + + return (result); +} + +/////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::filters::Convolution3D::Convolution3D () + : PCLBase () + , surface_ () + , tree_ () + , search_radius_ (0) +{} + +/////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::filters::Convolution3D::initCompute () +{ + if (!PCLBase::initCompute ()) + { + PCL_ERROR ("[pcl::filters::Convlution3D::initCompute] init failed!\n"); + return (false); + } + // Initialize the spatial locator + if (!tree_) + { + if (input_->isOrganized ()) + tree_.reset (new pcl::search::OrganizedNeighbor ()); + else + tree_.reset (new pcl::search::KdTree (false)); + } + // If no search surface has been defined, use the input dataset as the search surface itself + if (!surface_) + surface_ = input_; + // Send the surface dataset to the spatial locator + tree_->setInputCloud (surface_); + // Do a fast check to see if the search parameters are well defined + if (search_radius_ <= 0.0) + { + PCL_ERROR ("[pcl::filters::Convlution3D::initCompute] search radius (%f) must be > 0", + search_radius_); + return (false); + } + // Make sure the provided kernel implements the required interface + if (dynamic_cast* > (&kernel_) == 0) + { + PCL_ERROR ("[pcl::filters::Convlution3D::initCompute] init failed"); + PCL_ERROR ("kernel_ must implement ConvolvingKernel interface\n!"); + return (false); + } + kernel_.setInputCloud (surface_); + // Initialize convolving kernel + if (!kernel_.initCompute ()) + { + PCL_ERROR ("[pcl::filters::Convlution3D::initCompute] kernel initialization failed!\n"); + return (false); + } + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::filters::Convolution3D::convolve (PointCloudOut& output) +{ + if (!initCompute ()) + { + PCL_ERROR ("[pcl::filters::Convlution3D::convolve] init failed!\n"); + return; + } + output.resize (surface_->size ()); + output.width = surface_->width; + output.height = surface_->height; + output.is_dense = surface_->is_dense; + std::vector nn_indices; + std::vector nn_distances; + +#ifdef _OPENMP +#pragma omp parallel for shared (output) private (nn_indices, nn_distances) num_threads (threads_) +#endif + for (std::size_t point_idx = 0; point_idx < surface_->size (); ++point_idx) + { + const PointInT& point_in = surface_->points [point_idx]; + PointOutT& point_out = output [point_idx]; + if (isFinite (point_in) && + tree_->radiusSearch (point_in, search_radius_, nn_indices, nn_distances)) + { + point_out = kernel_ (nn_indices, nn_distances); + } + else + { + kernel_.makeInfinite (point_out); + output.is_dense = false; + } + } +} + +#endif diff --git a/pcl-1.7/pcl/filters/impl/covariance_sampling.hpp b/pcl-1.7/pcl/filters/impl/covariance_sampling.hpp new file mode 100644 index 0000000..a5285d6 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/covariance_sampling.hpp @@ -0,0 +1,276 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + + * All rights reserved. + + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_IMPL_COVARIANCE_SAMPLING_H_ +#define PCL_FILTERS_IMPL_COVARIANCE_SAMPLING_H_ + +#include +#include +#include + +/////////////////////////////////////////////////////////////////////////////// +template bool +pcl::CovarianceSampling::initCompute () +{ + if (!FilterIndices::initCompute ()) + return false; + + if (num_samples_ > indices_->size ()) + { + PCL_ERROR ("[pcl::CovarianceSampling::initCompute] The number of samples you asked for (%d) is larger than the number of input indices (%lu)\n", + num_samples_, indices_->size ()); + return false; + } + + // Prepare the point cloud by centering at the origin and then scaling the points such that the average distance from + // the origin is 1.0 => rotations and translations will have the same magnitude + Eigen::Vector3f centroid (0.f, 0.f, 0.f); + for (size_t p_i = 0; p_i < indices_->size (); ++p_i) + centroid += (*input_)[(*indices_)[p_i]].getVector3fMap (); + centroid /= float (indices_->size ()); + + scaled_points_.resize (indices_->size ()); + double average_norm = 0.0; + for (size_t p_i = 0; p_i < indices_->size (); ++p_i) + { + scaled_points_[p_i] = (*input_)[(*indices_)[p_i]].getVector3fMap () - centroid; + average_norm += scaled_points_[p_i].norm (); + } + average_norm /= double (scaled_points_.size ()); + for (size_t p_i = 0; p_i < scaled_points_.size (); ++p_i) + scaled_points_[p_i] /= float (average_norm); + + return (true); +} + +/////////////////////////////////////////////////////////////////////////////// +template double +pcl::CovarianceSampling::computeConditionNumber () +{ + Eigen::Matrix covariance_matrix; + if (!computeCovarianceMatrix (covariance_matrix)) + return (-1.); + + Eigen::EigenSolver > eigen_solver; + eigen_solver.compute (covariance_matrix, true); + + Eigen::MatrixXcd complex_eigenvalues = eigen_solver.eigenvalues (); + + double max_ev = -std::numeric_limits::max (), + min_ev = std::numeric_limits::max (); + for (size_t i = 0; i < 6; ++i) + { + if (real (complex_eigenvalues (i, 0)) > max_ev) + max_ev = real (complex_eigenvalues (i, 0)); + + if (real (complex_eigenvalues (i, 0)) < min_ev) + min_ev = real (complex_eigenvalues (i, 0)); + } + + return (max_ev / min_ev); +} + + +/////////////////////////////////////////////////////////////////////////////// +template double +pcl::CovarianceSampling::computeConditionNumber (const Eigen::Matrix &covariance_matrix) +{ + Eigen::EigenSolver > eigen_solver; + eigen_solver.compute (covariance_matrix, true); + + Eigen::MatrixXcd complex_eigenvalues = eigen_solver.eigenvalues (); + + double max_ev = -std::numeric_limits::max (), + min_ev = std::numeric_limits::max (); + for (size_t i = 0; i < 6; ++i) + { + if (real (complex_eigenvalues (i, 0)) > max_ev) + max_ev = real (complex_eigenvalues (i, 0)); + + if (real (complex_eigenvalues (i, 0)) < min_ev) + min_ev = real (complex_eigenvalues (i, 0)); + } + + return (max_ev / min_ev); +} + + +/////////////////////////////////////////////////////////////////////////////// +template bool +pcl::CovarianceSampling::computeCovarianceMatrix (Eigen::Matrix &covariance_matrix) +{ + if (!initCompute ()) + return false; + + //--- Part A from the paper + // Set up matrix F + Eigen::Matrix f_mat = Eigen::Matrix (6, indices_->size ()); + for (size_t p_i = 0; p_i < scaled_points_.size (); ++p_i) + { + f_mat.block<3, 1> (0, p_i) = scaled_points_[p_i].cross ( + (*input_normals_)[(*indices_)[p_i]].getNormalVector3fMap ()).template cast (); + f_mat.block<3, 1> (3, p_i) = (*input_normals_)[(*indices_)[p_i]].getNormalVector3fMap ().template cast (); + } + + // Compute the covariance matrix C and its 6 eigenvectors (initially complex, move them to a double matrix) + covariance_matrix = f_mat * f_mat.transpose (); + return true; +} + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::CovarianceSampling::applyFilter (std::vector &sampled_indices) +{ + if (!initCompute ()) + return; + + //--- Part A from the paper + // Set up matrix F + Eigen::Matrix f_mat = Eigen::Matrix (6, indices_->size ()); + for (size_t p_i = 0; p_i < scaled_points_.size (); ++p_i) + { + f_mat.block<3, 1> (0, p_i) = scaled_points_[p_i].cross ( + (*input_normals_)[(*indices_)[p_i]].getNormalVector3fMap ()).template cast (); + f_mat.block<3, 1> (3, p_i) = (*input_normals_)[(*indices_)[p_i]].getNormalVector3fMap ().template cast (); + } + + // Compute the covariance matrix C and its 6 eigenvectors (initially complex, move them to a double matrix) + Eigen::Matrix c_mat (f_mat * f_mat.transpose ()); + + Eigen::EigenSolver > eigen_solver; + eigen_solver.compute (c_mat, true); + Eigen::MatrixXcd complex_eigenvectors = eigen_solver.eigenvectors (); + + Eigen::Matrix x; + for (size_t i = 0; i < 6; ++i) + for (size_t j = 0; j < 6; ++j) + x (i, j) = real (complex_eigenvectors (i, j)); + + + //--- Part B from the paper + /// TODO figure out how to fill the candidate_indices - see subsequent paper paragraphs + std::vector candidate_indices; + candidate_indices.resize (indices_->size ()); + for (size_t p_i = 0; p_i < candidate_indices.size (); ++p_i) + candidate_indices[p_i] = p_i; + + // Compute the v 6-vectors + typedef Eigen::Matrix Vector6d; + std::vector > v; + v.resize (candidate_indices.size ()); + for (size_t p_i = 0; p_i < candidate_indices.size (); ++p_i) + { + v[p_i].block<3, 1> (0, 0) = scaled_points_[p_i].cross ( + (*input_normals_)[(*indices_)[candidate_indices[p_i]]].getNormalVector3fMap ()).template cast (); + v[p_i].block<3, 1> (3, 0) = (*input_normals_)[(*indices_)[candidate_indices[p_i]]].getNormalVector3fMap ().template cast (); + } + + + // Set up the lists to be sorted + std::vector > > L; + L.resize (6); + + for (size_t i = 0; i < 6; ++i) + { + for (size_t p_i = 0; p_i < candidate_indices.size (); ++p_i) + L[i].push_back (std::make_pair (p_i, fabs (v[p_i].dot (x.block<6, 1> (0, i))))); + + // Sort in decreasing order + L[i].sort (sort_dot_list_function); + } + + // Initialize the 6 t's + std::vector t (6, 0.0); + + sampled_indices.resize (num_samples_); + std::vector point_sampled (candidate_indices.size (), false); + // Now select the actual points + for (size_t sample_i = 0; sample_i < num_samples_; ++sample_i) + { + // Find the most unconstrained dimension, i.e., the minimum t + size_t min_t_i = 0; + for (size_t i = 0; i < 6; ++i) + { + if (t[min_t_i] > t[i]) + min_t_i = i; + } + + // Add the point from the top of the list corresponding to the dimension to the set of samples + while (point_sampled [L[min_t_i].front ().first]) + L[min_t_i].pop_front (); + + sampled_indices[sample_i] = L[min_t_i].front ().first; + point_sampled[L[min_t_i].front ().first] = true; + L[min_t_i].pop_front (); + + // Update the running totals + for (size_t i = 0; i < 6; ++i) + { + double val = v[sampled_indices[sample_i]].dot (x.block<6, 1> (0, i)); + t[i] += val * val; + } + } + + // Remap the sampled_indices to the input_ cloud + for (size_t i = 0; i < sampled_indices.size (); ++i) + sampled_indices[i] = (*indices_)[candidate_indices[sampled_indices[i]]]; +} + + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::CovarianceSampling::applyFilter (Cloud &output) +{ + std::vector sampled_indices; + applyFilter (sampled_indices); + + output.resize (sampled_indices.size ()); + output.header = input_->header; + output.height = 1; + output.width = uint32_t (output.size ()); + output.is_dense = true; + for (size_t i = 0; i < sampled_indices.size (); ++i) + output[i] = (*input_)[sampled_indices[i]]; +} + + +#define PCL_INSTANTIATE_CovarianceSampling(T,NT) template class PCL_EXPORTS pcl::CovarianceSampling; + +#endif /* PCL_FILTERS_IMPL_COVARIANCE_SAMPLING_H_ */ diff --git a/pcl-1.7/pcl/filters/impl/crop_box.hpp b/pcl-1.7/pcl/filters/impl/crop_box.hpp new file mode 100644 index 0000000..6f55f9e --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/crop_box.hpp @@ -0,0 +1,141 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: extract_indices.hpp 1897 2011-07-26 20:35:49Z rusu $ + * + */ + +#ifndef PCL_FILTERS_IMPL_CROP_BOX_H_ +#define PCL_FILTERS_IMPL_CROP_BOX_H_ + +#include +#include + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::CropBox::applyFilter (PointCloud &output) +{ + std::vector indices; + if (keep_organized_) + { + bool temp = extract_removed_indices_; + extract_removed_indices_ = true; + applyFilter (indices); + extract_removed_indices_ = temp; + + output = *input_; + for (int rii = 0; rii < static_cast (removed_indices_->size ()); ++rii) // rii = removed indices iterator + output.points[(*removed_indices_)[rii]].x = output.points[(*removed_indices_)[rii]].y = output.points[(*removed_indices_)[rii]].z = user_filter_value_; + if (!pcl_isfinite (user_filter_value_)) + output.is_dense = false; + } + else + { + output.is_dense = true; + applyFilter (indices); + pcl::copyPointCloud (*input_, indices, output); + } +} + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::CropBox::applyFilter (std::vector &indices) +{ + indices.resize (input_->points.size ()); + removed_indices_->resize (input_->points.size ()); + int indices_count = 0; + int removed_indices_count = 0; + + Eigen::Affine3f transform = Eigen::Affine3f::Identity (); + Eigen::Affine3f inverse_transform = Eigen::Affine3f::Identity (); + + if (rotation_ != Eigen::Vector3f::Zero ()) + { + pcl::getTransformation (0, 0, 0, + rotation_ (0), rotation_ (1), rotation_ (2), + transform); + inverse_transform = transform.inverse (); + } + + for (size_t index = 0; index < indices_->size (); ++index) + { + if (!input_->is_dense) + // Check if the point is invalid + if (!isFinite (input_->points[index])) + continue; + + // Get local point + PointT local_pt = input_->points[(*indices_)[index]]; + + // Transform point to world space + if (!(transform_.matrix ().isIdentity ())) + local_pt = pcl::transformPoint (local_pt, transform_); + + if (translation_ != Eigen::Vector3f::Zero ()) + { + local_pt.x -= translation_ (0); + local_pt.y -= translation_ (1); + local_pt.z -= translation_ (2); + } + + // Transform point to local space of crop box + if (!(inverse_transform.matrix ().isIdentity ())) + local_pt = pcl::transformPoint (local_pt, inverse_transform); + + // If outside the cropbox + if ( (local_pt.x < min_pt_[0] || local_pt.y < min_pt_[1] || local_pt.z < min_pt_[2]) || + (local_pt.x > max_pt_[0] || local_pt.y > max_pt_[1] || local_pt.z > max_pt_[2])) + { + if (negative_) + indices[indices_count++] = (*indices_)[index]; + else if (extract_removed_indices_) + (*removed_indices_)[removed_indices_count++] = static_cast (index); + } + // If inside the cropbox + else + { + if (negative_ && extract_removed_indices_) + (*removed_indices_)[removed_indices_count++] = static_cast (index); + else if (!negative_) + indices[indices_count++] = (*indices_)[index]; + } + } + indices.resize (indices_count); + removed_indices_->resize (removed_indices_count); +} + +#define PCL_INSTANTIATE_CropBox(T) template class PCL_EXPORTS pcl::CropBox; + +#endif // PCL_FILTERS_IMPL_CROP_BOX_H_ diff --git a/pcl-1.7/pcl/filters/impl/crop_hull.hpp b/pcl-1.7/pcl/filters/impl/crop_hull.hpp new file mode 100644 index 0000000..1b7e2a9 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/crop_hull.hpp @@ -0,0 +1,329 @@ + /* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FILTERS_IMPL_CROP_HULL_H_ +#define PCL_FILTERS_IMPL_CROP_HULL_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::CropHull::applyFilter (PointCloud &output) +{ + if (dim_ == 2) + { + // in this case we are assuming all the points lie in the same plane as the + // 2D convex hull, so the choice of projection just changes the + // conditioning of the problem: choose to squash the XYZ component of the + // hull-points that has least variation - this will also give reasonable + // results if the points don't lie exactly in the same plane + const Eigen::Vector3f range = getHullCloudRange (); + if (range[0] <= range[1] && range[0] <= range[2]) + applyFilter2D<1,2> (output); + else if (range[1] <= range[2] && range[1] <= range[0]) + applyFilter2D<2,0> (output); + else + applyFilter2D<0,1> (output); + } + else + { + applyFilter3D (output); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::CropHull::applyFilter (std::vector &indices) +{ + if (dim_ == 2) + { + // in this case we are assuming all the points lie in the same plane as the + // 2D convex hull, so the choice of projection just changes the + // conditioning of the problem: choose to squash the XYZ component of the + // hull-points that has least variation - this will also give reasonable + // results if the points don't lie exactly in the same plane + const Eigen::Vector3f range = getHullCloudRange (); + if (range[0] <= range[1] && range[0] <= range[2]) + applyFilter2D<1,2> (indices); + else if (range[1] <= range[2] && range[1] <= range[0]) + applyFilter2D<2,0> (indices); + else + applyFilter2D<0,1> (indices); + } + else + { + applyFilter3D (indices); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template Eigen::Vector3f +pcl::CropHull::getHullCloudRange () +{ + Eigen::Vector3f cloud_min ( + std::numeric_limits ().max (), + std::numeric_limits ().max (), + std::numeric_limits ().max () + ); + Eigen::Vector3f cloud_max ( + -std::numeric_limits ().max (), + -std::numeric_limits ().max (), + -std::numeric_limits ().max () + ); + for (size_t index = 0; index < indices_->size (); index++) + { + Eigen::Vector3f pt = input_->points[(*indices_)[index]].getVector3fMap (); + for (int i = 0; i < 3; i++) + { + if (pt[i] < cloud_min[i]) cloud_min[i] = pt[i]; + if (pt[i] > cloud_max[i]) cloud_max[i] = pt[i]; + } + } + + return (cloud_max - cloud_min); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template template void +pcl::CropHull::applyFilter2D (PointCloud &output) +{ + for (size_t index = 0; index < indices_->size (); index++) + { + // iterate over polygons faster than points because we expect this data + // to be, in general, more cache-local - the point cloud might be huge + size_t poly; + for (poly = 0; poly < hull_polygons_.size (); poly++) + { + if (isPointIn2DPolyWithVertIndices ( + input_->points[(*indices_)[index]], hull_polygons_[poly], *hull_cloud_ + )) + { + if (crop_outside_) + output.push_back (input_->points[(*indices_)[index]]); + // once a point has tested +ve for being inside one polygon, we can + // stop checking the others: + break; + } + } + // If we're removing points *inside* the hull, only remove points that + // haven't been found inside any polygons + if (poly == hull_polygons_.size () && !crop_outside_) + output.push_back (input_->points[(*indices_)[index]]); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template template void +pcl::CropHull::applyFilter2D (std::vector &indices) +{ + // see comments in (PointCloud& output) overload + for (size_t index = 0; index < indices_->size (); index++) + { + size_t poly; + for (poly = 0; poly < hull_polygons_.size (); poly++) + { + if (isPointIn2DPolyWithVertIndices ( + input_->points[(*indices_)[index]], hull_polygons_[poly], *hull_cloud_ + )) + { + if (crop_outside_) + indices.push_back ((*indices_)[index]); + break; + } + } + if (poly == hull_polygons_.size () && !crop_outside_) + indices.push_back ((*indices_)[index]); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::CropHull::applyFilter3D (PointCloud &output) +{ + // This algorithm could definitely be sped up using kdtree/octree + // information, if that is available! + + for (size_t index = 0; index < indices_->size (); index++) + { + // test ray-crossings for three random rays, and take vote of crossings + // counts to determine if each point is inside the hull: the vote avoids + // tricky edge and corner cases when rays might fluke through the edge + // between two polygons + // 'random' rays are arbitrary - basically anything that is less likely to + // hit the edge between polygons than coordinate-axis aligned rays would + // be. + size_t crossings[3] = {0,0,0}; + Eigen::Vector3f rays[3] = + { + Eigen::Vector3f (0.264882f, 0.688399f, 0.675237f), + Eigen::Vector3f (0.0145419f, 0.732901f, 0.68018f), + Eigen::Vector3f (0.856514f, 0.508771f, 0.0868081f) + }; + + for (size_t poly = 0; poly < hull_polygons_.size (); poly++) + for (size_t ray = 0; ray < 3; ray++) + crossings[ray] += rayTriangleIntersect + (input_->points[(*indices_)[index]], rays[ray], hull_polygons_[poly], *hull_cloud_); + + if (crop_outside_ && (crossings[0]&1) + (crossings[1]&1) + (crossings[2]&1) > 1) + output.push_back (input_->points[(*indices_)[index]]); + else if (!crop_outside_) + output.push_back (input_->points[(*indices_)[index]]); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::CropHull::applyFilter3D (std::vector &indices) +{ + // see comments in applyFilter3D (PointCloud& output) + for (size_t index = 0; index < indices_->size (); index++) + { + size_t crossings[3] = {0,0,0}; + Eigen::Vector3f rays[3] = + { + Eigen::Vector3f(0.264882f, 0.688399f, 0.675237f), + Eigen::Vector3f(0.0145419f, 0.732901f, 0.68018f), + Eigen::Vector3f(0.856514f, 0.508771f, 0.0868081f) + }; + + for (size_t poly = 0; poly < hull_polygons_.size (); poly++) + for (size_t ray = 0; ray < 3; ray++) + crossings[ray] += rayTriangleIntersect + (input_->points[(*indices_)[index]], rays[ray], hull_polygons_[poly], *hull_cloud_); + + if (crop_outside_ && (crossings[0]&1) + (crossings[1]&1) + (crossings[2]&1) > 1) + indices.push_back ((*indices_)[index]); + else if (!crop_outside_) + indices.push_back ((*indices_)[index]); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template template bool +pcl::CropHull::isPointIn2DPolyWithVertIndices ( + const PointT& point, const Vertices& verts, const PointCloud& cloud) +{ + bool in_poly = false; + double x1, x2, y1, y2; + + const int nr_poly_points = static_cast(verts.vertices.size ()); + double xold = cloud[verts.vertices[nr_poly_points - 1]].getVector3fMap ()[PlaneDim1]; + double yold = cloud[verts.vertices[nr_poly_points - 1]].getVector3fMap ()[PlaneDim2]; + for (int i = 0; i < nr_poly_points; i++) + { + const double xnew = cloud[verts.vertices[i]].getVector3fMap ()[PlaneDim1]; + const double ynew = cloud[verts.vertices[i]].getVector3fMap ()[PlaneDim2]; + if (xnew > xold) + { + x1 = xold; + x2 = xnew; + y1 = yold; + y2 = ynew; + } + else + { + x1 = xnew; + x2 = xold; + y1 = ynew; + y2 = yold; + } + + if ((xnew < point.getVector3fMap ()[PlaneDim1]) == (point.getVector3fMap ()[PlaneDim1] <= xold) && + (point.getVector3fMap ()[PlaneDim2] - y1) * (x2 - x1) < (y2 - y1) * (point.getVector3fMap ()[PlaneDim1] - x1)) + { + in_poly = !in_poly; + } + xold = xnew; + yold = ynew; + } + + return (in_poly); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::CropHull::rayTriangleIntersect (const PointT& point, + const Eigen::Vector3f& ray, + const Vertices& verts, + const PointCloud& cloud) +{ + // Algorithm here is adapted from: + // http://softsurfer.com/Archive/algorithm_0105/algorithm_0105.htm#intersect_RayTriangle() + // + // Original copyright notice: + // Copyright 2001, softSurfer (www.softsurfer.com) + // This code may be freely used and modified for any purpose + // providing that this copyright notice is included with it. + // + assert (verts.vertices.size () == 3); + + const Eigen::Vector3f p = point.getVector3fMap (); + const Eigen::Vector3f a = cloud[verts.vertices[0]].getVector3fMap (); + const Eigen::Vector3f b = cloud[verts.vertices[1]].getVector3fMap (); + const Eigen::Vector3f c = cloud[verts.vertices[2]].getVector3fMap (); + const Eigen::Vector3f u = b - a; + const Eigen::Vector3f v = c - a; + const Eigen::Vector3f n = u.cross (v); + const float n_dot_ray = n.dot (ray); + + if (std::fabs (n_dot_ray) < 1e-9) + return (false); + + const float r = n.dot (a - p) / n_dot_ray; + + if (r < 0) + return (false); + + const Eigen::Vector3f w = p + r * ray - a; + const float denominator = u.dot (v) * u.dot (v) - u.dot (u) * v.dot (v); + const float s_numerator = u.dot (v) * w.dot (v) - v.dot (v) * w.dot (u); + const float s = s_numerator / denominator; + if (s < 0 || s > 1) + return (false); + + const float t_numerator = u.dot (v) * w.dot (u) - u.dot (u) * w.dot (v); + const float t = t_numerator / denominator; + if (t < 0 || s+t > 1) + return (false); + + return (true); +} + +#define PCL_INSTANTIATE_CropHull(T) template class PCL_EXPORTS pcl::CropHull; + +#endif // PCL_FILTERS_IMPL_CROP_HULL_H_ diff --git a/pcl-1.7/pcl/filters/impl/extract_indices.hpp b/pcl-1.7/pcl/filters/impl/extract_indices.hpp new file mode 100644 index 0000000..234a92a --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/extract_indices.hpp @@ -0,0 +1,155 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_IMPL_EXTRACT_INDICES_HPP_ +#define PCL_FILTERS_IMPL_EXTRACT_INDICES_HPP_ + +#include +#include + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ExtractIndices::filterDirectly (PointCloudPtr &cloud) +{ + std::vector indices; + bool temp = extract_removed_indices_; + extract_removed_indices_ = true; + this->setInputCloud (cloud); + applyFilterIndices (indices); + extract_removed_indices_ = temp; + + std::vector fields; + pcl::for_each_type (pcl::detail::FieldAdder (fields)); + for (int rii = 0; rii < static_cast (removed_indices_->size ()); ++rii) // rii = removed indices iterator + { + uint8_t* pt_data = reinterpret_cast (&cloud->points[(*removed_indices_)[rii]]); + for (int fi = 0; fi < static_cast (fields.size ()); ++fi) // fi = field iterator + memcpy (pt_data + fields[fi].offset, &user_filter_value_, sizeof (float)); + } + if (!pcl_isfinite (user_filter_value_)) + cloud->is_dense = false; +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ExtractIndices::applyFilter (PointCloud &output) +{ + std::vector indices; + if (keep_organized_) + { + bool temp = extract_removed_indices_; + extract_removed_indices_ = true; + applyFilterIndices (indices); + extract_removed_indices_ = temp; + + output = *input_; + std::vector fields; + pcl::for_each_type (pcl::detail::FieldAdder (fields)); + for (int rii = 0; rii < static_cast (removed_indices_->size ()); ++rii) // rii = removed indices iterator + { + uint8_t* pt_data = reinterpret_cast (&output.points[(*removed_indices_)[rii]]); + for (int fi = 0; fi < static_cast (fields.size ()); ++fi) // fi = field iterator + memcpy (pt_data + fields[fi].offset, &user_filter_value_, sizeof (float)); + } + if (!pcl_isfinite (user_filter_value_)) + output.is_dense = false; + } + else + { + applyFilterIndices (indices); + copyPointCloud (*input_, indices, output); + } +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ExtractIndices::applyFilterIndices (std::vector &indices) +{ + if (indices_->size () > input_->points.size ()) + { + PCL_ERROR ("[pcl::%s::applyFilter] The indices size exceeds the size of the input.\n", getClassName ().c_str ()); + indices.clear (); + removed_indices_->clear (); + return; + } + + if (!negative_) // Normal functionality + { + indices = *indices_; + + if (extract_removed_indices_) + { + // Set up the full indices set + std::vector full_indices (input_->points.size ()); + for (int fii = 0; fii < static_cast (full_indices.size ()); ++fii) // fii = full indices iterator + full_indices[fii] = fii; + + // Set up the sorted input indices + std::vector sorted_input_indices = *indices_; + std::sort (sorted_input_indices.begin (), sorted_input_indices.end ()); + + // Store the difference in removed_indices + removed_indices_->clear (); + set_difference (full_indices.begin (), full_indices.end (), sorted_input_indices.begin (), sorted_input_indices.end (), inserter (*removed_indices_, removed_indices_->begin ())); + } + } + else // Inverted functionality + { + // Set up the full indices set + std::vector full_indices (input_->points.size ()); + for (int fii = 0; fii < static_cast (full_indices.size ()); ++fii) // fii = full indices iterator + full_indices[fii] = fii; + + // Set up the sorted input indices + std::vector sorted_input_indices = *indices_; + std::sort (sorted_input_indices.begin (), sorted_input_indices.end ()); + + // Store the difference in indices + indices.clear (); + set_difference (full_indices.begin (), full_indices.end (), sorted_input_indices.begin (), sorted_input_indices.end (), inserter (indices, indices.begin ())); + + if (extract_removed_indices_) + removed_indices_ = indices_; + } +} + +#define PCL_INSTANTIATE_ExtractIndices(T) template class PCL_EXPORTS pcl::ExtractIndices; + +#endif // PCL_FILTERS_IMPL_EXTRACT_INDICES_HPP_ + diff --git a/pcl-1.7/pcl/filters/impl/fast_bilateral.hpp b/pcl-1.7/pcl/filters/impl/fast_bilateral.hpp new file mode 100644 index 0000000..c5dbc5c --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/fast_bilateral.hpp @@ -0,0 +1,218 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2004, Sylvain Paris and Francois Sillion + + * All rights reserved. + + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_FILTERS_IMPL_FAST_BILATERAL_HPP_ +#define PCL_FILTERS_IMPL_FAST_BILATERAL_HPP_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::FastBilateralFilter::applyFilter (PointCloud &output) +{ + if (!input_->isOrganized ()) + { + PCL_ERROR ("[pcl::FastBilateralFilter] Input cloud needs to be organized.\n"); + return; + } + + copyPointCloud (*input_, output); + float base_max = -std::numeric_limits::max (), + base_min = std::numeric_limits::max (); + bool found_finite = false; + for (size_t x = 0; x < output.width; ++x) + { + for (size_t y = 0; y < output.height; ++y) + { + if (pcl_isfinite (output (x, y).z)) + { + if (base_max < output (x, y).z) + base_max = output (x, y).z; + if (base_min > output (x, y).z) + base_min = output (x, y).z; + found_finite = true; + } + } + } + if (!found_finite) + { + PCL_WARN ("[pcl::FastBilateralFilter] Given an empty cloud. Doing nothing.\n"); + return; + } + + for (size_t x = 0; x < output.width; ++x) + for (size_t y = 0; y < output.height; ++y) + if (!pcl_isfinite (output (x, y).z)) + output (x, y).z = base_max; + + const float base_delta = base_max - base_min; + + const size_t padding_xy = 2; + const size_t padding_z = 2; + + const size_t small_width = static_cast (static_cast (input_->width - 1) / sigma_s_) + 1 + 2 * padding_xy; + const size_t small_height = static_cast (static_cast (input_->height - 1) / sigma_s_) + 1 + 2 * padding_xy; + const size_t small_depth = static_cast (base_delta / sigma_r_) + 1 + 2 * padding_z; + + + Array3D data (small_width, small_height, small_depth); + for (size_t x = 0; x < input_->width; ++x) + { + const size_t small_x = static_cast (static_cast (x) / sigma_s_ + 0.5f) + padding_xy; + for (size_t y = 0; y < input_->height; ++y) + { + const float z = output (x,y).z - base_min; + + const size_t small_y = static_cast (static_cast (y) / sigma_s_ + 0.5f) + padding_xy; + const size_t small_z = static_cast (static_cast (z) / sigma_r_ + 0.5f) + padding_z; + + Eigen::Vector2f& d = data (small_x, small_y, small_z); + d[0] += output (x,y).z; + d[1] += 1.0f; + } + } + + + std::vector offset (3); + offset[0] = &(data (1,0,0)) - &(data (0,0,0)); + offset[1] = &(data (0,1,0)) - &(data (0,0,0)); + offset[2] = &(data (0,0,1)) - &(data (0,0,0)); + + Array3D buffer (small_width, small_height, small_depth); + + for (size_t dim = 0; dim < 3; ++dim) + { + const long int off = offset[dim]; + for (size_t n_iter = 0; n_iter < 2; ++n_iter) + { + std::swap (buffer, data); + for(size_t x = 1; x < small_width - 1; ++x) + for(size_t y = 1; y < small_height - 1; ++y) + { + Eigen::Vector2f* d_ptr = &(data (x,y,1)); + Eigen::Vector2f* b_ptr = &(buffer (x,y,1)); + + for(size_t z = 1; z < small_depth - 1; ++z, ++d_ptr, ++b_ptr) + *d_ptr = (*(b_ptr - off) + *(b_ptr + off) + 2.0 * (*b_ptr)) / 4.0; + } + } + } + + if (early_division_) + { + for (std::vector::iterator d = data.begin (); d != data.end (); ++d) + *d /= ((*d)[0] != 0) ? (*d)[1] : 1; + + for (size_t x = 0; x < input_->width; x++) + for (size_t y = 0; y < input_->height; y++) + { + const float z = output (x,y).z - base_min; + const Eigen::Vector2f D = data.trilinear_interpolation (static_cast (x) / sigma_s_ + padding_xy, + static_cast (y) / sigma_s_ + padding_xy, + z / sigma_r_ + padding_z); + output(x,y).z = D[0]; + } + } + else + { + for (size_t x = 0; x < input_->width; ++x) + for (size_t y = 0; y < input_->height; ++y) + { + const float z = output (x,y).z - base_min; + const Eigen::Vector2f D = data.trilinear_interpolation (static_cast (x) / sigma_s_ + padding_xy, + static_cast (y) / sigma_s_ + padding_xy, + z / sigma_r_ + padding_z); + output (x,y).z = D[0] / D[1]; + } + } +} + + + +////////////////////////////////////////////////////////////////////////////////////////////// +template size_t +pcl::FastBilateralFilter::Array3D::clamp (const size_t min_value, + const size_t max_value, + const size_t x) +{ + if (x >= min_value && x <= max_value) + { + return x; + } + else if (x < min_value) + { + return (min_value); + } + else + { + return (max_value); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template Eigen::Vector2f +pcl::FastBilateralFilter::Array3D::trilinear_interpolation (const float x, + const float y, + const float z) +{ + const size_t x_index = clamp (0, x_dim_ - 1, static_cast (x)); + const size_t xx_index = clamp (0, x_dim_ - 1, x_index + 1); + + const size_t y_index = clamp (0, y_dim_ - 1, static_cast (y)); + const size_t yy_index = clamp (0, y_dim_ - 1, y_index + 1); + + const size_t z_index = clamp (0, z_dim_ - 1, static_cast (z)); + const size_t zz_index = clamp (0, z_dim_ - 1, z_index + 1); + + const float x_alpha = x - static_cast (x_index); + const float y_alpha = y - static_cast (y_index); + const float z_alpha = z - static_cast (z_index); + + return + (1.0f-x_alpha) * (1.0f-y_alpha) * (1.0f-z_alpha) * (*this)(x_index, y_index, z_index) + + x_alpha * (1.0f-y_alpha) * (1.0f-z_alpha) * (*this)(xx_index, y_index, z_index) + + (1.0f-x_alpha) * y_alpha * (1.0f-z_alpha) * (*this)(x_index, yy_index, z_index) + + x_alpha * y_alpha * (1.0f-z_alpha) * (*this)(xx_index, yy_index, z_index) + + (1.0f-x_alpha) * (1.0f-y_alpha) * z_alpha * (*this)(x_index, y_index, zz_index) + + x_alpha * (1.0f-y_alpha) * z_alpha * (*this)(xx_index, y_index, zz_index) + + (1.0f-x_alpha) * y_alpha * z_alpha * (*this)(x_index, yy_index, zz_index) + + x_alpha * y_alpha * z_alpha * (*this)(xx_index, yy_index, zz_index); +} + +#endif /* PCL_FILTERS_IMPL_FAST_BILATERAL_HPP_ */ diff --git a/pcl-1.7/pcl/filters/impl/fast_bilateral_omp.hpp b/pcl-1.7/pcl/filters/impl/fast_bilateral_omp.hpp new file mode 100644 index 0000000..aae2c51 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/fast_bilateral_omp.hpp @@ -0,0 +1,199 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2004, Sylvain Paris and Francois Sillion + + * All rights reserved. + + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: fast_bilateral_omp.hpp 8381 2013-01-02 23:12:44Z sdmiller $ + * + */ +#ifndef PCL_FILTERS_IMPL_FAST_BILATERAL_OMP_HPP_ +#define PCL_FILTERS_IMPL_FAST_BILATERAL_OMP_HPP_ + +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::FastBilateralFilterOMP::applyFilter (PointCloud &output) +{ + if (!input_->isOrganized ()) + { + PCL_ERROR ("[pcl::FastBilateralFilterOMP] Input cloud needs to be organized.\n"); + return; + } + + copyPointCloud (*input_, output); + float base_max = -std::numeric_limits::max (), + base_min = std::numeric_limits::max (); + bool found_finite = false; + for (size_t x = 0; x < output.width; ++x) + { + for (size_t y = 0; y < output.height; ++y) + { + if (pcl_isfinite (output (x, y).z)) + { + if (base_max < output (x, y).z) + base_max = output (x, y).z; + if (base_min > output (x, y).z) + base_min = output (x, y).z; + found_finite = true; + } + } + } + if (!found_finite) + { + PCL_WARN ("[pcl::FastBilateralFilterOMP] Given an empty cloud. Doing nothing.\n"); + return; + } +#ifdef _OPENMP +#pragma omp parallel for num_threads (threads_) +#endif + for (long int i = 0; i < static_cast (output.size ()); ++i) + if (!pcl_isfinite (output.at(i).z)) + output.at(i).z = base_max; + + const float base_delta = base_max - base_min; + + const size_t padding_xy = 2; + const size_t padding_z = 2; + + const size_t small_width = static_cast (static_cast (input_->width - 1) / sigma_s_) + 1 + 2 * padding_xy; + const size_t small_height = static_cast (static_cast (input_->height - 1) / sigma_s_) + 1 + 2 * padding_xy; + const size_t small_depth = static_cast (base_delta / sigma_r_) + 1 + 2 * padding_z; + + Array3D data (small_width, small_height, small_depth); +#ifdef _OPENMP +#pragma omp parallel for num_threads (threads_) +#endif + for (long int i = 0; i < static_cast (small_width * small_height); ++i) + { + size_t small_x = static_cast (i % small_width); + size_t small_y = static_cast (i / small_width); + size_t start_x = static_cast( + std::max ((static_cast (small_x) - static_cast (padding_xy) - 0.5f) * sigma_s_ + 1, 0.f)); + size_t end_x = static_cast( + std::max ((static_cast (small_x) - static_cast (padding_xy) + 0.5f) * sigma_s_ + 1, 0.f)); + size_t start_y = static_cast( + std::max ((static_cast (small_y) - static_cast (padding_xy) - 0.5f) * sigma_s_ + 1, 0.f)); + size_t end_y = static_cast( + std::max ((static_cast (small_y) - static_cast (padding_xy) + 0.5f) * sigma_s_ + 1, 0.f)); + for (size_t x = start_x; x < end_x && x < input_->width; ++x) + { + for (size_t y = start_y; y < end_y && y < input_->height; ++y) + { + const float z = output (x,y).z - base_min; + const size_t small_z = static_cast (static_cast (z) / sigma_r_ + 0.5f) + padding_z; + Eigen::Vector2f& d = data (small_x, small_y, small_z); + d[0] += output (x,y).z; + d[1] += 1.0f; + } + } + } + + std::vector offset (3); + offset[0] = &(data (1,0,0)) - &(data (0,0,0)); + offset[1] = &(data (0,1,0)) - &(data (0,0,0)); + offset[2] = &(data (0,0,1)) - &(data (0,0,0)); + + Array3D buffer (small_width, small_height, small_depth); + + for (size_t dim = 0; dim < 3; ++dim) + { + for (size_t n_iter = 0; n_iter < 2; ++n_iter) + { + Array3D* current_buffer = (n_iter % 2 == 1 ? &buffer : &data); + Array3D* current_data =(n_iter % 2 == 1 ? &data : &buffer); +#ifdef _OPENMP +#pragma omp parallel for num_threads (threads_) +#endif + for(long int i = 0; i < static_cast ((small_width - 2)*(small_height - 2)); ++i) + { + size_t x = static_cast (i % (small_width - 2) + 1); + size_t y = static_cast (i / (small_width - 2) + 1); + const long int off = offset[dim]; + Eigen::Vector2f* d_ptr = &(current_data->operator() (x,y,1)); + Eigen::Vector2f* b_ptr = &(current_buffer->operator() (x,y,1)); + + for(size_t z = 1; z < small_depth - 1; ++z, ++d_ptr, ++b_ptr) + *d_ptr = (*(b_ptr - off) + *(b_ptr + off) + 2.0 * (*b_ptr)) / 4.0; + } + } + } + // Note: this works because there are an even number of iterations. + // If there were an odd number, we would need to end with a: + // std::swap (data, buffer); + + if (early_division_) + { + for (std::vector::iterator d = data.begin (); d != data.end (); ++d) + *d /= ((*d)[0] != 0) ? (*d)[1] : 1; + +#ifdef _OPENMP +#pragma omp parallel for num_threads (threads_) +#endif + for (long int i = 0; i < static_cast (input_->size ()); ++i) + { + size_t x = static_cast (i % input_->width); + size_t y = static_cast (i / input_->width); + const float z = output (x,y).z - base_min; + const Eigen::Vector2f D = data.trilinear_interpolation (static_cast (x) / sigma_s_ + padding_xy, + static_cast (y) / sigma_s_ + padding_xy, + z / sigma_r_ + padding_z); + output(x,y).z = D[0]; + } + } + else + { +#ifdef _OPENMP +#pragma omp parallel for num_threads (threads_) +#endif + for (long i = 0; i < static_cast (input_->size ()); ++i) + { + size_t x = static_cast (i % input_->width); + size_t y = static_cast (i / input_->width); + const float z = output (x,y).z - base_min; + const Eigen::Vector2f D = data.trilinear_interpolation (static_cast (x) / sigma_s_ + padding_xy, + static_cast (y) / sigma_s_ + padding_xy, + z / sigma_r_ + padding_z); + output (x,y).z = D[0] / D[1]; + } + } +} + + + +#endif /* PCL_FILTERS_IMPL_FAST_BILATERAL_OMP_HPP_ */ + diff --git a/pcl-1.7/pcl/filters/impl/filter.hpp b/pcl-1.7/pcl/filters/impl/filter.hpp new file mode 100644 index 0000000..90c6526 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/filter.hpp @@ -0,0 +1,137 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_IMPL_FILTER_H_ +#define PCL_FILTERS_IMPL_FILTER_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////// +template void +pcl::removeNaNFromPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + std::vector &index) +{ + // If the clouds are not the same, prepare the output + if (&cloud_in != &cloud_out) + { + cloud_out.header = cloud_in.header; + cloud_out.points.resize (cloud_in.points.size ()); + } + // Reserve enough space for the indices + index.resize (cloud_in.points.size ()); + size_t j = 0; + + // If the data is dense, we don't need to check for NaN + if (cloud_in.is_dense) + { + // Simply copy the data + cloud_out = cloud_in; + for (j = 0; j < cloud_out.points.size (); ++j) + index[j] = static_cast(j); + } + else + { + for (size_t i = 0; i < cloud_in.points.size (); ++i) + { + if (!pcl_isfinite (cloud_in.points[i].x) || + !pcl_isfinite (cloud_in.points[i].y) || + !pcl_isfinite (cloud_in.points[i].z)) + continue; + cloud_out.points[j] = cloud_in.points[i]; + index[j] = static_cast(i); + j++; + } + if (j != cloud_in.points.size ()) + { + // Resize to the correct size + cloud_out.points.resize (j); + index.resize (j); + } + + cloud_out.height = 1; + cloud_out.width = static_cast(j); + + // Removing bad points => dense (note: 'dense' doesn't mean 'organized') + cloud_out.is_dense = true; + } +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::removeNaNNormalsFromPointCloud (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out, + std::vector &index) +{ + // If the clouds are not the same, prepare the output + if (&cloud_in != &cloud_out) + { + cloud_out.header = cloud_in.header; + cloud_out.points.resize (cloud_in.points.size ()); + } + // Reserve enough space for the indices + index.resize (cloud_in.points.size ()); + size_t j = 0; + + for (size_t i = 0; i < cloud_in.points.size (); ++i) + { + if (!pcl_isfinite (cloud_in.points[i].normal_x) || + !pcl_isfinite (cloud_in.points[i].normal_y) || + !pcl_isfinite (cloud_in.points[i].normal_z)) + continue; + cloud_out.points[j] = cloud_in.points[i]; + index[j] = static_cast(i); + j++; + } + if (j != cloud_in.points.size ()) + { + // Resize to the correct size + cloud_out.points.resize (j); + index.resize (j); + } + + cloud_out.height = 1; + cloud_out.width = static_cast(j); +} + + +#define PCL_INSTANTIATE_removeNaNFromPointCloud(T) template PCL_EXPORTS void pcl::removeNaNFromPointCloud(const pcl::PointCloud&, pcl::PointCloud&, std::vector&); +#define PCL_INSTANTIATE_removeNaNNormalsFromPointCloud(T) template PCL_EXPORTS void pcl::removeNaNNormalsFromPointCloud(const pcl::PointCloud&, pcl::PointCloud&, std::vector&); + +#endif // PCL_FILTERS_IMPL_FILTER_H_ + diff --git a/pcl-1.7/pcl/filters/impl/filter_indices.hpp b/pcl-1.7/pcl/filters/impl/filter_indices.hpp new file mode 100644 index 0000000..b194d68 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/filter_indices.hpp @@ -0,0 +1,80 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: filter.hpp 1800 2011-07-15 11:45:31Z marton $ + * + */ + +#ifndef PCL_FILTERS_IMPL_FILTER_INDICES_H_ +#define PCL_FILTERS_IMPL_FILTER_INDICES_H_ + +#include +#include + +template void +pcl::removeNaNFromPointCloud (const pcl::PointCloud &cloud_in, + std::vector &index) +{ + // Reserve enough space for the indices + index.resize (cloud_in.points.size ()); + int j = 0; + + // If the data is dense, we don't need to check for NaN + if (cloud_in.is_dense) + { + for (j = 0; j < static_cast (cloud_in.points.size ()); ++j) + index[j] = j; + } + else + { + for (int i = 0; i < static_cast (cloud_in.points.size ()); ++i) + { + if (!pcl_isfinite (cloud_in.points[i].x) || + !pcl_isfinite (cloud_in.points[i].y) || + !pcl_isfinite (cloud_in.points[i].z)) + continue; + index[j] = i; + j++; + } + if (j != static_cast (cloud_in.points.size ())) + { + // Resize to the correct size + index.resize (j); + } + } +} + +#define PCL_INSTANTIATE_removeNanFromPointCloud(T) template PCL_EXPORTS void pcl::removeNaNFromPointCloud(const pcl::PointCloud&, std::vector&); + +#endif // PCL_FILTERS_IMPL_FILTER_INDICES_H_ + diff --git a/pcl-1.7/pcl/filters/impl/frustum_culling.hpp b/pcl-1.7/pcl/filters/impl/frustum_culling.hpp new file mode 100644 index 0000000..7470b79 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/frustum_culling.hpp @@ -0,0 +1,181 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FILTERS_IMPL_FRUSTUM_CULLING_HPP_ +#define PCL_FILTERS_IMPL_FRUSTUM_CULLING_HPP_ + +#include +#include +#include + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::FrustumCulling::applyFilter (PointCloud& output) +{ + std::vector indices; + if (keep_organized_) + { + bool temp = extract_removed_indices_; + extract_removed_indices_ = true; + applyFilter (indices); + extract_removed_indices_ = temp; + copyPointCloud (*input_, output); + + for (size_t rii = 0; rii < removed_indices_->size (); ++rii) + { + PointT &pt_to_remove = output.at ((*removed_indices_)[rii]); + pt_to_remove.x = pt_to_remove.y = pt_to_remove.z = user_filter_value_; + if (!pcl_isfinite (user_filter_value_)) + output.is_dense = false; + } + } + else + { + output.is_dense = true; + applyFilter (indices); + copyPointCloud (*input_, indices, output); + } +} + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::FrustumCulling::applyFilter (std::vector &indices) +{ + Eigen::Vector4f pl_n; // near plane + Eigen::Vector4f pl_f; // far plane + Eigen::Vector4f pl_t; // top plane + Eigen::Vector4f pl_b; // bottom plane + Eigen::Vector4f pl_r; // right plane + Eigen::Vector4f pl_l; // left plane + + Eigen::Vector3f view = camera_pose_.block (0, 0, 3, 1); // view vector for the camera - first column of the rotation matrix + Eigen::Vector3f up = camera_pose_.block (0, 1, 3, 1); // up vector for the camera - second column of the rotation matix + Eigen::Vector3f right = camera_pose_.block (0, 2, 3, 1); // right vector for the camera - third column of the rotation matrix + Eigen::Vector3f T = camera_pose_.block (0, 3, 3, 1); // The (X, Y, Z) position of the camera w.r.t origin + + + float vfov_rad = float (vfov_ * M_PI / 180); // degrees to radians + float hfov_rad = float (hfov_ * M_PI / 180); // degrees to radians + + float np_h = float (2 * tan (vfov_rad / 2) * np_dist_); // near plane height + float np_w = float (2 * tan (hfov_rad / 2) * np_dist_); // near plane width + + float fp_h = float (2 * tan (vfov_rad / 2) * fp_dist_); // far plane height + float fp_w = float (2 * tan (hfov_rad / 2) * fp_dist_); // far plane width + + Eigen::Vector3f fp_c (T + view * fp_dist_); // far plane center + Eigen::Vector3f fp_tl (fp_c + (up * fp_h / 2) - (right * fp_w / 2)); // Top left corner of the far plane + Eigen::Vector3f fp_tr (fp_c + (up * fp_h / 2) + (right * fp_w / 2)); // Top right corner of the far plane + Eigen::Vector3f fp_bl (fp_c - (up * fp_h / 2) - (right * fp_w / 2)); // Bottom left corner of the far plane + Eigen::Vector3f fp_br (fp_c - (up * fp_h / 2) + (right * fp_w / 2)); // Bottom right corner of the far plane + + Eigen::Vector3f np_c (T + view * np_dist_); // near plane center + //Eigen::Vector3f np_tl = np_c + (up * np_h/2) - (right * np_w/2); // Top left corner of the near plane + Eigen::Vector3f np_tr (np_c + (up * np_h / 2) + (right * np_w / 2)); // Top right corner of the near plane + Eigen::Vector3f np_bl (np_c - (up * np_h / 2) - (right * np_w / 2)); // Bottom left corner of the near plane + Eigen::Vector3f np_br (np_c - (up * np_h / 2) + (right * np_w / 2)); // Bottom right corner of the near plane + + pl_f.block (0, 0, 3, 1).matrix () = (fp_bl - fp_br).cross (fp_tr - fp_br); // Far plane equation - cross product of the + pl_f (3) = -fp_c.dot (pl_f.block (0, 0, 3, 1)); // perpendicular edges of the far plane + + pl_n.block (0, 0, 3, 1).matrix () = (np_tr - np_br).cross (np_bl - np_br); // Near plane equation - cross product of the + pl_n (3) = -np_c.dot (pl_n.block (0, 0, 3, 1)); // perpendicular edges of the far plane + + Eigen::Vector3f a (fp_bl - T); // Vector connecting the camera and far plane bottom left + Eigen::Vector3f b (fp_br - T); // Vector connecting the camera and far plane bottom right + Eigen::Vector3f c (fp_tr - T); // Vector connecting the camera and far plane top right + Eigen::Vector3f d (fp_tl - T); // Vector connecting the camera and far plane top left + + // Frustum and the vectors a, b, c and d. T is the position of the camera + // _________ + // /| . | + // d / | c . | + // / | __._____| + // / / . . + // a <---/-/ . . + // / / . . b + // / . + // . + // T + // + + pl_r.block (0, 0, 3, 1).matrix () = b.cross (c); + pl_l.block (0, 0, 3, 1).matrix () = d.cross (a); + pl_t.block (0, 0, 3, 1).matrix () = c.cross (d); + pl_b.block (0, 0, 3, 1).matrix () = a.cross (b); + + pl_r (3) = -T.dot (pl_r.block (0, 0, 3, 1)); + pl_l (3) = -T.dot (pl_l.block (0, 0, 3, 1)); + pl_t (3) = -T.dot (pl_t.block (0, 0, 3, 1)); + pl_b (3) = -T.dot (pl_b.block (0, 0, 3, 1)); + + if (extract_removed_indices_) + { + removed_indices_->resize (indices_->size ()); + } + indices.resize (indices_->size ()); + size_t indices_ctr = 0; + size_t removed_ctr = 0; + for (size_t i = 0; i < indices_->size (); i++) + { + int idx = indices_->at (i); + Eigen::Vector4f pt (input_->points[idx].x, + input_->points[idx].y, + input_->points[idx].z, + 1.0f); + bool is_in_fov = (pt.dot (pl_l) <= 0) && + (pt.dot (pl_r) <= 0) && + (pt.dot (pl_t) <= 0) && + (pt.dot (pl_b) <= 0) && + (pt.dot (pl_f) <= 0) && + (pt.dot (pl_n) <= 0); + if (is_in_fov ^ negative_) + { + indices[indices_ctr++] = idx; + } + else if (extract_removed_indices_) + { + (*removed_indices_)[removed_ctr++] = idx; + } + } + indices.resize (indices_ctr); + removed_indices_->resize (removed_ctr); +} + +#define PCL_INSTANTIATE_FrustumCulling(T) template class PCL_EXPORTS pcl::FrustumCulling; + +#endif diff --git a/pcl-1.7/pcl/filters/impl/grid_minimum.hpp b/pcl-1.7/pcl/filters/impl/grid_minimum.hpp new file mode 100644 index 0000000..a8b8bf5 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/grid_minimum.hpp @@ -0,0 +1,198 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2014, RadiantBlue Technologies, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_IMPL_VOXEL_GRID_MINIMUM_H_ +#define PCL_FILTERS_IMPL_VOXEL_GRID_MINIMUM_H_ + +#include +#include +#include + +struct point_index_idx +{ + unsigned int idx; + unsigned int cloud_point_index; + + point_index_idx (unsigned int idx_, unsigned int cloud_point_index_) : idx (idx_), cloud_point_index (cloud_point_index_) {} + bool operator < (const point_index_idx &p) const { return (idx < p.idx); } +}; + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridMinimum::applyFilter (PointCloud &output) +{ + // Has the input dataset been set already? + if (!input_) + { + PCL_WARN ("[pcl::%s::applyFilter] No input dataset given!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + std::vector indices; + + output.is_dense = true; + applyFilterIndices (indices); + pcl::copyPointCloud (*input_, indices, output); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridMinimum::applyFilterIndices (std::vector &indices) +{ + indices.resize (indices_->size ()); + int oii = 0; + + // Get the minimum and maximum dimensions + Eigen::Vector4f min_p, max_p; + getMinMax3D (*input_, *indices_, min_p, max_p); + + // Check that the resolution is not too small, given the size of the data + int64_t dx = static_cast ((max_p[0] - min_p[0]) * inverse_resolution_)+1; + int64_t dy = static_cast ((max_p[1] - min_p[1]) * inverse_resolution_)+1; + + if ((dx*dy) > static_cast (std::numeric_limits::max ())) + { + PCL_WARN ("[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.", getClassName ().c_str ()); + return; + } + + Eigen::Vector4i min_b, max_b, div_b, divb_mul; + + // Compute the minimum and maximum bounding box values + min_b[0] = static_cast (floor (min_p[0] * inverse_resolution_)); + max_b[0] = static_cast (floor (max_p[0] * inverse_resolution_)); + min_b[1] = static_cast (floor (min_p[1] * inverse_resolution_)); + max_b[1] = static_cast (floor (max_p[1] * inverse_resolution_)); + + // Compute the number of divisions needed along all axis + div_b = max_b - min_b + Eigen::Vector4i::Ones (); + div_b[3] = 0; + + // Set up the division multiplier + divb_mul = Eigen::Vector4i (1, div_b[0], 0, 0); + + std::vector index_vector; + index_vector.reserve (indices_->size ()); + + // First pass: go over all points and insert them into the index_vector vector + // with calculated idx. Points with the same idx value will contribute to the + // same point of resulting CloudPoint + for (std::vector::const_iterator it = indices_->begin (); it != indices_->end (); ++it) + { + if (!input_->is_dense) + // Check if the point is invalid + if (!pcl_isfinite (input_->points[*it].x) || + !pcl_isfinite (input_->points[*it].y) || + !pcl_isfinite (input_->points[*it].z)) + continue; + + int ijk0 = static_cast (floor (input_->points[*it].x * inverse_resolution_) - static_cast (min_b[0])); + int ijk1 = static_cast (floor (input_->points[*it].y * inverse_resolution_) - static_cast (min_b[1])); + + // Compute the grid cell index + int idx = ijk0 * divb_mul[0] + ijk1 * divb_mul[1]; + index_vector.push_back (point_index_idx (static_cast (idx), *it)); + } + + // Second pass: sort the index_vector vector using value representing target cell as index + // in effect all points belonging to the same output cell will be next to each other + std::sort (index_vector.begin (), index_vector.end (), std::less ()); + + // Third pass: count output cells + // we need to skip all the same, adjacenent idx values + unsigned int total = 0; + unsigned int index = 0; + + // first_and_last_indices_vector[i] represents the index in index_vector of the first point in + // index_vector belonging to the voxel which corresponds to the i-th output point, + // and of the first point not belonging to. + std::vector > first_and_last_indices_vector; + + // Worst case size + first_and_last_indices_vector.reserve (index_vector.size ()); + while (index < index_vector.size ()) + { + unsigned int i = index + 1; + while (i < index_vector.size () && index_vector[i].idx == index_vector[index].idx) + ++i; + ++total; + first_and_last_indices_vector.push_back (std::pair (index, i)); + index = i; + } + + // Fourth pass: locate grid minimums + indices.resize (total); + + index = 0; + + for (unsigned int cp = 0; cp < first_and_last_indices_vector.size (); ++cp) + { + unsigned int first_index = first_and_last_indices_vector[cp].first; + unsigned int last_index = first_and_last_indices_vector[cp].second; + unsigned int min_index = index_vector[first_index].cloud_point_index; + float min_z = input_->points[index_vector[first_index].cloud_point_index].z; + + for (unsigned int i = first_index + 1; i < last_index; ++i) + { + if (input_->points[index_vector[i].cloud_point_index].z < min_z) + { + min_z = input_->points[index_vector[i].cloud_point_index].z; + min_index = index_vector[i].cloud_point_index; + } + } + + indices[index] = min_index; + + ++index; + } + + oii = indices.size (); + + // Resize the output arrays + indices.resize (oii); +} + +#define PCL_INSTANTIATE_GridMinimum(T) template class PCL_EXPORTS pcl::GridMinimum; + +#endif // PCL_FILTERS_IMPL_VOXEL_GRID_MINIMUM_H_ + diff --git a/pcl-1.7/pcl/filters/impl/local_maximum.hpp b/pcl-1.7/pcl/filters/impl/local_maximum.hpp new file mode 100644 index 0000000..c58953d --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/local_maximum.hpp @@ -0,0 +1,191 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2014, RadiantBlue Technologies, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_IMPL_LOCAL_MAXIMUM_H_ +#define PCL_FILTERS_IMPL_LOCAL_MAXIMUM_H_ + +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LocalMaximum::applyFilter (PointCloud &output) +{ + // Has the input dataset been set already? + if (!input_) + { + PCL_WARN ("[pcl::%s::applyFilter] No input dataset given!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + std::vector indices; + + output.is_dense = true; + applyFilterIndices (indices); + pcl::copyPointCloud (*input_, indices, output); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LocalMaximum::applyFilterIndices (std::vector &indices) +{ + typename PointCloud::Ptr cloud_projected (new PointCloud); + + // Create a set of planar coefficients with X=Y=0,Z=1 + pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients ()); + coefficients->values.resize (4); + coefficients->values[0] = coefficients->values[1] = 0; + coefficients->values[2] = 1.0; + coefficients->values[3] = 0; + + // Create the filtering object and project input into xy plane + pcl::ProjectInliers proj; + proj.setModelType (pcl::SACMODEL_PLANE); + proj.setInputCloud (input_); + proj.setModelCoefficients (coefficients); + proj.filter (*cloud_projected); + + // Initialize the search class + if (!searcher_) + { + if (input_->isOrganized ()) + searcher_.reset (new pcl::search::OrganizedNeighbor ()); + else + searcher_.reset (new pcl::search::KdTree (false)); + } + searcher_->setInputCloud (cloud_projected); + + // The arrays to be used + indices.resize (indices_->size ()); + removed_indices_->resize (indices_->size ()); + int oii = 0, rii = 0; // oii = output indices iterator, rii = removed indices iterator + + std::vector point_is_max (indices_->size (), false); + std::vector point_is_visited (indices_->size (), false); + + // Find all points within xy radius (i.e., a vertical cylinder) of the query + // point, removing those that are locally maximal (i.e., highest z within the + // cylinder) + for (int iii = 0; iii < static_cast (indices_->size ()); ++iii) + { + if (!isFinite (input_->points[(*indices_)[iii]])) + { + continue; + } + + // Points in the neighborhood of a previously identified local max, will + // not be maximal in their own neighborhood + if (point_is_visited[(*indices_)[iii]] && !point_is_max[(*indices_)[iii]]) + { + continue; + } + + // Assume the current query point is the maximum, mark as visited + point_is_max[(*indices_)[iii]] = true; + point_is_visited[(*indices_)[iii]] = true; + + // Perform the radius search in the projected cloud + std::vector radius_indices; + std::vector radius_dists; + PointT p = cloud_projected->points[(*indices_)[iii]]; + if (searcher_->radiusSearch (p, radius_, radius_indices, radius_dists) == 0) + { + PCL_WARN ("[pcl::%s::applyFilter] Searching for neighbors within radius %f failed.\n", getClassName ().c_str (), radius_); + continue; + } + + // If query point is alone, we retain it regardless + if (radius_indices.size () == 1) + { + point_is_max[(*indices_)[iii]] = false; + } + + // Check to see if a neighbor is higher than the query point + float query_z = input_->points[(*indices_)[iii]].z; + for (size_t k = 1; k < radius_indices.size (); ++k) // k = 1 is the first neighbor + { + if (input_->points[radius_indices[k]].z > query_z) + { + // Query point is not the local max, no need to check others + point_is_max[(*indices_)[iii]] = false; + break; + } + } + + // If the query point was a local max, all neighbors can be marked as + // visited, excluding them from future consideration as local maxima + if (point_is_max[(*indices_)[iii]]) + { + for (size_t k = 1; k < radius_indices.size (); ++k) // k = 1 is the first neighbor + { + point_is_visited[radius_indices[k]] = true; + } + } + + // Points that are local maxima are passed to removed indices + // Unless negative was set, then it's the opposite condition + if ((!negative_ && point_is_max[(*indices_)[iii]]) || (negative_ && !point_is_max[(*indices_)[iii]])) + { + if (extract_removed_indices_) + { + (*removed_indices_)[rii++] = (*indices_)[iii]; + } + + continue; + } + + // Otherwise it was a normal point for output (inlier) + indices[oii++] = (*indices_)[iii]; + } + + // Resize the output arrays + indices.resize (oii); + removed_indices_->resize (rii); +} + +#define PCL_INSTANTIATE_LocalMaximum(T) template class PCL_EXPORTS pcl::LocalMaximum; + +#endif // PCL_FILTERS_IMPL_LOCAL_MAXIMUM_H_ + diff --git a/pcl-1.7/pcl/filters/impl/median_filter.hpp b/pcl-1.7/pcl/filters/impl/median_filter.hpp new file mode 100644 index 0000000..4d8a27c --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/median_filter.hpp @@ -0,0 +1,92 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + + * All rights reserved. + + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_IMPL_MEDIAN_FILTER_HPP_ +#define PCL_FILTERS_IMPL_MEDIAN_FILTER_HPP_ + +#include +#include + +template void +pcl::MedianFilter::applyFilter (PointCloud &output) +{ + if (!input_->isOrganized ()) + { + PCL_ERROR ("[pcl::MedianFilter] Input cloud needs to be organized\n"); + return; + } + + // Copy everything from the input cloud to the output cloud (takes care of all the fields) + copyPointCloud (*input_, output); + + int height = static_cast (output.height); + int width = static_cast (output.width); + for (int y = 0; y < height; ++y) + for (int x = 0; x < width; ++x) + if (pcl::isFinite ((*input_)(x, y))) + { + std::vector vals; + vals.reserve (window_size_ * window_size_); + // Fill in the vector of values with the depths around the interest point + for (int y_dev = -window_size_/2; y_dev <= window_size_/2; ++y_dev) + for (int x_dev = -window_size_/2; x_dev <= window_size_/2; ++x_dev) + { + if (x + x_dev >= 0 && x + x_dev < width && + y + y_dev >= 0 && y + y_dev < height && + pcl::isFinite ((*input_)(x+x_dev, y+y_dev))) + vals.push_back ((*input_)(x+x_dev, y+y_dev).z); + } + + if (vals.size () == 0) + continue; + + // The output depth will be the median of all the depths in the window + partial_sort (vals.begin (), vals.begin () + vals.size () / 2 + 1, vals.end ()); + float new_depth = vals[vals.size () / 2]; + // Do not allow points to move more than the set max_allowed_movement_ + if (fabs (new_depth - (*input_)(x, y).z) < max_allowed_movement_) + output (x, y).z = new_depth; + else + output (x, y).z = (*input_)(x, y).z + + max_allowed_movement_ * (new_depth - (*input_)(x, y).z) / fabsf (new_depth - (*input_)(x, y).z); + } +} + + +#endif /* PCL_FILTERS_IMPL_MEDIAN_FILTER_HPP_ */ diff --git a/pcl-1.7/pcl/filters/impl/model_outlier_removal.hpp b/pcl-1.7/pcl/filters/impl/model_outlier_removal.hpp new file mode 100644 index 0000000..e7e9ff6 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/model_outlier_removal.hpp @@ -0,0 +1,265 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_FILTERS_IMPL_MODEL_OUTLIER_REMOVAL_HPP_ +#define PCL_FILTERS_IMPL_MODEL_OUTLIER_REMOVAL_HPP_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::ModelOutlierRemoval::initSACModel (pcl::SacModel model_type) +{ + // Build the model + switch (model_type) + { + case SACMODEL_PLANE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: modelPLANE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelPlane (input_)); + break; + } + case SACMODEL_LINE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: modelLINE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelLine (input_)); + break; + } + case SACMODEL_CIRCLE2D: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: modelCIRCLE2D\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelCircle2D (input_)); + break; + } + case SACMODEL_SPHERE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: modelSPHERE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelSphere (input_)); + break; + } + case SACMODEL_PARALLEL_LINE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: modelPARALLEL_LINE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelParallelLine (input_)); + break; + } + case SACMODEL_PERPENDICULAR_PLANE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: modelPERPENDICULAR_PLANE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelPerpendicularPlane (input_)); + break; + } + case SACMODEL_CYLINDER: + { + PCL_DEBUG ("[pcl::%s::segment] Using a model of type: modelCYLINDER\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelCylinder (input_)); + break; + } + case SACMODEL_NORMAL_PLANE: + { + PCL_DEBUG ("[pcl::%s::segment] Using a model of type: modelNORMAL_PLANE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelNormalPlane (input_)); + break; + } + case SACMODEL_CONE: + { + PCL_DEBUG ("[pcl::%s::segment] Using a model of type: modelCONE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelCone (input_)); + break; + } + case SACMODEL_NORMAL_SPHERE: + { + PCL_DEBUG ("[pcl::%s::segment] Using a model of type: modelNORMAL_SPHERE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelNormalSphere (input_)); + break; + } + case SACMODEL_NORMAL_PARALLEL_PLANE: + { + PCL_DEBUG ("[pcl::%s::segment] Using a model of type: modelNORMAL_PARALLEL_PLANE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelNormalParallelPlane (input_)); + break; + } + case SACMODEL_PARALLEL_PLANE: + { + PCL_DEBUG ("[pcl::%s::segment] Using a model of type: modelPARALLEL_PLANE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelParallelPlane (input_)); + break; + } + default: + { + PCL_ERROR ("[pcl::%s::initSACModel] No valid model given!\n", getClassName ().c_str ()); + return (false); + } + } + return (true); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ModelOutlierRemoval::applyFilter (PointCloud &output) +{ + std::vector indices; + if (keep_organized_) + { + bool temp = extract_removed_indices_; + extract_removed_indices_ = true; + applyFilterIndices (indices); + extract_removed_indices_ = temp; + + output = *input_; + for (int rii = 0; rii < static_cast (removed_indices_->size ()); ++rii) // rii = removed indices iterator + output.points[ (*removed_indices_)[rii]].x = output.points[ (*removed_indices_)[rii]].y = output.points[ (*removed_indices_)[rii]].z = user_filter_value_; + if (!pcl_isfinite (user_filter_value_)) + output.is_dense = false; + } + else + { + applyFilterIndices (indices); + copyPointCloud (*input_, indices, output); + } +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ModelOutlierRemoval::applyFilterIndices (std::vector &indices) +{ + //The arrays to be used + indices.resize (indices_->size ()); + removed_indices_->resize (indices_->size ()); + int oii = 0, rii = 0; // oii = output indices iterator, rii = removed indices iterator + //is the filtersetup correct? + bool valid_setup = true; + + valid_setup &= initSACModel (model_type_); + + typedef SampleConsensusModelFromNormals SACModelFromNormals; + // Returns NULL if cast isn't possible + SACModelFromNormals *model_from_normals = dynamic_cast (& (*model_)); + + if (model_from_normals) + { + if (!cloud_normals_) + { + valid_setup = false; + PCL_ERROR ("[pcl::ModelOutlierRemoval::applyFilterIndices]: no normals cloud set.\n"); + } + else + { + model_from_normals->setNormalDistanceWeight (normals_distance_weight_); + model_from_normals->setInputNormals (cloud_normals_); + } + } + + //if the filter setup is invalid filter for nan and return; + if (!valid_setup) + { + for (int iii = 0; iii < static_cast (indices_->size ()); ++iii) // iii = input indices iterator + { + // Non-finite entries are always passed to removed indices + if (!isFinite (input_->points[ (*indices_)[iii]])) + { + if (extract_removed_indices_) + (*removed_indices_)[rii++] = (*indices_)[iii]; + continue; + } + indices[oii++] = (*indices_)[iii]; + } + return; + } + // check distance of pointcloud to model + std::vector distances; + //TODO: get signed distances ! + model_->getDistancesToModel (model_coefficients_, distances); + bool thresh_result; + + // Filter for non-finite entries and the specified field limits + for (int iii = 0; iii < static_cast (indices_->size ()); ++iii) // iii = input indices iterator + { + // Non-finite entries are always passed to removed indices + if (!isFinite (input_->points[ (*indices_)[iii]])) + { + if (extract_removed_indices_) + (*removed_indices_)[rii++] = (*indices_)[iii]; + continue; + } + + // use threshold function to seperate outliers from inliers: + thresh_result = threshold_function_ (distances[iii]); + + // in normal mode: define outliers as false thresh_result + if (!negative_ && !thresh_result) + { + if (extract_removed_indices_) + (*removed_indices_)[rii++] = (*indices_)[iii]; + continue; + } + + // in negative_ mode: define outliers as true thresh_result + if (negative_ && thresh_result) + { + if (extract_removed_indices_) + (*removed_indices_)[rii++] = (*indices_)[iii]; + continue; + } + + // Otherwise it was a normal point for output (inlier) + indices[oii++] = (*indices_)[iii]; + + } + + // Resize the output arrays + indices.resize (oii); + removed_indices_->resize (rii); + +} + +#define PCL_INSTANTIATE_ModelOutlierRemoval(T) template class PCL_EXPORTS pcl::ModelOutlierRemoval; + +#endif // PCL_FILTERS_IMPL_MODEL_OUTLIER_REMOVAL_HPP_ diff --git a/pcl-1.7/pcl/filters/impl/morphological_filter.hpp b/pcl-1.7/pcl/filters/impl/morphological_filter.hpp new file mode 100644 index 0000000..59a0a96 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/morphological_filter.hpp @@ -0,0 +1,208 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2014, RadiantBlue Technologies, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_IMPL_MORPHOLOGICAL_FILTER_H_ +#define PCL_FILTERS_IMPL_MORPHOLOGICAL_FILTER_H_ + +#include +#include + +#include + +#include +#include +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::applyMorphologicalOperator (const typename pcl::PointCloud::ConstPtr &cloud_in, + float resolution, const int morphological_operator, + pcl::PointCloud &cloud_out) +{ + if (cloud_in->empty ()) + return; + + pcl::copyPointCloud (*cloud_in, cloud_out); + + pcl::octree::OctreePointCloudSearch tree (resolution); + + tree.setInputCloud (cloud_in); + tree.addPointsFromInputCloud (); + + float half_res = resolution / 2.0f; + + switch (morphological_operator) + { + case MORPH_DILATE: + case MORPH_ERODE: + { + for (size_t p_idx = 0; p_idx < cloud_in->points.size (); ++p_idx) + { + Eigen::Vector3f bbox_min, bbox_max; + std::vector pt_indices; + float minx = cloud_in->points[p_idx].x - half_res; + float miny = cloud_in->points[p_idx].y - half_res; + float minz = -std::numeric_limits::max (); + float maxx = cloud_in->points[p_idx].x + half_res; + float maxy = cloud_in->points[p_idx].y + half_res; + float maxz = std::numeric_limits::max (); + bbox_min = Eigen::Vector3f (minx, miny, minz); + bbox_max = Eigen::Vector3f (maxx, maxy, maxz); + tree.boxSearch (bbox_min, bbox_max, pt_indices); + + if (pt_indices.size () > 0) + { + Eigen::Vector4f min_pt, max_pt; + pcl::getMinMax3D (*cloud_in, pt_indices, min_pt, max_pt); + + switch (morphological_operator) + { + case MORPH_DILATE: + { + cloud_out.points[p_idx].z = max_pt.z (); + break; + } + case MORPH_ERODE: + { + cloud_out.points[p_idx].z = min_pt.z (); + break; + } + } + } + } + break; + } + case MORPH_OPEN: + case MORPH_CLOSE: + { + pcl::PointCloud cloud_temp; + + pcl::copyPointCloud (*cloud_in, cloud_temp); + + for (size_t p_idx = 0; p_idx < cloud_temp.points.size (); ++p_idx) + { + Eigen::Vector3f bbox_min, bbox_max; + std::vector pt_indices; + float minx = cloud_temp.points[p_idx].x - half_res; + float miny = cloud_temp.points[p_idx].y - half_res; + float minz = -std::numeric_limits::max (); + float maxx = cloud_temp.points[p_idx].x + half_res; + float maxy = cloud_temp.points[p_idx].y + half_res; + float maxz = std::numeric_limits::max (); + bbox_min = Eigen::Vector3f (minx, miny, minz); + bbox_max = Eigen::Vector3f (maxx, maxy, maxz); + tree.boxSearch (bbox_min, bbox_max, pt_indices); + + if (pt_indices.size () > 0) + { + Eigen::Vector4f min_pt, max_pt; + pcl::getMinMax3D (cloud_temp, pt_indices, min_pt, max_pt); + + switch (morphological_operator) + { + case MORPH_OPEN: + { + cloud_out.points[p_idx].z = min_pt.z (); + break; + } + case MORPH_CLOSE: + { + cloud_out.points[p_idx].z = max_pt.z (); + break; + } + } + } + } + + cloud_temp.swap (cloud_out); + + for (size_t p_idx = 0; p_idx < cloud_temp.points.size (); ++p_idx) + { + Eigen::Vector3f bbox_min, bbox_max; + std::vector pt_indices; + float minx = cloud_temp.points[p_idx].x - half_res; + float miny = cloud_temp.points[p_idx].y - half_res; + float minz = -std::numeric_limits::max (); + float maxx = cloud_temp.points[p_idx].x + half_res; + float maxy = cloud_temp.points[p_idx].y + half_res; + float maxz = std::numeric_limits::max (); + bbox_min = Eigen::Vector3f (minx, miny, minz); + bbox_max = Eigen::Vector3f (maxx, maxy, maxz); + tree.boxSearch (bbox_min, bbox_max, pt_indices); + + if (pt_indices.size () > 0) + { + Eigen::Vector4f min_pt, max_pt; + pcl::getMinMax3D (cloud_temp, pt_indices, min_pt, max_pt); + + switch (morphological_operator) + { + case MORPH_OPEN: + default: + { + cloud_out.points[p_idx].z = max_pt.z (); + break; + } + case MORPH_CLOSE: + { + cloud_out.points[p_idx].z = min_pt.z (); + break; + } + } + } + } + break; + } + default: + { + PCL_ERROR ("Morphological operator is not supported!\n"); + break; + } + } + + return; +} + +#define PCL_INSTANTIATE_applyMorphologicalOperator(T) template PCL_EXPORTS void pcl::applyMorphologicalOperator (const pcl::PointCloud::ConstPtr &, float, const int, pcl::PointCloud &); + +#endif //#ifndef PCL_FILTERS_IMPL_MORPHOLOGICAL_FILTER_H_ + diff --git a/pcl-1.7/pcl/filters/impl/normal_refinement.hpp b/pcl-1.7/pcl/filters/impl/normal_refinement.hpp new file mode 100644 index 0000000..6a744ab --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/normal_refinement.hpp @@ -0,0 +1,122 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_IMPL_NORMAL_REFINEMENT_H_ +#define PCL_FILTERS_IMPL_NORMAL_REFINEMENT_H_ + +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::NormalRefinement::applyFilter (PointCloud &output) +{ + // Check input + if (input_->empty ()) + { + PCL_ERROR ("[pcl::%s::applyFilter] No source was input!\n", + getClassName ().c_str ()); + } + + // Copy to output + output = *input_; + + // Check that correspondences are non-empty + if (k_indices_.empty () || k_sqr_distances_.empty ()) + { + PCL_ERROR ("[pcl::%s::applyFilter] No point correspondences given! Returning original input.\n", + getClassName ().c_str ()); + return; + } + + // Check that correspondences are OK + const unsigned int size = k_indices_.size (); + if (k_sqr_distances_.size () != size || input_->size () != size) + { + PCL_ERROR ("[pcl::%s::applyFilter] Inconsistency between size of correspondence indices/distances or input! Returning original input.\n", + getClassName ().c_str ()); + return; + } + + // Run refinement while monitoring convergence + for (unsigned int i = 0; i < max_iterations_; ++i) + { + // Output of the current iteration + PointCloud tmp = output; + + // Mean change in direction, measured by dot products + float ddot = 0.0f; + + // Loop over all points in current output and write refined normal to tmp + int num_valids = 0; + for(unsigned int j = 0; j < size; ++j) + { + // Point to write to + NormalT& tmpj = tmp[j]; + + // Refine + if (refineNormal (output, j, k_indices_[j], k_sqr_distances_[j], tmpj)) + { + // Accumulate using similarity in direction between previous iteration and current + const NormalT& outputj = output[j]; + ddot += tmpj.normal_x * outputj.normal_x + tmpj.normal_y * outputj.normal_y + tmpj.normal_z * outputj.normal_z; + ++num_valids; + } + } + + // Take mean of similarities + ddot /= static_cast (num_valids); + + // Negate to since we want an error measure to approach zero + ddot = 1.0f - ddot; + + // Update output + output = tmp; + + // Break if converged + if (ddot < convergence_threshold_) + { + PCL_DEBUG("[pcl::%s::applyFilter] Converged after %i iterations with mean error of %f.\n", + getClassName ().c_str (), i+1, ddot); + break; + } + } +} + +#endif diff --git a/pcl-1.7/pcl/filters/impl/normal_space.hpp b/pcl-1.7/pcl/filters/impl/normal_space.hpp new file mode 100644 index 0000000..e3809d7 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/normal_space.hpp @@ -0,0 +1,281 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FILTERS_IMPL_NORMAL_SPACE_SAMPLE_H_ +#define PCL_FILTERS_IMPL_NORMAL_SPACE_SAMPLE_H_ + +#include +#include + +#include +#include + +/////////////////////////////////////////////////////////////////////////////// +template bool +pcl::NormalSpaceSampling::initCompute () +{ + if (!FilterIndices::initCompute ()) + return false; + + // If sample size is 0 or if the sample size is greater then input cloud size then return entire copy of cloud + if (sample_ >= input_->size ()) + { + PCL_ERROR ("[NormalSpaceSampling::initCompute] Requested more samples than the input cloud size: %d vs %lu\n", + sample_, input_->size ()); + return false; + } + + boost::mt19937 rng (static_cast (seed_)); + boost::uniform_int uniform_distrib (0, unsigned (input_->size ())); + if (rng_uniform_distribution_ != NULL) + delete rng_uniform_distribution_; + rng_uniform_distribution_ = new boost::variate_generator > (rng, uniform_distrib); + + return (true); +} + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::NormalSpaceSampling::applyFilter (PointCloud &output) +{ + std::vector indices; + if (keep_organized_) + { + bool temp = extract_removed_indices_; + extract_removed_indices_ = true; + applyFilter (indices); + extract_removed_indices_ = temp; + + output = *input_; + for (int rii = 0; rii < static_cast (removed_indices_->size ()); ++rii) // rii = removed indices iterator + output.points[(*removed_indices_)[rii]].x = output.points[(*removed_indices_)[rii]].y = output.points[(*removed_indices_)[rii]].z = user_filter_value_; + if (!pcl_isfinite (user_filter_value_)) + output.is_dense = false; + } + else + { + output.is_dense = true; + applyFilter (indices); + pcl::copyPointCloud (*input_, indices, output); + } +} + +/////////////////////////////////////////////////////////////////////////////// +template bool +pcl::NormalSpaceSampling::isEntireBinSampled (boost::dynamic_bitset<> &array, + unsigned int start_index, + unsigned int length) +{ + bool status = true; + for (unsigned int i = start_index; i < start_index + length; i++) + { + status = status & array.test (i); + } + return status; +} + +/////////////////////////////////////////////////////////////////////////////// +template unsigned int +pcl::NormalSpaceSampling::findBin (const float *normal, unsigned int) +{ + unsigned int bin_number = 0; + // Holds the bin numbers for direction cosines in x,y,z directions + unsigned int t[3] = {0,0,0}; + + // dcos is the direction cosine. + float dcos = 0.0; + float bin_size = 0.0; + // max_cos and min_cos are the maximum and minimum values of cos(theta) respectively + float max_cos = 1.0; + float min_cos = -1.0; + +// dcos = cosf (normal[0]); + dcos = normal[0]; + bin_size = (max_cos - min_cos) / static_cast (binsx_); + + // Finding bin number for direction cosine in x direction + unsigned int k = 0; + for (float i = min_cos; (i + bin_size) < (max_cos - bin_size); i += bin_size , k++) + { + if (dcos >= i && dcos <= (i+bin_size)) + { + break; + } + } + t[0] = k; + +// dcos = cosf (normal[1]); + dcos = normal[1]; + bin_size = (max_cos - min_cos) / static_cast (binsy_); + + // Finding bin number for direction cosine in y direction + k = 0; + for (float i = min_cos; (i + bin_size) < (max_cos - bin_size); i += bin_size , k++) + { + if (dcos >= i && dcos <= (i+bin_size)) + { + break; + } + } + t[1] = k; + +// dcos = cosf (normal[2]); + dcos = normal[2]; + bin_size = (max_cos - min_cos) / static_cast (binsz_); + + // Finding bin number for direction cosine in z direction + k = 0; + for (float i = min_cos; (i + bin_size) < (max_cos - bin_size); i += bin_size , k++) + { + if (dcos >= i && dcos <= (i+bin_size)) + { + break; + } + } + t[2] = k; + + bin_number = t[0] * (binsy_*binsz_) + t[1] * binsz_ + t[2]; + return bin_number; +} + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::NormalSpaceSampling::applyFilter (std::vector &indices) +{ + if (!initCompute ()) + { + indices = *indices_; + return; + } + + unsigned int max_values = (std::min) (sample_, static_cast (input_normals_->size ())); + // Resize output indices to sample size + indices.resize (max_values); + removed_indices_->resize (max_values); + + // Allocate memory for the histogram of normals. Normals will then be sampled from each bin. + unsigned int n_bins = binsx_ * binsy_ * binsz_; + // list holds the indices of points in that bin. Using list to avoid repeated resizing of vectors. + // Helps when the point cloud is large. + std::vector > normals_hg; + normals_hg.reserve (n_bins); + for (unsigned int i = 0; i < n_bins; i++) + normals_hg.push_back (std::list ()); + + for (std::vector::const_iterator it = indices_->begin (); it != indices_->end (); ++it) + { + unsigned int bin_number = findBin (input_normals_->points[*it].normal, n_bins); + normals_hg[bin_number].push_back (*it); + } + + + // Setting up random access for the list created above. Maintaining the iterators to individual elements of the list + // in a vector. Using vector now as the size of the list is known. + std::vector::iterator> > random_access (normals_hg.size ()); + for (unsigned int i = 0; i < normals_hg.size (); i++) + { + random_access.push_back (std::vector::iterator> ()); + random_access[i].resize (normals_hg[i].size ()); + + unsigned int j = 0; + for (std::list::iterator itr = normals_hg[i].begin (); itr != normals_hg[i].end (); itr++, j++) + random_access[i][j] = itr; + } + std::vector start_index (normals_hg.size ()); + start_index[0] = 0; + unsigned int prev_index = start_index[0]; + for (unsigned int i = 1; i < normals_hg.size (); i++) + { + start_index[i] = prev_index + static_cast (normals_hg[i-1].size ()); + prev_index = start_index[i]; + } + + // Maintaining flags to check if a point is sampled + boost::dynamic_bitset<> is_sampled_flag (input_normals_->points.size ()); + // Maintaining flags to check if all points in the bin are sampled + boost::dynamic_bitset<> bin_empty_flag (normals_hg.size ()); + unsigned int i = 0; + while (i < sample_) + { + // Iterating through every bin and picking one point at random, until the required number of points are sampled. + for (unsigned int j = 0; j < normals_hg.size (); j++) + { + unsigned int M = static_cast (normals_hg[j].size ()); + if (M == 0 || bin_empty_flag.test (j)) // bin_empty_flag(i) is set if all points in that bin are sampled.. + continue; + + unsigned int pos = 0; + unsigned int random_index = 0; + + // Picking up a sample at random from jth bin + do + { + random_index = static_cast ((*rng_uniform_distribution_) () % M); + pos = start_index[j] + random_index; + } while (is_sampled_flag.test (pos)); + + is_sampled_flag.flip (start_index[j] + random_index); + + // Checking if all points in bin j are sampled. + if (isEntireBinSampled (is_sampled_flag, start_index[j], static_cast (normals_hg[j].size ()))) + bin_empty_flag.flip (j); + + unsigned int index = *(random_access[j][random_index]); + indices[i] = index; + i++; + if (i == sample_) + break; + } + } + + // If we need to return the indices that we haven't sampled + if (extract_removed_indices_) + { + std::vector indices_temp = indices; + std::sort (indices_temp.begin (), indices_temp.end ()); + + std::vector all_indices_temp = *indices_; + std::sort (all_indices_temp.begin (), all_indices_temp.end ()); + set_difference (all_indices_temp.begin (), all_indices_temp.end (), + indices_temp.begin (), indices_temp.end (), + inserter (*removed_indices_, removed_indices_->begin ())); + } +} + +#define PCL_INSTANTIATE_NormalSpaceSampling(T,NT) template class PCL_EXPORTS pcl::NormalSpaceSampling; + +#endif // PCL_FILTERS_IMPL_NORMAL_SPACE_SAMPLE_H_ diff --git a/pcl-1.7/pcl/filters/impl/passthrough.hpp b/pcl-1.7/pcl/filters/impl/passthrough.hpp new file mode 100644 index 0000000..e2e0a41 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/passthrough.hpp @@ -0,0 +1,167 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_IMPL_PASSTHROUGH_HPP_ +#define PCL_FILTERS_IMPL_PASSTHROUGH_HPP_ + +#include +#include + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PassThrough::applyFilter (PointCloud &output) +{ + std::vector indices; + if (keep_organized_) + { + bool temp = extract_removed_indices_; + extract_removed_indices_ = true; + applyFilterIndices (indices); + extract_removed_indices_ = temp; + + output = *input_; + for (int rii = 0; rii < static_cast (removed_indices_->size ()); ++rii) // rii = removed indices iterator + output.points[(*removed_indices_)[rii]].x = output.points[(*removed_indices_)[rii]].y = output.points[(*removed_indices_)[rii]].z = user_filter_value_; + if (!pcl_isfinite (user_filter_value_)) + output.is_dense = false; + } + else + { + output.is_dense = true; + applyFilterIndices (indices); + copyPointCloud (*input_, indices, output); + } +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PassThrough::applyFilterIndices (std::vector &indices) +{ + // The arrays to be used + indices.resize (indices_->size ()); + removed_indices_->resize (indices_->size ()); + int oii = 0, rii = 0; // oii = output indices iterator, rii = removed indices iterator + + // Has a field name been specified? + if (filter_field_name_.empty ()) + { + // Only filter for non-finite entries then + for (int iii = 0; iii < static_cast (indices_->size ()); ++iii) // iii = input indices iterator + { + // Non-finite entries are always passed to removed indices + if (!pcl_isfinite (input_->points[(*indices_)[iii]].x) || + !pcl_isfinite (input_->points[(*indices_)[iii]].y) || + !pcl_isfinite (input_->points[(*indices_)[iii]].z)) + { + if (extract_removed_indices_) + (*removed_indices_)[rii++] = (*indices_)[iii]; + continue; + } + indices[oii++] = (*indices_)[iii]; + } + } + else + { + // Attempt to get the field name's index + std::vector fields; + int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields); + if (distance_idx == -1) + { + PCL_WARN ("[pcl::%s::applyFilter] Unable to find field name in point type.\n", getClassName ().c_str ()); + indices.clear (); + removed_indices_->clear (); + return; + } + + // Filter for non-finite entries and the specified field limits + for (int iii = 0; iii < static_cast (indices_->size ()); ++iii) // iii = input indices iterator + { + // Non-finite entries are always passed to removed indices + if (!pcl_isfinite (input_->points[(*indices_)[iii]].x) || + !pcl_isfinite (input_->points[(*indices_)[iii]].y) || + !pcl_isfinite (input_->points[(*indices_)[iii]].z)) + { + if (extract_removed_indices_) + (*removed_indices_)[rii++] = (*indices_)[iii]; + continue; + } + + // Get the field's value + const uint8_t* pt_data = reinterpret_cast (&input_->points[(*indices_)[iii]]); + float field_value = 0; + memcpy (&field_value, pt_data + fields[distance_idx].offset, sizeof (float)); + + // Remove NAN/INF/-INF values. We expect passthrough to output clean valid data. + if (!pcl_isfinite (field_value)) + { + if (extract_removed_indices_) + (*removed_indices_)[rii++] = (*indices_)[iii]; + continue; + } + + // Outside of the field limits are passed to removed indices + if (!negative_ && (field_value < filter_limit_min_ || field_value > filter_limit_max_)) + { + if (extract_removed_indices_) + (*removed_indices_)[rii++] = (*indices_)[iii]; + continue; + } + + // Inside of the field limits are passed to removed indices if negative was set + if (negative_ && field_value >= filter_limit_min_ && field_value <= filter_limit_max_) + { + if (extract_removed_indices_) + (*removed_indices_)[rii++] = (*indices_)[iii]; + continue; + } + + // Otherwise it was a normal point for output (inlier) + indices[oii++] = (*indices_)[iii]; + } + } + + // Resize the output arrays + indices.resize (oii); + removed_indices_->resize (rii); +} + +#define PCL_INSTANTIATE_PassThrough(T) template class PCL_EXPORTS pcl::PassThrough; + +#endif // PCL_FILTERS_IMPL_PASSTHROUGH_HPP_ + diff --git a/pcl-1.7/pcl/filters/impl/plane_clipper3D.hpp b/pcl-1.7/pcl/filters/impl/plane_clipper3D.hpp new file mode 100644 index 0000000..a242ade --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/plane_clipper3D.hpp @@ -0,0 +1,228 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_FILTERS_IMPL_PLANE_CLIPPER3D_HPP +#define PCL_FILTERS_IMPL_PLANE_CLIPPER3D_HPP + +#include + +template +pcl::PlaneClipper3D::PlaneClipper3D (const Eigen::Vector4f& plane_params) +: plane_params_ (plane_params) +{ +} + +template +pcl::PlaneClipper3D::~PlaneClipper3D () throw () +{ +} + +template void +pcl::PlaneClipper3D::setPlaneParameters (const Eigen::Vector4f& plane_params) +{ + plane_params_ = plane_params; +} + +template const Eigen::Vector4f& +pcl::PlaneClipper3D::getPlaneParameters () const +{ + return plane_params_; +} + +template pcl::Clipper3D* +pcl::PlaneClipper3D::clone () const +{ + return new PlaneClipper3D (plane_params_); +} + +template float +pcl::PlaneClipper3D::getDistance (const PointT& point) const +{ + return (plane_params_[0] * point.x + plane_params_[1] * point.y + plane_params_[2] * point.z + plane_params_[3]); +} + +template bool +pcl::PlaneClipper3D::clipPoint3D (const PointT& point) const +{ + return ((plane_params_[0] * point.x + plane_params_[1] * point.y + plane_params_[2] * point.z ) >= -plane_params_[3]); +} + +/** + * @attention untested code + */ +template bool +pcl::PlaneClipper3D::clipLineSegment3D (PointT& point1, PointT& point2) const +{ + float dist1 = getDistance (point1); + float dist2 = getDistance (point2); + + if (dist1 * dist2 > 0) // both on same side of the plane -> nothing to clip + return (dist1 > 0); // true if both are on positive side, thus visible + + float lambda = dist2 / (dist2 - dist1); + + // get the plane intersecion + PointT intersection; + intersection.x = (point1.x - point2.x) * lambda + point2.x; + intersection.y = (point1.y - point2.y) * lambda + point2.y; + intersection.z = (point1.z - point2.z) * lambda + point2.z; + + // point1 is visible, point2 not => point2 needs to be replaced by intersection + if (dist1 >= 0) + point2 = intersection; + else + point1 = intersection; + + return false; +} + +/** + * @attention untested code + */ +template void +pcl::PlaneClipper3D::clipPlanarPolygon3D (const std::vector >& polygon, std::vector >& clipped_polygon) const +{ + clipped_polygon.clear (); + clipped_polygon.reserve (polygon.size ()); + + // test for degenerated polygons + if (polygon.size () < 3) + { + if (polygon.size () == 1) + { + // point outside clipping area ? + if (clipPoint3D (polygon [0])) + clipped_polygon.push_back (polygon [0]); + } + else if (polygon.size () == 2) + { + clipped_polygon.push_back (polygon [0]); + clipped_polygon.push_back (polygon [1]); + if (!clipLineSegment3D (clipped_polygon [0], clipped_polygon [1])) + clipped_polygon.clear (); + } + return; + } + + float previous_distance = getDistance (polygon [0]); + + if (previous_distance > 0) + clipped_polygon.push_back (polygon [0]); + + typename std::vector >::const_iterator prev_it = polygon.begin (); + + for (typename std::vector >::const_iterator pIt = prev_it + 1; pIt != polygon.end (); prev_it = pIt++) + { + // if we intersect plane + float distance = getDistance (*pIt); + if (distance * previous_distance < 0) + { + float lambda = distance / (distance - previous_distance); + + PointT intersection; + intersection.x = (prev_it->x - pIt->x) * lambda + pIt->x; + intersection.y = (prev_it->y - pIt->y) * lambda + pIt->y; + intersection.z = (prev_it->z - pIt->z) * lambda + pIt->z; + + clipped_polygon.push_back (intersection); + } + if (distance > 0) + clipped_polygon.push_back (*pIt); + + previous_distance = distance; + } +} + +/** + * @attention untested code + */ +template void +pcl::PlaneClipper3D::clipPlanarPolygon3D (std::vector > &polygon) const +{ + std::vector > clipped; + clipPlanarPolygon3D (polygon, clipped); + polygon = clipped; +} + +// /ToDo: write fast version using eigen map and single matrix vector multiplication, that uses advantages of eigens SSE operations. +template void +pcl::PlaneClipper3D::clipPointCloud3D (const pcl::PointCloud& cloud_in, std::vector& clipped, const std::vector& indices) const +{ + if (indices.empty ()) + { + clipped.reserve (cloud_in.size ()); + /* +#if 0 + Eigen::MatrixXf points = cloud_in.getMatrixXfMap (4, sizeof (PointT) / sizeof (float), offsetof(PointT,x) / sizeof (float)); + Eigen::VectorXf distances = plane_params_.transpose () * points; + for (register unsigned rIdx = 0; rIdx < cloud_in.size (); ++ rIdx) + { + if (distances (rIdx, 0) >= -plane_params_[3]) + clipped.push_back (rIdx); + } +#else + Eigen::Matrix4Xf points (4, cloud_in.size ()); + for (register unsigned rIdx = 0; rIdx < cloud_in.size (); ++ rIdx) + { + points (0, rIdx) = cloud_in[rIdx].x; + points (1, rIdx) = cloud_in[rIdx].y; + points (2, rIdx) = cloud_in[rIdx].z; + points (3, rIdx) = 1; + } + Eigen::VectorXf distances = plane_params_.transpose () * points; + for (register unsigned rIdx = 0; rIdx < cloud_in.size (); ++ rIdx) + { + if (distances (rIdx, 0) >= 0) + clipped.push_back (rIdx); + } + +#endif + + //cout << "points : " << points.rows () << " x " << points.cols () << " * " << plane_params_.transpose ().rows () << " x " << plane_params_.transpose ().cols () << endl; + + //cout << "distances: " << distances.rows () << " x " << distances.cols () << endl; + /*/ + for (register unsigned pIdx = 0; pIdx < cloud_in.size (); ++pIdx) + if (clipPoint3D (cloud_in[pIdx])) + clipped.push_back (pIdx); + //*/ + } + else + { + for (std::vector::const_iterator iIt = indices.begin (); iIt != indices.end (); ++iIt) + if (clipPoint3D (cloud_in[*iIt])) + clipped.push_back (*iIt); + } +} +#endif //PCL_FILTERS_IMPL_PLANE_CLIPPER3D_HPP diff --git a/pcl-1.7/pcl/filters/impl/project_inliers.hpp b/pcl-1.7/pcl/filters/impl/project_inliers.hpp new file mode 100644 index 0000000..8e0473d --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/project_inliers.hpp @@ -0,0 +1,166 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_IMPL_PROJECT_INLIERS_H_ +#define PCL_FILTERS_IMPL_PROJECT_INLIERS_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ProjectInliers::applyFilter (PointCloud &output) +{ + if (indices_->empty ()) + { + PCL_WARN ("[pcl::%s::applyFilter] No indices given or empty indices!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + //Eigen::Map model_coefficients (&model_->values[0], model_->values.size ()); + // More expensive than a map but safer (32bit architectures seem to complain) + Eigen::VectorXf model_coefficients (model_->values.size ()); + for (size_t i = 0; i < model_->values.size (); ++i) + model_coefficients[i] = model_->values[i]; + + // Initialize the Sample Consensus model and set its parameters + if (!initSACModel (model_type_)) + { + PCL_ERROR ("[pcl::%s::segment] Error initializing the SAC model!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + if (copy_all_data_) + sacmodel_->projectPoints (*indices_, model_coefficients, output, true); + else + sacmodel_->projectPoints (*indices_, model_coefficients, output, false); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::ProjectInliers::initSACModel (int model_type) +{ + // Build the model + switch (model_type) + { + case SACMODEL_PLANE: + { + //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_PLANE\n", getClassName ().c_str ()); + sacmodel_.reset (new SampleConsensusModelPlane (input_)); + break; + } + case SACMODEL_LINE: + { + //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_LINE\n", getClassName ().c_str ()); + sacmodel_.reset (new SampleConsensusModelLine (input_)); + break; + } + case SACMODEL_CIRCLE2D: + { + //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_CIRCLE2D\n", getClassName ().c_str ()); + sacmodel_.reset (new SampleConsensusModelCircle2D (input_)); + break; + } + case SACMODEL_SPHERE: + { + //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_SPHERE\n", getClassName ().c_str ()); + sacmodel_.reset (new SampleConsensusModelSphere (input_)); + break; + } + case SACMODEL_PARALLEL_LINE: + { + //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_PARALLEL_LINE\n", getClassName ().c_str ()); + sacmodel_.reset (new SampleConsensusModelParallelLine (input_)); + break; + } + case SACMODEL_PERPENDICULAR_PLANE: + { + //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_PERPENDICULAR_PLANE\n", getClassName ().c_str ()); + sacmodel_.reset (new SampleConsensusModelPerpendicularPlane (input_)); + break; + } + case SACMODEL_CYLINDER: + { + //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_CYLINDER\n", getClassName ().c_str ()); + sacmodel_.reset (new SampleConsensusModelCylinder (input_)); + break; + } + case SACMODEL_NORMAL_PLANE: + { + //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_NORMAL_PLANE\n", getClassName ().c_str ()); + sacmodel_.reset (new SampleConsensusModelNormalPlane (input_)); + break; + } + case SACMODEL_CONE: + { + //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_CONE\n", getClassName ().c_str ()); + sacmodel_.reset (new SampleConsensusModelCone (input_)); + break; + } + case SACMODEL_NORMAL_SPHERE: + { + //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_NORMAL_SPHERE\n", getClassName ().c_str ()); + sacmodel_.reset (new SampleConsensusModelNormalSphere (input_)); + break; + } + case SACMODEL_NORMAL_PARALLEL_PLANE: + { + //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_NORMAL_PARALLEL_PLANE\n", getClassName ().c_str ()); + sacmodel_.reset (new SampleConsensusModelNormalParallelPlane (input_)); + break; + } + case SACMODEL_PARALLEL_PLANE: + { + //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_PARALLEL_PLANE\n", getClassName ().c_str ()); + sacmodel_.reset (new SampleConsensusModelParallelPlane (input_)); + break; + } + default: + { + PCL_ERROR ("[pcl::%s::initSACModel] No valid model given!\n", getClassName ().c_str ()); + return (false); + } + } + return (true); +} + +#define PCL_INSTANTIATE_ProjectInliers(T) template class PCL_EXPORTS pcl::ProjectInliers; + +#endif // PCL_FILTERS_IMPL_PROJECT_INLIERS_H_ + diff --git a/pcl-1.7/pcl/filters/impl/radius_outlier_removal.hpp b/pcl-1.7/pcl/filters/impl/radius_outlier_removal.hpp new file mode 100644 index 0000000..033f944 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/radius_outlier_removal.hpp @@ -0,0 +1,127 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_IMPL_RADIUS_OUTLIER_REMOVAL_H_ +#define PCL_FILTERS_IMPL_RADIUS_OUTLIER_REMOVAL_H_ + +#include +#include + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RadiusOutlierRemoval::applyFilter (PointCloud &output) +{ + std::vector indices; + if (keep_organized_) + { + bool temp = extract_removed_indices_; + extract_removed_indices_ = true; + applyFilterIndices (indices); + extract_removed_indices_ = temp; + + output = *input_; + for (int rii = 0; rii < static_cast (removed_indices_->size ()); ++rii) // rii = removed indices iterator + output.points[(*removed_indices_)[rii]].x = output.points[(*removed_indices_)[rii]].y = output.points[(*removed_indices_)[rii]].z = user_filter_value_; + if (!pcl_isfinite (user_filter_value_)) + output.is_dense = false; + } + else + { + applyFilterIndices (indices); + copyPointCloud (*input_, indices, output); + } +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RadiusOutlierRemoval::applyFilterIndices (std::vector &indices) +{ + if (search_radius_ == 0.0) + { + PCL_ERROR ("[pcl::%s::applyFilter] No radius defined!\n", getClassName ().c_str ()); + indices.clear (); + removed_indices_->clear (); + return; + } + + // Initialize the search class + if (!searcher_) + { + if (input_->isOrganized ()) + searcher_.reset (new pcl::search::OrganizedNeighbor ()); + else + searcher_.reset (new pcl::search::KdTree (false)); + } + searcher_->setInputCloud (input_); + + // The arrays to be used + std::vector nn_indices (indices_->size ()); + std::vector nn_dists (indices_->size ()); + indices.resize (indices_->size ()); + removed_indices_->resize (indices_->size ()); + int oii = 0, rii = 0; // oii = output indices iterator, rii = removed indices iterator + + for (std::vector::const_iterator it = indices_->begin (); it != indices_->end (); ++it) + { + // Perform the radius search + // Note: k includes the query point, so is always at least 1 + int k = searcher_->radiusSearch (*it, search_radius_, nn_indices, nn_dists); + + // Points having too few neighbors are outliers and are passed to removed indices + // Unless negative was set, then it's the opposite condition + if ((!negative_ && k <= min_pts_radius_) || (negative_ && k > min_pts_radius_)) + { + if (extract_removed_indices_) + (*removed_indices_)[rii++] = *it; + continue; + } + + // Otherwise it was a normal point for output (inlier) + indices[oii++] = *it; + } + + // Resize the output arrays + indices.resize (oii); + removed_indices_->resize (rii); +} + +#define PCL_INSTANTIATE_RadiusOutlierRemoval(T) template class PCL_EXPORTS pcl::RadiusOutlierRemoval; + +#endif // PCL_FILTERS_IMPL_RADIUS_OUTLIER_REMOVAL_H_ + diff --git a/pcl-1.7/pcl/filters/impl/random_sample.hpp b/pcl-1.7/pcl/filters/impl/random_sample.hpp new file mode 100644 index 0000000..0aea70f --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/random_sample.hpp @@ -0,0 +1,163 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: extract_indices.hpp 1897 2011-07-26 20:35:49Z rusu $ + * + */ + +#ifndef PCL_FILTERS_IMPL_RANDOM_SAMPLE_H_ +#define PCL_FILTERS_IMPL_RANDOM_SAMPLE_H_ + +#include +#include +#include + + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::RandomSample::applyFilter (PointCloud &output) +{ + std::vector indices; + if (keep_organized_) + { + bool temp = extract_removed_indices_; + extract_removed_indices_ = true; + applyFilter (indices); + extract_removed_indices_ = temp; + copyPointCloud (*input_, output); + // Get X, Y, Z fields + std::vector fields; + pcl::getFields (*input_, fields); + std::vector offsets; + for (size_t i = 0; i < fields.size (); ++i) + { + if (fields[i].name == "x" || + fields[i].name == "y" || + fields[i].name == "z") + offsets.push_back (fields[i].offset); + } + // For every "removed" point, set the x,y,z fields to user_filter_value_ + const static float user_filter_value = user_filter_value_; + for (size_t rii = 0; rii < removed_indices_->size (); ++rii) + { + uint8_t* pt_data = reinterpret_cast (&output[(*removed_indices_)[rii]]); + for (size_t i = 0; i < offsets.size (); ++i) + { + memcpy (pt_data + offsets[i], &user_filter_value, sizeof (float)); + } + if (!pcl_isfinite (user_filter_value_)) + output.is_dense = false; + } + } + else + { + output.is_dense = true; + applyFilter (indices); + copyPointCloud (*input_, indices, output); + } +} + +/////////////////////////////////////////////////////////////////////////////// +template +void +pcl::RandomSample::applyFilter (std::vector &indices) +{ + unsigned N = static_cast (indices_->size ()); + + unsigned int sample_size = negative_ ? N - sample_ : sample_; + // If sample size is 0 or if the sample size is greater then input cloud size + // then return all indices + if (sample_size >= N) + { + indices = *indices_; + removed_indices_->clear (); + } + else + { + // Resize output indices to sample size + indices.resize (static_cast (sample_size)); + if (extract_removed_indices_) + removed_indices_->resize (static_cast (N - sample_size)); + + // Set random seed so derived indices are the same each time the filter runs + std::srand (seed_); + + // Algorithm A + unsigned top = N - sample_size; + unsigned i = 0; + unsigned index = 0; + std::vector added; + if (extract_removed_indices_) + added.resize (indices_->size (), false); + for (size_t n = sample_size; n >= 2; n--) + { + float V = unifRand (); + unsigned S = 0; + float quot = static_cast (top) / static_cast (N); + while (quot > V) + { + S++; + top--; + N--; + quot = quot * static_cast (top) / static_cast (N); + } + index += S; + if (extract_removed_indices_) + added[index] = true; + indices[i++] = (*indices_)[index++]; + N--; + } + + index += N * static_cast (unifRand ()); + if (extract_removed_indices_) + added[index] = true; + indices[i++] = (*indices_)[index++]; + + // Now populate removed_indices_ appropriately + if (extract_removed_indices_) + { + unsigned ri = 0; + for (size_t i = 0; i < added.size (); i++) + { + if (!added[i]) + { + (*removed_indices_)[ri++] = (*indices_)[i]; + } + } + } + } +} + +#define PCL_INSTANTIATE_RandomSample(T) template class PCL_EXPORTS pcl::RandomSample; + +#endif // PCL_FILTERS_IMPL_RANDOM_SAMPLE_H_ diff --git a/pcl-1.7/pcl/filters/impl/sampling_surface_normal.hpp b/pcl-1.7/pcl/filters/impl/sampling_surface_normal.hpp new file mode 100644 index 0000000..6ea6fbd --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/sampling_surface_normal.hpp @@ -0,0 +1,313 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FILTERS_IMPL_SAMPLING_SURFACE_NORMAL_H_ +#define PCL_FILTERS_IMPL_SAMPLING_SURFACE_NORMAL_H_ + +#include +#include +#include +#include + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::SamplingSurfaceNormal::applyFilter (PointCloud &output) +{ + std::vector indices; + size_t npts = input_->points.size (); + for (unsigned int i = 0; i < npts; i++) + indices.push_back (i); + + Vector max_vec (3, 1); + Vector min_vec (3, 1); + findXYZMaxMin (*input_, max_vec, min_vec); + PointCloud data = *input_; + partition (data, 0, npts, min_vec, max_vec, indices, output); + output.width = 1; + output.height = uint32_t (output.points.size ()); +} + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::SamplingSurfaceNormal::findXYZMaxMin (const PointCloud& cloud, Vector& max_vec, Vector& min_vec) +{ + float maxval = cloud.points[0].x; + float minval = cloud.points[0].x; + + for (unsigned int i = 0; i < cloud.points.size (); i++) + { + if (cloud.points[i].x > maxval) + { + maxval = cloud.points[i].x; + } + if (cloud.points[i].x < minval) + { + minval = cloud.points[i].x; + } + } + max_vec (0) = maxval; + min_vec (0) = minval; + + maxval = cloud.points[0].y; + minval = cloud.points[0].y; + + for (unsigned int i = 0; i < cloud.points.size (); i++) + { + if (cloud.points[i].y > maxval) + { + maxval = cloud.points[i].y; + } + if (cloud.points[i].y < minval) + { + minval = cloud.points[i].y; + } + } + max_vec (1) = maxval; + min_vec (1) = minval; + + maxval = cloud.points[0].z; + minval = cloud.points[0].z; + + for (unsigned int i = 0; i < cloud.points.size (); i++) + { + if (cloud.points[i].z > maxval) + { + maxval = cloud.points[i].z; + } + if (cloud.points[i].z < minval) + { + minval = cloud.points[i].z; + } + } + max_vec (2) = maxval; + min_vec (2) = minval; +} + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::SamplingSurfaceNormal::partition ( + const PointCloud& cloud, const int first, const int last, + const Vector min_values, const Vector max_values, + std::vector& indices, PointCloud& output) +{ + const int count (last - first); + if (count <= static_cast (sample_)) + { + samplePartition (cloud, first, last, indices, output); + return; + } + int cutDim = 0; + (max_values - min_values).maxCoeff (&cutDim); + + const int rightCount (count / 2); + const int leftCount (count - rightCount); + assert (last - rightCount == first + leftCount); + + // sort, hack std::nth_element + std::nth_element (indices.begin () + first, indices.begin () + first + leftCount, + indices.begin () + last, CompareDim (cutDim, cloud)); + + const int cutIndex (indices[first+leftCount]); + const float cutVal = findCutVal (cloud, cutDim, cutIndex); + + // update bounds for left + Vector leftMaxValues (max_values); + leftMaxValues[cutDim] = cutVal; + // update bounds for right + Vector rightMinValues (min_values); + rightMinValues[cutDim] = cutVal; + + // recurse + partition (cloud, first, first + leftCount, min_values, leftMaxValues, indices, output); + partition (cloud, first + leftCount, last, rightMinValues, max_values, indices, output); +} + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::SamplingSurfaceNormal::samplePartition ( + const PointCloud& data, const int first, const int last, + std::vector & indices, PointCloud& output) +{ + pcl::PointCloud cloud; + + for (int i = first; i < last; i++) + { + PointT pt; + pt.x = data.points[indices[i]].x; + pt.y = data.points[indices[i]].y; + pt.z = data.points[indices[i]].z; + cloud.points.push_back (pt); + } + cloud.width = 1; + cloud.height = uint32_t (cloud.points.size ()); + + Eigen::Vector4f normal; + float curvature = 0; + //pcl::computePointNormal (cloud, normal, curvature); + + computeNormal (cloud, normal, curvature); + + for (unsigned int i = 0; i < cloud.points.size (); i++) + { + // TODO: change to Boost random number generators! + const float r = float (std::rand ()) / float (RAND_MAX); + + if (r < ratio_) + { + PointT pt = cloud.points[i]; + pt.normal[0] = normal (0); + pt.normal[1] = normal (1); + pt.normal[2] = normal (2); + pt.curvature = curvature; + + output.points.push_back (pt); + } + } +} + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::SamplingSurfaceNormal::computeNormal (const PointCloud& cloud, Eigen::Vector4f &normal, float& curvature) +{ + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix; + Eigen::Vector4f xyz_centroid; + float nx = 0.0; + float ny = 0.0; + float nz = 0.0; + + if (computeMeanAndCovarianceMatrix (cloud, covariance_matrix, xyz_centroid) == 0) + { + nx = ny = nz = curvature = std::numeric_limits::quiet_NaN (); + return; + } + + // Get the plane normal and surface curvature + solvePlaneParameters (covariance_matrix, nx, ny, nz, curvature); + normal (0) = nx; + normal (1) = ny; + normal (2) = nz; + + normal (3) = 0; + // Hessian form (D = nc . p_plane (centroid here) + p) + normal (3) = -1 * normal.dot (xyz_centroid); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline unsigned int +pcl::SamplingSurfaceNormal::computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, + Eigen::Matrix3f &covariance_matrix, + Eigen::Vector4f ¢roid) +{ + // create the buffer on the stack which is much faster than using cloud.points[indices[i]] and centroid as a buffer + Eigen::Matrix accu = Eigen::Matrix::Zero (); + unsigned int point_count = 0; + for (unsigned int i = 0; i < cloud.points.size (); i++) + { + if (!isFinite (cloud[i])) + { + continue; + } + + ++point_count; + accu [0] += cloud[i].x * cloud[i].x; + accu [1] += cloud[i].x * cloud[i].y; + accu [2] += cloud[i].x * cloud[i].z; + accu [3] += cloud[i].y * cloud[i].y; // 4 + accu [4] += cloud[i].y * cloud[i].z; // 5 + accu [5] += cloud[i].z * cloud[i].z; // 8 + accu [6] += cloud[i].x; + accu [7] += cloud[i].y; + accu [8] += cloud[i].z; + } + + accu /= static_cast (point_count); + centroid[0] = accu[6]; centroid[1] = accu[7]; centroid[2] = accu[8]; + centroid[3] = 0; + covariance_matrix.coeffRef (0) = accu [0] - accu [6] * accu [6]; + covariance_matrix.coeffRef (1) = accu [1] - accu [6] * accu [7]; + covariance_matrix.coeffRef (2) = accu [2] - accu [6] * accu [8]; + covariance_matrix.coeffRef (4) = accu [3] - accu [7] * accu [7]; + covariance_matrix.coeffRef (5) = accu [4] - accu [7] * accu [8]; + covariance_matrix.coeffRef (8) = accu [5] - accu [8] * accu [8]; + covariance_matrix.coeffRef (3) = covariance_matrix.coeff (1); + covariance_matrix.coeffRef (6) = covariance_matrix.coeff (2); + covariance_matrix.coeffRef (7) = covariance_matrix.coeff (5); + + return (static_cast (point_count)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SamplingSurfaceNormal::solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix, + float &nx, float &ny, float &nz, float &curvature) +{ + // Extract the smallest eigenvalue and its eigenvector + EIGEN_ALIGN16 Eigen::Vector3f::Scalar eigen_value; + EIGEN_ALIGN16 Eigen::Vector3f eigen_vector; + pcl::eigen33 (covariance_matrix, eigen_value, eigen_vector); + + nx = eigen_vector [0]; + ny = eigen_vector [1]; + nz = eigen_vector [2]; + + // Compute the curvature surface change + float eig_sum = covariance_matrix.coeff (0) + covariance_matrix.coeff (4) + covariance_matrix.coeff (8); + if (eig_sum != 0) + curvature = fabsf (eigen_value / eig_sum); + else + curvature = 0; +} + +/////////////////////////////////////////////////////////////////////////////// +template float +pcl::SamplingSurfaceNormal::findCutVal ( + const PointCloud& cloud, const int cut_dim, const int cut_index) +{ + if (cut_dim == 0) + return (cloud.points[cut_index].x); + else if (cut_dim == 1) + return (cloud.points[cut_index].y); + else if (cut_dim == 2) + return (cloud.points[cut_index].z); + + return (0.0f); +} + + +#define PCL_INSTANTIATE_SamplingSurfaceNormal(T) template class PCL_EXPORTS pcl::SamplingSurfaceNormal; + +#endif // PCL_FILTERS_IMPL_NORMAL_SPACE_SAMPLE_H_ diff --git a/pcl-1.7/pcl/filters/impl/shadowpoints.hpp b/pcl-1.7/pcl/filters/impl/shadowpoints.hpp new file mode 100644 index 0000000..0d2b527 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/shadowpoints.hpp @@ -0,0 +1,111 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FILTERS_IMPL_SHADOW_POINTS_FILTER_H_ +#define PCL_FILTERS_IMPL_SHADOW_POINTS_FILTER_H_ + +#include + +#include + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::ShadowPoints::applyFilter (PointCloud &output) +{ + assert (input_normals_ != NULL); + output.points.resize (input_->points.size ()); + if (extract_removed_indices_) + removed_indices_->resize (input_->points.size ()); + + unsigned int cp = 0; + unsigned int ri = 0; + for (unsigned int i = 0; i < input_->points.size (); i++) + { + const NormalT &normal = input_normals_->points[i]; + const PointT &pt = input_->points[i]; + float val = fabsf (normal.normal_x * pt.x + normal.normal_y * pt.y + normal.normal_z * pt.z); + + if ( (val >= threshold_) ^ negative_) + output.points[cp++] = pt; + else + { + if (extract_removed_indices_) + (*removed_indices_)[ri++] = i; + if (keep_organized_) + { + PointT &pt_new = output.points[cp++] = pt; + pt_new.x = pt_new.y = pt_new.z = user_filter_value_; + } + + } + } + output.points.resize (cp); + removed_indices_->resize (ri); + output.width = 1; + output.height = static_cast (output.points.size ()); +} + +/////////////////////////////////////////////////////////////////////////////// +template void +pcl::ShadowPoints::applyFilter (std::vector &indices) +{ + assert (input_normals_ != NULL); + indices.resize (input_->points.size ()); + if (extract_removed_indices_) + removed_indices_->resize (indices_->size ()); + + unsigned int k = 0; + unsigned int z = 0; + for (std::vector::const_iterator idx = indices_->begin (); idx != indices_->end (); ++idx) + { + const NormalT &normal = input_normals_->points[*idx]; + const PointT &pt = input_->points[*idx]; + + float val = fabsf (normal.normal_x * pt.x + normal.normal_y * pt.y + normal.normal_z * pt.z); + + if ( (val >= threshold_) ^ negative_) + indices[k++] = *idx; + else if (extract_removed_indices_) + (*removed_indices_)[z++] = *idx; + } + indices.resize (k); + removed_indices_->resize (z); +} + +#define PCL_INSTANTIATE_ShadowPoints(T,NT) template class PCL_EXPORTS pcl::ShadowPoints; + +#endif // PCL_FILTERS_IMPL_NORMAL_SPACE_SAMPLE_H_ diff --git a/pcl-1.7/pcl/filters/impl/statistical_outlier_removal.hpp b/pcl-1.7/pcl/filters/impl/statistical_outlier_removal.hpp new file mode 100644 index 0000000..88a8297 --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/statistical_outlier_removal.hpp @@ -0,0 +1,166 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_IMPL_STATISTICAL_OUTLIER_REMOVAL_H_ +#define PCL_FILTERS_IMPL_STATISTICAL_OUTLIER_REMOVAL_H_ + +#include +#include + +#include + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::StatisticalOutlierRemoval::applyFilter (PointCloud &output) +{ + std::vector indices; + if (keep_organized_) + { + bool temp = extract_removed_indices_; + extract_removed_indices_ = true; + applyFilterIndices (indices); + extract_removed_indices_ = temp; + + output = *input_; + for (int rii = 0; rii < static_cast (removed_indices_->size ()); ++rii) // rii = removed indices iterator + output.points[(*removed_indices_)[rii]].x = output.points[(*removed_indices_)[rii]].y = output.points[(*removed_indices_)[rii]].z = user_filter_value_; + if (!pcl_isfinite (user_filter_value_)) + output.is_dense = false; + } + else + { + applyFilterIndices (indices); + copyPointCloud (*input_, indices, output); + } +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::StatisticalOutlierRemoval::applyFilterIndices (std::vector &indices) +{ + int search_state = 0; + + // Initialize the search class + if (!searcher_) + { + if (input_->isOrganized ()) + searcher_.reset (new pcl::search::OrganizedNeighbor ()); + else + searcher_.reset (new pcl::search::KdTree (false)); + } + + searcher_->setInputCloud (input_); + + // The arrays to be used + std::vector nn_indices (mean_k_); + std::vector nn_dists (mean_k_); + std::vector distances (indices_->size ()); + indices.resize (indices_->size ()); + removed_indices_->resize (indices_->size ()); + int oii = 0, rii = 0; // oii = output indices iterator, rii = removed indices iterator + + // First pass: Compute the mean distances for all points with respect to their k nearest neighbors + int valid_distances = 0; + for (int iii = 0; iii < static_cast (indices_->size ()); ++iii) // iii = input indices iterator + { + if (!pcl_isfinite (input_->points[(*indices_)[iii]].x) || + !pcl_isfinite (input_->points[(*indices_)[iii]].y) || + !pcl_isfinite (input_->points[(*indices_)[iii]].z)) + { + distances[iii] = 0.0; + continue; + } + + search_state = searcher_->nearestKSearch ((*indices_)[iii], mean_k_ + 1, nn_indices, nn_dists); + + // Perform the nearest k search + if (search_state == 0) + { + distances[iii] = 0.0; + PCL_WARN ("[pcl::%s::applyFilter] Searching for the closest %d neighbors failed.\n", getClassName ().c_str (), mean_k_); + continue; + } + + // Calculate the mean distance to its neighbors + double dist_sum = 0.0; + for (int k = 1; k < mean_k_ + 1; ++k) // k = 0 is the query point + dist_sum += sqrt (nn_dists[k]); + distances[iii] = static_cast (dist_sum / mean_k_); + valid_distances++; + } + + // Estimate the mean and the standard deviation of the distance vector + double sum = 0, sq_sum = 0; + for (size_t i = 0; i < distances.size (); ++i) + { + sum += distances[i]; + sq_sum += distances[i] * distances[i]; + } + double mean = sum / static_cast(valid_distances); + double variance = (sq_sum - sum * sum / static_cast(valid_distances)) / (static_cast(valid_distances) - 1); + double stddev = sqrt (variance); + //getMeanStd (distances, mean, stddev); + + double distance_threshold = mean + std_mul_ * stddev; + + // Second pass: Classify the points on the computed distance threshold + for (int iii = 0; iii < static_cast (indices_->size ()); ++iii) // iii = input indices iterator + { + // Points having a too high average distance are outliers and are passed to removed indices + // Unless negative was set, then it's the opposite condition + if ((!negative_ && distances[iii] > distance_threshold) || (negative_ && distances[iii] <= distance_threshold)) + { + if (extract_removed_indices_) + (*removed_indices_)[rii++] = (*indices_)[iii]; + continue; + } + + // Otherwise it was a normal point for output (inlier) + indices[oii++] = (*indices_)[iii]; + } + + // Resize the output arrays + indices.resize (oii); + removed_indices_->resize (rii); +} + +#define PCL_INSTANTIATE_StatisticalOutlierRemoval(T) template class PCL_EXPORTS pcl::StatisticalOutlierRemoval; + +#endif // PCL_FILTERS_IMPL_STATISTICAL_OUTLIER_REMOVAL_H_ + diff --git a/pcl-1.7/pcl/filters/impl/voxel_grid.hpp b/pcl-1.7/pcl/filters/impl/voxel_grid.hpp new file mode 100644 index 0000000..00677aa --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/voxel_grid.hpp @@ -0,0 +1,499 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_IMPL_VOXEL_GRID_H_ +#define PCL_FILTERS_IMPL_VOXEL_GRID_H_ + +#include +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::getMinMax3D (const typename pcl::PointCloud::ConstPtr &cloud, + const std::string &distance_field_name, float min_distance, float max_distance, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative) +{ + Eigen::Array4f min_p, max_p; + min_p.setConstant (FLT_MAX); + max_p.setConstant (-FLT_MAX); + + // Get the fields list and the distance field index + std::vector fields; + int distance_idx = pcl::getFieldIndex (*cloud, distance_field_name, fields); + + float distance_value; + // If dense, no need to check for NaNs + if (cloud->is_dense) + { + for (size_t i = 0; i < cloud->points.size (); ++i) + { + // Get the distance value + const uint8_t* pt_data = reinterpret_cast (&cloud->points[i]); + memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float)); + + if (limit_negative) + { + // Use a threshold for cutting out points which inside the interval + if ((distance_value < max_distance) && (distance_value > min_distance)) + continue; + } + else + { + // Use a threshold for cutting out points which are too close/far away + if ((distance_value > max_distance) || (distance_value < min_distance)) + continue; + } + // Create the point structure and get the min/max + pcl::Array4fMapConst pt = cloud->points[i].getArray4fMap (); + min_p = min_p.min (pt); + max_p = max_p.max (pt); + } + } + else + { + for (size_t i = 0; i < cloud->points.size (); ++i) + { + // Get the distance value + const uint8_t* pt_data = reinterpret_cast (&cloud->points[i]); + memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float)); + + if (limit_negative) + { + // Use a threshold for cutting out points which inside the interval + if ((distance_value < max_distance) && (distance_value > min_distance)) + continue; + } + else + { + // Use a threshold for cutting out points which are too close/far away + if ((distance_value > max_distance) || (distance_value < min_distance)) + continue; + } + + // Check if the point is invalid + if (!pcl_isfinite (cloud->points[i].x) || + !pcl_isfinite (cloud->points[i].y) || + !pcl_isfinite (cloud->points[i].z)) + continue; + // Create the point structure and get the min/max + pcl::Array4fMapConst pt = cloud->points[i].getArray4fMap (); + min_p = min_p.min (pt); + max_p = max_p.max (pt); + } + } + min_pt = min_p; + max_pt = max_p; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::getMinMax3D (const typename pcl::PointCloud::ConstPtr &cloud, + const std::vector &indices, + const std::string &distance_field_name, float min_distance, float max_distance, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative) +{ + Eigen::Array4f min_p, max_p; + min_p.setConstant (FLT_MAX); + max_p.setConstant (-FLT_MAX); + + // Get the fields list and the distance field index + std::vector fields; + int distance_idx = pcl::getFieldIndex (*cloud, distance_field_name, fields); + + float distance_value; + // If dense, no need to check for NaNs + if (cloud->is_dense) + { + for (std::vector::const_iterator it = indices.begin (); it != indices.end (); ++it) + { + // Get the distance value + const uint8_t* pt_data = reinterpret_cast (&cloud->points[*it]); + memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float)); + + if (limit_negative) + { + // Use a threshold for cutting out points which inside the interval + if ((distance_value < max_distance) && (distance_value > min_distance)) + continue; + } + else + { + // Use a threshold for cutting out points which are too close/far away + if ((distance_value > max_distance) || (distance_value < min_distance)) + continue; + } + // Create the point structure and get the min/max + pcl::Array4fMapConst pt = cloud->points[*it].getArray4fMap (); + min_p = min_p.min (pt); + max_p = max_p.max (pt); + } + } + else + { + for (std::vector::const_iterator it = indices.begin (); it != indices.end (); ++it) + { + // Get the distance value + const uint8_t* pt_data = reinterpret_cast (&cloud->points[*it]); + memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float)); + + if (limit_negative) + { + // Use a threshold for cutting out points which inside the interval + if ((distance_value < max_distance) && (distance_value > min_distance)) + continue; + } + else + { + // Use a threshold for cutting out points which are too close/far away + if ((distance_value > max_distance) || (distance_value < min_distance)) + continue; + } + + // Check if the point is invalid + if (!pcl_isfinite (cloud->points[*it].x) || + !pcl_isfinite (cloud->points[*it].y) || + !pcl_isfinite (cloud->points[*it].z)) + continue; + // Create the point structure and get the min/max + pcl::Array4fMapConst pt = cloud->points[*it].getArray4fMap (); + min_p = min_p.min (pt); + max_p = max_p.max (pt); + } + } + min_pt = min_p; + max_pt = max_p; +} + +struct cloud_point_index_idx +{ + unsigned int idx; + unsigned int cloud_point_index; + + cloud_point_index_idx (unsigned int idx_, unsigned int cloud_point_index_) : idx (idx_), cloud_point_index (cloud_point_index_) {} + bool operator < (const cloud_point_index_idx &p) const { return (idx < p.idx); } +}; + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::VoxelGrid::applyFilter (PointCloud &output) +{ + // Has the input dataset been set already? + if (!input_) + { + PCL_WARN ("[pcl::%s::applyFilter] No input dataset given!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + // Copy the header (and thus the frame_id) + allocate enough space for points + output.height = 1; // downsampling breaks the organized structure + output.is_dense = true; // we filter out invalid points + + Eigen::Vector4f min_p, max_p; + // Get the minimum and maximum dimensions + if (!filter_field_name_.empty ()) // If we don't want to process the entire cloud... + getMinMax3D (input_, *indices_, filter_field_name_, static_cast (filter_limit_min_), static_cast (filter_limit_max_), min_p, max_p, filter_limit_negative_); + else + getMinMax3D (*input_, *indices_, min_p, max_p); + + // Check that the leaf size is not too small, given the size of the data + int64_t dx = static_cast((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1; + int64_t dy = static_cast((max_p[1] - min_p[1]) * inverse_leaf_size_[1])+1; + int64_t dz = static_cast((max_p[2] - min_p[2]) * inverse_leaf_size_[2])+1; + + if ((dx*dy*dz) > static_cast(std::numeric_limits::max())) + { + PCL_WARN("[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.", getClassName().c_str()); + output = *input_; + return; + } + + // Compute the minimum and maximum bounding box values + min_b_[0] = static_cast (floor (min_p[0] * inverse_leaf_size_[0])); + max_b_[0] = static_cast (floor (max_p[0] * inverse_leaf_size_[0])); + min_b_[1] = static_cast (floor (min_p[1] * inverse_leaf_size_[1])); + max_b_[1] = static_cast (floor (max_p[1] * inverse_leaf_size_[1])); + min_b_[2] = static_cast (floor (min_p[2] * inverse_leaf_size_[2])); + max_b_[2] = static_cast (floor (max_p[2] * inverse_leaf_size_[2])); + + // Compute the number of divisions needed along all axis + div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones (); + div_b_[3] = 0; + + // Set up the division multiplier + divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0); + + int centroid_size = 4; + if (downsample_all_data_) + centroid_size = boost::mpl::size::value; + + // ---[ RGB special case + std::vector fields; + int rgba_index = -1; + rgba_index = pcl::getFieldIndex (*input_, "rgb", fields); + if (rgba_index == -1) + rgba_index = pcl::getFieldIndex (*input_, "rgba", fields); + if (rgba_index >= 0) + { + rgba_index = fields[rgba_index].offset; + centroid_size += 3; + } + + std::vector index_vector; + index_vector.reserve (indices_->size ()); + + // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first... + if (!filter_field_name_.empty ()) + { + // Get the distance field index + std::vector fields; + int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields); + if (distance_idx == -1) + PCL_WARN ("[pcl::%s::applyFilter] Invalid filter field name. Index is %d.\n", getClassName ().c_str (), distance_idx); + + // First pass: go over all points and insert them into the index_vector vector + // with calculated idx. Points with the same idx value will contribute to the + // same point of resulting CloudPoint + for (std::vector::const_iterator it = indices_->begin (); it != indices_->end (); ++it) + { + if (!input_->is_dense) + // Check if the point is invalid + if (!pcl_isfinite (input_->points[*it].x) || + !pcl_isfinite (input_->points[*it].y) || + !pcl_isfinite (input_->points[*it].z)) + continue; + + // Get the distance value + const uint8_t* pt_data = reinterpret_cast (&input_->points[*it]); + float distance_value = 0; + memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float)); + + if (filter_limit_negative_) + { + // Use a threshold for cutting out points which inside the interval + if ((distance_value < filter_limit_max_) && (distance_value > filter_limit_min_)) + continue; + } + else + { + // Use a threshold for cutting out points which are too close/far away + if ((distance_value > filter_limit_max_) || (distance_value < filter_limit_min_)) + continue; + } + + int ijk0 = static_cast (floor (input_->points[*it].x * inverse_leaf_size_[0]) - static_cast (min_b_[0])); + int ijk1 = static_cast (floor (input_->points[*it].y * inverse_leaf_size_[1]) - static_cast (min_b_[1])); + int ijk2 = static_cast (floor (input_->points[*it].z * inverse_leaf_size_[2]) - static_cast (min_b_[2])); + + // Compute the centroid leaf index + int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2]; + index_vector.push_back (cloud_point_index_idx (static_cast (idx), *it)); + } + } + // No distance filtering, process all data + else + { + // First pass: go over all points and insert them into the index_vector vector + // with calculated idx. Points with the same idx value will contribute to the + // same point of resulting CloudPoint + for (std::vector::const_iterator it = indices_->begin (); it != indices_->end (); ++it) + { + if (!input_->is_dense) + // Check if the point is invalid + if (!pcl_isfinite (input_->points[*it].x) || + !pcl_isfinite (input_->points[*it].y) || + !pcl_isfinite (input_->points[*it].z)) + continue; + + int ijk0 = static_cast (floor (input_->points[*it].x * inverse_leaf_size_[0]) - static_cast (min_b_[0])); + int ijk1 = static_cast (floor (input_->points[*it].y * inverse_leaf_size_[1]) - static_cast (min_b_[1])); + int ijk2 = static_cast (floor (input_->points[*it].z * inverse_leaf_size_[2]) - static_cast (min_b_[2])); + + // Compute the centroid leaf index + int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2]; + index_vector.push_back (cloud_point_index_idx (static_cast (idx), *it)); + } + } + + // Second pass: sort the index_vector vector using value representing target cell as index + // in effect all points belonging to the same output cell will be next to each other + std::sort (index_vector.begin (), index_vector.end (), std::less ()); + + // Third pass: count output cells + // we need to skip all the same, adjacenent idx values + unsigned int total = 0; + unsigned int index = 0; + // first_and_last_indices_vector[i] represents the index in index_vector of the first point in + // index_vector belonging to the voxel which corresponds to the i-th output point, + // and of the first point not belonging to. + std::vector > first_and_last_indices_vector; + // Worst case size + first_and_last_indices_vector.reserve (index_vector.size ()); + while (index < index_vector.size ()) + { + unsigned int i = index + 1; + while (i < index_vector.size () && index_vector[i].idx == index_vector[index].idx) + ++i; + if (i - index >= min_points_per_voxel_) + { + ++total; + first_and_last_indices_vector.push_back (std::pair (index, i)); + } + index = i; + } + + // Fourth pass: compute centroids, insert them into their final position + output.points.resize (total); + if (save_leaf_layout_) + { + try + { + // Resizing won't reset old elements to -1. If leaf_layout_ has been used previously, it needs to be re-initialized to -1 + uint32_t new_layout_size = div_b_[0]*div_b_[1]*div_b_[2]; + //This is the number of elements that need to be re-initialized to -1 + uint32_t reinit_size = std::min (static_cast (new_layout_size), static_cast (leaf_layout_.size())); + for (uint32_t i = 0; i < reinit_size; i++) + { + leaf_layout_[i] = -1; + } + leaf_layout_.resize (new_layout_size, -1); + } + catch (std::bad_alloc&) + { + throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout", + "voxel_grid.hpp", "applyFilter"); + } + catch (std::length_error&) + { + throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout", + "voxel_grid.hpp", "applyFilter"); + } + } + + index = 0; + Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size); + Eigen::VectorXf temporary = Eigen::VectorXf::Zero (centroid_size); + + for (unsigned int cp = 0; cp < first_and_last_indices_vector.size (); ++cp) + { + // calculate centroid - sum values from all input points, that have the same idx value in index_vector array + unsigned int first_index = first_and_last_indices_vector[cp].first; + unsigned int last_index = first_and_last_indices_vector[cp].second; + if (!downsample_all_data_) + { + centroid[0] = input_->points[index_vector[first_index].cloud_point_index].x; + centroid[1] = input_->points[index_vector[first_index].cloud_point_index].y; + centroid[2] = input_->points[index_vector[first_index].cloud_point_index].z; + } + else + { + // ---[ RGB special case + if (rgba_index >= 0) + { + // Fill r/g/b data, assuming that the order is BGRA + pcl::RGB rgb; + memcpy (&rgb, reinterpret_cast (&input_->points[index_vector[first_index].cloud_point_index]) + rgba_index, sizeof (RGB)); + centroid[centroid_size-3] = rgb.r; + centroid[centroid_size-2] = rgb.g; + centroid[centroid_size-1] = rgb.b; + } + pcl::for_each_type (NdCopyPointEigenFunctor (input_->points[index_vector[first_index].cloud_point_index], centroid)); + } + + for (unsigned int i = first_index + 1; i < last_index; ++i) + { + if (!downsample_all_data_) + { + centroid[0] += input_->points[index_vector[i].cloud_point_index].x; + centroid[1] += input_->points[index_vector[i].cloud_point_index].y; + centroid[2] += input_->points[index_vector[i].cloud_point_index].z; + } + else + { + // ---[ RGB special case + if (rgba_index >= 0) + { + // Fill r/g/b data, assuming that the order is BGRA + pcl::RGB rgb; + memcpy (&rgb, reinterpret_cast (&input_->points[index_vector[i].cloud_point_index]) + rgba_index, sizeof (RGB)); + temporary[centroid_size-3] = rgb.r; + temporary[centroid_size-2] = rgb.g; + temporary[centroid_size-1] = rgb.b; + } + pcl::for_each_type (NdCopyPointEigenFunctor (input_->points[index_vector[i].cloud_point_index], temporary)); + centroid += temporary; + } + } + + // index is centroid final position in resulting PointCloud + if (save_leaf_layout_) + leaf_layout_[index_vector[first_index].idx] = index; + + centroid /= static_cast (last_index - first_index); + + // store centroid + // Do we need to process all the fields? + if (!downsample_all_data_) + { + output.points[index].x = centroid[0]; + output.points[index].y = centroid[1]; + output.points[index].z = centroid[2]; + } + else + { + pcl::for_each_type (pcl::NdCopyEigenPointFunctor (centroid, output.points[index])); + // ---[ RGB special case + if (rgba_index >= 0) + { + // pack r/g/b into rgb + float r = centroid[centroid_size-3], g = centroid[centroid_size-2], b = centroid[centroid_size-1]; + int rgb = (static_cast (r) << 16) | (static_cast (g) << 8) | static_cast (b); + memcpy (reinterpret_cast (&output.points[index]) + rgba_index, &rgb, sizeof (float)); + } + } + ++index; + } + output.width = static_cast (output.points.size ()); +} + +#define PCL_INSTANTIATE_VoxelGrid(T) template class PCL_EXPORTS pcl::VoxelGrid; +#define PCL_INSTANTIATE_getMinMax3D(T) template PCL_EXPORTS void pcl::getMinMax3D (const pcl::PointCloud::ConstPtr &, const std::string &, float, float, Eigen::Vector4f &, Eigen::Vector4f &, bool); + +#endif // PCL_FILTERS_IMPL_VOXEL_GRID_H_ + diff --git a/pcl-1.7/pcl/filters/impl/voxel_grid_covariance.hpp b/pcl-1.7/pcl/filters/impl/voxel_grid_covariance.hpp new file mode 100644 index 0000000..b82ba2b --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/voxel_grid_covariance.hpp @@ -0,0 +1,447 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_VOXEL_GRID_COVARIANCE_IMPL_H_ +#define PCL_VOXEL_GRID_COVARIANCE_IMPL_H_ + +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::VoxelGridCovariance::applyFilter (PointCloud &output) +{ + voxel_centroids_leaf_indices_.clear (); + + // Has the input dataset been set already? + if (!input_) + { + PCL_WARN ("[pcl::%s::applyFilter] No input dataset given!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + // Copy the header (and thus the frame_id) + allocate enough space for points + output.height = 1; // downsampling breaks the organized structure + output.is_dense = true; // we filter out invalid points + output.points.clear (); + + Eigen::Vector4f min_p, max_p; + // Get the minimum and maximum dimensions + if (!filter_field_name_.empty ()) // If we don't want to process the entire cloud... + getMinMax3D (input_, filter_field_name_, static_cast (filter_limit_min_), static_cast (filter_limit_max_), min_p, max_p, filter_limit_negative_); + else + getMinMax3D (*input_, min_p, max_p); + + // Check that the leaf size is not too small, given the size of the data + int64_t dx = static_cast((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1; + int64_t dy = static_cast((max_p[1] - min_p[1]) * inverse_leaf_size_[1])+1; + int64_t dz = static_cast((max_p[2] - min_p[2]) * inverse_leaf_size_[2])+1; + + if((dx*dy*dz) > std::numeric_limits::max()) + { + PCL_WARN("[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.", getClassName().c_str()); + output.clear(); + return; + } + + // Compute the minimum and maximum bounding box values + min_b_[0] = static_cast (floor (min_p[0] * inverse_leaf_size_[0])); + max_b_[0] = static_cast (floor (max_p[0] * inverse_leaf_size_[0])); + min_b_[1] = static_cast (floor (min_p[1] * inverse_leaf_size_[1])); + max_b_[1] = static_cast (floor (max_p[1] * inverse_leaf_size_[1])); + min_b_[2] = static_cast (floor (min_p[2] * inverse_leaf_size_[2])); + max_b_[2] = static_cast (floor (max_p[2] * inverse_leaf_size_[2])); + + // Compute the number of divisions needed along all axis + div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones (); + div_b_[3] = 0; + + // Clear the leaves + leaves_.clear (); + + // Set up the division multiplier + divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0); + + int centroid_size = 4; + + if (downsample_all_data_) + centroid_size = boost::mpl::size::value; + + // ---[ RGB special case + std::vector fields; + int rgba_index = -1; + rgba_index = pcl::getFieldIndex (*input_, "rgb", fields); + if (rgba_index == -1) + rgba_index = pcl::getFieldIndex (*input_, "rgba", fields); + if (rgba_index >= 0) + { + rgba_index = fields[rgba_index].offset; + centroid_size += 3; + } + + // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first... + if (!filter_field_name_.empty ()) + { + // Get the distance field index + std::vector fields; + int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields); + if (distance_idx == -1) + PCL_WARN ("[pcl::%s::applyFilter] Invalid filter field name. Index is %d.\n", getClassName ().c_str (), distance_idx); + + // First pass: go over all points and insert them into the right leaf + for (size_t cp = 0; cp < input_->points.size (); ++cp) + { + if (!input_->is_dense) + // Check if the point is invalid + if (!pcl_isfinite (input_->points[cp].x) || + !pcl_isfinite (input_->points[cp].y) || + !pcl_isfinite (input_->points[cp].z)) + continue; + + // Get the distance value + const uint8_t* pt_data = reinterpret_cast (&input_->points[cp]); + float distance_value = 0; + memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float)); + + if (filter_limit_negative_) + { + // Use a threshold for cutting out points which inside the interval + if ((distance_value < filter_limit_max_) && (distance_value > filter_limit_min_)) + continue; + } + else + { + // Use a threshold for cutting out points which are too close/far away + if ((distance_value > filter_limit_max_) || (distance_value < filter_limit_min_)) + continue; + } + + int ijk0 = static_cast (floor (input_->points[cp].x * inverse_leaf_size_[0]) - static_cast (min_b_[0])); + int ijk1 = static_cast (floor (input_->points[cp].y * inverse_leaf_size_[1]) - static_cast (min_b_[1])); + int ijk2 = static_cast (floor (input_->points[cp].z * inverse_leaf_size_[2]) - static_cast (min_b_[2])); + + // Compute the centroid leaf index + int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2]; + + Leaf& leaf = leaves_[idx]; + if (leaf.nr_points == 0) + { + leaf.centroid.resize (centroid_size); + leaf.centroid.setZero (); + } + + Eigen::Vector3d pt3d (input_->points[cp].x, input_->points[cp].y, input_->points[cp].z); + // Accumulate point sum for centroid calculation + leaf.mean_ += pt3d; + // Accumulate x*xT for single pass covariance calculation + leaf.cov_ += pt3d * pt3d.transpose (); + + // Do we need to process all the fields? + if (!downsample_all_data_) + { + Eigen::Vector4f pt (input_->points[cp].x, input_->points[cp].y, input_->points[cp].z, 0); + leaf.centroid.template head<4> () += pt; + } + else + { + // Copy all the fields + Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size); + // ---[ RGB special case + if (rgba_index >= 0) + { + // fill r/g/b data + int rgb; + memcpy (&rgb, reinterpret_cast (&input_->points[cp]) + rgba_index, sizeof (int)); + centroid[centroid_size - 3] = static_cast ((rgb >> 16) & 0x0000ff); + centroid[centroid_size - 2] = static_cast ((rgb >> 8) & 0x0000ff); + centroid[centroid_size - 1] = static_cast ((rgb) & 0x0000ff); + } + pcl::for_each_type (NdCopyPointEigenFunctor (input_->points[cp], centroid)); + leaf.centroid += centroid; + } + ++leaf.nr_points; + } + } + // No distance filtering, process all data + else + { + // First pass: go over all points and insert them into the right leaf + for (size_t cp = 0; cp < input_->points.size (); ++cp) + { + if (!input_->is_dense) + // Check if the point is invalid + if (!pcl_isfinite (input_->points[cp].x) || + !pcl_isfinite (input_->points[cp].y) || + !pcl_isfinite (input_->points[cp].z)) + continue; + + int ijk0 = static_cast (floor (input_->points[cp].x * inverse_leaf_size_[0]) - static_cast (min_b_[0])); + int ijk1 = static_cast (floor (input_->points[cp].y * inverse_leaf_size_[1]) - static_cast (min_b_[1])); + int ijk2 = static_cast (floor (input_->points[cp].z * inverse_leaf_size_[2]) - static_cast (min_b_[2])); + + // Compute the centroid leaf index + int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2]; + + //int idx = (((input_->points[cp].getArray4fmap () * inverse_leaf_size_).template cast ()).matrix () - min_b_).dot (divb_mul_); + Leaf& leaf = leaves_[idx]; + if (leaf.nr_points == 0) + { + leaf.centroid.resize (centroid_size); + leaf.centroid.setZero (); + } + + Eigen::Vector3d pt3d (input_->points[cp].x, input_->points[cp].y, input_->points[cp].z); + // Accumulate point sum for centroid calculation + leaf.mean_ += pt3d; + // Accumulate x*xT for single pass covariance calculation + leaf.cov_ += pt3d * pt3d.transpose (); + + // Do we need to process all the fields? + if (!downsample_all_data_) + { + Eigen::Vector4f pt (input_->points[cp].x, input_->points[cp].y, input_->points[cp].z, 0); + leaf.centroid.template head<4> () += pt; + } + else + { + // Copy all the fields + Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size); + // ---[ RGB special case + if (rgba_index >= 0) + { + // Fill r/g/b data, assuming that the order is BGRA + int rgb; + memcpy (&rgb, reinterpret_cast (&input_->points[cp]) + rgba_index, sizeof (int)); + centroid[centroid_size - 3] = static_cast ((rgb >> 16) & 0x0000ff); + centroid[centroid_size - 2] = static_cast ((rgb >> 8) & 0x0000ff); + centroid[centroid_size - 1] = static_cast ((rgb) & 0x0000ff); + } + pcl::for_each_type (NdCopyPointEigenFunctor (input_->points[cp], centroid)); + leaf.centroid += centroid; + } + ++leaf.nr_points; + } + } + + // Second pass: go over all leaves and compute centroids and covariance matrices + output.points.reserve (leaves_.size ()); + if (searchable_) + voxel_centroids_leaf_indices_.reserve (leaves_.size ()); + int cp = 0; + if (save_leaf_layout_) + leaf_layout_.resize (div_b_[0] * div_b_[1] * div_b_[2], -1); + + // Eigen values and vectors calculated to prevent near singluar matrices + Eigen::SelfAdjointEigenSolver eigensolver; + Eigen::Matrix3d eigen_val; + Eigen::Vector3d pt_sum; + + // Eigen values less than a threshold of max eigen value are inflated to a set fraction of the max eigen value. + double min_covar_eigvalue; + + for (typename std::map::iterator it = leaves_.begin (); it != leaves_.end (); ++it) + { + + // Normalize the centroid + Leaf& leaf = it->second; + + // Normalize the centroid + leaf.centroid /= static_cast (leaf.nr_points); + // Point sum used for single pass covariance calculation + pt_sum = leaf.mean_; + // Normalize mean + leaf.mean_ /= leaf.nr_points; + + // If the voxel contains sufficient points, its covariance is calculated and is added to the voxel centroids and output clouds. + // Points with less than the minimum points will have a can not be accuratly approximated using a normal distribution. + if (leaf.nr_points >= min_points_per_voxel_) + { + if (save_leaf_layout_) + leaf_layout_[it->first] = cp++; + + output.push_back (PointT ()); + + // Do we need to process all the fields? + if (!downsample_all_data_) + { + output.points.back ().x = leaf.centroid[0]; + output.points.back ().y = leaf.centroid[1]; + output.points.back ().z = leaf.centroid[2]; + } + else + { + pcl::for_each_type (pcl::NdCopyEigenPointFunctor (leaf.centroid, output.back ())); + // ---[ RGB special case + if (rgba_index >= 0) + { + // pack r/g/b into rgb + float r = leaf.centroid[centroid_size - 3], g = leaf.centroid[centroid_size - 2], b = leaf.centroid[centroid_size - 1]; + int rgb = (static_cast (r)) << 16 | (static_cast (g)) << 8 | (static_cast (b)); + memcpy (reinterpret_cast (&output.points.back ()) + rgba_index, &rgb, sizeof (float)); + } + } + + // Stores the voxel indice for fast access searching + if (searchable_) + voxel_centroids_leaf_indices_.push_back (static_cast (it->first)); + + // Single pass covariance calculation + leaf.cov_ = (leaf.cov_ - 2 * (pt_sum * leaf.mean_.transpose ())) / leaf.nr_points + leaf.mean_ * leaf.mean_.transpose (); + leaf.cov_ *= (leaf.nr_points - 1.0) / leaf.nr_points; + + //Normalize Eigen Val such that max no more than 100x min. + eigensolver.compute (leaf.cov_); + eigen_val = eigensolver.eigenvalues ().asDiagonal (); + leaf.evecs_ = eigensolver.eigenvectors (); + + if (eigen_val (0, 0) < 0 || eigen_val (1, 1) < 0 || eigen_val (2, 2) <= 0) + { + leaf.nr_points = -1; + continue; + } + + // Avoids matrices near singularities (eq 6.11)[Magnusson 2009] + + min_covar_eigvalue = min_covar_eigvalue_mult_ * eigen_val (2, 2); + if (eigen_val (0, 0) < min_covar_eigvalue) + { + eigen_val (0, 0) = min_covar_eigvalue; + + if (eigen_val (1, 1) < min_covar_eigvalue) + { + eigen_val (1, 1) = min_covar_eigvalue; + } + + leaf.cov_ = leaf.evecs_ * eigen_val * leaf.evecs_.inverse (); + } + leaf.evals_ = eigen_val.diagonal (); + + leaf.icov_ = leaf.cov_.inverse (); + if (leaf.icov_.maxCoeff () == std::numeric_limits::infinity ( ) + || leaf.icov_.minCoeff () == -std::numeric_limits::infinity ( ) ) + { + leaf.nr_points = -1; + } + + } + } + + output.width = static_cast (output.points.size ()); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::VoxelGridCovariance::getNeighborhoodAtPoint (const PointT& reference_point, std::vector &neighbors) +{ + neighbors.clear (); + + // Find displacement coordinates + Eigen::MatrixXi relative_coordinates = pcl::getAllNeighborCellIndices (); + Eigen::Vector4i ijk (static_cast (floor (reference_point.x / leaf_size_[0])), + static_cast (floor (reference_point.y / leaf_size_[1])), + static_cast (floor (reference_point.z / leaf_size_[2])), 0); + Eigen::Array4i diff2min = min_b_ - ijk; + Eigen::Array4i diff2max = max_b_ - ijk; + neighbors.reserve (relative_coordinates.cols ()); + + // Check each neighbor to see if it is occupied and contains sufficient points + // Slower than radius search because needs to check 26 indices + for (int ni = 0; ni < relative_coordinates.cols (); ni++) + { + Eigen::Vector4i displacement = (Eigen::Vector4i () << relative_coordinates.col (ni), 0).finished (); + // Checking if the specified cell is in the grid + if ((diff2min <= displacement.array ()).all () && (diff2max >= displacement.array ()).all ()) + { + typename std::map::iterator leaf_iter = leaves_.find (((ijk + displacement - min_b_).dot (divb_mul_))); + if (leaf_iter != leaves_.end () && leaf_iter->second.nr_points >= min_points_per_voxel_) + { + LeafConstPtr leaf = &(leaf_iter->second); + neighbors.push_back (leaf); + } + } + } + + return (static_cast (neighbors.size ())); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::VoxelGridCovariance::getDisplayCloud (pcl::PointCloud& cell_cloud) +{ + cell_cloud.clear (); + + int pnt_per_cell = 1000; + boost::mt19937 rng; + boost::normal_distribution<> nd (0.0, leaf_size_.head (3).norm ()); + boost::variate_generator > var_nor (rng, nd); + + Eigen::LLT llt_of_cov; + Eigen::Matrix3d cholesky_decomp; + Eigen::Vector3d cell_mean; + Eigen::Vector3d rand_point; + Eigen::Vector3d dist_point; + + // Generate points for each occupied voxel with sufficient points. + for (typename std::map::iterator it = leaves_.begin (); it != leaves_.end (); ++it) + { + Leaf& leaf = it->second; + + if (leaf.nr_points >= min_points_per_voxel_) + { + cell_mean = leaf.mean_; + llt_of_cov.compute (leaf.cov_); + cholesky_decomp = llt_of_cov.matrixL (); + + // Random points generated by sampling the normal distribution given by voxel mean and covariance matrix + for (int i = 0; i < pnt_per_cell; i++) + { + rand_point = Eigen::Vector3d (var_nor (), var_nor (), var_nor ()); + dist_point = cell_mean + cholesky_decomp * rand_point; + cell_cloud.push_back (PointXYZ (static_cast (dist_point (0)), static_cast (dist_point (1)), static_cast (dist_point (2)))); + } + } + } +} + +#define PCL_INSTANTIATE_VoxelGridCovariance(T) template class PCL_EXPORTS pcl::VoxelGridCovariance; + +#endif // PCL_VOXEL_GRID_COVARIANCE_IMPL_H_ diff --git a/pcl-1.7/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp b/pcl-1.7/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp new file mode 100644 index 0000000..5e409aa --- /dev/null +++ b/pcl-1.7/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp @@ -0,0 +1,442 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : Christian Potthast + * Email : potthast@usc.edu + * + */ + +#ifndef PCL_FILTERS_IMPL_VOXEL_GRID_OCCLUSION_ESTIMATION_H_ +#define PCL_FILTERS_IMPL_VOXEL_GRID_OCCLUSION_ESTIMATION_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::VoxelGridOcclusionEstimation::initializeVoxelGrid () +{ + // initialization set to true + initialized_ = true; + + // create the voxel grid and store the output cloud + this->filter (filtered_cloud_); + + // Get the minimum and maximum bounding box dimensions + b_min_[0] = (static_cast ( min_b_[0]) * leaf_size_[0]); + b_min_[1] = (static_cast ( min_b_[1]) * leaf_size_[1]); + b_min_[2] = (static_cast ( min_b_[2]) * leaf_size_[2]); + b_max_[0] = (static_cast ( (max_b_[0]) + 1) * leaf_size_[0]); + b_max_[1] = (static_cast ( (max_b_[1]) + 1) * leaf_size_[1]); + b_max_[2] = (static_cast ( (max_b_[2]) + 1) * leaf_size_[2]); + + // set the sensor origin and sensor orientation + sensor_origin_ = filtered_cloud_.sensor_origin_; + sensor_orientation_ = filtered_cloud_.sensor_orientation_; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::VoxelGridOcclusionEstimation::occlusionEstimation (int& out_state, + const Eigen::Vector3i& in_target_voxel) +{ + if (!initialized_) + { + PCL_ERROR ("Voxel grid not initialized; call initializeVoxelGrid () first! \n"); + return -1; + } + + // estimate direction to target voxel + Eigen::Vector4f p = getCentroidCoordinate (in_target_voxel); + Eigen::Vector4f direction = p - sensor_origin_; + direction.normalize (); + + // estimate entry point into the voxel grid + float tmin = rayBoxIntersection (sensor_origin_, direction); + + if (tmin == -1) + { + PCL_ERROR ("The ray does not intersect with the bounding box \n"); + return -1; + } + + // ray traversal + out_state = rayTraversal (in_target_voxel, sensor_origin_, direction, tmin); + + return 0; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::VoxelGridOcclusionEstimation::occlusionEstimation (int& out_state, + std::vector& out_ray, + const Eigen::Vector3i& in_target_voxel) +{ + if (!initialized_) + { + PCL_ERROR ("Voxel grid not initialized; call initializeVoxelGrid () first! \n"); + return -1; + } + + // estimate direction to target voxel + Eigen::Vector4f p = getCentroidCoordinate (in_target_voxel); + Eigen::Vector4f direction = p - sensor_origin_; + direction.normalize (); + + // estimate entry point into the voxel grid + float tmin = rayBoxIntersection (sensor_origin_, direction); + + if (tmin == -1) + { + PCL_ERROR ("The ray does not intersect with the bounding box \n"); + return -1; + } + + // ray traversal + out_state = rayTraversal (out_ray, in_target_voxel, sensor_origin_, direction, tmin); + + return 0; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::VoxelGridOcclusionEstimation::occlusionEstimationAll (std::vector& occluded_voxels) +{ + if (!initialized_) + { + PCL_ERROR ("Voxel grid not initialized; call initializeVoxelGrid () first! \n"); + return -1; + } + + // reserve space for the ray vector + int reserve_size = div_b_[0] * div_b_[1] * div_b_[2]; + occluded_voxels.reserve (reserve_size); + + // iterate over the entire voxel grid + for (int kk = min_b_.z (); kk <= max_b_.z (); ++kk) + for (int jj = min_b_.y (); jj <= max_b_.y (); ++jj) + for (int ii = min_b_.x (); ii <= max_b_.x (); ++ii) + { + Eigen::Vector3i ijk (ii, jj, kk); + // process all free voxels + int index = this->getCentroidIndexAt (ijk); + if (index == -1) + { + // estimate direction to target voxel + Eigen::Vector4f p = getCentroidCoordinate (ijk); + Eigen::Vector4f direction = p - sensor_origin_; + direction.normalize (); + + // estimate entry point into the voxel grid + float tmin = rayBoxIntersection (sensor_origin_, direction); + + // ray traversal + int state = rayTraversal (ijk, sensor_origin_, direction, tmin); + + // if voxel is occluded + if (state == 1) + occluded_voxels.push_back (ijk); + } + } + return 0; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::VoxelGridOcclusionEstimation::rayBoxIntersection (const Eigen::Vector4f& origin, + const Eigen::Vector4f& direction) +{ + float tmin, tmax, tymin, tymax, tzmin, tzmax; + + if (direction[0] >= 0) + { + tmin = (b_min_[0] - origin[0]) / direction[0]; + tmax = (b_max_[0] - origin[0]) / direction[0]; + } + else + { + tmin = (b_max_[0] - origin[0]) / direction[0]; + tmax = (b_min_[0] - origin[0]) / direction[0]; + } + + if (direction[1] >= 0) + { + tymin = (b_min_[1] - origin[1]) / direction[1]; + tymax = (b_max_[1] - origin[1]) / direction[1]; + } + else + { + tymin = (b_max_[1] - origin[1]) / direction[1]; + tymax = (b_min_[1] - origin[1]) / direction[1]; + } + + if ((tmin > tymax) || (tymin > tmax)) + { + PCL_ERROR ("no intersection with the bounding box \n"); + tmin = -1.0f; + return tmin; + } + + if (tymin > tmin) + tmin = tymin; + if (tymax < tmax) + tmax = tymax; + + if (direction[2] >= 0) + { + tzmin = (b_min_[2] - origin[2]) / direction[2]; + tzmax = (b_max_[2] - origin[2]) / direction[2]; + } + else + { + tzmin = (b_max_[2] - origin[2]) / direction[2]; + tzmax = (b_min_[2] - origin[2]) / direction[2]; + } + + if ((tmin > tzmax) || (tzmin > tmax)) + { + PCL_ERROR ("no intersection with the bounding box \n"); + tmin = -1.0f; + return tmin; + } + + if (tzmin > tmin) + tmin = tzmin; + if (tzmax < tmax) + tmax = tzmax; + + return tmin; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::VoxelGridOcclusionEstimation::rayTraversal (const Eigen::Vector3i& target_voxel, + const Eigen::Vector4f& origin, + const Eigen::Vector4f& direction, + const float t_min) +{ + // coordinate of the boundary of the voxel grid + Eigen::Vector4f start = origin + t_min * direction; + + // i,j,k coordinate of the voxel were the ray enters the voxel grid + Eigen::Vector3i ijk = getGridCoordinatesRound (start[0], start[1], start[2]); + + // steps in which direction we have to travel in the voxel grid + int step_x, step_y, step_z; + + // centroid coordinate of the entry voxel + Eigen::Vector4f voxel_max = getCentroidCoordinate (ijk); + + if (direction[0] >= 0) + { + voxel_max[0] += leaf_size_[0] * 0.5f; + step_x = 1; + } + else + { + voxel_max[0] -= leaf_size_[0] * 0.5f; + step_x = -1; + } + if (direction[1] >= 0) + { + voxel_max[1] += leaf_size_[1] * 0.5f; + step_y = 1; + } + else + { + voxel_max[1] -= leaf_size_[1] * 0.5f; + step_y = -1; + } + if (direction[2] >= 0) + { + voxel_max[2] += leaf_size_[2] * 0.5f; + step_z = 1; + } + else + { + voxel_max[2] -= leaf_size_[2] * 0.5f; + step_z = -1; + } + + float t_max_x = t_min + (voxel_max[0] - start[0]) / direction[0]; + float t_max_y = t_min + (voxel_max[1] - start[1]) / direction[1]; + float t_max_z = t_min + (voxel_max[2] - start[2]) / direction[2]; + + float t_delta_x = leaf_size_[0] / static_cast (fabs (direction[0])); + float t_delta_y = leaf_size_[1] / static_cast (fabs (direction[1])); + float t_delta_z = leaf_size_[2] / static_cast (fabs (direction[2])); + + // index of the point in the point cloud + int index; + + while ( (ijk[0] < max_b_[0]+1) && (ijk[0] >= min_b_[0]) && + (ijk[1] < max_b_[1]+1) && (ijk[1] >= min_b_[1]) && + (ijk[2] < max_b_[2]+1) && (ijk[2] >= min_b_[2]) ) + { + // check if we reached target voxel + if (ijk[0] == target_voxel[0] && ijk[1] == target_voxel[1] && ijk[2] == target_voxel[2]) + return 0; + + // check if voxel is occupied, if yes return 1 for occluded + index = this->getCentroidIndexAt (ijk); + if (index != -1) + return 1; + + // estimate next voxel + if(t_max_x <= t_max_y && t_max_x <= t_max_z) + { + t_max_x += t_delta_x; + ijk[0] += step_x; + } + else if(t_max_y <= t_max_z && t_max_y <= t_max_x) + { + t_max_y += t_delta_y; + ijk[1] += step_y; + } + else + { + t_max_z += t_delta_z; + ijk[2] += step_z; + } + } + return 0; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::VoxelGridOcclusionEstimation::rayTraversal (std::vector & out_ray, + const Eigen::Vector3i& target_voxel, + const Eigen::Vector4f& origin, + const Eigen::Vector4f& direction, + const float t_min) +{ + // reserve space for the ray vector + int reserve_size = div_b_.maxCoeff () * div_b_.maxCoeff (); + out_ray.reserve (reserve_size); + + // coordinate of the boundary of the voxel grid + Eigen::Vector4f start = origin + t_min * direction; + + // i,j,k coordinate of the voxel were the ray enters the voxel grid + Eigen::Vector3i ijk = getGridCoordinatesRound (start[0], start[1], start[2]); + //Eigen::Vector3i ijk = this->getGridCoordinates (start_x, start_y, start_z); + + // steps in which direction we have to travel in the voxel grid + int step_x, step_y, step_z; + + // centroid coordinate of the entry voxel + Eigen::Vector4f voxel_max = getCentroidCoordinate (ijk); + + if (direction[0] >= 0) + { + voxel_max[0] += leaf_size_[0] * 0.5f; + step_x = 1; + } + else + { + voxel_max[0] -= leaf_size_[0] * 0.5f; + step_x = -1; + } + if (direction[1] >= 0) + { + voxel_max[1] += leaf_size_[1] * 0.5f; + step_y = 1; + } + else + { + voxel_max[1] -= leaf_size_[1] * 0.5f; + step_y = -1; + } + if (direction[2] >= 0) + { + voxel_max[2] += leaf_size_[2] * 0.5f; + step_z = 1; + } + else + { + voxel_max[2] -= leaf_size_[2] * 0.5f; + step_z = -1; + } + + float t_max_x = t_min + (voxel_max[0] - start[0]) / direction[0]; + float t_max_y = t_min + (voxel_max[1] - start[1]) / direction[1]; + float t_max_z = t_min + (voxel_max[2] - start[2]) / direction[2]; + + float t_delta_x = leaf_size_[0] / static_cast (fabs (direction[0])); + float t_delta_y = leaf_size_[1] / static_cast (fabs (direction[1])); + float t_delta_z = leaf_size_[2] / static_cast (fabs (direction[2])); + + // the index of the cloud (-1 if empty) + int index = -1; + int result = 0; + + while ( (ijk[0] < max_b_[0]+1) && (ijk[0] >= min_b_[0]) && + (ijk[1] < max_b_[1]+1) && (ijk[1] >= min_b_[1]) && + (ijk[2] < max_b_[2]+1) && (ijk[2] >= min_b_[2]) ) + { + // add voxel to ray + out_ray.push_back (ijk); + + // check if we reached target voxel + if (ijk[0] == target_voxel[0] && ijk[1] == target_voxel[1] && ijk[2] == target_voxel[2]) + break; + + // check if voxel is occupied + index = this->getCentroidIndexAt (ijk); + if (index != -1) + result = 1; + + // estimate next voxel + if(t_max_x <= t_max_y && t_max_x <= t_max_z) + { + t_max_x += t_delta_x; + ijk[0] += step_x; + } + else if(t_max_y <= t_max_z && t_max_y <= t_max_x) + { + t_max_y += t_delta_y; + ijk[1] += step_y; + } + else + { + t_max_z += t_delta_z; + ijk[2] += step_z; + } + } + return result; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +#define PCL_INSTANTIATE_VoxelGridOcclusionEstimation(T) template class PCL_EXPORTS pcl::VoxelGridOcclusionEstimation; + +#endif // PCL_FILTERS_IMPL_VOXEL_GRID_OCCLUSION_ESTIMATION_H_ diff --git a/pcl-1.7/pcl/filters/local_maximum.h b/pcl-1.7/pcl/filters/local_maximum.h new file mode 100644 index 0000000..8a8cf28 --- /dev/null +++ b/pcl-1.7/pcl/filters/local_maximum.h @@ -0,0 +1,133 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2014, RadiantBlue Technologies, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_LOCAL_MAXIMUM_H_ +#define PCL_FILTERS_LOCAL_MAXIMUM_H_ + +#include +#include + +namespace pcl +{ + /** \brief LocalMaximum downsamples the cloud, by eliminating points that are locally maximal. + * + * The LocalMaximum class analyzes each point and removes those that are + * found to be locally maximal with respect to their neighbors (found via + * radius search). The comparison is made in the z dimension only at this + * time. + * + * \author Bradley J Chambers + * \ingroup filters + */ + template + class LocalMaximum: public FilterIndices + { + protected: + typedef typename FilterIndices::PointCloud PointCloud; + typedef typename pcl::search::Search::Ptr SearcherPtr; + + public: + /** \brief Empty constructor. */ + LocalMaximum (bool extract_removed_indices = false) : + FilterIndices::FilterIndices (extract_removed_indices), + searcher_ (), + radius_ (1) + { + filter_name_ = "LocalMaximum"; + } + + /** \brief Set the radius to use to determine if a point is the local max. + * \param[in] radius The radius to use to determine if a point is the local max. + */ + inline void + setRadius (float radius) { radius_ = radius; } + + /** \brief Get the radius to use to determine if a point is the local max. + * \return The radius to use to determine if a point is the local max. + */ + inline float + getRadius () const { return (radius_); } + + protected: + using PCLBase::input_; + using PCLBase::indices_; + using Filter::filter_name_; + using Filter::getClassName; + using FilterIndices::negative_; + using FilterIndices::extract_removed_indices_; + using FilterIndices::removed_indices_; + + /** \brief Downsample a Point Cloud by eliminating points that are locally maximal in z + * \param[out] output the resultant point cloud message + */ + void + applyFilter (PointCloud &output); + + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. + */ + void + applyFilter (std::vector &indices) + { + applyFilterIndices (indices); + } + + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. + */ + void + applyFilterIndices (std::vector &indices); + + private: + /** \brief A pointer to the spatial search object. */ + SearcherPtr searcher_; + + /** \brief The radius to use to determine if a point is the local max. */ + float radius_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FILTERS_LOCAL_MAXIMUM_H_ + diff --git a/pcl-1.7/pcl/filters/median_filter.h b/pcl-1.7/pcl/filters/median_filter.h new file mode 100644 index 0000000..8937882 --- /dev/null +++ b/pcl-1.7/pcl/filters/median_filter.h @@ -0,0 +1,119 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + + * All rights reserved. + + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + + +#ifndef PCL_FILTERS_MEDIAN_FILTER_H_ +#define PCL_FILTERS_MEDIAN_FILTER_H_ + +#include + +namespace pcl +{ + /** \brief Implementation of the median filter. + * The median filter is one of the simplest and wide-spread image processing filters. It is known to perform well + * with "shot"/impulse noise (some individual pixels having extreme values), it does not reduce contrast across steps + * in the function (as compared to filters based on averaging), and it is robust to outliers. Furthermore, it is + * simple to implement and efficient, as it requires a single pass over the image. It consists of a moving window of + * fixed size that replaces the pixel in the center with the median inside the window. + * + * \note This algorithm filters only the depth (z-component) of _organized_ and untransformed (i.e., in camera coordinates) + * point clouds. An error will be outputted if an unorganized cloud is given to the class instance. + * + * \author Alexandru E. Ichim + * \ingroup filters + */ + template + class MedianFilter : public pcl::Filter + { + using pcl::Filter::input_; + typedef typename pcl::Filter::PointCloud PointCloud; + + public: + /** \brief Empty constructor. */ + MedianFilter () + : window_size_ (5) + , max_allowed_movement_ (std::numeric_limits::max ()) + { } + + /** \brief Set the window size of the filter. + * \param[in] window_size the new window size + */ + inline void + setWindowSize (int window_size) + { window_size_ = window_size; } + + /** \brief Get the window size of the filter. + * \returns the window size of the filter + */ + inline int + getWindowSize () const + { return window_size_; } + + /** \brief Set the largest value one dexel is allowed to move + * \param[in] max_allowed_movement maximum value a dexel is allowed to move during filtering + */ + inline void + setMaxAllowedMovement (float max_allowed_movement) + { max_allowed_movement_ = max_allowed_movement; } + + /** \brief Get the maximum distance one point is allowed to move along the z-axis. + * \returns the maximum distance a dexel is allowed to move + */ + inline float + getMaxAllowedMovement () const + { return max_allowed_movement_; } + + /** \brief Filter the input data and store the results into output. + * \param[out] output the result point cloud + */ + void + applyFilter (PointCloud &output); + + protected: + int window_size_; + float max_allowed_movement_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#else +#define PCL_INSTANTIATE_MedianFilter(T) template class PCL_EXPORTS pcl::MedianFilter; +#endif +#endif /* PCL_FILTERS_MEDIAN_FILTER_H_ */ diff --git a/pcl-1.7/pcl/filters/model_outlier_removal.h b/pcl-1.7/pcl/filters/model_outlier_removal.h new file mode 100644 index 0000000..b513ffc --- /dev/null +++ b/pcl-1.7/pcl/filters/model_outlier_removal.h @@ -0,0 +1,257 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_FILTERS_MODEL_OUTLIER_REMOVAL_H_ +#define PCL_FILTERS_MODEL_OUTLIER_REMOVAL_H_ + +#include +#include + +// Sample Consensus models +#include +#include + +namespace pcl +{ + /** \brief @b ModelOutlierRemoval filters points in a cloud based on the distance between model and point. + * \details Iterates through the entire input once, automatically filtering non-finite points and the points outside + * the model specified by setSampleConsensusModelPointer() and the threshold specified by setThreholdFunctionPointer(). + *

+ * Usage example: + * \code + * pcl::ModelCoefficients model_coeff; + * model_coeff.values.resize(4); + * model_coeff.values[0] = 0; model_coeff.values[1] = 0; model_coeff.values[2] = 1.5; model_coeff.values[3] = 0.5; + * pcl::ModelOutlierRemoval filter; + * filter.setModelCoefficients (model_coeff); + * filter.setThreshold (0.1); + * filter.setModelType (pcl::SACMODEL_PLANE); + * filter.setInputCloud (*cloud_in); + * filter.setFilterLimitsNegative (false); + * filter.filter (*cloud_out); + * \endcode + */ + template + class ModelOutlierRemoval : public FilterIndices + { + protected: + typedef typename FilterIndices::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + typedef typename SampleConsensusModel::Ptr SampleConsensusModelPtr; + + public: + typedef typename pcl::PointCloud::Ptr PointCloudNPtr; + typedef typename pcl::PointCloud::ConstPtr PointCloudNConstPtr; + + /** \brief Constructor. + * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false). + */ + inline + ModelOutlierRemoval (bool extract_removed_indices = false) : + FilterIndices::FilterIndices (extract_removed_indices) + { + thresh_ = 0; + normals_distance_weight_ = 0; + filter_name_ = "ModelOutlierRemoval"; + setThresholdFunction (&pcl::ModelOutlierRemoval::checkSingleThreshold, *this); + } + + /** \brief sets the models coefficients */ + inline void + setModelCoefficients (const pcl::ModelCoefficients model_coefficients) + { + model_coefficients_.resize (model_coefficients.values.size ()); + for (unsigned int i = 0; i < model_coefficients.values.size (); i++) + { + model_coefficients_[i] = model_coefficients.values[i]; + } + } + + /** \brief returns the models coefficients + */ + inline pcl::ModelCoefficients + getModelCoefficients () const + { + pcl::ModelCoefficients mc; + mc.values.resize (model_coefficients_.size ()); + for (unsigned int i = 0; i < mc.values.size (); i++) + mc.values[i] = model_coefficients_[i]; + return (mc); + } + + /** \brief Set the type of SAC model used. */ + inline void + setModelType (pcl::SacModel model) + { + model_type_ = model; + } + + /** \brief Get the type of SAC model used. */ + inline pcl::SacModel + getModelType () const + { + return (model_type_); + } + + /** \brief Set the thresholdfunction*/ + inline void + setThreshold (float thresh) + { + thresh_ = thresh; + } + + /** \brief Get the thresholdfunction*/ + inline float + getThreshold () const + { + return (thresh_); + } + + /** \brief Set the normals cloud*/ + inline void + setInputNormals (const PointCloudNConstPtr normals_ptr) + { + cloud_normals_ = normals_ptr; + } + + /** \brief Get the normals cloud*/ + inline PointCloudNConstPtr + getInputNormals () const + { + return (cloud_normals_); + } + + /** \brief Set the normals distance weight*/ + inline void + setNormalDistanceWeight (const double weight) + { + normals_distance_weight_ = weight; + } + + /** \brief get the normal distance weight*/ + inline double + getNormalDistanceWeight () const + { + return (normals_distance_weight_); + } + + /** \brief Register a different threshold function + * \param[in] pointer to a threshold function + */ + void + setThresholdFunction (boost::function thresh) + { + threshold_function_ = thresh; + } + + /** \brief Register a different threshold function + * \param[in] pointer to a threshold function + * \param[in] instance + */ + template void + setThresholdFunction (bool (T::*thresh_function) (double), T& instance) + { + setThresholdFunction (boost::bind (thresh_function, boost::ref (instance), _1)); + } + + protected: + using PCLBase::input_; + using PCLBase::indices_; + using Filter::filter_name_; + using Filter::getClassName; + using FilterIndices::negative_; + using FilterIndices::keep_organized_; + using FilterIndices::user_filter_value_; + using FilterIndices::extract_removed_indices_; + using FilterIndices::removed_indices_; + + /** \brief Filtered results are stored in a separate point cloud. + * \param[out] output The resultant point cloud. + */ + void + applyFilter (PointCloud &output); + + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. + */ + void + applyFilter (std::vector &indices) + { + applyFilterIndices (indices); + } + + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. + */ + void + applyFilterIndices (std::vector &indices); + + protected: + double normals_distance_weight_; + PointCloudNConstPtr cloud_normals_; + + /** \brief The model used to calculate distances */ + SampleConsensusModelPtr model_; + + /** \brief The threshold used to seperate outliers (removed_indices) from inliers (indices) */ + float thresh_; + + /** \brief The model coefficients */ + Eigen::VectorXf model_coefficients_; + + /** \brief The type of model to use (user given parameter). */ + pcl::SacModel model_type_; + boost::function threshold_function_; + + inline bool + checkSingleThreshold (double value) + { + return (value < thresh_); + } + + private: + virtual bool + initSACModel (pcl::SacModel model_type); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_FILTERS_MODEL_OUTLIER_REMOVAL_H_ diff --git a/pcl-1.7/pcl/filters/morphological_filter.h b/pcl-1.7/pcl/filters/morphological_filter.h new file mode 100644 index 0000000..4ea8dda --- /dev/null +++ b/pcl-1.7/pcl/filters/morphological_filter.h @@ -0,0 +1,82 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2014, RadiantBlue Technologies, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_MORPHOLOGICAL_FILTER_H_ +#define PCL_FILTERS_MORPHOLOGICAL_FILTER_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + enum MorphologicalOperators + { + MORPH_OPEN, + MORPH_CLOSE, + MORPH_DILATE, + MORPH_ERODE + }; +} + +namespace pcl +{ + /** \brief Apply morphological operator to the z dimension of the input point cloud + * \param[in] cloud_in the input point cloud dataset + * \param[in] resolution the window size to be used for the morphological operation + * \param[in] morphological_operator the morphological operator to apply (open, close, dilate, erode) + * \param[out] cloud_out the resultant output point cloud dataset + * \ingroup filters + */ + template PCL_EXPORTS void + applyMorphologicalOperator (const typename pcl::PointCloud::ConstPtr &cloud_in, + float resolution, const int morphological_operator, + pcl::PointCloud &cloud_out); +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FILTERS_MORPHOLOGICAL_FILTER_H_ + diff --git a/pcl-1.7/pcl/filters/normal_refinement.h b/pcl-1.7/pcl/filters/normal_refinement.h new file mode 100644 index 0000000..8565479 --- /dev/null +++ b/pcl-1.7/pcl/filters/normal_refinement.h @@ -0,0 +1,308 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_NORMAL_REFINEMENT_H_ +#define PCL_FILTERS_NORMAL_REFINEMENT_H_ + +#include + +namespace pcl +{ + /** \brief Assign weights of nearby normals used for refinement + * \todo Currently, this function equalizes all weights to 1 + * @param cloud the point cloud data + * @param index a \a valid index in \a cloud representing a \a valid (i.e., finite) query point + * @param k_indices indices of neighboring points + * @param k_sqr_distances squared distances to the neighboring points + * @return weights + * \ingroup filters + */ + template inline std::vector + assignNormalWeights (const PointCloud&, + int, + const std::vector& k_indices, + const std::vector& k_sqr_distances) + { + // Check inputs + if (k_indices.size () != k_sqr_distances.size ()) + PCL_ERROR("[pcl::assignNormalWeights] inequal size of neighbor indices and distances!\n"); + + // TODO: For now we use uniform weights + return (std::vector (k_indices.size (), 1.0f)); + } + + /** \brief Refine an indexed point based on its neighbors, this function only writes to the normal_* fields + * + * \note If the indexed point has only NaNs in its neighborhood, the resulting normal will be zero. + * + * @param cloud the point cloud data + * @param index a \a valid index in \a cloud representing a \a valid (i.e., finite) query point + * @param k_indices indices of neighboring points + * @param k_sqr_distances squared distances to the neighboring points + * @param point the output point, only normal_* fields are written + * @return false if an error occurred (norm of summed normals zero or all neighbors NaN) + * \ingroup filters + */ + template inline bool + refineNormal (const PointCloud& cloud, + int index, + const std::vector& k_indices, + const std::vector& k_sqr_distances, + NormalT& point) + { + // Start by zeroing result + point.normal_x = 0.0f; + point.normal_y = 0.0f; + point.normal_z = 0.0f; + + // Check inputs + if (k_indices.size () != k_sqr_distances.size ()) + { + PCL_ERROR("[pcl::refineNormal] inequal size of neighbor indices and distances!\n"); + return (false); + } + + // Get weights + const std::vector weights = assignNormalWeights (cloud, index, k_indices, k_sqr_distances); + + // Loop over all neighbors and accumulate sum of normal components + float nx = 0.0f; + float ny = 0.0f; + float nz = 0.0f; + for (unsigned int i = 0; i < k_indices.size (); ++i) { + // Neighbor + const NormalT& pointi = cloud[k_indices[i]]; + + // Accumulate if not NaN + if (pcl_isfinite (pointi.normal_x) && pcl_isfinite (pointi.normal_y) && pcl_isfinite (pointi.normal_z)) + { + const float& weighti = weights[i]; + nx += weighti * pointi.normal_x; + ny += weighti * pointi.normal_y; + nz += weighti * pointi.normal_z; + } + } + + // Normalize if norm valid and non-zero + const float norm = sqrtf (nx * nx + ny * ny + nz * nz); + if (pcl_isfinite (norm) && norm > std::numeric_limits::epsilon ()) + { + point.normal_x = nx / norm; + point.normal_y = ny / norm; + point.normal_z = nz / norm; + + return (true); + } + + return (false); + } + + /** \brief %Normal vector refinement class + * + * This class refines a set of already estimated normals by iteratively updating each normal to the (weighted) + * mean of all normals in its neighborhood. The intention is that you reuse the same point correspondences + * as used when estimating the original normals in order to avoid repeating a nearest neighbor search. + * + * \note This class avoids points for which a NaN is encountered in the neighborhood. In the special case + * where a point has only NaNs in its neighborhood, the resultant refined normal will be set to zero, + * i.e. this class only produces finite normals. + * + * \details Usage example: + * + * \code + * // Input point cloud + * pcl::PointCloud cloud; + * + * // Fill cloud... + * + * // Estimated and refined normals + * pcl::PointCloud normals; + * pcl::PointCloud normals_refined; + * + * // Search parameters + * const int k = 5; + * std::vector > k_indices; + * std::vector > k_sqr_distances; + * + * // Run search + * pcl::search::KdTree search; + * search.setInputCloud (cloud.makeShared ()); + * search.nearestKSearch (cloud, std::vector (), k, k_indices, k_sqr_distances); + * + * // Use search results for normal estimation + * pcl::NormalEstimation ne; + * for (unsigned int i = 0; i < cloud.size (); ++i) + * { + * NormalT normal; + * ne.computePointNormal (cloud, k_indices[i] + * normal.normal_x, normal.normal_y, normal.normal_z, normal.curvature); + * pcl::flipNormalTowardsViewpoint (cloud[i], cloud.sensor_origin_[0], cloud.sensor_origin_[1], cloud.sensor_origin_[2], + * normal.normal_x, normal.normal_y, normal.normal_z); + * normals.push_back (normal); + * } + * + * // Run refinement using search results + * pcl::NormalRefinement nr (k_indices, k_sqr_distances); + * nr.setInputCloud (normals.makeShared ()); + * nr.filter (normals_refined); + * \endcode + * + * \author Anders Glent Buch + * \ingroup filters + */ + template + class NormalRefinement : public Filter + { + using Filter::input_; + using Filter::filter_name_; + using Filter::getClassName; + + typedef typename Filter::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + /** \brief Empty constructor, sets default convergence parameters + */ + NormalRefinement () : + Filter::Filter () + { + filter_name_ = "NormalRefinement"; + setMaxIterations (15); + setConvergenceThreshold (0.00001f); + } + + /** \brief Constructor for setting correspondences, sets default convergence parameters + * @param k_indices indices of neighboring points + * @param k_sqr_distances squared distances to the neighboring points + */ + NormalRefinement (const std::vector< std::vector >& k_indices, const std::vector< std::vector >& k_sqr_distances) : + Filter::Filter () + { + filter_name_ = "NormalRefinement"; + setCorrespondences (k_indices, k_sqr_distances); + setMaxIterations (15); + setConvergenceThreshold (0.00001f); + } + + /** \brief Set correspondences calculated from nearest neighbor search + * @param k_indices indices of neighboring points + * @param k_sqr_distances squared distances to the neighboring points + */ + inline void + setCorrespondences (const std::vector< std::vector >& k_indices, const std::vector< std::vector >& k_sqr_distances) + { + k_indices_ = k_indices; + k_sqr_distances_ = k_sqr_distances; + } + + /** \brief Get correspondences (copy) + * @param k_indices indices of neighboring points + * @param k_sqr_distances squared distances to the neighboring points + */ + inline void + getCorrespondences (std::vector< std::vector >& k_indices, std::vector< std::vector >& k_sqr_distances) + { + k_indices.assign (k_indices_.begin (), k_indices_.end ()); + k_sqr_distances.assign (k_sqr_distances_.begin (), k_sqr_distances_.end ()); + } + + /** \brief Set maximum iterations + * @param max_iterations maximum iterations + */ + inline void + setMaxIterations (unsigned int max_iterations) + { + max_iterations_ = max_iterations; + } + + /** \brief Get maximum iterations + * @return maximum iterations + */ + inline unsigned int + getMaxIterations () + { + return max_iterations_; + } + + /** \brief Set convergence threshold + * @param convergence_threshold convergence threshold + */ + inline void + setConvergenceThreshold (float convergence_threshold) + { + convergence_threshold_ = convergence_threshold; + } + + /** \brief Get convergence threshold + * @return convergence threshold + */ + inline float + getConvergenceThreshold () + { + return convergence_threshold_; + } + + protected: + /** \brief Filter a Point Cloud. + * \param output the resultant point cloud message + */ + void + applyFilter (PointCloud &output); + + private: + /** \brief indices of neighboring points */ + std::vector< std::vector > k_indices_; + + /** \brief squared distances to the neighboring points */ + std::vector< std::vector > k_sqr_distances_; + + /** \brief Maximum allowable iterations over the whole point cloud for refinement */ + unsigned int max_iterations_; + + /** \brief Convergence threshold in the interval [0,1] on the mean of 1 - dot products between previous iteration and the current */ + float convergence_threshold_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#else +#define PCL_INSTANTIATE_NormalRefinement(T) template class PCL_EXPORTS pcl::NormalRefinement; +#endif + +#endif diff --git a/pcl-1.7/pcl/filters/normal_space.h b/pcl-1.7/pcl/filters/normal_space.h new file mode 100644 index 0000000..e7b6012 --- /dev/null +++ b/pcl-1.7/pcl/filters/normal_space.h @@ -0,0 +1,209 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FILTERS_NORMAL_SUBSAMPLE_H_ +#define PCL_FILTERS_NORMAL_SUBSAMPLE_H_ + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief @b NormalSpaceSampling samples the input point cloud in the space of normal directions computed at every point. + * \ingroup filters + */ + template + class NormalSpaceSampling : public FilterIndices + { + using FilterIndices::filter_name_; + using FilterIndices::getClassName; + using FilterIndices::indices_; + using FilterIndices::input_; + using FilterIndices::keep_organized_; + using FilterIndices::extract_removed_indices_; + using FilterIndices::removed_indices_; + using FilterIndices::user_filter_value_; + + typedef typename FilterIndices::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + typedef typename pcl::PointCloud::ConstPtr NormalsConstPtr; + + public: + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Empty constructor. */ + NormalSpaceSampling () + : sample_ (std::numeric_limits::max ()) + , seed_ (static_cast (time (NULL))) + , binsx_ () + , binsy_ () + , binsz_ () + , input_normals_ () + , rng_uniform_distribution_ (NULL) + { + filter_name_ = "NormalSpaceSampling"; + } + + /** \brief Destructor. */ + ~NormalSpaceSampling () + { + if (rng_uniform_distribution_ != NULL) + delete rng_uniform_distribution_; + } + + /** \brief Set number of indices to be sampled. + * \param[in] sample the number of sample indices + */ + inline void + setSample (unsigned int sample) + { sample_ = sample; } + + /** \brief Get the value of the internal \a sample parameter. */ + inline unsigned int + getSample () const + { return (sample_); } + + /** \brief Set seed of random function. + * \param[in] seed the input seed + */ + inline void + setSeed (unsigned int seed) + { seed_ = seed; } + + /** \brief Get the value of the internal \a seed parameter. */ + inline unsigned int + getSeed () const + { return (seed_); } + + /** \brief Set the number of bins in x, y and z direction + * \param[in] binsx number of bins in x direction + * \param[in] binsy number of bins in y direction + * \param[in] binsz number of bins in z direction + */ + inline void + setBins (unsigned int binsx, unsigned int binsy, unsigned int binsz) + { + binsx_ = binsx; + binsy_ = binsy; + binsz_ = binsz; + } + + /** \brief Get the number of bins in x, y and z direction + * \param[out] binsx number of bins in x direction + * \param[out] binsy number of bins in y direction + * \param[out] binsz number of bins in z direction + */ + inline void + getBins (unsigned int& binsx, unsigned int& binsy, unsigned int& binsz) const + { + binsx = binsx_; + binsy = binsy_; + binsz = binsz_; + } + + /** \brief Set the normals computed on the input point cloud + * \param[in] normals the normals computed for the input cloud + */ + inline void + setNormals (const NormalsConstPtr &normals) { input_normals_ = normals; } + + /** \brief Get the normals computed on the input point cloud */ + inline NormalsConstPtr + getNormals () const { return (input_normals_); } + + protected: + /** \brief Number of indices that will be returned. */ + unsigned int sample_; + /** \brief Random number seed. */ + unsigned int seed_; + + /** \brief Number of bins in x direction. */ + unsigned int binsx_; + /** \brief Number of bins in y direction. */ + unsigned int binsy_; + /** \brief Number of bins in z direction. */ + unsigned int binsz_; + + /** \brief The normals computed at each point in the input cloud */ + NormalsConstPtr input_normals_; + + /** \brief Sample of point indices into a separate PointCloud + * \param[out] output the resultant point cloud + */ + void + applyFilter (PointCloud &output); + + /** \brief Sample of point indices + * \param[out] indices the resultant point cloud indices + */ + void + applyFilter (std::vector &indices); + + bool + initCompute (); + + private: + /** \brief Finds the bin number of the input normal, returns the bin number + * \param[in] normal the input normal + * \param[in] nbins total number of bins + */ + unsigned int + findBin (const float *normal, unsigned int nbins); + + /** \brief Checks of the entire bin is sampled, returns true or false + * \param[out] array flag which says whether a point is sampled or not + * \param[in] start_index the index to the first point of the bin in array. + * \param[in] length number of points in the bin + */ + bool + isEntireBinSampled (boost::dynamic_bitset<> &array, unsigned int start_index, unsigned int length); + + /** \brief Uniform random distribution. */ + boost::variate_generator > *rng_uniform_distribution_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FILTERS_NORMAL_SPACE_SUBSAMPLE_H_ diff --git a/pcl-1.7/pcl/filters/passthrough.h b/pcl-1.7/pcl/filters/passthrough.h new file mode 100644 index 0000000..077a9f9 --- /dev/null +++ b/pcl-1.7/pcl/filters/passthrough.h @@ -0,0 +1,383 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_PASSTHROUGH_H_ +#define PCL_FILTERS_PASSTHROUGH_H_ + +#include + +namespace pcl +{ + /** \brief @b PassThrough passes points in a cloud based on constraints for one particular field of the point type. + * \details Iterates through the entire input once, automatically filtering non-finite points and the points outside + * the interval specified by setFilterLimits(), which applies only to the field specified by setFilterFieldName(). + *

+ * Usage example: + * \code + * pcl::PassThrough ptfilter (true); // Initializing with true will allow us to extract the removed indices + * ptfilter.setInputCloud (cloud_in); + * ptfilter.setFilterFieldName ("x"); + * ptfilter.setFilterLimits (0.0, 1000.0); + * ptfilter.filter (*indices_x); + * // The indices_x array indexes all points of cloud_in that have x between 0.0 and 1000.0 + * indices_rem = ptfilter.getRemovedIndices (); + * // The indices_rem array indexes all points of cloud_in that have x smaller than 0.0 or larger than 1000.0 + * // and also indexes all non-finite points of cloud_in + * ptfilter.setIndices (indices_x); + * ptfilter.setFilterFieldName ("z"); + * ptfilter.setFilterLimits (-10.0, 10.0); + * ptfilter.setNegative (true); + * ptfilter.filter (*indices_xz); + * // The indices_xz array indexes all points of cloud_in that have x between 0.0 and 1000.0 and z larger than 10.0 or smaller than -10.0 + * ptfilter.setIndices (indices_xz); + * ptfilter.setFilterFieldName ("intensity"); + * ptfilter.setFilterLimits (FLT_MIN, 0.5); + * ptfilter.setNegative (false); + * ptfilter.filter (*cloud_out); + * // The resulting cloud_out contains all points of cloud_in that are finite and have: + * // x between 0.0 and 1000.0, z larger than 10.0 or smaller than -10.0 and intensity smaller than 0.5. + * \endcode + * \author Radu Bogdan Rusu + * \ingroup filters + */ + template + class PassThrough : public FilterIndices + { + protected: + typedef typename FilterIndices::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + typedef typename pcl::traits::fieldList::type FieldList; + + public: + + typedef boost::shared_ptr< PassThrough > Ptr; + typedef boost::shared_ptr< const PassThrough > ConstPtr; + + + /** \brief Constructor. + * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false). + */ + PassThrough (bool extract_removed_indices = false) : + FilterIndices::FilterIndices (extract_removed_indices), + filter_field_name_ (""), + filter_limit_min_ (FLT_MIN), + filter_limit_max_ (FLT_MAX) + { + filter_name_ = "PassThrough"; + } + + /** \brief Provide the name of the field to be used for filtering data. + * \details In conjunction with setFilterLimits(), points having values outside this interval for this field will be discarded. + * \param[in] field_name The name of the field that will be used for filtering. + */ + inline void + setFilterFieldName (const std::string &field_name) + { + filter_field_name_ = field_name; + } + + /** \brief Retrieve the name of the field to be used for filtering data. + * \return The name of the field that will be used for filtering. + */ + inline std::string const + getFilterFieldName () + { + return (filter_field_name_); + } + + /** \brief Set the numerical limits for the field for filtering data. + * \details In conjunction with setFilterFieldName(), points having values outside this interval for this field will be discarded. + * \param[in] limit_min The minimum allowed field value (default = FLT_MIN). + * \param[in] limit_max The maximum allowed field value (default = FLT_MAX). + */ + inline void + setFilterLimits (const float &limit_min, const float &limit_max) + { + filter_limit_min_ = limit_min; + filter_limit_max_ = limit_max; + } + + /** \brief Get the numerical limits for the field for filtering data. + * \param[out] limit_min The minimum allowed field value (default = FLT_MIN). + * \param[out] limit_max The maximum allowed field value (default = FLT_MAX). + */ + inline void + getFilterLimits (float &limit_min, float &limit_max) + { + limit_min = filter_limit_min_; + limit_max = filter_limit_max_; + } + + /** \brief Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max) + * Default: false. + * \warning This method will be removed in the future. Use setNegative() instead. + * \param[in] limit_negative return data inside the interval (false) or outside (true) + */ + inline void + setFilterLimitsNegative (const bool limit_negative) + { + negative_ = limit_negative; + } + + /** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). + * \warning This method will be removed in the future. Use getNegative() instead. + * \param[out] limit_negative true if data \b outside the interval [min; max] is to be returned, false otherwise + */ + inline void + getFilterLimitsNegative (bool &limit_negative) + { + limit_negative = negative_; + } + + /** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). + * \warning This method will be removed in the future. Use getNegative() instead. + * \return true if data \b outside the interval [min; max] is to be returned, false otherwise + */ + inline bool + getFilterLimitsNegative () + { + return (negative_); + } + + protected: + using PCLBase::input_; + using PCLBase::indices_; + using Filter::filter_name_; + using Filter::getClassName; + using FilterIndices::negative_; + using FilterIndices::keep_organized_; + using FilterIndices::user_filter_value_; + using FilterIndices::extract_removed_indices_; + using FilterIndices::removed_indices_; + + /** \brief Filtered results are stored in a separate point cloud. + * \param[out] output The resultant point cloud. + */ + void + applyFilter (PointCloud &output); + + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. + */ + void + applyFilter (std::vector &indices) + { + applyFilterIndices (indices); + } + + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. + */ + void + applyFilterIndices (std::vector &indices); + + private: + /** \brief The name of the field that will be used for filtering. */ + std::string filter_field_name_; + + /** \brief The minimum allowed field value (default = FLT_MIN). */ + float filter_limit_min_; + + /** \brief The maximum allowed field value (default = FLT_MIN). */ + float filter_limit_max_; + }; + + //////////////////////////////////////////////////////////////////////////////////////////// + /** \brief PassThrough uses the base Filter class methods to pass through all data that satisfies the user given + * constraints. + * \author Radu B. Rusu + * \ingroup filters + */ + template<> + class PCL_EXPORTS PassThrough : public Filter + { + typedef pcl::PCLPointCloud2 PCLPointCloud2; + typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr; + typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr; + + using Filter::removed_indices_; + using Filter::extract_removed_indices_; + + public: + /** \brief Constructor. */ + PassThrough (bool extract_removed_indices = false) : + Filter::Filter (extract_removed_indices), keep_organized_ (false), + user_filter_value_ (std::numeric_limits::quiet_NaN ()), + filter_field_name_ (""), filter_limit_min_ (-FLT_MAX), filter_limit_max_ (FLT_MAX), + filter_limit_negative_ (false) + { + filter_name_ = "PassThrough"; + } + + /** \brief Set whether the filtered points should be kept and set to the + * value given through \a setUserFilterValue (default: NaN), or removed + * from the PointCloud, thus potentially breaking its organized + * structure. By default, points are removed. + * + * \param[in] val set to true whether the filtered points should be kept and + * set to a given user value (default: NaN) + */ + inline void + setKeepOrganized (bool val) + { + keep_organized_ = val; + } + + /** \brief Obtain the value of the internal \a keep_organized_ parameter. */ + inline bool + getKeepOrganized () + { + return (keep_organized_); + } + + /** \brief Provide a value that the filtered points should be set to + * instead of removing them. Used in conjunction with \a + * setKeepOrganized (). + * \param[in] val the user given value that the filtered point dimensions should be set to + */ + inline void + setUserFilterValue (float val) + { + user_filter_value_ = val; + } + + /** \brief Provide the name of the field to be used for filtering data. In conjunction with \a setFilterLimits, + * points having values outside this interval will be discarded. + * \param[in] field_name the name of the field that contains values used for filtering + */ + inline void + setFilterFieldName (const std::string &field_name) + { + filter_field_name_ = field_name; + } + + /** \brief Get the name of the field used for filtering. */ + inline std::string const + getFilterFieldName () + { + return (filter_field_name_); + } + + /** \brief Set the field filter limits. All points having field values outside this interval will be discarded. + * \param[in] limit_min the minimum allowed field value + * \param[in] limit_max the maximum allowed field value + */ + inline void + setFilterLimits (const double &limit_min, const double &limit_max) + { + filter_limit_min_ = limit_min; + filter_limit_max_ = limit_max; + } + + /** \brief Get the field filter limits (min/max) set by the user. The default values are -FLT_MAX, FLT_MAX. + * \param[out] limit_min the minimum allowed field value + * \param[out] limit_max the maximum allowed field value + */ + inline void + getFilterLimits (double &limit_min, double &limit_max) + { + limit_min = filter_limit_min_; + limit_max = filter_limit_max_; + } + + /** \brief Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max). + * Default: false. + * \param[in] limit_negative return data inside the interval (false) or outside (true) + */ + inline void + setFilterLimitsNegative (const bool limit_negative) + { + filter_limit_negative_ = limit_negative; + } + + /** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). + * \param[out] limit_negative true if data \b outside the interval [min; max] is to be returned, false otherwise + */ + inline void + getFilterLimitsNegative (bool &limit_negative) + { + limit_negative = filter_limit_negative_; + } + + /** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). + * \return true if data \b outside the interval [min; max] is to be returned, false otherwise + */ + inline bool + getFilterLimitsNegative () + { + return (filter_limit_negative_); + } + + protected: + void + applyFilter (PCLPointCloud2 &output); + + private: + /** \brief Keep the structure of the data organized, by setting the + * filtered points to the a user given value (NaN by default). + */ + bool keep_organized_; + + /** \brief User given value to be set to any filtered point. Casted to + * the correct field type. + */ + float user_filter_value_; + + /** \brief The desired user filter field name. */ + std::string filter_field_name_; + + /** \brief The minimum allowed filter value a point will be considered from. */ + double filter_limit_min_; + + /** \brief The maximum allowed filter value a point will be considered from. */ + double filter_limit_max_; + + /** \brief Set to true if we want to return the data outside (\a filter_limit_min_;\a filter_limit_max_). Default: false. */ + bool filter_limit_negative_; + + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_FILTERS_PASSTHROUGH_H_ + diff --git a/pcl-1.7/pcl/filters/plane_clipper3D.h b/pcl-1.7/pcl/filters/plane_clipper3D.h new file mode 100644 index 0000000..3f16c63 --- /dev/null +++ b/pcl-1.7/pcl/filters/plane_clipper3D.h @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_PLANE_CLIPPER3D_H_ +#define PCL_PLANE_CLIPPER3D_H_ +#include "clipper3D.h" + +namespace pcl +{ + /** + * @author Suat Gedikli + * @brief Implementation of a plane clipper in 3D + * \ingroup filters + */ + template + class PlaneClipper3D : public Clipper3D + { + public: + + typedef boost::shared_ptr< PlaneClipper3D > Ptr; + typedef boost::shared_ptr< const PlaneClipper3D > ConstPtr; + + /** + * @author Suat Gedikli + * @brief Constructor taking the homogeneous representation of the plane as a Eigen::Vector4f + * @param[in] plane_params plane parameters, need not necessarily be normalized + */ + PlaneClipper3D (const Eigen::Vector4f& plane_params); + + virtual ~PlaneClipper3D () throw (); + + /** + * \brief Set new plane parameters + * \param plane_params + */ + void setPlaneParameters (const Eigen::Vector4f& plane_params); + + /** + * \brief return the current plane parameters + * \return the current plane parameters + */ + const Eigen::Vector4f& getPlaneParameters () const; + + virtual bool + clipPoint3D (const PointT& point) const; + + virtual bool + clipLineSegment3D (PointT& from, PointT& to) const; + + virtual void + clipPlanarPolygon3D (std::vector >& polygon) const; + + virtual void + clipPlanarPolygon3D (const std::vector >& polygon, std::vector >& clipped_polygon) const; + + virtual void + clipPointCloud3D (const pcl::PointCloud &cloud_in, std::vector& clipped, const std::vector& indices = std::vector ()) const; + + virtual Clipper3D* + clone () const; + + protected: + float + getDistance (const PointT& point) const; + + private: + Eigen::Vector4f plane_params_; + }; +} + +#include + +#endif // PCL_PLANE_CLIPPER3D_H_ diff --git a/pcl-1.7/pcl/filters/project_inliers.h b/pcl-1.7/pcl/filters/project_inliers.h new file mode 100644 index 0000000..bed7b96 --- /dev/null +++ b/pcl-1.7/pcl/filters/project_inliers.h @@ -0,0 +1,292 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_PROJECT_INLIERS_H_ +#define PCL_FILTERS_PROJECT_INLIERS_H_ + +#include +#include +#include +// Sample Consensus models +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b ProjectInliers uses a model and a set of inlier indices from a PointCloud to project them into a + * separate PointCloud. + * \author Radu Bogdan Rusu + * \ingroup filters + */ + template + class ProjectInliers : public Filter + { + using Filter::input_; + using Filter::indices_; + using Filter::filter_name_; + using Filter::getClassName; + + typedef typename Filter::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename SampleConsensusModel::Ptr SampleConsensusModelPtr; + public: + + typedef boost::shared_ptr< ProjectInliers > Ptr; + typedef boost::shared_ptr< const ProjectInliers > ConstPtr; + + + /** \brief Empty constructor. */ + ProjectInliers () : model_ (), sacmodel_ (), model_type_ (), copy_all_data_ (false) + { + filter_name_ = "ProjectInliers"; + } + + /** \brief Empty destructor */ + virtual ~ProjectInliers () {} + + /** \brief The type of model to use (user given parameter). + * \param model the model type (check \a model_types.h) + */ + inline void + setModelType (int model) + { + model_type_ = model; + } + + /** \brief Get the type of SAC model used. */ + inline int + getModelType () + { + return (model_type_); + } + + /** \brief Provide a pointer to the model coefficients. + * \param model a pointer to the model coefficients + */ + inline void + setModelCoefficients (const ModelCoefficientsConstPtr &model) + { + model_ = model; + } + + /** \brief Get a pointer to the model coefficients. */ + inline ModelCoefficientsConstPtr + getModelCoefficients () + { + return (model_); + } + + /** \brief Set whether all data will be returned, or only the projected inliers. + * \param val true if all data should be returned, false if only the projected inliers + */ + inline void + setCopyAllData (bool val) + { + copy_all_data_ = val; + } + + /** \brief Get whether all data is being copied (true), or only the projected inliers (false). */ + inline bool + getCopyAllData () + { + return (copy_all_data_); + } + protected: + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Project point indices into a separate PointCloud + * \param output the resultant point cloud message + */ + void + applyFilter (PointCloud &output); + + private: + /** \brief A pointer to the vector of model coefficients. */ + ModelCoefficientsConstPtr model_; + + /** \brief The model that needs to be segmented. */ + SampleConsensusModelPtr sacmodel_; + + /** \brief The type of model to use (user given parameter). */ + int model_type_; + + /** \brief True if all data will be returned, false if only the projected inliers. Default: false. */ + bool copy_all_data_; + + /** \brief Initialize the Sample Consensus model and set its parameters. + * \param model_type the type of SAC model that is to be used + */ + virtual bool + initSACModel (int model_type); + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b ProjectInliers uses a model and a set of inlier indices from a PointCloud to project them into a + * separate PointCloud. + * \note setFilterFieldName (), setFilterLimits (), and setFilterLimitNegative () are ignored. + * \author Radu Bogdan Rusu + * \ingroup filters + */ + template<> + class PCL_EXPORTS ProjectInliers : public Filter + { + using Filter::filter_name_; + using Filter::getClassName; + + typedef pcl::PCLPointCloud2 PCLPointCloud2; + typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr; + typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr; + + typedef SampleConsensusModel::Ptr SampleConsensusModelPtr; + + public: + /** \brief Empty constructor. */ + ProjectInliers () : model_type_ (), copy_all_data_ (false), copy_all_fields_ (true), model_ (), sacmodel_ () + { + filter_name_ = "ProjectInliers"; + } + + /** \brief Empty destructor */ + virtual ~ProjectInliers () {} + + /** \brief The type of model to use (user given parameter). + * \param[in] model the model type (check \a model_types.h) + */ + inline void + setModelType (int model) + { + model_type_ = model; + } + + /** \brief Get the type of SAC model used. */ + inline int + getModelType () const + { + return (model_type_); + } + + /** \brief Provide a pointer to the model coefficients. + * \param[in] model a pointer to the model coefficients + */ + inline void + setModelCoefficients (const ModelCoefficientsConstPtr &model) + { + model_ = model; + } + + /** \brief Get a pointer to the model coefficients. */ + inline ModelCoefficientsConstPtr + getModelCoefficients () const + { + return (model_); + } + + /** \brief Set whether all fields should be copied, or only the XYZ. + * \param[in] val true if all fields will be returned, false if only XYZ + */ + inline void + setCopyAllFields (bool val) + { + copy_all_fields_ = val; + } + + /** \brief Get whether all fields are being copied (true), or only XYZ (false). */ + inline bool + getCopyAllFields () const + { + return (copy_all_fields_); + } + + /** \brief Set whether all data will be returned, or only the projected inliers. + * \param[in] val true if all data should be returned, false if only the projected inliers + */ + inline void + setCopyAllData (bool val) + { + copy_all_data_ = val; + } + + /** \brief Get whether all data is being copied (true), or only the projected inliers (false). */ + inline bool + getCopyAllData () const + { + return (copy_all_data_); + } + protected: + /** \brief The type of model to use (user given parameter). */ + int model_type_; + + /** \brief True if all data will be returned, false if only the projected inliers. Default: false. */ + bool copy_all_data_; + + /** \brief True if all fields will be returned, false if only XYZ. Default: true. */ + bool copy_all_fields_; + + /** \brief A pointer to the vector of model coefficients. */ + ModelCoefficientsConstPtr model_; + + void + applyFilter (PCLPointCloud2 &output); + + private: + /** \brief The model that needs to be segmented. */ + SampleConsensusModelPtr sacmodel_; + + virtual bool + initSACModel (int model_type); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FILTERS_PROJECT_INLIERS_H_ diff --git a/pcl-1.7/pcl/filters/radius_outlier_removal.h b/pcl-1.7/pcl/filters/radius_outlier_removal.h new file mode 100644 index 0000000..1f1024b --- /dev/null +++ b/pcl-1.7/pcl/filters/radius_outlier_removal.h @@ -0,0 +1,274 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_RADIUS_OUTLIER_REMOVAL_H_ +#define PCL_FILTERS_RADIUS_OUTLIER_REMOVAL_H_ + +#include +#include + +namespace pcl +{ + /** \brief @b RadiusOutlierRemoval filters points in a cloud based on the number of neighbors they have. + * \details Iterates through the entire input once, and for each point, retrieves the number of neighbors within a certain radius. + * The point will be considered an outlier if it has too few neighbors, as determined by setMinNeighborsInRadius(). + * The radius can be changed using setRadiusSearch(). + *
+ * The neighbors found for each query point will be found amongst ALL points of setInputCloud(), not just those indexed by setIndices(). + * The setIndices() method only indexes the points that will be iterated through as search query points. + *

+ * Usage example: + * \code + * pcl::RadiusOutlierRemoval rorfilter (true); // Initializing with true will allow us to extract the removed indices + * rorfilter.setInputCloud (cloud_in); + * rorfilter.setRadiusSearch (0.1); + * rorfilter.setMinNeighborsInRadius (5); + * rorfilter.setNegative (true); + * rorfilter.filter (*cloud_out); + * // The resulting cloud_out contains all points of cloud_in that have 4 or less neighbors within the 0.1 search radius + * indices_rem = rorfilter.getRemovedIndices (); + * // The indices_rem array indexes all points of cloud_in that have 5 or more neighbors within the 0.1 search radius + * \endcode + * \author Radu Bogdan Rusu + * \ingroup filters + */ + template + class RadiusOutlierRemoval : public FilterIndices + { + protected: + typedef typename FilterIndices::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + typedef typename pcl::search::Search::Ptr SearcherPtr; + + public: + + typedef boost::shared_ptr< RadiusOutlierRemoval > Ptr; + typedef boost::shared_ptr< const RadiusOutlierRemoval > ConstPtr; + + + /** \brief Constructor. + * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false). + */ + RadiusOutlierRemoval (bool extract_removed_indices = false) : + FilterIndices::FilterIndices (extract_removed_indices), + searcher_ (), + search_radius_ (0.0), + min_pts_radius_ (1) + { + filter_name_ = "RadiusOutlierRemoval"; + } + + /** \brief Set the radius of the sphere that will determine which points are neighbors. + * \details The number of points within this distance from the query point will need to be equal or greater + * than setMinNeighborsInRadius() in order to be classified as an inlier point (i.e. will not be filtered). + * \param[in] radius The radius of the sphere for nearest neighbor searching. + */ + inline void + setRadiusSearch (double radius) + { + search_radius_ = radius; + } + + /** \brief Get the radius of the sphere that will determine which points are neighbors. + * \details The number of points within this distance from the query point will need to be equal or greater + * than setMinNeighborsInRadius() in order to be classified as an inlier point (i.e. will not be filtered). + * \return The radius of the sphere for nearest neighbor searching. + */ + inline double + getRadiusSearch () + { + return (search_radius_); + } + + /** \brief Set the number of neighbors that need to be present in order to be classified as an inlier. + * \details The number of points within setRadiusSearch() from the query point will need to be equal or greater + * than this number in order to be classified as an inlier point (i.e. will not be filtered). + * \param min_pts The minimum number of neighbors (default = 1). + */ + inline void + setMinNeighborsInRadius (int min_pts) + { + min_pts_radius_ = min_pts; + } + + /** \brief Get the number of neighbors that need to be present in order to be classified as an inlier. + * \details The number of points within setRadiusSearch() from the query point will need to be equal or greater + * than this number in order to be classified as an inlier point (i.e. will not be filtered). + * \return The minimum number of neighbors (default = 1). + */ + inline int + getMinNeighborsInRadius () + { + return (min_pts_radius_); + } + + protected: + using PCLBase::input_; + using PCLBase::indices_; + using Filter::filter_name_; + using Filter::getClassName; + using FilterIndices::negative_; + using FilterIndices::keep_organized_; + using FilterIndices::user_filter_value_; + using FilterIndices::extract_removed_indices_; + using FilterIndices::removed_indices_; + + /** \brief Filtered results are stored in a separate point cloud. + * \param[out] output The resultant point cloud. + */ + void + applyFilter (PointCloud &output); + + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. + */ + void + applyFilter (std::vector &indices) + { + applyFilterIndices (indices); + } + + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. + */ + void + applyFilterIndices (std::vector &indices); + + private: + /** \brief A pointer to the spatial search object. */ + SearcherPtr searcher_; + + /** \brief The nearest neighbors search radius for each point. */ + double search_radius_; + + /** \brief The minimum number of neighbors that a point needs to have in the given search radius to be considered an inlier. */ + int min_pts_radius_; + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b RadiusOutlierRemoval is a simple filter that removes outliers if the number of neighbors in a certain + * search radius is smaller than a given K. + * \note setFilterFieldName (), setFilterLimits (), and setFilterLimitNegative () are ignored. + * \author Radu Bogdan Rusu + * \ingroup filters + */ + template<> + class PCL_EXPORTS RadiusOutlierRemoval : public Filter + { + using Filter::filter_name_; + using Filter::getClassName; + + using Filter::removed_indices_; + using Filter::extract_removed_indices_; + + typedef pcl::search::Search KdTree; + typedef pcl::search::Search::Ptr KdTreePtr; + + typedef pcl::PCLPointCloud2 PCLPointCloud2; + typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr; + typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr; + + public: + /** \brief Empty constructor. */ + RadiusOutlierRemoval (bool extract_removed_indices = false) : + Filter::Filter (extract_removed_indices), + search_radius_ (0.0), min_pts_radius_ (1), tree_ () + { + filter_name_ = "RadiusOutlierRemoval"; + } + + /** \brief Set the sphere radius that is to be used for determining the k-nearest neighbors for filtering. + * \param radius the sphere radius that is to contain all k-nearest neighbors + */ + inline void + setRadiusSearch (double radius) + { + search_radius_ = radius; + } + + /** \brief Get the sphere radius used for determining the k-nearest neighbors. */ + inline double + getRadiusSearch () + { + return (search_radius_); + } + + /** \brief Set the minimum number of neighbors that a point needs to have in the given search radius in order to + * be considered an inlier (i.e., valid). + * \param min_pts the minimum number of neighbors + */ + inline void + setMinNeighborsInRadius (int min_pts) + { + min_pts_radius_ = min_pts; + } + + /** \brief Get the minimum number of neighbors that a point needs to have in the given search radius to be + * considered an inlier and avoid being filtered. + */ + inline double + getMinNeighborsInRadius () + { + return (min_pts_radius_); + } + + protected: + /** \brief The nearest neighbors search radius for each point. */ + double search_radius_; + + /** \brief The minimum number of neighbors that a point needs to have in the given search radius to be considered + * an inlier. + */ + int min_pts_radius_; + + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + + void + applyFilter (PCLPointCloud2 &output); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_FILTERS_RADIUS_OUTLIER_REMOVAL_H_ + diff --git a/pcl-1.7/pcl/filters/random_sample.h b/pcl-1.7/pcl/filters/random_sample.h new file mode 100644 index 0000000..e2b0fb6 --- /dev/null +++ b/pcl-1.7/pcl/filters/random_sample.h @@ -0,0 +1,244 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: extract_indices.h 1370 2011-06-19 01:06:01Z jspricke $ + * + */ + +#ifndef PCL_FILTERS_RANDOM_SUBSAMPLE_H_ +#define PCL_FILTERS_RANDOM_SUBSAMPLE_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief @b RandomSample applies a random sampling with uniform probability. + * Based off Algorithm A from the paper "Faster Methods for Random Sampling" + * by Jeffrey Scott Vitter. The algorithm runs in O(N) and results in sorted + * indices + * http://www.ittc.ku.edu/~jsv/Papers/Vit84.sampling.pdf + * \author Justin Rosen + * \ingroup filters + */ + template + class RandomSample : public FilterIndices + { + using FilterIndices::filter_name_; + using FilterIndices::getClassName; + using FilterIndices::indices_; + using FilterIndices::input_; + using FilterIndices::negative_; + using FilterIndices::keep_organized_; + using FilterIndices::user_filter_value_; + using FilterIndices::extract_removed_indices_; + using FilterIndices::removed_indices_; + + typedef typename FilterIndices::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + + typedef boost::shared_ptr< RandomSample > Ptr; + typedef boost::shared_ptr< const RandomSample > ConstPtr; + + /** \brief Empty constructor. */ + RandomSample (bool extract_removed_indices = false) : + FilterIndices (extract_removed_indices), + sample_ (UINT_MAX), + seed_ (static_cast (time (NULL))) + { + filter_name_ = "RandomSample"; + } + + /** \brief Set number of indices to be sampled. + * \param sample + */ + inline void + setSample (unsigned int sample) + { + sample_ = sample; + } + + /** \brief Get the value of the internal \a sample parameter. + */ + inline unsigned int + getSample () + { + return (sample_); + } + + /** \brief Set seed of random function. + * \param seed + */ + inline void + setSeed (unsigned int seed) + { + seed_ = seed; + } + + /** \brief Get the value of the internal \a seed parameter. + */ + inline unsigned int + getSeed () + { + return (seed_); + } + + protected: + + /** \brief Number of indices that will be returned. */ + unsigned int sample_; + /** \brief Random number seed. */ + unsigned int seed_; + + /** \brief Sample of point indices into a separate PointCloud + * \param output the resultant point cloud + */ + void + applyFilter (PointCloud &output); + + /** \brief Sample of point indices + * \param indices the resultant point cloud indices + */ + void + applyFilter (std::vector &indices); + + /** \brief Return a random number fast using a LCG (Linear Congruential Generator) algorithm. + * See http://software.intel.com/en-us/articles/fast-random-number-generator-on-the-intel-pentiumr-4-processor/ for more information. + */ + inline float + unifRand () + { + return (static_cast(rand () / double (RAND_MAX))); + //return (((214013 * seed_ + 2531011) >> 16) & 0x7FFF); + } + }; + + /** \brief @b RandomSample applies a random sampling with uniform probability. + * \author Justin Rosen + * \ingroup filters + */ + template<> + class PCL_EXPORTS RandomSample : public FilterIndices + { + using FilterIndices::filter_name_; + using FilterIndices::getClassName; + + typedef pcl::PCLPointCloud2 PCLPointCloud2; + typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr; + typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr; + + public: + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Empty constructor. */ + RandomSample () : sample_ (UINT_MAX), seed_ (static_cast (time (NULL))) + { + filter_name_ = "RandomSample"; + } + + /** \brief Set number of indices to be sampled. + * \param sample + */ + inline void + setSample (unsigned int sample) + { + sample_ = sample; + } + + /** \brief Get the value of the internal \a sample parameter. + */ + inline unsigned int + getSample () + { + return (sample_); + } + + /** \brief Set seed of random function. + * \param seed + */ + inline void + setSeed (unsigned int seed) + { + seed_ = seed; + } + + /** \brief Get the value of the internal \a seed parameter. + */ + inline unsigned int + getSeed () + { + return (seed_); + } + + protected: + + /** \brief Number of indices that will be returned. */ + unsigned int sample_; + /** \brief Random number seed. */ + unsigned int seed_; + + /** \brief Sample of point indices into a separate PointCloud + * \param output the resultant point cloud + */ + void + applyFilter (PCLPointCloud2 &output); + + /** \brief Sample of point indices + * \param indices the resultant point cloud indices + */ + void + applyFilter (std::vector &indices); + + /** \brief Return a random number fast using a LCG (Linear Congruential Generator) algorithm. + * See http://software.intel.com/en-us/articles/fast-random-number-generator-on-the-intel-pentiumr-4-processor/ for more information. + */ + inline float + unifRand () + { + return (static_cast (rand () / double (RAND_MAX))); + //return (((214013 * seed_ + 2531011) >> 16) & 0x7FFF); + } + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FILTERS_RANDOM_SUBSAMPLE_H_ diff --git a/pcl-1.7/pcl/filters/sampling_surface_normal.h b/pcl-1.7/pcl/filters/sampling_surface_normal.h new file mode 100644 index 0000000..cdffff7 --- /dev/null +++ b/pcl-1.7/pcl/filters/sampling_surface_normal.h @@ -0,0 +1,253 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FILTERS_SAMPLING_SURFACE_NORMAL_H_ +#define PCL_FILTERS_SAMPLING_SURFACE_NORMAL_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief @b SamplingSurfaceNormal divides the input space into grids until each grid contains a maximum of N points, + * and samples points randomly within each grid. Normal is computed using the N points of each grid. All points + * sampled within a grid are assigned the same normal. + * + * \author Aravindhan K Krishnan. This code is ported from libpointmatcher (https://github.com/ethz-asl/libpointmatcher) + * \ingroup filters + */ + template + class SamplingSurfaceNormal: public Filter + { + using Filter::filter_name_; + using Filter::getClassName; + using Filter::indices_; + using Filter::input_; + + typedef typename Filter::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename Eigen::Matrix Vector; + + public: + + typedef boost::shared_ptr< SamplingSurfaceNormal > Ptr; + typedef boost::shared_ptr< const SamplingSurfaceNormal > ConstPtr; + + /** \brief Empty constructor. */ + SamplingSurfaceNormal () : + sample_ (10), seed_ (static_cast (time (NULL))), ratio_ () + { + filter_name_ = "SamplingSurfaceNormal"; + srand (seed_); + } + + /** \brief Set maximum number of samples in each grid + * \param[in] sample maximum number of samples in each grid + */ + inline void + setSample (unsigned int sample) + { + sample_ = sample; + } + + /** \brief Get the value of the internal \a sample parameter. */ + inline unsigned int + getSample () const + { + return (sample_); + } + + /** \brief Set seed of random function. + * \param[in] seed the input seed + */ + inline void + setSeed (unsigned int seed) + { + seed_ = seed; + srand (seed_); + } + + /** \brief Get the value of the internal \a seed parameter. */ + inline unsigned int + getSeed () const + { + return (seed_); + } + + /** \brief Set ratio of points to be sampled in each grid + * \param[in] ratio sample the ratio of points to be sampled in each grid + */ + inline void + setRatio (float ratio) + { + ratio_ = ratio; + } + + /** \brief Get the value of the internal \a ratio parameter. */ + inline float + getRatio () const + { + return ratio_; + } + + protected: + + /** \brief Maximum number of samples in each grid. */ + unsigned int sample_; + /** \brief Random number seed. */ + unsigned int seed_; + /** \brief Ratio of points to be sampled in each grid */ + float ratio_; + + /** \brief Sample of point indices into a separate PointCloud + * \param[out] output the resultant point cloud + */ + void + applyFilter (PointCloud &output); + + private: + + /** \brief @b CompareDim is a comparator object for sorting across a specific dimenstion (i,.e X, Y or Z) + */ + struct CompareDim + { + /** \brief The dimension to sort */ + const int dim; + /** \brief The input point cloud to sort */ + const pcl::PointCloud & cloud; + + /** \brief Constructor. */ + CompareDim (const int dim, const pcl::PointCloud & cloud) : dim (dim), cloud (cloud) + { + } + + /** \brief The operator function for sorting. */ + bool + operator () (const int& p0, const int& p1) + { + if (dim == 0) + return (cloud.points[p0].x < cloud.points[p1].x); + else if (dim == 1) + return (cloud.points[p0].y < cloud.points[p1].y); + else if (dim == 2) + return (cloud.points[p0].z < cloud.points[p1].z); + return (false); + } + }; + + /** \brief Finds the max and min values in each dimension + * \param[in] cloud the input cloud + * \param[out] max_vec the max value vector + * \param[out] min_vec the min value vector + */ + void + findXYZMaxMin (const PointCloud& cloud, Vector& max_vec, Vector& min_vec); + + /** \brief Recursively partition the point cloud, stopping when each grid contains less than sample_ points + * Points are randomly sampled when a grid is found + * \param cloud + * \param first + * \param last + * \param min_values + * \param max_values + * \param indices + * \param[out] outcloud output the resultant point cloud + */ + void + partition (const PointCloud& cloud, const int first, const int last, + const Vector min_values, const Vector max_values, + std::vector& indices, PointCloud& outcloud); + + /** \brief Randomly sample the points in each grid. + * \param[in] data + * \param[in] first + * \param[in] last + * \param[out] indices + * \param[out] output the resultant point cloud + */ + void + samplePartition (const PointCloud& data, const int first, const int last, + std::vector& indices, PointCloud& outcloud); + + /** \brief Returns the threshold for splitting in a given dimension. + * \param[in] cloud the input cloud + * \param[in] cut_dim the input dimension (0=x, 1=y, 2=z) + * \param[in] cut_index the input index in the cloud + */ + float + findCutVal (const PointCloud& cloud, const int cut_dim, const int cut_index); + + /** \brief Computes the normal for points in a grid. This is a port from features to avoid features dependency for + * filters + * \param[in] cloud The input cloud + * \param[out] normal the computed normal + * \param[out] curvature the computed curvature + */ + void + computeNormal (const PointCloud& cloud, Eigen::Vector4f &normal, float& curvature); + + /** \brief Computes the covariance matrix for points in the cloud. This is a port from features to avoid features dependency for + * filters + * \param[in] cloud The input cloud + * \param[out] covariance_matrix the covariance matrix + * \param[out] centroid the centroid + */ + unsigned int + computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, + Eigen::Matrix3f &covariance_matrix, + Eigen::Vector4f ¢roid); + + /** \brief Solve the eigenvalues and eigenvectors of a given 3x3 covariance matrix, and estimate the least-squares + * plane normal and surface curvature. + * \param[in] covariance_matrix the 3x3 covariance matrix + * \param[out] (nx ny nz) plane_parameters the resultant plane parameters as: a, b, c, d (ax + by + cz + d = 0) + * \param[out] curvature the estimated surface curvature as a measure of + */ + void + solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix, + float &nx, float &ny, float &nz, float &curvature); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FILTERS_SAMPLING_SURFACE_NORMAL_H_ diff --git a/pcl-1.7/pcl/filters/shadowpoints.h b/pcl-1.7/pcl/filters/shadowpoints.h new file mode 100644 index 0000000..1f2733e --- /dev/null +++ b/pcl-1.7/pcl/filters/shadowpoints.h @@ -0,0 +1,133 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FILTERS_SHADOW_POINTS_FILTER_H_ +#define PCL_FILTERS_SHADOW_POINTS_FILTER_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief @b ShadowPoints removes the ghost points appearing on edge discontinuties + * + * \author Aravindhan K Krishnan. This code is ported from libpointmatcher (https://github.com/ethz-asl/libpointmatcher) + * \ingroup filters + */ + template + class ShadowPoints : public FilterIndices + { + using FilterIndices::filter_name_; + using FilterIndices::getClassName; + using FilterIndices::indices_; + using FilterIndices::input_; + using FilterIndices::removed_indices_; + using FilterIndices::extract_removed_indices_; + using FilterIndices::negative_; + using FilterIndices::user_filter_value_; + using FilterIndices::keep_organized_; + + typedef typename FilterIndices::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + typedef typename pcl::PointCloud::Ptr NormalsPtr; + + public: + + typedef boost::shared_ptr< ShadowPoints > Ptr; + typedef boost::shared_ptr< const ShadowPoints > ConstPtr; + + /** \brief Empty constructor. */ + ShadowPoints (bool extract_removed_indices = false) : + FilterIndices (extract_removed_indices), + input_normals_ (), + threshold_ (0.1f) + { + filter_name_ = "ShadowPoints"; + } + + /** \brief Set the normals computed on the input point cloud + * \param[in] normals the normals computed for the input cloud + */ + inline void + setNormals (const NormalsPtr &normals) { input_normals_ = normals; } + + /** \brief Get the normals computed on the input point cloud */ + inline NormalsPtr + getNormals () const { return (input_normals_); } + + /** \brief Set the threshold for shadow points rejection + * \param[in] threshold the threshold + */ + inline void + setThreshold (float threshold) { threshold_ = threshold; } + + /** \brief Get the threshold for shadow points rejection */ + inline float + getThreshold () const { return threshold_; } + + protected: + + /** \brief The normals computed at each point in the input cloud */ + NormalsPtr input_normals_; + + /** \brief Sample of point indices into a separate PointCloud + * \param[out] output the resultant point cloud + */ + void + applyFilter (PointCloud &output); + + /** \brief Sample of point indices + * \param[out] indices the resultant point cloud indices + */ + void + applyFilter (std::vector &indices); + + private: + + /** \brief Threshold for shadow point rejection + */ + float threshold_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FILTERS_SHADOW_POINTS_FILTER_H_ diff --git a/pcl-1.7/pcl/filters/statistical_outlier_removal.h b/pcl-1.7/pcl/filters/statistical_outlier_removal.h new file mode 100644 index 0000000..d2016f9 --- /dev/null +++ b/pcl-1.7/pcl/filters/statistical_outlier_removal.h @@ -0,0 +1,324 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_STATISTICAL_OUTLIER_REMOVAL_H_ +#define PCL_FILTERS_STATISTICAL_OUTLIER_REMOVAL_H_ + +#include +#include + +namespace pcl +{ + /** \brief @b StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. + * \details The algorithm iterates through the entire input twice: + * During the first iteration it will compute the average distance that each point has to its nearest k neighbors. + * The value of k can be set using setMeanK(). + * Next, the mean and standard deviation of all these distances are computed in order to determine a distance threshold. + * The distance threshold will be equal to: mean + stddev_mult * stddev. + * The multiplier for the standard deviation can be set using setStddevMulThresh(). + * During the next iteration the points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively. + *
+ * The neighbors found for each query point will be found amongst ALL points of setInputCloud(), not just those indexed by setIndices(). + * The setIndices() method only indexes the points that will be iterated through as search query points. + *

+ * For more information: + * - R. B. Rusu, Z. C. Marton, N. Blodow, M. Dolha, and M. Beetz. + * Towards 3D Point Cloud Based Object Maps for Household Environments + * Robotics and Autonomous Systems Journal (Special Issue on Semantic Knowledge), 2008. + *

+ * Usage example: + * \code + * pcl::StatisticalOutlierRemoval sorfilter (true); // Initializing with true will allow us to extract the removed indices + * sorfilter.setInputCloud (cloud_in); + * sorfilter.setMeanK (8); + * sorfilter.setStddevMulThresh (1.0); + * sorfilter.filter (*cloud_out); + * // The resulting cloud_out contains all points of cloud_in that have an average distance to their 8 nearest neighbors that is below the computed threshold + * // Using a standard deviation multiplier of 1.0 and assuming the average distances are normally distributed there is a 84.1% chance that a point will be an inlier + * indices_rem = sorfilter.getRemovedIndices (); + * // The indices_rem array indexes all points of cloud_in that are outliers + * \endcode + * \author Radu Bogdan Rusu + * \ingroup filters + */ + template + class StatisticalOutlierRemoval : public FilterIndices + { + protected: + typedef typename FilterIndices::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + typedef typename pcl::search::Search::Ptr SearcherPtr; + + public: + + typedef boost::shared_ptr< StatisticalOutlierRemoval > Ptr; + typedef boost::shared_ptr< const StatisticalOutlierRemoval > ConstPtr; + + + /** \brief Constructor. + * \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false). + */ + StatisticalOutlierRemoval (bool extract_removed_indices = false) : + FilterIndices::FilterIndices (extract_removed_indices), + searcher_ (), + mean_k_ (1), + std_mul_ (0.0), + build_tree_t_ (0.0), + nn_time_ (0.0) + { + filter_name_ = "StatisticalOutlierRemoval"; + } + + /** \brief Set the number of nearest neighbors to use for mean distance estimation. + * \param[in] nr_k The number of points to use for mean distance estimation. + */ + inline void + setMeanK (int nr_k) + { + mean_k_ = nr_k; + } + + /** \brief Get the number of nearest neighbors to use for mean distance estimation. + * \return The number of points to use for mean distance estimation. + */ + inline int + getMeanK () + { + return (mean_k_); + } + + /** \brief Set the standard deviation multiplier for the distance threshold calculation. + * \details The distance threshold will be equal to: mean + stddev_mult * stddev. + * Points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively. + * \param[in] stddev_mult The standard deviation multiplier. + */ + inline void + setStddevMulThresh (double stddev_mult) + { + std_mul_ = stddev_mult; + } + + /** \brief Get the standard deviation multiplier for the distance threshold calculation. + * \details The distance threshold will be equal to: mean + stddev_mult * stddev. + * Points will be classified as inlier or outlier if their average neighbor distance is below or above this threshold respectively. + */ + inline double + getStddevMulThresh () + { + return (std_mul_); + } + + // kdtree building time + inline double getBuildTime() + { + return build_tree_t_; + } + + // nn search time + inline double getNnTime() + { + return nn_time_; + } + + protected: + using PCLBase::input_; + using PCLBase::indices_; + using Filter::filter_name_; + using Filter::getClassName; + using FilterIndices::negative_; + using FilterIndices::keep_organized_; + using FilterIndices::user_filter_value_; + using FilterIndices::extract_removed_indices_; + using FilterIndices::removed_indices_; + + /** \brief Filtered results are stored in a separate point cloud. + * \param[out] output The resultant point cloud. + */ + void + applyFilter (PointCloud &output); + + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. + */ + void + applyFilter (std::vector &indices) + { + applyFilterIndices (indices); + } + + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. + */ + void + applyFilterIndices (std::vector &indices); + + // kdtree building time + float build_tree_t_; + + // neighbouring search time + float nn_time_; + + private: + /** \brief A pointer to the spatial search object. */ + SearcherPtr searcher_; + + /** \brief The number of points to use for mean distance estimation. */ + int mean_k_; + + /** \brief Standard deviations threshold (i.e., points outside of + * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers). */ + double std_mul_; + }; + + /** \brief @b StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more + * information check: + * - R. B. Rusu, Z. C. Marton, N. Blodow, M. Dolha, and M. Beetz. + * Towards 3D Point Cloud Based Object Maps for Household Environments + * Robotics and Autonomous Systems Journal (Special Issue on Semantic Knowledge), 2008. + * + * \note setFilterFieldName (), setFilterLimits (), and setFilterLimitNegative () are ignored. + * \author Radu Bogdan Rusu + * \ingroup filters + */ + template<> + class PCL_EXPORTS StatisticalOutlierRemoval : public Filter + { + using Filter::filter_name_; + using Filter::getClassName; + + using Filter::removed_indices_; + using Filter::extract_removed_indices_; + + typedef pcl::search::Search KdTree; + typedef pcl::search::Search::Ptr KdTreePtr; + + typedef pcl::PCLPointCloud2 PCLPointCloud2; + typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr; + typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr; + + public: + /** \brief Empty constructor. */ + StatisticalOutlierRemoval (bool extract_removed_indices = false) : + Filter::Filter (extract_removed_indices), mean_k_ (2), + std_mul_ (0.0), tree_ (), negative_ (false) + { + filter_name_ = "StatisticalOutlierRemoval"; + } + + /** \brief Set the number of points (k) to use for mean distance estimation + * \param nr_k the number of points to use for mean distance estimation + */ + inline void + setMeanK (int nr_k) + { + mean_k_ = nr_k; + } + + /** \brief Get the number of points to use for mean distance estimation. */ + inline int + getMeanK () + { + return (mean_k_); + } + + /** \brief Set the standard deviation multiplier threshold. All points outside the + * \f[ \mu \pm \sigma \cdot std\_mul \f] + * will be considered outliers, where \f$ \mu \f$ is the estimated mean, + * and \f$ \sigma \f$ is the standard deviation. + * \param std_mul the standard deviation multiplier threshold + */ + inline void + setStddevMulThresh (double std_mul) + { + std_mul_ = std_mul; + } + + /** \brief Get the standard deviation multiplier threshold as set by the user. */ + inline double + getStddevMulThresh () + { + return (std_mul_); + } + + /** \brief Set whether the indices should be returned, or all points \e except the indices. + * \param negative true if all points \e except the input indices will be returned, false otherwise + */ + inline void + setNegative (bool negative) + { + negative_ = negative; + } + + /** \brief Get the value of the internal #negative_ parameter. If + * true, all points \e except the input indices will be returned. + * \return The value of the "negative" flag + */ + inline bool + getNegative () + { + return (negative_); + } + + protected: + /** \brief The number of points to use for mean distance estimation. */ + int mean_k_; + + /** \brief Standard deviations threshold (i.e., points outside of + * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers). + */ + double std_mul_; + + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + + /** \brief If true, the outliers will be returned instead of the inliers (default: false). */ + bool negative_; + + void + applyFilter (PCLPointCloud2 &output); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_FILTERS_STATISTICAL_OUTLIER_REMOVAL_H_ + diff --git a/pcl-1.7/pcl/filters/voxel_grid.h b/pcl-1.7/pcl/filters/voxel_grid.h new file mode 100644 index 0000000..2d2c464 --- /dev/null +++ b/pcl-1.7/pcl/filters/voxel_grid.h @@ -0,0 +1,856 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FILTERS_VOXEL_GRID_MAP_H_ +#define PCL_FILTERS_VOXEL_GRID_MAP_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief Obtain the maximum and minimum points in 3D from a given point cloud. + * \param[in] cloud the pointer to a pcl::PCLPointCloud2 dataset + * \param[in] x_idx the index of the X channel + * \param[in] y_idx the index of the Y channel + * \param[in] z_idx the index of the Z channel + * \param[out] min_pt the minimum data point + * \param[out] max_pt the maximum data point + */ + PCL_EXPORTS void + getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt); + + /** \brief Obtain the maximum and minimum points in 3D from a given point cloud. + * \note Performs internal data filtering as well. + * \param[in] cloud the pointer to a pcl::PCLPointCloud2 dataset + * \param[in] x_idx the index of the X channel + * \param[in] y_idx the index of the Y channel + * \param[in] z_idx the index of the Z channel + * \param[in] distance_field_name the name of the dimension to filter data along to + * \param[in] min_distance the minimum acceptable value in \a distance_field_name data + * \param[in] max_distance the maximum acceptable value in \a distance_field_name data + * \param[out] min_pt the minimum data point + * \param[out] max_pt the maximum data point + * \param[in] limit_negative \b false if data \b inside of the [min_distance; max_distance] interval should be + * considered, \b true otherwise. + */ + PCL_EXPORTS void + getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx, + const std::string &distance_field_name, float min_distance, float max_distance, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative = false); + + /** \brief Get the relative cell indices of the "upper half" 13 neighbors. + * \note Useful in combination with getNeighborCentroidIndices() from \ref VoxelGrid + * \ingroup filters + */ + inline Eigen::MatrixXi + getHalfNeighborCellIndices () + { + Eigen::MatrixXi relative_coordinates (3, 13); + int idx = 0; + + // 0 - 8 + for (int i = -1; i < 2; i++) + { + for (int j = -1; j < 2; j++) + { + relative_coordinates (0, idx) = i; + relative_coordinates (1, idx) = j; + relative_coordinates (2, idx) = -1; + idx++; + } + } + // 9 - 11 + for (int i = -1; i < 2; i++) + { + relative_coordinates (0, idx) = i; + relative_coordinates (1, idx) = -1; + relative_coordinates (2, idx) = 0; + idx++; + } + // 12 + relative_coordinates (0, idx) = -1; + relative_coordinates (1, idx) = 0; + relative_coordinates (2, idx) = 0; + + return (relative_coordinates); + } + + /** \brief Get the relative cell indices of all the 26 neighbors. + * \note Useful in combination with getNeighborCentroidIndices() from \ref VoxelGrid + * \ingroup filters + */ + inline Eigen::MatrixXi + getAllNeighborCellIndices () + { + Eigen::MatrixXi relative_coordinates = getHalfNeighborCellIndices (); + Eigen::MatrixXi relative_coordinates_all( 3, 26); + relative_coordinates_all.block<3, 13> (0, 0) = relative_coordinates; + relative_coordinates_all.block<3, 13> (0, 13) = -relative_coordinates; + return (relative_coordinates_all); + } + + /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions + * in a given pointcloud, without considering points outside of a distance threshold from the laser origin + * \param[in] cloud the point cloud data message + * \param[in] distance_field_name the field name that contains the distance values + * \param[in] min_distance the minimum distance a point will be considered from + * \param[in] max_distance the maximum distance a point will be considered to + * \param[out] min_pt the resultant minimum bounds + * \param[out] max_pt the resultant maximum bounds + * \param[in] limit_negative if set to true, then all points outside of the interval (min_distance;max_distace) are considered + * \ingroup filters + */ + template void + getMinMax3D (const typename pcl::PointCloud::ConstPtr &cloud, + const std::string &distance_field_name, float min_distance, float max_distance, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative = false); + + /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions + * in a given pointcloud, without considering points outside of a distance threshold from the laser origin + * \param[in] cloud the point cloud data message + * \param[in] indices the vector of indices to use + * \param[in] distance_field_name the field name that contains the distance values + * \param[in] min_distance the minimum distance a point will be considered from + * \param[in] max_distance the maximum distance a point will be considered to + * \param[out] min_pt the resultant minimum bounds + * \param[out] max_pt the resultant maximum bounds + * \param[in] limit_negative if set to true, then all points outside of the interval (min_distance;max_distace) are considered + * \ingroup filters + */ + template void + getMinMax3D (const typename pcl::PointCloud::ConstPtr &cloud, + const std::vector &indices, + const std::string &distance_field_name, float min_distance, float max_distance, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative = false); + + /** \brief VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. + * + * The VoxelGrid class creates a *3D voxel grid* (think about a voxel + * grid as a set of tiny 3D boxes in space) over the input point cloud data. + * Then, in each *voxel* (i.e., 3D box), all the points present will be + * approximated (i.e., *downsampled*) with their centroid. This approach is + * a bit slower than approximating them with the center of the voxel, but it + * represents the underlying surface more accurately. + * + * \author Radu B. Rusu, Bastian Steder + * \ingroup filters + */ + template + class VoxelGrid: public Filter + { + protected: + using Filter::filter_name_; + using Filter::getClassName; + using Filter::input_; + using Filter::indices_; + + typedef typename Filter::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + typedef boost::shared_ptr< VoxelGrid > Ptr; + typedef boost::shared_ptr< const VoxelGrid > ConstPtr; + + + public: + /** \brief Empty constructor. */ + VoxelGrid () : + leaf_size_ (Eigen::Vector4f::Zero ()), + inverse_leaf_size_ (Eigen::Array4f::Zero ()), + downsample_all_data_ (true), + save_leaf_layout_ (false), + leaf_layout_ (), + min_b_ (Eigen::Vector4i::Zero ()), + max_b_ (Eigen::Vector4i::Zero ()), + div_b_ (Eigen::Vector4i::Zero ()), + divb_mul_ (Eigen::Vector4i::Zero ()), + filter_field_name_ (""), + filter_limit_min_ (-FLT_MAX), + filter_limit_max_ (FLT_MAX), + filter_limit_negative_ (false), + min_points_per_voxel_ (0) + { + filter_name_ = "VoxelGrid"; + } + + /** \brief Destructor. */ + virtual ~VoxelGrid () + { + } + + /** \brief Set the voxel grid leaf size. + * \param[in] leaf_size the voxel grid leaf size + */ + inline void + setLeafSize (const Eigen::Vector4f &leaf_size) + { + leaf_size_ = leaf_size; + // Avoid division errors + if (leaf_size_[3] == 0) + leaf_size_[3] = 1; + // Use multiplications instead of divisions + inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array (); + } + + /** \brief Set the voxel grid leaf size. + * \param[in] lx the leaf size for X + * \param[in] ly the leaf size for Y + * \param[in] lz the leaf size for Z + */ + inline void + setLeafSize (float lx, float ly, float lz) + { + leaf_size_[0] = lx; leaf_size_[1] = ly; leaf_size_[2] = lz; + // Avoid division errors + if (leaf_size_[3] == 0) + leaf_size_[3] = 1; + // Use multiplications instead of divisions + inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array (); + } + + /** \brief Get the voxel grid leaf size. */ + inline Eigen::Vector3f + getLeafSize () { return (leaf_size_.head<3> ()); } + + /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. + * \param[in] downsample the new value (true/false) + */ + inline void + setDownsampleAllData (bool downsample) { downsample_all_data_ = downsample; } + + /** \brief Get the state of the internal downsampling parameter (true if + * all fields need to be downsampled, false if just XYZ). + */ + inline bool + getDownsampleAllData () { return (downsample_all_data_); } + + /** \brief Set the minimum number of points required for a voxel to be used. + * \param[in] min_points_per_voxel the minimum number of points for required for a voxel to be used + */ + inline void + setMinimumPointsNumberPerVoxel (unsigned int min_points_per_voxel) { min_points_per_voxel_ = min_points_per_voxel; } + + /** \brief Return the minimum number of points required for a voxel to be used. + */ + inline unsigned int + getMinimumPointsNumberPerVoxel () { return min_points_per_voxel_; } + + /** \brief Set to true if leaf layout information needs to be saved for later access. + * \param[in] save_leaf_layout the new value (true/false) + */ + inline void + setSaveLeafLayout (bool save_leaf_layout) { save_leaf_layout_ = save_leaf_layout; } + + /** \brief Returns true if leaf layout information will to be saved for later access. */ + inline bool + getSaveLeafLayout () { return (save_leaf_layout_); } + + /** \brief Get the minimum coordinates of the bounding box (after + * filtering is performed). + */ + inline Eigen::Vector3i + getMinBoxCoordinates () { return (min_b_.head<3> ()); } + + /** \brief Get the minimum coordinates of the bounding box (after + * filtering is performed). + */ + inline Eigen::Vector3i + getMaxBoxCoordinates () { return (max_b_.head<3> ()); } + + /** \brief Get the number of divisions along all 3 axes (after filtering + * is performed). + */ + inline Eigen::Vector3i + getNrDivisions () { return (div_b_.head<3> ()); } + + /** \brief Get the multipliers to be applied to the grid coordinates in + * order to find the centroid index (after filtering is performed). + */ + inline Eigen::Vector3i + getDivisionMultiplier () { return (divb_mul_.head<3> ()); } + + /** \brief Returns the index in the resulting downsampled cloud of the specified point. + * + * \note for efficiency, user must make sure that the saving of the leaf layout is enabled and filtering + * performed, and that the point is inside the grid, to avoid invalid access (or use + * getGridCoordinates+getCentroidIndexAt) + * + * \param[in] p the point to get the index at + */ + inline int + getCentroidIndex (const PointT &p) + { + return (leaf_layout_.at ((Eigen::Vector4i (static_cast (floor (p.x * inverse_leaf_size_[0])), + static_cast (floor (p.y * inverse_leaf_size_[1])), + static_cast (floor (p.z * inverse_leaf_size_[2])), 0) - min_b_).dot (divb_mul_))); + } + + /** \brief Returns the indices in the resulting downsampled cloud of the points at the specified grid coordinates, + * relative to the grid coordinates of the specified point (or -1 if the cell was empty/out of bounds). + * \param[in] reference_point the coordinates of the reference point (corresponding cell is allowed to be empty/out of bounds) + * \param[in] relative_coordinates matrix with the columns being the coordinates of the requested cells, relative to the reference point's cell + * \note for efficiency, user must make sure that the saving of the leaf layout is enabled and filtering performed + */ + inline std::vector + getNeighborCentroidIndices (const PointT &reference_point, const Eigen::MatrixXi &relative_coordinates) + { + Eigen::Vector4i ijk (static_cast (floor (reference_point.x * inverse_leaf_size_[0])), + static_cast (floor (reference_point.y * inverse_leaf_size_[1])), + static_cast (floor (reference_point.z * inverse_leaf_size_[2])), 0); + Eigen::Array4i diff2min = min_b_ - ijk; + Eigen::Array4i diff2max = max_b_ - ijk; + std::vector neighbors (relative_coordinates.cols()); + for (int ni = 0; ni < relative_coordinates.cols (); ni++) + { + Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished(); + // checking if the specified cell is in the grid + if ((diff2min <= displacement.array()).all() && (diff2max >= displacement.array()).all()) + neighbors[ni] = leaf_layout_[((ijk + displacement - min_b_).dot (divb_mul_))]; // .at() can be omitted + else + neighbors[ni] = -1; // cell is out of bounds, consider it empty + } + return (neighbors); + } + + /** \brief Returns the layout of the leafs for fast access to cells relative to current position. + * \note position at (i-min_x) + (j-min_y)*div_x + (k-min_z)*div_x*div_y holds the index of the element at coordinates (i,j,k) in the grid (-1 if empty) + */ + inline std::vector + getLeafLayout () { return (leaf_layout_); } + + /** \brief Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z). + * \param[in] x the X point coordinate to get the (i, j, k) index at + * \param[in] y the Y point coordinate to get the (i, j, k) index at + * \param[in] z the Z point coordinate to get the (i, j, k) index at + */ + inline Eigen::Vector3i + getGridCoordinates (float x, float y, float z) + { + return (Eigen::Vector3i (static_cast (floor (x * inverse_leaf_size_[0])), + static_cast (floor (y * inverse_leaf_size_[1])), + static_cast (floor (z * inverse_leaf_size_[2])))); + } + + /** \brief Returns the index in the downsampled cloud corresponding to a given set of coordinates. + * \param[in] ijk the coordinates (i,j,k) in the grid (-1 if empty) + */ + inline int + getCentroidIndexAt (const Eigen::Vector3i &ijk) + { + int idx = ((Eigen::Vector4i() << ijk, 0).finished() - min_b_).dot (divb_mul_); + if (idx < 0 || idx >= static_cast (leaf_layout_.size ())) // this checks also if leaf_layout_.size () == 0 i.e. everything was computed as needed + { + //if (verbose) + // PCL_ERROR ("[pcl::%s::getCentroidIndexAt] Specified coordinate is outside grid bounds, or leaf layout is not saved, make sure to call setSaveLeafLayout(true) and filter(output) first!\n", getClassName ().c_str ()); + return (-1); + } + return (leaf_layout_[idx]); + } + + /** \brief Provide the name of the field to be used for filtering data. In conjunction with \a setFilterLimits, + * points having values outside this interval will be discarded. + * \param[in] field_name the name of the field that contains values used for filtering + */ + inline void + setFilterFieldName (const std::string &field_name) + { + filter_field_name_ = field_name; + } + + /** \brief Get the name of the field used for filtering. */ + inline std::string const + getFilterFieldName () + { + return (filter_field_name_); + } + + /** \brief Set the field filter limits. All points having field values outside this interval will be discarded. + * \param[in] limit_min the minimum allowed field value + * \param[in] limit_max the maximum allowed field value + */ + inline void + setFilterLimits (const double &limit_min, const double &limit_max) + { + filter_limit_min_ = limit_min; + filter_limit_max_ = limit_max; + } + + /** \brief Get the field filter limits (min/max) set by the user. The default values are -FLT_MAX, FLT_MAX. + * \param[out] limit_min the minimum allowed field value + * \param[out] limit_max the maximum allowed field value + */ + inline void + getFilterLimits (double &limit_min, double &limit_max) + { + limit_min = filter_limit_min_; + limit_max = filter_limit_max_; + } + + /** \brief Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max). + * Default: false. + * \param[in] limit_negative return data inside the interval (false) or outside (true) + */ + inline void + setFilterLimitsNegative (const bool limit_negative) + { + filter_limit_negative_ = limit_negative; + } + + /** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). + * \param[out] limit_negative true if data \b outside the interval [min; max] is to be returned, false otherwise + */ + inline void + getFilterLimitsNegative (bool &limit_negative) + { + limit_negative = filter_limit_negative_; + } + + /** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). + * \return true if data \b outside the interval [min; max] is to be returned, false otherwise + */ + inline bool + getFilterLimitsNegative () + { + return (filter_limit_negative_); + } + + protected: + /** \brief The size of a leaf. */ + Eigen::Vector4f leaf_size_; + + /** \brief Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons. */ + Eigen::Array4f inverse_leaf_size_; + + /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. */ + bool downsample_all_data_; + + /** \brief Set to true if leaf layout information needs to be saved in \a leaf_layout_. */ + bool save_leaf_layout_; + + /** \brief The leaf layout information for fast access to cells relative to current position **/ + std::vector leaf_layout_; + + /** \brief The minimum and maximum bin coordinates, the number of divisions, and the division multiplier. */ + Eigen::Vector4i min_b_, max_b_, div_b_, divb_mul_; + + /** \brief The desired user filter field name. */ + std::string filter_field_name_; + + /** \brief The minimum allowed filter value a point will be considered from. */ + double filter_limit_min_; + + /** \brief The maximum allowed filter value a point will be considered from. */ + double filter_limit_max_; + + /** \brief Set to true if we want to return the data outside (\a filter_limit_min_;\a filter_limit_max_). Default: false. */ + bool filter_limit_negative_; + + /** \brief Minimum number of points per voxel for the centroid to be computed */ + unsigned int min_points_per_voxel_; + + typedef typename pcl::traits::fieldList::type FieldList; + + /** \brief Downsample a Point Cloud using a voxelized grid approach + * \param[out] output the resultant point cloud message + */ + void + applyFilter (PointCloud &output); + }; + + /** \brief VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. + * + * The VoxelGrid class creates a *3D voxel grid* (think about a voxel + * grid as a set of tiny 3D boxes in space) over the input point cloud data. + * Then, in each *voxel* (i.e., 3D box), all the points present will be + * approximated (i.e., *downsampled*) with their centroid. This approach is + * a bit slower than approximating them with the center of the voxel, but it + * represents the underlying surface more accurately. + * + * \author Radu B. Rusu, Bastian Steder, Radoslaw Cybulski + * \ingroup filters + */ + template <> + class PCL_EXPORTS VoxelGrid : public Filter + { + using Filter::filter_name_; + using Filter::getClassName; + + typedef pcl::PCLPointCloud2 PCLPointCloud2; + typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr; + typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr; + + public: + /** \brief Empty constructor. */ + VoxelGrid () : + leaf_size_ (Eigen::Vector4f::Zero ()), + inverse_leaf_size_ (Eigen::Array4f::Zero ()), + downsample_all_data_ (true), + save_leaf_layout_ (false), + leaf_layout_ (), + min_b_ (Eigen::Vector4i::Zero ()), + max_b_ (Eigen::Vector4i::Zero ()), + div_b_ (Eigen::Vector4i::Zero ()), + divb_mul_ (Eigen::Vector4i::Zero ()), + filter_field_name_ (""), + filter_limit_min_ (-FLT_MAX), + filter_limit_max_ (FLT_MAX), + filter_limit_negative_ (false), + min_points_per_voxel_ (0) + { + filter_name_ = "VoxelGrid"; + } + + /** \brief Destructor. */ + virtual ~VoxelGrid () + { + } + + /** \brief Set the voxel grid leaf size. + * \param[in] leaf_size the voxel grid leaf size + */ + inline void + setLeafSize (const Eigen::Vector4f &leaf_size) + { + leaf_size_ = leaf_size; + // Avoid division errors + if (leaf_size_[3] == 0) + leaf_size_[3] = 1; + // Use multiplications instead of divisions + inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array (); + } + + /** \brief Set the voxel grid leaf size. + * \param[in] lx the leaf size for X + * \param[in] ly the leaf size for Y + * \param[in] lz the leaf size for Z + */ + inline void + setLeafSize (float lx, float ly, float lz) + { + leaf_size_[0] = lx; leaf_size_[1] = ly; leaf_size_[2] = lz; + // Avoid division errors + if (leaf_size_[3] == 0) + leaf_size_[3] = 1; + // Use multiplications instead of divisions + inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array (); + } + + /** \brief Get the voxel grid leaf size. */ + inline Eigen::Vector3f + getLeafSize () { return (leaf_size_.head<3> ()); } + + /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. + * \param[in] downsample the new value (true/false) + */ + inline void + setDownsampleAllData (bool downsample) { downsample_all_data_ = downsample; } + + /** \brief Get the state of the internal downsampling parameter (true if + * all fields need to be downsampled, false if just XYZ). + */ + inline bool + getDownsampleAllData () { return (downsample_all_data_); } + + /** \brief Set the minimum number of points required for a voxel to be used. + * \param[in] min_points_per_voxel the minimum number of points for required for a voxel to be used + */ + inline void + setMinimumPointsNumberPerVoxel (unsigned int min_points_per_voxel) { min_points_per_voxel_ = min_points_per_voxel; } + + /** \brief Return the minimum number of points required for a voxel to be used. + */ + inline unsigned int + getMinimumPointsNumberPerVoxel () { return min_points_per_voxel_; } + + /** \brief Set to true if leaf layout information needs to be saved for later access. + * \param[in] save_leaf_layout the new value (true/false) + */ + inline void + setSaveLeafLayout (bool save_leaf_layout) { save_leaf_layout_ = save_leaf_layout; } + + /** \brief Returns true if leaf layout information will to be saved for later access. */ + inline bool + getSaveLeafLayout () { return (save_leaf_layout_); } + + /** \brief Get the minimum coordinates of the bounding box (after + * filtering is performed). + */ + inline Eigen::Vector3i + getMinBoxCoordinates () { return (min_b_.head<3> ()); } + + /** \brief Get the minimum coordinates of the bounding box (after + * filtering is performed). + */ + inline Eigen::Vector3i + getMaxBoxCoordinates () { return (max_b_.head<3> ()); } + + /** \brief Get the number of divisions along all 3 axes (after filtering + * is performed). + */ + inline Eigen::Vector3i + getNrDivisions () { return (div_b_.head<3> ()); } + + /** \brief Get the multipliers to be applied to the grid coordinates in + * order to find the centroid index (after filtering is performed). + */ + inline Eigen::Vector3i + getDivisionMultiplier () { return (divb_mul_.head<3> ()); } + + /** \brief Returns the index in the resulting downsampled cloud of the specified point. + * \note for efficiency, user must make sure that the saving of the leaf layout is enabled and filtering performed, + * and that the point is inside the grid, to avoid invalid access (or use getGridCoordinates+getCentroidIndexAt) + * \param[in] x the X point coordinate to get the index at + * \param[in] y the Y point coordinate to get the index at + * \param[in] z the Z point coordinate to get the index at + */ + inline int + getCentroidIndex (float x, float y, float z) + { + return (leaf_layout_.at ((Eigen::Vector4i (static_cast (floor (x * inverse_leaf_size_[0])), + static_cast (floor (y * inverse_leaf_size_[1])), + static_cast (floor (z * inverse_leaf_size_[2])), + 0) + - min_b_).dot (divb_mul_))); + } + + /** \brief Returns the indices in the resulting downsampled cloud of the points at the specified grid coordinates, + * relative to the grid coordinates of the specified point (or -1 if the cell was empty/out of bounds). + * \param[in] x the X coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds) + * \param[in] y the Y coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds) + * \param[in] z the Z coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds) + * \param[out] relative_coordinates matrix with the columns being the coordinates of the requested cells, relative to the reference point's cell + * \note for efficiency, user must make sure that the saving of the leaf layout is enabled and filtering performed + */ + inline std::vector + getNeighborCentroidIndices (float x, float y, float z, const Eigen::MatrixXi &relative_coordinates) + { + Eigen::Vector4i ijk (static_cast (floor (x * inverse_leaf_size_[0])), + static_cast (floor (y * inverse_leaf_size_[1])), + static_cast (floor (z * inverse_leaf_size_[2])), 0); + Eigen::Array4i diff2min = min_b_ - ijk; + Eigen::Array4i diff2max = max_b_ - ijk; + std::vector neighbors (relative_coordinates.cols()); + for (int ni = 0; ni < relative_coordinates.cols (); ni++) + { + Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished(); + // checking if the specified cell is in the grid + if ((diff2min <= displacement.array()).all() && (diff2max >= displacement.array()).all()) + neighbors[ni] = leaf_layout_[((ijk + displacement - min_b_).dot (divb_mul_))]; // .at() can be omitted + else + neighbors[ni] = -1; // cell is out of bounds, consider it empty + } + return (neighbors); + } + + /** \brief Returns the indices in the resulting downsampled cloud of the points at the specified grid coordinates, + * relative to the grid coordinates of the specified point (or -1 if the cell was empty/out of bounds). + * \param[in] x the X coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds) + * \param[in] y the Y coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds) + * \param[in] z the Z coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds) + * \param[out] relative_coordinates vector with the elements being the coordinates of the requested cells, relative to the reference point's cell + * \note for efficiency, user must make sure that the saving of the leaf layout is enabled and filtering performed + */ + inline std::vector + getNeighborCentroidIndices (float x, float y, float z, const std::vector &relative_coordinates) + { + Eigen::Vector4i ijk (static_cast (floorf (x * inverse_leaf_size_[0])), static_cast (floorf (y * inverse_leaf_size_[1])), static_cast (floorf (z * inverse_leaf_size_[2])), 0); + std::vector neighbors; + neighbors.reserve (relative_coordinates.size ()); + for (std::vector::const_iterator it = relative_coordinates.begin (); it != relative_coordinates.end (); it++) + neighbors.push_back (leaf_layout_[(ijk + (Eigen::Vector4i() << *it, 0).finished() - min_b_).dot (divb_mul_)]); + return (neighbors); + } + + /** \brief Returns the layout of the leafs for fast access to cells relative to current position. + * \note position at (i-min_x) + (j-min_y)*div_x + (k-min_z)*div_x*div_y holds the index of the element at coordinates (i,j,k) in the grid (-1 if empty) + */ + inline std::vector + getLeafLayout () { return (leaf_layout_); } + + /** \brief Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z). + * \param[in] x the X point coordinate to get the (i, j, k) index at + * \param[in] y the Y point coordinate to get the (i, j, k) index at + * \param[in] z the Z point coordinate to get the (i, j, k) index at + */ + inline Eigen::Vector3i + getGridCoordinates (float x, float y, float z) + { + return (Eigen::Vector3i (static_cast (floor (x * inverse_leaf_size_[0])), + static_cast (floor (y * inverse_leaf_size_[1])), + static_cast (floor (z * inverse_leaf_size_[2])))); + } + + /** \brief Returns the index in the downsampled cloud corresponding to a given set of coordinates. + * \param[in] ijk the coordinates (i,j,k) in the grid (-1 if empty) + */ + inline int + getCentroidIndexAt (const Eigen::Vector3i &ijk) + { + int idx = ((Eigen::Vector4i() << ijk, 0).finished() - min_b_).dot (divb_mul_); + if (idx < 0 || idx >= static_cast (leaf_layout_.size ())) // this checks also if leaf_layout_.size () == 0 i.e. everything was computed as needed + { + //if (verbose) + // PCL_ERROR ("[pcl::%s::getCentroidIndexAt] Specified coordinate is outside grid bounds, or leaf layout is not saved, make sure to call setSaveLeafLayout(true) and filter(output) first!\n", getClassName ().c_str ()); + return (-1); + } + return (leaf_layout_[idx]); + } + + /** \brief Provide the name of the field to be used for filtering data. In conjunction with \a setFilterLimits, + * points having values outside this interval will be discarded. + * \param[in] field_name the name of the field that contains values used for filtering + */ + inline void + setFilterFieldName (const std::string &field_name) + { + filter_field_name_ = field_name; + } + + /** \brief Get the name of the field used for filtering. */ + inline std::string const + getFilterFieldName () + { + return (filter_field_name_); + } + + /** \brief Set the field filter limits. All points having field values outside this interval will be discarded. + * \param[in] limit_min the minimum allowed field value + * \param[in] limit_max the maximum allowed field value + */ + inline void + setFilterLimits (const double &limit_min, const double &limit_max) + { + filter_limit_min_ = limit_min; + filter_limit_max_ = limit_max; + } + + /** \brief Get the field filter limits (min/max) set by the user. The default values are -FLT_MAX, FLT_MAX. + * \param[out] limit_min the minimum allowed field value + * \param[out] limit_max the maximum allowed field value + */ + inline void + getFilterLimits (double &limit_min, double &limit_max) + { + limit_min = filter_limit_min_; + limit_max = filter_limit_max_; + } + + /** \brief Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max). + * Default: false. + * \param[in] limit_negative return data inside the interval (false) or outside (true) + */ + inline void + setFilterLimitsNegative (const bool limit_negative) + { + filter_limit_negative_ = limit_negative; + } + + /** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). + * \param[out] limit_negative true if data \b outside the interval [min; max] is to be returned, false otherwise + */ + inline void + getFilterLimitsNegative (bool &limit_negative) + { + limit_negative = filter_limit_negative_; + } + + /** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). + * \return true if data \b outside the interval [min; max] is to be returned, false otherwise + */ + inline bool + getFilterLimitsNegative () + { + return (filter_limit_negative_); + } + + protected: + /** \brief The size of a leaf. */ + Eigen::Vector4f leaf_size_; + + /** \brief Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons. */ + Eigen::Array4f inverse_leaf_size_; + + /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. */ + bool downsample_all_data_; + + /** \brief Set to true if leaf layout information needs to be saved in \a + * leaf_layout. + */ + bool save_leaf_layout_; + + /** \brief The leaf layout information for fast access to cells relative + * to current position + */ + std::vector leaf_layout_; + + /** \brief The minimum and maximum bin coordinates, the number of + * divisions, and the division multiplier. + */ + Eigen::Vector4i min_b_, max_b_, div_b_, divb_mul_; + + /** \brief The desired user filter field name. */ + std::string filter_field_name_; + + /** \brief The minimum allowed filter value a point will be considered from. */ + double filter_limit_min_; + + /** \brief The maximum allowed filter value a point will be considered from. */ + double filter_limit_max_; + + /** \brief Set to true if we want to return the data outside (\a filter_limit_min_;\a filter_limit_max_). Default: false. */ + bool filter_limit_negative_; + + /** \brief Minimum number of points per voxel for the centroid to be computed */ + unsigned int min_points_per_voxel_; + + /** \brief Downsample a Point Cloud using a voxelized grid approach + * \param[out] output the resultant point cloud + */ + void + applyFilter (PCLPointCloud2 &output); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FILTERS_VOXEL_GRID_MAP_H_ diff --git a/pcl-1.7/pcl/filters/voxel_grid_covariance.h b/pcl-1.7/pcl/filters/voxel_grid_covariance.h new file mode 100644 index 0000000..d4e6a09 --- /dev/null +++ b/pcl-1.7/pcl/filters/voxel_grid_covariance.h @@ -0,0 +1,547 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_VOXEL_GRID_COVARIANCE_H_ +#define PCL_VOXEL_GRID_COVARIANCE_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief A searchable voxel strucure containing the mean and covariance of the data. + * \note For more information please see + * Magnusson, M. (2009). The Three-Dimensional Normal-Distributions Transform — + * an Efï¬cient Representation for Registration, Surface Analysis, and Loop Detection. + * PhD thesis, Orebro University. Orebro Studies in Technology 36 + * \author Brian Okorn (Space and Naval Warfare Systems Center Pacific) + */ + template + class VoxelGridCovariance : public VoxelGrid + { + protected: + using VoxelGrid::filter_name_; + using VoxelGrid::getClassName; + using VoxelGrid::input_; + using VoxelGrid::indices_; + using VoxelGrid::filter_limit_negative_; + using VoxelGrid::filter_limit_min_; + using VoxelGrid::filter_limit_max_; + using VoxelGrid::filter_field_name_; + + using VoxelGrid::downsample_all_data_; + using VoxelGrid::leaf_layout_; + using VoxelGrid::save_leaf_layout_; + using VoxelGrid::leaf_size_; + using VoxelGrid::min_b_; + using VoxelGrid::max_b_; + using VoxelGrid::inverse_leaf_size_; + using VoxelGrid::div_b_; + using VoxelGrid::divb_mul_; + + + typedef typename pcl::traits::fieldList::type FieldList; + typedef typename Filter::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + + typedef boost::shared_ptr< VoxelGrid > Ptr; + typedef boost::shared_ptr< const VoxelGrid > ConstPtr; + + + /** \brief Simple structure to hold a centroid, covarince and the number of points in a leaf. + * Inverse covariance, eigen vectors and engen values are precomputed. */ + struct Leaf + { + /** \brief Constructor. + * Sets \ref nr_points, \ref icov_, \ref mean_ and \ref evals_ to 0 and \ref cov_ and \ref evecs_ to the identity matrix + */ + Leaf () : + nr_points (0), + mean_ (Eigen::Vector3d::Zero ()), + centroid (), + cov_ (Eigen::Matrix3d::Identity ()), + icov_ (Eigen::Matrix3d::Zero ()), + evecs_ (Eigen::Matrix3d::Identity ()), + evals_ (Eigen::Vector3d::Zero ()) + { + } + + /** \brief Get the voxel covariance. + * \return covariance matrix + */ + Eigen::Matrix3d + getCov () const + { + return (cov_); + } + + /** \brief Get the inverse of the voxel covariance. + * \return inverse covariance matrix + */ + Eigen::Matrix3d + getInverseCov () const + { + return (icov_); + } + + /** \brief Get the voxel centroid. + * \return centroid + */ + Eigen::Vector3d + getMean () const + { + return (mean_); + } + + /** \brief Get the eigen vectors of the voxel covariance. + * \note Order corresponds with \ref getEvals + * \return matrix whose columns contain eigen vectors + */ + Eigen::Matrix3d + getEvecs () const + { + return (evecs_); + } + + /** \brief Get the eigen values of the voxel covariance. + * \note Order corresponds with \ref getEvecs + * \return vector of eigen values + */ + Eigen::Vector3d + getEvals () const + { + return (evals_); + } + + /** \brief Get the number of points contained by this voxel. + * \return number of points + */ + int + getPointCount () const + { + return (nr_points); + } + + /** \brief Number of points contained by voxel */ + int nr_points; + + /** \brief 3D voxel centroid */ + Eigen::Vector3d mean_; + + /** \brief Nd voxel centroid + * \note Differs from \ref mean_ when color data is used + */ + Eigen::VectorXf centroid; + + /** \brief Voxel covariance matrix */ + Eigen::Matrix3d cov_; + + /** \brief Inverse of voxel covariance matrix */ + Eigen::Matrix3d icov_; + + /** \brief Eigen vectors of voxel covariance matrix */ + Eigen::Matrix3d evecs_; + + /** \brief Eigen values of voxel covariance matrix */ + Eigen::Vector3d evals_; + + }; + + /** \brief Pointer to VoxelGridCovariance leaf structure */ + typedef Leaf* LeafPtr; + + /** \brief Const pointer to VoxelGridCovariance leaf structure */ + typedef const Leaf* LeafConstPtr; + + public: + + /** \brief Constructor. + * Sets \ref leaf_size_ to 0 and \ref searchable_ to false. + */ + VoxelGridCovariance () : + searchable_ (true), + min_points_per_voxel_ (6), + min_covar_eigvalue_mult_ (0.01), + leaves_ (), + voxel_centroids_ (), + voxel_centroids_leaf_indices_ (), + kdtree_ () + { + downsample_all_data_ = false; + save_leaf_layout_ = false; + leaf_size_.setZero (); + min_b_.setZero (); + max_b_.setZero (); + filter_name_ = "VoxelGridCovariance"; + } + + /** \brief Set the minimum number of points required for a cell to be used (must be 3 or greater for covariance calculation). + * \param[in] min_points_per_voxel the minimum number of points for required for a voxel to be used + */ + inline void + setMinPointPerVoxel (int min_points_per_voxel) + { + if(min_points_per_voxel > 2) + { + min_points_per_voxel_ = min_points_per_voxel; + } + else + { + PCL_WARN ("%s: Covariance calculation requires at least 3 points, setting Min Point per Voxel to 3 ", this->getClassName ().c_str ()); + min_points_per_voxel_ = 3; + } + } + + /** \brief Get the minimum number of points required for a cell to be used. + * \return the minimum number of points for required for a voxel to be used + */ + inline int + getMinPointPerVoxel () + { + return min_points_per_voxel_; + } + + /** \brief Set the minimum allowable ratio between eigenvalues to prevent singular covariance matrices. + * \param[in] min_covar_eigvalue_mult the minimum allowable ratio between eigenvalues + */ + inline void + setCovEigValueInflationRatio (double min_covar_eigvalue_mult) + { + min_covar_eigvalue_mult_ = min_covar_eigvalue_mult; + } + + /** \brief Get the minimum allowable ratio between eigenvalues to prevent singular covariance matrices. + * \return the minimum allowable ratio between eigenvalues + */ + inline double + getCovEigValueInflationRatio () + { + return min_covar_eigvalue_mult_; + } + + /** \brief Filter cloud and initializes voxel structure. + * \param[out] output cloud containing centroids of voxels containing a sufficient number of points + * \param[in] searchable flag if voxel structure is searchable, if true then kdtree is built + */ + inline void + filter (PointCloud &output, bool searchable = false) + { + searchable_ = searchable; + applyFilter (output); + + voxel_centroids_ = PointCloudPtr (new PointCloud (output)); + + if (searchable_ && voxel_centroids_->size() > 0) + { + // Initiates kdtree of the centroids of voxels containing a sufficient number of points + kdtree_.setInputCloud (voxel_centroids_); + } + } + + /** \brief Initializes voxel structure. + * \param[in] searchable flag if voxel structure is searchable, if true then kdtree is built + */ + inline void + filter (bool searchable = false) + { + searchable_ = searchable; + voxel_centroids_ = PointCloudPtr (new PointCloud); + applyFilter (*voxel_centroids_); + + if (searchable_ && voxel_centroids_->size() > 0) + { + // Initiates kdtree of the centroids of voxels containing a sufficient number of points + kdtree_.setInputCloud (voxel_centroids_); + } + } + + /** \brief Get the voxel containing point p. + * \param[in] index the index of the leaf structure node + * \return const pointer to leaf structure + */ + inline LeafConstPtr + getLeaf (int index) + { + typename std::map::iterator leaf_iter = leaves_.find (index); + if (leaf_iter != leaves_.end ()) + { + LeafConstPtr ret (&(leaf_iter->second)); + return ret; + } + else + return NULL; + } + + /** \brief Get the voxel containing point p. + * \param[in] p the point to get the leaf structure at + * \return const pointer to leaf structure + */ + inline LeafConstPtr + getLeaf (PointT &p) + { + // Generate index associated with p + int ijk0 = static_cast (floor (p.x * inverse_leaf_size_[0]) - min_b_[0]); + int ijk1 = static_cast (floor (p.y * inverse_leaf_size_[1]) - min_b_[1]); + int ijk2 = static_cast (floor (p.z * inverse_leaf_size_[2]) - min_b_[2]); + + // Compute the centroid leaf index + int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2]; + + // Find leaf associated with index + typename std::map::iterator leaf_iter = leaves_.find (idx); + if (leaf_iter != leaves_.end ()) + { + // If such a leaf exists return the pointer to the leaf structure + LeafConstPtr ret (&(leaf_iter->second)); + return ret; + } + else + return NULL; + } + + /** \brief Get the voxel containing point p. + * \param[in] p the point to get the leaf structure at + * \return const pointer to leaf structure + */ + inline LeafConstPtr + getLeaf (Eigen::Vector3f &p) + { + // Generate index associated with p + int ijk0 = static_cast (floor (p[0] * inverse_leaf_size_[0]) - min_b_[0]); + int ijk1 = static_cast (floor (p[1] * inverse_leaf_size_[1]) - min_b_[1]); + int ijk2 = static_cast (floor (p[2] * inverse_leaf_size_[2]) - min_b_[2]); + + // Compute the centroid leaf index + int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2]; + + // Find leaf associated with index + typename std::map::iterator leaf_iter = leaves_.find (idx); + if (leaf_iter != leaves_.end ()) + { + // If such a leaf exists return the pointer to the leaf structure + LeafConstPtr ret (&(leaf_iter->second)); + return ret; + } + else + return NULL; + + } + + /** \brief Get the voxels surrounding point p, not including the voxel contating point p. + * \note Only voxels containing a sufficient number of points are used (slower than radius search in practice). + * \param[in] reference_point the point to get the leaf structure at + * \param[out] neighbors + * \return number of neighbors found + */ + int + getNeighborhoodAtPoint (const PointT& reference_point, std::vector &neighbors); + + /** \brief Get the leaf structure map + * \return a map contataining all leaves + */ + inline const std::map& + getLeaves () + { + return leaves_; + } + + /** \brief Get a pointcloud containing the voxel centroids + * \note Only voxels containing a sufficient number of points are used. + * \return a map contataining all leaves + */ + inline PointCloudPtr + getCentroids () + { + return voxel_centroids_; + } + + + /** \brief Get a cloud to visualize each voxels normal distribution. + * \param[out] cell_cloud a cloud created by sampling the normal distributions of each voxel + */ + void + getDisplayCloud (pcl::PointCloud& cell_cloud); + + /** \brief Search for the k-nearest occupied voxels for the given query point. + * \note Only voxels containing a sufficient number of points are used. + * \param[in] point the given query point + * \param[in] k the number of neighbors to search for + * \param[out] k_leaves the resultant leaves of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \return number of neighbors found + */ + int + nearestKSearch (const PointT &point, int k, + std::vector &k_leaves, std::vector &k_sqr_distances) + { + k_leaves.clear (); + + // Check if kdtree has been built + if (!searchable_) + { + PCL_WARN ("%s: Not Searchable", this->getClassName ().c_str ()); + return 0; + } + + // Find k-nearest neighbors in the occupied voxel centroid cloud + std::vector k_indices; + k = kdtree_.nearestKSearch (point, k, k_indices, k_sqr_distances); + + // Find leaves corresponding to neighbors + k_leaves.reserve (k); + for (std::vector::iterator iter = k_indices.begin (); iter != k_indices.end (); iter++) + { + k_leaves.push_back (&leaves_[voxel_centroids_leaf_indices_[*iter]]); + } + return k; + } + + /** \brief Search for the k-nearest occupied voxels for the given query point. + * \note Only voxels containing a sufficient number of points are used. + * \param[in] cloud the given query point + * \param[in] index the index + * \param[in] k the number of neighbors to search for + * \param[out] k_leaves the resultant leaves of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \return number of neighbors found + */ + inline int + nearestKSearch (const PointCloud &cloud, int index, int k, + std::vector &k_leaves, std::vector &k_sqr_distances) + { + if (index >= static_cast (cloud.points.size ()) || index < 0) + return (0); + return (nearestKSearch (cloud.points[index], k, k_leaves, k_sqr_distances)); + } + + + /** \brief Search for all the nearest occupied voxels of the query point in a given radius. + * \note Only voxels containing a sufficient number of points are used. + * \param[in] point the given query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_leaves the resultant leaves of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn + * \return number of neighbors found + */ + int + radiusSearch (const PointT &point, double radius, std::vector &k_leaves, + std::vector &k_sqr_distances, unsigned int max_nn = 0) + { + k_leaves.clear (); + + // Check if kdtree has been built + if (!searchable_) + { + PCL_WARN ("%s: Not Searchable", this->getClassName ().c_str ()); + return 0; + } + + // Find neighbors within radius in the occupied voxel centroid cloud + std::vector k_indices; + int k = kdtree_.radiusSearch (point, radius, k_indices, k_sqr_distances, max_nn); + + // Find leaves corresponding to neighbors + k_leaves.reserve (k); + for (std::vector::iterator iter = k_indices.begin (); iter != k_indices.end (); iter++) + { + k_leaves.push_back (&leaves_[voxel_centroids_leaf_indices_[*iter]]); + } + return k; + } + + /** \brief Search for all the nearest occupied voxels of the query point in a given radius. + * \note Only voxels containing a sufficient number of points are used. + * \param[in] cloud the given query point + * \param[in] index a valid index in cloud representing a valid (i.e., finite) query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_leaves the resultant leaves of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn + * \return number of neighbors found + */ + inline int + radiusSearch (const PointCloud &cloud, int index, double radius, + std::vector &k_leaves, std::vector &k_sqr_distances, + unsigned int max_nn = 0) + { + if (index >= static_cast (cloud.points.size ()) || index < 0) + return (0); + return (radiusSearch (cloud.points[index], radius, k_leaves, k_sqr_distances, max_nn)); + } + + protected: + + /** \brief Filter cloud and initializes voxel structure. + * \param[out] output cloud containing centroids of voxels containing a sufficient number of points + */ + void applyFilter (PointCloud &output); + + /** \brief Flag to determine if voxel structure is searchable. */ + bool searchable_; + + /** \brief Minimum points contained with in a voxel to allow it to be useable. */ + int min_points_per_voxel_; + + /** \brief Minimum allowable ratio between eigenvalues to prevent singular covariance matrices. */ + double min_covar_eigvalue_mult_; + + /** \brief Voxel structure containing all leaf nodes (includes voxels with less than a sufficient number of points). */ + std::map leaves_; + + /** \brief Point cloud containing centroids of voxels containing atleast minimum number of points. */ + PointCloudPtr voxel_centroids_; + + /** \brief Indices of leaf structurs associated with each point in \ref voxel_centroids_ (used for searching). */ + std::vector voxel_centroids_leaf_indices_; + + /** \brief KdTree generated using \ref voxel_centroids_ (used for searching). */ + KdTreeFLANN kdtree_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_VOXEL_GRID_COVARIANCE_H_ diff --git a/pcl-1.7/pcl/filters/voxel_grid_label.h b/pcl-1.7/pcl/filters/voxel_grid_label.h new file mode 100644 index 0000000..aca4dab --- /dev/null +++ b/pcl-1.7/pcl/filters/voxel_grid_label.h @@ -0,0 +1,75 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_VOXEL_GRID_LABEL_H_ +#define PCL_VOXEL_GRID_LABEL_H_ + +#include +#include + +namespace pcl +{ + /** \brief + * + * + * \author Christian Potthast (potthast@usc.edu) + */ + class PCL_EXPORTS VoxelGridLabel : public VoxelGrid + { + public: + + typedef boost::shared_ptr< VoxelGridLabel > Ptr; + typedef boost::shared_ptr< const VoxelGridLabel > ConstPtr; + + + /** \brief Constructor. + * Sets \ref leaf_size_ to 0 and \ref searchable_ to false. + */ + VoxelGridLabel () {}; + + protected: + + /** \brief Filter cloud and initializes voxel structure. + * \param[out] output cloud containing centroids of voxels containing a sufficient number of points + */ + void + applyFilter (PointCloud &output); + + }; +} + +#endif //#ifndef PCL_VOXEL_GRID_LABEL_H_ diff --git a/pcl-1.7/pcl/filters/voxel_grid_occlusion_estimation.h b/pcl-1.7/pcl/filters/voxel_grid_occlusion_estimation.h new file mode 100644 index 0000000..90e46b0 --- /dev/null +++ b/pcl-1.7/pcl/filters/voxel_grid_occlusion_estimation.h @@ -0,0 +1,253 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : Christian Potthast + * Email : potthast@usc.edu + * + */ + +#ifndef PCL_FILTERS_VOXEL_GRID_OCCLUSION_ESTIMATION_H_ +#define PCL_FILTERS_VOXEL_GRID_OCCLUSION_ESTIMATION_H_ + +#include + +namespace pcl +{ + /** \brief VoxelGrid to estimate occluded space in the scene. + * The ray traversal algorithm is implemented by the work of + * 'John Amanatides and Andrew Woo, A Fast Voxel Traversal Algorithm for Ray Tracing' + * + * \author Christian Potthast + * \ingroup filters + */ + template + class VoxelGridOcclusionEstimation: public VoxelGrid + { + protected: + using VoxelGrid::min_b_; + using VoxelGrid::max_b_; + using VoxelGrid::div_b_; + using VoxelGrid::leaf_size_; + using VoxelGrid::inverse_leaf_size_; + + typedef typename Filter::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + /** \brief Empty constructor. */ + VoxelGridOcclusionEstimation () + { + initialized_ = false; + this->setSaveLeafLayout (true); + } + + /** \brief Destructor. */ + virtual ~VoxelGridOcclusionEstimation () + { + } + + /** \brief Initialize the voxel grid, needs to be called first + * Builts the voxel grid and computes additional values for + * the ray traversal algorithm. + */ + void + initializeVoxelGrid (); + + /** \brief Returns the state (free = 0, occluded = 1) of the voxel + * after utilizing a ray traversal algorithm to a target voxel + * in (i, j, k) coordinates. + * \param[out] out_state The state of the voxel. + * \param[in] in_target_voxel The target voxel coordinate (i, j, k) of the voxel. + * \return the state (free = 0, occluded = 1) of the voxel + */ + int + occlusionEstimation (int& out_state, + const Eigen::Vector3i& in_target_voxel); + + /** \brief Returns the state (free = 0, occluded = 1) of the voxel + * after utilizing a ray traversal algorithm to a target voxel + * in (i, j, k) coordinates. Additionally, this function returns + * the voxels penetrated of the ray-traversal algorithm till reaching + * the target voxel. + * \param[out] out_state The state of the voxel. + * \param[out] out_ray The voxels penetrated of the ray-traversal algorithm. + * \param[in] in_target_voxel The target voxel coordinate (i, j, k) of the voxel. + * \return the state (free = 0, occluded = 1) of the voxel + */ + int + occlusionEstimation (int& out_state, + std::vector& out_ray, + const Eigen::Vector3i& in_target_voxel); + + /** \brief Returns the voxel coordinates (i, j, k) of all occluded + * voxels in the voxel gird. + * \param[out] occluded_voxels the coordinates (i, j, k) of all occluded voxels + * \return the voxel coordinates (i, j, k) + */ + int + occlusionEstimationAll (std::vector& occluded_voxels); + + /** \brief Returns the voxel grid filtered point cloud + * \return The voxel grid filtered point cloud + */ + inline PointCloud + getFilteredPointCloud () { return filtered_cloud_; } + + + /** \brief Returns the minimum bounding of coordinates of the voxel grid (x,y,z). + * \return the minimum coordinates (x,y,z) + */ + inline Eigen::Vector3f + getMinBoundCoordinates () { return (b_min_.head<3> ()); } + + /** \brief Returns the maximum bounding of coordinates of the voxel grid (x,y,z). + * \return the maximum coordinates (x,y,z) + */ + inline Eigen::Vector3f + getMaxBoundCoordinates () { return (b_max_.head<3> ()); } + + /** \brief Returns the corresponding centroid (x,y,z) coordinates + * in the grid of voxel (i,j,k). + * \param[in] ijk the coordinate (i, j, k) of the voxel + * \return the (x,y,z) coordinate of the voxel centroid + */ + inline Eigen::Vector4f + getCentroidCoordinate (const Eigen::Vector3i& ijk) + { + int i,j,k; + i = ((b_min_[0] < 0) ? (abs (min_b_[0]) + ijk[0]) : (ijk[0] - min_b_[0])); + j = ((b_min_[1] < 0) ? (abs (min_b_[1]) + ijk[1]) : (ijk[1] - min_b_[1])); + k = ((b_min_[2] < 0) ? (abs (min_b_[2]) + ijk[2]) : (ijk[2] - min_b_[2])); + + Eigen::Vector4f xyz; + xyz[0] = b_min_[0] + (leaf_size_[0] * 0.5f) + (static_cast (i) * leaf_size_[0]); + xyz[1] = b_min_[1] + (leaf_size_[1] * 0.5f) + (static_cast (j) * leaf_size_[1]); + xyz[2] = b_min_[2] + (leaf_size_[2] * 0.5f) + (static_cast (k) * leaf_size_[2]); + xyz[3] = 0; + return xyz; + } + + // inline void + // setSensorOrigin (const Eigen::Vector4f origin) { sensor_origin_ = origin; } + + // inline void + // setSensorOrientation (const Eigen::Quaternionf orientation) { sensor_orientation_ = orientation; } + + protected: + + /** \brief Returns the scaling value (tmin) were the ray intersects with the + * voxel grid bounding box. (p_entry = origin + tmin * orientation) + * \param[in] origin The sensor origin + * \param[in] direction The sensor orientation + * \return the scaling value + */ + float + rayBoxIntersection (const Eigen::Vector4f& origin, + const Eigen::Vector4f& direction); + + /** \brief Returns the state of the target voxel (0 = visible, 1 = occupied) + * unsing a ray traversal algorithm. + * \param[in] target_voxel The target voxel in the voxel grid with coordinate (i, j, k). + * \param[in] origin The sensor origin. + * \param[in] direction The sensor orientation + * \param[in] t_min The scaling value (tmin). + * \return The estimated voxel state. + */ + int + rayTraversal (const Eigen::Vector3i& target_voxel, + const Eigen::Vector4f& origin, + const Eigen::Vector4f& direction, + const float t_min); + + /** \brief Returns the state of the target voxel (0 = visible, 1 = occupied) and + * the voxels penetrated by the ray unsing a ray traversal algorithm. + * \param[out] out_ray The voxels penetrated by the ray in (i, j, k) coordinates + * \param[in] target_voxel The target voxel in the voxel grid with coordinate (i, j, k). + * \param[in] origin The sensor origin. + * \param[in] direction The sensor orientation + * \param[in] t_min The scaling value (tmin). + * \return The estimated voxel state. + */ + int + rayTraversal (std::vector & out_ray, + const Eigen::Vector3i& target_voxel, + const Eigen::Vector4f& origin, + const Eigen::Vector4f& direction, + const float t_min); + + /** \brief Returns a rounded value. + * \param[in] d + * \return rounded value + */ + inline float + round (float d) + { + return static_cast (floor (d + 0.5f)); + } + + // We use round here instead of floor due to some numerical issues. + /** \brief Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z). + * \param[in] x the X point coordinate to get the (i, j, k) index at + * \param[in] y the Y point coordinate to get the (i, j, k) index at + * \param[in] z the Z point coordinate to get the (i, j, k) index at + */ + inline Eigen::Vector3i + getGridCoordinatesRound (float x, float y, float z) + { + return Eigen::Vector3i (static_cast (round (x * inverse_leaf_size_[0])), + static_cast (round (y * inverse_leaf_size_[1])), + static_cast (round (z * inverse_leaf_size_[2]))); + } + + // initialization flag + bool initialized_; + + Eigen::Vector4f sensor_origin_; + Eigen::Quaternionf sensor_orientation_; + + // minimum and maximum bounding box coordinates + Eigen::Vector4f b_min_, b_max_; + + // voxel grid filtered cloud + PointCloud filtered_cloud_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_FILTERS_VOXEL_GRID_OCCLUSION_ESTIMATION_H_ diff --git a/pcl-1.7/pcl/for_each_type.h b/pcl-1.7/pcl/for_each_type.h new file mode 100644 index 0000000..d6973d4 --- /dev/null +++ b/pcl-1.7/pcl/for_each_type.h @@ -0,0 +1,109 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_FOR_EACH_TYPE_H_ +#define PCL_FOR_EACH_TYPE_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#ifndef Q_MOC_RUN +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#endif + +namespace pcl +{ + ////////////////////////////////////////////////////////////////////////////////////////////// + template + struct for_each_type_impl + { + template + static void execute (F) {} + }; + + ////////////////////////////////////////////////////////////////////////////////////////////// + template <> + struct for_each_type_impl + { + template + static void execute (F f) + { + typedef typename boost::mpl::deref::type arg; + +#if (defined _WIN32 && defined _MSC_VER) + boost::mpl::aux::unwrap (f, 0).operator() (); +#else + boost::mpl::aux::unwrap (f, 0).template operator() (); +#endif + + typedef typename boost::mpl::next::type iter; + for_each_type_impl::value> + ::template execute (f); + } + }; + + ////////////////////////////////////////////////////////////////////////////////////////////// + template inline void + for_each_type (F f) + { + BOOST_MPL_ASSERT (( boost::mpl::is_sequence )); + typedef typename boost::mpl::begin::type first; + typedef typename boost::mpl::end::type last; + for_each_type_impl::value>::template execute (f); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + struct intersect + { + typedef typename boost::mpl::remove_if > >::type type; + }; +} + +#endif //#ifndef PCL_FOR_EACH_TYPE_H_ diff --git a/pcl-1.7/pcl/geometry/boost.h b/pcl-1.7/pcl/geometry/boost.h new file mode 100644 index 0000000..e7ec3e8 --- /dev/null +++ b/pcl-1.7/pcl/geometry/boost.h @@ -0,0 +1,55 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_GEOMETRY_BOOST_H +#define PCL_GEOMETRY_BOOST_H + +#ifdef __GNUC__ +# pragma GCC system_header +#endif + +#include +#include +#include +#include +#include +#include + +#endif // PCL_GEOMETRY_BOOST_H diff --git a/pcl-1.7/pcl/geometry/eigen.h b/pcl-1.7/pcl/geometry/eigen.h new file mode 100644 index 0000000..caa8f3e --- /dev/null +++ b/pcl-1.7/pcl/geometry/eigen.h @@ -0,0 +1,51 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_GEOMETRY_EIGEN_H +#define PCL_GEOMETRY_EIGEN_H + +#ifdef __GNUC__ +# pragma GCC system_header +#endif + +#include +#include + +#endif // PCL_GEOMETRY_EIGEN_H diff --git a/pcl-1.7/pcl/geometry/get_boundary.h b/pcl-1.7/pcl/geometry/get_boundary.h new file mode 100644 index 0000000..ec08121 --- /dev/null +++ b/pcl-1.7/pcl/geometry/get_boundary.h @@ -0,0 +1,95 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_GEOMETRY_GET_BOUNDARY_H +#define PCL_GEOMETRY_GET_BOUNDARY_H + +#include + +namespace pcl +{ + namespace geometry + { + /** \brief Get a collection of boundary half-edges for the input mesh. + * \param[in] mesh The input mesh. + * \param[out] boundary_he_collection Collection of boundary half-edges. Each element in the vector is one connected boundary. The whole boundary is the union of all elements. + * \param [in] expected_size If you already know the size of the longest boundary you can tell this here. Defaults to 3 (minimum possible boundary). + * \author Martin Saelzle + * \ingroup geometry + */ + template void + getBoundBoundaryHalfEdges (const MeshT& mesh, + std::vector & boundary_he_collection, + const size_t expected_size = 3) + { + typedef MeshT Mesh; + typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex; + typedef typename Mesh::HalfEdgeIndices HalfEdgeIndices; + typedef typename Mesh::InnerHalfEdgeAroundFaceCirculator IHEAFC; + + boundary_he_collection.clear (); + + HalfEdgeIndices boundary_he; boundary_he.reserve (expected_size); + std::vector visited (mesh.sizeEdges (), false); + IHEAFC circ, circ_end; + + for (HalfEdgeIndex i (0); i + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::approximatePolygon (const PlanarPolygon& polygon, PlanarPolygon& approx_polygon, float threshold, bool refine, bool closed) +{ + const Eigen::Vector4f& coefficients = polygon.getCoefficients (); + const typename pcl::PointCloud::VectorType &contour = polygon.getContour (); + + Eigen::Vector3f rotation_axis (coefficients[1], -coefficients[0], 0.0f); + rotation_axis.normalize (); + + float rotation_angle = acosf (coefficients [2]); + Eigen::Affine3f transformation = Eigen::Translation3f (0, 0, coefficients [3]) * Eigen::AngleAxisf (rotation_angle, rotation_axis); + + typename pcl::PointCloud::VectorType polygon2D (contour.size ()); + for (unsigned pIdx = 0; pIdx < polygon2D.size (); ++pIdx) + polygon2D [pIdx].getVector3fMap () = transformation * contour [pIdx].getVector3fMap (); + + typename pcl::PointCloud::VectorType approx_polygon2D; + approximatePolygon2D (polygon2D, approx_polygon2D, threshold, refine, closed); + + typename pcl::PointCloud::VectorType &approx_contour = approx_polygon.getContour (); + approx_contour.resize (approx_polygon2D.size ()); + + Eigen::Affine3f inv_transformation = transformation.inverse (); + for (unsigned pIdx = 0; pIdx < approx_polygon2D.size (); ++pIdx) + approx_contour [pIdx].getVector3fMap () = inv_transformation * approx_polygon2D [pIdx].getVector3fMap (); +} + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::approximatePolygon2D (const typename pcl::PointCloud::VectorType &polygon, + typename pcl::PointCloud::VectorType &approx_polygon, + float threshold, bool refine, bool closed) +{ + approx_polygon.clear (); + if (polygon.size () < 3) + return; + + std::vector > intervals; + std::pair interval (0, 0); + + if (closed) + { + float max_distance = .0f; + for (unsigned idx = 1; idx < polygon.size (); ++idx) + { + float distance = (polygon [0].x - polygon [idx].x) * (polygon [0].x - polygon [idx].x) + + (polygon [0].y - polygon [idx].y) * (polygon [0].y - polygon [idx].y); + + if (distance > max_distance) + { + max_distance = distance; + interval.second = idx; + } + } + + for (unsigned idx = 1; idx < polygon.size (); ++idx) + { + float distance = (polygon [interval.second].x - polygon [idx].x) * (polygon [interval.second].x - polygon [idx].x) + + (polygon [interval.second].y - polygon [idx].y) * (polygon [interval.second].y - polygon [idx].y); + + if (distance > max_distance) + { + max_distance = distance; + interval.first = idx; + } + } + + if (max_distance < threshold * threshold) + return; + + intervals.push_back (interval); + std::swap (interval.first, interval.second); + intervals.push_back (interval); + } + else + { + interval.first = 0; + interval.second = static_cast (polygon.size ()) - 1; + intervals.push_back (interval); + } + + std::vector result; + // recursively refine + while (!intervals.empty ()) + { + std::pair& currentInterval = intervals.back (); + float line_x = polygon [currentInterval.first].y - polygon [currentInterval.second].y; + float line_y = polygon [currentInterval.second].x - polygon [currentInterval.first].x; + float line_d = polygon [currentInterval.first].x * polygon [currentInterval.second].y - polygon [currentInterval.first].y * polygon [currentInterval.second].x; + + float linelen = 1.0f / sqrtf (line_x * line_x + line_y * line_y); + + line_x *= linelen; + line_y *= linelen; + line_d *= linelen; + + float max_distance = 0.0; + unsigned first_index = currentInterval.first + 1; + unsigned max_index = 0; + + // => 0-crossing + if (currentInterval.first > currentInterval.second) + { + for (unsigned idx = first_index; idx < polygon.size(); idx++) + { + float distance = fabsf (line_x * polygon[idx].x + line_y * polygon[idx].y + line_d); + if (distance > max_distance) + { + max_distance = distance; + max_index = idx; + } + } + first_index = 0; + } + + for (unsigned int idx = first_index; idx < currentInterval.second; idx++) + { + float distance = fabsf (line_x * polygon[idx].x + line_y * polygon[idx].y + line_d); + if (distance > max_distance) + { + max_distance = distance; + max_index = idx; + } + } + + if (max_distance > threshold) + { + std::pair interval (max_index, currentInterval.second); + currentInterval.second = max_index; + intervals.push_back (interval); + } + else + { + result.push_back (currentInterval.second); + intervals.pop_back (); + } + } + + approx_polygon.reserve (result.size ()); + if (refine) + { + std::vector lines (result.size ()); + std::reverse (result.begin (), result.end ()); + for (unsigned rIdx = 0; rIdx < result.size (); ++rIdx) + { + unsigned nIdx = rIdx + 1; + if (nIdx == result.size ()) + nIdx = 0; + + Eigen::Vector2f centroid = Eigen::Vector2f::Zero (); + Eigen::Matrix2f covariance = Eigen::Matrix2f::Zero (); + unsigned pIdx = result[rIdx]; + unsigned num_points = 0; + if (pIdx > result[nIdx]) + { + num_points = static_cast (polygon.size ()) - pIdx; + for (; pIdx < polygon.size (); ++pIdx) + { + covariance.coeffRef (0) += polygon [pIdx].x * polygon [pIdx].x; + covariance.coeffRef (1) += polygon [pIdx].x * polygon [pIdx].y; + covariance.coeffRef (3) += polygon [pIdx].y * polygon [pIdx].y; + centroid [0] += polygon [pIdx].x; + centroid [1] += polygon [pIdx].y; + } + pIdx = 0; + } + + num_points += result[nIdx] - pIdx; + for (; pIdx < result[nIdx]; ++pIdx) + { + covariance.coeffRef (0) += polygon [pIdx].x * polygon [pIdx].x; + covariance.coeffRef (1) += polygon [pIdx].x * polygon [pIdx].y; + covariance.coeffRef (3) += polygon [pIdx].y * polygon [pIdx].y; + centroid [0] += polygon [pIdx].x; + centroid [1] += polygon [pIdx].y; + } + + covariance.coeffRef (2) = covariance.coeff (1); + + float norm = 1.0f / float (num_points); + centroid *= norm; + covariance *= norm; + covariance.coeffRef (0) -= centroid [0] * centroid [0]; + covariance.coeffRef (1) -= centroid [0] * centroid [1]; + covariance.coeffRef (3) -= centroid [1] * centroid [1]; + + float eval; + Eigen::Vector2f normal; + eigen22 (covariance, eval, normal); + + // select the one which is more "parallel" to the original line + Eigen::Vector2f direction; + direction [0] = polygon[result[nIdx]].x - polygon[result[rIdx]].x; + direction [1] = polygon[result[nIdx]].y - polygon[result[rIdx]].y; + direction.normalize (); + + if (fabs (direction.dot (normal)) > float(M_SQRT1_2)) + { + std::swap (normal [0], normal [1]); + normal [0] = -normal [0]; + } + + // needs to be on the left side of the edge + if (direction [0] * normal [1] < direction [1] * normal [0]) + normal *= -1.0; + + lines [rIdx].head<2> ().matrix () = normal; + lines [rIdx] [2] = -normal.dot (centroid); + } + + float threshold2 = threshold * threshold; + for (unsigned rIdx = 0; rIdx < lines.size (); ++rIdx) + { + unsigned nIdx = rIdx + 1; + if (nIdx == result.size ()) + nIdx = 0; + + Eigen::Vector3f vertex = lines [rIdx].cross (lines [nIdx]); + vertex /= vertex [2]; + vertex [2] = 0.0; + + PointT point; + // test whether we need another edge since the intersection point is too far away from the original vertex + Eigen::Vector3f pq = polygon [result[nIdx]].getVector3fMap () - vertex; + pq [2] = 0.0; + + float distance = pq.squaredNorm (); + if (distance > threshold2) + { + // test whether the old point is inside the new polygon or outside + if ((pq [0] * lines [rIdx] [0] + pq [1] * lines [rIdx] [1] < 0.0) && + (pq [0] * lines [nIdx] [0] + pq [1] * lines [nIdx] [1] < 0.0) ) + { + float distance1 = lines [rIdx] [0] * polygon[result[nIdx]].x + lines [rIdx] [1] * polygon[result[nIdx]].y + lines [rIdx] [2]; + float distance2 = lines [nIdx] [0] * polygon[result[nIdx]].x + lines [nIdx] [1] * polygon[result[nIdx]].y + lines [nIdx] [2]; + + point.x = polygon[result[nIdx]].x - distance1 * lines [rIdx] [0]; + point.y = polygon[result[nIdx]].y - distance1 * lines [rIdx] [1]; + + approx_polygon.push_back (point); + + vertex [0] = polygon[result[nIdx]].x - distance2 * lines [nIdx] [0]; + vertex [1] = polygon[result[nIdx]].y - distance2 * lines [nIdx] [1]; + } + } + point.getVector3fMap () = vertex; + approx_polygon.push_back (point); + } + } + else + { + // we have a new polygon in results, but inverted (clockwise <-> counter-clockwise) + for (std::vector::reverse_iterator it = result.rbegin (); it != result.rend (); ++it) + approx_polygon.push_back (polygon [*it]); + } +} + +#endif // PCL_GEOMETRY_POLYGON_OPERATIONS_HPP_ diff --git a/pcl-1.7/pcl/geometry/line_iterator.h b/pcl-1.7/pcl/geometry/line_iterator.h new file mode 100644 index 0000000..74d919c --- /dev/null +++ b/pcl-1.7/pcl/geometry/line_iterator.h @@ -0,0 +1,275 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef __PCL_LINE_ITERATOR__ +#define __PCL_LINE_ITERATOR__ +#include "organized_index_iterator.h" + +namespace pcl +{ +/** \brief Organized Index Iterator for iterating over the "pixels" for a given line using the Bresenham algorithm. + * Supports 4 and 8 neighborhood connectivity + * \note iterator does not visit the given end-point (on purpose). + * \author Suat Gedikli + * \ingroup geometry + */ +class LineIterator : public OrganizedIndexIterator +{ + public: + /** \brief Neighborhood connectivity */ + typedef enum {Neighbor4 = 4, Neighbor8 = 8} Neighborhood; + public: + /** \brief Constructor + * \param x_start column of the start pixel of the line + * \param y_start row of the start pixel of the line + * \param x_end column of the end pixel of the line + * \param y_end row of the end pixel of the line + * \param width width of the organized structure e.g. image/cloud/map etc.. + * \param neighborhood connectivity of the neighborhood + */ + LineIterator (unsigned x_start, unsigned y_start, unsigned x_end, unsigned y_end, unsigned width, const Neighborhood& neighborhood = Neighbor8); + + /** \brief Destructor*/ + virtual ~LineIterator (); + + virtual void operator ++ (); + virtual unsigned getRowIndex () const; + virtual unsigned getColumnIndex () const; + virtual bool isValid () const; + virtual void reset (); + protected: + /** \brief initializes the variables for the Bresenham algorithm + * \param[in] neighborhood connectivity to the neighborhood. Either 4 or 8 + */ + void init (const Neighborhood& neighborhood); + + /** \brief current column index*/ + unsigned x_; + + /** \brief current row index*/ + unsigned y_; + + /** \brief column index of first pixel/point*/ + unsigned x_start_; + + /** \brief row index of first pixel/point*/ + unsigned y_start_; + + /** \brief column index of end pixel/point*/ + unsigned x_end_; + + /** \brief row index of end pixel/point*/ + unsigned y_end_; + + // calculated values + /** \brief current distance to the line*/ + int error_; + + /** \brief error threshold*/ + int error_max_; + + /** \brief increment of error (distance) value in case of an y-step (if dx > dy)*/ + int error_minus_; + + /** \brief increment of error (distance) value in case of just an x-step (if dx > dy)*/ + int error_plus_; + + /** \brief increment of column index in case of just an x-step (if dx > dy)*/ + int x_plus_; + + /** \brief increment of row index in case of just an x-step (if dx > dy)*/ + int y_plus_; + + /** \brief increment of column index in case of just an y-step (if dx > dy)*/ + int x_minus_; + + /** \brief increment of row index in case of just an y-step (if dx > dy)*/ + int y_minus_; + + /** \brief increment pixel/point index in case of just an x-step (if dx > dy)*/ + int index_plus_; + + /** \brief increment pixel/point index in case of just an y-step (if dx > dy)*/ + int index_minus_; +}; + +//////////////////////////////////////////////////////////////////////////////// +//////////////////////////////////////////////////////////////////////////////// +//////////////////////////////////////////////////////////////////////////////// + + +//////////////////////////////////////////////////////////////////////////////// +inline LineIterator::LineIterator (unsigned x_start, unsigned y_start, unsigned x_end, unsigned y_end, unsigned width, const Neighborhood& neighborhood) +: OrganizedIndexIterator (width) +, x_start_ (x_start) +, y_start_ (y_start) +, x_end_ (x_end) +, y_end_ (y_end) +{ + init (neighborhood); +} + +//////////////////////////////////////////////////////////////////////////////// +inline LineIterator::~LineIterator () +{ +} + +//////////////////////////////////////////////////////////////////////////////// +inline void +LineIterator::init (const Neighborhood& neighborhood) +{ + x_ = x_start_; + y_ = y_start_; + index_ = x_ * width_ + y_; + error_ = 0; + + int delta_x = x_end_ - x_start_; + int delta_y = y_end_ - y_start_; + + int x_dir = ( (delta_x > 0) ? 1 : -1 ) ; + int y_dir = ( (delta_y > 0) ? 1 : -1 ) ; + + delta_x *= x_dir; + delta_y *= y_dir; + + if(delta_x >= delta_y) + { + if( neighborhood == Neighbor4 ) + { + error_max_ = delta_x - delta_y; + x_minus_ = 0; + y_minus_ = y_dir; + x_plus_ = x_dir; + y_plus_ = 0; + + error_minus_ = -(delta_x * 2); + error_plus_ = (delta_y * 2); + } + else + { + error_max_ = delta_x - (delta_y * 2); + x_minus_ = x_dir; + y_minus_ = y_dir; + x_plus_ = x_dir; + y_plus_ = 0; + + error_minus_ = (delta_y - delta_x) * 2; + error_plus_ = (delta_y * 2); + } + } + else + { + if( neighborhood == Neighbor4 ) + { + error_max_ = delta_y - delta_x; + x_minus_ = x_dir; + y_minus_ = 0; + x_plus_ = 0; + y_plus_ = y_dir; + + error_minus_ = -(delta_y * 2); + error_plus_ = (delta_x * 2); + } + else + { + error_max_ = delta_y - (delta_x * 2); + x_minus_ = x_dir; + y_minus_ = y_dir; + x_plus_ = 0; + y_plus_ = y_dir; + + error_minus_ = (delta_x - delta_y) * 2; + error_plus_ = (delta_x * 2); + } + } + + index_minus_ = x_minus_ + y_minus_ * width_; + index_plus_ = x_plus_ + y_plus_ * width_; +} + +//////////////////////////////////////////////////////////////////////////////// +inline void +LineIterator::operator ++ () +{ + if (error_ >= error_max_ ) + { + x_ += x_minus_; + y_ += y_minus_; + error_ += error_minus_; + index_ += index_minus_; + } + else + { + x_ += x_plus_; + y_ += y_plus_; + error_ += error_plus_; + index_ += index_plus_; + } +} + +//////////////////////////////////////////////////////////////////////////////// +inline unsigned +LineIterator::getRowIndex () const +{ + return y_; +} + +//////////////////////////////////////////////////////////////////////////////// +inline unsigned +LineIterator::getColumnIndex () const +{ + return x_; +} + +//////////////////////////////////////////////////////////////////////////////// +inline bool +LineIterator::isValid () const +{ + return (x_ != x_end_ || y_ != y_end_); +} + +//////////////////////////////////////////////////////////////////////////////// +inline void +LineIterator::reset () +{ + x_ = x_start_; + y_ = y_start_; + error_ = 0; + index_ = x_ * width_ + y_; +} + +} // namespace pcl + +#endif // __PCL_LINE_ITERATOR__ diff --git a/pcl-1.7/pcl/geometry/mesh_base.h b/pcl-1.7/pcl/geometry/mesh_base.h new file mode 100644 index 0000000..a50eb50 --- /dev/null +++ b/pcl-1.7/pcl/geometry/mesh_base.h @@ -0,0 +1,2154 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_GEOMETRY_MESH_BASE_H +#define PCL_GEOMETRY_MESH_BASE_H + +#include + +#include +#include +#include +#include +#include +#include +#include + +//////////////////////////////////////////////////////////////////////////////// +// Global variables used during testing +//////////////////////////////////////////////////////////////////////////////// + +#ifdef PCL_GEOMETRY_MESH_BASE_TEST_DELETE_FACE_MANIFOLD_2 +namespace pcl +{ + namespace geometry + { + bool g_pcl_geometry_mesh_base_test_delete_face_manifold_2_success; + } // End namespace geometry +} // End namespace pcl +#endif + +//////////////////////////////////////////////////////////////////////////////// +// Forward declarations +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + template + class MeshIO; + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// MeshBase +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief Base class for the half-edge mesh. + * \tparam DerivedT Has to implement the method 'addFaceImpl'. Please have a look at pcl::geometry::TriangleMesh, pcl::geometry::QuadMesh and pcl::geometry::PolygonMesh. + * \tparam MeshTraitsT Please have a look at pcl::geometry::DefaultMeshTraits. + * \tparam MeshTagT Tag describing the type of the mesh, e.g. TriangleMeshTag, QuadMeshTag, PolygonMeshTag. + * \author Martin Saelzle + * \ingroup geometry + * \todo Add documentation + */ + template + class MeshBase + { + public: + + typedef MeshBase Self; + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef DerivedT Derived; + + // These have to be defined in the traits class. + typedef typename MeshTraitsT::VertexData VertexData; + typedef typename MeshTraitsT::HalfEdgeData HalfEdgeData; + typedef typename MeshTraitsT::EdgeData EdgeData; + typedef typename MeshTraitsT::FaceData FaceData; + typedef typename MeshTraitsT::IsManifold IsManifold; + + // Check if the mesh traits are defined correctly. + BOOST_CONCEPT_ASSERT ((boost::Convertible )); + + typedef MeshTagT MeshTag; + + // Data + typedef boost::integral_constant ::value> HasVertexData; + typedef boost::integral_constant ::value> HasHalfEdgeData; + typedef boost::integral_constant ::value> HasEdgeData; + typedef boost::integral_constant ::value> HasFaceData; + + typedef pcl::PointCloud VertexDataCloud; + typedef pcl::PointCloud HalfEdgeDataCloud; + typedef pcl::PointCloud EdgeDataCloud; + typedef pcl::PointCloud FaceDataCloud; + + // Indices + typedef pcl::geometry::VertexIndex VertexIndex; + typedef pcl::geometry::HalfEdgeIndex HalfEdgeIndex; + typedef pcl::geometry::EdgeIndex EdgeIndex; + typedef pcl::geometry::FaceIndex FaceIndex; + + typedef std::vector VertexIndices; + typedef std::vector HalfEdgeIndices; + typedef std::vector EdgeIndices; + typedef std::vector FaceIndices; + + // Circulators + typedef pcl::geometry::VertexAroundVertexCirculator VertexAroundVertexCirculator; + typedef pcl::geometry::OutgoingHalfEdgeAroundVertexCirculator OutgoingHalfEdgeAroundVertexCirculator; + typedef pcl::geometry::IncomingHalfEdgeAroundVertexCirculator IncomingHalfEdgeAroundVertexCirculator; + typedef pcl::geometry::FaceAroundVertexCirculator FaceAroundVertexCirculator; + typedef pcl::geometry::VertexAroundFaceCirculator VertexAroundFaceCirculator; + typedef pcl::geometry::InnerHalfEdgeAroundFaceCirculator InnerHalfEdgeAroundFaceCirculator; + typedef pcl::geometry::OuterHalfEdgeAroundFaceCirculator OuterHalfEdgeAroundFaceCirculator; + typedef pcl::geometry::FaceAroundFaceCirculator FaceAroundFaceCirculator; + + /** \brief Constructor. */ + MeshBase () + : vertex_data_cloud_ (), + half_edge_data_cloud_ (), + edge_data_cloud_ (), + face_data_cloud_ (), + vertices_ (), + half_edges_ (), + faces_ (), + inner_he_ (), + free_he_ (), + is_new_ (), + make_adjacent_ (), + is_boundary_ (), + delete_faces_vertex_ (), + delete_faces_face_ () + { + } + + //////////////////////////////////////////////////////////////////////// + // addVertex / addFace / deleteVertex / deleteEdge / deleteFace / cleanUp + //////////////////////////////////////////////////////////////////////// + + /** \brief Add a vertex to the mesh. + * \param[in] vertex_data Data that is stored in the vertex. This is only added if the mesh has data associated with the vertices. + * \return Index to the new vertex. + */ + inline VertexIndex + addVertex (const VertexData& vertex_data=VertexData ()) + { + vertices_.push_back (Vertex ()); + this->addData (vertex_data_cloud_, vertex_data, HasVertexData ()); + return (VertexIndex (static_cast (this->sizeVertices () - 1))); + } + + /** \brief Add a face to the mesh. Data is only added if it is associated with the elements. The last vertex is connected with the first one. + * \param[in] vertices Indices to the vertices of the new face. + * \param[in] face_data Data that is set for the face. + * \param[in] half_edge_data Data that is set for all added half-edges. + * \param[in] edge_data Data that is set for all added edges. + * \return Index to the new face. Failure is signaled by returning an invalid face index. + * \warning The vertices must be valid and unique (each vertex may be contained only once). Not complying with this requirement results in undefined behavior! + */ + inline FaceIndex + addFace (const VertexIndices& vertices, + const FaceData& face_data = FaceData (), + const EdgeData& edge_data = EdgeData (), + const HalfEdgeData& half_edge_data = HalfEdgeData ()) + { + // NOTE: The derived class has to implement addFaceImpl. If needed it can use the general method addFaceImplBase. + return (static_cast (this)->addFaceImpl (vertices, face_data, edge_data, half_edge_data)); + } + + /** \brief Mark the given vertex and all connected half-edges and faces as deleted. + * \note Call cleanUp () to finally delete all mesh-elements. + */ + void + deleteVertex (const VertexIndex& idx_vertex) + { + assert (this->isValid (idx_vertex)); + if (this->isDeleted (idx_vertex)) return; + + delete_faces_vertex_.clear (); + FaceAroundVertexCirculator circ = this->getFaceAroundVertexCirculator (idx_vertex); + const FaceAroundVertexCirculator circ_end = circ; + do + { + if (circ.getTargetIndex ().isValid ()) // Check for boundary. + { + delete_faces_vertex_.push_back (circ.getTargetIndex ()); + } + } while (++circ!=circ_end); + + for (FaceIndices::const_iterator it = delete_faces_vertex_.begin (); it!=delete_faces_vertex_.end (); ++it) + { + this->deleteFace (*it); + } + } + + /** \brief Mark the given half-edge, the opposite half-edge and the associated faces as deleted. + * \note Call cleanUp () to finally delete all mesh-elements. + */ + void + deleteEdge (const HalfEdgeIndex& idx_he) + { + assert (this->isValid (idx_he)); + if (this->isDeleted (idx_he)) return; + + HalfEdgeIndex opposite = this->getOppositeHalfEdgeIndex (idx_he); + + if (this->isBoundary (idx_he)) this->markDeleted (idx_he); + else this->deleteFace (this->getFaceIndex (idx_he)); + if (this->isBoundary (opposite)) this->markDeleted (opposite); + else this->deleteFace (this->getFaceIndex (opposite)); + } + + /** \brief Mark the given edge (both half-edges) and the associated faces as deleted. + * \note Call cleanUp () to finally delete all mesh-elements. + */ + inline void + deleteEdge (const EdgeIndex& idx_edge) + { + assert (this->isValid (idx_edge)); + this->deleteEdge (pcl::geometry::toHalfEdgeIndex (idx_edge)); + assert (this->isDeleted (pcl::geometry::toHalfEdgeIndex (idx_edge, false))); // Bug in this class! + } + + /** \brief Mark the given face as deleted. More faces are deleted if the manifold mesh would become non-manifold. + * \note Call cleanUp () to finally delete all mesh-elements. + */ + inline void + deleteFace (const FaceIndex& idx_face) + { + assert (this->isValid (idx_face)); + if (this->isDeleted (idx_face)) return; + + this->deleteFace (idx_face, IsManifold ()); + } + + /** \brief Removes all mesh elements and data that are marked as deleted. + * \note This removes all isolated vertices as well. + */ + void + cleanUp () + { + // Copy the non-deleted mesh elements and store the index to their new position + const VertexIndices new_vertex_indices = + this->remove + (vertices_, vertex_data_cloud_); + const HalfEdgeIndices new_half_edge_indices = + this->remove + (half_edges_, half_edge_data_cloud_); + const FaceIndices new_face_indices = + this->remove + (faces_, face_data_cloud_); + + // Remove deleted edge data + if (HasEdgeData::value) + { + typename EdgeDataCloud::const_iterator it_ed_old = edge_data_cloud_.begin (); + typename EdgeDataCloud::iterator it_ed_new = edge_data_cloud_.begin (); + + HalfEdgeIndices::const_iterator it_ind = new_half_edge_indices.begin (); + HalfEdgeIndices::const_iterator it_ind_end = new_half_edge_indices.end (); + + for (; it_ind!=it_ind_end; it_ind+=2, ++it_ed_old) + { + if (it_ind->isValid ()) + { + *it_ed_new++ = *it_ed_old; + } + } + edge_data_cloud_.resize (this->sizeEdges ()); + } + + // Adjust the indices + for (VertexIterator it = vertices_.begin (); it!=vertices_.end (); ++it) + { + if (it->idx_outgoing_half_edge_.isValid ()) + { + it->idx_outgoing_half_edge_ = new_half_edge_indices [it->idx_outgoing_half_edge_.get ()]; + } + } + + for (HalfEdgeIterator it = half_edges_.begin (); it!=half_edges_.end (); ++it) + { + it->idx_terminating_vertex_ = new_vertex_indices [it->idx_terminating_vertex_.get ()]; + it->idx_next_half_edge_ = new_half_edge_indices [it->idx_next_half_edge_.get ()]; + it->idx_prev_half_edge_ = new_half_edge_indices [it->idx_prev_half_edge_.get ()]; + if (it->idx_face_.isValid ()) + { + it->idx_face_ = new_face_indices [it->idx_face_.get ()]; + } + } + + for (FaceIterator it = faces_.begin (); it!=faces_.end (); ++it) + { + it->idx_inner_half_edge_ = new_half_edge_indices [it->idx_inner_half_edge_.get ()]; + } + } + + //////////////////////////////////////////////////////////////////////// + // Vertex connectivity + //////////////////////////////////////////////////////////////////////// + + /** \brief Get the outgoing half-edge index to a given vertex. */ + inline HalfEdgeIndex + getOutgoingHalfEdgeIndex (const VertexIndex& idx_vertex) const + { + assert (this->isValid (idx_vertex)); + return (this->getVertex (idx_vertex).idx_outgoing_half_edge_); + } + + /** \brief Get the incoming half-edge index to a given vertex. */ + inline HalfEdgeIndex + getIncomingHalfEdgeIndex (const VertexIndex& idx_vertex) const + { + assert (this->isValid (idx_vertex)); + return (this->getOppositeHalfEdgeIndex (this->getOutgoingHalfEdgeIndex (idx_vertex))); + } + + //////////////////////////////////////////////////////////////////////// + // Half-edge connectivity + //////////////////////////////////////////////////////////////////////// + + /** \brief Get the terminating vertex index to a given half-edge. */ + inline VertexIndex + getTerminatingVertexIndex (const HalfEdgeIndex& idx_half_edge) const + { + assert (this->isValid (idx_half_edge)); + return (this->getHalfEdge (idx_half_edge).idx_terminating_vertex_); + } + + /** \brief Get the originating vertex index to a given half-edge. */ + inline VertexIndex + getOriginatingVertexIndex (const HalfEdgeIndex& idx_half_edge) const + { + assert (this->isValid (idx_half_edge)); + return (this->getTerminatingVertexIndex (this->getOppositeHalfEdgeIndex (idx_half_edge))); + } + + /** \brief Get the opposite half-edge index to a given half-edge. */ + inline HalfEdgeIndex + getOppositeHalfEdgeIndex (const HalfEdgeIndex& idx_half_edge) const + { + assert (this->isValid (idx_half_edge)); + // Check if the index is even or odd and return the other index. + return (HalfEdgeIndex (idx_half_edge.get () & 1 ? idx_half_edge.get () - 1 : idx_half_edge.get () + 1)); + } + + /** \brief Get the next half-edge index to a given half-edge. */ + inline HalfEdgeIndex + getNextHalfEdgeIndex (const HalfEdgeIndex& idx_half_edge) const + { + assert (this->isValid (idx_half_edge)); + return (this->getHalfEdge (idx_half_edge).idx_next_half_edge_); + } + + /** \brief Get the previous half-edge index to a given half-edge. */ + inline HalfEdgeIndex + getPrevHalfEdgeIndex (const HalfEdgeIndex& idx_half_edge) const + { + assert (this->isValid (idx_half_edge)); + return (this->getHalfEdge (idx_half_edge).idx_prev_half_edge_); + } + + /** \brief Get the face index to a given half-edge. */ + inline FaceIndex + getFaceIndex (const HalfEdgeIndex& idx_half_edge) const + { + assert (this->isValid (idx_half_edge)); + return (this->getHalfEdge (idx_half_edge).idx_face_); + } + + /** \brief Get the face index to a given half-edge. */ + inline FaceIndex + getOppositeFaceIndex (const HalfEdgeIndex& idx_half_edge) const + { + assert (this->isValid (idx_half_edge)); + return (this->getFaceIndex (this->getOppositeHalfEdgeIndex (idx_half_edge))); + } + + //////////////////////////////////////////////////////////////////////// + // Face connectivity + //////////////////////////////////////////////////////////////////////// + + /** \brief Get the inner half-edge index to a given face. */ + inline HalfEdgeIndex + getInnerHalfEdgeIndex (const FaceIndex& idx_face) const + { + assert (this->isValid (idx_face)); + return (this->getFace (idx_face).idx_inner_half_edge_); + } + + /** \brief Get the outer half-edge inex to a given face. */ + inline HalfEdgeIndex + getOuterHalfEdgeIndex (const FaceIndex& idx_face) const + { + assert (this->isValid (idx_face)); + return (this->getOppositeHalfEdgeIndex (this->getInnerHalfEdgeIndex (idx_face))); + } + + //////////////////////////////////////////////////////////////////////// + // Circulators + //////////////////////////////////////////////////////////////////////// + + /** \see pcl::geometry::VertexAroundVertexCirculator */ + inline VertexAroundVertexCirculator + getVertexAroundVertexCirculator (const VertexIndex& idx_vertex) const + { + assert (this->isValid (idx_vertex)); + return (VertexAroundVertexCirculator (idx_vertex, this)); + } + + /** \see pcl::geometry::VertexAroundVertexCirculator */ + inline VertexAroundVertexCirculator + getVertexAroundVertexCirculator (const HalfEdgeIndex& idx_outgoing_half_edge) const + { + assert (this->isValid (idx_outgoing_half_edge)); + return (VertexAroundVertexCirculator (idx_outgoing_half_edge, this)); + } + + /** \see pcl::geometry::OutgoingHalfEdgeAroundVertexCirculator */ + inline OutgoingHalfEdgeAroundVertexCirculator + getOutgoingHalfEdgeAroundVertexCirculator (const VertexIndex& idx_vertex) const + { + assert (this->isValid (idx_vertex)); + return (OutgoingHalfEdgeAroundVertexCirculator (idx_vertex, this)); + } + + /** \see pcl::geometry::OutgoingHalfEdgeAroundVertexCirculator */ + inline OutgoingHalfEdgeAroundVertexCirculator + getOutgoingHalfEdgeAroundVertexCirculator (const HalfEdgeIndex& idx_outgoing_half_edge) const + { + assert (this->isValid (idx_outgoing_half_edge)); + return (OutgoingHalfEdgeAroundVertexCirculator (idx_outgoing_half_edge, this)); + } + + /** \see pcl::geometry::IncomingHalfEdgeAroundVertexCirculator */ + inline IncomingHalfEdgeAroundVertexCirculator + getIncomingHalfEdgeAroundVertexCirculator (const VertexIndex& idx_vertex) const + { + assert (this->isValid (idx_vertex)); + return (IncomingHalfEdgeAroundVertexCirculator (idx_vertex, this)); + } + + /** \see pcl::geometry::IncomingHalfEdgeAroundVertexCirculator */ + inline IncomingHalfEdgeAroundVertexCirculator + getIncomingHalfEdgeAroundVertexCirculator (const HalfEdgeIndex& idx_incoming_half_edge) const + { + assert (this->isValid (idx_incoming_half_edge)); + return (IncomingHalfEdgeAroundVertexCirculator (idx_incoming_half_edge, this)); + } + + /** \see pcl::geometry::FaceAroundVertexCirculator */ + inline FaceAroundVertexCirculator + getFaceAroundVertexCirculator (const VertexIndex& idx_vertex) const + { + assert (this->isValid (idx_vertex)); + return (FaceAroundVertexCirculator (idx_vertex, this)); + } + + /** \see pcl::geometry::FaceAroundVertexCirculator */ + inline FaceAroundVertexCirculator + getFaceAroundVertexCirculator (const HalfEdgeIndex& idx_outgoing_half_edge) const + { + assert (this->isValid (idx_outgoing_half_edge)); + return (FaceAroundVertexCirculator (idx_outgoing_half_edge, this)); + } + + /** \see pcl::geometry::VertexAroundFaceCirculator */ + inline VertexAroundFaceCirculator + getVertexAroundFaceCirculator (const FaceIndex& idx_face) const + { + assert (this->isValid (idx_face)); + return (VertexAroundFaceCirculator (idx_face, this)); + } + + /** \see pcl::geometry::VertexAroundFaceCirculator */ + inline VertexAroundFaceCirculator + getVertexAroundFaceCirculator (const HalfEdgeIndex& idx_inner_half_edge) const + { + assert (this->isValid (idx_inner_half_edge)); + return (VertexAroundFaceCirculator (idx_inner_half_edge, this)); + } + + /** \see pcl::geometry::InnerHalfEdgeAroundFaceCirculator */ + inline InnerHalfEdgeAroundFaceCirculator + getInnerHalfEdgeAroundFaceCirculator (const FaceIndex& idx_face) const + { + assert (this->isValid (idx_face)); + return (InnerHalfEdgeAroundFaceCirculator (idx_face, this)); + } + + /** \see pcl::geometry::InnerHalfEdgeAroundFaceCirculator */ + inline InnerHalfEdgeAroundFaceCirculator + getInnerHalfEdgeAroundFaceCirculator (const HalfEdgeIndex& idx_inner_half_edge) const + { + assert (this->isValid (idx_inner_half_edge)); + return (InnerHalfEdgeAroundFaceCirculator (idx_inner_half_edge, this)); + } + + /** \see pcl::geometry::OuterHalfEdgeAroundFaceCirculator */ + inline OuterHalfEdgeAroundFaceCirculator + getOuterHalfEdgeAroundFaceCirculator (const FaceIndex& idx_face) const + { + assert (this->isValid (idx_face)); + return (OuterHalfEdgeAroundFaceCirculator (idx_face, this)); + } + + /** \see pcl::geometry::OuterHalfEdgeAroundFaceCirculator */ + inline OuterHalfEdgeAroundFaceCirculator + getOuterHalfEdgeAroundFaceCirculator (const HalfEdgeIndex& idx_inner_half_edge) const + { + assert (this->isValid (idx_inner_half_edge)); + return (OuterHalfEdgeAroundFaceCirculator (idx_inner_half_edge, this)); + } + + /** \see pcl::geometry::FaceAroundFaceCirculator */ + inline FaceAroundFaceCirculator + getFaceAroundFaceCirculator (const FaceIndex& idx_face) const + { + assert (this->isValid (idx_face)); + return (FaceAroundFaceCirculator (idx_face, this)); + } + + /** \see pcl::geometry::FaceAroundFaceCirculator */ + inline FaceAroundFaceCirculator + getFaceAroundFaceCirculator (const HalfEdgeIndex& idx_inner_half_edge) const + { + assert (this->isValid (idx_inner_half_edge)); + return (FaceAroundFaceCirculator (idx_inner_half_edge, this)); + } + + ////////////////////////////////////////////////////////////////////////// + // isEqualTopology + ////////////////////////////////////////////////////////////////////////// + + /** \brief Check if the other mesh has the same topology as this mesh. */ + bool + isEqualTopology (const Self& other) const + { + if (this->sizeVertices () != other.sizeVertices ()) return (false); + if (this->sizeHalfEdges () != other.sizeHalfEdges ()) return (false); + if (this->sizeFaces () != other.sizeFaces ()) return (false); + + for (unsigned int i=0; isizeVertices (); ++i) + { + if (this->getOutgoingHalfEdgeIndex (VertexIndex (i)) != + other.getOutgoingHalfEdgeIndex (VertexIndex (i))) return (false); + } + + for (unsigned int i=0; isizeHalfEdges (); ++i) + { + if (this->getTerminatingVertexIndex (HalfEdgeIndex (i)) != + other.getTerminatingVertexIndex (HalfEdgeIndex (i))) return (false); + + if (this->getNextHalfEdgeIndex (HalfEdgeIndex (i)) != + other.getNextHalfEdgeIndex (HalfEdgeIndex (i))) return (false); + + if (this->getPrevHalfEdgeIndex (HalfEdgeIndex (i)) != + other.getPrevHalfEdgeIndex (HalfEdgeIndex (i))) return (false); + + if (this->getFaceIndex (HalfEdgeIndex (i)) != + other.getFaceIndex (HalfEdgeIndex (i))) return (false); + } + + for (unsigned int i=0; isizeFaces (); ++i) + { + if (this->getInnerHalfEdgeIndex (FaceIndex (i)) != + other.getInnerHalfEdgeIndex (FaceIndex (i))) return (false); + } + + return (true); + } + + //////////////////////////////////////////////////////////////////////// + // isValid + //////////////////////////////////////////////////////////////////////// + + /** \brief Check if the given vertex index is a valid index into the mesh. */ + inline bool + isValid (const VertexIndex& idx_vertex) const + { + return (idx_vertex >= VertexIndex (0) && idx_vertex < VertexIndex (int (vertices_.size ()))); + } + + /** \brief Check if the given half-edge index is a valid index into the mesh. */ + inline bool + isValid (const HalfEdgeIndex& idx_he) const + { + return (idx_he >= HalfEdgeIndex (0) && idx_he < HalfEdgeIndex (half_edges_.size ())); + } + + /** \brief Check if the given edge index is a valid index into the mesh. */ + inline bool + isValid (const EdgeIndex& idx_edge) const + { + return (idx_edge >= EdgeIndex (0) && idx_edge < EdgeIndex (half_edges_.size () / 2)); + } + + /** \brief Check if the given face index is a valid index into the mesh. */ + inline bool + isValid (const FaceIndex& idx_face) const + { + return (idx_face >= FaceIndex (0) && idx_face < FaceIndex (faces_.size ())); + } + + //////////////////////////////////////////////////////////////////////// + // isDeleted + //////////////////////////////////////////////////////////////////////// + + /** \brief Check if the given vertex is marked as deleted. */ + inline bool + isDeleted (const VertexIndex& idx_vertex) const + { + assert (this->isValid (idx_vertex)); + return (!this->getOutgoingHalfEdgeIndex (idx_vertex).isValid ()); + } + + /** \brief Check if the given half-edge is marked as deleted. */ + inline bool + isDeleted (const HalfEdgeIndex& idx_he) const + { + assert (this->isValid (idx_he)); + return (!this->getTerminatingVertexIndex (idx_he).isValid ()); + } + + /** \brief Check if the given edge (any of the two half-edges) is marked as deleted. */ + inline bool + isDeleted (const EdgeIndex& idx_edge) const + { + assert (this->isValid (idx_edge)); + return (this->isDeleted (pcl::geometry::toHalfEdgeIndex (idx_edge, true)) || + this->isDeleted (pcl::geometry::toHalfEdgeIndex (idx_edge, false))); + } + + /** \brief Check if the given face is marked as deleted. */ + inline bool + isDeleted (const FaceIndex& idx_face) const + { + assert (this->isValid (idx_face)); + return (!this->getInnerHalfEdgeIndex (idx_face).isValid ()); + } + + //////////////////////////////////////////////////////////////////////// + // isIsolated + //////////////////////////////////////////////////////////////////////// + + /** \brief Check if the given vertex is isolated (not connected to other elements). */ + inline bool + isIsolated (const VertexIndex& idx_vertex) const + { + assert (this->isValid (idx_vertex)); + return (!this->getOutgoingHalfEdgeIndex (idx_vertex).isValid ()); + } + + //////////////////////////////////////////////////////////////////////// + // isBoundary + //////////////////////////////////////////////////////////////////////// + + /** \brief Check if the given vertex lies on the boundary. Isolated vertices are considered to be on the boundary. */ + inline bool + isBoundary (const VertexIndex& idx_vertex) const + { + assert (this->isValid (idx_vertex)); + if (this->isIsolated (idx_vertex)) return (true); + return (this->isBoundary (this->getOutgoingHalfEdgeIndex (idx_vertex))); + } + + /** \brief Check if the given half-edge lies on the bounddary. */ + inline bool + isBoundary (const HalfEdgeIndex& idx_he) const + { + assert (this->isValid (idx_he)); + return (!this->getFaceIndex (idx_he).isValid ()); + } + + /** \brief Check if the given edge lies on the boundary (any of the two half-edges lies on the boundary. */ + inline bool + isBoundary (const EdgeIndex& idx_edge) const + { + assert (this->isValid (idx_edge)); + const HalfEdgeIndex& idx = pcl::geometry::toHalfEdgeIndex (idx_edge); + return (this->isBoundary (idx) || this->isBoundary (this->getOppositeHalfEdgeIndex (idx))); + } + + /** \brief Check if the given face lies on the boundary. There are two versions of this method, selected by the template parameter. + * \tparam CheckVerticesT Check if any vertex lies on the boundary (true) or check if any edge lies on the boundary (false). + */ + template inline bool + isBoundary (const FaceIndex& idx_face) const + { + assert (this->isValid (idx_face)); + return (this->isBoundary (idx_face, boost::integral_constant ())); + } + + /** \brief Check if the given face lies on the boundary. This method uses isBoundary \c true which checks if any vertex lies on the boundary. */ + inline bool + isBoundary (const FaceIndex& idx_face) const + { + assert (this->isValid (idx_face)); + return (this->isBoundary (idx_face, boost::true_type ())); + } + + //////////////////////////////////////////////////////////////////////// + // isManifold + //////////////////////////////////////////////////////////////////////// + + /** \brief Check if the given vertex is manifold. Isolated vertices are manifold. */ + inline bool + isManifold (const VertexIndex& idx_vertex) const + { + assert (this->isValid (idx_vertex)); + if (this->isIsolated (idx_vertex)) return (true); + return (this->isManifold (idx_vertex, IsManifold ())); + } + + /** \brief Check if the mesh is manifold. */ + inline bool + isManifold () const + { + return (this->isManifold (IsManifold ())); + } + + //////////////////////////////////////////////////////////////////////// + // size + //////////////////////////////////////////////////////////////////////// + + /** \brief Get the number of the vertices. */ + inline size_t + sizeVertices () const + { + return (vertices_.size ()); + } + + /** \brief Get the number of the half-edges. */ + inline size_t + sizeHalfEdges () const + { + assert (half_edges_.size () % 2 == 0); // This would be a bug in the mesh. + return (half_edges_.size ()); + } + + /** \brief Get the number of the edges. */ + inline size_t + sizeEdges () const + { + assert (half_edges_.size () % 2 == 0); // This would be a bug in the mesh. + return (half_edges_.size () / 2); + } + + /** \brief Get the number of the faces. */ + inline size_t + sizeFaces () const + { + return (faces_.size ()); + } + + //////////////////////////////////////////////////////////////////////// + // empty + //////////////////////////////////////////////////////////////////////// + + /** \brief Check if the mesh is empty. */ + inline bool + empty () const + { + return (this->emptyVertices () && this->emptyEdges () && this->emptyFaces ()); + } + + /** \brief Check if the vertices are empty. */ + inline bool + emptyVertices () const + { + return (vertices_.empty ()); + } + + /** \brief Check if the edges are empty. */ + inline bool + emptyEdges () const + { + return (half_edges_.empty ()); + } + + /** \brief Check if the faces are empty. */ + inline bool + emptyFaces () const + { + return (faces_.empty ()); + } + + //////////////////////////////////////////////////////////////////////// + // reserve + //////////////////////////////////////////////////////////////////////// + + /** \brief Reserve storage space n vertices. */ + inline void + reserveVertices (const size_t n) + { + vertices_.reserve (n); + this->reserveData (vertex_data_cloud_, n, HasVertexData ()); + } + + /** \brief Reserve storage space for n edges (2*n storage space is reserved for the half-edges). */ + inline void + reserveEdges (const size_t n) + { + half_edges_.reserve (2*n); + this->reserveData (half_edge_data_cloud_, 2*n, HasHalfEdgeData ()); + this->reserveData (edge_data_cloud_ , n, HasEdgeData ()); + } + + /** \brief Reserve storage space for n faces. */ + inline void + reserveFaces (const size_t n) + { + faces_.reserve (n); + this->reserveData (face_data_cloud_, n, HasFaceData ()); + } + + //////////////////////////////////////////////////////////////////////// + // resize + //////////////////////////////////////////////////////////////////////// + + /** \brief Resize the the vertices to n elements. */ + inline void + resizeVertices (const size_t n, const VertexData& data = VertexData ()) + { + vertices_.resize (n); + this->resizeData (vertex_data_cloud_, n, data, HasVertexData ()); + } + + /** \brief Resize the edges to n elements (half-edges will hold 2*n elements). */ + inline void + resizeEdges (const size_t n, + const EdgeData& edge_data = EdgeData (), + const HalfEdgeData he_data = HalfEdgeData ()) + { + half_edges_.resize (2*n); + this->resizeData (half_edge_data_cloud_, 2*n, he_data , HasHalfEdgeData ()); + this->resizeData (edge_data_cloud_ , n, edge_data, HasEdgeData ()); + } + + /** \brief Resize the faces to n elements. */ + inline void + resizeFaces (const size_t n, const FaceData& data = FaceData ()) + { + faces_.resize (n); + this->resizeData (face_data_cloud_, n, data, HasFaceData ()); + } + + //////////////////////////////////////////////////////////////////////// + // clear + //////////////////////////////////////////////////////////////////////// + + /** \brief Clear all mesh elements and data. */ + void + clear () + { + vertices_.clear (); + half_edges_.clear (); + faces_.clear (); + + this->clearData (vertex_data_cloud_ , HasVertexData ()); + this->clearData (half_edge_data_cloud_, HasHalfEdgeData ()); + this->clearData (edge_data_cloud_ , HasEdgeData ()); + this->clearData (face_data_cloud_ , HasFaceData ()); + } + + //////////////////////////////////////////////////////////////////////// + // get / set the vertex data cloud + //////////////////////////////////////////////////////////////////////// + + /** \brief Get access to the stored vertex data. + * \warning Please make sure to NOT add or remove elements from the cloud. + */ + inline VertexDataCloud& + getVertexDataCloud () + { + return (vertex_data_cloud_); + } + + /** \brief Get the stored vertex data. */ + inline VertexDataCloud + getVertexDataCloud () const + { + return (vertex_data_cloud_); + } + + /** \brief Change the stored vertex data. + * \param[in] vertex_data_cloud The new vertex data. Must be the same as the current data. + * \return true if the cloud could be set. + */ + inline bool + setVertexDataCloud (const VertexDataCloud& vertex_data_cloud) + { + if (vertex_data_cloud.size () == vertex_data_cloud_.size ()) + { + vertex_data_cloud_ = vertex_data_cloud; + return (true); + } + else + { + return (false); + } + } + + //////////////////////////////////////////////////////////////////////// + // get / set the half-edge data cloud + //////////////////////////////////////////////////////////////////////// + + /** \brief Get access to the stored half-edge data. + * \warning Please make sure to NOT add or remove elements from the cloud. + */ + inline HalfEdgeDataCloud& + getHalfEdgeDataCloud () + { + return (half_edge_data_cloud_); + } + + /** \brief Get the stored half-edge data. */ + inline HalfEdgeDataCloud + getHalfEdgeDataCloud () const + { + return (half_edge_data_cloud_); + } + + /** \brief Change the stored half-edge data. + * \param[in] half_edge_data_cloud The new half-edge data. Must be the same as the current data. + * \return true if the cloud could be set. + */ + inline bool + setHalfEdgeDataCloud (const HalfEdgeDataCloud& half_edge_data_cloud) + { + if (half_edge_data_cloud.size () == half_edge_data_cloud_.size ()) + { + half_edge_data_cloud_ = half_edge_data_cloud; + return (true); + } + else + { + return (false); + } + } + + //////////////////////////////////////////////////////////////////////// + // get / set the edge data cloud + //////////////////////////////////////////////////////////////////////// + + /** \brief Get access to the stored edge data. + * \warning Please make sure to NOT add or remove elements from the cloud. + */ + inline EdgeDataCloud& + getEdgeDataCloud () + { + return (edge_data_cloud_); + } + + /** \brief Get the stored edge data. */ + inline EdgeDataCloud + getEdgeDataCloud () const + { + return (edge_data_cloud_); + } + + /** \brief Change the stored edge data. + * \param[in] edge_data_cloud The new edge data. Must be the same as the current data. + * \return true if the cloud could be set. + */ + inline bool + setEdgeDataCloud (const EdgeDataCloud& edge_data_cloud) + { + if (edge_data_cloud.size () == edge_data_cloud_.size ()) + { + edge_data_cloud_ = edge_data_cloud; + return (true); + } + else + { + return (false); + } + } + + //////////////////////////////////////////////////////////////////////// + // get / set the face data cloud + //////////////////////////////////////////////////////////////////////// + + /** \brief Get access to the stored face data. + * \warning Please make sure to NOT add or remove elements from the cloud. + */ + inline FaceDataCloud& + getFaceDataCloud () + { + return (face_data_cloud_); + } + + /** \brief Get the stored face data. */ + inline FaceDataCloud + getFaceDataCloud () const + { + return (face_data_cloud_); + } + + /** \brief Change the stored face data. + * \param[in] face_data_cloud The new face data. Must be the same as the current data. + * \return true if the cloud could be set. + */ + inline bool + setFaceDataCloud (const FaceDataCloud& face_data_cloud) + { + if (face_data_cloud.size () == face_data_cloud_.size ()) + { + face_data_cloud_ = face_data_cloud; + return (true); + } + else + { + return (false); + } + } + + //////////////////////////////////////////////////////////////////////// + // getVertexIndex / getHalfEdgeIndex / getEdgeIndex / getFaceIndex + //////////////////////////////////////////////////////////////////////// + + /** \brief Get the index associated to the given vertex data. + * \return Invalid index if the mesh does not have associated vertex data. + */ + inline VertexIndex + getVertexIndex (const VertexData& vertex_data) const + { + if (HasVertexData::value) + { + assert (&vertex_data >= &vertex_data_cloud_.front () && &vertex_data <= &vertex_data_cloud_.back ()); + return (VertexIndex (std::distance (&vertex_data_cloud_.front (), &vertex_data))); + } + else + { + return (VertexIndex ()); + } + } + + /** \brief Get the index associated to the given half-edge data. */ + inline HalfEdgeIndex + getHalfEdgeIndex (const HalfEdgeData& half_edge_data) const + { + if (HasHalfEdgeData::value) + { + assert (&half_edge_data >= &half_edge_data_cloud_.front () && &half_edge_data <= &half_edge_data_cloud_.back ()); + return (HalfEdgeIndex (std::distance (&half_edge_data_cloud_.front (), &half_edge_data))); + } + else + { + return (HalfEdgeIndex ()); + } + } + + /** \brief Get the index associated to the given edge data. */ + inline EdgeIndex + getEdgeIndex (const EdgeData& edge_data) const + { + if (HasEdgeData::value) + { + assert (&edge_data >= &edge_data_cloud_.front () && &edge_data <= &edge_data_cloud_.back ()); + return (EdgeIndex (std::distance (&edge_data_cloud_.front (), &edge_data))); + } + else + { + return (EdgeIndex ()); + } + } + + /** \brief Get the index associated to the given face data. */ + inline FaceIndex + getFaceIndex (const FaceData& face_data) const + { + if (HasFaceData::value) + { + assert (&face_data >= &face_data_cloud_.front () && &face_data <= &face_data_cloud_.back ()); + return (FaceIndex (std::distance (&face_data_cloud_.front (), &face_data))); + } + else + { + return (FaceIndex ()); + } + } + + protected: + + //////////////////////////////////////////////////////////////////////// + // Types + //////////////////////////////////////////////////////////////////////// + + // Elements + typedef pcl::geometry::Vertex Vertex; + typedef pcl::geometry::HalfEdge HalfEdge; + typedef pcl::geometry::Face Face; + + typedef std::vector Vertices; + typedef std::vector HalfEdges; + typedef std::vector Faces; + + typedef typename Vertices::iterator VertexIterator; + typedef typename HalfEdges::iterator HalfEdgeIterator; + typedef typename Faces::iterator FaceIterator; + + typedef typename Vertices::const_iterator VertexConstIterator; + typedef typename HalfEdges::const_iterator HalfEdgeConstIterator; + typedef typename Faces::const_iterator FaceConstIterator; + + /** \brief General implementation of addFace. */ + FaceIndex + addFaceImplBase (const VertexIndices& vertices, + const FaceData& face_data, + const EdgeData& edge_data, + const HalfEdgeData& half_edge_data) + { + const int n = static_cast (vertices.size ()); + if (n < 3) return (FaceIndex ()); + + // Check for topological errors + inner_he_.resize (n); + free_he_.resize (n); + is_new_.resize (n); + make_adjacent_.resize (n); + int i, j; + for (i=0; icheckTopology1 (vertices [i], vertices [(i+1)%n], inner_he_ [i], is_new_ [i], IsManifold ())) + { + return (FaceIndex ()); + } + } + for (i=0; icheckTopology2 (inner_he_ [i], inner_he_ [j], is_new_ [i], is_new_ [j], this->isIsolated (vertices [j]), make_adjacent_ [i], free_he_ [i], IsManifold ())) + { + return (FaceIndex ()); + } + } + + // Reconnect the existing half-edges if needed + if (!IsManifold::value) + { + for (i=0; imakeAdjacent (inner_he_ [i], inner_he_ [(i+1)%n], free_he_ [i]); + } + } + } + + // Add new half-edges if needed + for (i=0; iaddEdge (vertices [i], vertices [(i+1)%n], half_edge_data, edge_data); + } + } + + // Connect + for (i=0; iconnectNewNew (inner_he_ [i], inner_he_ [j], vertices [j], IsManifold ()); + else if ( is_new_ [i] && !is_new_ [j]) this->connectNewOld (inner_he_ [i], inner_he_ [j], vertices [j]); + else if (!is_new_ [i] && is_new_ [j]) this->connectOldNew (inner_he_ [i], inner_he_ [j], vertices [j]); + else this->connectOldOld (inner_he_ [i], inner_he_ [j], vertices [j], IsManifold ()); + } + return (this->connectFace (inner_he_, face_data)); + } + + //////////////////////////////////////////////////////////////////////// + // addEdge + //////////////////////////////////////////////////////////////////////// + + /** \brief Add an edge between the two given vertices and connect them with the vertices. + * \param[in] idx_v_a The first vertex index + * \param[in] idx_v_b The second vertex index + * \param[in] he_data Data associated with the half-edges. This is only added if the mesh has data associated with the half-edges. + * \param[in] edge_data Data associated with the edge. This is only added if the mesh has data associated with the edges. + * \return Index to the half-edge from vertex a to vertex b. + */ + HalfEdgeIndex + addEdge (const VertexIndex& idx_v_a, + const VertexIndex& idx_v_b, + const HalfEdgeData& he_data, + const EdgeData& edge_data) + { + half_edges_.push_back (HalfEdge (idx_v_b)); + half_edges_.push_back (HalfEdge (idx_v_a)); + + this->addData (half_edge_data_cloud_, he_data , HasHalfEdgeData ()); + this->addData (half_edge_data_cloud_, he_data , HasHalfEdgeData ()); + this->addData (edge_data_cloud_ , edge_data, HasEdgeData ()); + + return (HalfEdgeIndex (static_cast (half_edges_.size () - 2))); + } + + //////////////////////////////////////////////////////////////////////// + // topology checks + //////////////////////////////////////////////////////////////////////// + + /** \brief Check if the edge between the two vertices can be added. + * \param[in] idx_v_a Index to the first vertex. + * \param[in] idx_v_b Index to the second vertex. + * \param[out] idx_he_ab Index to the half-edge ab if is_new_ab=false. + * \param[out] is_new_ab true if the edge between the vertices exists already. Must be initialized with true! + * \return true if the half-edge may be added. + */ + bool + checkTopology1 (const VertexIndex& idx_v_a, + const VertexIndex& idx_v_b, + HalfEdgeIndex& idx_he_ab, + std::vector ::reference is_new_ab, + boost::true_type /*is_manifold*/) const + { + is_new_ab = true; + if (this->isIsolated (idx_v_a)) return (true); + + idx_he_ab = this->getOutgoingHalfEdgeIndex (idx_v_a); + + if (!this->isBoundary (idx_he_ab)) return (false); + if (this->getTerminatingVertexIndex (idx_he_ab) == idx_v_b) is_new_ab = false; + return (true); + } + + /** \brief Non manifold version of checkTopology1 */ + bool + checkTopology1 (const VertexIndex& idx_v_a, + const VertexIndex& idx_v_b, + HalfEdgeIndex& idx_he_ab, + std::vector ::reference is_new_ab, + boost::false_type /*is_manifold*/) const + { + is_new_ab = true; + if (this->isIsolated (idx_v_a)) return (true); + if (!this->isBoundary (this->getOutgoingHalfEdgeIndex (idx_v_a))) return (false); + + VertexAroundVertexCirculator circ = this->getVertexAroundVertexCirculator (this->getOutgoingHalfEdgeIndex (idx_v_a)); + const VertexAroundVertexCirculator circ_end = circ; + + do + { + if (circ.getTargetIndex () == idx_v_b) + { + idx_he_ab = circ.getCurrentHalfEdgeIndex (); + if (!this->isBoundary (idx_he_ab)) return (false); + + is_new_ab = false; + return (true); + } + } while (++circ!=circ_end); + + return (true); + } + + /** \brief Check if the face may be added (mesh does not become non-manifold). */ + inline bool + checkTopology2 (const HalfEdgeIndex& /*idx_he_ab*/, + const HalfEdgeIndex& /*idx_he_bc*/, + const bool is_new_ab, + const bool is_new_bc, + const bool is_isolated_b, + std::vector ::reference /*make_adjacent_ab_bc*/, + HalfEdgeIndex& /*idx_free_half_edge*/, + boost::true_type /*is_manifold*/) const + { + if (is_new_ab && is_new_bc && !is_isolated_b) return (false); + else return (true); + } + + /** \brief Check if the half-edge bc is the next half-edge of ab. + * \param[in] idx_he_ab Index to the half-edge between the vertices a and b. + * \param[in] idx_he_bc Index to the half-edge between the vertices b and c. + * \param[in] is_new_ab Half-edge ab is new. + * \param[in] is_new_bc Half-edge bc is new. + * \param[out] make_adjacent_ab_bc Half-edges ab and bc need to be made adjacent. + * \param[out] idx_free_half_edge Free half-edge (needed for makeAdjacent) + * \return true if addFace may be continued. + */ + inline bool + checkTopology2 (const HalfEdgeIndex& idx_he_ab, + const HalfEdgeIndex& idx_he_bc, + const bool is_new_ab, + const bool is_new_bc, + const bool /*is_isolated_b*/, + std::vector ::reference make_adjacent_ab_bc, + HalfEdgeIndex& idx_free_half_edge, + boost::false_type /*is_manifold*/) const + { + if (is_new_ab || is_new_bc) + { + make_adjacent_ab_bc = false; + return (true); // Make adjacent is only needed for two old half-edges + } + + if (this->getNextHalfEdgeIndex (idx_he_ab) == idx_he_bc) + { + make_adjacent_ab_bc = false; + return (true); // already adjacent + } + + make_adjacent_ab_bc = true; + + // Find the next boundary half edge + IncomingHalfEdgeAroundVertexCirculator circ = this->getIncomingHalfEdgeAroundVertexCirculator (this->getOppositeHalfEdgeIndex (idx_he_bc)); + + do ++circ; while (!this->isBoundary (circ.getTargetIndex ())); + idx_free_half_edge = circ.getTargetIndex (); + + // This would detach the faces around the vertex from each other. + if (circ.getTargetIndex () == idx_he_ab) return (false); + else return (true); + } + + /** \brief Make the half-edges bc the next half-edge of ab. + * \param[in] idx_he_ab Index to the half-edge between the vertices a and b. + * \param[in] idx_he_bc Index to the half-edge between the vertices b and c. + * \param[in, out] idx_free_half_edge Free half-edge needed to re-connect the half-edges around vertex b. + */ + void + makeAdjacent (const HalfEdgeIndex& idx_he_ab, + const HalfEdgeIndex& idx_he_bc, + HalfEdgeIndex& idx_free_half_edge) + { + // Re-link. No references! + const HalfEdgeIndex idx_he_ab_next = this->getNextHalfEdgeIndex (idx_he_ab); + const HalfEdgeIndex idx_he_bc_prev = this->getPrevHalfEdgeIndex (idx_he_bc); + const HalfEdgeIndex idx_he_free_next = this->getNextHalfEdgeIndex (idx_free_half_edge); + + this->connectPrevNext (idx_he_ab, idx_he_bc); + this->connectPrevNext (idx_free_half_edge, idx_he_ab_next); + this->connectPrevNext (idx_he_bc_prev, idx_he_free_next); + } + + //////////////////////////////////////////////////////////////////////// + // connect + //////////////////////////////////////////////////////////////////////// + + /** \brief Add a face to the mesh and connect it to the half-edges. + * \param[in] inner_he Inner half-edges of the face. + * \param[in] face_data Data that is stored in the face. This is only added if the mesh has data associated with the faces. + * \return Index to the new face. + */ + FaceIndex + connectFace (const HalfEdgeIndices& inner_he, + const FaceData& face_data) + { + faces_.push_back (Face (inner_he.back ())); + this->addData (face_data_cloud_, face_data, HasFaceData ()); + + const FaceIndex idx_face (static_cast (this->sizeFaces () - 1)); + + for (HalfEdgeIndices::const_iterator it=inner_he.begin (); it!=inner_he.end (); ++it) + { + this->setFaceIndex (*it, idx_face); + } + + return (idx_face); + } + + /** \brief Connect the next and prev indices of the two half-edges with each other. */ + inline void + connectPrevNext (const HalfEdgeIndex& idx_he_ab, + const HalfEdgeIndex& idx_he_bc) + { + this->setNextHalfEdgeIndex (idx_he_ab, idx_he_bc); + this->setPrevHalfEdgeIndex (idx_he_bc, idx_he_ab); + } + + /** \brief Both half-edges are new (manifold version). */ + void + connectNewNew (const HalfEdgeIndex& idx_he_ab, + const HalfEdgeIndex& idx_he_bc, + const VertexIndex& idx_v_b, + boost::true_type /*is_manifold*/) + { + const HalfEdgeIndex idx_he_ba = this->getOppositeHalfEdgeIndex (idx_he_ab); + const HalfEdgeIndex idx_he_cb = this->getOppositeHalfEdgeIndex (idx_he_bc); + + this->connectPrevNext (idx_he_ab, idx_he_bc); + this->connectPrevNext (idx_he_cb, idx_he_ba); + + this->setOutgoingHalfEdgeIndex (idx_v_b, idx_he_ba); + } + + /** \brief Both half-edges are new (non-manifold version). */ + void + connectNewNew (const HalfEdgeIndex& idx_he_ab, + const HalfEdgeIndex& idx_he_bc, + const VertexIndex& idx_v_b, + boost::false_type /*is_manifold*/) + { + if (this->isIsolated (idx_v_b)) + { + this->connectNewNew (idx_he_ab, idx_he_bc, idx_v_b, boost::true_type ()); + } + else + { + const HalfEdgeIndex idx_he_ba = this->getOppositeHalfEdgeIndex (idx_he_ab); + const HalfEdgeIndex idx_he_cb = this->getOppositeHalfEdgeIndex (idx_he_bc); + + // No references! + const HalfEdgeIndex idx_he_b_out = this->getOutgoingHalfEdgeIndex (idx_v_b); + const HalfEdgeIndex idx_he_b_out_prev = this->getPrevHalfEdgeIndex (idx_he_b_out); + + this->connectPrevNext (idx_he_ab, idx_he_bc); + this->connectPrevNext (idx_he_cb, idx_he_b_out); + this->connectPrevNext (idx_he_b_out_prev, idx_he_ba); + } + } + + /** \brief The first half-edge is new. */ + void + connectNewOld (const HalfEdgeIndex& idx_he_ab, + const HalfEdgeIndex& idx_he_bc, + const VertexIndex& idx_v_b) + { + const HalfEdgeIndex idx_he_ba = this->getOppositeHalfEdgeIndex (idx_he_ab); + const HalfEdgeIndex idx_he_bc_prev = this->getPrevHalfEdgeIndex (idx_he_bc); // No reference! + + this->connectPrevNext (idx_he_ab, idx_he_bc); + this->connectPrevNext (idx_he_bc_prev, idx_he_ba); + + this->setOutgoingHalfEdgeIndex (idx_v_b, idx_he_ba); + } + + /** \brief The second half-edge is new. */ + void + connectOldNew (const HalfEdgeIndex& idx_he_ab, + const HalfEdgeIndex& idx_he_bc, + const VertexIndex& idx_v_b) + { + const HalfEdgeIndex idx_he_cb = this->getOppositeHalfEdgeIndex (idx_he_bc); + const HalfEdgeIndex idx_he_ab_next = this->getNextHalfEdgeIndex (idx_he_ab); // No reference! + + this->connectPrevNext (idx_he_ab, idx_he_bc); + this->connectPrevNext (idx_he_cb, idx_he_ab_next); + + this->setOutgoingHalfEdgeIndex (idx_v_b, idx_he_ab_next); + } + + /** \brief Both half-edges are old (manifold version). */ + void + connectOldOld (const HalfEdgeIndex& /*idx_he_ab*/, + const HalfEdgeIndex& /*idx_he_bc*/, + const VertexIndex& /*idx_v_b*/, + boost::true_type /*is_manifold*/) + { + } + + /** \brief Both half-edges are old (non-manifold version). */ + void + connectOldOld (const HalfEdgeIndex& /*idx_he_ab*/, + const HalfEdgeIndex& idx_he_bc, + const VertexIndex& idx_v_b, + boost::false_type /*is_manifold*/) + { + const HalfEdgeIndex& idx_he_b_out = this->getOutgoingHalfEdgeIndex (idx_v_b); + + // The outgoing half edge MUST be a boundary half-edge (if there is one) + if (idx_he_b_out == idx_he_bc) // he_bc is no longer on the boundary + { + OutgoingHalfEdgeAroundVertexCirculator circ = this->getOutgoingHalfEdgeAroundVertexCirculator (idx_he_b_out); + const OutgoingHalfEdgeAroundVertexCirculator circ_end = circ; + + while (++circ!=circ_end) + { + if (this->isBoundary (circ.getTargetIndex ())) + { + this->setOutgoingHalfEdgeIndex (idx_v_b, circ.getTargetIndex ()); + return; + } + } + } + } + + //////////////////////////////////////////////////////////////////////// + // addData + //////////////////////////////////////////////////////////////////////// + + /** \brief Add mesh data. */ + template + inline void + addData (pcl::PointCloud & cloud, const DataT& data, boost::true_type /*has_data*/) + { + cloud.push_back (data); + } + + /** \brief Does nothing. */ + template + inline void + addData (pcl::PointCloud & /*cloud*/, const DataT& /*data*/, boost::false_type /*has_data*/) + { + } + + //////////////////////////////////////////////////////////////////////// + // deleteFace + //////////////////////////////////////////////////////////////////////// + + /** \brief Manifold version of deleteFace. If the mesh becomes non-manifold due to the delete operation the faces around the non-manifold vertex are deleted until the mesh becomes manifold again. */ + void + deleteFace (const FaceIndex& idx_face, + boost::true_type /*is_manifold*/) + { + assert (this->isValid (idx_face)); + delete_faces_face_.clear (); + delete_faces_face_.push_back (idx_face); + + while (!delete_faces_face_.empty ()) + { + const FaceIndex idx_face_cur = delete_faces_face_.back (); + delete_faces_face_.pop_back (); + + // This calls the non-manifold version of deleteFace, which will call the manifold version of reconnect. + this->deleteFace (idx_face_cur, boost::false_type ()); + } + } + + /** \brief Non-manifold version of deleteFace. */ + void + deleteFace (const FaceIndex& idx_face, + boost::false_type /*is_manifold*/) + { + assert (this->isValid (idx_face)); + if (this->isDeleted (idx_face)) return; + + // Store all half-edges in the face + inner_he_.clear (); + is_boundary_.clear (); + InnerHalfEdgeAroundFaceCirculator circ = this->getInnerHalfEdgeAroundFaceCirculator (idx_face); + const InnerHalfEdgeAroundFaceCirculator circ_end = circ; + do + { + inner_he_.push_back (circ.getTargetIndex ()); + is_boundary_.push_back (this->isBoundary (this->getOppositeHalfEdgeIndex (circ.getTargetIndex ()))); + } while (++circ != circ_end); + assert (inner_he_.size () >= 3); // Minimum should be a triangle. + + const int n = static_cast (inner_he_.size ()); + int j; + + if (IsManifold::value) + { + for (int i=0; ireconnect (inner_he_ [i], inner_he_ [j], is_boundary_ [i], is_boundary_ [j]); + } + for (int i=0; igetHalfEdge (inner_he_ [i]).idx_face_.invalidate (); + } + } + else + { + for (int i=0; ireconnect (inner_he_ [i], inner_he_ [j], is_boundary_ [i], is_boundary_ [j]); + this->getHalfEdge (inner_he_ [i]).idx_face_.invalidate (); + } + } + + this->markDeleted (idx_face); + } + + //////////////////////////////////////////////////////////////////////// + // reconnect + //////////////////////////////////////////////////////////////////////// + + /** \brief Deconnect the input half-edges from the mesh and adjust the indices of the connected half-edges. */ + void + reconnect (const HalfEdgeIndex& idx_he_ab, + const HalfEdgeIndex& idx_he_bc, + const bool is_boundary_ba, + const bool is_boundary_cb) + { + const HalfEdgeIndex idx_he_ba = this->getOppositeHalfEdgeIndex (idx_he_ab); + const HalfEdgeIndex idx_he_cb = this->getOppositeHalfEdgeIndex (idx_he_bc); + const VertexIndex idx_v_b = this->getTerminatingVertexIndex (idx_he_ab); + + if (is_boundary_ba && is_boundary_cb) // boundary - boundary + { + const HalfEdgeIndex& idx_he_cb_next = this->getNextHalfEdgeIndex (idx_he_cb); + + if (idx_he_cb_next == idx_he_ba) // Vertex b is isolated + { + this->markDeleted (idx_v_b); + } + else + { + this->connectPrevNext (this->getPrevHalfEdgeIndex (idx_he_ba), idx_he_cb_next); + this->setOutgoingHalfEdgeIndex (idx_v_b, idx_he_cb_next); + } + + this->markDeleted (idx_he_ab); + this->markDeleted (idx_he_ba); + } + else if (is_boundary_ba && !is_boundary_cb) // boundary - no boundary + { + this->connectPrevNext (this->getPrevHalfEdgeIndex (idx_he_ba), idx_he_bc); + this->setOutgoingHalfEdgeIndex (idx_v_b, idx_he_bc); + + this->markDeleted (idx_he_ab); + this->markDeleted (idx_he_ba); + } + else if (!is_boundary_ba && is_boundary_cb) // no boundary - boundary + { + const HalfEdgeIndex& idx_he_cb_next = this->getNextHalfEdgeIndex (idx_he_cb); + this->connectPrevNext (idx_he_ab, idx_he_cb_next); + this->setOutgoingHalfEdgeIndex (idx_v_b, idx_he_cb_next); + } + else // no boundary - no boundary + { + this->reconnectNBNB (idx_he_bc, idx_he_cb, idx_v_b, IsManifold ()); + } + } + + /** \brief Both edges are not on the boundary. Manifold version. */ + void + reconnectNBNB (const HalfEdgeIndex& idx_he_bc, + const HalfEdgeIndex& idx_he_cb, + const VertexIndex& idx_v_b, + boost::true_type /*is_manifold*/) + { + if (this->isBoundary (idx_v_b)) + { + // Deletion of this face makes the mesh non-manifold + // -> delete the neighboring faces until it is manifold again + IncomingHalfEdgeAroundVertexCirculator circ = this->getIncomingHalfEdgeAroundVertexCirculator (idx_he_cb); + + while (!this->isBoundary (circ.getTargetIndex ())) + { + delete_faces_face_.push_back (this->getFaceIndex ((circ++).getTargetIndex ())); + +#ifdef PCL_GEOMETRY_MESH_BASE_TEST_DELETE_FACE_MANIFOLD_2 + if (circ == this->getIncomingHalfEdgeAroundVertexCirculator (idx_he_cb)) // Abort infinity loop + { + // In a manifold mesh we can't invalidate the face while reconnecting! + // See the implementation of + // deleteFace (const FaceIndex& idx_face, + // boost::false_type /*is_manifold*/) + pcl::geometry::g_pcl_geometry_mesh_base_test_delete_face_manifold_2_success = false; + return; + } +#endif + } + } + else + { + this->setOutgoingHalfEdgeIndex (idx_v_b, idx_he_bc); + } + } + + /** \brief Both edges are not on the boundary. Non-manifold version. */ + void + reconnectNBNB (const HalfEdgeIndex& idx_he_bc, + const HalfEdgeIndex& /*idx_he_cb*/, + const VertexIndex& idx_v_b, + boost::false_type /*is_manifold*/) + { + if (!this->isBoundary (idx_v_b)) + { + this->setOutgoingHalfEdgeIndex (idx_v_b, idx_he_bc); + } + } + + //////////////////////////////////////////////////////////////////////// + // markDeleted + //////////////////////////////////////////////////////////////////////// + + /** \brief Mark the given vertex as deleted. */ + inline void + markDeleted (const VertexIndex& idx_vertex) + { + assert (this->isValid (idx_vertex)); + this->getVertex (idx_vertex).idx_outgoing_half_edge_.invalidate (); + } + + /** \brief Mark the given half-edge as deleted. */ + inline void + markDeleted (const HalfEdgeIndex& idx_he) + { + assert (this->isValid (idx_he)); + this->getHalfEdge (idx_he).idx_terminating_vertex_.invalidate (); + } + + /** \brief Mark the given edge (both half-edges) as deleted. */ + inline void + markDeleted (const EdgeIndex& idx_edge) + { + assert (this->isValid (idx_edge)); + this->markDeleted (pcl::geometry::toHalfEdgeIndex (idx_edge, true)); + this->markDeleted (pcl::geometry::toHalfEdgeIndex (idx_edge, false)); + } + + /** \brief Mark the given face as deleted. */ + inline void + markDeleted (const FaceIndex& idx_face) + { + assert (this->isValid (idx_face)); + this->getFace (idx_face).idx_inner_half_edge_.invalidate (); + } + + //////////////////////////////////////////////////////////////////////// + // For cleanUp + //////////////////////////////////////////////////////////////////////// + + /** \brief Removes mesh elements and data that are marked as deleted from the container. + * \param IndexContainerT e.g. std::vector \ + * \param ElementContainerT e.g. std::vector \ + * \param DataContainerT e.g. std::vector \ + * \param HasDataT Integral constant specifying if the mesh has data associated with the elements. + * \param[in, out] elements Container for the mesh elements. Resized to the new size. + * \param[in, out] data_cloud Container for the mesh data. Resized to the new size. + * \return Container with the same size as the old input data. Holds the indices to the new elements for each non-deleted element and an invalid index if it is deleted. + */ + template IndexContainerT + remove (ElementContainerT& elements, DataContainerT& data_cloud) + { + typedef typename IndexContainerT::value_type Index; + typedef typename ElementContainerT::value_type Element; + + if (HasDataT::value) assert (elements.size () == data_cloud.size ()); + else assert (data_cloud.empty ()); // Bug in this class! + + IndexContainerT new_indices (elements.size (), typename IndexContainerT::value_type ()); + Index ind_old (0), ind_new (0); + + typename ElementContainerT::const_iterator it_e_old = elements.begin (); + typename ElementContainerT::iterator it_e_new = elements.begin (); + + typename DataContainerT::const_iterator it_d_old = data_cloud.begin (); + typename DataContainerT::iterator it_d_new = data_cloud.begin (); + + typename IndexContainerT::iterator it_ind_new = new_indices.begin (); + typename IndexContainerT::const_iterator it_ind_new_end = new_indices.end (); + + while (it_ind_new!=it_ind_new_end) + { + if (!this->isDeleted (ind_old)) + { + *it_ind_new = ind_new++; + + // TODO: Test for self assignment? + *it_e_new++ = *it_e_old; + this->assignIf (it_d_old, it_d_new, HasDataT ()); + this->incrementIf ( it_d_new, HasDataT ()); + } + ++ind_old; + ++it_e_old; + this->incrementIf (it_d_old, HasDataT ()); + ++it_ind_new; + } + + elements.resize (ind_new.get (), Element ()); + if (HasDataT::value) + { + data_cloud.resize (ind_new.get ()); + } + else if (it_d_old != data_cloud.begin () || it_d_new != data_cloud.begin ()) + { + std::cerr << "TODO: Bug in MeshBase::remove!\n"; + assert (false); + exit (EXIT_FAILURE); + } + + return (new_indices); + } + + /** \brief Increment the iterator. */ + template inline void + incrementIf (IteratorT& it, boost::true_type /*has_data*/) const + { + ++it; + } + + /** \brief Does nothing. */ + template inline void + incrementIf (IteratorT& /*it*/, boost::false_type /*has_data*/) const + { + } + + /** \brief Assign the source iterator to the target iterator. */ + template inline void + assignIf (const ConstIteratorT source, IteratorT target, boost::true_type /*has_data*/) const + { + *target = *source; + } + + /** \brief Does nothing. */ + template inline void + assignIf (const ConstIteratorT /*source*/, IteratorT /*target*/, boost::false_type /*has_data*/) const + { + } + + //////////////////////////////////////////////////////////////////////// + // Vertex / Half-edge / Face connectivity + //////////////////////////////////////////////////////////////////////// + + /** \brief Set the outgoing half-edge index to a given vertex. */ + inline void + setOutgoingHalfEdgeIndex (const VertexIndex& idx_vertex, const HalfEdgeIndex& idx_outgoing_half_edge) + { + assert (this->isValid (idx_vertex)); + this->getVertex (idx_vertex).idx_outgoing_half_edge_ = idx_outgoing_half_edge; + } + + /** \brief Set the terminating vertex index to a given half-edge. */ + inline void + setTerminatingVertexIndex (const HalfEdgeIndex& idx_half_edge, const VertexIndex& idx_terminating_vertex) + { + assert (this->isValid (idx_half_edge)); + this->getHalfEdge (idx_half_edge).idx_terminating_vertex_ = idx_terminating_vertex; + } + + /** \brief Set the next half_edge index to a given half-edge. */ + inline void + setNextHalfEdgeIndex (const HalfEdgeIndex& idx_half_edge, const HalfEdgeIndex& idx_next_half_edge) + { + assert (this->isValid (idx_half_edge)); + this->getHalfEdge (idx_half_edge).idx_next_half_edge_ = idx_next_half_edge; + } + + /** \brief Set the previous half-edge index to a given half-edge. */ + inline void + setPrevHalfEdgeIndex (const HalfEdgeIndex& idx_half_edge, + const HalfEdgeIndex& idx_prev_half_edge) + { + assert (this->isValid (idx_half_edge)); + this->getHalfEdge (idx_half_edge).idx_prev_half_edge_ = idx_prev_half_edge; + } + + /** \brief Set the face index to a given half-edge. */ + inline void + setFaceIndex (const HalfEdgeIndex& idx_half_edge, const FaceIndex& idx_face) + { + assert (this->isValid (idx_half_edge)); + this->getHalfEdge (idx_half_edge).idx_face_ = idx_face; + } + + /** \brief Set the inner half-edge index to a given face. */ + inline void + setInnerHalfEdgeIndex (const FaceIndex& idx_face, const HalfEdgeIndex& idx_inner_half_edge) + { + assert (this->isValid (idx_face)); + this->getFace (idx_face).idx_inner_half_edge_ = idx_inner_half_edge; + } + + //////////////////////////////////////////////////////////////////////// + // isBoundary / isManifold + //////////////////////////////////////////////////////////////////////// + + /** \brief Check if any vertex of the face lies on the boundary. */ + bool + isBoundary (const FaceIndex& idx_face, boost::true_type /*check_vertices*/) const + { + VertexAroundFaceCirculator circ = this->getVertexAroundFaceCirculator (idx_face); + const VertexAroundFaceCirculator circ_end = circ; + + do + { + if (this->isBoundary (circ.getTargetIndex ())) + { + return (true); + } + } while (++circ!=circ_end); + + return (false); + } + + /** \brief Check if any edge of the face lies on the boundary. */ + bool + isBoundary (const FaceIndex& idx_face, boost::false_type /*check_vertices*/) const + { + OuterHalfEdgeAroundFaceCirculator circ = this->getOuterHalfEdgeAroundFaceCirculator (idx_face); + const OuterHalfEdgeAroundFaceCirculator circ_end = circ; + + do + { + if (this->isBoundary (circ.getTargetIndex ())) + { + return (true); + } + } while (++circ!=circ_end); + + return (false); + } + + /** \brief Always manifold. */ + inline bool + isManifold (const VertexIndex&, boost::true_type /*is_manifold*/) const + { + return (true); + } + + /** \brief Check if the given vertex is manifold. */ + bool + isManifold (const VertexIndex& idx_vertex, boost::false_type /*is_manifold*/) const + { + OutgoingHalfEdgeAroundVertexCirculator circ = this->getOutgoingHalfEdgeAroundVertexCirculator (idx_vertex); + const OutgoingHalfEdgeAroundVertexCirculator circ_end = circ; + + if (!this->isBoundary ((circ++).getTargetIndex ())) return (true); + do + { + if (this->isBoundary (circ.getTargetIndex ())) return (false); + } while (++circ != circ_end); + + return (true); + } + + /** \brief Always manifold. */ + inline bool + isManifold (boost::true_type /*is_manifold*/) const + { + return (true); + } + + /** \brief Check if all vertices in the mesh are manifold. */ + bool + isManifold (boost::false_type /*is_manifold*/) const + { + for (unsigned int i=0; isizeVertices (); ++i) + { + if (!this->isManifold (VertexIndex (i))) return (false); + } + return (true); + } + + //////////////////////////////////////////////////////////////////////// + // reserveData / resizeData / clearData + //////////////////////////////////////////////////////////////////////// + + /** \brief Reserve storage space for the mesh data. */ + template inline void + reserveData (DataCloudT& cloud, const size_t n, boost::true_type /*has_data*/) const + { + cloud.reserve (n); + } + + /** \brief Does nothing */ + template inline void + reserveData (DataCloudT& /*cloud*/, const size_t /*n*/, boost::false_type /*has_data*/) const + { + } + + /** \brief Resize the mesh data. */ + template inline void + resizeData (DataCloudT& /*data_cloud*/, const size_t n, const typename DataCloudT::value_type& data, boost::true_type /*has_data*/) const + { + data.resize (n, data); + } + + /** \brief Does nothing. */ + template inline void + resizeData (DataCloudT& /*data_cloud*/, const size_t /*n*/, const typename DataCloudT::value_type& /*data*/, boost::false_type /*has_data*/) const + { + } + + /** \brief Clear the mesh data. */ + template inline void + clearData (DataCloudT& cloud, boost::true_type /*has_data*/) const + { + cloud.clear (); + } + + /** \brief Does nothing. */ + template inline void + clearData (DataCloudT& /*cloud*/, boost::false_type /*has_data*/) const + { + } + + //////////////////////////////////////////////////////////////////////// + // get / set Vertex + //////////////////////////////////////////////////////////////////////// + + /** \brief Get the vertex for the given index. */ + inline Vertex& + getVertex (const VertexIndex& idx_vertex) + { + assert (this->isValid (idx_vertex)); + return (vertices_ [idx_vertex.get ()]); + } + + /** \brief Get the vertex for the given index. */ + inline Vertex + getVertex (const VertexIndex& idx_vertex) const + { + assert (this->isValid (idx_vertex)); + return (vertices_ [idx_vertex.get ()]); + } + + /** \brief Set the vertex at the given index. */ + inline void + setVertex (const VertexIndex& idx_vertex, const Vertex& vertex) + { + assert (this->isValid (idx_vertex)); + vertices_ [idx_vertex.get ()] = vertex; + } + + //////////////////////////////////////////////////////////////////////// + // get / set HalfEdge + //////////////////////////////////////////////////////////////////////// + + /** \brief Get the half-edge for the given index. */ + inline HalfEdge& + getHalfEdge (const HalfEdgeIndex& idx_he) + { + assert (this->isValid (idx_he)); + return (half_edges_ [idx_he.get ()]); + } + + /** \brief Get the half-edge for the given index. */ + inline HalfEdge + getHalfEdge (const HalfEdgeIndex& idx_he) const + { + assert (this->isValid (idx_he)); + return (half_edges_ [idx_he.get ()]); + } + + /** \brief Set the half-edge at the given index. */ + inline void + setHalfEdge (const HalfEdgeIndex& idx_he, const HalfEdge& half_edge) + { + assert (this->isValid (idx_he)); + half_edges_ [idx_he.get ()] = half_edge; + } + + //////////////////////////////////////////////////////////////////////// + // get / set Face + //////////////////////////////////////////////////////////////////////// + + /** \brief Get the face for the given index. */ + inline Face& + getFace (const FaceIndex& idx_face) + { + assert (this->isValid (idx_face)); + return (faces_ [idx_face.get ()]); + } + + /** \brief Get the face for the given index. */ + inline Face + getFace (const FaceIndex& idx_face) const + { + assert (this->isValid (idx_face)); + return (faces_ [idx_face.get ()]); + } + + /** \brief Set the face at the given index. */ + inline void + setFace (const FaceIndex& idx_face, const Face& face) + { + assert (this->isValid (idx_face)); + faces_ [idx_face.get ()] = face; + } + + private: + + //////////////////////////////////////////////////////////////////////// + // Members + //////////////////////////////////////////////////////////////////////// + + /** \brief Data stored for the vertices. */ + VertexDataCloud vertex_data_cloud_; + + /** \brief Data stored for the half-edges. */ + HalfEdgeDataCloud half_edge_data_cloud_; + + /** \brief Data stored for the edges. */ + EdgeDataCloud edge_data_cloud_; + + /** \brief Data stored for the faces. */ + FaceDataCloud face_data_cloud_; + + /** \brief Connectivity information for the vertices. */ + Vertices vertices_; + + /** \brief Connectivity information for the half-edges. */ + HalfEdges half_edges_; + + /** \brief Connectivity information for the faces. */ + Faces faces_; + + // NOTE: It is MUCH faster to store these variables permamently. + + /** \brief Storage for addFaceImplBase and deleteFace. */ + HalfEdgeIndices inner_he_; + + /** \brief Storage for addFaceImplBase. */ + HalfEdgeIndices free_he_; + + /** \brief Storage for addFaceImplBase. */ + std::vector is_new_; + + /** \brief Storage for addFaceImplBase. */ + std::vector make_adjacent_; + + /** \brief Storage for deleteFace. */ + std::vector is_boundary_; + + /** \brief Storage for deleteVertex. */ + FaceIndices delete_faces_vertex_; + + /** \brief Storage for deleteFace. */ + FaceIndices delete_faces_face_; + + public: + + template + friend class pcl::geometry::MeshIO; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } // End namespace geometry +} // End namespace pcl + +#endif // PCL_GEOMETRY_MESH_BASE_H diff --git a/pcl-1.7/pcl/geometry/mesh_circulators.h b/pcl-1.7/pcl/geometry/mesh_circulators.h new file mode 100644 index 0000000..a52b2e1 --- /dev/null +++ b/pcl-1.7/pcl/geometry/mesh_circulators.h @@ -0,0 +1,915 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +// NOTE: This file has been created with 'pcl_src/geometry/include/pcl/geometry/mesh_circulators.py' + +#ifndef PCL_GEOMETRY_MESH_CIRCULATORS_H +#define PCL_GEOMETRY_MESH_CIRCULATORS_H + +#include +#include + +//////////////////////////////////////////////////////////////////////////////// +// VertexAroundVertexCirculator +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief Circulates counter-clockwise around a vertex and returns an index to the terminating vertex of the outgoing half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getVertexAroundVertexCirculator (). + * \tparam MeshT Mesh to which this circulator belongs to. + * \note The circulator can't be used to change the connectivity in the mesh (only const circulators are valid). + * \author Martin Saelzle + * \ingroup geometry + */ + template + class VertexAroundVertexCirculator + : boost::equality_comparable + , boost::unit_steppable + > > + { + public: + + typedef boost::equality_comparable + , boost::unit_steppable > > Base; + typedef pcl::geometry::VertexAroundVertexCirculator Self; + + typedef MeshT Mesh; + typedef typename Mesh::VertexIndex VertexIndex; + typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex; + + /** \brief Constructor resulting in an invalid circulator. */ + VertexAroundVertexCirculator () + : mesh_ (NULL), + idx_outgoing_half_edge_ () + { + } + + /** \brief Construct from the vertex around which we want to circulate. */ + VertexAroundVertexCirculator (const VertexIndex& idx_vertex, + Mesh*const mesh) + : mesh_ (mesh), + idx_outgoing_half_edge_ (mesh->getOutgoingHalfEdgeIndex (idx_vertex)) + { + } + + /** \brief Construct directly from the outgoing half-edge. */ + VertexAroundVertexCirculator (const HalfEdgeIndex& idx_outgoing_half_edge, + Mesh*const mesh) + : mesh_ (mesh), + idx_outgoing_half_edge_ (idx_outgoing_half_edge) + { + } + + /** \brief Check if the circulator is valid. + * \warning Does NOT check if the stored mesh pointer is valid. You have to ensure this yourself when constructing the circulator. */ + inline bool + isValid () const + { + return (idx_outgoing_half_edge_.isValid ()); + } + + /** \brief Comparison operators (with boost::operators): == != + * \warning Does NOT check if the circulators belong to the same mesh. Please check this yourself. */ + inline bool + operator == (const Self& other) const + { + return (idx_outgoing_half_edge_ == other.idx_outgoing_half_edge_); + } + + /** \brief Increment operators (with boost::operators): ++ (pre and post) */ + inline Self& + operator ++ () + { + idx_outgoing_half_edge_ = mesh_->getNextHalfEdgeIndex (mesh_->getOppositeHalfEdgeIndex (idx_outgoing_half_edge_)); + return (*this); + } + + /** \brief Decrement operators (with boost::operators): -- (pre and post) */ + inline Self& + operator -- () + { + idx_outgoing_half_edge_ = mesh_->getOppositeHalfEdgeIndex (mesh_->getPrevHalfEdgeIndex (idx_outgoing_half_edge_)); + return (*this); + } + + /** \brief Get the index to the target vertex. */ + inline VertexIndex + getTargetIndex () const + { + return (mesh_->getTerminatingVertexIndex (idx_outgoing_half_edge_)); + } + + /** \brief Get the half-edge that is currently stored in the circulator. */ + inline HalfEdgeIndex + getCurrentHalfEdgeIndex () const + { + return (idx_outgoing_half_edge_); + } + + /** \brief The mesh to which this circulator belongs to. */ + Mesh* mesh_; + + /** \brief The outgoing half-edge of the vertex around which we want to circulate. */ + HalfEdgeIndex idx_outgoing_half_edge_; + }; + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// OutgoingHalfEdgeAroundVertexCirculator +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief Circulates counter-clockwise around a vertex and returns an index to the outgoing half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getOutgoingHalfEdgeAroundVertexCirculator (). + * \tparam MeshT Mesh to which this circulator belongs to. + * \note The circulator can't be used to change the connectivity in the mesh (only const circulators are valid). + * \author Martin Saelzle + * \ingroup geometry + */ + template + class OutgoingHalfEdgeAroundVertexCirculator + : boost::equality_comparable + , boost::unit_steppable + > > + { + public: + + typedef boost::equality_comparable + , boost::unit_steppable > > Base; + typedef pcl::geometry::OutgoingHalfEdgeAroundVertexCirculator Self; + + typedef MeshT Mesh; + typedef typename Mesh::VertexIndex VertexIndex; + typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex; + + /** \brief Constructor resulting in an invalid circulator. */ + OutgoingHalfEdgeAroundVertexCirculator () + : mesh_ (NULL), + idx_outgoing_half_edge_ () + { + } + + /** \brief Construct from the vertex around which we want to circulate. */ + OutgoingHalfEdgeAroundVertexCirculator (const VertexIndex& idx_vertex, + Mesh*const mesh) + : mesh_ (mesh), + idx_outgoing_half_edge_ (mesh->getOutgoingHalfEdgeIndex (idx_vertex)) + { + } + + /** \brief Construct directly from the outgoing half-edge. */ + OutgoingHalfEdgeAroundVertexCirculator (const HalfEdgeIndex& idx_outgoing_half_edge, + Mesh*const mesh) + : mesh_ (mesh), + idx_outgoing_half_edge_ (idx_outgoing_half_edge) + { + } + + /** \brief Check if the circulator is valid. + * \warning Does NOT check if the stored mesh pointer is valid. You have to ensure this yourself when constructing the circulator. */ + inline bool + isValid () const + { + return (idx_outgoing_half_edge_.isValid ()); + } + + /** \brief Comparison operators (with boost::operators): == != + * \warning Does NOT check if the circulators belong to the same mesh. Please check this yourself. */ + inline bool + operator == (const Self& other) const + { + return (idx_outgoing_half_edge_ == other.idx_outgoing_half_edge_); + } + + /** \brief Increment operators (with boost::operators): ++ (pre and post) */ + inline Self& + operator ++ () + { + idx_outgoing_half_edge_ = mesh_->getNextHalfEdgeIndex (mesh_->getOppositeHalfEdgeIndex (idx_outgoing_half_edge_)); + return (*this); + } + + /** \brief Decrement operators (with boost::operators): -- (pre and post) */ + inline Self& + operator -- () + { + idx_outgoing_half_edge_ = mesh_->getOppositeHalfEdgeIndex (mesh_->getPrevHalfEdgeIndex (idx_outgoing_half_edge_)); + return (*this); + } + + /** \brief Get the index to the outgoing half-edge. */ + inline HalfEdgeIndex + getTargetIndex () const + { + return (idx_outgoing_half_edge_); + } + + /** \brief Get the half-edge that is currently stored in the circulator. */ + inline HalfEdgeIndex + getCurrentHalfEdgeIndex () const + { + return (idx_outgoing_half_edge_); + } + + /** \brief The mesh to which this circulator belongs to. */ + Mesh* mesh_; + + /** \brief The outgoing half-edge of the vertex around which we want to circulate. */ + HalfEdgeIndex idx_outgoing_half_edge_; + }; + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// IncomingHalfEdgeAroundVertexCirculator +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief Circulates counter-clockwise around a vertex and returns an index to the incoming half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getIncomingHalfEdgeAroundVertexCirculator (). + * \tparam MeshT Mesh to which this circulator belongs to. + * \note The circulator can't be used to change the connectivity in the mesh (only const circulators are valid). + * \author Martin Saelzle + * \ingroup geometry + */ + template + class IncomingHalfEdgeAroundVertexCirculator + : boost::equality_comparable + , boost::unit_steppable + > > + { + public: + + typedef boost::equality_comparable + , boost::unit_steppable > > Base; + typedef pcl::geometry::IncomingHalfEdgeAroundVertexCirculator Self; + + typedef MeshT Mesh; + typedef typename Mesh::VertexIndex VertexIndex; + typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex; + + /** \brief Constructor resulting in an invalid circulator. */ + IncomingHalfEdgeAroundVertexCirculator () + : mesh_ (NULL), + idx_incoming_half_edge_ () + { + } + + /** \brief Construct from the vertex around which we want to circulate. */ + IncomingHalfEdgeAroundVertexCirculator (const VertexIndex& idx_vertex, + Mesh*const mesh) + : mesh_ (mesh), + idx_incoming_half_edge_ (mesh->getIncomingHalfEdgeIndex (idx_vertex)) + { + } + + /** \brief Construct directly from the incoming half-edge. */ + IncomingHalfEdgeAroundVertexCirculator (const HalfEdgeIndex& idx_incoming_half_edge, + Mesh*const mesh) + : mesh_ (mesh), + idx_incoming_half_edge_ (idx_incoming_half_edge) + { + } + + /** \brief Check if the circulator is valid. + * \warning Does NOT check if the stored mesh pointer is valid. You have to ensure this yourself when constructing the circulator. */ + inline bool + isValid () const + { + return (idx_incoming_half_edge_.isValid ()); + } + + /** \brief Comparison operators (with boost::operators): == != + * \warning Does NOT check if the circulators belong to the same mesh. Please check this yourself. */ + inline bool + operator == (const Self& other) const + { + return (idx_incoming_half_edge_ == other.idx_incoming_half_edge_); + } + + /** \brief Increment operators (with boost::operators): ++ (pre and post) */ + inline Self& + operator ++ () + { + idx_incoming_half_edge_ = mesh_->getOppositeHalfEdgeIndex (mesh_->getNextHalfEdgeIndex (idx_incoming_half_edge_)); + return (*this); + } + + /** \brief Decrement operators (with boost::operators): -- (pre and post) */ + inline Self& + operator -- () + { + idx_incoming_half_edge_ = mesh_->getPrevHalfEdgeIndex (mesh_->getOppositeHalfEdgeIndex (idx_incoming_half_edge_)); + return (*this); + } + + /** \brief Get the index to the incoming half-edge. */ + inline HalfEdgeIndex + getTargetIndex () const + { + return (idx_incoming_half_edge_); + } + + /** \brief Get the half-edge that is currently stored in the circulator. */ + inline HalfEdgeIndex + getCurrentHalfEdgeIndex () const + { + return (idx_incoming_half_edge_); + } + + /** \brief The mesh to which this circulator belongs to. */ + Mesh* mesh_; + + /** \brief The incoming half-edge of the vertex around which we want to circulate. */ + HalfEdgeIndex idx_incoming_half_edge_; + }; + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// FaceAroundVertexCirculator +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief Circulates counter-clockwise around a vertex and returns an index to the face of the outgoing half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getFaceAroundVertexCirculator (). + * \tparam MeshT Mesh to which this circulator belongs to. + * \note The circulator can't be used to change the connectivity in the mesh (only const circulators are valid). + * \author Martin Saelzle + * \ingroup geometry + */ + template + class FaceAroundVertexCirculator + : boost::equality_comparable + , boost::unit_steppable + > > + { + public: + + typedef boost::equality_comparable + , boost::unit_steppable > > Base; + typedef pcl::geometry::FaceAroundVertexCirculator Self; + + typedef MeshT Mesh; + typedef typename Mesh::FaceIndex FaceIndex; + typedef typename Mesh::VertexIndex VertexIndex; + typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex; + + /** \brief Constructor resulting in an invalid circulator. */ + FaceAroundVertexCirculator () + : mesh_ (NULL), + idx_outgoing_half_edge_ () + { + } + + /** \brief Construct from the vertex around which we want to circulate. */ + FaceAroundVertexCirculator (const VertexIndex& idx_vertex, + Mesh*const mesh) + : mesh_ (mesh), + idx_outgoing_half_edge_ (mesh->getOutgoingHalfEdgeIndex (idx_vertex)) + { + } + + /** \brief Construct directly from the outgoing half-edge. */ + FaceAroundVertexCirculator (const HalfEdgeIndex& idx_outgoing_half_edge, + Mesh*const mesh) + : mesh_ (mesh), + idx_outgoing_half_edge_ (idx_outgoing_half_edge) + { + } + + /** \brief Check if the circulator is valid. + * \warning Does NOT check if the stored mesh pointer is valid. You have to ensure this yourself when constructing the circulator. */ + inline bool + isValid () const + { + return (idx_outgoing_half_edge_.isValid ()); + } + + /** \brief Comparison operators (with boost::operators): == != + * \warning Does NOT check if the circulators belong to the same mesh. Please check this yourself. */ + inline bool + operator == (const Self& other) const + { + return (idx_outgoing_half_edge_ == other.idx_outgoing_half_edge_); + } + + /** \brief Increment operators (with boost::operators): ++ (pre and post) */ + inline Self& + operator ++ () + { + idx_outgoing_half_edge_ = mesh_->getNextHalfEdgeIndex (mesh_->getOppositeHalfEdgeIndex (idx_outgoing_half_edge_)); + return (*this); + } + + /** \brief Decrement operators (with boost::operators): -- (pre and post) */ + inline Self& + operator -- () + { + idx_outgoing_half_edge_ = mesh_->getOppositeHalfEdgeIndex (mesh_->getPrevHalfEdgeIndex (idx_outgoing_half_edge_)); + return (*this); + } + + /** \brief Get the index to the target face. */ + inline FaceIndex + getTargetIndex () const + { + return (mesh_->getFaceIndex (idx_outgoing_half_edge_)); + } + + /** \brief Get the half-edge that is currently stored in the circulator. */ + inline HalfEdgeIndex + getCurrentHalfEdgeIndex () const + { + return (idx_outgoing_half_edge_); + } + + /** \brief The mesh to which this circulator belongs to. */ + Mesh* mesh_; + + /** \brief The outgoing half-edge of the vertex around which we want to circulate. */ + HalfEdgeIndex idx_outgoing_half_edge_; + }; + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// VertexAroundFaceCirculator +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief Circulates clockwise around a face and returns an index to the terminating vertex of the inner half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getVertexAroundFaceCirculator (). + * \tparam MeshT Mesh to which this circulator belongs to. + * \note The circulator can't be used to change the connectivity in the mesh (only const circulators are valid). + * \author Martin Saelzle + * \ingroup geometry + */ + template + class VertexAroundFaceCirculator + : boost::equality_comparable + , boost::unit_steppable + > > + { + public: + + typedef boost::equality_comparable + , boost::unit_steppable > > Base; + typedef pcl::geometry::VertexAroundFaceCirculator Self; + + typedef MeshT Mesh; + typedef typename Mesh::VertexIndex VertexIndex; + typedef typename Mesh::FaceIndex FaceIndex; + typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex; + + /** \brief Constructor resulting in an invalid circulator. */ + VertexAroundFaceCirculator () + : mesh_ (NULL), + idx_inner_half_edge_ () + { + } + + /** \brief Construct from the face around which we want to circulate. */ + VertexAroundFaceCirculator (const FaceIndex& idx_face, + Mesh*const mesh) + : mesh_ (mesh), + idx_inner_half_edge_ (mesh->getInnerHalfEdgeIndex (idx_face)) + { + } + + /** \brief Construct directly from the inner half-edge. */ + VertexAroundFaceCirculator (const HalfEdgeIndex& idx_inner_half_edge, + Mesh*const mesh) + : mesh_ (mesh), + idx_inner_half_edge_ (idx_inner_half_edge) + { + } + + /** \brief Check if the circulator is valid. + * \warning Does NOT check if the stored mesh pointer is valid. You have to ensure this yourself when constructing the circulator. */ + inline bool + isValid () const + { + return (idx_inner_half_edge_.isValid ()); + } + + /** \brief Comparison operators (with boost::operators): == != + * \warning Does NOT check if the circulators belong to the same mesh. Please check this yourself. */ + inline bool + operator == (const Self& other) const + { + return (idx_inner_half_edge_ == other.idx_inner_half_edge_); + } + + /** \brief Increment operators (with boost::operators): ++ (pre and post) */ + inline Self& + operator ++ () + { + idx_inner_half_edge_ = mesh_->getNextHalfEdgeIndex (idx_inner_half_edge_); + return (*this); + } + + /** \brief Decrement operators (with boost::operators): -- (pre and post) */ + inline Self& + operator -- () + { + idx_inner_half_edge_ = mesh_->getPrevHalfEdgeIndex (idx_inner_half_edge_); + return (*this); + } + + /** \brief Get the index to the target vertex. */ + inline VertexIndex + getTargetIndex () const + { + return (mesh_->getTerminatingVertexIndex (idx_inner_half_edge_)); + } + + /** \brief Get the half-edge that is currently stored in the circulator. */ + inline HalfEdgeIndex + getCurrentHalfEdgeIndex () const + { + return (idx_inner_half_edge_); + } + + /** \brief The mesh to which this circulator belongs to. */ + Mesh* mesh_; + + /** \brief The inner half-edge of the face around which we want to circulate. */ + HalfEdgeIndex idx_inner_half_edge_; + }; + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// InnerHalfEdgeAroundFaceCirculator +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief Circulates clockwise around a face and returns an index to the inner half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getInnerHalfEdgeAroundFaceCirculator (). + * \tparam MeshT Mesh to which this circulator belongs to. + * \note The circulator can't be used to change the connectivity in the mesh (only const circulators are valid). + * \author Martin Saelzle + * \ingroup geometry + */ + template + class InnerHalfEdgeAroundFaceCirculator + : boost::equality_comparable + , boost::unit_steppable + > > + { + public: + + typedef boost::equality_comparable + , boost::unit_steppable > > Base; + typedef pcl::geometry::InnerHalfEdgeAroundFaceCirculator Self; + + typedef MeshT Mesh; + typedef typename Mesh::FaceIndex FaceIndex; + typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex; + + /** \brief Constructor resulting in an invalid circulator. */ + InnerHalfEdgeAroundFaceCirculator () + : mesh_ (NULL), + idx_inner_half_edge_ () + { + } + + /** \brief Construct from the face around which we want to circulate. */ + InnerHalfEdgeAroundFaceCirculator (const FaceIndex& idx_face, + Mesh*const mesh) + : mesh_ (mesh), + idx_inner_half_edge_ (mesh->getInnerHalfEdgeIndex (idx_face)) + { + } + + /** \brief Construct directly from the inner half-edge. */ + InnerHalfEdgeAroundFaceCirculator (const HalfEdgeIndex& idx_inner_half_edge, + Mesh*const mesh) + : mesh_ (mesh), + idx_inner_half_edge_ (idx_inner_half_edge) + { + } + + /** \brief Check if the circulator is valid. + * \warning Does NOT check if the stored mesh pointer is valid. You have to ensure this yourself when constructing the circulator. */ + inline bool + isValid () const + { + return (idx_inner_half_edge_.isValid ()); + } + + /** \brief Comparison operators (with boost::operators): == != + * \warning Does NOT check if the circulators belong to the same mesh. Please check this yourself. */ + inline bool + operator == (const Self& other) const + { + return (idx_inner_half_edge_ == other.idx_inner_half_edge_); + } + + /** \brief Increment operators (with boost::operators): ++ (pre and post) */ + inline Self& + operator ++ () + { + idx_inner_half_edge_ = mesh_->getNextHalfEdgeIndex (idx_inner_half_edge_); + return (*this); + } + + /** \brief Decrement operators (with boost::operators): -- (pre and post) */ + inline Self& + operator -- () + { + idx_inner_half_edge_ = mesh_->getPrevHalfEdgeIndex (idx_inner_half_edge_); + return (*this); + } + + /** \brief Get the index to the inner half-edge. */ + inline HalfEdgeIndex + getTargetIndex () const + { + return (idx_inner_half_edge_); + } + + /** \brief Get the half-edge that is currently stored in the circulator. */ + inline HalfEdgeIndex + getCurrentHalfEdgeIndex () const + { + return (idx_inner_half_edge_); + } + + /** \brief The mesh to which this circulator belongs to. */ + Mesh* mesh_; + + /** \brief The inner half-edge of the face around which we want to circulate. */ + HalfEdgeIndex idx_inner_half_edge_; + }; + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// OuterHalfEdgeAroundFaceCirculator +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief Circulates clockwise around a face and returns an index to the outer half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getOuterHalfEdgeAroundFaceCirculator (). + * \tparam MeshT Mesh to which this circulator belongs to. + * \note The circulator can't be used to change the connectivity in the mesh (only const circulators are valid). + * \author Martin Saelzle + * \ingroup geometry + */ + template + class OuterHalfEdgeAroundFaceCirculator + : boost::equality_comparable + , boost::unit_steppable + > > + { + public: + + typedef boost::equality_comparable + , boost::unit_steppable > > Base; + typedef pcl::geometry::OuterHalfEdgeAroundFaceCirculator Self; + + typedef MeshT Mesh; + typedef typename Mesh::FaceIndex FaceIndex; + typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex; + + /** \brief Constructor resulting in an invalid circulator. */ + OuterHalfEdgeAroundFaceCirculator () + : mesh_ (NULL), + idx_inner_half_edge_ () + { + } + + /** \brief Construct from the face around which we want to circulate. */ + OuterHalfEdgeAroundFaceCirculator (const FaceIndex& idx_face, + Mesh*const mesh) + : mesh_ (mesh), + idx_inner_half_edge_ (mesh->getInnerHalfEdgeIndex (idx_face)) + { + } + + /** \brief Construct directly from the inner half-edge. */ + OuterHalfEdgeAroundFaceCirculator (const HalfEdgeIndex& idx_inner_half_edge, + Mesh*const mesh) + : mesh_ (mesh), + idx_inner_half_edge_ (idx_inner_half_edge) + { + } + + /** \brief Check if the circulator is valid. + * \warning Does NOT check if the stored mesh pointer is valid. You have to ensure this yourself when constructing the circulator. */ + inline bool + isValid () const + { + return (idx_inner_half_edge_.isValid ()); + } + + /** \brief Comparison operators (with boost::operators): == != + * \warning Does NOT check if the circulators belong to the same mesh. Please check this yourself. */ + inline bool + operator == (const Self& other) const + { + return (idx_inner_half_edge_ == other.idx_inner_half_edge_); + } + + /** \brief Increment operators (with boost::operators): ++ (pre and post) */ + inline Self& + operator ++ () + { + idx_inner_half_edge_ = mesh_->getNextHalfEdgeIndex (idx_inner_half_edge_); + return (*this); + } + + /** \brief Decrement operators (with boost::operators): -- (pre and post) */ + inline Self& + operator -- () + { + idx_inner_half_edge_ = mesh_->getPrevHalfEdgeIndex (idx_inner_half_edge_); + return (*this); + } + + /** \brief Get the index to the outer half-edge. */ + inline HalfEdgeIndex + getTargetIndex () const + { + return (mesh_->getOppositeHalfEdgeIndex (idx_inner_half_edge_)); + } + + /** \brief Get the half-edge that is currently stored in the circulator. */ + inline HalfEdgeIndex + getCurrentHalfEdgeIndex () const + { + return (idx_inner_half_edge_); + } + + /** \brief The mesh to which this circulator belongs to. */ + Mesh* mesh_; + + /** \brief The inner half-edge of the face around which we want to circulate. */ + HalfEdgeIndex idx_inner_half_edge_; + }; + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// FaceAroundFaceCirculator +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief Circulates clockwise around a face and returns an index to the face of the outer half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getFaceAroundFaceCirculator (). + * \tparam MeshT Mesh to which this circulator belongs to. + * \note The circulator can't be used to change the connectivity in the mesh (only const circulators are valid). + * \author Martin Saelzle + * \ingroup geometry + */ + template + class FaceAroundFaceCirculator + : boost::equality_comparable + , boost::unit_steppable + > > + { + public: + + typedef boost::equality_comparable + , boost::unit_steppable > > Base; + typedef pcl::geometry::FaceAroundFaceCirculator Self; + + typedef MeshT Mesh; + typedef typename Mesh::FaceIndex FaceIndex; + typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex; + + /** \brief Constructor resulting in an invalid circulator. */ + FaceAroundFaceCirculator () + : mesh_ (NULL), + idx_inner_half_edge_ () + { + } + + /** \brief Construct from the face around which we want to circulate. */ + FaceAroundFaceCirculator (const FaceIndex& idx_face, + Mesh*const mesh) + : mesh_ (mesh), + idx_inner_half_edge_ (mesh->getInnerHalfEdgeIndex (idx_face)) + { + } + + /** \brief Construct directly from the inner half-edge. */ + FaceAroundFaceCirculator (const HalfEdgeIndex& idx_inner_half_edge, + Mesh*const mesh) + : mesh_ (mesh), + idx_inner_half_edge_ (idx_inner_half_edge) + { + } + + /** \brief Check if the circulator is valid. + * \warning Does NOT check if the stored mesh pointer is valid. You have to ensure this yourself when constructing the circulator. */ + inline bool + isValid () const + { + return (idx_inner_half_edge_.isValid ()); + } + + /** \brief Comparison operators (with boost::operators): == != + * \warning Does NOT check if the circulators belong to the same mesh. Please check this yourself. */ + inline bool + operator == (const Self& other) const + { + return (idx_inner_half_edge_ == other.idx_inner_half_edge_); + } + + /** \brief Increment operators (with boost::operators): ++ (pre and post) */ + inline Self& + operator ++ () + { + idx_inner_half_edge_ = mesh_->getNextHalfEdgeIndex (idx_inner_half_edge_); + return (*this); + } + + /** \brief Decrement operators (with boost::operators): -- (pre and post) */ + inline Self& + operator -- () + { + idx_inner_half_edge_ = mesh_->getPrevHalfEdgeIndex (idx_inner_half_edge_); + return (*this); + } + + /** \brief Get the index to the target face. */ + inline FaceIndex + getTargetIndex () const + { + return (mesh_->getOppositeFaceIndex (idx_inner_half_edge_)); + } + + /** \brief Get the half-edge that is currently stored in the circulator. */ + inline HalfEdgeIndex + getCurrentHalfEdgeIndex () const + { + return (idx_inner_half_edge_); + } + + /** \brief The mesh to which this circulator belongs to. */ + Mesh* mesh_; + + /** \brief The inner half-edge of the face around which we want to circulate. */ + HalfEdgeIndex idx_inner_half_edge_; + }; + } // End namespace geometry +} // End namespace pcl + +#endif // PCL_GEOMETRY_MESH_CIRCULATORS_H diff --git a/pcl-1.7/pcl/geometry/mesh_conversion.h b/pcl-1.7/pcl/geometry/mesh_conversion.h new file mode 100644 index 0000000..64f0003 --- /dev/null +++ b/pcl-1.7/pcl/geometry/mesh_conversion.h @@ -0,0 +1,134 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_GEOMETRY_MESH_CONVERSION_H +#define PCL_GEOMETRY_MESH_CONVERSION_H + +#include +#include + +namespace pcl +{ + namespace geometry + { + /** \brief Convert a half-edge mesh to a face-vertex mesh. + * \param[in] half_edge_mesh The input mesh. + * \param[out] face_vertex_mesh The output mesh. + * \author Martin Saelzle + * \ingroup geometry + */ + template void + toFaceVertexMesh (const HalfEdgeMeshT& half_edge_mesh, pcl::PolygonMesh& face_vertex_mesh) + { + typedef HalfEdgeMeshT HalfEdgeMesh; + typedef typename HalfEdgeMesh::VertexAroundFaceCirculator VAFC; + typedef typename HalfEdgeMesh::FaceIndex FaceIndex; + + pcl::Vertices polygon; + pcl::toPCLPointCloud2 (half_edge_mesh.getVertexDataCloud (), face_vertex_mesh.cloud); + + face_vertex_mesh.polygons.reserve (half_edge_mesh.sizeFaces ()); + for (size_t i=0; i int + toHalfEdgeMesh (const pcl::PolygonMesh& face_vertex_mesh, HalfEdgeMeshT& half_edge_mesh) + { + typedef HalfEdgeMeshT HalfEdgeMesh; + typedef typename HalfEdgeMesh::VertexDataCloud VertexDataCloud; + typedef typename HalfEdgeMesh::VertexIndex VertexIndex; + typedef typename HalfEdgeMesh::VertexIndices VertexIndices; + + BOOST_STATIC_ASSERT (HalfEdgeMesh::HasVertexData::value); // Output mesh must have data associated with the vertices! + + VertexDataCloud vertices; + pcl::fromPCLPointCloud2 (face_vertex_mesh.cloud, vertices); + + half_edge_mesh.reserveVertices (vertices.size ()); + half_edge_mesh.reserveEdges (3 * face_vertex_mesh.polygons.size ()); + half_edge_mesh.reserveFaces ( face_vertex_mesh.polygons.size ()); + + for (typename VertexDataCloud::const_iterator it=vertices.begin (); it!=vertices.end (); ++it) + { + half_edge_mesh.addVertex (*it); + } + + assert (half_edge_mesh.sizeVertices () == vertices.size ()); + + int count_not_added = 0; + VertexIndices vi; + vi.reserve (3); // Minimum number (triangle) + for (size_t i=0; i + +namespace pcl +{ + namespace geometry + { + template + class MeshBase; + + template + class MeshIO; + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// Vertex +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief A vertex is a node in the mesh. + * \author Martin Saelzle + * \ingroup geometry + */ + class Vertex + { + private: + + typedef pcl::geometry::HalfEdgeIndex HalfEdgeIndex; + + /** \brief Constructor. + * \param[in] idx_outgoing_half_edge Index to the outgoing half-edge. Defaults to an invalid index. + */ + explicit Vertex (const HalfEdgeIndex& idx_outgoing_half_edge = HalfEdgeIndex ()) + : idx_outgoing_half_edge_ (idx_outgoing_half_edge) + {} + + /** \brief Index to the outgoing half-edge. The vertex is considered to be deleted if it stores an invalid outgoing half-edge index. */ + HalfEdgeIndex idx_outgoing_half_edge_; + + template + friend class pcl::geometry::MeshBase; + + template + friend class pcl::geometry::MeshIO; + }; + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// HalfEdge +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief An edge is a connection between two vertices. In a half-edge mesh the edge is split into two half-edges with opposite orientation. Each half-edge stores the index to the terminating vertex, the next half-edge, the previous half-edge and the face it belongs to. The opposite half-edge is accessed implicitly. + * \author Martin Saelzle + * \ingroup geometry + */ + class HalfEdge + { + private: + + typedef pcl::geometry::VertexIndex VertexIndex; + typedef pcl::geometry::HalfEdgeIndex HalfEdgeIndex; + typedef pcl::geometry::FaceIndex FaceIndex; + + /** \brief Constructor. + * \param[in] idx_terminating_vertex Index to the terminating vertex. Defaults to an invalid index. + * \param[in] idx_next_half_edge Index to the next half-edge. Defaults to an invalid index. + * \param[in] idx_prev_half_edge Index to the previous half-edge. Defaults to an invalid index. + * \param[in] idx_face Index to the face. Defaults to an invalid index. + */ + explicit HalfEdge (const VertexIndex& idx_terminating_vertex = VertexIndex (), + const HalfEdgeIndex& idx_next_half_edge = HalfEdgeIndex (), + const HalfEdgeIndex& idx_prev_half_edge = HalfEdgeIndex (), + const FaceIndex& idx_face = FaceIndex ()) + : idx_terminating_vertex_ (idx_terminating_vertex), + idx_next_half_edge_ (idx_next_half_edge), + idx_prev_half_edge_ (idx_prev_half_edge), + idx_face_ (idx_face) + { + } + + /** \brief Index to the terminating vertex. The half-edge is considered to be deleted if it stores an invalid terminating vertex index. */ + VertexIndex idx_terminating_vertex_; + + /** \brief Index to the next half-edge. */ + HalfEdgeIndex idx_next_half_edge_; + + /** \brief Index to the previous half-edge. */ + HalfEdgeIndex idx_prev_half_edge_; + + /** \brief Index to the face. The half-edge is considered to be on the boundary if it stores an invalid face index. */ + FaceIndex idx_face_; + + template + friend class pcl::geometry::MeshBase; + + template + friend class pcl::geometry::MeshIO; + }; + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// Face +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief A face is a closed loop of edges. + * \author Martin Saelzle + * \ingroup geometry + */ + class Face + { + private: + + typedef pcl::geometry::HalfEdgeIndex HalfEdgeIndex; + + /** \brief Constructor. + * \param[in] inner_half_edge_idx Index to the outgoing half-edge. Defaults to an invalid index + */ + explicit Face (const HalfEdgeIndex& idx_inner_half_edge = HalfEdgeIndex ()) + : idx_inner_half_edge_ (idx_inner_half_edge) + {} + + /** \brief Index to the inner half-edge. The face is considered to be deleted if it stores an invalid inner half-edge index. */ + HalfEdgeIndex idx_inner_half_edge_; + + template + friend class pcl::geometry::MeshBase; + + template + friend class pcl::geometry::MeshIO; + }; + } // End namespace geometry +} // End namespace pcl + +#endif // PCL_GEOMETRY_MESH_ELEMENTS_H diff --git a/pcl-1.7/pcl/geometry/mesh_indices.h b/pcl-1.7/pcl/geometry/mesh_indices.h new file mode 100644 index 0000000..36f82b7 --- /dev/null +++ b/pcl-1.7/pcl/geometry/mesh_indices.h @@ -0,0 +1,633 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +// NOTE: This file has been created with 'pcl_src/geometry/include/pcl/geometry/mesh_indices.py' + +#ifndef PCL_GEOMETRY_MESH_INDICES_H +#define PCL_GEOMETRY_MESH_INDICES_H + +#include + +#include + +//////////////////////////////////////////////////////////////////////////////// +// VertexIndex +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief Index used to access elements in the half-edge mesh. It is basically just a wrapper around an integer with a few added methods. + * \author Martin Saelzle + * \ingroup geometry + */ + class VertexIndex + : boost::totally_ordered <= >= == != + , boost::unit_steppable > > + { + public: + + typedef boost::totally_ordered > > Base; + typedef pcl::geometry::VertexIndex Self; + + /** \brief Constructor. Initializes with an invalid index. */ + VertexIndex () + : index_ (-1) + { + } + + /** \brief Constructor. + * \param[in] index The integer index. + */ + explicit VertexIndex (const int index) + : index_ (index) + { + } + + /** \brief Returns true if the index is valid. */ + inline bool + isValid () const + { + return (index_ >= 0); + } + + /** \brief Invalidate the index. */ + inline void + invalidate () + { + index_ = -1; + } + + /** \brief Get the index. */ + inline int + get () const + { + return (index_); + } + + /** \brief Set the index. */ + inline void + set (const int index) + { + index_ = index; + } + + /** \brief Comparison operators (with boost::operators): < > <= >= */ + inline bool + operator < (const Self& other) const + { + return (this->get () < other.get ()); + } + + /** \brief Comparison operators (with boost::operators): == != */ + inline bool + operator == (const Self& other) const + { + return (this->get () == other.get ()); + } + + /** \brief Increment operators (with boost::operators): ++ (pre and post) */ + inline Self& + operator ++ () + { + ++index_; + return (*this); + } + + /** \brief Decrement operators (with boost::operators): \-\- (pre and post) */ + inline Self& + operator -- () + { + --index_; + return (*this); + } + + /** \brief Addition operators (with boost::operators): + += */ + inline Self& + operator += (const Self& other) + { + index_ += other.get (); + return (*this); + } + + /** \brief Subtraction operators (with boost::operators): - -= */ + inline Self& + operator -= (const Self& other) + { + index_ -= other.get (); + return (*this); + } + + private: + + /** \brief Stored index. */ + int index_; + + friend std::istream& + operator >> (std::istream& is, pcl::geometry::VertexIndex& index); + }; + + /** \brief ostream operator. */ + inline std::ostream& + operator << (std::ostream& os, const pcl::geometry::VertexIndex& index) + { + return (os << index.get ()); + } + + /** \brief istream operator. */ + inline std::istream& + operator >> (std::istream& is, pcl::geometry::VertexIndex& index) + { + return (is >> index.index_); + } + + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// HalfEdgeIndex +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief Index used to access elements in the half-edge mesh. It is basically just a wrapper around an integer with a few added methods. + * \author Martin Saelzle + * \ingroup geometry + */ + class HalfEdgeIndex + : boost::totally_ordered <= >= == != + , boost::unit_steppable > > + { + public: + + typedef boost::totally_ordered > > Base; + typedef pcl::geometry::HalfEdgeIndex Self; + + /** \brief Constructor. Initializes with an invalid index. */ + HalfEdgeIndex () + : index_ (-1) + { + } + + /** \brief Constructor. + * \param[in] index The integer index. + */ + explicit HalfEdgeIndex (const int index) + : index_ (index) + { + } + + /** \brief Returns true if the index is valid. */ + inline bool + isValid () const + { + return (index_ >= 0); + } + + /** \brief Invalidate the index. */ + inline void + invalidate () + { + index_ = -1; + } + + /** \brief Get the index. */ + inline int + get () const + { + return (index_); + } + + /** \brief Set the index. */ + inline void + set (const int index) + { + index_ = index; + } + + /** \brief Comparison operators (with boost::operators): < > <= >= */ + inline bool + operator < (const Self& other) const + { + return (this->get () < other.get ()); + } + + /** \brief Comparison operators (with boost::operators): == != */ + inline bool + operator == (const Self& other) const + { + return (this->get () == other.get ()); + } + + /** \brief Increment operators (with boost::operators): ++ (pre and post) */ + inline Self& + operator ++ () + { + ++index_; + return (*this); + } + + /** \brief Decrement operators (with boost::operators): \-\- (pre and post) */ + inline Self& + operator -- () + { + --index_; + return (*this); + } + + /** \brief Addition operators (with boost::operators): + += */ + inline Self& + operator += (const Self& other) + { + index_ += other.get (); + return (*this); + } + + /** \brief Subtraction operators (with boost::operators): - -= */ + inline Self& + operator -= (const Self& other) + { + index_ -= other.get (); + return (*this); + } + + private: + + /** \brief Stored index. */ + int index_; + + friend std::istream& + operator >> (std::istream& is, pcl::geometry::HalfEdgeIndex& index); + }; + + /** \brief ostream operator. */ + inline std::ostream& + operator << (std::ostream& os, const pcl::geometry::HalfEdgeIndex& index) + { + return (os << index.get ()); + } + + /** \brief istream operator. */ + inline std::istream& + operator >> (std::istream& is, pcl::geometry::HalfEdgeIndex& index) + { + return (is >> index.index_); + } + + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// EdgeIndex +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief Index used to access elements in the half-edge mesh. It is basically just a wrapper around an integer with a few added methods. + * \author Martin Saelzle + * \ingroup geometry + */ + class EdgeIndex + : boost::totally_ordered <= >= == != + , boost::unit_steppable > > + { + public: + + typedef boost::totally_ordered > > Base; + typedef pcl::geometry::EdgeIndex Self; + + /** \brief Constructor. Initializes with an invalid index. */ + EdgeIndex () + : index_ (-1) + { + } + + /** \brief Constructor. + * \param[in] index The integer index. + */ + explicit EdgeIndex (const int index) + : index_ (index) + { + } + + /** \brief Returns true if the index is valid. */ + inline bool + isValid () const + { + return (index_ >= 0); + } + + /** \brief Invalidate the index. */ + inline void + invalidate () + { + index_ = -1; + } + + /** \brief Get the index. */ + inline int + get () const + { + return (index_); + } + + /** \brief Set the index. */ + inline void + set (const int index) + { + index_ = index; + } + + /** \brief Comparison operators (with boost::operators): < > <= >= */ + inline bool + operator < (const Self& other) const + { + return (this->get () < other.get ()); + } + + /** \brief Comparison operators (with boost::operators): == != */ + inline bool + operator == (const Self& other) const + { + return (this->get () == other.get ()); + } + + /** \brief Increment operators (with boost::operators): ++ (pre and post) */ + inline Self& + operator ++ () + { + ++index_; + return (*this); + } + + /** \brief Decrement operators (with boost::operators): \-\- (pre and post) */ + inline Self& + operator -- () + { + --index_; + return (*this); + } + + /** \brief Addition operators (with boost::operators): + += */ + inline Self& + operator += (const Self& other) + { + index_ += other.get (); + return (*this); + } + + /** \brief Subtraction operators (with boost::operators): - -= */ + inline Self& + operator -= (const Self& other) + { + index_ -= other.get (); + return (*this); + } + + private: + + /** \brief Stored index. */ + int index_; + + friend std::istream& + operator >> (std::istream& is, pcl::geometry::EdgeIndex& index); + }; + + /** \brief ostream operator. */ + inline std::ostream& + operator << (std::ostream& os, const pcl::geometry::EdgeIndex& index) + { + return (os << index.get ()); + } + + /** \brief istream operator. */ + inline std::istream& + operator >> (std::istream& is, pcl::geometry::EdgeIndex& index) + { + return (is >> index.index_); + } + + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// FaceIndex +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief Index used to access elements in the half-edge mesh. It is basically just a wrapper around an integer with a few added methods. + * \author Martin Saelzle + * \ingroup geometry + */ + class FaceIndex + : boost::totally_ordered <= >= == != + , boost::unit_steppable > > + { + public: + + typedef boost::totally_ordered > > Base; + typedef pcl::geometry::FaceIndex Self; + + /** \brief Constructor. Initializes with an invalid index. */ + FaceIndex () + : index_ (-1) + { + } + + /** \brief Constructor. + * \param[in] index The integer index. + */ + explicit FaceIndex (const int index) + : index_ (index) + { + } + + /** \brief Returns true if the index is valid. */ + inline bool + isValid () const + { + return (index_ >= 0); + } + + /** \brief Invalidate the index. */ + inline void + invalidate () + { + index_ = -1; + } + + /** \brief Get the index. */ + inline int + get () const + { + return (index_); + } + + /** \brief Set the index. */ + inline void + set (const int index) + { + index_ = index; + } + + /** \brief Comparison operators (with boost::operators): < > <= >= */ + inline bool + operator < (const Self& other) const + { + return (this->get () < other.get ()); + } + + /** \brief Comparison operators (with boost::operators): == != */ + inline bool + operator == (const Self& other) const + { + return (this->get () == other.get ()); + } + + /** \brief Increment operators (with boost::operators): ++ (pre and post) */ + inline Self& + operator ++ () + { + ++index_; + return (*this); + } + + /** \brief Decrement operators (with boost::operators): \-\- (pre and post) */ + inline Self& + operator -- () + { + --index_; + return (*this); + } + + /** \brief Addition operators (with boost::operators): + += */ + inline Self& + operator += (const Self& other) + { + index_ += other.get (); + return (*this); + } + + /** \brief Subtraction operators (with boost::operators): - -= */ + inline Self& + operator -= (const Self& other) + { + index_ -= other.get (); + return (*this); + } + + private: + + /** \brief Stored index. */ + int index_; + + friend std::istream& + operator >> (std::istream& is, pcl::geometry::FaceIndex& index); + }; + + /** \brief ostream operator. */ + inline std::ostream& + operator << (std::ostream& os, const pcl::geometry::FaceIndex& index) + { + return (os << index.get ()); + } + + /** \brief istream operator. */ + inline std::istream& + operator >> (std::istream& is, pcl::geometry::FaceIndex& index) + { + return (is >> index.index_); + } + + } // End namespace geometry +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// Conversions +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace geometry + { + /** \brief Convert the given half-edge index to an edge index. */ + inline pcl::geometry::EdgeIndex + toEdgeIndex (const HalfEdgeIndex& index) + { + return (index.isValid () ? EdgeIndex (index.get () / 2) : EdgeIndex ()); + } + + /** \brief Convert the given edge index to a half-edge index. + * \param index + * \param[in] get_first The first half-edge of the edge is returned if this variable is true; elsewise the second. + */ + inline pcl::geometry::HalfEdgeIndex + toHalfEdgeIndex (const EdgeIndex& index, const bool get_first=true) + { + return (index.isValid () ? HalfEdgeIndex (index.get () * 2 + static_cast (!get_first)) : HalfEdgeIndex ()); + } + } // End namespace geometry +} // End namespace pcl + +#endif // PCL_GEOMETRY_MESH_INDICES_H diff --git a/pcl-1.7/pcl/geometry/mesh_io.h b/pcl-1.7/pcl/geometry/mesh_io.h new file mode 100644 index 0000000..148b44b --- /dev/null +++ b/pcl-1.7/pcl/geometry/mesh_io.h @@ -0,0 +1,265 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_GEOMETRY_MESH_IO_H +#define PCL_GEOMETRY_MESH_IO_H + +#include +#include +#include +#include + +namespace pcl +{ + namespace geometry + { + /** \brief Read / write the half-edge mesh from / to a file. + * \tparam MeshT e.g. pcl::geometry::TriangleMesh or pcl::geometry::PolygonMesh + * \author Martin Saelzle + * \ingroup geometry + * \todo + * - Only writes the topology (not the mesh data). + * - Supports only ascii. + * - Does not consider the mesh traits (e.g. manifold or not) + */ + template + class MeshIO + { + public: + + typedef MeshT Mesh; + + typedef typename Mesh::Vertex Vertex; + typedef typename Mesh::HalfEdge HalfEdge; + typedef typename Mesh::Face Face; + + typedef typename Mesh::Vertices Vertices; + typedef typename Mesh::HalfEdges HalfEdges; + typedef typename Mesh::Faces Faces; + + typedef typename Mesh::VertexIndex VertexIndex; + typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex; + typedef typename Mesh::FaceIndex FaceIndex; + + /** \brief Constructor. */ + MeshIO () + { + } + + /** \brief Read the mesh from a file with the given filename. + * \param[in] filename Path to the file. + * \param[out] mesh The loaded mesh. + * \return true if success. + */ + bool + read (const std::string& filename, Mesh& mesh) const + { + std::ifstream file (filename.c_str ()); + + if (!file.is_open ()) + { + std::cerr << "Error in MeshIO::read: Could not open the file '" << filename << "'\n"; + return (false); + } + + // Read the header + std::string line; + unsigned int line_number = 1; + int n_v = -1, n_he = -1, n_f = -1; + + if (!std::getline (file, line) || line.compare ("PCL half-edge mesh") != 0) + { + std::cerr << "Error loading '" << filename << "' (line " << line_number << "): Wrong file format.\n"; + return (false); + } + ++line_number; + + if (!std::getline (file, line)) + { + std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Number of vertices / half-edges / faces not found.\n"; + return (false); + } + { + std::istringstream iss (line); + if (!(iss >> n_v >> n_he >> n_f) || iss.good ()) // Don't allow more than 3 en + { + std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Could not read the number of vertices / half-edges / faces.\n"; + return (false); + } + } + if (n_v < 0 || n_he < 0 || n_f < 0) + { + std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Invalid number of vertices / half-edges / faces.\n"; + return (false); + } + ++line_number; + + // Read the vertices. + { + mesh.vertices_.reserve (n_v); + HalfEdgeIndex idx_ohe; // Outgoing half-edge; + + for (int i=0; i> idx_ohe) || iss.good ()) + { + std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Could not read the vertex.\n"; + return (false); + } + mesh.vertices_.push_back (Vertex (idx_ohe)); + } + } + + // Read the half-edges. + { + mesh.half_edges_.reserve (n_he); + VertexIndex idx_tv; // Terminating vertex. + HalfEdgeIndex idx_nhe; // Next half-edge; + HalfEdgeIndex idx_phe; // Previous half-edge. + FaceIndex idx_f; // Face. + + for (int i=0; i> idx_tv >> idx_nhe >> idx_phe >> idx_f) || iss.good ()) + { + std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Could not read the half-edge.\n"; + return (false); + } + mesh.half_edges_.push_back (HalfEdge (idx_tv, idx_nhe, idx_phe, idx_f)); + } + } + + // Read the faces. + { + mesh.faces_.reserve (n_f); + HalfEdgeIndex idx_ihe; // Inner half-edge. + + for (int i=0; i> idx_ihe) || iss.good ()) + { + std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Could not read the face.\n"; + return (false); + } + mesh.faces_.push_back (Face (idx_ihe)); + } + } + + // Set the data + if (Mesh::HasVertexData::value) mesh.vertex_data_cloud_. resize (n_v); + if (Mesh::HasHalfEdgeData::value) mesh.half_edge_data_cloud_.resize (n_he); + if (Mesh::HasEdgeData::value) mesh.edge_data_cloud_. resize (n_he / 2); + if (Mesh::HasFaceData::value) mesh.face_data_cloud_. resize (n_f); + + return (true); + } + + /** \brief Write the mesh to a file with the given filename. + * \param[in] filename Path to the file. + * \param[in] mesh The saved mesh. + * \return true if success + */ + bool + write (const std::string& filename, const Mesh& mesh) const + { + std::ofstream file (filename.c_str ()); + + // Write the header + if (!file.is_open ()) + { + std::cerr << "Error in MeshIO::write: Could not open the file '" << filename << "'\n"; + return (false); + } + + file << "PCL half-edge mesh\n"; + file << mesh.sizeVertices () << " " + << mesh.sizeHalfEdges () << " " + << mesh.sizeFaces () << "\n"; + + // Write the vertices + for (typename Vertices::const_iterator it=mesh.vertices_.begin (); it!=mesh.vertices_.end (); ++it) + { + file << it->idx_outgoing_half_edge_ << "\n"; + } + + // Write the half-edges + for (typename HalfEdges::const_iterator it=mesh.half_edges_.begin (); it!=mesh.half_edges_.end (); ++it) + { + file << it->idx_terminating_vertex_ << " " + << it->idx_next_half_edge_ << " " + << it->idx_prev_half_edge_ << " " + << it->idx_face_ << "\n"; + } + + // Write the faces + for (typename Faces::const_iterator it=mesh.faces_.begin (); it!=mesh.faces_.end (); ++it) + { + file << it->idx_inner_half_edge_ << "\n"; + } + + return (true); + } + }; + + } // End namespace geometry +} // End namespace pcl + +#endif // PCL_GEOMETRY_MESH_IO_H diff --git a/pcl-1.7/pcl/geometry/mesh_traits.h b/pcl-1.7/pcl/geometry/mesh_traits.h new file mode 100644 index 0000000..0c23243 --- /dev/null +++ b/pcl-1.7/pcl/geometry/mesh_traits.h @@ -0,0 +1,86 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_GEOMETRY_MESH_TRAITS_H +#define PCL_GEOMETRY_MESH_TRAITS_H + +#include + +namespace pcl +{ + namespace geometry + { + /** \brief No data is associated with the vertices / half-edges / edges / faces. */ + struct NoData + { +#if defined(_LIBCPP_VERSION) && _LIBCPP_VERSION <= 1101 + operator unsigned char() const + { + return 0; + } +#endif + }; + + /** \brief The mesh traits are used to set up compile time settings for the mesh. + * \tparam VertexDataT Data stored for each vertex. Defaults to pcl::NoData. + * \tparam HalfEdgeDataT Data stored for each half-edge. Defaults to pcl::NoData. + * \tparam EdgeDataT Data stored for each edge. Defaults to pcl::NoData. + * \tparam FaceDataT Data stored for each face. Defaults to pcl::NoData. + * \author Martin Saelzle + * \ingroup geometry + */ + template + struct DefaultMeshTraits + { + typedef VertexDataT VertexData; + typedef HalfEdgeDataT HalfEdgeData; + typedef EdgeDataT EdgeData; + typedef FaceDataT FaceData; + + /** \brief Specifies wether the mesh is manifold or not (only non-manifold vertices can be represented). */ + typedef boost::false_type IsManifold; + }; + } // End namespace geometry +} // End namespace pcl + +#endif // PCL_GEOMETRY_MESH_TRAITS_H diff --git a/pcl-1.7/pcl/geometry/organized_index_iterator.h b/pcl-1.7/pcl/geometry/organized_index_iterator.h new file mode 100644 index 0000000..479e0f3 --- /dev/null +++ b/pcl-1.7/pcl/geometry/organized_index_iterator.h @@ -0,0 +1,153 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef __PCL_ORGANIZED_INDEX_ITERATOR__ +#define __PCL_ORGANIZED_INDEX_ITERATOR__ + +namespace pcl +{ +/** \brief base class for iterators on 2-dimensional maps like images/organized clouds etc. + * \author Suat Gedikli + * \ingroup geometry + */ +class OrganizedIndexIterator +{ + public: + /** \brief constructor + * \param[in] width the width of the image/organized cloud + */ + OrganizedIndexIterator (unsigned width); + + /** \brief virtual destructor*/ + virtual ~OrganizedIndexIterator (); + + /** \brief go to next pixel/point in image/cloud*/ + virtual void operator ++ () = 0; + + /** \brief go to next pixel/point in image/cloud*/ + virtual void operator ++ (int); + + /** \brief returns the pixel/point index in the linearized memory of the image/cloud + * \return the pixel/point index in the linearized memory of the image/cloud + */ + unsigned operator* () const; + + /** \brief returns the pixel/point index in the linearized memory of the image/cloud + * \return the pixel/point index in the linearized memory of the image/cloud + */ + virtual unsigned getIndex () const; + + /** \brief returns the row index (y-coordinate) of the current pixel/point + * \return the row index (y-coordinate) of the current pixel/point + */ + virtual unsigned getRowIndex () const; + + /** \brief returns the col index (x-coordinate) of the current pixel/point + * \return the col index (x-coordinate) of the current pixel/point + */ + virtual unsigned getColumnIndex () const; + + /** \brief return whether the current visited pixel/point is valid or not. + * \return true if the current pixel/point is within the points to be iterated over, false otherwise + */ + virtual bool isValid () const = 0; + + /** \brief resets the iterator to the beginning of the line + */ + virtual void reset () = 0; + + protected: + /** \brief the width of the image/cloud*/ + unsigned width_; + + /** \brief the index of the current pixel/point*/ + unsigned index_; +}; + +//////////////////////////////////////////////////////////////////////////////// +//////////////////////////////////////////////////////////////////////////////// +//////////////////////////////////////////////////////////////////////////////// + +//////////////////////////////////////////////////////////////////////////////// +inline OrganizedIndexIterator::OrganizedIndexIterator (unsigned width) +: width_ (width) +, index_ (0) +{ +} + +//////////////////////////////////////////////////////////////////////////////// +inline OrganizedIndexIterator::~OrganizedIndexIterator () +{ +} + +//////////////////////////////////////////////////////////////////////////////// +inline void +OrganizedIndexIterator::operator++ (int) +{ + return operator ++(); +} + +//////////////////////////////////////////////////////////////////////////////// +inline unsigned +pcl::OrganizedIndexIterator::operator * () const +{ + return index_; +} + +//////////////////////////////////////////////////////////////////////////////// +inline unsigned +pcl::OrganizedIndexIterator::getIndex () const +{ + return index_; +} + +//////////////////////////////////////////////////////////////////////////////// +/** \brief default implementation. Should be overloaded + */ +inline unsigned +pcl::OrganizedIndexIterator::getRowIndex () const +{ + return index_ / width_; +} + +//////////////////////////////////////////////////////////////////////////////// +inline unsigned +pcl::OrganizedIndexIterator::getColumnIndex () const +{ + return index_ % width_; +} +} // namespace pcl + +#endif // __PCL_ORGANIZED_INDEX_ITERATOR__ \ No newline at end of file diff --git a/pcl-1.7/pcl/geometry/planar_polygon.h b/pcl-1.7/pcl/geometry/planar_polygon.h new file mode 100644 index 0000000..1619e48 --- /dev/null +++ b/pcl-1.7/pcl/geometry/planar_polygon.h @@ -0,0 +1,145 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: planar_polygon.h 4696 2012-02-23 06:12:55Z rusu $ + * + */ + +#ifndef PCL_GEOMETRY_PLANAR_POLYGON_H_ +#define PCL_GEOMETRY_PLANAR_POLYGON_H_ + + +#include +#include +#include + +namespace pcl +{ + /** \brief PlanarPolygon represents a planar (2D) polygon, potentially in a 3D space. + * \author Alex Trevor + */ + template + class PlanarPolygon + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Empty constructor for PlanarPolygon */ + PlanarPolygon () : contour_ (), coefficients_ () + {} + + /** \brief Constructor for PlanarPolygon + * \param[in] contour a vector of points bounding the polygon + * \param[in] coefficients a vector of the plane's coefficients (a,b,c,d) + */ + PlanarPolygon (typename pcl::PointCloud::VectorType &contour, + Eigen::Vector4f& coefficients) + : contour_ (contour), coefficients_ (coefficients) + {} + + /** \brief Destructor. */ + virtual ~PlanarPolygon () {} + + /** \brief Set the internal contour + * \param[in] contour the new planar polygonal contour + */ + void + setContour (const pcl::PointCloud &contour) + { + contour_ = contour.points; + } + + /** \brief Getter for the contour / boundary */ + typename pcl::PointCloud::VectorType& + getContour () + { + return (contour_); + } + + /** \brief Getter for the contour / boundary */ + const typename pcl::PointCloud::VectorType& + getContour () const + { + return (contour_); + } + + /** \brief Setr the internal coefficients + * \param[in] coefficients the new coefficients to be set + */ + void + setCoefficients (const Eigen::Vector4f &coefficients) + { + coefficients_ = coefficients; + } + + /** \brief Set the internal coefficients + * \param[in] coefficients the new coefficients to be set + */ + void + setCoefficients (const pcl::ModelCoefficients &coefficients) + { + for (int i = 0; i < 4; i++) + coefficients_[i] = coefficients.values.at (i); + } + + /** \brief Getter for the coefficients */ + Eigen::Vector4f& + getCoefficients () + { + return (coefficients_); + } + + /** \brief Getter for the coefficients */ + const Eigen::Vector4f& + getCoefficients () const + { + return (coefficients_); + } + + protected: + /** \brief A list of points on the boundary/contour of the planar region. */ + typename pcl::PointCloud::VectorType contour_; + + /** \brief A list of model coefficients (a,b,c,d). */ + Eigen::Vector4f coefficients_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#endif //#ifndef PCL_GEOMETRY_PLANAR_POLYGON_H_ + diff --git a/pcl-1.7/pcl/geometry/polygon_mesh.h b/pcl-1.7/pcl/geometry/polygon_mesh.h new file mode 100644 index 0000000..1171565 --- /dev/null +++ b/pcl-1.7/pcl/geometry/polygon_mesh.h @@ -0,0 +1,203 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_GEOMETRY_POLYGON_MESH_H +#define PCL_GEOMETRY_POLYGON_MESH_H + +#include + +namespace pcl +{ + namespace geometry + { + /** \brief Tag describing the type of the mesh. */ + struct PolygonMeshTag {}; + + /** \brief General half-edge mesh that can store any polygon with a minimum number of vertices of 3. + * \tparam MeshTraitsT Please have a look at pcl::geometry::DefaultMeshTraits. + * \author Martin Saelzle + * \ingroup geometry + */ + template + class PolygonMesh : public pcl::geometry::MeshBase , MeshTraitsT, PolygonMeshTag> + { + public: + + typedef pcl::geometry::MeshBase , MeshTraitsT, PolygonMeshTag> Base; + + typedef PolygonMesh Self; + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef typename Base::VertexData VertexData; + typedef typename Base::HalfEdgeData HalfEdgeData; + typedef typename Base::EdgeData EdgeData; + typedef typename Base::FaceData FaceData; + typedef typename Base::IsManifold IsManifold; + typedef typename Base::MeshTag MeshTag; + + typedef typename Base::HasVertexData HasVertexData; + typedef typename Base::HasHalfEdgeData HasHalfEdgeData; + typedef typename Base::HasEdgeData HasEdgeData; + typedef typename Base::HasFaceData HasFaceData; + + typedef typename Base::VertexDataCloud VertexDataCloud; + typedef typename Base::HalfEdgeDataCloud HalfEdgeDataCloud; + typedef typename Base::EdgeDataCloud EdgeDataCloud; + typedef typename Base::FaceDataCloud FaceDataCloud; + + // Indices + typedef typename Base::VertexIndex VertexIndex; + typedef typename Base::HalfEdgeIndex HalfEdgeIndex; + typedef typename Base::EdgeIndex EdgeIndex; + typedef typename Base::FaceIndex FaceIndex; + + typedef typename Base::VertexIndices VertexIndices; + typedef typename Base::HalfEdgeIndices HalfEdgeIndices; + typedef typename Base::EdgeIndices EdgeIndices; + typedef typename Base::FaceIndices FaceIndices; + + // Circulators + typedef typename Base::VertexAroundVertexCirculator VertexAroundVertexCirculator; + typedef typename Base::OutgoingHalfEdgeAroundVertexCirculator OutgoingHalfEdgeAroundVertexCirculator; + typedef typename Base::IncomingHalfEdgeAroundVertexCirculator IncomingHalfEdgeAroundVertexCirculator; + typedef typename Base::FaceAroundVertexCirculator FaceAroundVertexCirculator; + typedef typename Base::VertexAroundFaceCirculator VertexAroundFaceCirculator; + typedef typename Base::InnerHalfEdgeAroundFaceCirculator InnerHalfEdgeAroundFaceCirculator; + typedef typename Base::OuterHalfEdgeAroundFaceCirculator OuterHalfEdgeAroundFaceCirculator; + typedef typename Base::FaceAroundFaceCirculator FaceAroundFaceCirculator; + + /** \brief Constructor. */ + PolygonMesh () + : Base (), + add_triangle_ (3), + add_quad_ (4) + { + } + + /** \brief The base method of addFace is hidden because of the overloads in this class. */ + using Base::addFace; + + /** \brief Add a triangle to the mesh. Data is only added if it is associated with the elements. The last vertex is connected with the first one. + * \param[in] idx_v_0 Index to the first vertex. + * \param[in] idx_v_1 Index to the second vertex. + * \param[in] idx_v_2 Index to the third vertex. + * \param[in] face_data Data that is set for the face. + * \param[in] half_edge_data Data that is set for all added half-edges. + * \param[in] edge_data Data that is set for all added edges. + * \return Index to the new face. Failure is signaled by returning an invalid face index. + * \warning The vertices must be valid and unique (each vertex may be contained only once). Not complying with this requirement results in undefined behavior! + */ + inline FaceIndex + addFace (const VertexIndex& idx_v_0, + const VertexIndex& idx_v_1, + const VertexIndex& idx_v_2, + const FaceData& face_data = FaceData (), + const EdgeData& edge_data = EdgeData (), + const HalfEdgeData& half_edge_data = HalfEdgeData ()) + { + add_triangle_ [0] = idx_v_0; + add_triangle_ [1] = idx_v_1; + add_triangle_ [2] = idx_v_2; + + return (this->addFaceImplBase (add_triangle_, face_data, edge_data, half_edge_data)); + } + + /** \brief Add a quad to the mesh. Data is only added if it is associated with the elements. The last vertex is connected with the first one. + * \param[in] idx_v_0 Index to the first vertex. + * \param[in] idx_v_1 Index to the second vertex. + * \param[in] idx_v_2 Index to the third vertex. + * \param[in] idx_v_3 Index to the fourth vertex. + * \param[in] face_data Data that is set for the face. + * \param[in] half_edge_data Data that is set for all added half-edges. + * \param[in] edge_data Data that is set for all added edges. + * \return Index to the new face. Failure is signaled by returning an invalid face index. + * \warning The vertices must be valid and unique (each vertex may be contained only once). Not complying with this requirement results in undefined behavior! + */ + inline FaceIndex + addFace (const VertexIndex& idx_v_0, + const VertexIndex& idx_v_1, + const VertexIndex& idx_v_2, + const VertexIndex& idx_v_3, + const FaceData& face_data = FaceData (), + const EdgeData& edge_data = EdgeData (), + const HalfEdgeData& half_edge_data = HalfEdgeData ()) + { + add_quad_ [0] = idx_v_0; + add_quad_ [1] = idx_v_1; + add_quad_ [2] = idx_v_2; + add_quad_ [3] = idx_v_3; + + return (this->addFaceImplBase (add_quad_, face_data, edge_data, half_edge_data)); + } + + private: + + // NOTE: Can't use the typedef of Base as a friend. + friend class pcl::geometry::MeshBase , MeshTraitsT, pcl::geometry::PolygonMeshTag>; + + /** \brief addFace for the polygon mesh. */ + inline FaceIndex + addFaceImpl (const VertexIndices& vertices, + const FaceData& face_data, + const EdgeData& edge_data, + const HalfEdgeData& half_edge_data) + { + return (this->addFaceImplBase (vertices, face_data, edge_data, half_edge_data)); + } + + //////////////////////////////////////////////////////////////////////// + // Members + //////////////////////////////////////////////////////////////////////// + + /** \brief Storage for adding a triangle. */ + VertexIndices add_triangle_; + + /** \brief Storage for adding a quad. */ + VertexIndices add_quad_; + + public: + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } // End namespace geom +} // End namespace pcl + +#endif // PCL_GEOMETRY_POLYGON_MESH_H diff --git a/pcl-1.7/pcl/geometry/polygon_operations.h b/pcl-1.7/pcl/geometry/polygon_operations.h new file mode 100644 index 0000000..ec6c1a7 --- /dev/null +++ b/pcl-1.7/pcl/geometry/polygon_operations.h @@ -0,0 +1,72 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: point_operators.h 4389 2012-02-10 10:10:26Z nizar $ + * + */ + +#ifndef PCL_GEOMETRY_POLYGON_OPERATORS_H +#define PCL_GEOMETRY_POLYGON_OPERATORS_H + +#include "planar_polygon.h" +#include + +namespace pcl +{ + /** \brief see approximatePolygon2D + * \author Suat Gedikli + */ + template + void approximatePolygon (const PlanarPolygon& polygon, PlanarPolygon& approx_polygon, float threshold, bool refine = false, bool closed = true); + + /** \brief returns an approximate polygon to given 2D contour. Uses just X and Y values. + * \note if refinement is not turned on, the resulting polygon will contain points from the original contour with their original z values (if any) + * \note if refinement is turned on, the z values of the refined polygon are not valid and should be set to 0 if point contains z attribute. + * \param [in] polygon input polygon + * \param [out] approx_polygon approximate polygon + * \param [in] threshold maximum allowed distance of an input vertex to an output edge + * \param refine + * \param [in] closed whether it is a closed polygon or a polyline + * \author Suat Gedikli + */ + template + void approximatePolygon2D (const typename PointCloud::VectorType &polygon, + typename PointCloud::VectorType &approx_polygon, + float threshold, bool refine = false, bool closed = true); + +} // namespace pcl + +#include "impl/polygon_operations.hpp" +#endif // PCL_GEOMETRY_POLYGON_OPERATORS_H======= diff --git a/pcl-1.7/pcl/geometry/quad_mesh.h b/pcl-1.7/pcl/geometry/quad_mesh.h new file mode 100644 index 0000000..9f5ae75 --- /dev/null +++ b/pcl-1.7/pcl/geometry/quad_mesh.h @@ -0,0 +1,177 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_GEOMETRY_QUAD_MESH_H +#define PCL_GEOMETRY_QUAD_MESH_H + +#include + +namespace pcl +{ + namespace geometry + { + /** \brief Tag describing the type of the mesh. */ + struct QuadMeshTag {}; + + /** \brief Half-edge mesh that can only store quads. + * \tparam MeshTraitsT Please have a look at pcl::geometry::DefaultMeshTraits. + * \author Martin Saelzle + * \ingroup geometry + */ + template + class QuadMesh : public pcl::geometry::MeshBase , MeshTraitsT, QuadMeshTag> + { + public: + + typedef pcl::geometry::MeshBase , MeshTraitsT, QuadMeshTag> Base; + + typedef QuadMesh Self; + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef typename Base::VertexData VertexData; + typedef typename Base::HalfEdgeData HalfEdgeData; + typedef typename Base::EdgeData EdgeData; + typedef typename Base::FaceData FaceData; + typedef typename Base::IsManifold IsManifold; + typedef typename Base::MeshTag MeshTag; + + typedef typename Base::HasVertexData HasVertexData; + typedef typename Base::HasHalfEdgeData HasHalfEdgeData; + typedef typename Base::HasEdgeData HasEdgeData; + typedef typename Base::HasFaceData HasFaceData; + + typedef typename Base::VertexDataCloud VertexDataCloud; + typedef typename Base::HalfEdgeDataCloud HalfEdgeDataCloud; + typedef typename Base::EdgeDataCloud EdgeDataCloud; + typedef typename Base::FaceDataCloud FaceDataCloud; + + // Indices + typedef typename Base::VertexIndex VertexIndex; + typedef typename Base::HalfEdgeIndex HalfEdgeIndex; + typedef typename Base::EdgeIndex EdgeIndex; + typedef typename Base::FaceIndex FaceIndex; + + typedef typename Base::VertexIndices VertexIndices; + typedef typename Base::HalfEdgeIndices HalfEdgeIndices; + typedef typename Base::EdgeIndices EdgeIndices; + typedef typename Base::FaceIndices FaceIndices; + + // Circulators + typedef typename Base::VertexAroundVertexCirculator VertexAroundVertexCirculator; + typedef typename Base::OutgoingHalfEdgeAroundVertexCirculator OutgoingHalfEdgeAroundVertexCirculator; + typedef typename Base::IncomingHalfEdgeAroundVertexCirculator IncomingHalfEdgeAroundVertexCirculator; + typedef typename Base::FaceAroundVertexCirculator FaceAroundVertexCirculator; + typedef typename Base::VertexAroundFaceCirculator VertexAroundFaceCirculator; + typedef typename Base::InnerHalfEdgeAroundFaceCirculator InnerHalfEdgeAroundFaceCirculator; + typedef typename Base::OuterHalfEdgeAroundFaceCirculator OuterHalfEdgeAroundFaceCirculator; + typedef typename Base::FaceAroundFaceCirculator FaceAroundFaceCirculator; + + /** \brief Constructor. */ + QuadMesh () + : Base (), + add_quad_ (4) + { + } + + /** \brief The base method of addFace is hidden because of the overloads in this class. */ + using Base::addFace; + + /** \brief Add a quad to the mesh. Data is only added if it is associated with the elements. The last vertex is connected with the first one. + * \param[in] idx_v_0 Index to the first vertex. + * \param[in] idx_v_1 Index to the second vertex. + * \param[in] idx_v_2 Index to the third vertex. + * \param[in] idx_v_3 Index to the fourth vertex. + * \param[in] face_data Data that is set for the face. + * \param[in] half_edge_data Data that is set for all added half-edges. + * \param[in] edge_data Data that is set for all added edges. + * \return Index to the new face. Failure is signaled by returning an invalid face index. + * \warning The vertices must be valid and unique (each vertex may be contained only once). Not complying with this requirement results in undefined behavior! + */ + inline FaceIndex + addFace (const VertexIndex& idx_v_0, + const VertexIndex& idx_v_1, + const VertexIndex& idx_v_2, + const VertexIndex& idx_v_3, + const FaceData& face_data = FaceData (), + const EdgeData& edge_data = EdgeData (), + const HalfEdgeData& half_edge_data = HalfEdgeData ()) + { + add_quad_ [0] = idx_v_0; + add_quad_ [1] = idx_v_1; + add_quad_ [2] = idx_v_2; + add_quad_ [3] = idx_v_3; + + return (this->addFaceImplBase (add_quad_, face_data, edge_data, half_edge_data)); + } + + private: + + // NOTE: Can't use the typedef of Base as a friend. + friend class pcl::geometry::MeshBase , MeshTraitsT, pcl::geometry::QuadMeshTag>; + + /** \brief addFace for the quad mesh. */ + inline FaceIndex + addFaceImpl (const VertexIndices& vertices, + const FaceData& face_data, + const EdgeData& edge_data, + const HalfEdgeData& half_edge_data) + { + if (vertices.size () == 4) + return (this->addFaceImplBase (vertices, face_data, edge_data, half_edge_data)); + else + return (FaceIndex ()); + } + + //////////////////////////////////////////////////////////////////////// + // Members + //////////////////////////////////////////////////////////////////////// + + /** \brief Storage for adding a quad. */ + VertexIndices add_quad_; + + public: + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } // End namespace geom +} // End namespace pcl + +#endif // PCL_GEOMETRY_QUAD_MESH_H diff --git a/pcl-1.7/pcl/geometry/triangle_mesh.h b/pcl-1.7/pcl/geometry/triangle_mesh.h new file mode 100644 index 0000000..ae331e7 --- /dev/null +++ b/pcl-1.7/pcl/geometry/triangle_mesh.h @@ -0,0 +1,361 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_GEOMETRY_TRIANGLE_MESH_H +#define PCL_GEOMETRY_TRIANGLE_MESH_H + +#include + +#include + +namespace pcl +{ + namespace geometry + { + /** \brief Tag describing the type of the mesh. */ + struct TriangleMeshTag {}; + + /** \brief Half-edge mesh that can only store triangles. + * \tparam MeshTraitsT Please have a look at pcl::geometry::DefaultMeshTraits. + * \author Martin Saelzle + * \ingroup geometry + */ + template + class TriangleMesh : public pcl::geometry::MeshBase , MeshTraitsT, TriangleMeshTag> + { + public: + + typedef pcl::geometry::MeshBase , MeshTraitsT, TriangleMeshTag> Base; + + typedef TriangleMesh Self; + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef typename Base::VertexData VertexData; + typedef typename Base::HalfEdgeData HalfEdgeData; + typedef typename Base::EdgeData EdgeData; + typedef typename Base::FaceData FaceData; + typedef typename Base::IsManifold IsManifold; + typedef typename Base::MeshTag MeshTag; + + typedef typename Base::HasVertexData HasVertexData; + typedef typename Base::HasHalfEdgeData HasHalfEdgeData; + typedef typename Base::HasEdgeData HasEdgeData; + typedef typename Base::HasFaceData HasFaceData; + + typedef typename Base::VertexDataCloud VertexDataCloud; + typedef typename Base::HalfEdgeDataCloud HalfEdgeDataCloud; + typedef typename Base::EdgeDataCloud EdgeDataCloud; + typedef typename Base::FaceDataCloud FaceDataCloud; + + // Indices + typedef typename Base::VertexIndex VertexIndex; + typedef typename Base::HalfEdgeIndex HalfEdgeIndex; + typedef typename Base::EdgeIndex EdgeIndex; + typedef typename Base::FaceIndex FaceIndex; + typedef std::pair FaceIndexPair; + + typedef typename Base::VertexIndices VertexIndices; + typedef typename Base::HalfEdgeIndices HalfEdgeIndices; + typedef typename Base::EdgeIndices EdgeIndices; + typedef typename Base::FaceIndices FaceIndices; + + // Circulators + typedef typename Base::VertexAroundVertexCirculator VertexAroundVertexCirculator; + typedef typename Base::OutgoingHalfEdgeAroundVertexCirculator OutgoingHalfEdgeAroundVertexCirculator; + typedef typename Base::IncomingHalfEdgeAroundVertexCirculator IncomingHalfEdgeAroundVertexCirculator; + typedef typename Base::FaceAroundVertexCirculator FaceAroundVertexCirculator; + typedef typename Base::VertexAroundFaceCirculator VertexAroundFaceCirculator; + typedef typename Base::InnerHalfEdgeAroundFaceCirculator InnerHalfEdgeAroundFaceCirculator; + typedef typename Base::OuterHalfEdgeAroundFaceCirculator OuterHalfEdgeAroundFaceCirculator; + typedef typename Base::FaceAroundFaceCirculator FaceAroundFaceCirculator; + + /** \brief Constructor. */ + TriangleMesh () + : Base (), + add_triangle_ (3), + inner_he_atp_ (4), + is_new_atp_ (4) + { + } + + /** \brief The base method of addFace is hidden because of the overloads in this class. */ + using Base::addFace; + + /** \brief Add a triangle to the mesh. Data is only added if it is associated with the elements. The last vertex is connected with the first one. + * \param[in] idx_v_0 Index to the first vertex. + * \param[in] idx_v_1 Index to the second vertex. + * \param[in] idx_v_2 Index to the third vertex. + * \param[in] face_data Data that is set for the face. + * \param[in] half_edge_data Data that is set for all added half-edges. + * \param[in] edge_data Data that is set for all added edges. + * \return Index to the new face. Failure is signaled by returning an invalid face index. + * \warning The vertices must be valid and unique (each vertex may be contained only once). Not complying with this requirement results in undefined behavior! + */ + inline FaceIndex + addFace (const VertexIndex& idx_v_0, + const VertexIndex& idx_v_1, + const VertexIndex& idx_v_2, + const FaceData& face_data = FaceData (), + const EdgeData& edge_data = EdgeData (), + const HalfEdgeData& half_edge_data = HalfEdgeData ()) + { + add_triangle_ [0] = idx_v_0; + add_triangle_ [1] = idx_v_1; + add_triangle_ [2] = idx_v_2; + + return (this->addFaceImplBase (add_triangle_, face_data, edge_data, half_edge_data)); + } + + /** \brief Add two triangles for the four given input vertices. When using a manifold triangle mesh it is not possible to connect two bounded regions without going through a non-manifold intermediate step. This method first tries to add the triangles individually and if this fails connects the whole configuration at once (if possible). + * \param[in] vertices Indices to the vertices of the new face. (The size must be equal to four). + * \param[in] face_data Data that is set for the face. + * \param[in] half_edge_data Data that is set for all added half-edges. + * \param[in] edge_data Data that is set for all added edges. + * \return Pair of face indices. The first index is valid if one triangle was added. Both indices are valid if two triangles were added. + * \warning The vertices must be valid and unique (each vertex may be contained only once). Not complying with this requirement results in undefined behavior! + */ + FaceIndexPair + addTrianglePair (const VertexIndices& vertices, + const FaceData& face_data = FaceData (), + const EdgeData& edge_data = EdgeData (), + const HalfEdgeData& half_edge_data = HalfEdgeData ()) + { + if (vertices.size () != 4) + { + return (std::make_pair (FaceIndex (), FaceIndex ())); + } + else + { + return (this->addTrianglePair (vertices [0], vertices [1], vertices [2], vertices [3], face_data, edge_data, half_edge_data)); + } + } + + /** \brief Add two triangles for the four given input vertices. When using a manifold triangle mesh it is not possible to connect two bounded regions without going through a non-manifold intermediate step. This method first tries to add the triangles individually and if this fails connects the whole configuration at once (if possible). + * \param[in] idx_v_0 Index to the first vertex. + * \param[in] idx_v_1 Index to the second vertex. + * \param[in] idx_v_2 Index to the third vertex. + * \param[in] idx_v_3 Index to the fourth vertex. + * \param[in] face_data Data that is set for the face. + * \param[in] half_edge_data Data that is set for all added half-edges. + * \param[in] edge_data Data that is set for all added edges. + * \return Pair of face indices. The first index is valid if one triangle was added. Both indices are valid if two triangles were added. + * \warning The vertices must be valid and unique (each vertex may be contained only once). Not complying with this requirement results in undefined behavior! + */ + inline FaceIndexPair + addTrianglePair (const VertexIndex& idx_v_0, + const VertexIndex& idx_v_1, + const VertexIndex& idx_v_2, + const VertexIndex& idx_v_3, + const FaceData& face_data = FaceData (), + const EdgeData& edge_data = EdgeData (), + const HalfEdgeData& half_edge_data = HalfEdgeData ()) + { + // Try to add two faces + // 3 - 2 + // | / | + // 0 - 1 + FaceIndex idx_face_0 = this->addFace (idx_v_0, idx_v_1, idx_v_2, face_data); + FaceIndex idx_face_1 = this->addFace (idx_v_0, idx_v_2, idx_v_3, face_data); + + if (idx_face_0.isValid ()) + { + return (std::make_pair (idx_face_0, idx_face_1)); + } + else if (idx_face_1.isValid ()) + { + idx_face_0 = this->addFace (idx_v_0, idx_v_1, idx_v_2, face_data); // might be possible to add now + return (std::make_pair (idx_face_1, idx_face_0)); + } + + // Try to add two faces + // 3 - 2 + // | \ | + // 0 - 1 + idx_face_0 = this->addFace (idx_v_1, idx_v_2, idx_v_3, face_data); + idx_face_1 = this->addFace (idx_v_0, idx_v_1, idx_v_3, face_data); + + if (idx_face_0.isValid ()) + { + return (std::make_pair (idx_face_0, idx_face_1)); + } + else if (idx_face_1.isValid ()) + { + idx_face_0 = this->addFace (idx_v_1, idx_v_2, idx_v_3, face_data); // might be possible to add now + return (std::make_pair (idx_face_1, idx_face_0)); + } + + if (!IsManifold::value) + { + return (std::make_pair (FaceIndex (), FaceIndex ())); + } + + // Check manifoldness + if (!Base::checkTopology1 (idx_v_0,idx_v_1, inner_he_atp_ [0], is_new_atp_ [0], IsManifold ()) || + !Base::checkTopology1 (idx_v_1,idx_v_2, inner_he_atp_ [1], is_new_atp_ [1], IsManifold ()) || + !Base::checkTopology1 (idx_v_2,idx_v_3, inner_he_atp_ [2], is_new_atp_ [2], IsManifold ()) || + !Base::checkTopology1 (idx_v_3,idx_v_0, inner_he_atp_ [3], is_new_atp_ [3], IsManifold ())) + { + return (std::make_pair (FaceIndex (), FaceIndex ())); + } + + // Connect the triangle pair + if (!is_new_atp_ [0] && is_new_atp_ [1] && !is_new_atp_ [2] && is_new_atp_ [3]) + { + return (this->connectTrianglePair (inner_he_atp_ [0], inner_he_atp_ [2], idx_v_0, idx_v_1, idx_v_2, idx_v_3, face_data, edge_data, half_edge_data)); + } + else if (is_new_atp_ [0] && !is_new_atp_ [1] && is_new_atp_ [2] && !is_new_atp_ [3]) + { + return (this->connectTrianglePair (inner_he_atp_ [1], inner_he_atp_ [3], idx_v_1, idx_v_2, idx_v_3, idx_v_0, face_data, edge_data, half_edge_data)); + } + else + { + return (std::make_pair (FaceIndex (), FaceIndex ())); + } + } + + private: + + // NOTE: Can't use the typedef of Base as a friend. + friend class pcl::geometry::MeshBase , MeshTraitsT, pcl::geometry::TriangleMeshTag>; + + /** \brief addFace for the triangular mesh. */ + inline FaceIndex + addFaceImpl (const VertexIndices& vertices, + const FaceData& face_data, + const EdgeData& edge_data, + const HalfEdgeData& half_edge_data) + { + if (vertices.size () == 3) + return (this->addFaceImplBase (vertices, face_data, edge_data, half_edge_data)); + else + return (FaceIndex ()); + } + + /** \brief Connect the triangles a-b-c and a-c-d. The edges a-b and c-d must be old and the edges b-c and d-a must be new. */ + // d - c + // | / | + // a - b + FaceIndexPair + connectTrianglePair (const HalfEdgeIndex& idx_he_ab, + const HalfEdgeIndex& idx_he_cd, + const VertexIndex& idx_v_a, + const VertexIndex& idx_v_b, + const VertexIndex& idx_v_c, + const VertexIndex& idx_v_d, + const FaceData& face_data, + const EdgeData& edge_data, + const HalfEdgeData& he_data) + { + // Add new half-edges + const HalfEdgeIndex idx_he_bc = Base::addEdge (idx_v_b, idx_v_c, he_data, edge_data); + const HalfEdgeIndex idx_he_da = Base::addEdge (idx_v_d, idx_v_a, he_data, edge_data); + const HalfEdgeIndex idx_he_ca = Base::addEdge (idx_v_c, idx_v_a, he_data, edge_data); + + const HalfEdgeIndex idx_he_cb = Base::getOppositeHalfEdgeIndex (idx_he_bc); + const HalfEdgeIndex idx_he_ad = Base::getOppositeHalfEdgeIndex (idx_he_da); + const HalfEdgeIndex idx_he_ac = Base::getOppositeHalfEdgeIndex (idx_he_ca); + + // Get the existing half-edges + const HalfEdgeIndex idx_he_ab_prev = Base::getPrevHalfEdgeIndex (idx_he_ab); // No reference! + const HalfEdgeIndex idx_he_ab_next = Base::getNextHalfEdgeIndex (idx_he_ab); // No reference! + + const HalfEdgeIndex idx_he_cd_prev = Base::getPrevHalfEdgeIndex (idx_he_cd); // No reference! + const HalfEdgeIndex idx_he_cd_next = Base::getNextHalfEdgeIndex (idx_he_cd); // No reference! + + // Connect the outer half-edges + Base::connectPrevNext (idx_he_ab_prev, idx_he_ad ); + Base::connectPrevNext (idx_he_ad , idx_he_cd_next); + Base::connectPrevNext (idx_he_cd_prev, idx_he_cb ); + Base::connectPrevNext (idx_he_cb , idx_he_ab_next); + + // Connect the inner half-edges + Base::connectPrevNext (idx_he_ab, idx_he_bc); + Base::connectPrevNext (idx_he_bc, idx_he_ca); + Base::connectPrevNext (idx_he_ca, idx_he_ab); + + Base::connectPrevNext (idx_he_ac, idx_he_cd); + Base::connectPrevNext (idx_he_cd, idx_he_da); + Base::connectPrevNext (idx_he_da, idx_he_ac); + + // Connect the vertices to the boundary half-edges + Base::setOutgoingHalfEdgeIndex (idx_v_a, idx_he_ad ); + Base::setOutgoingHalfEdgeIndex (idx_v_b, idx_he_ab_next); + Base::setOutgoingHalfEdgeIndex (idx_v_c, idx_he_cb ); + Base::setOutgoingHalfEdgeIndex (idx_v_d, idx_he_cd_next); + + // Add and connect the faces + HalfEdgeIndices inner_he_abc; inner_he_abc.reserve (3); + inner_he_abc.push_back (idx_he_ab); + inner_he_abc.push_back (idx_he_bc); + inner_he_abc.push_back (idx_he_ca); + + HalfEdgeIndices inner_he_acd; inner_he_acd.reserve (3); + inner_he_acd.push_back (idx_he_ac); + inner_he_acd.push_back (idx_he_cd); + inner_he_acd.push_back (idx_he_da); + + const FaceIndex idx_f_abc = Base::connectFace (inner_he_abc, face_data); + const FaceIndex idx_f_acd = Base::connectFace (inner_he_acd, face_data); + + return (std::make_pair (idx_f_abc, idx_f_acd)); + } + + //////////////////////////////////////////////////////////////////////// + // Members + //////////////////////////////////////////////////////////////////////// + + /** \brief Storage for adding a triangle. */ + VertexIndices add_triangle_; + + /** \brief Storage for addTrianglePair. */ + HalfEdgeIndices inner_he_atp_; + + /** \brief Storage for addTrianglePair. */ + std::vector is_new_atp_; + + public: + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } // End namespace geom +} // End namespace pcl + +#endif // PCL_GEOMETRY_TRIANGLE_MESH_H diff --git a/pcl-1.7/pcl/horizon_kdtree.h b/pcl-1.7/pcl/horizon_kdtree.h new file mode 100644 index 0000000..0bc1459 --- /dev/null +++ b/pcl-1.7/pcl/horizon_kdtree.h @@ -0,0 +1,841 @@ +// #define RECORDING + +/****** + Data structures +******/ +struct Interval { + float low, high; +}; + +/****** + Point structure, to represent individual points + in the Point Cloud. + ******/ +struct Point { +public: + float x; + float y; + float z; + + int dim; // dimension + + // to-do: add normal information + Point () : \ + x(.0), y(.0), z(.0), dim(3) {} +public: + float operator[] (int i) { + if (i == 0) return x; + if (i == 1) return y; + if (i == 2) return z; + + // Default: return z value + return z; + } +}; + +/****** + ******/ +struct Leader +{ + Point p; + std::vector neighbors; + + Leader () + { + neighbors.resize(0); + } +}; + +/****** + ******/ +struct Node +{ + int s_dim; // split dim + float s_val; // split value + + int leaf_idx; + + Node * left_child; + Node * right_child; + + /********************** + Bounding box: + includes xmin, xmax, ymin, ymax, zmin, zmax + flann impl: + https://github.com/mariusmuja/flann/blob/master/src/cpp/flann/algorithms/kdtree_single_index.h + ***********************/ + std::vector bbox; + std::vector index_list; + + std::vector leaders; + + Node () : \ + s_dim(-1), s_val(0.0), leaf_idx(-1), \ + left_child(NULL), right_child(NULL) + { + bbox.resize(0); + index_list.resize(0); + + leaders.resize(0); + } + + ~Node() + { + bbox.clear(); + leaders.clear(); + } +}; + +/***************** + customized KD-Tree data structure + ****************/ +class KdTreeH +{ +public: + typedef std::vector Points; + typedef std::vector * PointsPtr; + + typedef std::vector * IndexPtr; + typedef Node * NodePtr; + + int approx_nn_ops_num_; + int approx_radius_ops_num_; + int approx_leaders_num_; + int approx_followers_num_; + + KdTreeH(std::vector * points_ptr, \ + std::vector * index_ptr, \ + int max_leaf_size, float para_Radius, float para_NN): \ + dim_(3), leaf_node_num_(0) + { + // Initialization + index_ = index_ptr; // POINTER to indices + points_ = points_ptr; // POINTER to points + + max_leaf_size_ = max_leaf_size; + dim_ = (*points_ptr)[0].dim; // dimension + + para_Radius_ = para_Radius; + para_NN_ = para_NN; + + approx_nn_ops_num_ = 0; + approx_radius_ops_num_ = 0; + approx_leaders_num_ = 0; + approx_followers_num_ = 0; + } + + ~KdTreeH() { deleteNode(root_node_); } + + /******* + *******/ + void deleteNode(Node * node_p) + { + if (node_p->left_child) deleteNode(node_p->left_child); + if (node_p->right_child) deleteNode(node_p->right_child); + delete node_p; + } + + /******* + *******/ + void buildKDTree() + { + // compute bounding box of the root node + std::vector bbox; + std::vector *bbox_ptr = NULL; + + int left = 0; + int right = (index_->size()) - 1; + + computeBoundingBox(left, right, bbox); + bbox_ptr = &bbox; + root_node_ = divideTree(left, right, bbox_ptr); + } + + NodePtr get_root() { return root_node_; } + int get_leaf_number() { return leaf_node_num_;} + + /****** + Traverse top down to find the leaf node. + ******/ + NodePtr traverse_tree(NodePtr cur_node, Point query, \ + std::vector & backtrack_stack) + { + /* Traverse the tree top-down to find the leaf node. */ + while(cur_node->s_dim != -1) // non-leaf node + { + int s_dim = cur_node->s_dim; + float s_val = cur_node->s_val; + + if (query[s_dim] > s_val) + { + backtrack_stack.push_back(cur_node->left_child); + cur_node = cur_node->right_child; + } + else + { + backtrack_stack.push_back(cur_node->right_child); + cur_node = cur_node->left_child; + } + } + return cur_node; + } + + /******* + reference for impl: + https://stackoverflow.com/questions/4578967/cube-sphere-intersection-test + *******/ + bool check_intersection(Point query, float radius, NodePtr cur_node) + { + float dist_squared = radius * radius; + + float x_min = (cur_node->bbox)[0].low; + float x_max = (cur_node->bbox)[0].high; + + float y_min = (cur_node->bbox)[1].low; + float y_max = (cur_node->bbox)[1].high; + + float z_min = (cur_node->bbox)[2].low; + float z_max = (cur_node->bbox)[2].high; + + if (query.x < x_min) + dist_squared -= (query.x - x_min) * (query.x - x_min); + else if (query.x > x_max) + dist_squared -= (query.x - x_max) * (query.x - x_max); + + if (query.y < y_min) + dist_squared -= (query.y - y_min) * (query.y - y_min); + else if (query.y > y_max) + dist_squared -= (query.y - y_max) * (query.y - y_max); + + if (query.z < z_min) + dist_squared -= (query.z - z_min) * (query.z - z_min); + else if (query.z > z_max) + dist_squared -= (query.z - z_max) * (query.z - z_max); + + return dist_squared > 0; + } + + /****** + Search (radius) inside a node (not necessarily a leaf node). + ******/ + void radiusSearch_unit(std::vector ind, \ + Point query, float radius, \ + std::vector &k_indices, \ + std::vector &k_dists) + { + float dist_ = 0.0; + for (int i = 0; i < ind.size(); i++) + { + dist_ = dist(query, (*points_)[ ind[i] ]); +#ifdef RECORDING + approx_radius_ops_num_ += 1; +#endif + if (dist_ < radius) + { + k_indices.push_back(ind[i]); + k_dists.push_back(dist_); + } + } + } + + /****** + Radius Search + ******/ + int radiusSearch(Point query, float radius, \ + std::vector &k_indices, \ + std::vector &k_dists) + { + int back_track = 0; + std::vector backtrack_stack; + + NodePtr cur_node = root_node_; + cur_node = traverse_tree(cur_node, query, backtrack_stack); + + /* Search in the leaf node. */ + radiusSearch_unit(cur_node->index_list, query, radius, \ + k_indices, k_dists); + + /* Backtrack && prune */ + for(;backtrack_stack.size();) + { + cur_node = backtrack_stack.back(); + backtrack_stack.pop_back(); + + float dist_min_ = radius; + + // Prune + bool visit_ = check_intersection(query, dist_min_, cur_node); + if (visit_) + { + back_track += 1; + if (cur_node->s_dim != -1) + cur_node = traverse_tree(cur_node, \ + query, backtrack_stack); + radiusSearch_unit(cur_node->index_list, query, \ + radius, k_indices, k_dists); + } + } + + return back_track; + } + + /****** + Searching Unit. + + Search inside a node in Brute Force manner. + (The node is not necessarily a leaf node, since + in our implementation each node maintains a list + of indices.) + *******/ + void bruteForceSearch(std::vector ind, Point query, \ + std::vector &k_indices, \ + std::vector &k_dists) + { + float dist_ = 0.0; + + for (int i = 0; i < ind.size(); i++) + { + dist_ = dist(query, (*points_)[ ind[i] ]); + +#ifdef RECORDING + approx_nn_ops_num_ += 1; +#endif + + // caution: + // make sure to k_dists.resize(0) and k_indices.resize(0) + // initially, otherwise the code below doesn't work + if (k_dists.size()) + { + if (dist_ < k_dists[0]) + { + k_indices.pop_back(); + k_dists.pop_back(); + + k_indices.push_back(ind[i]); + k_dists.push_back(dist_); + } + } + else + { + k_indices.push_back(ind[i]); + k_dists.push_back(dist_); + } + } + } + + /****** + Nearest Neighbor Search + ******/ + int nearestKSearch(Point query, int knn, \ + std::vector &k_indices, \ + std::vector &k_dists) + { + int back_track = 0; + std::vector backtrack_stack; + + NodePtr cur_node = root_node_; + cur_node = traverse_tree(cur_node, query, backtrack_stack); + + /* Search the leaf node. */ + bruteForceSearch(cur_node->index_list, query, k_indices, k_dists); + + /* Backtrack && prune */ + for(;backtrack_stack.size();) + { + cur_node = backtrack_stack.back(); + backtrack_stack.pop_back(); + + float dist_min_ = k_dists[0]; // radius + + // Prune + bool visit_ = check_intersection(query, dist_min_, cur_node); + if (visit_) + { + back_track += 1; + if (cur_node->s_dim != -1) + cur_node = traverse_tree(cur_node, query, backtrack_stack); + bruteForceSearch(cur_node->index_list, query, k_indices, k_dists); + } + } + return back_track; + } + + /****** + ******/ + bool bruteForceSearchUnitApprox(NodePtr cur_leaf, Point query_point, std::vector &k_indices, std::vector &k_dists) + { + bool findleader = false; + + if ((cur_leaf->leaders).size()) + { + std::vector dis_list; + for (int i = 0; i < (cur_leaf->leaders).size(); i++) + { + float dis = getDistance(query_point, (cur_leaf->leaders)[i].p); + dis_list.push_back(dis); + } + + int index = min_element(dis_list.begin(), dis_list.end()) - dis_list.begin(); + float dis_min = sqrt(dis_list[index]); + + if (dis_min < para_NN_) + { + bruteForceSearch(((cur_leaf->leaders)[index].neighbors), query_point, k_indices, k_dists); + findleader = true; +#ifdef RECORDING + approx_followers_num_ += 1; +#endif + } + else + { + bruteForceSearch(cur_leaf->index_list, query_point, k_indices, k_dists); +#ifdef RECORDING + approx_leaders_num_ += 1; +#endif + } + } + else + { + bruteForceSearch(cur_leaf->index_list, query_point, k_indices, k_dists); +#ifdef RECORDING + approx_leaders_num_ += 1; +#endif + } + return findleader; + } + + /****** + ******/ + int nearestKSearchApprox(Point query, int knn, \ + std::vector &k_indices, \ + std::vector &k_dists) + { + int back_track = 0; + std::vector backtrack_stack; + + NodePtr cur_node = root_node_; + cur_node = traverse_tree(cur_node, query, backtrack_stack); + + /* Search the leaf node. */ + bool findleader = bruteForceSearchUnitApprox(cur_node, query, k_indices, k_dists); + + // Backtrack && prune + if (!findleader) + { + for(;backtrack_stack.size();) + { + NodePtr backtrack_node = backtrack_stack.back(); + backtrack_stack.pop_back(); + + float dist_min_ = k_dists[0]; // radius + + // Prune + bool visit_ = check_intersection(query, dist_min_, backtrack_node); + if (visit_) + { + back_track += 1; + if (backtrack_node->s_dim != -1) + backtrack_node = traverse_tree(backtrack_node, query, backtrack_stack); + + bruteForceSearch(backtrack_node->index_list, query, k_indices, k_dists); + } + } + Leader leader_point; + leader_point.p = query; + (leader_point.neighbors).push_back((k_indices[0])); + (cur_node->leaders).push_back(leader_point); + } + return back_track; + } + + /****** + ******/ + bool radiusSearchUnitApprox(NodePtr cur_leaf, Point query_point, float radius, std::vector &k_indices, std::vector &k_dists) + { + bool findleader = false; + + // if leader already exist on leaf node + if ((cur_leaf->leaders).size()) + { + std::vector dis_list; + for (int i = 0; i < (cur_leaf->leaders).size(); i++) + { + float dis = getDistance(query_point, (cur_leaf->leaders)[i].p); + dis_list.push_back(dis); + } + + int index = min_element(dis_list.begin(), dis_list.end()) - dis_list.begin(); + float dis_min = sqrt(dis_list[index]); + + if (dis_min < para_Radius_ * radius) + { + radiusSearch_unit(((cur_leaf->leaders)[index].neighbors), query_point, radius, k_indices, k_dists); + findleader = true; +#ifdef RECORDING + approx_followers_num_ += 1; +#endif + } + else + { + radiusSearch_unit(cur_leaf->index_list, query_point, radius, k_indices, k_dists); +#ifdef RECORDING + approx_leaders_num_ += 1; +#endif + } + } + // create new leader + else + { + radiusSearch_unit(cur_leaf->index_list, query_point, radius, k_indices, k_dists); +#ifdef RECORDING + approx_leaders_num_ += 1; +#endif + } + + return findleader; + } + + /****** + ******/ + int radiusSearchApprox(Point query, float radius, \ + std::vector &k_indices, \ + std::vector &k_dists) + { + int back_track = 0; + std::vector backtrack_stack; + + NodePtr cur_node = root_node_; + cur_node = traverse_tree(cur_node, query, backtrack_stack); + + /* Search the leaf node. */ + bool findleader = radiusSearchUnitApprox(cur_node, query, radius, k_indices, k_dists); + + // Backtrack && prune + if (!findleader) + { + for(;backtrack_stack.size();) + { + NodePtr backtrack_node = backtrack_stack.back(); + backtrack_stack.pop_back(); + + float dist_min_ = radius; + + // Prune + bool visit_ = check_intersection(query, dist_min_, backtrack_node); + if (visit_) + { + back_track += 1; + if (backtrack_node->s_dim != -1) + backtrack_node = traverse_tree(backtrack_node, query, backtrack_stack); + radiusSearch_unit(backtrack_node->index_list, query, radius, k_indices, k_dists); + } + } + Leader leader_point; + if (k_indices.size()) + { + leader_point.p = query; + for (int i = 0; i < k_indices.size(); i++) + (leader_point.neighbors).push_back((k_indices[i])); + (cur_node->leaders).push_back(leader_point); + } + } + return back_track; + } + +private: + + NodePtr root_node_; + + IndexPtr index_; + PointsPtr points_; + + int dim_; + // point data dimension (by default 3) + + int max_leaf_size_; + // to control the leaf node size + + int leaf_node_num_; + + std::vector leaf_nodes_; + // store the pointers to a leaf node + // so that we could get the content of the leaf node by index + + // Parameter for Approx radius search + float para_Radius_; + + // Parameter for Approx NN search + float para_NN_; + +private: + float getDistance(Point point, Point centroid) + { + float distance = pow((centroid.x - point.x), 2) + pow((centroid.y - point.y), 2) + pow((centroid.z - point.z), 2); + return distance; + } + + /* + Helper function + */ + float dist(Point p1, Point p2) + { + return sqrt(pow((p1.x - p2.x),2) + \ + pow((p1.y - p2.y),2) + pow((p1.z - p2.z),2)); + } + + /****** + Divide the tree. + The tree is built with this function in a + recursive fashion. + + Args: + Returns: + ******/ + NodePtr divideTree(int left, int right, std::vector *bbox_ptr) + { + NodePtr node = new Node(); + + // find the indices for the current node + for (int i = left; i <= right; ++i) { + (node->index_list).push_back((*index_)[i]); + } + // store the bounding box + node->bbox = *bbox_ptr; + + int count = right - left; + + if(count <= max_leaf_size_) + { + // leaf node + node->s_dim = -1; + node->s_val = -1; + + node->leaf_idx = leaf_node_num_; + leaf_node_num_ += 1; + + leaf_nodes_.push_back(node); + + return node; + } + else + { + // splitting dim + int split_dim = 0; + float span = 0.0; + std::vector value_list; + + findSplitDim(split_dim, span, bbox_ptr); + node->s_dim = split_dim; + + // splitting value + float split_val = 0.0; + + // Original Implementation by QuickSort and Select Median Value + // findMedian(left, right, split_dim, split_val); + + //Alternative Version to Select Median by QuickSelect + getValueList(left, right, split_dim, value_list); + std::vector* value_list_ptr = &value_list; + qSelectMedian(value_list_ptr, split_val); + + // FLANN's implementation: + // split_val = ((*bbox_ptr)[split_dim].low + + // (*bbox_ptr)[split_dim].high) / 2; + node->s_val = split_val; + + // process the indices + int lim1 = 0, lim2 = 0, split_delta = 0; + planeSplit(left, right, split_dim, split_val, lim1, lim2); + split_delta = (lim1 + lim2) / 2; + + std::vector bbox_l; + std::vector bbox_r; + computeBoundingBox(left, left + lim2, bbox_l); + computeBoundingBox(left + lim2 + 1, right, bbox_r); + + node->left_child = divideTree(left, left + lim2, &bbox_l); + node->right_child = divideTree(left + lim2 + 1, right, &bbox_r); + + return node; + } + } + + /********************************************************************** + Using flann's implementation to find the splitting index. + The idea is to split the points into three parts by changing the + order of the indices. By the end of planeSplit, the index_ variable + is re-arranged: + + index_ [left : lim1]: + indices of points whose value on the split dim < spit value + + index_ [lim1 : lim2]: + indices of points whose value on the split dim == spit value + + index_ [lim2 : right]: + indices of points whose value on the split dim > spit value + + **********************************************************************/ + void planeSplit(int left, int right, int split_dim, + float split_val, int& lim1, int& lim2) + { + int start = 0; + int end = right - left; + + for (;;) { + while (start <= end && (*points_)[(*index_)[left + start]][split_dim] < split_val) + ++start; + while (start <= end && (*points_)[(*index_)[left + end]][split_dim] >= split_val) + --end; + + if (start > end) break; + std::swap((*index_)[left + start], (*index_)[left + end]); ++start; --end; + } + lim1 = start; + + end = right - left; + for (;; ) { + while (start <= end && (*points_)[(*index_)[left + start]][split_dim] <= split_val) + ++start; + while (start <= end && (*points_)[(*index_)[left + end]][split_dim] > split_val) + --end; + if (start > end) break; + std::swap((*index_)[left + start], (*index_)[left + end]); ++start; --end; + } + lim2 = end; + } + + /****** + ******/ + inline void swap(std::vector* value_list, int a, int b) + { + float tmpa = (*value_list)[a]; + float tmpb = (*value_list)[b]; + (*value_list)[a] = tmpb; + (*value_list)[b] = tmpa; + } + + /****** + ******/ + void getValueList(int left, int right, int split_dim, std::vector &value_list) + { + for (int i = left; i <= right; i++) + value_list.push_back((*points_)[(*index_)[i]][split_dim]); + } + + /****** + ******/ + void qSelectMedian(std::vector* value_list, float &median_value) + { + int left = 0; + int right = value_list->size() - 1; + int middle = value_list->size() / 2; + while(1) + { + float pivot = (*value_list)[middle]; + swap(value_list, middle, right); + int store = left; + + for (int i = left; i < right; i++) + { + if ((*value_list)[i] < pivot) + { + if (i != store) + swap(value_list, i, store); + store++; + } + } + swap(value_list, store, right); + + if ((*value_list)[store] == (*value_list)[middle]) + { + median_value = (*value_list)[middle]; + break; + } + + if (store > middle) right = store - 1; + else left = store; + } + } + + + /****** + Calculate the median value + reference: + https://stackoverflow.com/questions/10662013/finding-the-median-of-an-unsorted-array + ******/ + void findMedian(int left, int right, int split_dim, float &median_value) + { + std::vector dim_sorted; + for (int i = left; i <= right; ++i) + { + dim_sorted.push_back((*points_)[(*index_)[i]][split_dim]); + } + std::sort(dim_sorted.begin(), dim_sorted.end()); + + int median_pos = (right - left) / 2; + + median_value = dim_sorted[median_pos]; + } + + /****** + Compute the bounding box of current node + given indices of points. + ******/ + void computeBoundingBox(int left, int right, \ + std::vector & bbox) + { + int cur_dim = 0; + for ( ;cur_dim < dim_; cur_dim++) + { + Interval bounds; + computeMinMax(left, right, cur_dim, bounds.low, bounds.high); + bbox.push_back(bounds); + } + } + + /****** + Choose the split dimension. + Current strategy: the one with maximum span value. + span == MAX(dim) - MIN(dim) + ******/ + void findSplitDim(int &best_dim, float &span, \ + std::vector *bbox_ptr) + { + int cur_dim = 0; // 0: x, 1: y, 2: z + + float min_ = 0.0, max_ = 0.0; + span = 0.0; + + for ( ;cur_dim < dim_; cur_dim++) + { + min_ = (*bbox_ptr)[cur_dim].low; + max_ = (*bbox_ptr)[cur_dim].high; + + if ((max_ - min_) > span) + { + best_dim = cur_dim; + span = (max_ - min_); + } + } + } + + /****** + Give specified indices (index_[left] to index_[right]), + compute the span (max value - min value) + on a specific dimension. + ******/ + void computeMinMax(int left, int right, int dim, float& min_val, float& max_val) + { + min_val = (*points_)[(*index_)[left]][dim]; + max_val = (*points_)[(*index_)[left]][dim]; + + for (int i = left + 1; i <= right; ++i) { + + float val = (*points_)[(*index_)[i]][dim]; + + if (val < min_val) min_val = val; + if (val > max_val) max_val = val; + } + } +}; diff --git a/pcl-1.7/pcl/impl/cloud_iterator.hpp b/pcl-1.7/pcl/impl/cloud_iterator.hpp new file mode 100644 index 0000000..fc5bb18 --- /dev/null +++ b/pcl-1.7/pcl/impl/cloud_iterator.hpp @@ -0,0 +1,557 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_POINT_CLOUD_ITERATOR_HPP_ +#define PCL_POINT_CLOUD_ITERATOR_HPP_ + +#include + +namespace pcl +{ + /** \brief + * \author Suat Gedikli + */ + template + class DefaultIterator : public CloudIterator::Iterator + { + public: + DefaultIterator (PointCloud& cloud) + : cloud_ (cloud) + , iterator_ (cloud.begin ()) + { + } + + ~DefaultIterator () + { + } + + void operator ++ () + { + ++iterator_; + } + + void operator ++ (int) + { + iterator_++; + } + + PointT& operator* () const + { + return (*iterator_); + } + + PointT* operator-> () + { + return (&(*iterator_)); + } + + unsigned getCurrentPointIndex () const + { + return (iterator_ - cloud_.begin ()); + } + + unsigned getCurrentIndex () const + { + return (iterator_ - cloud_.begin ()); + } + + size_t size () const + { + return cloud_.size (); + } + + void reset () + { + iterator_ = cloud_.begin (); + } + + bool isValid () const + { + return (iterator_ != cloud_.end ()); + } + private: + PointCloud& cloud_; + typename PointCloud::iterator iterator_; + }; + + /** \brief + * \author Suat Gedikli + */ + template + class IteratorIdx : public CloudIterator::Iterator + { + public: + IteratorIdx (PointCloud& cloud, const std::vector& indices) + : cloud_ (cloud) + , indices_ (indices) + , iterator_ (indices_.begin ()) + { + } + + IteratorIdx (PointCloud& cloud, const PointIndices& indices) + : cloud_ (cloud) + , indices_ (indices.indices) + , iterator_ (indices_.begin ()) + { + } + + virtual ~IteratorIdx () {} + + void operator ++ () + { + ++iterator_; + } + + void operator ++ (int) + { + iterator_++; + } + + PointT& operator* () const + { + return (cloud_.points [*iterator_]); + } + + PointT* operator-> () + { + return (&(cloud_.points [*iterator_])); + } + + unsigned getCurrentPointIndex () const + { + return (*iterator_); + } + + unsigned getCurrentIndex () const + { + return (iterator_ - indices_.begin ()); + } + + size_t size () const + { + return indices_.size (); + } + + void reset () + { + iterator_ = indices_.begin (); + } + + bool isValid () const + { + return (iterator_ != indices_.end ()); + } + + private: + PointCloud& cloud_; + std::vector indices_; + std::vector::iterator iterator_; + }; + + /** \brief + * \author Suat Gedikli + */ + template + class ConstCloudIterator::DefaultConstIterator : public ConstCloudIterator::Iterator + { + public: + DefaultConstIterator (const PointCloud& cloud) + : cloud_ (cloud) + , iterator_ (cloud.begin ()) + { + } + + ~DefaultConstIterator () + { + } + + void operator ++ () + { + ++iterator_; + } + + void operator ++ (int) + { + iterator_++; + } + + const PointT& operator* () const + { + return (*iterator_); + } + + const PointT* operator-> () const + { + return (&(*iterator_)); + } + + unsigned getCurrentPointIndex () const + { + return (unsigned (iterator_ - cloud_.begin ())); + } + + unsigned getCurrentIndex () const + { + return (unsigned (iterator_ - cloud_.begin ())); + } + + size_t size () const + { + return cloud_.size (); + } + + void reset () + { + iterator_ = cloud_.begin (); + } + + bool isValid () const + { + return (iterator_ != cloud_.end ()); + } + private: + const PointCloud& cloud_; + typename PointCloud::const_iterator iterator_; + }; + + /** \brief + * \author Suat Gedikli + */ + template + class ConstCloudIterator::ConstIteratorIdx : public ConstCloudIterator::Iterator + { + public: + ConstIteratorIdx (const PointCloud& cloud, + const std::vector& indices) + : cloud_ (cloud) + , indices_ (indices) + , iterator_ (indices_.begin ()) + { + } + + ConstIteratorIdx (const PointCloud& cloud, + const PointIndices& indices) + : cloud_ (cloud) + , indices_ (indices.indices) + , iterator_ (indices_.begin ()) + { + } + + virtual ~ConstIteratorIdx () {} + + void operator ++ () + { + ++iterator_; + } + + void operator ++ (int) + { + iterator_++; + } + + const PointT& operator* () const + { + return (cloud_.points[*iterator_]); + } + + const PointT* operator-> () const + { + return (&(cloud_.points [*iterator_])); + } + + unsigned getCurrentPointIndex () const + { + return (unsigned (*iterator_)); + } + + unsigned getCurrentIndex () const + { + return (unsigned (iterator_ - indices_.begin ())); + } + + size_t size () const + { + return indices_.size (); + } + + void reset () + { + iterator_ = indices_.begin (); + } + + bool isValid () const + { + return (iterator_ != indices_.end ()); + } + + private: + const PointCloud& cloud_; + std::vector indices_; + std::vector::iterator iterator_; + }; +} // namespace pcl + +////////////////////////////////////////////////////////////////////////////// +template +pcl::CloudIterator::CloudIterator (PointCloud& cloud) + : iterator_ (new DefaultIterator (cloud)) +{ +} + +////////////////////////////////////////////////////////////////////////////// +template +pcl::CloudIterator::CloudIterator ( + PointCloud& cloud, const std::vector& indices) + : iterator_ (new IteratorIdx (cloud, indices)) +{ +} + +////////////////////////////////////////////////////////////////////////////// +template +pcl::CloudIterator::CloudIterator ( + PointCloud& cloud, const PointIndices& indices) + : iterator_ (new IteratorIdx (cloud, indices)) +{ +} + +////////////////////////////////////////////////////////////////////////////// +template +pcl::CloudIterator::CloudIterator ( + PointCloud& cloud, const Correspondences& corrs, bool source) +{ + std::vector indices; + indices.reserve (corrs.size ()); + if (source) + { + for (typename Correspondences::const_iterator indexIt = corrs.begin (); indexIt != corrs.end (); ++indexIt) + indices.push_back (indexIt->index_query); + } + else + { + for (typename Correspondences::const_iterator indexIt = corrs.begin (); indexIt != corrs.end (); ++indexIt) + indices.push_back (indexIt->index_match); + } + iterator_ = new IteratorIdx (cloud, indices); +} + +////////////////////////////////////////////////////////////////////////////// +template +pcl::CloudIterator::~CloudIterator () +{ + delete iterator_; +} + +////////////////////////////////////////////////////////////////////////////// +template void +pcl::CloudIterator::operator ++ () +{ + iterator_->operator++ (); +} + +////////////////////////////////////////////////////////////////////////////// +template void +pcl::CloudIterator::operator ++ (int) +{ + iterator_->operator++ (0); +} + +////////////////////////////////////////////////////////////////////////////// +template PointT& +pcl::CloudIterator::operator* () const +{ + return (iterator_->operator * ()); +} + +////////////////////////////////////////////////////////////////////////////// +template PointT* +pcl::CloudIterator::operator-> () const +{ + return (iterator_->operator-> ()); +} + +////////////////////////////////////////////////////////////////////////////// +template unsigned +pcl::CloudIterator::getCurrentPointIndex () const +{ + return (iterator_->getCurrentPointIndex ()); +} + +////////////////////////////////////////////////////////////////////////////// +template unsigned +pcl::CloudIterator::getCurrentIndex () const +{ + return (iterator_->getCurrentIndex ()); +} + +////////////////////////////////////////////////////////////////////////////// +template size_t +pcl::CloudIterator::size () const +{ + return (iterator_->size ()); +} + +////////////////////////////////////////////////////////////////////////////// +template void +pcl::CloudIterator::reset () +{ + iterator_->reset (); +} + +////////////////////////////////////////////////////////////////////////////// +template bool +pcl::CloudIterator::isValid () const +{ + return (iterator_->isValid ()); +} + + +////////////////////////////////////////////////////////////////////////////// +template +pcl::ConstCloudIterator::ConstCloudIterator (const PointCloud& cloud) + : iterator_ (new typename pcl::ConstCloudIterator::DefaultConstIterator (cloud)) +{ +} + +////////////////////////////////////////////////////////////////////////////// +template +pcl::ConstCloudIterator::ConstCloudIterator ( + const PointCloud& cloud, const std::vector& indices) + : iterator_ (new typename pcl::ConstCloudIterator::ConstIteratorIdx (cloud, indices)) +{ +} + +////////////////////////////////////////////////////////////////////////////// +template +pcl::ConstCloudIterator::ConstCloudIterator ( + const PointCloud& cloud, const PointIndices& indices) + : iterator_ (new typename pcl::ConstCloudIterator::ConstIteratorIdx (cloud, indices)) +{ +} + +////////////////////////////////////////////////////////////////////////////// +template +pcl::ConstCloudIterator::ConstCloudIterator ( + const PointCloud& cloud, const Correspondences& corrs, bool source) +{ + std::vector indices; + indices.reserve (corrs.size ()); + if (source) + { + for (typename Correspondences::const_iterator indexIt = corrs.begin (); indexIt != corrs.end (); ++indexIt) + indices.push_back (indexIt->index_query); + } + else + { + for (typename Correspondences::const_iterator indexIt = corrs.begin (); indexIt != corrs.end (); ++indexIt) + indices.push_back (indexIt->index_match); + } + iterator_ = new typename pcl::ConstCloudIterator::ConstIteratorIdx (cloud, indices); +} + +////////////////////////////////////////////////////////////////////////////// +template +pcl::ConstCloudIterator::~ConstCloudIterator () +{ + delete iterator_; +} + +////////////////////////////////////////////////////////////////////////////// +template void +pcl::ConstCloudIterator::operator ++ () +{ + iterator_->operator++ (); +} + +////////////////////////////////////////////////////////////////////////////// +template void +pcl::ConstCloudIterator::operator ++ (int) +{ + iterator_->operator++ (0); +} + +////////////////////////////////////////////////////////////////////////////// +template const PointT& +pcl::ConstCloudIterator::operator* () const +{ + return (iterator_->operator * ()); +} + +////////////////////////////////////////////////////////////////////////////// +template const PointT* +pcl::ConstCloudIterator::operator-> () const +{ + return (iterator_->operator-> ()); +} + +////////////////////////////////////////////////////////////////////////////// +template unsigned +pcl::ConstCloudIterator::getCurrentPointIndex () const +{ + return (iterator_->getCurrentPointIndex ()); +} + +////////////////////////////////////////////////////////////////////////////// +template unsigned +pcl::ConstCloudIterator::getCurrentIndex () const +{ + return (iterator_->getCurrentIndex ()); +} + +////////////////////////////////////////////////////////////////////////////// +template size_t +pcl::ConstCloudIterator::size () const +{ + return (iterator_->size ()); +} + +////////////////////////////////////////////////////////////////////////////// +template void +pcl::ConstCloudIterator::reset () +{ + iterator_->reset (); +} + +////////////////////////////////////////////////////////////////////////////// +template bool +pcl::ConstCloudIterator::isValid () const +{ + return (iterator_->isValid ()); +} + +#endif // PCL_POINT_CLOUD_ITERATOR_HPP_ + diff --git a/pcl-1.7/pcl/impl/instantiate.hpp b/pcl-1.7/pcl/impl/instantiate.hpp new file mode 100644 index 0000000..528f96c --- /dev/null +++ b/pcl-1.7/pcl/impl/instantiate.hpp @@ -0,0 +1,115 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_IMPL_INSTANTIATE_H_ +#define PCL_IMPL_INSTANTIATE_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#include + +//#define PCL_POINT_TYPES (bool)(int)(float)(double) +//#define PCL_TEMPLATES (Type)(Othertype) + +// +// PCL_INSTANTIATE: call to instantiate template TEMPLATE for all +// POINT_TYPES +// + +#ifdef PCL_NO_PRECOMPILE + +#define PCL_INSTANTIATE_PRODUCT_IMPL(r, product) +#define PCL_INSTANTIATE_IMPL(r, TEMPLATE, POINT_TYPE) +#define PCL_INSTANTIATE(TEMPLATE, POINT_TYPES) +#define PCL_INSTANTIATE_PRODUCT_IMPL(r, product) +#define PCL_INSTANTIATE_PRODUCT(TEMPLATE, PRODUCT) + +#else + +#include +#include +#include +#include +#include + +#define PCL_INSTANTIATE_IMPL(r, TEMPLATE, POINT_TYPE) \ + BOOST_PP_CAT(PCL_INSTANTIATE_, TEMPLATE)(POINT_TYPE) + +#define PCL_INSTANTIATE(TEMPLATE, POINT_TYPES) \ + BOOST_PP_SEQ_FOR_EACH(PCL_INSTANTIATE_IMPL, TEMPLATE, POINT_TYPES) + + +// +// PCL_INSTANTIATE_PRODUCT(templatename, (seq1)(seq2)...(seqN)) +// +// instantiate templates +// +// A call to PCL_INSTANTIATE_PRODUCT(T, ((a)(b)) ((d)(e)) ) results in calls +// +// PCL_INSTANTIATE_T(a, d) +// PCL_INSTANTIATE_T(a, e) +// PCL_INSTANTIATE_T(b, d) +// PCL_INSTANTIATE_T(b, e) +// +// That is, PCL_INSTANTIATE_T is called for the cartesian product of the sequences seq1 ... seqN +// +// BE CAREFUL WITH YOUR PARENTHESIS! The argument PRODUCT is a +// sequence of sequences. e.g. if it were three sequences of, +// 1. letters, 2. numbers, and 3. our favorite transylvanians, it +// would be +// +// ((x)(y)(z))((1)(2)(3))((dracula)(radu)) +// +#ifdef _MSC_VER +#define PCL_INSTANTIATE_PRODUCT_IMPL(r, product) \ + BOOST_PP_CAT(PCL_INSTANTIATE_, BOOST_PP_SEQ_HEAD(product)) \ + BOOST_PP_EXPAND(BOOST_PP_SEQ_TO_TUPLE(BOOST_PP_SEQ_TAIL(product))) +#else +#define PCL_INSTANTIATE_PRODUCT_IMPL(r, product) \ + BOOST_PP_EXPAND(BOOST_PP_CAT(PCL_INSTANTIATE_, BOOST_PP_SEQ_HEAD(product)) \ + BOOST_PP_SEQ_TO_TUPLE(BOOST_PP_SEQ_TAIL(product))) +#endif + + +#define PCL_INSTANTIATE_PRODUCT(TEMPLATE, PRODUCT) \ + BOOST_PP_SEQ_FOR_EACH_PRODUCT(PCL_INSTANTIATE_PRODUCT_IMPL, ((TEMPLATE))PRODUCT) + +#endif + +#endif diff --git a/pcl-1.7/pcl/impl/pcl_base.hpp b/pcl-1.7/pcl/impl/pcl_base.hpp new file mode 100644 index 0000000..7d4ae73 --- /dev/null +++ b/pcl-1.7/pcl/impl/pcl_base.hpp @@ -0,0 +1,182 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_PCL_IMPL_BASE_HPP_ +#define PCL_PCL_IMPL_BASE_HPP_ + +#include +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::PCLBase::PCLBase () + : input_ () + , indices_ () + , use_indices_ (false) + , fake_indices_ (false) +{ +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::PCLBase::PCLBase (const PCLBase& base) + : input_ (base.input_) + , indices_ (base.indices_) + , use_indices_ (base.use_indices_) + , fake_indices_ (base.fake_indices_) +{ +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PCLBase::setInputCloud (const PointCloudConstPtr &cloud) +{ + input_ = cloud; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PCLBase::setIndices (const IndicesPtr &indices) +{ + indices_ = indices; + fake_indices_ = false; + use_indices_ = true; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PCLBase::setIndices (const IndicesConstPtr &indices) +{ + indices_.reset (new std::vector (*indices)); + fake_indices_ = false; + use_indices_ = true; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PCLBase::setIndices (const PointIndicesConstPtr &indices) +{ + indices_.reset (new std::vector (indices->indices)); + fake_indices_ = false; + use_indices_ = true; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PCLBase::setIndices (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols) +{ + if ((nb_rows > input_->height) || (row_start > input_->height)) + { + PCL_ERROR ("[PCLBase::setIndices] cloud is only %d height", input_->height); + return; + } + + if ((nb_cols > input_->width) || (col_start > input_->width)) + { + PCL_ERROR ("[PCLBase::setIndices] cloud is only %d width", input_->width); + return; + } + + size_t row_end = row_start + nb_rows; + if (row_end > input_->height) + { + PCL_ERROR ("[PCLBase::setIndices] %d is out of rows range %d", row_end, input_->height); + return; + } + + size_t col_end = col_start + nb_cols; + if (col_end > input_->width) + { + PCL_ERROR ("[PCLBase::setIndices] %d is out of columns range %d", col_end, input_->width); + return; + } + + indices_.reset (new std::vector); + indices_->reserve (nb_cols * nb_rows); + for(size_t i = row_start; i < row_end; i++) + for(size_t j = col_start; j < col_end; j++) + indices_->push_back (static_cast ((i * input_->width) + j)); + fake_indices_ = false; + use_indices_ = true; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::PCLBase::initCompute () +{ + // Check if input was set + if (!input_) + return (false); + + // If no point indices have been given, construct a set of indices for the entire input point cloud + if (!indices_) + { + fake_indices_ = true; + indices_.reset (new std::vector); + try + { + indices_->resize (input_->points.size ()); + } + catch (std::bad_alloc) + { + PCL_ERROR ("[initCompute] Failed to allocate %lu indices.\n", input_->points.size ()); + } + for (size_t i = 0; i < indices_->size (); ++i) { (*indices_)[i] = static_cast(i); } + } + + // If we have a set of fake indices, but they do not match the number of points in the cloud, update them + if (fake_indices_ && indices_->size () != input_->points.size ()) + { + size_t indices_size = indices_->size (); + indices_->resize (input_->points.size ()); + for (size_t i = indices_size; i < indices_->size (); ++i) { (*indices_)[i] = static_cast(i); } + } + + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::PCLBase::deinitCompute () +{ + return (true); +} + +#define PCL_INSTANTIATE_PCLBase(T) template class PCL_EXPORTS pcl::PCLBase; + +#endif //#ifndef PCL_PCL_IMPL_BASE_HPP_ + diff --git a/pcl-1.7/pcl/impl/point_types.hpp b/pcl-1.7/pcl/impl/point_types.hpp new file mode 100644 index 0000000..4c4a0ab --- /dev/null +++ b/pcl-1.7/pcl/impl/point_types.hpp @@ -0,0 +1,1518 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_IMPL_POINT_TYPES_HPP_ +#define PCL_IMPL_POINT_TYPES_HPP_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include + +// Define all PCL point types +#define PCL_POINT_TYPES \ + (pcl::PointXYZ) \ + (pcl::PointXYZI) \ + (pcl::PointXYZL) \ + (pcl::Label) \ + (pcl::PointXYZRGBA) \ + (pcl::PointXYZRGB) \ + (pcl::PointXYZRGBL) \ + (pcl::PointXYZHSV) \ + (pcl::PointXY) \ + (pcl::InterestPoint) \ + (pcl::Axis) \ + (pcl::Normal) \ + (pcl::PointNormal) \ + (pcl::PointXYZRGBNormal) \ + (pcl::PointXYZINormal) \ + (pcl::PointWithRange) \ + (pcl::PointWithViewpoint) \ + (pcl::MomentInvariants) \ + (pcl::PrincipalRadiiRSD) \ + (pcl::Boundary) \ + (pcl::PrincipalCurvatures) \ + (pcl::PFHSignature125) \ + (pcl::PFHRGBSignature250) \ + (pcl::PPFSignature) \ + (pcl::CPPFSignature) \ + (pcl::PPFRGBSignature) \ + (pcl::NormalBasedSignature12) \ + (pcl::FPFHSignature33) \ + (pcl::VFHSignature308) \ + (pcl::ESFSignature640) \ + (pcl::Narf36) \ + (pcl::IntensityGradient) \ + (pcl::PointWithScale) \ + (pcl::PointSurfel) \ + (pcl::ShapeContext1980) \ + (pcl::SHOT352) \ + (pcl::SHOT1344) \ + (pcl::PointUV) \ + (pcl::ReferenceFrame) + +// Define all point types that include RGB data +#define PCL_RGB_POINT_TYPES \ + (pcl::PointXYZRGBA) \ + (pcl::PointXYZRGB) \ + (pcl::PointXYZRGBL) \ + (pcl::PointXYZRGBNormal) \ + (pcl::PointSurfel) \ + +// Define all point types that include XYZ data +#define PCL_XYZ_POINT_TYPES \ + (pcl::PointXYZ) \ + (pcl::PointXYZI) \ + (pcl::PointXYZL) \ + (pcl::PointXYZRGBA) \ + (pcl::PointXYZRGB) \ + (pcl::PointXYZRGBL) \ + (pcl::PointXYZHSV) \ + (pcl::InterestPoint) \ + (pcl::PointNormal) \ + (pcl::PointXYZRGBNormal) \ + (pcl::PointXYZINormal) \ + (pcl::PointWithRange) \ + (pcl::PointWithViewpoint) \ + (pcl::PointWithScale) \ + (pcl::PointSurfel) + +// Define all point types with XYZ and label +#define PCL_XYZL_POINT_TYPES \ + (pcl::PointXYZL) \ + (pcl::PointXYZRGBL) + +// Define all point types that include normal[3] data +#define PCL_NORMAL_POINT_TYPES \ + (pcl::Normal) \ + (pcl::PointNormal) \ + (pcl::PointXYZRGBNormal) \ + (pcl::PointXYZINormal) \ + (pcl::PointSurfel) + +// Define all point types that represent features +#define PCL_FEATURE_POINT_TYPES \ + (pcl::PFHSignature125) \ + (pcl::PFHRGBSignature250) \ + (pcl::PPFSignature) \ + (pcl::CPPFSignature) \ + (pcl::PPFRGBSignature) \ + (pcl::NormalBasedSignature12) \ + (pcl::FPFHSignature33) \ + (pcl::VFHSignature308) \ + (pcl::ESFSignature640) \ + (pcl::Narf36) + +namespace pcl +{ + + typedef Eigen::Map Array3fMap; + typedef const Eigen::Map Array3fMapConst; + typedef Eigen::Map Array4fMap; + typedef const Eigen::Map Array4fMapConst; + typedef Eigen::Map Vector3fMap; + typedef const Eigen::Map Vector3fMapConst; + typedef Eigen::Map Vector4fMap; + typedef const Eigen::Map Vector4fMapConst; + + typedef Eigen::Matrix Vector3c; + typedef Eigen::Map Vector3cMap; + typedef const Eigen::Map Vector3cMapConst; + typedef Eigen::Matrix Vector4c; + typedef Eigen::Map Vector4cMap; + typedef const Eigen::Map Vector4cMapConst; + +#define PCL_ADD_UNION_POINT4D \ + union EIGEN_ALIGN16 { \ + float data[4]; \ + struct { \ + float x; \ + float y; \ + float z; \ + }; \ + }; + +#define PCL_ADD_EIGEN_MAPS_POINT4D \ + inline pcl::Vector3fMap getVector3fMap () { return (pcl::Vector3fMap (data)); } \ + inline pcl::Vector3fMapConst getVector3fMap () const { return (pcl::Vector3fMapConst (data)); } \ + inline pcl::Vector4fMap getVector4fMap () { return (pcl::Vector4fMap (data)); } \ + inline pcl::Vector4fMapConst getVector4fMap () const { return (pcl::Vector4fMapConst (data)); } \ + inline pcl::Array3fMap getArray3fMap () { return (pcl::Array3fMap (data)); } \ + inline pcl::Array3fMapConst getArray3fMap () const { return (pcl::Array3fMapConst (data)); } \ + inline pcl::Array4fMap getArray4fMap () { return (pcl::Array4fMap (data)); } \ + inline pcl::Array4fMapConst getArray4fMap () const { return (pcl::Array4fMapConst (data)); } + +#define PCL_ADD_POINT4D \ + PCL_ADD_UNION_POINT4D \ + PCL_ADD_EIGEN_MAPS_POINT4D + +#define PCL_ADD_UNION_NORMAL4D \ + union EIGEN_ALIGN16 { \ + float data_n[4]; \ + float normal[3]; \ + struct { \ + float normal_x; \ + float normal_y; \ + float normal_z; \ + }; \ + }; + +#define PCL_ADD_EIGEN_MAPS_NORMAL4D \ + inline pcl::Vector3fMap getNormalVector3fMap () { return (pcl::Vector3fMap (data_n)); } \ + inline pcl::Vector3fMapConst getNormalVector3fMap () const { return (pcl::Vector3fMapConst (data_n)); } \ + inline pcl::Vector4fMap getNormalVector4fMap () { return (pcl::Vector4fMap (data_n)); } \ + inline pcl::Vector4fMapConst getNormalVector4fMap () const { return (pcl::Vector4fMapConst (data_n)); } + +#define PCL_ADD_NORMAL4D \ + PCL_ADD_UNION_NORMAL4D \ + PCL_ADD_EIGEN_MAPS_NORMAL4D + +#define PCL_ADD_UNION_RGB \ + union \ + { \ + union \ + { \ + struct \ + { \ + uint8_t b; \ + uint8_t g; \ + uint8_t r; \ + uint8_t a; \ + }; \ + float rgb; \ + }; \ + uint32_t rgba; \ + }; + +#define PCL_ADD_EIGEN_MAPS_RGB \ + inline Eigen::Vector3i getRGBVector3i () { return (Eigen::Vector3i (r, g, b)); } \ + inline const Eigen::Vector3i getRGBVector3i () const { return (Eigen::Vector3i (r, g, b)); } \ + inline Eigen::Vector4i getRGBVector4i () { return (Eigen::Vector4i (r, g, b, a)); } \ + inline const Eigen::Vector4i getRGBVector4i () const { return (Eigen::Vector4i (r, g, b, a)); } \ + inline Eigen::Vector4i getRGBAVector4i () { return (Eigen::Vector4i (r, g, b, a)); } \ + inline const Eigen::Vector4i getRGBAVector4i () const { return (Eigen::Vector4i (r, g, b, a)); } \ + inline pcl::Vector3cMap getBGRVector3cMap () { return (pcl::Vector3cMap (reinterpret_cast (&rgba))); } \ + inline pcl::Vector3cMapConst getBGRVector3cMap () const { return (pcl::Vector3cMapConst (reinterpret_cast (&rgba))); } \ + inline pcl::Vector4cMap getBGRAVector4cMap () { return (pcl::Vector4cMap (reinterpret_cast (&rgba))); } \ + inline pcl::Vector4cMapConst getBGRAVector4cMap () const { return (pcl::Vector4cMapConst (reinterpret_cast (&rgba))); } + +#define PCL_ADD_RGB \ + PCL_ADD_UNION_RGB \ + PCL_ADD_EIGEN_MAPS_RGB + +#define PCL_ADD_INTENSITY \ + struct \ + { \ + float intensity; \ + }; \ + +#define PCL_ADD_INTENSITY_8U \ + struct \ + { \ + uint8_t intensity; \ + }; \ + +#define PCL_ADD_INTENSITY_32U \ + struct \ + { \ + uint32_t intensity; \ + }; \ + + + struct _PointXYZ + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZ& p); + /** \brief A point structure representing Euclidean xyz coordinates. (SSE friendly) + * \ingroup common + */ + struct EIGEN_ALIGN16 PointXYZ : public _PointXYZ + { + inline PointXYZ (const _PointXYZ &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + } + + inline PointXYZ () + { + x = y = z = 0.0f; + data[3] = 1.0f; + } + + inline PointXYZ (float _x, float _y, float _z) + { + x = _x; y = _y; z = _z; + data[3] = 1.0f; + } + + friend std::ostream& operator << (std::ostream& os, const PointXYZ& p); + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + +#ifdef RGB +#undef RGB +#endif + struct _RGB + { + PCL_ADD_RGB; + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const RGB& p); + /** \brief A structure representing RGB color information. + * + * The RGBA information is available either as separate r, g, b, or as a + * packed uint32_t rgba value. To pack it, use: + * + * \code + * int rgb = ((int)r) << 16 | ((int)g) << 8 | ((int)b); + * \endcode + * + * To unpack it use: + * + * \code + * int rgb = ...; + * uint8_t r = (rgb >> 16) & 0x0000ff; + * uint8_t g = (rgb >> 8) & 0x0000ff; + * uint8_t b = (rgb) & 0x0000ff; + * \endcode + * + */ + struct RGB: public _RGB + { + inline RGB (const _RGB &p) + { + rgba = p.rgba; + } + + inline RGB () + { + r = g = b = a = 0; + } + + friend std::ostream& operator << (std::ostream& os, const RGB& p); + }; + + + struct _Intensity + { + PCL_ADD_INTENSITY; + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Intensity& p); + /** \brief A point structure representing the grayscale intensity in single-channel images. + * Intensity is represented as a float value. + * \ingroup common + */ + struct Intensity: public _Intensity + { + inline Intensity (const _Intensity &p) + { + intensity = p.intensity; + } + + inline Intensity () + { + intensity = 0.0f; + } + + friend std::ostream& operator << (std::ostream& os, const Intensity& p); + }; + + + struct _Intensity8u + { + PCL_ADD_INTENSITY_8U; + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Intensity8u& p); + /** \brief A point structure representing the grayscale intensity in single-channel images. + * Intensity is represented as a uint8_t value. + * \ingroup common + */ + struct Intensity8u: public _Intensity8u + { + inline Intensity8u (const _Intensity8u &p) + { + intensity = p.intensity; + } + + inline Intensity8u () + { + intensity = 0; + } + +#if defined(_LIBCPP_VERSION) && _LIBCPP_VERSION <= 1101 + operator unsigned char() const + { + return intensity; + } +#endif + + friend std::ostream& operator << (std::ostream& os, const Intensity8u& p); + }; + + struct _Intensity32u + { + PCL_ADD_INTENSITY_32U; + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Intensity32u& p); + /** \brief A point structure representing the grayscale intensity in single-channel images. + * Intensity is represented as a uint8_t value. + * \ingroup common + */ + struct Intensity32u: public _Intensity32u + { + inline Intensity32u (const _Intensity32u &p) + { + intensity = p.intensity; + } + + inline Intensity32u () + { + intensity = 0; + } + + friend std::ostream& operator << (std::ostream& os, const Intensity32u& p); + }; + + /** \brief A point structure representing Euclidean xyz coordinates, and the intensity value. + * \ingroup common + */ + struct EIGEN_ALIGN16 _PointXYZI + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + union + { + struct + { + float intensity; + }; + float data_c[4]; + }; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZI& p); + struct PointXYZI : public _PointXYZI + { + inline PointXYZI (const _PointXYZI &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + intensity = p.intensity; + } + + inline PointXYZI () + { + x = y = z = 0.0f; + data[3] = 1.0f; + intensity = 0.0f; + } + inline PointXYZI (float _intensity) + { + x = y = z = 0.0f; + data[3] = 1.0f; + intensity = _intensity; + } + friend std::ostream& operator << (std::ostream& os, const PointXYZI& p); + }; + + + struct EIGEN_ALIGN16 _PointXYZL + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + uint32_t label; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZL& p); + struct PointXYZL : public _PointXYZL + { + inline PointXYZL (const _PointXYZL &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + label = p.label; + } + + inline PointXYZL () + { + x = y = z = 0.0f; + data[3] = 1.0f; + label = 0; + } + + friend std::ostream& operator << (std::ostream& os, const PointXYZL& p); + }; + + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Label& p); + struct Label + { + uint32_t label; + + friend std::ostream& operator << (std::ostream& os, const Label& p); + }; + + + struct EIGEN_ALIGN16 _PointXYZRGBA + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_RGB; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZRGBA& p); + /** \brief A point structure representing Euclidean xyz coordinates, and the RGBA color. + * + * The RGBA information is available either as separate r, g, b, or as a + * packed uint32_t rgba value. To pack it, use: + * + * \code + * int rgb = ((int)r) << 16 | ((int)g) << 8 | ((int)b); + * \endcode + * + * To unpack it use: + * + * \code + * int rgb = ...; + * uint8_t r = (rgb >> 16) & 0x0000ff; + * uint8_t g = (rgb >> 8) & 0x0000ff; + * uint8_t b = (rgb) & 0x0000ff; + * \endcode + * + * \ingroup common + */ + struct EIGEN_ALIGN16 PointXYZRGBA : public _PointXYZRGBA + { + inline PointXYZRGBA (const _PointXYZRGBA &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + rgba = p.rgba; + } + + inline PointXYZRGBA () + { + x = y = z = 0.0f; + data[3] = 1.0f; + r = g = b = 0; + a = 255; + } + + friend std::ostream& operator << (std::ostream& os, const PointXYZRGBA& p); + }; + + + struct EIGEN_ALIGN16 _PointXYZRGB + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_RGB; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + struct EIGEN_ALIGN16 _PointXYZRGBL + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_RGB; + uint32_t label; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZRGB& p); + /** \brief A point structure representing Euclidean xyz coordinates, and the RGB color. + * + * Due to historical reasons (PCL was first developed as a ROS package), the + * RGB information is packed into an integer and casted to a float. This is + * something we wish to remove in the near future, but in the meantime, the + * following code snippet should help you pack and unpack RGB colors in your + * PointXYZRGB structure: + * + * \code + * // pack r/g/b into rgb + * uint8_t r = 255, g = 0, b = 0; // Example: Red color + * uint32_t rgb = ((uint32_t)r << 16 | (uint32_t)g << 8 | (uint32_t)b); + * p.rgb = *reinterpret_cast(&rgb); + * \endcode + * + * To unpack the data into separate values, use: + * + * \code + * PointXYZRGB p; + * // unpack rgb into r/g/b + * uint32_t rgb = *reinterpret_cast(&p.rgb); + * uint8_t r = (rgb >> 16) & 0x0000ff; + * uint8_t g = (rgb >> 8) & 0x0000ff; + * uint8_t b = (rgb) & 0x0000ff; + * \endcode + * + * + * Alternatively, from 1.1.0 onwards, you can use p.r, p.g, and p.b directly. + * + * \ingroup common + */ + struct EIGEN_ALIGN16 PointXYZRGB : public _PointXYZRGB + { + inline PointXYZRGB (const _PointXYZRGB &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + rgb = p.rgb; + } + + inline PointXYZRGB () + { + x = y = z = 0.0f; + data[3] = 1.0f; + r = g = b = a = 0; + } + inline PointXYZRGB (uint8_t _r, uint8_t _g, uint8_t _b) + { + x = y = z = 0.0f; + data[3] = 1.0f; + r = _r; + g = _g; + b = _b; + a = 0; + } + + friend std::ostream& operator << (std::ostream& os, const PointXYZRGB& p); + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZRGBL& p); + struct EIGEN_ALIGN16 PointXYZRGBL : public _PointXYZRGBL + { + inline PointXYZRGBL (const _PointXYZRGBL &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + rgba = p.rgba; + label = p.label; + } + + inline PointXYZRGBL () + { + x = y = z = 0.0f; + data[3] = 1.0f; + r = g = b = 0; + a = 0; + label = 255; + } + inline PointXYZRGBL (uint8_t _r, uint8_t _g, uint8_t _b, uint32_t _label) + { + x = y = z = 0.0f; + data[3] = 1.0f; + r = _r; + g = _g; + b = _b; + a = 0; + label = _label; + } + + friend std::ostream& operator << (std::ostream& os, const PointXYZRGBL& p); + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + + struct _PointXYZHSV + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + union + { + struct + { + float h; + float s; + float v; + }; + float data_c[4]; + }; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + } EIGEN_ALIGN16; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZHSV& p); + struct EIGEN_ALIGN16 PointXYZHSV : public _PointXYZHSV + { + inline PointXYZHSV (const _PointXYZHSV &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + h = p.h; s = p.s; v = p.v; + } + + inline PointXYZHSV () + { + x = y = z = 0.0f; + data[3] = 1.0f; + h = s = v = data_c[3] = 0; + } + inline PointXYZHSV (float _h, float _v, float _s) + { + x = y = z = 0.0f; + data[3] = 1.0f; + h = _h; v = _v; s = _s; + data_c[3] = 0; + } + + friend std::ostream& operator << (std::ostream& os, const PointXYZHSV& p); + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXY& p); + /** \brief A 2D point structure representing Euclidean xy coordinates. + * \ingroup common + */ + struct PointXY + { + float x; + float y; + + friend std::ostream& operator << (std::ostream& os, const PointXY& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointUV& p); + /** \brief A 2D point structure representing pixel image coordinates. + * \note We use float to be able to represent subpixels. + * \ingroup common + */ + struct PointUV + { + float u; + float v; + + friend std::ostream& operator << (std::ostream& os, const PointUV& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const InterestPoint& p); + /** \brief A point structure representing an interest point with Euclidean xyz coordinates, and an interest value. + * \ingroup common + */ + struct EIGEN_ALIGN16 InterestPoint + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + union + { + struct + { + float strength; + }; + float data_c[4]; + }; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + friend std::ostream& operator << (std::ostream& os, const InterestPoint& p); + }; + + struct EIGEN_ALIGN16 _Normal + { + PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) + union + { + struct + { + float curvature; + }; + float data_c[4]; + }; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Normal& p); + /** \brief A point structure representing normal coordinates and the surface curvature estimate. (SSE friendly) + * \ingroup common + */ + struct Normal : public _Normal + { + inline Normal (const _Normal &p) + { + normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z; + data_n[3] = 0.0f; + curvature = p.curvature; + } + + inline Normal () + { + normal_x = normal_y = normal_z = data_n[3] = 0.0f; + curvature = 0; + } + + inline Normal (float n_x, float n_y, float n_z) + { + normal_x = n_x; normal_y = n_y; normal_z = n_z; + curvature = 0; + data_n[3] = 0.0f; + } + + friend std::ostream& operator << (std::ostream& os, const Normal& p); + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + + struct EIGEN_ALIGN16 _Axis + { + PCL_ADD_NORMAL4D; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Axis& p); + /** \brief A point structure representing an Axis using its normal coordinates. (SSE friendly) + * \ingroup common + */ + struct EIGEN_ALIGN16 Axis : public _Axis + { + inline Axis (const _Axis &p) + { + normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z; + data_n[3] = 0.0f; + } + + inline Axis () + { + normal_x = normal_y = normal_z = data_n[3] = 0.0f; + } + + inline Axis (float n_x, float n_y, float n_z) + { + normal_x = n_x; normal_y = n_y; normal_z = n_z; + data_n[3] = 0.0f; + } + + friend std::ostream& operator << (std::ostream& os, const Axis& p); + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + + struct EIGEN_ALIGN16 _PointNormal + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) + union + { + struct + { + float curvature; + }; + float data_c[4]; + }; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointNormal& p); + /** \brief A point structure representing Euclidean xyz coordinates, together with normal coordinates and the surface curvature estimate. (SSE friendly) + * \ingroup common + */ + struct PointNormal : public _PointNormal + { + inline PointNormal (const _PointNormal &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z; data_n[3] = 0.0f; + curvature = p.curvature; + } + + inline PointNormal () + { + x = y = z = 0.0f; + data[3] = 1.0f; + normal_x = normal_y = normal_z = data_n[3] = 0.0f; + } + + friend std::ostream& operator << (std::ostream& os, const PointNormal& p); + }; + + + struct EIGEN_ALIGN16 _PointXYZRGBNormal + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) + union + { + struct + { + PCL_ADD_UNION_RGB; + float curvature; + }; + float data_c[4]; + }; + PCL_ADD_EIGEN_MAPS_RGB; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZRGBNormal& p); + /** \brief A point structure representing Euclidean xyz coordinates, and the RGB color, together with normal coordinates and the surface curvature estimate. + * Due to historical reasons (PCL was first developed as a ROS package), the + * RGB information is packed into an integer and casted to a float. This is + * something we wish to remove in the near future, but in the meantime, the + * following code snippet should help you pack and unpack RGB colors in your + * PointXYZRGB structure: + * + * \code + * // pack r/g/b into rgb + * uint8_t r = 255, g = 0, b = 0; // Example: Red color + * uint32_t rgb = ((uint32_t)r << 16 | (uint32_t)g << 8 | (uint32_t)b); + * p.rgb = *reinterpret_cast(&rgb); + * \endcode + * + * To unpack the data into separate values, use: + * + * \code + * PointXYZRGB p; + * // unpack rgb into r/g/b + * uint32_t rgb = *reinterpret_cast(&p.rgb); + * uint8_t r = (rgb >> 16) & 0x0000ff; + * uint8_t g = (rgb >> 8) & 0x0000ff; + * uint8_t b = (rgb) & 0x0000ff; + * \endcode + * + * + * Alternatively, from 1.1.0 onwards, you can use p.r, p.g, and p.b directly. + * \ingroup common + */ + struct PointXYZRGBNormal : public _PointXYZRGBNormal + { + inline PointXYZRGBNormal (const _PointXYZRGBNormal &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z; data_n[3] = 0.0f; + curvature = p.curvature; + rgba = p.rgba; + } + + inline PointXYZRGBNormal () + { + x = y = z = 0.0f; + data[3] = 1.0f; + r = g = b = a = 0; + normal_x = normal_y = normal_z = data_n[3] = 0.0f; + curvature = 0; + } + + friend std::ostream& operator << (std::ostream& os, const PointXYZRGBNormal& p); + }; + + struct EIGEN_ALIGN16 _PointXYZINormal + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) + union + { + struct + { + float intensity; + float curvature; + }; + float data_c[4]; + }; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZINormal& p); + /** \brief A point structure representing Euclidean xyz coordinates, intensity, together with normal coordinates and the surface curvature estimate. + * \ingroup common + */ + struct PointXYZINormal : public _PointXYZINormal + { + inline PointXYZINormal (const _PointXYZINormal &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + normal_x = p.normal_x; normal_y = p.normal_y; normal_z = p.normal_z; data_n[3] = 0.0f; + curvature = p.curvature; + intensity = p.intensity; + } + + inline PointXYZINormal () + { + x = y = z = 0.0f; + data[3] = 1.0f; + normal_x = normal_y = normal_z = data_n[3] = 0.0f; + intensity = 0.0f; + } + + friend std::ostream& operator << (std::ostream& os, const PointXYZINormal& p); + }; + + + struct EIGEN_ALIGN16 _PointWithRange + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + union + { + struct + { + float range; + }; + float data_c[4]; + }; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointWithRange& p); + /** \brief A point structure representing Euclidean xyz coordinates, padded with an extra range float. + * \ingroup common + */ + struct PointWithRange : public _PointWithRange + { + inline PointWithRange (const _PointWithRange &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + range = p.range; + } + + inline PointWithRange () + { + x = y = z = 0.0f; + data[3] = 1.0f; + range = 0.0f; + } + + friend std::ostream& operator << (std::ostream& os, const PointWithRange& p); + }; + + + struct EIGEN_ALIGN16 _PointWithViewpoint + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + union + { + struct + { + float vp_x; + float vp_y; + float vp_z; + }; + float data_c[4]; + }; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointWithViewpoint& p); + /** \brief A point structure representing Euclidean xyz coordinates together with the viewpoint from which it was seen. + * \ingroup common + */ + struct EIGEN_ALIGN16 PointWithViewpoint : public _PointWithViewpoint + { + inline PointWithViewpoint (const _PointWithViewpoint &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + vp_x = p.vp_x; vp_y = p.vp_y; vp_z = p.vp_z; + } + + inline PointWithViewpoint (float _x = 0.0f, float _y = 0.0f, float _z = 0.0f, + float _vp_x = 0.0f, float _vp_y = 0.0f, float _vp_z = 0.0f) + { + x = _x; y = _y; z = _z; + data[3] = 1.0f; + vp_x = _vp_x; vp_y = _vp_y; vp_z = _vp_z; + } + + friend std::ostream& operator << (std::ostream& os, const PointWithViewpoint& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const MomentInvariants& p); + /** \brief A point structure representing the three moment invariants. + * \ingroup common + */ + struct MomentInvariants + { + float j1, j2, j3; + + friend std::ostream& operator << (std::ostream& os, const MomentInvariants& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PrincipalRadiiRSD& p); + /** \brief A point structure representing the minimum and maximum surface radii (in meters) computed using RSD. + * \ingroup common + */ + struct PrincipalRadiiRSD + { + float r_min, r_max; + + friend std::ostream& operator << (std::ostream& os, const PrincipalRadiiRSD& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Boundary& p); + /** \brief A point structure representing a description of whether a point is lying on a surface boundary or not. + * \ingroup common + */ + struct Boundary + { + uint8_t boundary_point; + +#if defined(_LIBCPP_VERSION) && _LIBCPP_VERSION <= 1101 + operator unsigned char() const + { + return boundary_point; + } +#endif + + friend std::ostream& operator << (std::ostream& os, const Boundary& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PrincipalCurvatures& p); + /** \brief A point structure representing the principal curvatures and their magnitudes. + * \ingroup common + */ + struct PrincipalCurvatures + { + union + { + float principal_curvature[3]; + struct + { + float principal_curvature_x; + float principal_curvature_y; + float principal_curvature_z; + }; + }; + float pc1; + float pc2; + + friend std::ostream& operator << (std::ostream& os, const PrincipalCurvatures& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PFHSignature125& p); + /** \brief A point structure representing the Point Feature Histogram (PFH). + * \ingroup common + */ + struct PFHSignature125 + { + float histogram[125]; + static int descriptorSize () { return 125; } + + friend std::ostream& operator << (std::ostream& os, const PFHSignature125& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PFHRGBSignature250& p); + /** \brief A point structure representing the Point Feature Histogram with colors (PFHRGB). + * \ingroup common + */ + struct PFHRGBSignature250 + { + float histogram[250]; + static int descriptorSize () { return 250; } + + friend std::ostream& operator << (std::ostream& os, const PFHRGBSignature250& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PPFSignature& p); + /** \brief A point structure for storing the Point Pair Feature (PPF) values + * \ingroup common + */ + struct PPFSignature + { + float f1, f2, f3, f4; + float alpha_m; + + friend std::ostream& operator << (std::ostream& os, const PPFSignature& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const CPPFSignature& p); + /** \brief A point structure for storing the Point Pair Feature (CPPF) values + * \ingroup common + */ + struct CPPFSignature + { + float f1, f2, f3, f4, f5, f6, f7, f8, f9, f10; + float alpha_m; + + friend std::ostream& operator << (std::ostream& os, const CPPFSignature& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PPFRGBSignature& p); + /** \brief A point structure for storing the Point Pair Color Feature (PPFRGB) values + * \ingroup common + */ + struct PPFRGBSignature + { + float f1, f2, f3, f4; + float r_ratio, g_ratio, b_ratio; + float alpha_m; + + friend std::ostream& operator << (std::ostream& os, const PPFRGBSignature& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const NormalBasedSignature12& p); + /** \brief A point structure representing the Normal Based Signature for + * a feature matrix of 4-by-3 + * \ingroup common + */ + struct NormalBasedSignature12 + { + float values[12]; + + friend std::ostream& operator << (std::ostream& os, const NormalBasedSignature12& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const ShapeContext1980& p); + /** \brief A point structure representing a Shape Context. + * \ingroup common + */ + struct ShapeContext1980 + { + float descriptor[1980]; + float rf[9]; + static int descriptorSize () { return 1980; } + + friend std::ostream& operator << (std::ostream& os, const ShapeContext1980& p); + }; + + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const SHOT352& p); + /** \brief A point structure representing the generic Signature of Histograms of OrienTations (SHOT) - shape only. + * \ingroup common + */ + struct SHOT352 + { + // hack + float data[3]; + float descriptor[352]; + float rf[9]; + static int descriptorSize () { return 352; } + + friend std::ostream& operator << (std::ostream& os, const SHOT352& p); + }; + + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const SHOT1344& p); + /** \brief A point structure representing the generic Signature of Histograms of OrienTations (SHOT) - shape+color. + * \ingroup common + */ + struct SHOT1344 + { + float descriptor[1344]; + float rf[9]; + static int descriptorSize () { return 1344; } + + friend std::ostream& operator << (std::ostream& os, const SHOT1344& p); + }; + + + /** \brief A structure representing the Local Reference Frame of a point. + * \ingroup common + */ + struct EIGEN_ALIGN16 _ReferenceFrame + { + union + { + float rf[9]; + struct + { + float x_axis[3]; + float y_axis[3]; + float z_axis[3]; + }; + }; + + inline Eigen::Map getXAxisVector3fMap () { return (Eigen::Vector3f::Map (x_axis)); } + inline const Eigen::Map getXAxisVector3fMap () const { return (Eigen::Vector3f::Map (x_axis)); } + inline Eigen::Map getYAxisVector3fMap () { return (Eigen::Vector3f::Map (y_axis)); } + inline const Eigen::Map getYAxisVector3fMap () const { return (Eigen::Vector3f::Map (y_axis)); } + inline Eigen::Map getZAxisVector3fMap () { return (Eigen::Vector3f::Map (z_axis)); } + inline const Eigen::Map getZAxisVector3fMap () const { return (Eigen::Vector3f::Map (z_axis)); } + inline Eigen::Map getMatrix3fMap () { return (Eigen::Matrix3f::Map (rf)); } + inline const Eigen::Map getMatrix3fMap () const { return (Eigen::Matrix3f::Map (rf)); } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const ReferenceFrame& p); + struct EIGEN_ALIGN16 ReferenceFrame : public _ReferenceFrame + { + inline ReferenceFrame (const _ReferenceFrame &p) + { + for (int d = 0; d < 9; ++d) + rf[d] = p.rf[d]; + } + + inline ReferenceFrame () + { + for (int d = 0; d < 3; ++d) + x_axis[d] = y_axis[d] = z_axis[d] = 0; + } + + friend std::ostream& operator << (std::ostream& os, const ReferenceFrame& p); + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const FPFHSignature33& p); + /** \brief A point structure representing the Fast Point Feature Histogram (FPFH). + * \ingroup common + */ + struct FPFHSignature33 + { + /* hack */ + float data[3]; + float histogram[33]; + static int descriptorSize () { return 33; } + + friend std::ostream& operator << (std::ostream& os, const FPFHSignature33& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const VFHSignature308& p); + /** \brief A point structure representing the Viewpoint Feature Histogram (VFH). + * \ingroup common + */ + struct VFHSignature308 + { + float histogram[308]; + static int descriptorSize () { return 308; } + + friend std::ostream& operator << (std::ostream& os, const VFHSignature308& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const ESFSignature640& p); + /** \brief A point structure representing the Ensemble of Shape Functions (ESF). + * \ingroup common + */ + struct ESFSignature640 + { + float histogram[640]; + static int descriptorSize () { return 640; } + + friend std::ostream& operator << (std::ostream& os, const ESFSignature640& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const GFPFHSignature16& p); + /** \brief A point structure representing the GFPFH descriptor with 16 bins. + * \ingroup common + */ + struct GFPFHSignature16 + { + float histogram[16]; + static int descriptorSize () { return 16; } + + friend std::ostream& operator << (std::ostream& os, const GFPFHSignature16& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Narf36& p); + /** \brief A point structure representing the Narf descriptor. + * \ingroup common + */ + struct Narf36 + { + float x, y, z, roll, pitch, yaw; + float descriptor[36]; + static int descriptorSize () { return 36; } + + friend std::ostream& operator << (std::ostream& os, const Narf36& p); + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const BorderDescription& p); + /** \brief A structure to store if a point in a range image lies on a border between an obstacle and the background. + * \ingroup common + */ + struct BorderDescription + { + int x, y; + BorderTraits traits; + //std::vector neighbors; + + friend std::ostream& operator << (std::ostream& os, const BorderDescription& p); + }; + + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const IntensityGradient& p); + /** \brief A point structure representing the intensity gradient of an XYZI point cloud. + * \ingroup common + */ + struct IntensityGradient + { + union + { + float gradient[3]; + struct + { + float gradient_x; + float gradient_y; + float gradient_z; + }; + }; + + friend std::ostream& operator << (std::ostream& os, const IntensityGradient& p); + }; + + /** \brief A point structure representing an N-D histogram. + * \ingroup common + */ + template + struct Histogram + { + float histogram[N]; + static int descriptorSize () { return N; } + }; + + struct EIGEN_ALIGN16 _PointWithScale + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + + union + { + /** \brief Diameter of the meaningfull keypoint neighborhood. */ + float scale; + float size; + }; + + /** \brief Computed orientation of the keypoint (-1 if not applicable). */ + float angle; + /** \brief The response by which the most strong keypoints have been selected. */ + float response; + /** \brief octave (pyramid layer) from which the keypoint has been extracted. */ + int octave; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointWithScale& p); + /** \brief A point structure representing a 3-D position and scale. + * \ingroup common + */ + struct PointWithScale : public _PointWithScale + { + inline PointWithScale (const _PointWithScale &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + scale = p.scale; + angle = p.angle; + response = p.response; + octave = p.octave; + } + + inline PointWithScale () + { + x = y = z = 0.0f; + scale = 1.0f; + angle = -1.0f; + response = 0.0f; + octave = 0; + data[3] = 1.0f; + } + + inline PointWithScale (float _x, float _y, float _z, float _scale) + { + x = _x; + y = _y; + z = _z; + scale = _scale; + angle = -1.0f; + response = 0.0f; + octave = 0; + data[3] = 1.0f; + } + + inline PointWithScale (float _x, float _y, float _z, float _scale, float _angle, float _response, int _octave) + { + x = _x; + y = _y; + z = _z; + scale = _scale; + angle = _angle; + response = _response; + octave = _octave; + data[3] = 1.0f; + } + + friend std::ostream& operator << (std::ostream& os, const PointWithScale& p); + }; + + + struct EIGEN_ALIGN16 _PointSurfel + { + PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) + union + { + struct + { + PCL_ADD_UNION_RGB; + float radius; + float confidence; + float curvature; + }; + float data_c[4]; + }; + PCL_ADD_EIGEN_MAPS_RGB; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointSurfel& p); + /** \brief A surfel, that is, a point structure representing Euclidean xyz coordinates, together with normal coordinates, a RGBA color, a radius, a confidence value and the surface curvature estimate. + * \ingroup common + */ + struct PointSurfel : public _PointSurfel + { + inline PointSurfel (const _PointSurfel &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + rgba = p.rgba; + radius = p.radius; + confidence = p.confidence; + curvature = p.curvature; + } + + inline PointSurfel () + { + x = y = z = 0.0f; + data[3] = 1.0f; + normal_x = normal_y = normal_z = data_n[3] = 0.0f; + rgba = 0; + radius = confidence = curvature = 0.0f; + } + + friend std::ostream& operator << (std::ostream& os, const PointSurfel& p); + }; + + template std::ostream& + operator << (std::ostream& os, const Histogram& p) + { + for (int i = 0; i < N; ++i) + os << (i == 0 ? "(" : "") << p.histogram[i] << (i < N-1 ? ", " : ")"); + return (os); + } +} // End namespace + +// Preserve API for PCL users < 1.4 +#include + +#endif diff --git a/pcl-1.7/pcl/in_hand_scanner/boost.h b/pcl-1.7/pcl/in_hand_scanner/boost.h new file mode 100644 index 0000000..8314cd0 --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/boost.h @@ -0,0 +1,59 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_APPS_IN_HAND_SCANNER_BOOST_H +#define PCL_APPS_IN_HAND_SCANNER_BOOST_H + +#ifdef __GNUC__ +# pragma GCC system_header +#endif + +#include +#include +#include +#include +#include +#include +//#include +#include +#include +#include + +#endif // PCL_APPS_IN_HAND_SCANNER_BOOST_H diff --git a/pcl-1.7/pcl/in_hand_scanner/common_types.h b/pcl-1.7/pcl/in_hand_scanner/common_types.h new file mode 100644 index 0000000..1dbb520 --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/common_types.h @@ -0,0 +1,97 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_APPS_IN_HAND_SCANNER_COMMON_TYPES_H +#define PCL_APPS_IN_HAND_SCANNER_COMMON_TYPES_H + +#include + +#include +#include +#include + +namespace pcl +{ + namespace ihs + { + struct PointIHS; + typedef pcl::PointCloud CloudIHS; + typedef CloudIHS::Ptr CloudIHSPtr; + typedef CloudIHS::ConstPtr CloudIHSConstPtr; + } // End namespace ihs +} // End namespace pcl + +#include + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::ihs::_PointIHS, + (float, x, x) + (float, y, y) + (float, z, z) + (float, normal_x, normal_x) + (float, normal_y, normal_y) + (float, normal_z, normal_z) + (float, rgb, rgb) + (float, weight, weight) + (unsigned int, age, age) + (uint32_t, directions, directions) + ) +POINT_CLOUD_REGISTER_POINT_WRAPPER (pcl::ihs::PointIHS, pcl::ihs::_PointIHS) + +namespace pcl +{ + namespace ihs + { + struct MeshTraits + { + typedef PointIHS VertexData; + typedef pcl::geometry::NoData HalfEdgeData; + typedef pcl::geometry::NoData EdgeData; + typedef pcl::geometry::NoData FaceData; + typedef boost::true_type IsManifold; + }; + + // NOTE: The drawMesh method in pcl::ihs::InHandScanner only supports triangles! + typedef pcl::geometry::TriangleMesh Mesh; + typedef Mesh::Ptr MeshPtr; + typedef Mesh::ConstPtr MeshConstPtr; + } // End namespace ihs +} // End namespace pcl + +#endif // PCL_APPS_IN_HAND_SCANNER_COMMON_TYPES_H diff --git a/pcl-1.7/pcl/in_hand_scanner/eigen.h b/pcl-1.7/pcl/in_hand_scanner/eigen.h new file mode 100644 index 0000000..9b42bed --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/eigen.h @@ -0,0 +1,52 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_APPS_IN_HAND_SCANNER_EIGEN_H +#define PCL_APPS_IN_HAND_SCANNER_EIGEN_H + +#ifdef __GNUC__ +# pragma GCC system_header +#endif + +#include +#include +#include + +#endif // PCL_APPS_IN_HAND_SCANNER_EIGEN_H diff --git a/pcl-1.7/pcl/in_hand_scanner/help_window.h b/pcl-1.7/pcl/in_hand_scanner/help_window.h new file mode 100644 index 0000000..9525426 --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/help_window.h @@ -0,0 +1,70 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + + +#ifndef PCL_APPS_IN_HAND_SCANNER_HELP_WINDOW_H +#define PCL_APPS_IN_HAND_SCANNER_HELP_WINDOW_H + +#include + +namespace Ui +{ + class HelpWindow; +} + +namespace pcl +{ + namespace ihs + { + class HelpWindow : public QDialog + { + Q_OBJECT + + public: + explicit HelpWindow (QWidget* parent = 0); + ~HelpWindow (); + + private: + Ui::HelpWindow* ui; + }; + } // End namespace ihs +} // End namespace pcl + +#endif // PCL_APPS_IN_HAND_SCANNER_HELP_WINDOW_H diff --git a/pcl-1.7/pcl/in_hand_scanner/icp.h b/pcl-1.7/pcl/in_hand_scanner/icp.h new file mode 100644 index 0000000..e5db6c1 --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/icp.h @@ -0,0 +1,225 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_APPS_IN_HAND_SCANNER_ICP_H +#define PCL_APPS_IN_HAND_SCANNER_ICP_H + +#include +#include +#include +#include + +//////////////////////////////////////////////////////////////////////////////// +// Forward declarations +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + template + class KdTree; +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// ICP +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace ihs + { + /** \brief Iterative Closest Point registration. + * \author Martin Saelzle + * \ingroup apps + */ + class PCL_EXPORTS ICP + { + public: + + typedef pcl::PointXYZRGBNormal PointXYZRGBNormal; + typedef pcl::PointCloud CloudXYZRGBNormal; + typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr; + typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr; + + typedef pcl::ihs::Mesh Mesh; + typedef pcl::ihs::MeshPtr MeshPtr; + typedef pcl::ihs::MeshConstPtr MeshConstPtr; + + /** \brief Constructor */ + ICP (); + + /** @{ */ + /** \brief Convergence is detected when the change of the fitness between the current and previous iteration becomes smaller than the given epsilon (set in cm^2). The fitness is the mean squared euclidean distance between corresponding points. + * \note Only accepted if it is greater than 0. + */ + void + setEpsilon (const float epsilon); + + float + getEpsilon () const; + /** @} */ + + /** @{ */ + /** \brief The registration fails if the number of iterations exceeds the maximum number of iterations. + * \note Must be greater than 0. Smaller values are set to 1. + */ + void + setMaxIterations (const unsigned int max_iter); + + unsigned int + getMaxIterations () const; + /** @} */ + + /** @{ */ + /** \brief The registration fails at the state of convergence if the overlap between the model and data shape is smaller than a minimum overlap. The overlap is the fraction of correspondences (after rejection) to the initial number of data points. + * \note Must be between zero and one. Values outside this range are clamped to the nearest valid value. + */ + void + setMinOverlap (const float overlap); + + float + getMinOverlap () const; + /** @} */ + + /** @{ */ + /** \brief The registration fails at the state of convergence if the fitness is bigger than this threshold (set in cm^2) + * \note Must be greater than zero. + */ + void + setMaxFitness (const float fitness); + + float + getMaxFitness () const; + /** @} */ + + /** @{ */ + /** \brief Correspondences are rejected if the squared distance is above a threshold. This threshold is initialized with infinity (all correspondences are accepted in the first iteration). The threshold of the next iterations is set to the fitness of the current iteration multiplied by the factor set by this method. + * \note Must be greater or equal one. Smaller values are set to one. + */ + void + setCorrespondenceRejectionFactor (const float factor); + + float + getCorrespondenceRejectionFactor () const; + /** @} */ + + /** @{ */ + /** \brief Correspondences are rejected if the angle between the normals is bigger than this threshold. Set in degrees. + * \note Must be between 180 degrees and 0. Values outside this range are clamped to the nearest valid value. + */ + void + setMaxAngle (const float angle); + + float + getMaxAngle () const; + /** @} */ + + /** \brief Find the transformation that aligns the data cloud (source) to the model mesh (target). + * \param[in] mesh_model Model mesh (target). + * \param[in] cloud_data Data cloud (source). + * \param[in] T_init Initial guess for the transformation. + * \paran[out] T_final The computed transformation. + * \return true if success. + */ + bool + findTransformation (const MeshConstPtr& mesh_model, + const CloudXYZRGBNormalConstPtr& cloud_data, + const Eigen::Matrix4f& T_init, + Eigen::Matrix4f& T_final); + + private: + + typedef pcl::PointNormal PointNormal; + typedef pcl::PointCloud CloudNormal; + typedef CloudNormal::Ptr CloudNormalPtr; + typedef CloudNormal::ConstPtr CloudNormalConstPtr; + + typedef pcl::KdTree KdTree; + typedef boost::shared_ptr KdTreePtr; + typedef boost::shared_ptr KdTreeConstPtr; + + /** \brief Selects the model points that are pointing towards to the camera (data coordinate system = camera coordinate system). + * \param[in] mesh_model Input mesh. + * \param[in] T_inv Transformation that brings the model mesh into the camera coordinate system. + * \return Cloud containing the selected points (the connectivity information of the mesh is currently not used during the registration). + */ + CloudNormalConstPtr + selectModelPoints (const MeshConstPtr& mesh_model, + const Eigen::Matrix4f& T_inv) const; + + /** \brief Selects the valid data points. The input cloud is organized -> contains nans which are removed + * \param[in] cloud_data Input cloud. + * \return Cloud containing the selected points. + */ + CloudNormalConstPtr + selectDataPoints (const CloudXYZRGBNormalConstPtr& cloud_data) const; + + /** \brief Finds the transformation that minimizes the point to plane distance from the source to the target cloud. The input clouds must be arranged to have one to one correspondences (point 0 in source corresponds to point 0 in target, point 1 in source to point 1 in target and so on). + * \param[in] cloud_source Source cloud (data). + * \param[in] cloud_target Target cloud (model). + * \param[out] T The computed transformation. + * \return true if success + */ + bool + minimizePointPlane (const CloudNormal& cloud_source, + const CloudNormal& cloud_target, + Eigen::Matrix4f& T) const; + + //////////////////////////////////////////////////////////////////////// + // Members + //////////////////////////////////////////////////////////////////////// + + KdTreePtr kd_tree_; + + // Convergence + float epsilon_; // in cm^2 + + // Registration failure + unsigned int max_iterations_; + float min_overlap_; // [0 1] + float max_fitness_; // in cm^2 + + // Correspondence rejection + float factor_; + float max_angle_; // in degrees + }; + } // End namespace ihs +} // End namespace pcl + +#endif // PCL_APPS_IN_HAND_SCANNER_ICP_H diff --git a/pcl-1.7/pcl/in_hand_scanner/impl/common_types.hpp b/pcl-1.7/pcl/in_hand_scanner/impl/common_types.hpp new file mode 100644 index 0000000..1dab37a --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/impl/common_types.hpp @@ -0,0 +1,127 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_APPS_IN_HAND_SCANNER_IMPL_COMMON_TYPES_HPP +#define PCL_APPS_IN_HAND_SCANNER_IMPL_COMMON_TYPES_HPP + +#include + +namespace pcl +{ + namespace ihs + { + struct EIGEN_ALIGN16 _PointIHS + { + PCL_ADD_POINT4D + PCL_ADD_NORMAL4D + PCL_ADD_RGB + float weight; + unsigned int age; + uint32_t directions; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + struct PointIHS : public pcl::ihs::_PointIHS + { + // NOTE: I rely on NaN in the default constructor! + inline PointIHS () + { + this->x = this->y = this->z = std::numeric_limits::quiet_NaN (); + this->data[3] = 1.f; + + this->normal_x = this->normal_y = this->normal_z = std::numeric_limits::quiet_NaN (); + this->data_n[3] = 0.f; + + this->b = this->g = this->r = 0; this->a = 255; + + this->weight = 0.f; + this->age = 0; + this->directions = 0; + } + + inline PointIHS (const PointIHS& other) + { + this->x = other.x; + this->y = other.y; + this->z = other.z; + this->data[3] = other.data[3]; + + this->normal_x = other.normal_x; + this->normal_y = other.normal_y; + this->normal_z = other.normal_z; + this->data_n[3] = other.data_n[3]; + + this->rgba = other.rgba; + + this->weight = other.weight; + this->age = other.age; + this->directions = other.directions; + } + + inline PointIHS (const pcl::PointXYZRGBNormal& other, const float weight) + { + this->x = other.x; + this->y = other.y; + this->z = other.z; + this->data[3] = other.data[3]; + + this->normal_x = other.normal_x; + this->normal_y = other.normal_y; + this->normal_z = other.normal_z; + this->data_n[3] = other.data_n[3]; + + this->rgba = other.rgba; + + this->weight = weight; + this->age = 0; + this->directions = 0; + } + + // inline Eigen::Vector3i getRGBVector3i () {return (Eigen::Vector3i (r, g, b));} + inline const Eigen::Vector3i getRGBVector3i () const {return (Eigen::Vector3i (r, g, b));} + // inline Eigen::Vector4i getRGBVector4i () {return (Eigen::Vector4i (r, g, b, a));} + inline const Eigen::Vector4i getRGBVector4i () const {return (Eigen::Vector4i (r, g, b, a));} + }; + + } // End namespace ihs +} // End namespace pcl + +#endif // PCL_APPS_IN_HAND_SCANNER_IMPL_COMMON_TYPES_HPP diff --git a/pcl-1.7/pcl/in_hand_scanner/in_hand_scanner.h b/pcl-1.7/pcl/in_hand_scanner/in_hand_scanner.h new file mode 100644 index 0000000..f7f4ae6 --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/in_hand_scanner.h @@ -0,0 +1,311 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_APPS_IN_HAND_SCANNER_IN_HAND_SCANNER_H +#define PCL_APPS_IN_HAND_SCANNER_IN_HAND_SCANNER_H + +#include +#include +#include + +#include +#include +#include +#include + +//////////////////////////////////////////////////////////////////////////////// +// Forward declarations +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + class OpenNIGrabber; + + namespace ihs + { + class ICP; + class InputDataProcessing; + class Integration; + class MeshProcessing; + } // End namespace ihs +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// InHandScanner +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace ihs + { + /** \brief + * \todo Add Documentation + */ + class PCL_EXPORTS InHandScanner : public pcl::ihs::OpenGLViewer + { + Q_OBJECT + + public: + + typedef pcl::ihs::OpenGLViewer Base; + typedef pcl::ihs::InHandScanner Self; + + typedef pcl::ihs::InputDataProcessing InputDataProcessing; + typedef boost::shared_ptr InputDataProcessingPtr; + typedef boost::shared_ptr InputDataProcessingConstPtr; + + typedef pcl::ihs::ICP ICP; + typedef boost::shared_ptr ICPPtr; + typedef boost::shared_ptr ICPConstPtr; + + typedef pcl::ihs::Integration Integration; + typedef boost::shared_ptr IntegrationPtr; + typedef boost::shared_ptr IntegrationConstPtr; + + typedef pcl::ihs::MeshProcessing MeshProcessing; + typedef boost::shared_ptr MeshProcessingPtr; + typedef boost::shared_ptr MeshProcessingConstPtr; + + /** \brief Switch between different branches of the scanning pipeline. */ + typedef enum RunningMode + { + RM_SHOW_MODEL = 0, /**< Shows the model shape (if it is available). */ + RM_UNPROCESSED = 1, /**< Shows the unprocessed input data. */ + RM_PROCESSED = 2, /**< Shows the processed input data. */ + RM_REGISTRATION_CONT = 3, /**< Registers new data to the first acquired data continuously. */ + RM_REGISTRATION_SINGLE = 4 /**< Registers new data once and returns to showing the processed data. */ + } RunningMode; + + /** \brief File type for saving and loading files. */ + typedef enum FileType + { + FT_PLY = 0, /**< Polygon File Format. */ + FT_VTK = 1 /**< VTK File Format. */ + } FileType; + + /** \brief Constructor. */ + explicit InHandScanner (Base* parent=0); + + /** \brief Destructor. */ + ~InHandScanner (); + + /** \brief Get the input data processing. */ + inline InputDataProcessing& + getInputDataProcessing () {return (*input_data_processing_);} + + /** \brief Get the registration. */ + inline ICP& + getICP () {return (*icp_);} + + /** \brief Get the integration. */ + inline Integration& + getIntegration () {return (*integration_);} + + signals: + + /** \brief Emitted when the running mode changes. */ + void + runningModeChanged (RunningMode new_running_mode) const; + + public slots: + + /** \brief Start the grabber (enables the scanning pipeline). */ + void + startGrabber (); + + /** \brief Shows the unprocessed input data. */ + void + showUnprocessedData (); + + /** \brief Shows the processed input data. */ + void + showProcessedData (); + + /** \brief Registers new data to the first acquired data continuously. */ + void + registerContinuously (); + + /** \brief Registers new data once and returns to showing the processed data. */ + void + registerOnce (); + + /** \brief Show the model shape (if one is available). */ + void + showModel (); + + /** \brief Removes unfit vertices regardless of their age. Unfit vertices are those that have not been observed from enough directions. */ + void + removeUnfitVertices (); + + /** \brief Reset the scanning pipeline. */ + void + reset (); + + /** \brief Saves the model mesh in a file with the given filename and filetype. + * \note The extension of the filename is ignored! + */ + void + saveAs (const std::string& filename, const FileType& filetype); + + /** \see http://doc.qt.digia.com/qt/qwidget.html#keyPressEvent */ + void + keyPressEvent (QKeyEvent* event); + + private: + + typedef pcl::PointXYZRGBA PointXYZRGBA; + typedef pcl::PointCloud CloudXYZRGBA; + typedef CloudXYZRGBA::Ptr CloudXYZRGBAPtr; + typedef CloudXYZRGBA::ConstPtr CloudXYZRGBAConstPtr; + + typedef pcl::PointXYZRGBNormal PointXYZRGBNormal; + typedef pcl::PointCloud CloudXYZRGBNormal; + typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr; + typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr; + + typedef pcl::ihs::PointIHS PointIHS; + typedef pcl::ihs::CloudIHS CloudIHS; + typedef pcl::ihs::CloudIHSPtr CloudIHSPtr; + typedef pcl::ihs::CloudIHSConstPtr CloudIHSConstPtr; + + typedef pcl::ihs::Mesh Mesh; + typedef pcl::ihs::MeshPtr MeshPtr; + typedef pcl::ihs::MeshConstPtr MeshConstPtr; + + typedef pcl::OpenNIGrabber Grabber; + typedef boost::shared_ptr GrabberPtr; + typedef boost::shared_ptr GrabberConstPtr; + + /** \brief Helper object for the computation thread. Please have a look at the documentation of calcFPS. */ + class ComputationFPS : public Base::FPS + { + public: + ComputationFPS () : Base::FPS () {} + ~ComputationFPS () {} + }; + + /** \brief Helper object for the visualization thread. Please have a look at the documentation of calcFPS. */ + class VisualizationFPS : public Base::FPS + { + public: + VisualizationFPS () : Base::FPS () {} + ~VisualizationFPS () {} + }; + + /** \brief Called when new data arries from the grabber. The grabbing - registration - integration pipeline is implemented here. */ + void + newDataCallback (const CloudXYZRGBAConstPtr& cloud_in); + + /** \see http://doc.qt.digia.com/qt/qwidget.html#paintEvent + * \see http://doc.qt.digia.com/qt/opengl-overpainting.html + */ + void + paintEvent (QPaintEvent* event); + + /** \brief Draw text over the opengl scene. + * \see http://doc.qt.digia.com/qt/opengl-overpainting.html + */ + void + drawText (); + + /** \brief Actual implementeation of startGrabber (needed so it can be run in a different thread and doesn't block the application when starting up). */ + void + startGrabberImpl (); + + //////////////////////////////////////////////////////////////////////// + // Members + //////////////////////////////////////////////////////////////////////// + + /** \brief Synchronization. */ + boost::mutex mutex_; + + /** \brief Please have a look at the documentation of ComputationFPS. */ + ComputationFPS computation_fps_; + + /** \brief Please have a look at the documentation of VisualizationFPS. */ + VisualizationFPS visualization_fps_; + + /** \brief Switch between different branches of the scanning pipeline. */ + RunningMode running_mode_; + + /** \brief The iteration of the scanning pipeline (grab - register - integrate). */ + unsigned int iteration_; + + /** \brief Used to get new data from the sensor. */ + GrabberPtr grabber_; + + /** \brief This variable is true if the grabber is starting. */ + bool starting_grabber_; + + /** \brief Connection of the grabber signal with the data processing thread. */ + boost::signals2::connection new_data_connection_; + + /** \brief Processes the data from the sensor. Output is input to the registration. */ + InputDataProcessingPtr input_data_processing_; + + /** \brief Registration (Iterative Closest Point). */ + ICPPtr icp_; + + /** \brief Transformation that brings the data cloud into model coordinates. */ + Eigen::Matrix4f transformation_; + + /** \brief Integrate the data cloud into a common model. */ + IntegrationPtr integration_; + + /** \brief Methods called after the integration. */ + MeshProcessingPtr mesh_processing_; + + /** \brief Model to which new data is registered to (stored as a mesh). */ + MeshPtr mesh_model_; + + /** \brief Prevent the application to crash while closing. */ + bool destructor_called_; + + public: + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } // End namespace ihs +} // End namespace pcl + +// http://doc.qt.digia.com/qt/qmetatype.html#Q_DECLARE_METATYPE +Q_DECLARE_METATYPE (pcl::ihs::InHandScanner::RunningMode) + +#endif // PCL_APPS_IN_HAND_SCANNER_IN_HAND_SCANNER_H diff --git a/pcl-1.7/pcl/in_hand_scanner/input_data_processing.h b/pcl-1.7/pcl/in_hand_scanner/input_data_processing.h new file mode 100644 index 0000000..3da5d32 --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/input_data_processing.h @@ -0,0 +1,243 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_APPS_IN_HAND_SCANNER_INPUT_DATA_PROCESSING_H +#define PCL_APPS_IN_HAND_SCANNER_INPUT_DATA_PROCESSING_H + +#include +#include +#include +#include + +//////////////////////////////////////////////////////////////////////////////// +// Forward declarations +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + template + class IntegralImageNormalEstimation; +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// InputDataProcessing +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace ihs + { + /** \brief Bundles methods that are applied to the input data from the sensor. + * \author Martin Saelzle + * \ingroup apps + */ + class PCL_EXPORTS InputDataProcessing + { + public: + + typedef pcl::PointXYZRGBA PointXYZRGBA; + typedef pcl::PointCloud CloudXYZRGBA; + typedef CloudXYZRGBA::Ptr CloudXYZRGBAPtr; + typedef CloudXYZRGBA::ConstPtr CloudXYZRGBAConstPtr; + + typedef pcl::PointXYZRGBNormal PointXYZRGBNormal; + typedef pcl::PointCloud CloudXYZRGBNormal; + typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr; + typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr; + + /** \brief Constructor */ + InputDataProcessing (); + + /** \brief Apply the segmentation on the input cloud (XYZ and HSV). + * \param[in] cloud_in The input cloud. + * \param[out] cloud_out The segmented cloud. + * \param[out] cloud_discarded Cloud containing all points that were removed during the HSV segmentation. The points in the XYZ segmentation are NOT used! + * \return true if success. + * \note Converts from m to cm. + */ + bool + segment (const CloudXYZRGBAConstPtr& cloud_in, + CloudXYZRGBNormalPtr& cloud_out, + CloudXYZRGBNormalPtr& cloud_discarded) const; + + /** \brief Calculate the normals of the input cloud. + * \param[in] cloud_in The input cloud. + * \param[out] cloud_out Input cloud with normals appended. + * \return true if success. + * \note Converts from m to cm. + */ + bool + calculateNormals (const CloudXYZRGBAConstPtr& cloud_in, + CloudXYZRGBNormalPtr& cloud_out) const; + + /** @{ */ + /** \brief Points outside of X - Y - Z - min / max are discarded. The unit is cm. The min values must be smaller than the max values. */ + inline void setXMin (const float x_min) {if (x_min < x_max_) x_min_ = x_min;} + inline void setXMax (const float x_max) {if (x_max > x_min_) x_max_ = x_max;} + inline void setYMin (const float y_min) {if (y_min < y_max_) y_min_ = y_min;} + inline void setYMax (const float y_max) {if (y_max > y_min_) y_max_ = y_max;} + inline void setZMin (const float z_min) {if (z_min < z_max_) z_min_ = z_min;} + inline void setZMax (const float z_max) {if (z_max > z_min_) z_max_ = z_max;} + + inline float getXMin () const {return (x_min_);} + inline float getXMax () const {return (x_max_);} + inline float getYMin () const {return (y_min_);} + inline float getYMax () const {return (y_max_);} + inline float getZMin () const {return (z_min_);} + inline float getZMax () const {return (z_max_);} + /** @} */ + + /** @{ */ + /** \brief Simple color segmentation in the HSV color space. Points inside of H - S - V min / max are discarded. H must be in the range 0 and 360, S and V in the range 0 and 1. + * \note If you set values outside of the allowed range the member variables are clamped to the next best value. E.g. H is set to 0 if you pass -1. + */ + inline void setHMin (const float h_min) {h_min_ = pcl::ihs::clamp (h_min, 0.f, 360.f);} + inline void setHMax (const float h_max) {h_max_ = pcl::ihs::clamp (h_max, 0.f, 360.f);} + inline void setSMin (const float s_min) {s_min_ = pcl::ihs::clamp (s_min, 0.f, 1.f);} + inline void setSMax (const float s_max) {s_max_ = pcl::ihs::clamp (s_max, 0.f, 1.f);} + inline void setVMin (const float v_min) {v_min_ = pcl::ihs::clamp (v_min, 0.f, 1.f);} + inline void setVMax (const float v_max) {v_max_ = pcl::ihs::clamp (v_max, 0.f, 1.f);} + + inline float getHMin () const {return (h_min_);} + inline float getHMax () const {return (h_max_);} + inline float getSMin () const {return (s_min_);} + inline float getSMax () const {return (s_max_);} + inline float getVMin () const {return (v_min_);} + inline float getVMax () const {return (v_max_);} + /** @} */ + + /** @{ */ + /** \brief If true the color values inside of H - S - V min / max are accepted instead of discarded. */ + inline void setColorSegmentationInverted (const bool hsv_inverted) {hsv_inverted_ = hsv_inverted;} + inline bool getColorSegmentationInverted () const {return (hsv_inverted_);} + /** @} */ + + /** @{ */ + /** \brief Enable / disable the color segmentation. */ + inline void setColorSegmentationEnabled (const bool hsv_enabled) {hsv_enabled_ = hsv_enabled;} + inline bool getColorSegmentationEnabled () const {return (hsv_enabled_);} + /** @} */ + + /** @{ */ + /** \brief The XYZ mask is eroded with a kernel of this size. */ + inline void setXYZErodeSize (const unsigned int size) {size_erode_ = size;} + inline unsigned int getXYZErodeSize () const {return (size_erode_);} + /** @} */ + + /** @{ */ + /** \brief The HSV mask is dilated with a kernel of this size. */ + inline void setHSVDilateSize (const unsigned int size) {size_dilate_ = size;} + inline unsigned int getHSVDilateSize () const {return (size_dilate_);} + /** @} */ + + private: + + typedef pcl::Normal Normal; + typedef pcl::PointCloud CloudNormals; + typedef boost::shared_ptr CloudNormalsPtr; + typedef boost::shared_ptr CloudNormalsConstPtr; + + typedef pcl::IntegralImageNormalEstimation NormalEstimation; + typedef boost::shared_ptr NormalEstimationPtr; + typedef boost::shared_ptr NormalEstimationConstPtr; + + typedef Eigen::Matrix MatrixXb; + typedef Eigen::MatrixXi MatrixXi; + + /** \brief Erodes the input mask k times with a diamond shaped structuring element. + * \see http://ostermiller.org/dilate_and_erode.html + */ + void + erode (MatrixXb& mask, const int k) const; + + /** \brief Dilates the input mask k times with a diamond shaped structuring element. + * \see http://ostermiller.org/dilate_and_erode.html + */ + void + dilate (MatrixXb& mask, const int k) const; + + /** \brief Calculates the manhattan distance map for the input matrix. + * \param[in] mat Input matrix. + * \param[in] comp Compared value. mat==comp will have zero distance. + * \return Matrix containing the distances to mat==comp + * \see http://ostermiller.org/dilate_and_erode.html + */ + MatrixXi + manhattan (const MatrixXb& mat, const bool comp) const; + + /** \brief Conversion from the RGB to HSV color space. */ + void + RGBToHSV (const unsigned char r, + const unsigned char g, + const unsigned char b, + float& h, + float& s, + float& v) const; + + //////////////////////////////////////////////////////////////////////// + // Members + //////////////////////////////////////////////////////////////////////// + + NormalEstimationPtr normal_estimation_; + + float x_min_; + float x_max_; + float y_min_; + float y_max_; + float z_min_; + float z_max_; + + float h_min_; + float h_max_; + float s_min_; + float s_max_; + float v_min_; + float v_max_; + + bool hsv_inverted_; + bool hsv_enabled_; + + unsigned int size_dilate_; + unsigned int size_erode_; + }; + } // End namespace ihs +} // End namespace pcl + +#endif // PCL_APPS_IN_HAND_SCANNER_INPUT_DATA_PROCESSING_H diff --git a/pcl-1.7/pcl/in_hand_scanner/integration.h b/pcl-1.7/pcl/in_hand_scanner/integration.h new file mode 100644 index 0000000..f6ff2e2 --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/integration.h @@ -0,0 +1,234 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_APPS_IN_HAND_SCANNER_INTEGRATION_H +#define PCL_APPS_IN_HAND_SCANNER_INTEGRATION_H + +#include + +#include +#include + +//////////////////////////////////////////////////////////////////////////////// +// Forward declarations +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + template + class KdTree; +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// Integration +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace ihs + { + /** \brief Integrate several clouds into a common mesh. + * \author Martin Saelzle + * \ingroup apps + */ + class PCL_EXPORTS Integration + { + public: + + typedef pcl::PointXYZRGBNormal PointXYZRGBNormal; + typedef pcl::PointCloud CloudXYZRGBNormal; + typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr; + typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr; + + typedef pcl::ihs::Mesh Mesh; + typedef pcl::ihs::MeshPtr MeshPtr; + typedef pcl::ihs::MeshConstPtr MeshConstPtr; + typedef Mesh::VertexIndex VertexIndex; + typedef Mesh::VertexIndices VertexIndices; + + /** \brief Constructor. */ + Integration (); + + /** \brief Reconstructs a mesh from an organized cloud. + * \param[in] cloud_data Input cloud. Must be organized. + * \param[in] mesh_model Reconstructed mesh. + * \return true if success. + */ + bool + reconstructMesh (const CloudXYZRGBNormalConstPtr& cloud_data, + MeshPtr& mesh_model) const; + + /** \brief Merge the organized cloud into the mesh. + * \param[in] cloud_data Input cloud. Must be organized. + * \param[in,out] mesh_model Mesh with new points integrated. + * \param[in] T Transformation that aligns the data cloud with the model mesh. + * \return true if success. + */ + bool + merge (const CloudXYZRGBNormalConstPtr& cloud_data, + MeshPtr& mesh_model, + const Eigen::Matrix4f& T) const; + + /** \brief Outlier rejection. In each merge step points that have not been observed again age by one iteration. Points that are observed again get an age of 0. Once a point reaches the maximum age it is decided if the point is removed or kept in the mesh. A point is removed if it has not been observed from a minimum number of directions. + * \param[in,out] mesh The mesh which should be processed. + * \param[in] cleanup Calls mesh.cleanup () if true. + */ + void + age (const MeshPtr& mesh, const bool cleanup=true) const; + + /** \brief Removes unfit vertices regardless of their age. Unfit vertices are those that have not been observed from enough directions. + * \param[in,out] mesh The which should be processed. + * \param[in] cleanup Calls mesh.cleanup () if true. + */ + void + removeUnfitVertices (const MeshPtr& mesh, const bool cleanup=true) const; + + /** @{ */ + /** \brief Corresponding points are averaged out if their distance is below a distance threshold. Else the points are added to the mesh as new vertices (Set in cm^2). + * \note Must be greater than zero. + */ + void setMaxSquaredDistance (const float squared_distance); + float getMaxSquaredDistance () const; + /** @} */ + + /** @{ */ + /** \brief Corresponding points are only averaged out if the angle between the normals is smaller than an angle threshold. + * \note Must be between 0 and 180. Values outside this range are clamped to the nearest valid value. + */ + void setMaxAngle (const float angle); + float getMaxAngle () const; + /** @} */ + + /** @{ */ + /** \brief Once a point reaches the maximum age it is decided if the point is removed or kept in the mesh. + * \note Must be greater than zero. + */ + void setMaxAge (const unsigned int age); + unsigned int getMaxAge () const; + /** @} */ + + /** @{ */ + /** \brief A point is removed if it has not been observed from a minimum number of directions. + * \note Must be greater than zero. + */ + void setMinDirections (const unsigned int directions); + unsigned int getMinDirections () const; + /** @} */ + + private: + + typedef pcl::PointXYZ PointXYZ; + typedef pcl::PointCloud CloudXYZ; + typedef CloudXYZ::Ptr CloudXYZPtr; + typedef CloudXYZ::ConstPtr CloudXYZConstPtr; + + typedef pcl::ihs::PointIHS PointIHS; + typedef pcl::ihs::CloudIHS CloudIHS; + typedef pcl::ihs::CloudIHSPtr CloudIHSPtr; + typedef pcl::ihs::CloudIHSConstPtr CloudIHSConstPtr; + + typedef pcl::KdTree KdTree; + typedef boost::shared_ptr KdTreePtr; + typedef boost::shared_ptr KdTreeConstPtr; + + uint8_t + trimRGB (const float val) const; + + /** \brief Adds two triangles between points 0-1-3 and 1-2-3 to the mesh. */ + void + addToMesh (const PointIHS& pt_0, + const PointIHS& pt_1, + const PointIHS& pt_2, + const PointIHS& pt_3, + VertexIndex& vi_0, + VertexIndex& vi_1, + VertexIndex& vi_2, + VertexIndex& vi_3, + const MeshPtr& mesh) const; + + /** \brief Adds a triangle between the points 0-1-2 to the mesh. */ + void + addToMesh (const PointIHS& pt_0, + const PointIHS& pt_1, + const PointIHS& pt_2, + VertexIndex& vi_0, + VertexIndex& vi_1, + VertexIndex& vi_2, + const MeshPtr& mesh) const; + + /** \brief Returns true if the distance between the three points is below a threshold. */ + bool + distanceThreshold (const PointIHS& pt_0, + const PointIHS& pt_1, + const PointIHS& pt_2) const; + + /** \brief Returns true if the distance between the four points is below a threshold. */ + bool + distanceThreshold (const PointIHS& pt_0, + const PointIHS& pt_1, + const PointIHS& pt_2, + const PointIHS& pt_3) const; + + //////////////////////////////////////////////////////////////////////// + // Members + //////////////////////////////////////////////////////////////////////// + + /** \brief Nearest neighbor search. */ + KdTreePtr kd_tree_; + + /** \brief Maximum squared distance below which points are averaged out. */ + float max_squared_distance_; + + /** \brief Maximum angle between normals below which points are averaged out. In degrees. */ + float max_angle_; + + /** \brief Minimum weight above which points are added. */ + float min_weight_; + + /** \brief Once a point reaches the maximum age it is decided if the point is removed or kept in the mesh. */ + unsigned int max_age_; + + /** \brief A point is removed if it has not been observed from a minimum number of directions. */ + unsigned int min_directions_; + }; + } // End namespace ihs +} // End namespace pcl + +#endif // PCL_APPS_IN_HAND_SCANNER_INTEGRATION_H diff --git a/pcl-1.7/pcl/in_hand_scanner/main_window.h b/pcl-1.7/pcl/in_hand_scanner/main_window.h new file mode 100644 index 0000000..674c985 --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/main_window.h @@ -0,0 +1,140 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_APPS_IN_HAND_SCANNER_MAIN_WINDOW_H +#define PCL_APPS_IN_HAND_SCANNER_MAIN_WINDOW_H + +#include + +#include + +//////////////////////////////////////////////////////////////////////////////// +// Forward declarations +//////////////////////////////////////////////////////////////////////////////// + +namespace Ui +{ + class MainWindow; +} + +namespace pcl +{ + namespace ihs + { + class HelpWindow; + } // End namespace ihs +} // End namespace pcl + +//////////////////////////////////////////////////////////////////////////////// +// MainWindow +//////////////////////////////////////////////////////////////////////////////// + +namespace pcl +{ + namespace ihs + { + class MainWindow : public QMainWindow + { + Q_OBJECT + + public: + + typedef pcl::ihs::InHandScanner InHandScanner; + typedef pcl::ihs::HelpWindow HelpWindow; + typedef InHandScanner::RunningMode RunningMode; + + explicit MainWindow (QWidget* parent = 0); + ~MainWindow (); + + public slots: + + void showHelp (); + void saveAs (); + + // In hand scanner + void runningModeChanged (const RunningMode mode); + void keyPressEvent (QKeyEvent* event); + + // Input data processing. + void setXMin (const int x_min); + void setXMax (const int x_max); + void setYMin (const int y_min); + void setYMax (const int y_max); + void setZMin (const int z_min); + void setZMax (const int z_max); + + void setHMin (const int h_min); + void setHMax (const int h_max); + void setSMin (const int s_min); + void setSMax (const int s_max); + void setVMin (const int v_min); + void setVMax (const int v_max); + + void setColorSegmentationInverted (const bool is_inverted); + void setColorSegmentationEnabled (const bool is_enabled); + + void setXYZErodeSize (const int size); + void setHSVDilateSize (const int size); + + // Registration + void setEpsilon (); + void setMaxIterations (const int iterations); + void setMinOverlap (const int overlap); + void setMaxFitness (); + + void setCorrespondenceRejectionFactor (const double factor); + void setCorrespondenceRejectionMaxAngle (const int angle); + + // Integration + void setMaxSquaredDistance (); + void setAveragingMaxAngle (const int angle); + void setMaxAge (const int age); + void setMinDirections (const int directions); + + private: + + Ui::MainWindow* ui_; + HelpWindow* help_window_; + InHandScanner* ihs_; + }; + } // End namespace ihs +} // End namespace pcl + +#endif // PCL_APPS_IN_HAND_SCANNER_MAIN_WINDOW_H diff --git a/pcl-1.7/pcl/in_hand_scanner/mesh_processing.h b/pcl-1.7/pcl/in_hand_scanner/mesh_processing.h new file mode 100644 index 0000000..544a07b --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/mesh_processing.h @@ -0,0 +1,78 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_APPS_IN_HAND_SCANNER_MESH_PROCESSING_H +#define PCL_APPS_IN_HAND_SCANNER_MESH_PROCESSING_H + +#include + +namespace pcl +{ + namespace ihs + { + /** \brief Contains methods that take advantage of the connectivity information in the mesh. + * \author Martin Saelzle + * \ingroup apps + */ + class MeshProcessing + { + public: + + typedef pcl::ihs::Mesh Mesh; + typedef Mesh::HalfEdgeIndices HalfEdgeIndices; + + // Currently works only on the manifold mesh. + BOOST_STATIC_ASSERT (Mesh::IsManifold::value); + + /** \brief Constructor. */ + MeshProcessing (); + + /** \brief Inserts triangles into jagged boundaries, removes isolated triangles and closes triangular holes. + * \param[in,out] mesh The mesh which should be processed. + * \param[in] boundary_collection Collection of boundary half-edges. + * \param[in] cleanup Calls mesh.cleanup () if true. + */ + void + processBoundary (Mesh& mesh, const std::vector & boundary_collection, const bool cleanup=true) const; + }; + } // End namespace ihs +} // End namespace pcl + +#endif // PCL_APPS_IN_HAND_SCANNER_MESH_PROCESSING_H diff --git a/pcl-1.7/pcl/in_hand_scanner/opengl_viewer.h b/pcl-1.7/pcl/in_hand_scanner/opengl_viewer.h new file mode 100644 index 0000000..ebbc0f2 --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/opengl_viewer.h @@ -0,0 +1,456 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_APPS_IN_HAND_SCANNER_OPENGL_VIEWER_H +#define PCL_APPS_IN_HAND_SCANNER_OPENGL_VIEWER_H + +#include + +#include + +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace ihs + { + namespace detail + { + /** \brief Mesh format more efficient for visualization than the half-edge data structure. + * \see http://en.wikipedia.org/wiki/Polygon_mesh#Face-vertex_meshes + * \note Only triangles are currently supported. + */ + class FaceVertexMesh + { + public: + + class Triangle + { + public: + + Triangle () : first (0), second (0), third (0) {} + Triangle (const unsigned int first, const unsigned int second, const unsigned int third) + : first (first), second (second), third (third) + { + } + + unsigned int first; + unsigned int second; + unsigned int third; + }; + + /** \brief Constructor */ + FaceVertexMesh (); + + /** \brief Constructor. Converts the input mesh into a face vertex mesh. */ + FaceVertexMesh (const Mesh& mesh, const Eigen::Isometry3d& T); + + typedef pcl::ihs::PointIHS PointIHS; + typedef pcl::ihs::CloudIHS CloudIHS; + typedef pcl::ihs::CloudIHSPtr CloudIHSPtr; + typedef pcl::ihs::CloudIHSConstPtr CloudIHSConstPtr; + + CloudIHS vertices; + std::vector triangles; + Eigen::Isometry3d transformation; + + public: + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } // End namespace detail + + /** \brief Viewer for the in-hand scanner based on Qt and OpenGL. + * \note Currently you have to derive from this class to use it. Implement the paintEvent: Call the paint event of this class and declare a QPainter. + */ + class PCL_EXPORTS OpenGLViewer : public QGLWidget + { + Q_OBJECT + + public: + + typedef pcl::PointXYZRGBNormal PointXYZRGBNormal; + typedef pcl::PointCloud CloudXYZRGBNormal; + typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr; + typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr; + + typedef pcl::ihs::Mesh Mesh; + typedef pcl::ihs::MeshPtr MeshPtr; + typedef pcl::ihs::MeshConstPtr MeshConstPtr; + + /** \brief How to draw the mesh. */ + typedef enum MeshRepresentation + { + MR_POINTS, /**< Draw the points. */ + MR_EDGES, /**< Wireframe represen of the mesh. */ + MR_FACES /**< Draw the faces of the mesh without edges. */ + } MeshRepresentation; + + /** \brief How to color the shapes. */ + typedef enum Coloring + { + COL_RGB, /**< Coloring according to the rgb values. */ + COL_ONE_COLOR, /**< Use one color for all points. */ + COL_VISCONF /**< Coloring according to the visibility confidence. */ + } Coloring; + + /** \brief Coefficients for the wireframe box. */ + class BoxCoefficients + { + public: + + BoxCoefficients () + : x_min (0), x_max (0), + y_min (0), y_max (0), + z_min (0), z_max (0), + transformation (Eigen::Isometry3d::Identity ()) + { + } + + BoxCoefficients (const float x_min, const float x_max, + const float y_min, const float y_max, + const float z_min, const float z_max, + const Eigen::Isometry3d& T) + : x_min (x_min), x_max (x_max), + y_min (y_min), y_max (y_max), + z_min (z_min), z_max (z_max), + transformation (T) + { + } + + float x_min; float x_max; + float y_min; float y_max; + float z_min; float z_max; + Eigen::Isometry3d transformation; + + public: + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + /** \brief Constructor. */ + explicit OpenGLViewer (QWidget* parent=0); + + /** \brief Destructor. */ + ~OpenGLViewer (); + + /** \brief Add a mesh to be drawn. + * \param[in] mesh The input mesh. + * \param[in] id Unique identifier for the mesh. The internal mesh is replaced by the input mesh if the id already exists. + * \param[in] T Transformation applied to the mesh. Defaults to an identity transformation. + * \return true if success. + * \note Converts the mesh to the internal representation better suited for visualization. Therefore this method takes some time. + */ + bool + addMesh (const MeshConstPtr& mesh, const std::string& id, const Eigen::Isometry3d& T = Eigen::Isometry3d::Identity ()); + + /** \brief Convert an organized cloud to a mesh and draw it. + * \param[in] cloud Organized input cloud. + * \param[in] id Unique identifier for the mesh. The internal mesh is replaced by the converted input mesh if the id already exists. + * \param[in] T Transformation applied to the mesh. Defaults to an identity transformation. + * \return true if success. + * \note This method takes some time for the conversion). + */ + bool + addMesh (const CloudXYZRGBNormalConstPtr& cloud, const std::string& id, const Eigen::Isometry3d& T = Eigen::Isometry3d::Identity ()); + + /** \brief Remove the mesh with the given id. + * \param[in] id Identifier of the mesh (results in a failure if the id does not exist). + * \return true if success. + */ + bool + removeMesh (const std::string& id); + + /** \brief Remove all meshes that are currently drawn. */ + void + removeAllMeshes (); + + /** \brief Set the coefficients for the box. */ + void + setBoxCoefficients (const BoxCoefficients& coeffs); + + /** \brief Enable / disable drawing the box. */ + void + setDrawBox (const bool enabled); + + /** \brief Check if the box is drawn. */ + bool + getDrawBox () const; + + /** \brief Set the point around which the camera rotates during mouse navigation. */ + void + setPivot (const Eigen::Vector3d& pivot); + + /** \brief Searches the given id in the drawn meshes and calculates the pivot as the centroid of the found geometry. + * \note Returns immediately and computes the pivot in another thread. + */ + void + setPivot (const std::string& id); + + /** \brief Stop the visualization timer. */ + void + stopTimer (); + + /** \brief The visibility confidence is normalized with this value (must be greater than 1). */ + void + setVisibilityConfidenceNormalization (const float vis_conf_norm); + + /** \see http://doc.qt.digia.com/qt/qwidget.html#minimumSizeHint-prop */ + virtual QSize + minimumSizeHint () const; + + /** \see http://doc.qt.digia.com/qt/qwidget.html#sizeHint-prop */ + virtual QSize + sizeHint () const; + + /** \brief Set the scaling factor to convert from meters to the unit of the drawn files. */ + void + setScalingFactor (const double scale); + + public slots: + + /** \brief Requests the scene to be re-drawn (called periodically from a timer). */ + void + timerCallback (); + + /** \brief Reset the virtual camera position and orientation. */ + void + resetCamera (); + + /** \brief Toggle the mesh representation. */ + void + toggleMeshRepresentation (); + + /** \brief Set the mesh representation. */ + void + setMeshRepresentation (const MeshRepresentation& representation); + + /** \brief Toggle the coloring mode. */ + void + toggleColoring (); + + /** \brief Set the coloring mode. */ + void + setColoring (const Coloring& coloring); + + protected: + + /** \brief Please have a look at the documentation of calcFPS. */ + class FPS + { + public: + + FPS () : fps_ (0.) {} + + inline double& value () {return (fps_);} + inline double value () const {return (fps_);} + + inline std::string + str () const + { + std::stringstream ss; + ss << std::setprecision (1) << std::fixed << fps_; + return (ss.str ()); + } + + protected: + + ~FPS () {} + + private: + + double fps_; + }; + + /** Measures the performance of the current thread (selected by passing the corresponding 'fps' helper object). The resulting value is stored in the fps object. */ + template void + calcFPS (FPS& fps) const + { + static pcl::StopWatch sw; + static unsigned int count = 0; + + ++count; + if (sw.getTimeSeconds () >= .2) + { + fps.value () = static_cast (count) / sw.getTimeSeconds (); + count = 0; + sw.reset (); + } + } + + /** \see http://doc.qt.digia.com/qt/qwidget.html#paintEvent + * \see http://doc.qt.digia.com/qt/opengl-overpainting.html + */ + virtual void + paintEvent (QPaintEvent* event); + + private: + + typedef Eigen::Matrix Color; + typedef Eigen::Matrix Colors; + typedef Eigen::Matrix Colormap; + + typedef boost::unordered_map CloudXYZRGBNormalMap; + + typedef pcl::ihs::PointIHS PointIHS; + typedef pcl::ihs::CloudIHS CloudIHS; + typedef pcl::ihs::CloudIHSPtr CloudIHSPtr; + typedef pcl::ihs::CloudIHSConstPtr CloudIHSConstPtr; + + typedef pcl::ihs::detail::FaceVertexMesh FaceVertexMesh; + typedef boost::shared_ptr < FaceVertexMesh> FaceVertexMeshPtr; + typedef boost::shared_ptr FaceVertexMeshConstPtr; + typedef boost::unordered_map FaceVertexMeshMap; + + /** \brief Check if the mesh with the given id is added. + * \note Must lock the mutex before calling this method. + */ + bool + getMeshIsAdded (const std::string& id); + + /** \brief Calculate the pivot for the stored id. */ + void + calcPivot (); + + /** \brief Draw all meshes. + * \note Only triangle meshes are currently supported. + */ + void + drawMeshes (); + + /** \brief Draw a wireframe box. */ + void + drawBox (); + + /** \see http://doc.qt.digia.com/qt/qglwidget.html#initializeGL */ + void + initializeGL (); + + /** \see http://www.opengl.org/sdk/docs/man/xhtml/glViewport.xml */ + void + setupViewport (const int w, const int h); + + /** \see http://doc.qt.digia.com/qt/qglwidget.html#resizeGL */ + void + resizeGL (int w, int h); + + /** \see http://doc.qt.digia.com/qt/qwidget.html#mousePressEvent */ + void + mousePressEvent (QMouseEvent* event); + + /** \see http://doc.qt.digia.com/qt/qwidget.html#mouseMoveEvent */ + void + mouseMoveEvent (QMouseEvent* event); + + /** \see http://doc.qt.digia.com/qt/qwidget.html#wheelEvent */ + void + wheelEvent (QWheelEvent* event); + + //////////////////////////////////////////////////////////////////////// + // Members + //////////////////////////////////////////////////////////////////////// + + /** \brief Synchronization. */ + boost::mutex mutex_vis_; + + /** \brief Visualization timer. */ + boost::shared_ptr timer_vis_; + + /** \brief Colormap. */ + Colormap colormap_; + + /** \brief The visibility confidence is normalized with this value. */ + float vis_conf_norm_; + + /** \brief Meshes stored for visualization. */ + FaceVertexMeshMap drawn_meshes_; + + /** \brief How to draw the mesh. */ + MeshRepresentation mesh_representation_; + + /** \brief How to color the shapes. */ + Coloring coloring_; + + /** \brief A box is drawn if this value is true. */ + bool draw_box_; + + /** \brief Coefficients of the drawn box. */ + BoxCoefficients box_coefficients_; + + /** \brief Scaling factor to convert from meters to the unit of the drawn files. */ + double scaling_factor_; + + /** \brief Rotation of the camera. */ + Eigen::Quaterniond R_cam_; + + /** \brief Translation of the camera. */ + Eigen::Vector3d t_cam_; + + /** \brief Center of rotation during mouse navigation. */ + Eigen::Vector3d cam_pivot_; + + /** \brief Compute the pivot for the mesh with the given id. */ + std::string cam_pivot_id_; + + /** \brief Set to true right after the mouse got pressed and false if the mouse got moved. */ + bool mouse_pressed_begin_; + + /** \brief Mouse x-position of the previous mouse move event. */ + int x_prev_; + + /** \brief Mouse y-position of the previous mouse move event. */ + int y_prev_; + + public: + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } // End namespace ihs +} // End namespace pcl + +// http://doc.qt.digia.com/qt/qmetatype.html#Q_DECLARE_METATYPE +Q_DECLARE_METATYPE (pcl::ihs::OpenGLViewer::MeshRepresentation) +Q_DECLARE_METATYPE (pcl::ihs::OpenGLViewer::Coloring) + +#endif // PCL_APPS_IN_HAND_SCANNER_OPENGL_VIEWER_H diff --git a/pcl-1.7/pcl/in_hand_scanner/ui_help_window.h b/pcl-1.7/pcl/in_hand_scanner/ui_help_window.h new file mode 100644 index 0000000..69c93a1 --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/ui_help_window.h @@ -0,0 +1,243 @@ +/******************************************************************************** +** Form generated from reading UI file 'help_window.ui' +** +** Created by: Qt User Interface Compiler version 4.8.7 +** +** WARNING! All changes made in this file will be lost when recompiling UI file! +********************************************************************************/ + +#ifndef UI_HELP_WINDOW_H +#define UI_HELP_WINDOW_H + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +QT_BEGIN_NAMESPACE + +class Ui_HelpWindow +{ +public: + QVBoxLayout *verticalLayout; + QTabWidget *tabWidget; + QWidget *tab_shortcuts; + QVBoxLayout *verticalLayout_5; + QTextBrowser *textBrowser; + QWidget *tab_input_data_processing; + QVBoxLayout *verticalLayout_2; + QTextBrowser *textBrowser_input_data_processing; + QWidget *tab_registration; + QVBoxLayout *verticalLayout_3; + QTextBrowser *textBrowser_registration; + QWidget *tab_integration; + QVBoxLayout *verticalLayout_4; + QTextBrowser *textBrowser_integration; + QDialogButtonBox *buttonBox_close; + + void setupUi(QDialog *HelpWindow) + { + if (HelpWindow->objectName().isEmpty()) + HelpWindow->setObjectName(QString::fromUtf8("HelpWindow")); + HelpWindow->resize(640, 480); + verticalLayout = new QVBoxLayout(HelpWindow); + verticalLayout->setObjectName(QString::fromUtf8("verticalLayout")); + tabWidget = new QTabWidget(HelpWindow); + tabWidget->setObjectName(QString::fromUtf8("tabWidget")); + tab_shortcuts = new QWidget(); + tab_shortcuts->setObjectName(QString::fromUtf8("tab_shortcuts")); + verticalLayout_5 = new QVBoxLayout(tab_shortcuts); + verticalLayout_5->setObjectName(QString::fromUtf8("verticalLayout_5")); + textBrowser = new QTextBrowser(tab_shortcuts); + textBrowser->setObjectName(QString::fromUtf8("textBrowser")); + + verticalLayout_5->addWidget(textBrowser); + + tabWidget->addTab(tab_shortcuts, QString()); + tab_input_data_processing = new QWidget(); + tab_input_data_processing->setObjectName(QString::fromUtf8("tab_input_data_processing")); + verticalLayout_2 = new QVBoxLayout(tab_input_data_processing); + verticalLayout_2->setObjectName(QString::fromUtf8("verticalLayout_2")); + textBrowser_input_data_processing = new QTextBrowser(tab_input_data_processing); + textBrowser_input_data_processing->setObjectName(QString::fromUtf8("textBrowser_input_data_processing")); + + verticalLayout_2->addWidget(textBrowser_input_data_processing); + + tabWidget->addTab(tab_input_data_processing, QString()); + tab_registration = new QWidget(); + tab_registration->setObjectName(QString::fromUtf8("tab_registration")); + verticalLayout_3 = new QVBoxLayout(tab_registration); + verticalLayout_3->setObjectName(QString::fromUtf8("verticalLayout_3")); + textBrowser_registration = new QTextBrowser(tab_registration); + textBrowser_registration->setObjectName(QString::fromUtf8("textBrowser_registration")); + + verticalLayout_3->addWidget(textBrowser_registration); + + tabWidget->addTab(tab_registration, QString()); + tab_integration = new QWidget(); + tab_integration->setObjectName(QString::fromUtf8("tab_integration")); + verticalLayout_4 = new QVBoxLayout(tab_integration); + verticalLayout_4->setObjectName(QString::fromUtf8("verticalLayout_4")); + textBrowser_integration = new QTextBrowser(tab_integration); + textBrowser_integration->setObjectName(QString::fromUtf8("textBrowser_integration")); + + verticalLayout_4->addWidget(textBrowser_integration); + + tabWidget->addTab(tab_integration, QString()); + + verticalLayout->addWidget(tabWidget); + + buttonBox_close = new QDialogButtonBox(HelpWindow); + buttonBox_close->setObjectName(QString::fromUtf8("buttonBox_close")); + buttonBox_close->setStandardButtons(QDialogButtonBox::Close); + + verticalLayout->addWidget(buttonBox_close); + + + retranslateUi(HelpWindow); + QObject::connect(buttonBox_close, SIGNAL(accepted()), HelpWindow, SLOT(accept())); + QObject::connect(buttonBox_close, SIGNAL(rejected()), HelpWindow, SLOT(reject())); + + tabWidget->setCurrentIndex(0); + + + QMetaObject::connectSlotsByName(HelpWindow); + } // setupUi + + void retranslateUi(QDialog *HelpWindow) + { + HelpWindow->setWindowTitle(QApplication::translate("HelpWindow", "Help", 0, QApplication::UnicodeUTF8)); + textBrowser->setHtml(QApplication::translate("HelpWindow", "\n" +"\n" +"

Main processing pipeline.

\n" +"


\n" +"

1 Shows the unprocessed input data.

\n" +"

" + "2 Shows the processed input data.

\n" +"

3 Registers new data to the first scan continuously.

\n" +"

4 Registers new data once and returns to showing the processed input data.

\n" +"

5 Shows the acquired model.

\n" +"

6 Removes all unfit points.

\n" +"

0 Resets the scanning pipeline.

\n" +"


\n" +"

Visualization

\n" +"


\n" +"

c Resets the camera.

\n" +"

k Toggles the coloring between rgb, one co" + "lor, visibility-confidence.

\n" +"

s Toggles the surface representation between points, wireframe and a closed surface.

", 0, QApplication::UnicodeUTF8)); + tabWidget->setTabText(tabWidget->indexOf(tab_shortcuts), QApplication::translate("HelpWindow", "Shortcuts", 0, QApplication::UnicodeUTF8)); + textBrowser_input_data_processing->setHtml(QApplication::translate("HelpWindow", "\n" +"\n" +"

Crop coordinates:

\n" +"


\n" +"

All points outside of X - Y - Z - min / max are discarded. The unit is cm. The minimum values must be smaller than the maximum values.

\n" +"


\n" +"

Erode size:

\n" +"


\n" +"

"Eats away" additional pixels at the borders. The size is the number of removed pixels. Disabled with a size of 0.

\n" +"


\n" +"

Color segmentation:" + "

\n" +"


\n" +"

Simple color segmentation in the HSV color space. Points inside of H - S - V min / max are discarded. H is between 0 and 360, S and V are between 0% and 100%.

\n" +"


\n" +"

Dilate size:

\n" +"


\n" +"

Dilates the color mask by a number of pixels. Disabled with a size of 0.

\n" +"


\n" +"

Inverted:

\n" +"


\n" +"

The color values inside of H - S - V min / max are accepted instead of discarded.

\n" +"


\n" +"

Enabled:

\n" +"


\n" +"

Enables / disables the color segmentation.

", 0, QApplication::UnicodeUTF8)); + tabWidget->setTabText(tabWidget->indexOf(tab_input_data_processing), QApplication::translate("HelpWindow", "Input data processing", 0, QApplication::UnicodeUTF8)); + textBrowser_registration->setHtml(QApplication::translate("HelpWindow", "\n" +"\n" +"

Epsilon:

\n" +"


\n" +"

Convergence is detected when the change of the fitness between the current and previous iteration becomes smaller than the given epsilon (set in cm2). The fitn" + "ess is the mean squared euclidean distance between corresponding points.

\n" +"


\n" +"

Max iterations:

\n" +"


\n" +"

The registration fails if the number of iterations exceeds the maximum number of iterations.

\n" +"


\n" +"

Min overlap:

\n" +"


\n" +"

The registration fails at the state of convergence if the overlap between the model and data shape is smaller than a minimum overlap. The overlap is the fraction of correspondences (after rejection) to the initial number of data points.

\n" +"


\n" +"

Max fitness:

\n" +"


\n" +"

The registration fails at the state of convergence if the fitness is bigger than this threshold (set in cm2).

\n" +"


\n" +"

Factor:

\n" +"


\n" +"

Correspondences are rejected if the squared distance is above a threshold. This threshold is initialized with infinity (all correspondences are accepted in the first iteration). The threshold of the next iterations is set to the fitness of the current iteration multiplied by the factor set by this method.

\n" +"


\n" +"

Max angle:

\n" +"


\n" +"

Correspondences are rejected if " + "the angle between the normals is bigger than this threshold. Set in degrees.

", 0, QApplication::UnicodeUTF8)); + tabWidget->setTabText(tabWidget->indexOf(tab_registration), QApplication::translate("HelpWindow", "Registration", 0, QApplication::UnicodeUTF8)); + textBrowser_integration->setHtml(QApplication::translate("HelpWindow", "\n" +"\n" +"

Outlier rejection:

\n" +"


\n" +"

In each merge step points that have not been observed again age by one iteration. Points that are observed again get an age of 0. Once a point reaches the maximum age it is decided if the point is removed or kept" + " in the mesh. A point is removed if it has not been observed from a minimum number of directions.

\n" +"


\n" +"

Max squared distance:

\n" +"


\n" +"

Corresponding points are averaged out if their distance is below a distance threshold. Else the points are added to the mesh as new vertices (Set in cm2).

\n" +"


\n" +"

Max angle:

\n" +"


\n" +"

Corresponding points are only averaged out if the angle between the normals is smaller than an angle threshold (Set in degrees).

\n" +"


\n" +"

Max age:

\n" +"


\n" +"

Once a point reaches the maximum age it is decided if the point is removed or kept in the mesh.

\n" +"


\n" +"

Min directions:

\n" +"


\n" +"

A point is removed if it has not been observed from a minimum number of directions.

", 0, QApplication::UnicodeUTF8)); + tabWidget->setTabText(tabWidget->indexOf(tab_integration), QApplication::translate("HelpWindow", "Integration", 0, QApplication::UnicodeUTF8)); + } // retranslateUi + +}; + +namespace Ui { + class HelpWindow: public Ui_HelpWindow {}; +} // namespace Ui + +QT_END_NAMESPACE + +#endif // UI_HELP_WINDOW_H diff --git a/pcl-1.7/pcl/in_hand_scanner/ui_main_window.h b/pcl-1.7/pcl/in_hand_scanner/ui_main_window.h new file mode 100644 index 0000000..f145b1e --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/ui_main_window.h @@ -0,0 +1,857 @@ +/******************************************************************************** +** Form generated from reading UI file 'main_window.ui' +** +** Created by: Qt User Interface Compiler version 4.8.7 +** +** WARNING! All changes made in this file will be lost when recompiling UI file! +********************************************************************************/ + +#ifndef UI_MAIN_WINDOW_H +#define UI_MAIN_WINDOW_H + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +QT_BEGIN_NAMESPACE + +class Ui_MainWindow +{ +public: + QAction *actionHelp; + QAction *actionReset_camera; + QAction *actionToggle_coloring; + QAction *actionMesh_representation; + QAction *actionSaveAs; + QWidget *centralWidget; + QGridLayout *gridLayout_7; + QHBoxLayout *horizontalLayout_main_controls; + QToolButton *toolButton_1; + QToolButton *toolButton_2; + QToolButton *toolButton_3; + QToolButton *toolButton_4; + QToolButton *toolButton_5; + QToolButton *toolButton_6; + QSpacerItem *horizontalSpacer_main_controls; + QToolButton *toolButton_0; + QWidget *placeholder_in_hand_scanner; + QDockWidget *dockWidget; + QWidget *dockWidgetContents; + QVBoxLayout *verticalLayout; + QToolBox *toolBox; + QWidget *page_input_data_processing; + QVBoxLayout *verticalLayout_2; + QGroupBox *groupBox_crop_xyz; + QGridLayout *gridLayout_3; + QSpinBox *spinBox_y_max; + QLabel *label_z_min; + QSpinBox *spinBox_x_max; + QSpinBox *spinBox_y_min; + QLabel *label_x_min; + QSpinBox *spinBox_z_max; + QSpinBox *spinBox_x_min; + QLabel *label_xyz_erode_size; + QLabel *label_y_min; + QLabel *label_x_max; + QSpinBox *spinBox_z_min; + QLabel *label_y_max; + QLabel *label_z_max; + QSpinBox *spinBox_xyz_erode_size; + QGroupBox *groupBox_segment_hsv; + QGridLayout *gridLayout; + QSpinBox *spinBox_h_max; + QLabel *label_s_max; + QSpinBox *spinBox_s_min; + QLabel *label_h_min; + QLabel *label_h_max; + QLabel *label_s_min; + QSpinBox *spinBox_v_min; + QLabel *label_v_min; + QSpinBox *spinBox_v_max; + QSpinBox *spinBox_h_min; + QLabel *label_v_max; + QSpinBox *spinBox_s_max; + QLabel *label_hsv_dilate_size; + QSpinBox *spinBox_hsv_dilate_size; + QCheckBox *checkBox_color_segmentation_inverted; + QCheckBox *checkBox_color_segmentation_enabled; + QSpacerItem *verticalSpacer_input_data_processing; + QWidget *page_registration; + QVBoxLayout *verticalLayout_3; + QGroupBox *groupBox_convergence; + QGridLayout *gridLayout_4; + QLabel *label_epsilon; + QLabel *label_max_iterations; + QLabel *label_min_overlap; + QLabel *label_max_fitness; + QSpinBox *spinBox_max_iterations; + QSpinBox *spinBox_min_overlap; + QLineEdit *lineEdit_epsilon; + QLineEdit *lineEdit_max_fitness; + QGroupBox *groupBox_correspondence_rejection; + QGridLayout *gridLayout_2; + QLabel *label_correspondence_rejection_factor; + QDoubleSpinBox *doubleSpinBox_correspondence_rejection_factor; + QLabel *label_correspondence_rejection_max_angle; + QSpinBox *spinBox_correspondence_rejection_max_angle; + QSpacerItem *verticalSpacer_registration; + QWidget *page_integration; + QVBoxLayout *verticalLayout_4; + QGroupBox *groupBox_averaging; + QGridLayout *gridLayout_5; + QLabel *label_max_squared_distance; + QLineEdit *lineEdit_max_squared_distance; + QLabel *label_averaging_max_angle; + QSpinBox *spinBox_averaging_max_angle; + QGroupBox *groupBox_outlier_removal; + QGridLayout *gridLayout_6; + QLabel *label_max_age; + QSpinBox *spinBox_max_age; + QLabel *label_min_directions; + QSpinBox *spinBox_min_directions; + QSpacerItem *verticalSpacer_integration; + QToolBar *toolBar; + QMenuBar *menuBar; + QMenu *menuFile; + + void setupUi(QMainWindow *MainWindow) + { + if (MainWindow->objectName().isEmpty()) + MainWindow->setObjectName(QString::fromUtf8("MainWindow")); + MainWindow->resize(1008, 600); + actionHelp = new QAction(MainWindow); + actionHelp->setObjectName(QString::fromUtf8("actionHelp")); + actionReset_camera = new QAction(MainWindow); + actionReset_camera->setObjectName(QString::fromUtf8("actionReset_camera")); + actionToggle_coloring = new QAction(MainWindow); + actionToggle_coloring->setObjectName(QString::fromUtf8("actionToggle_coloring")); + actionMesh_representation = new QAction(MainWindow); + actionMesh_representation->setObjectName(QString::fromUtf8("actionMesh_representation")); + actionSaveAs = new QAction(MainWindow); + actionSaveAs->setObjectName(QString::fromUtf8("actionSaveAs")); + centralWidget = new QWidget(MainWindow); + centralWidget->setObjectName(QString::fromUtf8("centralWidget")); + gridLayout_7 = new QGridLayout(centralWidget); + gridLayout_7->setSpacing(6); + gridLayout_7->setContentsMargins(11, 11, 11, 11); + gridLayout_7->setObjectName(QString::fromUtf8("gridLayout_7")); + horizontalLayout_main_controls = new QHBoxLayout(); + horizontalLayout_main_controls->setSpacing(6); + horizontalLayout_main_controls->setObjectName(QString::fromUtf8("horizontalLayout_main_controls")); + toolButton_1 = new QToolButton(centralWidget); + toolButton_1->setObjectName(QString::fromUtf8("toolButton_1")); + toolButton_1->setCheckable(true); + toolButton_1->setChecked(true); + toolButton_1->setAutoExclusive(true); + + horizontalLayout_main_controls->addWidget(toolButton_1); + + toolButton_2 = new QToolButton(centralWidget); + toolButton_2->setObjectName(QString::fromUtf8("toolButton_2")); + toolButton_2->setCheckable(true); + toolButton_2->setChecked(false); + toolButton_2->setAutoExclusive(true); + + horizontalLayout_main_controls->addWidget(toolButton_2); + + toolButton_3 = new QToolButton(centralWidget); + toolButton_3->setObjectName(QString::fromUtf8("toolButton_3")); + toolButton_3->setCheckable(true); + toolButton_3->setAutoExclusive(true); + + horizontalLayout_main_controls->addWidget(toolButton_3); + + toolButton_4 = new QToolButton(centralWidget); + toolButton_4->setObjectName(QString::fromUtf8("toolButton_4")); + toolButton_4->setCheckable(true); + toolButton_4->setAutoExclusive(true); + + horizontalLayout_main_controls->addWidget(toolButton_4); + + toolButton_5 = new QToolButton(centralWidget); + toolButton_5->setObjectName(QString::fromUtf8("toolButton_5")); + toolButton_5->setCheckable(true); + toolButton_5->setAutoExclusive(true); + + horizontalLayout_main_controls->addWidget(toolButton_5); + + toolButton_6 = new QToolButton(centralWidget); + toolButton_6->setObjectName(QString::fromUtf8("toolButton_6")); + toolButton_6->setCheckable(false); + toolButton_6->setAutoExclusive(false); + + horizontalLayout_main_controls->addWidget(toolButton_6); + + horizontalSpacer_main_controls = new QSpacerItem(40, 20, QSizePolicy::Expanding, QSizePolicy::Minimum); + + horizontalLayout_main_controls->addItem(horizontalSpacer_main_controls); + + toolButton_0 = new QToolButton(centralWidget); + toolButton_0->setObjectName(QString::fromUtf8("toolButton_0")); + toolButton_0->setCheckable(false); + toolButton_0->setAutoExclusive(false); + + horizontalLayout_main_controls->addWidget(toolButton_0); + + + gridLayout_7->addLayout(horizontalLayout_main_controls, 0, 0, 1, 1); + + placeholder_in_hand_scanner = new QWidget(centralWidget); + placeholder_in_hand_scanner->setObjectName(QString::fromUtf8("placeholder_in_hand_scanner")); + QSizePolicy sizePolicy(QSizePolicy::Preferred, QSizePolicy::Expanding); + sizePolicy.setHorizontalStretch(0); + sizePolicy.setVerticalStretch(0); + sizePolicy.setHeightForWidth(placeholder_in_hand_scanner->sizePolicy().hasHeightForWidth()); + placeholder_in_hand_scanner->setSizePolicy(sizePolicy); + + gridLayout_7->addWidget(placeholder_in_hand_scanner, 1, 0, 1, 1); + + MainWindow->setCentralWidget(centralWidget); + dockWidget = new QDockWidget(MainWindow); + dockWidget->setObjectName(QString::fromUtf8("dockWidget")); + QSizePolicy sizePolicy1(QSizePolicy::Preferred, QSizePolicy::Preferred); + sizePolicy1.setHorizontalStretch(0); + sizePolicy1.setVerticalStretch(0); + sizePolicy1.setHeightForWidth(dockWidget->sizePolicy().hasHeightForWidth()); + dockWidget->setSizePolicy(sizePolicy1); + dockWidget->setMinimumSize(QSize(324, 228)); + dockWidget->setFeatures(QDockWidget::DockWidgetFloatable|QDockWidget::DockWidgetMovable); + dockWidgetContents = new QWidget(); + dockWidgetContents->setObjectName(QString::fromUtf8("dockWidgetContents")); + verticalLayout = new QVBoxLayout(dockWidgetContents); + verticalLayout->setSpacing(6); + verticalLayout->setContentsMargins(11, 11, 11, 11); + verticalLayout->setObjectName(QString::fromUtf8("verticalLayout")); + toolBox = new QToolBox(dockWidgetContents); + toolBox->setObjectName(QString::fromUtf8("toolBox")); + toolBox->setMinimumSize(QSize(0, 0)); + page_input_data_processing = new QWidget(); + page_input_data_processing->setObjectName(QString::fromUtf8("page_input_data_processing")); + page_input_data_processing->setGeometry(QRect(0, 0, 300, 408)); + verticalLayout_2 = new QVBoxLayout(page_input_data_processing); + verticalLayout_2->setSpacing(6); + verticalLayout_2->setContentsMargins(11, 11, 11, 11); + verticalLayout_2->setObjectName(QString::fromUtf8("verticalLayout_2")); + groupBox_crop_xyz = new QGroupBox(page_input_data_processing); + groupBox_crop_xyz->setObjectName(QString::fromUtf8("groupBox_crop_xyz")); + gridLayout_3 = new QGridLayout(groupBox_crop_xyz); + gridLayout_3->setSpacing(6); + gridLayout_3->setContentsMargins(11, 11, 11, 11); + gridLayout_3->setObjectName(QString::fromUtf8("gridLayout_3")); + spinBox_y_max = new QSpinBox(groupBox_crop_xyz); + spinBox_y_max->setObjectName(QString::fromUtf8("spinBox_y_max")); + spinBox_y_max->setMinimum(-100); + spinBox_y_max->setMaximum(100); + spinBox_y_max->setSingleStep(5); + + gridLayout_3->addWidget(spinBox_y_max, 1, 3, 1, 1); + + label_z_min = new QLabel(groupBox_crop_xyz); + label_z_min->setObjectName(QString::fromUtf8("label_z_min")); + + gridLayout_3->addWidget(label_z_min, 2, 0, 1, 1); + + spinBox_x_max = new QSpinBox(groupBox_crop_xyz); + spinBox_x_max->setObjectName(QString::fromUtf8("spinBox_x_max")); + spinBox_x_max->setMinimum(-100); + spinBox_x_max->setMaximum(100); + spinBox_x_max->setSingleStep(5); + + gridLayout_3->addWidget(spinBox_x_max, 0, 3, 1, 1); + + spinBox_y_min = new QSpinBox(groupBox_crop_xyz); + spinBox_y_min->setObjectName(QString::fromUtf8("spinBox_y_min")); + spinBox_y_min->setMinimum(-100); + spinBox_y_min->setMaximum(100); + spinBox_y_min->setSingleStep(5); + + gridLayout_3->addWidget(spinBox_y_min, 1, 1, 1, 1); + + label_x_min = new QLabel(groupBox_crop_xyz); + label_x_min->setObjectName(QString::fromUtf8("label_x_min")); + + gridLayout_3->addWidget(label_x_min, 0, 0, 1, 1); + + spinBox_z_max = new QSpinBox(groupBox_crop_xyz); + spinBox_z_max->setObjectName(QString::fromUtf8("spinBox_z_max")); + spinBox_z_max->setMinimum(0); + spinBox_z_max->setMaximum(1000); + spinBox_z_max->setSingleStep(5); + + gridLayout_3->addWidget(spinBox_z_max, 2, 3, 1, 1); + + spinBox_x_min = new QSpinBox(groupBox_crop_xyz); + spinBox_x_min->setObjectName(QString::fromUtf8("spinBox_x_min")); + spinBox_x_min->setMinimum(-100); + spinBox_x_min->setMaximum(100); + spinBox_x_min->setSingleStep(5); + + gridLayout_3->addWidget(spinBox_x_min, 0, 1, 1, 1); + + label_xyz_erode_size = new QLabel(groupBox_crop_xyz); + label_xyz_erode_size->setObjectName(QString::fromUtf8("label_xyz_erode_size")); + + gridLayout_3->addWidget(label_xyz_erode_size, 3, 0, 1, 2); + + label_y_min = new QLabel(groupBox_crop_xyz); + label_y_min->setObjectName(QString::fromUtf8("label_y_min")); + + gridLayout_3->addWidget(label_y_min, 1, 0, 1, 1); + + label_x_max = new QLabel(groupBox_crop_xyz); + label_x_max->setObjectName(QString::fromUtf8("label_x_max")); + + gridLayout_3->addWidget(label_x_max, 0, 2, 1, 1); + + spinBox_z_min = new QSpinBox(groupBox_crop_xyz); + spinBox_z_min->setObjectName(QString::fromUtf8("spinBox_z_min")); + spinBox_z_min->setMinimum(0); + spinBox_z_min->setMaximum(1000); + spinBox_z_min->setSingleStep(5); + + gridLayout_3->addWidget(spinBox_z_min, 2, 1, 1, 1); + + label_y_max = new QLabel(groupBox_crop_xyz); + label_y_max->setObjectName(QString::fromUtf8("label_y_max")); + + gridLayout_3->addWidget(label_y_max, 1, 2, 1, 1); + + label_z_max = new QLabel(groupBox_crop_xyz); + label_z_max->setObjectName(QString::fromUtf8("label_z_max")); + + gridLayout_3->addWidget(label_z_max, 2, 2, 1, 1); + + spinBox_xyz_erode_size = new QSpinBox(groupBox_crop_xyz); + spinBox_xyz_erode_size->setObjectName(QString::fromUtf8("spinBox_xyz_erode_size")); + spinBox_xyz_erode_size->setMaximum(50); + + gridLayout_3->addWidget(spinBox_xyz_erode_size, 3, 2, 1, 2); + + + verticalLayout_2->addWidget(groupBox_crop_xyz); + + groupBox_segment_hsv = new QGroupBox(page_input_data_processing); + groupBox_segment_hsv->setObjectName(QString::fromUtf8("groupBox_segment_hsv")); + gridLayout = new QGridLayout(groupBox_segment_hsv); + gridLayout->setSpacing(6); + gridLayout->setContentsMargins(11, 11, 11, 11); + gridLayout->setObjectName(QString::fromUtf8("gridLayout")); + spinBox_h_max = new QSpinBox(groupBox_segment_hsv); + spinBox_h_max->setObjectName(QString::fromUtf8("spinBox_h_max")); + spinBox_h_max->setMaximum(360); + spinBox_h_max->setSingleStep(5); + + gridLayout->addWidget(spinBox_h_max, 0, 3, 1, 1); + + label_s_max = new QLabel(groupBox_segment_hsv); + label_s_max->setObjectName(QString::fromUtf8("label_s_max")); + + gridLayout->addWidget(label_s_max, 1, 2, 1, 1); + + spinBox_s_min = new QSpinBox(groupBox_segment_hsv); + spinBox_s_min->setObjectName(QString::fromUtf8("spinBox_s_min")); + spinBox_s_min->setMaximum(100); + spinBox_s_min->setSingleStep(5); + + gridLayout->addWidget(spinBox_s_min, 1, 1, 1, 1); + + label_h_min = new QLabel(groupBox_segment_hsv); + label_h_min->setObjectName(QString::fromUtf8("label_h_min")); + + gridLayout->addWidget(label_h_min, 0, 0, 1, 1); + + label_h_max = new QLabel(groupBox_segment_hsv); + label_h_max->setObjectName(QString::fromUtf8("label_h_max")); + + gridLayout->addWidget(label_h_max, 0, 2, 1, 1); + + label_s_min = new QLabel(groupBox_segment_hsv); + label_s_min->setObjectName(QString::fromUtf8("label_s_min")); + + gridLayout->addWidget(label_s_min, 1, 0, 1, 1); + + spinBox_v_min = new QSpinBox(groupBox_segment_hsv); + spinBox_v_min->setObjectName(QString::fromUtf8("spinBox_v_min")); + spinBox_v_min->setMaximum(100); + spinBox_v_min->setSingleStep(5); + + gridLayout->addWidget(spinBox_v_min, 2, 1, 1, 1); + + label_v_min = new QLabel(groupBox_segment_hsv); + label_v_min->setObjectName(QString::fromUtf8("label_v_min")); + + gridLayout->addWidget(label_v_min, 2, 0, 1, 1); + + spinBox_v_max = new QSpinBox(groupBox_segment_hsv); + spinBox_v_max->setObjectName(QString::fromUtf8("spinBox_v_max")); + spinBox_v_max->setMaximum(100); + spinBox_v_max->setSingleStep(5); + + gridLayout->addWidget(spinBox_v_max, 2, 3, 1, 1); + + spinBox_h_min = new QSpinBox(groupBox_segment_hsv); + spinBox_h_min->setObjectName(QString::fromUtf8("spinBox_h_min")); + spinBox_h_min->setMaximum(360); + spinBox_h_min->setSingleStep(5); + + gridLayout->addWidget(spinBox_h_min, 0, 1, 1, 1); + + label_v_max = new QLabel(groupBox_segment_hsv); + label_v_max->setObjectName(QString::fromUtf8("label_v_max")); + + gridLayout->addWidget(label_v_max, 2, 2, 1, 1); + + spinBox_s_max = new QSpinBox(groupBox_segment_hsv); + spinBox_s_max->setObjectName(QString::fromUtf8("spinBox_s_max")); + spinBox_s_max->setMaximum(100); + spinBox_s_max->setSingleStep(5); + + gridLayout->addWidget(spinBox_s_max, 1, 3, 1, 1); + + label_hsv_dilate_size = new QLabel(groupBox_segment_hsv); + label_hsv_dilate_size->setObjectName(QString::fromUtf8("label_hsv_dilate_size")); + + gridLayout->addWidget(label_hsv_dilate_size, 3, 0, 1, 2); + + spinBox_hsv_dilate_size = new QSpinBox(groupBox_segment_hsv); + spinBox_hsv_dilate_size->setObjectName(QString::fromUtf8("spinBox_hsv_dilate_size")); + spinBox_hsv_dilate_size->setMaximum(50); + + gridLayout->addWidget(spinBox_hsv_dilate_size, 3, 2, 1, 2); + + checkBox_color_segmentation_inverted = new QCheckBox(groupBox_segment_hsv); + checkBox_color_segmentation_inverted->setObjectName(QString::fromUtf8("checkBox_color_segmentation_inverted")); + + gridLayout->addWidget(checkBox_color_segmentation_inverted, 4, 0, 1, 2); + + checkBox_color_segmentation_enabled = new QCheckBox(groupBox_segment_hsv); + checkBox_color_segmentation_enabled->setObjectName(QString::fromUtf8("checkBox_color_segmentation_enabled")); + + gridLayout->addWidget(checkBox_color_segmentation_enabled, 4, 2, 1, 1); + + spinBox_h_min->raise(); + label_s_min->raise(); + spinBox_v_min->raise(); + spinBox_v_max->raise(); + label_s_max->raise(); + label_v_max->raise(); + spinBox_h_max->raise(); + label_h_min->raise(); + label_h_max->raise(); + label_v_min->raise(); + spinBox_s_max->raise(); + spinBox_s_min->raise(); + checkBox_color_segmentation_inverted->raise(); + label_hsv_dilate_size->raise(); + spinBox_hsv_dilate_size->raise(); + checkBox_color_segmentation_enabled->raise(); + + verticalLayout_2->addWidget(groupBox_segment_hsv); + + verticalSpacer_input_data_processing = new QSpacerItem(20, 40, QSizePolicy::Minimum, QSizePolicy::Expanding); + + verticalLayout_2->addItem(verticalSpacer_input_data_processing); + + toolBox->addItem(page_input_data_processing, QString::fromUtf8("Input data processing")); + page_registration = new QWidget(); + page_registration->setObjectName(QString::fromUtf8("page_registration")); + page_registration->setGeometry(QRect(0, 0, 300, 401)); + verticalLayout_3 = new QVBoxLayout(page_registration); + verticalLayout_3->setSpacing(6); + verticalLayout_3->setContentsMargins(11, 11, 11, 11); + verticalLayout_3->setObjectName(QString::fromUtf8("verticalLayout_3")); + groupBox_convergence = new QGroupBox(page_registration); + groupBox_convergence->setObjectName(QString::fromUtf8("groupBox_convergence")); + gridLayout_4 = new QGridLayout(groupBox_convergence); + gridLayout_4->setSpacing(6); + gridLayout_4->setContentsMargins(11, 11, 11, 11); + gridLayout_4->setObjectName(QString::fromUtf8("gridLayout_4")); + label_epsilon = new QLabel(groupBox_convergence); + label_epsilon->setObjectName(QString::fromUtf8("label_epsilon")); + + gridLayout_4->addWidget(label_epsilon, 0, 0, 1, 1); + + label_max_iterations = new QLabel(groupBox_convergence); + label_max_iterations->setObjectName(QString::fromUtf8("label_max_iterations")); + + gridLayout_4->addWidget(label_max_iterations, 1, 0, 1, 1); + + label_min_overlap = new QLabel(groupBox_convergence); + label_min_overlap->setObjectName(QString::fromUtf8("label_min_overlap")); + + gridLayout_4->addWidget(label_min_overlap, 2, 0, 1, 1); + + label_max_fitness = new QLabel(groupBox_convergence); + label_max_fitness->setObjectName(QString::fromUtf8("label_max_fitness")); + + gridLayout_4->addWidget(label_max_fitness, 3, 0, 1, 1); + + spinBox_max_iterations = new QSpinBox(groupBox_convergence); + spinBox_max_iterations->setObjectName(QString::fromUtf8("spinBox_max_iterations")); + spinBox_max_iterations->setMinimum(1); + spinBox_max_iterations->setMaximum(500); + + gridLayout_4->addWidget(spinBox_max_iterations, 1, 1, 1, 1); + + spinBox_min_overlap = new QSpinBox(groupBox_convergence); + spinBox_min_overlap->setObjectName(QString::fromUtf8("spinBox_min_overlap")); + spinBox_min_overlap->setMaximum(100); + + gridLayout_4->addWidget(spinBox_min_overlap, 2, 1, 1, 1); + + lineEdit_epsilon = new QLineEdit(groupBox_convergence); + lineEdit_epsilon->setObjectName(QString::fromUtf8("lineEdit_epsilon")); + + gridLayout_4->addWidget(lineEdit_epsilon, 0, 1, 1, 1); + + lineEdit_max_fitness = new QLineEdit(groupBox_convergence); + lineEdit_max_fitness->setObjectName(QString::fromUtf8("lineEdit_max_fitness")); + + gridLayout_4->addWidget(lineEdit_max_fitness, 3, 1, 1, 1); + + + verticalLayout_3->addWidget(groupBox_convergence); + + groupBox_correspondence_rejection = new QGroupBox(page_registration); + groupBox_correspondence_rejection->setObjectName(QString::fromUtf8("groupBox_correspondence_rejection")); + gridLayout_2 = new QGridLayout(groupBox_correspondence_rejection); + gridLayout_2->setSpacing(6); + gridLayout_2->setContentsMargins(11, 11, 11, 11); + gridLayout_2->setObjectName(QString::fromUtf8("gridLayout_2")); + label_correspondence_rejection_factor = new QLabel(groupBox_correspondence_rejection); + label_correspondence_rejection_factor->setObjectName(QString::fromUtf8("label_correspondence_rejection_factor")); + + gridLayout_2->addWidget(label_correspondence_rejection_factor, 0, 0, 1, 1); + + doubleSpinBox_correspondence_rejection_factor = new QDoubleSpinBox(groupBox_correspondence_rejection); + doubleSpinBox_correspondence_rejection_factor->setObjectName(QString::fromUtf8("doubleSpinBox_correspondence_rejection_factor")); + doubleSpinBox_correspondence_rejection_factor->setMinimum(1); + doubleSpinBox_correspondence_rejection_factor->setMaximum(100); + + gridLayout_2->addWidget(doubleSpinBox_correspondence_rejection_factor, 0, 1, 1, 1); + + label_correspondence_rejection_max_angle = new QLabel(groupBox_correspondence_rejection); + label_correspondence_rejection_max_angle->setObjectName(QString::fromUtf8("label_correspondence_rejection_max_angle")); + + gridLayout_2->addWidget(label_correspondence_rejection_max_angle, 1, 0, 1, 1); + + spinBox_correspondence_rejection_max_angle = new QSpinBox(groupBox_correspondence_rejection); + spinBox_correspondence_rejection_max_angle->setObjectName(QString::fromUtf8("spinBox_correspondence_rejection_max_angle")); + spinBox_correspondence_rejection_max_angle->setMaximum(180); + + gridLayout_2->addWidget(spinBox_correspondence_rejection_max_angle, 1, 1, 1, 1); + + + verticalLayout_3->addWidget(groupBox_correspondence_rejection); + + verticalSpacer_registration = new QSpacerItem(20, 40, QSizePolicy::Minimum, QSizePolicy::Expanding); + + verticalLayout_3->addItem(verticalSpacer_registration); + + toolBox->addItem(page_registration, QString::fromUtf8("Registration")); + page_integration = new QWidget(); + page_integration->setObjectName(QString::fromUtf8("page_integration")); + page_integration->setGeometry(QRect(0, 0, 300, 401)); + verticalLayout_4 = new QVBoxLayout(page_integration); + verticalLayout_4->setSpacing(6); + verticalLayout_4->setContentsMargins(11, 11, 11, 11); + verticalLayout_4->setObjectName(QString::fromUtf8("verticalLayout_4")); + groupBox_averaging = new QGroupBox(page_integration); + groupBox_averaging->setObjectName(QString::fromUtf8("groupBox_averaging")); + gridLayout_5 = new QGridLayout(groupBox_averaging); + gridLayout_5->setSpacing(6); + gridLayout_5->setContentsMargins(11, 11, 11, 11); + gridLayout_5->setObjectName(QString::fromUtf8("gridLayout_5")); + label_max_squared_distance = new QLabel(groupBox_averaging); + label_max_squared_distance->setObjectName(QString::fromUtf8("label_max_squared_distance")); + + gridLayout_5->addWidget(label_max_squared_distance, 0, 0, 1, 1); + + lineEdit_max_squared_distance = new QLineEdit(groupBox_averaging); + lineEdit_max_squared_distance->setObjectName(QString::fromUtf8("lineEdit_max_squared_distance")); + + gridLayout_5->addWidget(lineEdit_max_squared_distance, 0, 1, 1, 1); + + label_averaging_max_angle = new QLabel(groupBox_averaging); + label_averaging_max_angle->setObjectName(QString::fromUtf8("label_averaging_max_angle")); + + gridLayout_5->addWidget(label_averaging_max_angle, 1, 0, 1, 1); + + spinBox_averaging_max_angle = new QSpinBox(groupBox_averaging); + spinBox_averaging_max_angle->setObjectName(QString::fromUtf8("spinBox_averaging_max_angle")); + spinBox_averaging_max_angle->setMaximum(180); + + gridLayout_5->addWidget(spinBox_averaging_max_angle, 1, 1, 1, 1); + + + verticalLayout_4->addWidget(groupBox_averaging); + + groupBox_outlier_removal = new QGroupBox(page_integration); + groupBox_outlier_removal->setObjectName(QString::fromUtf8("groupBox_outlier_removal")); + gridLayout_6 = new QGridLayout(groupBox_outlier_removal); + gridLayout_6->setSpacing(6); + gridLayout_6->setContentsMargins(11, 11, 11, 11); + gridLayout_6->setObjectName(QString::fromUtf8("gridLayout_6")); + label_max_age = new QLabel(groupBox_outlier_removal); + label_max_age->setObjectName(QString::fromUtf8("label_max_age")); + + gridLayout_6->addWidget(label_max_age, 0, 0, 1, 1); + + spinBox_max_age = new QSpinBox(groupBox_outlier_removal); + spinBox_max_age->setObjectName(QString::fromUtf8("spinBox_max_age")); + spinBox_max_age->setMinimum(1); + spinBox_max_age->setMaximum(100); + + gridLayout_6->addWidget(spinBox_max_age, 0, 1, 1, 1); + + label_min_directions = new QLabel(groupBox_outlier_removal); + label_min_directions->setObjectName(QString::fromUtf8("label_min_directions")); + + gridLayout_6->addWidget(label_min_directions, 1, 0, 1, 1); + + spinBox_min_directions = new QSpinBox(groupBox_outlier_removal); + spinBox_min_directions->setObjectName(QString::fromUtf8("spinBox_min_directions")); + spinBox_min_directions->setMinimum(1); + spinBox_min_directions->setMaximum(100); + + gridLayout_6->addWidget(spinBox_min_directions, 1, 1, 1, 1); + + + verticalLayout_4->addWidget(groupBox_outlier_removal); + + verticalSpacer_integration = new QSpacerItem(20, 40, QSizePolicy::Minimum, QSizePolicy::Expanding); + + verticalLayout_4->addItem(verticalSpacer_integration); + + toolBox->addItem(page_integration, QString::fromUtf8("Integration")); + + verticalLayout->addWidget(toolBox); + + dockWidget->setWidget(dockWidgetContents); + MainWindow->addDockWidget(static_cast(2), dockWidget); + toolBar = new QToolBar(MainWindow); + toolBar->setObjectName(QString::fromUtf8("toolBar")); + MainWindow->addToolBar(Qt::TopToolBarArea, toolBar); + menuBar = new QMenuBar(MainWindow); + menuBar->setObjectName(QString::fromUtf8("menuBar")); + menuBar->setGeometry(QRect(0, 0, 1008, 22)); + menuFile = new QMenu(menuBar); + menuFile->setObjectName(QString::fromUtf8("menuFile")); + MainWindow->setMenuBar(menuBar); +#ifndef QT_NO_SHORTCUT + label_z_min->setBuddy(spinBox_z_min); + label_x_min->setBuddy(spinBox_x_min); + label_xyz_erode_size->setBuddy(spinBox_xyz_erode_size); + label_y_min->setBuddy(spinBox_y_min); + label_x_max->setBuddy(spinBox_x_max); + label_y_max->setBuddy(spinBox_y_max); + label_z_max->setBuddy(spinBox_z_max); + label_s_max->setBuddy(spinBox_s_max); + label_h_min->setBuddy(spinBox_h_min); + label_h_max->setBuddy(spinBox_h_max); + label_s_min->setBuddy(spinBox_s_min); + label_v_min->setBuddy(spinBox_v_min); + label_v_max->setBuddy(spinBox_v_max); + label_hsv_dilate_size->setBuddy(spinBox_hsv_dilate_size); + label_max_iterations->setBuddy(spinBox_max_iterations); + label_min_overlap->setBuddy(spinBox_min_overlap); + label_correspondence_rejection_factor->setBuddy(doubleSpinBox_correspondence_rejection_factor); + label_correspondence_rejection_max_angle->setBuddy(spinBox_correspondence_rejection_max_angle); +#endif // QT_NO_SHORTCUT + QWidget::setTabOrder(toolButton_1, toolButton_2); + QWidget::setTabOrder(toolButton_2, toolButton_3); + QWidget::setTabOrder(toolButton_3, toolButton_4); + QWidget::setTabOrder(toolButton_4, toolButton_5); + QWidget::setTabOrder(toolButton_5, toolButton_0); + QWidget::setTabOrder(toolButton_0, spinBox_x_min); + QWidget::setTabOrder(spinBox_x_min, spinBox_x_max); + QWidget::setTabOrder(spinBox_x_max, spinBox_y_min); + QWidget::setTabOrder(spinBox_y_min, spinBox_y_max); + QWidget::setTabOrder(spinBox_y_max, spinBox_z_min); + QWidget::setTabOrder(spinBox_z_min, spinBox_z_max); + QWidget::setTabOrder(spinBox_z_max, spinBox_xyz_erode_size); + QWidget::setTabOrder(spinBox_xyz_erode_size, spinBox_h_min); + QWidget::setTabOrder(spinBox_h_min, spinBox_h_max); + QWidget::setTabOrder(spinBox_h_max, spinBox_s_min); + QWidget::setTabOrder(spinBox_s_min, spinBox_s_max); + QWidget::setTabOrder(spinBox_s_max, spinBox_v_min); + QWidget::setTabOrder(spinBox_v_min, spinBox_v_max); + QWidget::setTabOrder(spinBox_v_max, spinBox_hsv_dilate_size); + QWidget::setTabOrder(spinBox_hsv_dilate_size, checkBox_color_segmentation_inverted); + QWidget::setTabOrder(checkBox_color_segmentation_inverted, checkBox_color_segmentation_enabled); + QWidget::setTabOrder(checkBox_color_segmentation_enabled, lineEdit_epsilon); + QWidget::setTabOrder(lineEdit_epsilon, spinBox_max_iterations); + QWidget::setTabOrder(spinBox_max_iterations, spinBox_min_overlap); + QWidget::setTabOrder(spinBox_min_overlap, lineEdit_max_fitness); + QWidget::setTabOrder(lineEdit_max_fitness, doubleSpinBox_correspondence_rejection_factor); + QWidget::setTabOrder(doubleSpinBox_correspondence_rejection_factor, spinBox_correspondence_rejection_max_angle); + QWidget::setTabOrder(spinBox_correspondence_rejection_max_angle, lineEdit_max_squared_distance); + QWidget::setTabOrder(lineEdit_max_squared_distance, spinBox_averaging_max_angle); + QWidget::setTabOrder(spinBox_averaging_max_angle, spinBox_max_age); + QWidget::setTabOrder(spinBox_max_age, spinBox_min_directions); + + toolBar->addAction(actionReset_camera); + toolBar->addAction(actionToggle_coloring); + toolBar->addAction(actionMesh_representation); + toolBar->addAction(actionHelp); + menuBar->addAction(menuFile->menuAction()); + menuFile->addAction(actionSaveAs); + + retranslateUi(MainWindow); + QObject::connect(spinBox_x_min, SIGNAL(valueChanged(int)), MainWindow, SLOT(setXMin(int))); + QObject::connect(spinBox_x_max, SIGNAL(valueChanged(int)), MainWindow, SLOT(setXMax(int))); + QObject::connect(spinBox_y_min, SIGNAL(valueChanged(int)), MainWindow, SLOT(setYMin(int))); + QObject::connect(spinBox_y_max, SIGNAL(valueChanged(int)), MainWindow, SLOT(setYMax(int))); + QObject::connect(spinBox_z_min, SIGNAL(valueChanged(int)), MainWindow, SLOT(setZMin(int))); + QObject::connect(spinBox_z_max, SIGNAL(valueChanged(int)), MainWindow, SLOT(setZMax(int))); + QObject::connect(spinBox_h_min, SIGNAL(valueChanged(int)), MainWindow, SLOT(setHMin(int))); + QObject::connect(spinBox_h_max, SIGNAL(valueChanged(int)), MainWindow, SLOT(setHMax(int))); + QObject::connect(spinBox_s_min, SIGNAL(valueChanged(int)), MainWindow, SLOT(setSMin(int))); + QObject::connect(spinBox_s_max, SIGNAL(valueChanged(int)), MainWindow, SLOT(setSMax(int))); + QObject::connect(spinBox_v_min, SIGNAL(valueChanged(int)), MainWindow, SLOT(setVMin(int))); + QObject::connect(spinBox_v_max, SIGNAL(valueChanged(int)), MainWindow, SLOT(setVMax(int))); + QObject::connect(checkBox_color_segmentation_inverted, SIGNAL(toggled(bool)), MainWindow, SLOT(setColorSegmentationInverted(bool))); + QObject::connect(spinBox_xyz_erode_size, SIGNAL(valueChanged(int)), MainWindow, SLOT(setXYZErodeSize(int))); + QObject::connect(spinBox_hsv_dilate_size, SIGNAL(valueChanged(int)), MainWindow, SLOT(setHSVDilateSize(int))); + QObject::connect(lineEdit_epsilon, SIGNAL(editingFinished()), MainWindow, SLOT(setEpsilon())); + QObject::connect(spinBox_max_iterations, SIGNAL(valueChanged(int)), MainWindow, SLOT(setMaxIterations(int))); + QObject::connect(spinBox_min_overlap, SIGNAL(valueChanged(int)), MainWindow, SLOT(setMinOverlap(int))); + QObject::connect(lineEdit_max_fitness, SIGNAL(editingFinished()), MainWindow, SLOT(setMaxFitness())); + QObject::connect(doubleSpinBox_correspondence_rejection_factor, SIGNAL(valueChanged(double)), MainWindow, SLOT(setCorrespondenceRejectionFactor(double))); + QObject::connect(spinBox_correspondence_rejection_max_angle, SIGNAL(valueChanged(int)), MainWindow, SLOT(setCorrespondenceRejectionMaxAngle(int))); + QObject::connect(lineEdit_max_squared_distance, SIGNAL(editingFinished()), MainWindow, SLOT(setMaxSquaredDistance())); + QObject::connect(spinBox_averaging_max_angle, SIGNAL(valueChanged(int)), MainWindow, SLOT(setAveragingMaxAngle(int))); + QObject::connect(spinBox_max_age, SIGNAL(valueChanged(int)), MainWindow, SLOT(setMaxAge(int))); + QObject::connect(spinBox_min_directions, SIGNAL(valueChanged(int)), MainWindow, SLOT(setMinDirections(int))); + QObject::connect(checkBox_color_segmentation_enabled, SIGNAL(toggled(bool)), MainWindow, SLOT(setColorSegmentationEnabled(bool))); + + toolBox->setCurrentIndex(0); + + + QMetaObject::connectSlotsByName(MainWindow); + } // setupUi + + void retranslateUi(QMainWindow *MainWindow) + { + MainWindow->setWindowTitle(QApplication::translate("MainWindow", "MainWindow", 0, QApplication::UnicodeUTF8)); + actionHelp->setText(QApplication::translate("MainWindow", "Help", 0, QApplication::UnicodeUTF8)); + actionReset_camera->setText(QApplication::translate("MainWindow", "Reset camera", 0, QApplication::UnicodeUTF8)); +#ifndef QT_NO_TOOLTIP + actionReset_camera->setToolTip(QApplication::translate("MainWindow", "

Reset the camera (Shortcut: c)

", 0, QApplication::UnicodeUTF8)); +#endif // QT_NO_TOOLTIP + actionToggle_coloring->setText(QApplication::translate("MainWindow", "Coloring", 0, QApplication::UnicodeUTF8)); +#ifndef QT_NO_TOOLTIP + actionToggle_coloring->setToolTip(QApplication::translate("MainWindow", "

Toggle the coloring (Shortcut: k):

- RGB

- One color

- Visibility-confidence

", 0, QApplication::UnicodeUTF8)); +#endif // QT_NO_TOOLTIP + actionMesh_representation->setText(QApplication::translate("MainWindow", "Mesh representation", 0, QApplication::UnicodeUTF8)); +#ifndef QT_NO_TOOLTIP + actionMesh_representation->setToolTip(QApplication::translate("MainWindow", "

Toggle the display of the mesh (Shortcut: s):

- Points

- Wireframe

- Closed surface

", 0, QApplication::UnicodeUTF8)); +#endif // QT_NO_TOOLTIP + actionSaveAs->setText(QApplication::translate("MainWindow", "Save As ...", 0, QApplication::UnicodeUTF8)); + actionSaveAs->setShortcut(QApplication::translate("MainWindow", "Ctrl+S", 0, QApplication::UnicodeUTF8)); +#ifndef QT_NO_TOOLTIP + toolButton_1->setToolTip(QApplication::translate("MainWindow", "

Shows the unprocessed input data (Shortcut: 1).

", 0, QApplication::UnicodeUTF8)); +#endif // QT_NO_TOOLTIP + toolButton_1->setText(QApplication::translate("MainWindow", "Input", 0, QApplication::UnicodeUTF8)); +#ifndef QT_NO_TOOLTIP + toolButton_2->setToolTip(QApplication::translate("MainWindow", "

Shows the processed input data (Shortcut: 2).

", 0, QApplication::UnicodeUTF8)); +#endif // QT_NO_TOOLTIP + toolButton_2->setText(QApplication::translate("MainWindow", "Processed", 0, QApplication::UnicodeUTF8)); +#ifndef QT_NO_TOOLTIP + toolButton_3->setToolTip(QApplication::translate("MainWindow", "

Continuous registration (Shortcut: 3).

", 0, QApplication::UnicodeUTF8)); +#endif // QT_NO_TOOLTIP + toolButton_3->setText(QApplication::translate("MainWindow", "Continuous registration", 0, QApplication::UnicodeUTF8)); +#ifndef QT_NO_TOOLTIP + toolButton_4->setToolTip(QApplication::translate("MainWindow", "

Registers new data once and returns to showing the processed input data (Shortcut: 4).

", 0, QApplication::UnicodeUTF8)); +#endif // QT_NO_TOOLTIP + toolButton_4->setText(QApplication::translate("MainWindow", "Single registration", 0, QApplication::UnicodeUTF8)); +#ifndef QT_NO_TOOLTIP + toolButton_5->setToolTip(QApplication::translate("MainWindow", "

Shows the acquired model (Shortcut: 5).

", 0, QApplication::UnicodeUTF8)); +#endif // QT_NO_TOOLTIP + toolButton_5->setText(QApplication::translate("MainWindow", "Show model", 0, QApplication::UnicodeUTF8)); +#ifndef QT_NO_TOOLTIP + toolButton_6->setToolTip(QApplication::translate("MainWindow", "

Removes all unfit points (Shortcut: 6)

", 0, QApplication::UnicodeUTF8)); +#endif // QT_NO_TOOLTIP + toolButton_6->setText(QApplication::translate("MainWindow", "Clean", 0, QApplication::UnicodeUTF8)); +#ifndef QT_NO_TOOLTIP + toolButton_0->setToolTip(QApplication::translate("MainWindow", "

Reset the scanning pipeline (Shortcut: 0).

", 0, QApplication::UnicodeUTF8)); +#endif // QT_NO_TOOLTIP + toolButton_0->setText(QApplication::translate("MainWindow", "Reset", 0, QApplication::UnicodeUTF8)); + dockWidget->setWindowTitle(QApplication::translate("MainWindow", "Settings", 0, QApplication::UnicodeUTF8)); +#ifndef QT_NO_TOOLTIP + toolBox->setToolTip(QString()); +#endif // QT_NO_TOOLTIP +#ifndef QT_NO_TOOLTIP + groupBox_crop_xyz->setToolTip(QString()); +#endif // QT_NO_TOOLTIP + groupBox_crop_xyz->setTitle(QApplication::translate("MainWindow", "Crop coordinates", 0, QApplication::UnicodeUTF8)); + label_z_min->setText(QApplication::translate("MainWindow", "z min", 0, QApplication::UnicodeUTF8)); + label_x_min->setText(QApplication::translate("MainWindow", "x min", 0, QApplication::UnicodeUTF8)); + label_xyz_erode_size->setText(QApplication::translate("MainWindow", "Erode size", 0, QApplication::UnicodeUTF8)); + label_y_min->setText(QApplication::translate("MainWindow", "y min", 0, QApplication::UnicodeUTF8)); + label_x_max->setText(QApplication::translate("MainWindow", "x max", 0, QApplication::UnicodeUTF8)); + label_y_max->setText(QApplication::translate("MainWindow", "y max", 0, QApplication::UnicodeUTF8)); + label_z_max->setText(QApplication::translate("MainWindow", "z max", 0, QApplication::UnicodeUTF8)); +#ifndef QT_NO_TOOLTIP + groupBox_segment_hsv->setToolTip(QString()); +#endif // QT_NO_TOOLTIP + groupBox_segment_hsv->setTitle(QApplication::translate("MainWindow", "Color segmentation", 0, QApplication::UnicodeUTF8)); + label_s_max->setText(QApplication::translate("MainWindow", "S max", 0, QApplication::UnicodeUTF8)); + label_h_min->setText(QApplication::translate("MainWindow", "H min", 0, QApplication::UnicodeUTF8)); + label_h_max->setText(QApplication::translate("MainWindow", "H max", 0, QApplication::UnicodeUTF8)); + label_s_min->setText(QApplication::translate("MainWindow", "S min", 0, QApplication::UnicodeUTF8)); + label_v_min->setText(QApplication::translate("MainWindow", "V min", 0, QApplication::UnicodeUTF8)); + label_v_max->setText(QApplication::translate("MainWindow", "V max", 0, QApplication::UnicodeUTF8)); + label_hsv_dilate_size->setText(QApplication::translate("MainWindow", "Dilate size", 0, QApplication::UnicodeUTF8)); + checkBox_color_segmentation_inverted->setText(QApplication::translate("MainWindow", "Inverted", 0, QApplication::UnicodeUTF8)); + checkBox_color_segmentation_enabled->setText(QApplication::translate("MainWindow", "Enabled", 0, QApplication::UnicodeUTF8)); + toolBox->setItemText(toolBox->indexOf(page_input_data_processing), QApplication::translate("MainWindow", "Input data processing", 0, QApplication::UnicodeUTF8)); + groupBox_convergence->setTitle(QApplication::translate("MainWindow", "Convergence and failure criteria", 0, QApplication::UnicodeUTF8)); + label_epsilon->setText(QApplication::translate("MainWindow", "Epsilon", 0, QApplication::UnicodeUTF8)); + label_max_iterations->setText(QApplication::translate("MainWindow", "Max iterations", 0, QApplication::UnicodeUTF8)); + label_min_overlap->setText(QApplication::translate("MainWindow", "Min overlap", 0, QApplication::UnicodeUTF8)); + label_max_fitness->setText(QApplication::translate("MainWindow", "Max fitness", 0, QApplication::UnicodeUTF8)); + groupBox_correspondence_rejection->setTitle(QApplication::translate("MainWindow", "Correspondence rejection", 0, QApplication::UnicodeUTF8)); + label_correspondence_rejection_factor->setText(QApplication::translate("MainWindow", "Factor", 0, QApplication::UnicodeUTF8)); + label_correspondence_rejection_max_angle->setText(QApplication::translate("MainWindow", "Max angle", 0, QApplication::UnicodeUTF8)); + toolBox->setItemText(toolBox->indexOf(page_registration), QApplication::translate("MainWindow", "Registration", 0, QApplication::UnicodeUTF8)); + groupBox_averaging->setTitle(QApplication::translate("MainWindow", "Averaging", 0, QApplication::UnicodeUTF8)); + label_max_squared_distance->setText(QApplication::translate("MainWindow", "Max squared distance", 0, QApplication::UnicodeUTF8)); + label_averaging_max_angle->setText(QApplication::translate("MainWindow", "Max angle", 0, QApplication::UnicodeUTF8)); + groupBox_outlier_removal->setTitle(QApplication::translate("MainWindow", "Outlier removal", 0, QApplication::UnicodeUTF8)); + label_max_age->setText(QApplication::translate("MainWindow", "Max age", 0, QApplication::UnicodeUTF8)); + label_min_directions->setText(QApplication::translate("MainWindow", "Min directions", 0, QApplication::UnicodeUTF8)); + toolBox->setItemText(toolBox->indexOf(page_integration), QApplication::translate("MainWindow", "Integration", 0, QApplication::UnicodeUTF8)); + toolBar->setWindowTitle(QApplication::translate("MainWindow", "toolBar", 0, QApplication::UnicodeUTF8)); + menuFile->setTitle(QApplication::translate("MainWindow", "File", 0, QApplication::UnicodeUTF8)); + } // retranslateUi + +}; + +namespace Ui { + class MainWindow: public Ui_MainWindow {}; +} // namespace Ui + +QT_END_NAMESPACE + +#endif // UI_MAIN_WINDOW_H diff --git a/pcl-1.7/pcl/in_hand_scanner/utils.h b/pcl-1.7/pcl/in_hand_scanner/utils.h new file mode 100644 index 0000000..2fe5b1e --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/utils.h @@ -0,0 +1,57 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_APPS_IN_HAND_SCANNER_UTILS_H +#define PCL_APPS_IN_HAND_SCANNER_UTILS_H + +namespace pcl +{ + namespace ihs + { + /** \brief Clamp the value to the given range. All values smaller than min are set to min and all values bigger than max are set to max. */ + template inline T + clamp (const T value, const T min, const T max) + { + return (value < min ? min : value > max ? max : value); + } + } // End namespace ihs +} // End namespace pcl + +#endif // PCL_APPS_IN_HAND_SCANNER_UTILS_H diff --git a/pcl-1.7/pcl/in_hand_scanner/visibility_confidence.h b/pcl-1.7/pcl/in_hand_scanner/visibility_confidence.h new file mode 100644 index 0000000..11fa7a6 --- /dev/null +++ b/pcl-1.7/pcl/in_hand_scanner/visibility_confidence.h @@ -0,0 +1,90 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_APPS_IN_HAND_SCANNER_VISIBILITY_CONFIDENCE_H +#define PCL_APPS_IN_HAND_SCANNER_VISIBILITY_CONFIDENCE_H + +#include + +#include +#include + +namespace pcl +{ + namespace ihs + { + // - Frequency 3 Icosahedron where each vertex corresponds to a viewing direction + // - First vertex aligned to z-axis + // - Removed vertices with z < 0.3 + // -> 31 directions, fitting nicely into a 32 bit integer + // -> Very oblique angles are not considered + class PCL_EXPORTS Dome + { + public: + + static const int num_directions = 31; + typedef Eigen::Matrix Vertices; + + Dome (); + + Vertices + getVertices () const; + + private: + + Vertices vertices_; + + public: + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS void + addDirection (const Eigen::Vector4f& normal, + const Eigen::Vector4f& direction, + uint32_t& directions); + + PCL_EXPORTS unsigned int + countDirections (const uint32_t directions); + + } // End namespace ihs +} // End namespace pcl + +#endif // PCL_APPS_IN_HAND_SCANNER_VISIBILITY_CONFIDENCE_H diff --git a/pcl-1.7/pcl/io/ascii_io.h b/pcl-1.7/pcl/io/ascii_io.h new file mode 100644 index 0000000..45c7717 --- /dev/null +++ b/pcl-1.7/pcl/io/ascii_io.h @@ -0,0 +1,177 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_IO_ASCII_IO_H_ +#define PCL_IO_ASCII_IO_H_ + +#include +#include +#include + + +namespace pcl +{ + /** \brief Ascii Point Cloud Reader. + * Read any ASCII file by setting the separating characters and input point fields. + * + * \author Adam Stambler (adasta@gmail.com) + * \ingroup io + */ + class PCL_EXPORTS ASCIIReader : public FileReader + { + public: + ASCIIReader (); + virtual ~ASCIIReader (); + using FileReader::read; + + /* Load only the meta information (number of points, their types, etc), + * and not the points themselves, from a given FILE file. Useful for fast + * evaluation of the underlying data structure. + * + * Returns: + * * < 0 (-1) on error + * * > 0 on success + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant point cloud dataset (only the header will be filled) + * \param[out] origin the sensor acquisition origin (only for > FILE_V7 - null if not present) + * \param[out] orientation the sensor acquisition orientation (only for > FILE_V7 - identity if not present) + * \param[out] file_version the FILE version of the file (either FILE_V6 or FILE_V7) + * \param[out] data_type the type of data (binary data=1, ascii=0, etc) + * \param[out] data_idx the offset of cloud data within the file + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + */ + virtual int + readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, + int &file_version, int &data_type, unsigned int &data_idx, const int offset = 0) ; + + + /** \brief Read a point cloud data from a FILE file and store it into a pcl/PCLPointCloud2. + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * \param[out] origin the sensor acquisition origin (only for > FILE_V7 - null if not present) + * \param[out] orientation the sensor acquisition orientation (only for > FILE_V7 - identity if not present) + * \param[out] file_version the FILE version of the file (either FILE_V6 or FILE_V7) + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + */ + virtual int + read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &file_version, + const int offset = 0); + + /** \brief Set the ascii file point fields using a list of fields. + * \param[in] fields is a list of point fields, in order, in the input ascii file + */ + void + setInputFields (const std::vector& fields); + + + /** \brief Set the ascii file point fields using a point type. + * \param[in] p a point type + */ + template + void setInputFields (const PointT p = PointT ()); + + + /** \brief Set the Separting characters for the ascii point fields 2. + * \param[in] chars string of separating characters + * Sets the separating characters for the point fields. The + * default separating characters are " \n\t," + */ + void + setSepChars (const std::string &chars); + + /** \brief Set the extension of the ascii point file type. + * \param[in] ext extension (example : ".txt" or ".xyz" ) + */ + void + setExtension (const std::string &ext) { extension_ = ext; } + + protected: + std::string sep_chars_; + std::string extension_; + std::vector fields_; + std::string name_; + + + /** \brief Parses token based on field type. + * \param[in] token string representation of point fields + * \param[in] field token point field type + * \param[out] data_target address that the point field data should be assigned to + * returns the size of the parsed point field in bytes + */ + int + parse (const std::string& token, const pcl::PCLPointField& field, uint8_t* data_target); + + /** \brief Returns the size in bytes of a point field type. + * \param[in] type point field type + * returns the size of the type in bytes + */ + uint32_t + typeSize (int type); + }; +} + +////////////////////////////////////////////////////////////////////////////// +template void +pcl::ASCIIReader::setInputFields (const PointT p) +{ + (void) p; + + pcl::getFields (fields_); + + // Remove empty fields and adjust offset + int offset =0; + for (std::vector::iterator field_iter = fields_.begin (); + field_iter != fields_.end (); field_iter++) + { + if (field_iter->name == "_") + field_iter = fields_.erase (field_iter); + field_iter->offset = offset; + offset += typeSize (field_iter->datatype); + } +} + +#endif // PCL_IO_ASCII_IO_H_ diff --git a/pcl-1.7/pcl/io/boost.h b/pcl-1.7/pcl/io/boost.h new file mode 100644 index 0000000..1e6b5a5 --- /dev/null +++ b/pcl-1.7/pcl/io/boost.h @@ -0,0 +1,84 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _PCL_IO_BOOST_H_ +#define _PCL_IO_BOOST_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif +#ifndef __CUDACC__ +//https://bugreports.qt-project.org/browse/QTBUG-22829 +#ifndef Q_MOC_RUN +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#ifndef Q_MOC_RUN +#include +#endif +#include +#include +#include +#include +#include +#if BOOST_VERSION >= 104900 +#include +#endif +#include +#define BOOST_PARAMETER_MAX_ARITY 7 +#include +#include +#endif +#endif +#endif // _PCL_IO_BOOST_H_ + diff --git a/pcl-1.7/pcl/io/debayer.h b/pcl-1.7/pcl/io/debayer.h new file mode 100644 index 0000000..c3a6f4d --- /dev/null +++ b/pcl-1.7/pcl/io/debayer.h @@ -0,0 +1,84 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_IO_DEBAYER_H +#define PCL_IO_DEBAYER_H + +#include +#include + +namespace pcl +{ + namespace io + { + /** \brief Various debayering methods. + * \author Suat Gedikli + * \ingroup io + */ + class PCL_EXPORTS DeBayer + { + public: + // Debayering methods + void + debayerBilinear ( + const unsigned char *bayer_pixel, unsigned char *rgb_buffer, + unsigned width, unsigned height, + int bayer_line_step = 0, + int bayer_line_step2 = 0, + unsigned rgb_line_step = 0) const; + + void + debayerEdgeAware ( + const unsigned char *bayer_pixel, unsigned char *rgb_buffer, + unsigned width, unsigned height, + int bayer_line_step = 0, + int bayer_line_step2 = 0, + unsigned rgb_line_step = 0) const; + + void + debayerEdgeAwareWeighted ( + const unsigned char *bayer_pixel, unsigned char *rgb_buffer, + unsigned width, unsigned height, + int bayer_line_step = 0, + int bayer_line_step2 = 0, + unsigned rgb_line_step = 0) const; + }; + } +} + +#endif // PCL_IO_DEBAYER_H + diff --git a/pcl-1.7/pcl/io/dinast_grabber.h b/pcl-1.7/pcl/io/dinast_grabber.h new file mode 100644 index 0000000..429a228 --- /dev/null +++ b/pcl-1.7/pcl/io/dinast_grabber.h @@ -0,0 +1,217 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_IO_DINAST_GRABBER_ +#define PCL_IO_DINAST_GRABBER_ + +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Grabber for DINAST devices (i.e., IPA-1002, IPA-1110, IPA-2001) + * \author Marco A. Gutierrez + * \ingroup io + */ + class PCL_EXPORTS DinastGrabber: public Grabber + { + // Define callback signature typedefs + typedef void (sig_cb_dinast_point_cloud) (const boost::shared_ptr >&); + + public: + /** \brief Constructor that sets up the grabber constants. + * \param[in] device_position Number corresponding the device to grab + */ + DinastGrabber (const int device_position=1); + + /** \brief Destructor. It never throws. */ + virtual ~DinastGrabber () throw (); + + /** \brief Check if the grabber is running + * \return true if grabber is running / streaming. False otherwise. + */ + virtual bool + isRunning () const; + + /** \brief Returns the name of the concrete subclass, DinastGrabber. + * \return DinastGrabber. + */ + virtual std::string + getName () const + { return (std::string ("DinastGrabber")); } + + /** \brief Start the data acquisition process. + */ + virtual void + start (); + + /** \brief Stop the data acquisition process. + */ + virtual void + stop (); + + /** \brief Obtain the number of frames per second (FPS). */ + virtual float + getFramesPerSecond () const; + + /** \brief Get the version number of the currently opened device + */ + std::string + getDeviceVersion (); + + protected: + + /** \brief On initialization processing. */ + void + onInit (const int device_id); + + /** \brief Setup a Dinast 3D camera device + * \param[in] device_position Number corresponding the device to grab + * \param[in] id_vendor The ID of the camera vendor (should be 0x18d1) + * \param[in] id_product The ID of the product (should be 0x1402) + */ + void + setupDevice (int device_position, + const int id_vendor = 0x18d1, + const int id_product = 0x1402); + + /** \brief Send a RX data packet request + * \param[in] req_code the request to send (the request field for the setup packet) + * \param buffer + * \param[in] length the length field for the setup packet. The data buffer should be at least this size. + */ + bool + USBRxControlData (const unsigned char req_code, + unsigned char *buffer, + int length); + + /** \brief Send a TX data packet request + * \param[in] req_code the request to send (the request field for the setup packet) + * \param buffer + * \param[in] length the length field for the setup packet. The data buffer should be at least this size. + */ + bool + USBTxControlData (const unsigned char req_code, + unsigned char *buffer, + int length); + + /** \brief Check if we have a header in the global buffer, and return the position of the next valid image. + * \note If the image in the buffer is partial, return -1, as we have to wait until we add more data to it. + * \return the position of the next valid image (i.e., right after a valid header) or -1 in case the buffer + * either doesn't have an image or has a partial image + */ + int + checkHeader (); + + /** \brief Read image data and leaves it on image_ + */ + void + readImage (); + + /** \brief Obtains XYZI Point Cloud from the image of the camera + * \return the point cloud from the image data + */ + pcl::PointCloud::Ptr + getXYZIPointCloud (); + + /** \brief The function in charge of getting the data from the camera + */ + void + captureThreadFunction (); + + /** \brief Width of image */ + int image_width_; + + /** \brief Height of image */ + int image_height_; + + /** \brief Total size of image */ + int image_size_; + + /** \brief Length of a sync packet */ + int sync_packet_size_; + + double dist_max_2d_; + + /** \brief diagonal Field of View*/ + double fov_; + + /** \brief Size of pixel */ + enum pixel_size { RAW8=1, RGB16=2, RGB24=3, RGB32=4 }; + + /** \brief The libusb context*/ + libusb_context *context_; + + /** \brief the actual device_handle for the camera */ + struct libusb_device_handle *device_handle_; + + /** \brief Temporary USB read buffer, since we read two RGB16 images at a time size is the double of two images + * plus a sync packet. + */ + unsigned char *raw_buffer_ ; + + /** \brief Global circular buffer */ + boost::circular_buffer g_buffer_; + + /** \brief Bulk endpoint address value */ + unsigned char bulk_ep_; + + /** \brief Device command values */ + enum { CMD_READ_START=0xC7, CMD_READ_STOP=0xC8, CMD_GET_VERSION=0xDC, CMD_SEND_DATA=0xDE }; + + unsigned char *image_; + + /** \brief Since there is no header after the first image, we need to save the state */ + bool second_image_; + + bool running_; + + boost::thread capture_thread_; + + mutable boost::mutex capture_mutex_; + boost::signals2::signal* point_cloud_signal_; + }; +} //namespace pcl + +#endif // PCL_IO_DINAST_GRABBER_ diff --git a/pcl-1.7/pcl/io/eigen.h b/pcl-1.7/pcl/io/eigen.h new file mode 100644 index 0000000..565746e --- /dev/null +++ b/pcl-1.7/pcl/io/eigen.h @@ -0,0 +1,48 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _PCL_IO_EIGEN_H_ +#define _PCL_IO_EIGEN_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include + +#endif // _PCL_IO_EIGEN_H_ + diff --git a/pcl-1.7/pcl/io/file_grabber.h b/pcl-1.7/pcl/io/file_grabber.h new file mode 100644 index 0000000..7a0812b --- /dev/null +++ b/pcl-1.7/pcl/io/file_grabber.h @@ -0,0 +1,92 @@ + +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: file_grabber.h 8413 2013-01-15 08:37:39Z sdmiller $ + * + */ + +#pragma once +#ifndef PCL_IO_FILE_GRABBER_H_ +#define PCL_IO_FILE_GRABBER_H_ + +#include + +namespace pcl +{ + /** \brief FileGrabber provides a container-style interface for grabbers which operate on fixed-size input + * \author Stephen Miller + * \ingroup io + */ + template + class PCL_EXPORTS FileGrabber + { + public: + + /** \brief Empty destructor */ + virtual ~FileGrabber () {} + + /** \brief operator[] Returns the idx-th cloud in the dataset, without bounds checking. + * Note that in the future, this could easily be modified to do caching + * \param[in] idx The frame to load + */ + virtual const boost::shared_ptr< const pcl::PointCloud > + operator[] (size_t idx) const = 0; + + /** \brief size Returns the number of clouds currently loaded by the grabber */ + virtual size_t + size () const = 0; + + /** \brief at Returns the idx-th cloud in the dataset, with bounds checking + * \param[in] idx The frame to load + */ + virtual const boost::shared_ptr< const pcl::PointCloud > + at (size_t idx) const + { + if (idx >= size ()) + { + // Throw error + throw pcl::IOException ("[pcl::FileGrabber] Attempted to access element which is out of bounds!"); + } + else + { + return (operator[] (idx)); + } + } + }; +} +#endif//PCL_IO_FILE_GRABBER_H_ + diff --git a/pcl-1.7/pcl/io/file_io.h b/pcl-1.7/pcl/io/file_io.h new file mode 100644 index 0000000..481a821 --- /dev/null +++ b/pcl-1.7/pcl/io/file_io.h @@ -0,0 +1,465 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: file_io.h 827 2011-05-04 02:00:04Z nizar $ + * + */ + +#ifndef PCL_IO_FILE_IO_H_ +#define PCL_IO_FILE_IO_H_ + +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Point Cloud Data (FILE) file format reader interface. + * Any (FILE) format file reader should implement its virtual methodes. + * \author Nizar Sallem + * \ingroup io + */ + class PCL_EXPORTS FileReader + { + public: + /** \brief empty constructor */ + FileReader() {} + /** \brief empty destructor */ + virtual ~FileReader() {} + /** \brief Read a point cloud data header from a FILE file. + * + * Load only the meta information (number of points, their types, etc), + * and not the points themselves, from a given FILE file. Useful for fast + * evaluation of the underlying data structure. + * + * Returns: + * * < 0 (-1) on error + * * > 0 on success + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant point cloud dataset (only the header will be filled) + * \param[out] origin the sensor acquisition origin (only for > FILE_V7 - null if not present) + * \param[out] orientation the sensor acquisition orientation (only for > FILE_V7 - identity if not present) + * \param[out] file_version the FILE version of the file (either FILE_V6 or FILE_V7) + * \param[out] data_type the type of data (binary data=1, ascii=0, etc) + * \param[out] data_idx the offset of cloud data within the file + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + */ + virtual int + readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, + int &file_version, int &data_type, unsigned int &data_idx, const int offset = 0) = 0; + + /** \brief Read a point cloud data from a FILE file and store it into a pcl/PCLPointCloud2. + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * \param[out] origin the sensor acquisition origin (only for > FILE_V7 - null if not present) + * \param[out] orientation the sensor acquisition orientation (only for > FILE_V7 - identity if not present) + * \param[out] file_version the FILE version of the file (either FILE_V6 or FILE_V7) + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + */ + virtual int + read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &file_version, + const int offset = 0) = 0; + + /** \brief Read a point cloud data from a FILE file (FILE_V6 only!) and store it into a pcl/PCLPointCloud2. + * + * \note This function is provided for backwards compatibility only and + * it can only read FILE_V6 files correctly, as pcl::PCLPointCloud2 + * does not contain a sensor origin/orientation. Reading any file + * > FILE_V6 will generate a warning. + * + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + */ + int + read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, const int offset = 0) + { + Eigen::Vector4f origin; + Eigen::Quaternionf orientation; + int file_version; + return (read (file_name, cloud, origin, orientation, file_version, offset)); + } + + /** \brief Read a point cloud data from any FILE file, and convert it to the given template format. + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + */ + template inline int + read (const std::string &file_name, pcl::PointCloud &cloud, const int offset =0) + { + pcl::PCLPointCloud2 blob; + int file_version; + int res = read (file_name, blob, cloud.sensor_origin_, cloud.sensor_orientation_, + file_version, offset); + + // Exit in case of error + if (res < 0) + return res; + pcl::fromPCLPointCloud2 (blob, cloud); + return (0); + } + }; + + /** \brief Point Cloud Data (FILE) file format writer. + * Any (FILE) format file reader should implement its virtual methodes + * \author Nizar Sallem + * \ingroup io + */ + class PCL_EXPORTS FileWriter + { + public: + /** \brief Empty constructor */ + FileWriter () {} + + /** \brief Empty destructor */ + virtual ~FileWriter () {} + + /** \brief Save point cloud data to a FILE file containing n-D points + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + * \param[in] binary set to true if the file is to be written in a binary + * FILE format, false (default) for ASCII + */ + virtual int + write (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), + const bool binary = false) = 0; + + /** \brief Save point cloud data to a FILE file containing n-D points + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message (boost shared pointer) + * \param[in] binary set to true if the file is to be written in a binary + * FILE format, false (default) for ASCII + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + */ + inline int + write (const std::string &file_name, const pcl::PCLPointCloud2::ConstPtr &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), + const bool binary = false) + { + return (write (file_name, *cloud, origin, orientation, binary)); + } + + /** \brief Save point cloud data to a FILE file containing n-D points + * \param[in] file_name the output file name + * \param[in] cloud the pcl::PointCloud data + * \param[in] binary set to true if the file is to be written in a binary + * FILE format, false (default) for ASCII + */ + template inline int + write (const std::string &file_name, + const pcl::PointCloud &cloud, + const bool binary = false) + { + Eigen::Vector4f origin = cloud.sensor_origin_; + Eigen::Quaternionf orientation = cloud.sensor_orientation_; + + pcl::PCLPointCloud2 blob; + pcl::toPCLPointCloud2 (cloud, blob); + + // Save the data + return (write (file_name, blob, origin, orientation, binary)); + } + }; + + /** \brief insers a value of type Type (uchar, char, uint, int, float, double, ...) into a stringstream. + * + * If the value is NaN, it inserst "nan". + * + * \param[in] cloud the cloud to copy from + * \param[in] point_index the index of the point + * \param[in] point_size the size of the point in the cloud + * \param[in] field_idx the index of the dimension/field + * \param[in] fields_count the current fields count + * \param[out] stream the ostringstream to copy into + */ + template inline void + copyValueString (const pcl::PCLPointCloud2 &cloud, + const unsigned int point_index, + const int point_size, + const unsigned int field_idx, + const unsigned int fields_count, + std::ostream &stream) + { + Type value; + memcpy (&value, &cloud.data[point_index * point_size + cloud.fields[field_idx].offset + fields_count * sizeof (Type)], sizeof (Type)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + } + template <> inline void + copyValueString (const pcl::PCLPointCloud2 &cloud, + const unsigned int point_index, + const int point_size, + const unsigned int field_idx, + const unsigned int fields_count, + std::ostream &stream) + { + int8_t value; + memcpy (&value, &cloud.data[point_index * point_size + cloud.fields[field_idx].offset + fields_count * sizeof (int8_t)], sizeof (int8_t)); + if (pcl_isnan (value)) + stream << "nan"; + else + // Numeric cast doesn't give us what we want for int8_t + stream << boost::numeric_cast(value); + } + template <> inline void + copyValueString (const pcl::PCLPointCloud2 &cloud, + const unsigned int point_index, + const int point_size, + const unsigned int field_idx, + const unsigned int fields_count, + std::ostream &stream) + { + uint8_t value; + memcpy (&value, &cloud.data[point_index * point_size + cloud.fields[field_idx].offset + fields_count * sizeof (uint8_t)], sizeof (uint8_t)); + if (pcl_isnan (value)) + stream << "nan"; + else + // Numeric cast doesn't give us what we want for uint8_t + stream << boost::numeric_cast(value); + } + + /** \brief Check whether a given value of type Type (uchar, char, uint, int, float, double, ...) is finite or not + * + * \param[in] cloud the cloud that contains the data + * \param[in] point_index the index of the point + * \param[in] point_size the size of the point in the cloud + * \param[in] field_idx the index of the dimension/field + * \param[in] fields_count the current fields count + * + * \return true if the value is finite, false otherwise + */ + template inline bool + isValueFinite (const pcl::PCLPointCloud2 &cloud, + const unsigned int point_index, + const int point_size, + const unsigned int field_idx, + const unsigned int fields_count) + { + Type value; + memcpy (&value, &cloud.data[point_index * point_size + cloud.fields[field_idx].offset + fields_count * sizeof (Type)], sizeof (Type)); + if (!pcl_isfinite (value)) + return (false); + return (true); + } + + /** \brief Copy one single value of type T (uchar, char, uint, int, float, double, ...) from a string + * + * Uses aoti/atof to do the conversion. + * Checks if the st is "nan" and converts it accordingly. + * + * \param[in] st the string containing the value to convert and copy + * \param[out] cloud the cloud to copy it to + * \param[in] point_index the index of the point + * \param[in] field_idx the index of the dimension/field + * \param[in] fields_count the current fields count + */ + template inline void + copyStringValue (const std::string &st, pcl::PCLPointCloud2 &cloud, + unsigned int point_index, unsigned int field_idx, unsigned int fields_count) + { + Type value; + if (st == "nan") + { + value = std::numeric_limits::quiet_NaN (); + cloud.is_dense = false; + } + else + { + std::istringstream is (st); + is.imbue (std::locale::classic ()); + if (!(is >> value)) + value = static_cast (atof (st.c_str ())); + } + + memcpy (&cloud.data[point_index * cloud.point_step + + cloud.fields[field_idx].offset + + fields_count * sizeof (Type)], reinterpret_cast (&value), sizeof (Type)); + } + + template <> inline void + copyStringValue (const std::string &st, pcl::PCLPointCloud2 &cloud, + unsigned int point_index, unsigned int field_idx, unsigned int fields_count) + { + int8_t value; + if (st == "nan") + { + value = static_cast (std::numeric_limits::quiet_NaN ()); + cloud.is_dense = false; + } + else + { + int val; + std::istringstream is (st); + is.imbue (std::locale::classic ()); + //is >> val; -- unfortunately this fails on older GCC versions and CLANG on MacOS + if (!(is >> val)) + val = static_cast (atof (st.c_str ())); + value = static_cast (val); + } + + memcpy (&cloud.data[point_index * cloud.point_step + + cloud.fields[field_idx].offset + + fields_count * sizeof (int8_t)], reinterpret_cast (&value), sizeof (int8_t)); + } + + template <> inline void + copyStringValue (const std::string &st, pcl::PCLPointCloud2 &cloud, + unsigned int point_index, unsigned int field_idx, unsigned int fields_count) + { + uint8_t value; + if (st == "nan") + { + value = static_cast (std::numeric_limits::quiet_NaN ()); + cloud.is_dense = false; + } + else + { + int val; + std::istringstream is (st); + is.imbue (std::locale::classic ()); + //is >> val; -- unfortunately this fails on older GCC versions and CLANG on MacOS + if (!(is >> val)) + val = static_cast (atof (st.c_str ())); + value = static_cast (val); + } + + memcpy (&cloud.data[point_index * cloud.point_step + + cloud.fields[field_idx].offset + + fields_count * sizeof (uint8_t)], reinterpret_cast (&value), sizeof (uint8_t)); + } + + namespace io + { + /** \brief Load a file into a PointCloud2 according to extension. + * \param[in] file_name the name of the file to load + * \param[out] blob the resultant pcl::PointCloud2 blob + * \ingroup io + */ + PCL_EXPORTS int + load (const std::string& file_name, pcl::PCLPointCloud2& blob); + + /** \brief Load a file into a template PointCloud type according to extension. + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant templated point cloud + * \ingroup io + */ + template int + load (const std::string& file_name, pcl::PointCloud& cloud); + + /** \brief Load a file into a PolygonMesh according to extension. + * \param[in] file_name the name of the file to load + * \param[out] mesh the resultant pcl::PolygonMesh + * \ingroup io + */ + PCL_EXPORTS int + load (const std::string& file_name, pcl::PolygonMesh& mesh); + + /** \brief Load a file into a TextureMesh according to extension. + * \param[in] file_name the name of the file to load + * \param[out] mesh the resultant pcl::TextureMesh + * \ingroup io + */ + PCL_EXPORTS int + load (const std::string& file_name, pcl::TextureMesh& mesh); + + /** \brief Save point cloud data to a binary file when available else to ASCII. + * \param[in] file_name the output file name + * \param[in] blob the point cloud data message + * \param[in] precision float precision when saving to ASCII files + * \ingroup io + */ + PCL_EXPORTS int + save (const std::string& file_name, const pcl::PCLPointCloud2& blob, unsigned precision = 5); + + /** \brief Save point cloud to a binary file when available else to ASCII. + * \param[in] file_name the output file name + * \param[in] cloud the point cloud + * \param[in] precision float precision when saving to ASCII files + * \ingroup io + */ + template int + save (const std::string& file_name, const pcl::PointCloud& cloud, unsigned precision = 5); + + /** \brief Saves a TextureMesh to a binary file when available else to ASCII. + * \param[in] file_name the name of the file to write to disk + * \param[in] tex_mesh the texture mesh to save + * \param[in] precision float precision when saving to ASCII files + * \ingroup io + */ + PCL_EXPORTS int + save (const std::string &file_name, const pcl::TextureMesh &tex_mesh, unsigned precision = 5); + + /** \brief Saves a PolygonMesh to a binary file when available else to ASCII. + * \param[in] file_name the name of the file to write to disk + * \param[in] mesh the polygonal mesh to save + * \param[in] precision float precision when saving to ASCII files + * \ingroup io + */ + PCL_EXPORTS int + save (const std::string &file_name, const pcl::PolygonMesh &mesh, unsigned precision = 5); + } +} + +#endif //#ifndef PCL_IO_FILE_IO_H_ diff --git a/pcl-1.7/pcl/io/grabber.h b/pcl-1.7/pcl/io/grabber.h new file mode 100644 index 0000000..0858ed4 --- /dev/null +++ b/pcl-1.7/pcl/io/grabber.h @@ -0,0 +1,273 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +#ifndef __PCL_IO_GRABBER__ +#define __PCL_IO_GRABBER__ + +// needed for the grabber interface / observers +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + + /** \brief Grabber interface for PCL 1.x device drivers + * \author Suat Gedikli + * \ingroup io + */ + class PCL_EXPORTS Grabber + { + public: + + /** \brief Constructor. */ + Grabber () : signals_ (), connections_ (), shared_connections_ () {} + + /** \brief virtual desctructor. */ + virtual inline ~Grabber () throw (); + + /** \brief registers a callback function/method to a signal with the corresponding signature + * \param[in] callback: the callback function/method + * \return Connection object, that can be used to disconnect the callback method from the signal again. + */ + template boost::signals2::connection + registerCallback (const boost::function& callback); + + /** \brief indicates whether a signal with given parameter-type exists or not + * \return true if signal exists, false otherwise + */ + template bool + providesCallback () const; + + /** \brief For devices that are streaming, the streams are started by calling this method. + * Trigger-based devices, just trigger the device once for each call of start. + */ + virtual void + start () = 0; + + /** \brief For devices that are streaming, the streams are stopped. + * This method has no effect for triggered devices. + */ + virtual void + stop () = 0; + + /** \brief returns the name of the concrete subclass. + * \return the name of the concrete driver. + */ + virtual std::string + getName () const = 0; + + /** \brief Indicates whether the grabber is streaming or not. This value is not defined for triggered devices. + * \return true if grabber is running / streaming. False otherwise. + */ + virtual bool + isRunning () const = 0; + + /** \brief returns fps. 0 if trigger based. */ + virtual float + getFramesPerSecond () const = 0; + + protected: + + virtual void + signalsChanged () { } + + template boost::signals2::signal* + find_signal () const; + + template int + num_slots () const; + + template void + disconnect_all_slots (); + + template void + block_signal (); + + template void + unblock_signal (); + + inline void + block_signals (); + + inline void + unblock_signals (); + + template boost::signals2::signal* + createSignal (); + + std::map signals_; + std::map > connections_; + std::map > shared_connections_; + } ; + + Grabber::~Grabber () throw () + { + for (std::map::iterator signal_it = signals_.begin (); signal_it != signals_.end (); ++signal_it) + delete signal_it->second; + } + + template boost::signals2::signal* + Grabber::find_signal () const + { + typedef boost::signals2::signal Signal; + + std::map::const_iterator signal_it = signals_.find (typeid (T).name ()); + if (signal_it != signals_.end ()) + return (dynamic_cast (signal_it->second)); + + return (NULL); + } + + template void + Grabber::disconnect_all_slots () + { + typedef boost::signals2::signal Signal; + + if (signals_.find (typeid (T).name ()) != signals_.end ()) + { + Signal* signal = dynamic_cast (signals_[typeid (T).name ()]); + signal->disconnect_all_slots (); + } + } + + template void + Grabber::block_signal () + { + if (connections_.find (typeid (T).name ()) != connections_.end ()) + for (std::vector::iterator cIt = shared_connections_[typeid (T).name ()].begin (); cIt != shared_connections_[typeid (T).name ()].end (); ++cIt) + cIt->block (); + } + + template void + Grabber::unblock_signal () + { + if (connections_.find (typeid (T).name ()) != connections_.end ()) + for (std::vector::iterator cIt = shared_connections_[typeid (T).name ()].begin (); cIt != shared_connections_[typeid (T).name ()].end (); ++cIt) + cIt->unblock (); + } + + void + Grabber::block_signals () + { + for (std::map::iterator signal_it = signals_.begin (); signal_it != signals_.end (); ++signal_it) + for (std::vector::iterator cIt = shared_connections_[signal_it->first].begin (); cIt != shared_connections_[signal_it->first].end (); ++cIt) + cIt->block (); + } + + void + Grabber::unblock_signals () + { + for (std::map::iterator signal_it = signals_.begin (); signal_it != signals_.end (); ++signal_it) + for (std::vector::iterator cIt = shared_connections_[signal_it->first].begin (); cIt != shared_connections_[signal_it->first].end (); ++cIt) + cIt->unblock (); + } + + template int + Grabber::num_slots () const + { + typedef boost::signals2::signal Signal; + + // see if we have a signal for this type + std::map::const_iterator signal_it = signals_.find (typeid (T).name ()); + if (signal_it != signals_.end ()) + { + Signal* signal = dynamic_cast (signal_it->second); + return (static_cast (signal->num_slots ())); + } + return (0); + } + + template boost::signals2::signal* + Grabber::createSignal () + { + typedef boost::signals2::signal Signal; + + if (signals_.find (typeid (T).name ()) == signals_.end ()) + { + Signal* signal = new Signal (); + signals_[typeid (T).name ()] = signal; + return (signal); + } + return (0); + } + + template boost::signals2::connection + Grabber::registerCallback (const boost::function & callback) + { + typedef boost::signals2::signal Signal; + if (signals_.find (typeid (T).name ()) == signals_.end ()) + { + std::stringstream sstream; + + sstream << "no callback for type:" << typeid (T).name (); + /* + sstream << "registered Callbacks are:" << std::endl; + for( std::map::const_iterator cIt = signals_.begin (); + cIt != signals_.end (); ++cIt) + { + sstream << cIt->first << std::endl; + }*/ + + PCL_THROW_EXCEPTION (pcl::IOException, "[" << getName () << "] " << sstream.str ()); + //return (boost::signals2::connection ()); + } + Signal* signal = dynamic_cast (signals_[typeid (T).name ()]); + boost::signals2::connection ret = signal->connect (callback); + + connections_[typeid (T).name ()].push_back (ret); + shared_connections_[typeid (T).name ()].push_back (boost::signals2::shared_connection_block (connections_[typeid (T).name ()].back (), false)); + signalsChanged (); + return (ret); + } + + template bool + Grabber::providesCallback () const + { + if (signals_.find (typeid (T).name ()) == signals_.end ()) + return (false); + return (true); + } + +} // namespace + +#endif diff --git a/pcl-1.7/pcl/io/hdl_grabber.h b/pcl-1.7/pcl/io/hdl_grabber.h new file mode 100644 index 0000000..d86eda2 --- /dev/null +++ b/pcl-1.7/pcl/io/hdl_grabber.h @@ -0,0 +1,268 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012 The MITRE Corporation + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#include "pcl/pcl_config.h" + +#ifndef PCL_IO_HDL_GRABBER_H_ +#define PCL_IO_HDL_GRABBER_H_ + +#include +#include +#include +#include +#include +#include + +#define HDL_Grabber_toRadians(x) ((x) * M_PI / 180.0) + +namespace pcl +{ + + /** \brief Grabber for the Velodyne High-Definition-Laser (HDL) + * \author Keven Ring + * \ingroup io + */ + class PCL_EXPORTS HDLGrabber : public Grabber + { + public: + /** \brief Signal used for a single sector + * Represents 1 corrected packet from the HDL Velodyne + */ + typedef void (sig_cb_velodyne_hdl_scan_point_cloud_xyz) ( + const boost::shared_ptr >&, + float, float); + /** \brief Signal used for a single sector + * Represents 1 corrected packet from the HDL Velodyne. Each laser has a different RGB + */ + typedef void (sig_cb_velodyne_hdl_scan_point_cloud_xyzrgb) ( + const boost::shared_ptr >&, + float, float); + /** \brief Signal used for a single sector + * Represents 1 corrected packet from the HDL Velodyne with the returned intensity. + */ + typedef void (sig_cb_velodyne_hdl_scan_point_cloud_xyzi) ( + const boost::shared_ptr >&, + float startAngle, float); + /** \brief Signal used for a 360 degree sweep + * Represents multiple corrected packets from the HDL Velodyne + * This signal is sent when the Velodyne passes angle "0" + */ + typedef void (sig_cb_velodyne_hdl_sweep_point_cloud_xyz) ( + const boost::shared_ptr >&); + /** \brief Signal used for a 360 degree sweep + * Represents multiple corrected packets from the HDL Velodyne with the returned intensity + * This signal is sent when the Velodyne passes angle "0" + */ + typedef void (sig_cb_velodyne_hdl_sweep_point_cloud_xyzi) ( + const boost::shared_ptr >&); + /** \brief Signal used for a 360 degree sweep + * Represents multiple corrected packets from the HDL Velodyne + * This signal is sent when the Velodyne passes angle "0". Each laser has a different RGB + */ + typedef void (sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgb) ( + const boost::shared_ptr >&); + + /** \brief Constructor taking an optional path to an HDL corrections file. The Grabber will listen on the default IP/port for data packets [192.168.3.255/2368] + * \param[in] correctionsFile Path to a file which contains the correction parameters for the HDL. This parameter is mandatory for the HDL-64, optional for the HDL-32 + * \param[in] pcapFile Path to a file which contains previously captured data packets. This parameter is optional + */ + HDLGrabber (const std::string& correctionsFile = "", + const std::string& pcapFile = ""); + + /** \brief Constructor taking a pecified IP/port and an optional path to an HDL corrections file. + * \param[in] ipAddress IP Address that should be used to listen for HDL packets + * \param[in] port UDP Port that should be used to listen for HDL packets + * \param[in] correctionsFile Path to a file which contains the correction parameters for the HDL. This field is mandatory for the HDL-64, optional for the HDL-32 + */ + HDLGrabber (const boost::asio::ip::address& ipAddress, + const unsigned short port, const std::string& correctionsFile = ""); + + /** \brief virtual Destructor inherited from the Grabber interface. It never throws. */ + virtual ~HDLGrabber () throw (); + + /** \brief Starts processing the Velodyne packets, either from the network or PCAP file. */ + virtual void start (); + + /** \brief Stops processing the Velodyne packets, either from the network or PCAP file */ + virtual void stop (); + + /** \brief Obtains the name of this I/O Grabber + * \return The name of the grabber + */ + virtual std::string getName () const; + + /** \brief Check if the grabber is still running. + * \return TRUE if the grabber is running, FALSE otherwise + */ + virtual bool isRunning () const; + + /** \brief Returns the number of frames per second. + */ + virtual float getFramesPerSecond () const; + + /** \brief Allows one to filter packets based on the SOURCE IP address and PORT + * This can be used, for instance, if multiple HDL LIDARs are on the same network + */ + void filterPackets (const boost::asio::ip::address& ipAddress, + const unsigned short port = 443); + + /** \brief Allows one to customize the colors used for each of the lasers. + */ + void setLaserColorRGB (const pcl::RGB& color, unsigned int laserNumber); + + /** \brief Any returns from the HDL with a distance less than this are discarded. + * This value is in meters + * Default: 0.0 + */ + void setMinimumDistanceThreshold(float & minThreshold); + + /** \brief Any returns from the HDL with a distance greater than this are discarded. + * This value is in meters + * Default: 10000.0 + */ + void setMaximumDistanceThreshold(float & maxThreshold); + + /** \brief Returns the current minimum distance threshold, in meters + */ + + float getMinimumDistanceThreshold(); + + /** \brief Returns the current maximum distance threshold, in meters + */ + float getMaximumDistanceThreshold(); + + protected: + static const int HDL_DATA_PORT = 2368; + static const int HDL_NUM_ROT_ANGLES = 36001; + static const int HDL_LASER_PER_FIRING = 32; + static const int HDL_MAX_NUM_LASERS = 64; + static const int HDL_FIRING_PER_PKT = 12; + static const boost::asio::ip::address HDL_DEFAULT_NETWORK_ADDRESS; + + enum HDLBlock + { + BLOCK_0_TO_31 = 0xeeff, BLOCK_32_TO_63 = 0xddff + }; + +#pragma pack(push, 1) + typedef struct HDLLaserReturn + { + unsigned short distance; + unsigned char intensity; + } HDLLaserReturn; +#pragma pack(pop) + + struct HDLFiringData + { + unsigned short blockIdentifier; + unsigned short rotationalPosition; + HDLLaserReturn laserReturns[HDL_LASER_PER_FIRING]; + }; + + struct HDLDataPacket + { + HDLFiringData firingData[HDL_FIRING_PER_PKT]; + unsigned int gpsTimestamp; + unsigned char blank1; + unsigned char blank2; + }; + + struct HDLLaserCorrection + { + double azimuthCorrection; + double verticalCorrection; + double distanceCorrection; + double verticalOffsetCorrection; + double horizontalOffsetCorrection; + double sinVertCorrection; + double cosVertCorrection; + double sinVertOffsetCorrection; + double cosVertOffsetCorrection; + }; + + private: + static double *cos_lookup_table_; + static double *sin_lookup_table_; + pcl::SynchronizedQueue hdl_data_; + boost::asio::ip::udp::endpoint udp_listener_endpoint_; + boost::asio::ip::address source_address_filter_; + unsigned short source_port_filter_; + boost::asio::io_service hdl_read_socket_service_; + boost::asio::ip::udp::socket *hdl_read_socket_; + std::string pcap_file_name_; + boost::thread *queue_consumer_thread_; + boost::thread *hdl_read_packet_thread_; + HDLLaserCorrection laser_corrections_[HDL_MAX_NUM_LASERS]; + bool terminate_read_packet_thread_; + boost::shared_ptr > current_scan_xyz_, + current_sweep_xyz_; + boost::shared_ptr > current_scan_xyzi_, + current_sweep_xyzi_; + boost::shared_ptr > current_scan_xyzrgb_, + current_sweep_xyzrgb_; + unsigned int last_azimuth_; + boost::signals2::signal* sweep_xyz_signal_; + boost::signals2::signal* sweep_xyzrgb_signal_; + boost::signals2::signal* sweep_xyzi_signal_; + boost::signals2::signal* scan_xyz_signal_; + boost::signals2::signal* scan_xyzrgb_signal_; + boost::signals2::signal* scan_xyzi_signal_; + pcl::RGB laser_rgb_mapping_[HDL_MAX_NUM_LASERS]; + float min_distance_threshold_; + float max_distance_threshold_; + + void processVelodynePackets (); + void enqueueHDLPacket (const unsigned char *data, + std::size_t bytesReceived); + void initialize (const std::string& correctionsFile); + void loadCorrectionsFile (const std::string& correctionsFile); + void loadHDL32Corrections (); + void readPacketsFromSocket (); +#ifdef HAVE_PCAP + void readPacketsFromPcap(); +#endif //#ifdef HAVE_PCAP + void toPointClouds (HDLDataPacket *dataPacket); + void fireCurrentSweep (); + void fireCurrentScan (const unsigned short startAngle, + const unsigned short endAngle); + void computeXYZI (pcl::PointXYZI& pointXYZI, int azimuth, + HDLLaserReturn laserReturn, HDLLaserCorrection correction); + bool isAddressUnspecified (const boost::asio::ip::address& ip_address); + }; +} + +#endif /* PCL_IO_HDL_GRABBER_H_ */ diff --git a/pcl-1.7/pcl/io/ifs_io.h b/pcl-1.7/pcl/io/ifs_io.h new file mode 100644 index 0000000..80eecaa --- /dev/null +++ b/pcl-1.7/pcl/io/ifs_io.h @@ -0,0 +1,258 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_IO_IFS_IO_H_ +#define PCL_IO_IFS_IO_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Indexed Face set (IFS) file format reader. This file format is used for + * the Brown Mesh Set for instance. + * \author Nizar Sallem + * \ingroup io + */ + class PCL_EXPORTS IFSReader + { + public: + /** Empty constructor */ + IFSReader () {} + /** Empty destructor */ + ~IFSReader () {} + + /** \brief we support two versions + * 1.0 classic + * 1.1 with texture coordinates addon + */ + enum + { + IFS_V1_0 = 0, + IFS_V1_1 = 1 + }; + + /** \brief Read a point cloud data header from an IFS file. + * + * Load only the meta information (number of points, their types, etc), + * and not the points themselves, from a given IFS file. Useful for fast + * evaluation of the underlying data structure. + * + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant point cloud dataset (only header will be filled) + * \param[out] ifs_version the IFS version of the file (IFS_V1_0 or IFS_V1_1) + * \param[out] data_idx the offset of cloud data within the file + * + * \return + * * < 0 (-1) on error + * * == 0 on success + */ + int + readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud, + int &ifs_version, unsigned int &data_idx); + + /** \brief Read a point cloud data from an IFS file and store it into a pcl/PCLPointCloud2. + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PCLPointCloud2 blob read from disk + * \param[out] ifs_version the IFS version of the file (either IFS_V1_0 or IFS_V1_1) + * + * \return + * * < 0 (-1) on error + * * == 0 on success + */ + int + read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, int &ifs_version); + + /** \brief Read a point cloud data from an IFS file and store it into a PolygonMesh. + * \param[in] file_name the name of the file containing the mesh data + * \param[out] mesh the resultant PolygonMesh + * \param[out] ifs_version the IFS version of the file (either IFS_V1_0 or IFS_V1_1) + * + * \return + * * < 0 (-1) on error + * * == 0 on success + */ + int + read (const std::string &file_name, pcl::PolygonMesh &mesh, int &ifs_version); + + /** \brief Read a point cloud data from an IFS file, and convert it to the + * given template pcl::PointCloud format. + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * + * \return + * * < 0 (-1) on error + * * == 0 on success + */ + template int + read (const std::string &file_name, pcl::PointCloud &cloud) + { + pcl::PCLPointCloud2 blob; + int ifs_version; + cloud.sensor_origin_ = Eigen::Vector4f::Zero (); + cloud.sensor_orientation_ = Eigen::Quaternionf::Identity (); + int res = read (file_name, blob, ifs_version); + + // If no error, convert the data + if (res == 0) + pcl::fromPCLPointCloud2 (blob, cloud); + return (res); + } + }; + + /** \brief Point Cloud Data (IFS) file format writer. + * \author Nizar Sallem + * \ingroup io + */ + class PCL_EXPORTS IFSWriter + { + public: + IFSWriter() {} + ~IFSWriter() {} + + /** \brief Save point cloud data to an IFS file containing 3D points. + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data + * \param[in] cloud_name the point cloud name to be stored inside the IFS file. + * + * \return + * * 0 on success + * * < 0 on error + */ + int + write (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, + const std::string &cloud_name = "cloud"); + + /** \brief Save point cloud data to an IFS file containing 3D points. + * \param[in] file_name the output file name + * \param[in] cloud the point cloud + * \param[in] cloud_name the point cloud name to be stored inside the IFS file. + * + * \return + * * 0 on success + * * < 0 on error + */ + template int + write (const std::string &file_name, const pcl::PointCloud &cloud, + const std::string &cloud_name = "cloud") + { + pcl::PCLPointCloud2 blob; + pcl::fromPCLPointCloud2 (blob, cloud); + return (write (file_name, blob, cloud_name)); + } + }; + + namespace io + { + /** \brief Load an IFS file into a PCLPointCloud2 blob type. + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant templated point cloud + * \return 0 on success < 0 on error + * + * \ingroup io + */ + inline int + loadIFSFile (const std::string &file_name, pcl::PCLPointCloud2 &cloud) + { + pcl::IFSReader p; + int ifs_version; + return (p.read (file_name, cloud, ifs_version)); + } + + /** \brief Load any IFS file into a templated PointCloud type. + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant templated point cloud + * \return 0 on success < 0 on error + * + * \ingroup io + */ + template inline int + loadIFSFile (const std::string &file_name, pcl::PointCloud &cloud) + { + pcl::IFSReader p; + return (p.read (file_name, cloud)); + } + + /** \brief Load any IFS file into a PolygonMesh type. + * \param[in] file_name the name of the file to load + * \param[out] mesh the resultant mesh + * \return 0 on success < 0 on error + * + * \ingroup io + */ + inline int + loadIFSFile (const std::string &file_name, pcl::PolygonMesh &mesh) + { + pcl::IFSReader p; + int ifs_version; + return (p.read (file_name, mesh, ifs_version)); + } + + /** \brief Save point cloud data to an IFS file containing 3D points + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \return 0 on success < 0 on error + * + * \ingroup io + */ + inline int + saveIFSFile (const std::string &file_name, const pcl::PCLPointCloud2 &cloud) + { + pcl::IFSWriter w; + return (w.write (file_name, cloud)); + } + + /** \brief Save point cloud data to an IFS file containing 3D points + * \param[in] file_name the output file name + * \param[in] cloud the point cloud + * \return 0 on success < 0 on error + * + * \ingroup io + */ + template int + saveIFSFile (const std::string &file_name, const pcl::PointCloud &cloud) + { + pcl::IFSWriter w; + return (w.write (file_name, cloud)); + } + } +} + +#endif //#ifndef PCL_IO_IFS_IO_H_ diff --git a/pcl-1.7/pcl/io/image.h b/pcl-1.7/pcl/io/image.h new file mode 100644 index 0000000..bc1459c --- /dev/null +++ b/pcl-1.7/pcl/io/image.h @@ -0,0 +1,215 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#include +#ifndef PCL_IO_IMAGE_H_ +#define PCL_IO_IMAGE_H_ + +#include +#include +#include + +#include + +namespace pcl +{ + namespace io + { + + /** + * @brief Image interface class providing an interface to fill a RGB or Grayscale image buffer. + * @param[in] image_metadata + * @ingroup io + */ + class PCL_EXPORTS Image + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef boost::chrono::high_resolution_clock Clock; + typedef boost::chrono::high_resolution_clock::time_point Timestamp; + + typedef enum + { + BAYER_GRBG, + YUV422, + RGB + } Encoding; + + Image (FrameWrapper::Ptr image_metadata) + : wrapper_ (image_metadata) + , timestamp_ (Clock::now ()) + {} + + Image (FrameWrapper::Ptr image_metadata, Timestamp time) + : wrapper_ (image_metadata) + , timestamp_ (time) + {} + + /** + * @brief virtual Destructor that never throws an exception. + */ + inline virtual ~Image () + {} + + /** + * @param[in] input_width width of input image + * @param[in] input_height height of input image + * @param[in] output_width width of desired output image + * @param[in] output_height height of desired output image + * @return wheter the resizing is supported or not. + */ + virtual bool + isResizingSupported (unsigned input_width, unsigned input_height, + unsigned output_width, unsigned output_height) const = 0; + + /** + * @brief fills a user given buffer with the RGB values, with an optional nearest-neighbor down sampling and an optional subregion + * @param[in] width desired width of output image. + * @param[in] height desired height of output image. + * @param[in,out] rgb_buffer the output RGB buffer. + * @param[in] rgb_line_step optional line step in bytes to allow the output in a rectangular subregion of the output buffer. + */ + virtual void + fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const = 0; + + /** + * @brief returns the encoding of the native data. + * @return encoding + */ + virtual Encoding + getEncoding () const = 0; + + /** + * @brief fills a user given buffer with the raw values. + * @param[in,out] rgb_buffer + */ + virtual void + fillRaw (unsigned char* rgb_buffer) const + { + memcpy (rgb_buffer, wrapper_->getData (), wrapper_->getDataSize ()); + } + + /** + * @brief fills a user given buffer with the gray values, with an optional nearest-neighbor down sampling and an optional subregion + * @param[in] width desired width of output image. + * @param[in] height desired height of output image. + * @param[in,out] gray_buffer the output gray buffer. + * @param[in] gray_line_step optional line step in bytes to allow the output in a rectangular subregion of the output buffer. + */ + virtual void + fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, + unsigned gray_line_step = 0) const = 0; + + /** + * @return width of the image + */ + unsigned + getWidth () const + { + return (wrapper_->getWidth ()); + } + + /** + * @return height of the image + */ + unsigned + getHeight () const + { + return (wrapper_->getHeight ()); + } + + /** + * @return frame id of the image. + * @note frame ids are ascending, but not necessarily synchronized with other streams + */ + unsigned + getFrameID () const + { + return (wrapper_->getFrameID ()); + } + + /** + * @return the timestamp of the image + * @note the time value is not synchronized with the system time + */ + pcl::uint64_t + getTimestamp () const + { + return (wrapper_->getTimestamp ()); + } + + + /** + * @return the timestamp of the image + * @note the time value *is* synchronized with the system time. + */ + Timestamp + getSystemTimestamp () const + { + return (timestamp_); + } + + // Get a const pointer to the raw depth buffer + const void* + getData () + { + return (wrapper_->getData ()); + } + + // Data buffer size in bytes + int + getDataSize () const + { + return (wrapper_->getDataSize ()); + } + + // Size of each row, including any padding + inline unsigned + getStep() const + { + return (getDataSize() / getHeight()); + } + + protected: + FrameWrapper::Ptr wrapper_; + Timestamp timestamp_; + }; + + } // namespace +} + +#endif //PCL_IO_IMAGE_H_ diff --git a/pcl-1.7/pcl/io/image_depth.h b/pcl-1.7/pcl/io/image_depth.h new file mode 100644 index 0000000..56867bc --- /dev/null +++ b/pcl-1.7/pcl/io/image_depth.h @@ -0,0 +1,191 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011 Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#pragma once +#include + +#ifndef PCL_IO_IMAGE_DEPTH_H_ +#define PCL_IO_IMAGE_DEPTH_H_ + +#include +#include +#include + +#include + +namespace pcl +{ + namespace io + { + /** \brief This class provides methods to fill a depth or disparity image. + */ + class PCL_EXPORTS DepthImage + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef boost::chrono::high_resolution_clock Clock; + typedef boost::chrono::high_resolution_clock::time_point Timestamp; + + /** \brief Constructor + * \param[in] depth_meta_data the actual data from the OpenNI library + * \param[in] baseline the baseline of the "stereo" camera, i.e. the distance between the projector and the IR camera for + * Primesense like cameras. e.g. 7.5cm for PSDK5 and PSDK6 reference design. + * \param[in] focal_length focal length of the "stereo" frame. + * \param[in] shadow_value defines which values in the depth data are indicating shadow (resulting from the parallax between projector and IR camera) + * \param[in] no_sample_value defines which values in the depth data are indicating that no depth (disparity) could be determined . + * \attention The focal length may change, depending whether the depth stream is registered/mapped to the RGB stream or not. + */ + DepthImage (FrameWrapper::Ptr depth_metadata, float baseline, float focal_length, pcl::uint64_t shadow_value, pcl::uint64_t no_sample_value); + DepthImage (FrameWrapper::Ptr depth_metadata, float baseline, float focal_length, pcl::uint64_t shadow_value, pcl::uint64_t no_sample_value, Timestamp time); + + /** \brief Destructor. Never throws an exception. */ + ~DepthImage (); + + /** \brief method to access the internal data structure from OpenNI. If the data is accessed just read-only, then this method is faster than a fillXXX method + * \return the actual depth data of type openni::VideoFrameRef. + */ + const FrameWrapper::Ptr + getMetaData () const; + + /** \brief fills a user given block of memory with the disparity values with additional nearest-neighbor down-scaling. + * \param[in] width the width of the desired disparity image. + * \param[in] height the height of the desired disparity image. + * \param[in,out] disparity_buffer the float pointer to the actual memory buffer to be filled with the disparity values. + * \param[in] line_step if only a rectangular sub region of the buffer needs to be filled, then line_step is the + * width in bytes (not floats) of the original width of the depth buffer. + */ + void + fillDisparityImage (unsigned width, unsigned height, float* disparity_buffer, unsigned line_step = 0) const; + + /** \brief fills a user given block of memory with the disparity values with additional nearest-neighbor down-scaling. + * \param[in] width width the width of the desired depth image. + * \param[in] height height the height of the desired depth image. + * \param[in,out] depth_buffer the float pointer to the actual memory buffer to be filled with the depth values. + * \param[in] line_step if only a rectangular sub region of the buffer needs to be filled, then line_step is the + * width in bytes (not floats) of the original width of the depth buffer. + */ + void + fillDepthImage (unsigned width, unsigned height, float* depth_buffer, unsigned line_step = 0) const; + + /** \brief fills a user given block of memory with the raw values with additional nearest-neighbor down-scaling. + * \param[in] width width the width of the desired raw image. + * \param[in] height height the height of the desired raw image. + * \param[in,out] depth_buffer the unsigned short pointer to the actual memory buffer to be filled with the raw values. + * \param[in] line_step if only a rectangular sub region of the buffer needs to be filled, then line_step is the + * width in bytes (not floats) of the original width of the depth buffer. + */ + void + fillDepthImageRaw (unsigned width, unsigned height, unsigned short* depth_buffer, unsigned line_step = 0) const; + + /** \brief method to access the baseline of the "stereo" frame that was used to retrieve the depth image. + * \return baseline in meters + */ + float + getBaseline () const; + + /** \brief method to access the focal length of the "stereo" frame that was used to retrieve the depth image. + * \return focal length in pixels + */ + float + getFocalLength () const; + + /** \brief method to access the shadow value, that indicates pixels lying in shadow in the depth image. + * \return shadow value + */ + pcl::uint64_t + getShadowValue () const; + + /** \brief method to access the no-sample value, that indicates pixels where no disparity could be determined for the depth image. + * \return no-sample value + */ + pcl::uint64_t + getNoSampleValue () const; + + /** \return the width of the depth image */ + unsigned + getWidth () const; + + /** \return the height of the depth image */ + unsigned + getHeight () const; + + /** \return an ascending id for the depth frame + * \attention not necessarily synchronized with other streams + */ + unsigned + getFrameID () const; + + /** \return a ascending timestamp for the depth frame + * \attention its not the system time, thus can not be used directly to synchronize different sensors. + * But definitely synchronized with other streams + */ + pcl::uint64_t + getTimestamp () const; + + Timestamp + getSystemTimestamp () const; + + // Get a const pointer to the raw depth buffer + const unsigned short* + getData (); + + // Data buffer size in bytes + int + getDataSize () const; + + // Size of each row, including any padding + inline unsigned + getStep() const + { + return (getDataSize() / getHeight()); + } + + protected: + pcl::io::FrameWrapper::Ptr wrapper_; + + float baseline_; + float focal_length_; + pcl::uint64_t shadow_value_; + pcl::uint64_t no_sample_value_; + Timestamp timestamp_; + }; + +}} // namespace + +#endif // PCL_IO_IMAGE_DEPTH_H_ diff --git a/pcl-1.7/pcl/io/image_grabber.h b/pcl-1.7/pcl/io/image_grabber.h new file mode 100644 index 0000000..5225147 --- /dev/null +++ b/pcl-1.7/pcl/io/image_grabber.h @@ -0,0 +1,318 @@ + +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#pragma once +#ifndef __PCL_IO_IMAGE_GRABBER__ +#define __PCL_IO_IMAGE_GRABBER__ + +#include "pcl/pcl_config.h" +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Base class for Image file grabber. + * \ingroup io + */ + class PCL_EXPORTS ImageGrabberBase : public Grabber + { + public: + /** \brief Constructor taking a folder of depth+[rgb] images. + * \param[in] directory Directory which contains an ordered set of images corresponding to an [RGB]D video, stored as TIFF, PNG, JPG, or PPM files. The naming convention is: frame_[timestamp]_["depth"/"rgb"].[extension] + * \param[in] frames_per_second frames per second. If 0, start() functions like a trigger, publishing the next PCD in the list. + * \param[in] repeat whether to play PCD file in an endless loop or not. + * \param pclzf_mode + */ + ImageGrabberBase (const std::string& directory, float frames_per_second, bool repeat, bool pclzf_mode); + + ImageGrabberBase (const std::string& depth_directory, const std::string& rgb_directory, float frames_per_second, bool repeat); + /** \brief Constructor taking a list of paths to PCD files, that are played in the order they appear in the list. + * \param[in] depth_image_files Path to the depth image files files. + * \param[in] frames_per_second frames per second. If 0, start() functions like a trigger, publishing the next PCD in the list. + * \param[in] repeat whether to play PCD file in an endless loop or not. + */ + ImageGrabberBase (const std::vector& depth_image_files, float frames_per_second, bool repeat); + + /** \brief Copy constructor. + * \param[in] src the Image Grabber base object to copy into this + */ + ImageGrabberBase (const ImageGrabberBase &src) : Grabber (), impl_ () + { + *this = src; + } + + /** \brief Copy operator. + * \param[in] src the Image Grabber base object to copy into this + */ + ImageGrabberBase& + operator = (const ImageGrabberBase &src) + { + impl_ = src.impl_; + return (*this); + } + + /** \brief Virtual destructor. */ + virtual ~ImageGrabberBase () throw (); + + /** \brief Starts playing the list of PCD files if frames_per_second is > 0. Otherwise it works as a trigger: publishes only the next PCD file in the list. */ + virtual void + start (); + + /** \brief Stops playing the list of PCD files if frames_per_second is > 0. Otherwise the method has no effect. */ + virtual void + stop (); + + /** \brief Triggers a callback with new data */ + virtual void + trigger (); + + /** \brief whether the grabber is started (publishing) or not. + * \return true only if publishing. + */ + virtual bool + isRunning () const; + + /** \return The name of the grabber */ + virtual std::string + getName () const; + + /** \brief Rewinds to the first PCD file in the list.*/ + virtual void + rewind (); + + /** \brief Returns the frames_per_second. 0 if grabber is trigger-based */ + virtual float + getFramesPerSecond () const; + + /** \brief Returns whether the repeat flag is on */ + bool + isRepeatOn () const; + + /** \brief Returns if the last frame is reached */ + bool + atLastFrame () const; + + /** \brief Returns the filename of the current indexed file */ + std::string + getCurrentDepthFileName () const; + + /** \brief Returns the filename of the previous indexed file + * SDM: adding this back in, but is this useful, or confusing? */ + std::string + getPrevDepthFileName () const; + + /** \brief Get the depth filename at a particular index */ + std::string + getDepthFileNameAtIndex (size_t idx) const; + + /** \brief Query only the timestamp of an index, if it exists */ + bool + getTimestampAtIndex (size_t idx, pcl::uint64_t ×tamp) const; + + /** \brief Manually set RGB image files. + * \param[in] rgb_image_files A vector of [tiff/png/jpg/ppm] files to use as input. There must be a 1-to-1 correspondence between these and the depth images you set + */ + void + setRGBImageFiles (const std::vector& rgb_image_files); + + /** \brief Define custom focal length and center pixel. This will override ANY other setting of parameters for the duration of the grabber's life, whether by factory defaults or explicitly read from a frame_[timestamp].xml file. + * \param[in] focal_length_x Horizontal focal length (fx) + * \param[in] focal_length_y Vertical focal length (fy) + * \param[in] principal_point_x Horizontal coordinates of the principal point (cx) + * \param[in] principal_point_y Vertical coordinates of the principal point (cy) + */ + virtual void + setCameraIntrinsics (const double focal_length_x, + const double focal_length_y, + const double principal_point_x, + const double principal_point_y); + + /** \brief Get the current focal length and center pixel. If the intrinsics have been manually set with setCameraIntrinsics, this will return those values. Else, if start () has been called and the grabber has found a frame_[timestamp].xml file, this will return the most recent values read. Else, returns factory defaults. + * \param[out] focal_length_x Horizontal focal length (fx) + * \param[out] focal_length_y Vertical focal length (fy) + * \param[out] principal_point_x Horizontal coordinates of the principal point (cx) + * \param[out] principal_point_y Vertical coordinates of the principal point (cy) + */ + virtual void + getCameraIntrinsics (double &focal_length_x, + double &focal_length_y, + double &principal_point_x, + double &principal_point_y) const; + + /** \brief Define the units the depth data is stored in. + * Defaults to mm (0.001), meaning a brightness of 1000 corresponds to 1 m*/ + void + setDepthImageUnits (float units); + + /** \brief Set the number of threads, if we wish to use OpenMP for quicker cloud population. + * Note that for a standard (< 4 core) machine this is unlikely to yield a drastic speedup.*/ + void + setNumberOfThreads (unsigned int nr_threads = 0); + + protected: + /** \brief Convenience function to see how many frames this consists of + */ + size_t + numFrames () const; + + /** \brief Gets the cloud in ROS form at location idx */ + bool + getCloudAt (size_t idx, pcl::PCLPointCloud2 &blob, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation) const; + + + private: + virtual void + publish (const pcl::PCLPointCloud2& blob, const Eigen::Vector4f& origin, const Eigen::Quaternionf& orientation) const = 0; + + + // to separate and hide the implementation from interface: PIMPL + struct ImageGrabberImpl; + ImageGrabberImpl* impl_; + }; + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template class PointCloud; + template class ImageGrabber : public ImageGrabberBase, public FileGrabber + { + public: + ImageGrabber (const std::string& dir, + float frames_per_second = 0, + bool repeat = false, + bool pclzf_mode = false); + + ImageGrabber (const std::string& depth_dir, + const std::string& rgb_dir, + float frames_per_second = 0, + bool repeat = false); + + ImageGrabber (const std::vector& depth_image_files, + float frames_per_second = 0, + bool repeat = false); + + /** \brief Empty destructor */ + virtual ~ImageGrabber () throw () {} + + // Inherited from FileGrabber + const boost::shared_ptr< const pcl::PointCloud > + operator[] (size_t idx) const; + + // Inherited from FileGrabber + size_t + size () const; + + protected: + virtual void + publish (const pcl::PCLPointCloud2& blob, + const Eigen::Vector4f& origin, + const Eigen::Quaternionf& orientation) const; + boost::signals2::signal >&)>* signal_; + }; + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template + ImageGrabber::ImageGrabber (const std::string& dir, + float frames_per_second, + bool repeat, + bool pclzf_mode) + : ImageGrabberBase (dir, frames_per_second, repeat, pclzf_mode) + { + signal_ = createSignal >&)>(); + } + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template + ImageGrabber::ImageGrabber (const std::string& depth_dir, + const std::string& rgb_dir, + float frames_per_second, + bool repeat) + : ImageGrabberBase (depth_dir, rgb_dir, frames_per_second, repeat) + { + signal_ = createSignal >&)>(); + } + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template + ImageGrabber::ImageGrabber (const std::vector& depth_image_files, + float frames_per_second, + bool repeat) + : ImageGrabberBase (depth_image_files, frames_per_second, repeat), signal_ () + { + signal_ = createSignal >&)>(); + } + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template const boost::shared_ptr< const pcl::PointCloud > + ImageGrabber::operator[] (size_t idx) const + { + pcl::PCLPointCloud2 blob; + Eigen::Vector4f origin; + Eigen::Quaternionf orientation; + getCloudAt (idx, blob, origin, orientation); + typename pcl::PointCloud::Ptr cloud (new pcl::PointCloud ()); + pcl::fromPCLPointCloud2 (blob, *cloud); + cloud->sensor_origin_ = origin; + cloud->sensor_orientation_ = orientation; + return (cloud); + } + + /////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template size_t + ImageGrabber::size () const + { + return (numFrames ()); + } + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template void + ImageGrabber::publish (const pcl::PCLPointCloud2& blob, const Eigen::Vector4f& origin, const Eigen::Quaternionf& orientation) const + { + typename pcl::PointCloud::Ptr cloud (new pcl::PointCloud ()); + pcl::fromPCLPointCloud2 (blob, *cloud); + cloud->sensor_origin_ = origin; + cloud->sensor_orientation_ = orientation; + + signal_->operator () (cloud); + } +} +#endif diff --git a/pcl-1.7/pcl/io/image_ir.h b/pcl-1.7/pcl/io/image_ir.h new file mode 100644 index 0000000..ce6a14e --- /dev/null +++ b/pcl-1.7/pcl/io/image_ir.h @@ -0,0 +1,114 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2011 Willow Garage, Inc. +* +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the copyright holder(s) nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +*/ +#ifndef PCL_IO_IMAGE_IR_H_ +#define PCL_IO_IMAGE_IR_H_ + +#include +#include + +#include + +namespace pcl +{ + namespace io + { + + /** + * @brief Class containing just a reference to IR meta data. + */ + class PCL_EXPORTS IRImage + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef boost::chrono::high_resolution_clock Clock; + typedef boost::chrono::high_resolution_clock::time_point Timestamp; + + IRImage (FrameWrapper::Ptr ir_metadata); + IRImage (FrameWrapper::Ptr ir_metadata, Timestamp time); + + ~IRImage () throw () + {} + + void + fillRaw (unsigned width, unsigned height, unsigned short* ir_buffer, unsigned line_step = 0) const; + + unsigned + getWidth () const; + + unsigned + getHeight () const; + + unsigned + getFrameID () const; + + pcl::uint64_t + getTimestamp () const; + + Timestamp + getSystemTimestamp () const; + + // Get a const pointer to the raw depth buffer. If the data is accessed just read-only, then this method is faster than a fillXXX method + const unsigned short* + getData (); + + // Data buffer size in bytes + int + getDataSize () const; + + // Size of each row, including any padding + inline unsigned + getStep() const + { + return (getDataSize() / getHeight()); + } + + /** \brief method to access the internal data structure wrapper, which needs to be cast to an + * approperate subclass before the getMetadata(..) function is available to access the native data type. + */ + const FrameWrapper::Ptr + getMetaData () const; + + protected: + FrameWrapper::Ptr wrapper_; + Timestamp timestamp_; + }; + + } // namespace +} + +#endif // PCL_IO_IMAGE_IR_H_ diff --git a/pcl-1.7/pcl/io/image_metadata_wrapper.h b/pcl-1.7/pcl/io/image_metadata_wrapper.h new file mode 100644 index 0000000..19dcb82 --- /dev/null +++ b/pcl-1.7/pcl/io/image_metadata_wrapper.h @@ -0,0 +1,83 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2014, respective authors. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#pragma once +#ifndef PCL_IO_IMAGE_METADATA_WRAPPER_H_ +#define PCL_IO_IMAGE_METADATA_WRAPPER_H_ + +#include +#include + +namespace pcl +{ + namespace io + { + + /** + * Pure abstract interface to wrap native frame data types. + */ + class FrameWrapper + { + public: + typedef boost::shared_ptr Ptr; + + virtual const void* + getData () const = 0; + + virtual unsigned + getDataSize () const = 0; + + virtual unsigned + getWidth () const = 0; + + virtual unsigned + getHeight () const = 0; + + virtual unsigned + getFrameID () const = 0; + + // Microseconds from some arbitrary start point + virtual pcl::uint64_t + getTimestamp () const = 0; + }; + + } // namespace +} + +#endif // PCL_IO_IMAGE_METADATA_WRAPPER_H_ diff --git a/pcl-1.7/pcl/io/image_rgb24.h b/pcl-1.7/pcl/io/image_rgb24.h new file mode 100644 index 0000000..41c155d --- /dev/null +++ b/pcl-1.7/pcl/io/image_rgb24.h @@ -0,0 +1,91 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#include + +#ifndef PCL_IO_IMAGE_RGB_H_ +#define PCL_IO_IMAGE_RGB_H_ + +#include +#include + +#include + +namespace pcl +{ + namespace io + { + /** + * @brief This class provides methods to fill a RGB or Grayscale image buffer from underlying RGB24 image. + * @ingroup io + */ + class PCL_EXPORTS ImageRGB24 : public pcl::io::Image + { + public: + + ImageRGB24 (FrameWrapper::Ptr image_metadata); + ImageRGB24 (FrameWrapper::Ptr image_metadata, Timestamp timestamp); + virtual ~ImageRGB24 () throw (); + + inline virtual Encoding + getEncoding () const + { + return (RGB); + } + + virtual void + fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const; + + virtual void + fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const; + + virtual bool + isResizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const; + + private: + + // Struct used for type conversion + typedef struct + { + uint8_t r; + uint8_t g; + uint8_t b; + } RGB888Pixel; + }; + + } // namespace +} + +#endif // PCL_IO_IMAGE_RGB_H_ diff --git a/pcl-1.7/pcl/io/image_yuv422.h b/pcl-1.7/pcl/io/image_yuv422.h new file mode 100644 index 0000000..61ecdd7 --- /dev/null +++ b/pcl-1.7/pcl/io/image_yuv422.h @@ -0,0 +1,79 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2011 Willow Garage, Inc. +* +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the copyright holder(s) nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +*/ +#include + +#ifndef PCL_IO_IMAGE_YUV422_H_ +#define PCL_IO_IMAGE_YUV422_H_ +#include + +#include + +namespace pcl +{ + namespace io + { + /** + * @brief Concrete implementation of the interface Image for a YUV 422 image used by Primesense devices. + * @ingroup io + */ + class PCL_EXPORTS ImageYUV422 : public pcl::io::Image + { + public: + ImageYUV422 (FrameWrapper::Ptr image_metadata); + ImageYUV422 (FrameWrapper::Ptr image_metadata, Timestamp timestamp); + + virtual ~ImageYUV422 () throw (); + + inline virtual Encoding + getEncoding () const + { + return (YUV422); + } + + virtual void + fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const; + + virtual void + fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const; + + virtual bool + isResizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const; + }; + + } // namespace +} + +#endif // PCL_IO_IMAGE_YUV22_H_ diff --git a/pcl-1.7/pcl/io/impl/entropy_range_coder.hpp b/pcl-1.7/pcl/io/impl/entropy_range_coder.hpp new file mode 100644 index 0000000..0b78515 --- /dev/null +++ b/pcl-1.7/pcl/io/impl/entropy_range_coder.hpp @@ -0,0 +1,682 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + * range coder based on Dmitry Subbotin's carry-less implementation (http://www.compression.ru/ds/) + * Added optimized symbol lookup and fixed/static frequency tables + * + */ + +#ifndef __PCL_IO_RANGECODING__HPP +#define __PCL_IO_RANGECODING__HPP + +#include +#include +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +unsigned long +pcl::AdaptiveRangeCoder::encodeCharVectorToStream (const std::vector& inputByteVector_arg, + std::ostream& outputByteStream_arg) +{ + DWord freq[257]; + uint8_t ch; + unsigned int i, j, f; + char out; + + // define limits + const DWord top = static_cast (1) << 24; + const DWord bottom = static_cast (1) << 16; + const DWord maxRange = static_cast (1) << 16; + + DWord low, range; + + unsigned int readPos; + unsigned int input_size; + + input_size = static_cast (inputByteVector_arg.size ()); + + // init output vector + outputCharVector_.clear (); + outputCharVector_.reserve (sizeof(char) * input_size); + + readPos = 0; + + low = 0; + range = static_cast (-1); + + // initialize cumulative frequency table + for (i = 0; i < 257; i++) + freq[i] = i; + + // scan input + while (readPos < input_size) + { + + // read byte + ch = inputByteVector_arg[readPos++]; + + // map range + low += freq[ch] * (range /= freq[256]); + range *= freq[ch + 1] - freq[ch]; + + // check range limits + while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -int (low) & (bottom - 1)), 1))) + { + out = static_cast (low >> 24); + range <<= 8; + low <<= 8; + outputCharVector_.push_back (out); + } + + // update frequency table + for (j = ch + 1; j < 257; j++) + freq[j]++; + + // detect overflow + if (freq[256] >= maxRange) + { + // rescale + for (f = 1; f <= 256; f++) + { + freq[f] /= 2; + if (freq[f] <= freq[f - 1]) + freq[f] = freq[f - 1] + 1; + } + } + + } + + // flush remaining data + for (i = 0; i < 4; i++) + { + out = static_cast (low >> 24); + outputCharVector_.push_back (out); + low <<= 8; + } + + // write to stream + outputByteStream_arg.write (&outputCharVector_[0], outputCharVector_.size ()); + + return (static_cast (outputCharVector_.size ())); + +} + +////////////////////////////////////////////////////////////////////////////////////////////// +unsigned long +pcl::AdaptiveRangeCoder::decodeStreamToCharVector (std::istream& inputByteStream_arg, + std::vector& outputByteVector_arg) +{ + uint8_t ch; + DWord freq[257]; + unsigned int i, j, f; + + // define limits + const DWord top = static_cast (1) << 24; + const DWord bottom = static_cast (1) << 16; + const DWord maxRange = static_cast (1) << 16; + + DWord low, range; + DWord code; + + unsigned int outputBufPos; + unsigned int output_size = static_cast (outputByteVector_arg.size ()); + + unsigned long streamByteCount; + + streamByteCount = 0; + + outputBufPos = 0; + + code = 0; + low = 0; + range = static_cast (-1); + + // init decoding + for (i = 0; i < 4; i++) + { + inputByteStream_arg.read (reinterpret_cast (&ch), sizeof(char)); + streamByteCount += sizeof(char); + code = (code << 8) | ch; + } + + // init cumulative frequency table + for (i = 0; i <= 256; i++) + freq[i] = i; + + // decoding loop + for (i = 0; i < output_size; i++) + { + uint8_t symbol = 0; + uint8_t sSize = 256 / 2; + + // map code to range + DWord count = (code - low) / (range /= freq[256]); + + // find corresponding symbol + while (sSize > 0) + { + if (freq[symbol + sSize] <= count) + { + symbol = static_cast (symbol + sSize); + } + sSize /= 2; + } + + // output symbol + outputByteVector_arg[outputBufPos++] = symbol; + + // update range limits + low += freq[symbol] * range; + range *= freq[symbol + 1] - freq[symbol]; + + // decode range limits + while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -int (low) & (bottom - 1)), 1))) + { + inputByteStream_arg.read (reinterpret_cast (&ch), sizeof(char)); + streamByteCount += sizeof(char); + code = code << 8 | ch; + range <<= 8; + low <<= 8; + } + + // update cumulative frequency table + for (j = symbol + 1; j < 257; j++) + freq[j]++; + + // detect overflow + if (freq[256] >= maxRange) + { + // rescale + for (f = 1; f <= 256; f++) + { + freq[f] /= 2; + if (freq[f] <= freq[f - 1]) + freq[f] = freq[f - 1] + 1; + } + } + } + + return (streamByteCount); + +} + +////////////////////////////////////////////////////////////////////////////////////////////// +unsigned long +pcl::StaticRangeCoder::encodeIntVectorToStream (std::vector& inputIntVector_arg, + std::ostream& outputByteStream_arg) +{ + + unsigned int inputsymbol; + unsigned int i, f; + char out; + + uint64_t frequencyTableSize; + uint8_t frequencyTableByteSize; + + // define numerical limits + const uint64_t top = static_cast (1) << 56; + const uint64_t bottom = static_cast (1) << 48; + const uint64_t maxRange = static_cast (1) << 48; + + unsigned long input_size = static_cast (inputIntVector_arg.size ()); + uint64_t low, range; + + unsigned int inputSymbol; + + unsigned int readPos; + + unsigned long streamByteCount; + + streamByteCount = 0; + + // init output vector + outputCharVector_.clear (); + outputCharVector_.reserve ((sizeof(char) * input_size * 2)); + + frequencyTableSize = 1; + + readPos = 0; + + // calculate frequency table + cFreqTable_[0] = cFreqTable_[1] = 0; + while (readPos < input_size) + { + inputSymbol = inputIntVector_arg[readPos++]; + + if (inputSymbol + 1 >= frequencyTableSize) + { + // frequency table is to small -> adaptively extend it + uint64_t oldfrequencyTableSize; + oldfrequencyTableSize = frequencyTableSize; + + do + { + // increase frequency table size by factor 2 + frequencyTableSize <<= 1; + } while (inputSymbol + 1 > frequencyTableSize); + + if (cFreqTable_.size () < frequencyTableSize + 1) + { + // resize frequency vector + cFreqTable_.resize (static_cast (frequencyTableSize + 1)); + } + + // init new frequency range with zero + memset (&cFreqTable_[static_cast (oldfrequencyTableSize + 1)], 0, + sizeof(uint64_t) * static_cast (frequencyTableSize - oldfrequencyTableSize)); + } + cFreqTable_[inputSymbol + 1]++; + } + frequencyTableSize++; + + // convert to cumulative frequency table + for (f = 1; f < frequencyTableSize; f++) + { + cFreqTable_[f] = cFreqTable_[f - 1] + cFreqTable_[f]; + if (cFreqTable_[f] <= cFreqTable_[f - 1]) + cFreqTable_[f] = cFreqTable_[f - 1] + 1; + } + + // rescale if numerical limits are reached + while (cFreqTable_[static_cast (frequencyTableSize - 1)] >= maxRange) + { + for (f = 1; f < cFreqTable_.size (); f++) + { + cFreqTable_[f] /= 2; + ; + if (cFreqTable_[f] <= cFreqTable_[f - 1]) + cFreqTable_[f] = cFreqTable_[f - 1] + 1; + } + } + + // calculate amount of bytes per frequency table entry + frequencyTableByteSize = static_cast (ceil ( + Log2 (static_cast (cFreqTable_[static_cast (frequencyTableSize - 1)])) / 8.0)); + + // write size of frequency table to output stream + outputByteStream_arg.write (reinterpret_cast (&frequencyTableSize), sizeof(frequencyTableSize)); + outputByteStream_arg.write (reinterpret_cast (&frequencyTableByteSize), sizeof(frequencyTableByteSize)); + + streamByteCount += sizeof(frequencyTableSize) + sizeof(frequencyTableByteSize); + + // write cumulative frequency table to output stream + for (f = 1; f < frequencyTableSize; f++) + { + outputByteStream_arg.write (reinterpret_cast (&cFreqTable_[f]), frequencyTableByteSize); + streamByteCount += frequencyTableByteSize; + } + + readPos = 0; + low = 0; + range = static_cast (-1); + + // start encoding + while (readPos < input_size) + { + + // read symol + inputsymbol = inputIntVector_arg[readPos++]; + + // map to range + low += cFreqTable_[inputsymbol] * (range /= cFreqTable_[static_cast (frequencyTableSize - 1)]); + range *= cFreqTable_[inputsymbol + 1] - cFreqTable_[inputsymbol]; + + // check range limits + while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -low & (bottom - 1)), 1))) + { + out = static_cast (low >> 56); + range <<= 8; + low <<= 8; + outputCharVector_.push_back (out); + } + + } + + // flush remaining data + for (i = 0; i < 8; i++) + { + out = static_cast (low >> 56); + outputCharVector_.push_back (out); + low <<= 8; + } + + // write encoded data to stream + outputByteStream_arg.write (&outputCharVector_[0], outputCharVector_.size ()); + + streamByteCount += static_cast (outputCharVector_.size ()); + + return (streamByteCount); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +unsigned long +pcl::StaticRangeCoder::decodeStreamToIntVector (std::istream& inputByteStream_arg, + std::vector& outputIntVector_arg) +{ + uint8_t ch; + unsigned int i, f; + + // define range limits + const uint64_t top = static_cast (1) << 56; + const uint64_t bottom = static_cast (1) << 48; + + uint64_t low, range; + uint64_t code; + + unsigned int outputBufPos; + unsigned long output_size; + + uint64_t frequencyTableSize; + unsigned char frequencyTableByteSize; + + unsigned long streamByteCount; + + streamByteCount = 0; + + outputBufPos = 0; + output_size = static_cast (outputIntVector_arg.size ()); + + // read size of cumulative frequency table from stream + inputByteStream_arg.read (reinterpret_cast (&frequencyTableSize), sizeof(frequencyTableSize)); + inputByteStream_arg.read (reinterpret_cast (&frequencyTableByteSize), sizeof(frequencyTableByteSize)); + + streamByteCount += sizeof(frequencyTableSize) + sizeof(frequencyTableByteSize); + + // check size of frequency table vector + if (cFreqTable_.size () < frequencyTableSize) + { + cFreqTable_.resize (static_cast (frequencyTableSize)); + } + + // init with zero + memset (&cFreqTable_[0], 0, sizeof(uint64_t) * static_cast (frequencyTableSize)); + + // read cumulative frequency table + for (f = 1; f < frequencyTableSize; f++) + { + inputByteStream_arg.read (reinterpret_cast (&cFreqTable_[f]), frequencyTableByteSize); + streamByteCount += frequencyTableByteSize; + } + + // initialize range & code + code = 0; + low = 0; + range = static_cast (-1); + + // init code vector + for (i = 0; i < 8; i++) + { + inputByteStream_arg.read (reinterpret_cast (&ch), sizeof(char)); + streamByteCount += sizeof(char); + code = (code << 8) | ch; + } + + // decoding + for (i = 0; i < output_size; i++) + { + uint64_t count = (code - low) / (range /= cFreqTable_[static_cast (frequencyTableSize - 1)]); + + // symbol lookup in cumulative frequency table + uint64_t symbol = 0; + uint64_t sSize = (frequencyTableSize - 1) / 2; + while (sSize > 0) + { + if (cFreqTable_[static_cast (symbol + sSize)] <= count) + { + symbol += sSize; + } + sSize /= 2; + } + + // write symbol to output stream + outputIntVector_arg[outputBufPos++] = static_cast (symbol); + + // map to range + low += cFreqTable_[static_cast (symbol)] * range; + range *= cFreqTable_[static_cast (symbol + 1)] - cFreqTable_[static_cast (symbol)]; + + // check range limits + while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -low & (bottom - 1)), 1))) + { + inputByteStream_arg.read (reinterpret_cast (&ch), sizeof(char)); + streamByteCount += sizeof(char); + code = code << 8 | ch; + range <<= 8; + low <<= 8; + } + + } + + return streamByteCount; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +unsigned long +pcl::StaticRangeCoder::encodeCharVectorToStream (const std::vector& inputByteVector_arg, + std::ostream& outputByteStream_arg) +{ + DWord freq[257]; + uint8_t ch; + int i, f; + char out; + + // define numerical limits + const DWord top = static_cast (1) << 24; + const DWord bottom = static_cast (1) << 16; + const DWord maxRange = static_cast (1) << 16; + + DWord low, range; + + unsigned int input_size; + input_size = static_cast (inputByteVector_arg.size ()); + + unsigned int readPos; + + unsigned long streamByteCount; + + streamByteCount = 0; + + // init output vector + outputCharVector_.clear (); + outputCharVector_.reserve (sizeof(char) * input_size); + + uint64_t FreqHist[257]; + + // calculate frequency table + memset (FreqHist, 0, sizeof(FreqHist)); + readPos = 0; + while (readPos < input_size) + { + uint8_t symbol = static_cast (inputByteVector_arg[readPos++]); + FreqHist[symbol + 1]++; + } + + // convert to cumulative frequency table + freq[0] = 0; + for (f = 1; f <= 256; f++) + { + freq[f] = freq[f - 1] + static_cast (FreqHist[f]); + if (freq[f] <= freq[f - 1]) + freq[f] = freq[f - 1] + 1; + } + + // rescale if numerical limits are reached + while (freq[256] >= maxRange) + { + for (f = 1; f <= 256; f++) + { + freq[f] /= 2; + ; + if (freq[f] <= freq[f - 1]) + freq[f] = freq[f - 1] + 1; + } + } + + // write cumulative frequency table to output stream + outputByteStream_arg.write (reinterpret_cast (&freq[0]), sizeof(freq)); + streamByteCount += sizeof(freq); + + readPos = 0; + + low = 0; + range = static_cast (-1); + + // start encoding + while (readPos < input_size) + { + + // read symol + ch = inputByteVector_arg[readPos++]; + + // map to range + low += freq[ch] * (range /= freq[256]); + range *= freq[ch + 1] - freq[ch]; + + // check range limits + while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -int (low) & (bottom - 1)), 1))) + { + out = static_cast (low >> 24); + range <<= 8; + low <<= 8; + outputCharVector_.push_back (out); + } + + } + + // flush remaining data + for (i = 0; i < 4; i++) + { + out = static_cast (low >> 24); + outputCharVector_.push_back (out); + low <<= 8; + } + + // write encoded data to stream + outputByteStream_arg.write (&outputCharVector_[0], outputCharVector_.size ()); + + streamByteCount += static_cast (outputCharVector_.size ()); + + return (streamByteCount); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +unsigned long +pcl::StaticRangeCoder::decodeStreamToCharVector (std::istream& inputByteStream_arg, + std::vector& outputByteVector_arg) +{ + uint8_t ch; + DWord freq[257]; + unsigned int i; + + // define range limits + const DWord top = static_cast (1) << 24; + const DWord bottom = static_cast (1) << 16; + + DWord low, range; + DWord code; + + unsigned int outputBufPos; + unsigned int output_size; + + unsigned long streamByteCount; + + streamByteCount = 0; + + output_size = static_cast (outputByteVector_arg.size ()); + + outputBufPos = 0; + + // read cumulative frequency table + inputByteStream_arg.read (reinterpret_cast (&freq[0]), sizeof(freq)); + streamByteCount += sizeof(freq); + + code = 0; + low = 0; + range = static_cast (-1); + + // init code + for (i = 0; i < 4; i++) + { + inputByteStream_arg.read (reinterpret_cast (&ch), sizeof(char)); + streamByteCount += sizeof(char); + code = (code << 8) | ch; + } + + // decoding + for (i = 0; i < output_size; i++) + { + // symbol lookup in cumulative frequency table + uint8_t symbol = 0; + uint8_t sSize = 256 / 2; + + DWord count = (code - low) / (range /= freq[256]); + + while (sSize > 0) + { + if (freq[symbol + sSize] <= count) + { + symbol = static_cast (symbol + sSize); + } + sSize /= 2; + } + + // write symbol to output stream + outputByteVector_arg[outputBufPos++] = symbol; + + low += freq[symbol] * range; + range *= freq[symbol + 1] - freq[symbol]; + + // check range limits + while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -int (low) & (bottom - 1)), 1))) + { + inputByteStream_arg.read (reinterpret_cast (&ch), sizeof(char)); + streamByteCount += sizeof(char); + code = code << 8 | ch; + range <<= 8; + low <<= 8; + } + + } + + return (streamByteCount); +} + +#endif + diff --git a/pcl-1.7/pcl/io/impl/lzf_image_io.hpp b/pcl-1.7/pcl/io/impl/lzf_image_io.hpp new file mode 100644 index 0000000..c6ddb44 --- /dev/null +++ b/pcl-1.7/pcl/io/impl/lzf_image_io.hpp @@ -0,0 +1,512 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_LZF_IMAGE_IO_HPP_ +#define PCL_LZF_IMAGE_IO_HPP_ + +#include +#include + +#define CLIP_CHAR(c) static_cast ((c)>255?255:(c)<0?0:(c)) + +////////////////////////////////////////////////////////////////////////////// +template bool +pcl::io::LZFDepth16ImageReader::read ( + const std::string &filename, pcl::PointCloud &cloud) +{ + uint32_t uncompressed_size; + std::vector compressed_data; + if (!loadImageBlob (filename, compressed_data, uncompressed_size)) + { + PCL_ERROR ("[pcl::io::LZFDepth16ImageReader::read] Unable to read image data from %s.\n", filename.c_str ()); + return (false); + } + + if (uncompressed_size != getWidth () * getHeight () * 2) + { + PCL_DEBUG ("[pcl::io::LZFDepth16ImageReader::read] Uncompressed data has wrong size (%u), while in fact it should be %u bytes. \n[pcl::io::LZFDepth16ImageReader::read] Are you sure %s is a 16-bit depth PCLZF file? Identifier says: %s\n", uncompressed_size, getWidth () * getHeight () * 2, filename.c_str (), getImageType ().c_str ()); + return (false); + } + + std::vector uncompressed_data (uncompressed_size); + decompress (compressed_data, uncompressed_data); + + if (uncompressed_data.empty ()) + { + PCL_ERROR ("[pcl::io::LZFDepth16ImageReader::read] Error uncompressing data stored in %s!\n", filename.c_str ()); + return (false); + } + + // Copy to PointT + cloud.width = getWidth (); + cloud.height = getHeight (); + cloud.is_dense = true; + cloud.resize (getWidth () * getHeight ()); + register int depth_idx = 0, point_idx = 0; + double constant_x = 1.0 / parameters_.focal_length_x, + constant_y = 1.0 / parameters_.focal_length_y; + for (uint32_t v = 0; v < cloud.height; ++v) + { + for (register uint32_t u = 0; u < cloud.width; ++u, ++point_idx, depth_idx += 2) + { + PointT &pt = cloud.points[point_idx]; + unsigned short val; + memcpy (&val, &uncompressed_data[depth_idx], sizeof (unsigned short)); + if (val == 0) + { + pt.x = pt.y = pt.z = std::numeric_limits::quiet_NaN (); + cloud.is_dense = false; + continue; + } + + pt.z = static_cast (val * z_multiplication_factor_); + pt.x = (static_cast (u) - static_cast (parameters_.principal_point_x)) + * pt.z * static_cast (constant_x); + pt.y = (static_cast (v) - static_cast (parameters_.principal_point_y)) + * pt.z * static_cast (constant_y); + } + } + cloud.sensor_origin_.setZero (); + cloud.sensor_orientation_.w () = 1.0f; + cloud.sensor_orientation_.x () = 0.0f; + cloud.sensor_orientation_.y () = 0.0f; + cloud.sensor_orientation_.z () = 0.0f; + return (true); +} + +/////////////////////////////////////////////////////////////////////////////// +template bool +pcl::io::LZFDepth16ImageReader::readOMP (const std::string &filename, + pcl::PointCloud &cloud, + unsigned int num_threads) +{ + uint32_t uncompressed_size; + std::vector compressed_data; + if (!loadImageBlob (filename, compressed_data, uncompressed_size)) + { + PCL_ERROR ("[pcl::io::LZFDepth16ImageReader::read] Unable to read image data from %s.\n", filename.c_str ()); + return (false); + } + + if (uncompressed_size != getWidth () * getHeight () * 2) + { + PCL_DEBUG ("[pcl::io::LZFDepth16ImageReader::read] Uncompressed data has wrong size (%u), while in fact it should be %u bytes. \n[pcl::io::LZFDepth16ImageReader::read] Are you sure %s is a 16-bit depth PCLZF file? Identifier says: %s\n", uncompressed_size, getWidth () * getHeight () * 2, filename.c_str (), getImageType ().c_str ()); + return (false); + } + + std::vector uncompressed_data (uncompressed_size); + decompress (compressed_data, uncompressed_data); + + if (uncompressed_data.empty ()) + { + PCL_ERROR ("[pcl::io::LZFDepth16ImageReader::read] Error uncompressing data stored in %s!\n", filename.c_str ()); + return (false); + } + + // Copy to PointT + cloud.width = getWidth (); + cloud.height = getHeight (); + cloud.is_dense = true; + cloud.resize (getWidth () * getHeight ()); + double constant_x = 1.0 / parameters_.focal_length_x, + constant_y = 1.0 / parameters_.focal_length_y; +#ifdef _OPENMP +#pragma omp parallel for num_threads (num_threads) +#endif + for (int i = 0; i < static_cast< int> (cloud.size ()); ++i) + { + int u = i % cloud.width; + int v = i / cloud.width; + PointT &pt = cloud.points[i]; + int depth_idx = 2*i; + unsigned short val; + memcpy (&val, &uncompressed_data[depth_idx], sizeof (unsigned short)); + if (val == 0) + { + pt.x = pt.y = pt.z = std::numeric_limits::quiet_NaN (); + if (cloud.is_dense) + { +#ifdef _OPENMP +#pragma omp critical +#endif + { + if (cloud.is_dense) + cloud.is_dense = false; + } + } + continue; + } + + pt.z = static_cast (val * z_multiplication_factor_); + pt.x = (static_cast (u) - static_cast (parameters_.principal_point_x)) + * pt.z * static_cast (constant_x); + pt.y = (static_cast (v) - static_cast (parameters_.principal_point_y)) + * pt.z * static_cast (constant_y); + + } + cloud.sensor_origin_.setZero (); + cloud.sensor_orientation_.w () = 1.0f; + cloud.sensor_orientation_.x () = 0.0f; + cloud.sensor_orientation_.y () = 0.0f; + cloud.sensor_orientation_.z () = 0.0f; + return (true); + +} + +////////////////////////////////////////////////////////////////////////////// +template bool +pcl::io::LZFRGB24ImageReader::read ( + const std::string &filename, pcl::PointCloud &cloud) +{ + uint32_t uncompressed_size; + std::vector compressed_data; + if (!loadImageBlob (filename, compressed_data, uncompressed_size)) + { + PCL_ERROR ("[pcl::io::LZFRGB24ImageReader::read] Unable to read image data from %s.\n", filename.c_str ()); + return (false); + } + + if (uncompressed_size != getWidth () * getHeight () * 3) + { + PCL_DEBUG ("[pcl::io::LZFRGB24ImageReader::read] Uncompressed data has wrong size (%u), while in fact it should be %u bytes. \n[pcl::io::LZFRGB24ImageReader::read] Are you sure %s is a 24-bit RGB PCLZF file? Identifier says: %s\n", uncompressed_size, getWidth () * getHeight () * 3, filename.c_str (), getImageType ().c_str ()); + return (false); + } + + std::vector uncompressed_data (uncompressed_size); + decompress (compressed_data, uncompressed_data); + + if (uncompressed_data.empty ()) + { + PCL_ERROR ("[pcl::io::LZFRGB24ImageReader::read] Error uncompressing data stored in %s!\n", filename.c_str ()); + return (false); + } + + // Copy to PointT + cloud.width = getWidth (); + cloud.height = getHeight (); + cloud.resize (getWidth () * getHeight ()); + + register int rgb_idx = 0; + unsigned char *color_r = reinterpret_cast (&uncompressed_data[0]); + unsigned char *color_g = reinterpret_cast (&uncompressed_data[getWidth () * getHeight ()]); + unsigned char *color_b = reinterpret_cast (&uncompressed_data[2 * getWidth () * getHeight ()]); + + for (size_t i = 0; i < cloud.size (); ++i, ++rgb_idx) + { + PointT &pt = cloud.points[i]; + + pt.b = color_b[rgb_idx]; + pt.g = color_g[rgb_idx]; + pt.r = color_r[rgb_idx]; + } + return (true); +} + +////////////////////////////////////////////////////////////////////////////// +template bool +pcl::io::LZFRGB24ImageReader::readOMP ( + const std::string &filename, pcl::PointCloud &cloud, unsigned int num_threads) +{ + uint32_t uncompressed_size; + std::vector compressed_data; + if (!loadImageBlob (filename, compressed_data, uncompressed_size)) + { + PCL_ERROR ("[pcl::io::LZFRGB24ImageReader::read] Unable to read image data from %s.\n", filename.c_str ()); + return (false); + } + + if (uncompressed_size != getWidth () * getHeight () * 3) + { + PCL_DEBUG ("[pcl::io::LZFRGB24ImageReader::read] Uncompressed data has wrong size (%u), while in fact it should be %u bytes. \n[pcl::io::LZFRGB24ImageReader::read] Are you sure %s is a 24-bit RGB PCLZF file? Identifier says: %s\n", uncompressed_size, getWidth () * getHeight () * 3, filename.c_str (), getImageType ().c_str ()); + return (false); + } + + std::vector uncompressed_data (uncompressed_size); + decompress (compressed_data, uncompressed_data); + + if (uncompressed_data.empty ()) + { + PCL_ERROR ("[pcl::io::LZFRGB24ImageReader::read] Error uncompressing data stored in %s!\n", filename.c_str ()); + return (false); + } + + // Copy to PointT + cloud.width = getWidth (); + cloud.height = getHeight (); + cloud.resize (getWidth () * getHeight ()); + + unsigned char *color_r = reinterpret_cast (&uncompressed_data[0]); + unsigned char *color_g = reinterpret_cast (&uncompressed_data[getWidth () * getHeight ()]); + unsigned char *color_b = reinterpret_cast (&uncompressed_data[2 * getWidth () * getHeight ()]); + +#ifdef _OPENMP +#pragma omp parallel for num_threads (num_threads) +#endif//_OPENMP + for (long int i = 0; i < cloud.size (); ++i) + { + PointT &pt = cloud.points[i]; + + pt.b = color_b[i]; + pt.g = color_g[i]; + pt.r = color_r[i]; + } + return (true); +} + +////////////////////////////////////////////////////////////////////////////// +template bool +pcl::io::LZFYUV422ImageReader::read ( + const std::string &filename, pcl::PointCloud &cloud) +{ + uint32_t uncompressed_size; + std::vector compressed_data; + if (!loadImageBlob (filename, compressed_data, uncompressed_size)) + { + PCL_ERROR ("[pcl::io::LZFYUV422ImageReader::read] Unable to read image data from %s.\n", filename.c_str ()); + return (false); + } + + if (uncompressed_size != getWidth () * getHeight () * 2) + { + PCL_DEBUG ("[pcl::io::LZFYUV422ImageReader::read] Uncompressed data has wrong size (%u), while in fact it should be %u bytes. \n[pcl::io::LZFYUV422ImageReader::read] Are you sure %s is a 16-bit YUV422 PCLZF file? Identifier says: %s\n", uncompressed_size, getWidth () * getHeight (), filename.c_str (), getImageType ().c_str ()); + return (false); + } + + std::vector uncompressed_data (uncompressed_size); + decompress (compressed_data, uncompressed_data); + + if (uncompressed_data.empty ()) + { + PCL_ERROR ("[pcl::io::LZFYUV422ImageReader::read] Error uncompressing data stored in %s!\n", filename.c_str ()); + return (false); + } + + // Convert YUV422 to RGB24 and copy to PointT + cloud.width = getWidth (); + cloud.height = getHeight (); + cloud.resize (getWidth () * getHeight ()); + + int wh2 = getWidth () * getHeight () / 2; + unsigned char *color_u = reinterpret_cast (&uncompressed_data[0]); + unsigned char *color_y = reinterpret_cast (&uncompressed_data[wh2]); + unsigned char *color_v = reinterpret_cast (&uncompressed_data[wh2 + getWidth () * getHeight ()]); + + register int y_idx = 0; + for (int i = 0; i < wh2; ++i, y_idx += 2) + { + int v = color_v[i] - 128; + int u = color_u[i] - 128; + + PointT &pt1 = cloud.points[y_idx + 0]; + pt1.r = CLIP_CHAR (color_y[y_idx + 0] + ((v * 18678 + 8192 ) >> 14)); + pt1.g = CLIP_CHAR (color_y[y_idx + 0] + ((v * -9519 - u * 6472 + 8192) >> 14)); + pt1.b = CLIP_CHAR (color_y[y_idx + 0] + ((u * 33292 + 8192 ) >> 14)); + + PointT &pt2 = cloud.points[y_idx + 1]; + pt2.r = CLIP_CHAR (color_y[y_idx + 1] + ((v * 18678 + 8192 ) >> 14)); + pt2.g = CLIP_CHAR (color_y[y_idx + 1] + ((v * -9519 - u * 6472 + 8192) >> 14)); + pt2.b = CLIP_CHAR (color_y[y_idx + 1] + ((u * 33292 + 8192 ) >> 14)); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////// +template bool +pcl::io::LZFYUV422ImageReader::readOMP ( + const std::string &filename, pcl::PointCloud &cloud, unsigned int num_threads) +{ + uint32_t uncompressed_size; + std::vector compressed_data; + if (!loadImageBlob (filename, compressed_data, uncompressed_size)) + { + PCL_ERROR ("[pcl::io::LZFYUV422ImageReader::read] Unable to read image data from %s.\n", filename.c_str ()); + return (false); + } + + if (uncompressed_size != getWidth () * getHeight () * 2) + { + PCL_DEBUG ("[pcl::io::LZFYUV422ImageReader::read] Uncompressed data has wrong size (%u), while in fact it should be %u bytes. \n[pcl::io::LZFYUV422ImageReader::read] Are you sure %s is a 16-bit YUV422 PCLZF file? Identifier says: %s\n", uncompressed_size, getWidth () * getHeight (), filename.c_str (), getImageType ().c_str ()); + return (false); + } + + std::vector uncompressed_data (uncompressed_size); + decompress (compressed_data, uncompressed_data); + + if (uncompressed_data.empty ()) + { + PCL_ERROR ("[pcl::io::LZFYUV422ImageReader::read] Error uncompressing data stored in %s!\n", filename.c_str ()); + return (false); + } + + // Convert YUV422 to RGB24 and copy to PointT + cloud.width = getWidth (); + cloud.height = getHeight (); + cloud.resize (getWidth () * getHeight ()); + + int wh2 = getWidth () * getHeight () / 2; + unsigned char *color_u = reinterpret_cast (&uncompressed_data[0]); + unsigned char *color_y = reinterpret_cast (&uncompressed_data[wh2]); + unsigned char *color_v = reinterpret_cast (&uncompressed_data[wh2 + getWidth () * getHeight ()]); + +#ifdef _OPENMP +#pragma omp parallel for num_threads (num_threads) +#endif//_OPENMP + for (int i = 0; i < wh2; ++i) + { + int y_idx = 2*i; + int v = color_v[i] - 128; + int u = color_u[i] - 128; + + PointT &pt1 = cloud.points[y_idx + 0]; + pt1.r = CLIP_CHAR (color_y[y_idx + 0] + ((v * 18678 + 8192 ) >> 14)); + pt1.g = CLIP_CHAR (color_y[y_idx + 0] + ((v * -9519 - u * 6472 + 8192) >> 14)); + pt1.b = CLIP_CHAR (color_y[y_idx + 0] + ((u * 33292 + 8192 ) >> 14)); + + PointT &pt2 = cloud.points[y_idx + 1]; + pt2.r = CLIP_CHAR (color_y[y_idx + 1] + ((v * 18678 + 8192 ) >> 14)); + pt2.g = CLIP_CHAR (color_y[y_idx + 1] + ((v * -9519 - u * 6472 + 8192) >> 14)); + pt2.b = CLIP_CHAR (color_y[y_idx + 1] + ((u * 33292 + 8192 ) >> 14)); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////// +template bool +pcl::io::LZFBayer8ImageReader::read ( + const std::string &filename, pcl::PointCloud &cloud) +{ + uint32_t uncompressed_size; + std::vector compressed_data; + if (!loadImageBlob (filename, compressed_data, uncompressed_size)) + { + PCL_ERROR ("[pcl::io::LZFBayer8ImageReader::read] Unable to read image data from %s.\n", filename.c_str ()); + return (false); + } + + if (uncompressed_size != getWidth () * getHeight ()) + { + PCL_DEBUG ("[pcl::io::LZFBayer8ImageReader::read] Uncompressed data has wrong size (%u), while in fact it should be %u bytes. \n[pcl::io::LZFBayer8ImageReader::read] Are you sure %s is a 8-bit Bayer PCLZF file? Identifier says: %s\n", uncompressed_size, getWidth () * getHeight (), filename.c_str (), getImageType ().c_str ()); + return (false); + } + + std::vector uncompressed_data (uncompressed_size); + decompress (compressed_data, uncompressed_data); + + if (uncompressed_data.empty ()) + { + PCL_ERROR ("[pcl::io::LZFBayer8ImageReader::read] Error uncompressing data stored in %s!\n", filename.c_str ()); + return (false); + } + + // Convert Bayer8 to RGB24 + std::vector rgb_buffer (getWidth () * getHeight () * 3); + pcl::io::DeBayer i; + i.debayerEdgeAware (reinterpret_cast (&uncompressed_data[0]), + static_cast (&rgb_buffer[0]), + getWidth (), getHeight ()); + // Copy to PointT + cloud.width = getWidth (); + cloud.height = getHeight (); + cloud.resize (getWidth () * getHeight ()); + register int rgb_idx = 0; + for (size_t i = 0; i < cloud.size (); ++i, rgb_idx += 3) + { + PointT &pt = cloud.points[i]; + + pt.b = rgb_buffer[rgb_idx + 2]; + pt.g = rgb_buffer[rgb_idx + 1]; + pt.r = rgb_buffer[rgb_idx + 0]; + } + return (true); +} + +////////////////////////////////////////////////////////////////////////////// +template bool +pcl::io::LZFBayer8ImageReader::readOMP ( + const std::string &filename, pcl::PointCloud &cloud, unsigned int num_threads) +{ + uint32_t uncompressed_size; + std::vector compressed_data; + if (!loadImageBlob (filename, compressed_data, uncompressed_size)) + { + PCL_ERROR ("[pcl::io::LZFBayer8ImageReader::read] Unable to read image data from %s.\n", filename.c_str ()); + return (false); + } + + if (uncompressed_size != getWidth () * getHeight ()) + { + PCL_DEBUG ("[pcl::io::LZFBayer8ImageReader::read] Uncompressed data has wrong size (%u), while in fact it should be %u bytes. \n[pcl::io::LZFBayer8ImageReader::read] Are you sure %s is a 8-bit Bayer PCLZF file? Identifier says: %s\n", uncompressed_size, getWidth () * getHeight (), filename.c_str (), getImageType ().c_str ()); + return (false); + } + + std::vector uncompressed_data (uncompressed_size); + decompress (compressed_data, uncompressed_data); + + if (uncompressed_data.empty ()) + { + PCL_ERROR ("[pcl::io::LZFBayer8ImageReader::read] Error uncompressing data stored in %s!\n", filename.c_str ()); + return (false); + } + + // Convert Bayer8 to RGB24 + std::vector rgb_buffer (getWidth () * getHeight () * 3); + pcl::io::DeBayer i; + i.debayerEdgeAware (reinterpret_cast (&uncompressed_data[0]), + static_cast (&rgb_buffer[0]), + getWidth (), getHeight ()); + // Copy to PointT + cloud.width = getWidth (); + cloud.height = getHeight (); + cloud.resize (getWidth () * getHeight ()); +#ifdef _OPENMP +#pragma omp parallel for num_threads (num_threads) +#endif//_OPENMP + for (long int i = 0; i < cloud.size (); ++i) + { + PointT &pt = cloud.points[i]; + long int rgb_idx = 3*i; + pt.b = rgb_buffer[rgb_idx + 2]; + pt.g = rgb_buffer[rgb_idx + 1]; + pt.r = rgb_buffer[rgb_idx + 0]; + } + return (true); +} + +#endif //#ifndef PCL_LZF_IMAGE_IO_HPP_ + diff --git a/pcl-1.7/pcl/io/impl/octree_pointcloud_compression.hpp b/pcl-1.7/pcl/io/impl/octree_pointcloud_compression.hpp new file mode 100644 index 0000000..5e0b5ec --- /dev/null +++ b/pcl-1.7/pcl/io/impl/octree_pointcloud_compression.hpp @@ -0,0 +1,568 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef OCTREE_COMPRESSION_HPP +#define OCTREE_COMPRESSION_HPP + +#include +#include + +#include +#include +#include +#include +#include +#include + +using namespace pcl::octree; + +namespace pcl +{ + namespace io + { + ////////////////////////////////////////////////////////////////////////////////////////////// + template void OctreePointCloudCompression< + PointT, LeafT, BranchT, OctreeT>::encodePointCloud ( + const PointCloudConstPtr &cloud_arg, + std::ostream& compressed_tree_data_out_arg) + { + unsigned char recent_tree_depth = + static_cast (this->getTreeDepth ()); + + // initialize octree + this->setInputCloud (cloud_arg); + + // add point to octree + this->addPointsFromInputCloud (); + + // make sure cloud contains points + if (this->leaf_count_>0) { + + + // color field analysis + cloud_with_color_ = false; + std::vector fields; + int rgba_index = -1; + rgba_index = pcl::getFieldIndex (*this->input_, "rgb", fields); + if (rgba_index == -1) + { + rgba_index = pcl::getFieldIndex (*this->input_, "rgba", fields); + } + if (rgba_index >= 0) + { + point_color_offset_ = static_cast (fields[rgba_index].offset); + cloud_with_color_ = true; + } + + // apply encoding configuration + cloud_with_color_ &= do_color_encoding_; + + + // if octree depth changed, we enforce I-frame encoding + i_frame_ |= (recent_tree_depth != this->getTreeDepth ());// | !(iFrameCounter%10); + + // enable I-frame rate + if (i_frame_counter_++==i_frame_rate_) + { + i_frame_counter_ =0; + i_frame_ = true; + } + + // increase frameID + frame_ID_++; + + // do octree encoding + if (!do_voxel_grid_enDecoding_) + { + point_count_data_vector_.clear (); + point_count_data_vector_.reserve (cloud_arg->points.size ()); + } + + // initialize color encoding + color_coder_.initializeEncoding (); + color_coder_.setPointCount (static_cast (cloud_arg->points.size ())); + color_coder_.setVoxelCount (static_cast (this->leaf_count_)); + + // initialize point encoding + point_coder_.initializeEncoding (); + point_coder_.setPointCount (static_cast (cloud_arg->points.size ())); + + // serialize octree + if (i_frame_) + // i-frame encoding - encode tree structure without referencing previous buffer + this->serializeTree (binary_tree_data_vector_, false); + else + // p-frame encoding - XOR encoded tree structure + this->serializeTree (binary_tree_data_vector_, true); + + + // write frame header information to stream + this->writeFrameHeader (compressed_tree_data_out_arg); + + // apply entropy coding to the content of all data vectors and send data to output stream + this->entropyEncoding (compressed_tree_data_out_arg); + + // prepare for next frame + this->switchBuffers (); + i_frame_ = false; + + // reset object count + object_count_ = 0; + + if (b_show_statistics_) + { + float bytes_per_XYZ = static_cast (compressed_point_data_len_) / static_cast (point_count_); + float bytes_per_color = static_cast (compressed_color_data_len_) / static_cast (point_count_); + + PCL_INFO ("*** POINTCLOUD ENCODING ***\n"); + PCL_INFO ("Frame ID: %d\n", frame_ID_); + if (i_frame_) + PCL_INFO ("Encoding Frame: Intra frame\n"); + else + PCL_INFO ("Encoding Frame: Prediction frame\n"); + PCL_INFO ("Number of encoded points: %ld\n", point_count_); + PCL_INFO ("XYZ compression percentage: %f%%\n", bytes_per_XYZ / (3.0f * sizeof(float)) * 100.0f); + PCL_INFO ("XYZ bytes per point: %f bytes\n", bytes_per_XYZ); + PCL_INFO ("Color compression percentage: %f%%\n", bytes_per_color / (sizeof (int)) * 100.0f); + PCL_INFO ("Color bytes per point: %f bytes\n", bytes_per_color); + PCL_INFO ("Size of uncompressed point cloud: %f kBytes\n", static_cast (point_count_) * (sizeof (int) + 3.0f * sizeof (float)) / 1024); + PCL_INFO ("Size of compressed point cloud: %d kBytes\n", (compressed_point_data_len_ + compressed_color_data_len_) / (1024)); + PCL_INFO ("Total bytes per point: %f\n", bytes_per_XYZ + bytes_per_color); + PCL_INFO ("Total compression percentage: %f\n", (bytes_per_XYZ + bytes_per_color) / (sizeof (int) + 3.0f * sizeof(float)) * 100.0f); + PCL_INFO ("Compression ratio: %f\n\n", static_cast (sizeof (int) + 3.0f * sizeof (float)) / static_cast (bytes_per_XYZ + bytes_per_color)); + } + } else { + if (b_show_statistics_) + PCL_INFO ("Info: Dropping empty point cloud\n"); + this->deleteTree(); + i_frame_counter_ = 0; + i_frame_ = true; + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + OctreePointCloudCompression::decodePointCloud ( + std::istream& compressed_tree_data_in_arg, + PointCloudPtr &cloud_arg) + { + + // synchronize to frame header + syncToHeader(compressed_tree_data_in_arg); + + // initialize octree + this->switchBuffers (); + this->setOutputCloud (cloud_arg); + + // color field analysis + cloud_with_color_ = false; + std::vector fields; + int rgba_index = -1; + rgba_index = pcl::getFieldIndex (*output_, "rgb", fields); + if (rgba_index == -1) + rgba_index = pcl::getFieldIndex (*output_, "rgba", fields); + if (rgba_index >= 0) + { + point_color_offset_ = static_cast (fields[rgba_index].offset); + cloud_with_color_ = true; + } + + // read header from input stream + this->readFrameHeader (compressed_tree_data_in_arg); + + // decode data vectors from stream + this->entropyDecoding (compressed_tree_data_in_arg); + + // initialize color and point encoding + color_coder_.initializeDecoding (); + point_coder_.initializeDecoding (); + + // initialize output cloud + output_->points.clear (); + output_->points.reserve (static_cast (point_count_)); + + if (i_frame_) + // i-frame decoding - decode tree structure without referencing previous buffer + this->deserializeTree (binary_tree_data_vector_, false); + else + // p-frame decoding - decode XOR encoded tree structure + this->deserializeTree (binary_tree_data_vector_, true); + + // assign point cloud properties + output_->height = 1; + output_->width = static_cast (cloud_arg->points.size ()); + output_->is_dense = false; + + if (b_show_statistics_) + { + float bytes_per_XYZ = static_cast (compressed_point_data_len_) / static_cast (point_count_); + float bytes_per_color = static_cast (compressed_color_data_len_) / static_cast (point_count_); + + PCL_INFO ("*** POINTCLOUD DECODING ***\n"); + PCL_INFO ("Frame ID: %d\n", frame_ID_); + if (i_frame_) + PCL_INFO ("Encoding Frame: Intra frame\n"); + else + PCL_INFO ("Encoding Frame: Prediction frame\n"); + PCL_INFO ("Number of encoded points: %ld\n", point_count_); + PCL_INFO ("XYZ compression percentage: %f%%\n", bytes_per_XYZ / (3.0f * sizeof (float)) * 100.0f); + PCL_INFO ("XYZ bytes per point: %f bytes\n", bytes_per_XYZ); + PCL_INFO ("Color compression percentage: %f%%\n", bytes_per_color / (sizeof (int)) * 100.0f); + PCL_INFO ("Color bytes per point: %f bytes\n", bytes_per_color); + PCL_INFO ("Size of uncompressed point cloud: %f kBytes\n", static_cast (point_count_) * (sizeof (int) + 3.0f * sizeof (float)) / 1024.0f); + PCL_INFO ("Size of compressed point cloud: %f kBytes\n", static_cast (compressed_point_data_len_ + compressed_color_data_len_) / 1024.0f); + PCL_INFO ("Total bytes per point: %d bytes\n", static_cast (bytes_per_XYZ + bytes_per_color)); + PCL_INFO ("Total compression percentage: %f%%\n", (bytes_per_XYZ + bytes_per_color) / (sizeof (int) + 3.0f * sizeof (float)) * 100.0f); + PCL_INFO ("Compression ratio: %f\n\n", static_cast (sizeof (int) + 3.0f * sizeof (float)) / static_cast (bytes_per_XYZ + bytes_per_color)); + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + OctreePointCloudCompression::entropyEncoding (std::ostream& compressed_tree_data_out_arg) + { + uint64_t binary_tree_data_vector_size; + uint64_t point_avg_color_data_vector_size; + + compressed_point_data_len_ = 0; + compressed_color_data_len_ = 0; + + // encode binary octree structure + binary_tree_data_vector_size = binary_tree_data_vector_.size (); + compressed_tree_data_out_arg.write (reinterpret_cast (&binary_tree_data_vector_size), sizeof (binary_tree_data_vector_size)); + compressed_point_data_len_ += entropy_coder_.encodeCharVectorToStream (binary_tree_data_vector_, + compressed_tree_data_out_arg); + + if (cloud_with_color_) + { + // encode averaged voxel color information + std::vector& pointAvgColorDataVector = color_coder_.getAverageDataVector (); + point_avg_color_data_vector_size = pointAvgColorDataVector.size (); + compressed_tree_data_out_arg.write (reinterpret_cast (&point_avg_color_data_vector_size), + sizeof (point_avg_color_data_vector_size)); + compressed_color_data_len_ += entropy_coder_.encodeCharVectorToStream (pointAvgColorDataVector, + compressed_tree_data_out_arg); + } + + if (!do_voxel_grid_enDecoding_) + { + uint64_t pointCountDataVector_size; + uint64_t point_diff_data_vector_size; + uint64_t point_diff_color_data_vector_size; + + // encode amount of points per voxel + pointCountDataVector_size = point_count_data_vector_.size (); + compressed_tree_data_out_arg.write (reinterpret_cast (&pointCountDataVector_size), sizeof (pointCountDataVector_size)); + compressed_point_data_len_ += entropy_coder_.encodeIntVectorToStream (point_count_data_vector_, + compressed_tree_data_out_arg); + + // encode differential point information + std::vector& point_diff_data_vector = point_coder_.getDifferentialDataVector (); + point_diff_data_vector_size = point_diff_data_vector.size (); + compressed_tree_data_out_arg.write (reinterpret_cast (&point_diff_data_vector_size), sizeof (point_diff_data_vector_size)); + compressed_point_data_len_ += entropy_coder_.encodeCharVectorToStream (point_diff_data_vector, + compressed_tree_data_out_arg); + if (cloud_with_color_) + { + // encode differential color information + std::vector& point_diff_color_data_vector = color_coder_.getDifferentialDataVector (); + point_diff_color_data_vector_size = point_diff_color_data_vector.size (); + compressed_tree_data_out_arg.write (reinterpret_cast (&point_diff_color_data_vector_size), + sizeof (point_diff_color_data_vector_size)); + compressed_color_data_len_ += entropy_coder_.encodeCharVectorToStream (point_diff_color_data_vector, + compressed_tree_data_out_arg); + } + } + // flush output stream + compressed_tree_data_out_arg.flush (); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + OctreePointCloudCompression::entropyDecoding (std::istream& compressed_tree_data_in_arg) + { + uint64_t binary_tree_data_vector_size; + uint64_t point_avg_color_data_vector_size; + + compressed_point_data_len_ = 0; + compressed_color_data_len_ = 0; + + // decode binary octree structure + compressed_tree_data_in_arg.read (reinterpret_cast (&binary_tree_data_vector_size), sizeof (binary_tree_data_vector_size)); + binary_tree_data_vector_.resize (static_cast (binary_tree_data_vector_size)); + compressed_point_data_len_ += entropy_coder_.decodeStreamToCharVector (compressed_tree_data_in_arg, + binary_tree_data_vector_); + + if (data_with_color_) + { + // decode averaged voxel color information + std::vector& point_avg_color_data_vector = color_coder_.getAverageDataVector (); + compressed_tree_data_in_arg.read (reinterpret_cast (&point_avg_color_data_vector_size), sizeof (point_avg_color_data_vector_size)); + point_avg_color_data_vector.resize (static_cast (point_avg_color_data_vector_size)); + compressed_color_data_len_ += entropy_coder_.decodeStreamToCharVector (compressed_tree_data_in_arg, + point_avg_color_data_vector); + } + + if (!do_voxel_grid_enDecoding_) + { + uint64_t point_count_data_vector_size; + uint64_t point_diff_data_vector_size; + uint64_t point_diff_color_data_vector_size; + + // decode amount of points per voxel + compressed_tree_data_in_arg.read (reinterpret_cast (&point_count_data_vector_size), sizeof (point_count_data_vector_size)); + point_count_data_vector_.resize (static_cast (point_count_data_vector_size)); + compressed_point_data_len_ += entropy_coder_.decodeStreamToIntVector (compressed_tree_data_in_arg, point_count_data_vector_); + point_count_data_vector_iterator_ = point_count_data_vector_.begin (); + + // decode differential point information + std::vector& pointDiffDataVector = point_coder_.getDifferentialDataVector (); + compressed_tree_data_in_arg.read (reinterpret_cast (&point_diff_data_vector_size), sizeof (point_diff_data_vector_size)); + pointDiffDataVector.resize (static_cast (point_diff_data_vector_size)); + compressed_point_data_len_ += entropy_coder_.decodeStreamToCharVector (compressed_tree_data_in_arg, + pointDiffDataVector); + + if (data_with_color_) + { + // decode differential color information + std::vector& pointDiffColorDataVector = color_coder_.getDifferentialDataVector (); + compressed_tree_data_in_arg.read (reinterpret_cast (&point_diff_color_data_vector_size), sizeof (point_diff_color_data_vector_size)); + pointDiffColorDataVector.resize (static_cast (point_diff_color_data_vector_size)); + compressed_color_data_len_ += entropy_coder_.decodeStreamToCharVector (compressed_tree_data_in_arg, + pointDiffColorDataVector); + } + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + OctreePointCloudCompression::writeFrameHeader (std::ostream& compressed_tree_data_out_arg) + { + // encode header identifier + compressed_tree_data_out_arg.write (reinterpret_cast (frame_header_identifier_), strlen (frame_header_identifier_)); + // encode point cloud header id + compressed_tree_data_out_arg.write (reinterpret_cast (&frame_ID_), sizeof (frame_ID_)); + // encode frame type (I/P-frame) + compressed_tree_data_out_arg.write (reinterpret_cast (&i_frame_), sizeof (i_frame_)); + if (i_frame_) + { + double min_x, min_y, min_z, max_x, max_y, max_z; + double octree_resolution; + unsigned char color_bit_depth; + double point_resolution; + + // get current configuration + octree_resolution = this->getResolution (); + color_bit_depth = color_coder_.getBitDepth (); + point_resolution= point_coder_.getPrecision (); + this->getBoundingBox (min_x, min_y, min_z, max_x, max_y, max_z); + + // encode amount of points + if (do_voxel_grid_enDecoding_) + point_count_ = this->leaf_count_; + else + point_count_ = this->object_count_; + + // encode coding configuration + compressed_tree_data_out_arg.write (reinterpret_cast (&do_voxel_grid_enDecoding_), sizeof (do_voxel_grid_enDecoding_)); + compressed_tree_data_out_arg.write (reinterpret_cast (&cloud_with_color_), sizeof (cloud_with_color_)); + compressed_tree_data_out_arg.write (reinterpret_cast (&point_count_), sizeof (point_count_)); + compressed_tree_data_out_arg.write (reinterpret_cast (&octree_resolution), sizeof (octree_resolution)); + compressed_tree_data_out_arg.write (reinterpret_cast (&color_bit_depth), sizeof (color_bit_depth)); + compressed_tree_data_out_arg.write (reinterpret_cast (&point_resolution), sizeof (point_resolution)); + + // encode octree bounding box + compressed_tree_data_out_arg.write (reinterpret_cast (&min_x), sizeof (min_x)); + compressed_tree_data_out_arg.write (reinterpret_cast (&min_y), sizeof (min_y)); + compressed_tree_data_out_arg.write (reinterpret_cast (&min_z), sizeof (min_z)); + compressed_tree_data_out_arg.write (reinterpret_cast (&max_x), sizeof (max_x)); + compressed_tree_data_out_arg.write (reinterpret_cast (&max_y), sizeof (max_y)); + compressed_tree_data_out_arg.write (reinterpret_cast (&max_z), sizeof (max_z)); + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + OctreePointCloudCompression::syncToHeader ( std::istream& compressed_tree_data_in_arg) + { + // sync to frame header + unsigned int header_id_pos = 0; + while (header_id_pos < strlen (frame_header_identifier_)) + { + char readChar; + compressed_tree_data_in_arg.read (static_cast (&readChar), sizeof (readChar)); + if (readChar != frame_header_identifier_[header_id_pos++]) + header_id_pos = (frame_header_identifier_[0]==readChar)?1:0; + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + OctreePointCloudCompression::readFrameHeader ( std::istream& compressed_tree_data_in_arg) + { + // read header + compressed_tree_data_in_arg.read (reinterpret_cast (&frame_ID_), sizeof (frame_ID_)); + compressed_tree_data_in_arg.read (reinterpret_cast(&i_frame_), sizeof (i_frame_)); + if (i_frame_) + { + double min_x, min_y, min_z, max_x, max_y, max_z; + double octree_resolution; + unsigned char color_bit_depth; + double point_resolution; + + // read coder configuration + compressed_tree_data_in_arg.read (reinterpret_cast (&do_voxel_grid_enDecoding_), sizeof (do_voxel_grid_enDecoding_)); + compressed_tree_data_in_arg.read (reinterpret_cast (&data_with_color_), sizeof (data_with_color_)); + compressed_tree_data_in_arg.read (reinterpret_cast (&point_count_), sizeof (point_count_)); + compressed_tree_data_in_arg.read (reinterpret_cast (&octree_resolution), sizeof (octree_resolution)); + compressed_tree_data_in_arg.read (reinterpret_cast (&color_bit_depth), sizeof (color_bit_depth)); + compressed_tree_data_in_arg.read (reinterpret_cast (&point_resolution), sizeof (point_resolution)); + + // read octree bounding box + compressed_tree_data_in_arg.read (reinterpret_cast (&min_x), sizeof (min_x)); + compressed_tree_data_in_arg.read (reinterpret_cast (&min_y), sizeof (min_y)); + compressed_tree_data_in_arg.read (reinterpret_cast (&min_z), sizeof (min_z)); + compressed_tree_data_in_arg.read (reinterpret_cast (&max_x), sizeof (max_x)); + compressed_tree_data_in_arg.read (reinterpret_cast (&max_y), sizeof (max_y)); + compressed_tree_data_in_arg.read (reinterpret_cast (&max_z), sizeof (max_z)); + + // reset octree and assign new bounding box & resolution + this->deleteTree (); + this->setResolution (octree_resolution); + this->defineBoundingBox (min_x, min_y, min_z, max_x, max_y, max_z); + + // configure color & point coding + color_coder_.setBitDepth (color_bit_depth); + point_coder_.setPrecision (static_cast (point_resolution)); + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + OctreePointCloudCompression::serializeTreeCallback ( + LeafT &leaf_arg, const OctreeKey & key_arg) + { + // reference to point indices vector stored within octree leaf + const std::vector& leafIdx = leaf_arg.getPointIndicesVector(); + + if (!do_voxel_grid_enDecoding_) + { + double lowerVoxelCorner[3]; + + // encode amount of points within voxel + point_count_data_vector_.push_back (static_cast (leafIdx.size ())); + + // calculate lower voxel corner based on octree key + lowerVoxelCorner[0] = static_cast (key_arg.x) * this->resolution_ + this->min_x_; + lowerVoxelCorner[1] = static_cast (key_arg.y) * this->resolution_ + this->min_y_; + lowerVoxelCorner[2] = static_cast (key_arg.z) * this->resolution_ + this->min_z_; + + // differentially encode points to lower voxel corner + point_coder_.encodePoints (leafIdx, lowerVoxelCorner, this->input_); + + if (cloud_with_color_) + // encode color of points + color_coder_.encodePoints (leafIdx, point_color_offset_, this->input_); + } + else + { + if (cloud_with_color_) + // encode average color of all points within voxel + color_coder_.encodeAverageOfPoints (leafIdx, point_color_offset_, this->input_); + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + OctreePointCloudCompression::deserializeTreeCallback (LeafT&, + const OctreeKey& key_arg) + { + double lowerVoxelCorner[3]; + std::size_t pointCount, i, cloudSize; + PointT newPoint; + + pointCount = 1; + + if (!do_voxel_grid_enDecoding_) + { + // get current cloud size + cloudSize = output_->points.size (); + + // get amount of point to be decoded + pointCount = *point_count_data_vector_iterator_; + point_count_data_vector_iterator_++; + + // increase point cloud by amount of voxel points + for (i = 0; i < pointCount; i++) + output_->points.push_back (newPoint); + + // calculcate position of lower voxel corner + lowerVoxelCorner[0] = static_cast (key_arg.x) * this->resolution_ + this->min_x_; + lowerVoxelCorner[1] = static_cast (key_arg.y) * this->resolution_ + this->min_y_; + lowerVoxelCorner[2] = static_cast (key_arg.z) * this->resolution_ + this->min_z_; + + // decode differentially encoded points + point_coder_.decodePoints (output_, lowerVoxelCorner, cloudSize, cloudSize + pointCount); + } + else + { + // calculate center of lower voxel corner + newPoint.x = static_cast ((static_cast (key_arg.x) + 0.5) * this->resolution_ + this->min_x_); + newPoint.y = static_cast ((static_cast (key_arg.y) + 0.5) * this->resolution_ + this->min_y_); + newPoint.z = static_cast ((static_cast (key_arg.z) + 0.5) * this->resolution_ + this->min_z_); + + // add point to point cloud + output_->points.push_back (newPoint); + } + + if (cloud_with_color_) + { + if (data_with_color_) + // decode color information + color_coder_.decodePoints (output_, output_->points.size () - pointCount, + output_->points.size (), point_color_offset_); + else + // set default color information + color_coder_.setDefaultColor (output_, output_->points.size () - pointCount, + output_->points.size (), point_color_offset_); + } + } + } +} + +#endif + diff --git a/pcl-1.7/pcl/io/impl/organized_pointcloud_compression.hpp b/pcl-1.7/pcl/io/impl/organized_pointcloud_compression.hpp new file mode 100644 index 0000000..8849aa3 --- /dev/null +++ b/pcl-1.7/pcl/io/impl/organized_pointcloud_compression.hpp @@ -0,0 +1,456 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef ORGANIZED_COMPRESSION_HPP +#define ORGANIZED_COMPRESSION_HPP + +#include + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include + +namespace pcl +{ + namespace io + { + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + OrganizedPointCloudCompression::encodePointCloud (const PointCloudConstPtr &cloud_arg, + std::ostream& compressedDataOut_arg, + bool doColorEncoding, + bool convertToMono, + bool bShowStatistics_arg, + int pngLevel_arg) + { + uint32_t cloud_width = cloud_arg->width; + uint32_t cloud_height = cloud_arg->height; + + float maxDepth, focalLength, disparityShift, disparityScale; + + // no disparity scaling/shifting required during decoding + disparityScale = 1.0f; + disparityShift = 0.0f; + + analyzeOrganizedCloud (cloud_arg, maxDepth, focalLength); + + // encode header identifier + compressedDataOut_arg.write (reinterpret_cast (frameHeaderIdentifier_), strlen (frameHeaderIdentifier_)); + // encode point cloud width + compressedDataOut_arg.write (reinterpret_cast (&cloud_width), sizeof (cloud_width)); + // encode frame type height + compressedDataOut_arg.write (reinterpret_cast (&cloud_height), sizeof (cloud_height)); + // encode frame max depth + compressedDataOut_arg.write (reinterpret_cast (&maxDepth), sizeof (maxDepth)); + // encode frame focal lenght + compressedDataOut_arg.write (reinterpret_cast (&focalLength), sizeof (focalLength)); + // encode frame disparity scale + compressedDataOut_arg.write (reinterpret_cast (&disparityScale), sizeof (disparityScale)); + // encode frame disparity shift + compressedDataOut_arg.write (reinterpret_cast (&disparityShift), sizeof (disparityShift)); + + // disparity and rgb image data + std::vector disparityData; + std::vector colorData; + + // compressed disparity and rgb image data + std::vector compressedDisparity; + std::vector compressedColor; + + uint32_t compressedDisparitySize = 0; + uint32_t compressedColorSize = 0; + + // Convert point cloud to disparity and rgb image + OrganizedConversion::convert (*cloud_arg, focalLength, disparityShift, disparityScale, convertToMono, disparityData, colorData); + + // Compress disparity information + encodeMonoImageToPNG (disparityData, cloud_width, cloud_height, compressedDisparity, pngLevel_arg); + + compressedDisparitySize = static_cast(compressedDisparity.size()); + // Encode size of compressed disparity image data + compressedDataOut_arg.write (reinterpret_cast (&compressedDisparitySize), sizeof (compressedDisparitySize)); + // Output compressed disparity to ostream + compressedDataOut_arg.write (reinterpret_cast (&compressedDisparity[0]), compressedDisparity.size () * sizeof(uint8_t)); + + // Compress color information + if (CompressionPointTraits::hasColor && doColorEncoding) + { + if (convertToMono) + { + encodeMonoImageToPNG (colorData, cloud_width, cloud_height, compressedColor, 1 /*Z_BEST_SPEED*/); + } else + { + encodeRGBImageToPNG (colorData, cloud_width, cloud_height, compressedColor, 1 /*Z_BEST_SPEED*/); + } + } + + compressedColorSize = static_cast(compressedColor.size ()); + // Encode size of compressed Color image data + compressedDataOut_arg.write (reinterpret_cast (&compressedColorSize), sizeof (compressedColorSize)); + // Output compressed disparity to ostream + compressedDataOut_arg.write (reinterpret_cast (&compressedColor[0]), compressedColor.size () * sizeof(uint8_t)); + + if (bShowStatistics_arg) + { + uint64_t pointCount = cloud_width * cloud_height; + float bytesPerPoint = static_cast (compressedDisparitySize+compressedColorSize) / static_cast (pointCount); + + PCL_INFO("*** POINTCLOUD ENCODING ***\n"); + PCL_INFO("Number of encoded points: %ld\n", pointCount); + PCL_INFO("Size of uncompressed point cloud: %.2f kBytes\n", (static_cast (pointCount) * CompressionPointTraits::bytesPerPoint) / 1024.0f); + PCL_INFO("Size of compressed point cloud: %.2f kBytes\n", static_cast (compressedDisparitySize+compressedColorSize) / 1024.0f); + PCL_INFO("Total bytes per point: %.4f bytes\n", static_cast (bytesPerPoint)); + PCL_INFO("Total compression percentage: %.4f%%\n", (bytesPerPoint) / (CompressionPointTraits::bytesPerPoint) * 100.0f); + PCL_INFO("Compression ratio: %.2f\n\n", static_cast (CompressionPointTraits::bytesPerPoint) / bytesPerPoint); + } + + // flush output stream + compressedDataOut_arg.flush(); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + OrganizedPointCloudCompression::encodeRawDisparityMapWithColorImage ( std::vector& disparityMap_arg, + std::vector& colorImage_arg, + uint32_t width_arg, + uint32_t height_arg, + std::ostream& compressedDataOut_arg, + bool doColorEncoding, + bool convertToMono, + bool bShowStatistics_arg, + int pngLevel_arg, + float focalLength_arg, + float disparityShift_arg, + float disparityScale_arg) + { + float maxDepth = -1; + + size_t cloud_size = width_arg*height_arg; + assert (disparityMap_arg.size()==cloud_size); + if (colorImage_arg.size()) + { + assert (colorImage_arg.size()==cloud_size*3); + } + + // encode header identifier + compressedDataOut_arg.write (reinterpret_cast (frameHeaderIdentifier_), strlen (frameHeaderIdentifier_)); + // encode point cloud width + compressedDataOut_arg.write (reinterpret_cast (&width_arg), sizeof (width_arg)); + // encode frame type height + compressedDataOut_arg.write (reinterpret_cast (&height_arg), sizeof (height_arg)); + // encode frame max depth + compressedDataOut_arg.write (reinterpret_cast (&maxDepth), sizeof (maxDepth)); + // encode frame focal lenght + compressedDataOut_arg.write (reinterpret_cast (&focalLength_arg), sizeof (focalLength_arg)); + // encode frame disparity scale + compressedDataOut_arg.write (reinterpret_cast (&disparityScale_arg), sizeof (disparityScale_arg)); + // encode frame disparity shift + compressedDataOut_arg.write (reinterpret_cast (&disparityShift_arg), sizeof (disparityShift_arg)); + + // compressed disparity and rgb image data + std::vector compressedDisparity; + std::vector compressedColor; + + uint32_t compressedDisparitySize = 0; + uint32_t compressedColorSize = 0; + + // Remove color information of invalid points + uint16_t* depth_ptr = &disparityMap_arg[0]; + uint8_t* color_ptr = &colorImage_arg[0]; + + size_t i; + for (i=0; i(compressedDisparity.size()); + // Encode size of compressed disparity image data + compressedDataOut_arg.write (reinterpret_cast (&compressedDisparitySize), sizeof (compressedDisparitySize)); + // Output compressed disparity to ostream + compressedDataOut_arg.write (reinterpret_cast (&compressedDisparity[0]), compressedDisparity.size () * sizeof(uint8_t)); + + // Compress color information + if (colorImage_arg.size() && doColorEncoding) + { + if (convertToMono) + { + size_t i, size; + vector monoImage; + size = width_arg*height_arg; + + monoImage.reserve(size); + + // grayscale conversion + for (i=0; i(0.2989 * static_cast(colorImage_arg[i*3+0]) + + 0.5870 * static_cast(colorImage_arg[i*3+1]) + + 0.1140 * static_cast(colorImage_arg[i*3+2])); + monoImage.push_back(grayvalue); + } + encodeMonoImageToPNG (monoImage, width_arg, height_arg, compressedColor, 1 /*Z_BEST_SPEED*/); + + } else + { + encodeRGBImageToPNG (colorImage_arg, width_arg, height_arg, compressedColor, 1 /*Z_BEST_SPEED*/); + } + + } + + compressedColorSize = static_cast(compressedColor.size ()); + // Encode size of compressed Color image data + compressedDataOut_arg.write (reinterpret_cast (&compressedColorSize), sizeof (compressedColorSize)); + // Output compressed disparity to ostream + compressedDataOut_arg.write (reinterpret_cast (&compressedColor[0]), compressedColor.size () * sizeof(uint8_t)); + + if (bShowStatistics_arg) + { + uint64_t pointCount = width_arg * height_arg; + float bytesPerPoint = static_cast (compressedDisparitySize+compressedColorSize) / static_cast (pointCount); + + PCL_INFO("*** POINTCLOUD ENCODING ***\n"); + PCL_INFO("Number of encoded points: %ld\n", pointCount); + PCL_INFO("Size of uncompressed disparity map+color image: %.2f kBytes\n", (static_cast (pointCount) * (sizeof(uint8_t)*3+sizeof(uint16_t))) / 1024.0f); + PCL_INFO("Size of compressed point cloud: %.2f kBytes\n", static_cast (compressedDisparitySize+compressedColorSize) / 1024.0f); + PCL_INFO("Total bytes per point: %.4f bytes\n", static_cast (bytesPerPoint)); + PCL_INFO("Total compression percentage: %.4f%%\n", (bytesPerPoint) / (sizeof(uint8_t)*3+sizeof(uint16_t)) * 100.0f); + PCL_INFO("Compression ratio: %.2f\n\n", static_cast (CompressionPointTraits::bytesPerPoint) / bytesPerPoint); + } + + // flush output stream + compressedDataOut_arg.flush(); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template bool + OrganizedPointCloudCompression::decodePointCloud (std::istream& compressedDataIn_arg, + PointCloudPtr &cloud_arg, + bool bShowStatistics_arg) + { + uint32_t cloud_width; + uint32_t cloud_height; + float maxDepth; + float focalLength; + float disparityShift = 0.0f; + float disparityScale; + + // disparity and rgb image data + std::vector disparityData; + std::vector colorData; + + // compressed disparity and rgb image data + std::vector compressedDisparity; + std::vector compressedColor; + + uint32_t compressedDisparitySize; + uint32_t compressedColorSize; + + // PNG decoded parameters + size_t png_width = 0; + size_t png_height = 0; + unsigned int png_channels = 1; + + // sync to frame header + unsigned int headerIdPos = 0; + bool valid_stream = true; + while (valid_stream && (headerIdPos < strlen (frameHeaderIdentifier_))) + { + char readChar; + compressedDataIn_arg.read (static_cast (&readChar), sizeof (readChar)); + if (compressedDataIn_arg.gcount()!= sizeof (readChar)) + valid_stream = false; + if (readChar != frameHeaderIdentifier_[headerIdPos++]) + headerIdPos = (frameHeaderIdentifier_[0] == readChar) ? 1 : 0; + + valid_stream &= compressedDataIn_arg.good (); + } + + if (valid_stream) { + + ////////////// + // reading frame header + compressedDataIn_arg.read (reinterpret_cast (&cloud_width), sizeof (cloud_width)); + compressedDataIn_arg.read (reinterpret_cast (&cloud_height), sizeof (cloud_height)); + compressedDataIn_arg.read (reinterpret_cast (&maxDepth), sizeof (maxDepth)); + compressedDataIn_arg.read (reinterpret_cast (&focalLength), sizeof (focalLength)); + compressedDataIn_arg.read (reinterpret_cast (&disparityScale), sizeof (disparityScale)); + compressedDataIn_arg.read (reinterpret_cast (&disparityShift), sizeof (disparityShift)); + + // reading compressed disparity data + compressedDataIn_arg.read (reinterpret_cast (&compressedDisparitySize), sizeof (compressedDisparitySize)); + compressedDisparity.resize (compressedDisparitySize); + compressedDataIn_arg.read (reinterpret_cast (&compressedDisparity[0]), compressedDisparitySize * sizeof(uint8_t)); + + // reading compressed rgb data + compressedDataIn_arg.read (reinterpret_cast (&compressedColorSize), sizeof (compressedColorSize)); + compressedColor.resize (compressedColorSize); + compressedDataIn_arg.read (reinterpret_cast (&compressedColor[0]), compressedColorSize * sizeof(uint8_t)); + + // decode PNG compressed disparity data + decodePNGToImage (compressedDisparity, disparityData, png_width, png_height, png_channels); + + // decode PNG compressed rgb data + decodePNGToImage (compressedColor, colorData, png_width, png_height, png_channels); + } + + if (disparityShift==0.0f) + { + // reconstruct point cloud + OrganizedConversion::convert (disparityData, + colorData, + static_cast(png_channels==1), + cloud_width, + cloud_height, + focalLength, + disparityShift, + disparityScale, + *cloud_arg); + } else + { + + // we need to decode a raw shift image + std::size_t size = disparityData.size(); + std::vector depthData; + depthData.resize(size); + + // initialize shift-to-depth converter + if (!sd_converter_.isInitialized()) + sd_converter_.generateLookupTable(); + + // convert shift to depth image + for (std::size_t i=0; i::convert (depthData, + colorData, + static_cast(png_channels==1), + cloud_width, + cloud_height, + focalLength, + *cloud_arg); + } + + if (bShowStatistics_arg) + { + uint64_t pointCount = cloud_width * cloud_height; + float bytesPerPoint = static_cast (compressedDisparitySize+compressedColorSize) / static_cast (pointCount); + + PCL_INFO("*** POINTCLOUD DECODING ***\n"); + PCL_INFO("Number of encoded points: %ld\n", pointCount); + PCL_INFO("Size of uncompressed point cloud: %.2f kBytes\n", (static_cast (pointCount) * CompressionPointTraits::bytesPerPoint) / 1024.0f); + PCL_INFO("Size of compressed point cloud: %.2f kBytes\n", static_cast (compressedDisparitySize+compressedColorSize) / 1024.0f); + PCL_INFO("Total bytes per point: %.4f bytes\n", static_cast (bytesPerPoint)); + PCL_INFO("Total compression percentage: %.4f%%\n", (bytesPerPoint) / (CompressionPointTraits::bytesPerPoint) * 100.0f); + PCL_INFO("Compression ratio: %.2f\n\n", static_cast (CompressionPointTraits::bytesPerPoint) / bytesPerPoint); + } + + return valid_stream; + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + OrganizedPointCloudCompression::analyzeOrganizedCloud (PointCloudConstPtr cloud_arg, + float& maxDepth_arg, + float& focalLength_arg) const + { + size_t width, height, it; + int centerX, centerY; + int x, y; + float maxDepth; + float focalLength; + + width = cloud_arg->width; + height = cloud_arg->height; + + // Center of organized point cloud + centerX = static_cast (width / 2); + centerY = static_cast (height / 2); + + // Ensure we have an organized point cloud + assert((width>1) && (height>1)); + assert(width*height == cloud_arg->points.size()); + + maxDepth = 0; + focalLength = 0; + + it = 0; + for (y = -centerY; y < +centerY; ++y) + for (x = -centerX; x < +centerX; ++x) + { + const PointT& point = cloud_arg->points[it++]; + + if (pcl::isFinite (point)) + { + if (maxDepth < point.z) + { + // Update maximum depth + maxDepth = point.z; + + // Calculate focal length + focalLength = 2.0f / (point.x / (static_cast (x) * point.z) + point.y / (static_cast (y) * point.z)); + } + } + } + + // Update return values + maxDepth_arg = maxDepth; + focalLength_arg = focalLength; + } + + } +} + +#endif + diff --git a/pcl-1.7/pcl/io/impl/pcd_io.hpp b/pcl-1.7/pcl/io/impl/pcd_io.hpp new file mode 100644 index 0000000..b6623fb --- /dev/null +++ b/pcl-1.7/pcl/io/impl/pcd_io.hpp @@ -0,0 +1,921 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_IO_PCD_IO_IMPL_H_ +#define PCL_IO_PCD_IO_IMPL_H_ + +#include +#include +#include +#include +#include +#include +#include + +#ifdef _WIN32 +# include +# ifndef WIN32_LEAN_AND_MEAN +# define WIN32_LEAN_AND_MEAN +# endif // WIN32_LEAN_AND_MEAN +# ifndef NOMINMAX +# define NOMINMAX +# endif // NOMINMAX +# include +# define pcl_open _open +# define pcl_close(fd) _close(fd) +# define pcl_lseek(fd,offset,origin) _lseek(fd,offset,origin) +#else +# include +# define pcl_open open +# define pcl_close(fd) close(fd) +# define pcl_lseek(fd,offset,origin) lseek(fd,offset,origin) +#endif + +#include + +///////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template std::string +pcl::PCDWriter::generateHeader (const pcl::PointCloud &cloud, const int nr_points) +{ + std::ostringstream oss; + oss.imbue (std::locale::classic ()); + + oss << "# .PCD v0.7 - Point Cloud Data file format" + "\nVERSION 0.7" + "\nFIELDS"; + + std::vector fields; + pcl::getFields (cloud, fields); + + std::stringstream field_names, field_types, field_sizes, field_counts; + for (size_t i = 0; i < fields.size (); ++i) + { + if (fields[i].name == "_") + continue; + // Add the regular dimension + field_names << " " << fields[i].name; + field_sizes << " " << pcl::getFieldSize (fields[i].datatype); + field_types << " " << pcl::getFieldType (fields[i].datatype); + int count = abs (static_cast (fields[i].count)); + if (count == 0) count = 1; // check for 0 counts (coming from older converter code) + field_counts << " " << count; + } + oss << field_names.str (); + oss << "\nSIZE" << field_sizes.str () + << "\nTYPE" << field_types.str () + << "\nCOUNT" << field_counts.str (); + // If the user passes in a number of points value, use that instead + if (nr_points != std::numeric_limits::max ()) + oss << "\nWIDTH " << nr_points << "\nHEIGHT " << 1 << "\n"; + else + oss << "\nWIDTH " << cloud.width << "\nHEIGHT " << cloud.height << "\n"; + + oss << "VIEWPOINT " << cloud.sensor_origin_[0] << " " << cloud.sensor_origin_[1] << " " << cloud.sensor_origin_[2] << " " << + cloud.sensor_orientation_.w () << " " << + cloud.sensor_orientation_.x () << " " << + cloud.sensor_orientation_.y () << " " << + cloud.sensor_orientation_.z () << "\n"; + + // If the user passes in a number of points value, use that instead + if (nr_points != std::numeric_limits::max ()) + oss << "POINTS " << nr_points << "\n"; + else + oss << "POINTS " << cloud.points.size () << "\n"; + + return (oss.str ()); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::PCDWriter::writeBinary (const std::string &file_name, + const pcl::PointCloud &cloud) +{ + if (cloud.empty ()) + { + throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Input point cloud has no data!"); + return (-1); + } + int data_idx = 0; + std::ostringstream oss; + oss << generateHeader (cloud) << "DATA binary\n"; + oss.flush (); + data_idx = static_cast (oss.tellp ()); + +#if _WIN32 + HANDLE h_native_file = CreateFileA (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL); + if (h_native_file == INVALID_HANDLE_VALUE) + { + throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during CreateFile!"); + return (-1); + } +#else + int fd = pcl_open (file_name.c_str (), O_RDWR | O_CREAT | O_TRUNC, static_cast (0600)); + if (fd < 0) + { + throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during open!"); + return (-1); + } +#endif + // Mandatory lock file + boost::interprocess::file_lock file_lock; + setLockingPermissions (file_name, file_lock); + + std::vector fields; + std::vector fields_sizes; + size_t fsize = 0; + size_t data_size = 0; + size_t nri = 0; + pcl::getFields (cloud, fields); + // Compute the total size of the fields + for (size_t i = 0; i < fields.size (); ++i) + { + if (fields[i].name == "_") + continue; + + int fs = fields[i].count * getFieldSize (fields[i].datatype); + fsize += fs; + fields_sizes.push_back (fs); + fields[nri++] = fields[i]; + } + fields.resize (nri); + + data_size = cloud.points.size () * fsize; + + // Prepare the map +#if _WIN32 + HANDLE fm = CreateFileMappingA (h_native_file, NULL, PAGE_READWRITE, 0, (DWORD) (data_idx + data_size), NULL); + char *map = static_cast(MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, data_idx + data_size)); + CloseHandle (fm); + +#else + // Stretch the file size to the size of the data + off_t result = pcl_lseek (fd, getpagesize () + data_size - 1, SEEK_SET); + + if (result < 0) + { + pcl_close (fd); + resetLockingPermissions (file_name, file_lock); + PCL_ERROR ("[pcl::PCDWriter::writeBinary] lseek errno: %d strerror: %s\n", errno, strerror (errno)); + + throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during lseek ()!"); + return (-1); + } + // Write a bogus entry so that the new file size comes in effect + result = static_cast (::write (fd, "", 1)); + if (result != 1) + { + pcl_close (fd); + resetLockingPermissions (file_name, file_lock); + throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during write ()!"); + return (-1); + } + + char *map = static_cast (mmap (0, data_idx + data_size, PROT_WRITE, MAP_SHARED, fd, 0)); + if (map == reinterpret_cast (-1)) //MAP_FAILED) + { + pcl_close (fd); + resetLockingPermissions (file_name, file_lock); + throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during mmap ()!"); + return (-1); + } +#endif + + // Copy the header + memcpy (&map[0], oss.str ().c_str (), data_idx); + + // Copy the data + char *out = &map[0] + data_idx; + for (size_t i = 0; i < cloud.points.size (); ++i) + { + int nrj = 0; + for (size_t j = 0; j < fields.size (); ++j) + { + memcpy (out, reinterpret_cast (&cloud.points[i]) + fields[j].offset, fields_sizes[nrj]); + out += fields_sizes[nrj++]; + } + } + + // If the user set the synchronization flag on, call msync +#if !_WIN32 + if (map_synchronization_) + msync (map, data_idx + data_size, MS_SYNC); +#endif + + // Unmap the pages of memory +#if _WIN32 + UnmapViewOfFile (map); +#else + if (munmap (map, (data_idx + data_size)) == -1) + { + pcl_close (fd); + resetLockingPermissions (file_name, file_lock); + throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during munmap ()!"); + return (-1); + } +#endif + // Close file +#if _WIN32 + CloseHandle (h_native_file); +#else + pcl_close (fd); +#endif + resetLockingPermissions (file_name, file_lock); + return (0); +} + +///////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name, + const pcl::PointCloud &cloud) +{ + if (cloud.points.empty ()) + { + throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Input point cloud has no data!"); + return (-1); + } + int data_idx = 0; + std::ostringstream oss; + oss << generateHeader (cloud) << "DATA binary_compressed\n"; + oss.flush (); + data_idx = static_cast (oss.tellp ()); + +#if _WIN32 + HANDLE h_native_file = CreateFileA (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL); + if (h_native_file == INVALID_HANDLE_VALUE) + { + throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during CreateFile!"); + return (-1); + } +#else + int fd = pcl_open (file_name.c_str (), O_RDWR | O_CREAT | O_TRUNC, static_cast (0600)); + if (fd < 0) + { + throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during open!"); + return (-1); + } +#endif + + // Mandatory lock file + boost::interprocess::file_lock file_lock; + setLockingPermissions (file_name, file_lock); + + std::vector fields; + size_t fsize = 0; + size_t data_size = 0; + size_t nri = 0; + pcl::getFields (cloud, fields); + std::vector fields_sizes (fields.size ()); + // Compute the total size of the fields + for (size_t i = 0; i < fields.size (); ++i) + { + if (fields[i].name == "_") + continue; + + fields_sizes[nri] = fields[i].count * pcl::getFieldSize (fields[i].datatype); + fsize += fields_sizes[nri]; + fields[nri] = fields[i]; + ++nri; + } + fields_sizes.resize (nri); + fields.resize (nri); + + // Compute the size of data + data_size = cloud.points.size () * fsize; + + ////////////////////////////////////////////////////////////////////// + // Empty array holding only the valid data + // data_size = nr_points * point_size + // = nr_points * (sizeof_field_1 + sizeof_field_2 + ... sizeof_field_n) + // = sizeof_field_1 * nr_points + sizeof_field_2 * nr_points + ... sizeof_field_n * nr_points + char *only_valid_data = static_cast (malloc (data_size)); + + // Convert the XYZRGBXYZRGB structure to XXYYZZRGBRGB to aid compression. For + // this, we need a vector of fields.size () (4 in this case), which points to + // each individual plane: + // pters[0] = &only_valid_data[offset_of_plane_x]; + // pters[1] = &only_valid_data[offset_of_plane_y]; + // pters[2] = &only_valid_data[offset_of_plane_z]; + // pters[3] = &only_valid_data[offset_of_plane_RGB]; + // + std::vector pters (fields.size ()); + int toff = 0; + for (size_t i = 0; i < pters.size (); ++i) + { + pters[i] = &only_valid_data[toff]; + toff += fields_sizes[i] * static_cast (cloud.points.size ()); + } + + // Go over all the points, and copy the data in the appropriate places + for (size_t i = 0; i < cloud.points.size (); ++i) + { + for (size_t j = 0; j < fields.size (); ++j) + { + memcpy (pters[j], reinterpret_cast (&cloud.points[i]) + fields[j].offset, fields_sizes[j]); + // Increment the pointer + pters[j] += fields_sizes[j]; + } + } + + char* temp_buf = static_cast (malloc (static_cast (static_cast (data_size) * 1.5f + 8.0f))); + // Compress the valid data + unsigned int compressed_size = pcl::lzfCompress (only_valid_data, + static_cast (data_size), + &temp_buf[8], + static_cast (static_cast(data_size) * 1.5f)); + unsigned int compressed_final_size = 0; + // Was the compression successful? + if (compressed_size) + { + char *header = &temp_buf[0]; + memcpy (&header[0], &compressed_size, sizeof (unsigned int)); + memcpy (&header[4], &data_size, sizeof (unsigned int)); + data_size = compressed_size + 8; + compressed_final_size = static_cast (data_size) + data_idx; + } + else + { +#if !_WIN32 + pcl_close (fd); +#endif + resetLockingPermissions (file_name, file_lock); + throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during compression!"); + return (-1); + } + +#if !_WIN32 + // Stretch the file size to the size of the data + off_t result = pcl_lseek (fd, getpagesize () + data_size - 1, SEEK_SET); + if (result < 0) + { + pcl_close (fd); + resetLockingPermissions (file_name, file_lock); + PCL_ERROR ("[pcl::PCDWriter::writeBinary] lseek errno: %d strerror: %s\n", errno, strerror (errno)); + + throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during lseek ()!"); + return (-1); + } + // Write a bogus entry so that the new file size comes in effect + result = static_cast (::write (fd, "", 1)); + if (result != 1) + { + pcl_close (fd); + resetLockingPermissions (file_name, file_lock); + throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during write ()!"); + return (-1); + } +#endif + + // Prepare the map +#if _WIN32 + HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, compressed_final_size, NULL); + char *map = static_cast(MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, compressed_final_size)); + CloseHandle (fm); + +#else + char *map = static_cast (mmap (0, compressed_final_size, PROT_WRITE, MAP_SHARED, fd, 0)); + if (map == reinterpret_cast (-1)) //MAP_FAILED) + { + pcl_close (fd); + resetLockingPermissions (file_name, file_lock); + throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during mmap ()!"); + return (-1); + } +#endif + + // Copy the header + memcpy (&map[0], oss.str ().c_str (), data_idx); + // Copy the compressed data + memcpy (&map[data_idx], temp_buf, data_size); + +#if !_WIN32 + // If the user set the synchronization flag on, call msync + if (map_synchronization_) + msync (map, compressed_final_size, MS_SYNC); +#endif + + // Unmap the pages of memory +#if _WIN32 + UnmapViewOfFile (map); +#else + if (munmap (map, (compressed_final_size)) == -1) + { + pcl_close (fd); + resetLockingPermissions (file_name, file_lock); + throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during munmap ()!"); + return (-1); + } +#endif + + // Close file +#if _WIN32 + CloseHandle (h_native_file); +#else + pcl_close (fd); +#endif + resetLockingPermissions (file_name, file_lock); + + free (only_valid_data); + free (temp_buf); + return (0); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PointCloud &cloud, + const int precision) +{ + if (cloud.empty ()) + { + throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Input point cloud has no data!"); + return (-1); + } + + if (cloud.width * cloud.height != cloud.points.size ()) + { + throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Number of points different than width * height!"); + return (-1); + } + + std::ofstream fs; + fs.open (file_name.c_str ()); // Open file + + if (!fs.is_open () || fs.fail ()) + { + throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Could not open file for writing!"); + return (-1); + } + + // Mandatory lock file + boost::interprocess::file_lock file_lock; + setLockingPermissions (file_name, file_lock); + + fs.precision (precision); + fs.imbue (std::locale::classic ()); + + std::vector fields; + pcl::getFields (cloud, fields); + + // Write the header information + fs << generateHeader (cloud) << "DATA ascii\n"; + + std::ostringstream stream; + stream.precision (precision); + stream.imbue (std::locale::classic ()); + // Iterate through the points + for (size_t i = 0; i < cloud.points.size (); ++i) + { + for (size_t d = 0; d < fields.size (); ++d) + { + // Ignore invalid padded dimensions that are inherited from binary data + if (fields[d].name == "_") + continue; + + int count = fields[d].count; + if (count == 0) + count = 1; // we simply cannot tolerate 0 counts (coming from older converter code) + + for (int c = 0; c < count; ++c) + { + switch (fields[d].datatype) + { + case pcl::PCLPointField::INT8: + { + int8_t value; + memcpy (&value, reinterpret_cast (&cloud.points[i]) + fields[d].offset + c * sizeof (int8_t), sizeof (int8_t)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + case pcl::PCLPointField::UINT8: + { + uint8_t value; + memcpy (&value, reinterpret_cast (&cloud.points[i]) + fields[d].offset + c * sizeof (uint8_t), sizeof (uint8_t)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + case pcl::PCLPointField::INT16: + { + int16_t value; + memcpy (&value, reinterpret_cast (&cloud.points[i]) + fields[d].offset + c * sizeof (int16_t), sizeof (int16_t)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + case pcl::PCLPointField::UINT16: + { + uint16_t value; + memcpy (&value, reinterpret_cast (&cloud.points[i]) + fields[d].offset + c * sizeof (uint16_t), sizeof (uint16_t)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + case pcl::PCLPointField::INT32: + { + int32_t value; + memcpy (&value, reinterpret_cast (&cloud.points[i]) + fields[d].offset + c * sizeof (int32_t), sizeof (int32_t)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + case pcl::PCLPointField::UINT32: + { + uint32_t value; + memcpy (&value, reinterpret_cast (&cloud.points[i]) + fields[d].offset + c * sizeof (uint32_t), sizeof (uint32_t)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + case pcl::PCLPointField::FLOAT32: + { + float value; + memcpy (&value, reinterpret_cast (&cloud.points[i]) + fields[d].offset + c * sizeof (float), sizeof (float)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + case pcl::PCLPointField::FLOAT64: + { + double value; + memcpy (&value, reinterpret_cast (&cloud.points[i]) + fields[d].offset + c * sizeof (double), sizeof (double)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + default: + PCL_WARN ("[pcl::PCDWriter::writeASCII] Incorrect field data type specified (%d)!\n", fields[d].datatype); + break; + } + + if (d < fields.size () - 1 || c < static_cast (fields[d].count - 1)) + stream << " "; + } + } + // Copy the stream, trim it, and write it to disk + std::string result = stream.str (); + boost::trim (result); + stream.str (""); + fs << result << "\n"; + } + fs.close (); // Close file + resetLockingPermissions (file_name, file_lock); + return (0); +} + + +///////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::PCDWriter::writeBinary (const std::string &file_name, + const pcl::PointCloud &cloud, + const std::vector &indices) +{ + if (cloud.points.empty () || indices.empty ()) + { + throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Input point cloud has no data or empty indices given!"); + return (-1); + } + int data_idx = 0; + std::ostringstream oss; + oss << generateHeader (cloud, static_cast (indices.size ())) << "DATA binary\n"; + oss.flush (); + data_idx = static_cast (oss.tellp ()); + +#if _WIN32 + HANDLE h_native_file = CreateFileA (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL); + if (h_native_file == INVALID_HANDLE_VALUE) + { + throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during CreateFile!"); + return (-1); + } +#else + int fd = pcl_open (file_name.c_str (), O_RDWR | O_CREAT | O_TRUNC, static_cast (0600)); + if (fd < 0) + { + throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during open!"); + return (-1); + } +#endif + // Mandatory lock file + boost::interprocess::file_lock file_lock; + setLockingPermissions (file_name, file_lock); + + std::vector fields; + std::vector fields_sizes; + size_t fsize = 0; + size_t data_size = 0; + size_t nri = 0; + pcl::getFields (cloud, fields); + // Compute the total size of the fields + for (size_t i = 0; i < fields.size (); ++i) + { + if (fields[i].name == "_") + continue; + + int fs = fields[i].count * getFieldSize (fields[i].datatype); + fsize += fs; + fields_sizes.push_back (fs); + fields[nri++] = fields[i]; + } + fields.resize (nri); + + data_size = indices.size () * fsize; + + // Prepare the map +#if _WIN32 + HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, data_idx + data_size, NULL); + char *map = static_cast(MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, data_idx + data_size)); + CloseHandle (fm); + +#else + // Stretch the file size to the size of the data + off_t result = pcl_lseek (fd, getpagesize () + data_size - 1, SEEK_SET); + if (result < 0) + { + pcl_close (fd); + resetLockingPermissions (file_name, file_lock); + PCL_ERROR ("[pcl::PCDWriter::writeBinary] lseek errno: %d strerror: %s\n", errno, strerror (errno)); + + throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during lseek ()!"); + return (-1); + } + // Write a bogus entry so that the new file size comes in effect + result = static_cast (::write (fd, "", 1)); + if (result != 1) + { + pcl_close (fd); + resetLockingPermissions (file_name, file_lock); + throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during write ()!"); + return (-1); + } + + char *map = static_cast (mmap (0, data_idx + data_size, PROT_WRITE, MAP_SHARED, fd, 0)); + if (map == reinterpret_cast (-1)) //MAP_FAILED) + { + pcl_close (fd); + resetLockingPermissions (file_name, file_lock); + throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during mmap ()!"); + return (-1); + } +#endif + + // Copy the header + memcpy (&map[0], oss.str ().c_str (), data_idx); + + char *out = &map[0] + data_idx; + // Copy the data + for (size_t i = 0; i < indices.size (); ++i) + { + int nrj = 0; + for (size_t j = 0; j < fields.size (); ++j) + { + memcpy (out, reinterpret_cast (&cloud.points[indices[i]]) + fields[j].offset, fields_sizes[nrj]); + out += fields_sizes[nrj++]; + } + } + +#if !_WIN32 + // If the user set the synchronization flag on, call msync + if (map_synchronization_) + msync (map, data_idx + data_size, MS_SYNC); +#endif + + // Unmap the pages of memory +#if _WIN32 + UnmapViewOfFile (map); +#else + if (munmap (map, (data_idx + data_size)) == -1) + { + pcl_close (fd); + resetLockingPermissions (file_name, file_lock); + throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during munmap ()!"); + return (-1); + } +#endif + // Close file +#if _WIN32 + CloseHandle(h_native_file); +#else + pcl_close (fd); +#endif + + resetLockingPermissions (file_name, file_lock); + return (0); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::PCDWriter::writeASCII (const std::string &file_name, + const pcl::PointCloud &cloud, + const std::vector &indices, + const int precision) +{ + if (cloud.points.empty () || indices.empty ()) + { + throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Input point cloud has no data or empty indices given!"); + return (-1); + } + + if (cloud.width * cloud.height != cloud.points.size ()) + { + throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Number of points different than width * height!"); + return (-1); + } + + std::ofstream fs; + fs.open (file_name.c_str ()); // Open file + if (!fs.is_open () || fs.fail ()) + { + throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Could not open file for writing!"); + return (-1); + } + + // Mandatory lock file + boost::interprocess::file_lock file_lock; + setLockingPermissions (file_name, file_lock); + + fs.precision (precision); + fs.imbue (std::locale::classic ()); + + std::vector fields; + pcl::getFields (cloud, fields); + + // Write the header information + fs << generateHeader (cloud, static_cast (indices.size ())) << "DATA ascii\n"; + + std::ostringstream stream; + stream.precision (precision); + stream.imbue (std::locale::classic ()); + + // Iterate through the points + for (size_t i = 0; i < indices.size (); ++i) + { + for (size_t d = 0; d < fields.size (); ++d) + { + // Ignore invalid padded dimensions that are inherited from binary data + if (fields[d].name == "_") + continue; + + int count = fields[d].count; + if (count == 0) + count = 1; // we simply cannot tolerate 0 counts (coming from older converter code) + + for (int c = 0; c < count; ++c) + { + switch (fields[d].datatype) + { + case pcl::PCLPointField::INT8: + { + int8_t value; + memcpy (&value, reinterpret_cast (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (int8_t), sizeof (int8_t)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + case pcl::PCLPointField::UINT8: + { + uint8_t value; + memcpy (&value, reinterpret_cast (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (uint8_t), sizeof (uint8_t)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + case pcl::PCLPointField::INT16: + { + int16_t value; + memcpy (&value, reinterpret_cast (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (int16_t), sizeof (int16_t)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + case pcl::PCLPointField::UINT16: + { + uint16_t value; + memcpy (&value, reinterpret_cast (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (uint16_t), sizeof (uint16_t)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + case pcl::PCLPointField::INT32: + { + int32_t value; + memcpy (&value, reinterpret_cast (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (int32_t), sizeof (int32_t)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + case pcl::PCLPointField::UINT32: + { + uint32_t value; + memcpy (&value, reinterpret_cast (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (uint32_t), sizeof (uint32_t)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + case pcl::PCLPointField::FLOAT32: + { + float value; + memcpy (&value, reinterpret_cast (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (float), sizeof (float)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + case pcl::PCLPointField::FLOAT64: + { + double value; + memcpy (&value, reinterpret_cast (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (double), sizeof (double)); + if (pcl_isnan (value)) + stream << "nan"; + else + stream << boost::numeric_cast(value); + break; + } + default: + PCL_WARN ("[pcl::PCDWriter::writeASCII] Incorrect field data type specified (%d)!\n", fields[d].datatype); + break; + } + + if (d < fields.size () - 1 || c < static_cast (fields[d].count - 1)) + stream << " "; + } + } + // Copy the stream, trim it, and write it to disk + std::string result = stream.str (); + boost::trim (result); + stream.str (""); + fs << result << "\n"; + } + fs.close (); // Close file + + resetLockingPermissions (file_name, file_lock); + + return (0); +} + +#endif //#ifndef PCL_IO_PCD_IO_H_ + diff --git a/pcl-1.7/pcl/io/impl/point_cloud_image_extractors.hpp b/pcl-1.7/pcl/io/impl/point_cloud_image_extractors.hpp new file mode 100644 index 0000000..bb37f19 --- /dev/null +++ b/pcl-1.7/pcl/io/impl/point_cloud_image_extractors.hpp @@ -0,0 +1,557 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_POINT_CLOUD_IMAGE_EXTRACTORS_IMPL_HPP_ +#define PCL_POINT_CLOUD_IMAGE_EXTRACTORS_IMPL_HPP_ + +#include +#include +#include +#include + +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::io::PointCloudImageExtractor::extract (const PointCloud& cloud, pcl::PCLImage& img) const +{ + if (!cloud.isOrganized () || cloud.points.size () != cloud.width * cloud.height) + return (false); + + bool result = this->extractImpl (cloud, img); + + if (paint_nans_with_black_ && result) + { + size_t size = img.encoding == "mono16" ? 2 : 3; + for (size_t i = 0; i < cloud.points.size (); ++i) + if (!pcl::isFinite (cloud[i])) + std::memset (&img.data[i * size], 0, size); + } + + return (result); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::io::PointCloudImageExtractorFromNormalField::extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const +{ + std::vector fields; + int field_x_idx = pcl::getFieldIndex (cloud, "normal_x", fields); + int field_y_idx = pcl::getFieldIndex (cloud, "normal_y", fields); + int field_z_idx = pcl::getFieldIndex (cloud, "normal_z", fields); + if (field_x_idx == -1 || field_y_idx == -1 || field_z_idx == -1) + return (false); + const size_t offset_x = fields[field_x_idx].offset; + const size_t offset_y = fields[field_y_idx].offset; + const size_t offset_z = fields[field_z_idx].offset; + + img.encoding = "rgb8"; + img.width = cloud.width; + img.height = cloud.height; + img.step = img.width * sizeof (unsigned char) * 3; + img.data.resize (img.step * img.height); + + for (size_t i = 0; i < cloud.points.size (); ++i) + { + float x; + float y; + float z; + pcl::getFieldValue (cloud.points[i], offset_x, x); + pcl::getFieldValue (cloud.points[i], offset_y, y); + pcl::getFieldValue (cloud.points[i], offset_z, z); + img.data[i * 3 + 0] = static_cast((x + 1.0) * 127); + img.data[i * 3 + 1] = static_cast((y + 1.0) * 127); + img.data[i * 3 + 2] = static_cast((z + 1.0) * 127); + } + + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::io::PointCloudImageExtractorFromRGBField::extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const +{ + std::vector fields; + int field_idx = pcl::getFieldIndex (cloud, "rgb", fields); + if (field_idx == -1) + { + field_idx = pcl::getFieldIndex (cloud, "rgba", fields); + if (field_idx == -1) + return (false); + } + const size_t offset = fields[field_idx].offset; + + img.encoding = "rgb8"; + img.width = cloud.width; + img.height = cloud.height; + img.step = img.width * sizeof (unsigned char) * 3; + img.data.resize (img.step * img.height); + + for (size_t i = 0; i < cloud.points.size (); ++i) + { + uint32_t val; + pcl::getFieldValue (cloud.points[i], offset, val); + img.data[i * 3 + 0] = (val >> 16) & 0x0000ff; + img.data[i * 3 + 1] = (val >> 8) & 0x0000ff; + img.data[i * 3 + 2] = (val) & 0x0000ff; + } + + return (true); +} + +// Lookup table is copied from (excluding the first entry): +// https://github.com/fiji/fiji/blob/master/luts/glasbey.lut +const uint8_t GLASBEY_LUT[] = +{ + 0, 0, 255, + 255, 0, 0, + 0, 255, 0, + 0, 0, 51, + 255, 0, 182, + 0, 83, 0, + 255, 211, 0, + 0, 159, 255, + 154, 77, 66, + 0, 255, 190, + 120, 63, 193, + 31, 150, 152, + 255, 172, 253, + 177, 204, 113, + 241, 8, 92, + 254, 143, 66, + 221, 0, 255, + 32, 26, 1, + 114, 0, 85, + 118, 108, 149, + 2, 173, 36, + 200, 255, 0, + 136, 108, 0, + 255, 183, 159, + 133, 133, 103, + 161, 3, 0, + 20, 249, 255, + 0, 71, 158, + 220, 94, 147, + 147, 212, 255, + 0, 76, 255, + 0, 66, 80, + 57, 167, 106, + 238, 112, 254, + 0, 0, 100, + 171, 245, 204, + 161, 146, 255, + 164, 255, 115, + 255, 206, 113, + 71, 0, 21, + 212, 173, 197, + 251, 118, 111, + 171, 188, 0, + 117, 0, 215, + 166, 0, 154, + 0, 115, 254, + 165, 93, 174, + 98, 132, 2, + 0, 121, 168, + 0, 255, 131, + 86, 53, 0, + 159, 0, 63, + 66, 45, 66, + 255, 242, 187, + 0, 93, 67, + 252, 255, 124, + 159, 191, 186, + 167, 84, 19, + 74, 39, 108, + 0, 16, 166, + 145, 78, 109, + 207, 149, 0, + 195, 187, 255, + 253, 68, 64, + 66, 78, 32, + 106, 1, 0, + 181, 131, 84, + 132, 233, 147, + 96, 217, 0, + 255, 111, 211, + 102, 75, 63, + 254, 100, 0, + 228, 3, 127, + 17, 199, 174, + 210, 129, 139, + 91, 118, 124, + 32, 59, 106, + 180, 84, 255, + 226, 8, 210, + 0, 1, 20, + 93, 132, 68, + 166, 250, 255, + 97, 123, 201, + 98, 0, 122, + 126, 190, 58, + 0, 60, 183, + 255, 253, 0, + 7, 197, 226, + 180, 167, 57, + 148, 186, 138, + 204, 187, 160, + 55, 0, 49, + 0, 40, 1, + 150, 122, 129, + 39, 136, 38, + 206, 130, 180, + 150, 164, 196, + 180, 32, 128, + 110, 86, 180, + 147, 0, 185, + 199, 48, 61, + 115, 102, 255, + 15, 187, 253, + 172, 164, 100, + 182, 117, 250, + 216, 220, 254, + 87, 141, 113, + 216, 85, 34, + 0, 196, 103, + 243, 165, 105, + 216, 255, 182, + 1, 24, 219, + 52, 66, 54, + 255, 154, 0, + 87, 95, 1, + 198, 241, 79, + 255, 95, 133, + 123, 172, 240, + 120, 100, 49, + 162, 133, 204, + 105, 255, 220, + 198, 82, 100, + 121, 26, 64, + 0, 238, 70, + 231, 207, 69, + 217, 128, 233, + 255, 211, 209, + 209, 255, 141, + 36, 0, 3, + 87, 163, 193, + 211, 231, 201, + 203, 111, 79 , + 62, 24, 0, + 0, 117, 223, + 112, 176, 88 , + 209, 24, 0, + 0, 30, 107, + 105, 200, 197, + 255, 203, 255, + 233, 194, 137, + 191, 129, 46, + 69, 42, 145, + 171, 76, 194, + 14, 117, 61, + 0, 30, 25, + 118, 73, 127, + 255, 169, 200, + 94, 55, 217, + 238, 230, 138, + 159, 54, 33, + 80, 0, 148, + 189, 144, 128, + 0, 109, 126, + 88, 223, 96, + 71, 80, 103, + 1, 93, 159, + 99, 48, 60, + 2, 206, 148, + 139, 83, 37, + 171, 0, 255, + 141, 42, 135, + 85, 83, 148, + 150, 255, 0, + 0, 152, 123, + 255, 138, 203, + 222, 69, 200, + 107, 109, 230, + 30, 0, 68, + 173, 76, 138, + 255, 134, 161, + 0, 35, 60, + 138, 205, 0, + 111, 202, 157, + 225, 75, 253, + 255, 176, 77, + 229, 232, 57, + 114, 16, 255, + 111, 82, 101, + 134, 137, 48, + 99, 38, 80, + 105, 38, 32, + 200, 110, 0, + 209, 164, 255, + 198, 210, 86, + 79, 103, 77, + 174, 165, 166, + 170, 45, 101, + 199, 81, 175, + 255, 89, 172, + 146, 102, 78, + 102, 134, 184, + 111, 152, 255, + 92, 255, 159, + 172, 137, 178, + 210, 34, 98, + 199, 207, 147, + 255, 185, 30, + 250, 148, 141, + 49, 34, 78, + 254, 81, 97, + 254, 141, 100, + 68, 54, 23, + 201, 162, 84, + 199, 232, 240, + 68, 152, 0, + 147, 172, 58, + 22, 75, 28, + 8, 84, 121, + 116, 45, 0, + 104, 60, 255, + 64, 41, 38, + 164, 113, 215, + 207, 0, 155, + 118, 1, 35, + 83, 0, 88, + 0, 82, 232, + 43, 92, 87, + 160, 217, 146, + 176, 26, 229, + 29, 3, 36, + 122, 58, 159, + 214, 209, 207, + 160, 100, 105, + 106, 157, 160, + 153, 219, 113, + 192, 56, 207, + 125, 255, 89, + 149, 0, 34, + 213, 162, 223, + 22, 131, 204, + 166, 249, 69, + 109, 105, 97, + 86, 188, 78, + 255, 109, 81, + 255, 3, 248, + 255, 0, 73, + 202, 0, 35, + 67, 109, 18, + 234, 170, 173, + 191, 165, 0, + 38, 44, 51, + 85, 185, 2, + 121, 182, 158, + 254, 236, 212, + 139, 165, 89, + 141, 254, 193, + 0, 60, 43, + 63, 17, 40, + 255, 221, 246, + 17, 26, 146, + 154, 66, 84, + 149, 157, 238, + 126, 130, 72, + 58, 6, 101, + 189, 117, 101, +}; + +const size_t GLASBEY_LUT_SIZE = sizeof (GLASBEY_LUT) / sizeof (GLASBEY_LUT[0]); + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::io::PointCloudImageExtractorFromLabelField::extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const +{ + std::vector fields; + int field_idx = pcl::getFieldIndex (cloud, "label", fields); + if (field_idx == -1) + return (false); + const size_t offset = fields[field_idx].offset; + + switch (color_mode_) + { + case COLORS_MONO: + { + img.encoding = "mono16"; + img.width = cloud.width; + img.height = cloud.height; + img.step = img.width * sizeof (unsigned short); + img.data.resize (img.step * img.height); + unsigned short* data = reinterpret_cast(&img.data[0]); + for (size_t i = 0; i < cloud.points.size (); ++i) + { + uint32_t val; + pcl::getFieldValue (cloud.points[i], offset, val); + data[i] = static_cast(val); + } + break; + } + case COLORS_RGB_RANDOM: + { + img.encoding = "rgb8"; + img.width = cloud.width; + img.height = cloud.height; + img.step = img.width * sizeof (unsigned char) * 3; + img.data.resize (img.step * img.height); + + std::srand(std::time(0)); + std::map colormap; + + for (size_t i = 0; i < cloud.points.size (); ++i) + { + uint32_t val; + pcl::getFieldValue (cloud.points[i], offset, val); + if (colormap.count (val) == 0) + { + colormap[val] = i * 3; + img.data[i * 3 + 0] = static_cast ((std::rand () % 256)); + img.data[i * 3 + 1] = static_cast ((std::rand () % 256)); + img.data[i * 3 + 2] = static_cast ((std::rand () % 256)); + } + else + { + memcpy (&img.data[i * 3], &img.data[colormap[val]], 3); + } + } + break; + } + case COLORS_RGB_GLASBEY: + { + img.encoding = "rgb8"; + img.width = cloud.width; + img.height = cloud.height; + img.step = img.width * sizeof (unsigned char) * 3; + img.data.resize (img.step * img.height); + + std::srand(std::time(0)); + std::set labels; + std::map colormap; + + // First pass: find unique labels + for (size_t i = 0; i < cloud.points.size (); ++i) + { + uint32_t val; + pcl::getFieldValue (cloud.points[i], offset, val); + labels.insert (val); + } + + // Assign Glasbey colors in ascending order of labels + size_t color = 0; + for (std::set::iterator iter = labels.begin (); iter != labels.end (); ++iter) + { + colormap[*iter] = color % GLASBEY_LUT_SIZE; + ++color; + } + + // Second pass: copy colors from the LUT + for (size_t i = 0; i < cloud.points.size (); ++i) + { + uint32_t val; + pcl::getFieldValue (cloud.points[i], offset, val); + memcpy (&img.data[i * 3], &GLASBEY_LUT[colormap[val] * 3], 3); + } + + break; + } + } + + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::io::PointCloudImageExtractorWithScaling::extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const +{ + std::vector fields; + int field_idx = pcl::getFieldIndex (cloud, field_name_, fields); + if (field_idx == -1) + return (false); + const size_t offset = fields[field_idx].offset; + + img.encoding = "mono16"; + img.width = cloud.width; + img.height = cloud.height; + img.step = img.width * sizeof (unsigned short); + img.data.resize (img.step * img.height); + unsigned short* data = reinterpret_cast(&img.data[0]); + + float scaling_factor = scaling_factor_; + float data_min = 0.0f; + if (scaling_method_ == SCALING_FULL_RANGE) + { + float min = std::numeric_limits::infinity(); + float max = -std::numeric_limits::infinity(); + for (size_t i = 0; i < cloud.points.size (); ++i) + { + float val; + pcl::getFieldValue (cloud.points[i], offset, val); + if (val < min) + min = val; + if (val > max) + max = val; + } + scaling_factor = min == max ? 0 : std::numeric_limits::max() / (max - min); + data_min = min; + } + + for (size_t i = 0; i < cloud.points.size (); ++i) + { + float val; + pcl::getFieldValue (cloud.points[i], offset, val); + if (scaling_method_ == SCALING_NO) + { + data[i] = val; + } + else if (scaling_method_ == SCALING_FULL_RANGE) + { + data[i] = (val - data_min) * scaling_factor; + } + else if (scaling_method_ == SCALING_FIXED_FACTOR) + { + data[i] = val * scaling_factor; + } + } + + return (true); +} + +#endif // PCL_POINT_CLOUD_IMAGE_EXTRACTORS_IMPL_HPP_ + diff --git a/pcl-1.7/pcl/io/impl/synchronized_queue.hpp b/pcl-1.7/pcl/io/impl/synchronized_queue.hpp new file mode 100644 index 0000000..bb7c106 --- /dev/null +++ b/pcl-1.7/pcl/io/impl/synchronized_queue.hpp @@ -0,0 +1,134 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012 + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +/* SynchronizedQueue Template, taken from + * http://stackoverflow.com/questions/10139251/shared-queue-c + */ + +#ifndef SYNCHRONIZED_QUEUE_H_ +#define SYNCHRONIZED_QUEUE_H_ + +#include + +namespace pcl +{ + + template + class SynchronizedQueue + { + public: + + SynchronizedQueue () : + queue_(), mutex_(), cond_(), request_to_end_(false), enqueue_data_(true) { } + + void + enqueue (const T& data) + { + boost::unique_lock lock (mutex_); + + if (enqueue_data_) + { + queue_.push (data); + cond_.notify_one (); + } + } + + bool + dequeue (T& result) + { + boost::unique_lock lock (mutex_); + + while (queue_.empty () && (!request_to_end_)) + { + cond_.wait (lock); + } + + if (request_to_end_) + { + doEndActions (); + return false; + } + + result = queue_.front (); + queue_.pop (); + + return true; + } + + void + stopQueue () + { + boost::unique_lock lock (mutex_); + request_to_end_ = true; + cond_.notify_one (); + } + + unsigned int + size () + { + boost::unique_lock lock (mutex_); + return static_cast (queue_.size ()); + } + + bool + isEmpty () const + { + boost::unique_lock lock (mutex_); + return (queue_.empty ()); + } + + private: + void + doEndActions () + { + enqueue_data_ = false; + + while (!queue_.empty ()) + { + queue_.pop (); + } + } + + std::queue queue_; // Use STL queue to store data + mutable boost::mutex mutex_; // The mutex to synchronise on + boost::condition_variable cond_; // The condition to wait for + + bool request_to_end_; + bool enqueue_data_; + }; +} +#endif /* SYNCHRONIZED_QUEUE_H_ */ diff --git a/pcl-1.7/pcl/io/impl/vtk_lib_io.hpp b/pcl-1.7/pcl/io/impl/vtk_lib_io.hpp new file mode 100644 index 0000000..695e346 --- /dev/null +++ b/pcl-1.7/pcl/io/impl/vtk_lib_io.hpp @@ -0,0 +1,507 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: vtk_io.hpp 4968 2012-05-03 06:39:52Z doria $ + * + */ + +#ifndef PCL_IO_VTK_IO_IMPL_H_ +#define PCL_IO_VTK_IO_IMPL_H_ + +// PCL +#include +#include +#include +#include + +// VTK +// Ignore warnings in the above headers +#ifdef __GNUC__ +#pragma GCC system_header +#endif +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::io::vtkPolyDataToPointCloud (vtkPolyData* const polydata, pcl::PointCloud& cloud) +{ + // This generic template will convert any VTK PolyData + // to a coordinate-only PointXYZ PCL format. + cloud.width = polydata->GetNumberOfPoints (); + cloud.height = 1; // This indicates that the point cloud is unorganized + cloud.is_dense = false; + cloud.points.resize (cloud.width * cloud.height); + + // Get a list of all the fields available + std::vector fields; + pcl::for_each_type::type>(pcl::detail::FieldAdder(fields)); + + // Check if XYZ is present + int x_idx = -1, y_idx = -1, z_idx = -1; + for (size_t d = 0; d < fields.size (); ++d) + { + if (fields[d].name == "x") + x_idx = fields[d].offset; + else if (fields[d].name == "y") + y_idx = fields[d].offset; + else if (fields[d].name == "z") + z_idx = fields[d].offset; + } + // Set the coordinates of the pcl::PointCloud (if the pcl::PointCloud supports coordinates) + if (x_idx != -1 && y_idx != -1 && z_idx != -1) + { + for (size_t i = 0; i < cloud.points.size (); ++i) + { + double coordinate[3]; + polydata->GetPoint (i, coordinate); + pcl::setFieldValue (cloud.points[i], x_idx, coordinate[0]); + pcl::setFieldValue (cloud.points[i], y_idx, coordinate[1]); + pcl::setFieldValue (cloud.points[i], z_idx, coordinate[2]); + } + } + + // Check if Normals are present + int normal_x_idx = -1, normal_y_idx = -1, normal_z_idx = -1; + for (size_t d = 0; d < fields.size (); ++d) + { + if (fields[d].name == "normal_x") + normal_x_idx = fields[d].offset; + else if (fields[d].name == "normal_y") + normal_y_idx = fields[d].offset; + else if (fields[d].name == "normal_z") + normal_z_idx = fields[d].offset; + } + // Set the normals of the pcl::PointCloud (if the pcl::PointCloud supports normals and the input vtkPolyData has normals) + vtkFloatArray* normals = vtkFloatArray::SafeDownCast (polydata->GetPointData ()->GetNormals ()); + if (normal_x_idx != -1 && normal_y_idx != -1 && normal_z_idx != -1 && normals) + { + for (size_t i = 0; i < cloud.points.size (); ++i) + { + float normal[3]; + normals->GetTupleValue (i, normal); + pcl::setFieldValue (cloud.points[i], normal_x_idx, normal[0]); + pcl::setFieldValue (cloud.points[i], normal_y_idx, normal[1]); + pcl::setFieldValue (cloud.points[i], normal_z_idx, normal[2]); + } + } + + // Set the colors of the pcl::PointCloud (if the pcl::PointCloud supports colors and the input vtkPolyData has colors) + vtkUnsignedCharArray* colors = vtkUnsignedCharArray::SafeDownCast (polydata->GetPointData ()->GetScalars ()); + int rgb_idx = -1; + for (size_t d = 0; d < fields.size (); ++d) + { + if (fields[d].name == "rgb" || fields[d].name == "rgba") + { + rgb_idx = fields[d].offset; + break; + } + } + + if (rgb_idx != -1 && colors) + { + for (size_t i = 0; i < cloud.points.size (); ++i) + { + unsigned char color[3]; + colors->GetTupleValue (i, color); + pcl::RGB rgb; + rgb.r = color[0]; rgb.g = color[1]; rgb.b = color[2]; + pcl::setFieldValue (cloud.points[i], rgb_idx, rgb.rgba); + } + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::io::vtkStructuredGridToPointCloud (vtkStructuredGrid* const structured_grid, pcl::PointCloud& cloud) +{ + int dimensions[3]; + structured_grid->GetDimensions (dimensions); + cloud.width = dimensions[0]; + cloud.height = dimensions[1]; // This indicates that the point cloud is organized + cloud.is_dense = true; + cloud.points.resize (cloud.width * cloud.height); + + // Get a list of all the fields available + std::vector fields; + pcl::for_each_type::type>(pcl::detail::FieldAdder(fields)); + + // Check if XYZ is present + int x_idx = -1, y_idx = -1, z_idx = -1; + for (size_t d = 0; d < fields.size (); ++d) + { + if (fields[d].name == "x") + x_idx = fields[d].offset; + else if (fields[d].name == "y") + y_idx = fields[d].offset; + else if (fields[d].name == "z") + z_idx = fields[d].offset; + } + + if (x_idx != -1 && y_idx != -1 && z_idx != -1) + { + for (size_t i = 0; i < cloud.width; ++i) + { + for (size_t j = 0; j < cloud.height; ++j) + { + int queryPoint[3] = {i, j, 0}; + vtkIdType pointId = vtkStructuredData::ComputePointId (dimensions, queryPoint); + double coordinate[3]; + if (structured_grid->IsPointVisible (pointId)) + { + structured_grid->GetPoint (pointId, coordinate); + pcl::setFieldValue (cloud (i, j), x_idx, coordinate[0]); + pcl::setFieldValue (cloud (i, j), y_idx, coordinate[1]); + pcl::setFieldValue (cloud (i, j), z_idx, coordinate[2]); + } + else + { + // Fill the point with an "empty" point? + } + } + } + } + + // Check if Normals are present + int normal_x_idx = -1, normal_y_idx = -1, normal_z_idx = -1; + for (size_t d = 0; d < fields.size (); ++d) + { + if (fields[d].name == "normal_x") + normal_x_idx = fields[d].offset; + else if (fields[d].name == "normal_y") + normal_y_idx = fields[d].offset; + else if (fields[d].name == "normal_z") + normal_z_idx = fields[d].offset; + } + // Set the normals of the pcl::PointCloud (if the pcl::PointCloud supports normals and the input vtkStructuredGrid has normals) + vtkFloatArray* normals = vtkFloatArray::SafeDownCast (structured_grid->GetPointData ()->GetNormals ()); + + if (normal_x_idx != -1 && normal_y_idx != -1 && normal_z_idx != -1 && normals) + { + for (size_t i = 0; i < cloud.width; ++i) + { + for (size_t j = 0; j < cloud.height; ++j) + { + int queryPoint[3] = {i, j, 0}; + vtkIdType pointId = vtkStructuredData::ComputePointId (dimensions, queryPoint); + float normal[3]; + if (structured_grid->IsPointVisible (pointId)) + { + normals->GetTupleValue (i, normal); + pcl::setFieldValue (cloud (i, j), normal_x_idx, normal[0]); + pcl::setFieldValue (cloud (i, j), normal_y_idx, normal[1]); + pcl::setFieldValue (cloud (i, j), normal_z_idx, normal[2]); + } + else + { + // Fill the point with an "empty" point? + } + } + } + } + + // Set the colors of the pcl::PointCloud (if the pcl::PointCloud supports colors and the input vtkStructuredGrid has colors) + vtkUnsignedCharArray* colors = vtkUnsignedCharArray::SafeDownCast (structured_grid->GetPointData ()->GetArray ("Colors")); + int rgb_idx = -1; + for (size_t d = 0; d < fields.size (); ++d) + { + if (fields[d].name == "rgb" || fields[d].name == "rgba") + { + rgb_idx = fields[d].offset; + break; + } + } + + if (rgb_idx != -1 && colors) + { + for (size_t i = 0; i < cloud.width; ++i) + { + for (size_t j = 0; j < cloud.height; ++j) + { + int queryPoint[3] = {i, j, 0}; + vtkIdType pointId = vtkStructuredData::ComputePointId(dimensions, queryPoint); + unsigned char color[3]; + if (structured_grid->IsPointVisible (pointId)) + { + colors->GetTupleValue (i, color); + pcl::RGB rgb; + rgb.r = color[0]; rgb.g = color[1]; rgb.b = color[2]; + pcl::setFieldValue (cloud (i, j), rgb_idx, rgb.rgba); + } + else + { + // Fill the point with an "empty" point? + } + } + } + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::io::pointCloudTovtkPolyData (const pcl::PointCloud& cloud, vtkPolyData* const pdata) +{ + // Get a list of all the fields available + std::vector fields; + pcl::for_each_type::type>(pcl::detail::FieldAdder(fields)); + + // Coordinates (always must have coordinates) + vtkIdType nr_points = cloud.points.size (); + vtkSmartPointer points = vtkSmartPointer::New (); + points->SetNumberOfPoints (nr_points); + // Get a pointer to the beginning of the data array + float *data = (static_cast (points->GetData ()))->GetPointer (0); + + // Set the points + if (cloud.is_dense) + { + for (vtkIdType i = 0; i < nr_points; ++i) + memcpy (&data[i * 3], &cloud[i].x, 12); // sizeof (float) * 3 + } + else + { + vtkIdType j = 0; // true point index + for (vtkIdType i = 0; i < nr_points; ++i) + { + // Check if the point is invalid + if (!pcl_isfinite (cloud[i].x) || + !pcl_isfinite (cloud[i].y) || + !pcl_isfinite (cloud[i].z)) + continue; + + memcpy (&data[j * 3], &cloud[i].x, 12); // sizeof (float) * 3 + j++; + } + nr_points = j; + points->SetNumberOfPoints (nr_points); + } + + // Create a temporary PolyData and add the points to it + vtkSmartPointer temp_polydata = vtkSmartPointer::New (); + temp_polydata->SetPoints (points); + + // Check if Normals are present + int normal_x_idx = -1, normal_y_idx = -1, normal_z_idx = -1; + for (size_t d = 0; d < fields.size (); ++d) + { + if (fields[d].name == "normal_x") + normal_x_idx = fields[d].offset; + else if (fields[d].name == "normal_y") + normal_y_idx = fields[d].offset; + else if (fields[d].name == "normal_z") + normal_z_idx = fields[d].offset; + } + if (normal_x_idx != -1 && normal_y_idx != -1 && normal_z_idx != -1) + { + vtkSmartPointer normals = vtkSmartPointer::New (); + normals->SetNumberOfComponents (3); //3d normals (ie x,y,z) + normals->SetNumberOfTuples (cloud.size ()); + normals->SetName ("Normals"); + + for (size_t i = 0; i < cloud.size (); ++i) + { + float normal[3]; + pcl::getFieldValue (cloud[i], normal_x_idx, normal[0]); + pcl::getFieldValue (cloud[i], normal_y_idx, normal[1]); + pcl::getFieldValue (cloud[i], normal_z_idx, normal[2]); + normals->SetTupleValue (i, normal); + } + temp_polydata->GetPointData ()->SetNormals (normals); + } + + // Colors (optional) + int rgb_idx = -1; + for (size_t d = 0; d < fields.size (); ++d) + { + if (fields[d].name == "rgb" || fields[d].name == "rgba") + { + rgb_idx = fields[d].offset; + break; + } + } + if (rgb_idx != -1) + { + vtkSmartPointer colors = vtkSmartPointer::New (); + colors->SetNumberOfComponents (3); + colors->SetNumberOfTuples (cloud.size ()); + colors->SetName ("RGB"); + + for (size_t i = 0; i < cloud.size (); ++i) + { + unsigned char color[3]; + pcl::RGB rgb; + pcl::getFieldValue (cloud[i], rgb_idx, rgb.rgba); + color[0] = rgb.r; color[1] = rgb.g; color[2] = rgb.b; + colors->SetTupleValue (i, color); + } + temp_polydata->GetPointData ()->SetScalars (colors); + } + + // Add 0D topology to every point + vtkSmartPointer vertex_glyph_filter = vtkSmartPointer::New (); + #if VTK_MAJOR_VERSION < 6 + vertex_glyph_filter->AddInputConnection (temp_polydata->GetProducerPort ()); + #else + vertex_glyph_filter->SetInputData (temp_polydata); + #endif + vertex_glyph_filter->Update (); + + pdata->DeepCopy (vertex_glyph_filter->GetOutput ()); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::io::pointCloudTovtkStructuredGrid (const pcl::PointCloud& cloud, vtkStructuredGrid* const structured_grid) +{ + // Get a list of all the fields available + std::vector fields; + pcl::for_each_type::type>(pcl::detail::FieldAdder(fields)); + + int dimensions[3] = {cloud.width, cloud.height, 1}; + structured_grid->SetDimensions (dimensions); + + vtkSmartPointer points = vtkSmartPointer::New (); + points->SetNumberOfPoints (cloud.width * cloud.height); + + for (size_t i = 0; i < cloud.width; ++i) + { + for (size_t j = 0; j < cloud.height; ++j) + { + int queryPoint[3] = {i, j, 0}; + vtkIdType pointId = vtkStructuredData::ComputePointId (dimensions, queryPoint); + const PointT &point = cloud (i, j); + + if (pcl::isFinite (point)) + { + float p[3] = {point.x, point.y, point.z}; + points->SetPoint (pointId, p); + } + else + { + } + } + } + + structured_grid->SetPoints (points); + + // Check if Normals are present + int normal_x_idx = -1, normal_y_idx = -1, normal_z_idx = -1; + for (size_t d = 0; d < fields.size (); ++d) + { + if (fields[d].name == "normal_x") + normal_x_idx = fields[d].offset; + else if (fields[d].name == "normal_y") + normal_y_idx = fields[d].offset; + else if (fields[d].name == "normal_z") + normal_z_idx = fields[d].offset; + } + + if (normal_x_idx != -1 && normal_y_idx != -1 && normal_z_idx != -1) + { + vtkSmartPointer normals = vtkSmartPointer::New (); + normals->SetNumberOfComponents (3); // Note this must come before the SetNumberOfTuples calls + normals->SetNumberOfTuples (cloud.width * cloud.height); + normals->SetName ("Normals"); + for (size_t i = 0; i < cloud.width; ++i) + { + for (size_t j = 0; j < cloud.height; ++j) + { + int queryPoint[3] = {i, j, 0}; + vtkIdType pointId = vtkStructuredData::ComputePointId (dimensions, queryPoint); + const PointT &point = cloud (i, j); + + float normal[3]; + pcl::getFieldValue (point, normal_x_idx, normal[0]); + pcl::getFieldValue (point, normal_y_idx, normal[1]); + pcl::getFieldValue (point, normal_z_idx, normal[2]); + normals->SetTupleValue (pointId, normal); + } + } + + structured_grid->GetPointData ()->SetNormals (normals); + } + + // Colors (optional) + int rgb_idx = -1; + for (size_t d = 0; d < fields.size (); ++d) + { + if (fields[d].name == "rgb" || fields[d].name == "rgba") + { + rgb_idx = fields[d].offset; + break; + } + } + + if (rgb_idx != -1) + { + vtkSmartPointer colors = vtkSmartPointer::New(); + colors->SetNumberOfComponents (3); // Note this must come before the SetNumberOfTuples calls + colors->SetNumberOfTuples (cloud.width * cloud.height); + colors->SetName ("Colors"); + for (size_t i = 0; i < cloud.width; ++i) + { + for (size_t j = 0; j < cloud.height; ++j) + { + int queryPoint[3] = {i, j, 0}; + vtkIdType pointId = vtkStructuredData::ComputePointId (dimensions, queryPoint); + const PointT &point = cloud (i, j); + + if (pcl::isFinite (point)) + { + + unsigned char color[3]; + pcl::RGB rgb; + pcl::getFieldValue (cloud[i], rgb_idx, rgb.rgba); + color[0] = rgb.r; color[1] = rgb.g; color[2] = rgb.b; + colors->SetTupleValue (pointId, color); + } + else + { + } + } + } + structured_grid->GetPointData ()->AddArray (colors); + } +} + +#endif //#ifndef PCL_IO_VTK_IO_H_ + diff --git a/pcl-1.7/pcl/io/io.h b/pcl-1.7/pcl/io/io.h new file mode 100644 index 0000000..25923d0 --- /dev/null +++ b/pcl-1.7/pcl/io/io.h @@ -0,0 +1,46 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_IO_IO_H_ +#define PCL_IO_IO_H_ + +#include + +#endif //#ifndef PCL_IO_IO_H_ + diff --git a/pcl-1.7/pcl/io/io_exception.h b/pcl-1.7/pcl/io/io_exception.h new file mode 100644 index 0000000..0586cf4 --- /dev/null +++ b/pcl-1.7/pcl/io/io_exception.h @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +#ifndef PCL_IO_EXCEPTION_H_ +#define PCL_IO_EXCEPTION_H_ + +#include +#include +#include +#include + + +//fom +#if defined _WIN32 && defined _MSC_VER && !defined __PRETTY_FUNCTION__ + #define __PRETTY_FUNCTION__ __FUNCTION__ +#endif + + +#define THROW_IO_EXCEPTION(format,...) throwIOException( __PRETTY_FUNCTION__, __FILE__, __LINE__, format , ##__VA_ARGS__ ) + + +namespace pcl +{ + namespace io + { + /** + * @brief General IO exception class + */ + class IOException : public std::exception + { + public: + IOException (const std::string& function_name, + const std::string& file_name, + unsigned line_number, + const std::string& message); + + virtual ~IOException () throw (); + + IOException& + operator= (const IOException& exception); + + virtual const char* + what () const throw (); + + const std::string& + getFunctionName () const; + + const std::string& + getFileName () const; + + unsigned + getLineNumber () const; + + protected: + std::string function_name_; + std::string file_name_; + unsigned line_number_; + std::string message_; + std::string message_long_; + }; + + inline void + throwIOException (const char* function, const char* file, unsigned line, const char* format, ...) + { + static char msg[1024]; + va_list args; + va_start (args, format); + vsnprintf (msg, 1024, format, args); + throw IOException (function, file, line, msg); + } + } // namespace +} +#endif // PCL_IO_EXCEPTION_H_ diff --git a/pcl-1.7/pcl/io/lzf.h b/pcl-1.7/pcl/io/lzf.h new file mode 100644 index 0000000..86c1c11 --- /dev/null +++ b/pcl-1.7/pcl/io/lzf.h @@ -0,0 +1,92 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2000-2008 Marc Alexander Lehmann + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_IO_LZF_H +#define PCL_IO_LZF_H + +#include + +namespace pcl +{ + /** \brief Compress in_len bytes stored at the memory block starting at + * \a in_data and write the result to \a out_data, up to a maximum length + * of \a out_len bytes using Marc Lehmann's LZF algorithm. + * + * If the output buffer is not large enough or any error occurs return 0, + * otherwise return the number of bytes used, which might be considerably + * more than in_len (but less than 104% of the original size), so it + * makes sense to always use out_len == in_len - 1), to ensure _some_ + * compression, and store the data uncompressed otherwise (with a flag, of + * course. + * + * \note The buffers must not be overlapping. + * + * \param[in] in_data the input uncompressed buffer + * \param[in] in_len the length of the input buffer + * \param[out] out_data the output buffer where the compressed result will be stored + * \param[out] out_len the length of the output buffer + * + */ + PCL_EXPORTS unsigned int + lzfCompress (const void *const in_data, unsigned int in_len, + void *out_data, unsigned int out_len); + + /** \brief Decompress data compressed with the \a lzfCompress function and + * stored at location \a in_data and length \a in_len. The result will be + * stored at \a out_data up to a maximum of \a out_len characters. + * + * If the output buffer is not large enough to hold the decompressed + * data, a 0 is returned and errno is set to E2BIG. Otherwise the number + * of decompressed bytes (i.e. the original length of the data) is + * returned. + * + * If an error in the compressed data is detected, a zero is returned and + * errno is set to EINVAL. + * + * This function is very fast, about as fast as a copying loop. + * \param[in] in_data the input compressed buffer + * \param[in] in_len the length of the input buffer + * \param[out] out_data the output buffer (must be resized to \a out_len) + * \param[out] out_len the length of the output buffer + */ + PCL_EXPORTS unsigned int + lzfDecompress (const void *const in_data, unsigned int in_len, + void *out_data, unsigned int out_len); +} + +#endif /* PCL_IO_LZF */ + diff --git a/pcl-1.7/pcl/io/lzf_image_io.h b/pcl-1.7/pcl/io/lzf_image_io.h new file mode 100644 index 0000000..bdee437 --- /dev/null +++ b/pcl-1.7/pcl/io/lzf_image_io.h @@ -0,0 +1,636 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_LZF_IMAGE_IO_H_ +#define PCL_LZF_IMAGE_IO_H_ + +#include +#include +#include + +namespace pcl +{ + namespace io + { + /** \brief Basic camera parameters placeholder. */ + struct CameraParameters + { + /** fx */ + double focal_length_x; + /** fy */ + double focal_length_y; + /** cx */ + double principal_point_x; + /** cy */ + double principal_point_y; + }; + + /** \brief PCL-LZF image format reader. + * The PCL-LZF image format is nothing else but a LZF-modified compression over + * an existing file type (e.g., PNG). However, in certain situations, like RGB data for + * example, an [RGBRGB...RGB] array will be first reordered into [RR...RGG...GBB...B] + * in order to ensure better compression. + * + * The current list of compressors/decompressors include: + * * LZF compressed 24-bit [RR...RGG...GBB...B] data + * * LZF compressed 8-bit Bayer data + * * LZF compressed 16-bit YUV422 data + * * LZF compressed 16-bit depth data + * + * Please note that files found using the above mentioned extensions will be treated + * as such. Inherit from this class and overwrite the I/O methods if you plan to change + * this behavior. + * + * The main advantage of using the PCL-LZF image I/O routines is a very good file size + * versus I/O speed ratio. Tests performed using LZF, Snappy, ZIP, GZ2, BZIP2, as well + * as PNG, JPEG, and TIFF compression have shown that the internal PCL LZF methods + * provide the best score for the types of applications PCL is suited for. + * + * \author Radu B. Rusu + * \ingroup io + */ + class PCL_EXPORTS LZFImageReader + { + public: + /** Empty constructor */ + LZFImageReader (); + /** Empty destructor */ + virtual ~LZFImageReader () {} + + /** \brief Read camera parameters from a given file and store them internally. + * \return true if operation successful, false otherwise + */ + bool + readParameters (const std::string &filename); + + /** \brief Read the parameters from a struct instead + * \param[in] parameters Camera parameters to use */ + inline void + setParameters (const CameraParameters ¶meters) + { + parameters_ = parameters; + } + + /** \brief Get the camera parameters currently being used + * returns a CameraParameters struct */ + inline CameraParameters + getParameters () const + { + return parameters_; + } + + /** \brief Get the image width as read from disk. */ + inline uint32_t + getWidth () const + { + return (width_); + } + + /** \brief Get the image height as read from disk. */ + inline uint32_t + getHeight () const + { + return (height_); + } + + /** \brief Get the type of the image read from disk. */ + inline std::string + getImageType () const + { + return (image_type_identifier_); + } + + protected: + /** \brief Read camera parameters from a given stream and store them internally. + * \return true if operation successful, false otherwise + */ + virtual bool + readParameters (std::istream&) { return (false); } + + /** \brief Load a compressed image array from disk + * \param[in] filename the file name to load the data from + * \param[out] data the size of the data + * \param uncompressed_size + * \return an array filled with the data loaded from disk, NULL if error + */ + bool + loadImageBlob (const std::string &filename, + std::vector &data, + uint32_t &uncompressed_size); + + /** \brief Realtime LZF decompression. + * \param[in] input the array to decompress + * \param[out] output the decompressed array + * \return true if operation successful, false otherwise + */ + bool + decompress (const std::vector &input, + std::vector &output); + + /** \brief The image width, as read from the file. */ + uint32_t width_; + + /** \brief The image height, as read from the file. */ + uint32_t height_; + + /** \brief The image type string, as read from the file. */ + std::string image_type_identifier_; + + /** \brief Internal set of camera parameters. */ + CameraParameters parameters_; + }; + + /** \brief PCL-LZF 16-bit depth image format reader. + * + * The main advantage of using the PCL-LZF image I/O routines is a very good file size + * versus I/O speed ratio. Tests performed using LZF, Snappy, ZIP, GZ2, BZIP2, as well + * as PNG, JPEG, and TIFF compression have shown that the internal PCL LZF methods + * provide the best score for the types of applications PCL is suited for. + * + * \author Radu B. Rusu + * \ingroup io + */ + class PCL_EXPORTS LZFDepth16ImageReader : public LZFImageReader + { + public: + using LZFImageReader::readParameters; + + /** Empty constructor */ + LZFDepth16ImageReader () + : LZFImageReader () + , z_multiplication_factor_ (0.001) // Set default multiplication factor + {} + + /** Empty destructor */ + virtual ~LZFDepth16ImageReader () {} + + /** \brief Read the data stored in a PCLZF depth file and convert it to a pcl::PointCloud type. + * \param[in] filename the file name to read the data from + * \param[out] cloud the resultant output point cloud + */ + template bool + read (const std::string &filename, pcl::PointCloud &cloud); + + /** \brief Read the data stored in a PCLZF depth file and convert it to a pcl::PointCloud type. + * \param[in] filename the file name to read the data from + * \param[in] num_threads The number of threads to use. 0 indicates OpenMP is free to choose. + * \param[out] cloud the resultant output point cloud + */ + template bool + readOMP (const std::string &filename, pcl::PointCloud &cloud, + unsigned int num_threads=0); + + /** \brief Read camera parameters from a given stream and store them internally. + * The parameters will be read from the \ ... \ tag. + * \return true if operation successful, false otherwise + */ + virtual bool + readParameters (std::istream& is); + + protected: + /** \brief Z-value depth multiplication factor + * (i.e., if raw data is in [mm] and we want [m], we need to multiply with 0.001) + */ + double z_multiplication_factor_; + }; + + /** \brief PCL-LZF 24-bit RGB image format reader. + * + * The main advantage of using the PCL-LZF image I/O routines is a very good file size + * versus I/O speed ratio. Tests performed using LZF, Snappy, ZIP, GZ2, BZIP2, as well + * as PNG, JPEG, and TIFF compression have shown that the internal PCL LZF methods + * provide the best score for the types of applications PCL is suited for. + * + * \author Radu B. Rusu + * \ingroup io + */ + class PCL_EXPORTS LZFRGB24ImageReader : public LZFImageReader + { + public: + using LZFImageReader::readParameters; + + /** Empty constructor */ + LZFRGB24ImageReader () : LZFImageReader () {} + /** Empty destructor */ + virtual ~LZFRGB24ImageReader () {} + + /** \brief Read the data stored in a PCLZF RGB file and convert it to a pcl::PointCloud type. + * \param[in] filename the file name to read the data from + * \param[out] cloud the resultant output point cloud + */ + template bool + read (const std::string &filename, pcl::PointCloud &cloud); + + /** \brief Read the data stored in a PCLZF RGB file and convert it to a pcl::PointCloud type. + * Note that, unless massively multithreaded, this will likely not result in a significant speedup and may even slow performance. + * \param[in] filename the file name to read the data from + * \param[in] num_threads The number of threads to use + * \param[out] cloud the resultant output point cloud + */ + template bool + readOMP (const std::string &filename, pcl::PointCloud &cloud, + unsigned int num_threads=0); + + /** \brief Read camera parameters from a given stream and store them internally. + * The parameters will be read from the \ ... \ tag. + * \return true if operation successful, false otherwise + */ + virtual bool + readParameters (std::istream& is); + + protected: + }; + + /** \brief PCL-LZF 8-bit Bayer image format reader. + * + * The main advantage of using the PCL-LZF image I/O routines is a very good file size + * versus I/O speed ratio. Tests performed using LZF, Snappy, ZIP, GZ2, BZIP2, as well + * as PNG, JPEG, and TIFF compression have shown that the internal PCL LZF methods + * provide the best score for the types of applications PCL is suited for. + * + * \author Radu B. Rusu + * \ingroup io + */ + class PCL_EXPORTS LZFYUV422ImageReader : public LZFRGB24ImageReader + { + public: + using LZFRGB24ImageReader::readParameters; + + /** Empty constructor */ + LZFYUV422ImageReader () : LZFRGB24ImageReader () {} + /** Empty destructor */ + ~LZFYUV422ImageReader () {} + + /** \brief Read the data stored in a PCLZF YUV422 16bit file and convert it to a pcl::PointCloud type. + * \param[in] filename the file name to read the data from + * \param[out] cloud the resultant output point cloud + */ + template bool + read (const std::string &filename, pcl::PointCloud &cloud); + + /** \brief Read the data stored in a PCLZF YUV422 file and convert it to a pcl::PointCloud type. + * Note that, unless massively multithreaded, this will likely not result in a significant speedup + * \param[in] filename the file name to read the data from + * \param[in] num_threads The number of threads to use + * \param[out] cloud the resultant output point cloud + */ + template bool + readOMP (const std::string &filename, pcl::PointCloud &cloud, + unsigned int num_threads=0); + }; + + /** \brief PCL-LZF 8-bit Bayer image format reader. + * + * The main advantage of using the PCL-LZF image I/O routines is a very good file size + * versus I/O speed ratio. Tests performed using LZF, Snappy, ZIP, GZ2, BZIP2, as well + * as PNG, JPEG, and TIFF compression have shown that the internal PCL LZF methods + * provide the best score for the types of applications PCL is suited for. + * + * \author Radu B. Rusu + * \ingroup io + */ + class PCL_EXPORTS LZFBayer8ImageReader : public LZFRGB24ImageReader + { + public: + using LZFRGB24ImageReader::readParameters; + + /** Empty constructor */ + LZFBayer8ImageReader () : LZFRGB24ImageReader () {} + /** Empty destructor */ + ~LZFBayer8ImageReader () {} + + /** \brief Read the data stored in a PCLZF Bayer 8bit file and convert it to a pcl::PointCloud type. + * \param[in] filename the file name to read the data from + * \param[out] cloud the resultant output point cloud + */ + template bool + read (const std::string &filename, pcl::PointCloud &cloud); + + /** \brief Read the data stored in a PCLZF Bayer 8bit file and convert it to a pcl::PointCloud type. + * Note that, unless massively multithreaded, this will likely not result in a significant speedup and may even slow performance. + * \param[in] filename the file name to read the data from + * \param[in] num_threads The number of threads to use + * \param[out] cloud the resultant output point cloud + */ + template bool + readOMP (const std::string &filename, pcl::PointCloud &cloud, + unsigned int num_threads=0); + }; + + /** \brief PCL-LZF image format writer. + * The PCL-LZF image format is nothing else but a LZF-modified compression over + * an existing file type (e.g., PNG). However, in certain situations, like RGB data for + * example, an [RGBRGB...RGB] array will be first reordered into [RR...RGG...GBB...B] + * in order to ensure better compression. + * + * The current list of compressors/decompressors include: + * * LZF compressed 24-bit [RR...RGG...GBB...B] data + * * LZF compressed 8-bit Bayer data + * * LZF compressed 16-bit YUV422 data + * * LZF compressed 16-bit depth data + * + * Please note that files found using the above mentioned extensions will be treated + * as such. Inherit from this class and overwrite the I/O methods if you plan to change + * this behavior. + * + * The main advantage of using the PCL-LZF image I/O routines is a very good file size + * versus I/O speed ratio. Tests performed using LZF, Snappy, ZIP, GZ2, BZIP2, as well + * as PNG, JPEG, and TIFF compression have shown that the internal PCL LZF methods + * provide the best score for the types of applications PCL is suited for. + * + * \author Radu B. Rusu + * \ingroup io + */ + class PCL_EXPORTS LZFImageWriter + { + public: + /** Empty constructor */ + LZFImageWriter () {} + /** Empty destructor */ + virtual ~LZFImageWriter () {} + + /** \brief Save an image into PCL-LZF format. Virtual. + * \param[in] data the array holding the image + * \param[in] width the with of the data array + * \param[in] height the height of the data array + * \param[in] filename the file name to write + * \return true if operation successful, false otherwise + */ + virtual bool + write (const char* data, + uint32_t width, uint32_t height, + const std::string &filename) = 0; + + /** \brief Write camera parameters to disk. Virtual. + * \param[in] parameters the camera parameters + * \param[in] filename the file name to write + * \return true if operation successful, false otherwise + */ + virtual bool + writeParameters (const CameraParameters ¶meters, + const std::string &filename) = 0; + + /** \brief Save an image and its camera parameters into PCL-LZF format. + * \param[in] data the array holding the image + * \param[in] width the with of the data array + * \param[in] height the height of the data array + * \param[in] parameters the camera parameters + * \param[in] filename_data the file name to write the data to + * \param[in] filename_xml the file name to write the parameters to + * \return true if operation successful, false otherwise + */ + virtual bool + write (const char* data, + uint32_t width, uint32_t height, + const CameraParameters ¶meters, + const std::string &filename_data, + const std::string &filename_xml) + { + bool res1 = write (data, width, height, filename_data); + bool res2 = writeParameters (parameters, filename_xml); + return (res1 && res2); + } + + /** \brief Write a single image/camera parameter to file, given an XML tag + * \param[in] parameter the value of the parameter to write + * \param[in] tag the value of the XML tag + * \param[in] filename the file name to write + * \return true if operation successful, false otherwise + * Example: + * \code + * pcl::io::LZFDepthImageWriter w; + * w.writeParameter (0.001, "depth.multiplication_factor", "parameters.xml"); + * \endcode + */ + bool + writeParameter (const double ¶meter, const std::string &tag, + const std::string &filename); + protected: + /** \brief Save a compressed image array to disk + * \param[in] data the data to save + * \param[in] data_size the size of the data + * \param[in] filename the file name to write the data to + * \return true if operation successful, false otherwise + */ + bool + saveImageBlob (const char* data, size_t data_size, + const std::string &filename); + + /** \brief Realtime LZF compression. + * \param[in] input the array to compress + * \param[in] input_size the size of the array to compress + * \param[in] width the with of the data array + * \param[in] height the height of the data array + * \param[in] image_type the type of the image to save. This should be an up to + * 16 characters string describing the data type. Examples are: "bayer8", "rgb24", + * "yuv422", "depth16". + * \param[out] output the compressed output array (must be pre-allocated!) + * \return the number of bytes in the output array + */ + uint32_t + compress (const char* input, uint32_t input_size, + uint32_t width, uint32_t height, + const std::string &image_type, + char *output); + }; + + /** \brief PCL-LZF 16-bit depth image format writer. + * + * The main advantage of using the PCL-LZF image I/O routines is a very good file size + * versus I/O speed ratio. Tests performed using LZF, Snappy, ZIP, GZ2, BZIP2, as well + * as PNG, JPEG, and TIFF compression have shown that the internal PCL LZF methods + * provide the best score for the types of applications PCL is suited for. + * + * \author Radu B. Rusu + * \ingroup io + */ + class PCL_EXPORTS LZFDepth16ImageWriter : public LZFImageWriter + { + public: + /** Empty constructor */ + LZFDepth16ImageWriter () + : LZFImageWriter () + , z_multiplication_factor_ (0.001) // Set default multiplication factor + {} + + /** Empty destructor */ + virtual ~LZFDepth16ImageWriter () {} + + /** \brief Save a 16-bit depth image into PCL-LZF format. + * \param[in] data the array holding the depth image + * \param[in] width the with of the data array + * \param[in] height the height of the data array + * \param[in] filename the file name to write (preferred extension: .pclzf) + * \return true if operation successful, false otherwise + */ + virtual bool + write (const char* data, + uint32_t width, uint32_t height, + const std::string &filename); + + /** \brief Write camera parameters to disk. + * \param[in] parameters the camera parameters + * \param[in] filename the file name to write + * \return true if operation successful, false otherwise + * This overwrites the following parameters in the xml file, under the + * \ tag: + * \...\ + * \...\ + * \...\ + * \...\ + * \...\ + */ + virtual bool + writeParameters (const CameraParameters ¶meters, + const std::string &filename); + + protected: + /** \brief Z-value depth multiplication factor + * (i.e., if raw data is in [mm] and we want [m], we need to multiply with 0.001) + */ + double z_multiplication_factor_; + }; + + /** \brief PCL-LZF 24-bit RGB image format writer. + * + * The main advantage of using the PCL-LZF image I/O routines is a very good file size + * versus I/O speed ratio. Tests performed using LZF, Snappy, ZIP, GZ2, BZIP2, as well + * as PNG, JPEG, and TIFF compression have shown that the internal PCL LZF methods + * provide the best score for the types of applications PCL is suited for. + * + * \author Radu B. Rusu + * \ingroup io + */ + class PCL_EXPORTS LZFRGB24ImageWriter : public LZFImageWriter + { + public: + /** Empty constructor */ + LZFRGB24ImageWriter () : LZFImageWriter () {} + /** Empty destructor */ + virtual ~LZFRGB24ImageWriter () {} + + /** \brief Save a 24-bit RGB image into PCL-LZF format. + * \param[in] data the array holding the RGB image (as [RGB..RGB] or [BGR..BGR]) + * \param[in] width the with of the data array + * \param[in] height the height of the data array + * \param[in] filename the file name to write (preferred extension: .pclzf) + * \return true if operation successful, false otherwise + */ + virtual bool + write (const char *data, + uint32_t width, uint32_t height, + const std::string &filename); + + /** \brief Write camera parameters to disk. + * \param[in] parameters the camera parameters + * \param[in] filename the file name to write + * \return true if operation successful, false otherwise + */ + virtual bool + writeParameters (const CameraParameters ¶meters, + const std::string &filename); + + protected: + }; + + /** \brief PCL-LZF 16-bit YUV422 image format writer. + * + * The main advantage of using the PCL-LZF image I/O routines is a very good file size + * versus I/O speed ratio. Tests performed using LZF, Snappy, ZIP, GZ2, BZIP2, as well + * as PNG, JPEG, and TIFF compression have shown that the internal PCL LZF methods + * provide the best score for the types of applications PCL is suited for. + * + * \author Radu B. Rusu + * \ingroup io + */ + class PCL_EXPORTS LZFYUV422ImageWriter : public LZFRGB24ImageWriter + { + public: + /** Empty constructor */ + LZFYUV422ImageWriter () : LZFRGB24ImageWriter () {} + /** Empty destructor */ + virtual ~LZFYUV422ImageWriter () {} + + /** \brief Save a 16-bit YUV422 image into PCL-LZF format. + * \param[in] data the array holding the YUV422 image (as [YUYV...YUYV]) + * \param[in] width the with of the data array + * \param[in] height the height of the data array + * \param[in] filename the file name to write (preferred extension: .pclzf) + * \return true if operation successful, false otherwise + */ + virtual bool + write (const char *data, + uint32_t width, uint32_t height, + const std::string &filename); + }; + + /** \brief PCL-LZF 8-bit Bayer image format writer. + * + * The main advantage of using the PCL-LZF image I/O routines is a very good file size + * versus I/O speed ratio. Tests performed using LZF, Snappy, ZIP, GZ2, BZIP2, as well + * as PNG, JPEG, and TIFF compression have shown that the internal PCL LZF methods + * provide the best score for the types of applications PCL is suited for. + * + * \author Radu B. Rusu + * \ingroup io + */ + class PCL_EXPORTS LZFBayer8ImageWriter : public LZFRGB24ImageWriter + { + public: + /** Empty constructor */ + LZFBayer8ImageWriter () : LZFRGB24ImageWriter () {} + /** Empty destructor */ + virtual ~LZFBayer8ImageWriter () {} + + /** \brief Save a 8-bit Bayer image into PCL-LZF format. + * \param[in] data the array holding the 8-bit Bayer array + * \param[in] width the with of the data array + * \param[in] height the height of the data array + * \param[in] filename the file name to write (preferred extension: .pclzf) + * \return true if operation successful, false otherwise + */ + virtual bool + write (const char *data, + uint32_t width, uint32_t height, + const std::string &filename); + }; + } +} + +#include + +#endif //#ifndef PCL_LZF_IMAGE_IO_H_ diff --git a/pcl-1.7/pcl/io/obj_io.h b/pcl-1.7/pcl/io/obj_io.h new file mode 100644 index 0000000..29c371c --- /dev/null +++ b/pcl-1.7/pcl/io/obj_io.h @@ -0,0 +1,347 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2013, Open Perception, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef OBJ_IO_H_ +#define OBJ_IO_H_ +#include +#include +#include +#include + +namespace pcl +{ + class PCL_EXPORTS MTLReader + { + public: + /** \brief empty constructor */ + MTLReader (); + + /** \brief empty destructor */ + virtual ~MTLReader() {} + + /** \brief Read a MTL file given its full path. + * \param[in] filename full path to MTL file + * \return 0 on success < 0 else. + */ + int + read (const std::string& filename); + + /** \brief Read a MTL file given an OBJ file full path and the MTL file name. + * \param[in] obj_file_name full path to OBJ file + * \param[in] mtl_file_name MTL file name + * \return 0 on success < 0 else. + */ + int + read (const std::string& obj_file_name, const std::string& mtl_file_name); + + std::vector::const_iterator + getMaterial (const std::string& material_name) const; + + /// materials array + std::vector materials_; + + private: + /// converts CIE XYZ to RGB + inline void + cie2rgb (const Eigen::Vector3f& xyz, pcl::TexMaterial::RGB& rgb) const; + /// fill a pcl::TexMaterial::RGB from a split line containing CIE x y z values + int + fillRGBfromXYZ (const std::vector& split_line, pcl::TexMaterial::RGB& rgb); + /// fill a pcl::TexMaterial::RGB from a split line containing r g b values + int + fillRGBfromRGB (const std::vector& split_line, pcl::TexMaterial::RGB& rgb); + /// matrix to convert CIE to RGB + Eigen::Matrix3f xyz_to_rgb_matrix_; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + class PCL_EXPORTS OBJReader : public FileReader + { + public: + /** \brief empty constructor */ + OBJReader() {} + /** \brief empty destructor */ + virtual ~OBJReader() {} + /** \brief Read a point cloud data header from a FILE file. + * + * Load only the meta information (number of points, their types, etc), + * and not the points themselves, from a given FILE file. Useful for fast + * evaluation of the underlying data structure. + * + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * \param[out] origin the sensor acquisition origin always null + * \param[out] orientation the sensor acquisition orientation always identity + * \param[out] file_version always 0 + * \param data_type + * \param data_idx + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + * + * \return 0 on success. + */ + int + readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, + int &file_version, int &data_type, unsigned int &data_idx, + const int offset); + + /** \brief Read a point cloud data from a FILE file and store it into a + * pcl/PCLPointCloud2. + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * \param[out] origin the sensor acquisition origin always null + * \param[out] orientation the sensor acquisition orientation always identity + * \param[out] file_version always 0 + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + * + * \return 0 on success. + */ + int + read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, + int &file_version, const int offset = 0); + + + /** \brief Read a point cloud data from a FILE file and store it into a + * pcl/PCLPointCloud2. + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + * + * \return 0 on success. + */ + int + read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, const int offset = 0); + + /** \brief Read a point cloud data from a FILE file and store it into a + * pcl/TextureMesh. + * \param[in] file_name the name of the file containing data + * \param[out] mesh the resultant TextureMesh read from disk + * \param[out] origin the sensor origin always null + * \param[out] orientation the sensor orientation always identity + * \param[out] file_version always 0 + * \param[in] offset the offset in the file where to expect the true + * header to begin. + * + * \return 0 on success. + */ + int + read (const std::string &file_name, pcl::TextureMesh &mesh, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, + int &file_version, const int offset = 0); + + /** \brief Read a point cloud data from a FILE file and store it into a + * pcl/TextureMesh. + * \param[in] file_name the name of the file containing data + * \param[out] mesh the resultant TextureMesh read from disk + * \param[in] offset the offset in the file where to expect the true + * header to begin. + * + * \return 0 on success. + */ + int + read (const std::string &file_name, pcl::TextureMesh &mesh, const int offset = 0); + + /** \brief Read a point cloud data from a FILE file and store it into a + * pcl/PolygonMesh. + * \param[in] file_name the name of the file containing data + * \param[out] mesh the resultant PolygonMesh read from disk + * \param[out] origin the sensor origin always null + * \param[out] orientation the sensor orientation always identity + * \param[out] file_version always 0 + * \param[in] offset the offset in the file where to expect the true + * header to begin. + * + * \return 0 on success. + */ + int + read (const std::string &file_name, pcl::PolygonMesh &mesh, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, + int &file_version, const int offset = 0); + + /** \brief Read a point cloud data from a FILE file and store it into a + * pcl/PolygonMesh. + * \param[in] file_name the name of the file containing data + * \param[out] mesh the resultant PolygonMesh read from disk + * \param[in] offset the offset in the file where to expect the true + * header to begin. + * + * \return 0 on success. + */ + int + read (const std::string &file_name, pcl::PolygonMesh &mesh, const int offset = 0); + + /** \brief Read a point cloud data from any FILE file, and convert it to the given + * template format. + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + */ + template inline int + read (const std::string &file_name, pcl::PointCloud &cloud, + const int offset =0) + { + pcl::PCLPointCloud2 blob; + int file_version; + int res = read (file_name, blob, cloud.sensor_origin_, cloud.sensor_orientation_, + file_version, offset); + if (res < 0) + return (res); + + pcl::fromPCLPointCloud2 (blob, cloud); + return (0); + } + + private: + /// Usually OBJ files come MTL files where texture materials are stored + std::vector companions_; + }; + + namespace io + { + /** \brief Load any OBJ file into a templated PointCloud type. + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant templated point cloud + * \param[out] origin the sensor acquisition origin, null + * \param[out] orientation the sensor acquisition orientation, identity + * \ingroup io + */ + inline int + loadOBJFile (const std::string &file_name, pcl::PCLPointCloud2 &cloud, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation) + { + pcl::OBJReader p; + int obj_version; + return (p.read (file_name, cloud, origin, orientation, obj_version)); + } + + /** \brief Load an OBJ file into a PCLPointCloud2 blob type. + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant templated point cloud + * \return 0 on success < 0 on error + * + * \ingroup io + */ + inline int + loadOBJFile (const std::string &file_name, pcl::PCLPointCloud2 &cloud) + { + pcl::OBJReader p; + return (p.read (file_name, cloud)); + } + + /** \brief Load any OBJ file into a templated PointCloud type + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant templated point cloud + * \ingroup io + */ + template inline int + loadOBJFile (const std::string &file_name, pcl::PointCloud &cloud) + { + pcl::OBJReader p; + return (p.read (file_name, cloud)); + } + + /** \brief Load any OBJ file into a PolygonMesh type. + * \param[in] file_name the name of the file to load + * \param[out] mesh the resultant mesh + * \return 0 on success < 0 on error + * + * \ingroup io + */ + inline int + loadOBJFile (const std::string &file_name, pcl::PolygonMesh &mesh) + { + pcl::OBJReader p; + return (p.read (file_name, mesh)); + } + + /** \brief Load any OBJ file into a TextureMesh type. + * \param[in] file_name the name of the file to load + * \param[out] mesh the resultant mesh + * \return 0 on success < 0 on error + * + * \ingroup io + */ + inline int + loadOBJFile (const std::string &file_name, pcl::TextureMesh &mesh) + { + pcl::OBJReader p; + return (p.read (file_name, mesh)); + } + + /** \brief Saves a TextureMesh in ascii OBJ format. + * \param[in] file_name the name of the file to write to disk + * \param[in] tex_mesh the texture mesh to save + * \param[in] precision the output ASCII precision + * \ingroup io + */ + PCL_EXPORTS int + saveOBJFile (const std::string &file_name, + const pcl::TextureMesh &tex_mesh, + unsigned precision = 5); + + /** \brief Saves a PolygonMesh in ascii PLY format. + * \param[in] file_name the name of the file to write to disk + * \param[in] mesh the polygonal mesh to save + * \param[in] precision the output ASCII precision default 5 + * \ingroup io + */ + PCL_EXPORTS int + saveOBJFile (const std::string &file_name, + const pcl::PolygonMesh &mesh, + unsigned precision = 5); + + } +} + +#endif /* OBJ_IO_H_ */ diff --git a/pcl-1.7/pcl/io/oni_grabber.h b/pcl-1.7/pcl/io/oni_grabber.h new file mode 100644 index 0000000..907a40d --- /dev/null +++ b/pcl-1.7/pcl/io/oni_grabber.h @@ -0,0 +1,210 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#ifdef HAVE_OPENNI + +#ifndef __PCL_IO_ONI_PLAYER__ +#define __PCL_IO_ONI_PLAYER__ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** */ + template class PointCloud; + /** */ + struct PointXYZ; + /** */ + struct PointXYZRGB; + /** */ + struct PointXYZRGBA; + /** */ + struct PointXYZI; + + /** \brief A simple ONI grabber. + * \author Suat Gedikli + * \ingroup io + */ + class PCL_EXPORTS ONIGrabber : public Grabber + { + public: + //define callback signature typedefs + typedef void (sig_cb_openni_image) (const boost::shared_ptr&); + typedef void (sig_cb_openni_depth_image) (const boost::shared_ptr&); + typedef void (sig_cb_openni_ir_image) (const boost::shared_ptr&); + typedef void (sig_cb_openni_image_depth_image) (const boost::shared_ptr&, const boost::shared_ptr&, float constant) ; + typedef void (sig_cb_openni_ir_depth_image) (const boost::shared_ptr&, const boost::shared_ptr&, float constant) ; + typedef void (sig_cb_openni_point_cloud) (const boost::shared_ptr >&); + typedef void (sig_cb_openni_point_cloud_rgb) (const boost::shared_ptr >&); + typedef void (sig_cb_openni_point_cloud_rgba) (const boost::shared_ptr >&); + typedef void (sig_cb_openni_point_cloud_i) (const boost::shared_ptr >&); + + /** \brief constuctor + * \param[in] file_name the path to the ONI file + * \param[in] repeat whether the play back should be in an infinite loop or not + * \param[in] stream whether the playback should be in streaming mode or in triggered mode. + */ + ONIGrabber (const std::string& file_name, bool repeat, bool stream); + + /** \brief destructor never throws an exception */ + virtual ~ONIGrabber () throw (); + + /** \brief For devices that are streaming, the streams are started by calling this method. + * Trigger-based devices, just trigger the device once for each call of start. + */ + virtual void + start (); + + /** \brief For devices that are streaming, the streams are stopped. + * This method has no effect for triggered devices. + */ + virtual void + stop (); + + /** \brief returns the name of the concrete subclass. + * \return the name of the concrete driver. + */ + virtual std::string + getName () const; + + /** \brief Indicates whether the grabber is streaming or not. This value is not defined for triggered devices. + * \return true if grabber is running / streaming. False otherwise. + */ + virtual bool + isRunning () const; + + /** \brief returns the frames pre second. 0 if it is trigger based. */ + virtual float + getFramesPerSecond () const; + + /** \brief Check if there is any data left in the ONI file to process. */ + inline bool + hasDataLeft () + { + return (device_->hasDataLeft ()); + } + + protected: + /** \brief internal OpenNI (openni_wrapper) callback that handles image streams */ + void + imageCallback (boost::shared_ptr image, void* cookie); + + /** \brief internal OpenNI (openni_wrapper) callback that handles depth streams */ + void + depthCallback (boost::shared_ptr depth_image, void* cookie); + + /** \brief internal OpenNI (openni_wrapper) callback that handles IR streams */ + void + irCallback (boost::shared_ptr ir_image, void* cookie); + + /** \brief internal callback that handles synchronized image + depth streams */ + void + imageDepthImageCallback (const boost::shared_ptr &image, + const boost::shared_ptr &depth_image); + + /** \brief internal callback that handles synchronized IR + depth streams */ + void + irDepthImageCallback (const boost::shared_ptr &image, + const boost::shared_ptr &depth_image); + + /** \brief internal method to assemble a point cloud object */ + boost::shared_ptr > + convertToXYZPointCloud (const boost::shared_ptr &depth) const; + + /** \brief internal method to assemble a point cloud object */ + boost::shared_ptr > + convertToXYZRGBPointCloud (const boost::shared_ptr &image, + const boost::shared_ptr &depth_image) const; + + /** \brief internal method to assemble a point cloud object */ + boost::shared_ptr > + convertToXYZRGBAPointCloud (const boost::shared_ptr &image, + const boost::shared_ptr &depth_image) const; + + /** \brief internal method to assemble a point cloud object */ + boost::shared_ptr > + convertToXYZIPointCloud (const boost::shared_ptr &image, + const boost::shared_ptr &depth_image) const; + + /** \brief synchronizer object to synchronize image and depth streams*/ + Synchronizer, boost::shared_ptr > rgb_sync_; + + /** \brief synchronizer object to synchronize IR and depth streams*/ + Synchronizer, boost::shared_ptr > ir_sync_; + + /** \brief the actual openni device*/ + boost::shared_ptr device_; + std::string rgb_frame_id_; + std::string depth_frame_id_; + bool running_; + unsigned image_width_; + unsigned image_height_; + unsigned depth_width_; + unsigned depth_height_; + openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle; + openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle; + openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle; + boost::signals2::signal* image_signal_; + boost::signals2::signal* depth_image_signal_; + boost::signals2::signal* ir_image_signal_; + boost::signals2::signal* image_depth_image_signal_; + boost::signals2::signal* ir_depth_image_signal_; + boost::signals2::signal* point_cloud_signal_; + boost::signals2::signal* point_cloud_i_signal_; + boost::signals2::signal* point_cloud_rgb_signal_; + boost::signals2::signal* point_cloud_rgba_signal_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + +} // namespace + +#endif // __PCL_IO_ONI_PLAYER__ +#endif // HAVE_OPENNI + diff --git a/pcl-1.7/pcl/io/openni_camera/image.h b/pcl-1.7/pcl/io/openni_camera/image.h new file mode 100644 index 0000000..bc1459c --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/image.h @@ -0,0 +1,215 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#include +#ifndef PCL_IO_IMAGE_H_ +#define PCL_IO_IMAGE_H_ + +#include +#include +#include + +#include + +namespace pcl +{ + namespace io + { + + /** + * @brief Image interface class providing an interface to fill a RGB or Grayscale image buffer. + * @param[in] image_metadata + * @ingroup io + */ + class PCL_EXPORTS Image + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef boost::chrono::high_resolution_clock Clock; + typedef boost::chrono::high_resolution_clock::time_point Timestamp; + + typedef enum + { + BAYER_GRBG, + YUV422, + RGB + } Encoding; + + Image (FrameWrapper::Ptr image_metadata) + : wrapper_ (image_metadata) + , timestamp_ (Clock::now ()) + {} + + Image (FrameWrapper::Ptr image_metadata, Timestamp time) + : wrapper_ (image_metadata) + , timestamp_ (time) + {} + + /** + * @brief virtual Destructor that never throws an exception. + */ + inline virtual ~Image () + {} + + /** + * @param[in] input_width width of input image + * @param[in] input_height height of input image + * @param[in] output_width width of desired output image + * @param[in] output_height height of desired output image + * @return wheter the resizing is supported or not. + */ + virtual bool + isResizingSupported (unsigned input_width, unsigned input_height, + unsigned output_width, unsigned output_height) const = 0; + + /** + * @brief fills a user given buffer with the RGB values, with an optional nearest-neighbor down sampling and an optional subregion + * @param[in] width desired width of output image. + * @param[in] height desired height of output image. + * @param[in,out] rgb_buffer the output RGB buffer. + * @param[in] rgb_line_step optional line step in bytes to allow the output in a rectangular subregion of the output buffer. + */ + virtual void + fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const = 0; + + /** + * @brief returns the encoding of the native data. + * @return encoding + */ + virtual Encoding + getEncoding () const = 0; + + /** + * @brief fills a user given buffer with the raw values. + * @param[in,out] rgb_buffer + */ + virtual void + fillRaw (unsigned char* rgb_buffer) const + { + memcpy (rgb_buffer, wrapper_->getData (), wrapper_->getDataSize ()); + } + + /** + * @brief fills a user given buffer with the gray values, with an optional nearest-neighbor down sampling and an optional subregion + * @param[in] width desired width of output image. + * @param[in] height desired height of output image. + * @param[in,out] gray_buffer the output gray buffer. + * @param[in] gray_line_step optional line step in bytes to allow the output in a rectangular subregion of the output buffer. + */ + virtual void + fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, + unsigned gray_line_step = 0) const = 0; + + /** + * @return width of the image + */ + unsigned + getWidth () const + { + return (wrapper_->getWidth ()); + } + + /** + * @return height of the image + */ + unsigned + getHeight () const + { + return (wrapper_->getHeight ()); + } + + /** + * @return frame id of the image. + * @note frame ids are ascending, but not necessarily synchronized with other streams + */ + unsigned + getFrameID () const + { + return (wrapper_->getFrameID ()); + } + + /** + * @return the timestamp of the image + * @note the time value is not synchronized with the system time + */ + pcl::uint64_t + getTimestamp () const + { + return (wrapper_->getTimestamp ()); + } + + + /** + * @return the timestamp of the image + * @note the time value *is* synchronized with the system time. + */ + Timestamp + getSystemTimestamp () const + { + return (timestamp_); + } + + // Get a const pointer to the raw depth buffer + const void* + getData () + { + return (wrapper_->getData ()); + } + + // Data buffer size in bytes + int + getDataSize () const + { + return (wrapper_->getDataSize ()); + } + + // Size of each row, including any padding + inline unsigned + getStep() const + { + return (getDataSize() / getHeight()); + } + + protected: + FrameWrapper::Ptr wrapper_; + Timestamp timestamp_; + }; + + } // namespace +} + +#endif //PCL_IO_IMAGE_H_ diff --git a/pcl-1.7/pcl/io/openni_camera/image_depth.h b/pcl-1.7/pcl/io/openni_camera/image_depth.h new file mode 100644 index 0000000..56867bc --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/image_depth.h @@ -0,0 +1,191 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011 Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#pragma once +#include + +#ifndef PCL_IO_IMAGE_DEPTH_H_ +#define PCL_IO_IMAGE_DEPTH_H_ + +#include +#include +#include + +#include + +namespace pcl +{ + namespace io + { + /** \brief This class provides methods to fill a depth or disparity image. + */ + class PCL_EXPORTS DepthImage + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef boost::chrono::high_resolution_clock Clock; + typedef boost::chrono::high_resolution_clock::time_point Timestamp; + + /** \brief Constructor + * \param[in] depth_meta_data the actual data from the OpenNI library + * \param[in] baseline the baseline of the "stereo" camera, i.e. the distance between the projector and the IR camera for + * Primesense like cameras. e.g. 7.5cm for PSDK5 and PSDK6 reference design. + * \param[in] focal_length focal length of the "stereo" frame. + * \param[in] shadow_value defines which values in the depth data are indicating shadow (resulting from the parallax between projector and IR camera) + * \param[in] no_sample_value defines which values in the depth data are indicating that no depth (disparity) could be determined . + * \attention The focal length may change, depending whether the depth stream is registered/mapped to the RGB stream or not. + */ + DepthImage (FrameWrapper::Ptr depth_metadata, float baseline, float focal_length, pcl::uint64_t shadow_value, pcl::uint64_t no_sample_value); + DepthImage (FrameWrapper::Ptr depth_metadata, float baseline, float focal_length, pcl::uint64_t shadow_value, pcl::uint64_t no_sample_value, Timestamp time); + + /** \brief Destructor. Never throws an exception. */ + ~DepthImage (); + + /** \brief method to access the internal data structure from OpenNI. If the data is accessed just read-only, then this method is faster than a fillXXX method + * \return the actual depth data of type openni::VideoFrameRef. + */ + const FrameWrapper::Ptr + getMetaData () const; + + /** \brief fills a user given block of memory with the disparity values with additional nearest-neighbor down-scaling. + * \param[in] width the width of the desired disparity image. + * \param[in] height the height of the desired disparity image. + * \param[in,out] disparity_buffer the float pointer to the actual memory buffer to be filled with the disparity values. + * \param[in] line_step if only a rectangular sub region of the buffer needs to be filled, then line_step is the + * width in bytes (not floats) of the original width of the depth buffer. + */ + void + fillDisparityImage (unsigned width, unsigned height, float* disparity_buffer, unsigned line_step = 0) const; + + /** \brief fills a user given block of memory with the disparity values with additional nearest-neighbor down-scaling. + * \param[in] width width the width of the desired depth image. + * \param[in] height height the height of the desired depth image. + * \param[in,out] depth_buffer the float pointer to the actual memory buffer to be filled with the depth values. + * \param[in] line_step if only a rectangular sub region of the buffer needs to be filled, then line_step is the + * width in bytes (not floats) of the original width of the depth buffer. + */ + void + fillDepthImage (unsigned width, unsigned height, float* depth_buffer, unsigned line_step = 0) const; + + /** \brief fills a user given block of memory with the raw values with additional nearest-neighbor down-scaling. + * \param[in] width width the width of the desired raw image. + * \param[in] height height the height of the desired raw image. + * \param[in,out] depth_buffer the unsigned short pointer to the actual memory buffer to be filled with the raw values. + * \param[in] line_step if only a rectangular sub region of the buffer needs to be filled, then line_step is the + * width in bytes (not floats) of the original width of the depth buffer. + */ + void + fillDepthImageRaw (unsigned width, unsigned height, unsigned short* depth_buffer, unsigned line_step = 0) const; + + /** \brief method to access the baseline of the "stereo" frame that was used to retrieve the depth image. + * \return baseline in meters + */ + float + getBaseline () const; + + /** \brief method to access the focal length of the "stereo" frame that was used to retrieve the depth image. + * \return focal length in pixels + */ + float + getFocalLength () const; + + /** \brief method to access the shadow value, that indicates pixels lying in shadow in the depth image. + * \return shadow value + */ + pcl::uint64_t + getShadowValue () const; + + /** \brief method to access the no-sample value, that indicates pixels where no disparity could be determined for the depth image. + * \return no-sample value + */ + pcl::uint64_t + getNoSampleValue () const; + + /** \return the width of the depth image */ + unsigned + getWidth () const; + + /** \return the height of the depth image */ + unsigned + getHeight () const; + + /** \return an ascending id for the depth frame + * \attention not necessarily synchronized with other streams + */ + unsigned + getFrameID () const; + + /** \return a ascending timestamp for the depth frame + * \attention its not the system time, thus can not be used directly to synchronize different sensors. + * But definitely synchronized with other streams + */ + pcl::uint64_t + getTimestamp () const; + + Timestamp + getSystemTimestamp () const; + + // Get a const pointer to the raw depth buffer + const unsigned short* + getData (); + + // Data buffer size in bytes + int + getDataSize () const; + + // Size of each row, including any padding + inline unsigned + getStep() const + { + return (getDataSize() / getHeight()); + } + + protected: + pcl::io::FrameWrapper::Ptr wrapper_; + + float baseline_; + float focal_length_; + pcl::uint64_t shadow_value_; + pcl::uint64_t no_sample_value_; + Timestamp timestamp_; + }; + +}} // namespace + +#endif // PCL_IO_IMAGE_DEPTH_H_ diff --git a/pcl-1.7/pcl/io/openni_camera/image_ir.h b/pcl-1.7/pcl/io/openni_camera/image_ir.h new file mode 100644 index 0000000..ce6a14e --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/image_ir.h @@ -0,0 +1,114 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2011 Willow Garage, Inc. +* +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the copyright holder(s) nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +*/ +#ifndef PCL_IO_IMAGE_IR_H_ +#define PCL_IO_IMAGE_IR_H_ + +#include +#include + +#include + +namespace pcl +{ + namespace io + { + + /** + * @brief Class containing just a reference to IR meta data. + */ + class PCL_EXPORTS IRImage + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef boost::chrono::high_resolution_clock Clock; + typedef boost::chrono::high_resolution_clock::time_point Timestamp; + + IRImage (FrameWrapper::Ptr ir_metadata); + IRImage (FrameWrapper::Ptr ir_metadata, Timestamp time); + + ~IRImage () throw () + {} + + void + fillRaw (unsigned width, unsigned height, unsigned short* ir_buffer, unsigned line_step = 0) const; + + unsigned + getWidth () const; + + unsigned + getHeight () const; + + unsigned + getFrameID () const; + + pcl::uint64_t + getTimestamp () const; + + Timestamp + getSystemTimestamp () const; + + // Get a const pointer to the raw depth buffer. If the data is accessed just read-only, then this method is faster than a fillXXX method + const unsigned short* + getData (); + + // Data buffer size in bytes + int + getDataSize () const; + + // Size of each row, including any padding + inline unsigned + getStep() const + { + return (getDataSize() / getHeight()); + } + + /** \brief method to access the internal data structure wrapper, which needs to be cast to an + * approperate subclass before the getMetadata(..) function is available to access the native data type. + */ + const FrameWrapper::Ptr + getMetaData () const; + + protected: + FrameWrapper::Ptr wrapper_; + Timestamp timestamp_; + }; + + } // namespace +} + +#endif // PCL_IO_IMAGE_IR_H_ diff --git a/pcl-1.7/pcl/io/openni_camera/image_metadata_wrapper.h b/pcl-1.7/pcl/io/openni_camera/image_metadata_wrapper.h new file mode 100644 index 0000000..19dcb82 --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/image_metadata_wrapper.h @@ -0,0 +1,83 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2014, respective authors. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#pragma once +#ifndef PCL_IO_IMAGE_METADATA_WRAPPER_H_ +#define PCL_IO_IMAGE_METADATA_WRAPPER_H_ + +#include +#include + +namespace pcl +{ + namespace io + { + + /** + * Pure abstract interface to wrap native frame data types. + */ + class FrameWrapper + { + public: + typedef boost::shared_ptr Ptr; + + virtual const void* + getData () const = 0; + + virtual unsigned + getDataSize () const = 0; + + virtual unsigned + getWidth () const = 0; + + virtual unsigned + getHeight () const = 0; + + virtual unsigned + getFrameID () const = 0; + + // Microseconds from some arbitrary start point + virtual pcl::uint64_t + getTimestamp () const = 0; + }; + + } // namespace +} + +#endif // PCL_IO_IMAGE_METADATA_WRAPPER_H_ diff --git a/pcl-1.7/pcl/io/openni_camera/image_rgb24.h b/pcl-1.7/pcl/io/openni_camera/image_rgb24.h new file mode 100644 index 0000000..41c155d --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/image_rgb24.h @@ -0,0 +1,91 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#include + +#ifndef PCL_IO_IMAGE_RGB_H_ +#define PCL_IO_IMAGE_RGB_H_ + +#include +#include + +#include + +namespace pcl +{ + namespace io + { + /** + * @brief This class provides methods to fill a RGB or Grayscale image buffer from underlying RGB24 image. + * @ingroup io + */ + class PCL_EXPORTS ImageRGB24 : public pcl::io::Image + { + public: + + ImageRGB24 (FrameWrapper::Ptr image_metadata); + ImageRGB24 (FrameWrapper::Ptr image_metadata, Timestamp timestamp); + virtual ~ImageRGB24 () throw (); + + inline virtual Encoding + getEncoding () const + { + return (RGB); + } + + virtual void + fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const; + + virtual void + fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const; + + virtual bool + isResizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const; + + private: + + // Struct used for type conversion + typedef struct + { + uint8_t r; + uint8_t g; + uint8_t b; + } RGB888Pixel; + }; + + } // namespace +} + +#endif // PCL_IO_IMAGE_RGB_H_ diff --git a/pcl-1.7/pcl/io/openni_camera/image_yuv422.h b/pcl-1.7/pcl/io/openni_camera/image_yuv422.h new file mode 100644 index 0000000..61ecdd7 --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/image_yuv422.h @@ -0,0 +1,79 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2011 Willow Garage, Inc. +* +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the copyright holder(s) nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +*/ +#include + +#ifndef PCL_IO_IMAGE_YUV422_H_ +#define PCL_IO_IMAGE_YUV422_H_ +#include + +#include + +namespace pcl +{ + namespace io + { + /** + * @brief Concrete implementation of the interface Image for a YUV 422 image used by Primesense devices. + * @ingroup io + */ + class PCL_EXPORTS ImageYUV422 : public pcl::io::Image + { + public: + ImageYUV422 (FrameWrapper::Ptr image_metadata); + ImageYUV422 (FrameWrapper::Ptr image_metadata, Timestamp timestamp); + + virtual ~ImageYUV422 () throw (); + + inline virtual Encoding + getEncoding () const + { + return (YUV422); + } + + virtual void + fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const; + + virtual void + fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const; + + virtual bool + isResizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const; + }; + + } // namespace +} + +#endif // PCL_IO_IMAGE_YUV22_H_ diff --git a/pcl-1.7/pcl/io/openni_camera/openni.h b/pcl-1.7/pcl/io/openni_camera/openni.h new file mode 100644 index 0000000..7c31b85 --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni.h @@ -0,0 +1,55 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#include +#ifdef HAVE_OPENNI + +#ifndef _PCL_OPENNI_OPENNI_H_ +#define _PCL_OPENNI_OPENNI_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +//work around for qt 5 bug: https://bugreports.qt-project.org/browse/QTBUG-29331 +#ifndef Q_MOC_RUN +#include +#endif // Q_MOC_RUN +#include + +#endif +#endif // _PCL_OPENNI_OPENNI_H_ diff --git a/pcl-1.7/pcl/io/openni_camera/openni_depth_image.h b/pcl-1.7/pcl/io/openni_camera/openni_depth_image.h new file mode 100644 index 0000000..d03fbb4 --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni_depth_image.h @@ -0,0 +1,229 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011 Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#include +#ifdef HAVE_OPENNI + +#ifndef __OPENNI_DEPTH_IMAGE__ +#define __OPENNI_DEPTH_IMAGE__ + +#include "openni.h" + +//#include // <-- because current header is included in NVCC-compiled code and contains . Consider +#include +#include "openni_exception.h" +#include + +namespace openni_wrapper +{ + /** \brief This class provides methods to fill a depth or disparity image. + * \author Suat Gedikli + */ + class PCL_EXPORTS DepthImage + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Constructor + * \param[in] depth_meta_data the actual data from the OpenNI library + * \param[in] baseline the baseline of the "stereo" camera, i.e. the distance between the projector and the IR camera for + * Primesense like cameras. e.g. 7.5cm for PSDK5 and PSDK6 reference design. + * \param[in] focal_length focal length of the "stereo" frame. + * \param[in] shadow_value defines which values in the depth data are indicating shadow (resulting from the parallax between projector and IR camera) + * \param[in] no_sample_value defines which values in the depth data are indicating that no depth (disparity) could be determined . + * \attention The focal length may change, depending whether the depth stream is registered/mapped to the RGB stream or not. + */ + inline DepthImage (boost::shared_ptr depth_meta_data, float baseline, float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) throw (); + + /** \brief Destructor. Never throws an exception. */ + inline virtual ~DepthImage () throw (); + + /** \brief method to access the internal data structure from OpenNI. If the data is accessed just read-only, then this method is faster than a fillXXX method + * \return the actual depth data of type xn::DepthMetaData. + */ + inline const xn::DepthMetaData& + getDepthMetaData () const throw (); + + /** \brief fills a user given block of memory with the disparity values with additional nearest-neighbor down-scaling. + * \param[in] width the width of the desired disparity image. + * \param[in] height the height of the desired disparity image. + * \param[in,out] disparity_buffer the float pointer to the actual memory buffer to be filled with the disparity values. + * \param[in] line_step if only a rectangular sub region of the buffer needs to be filled, then line_step is the + * width in bytes (not floats) of the original width of the depth buffer. + */ + void + fillDisparityImage (unsigned width, unsigned height, float* disparity_buffer, unsigned line_step = 0) const; + + /** \brief fills a user given block of memory with the disparity values with additional nearest-neighbor down-scaling. + * \param[in] width width the width of the desired depth image. + * \param[in] height height the height of the desired depth image. + * \param[in,out] depth_buffer the float pointer to the actual memory buffer to be filled with the depth values. + * \param[in] line_step if only a rectangular sub region of the buffer needs to be filled, then line_step is the + * width in bytes (not floats) of the original width of the depth buffer. + */ + void + fillDepthImage (unsigned width, unsigned height, float* depth_buffer, unsigned line_step = 0) const; + + /** \brief fills a user given block of memory with the raw values with additional nearest-neighbor down-scaling. + * \param[in] width width the width of the desired raw image. + * \param[in] height height the height of the desired raw image. + * \param[in,out] depth_buffer the unsigned short pointer to the actual memory buffer to be filled with the raw values. + * \param[in] line_step if only a rectangular sub region of the buffer needs to be filled, then line_step is the + * width in bytes (not floats) of the original width of the depth buffer. + */ + void + fillDepthImageRaw (unsigned width, unsigned height, unsigned short* depth_buffer, unsigned line_step = 0) const; + + /** \brief method to access the baseline of the "stereo" frame that was used to retrieve the depth image. + * \return baseline in meters + */ + inline float + getBaseline () const throw (); + + /** \brief method to access the focal length of the "stereo" frame that was used to retrieve the depth image. + * \return focal length in pixels + */ + inline float + getFocalLength () const throw (); + + /** \brief method to access the shadow value, that indicates pixels lying in shadow in the depth image. + * \return shadow value + */ + inline XnUInt64 + getShadowValue () const throw (); + + /** \brief method to access the no-sample value, that indicates pixels where no disparity could be determined for the depth image. + * \return no-sample value + */ + inline XnUInt64 + getNoSampleValue () const throw (); + + /** \return the width of the depth image */ + inline unsigned + getWidth () const throw (); + + /** \return the height of the depth image */ + inline unsigned + getHeight () const throw (); + + /** \return an ascending id for the depth frame + * \attention not necessarily synchronized with other streams + */ + inline unsigned + getFrameID () const throw (); + + /** \return a ascending timestamp for the depth frame + * \attention its not the system time, thus can not be used directly to synchronize different sensors. + * But definitely synchronized with other streams + */ + inline unsigned long + getTimeStamp () const throw (); + + protected: + boost::shared_ptr depth_md_; + float baseline_; + float focal_length_; + XnUInt64 shadow_value_; + XnUInt64 no_sample_value_; + } ; + + DepthImage::DepthImage (boost::shared_ptr depth_meta_data, float baseline, float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) throw () + : depth_md_ (depth_meta_data) + , baseline_ (baseline) + , focal_length_ (focal_length) + , shadow_value_ (shadow_value) + , no_sample_value_ (no_sample_value) { } + + DepthImage::~DepthImage () throw () { } + + const xn::DepthMetaData& + DepthImage::getDepthMetaData () const throw () + { + return *depth_md_; + } + + float + DepthImage::getBaseline () const throw () + { + return baseline_; + } + + float + DepthImage::getFocalLength () const throw () + { + return focal_length_; + } + + XnUInt64 + DepthImage::getShadowValue () const throw () + { + return shadow_value_; + } + + XnUInt64 + DepthImage::getNoSampleValue () const throw () + { + return no_sample_value_; + } + + unsigned + DepthImage::getWidth () const throw () + { + return depth_md_->XRes (); + } + + unsigned + DepthImage::getHeight () const throw () + { + return depth_md_->YRes (); + } + + unsigned + DepthImage::getFrameID () const throw () + { + return depth_md_->FrameID (); + } + + unsigned long + DepthImage::getTimeStamp () const throw () + { + return static_cast (depth_md_->Timestamp ()); + } +} // namespace +#endif +#endif //__OPENNI_DEPTH_IMAGE diff --git a/pcl-1.7/pcl/io/openni_camera/openni_device.h b/pcl-1.7/pcl/io/openni_camera/openni_device.h new file mode 100644 index 0000000..b4607b3 --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni_device.h @@ -0,0 +1,614 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#include +#ifdef HAVE_OPENNI + +#ifndef __OPENNI_IDEVICE_H__ +#define __OPENNI_IDEVICE_H__ +#include +#include +#include +#include "openni_exception.h" +#include "openni.h" + +#include +#include + + +/// @todo Get rid of all exception-specifications, these are useless and soon to be deprecated + +#ifndef _WIN32 +#define __stdcall +#endif + +namespace openni_wrapper +{ + class Image; + class DepthImage; + class IRImage; + + /** \brief Class representing an astract device for OpenNI devices: Primesense PSDK, Microsoft Kinect, Asus Xtion Pro/Live. + * \author Suat Gedikli + * \ingroup io + */ + class PCL_EXPORTS OpenNIDevice + { + public: + typedef enum + { + OpenNI_shift_values = 0, // Shift values (disparity) + OpenNI_12_bit_depth = 1, // Default mode: regular 12-bit depth + } DepthMode; + + typedef boost::function, void* cookie) > ImageCallbackFunction; + typedef boost::function, void* cookie) > DepthImageCallbackFunction; + typedef boost::function, void* cookie) > IRImageCallbackFunction; + typedef unsigned CallbackHandle; + + public: + + /** \brief virtual destructor. Never throws an exception. */ + virtual ~OpenNIDevice () throw (); + + /** \brief finds an image output mode that can be used to retrieve images in desired output mode. + * e.g If device just supports VGA at 30Hz, then the desired mode QVGA at 30Hz would be possible by down sampling, + * but the modes VGA at 25Hz and SXGA at 30Hz would not be compatible. + * \param[in] output_mode the desired output mode + * \param[out] mode the compatible mode that the device natively supports. + * \return true, if a compatible mode could be found, false otherwise. + */ + bool + findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw (); + + /** \brief finds a depth output mode that can be used to retrieve depth images in desired output mode. + * e.g If device just supports VGA at 30Hz, then a desired mode of QVGA at 30Hz would be possbile by downsampling, + * but the modes VGA at 25Hz and SXGA at 30Hz would not be compatible. + * \param[in] output_mode the desired output mode + * \param[out] mode the compatible mode that the device natively supports. + * \return true, if a compatible mode could be found, false otherwise. + */ + bool + findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw (); + + /** \brief returns whether a given mode is natively supported by the device or not + * \param[in] output_mode mode to be checked + * \return true if mode natively available, false otherwise + */ + bool + isImageModeSupported (const XnMapOutputMode& output_mode) const throw (); + + /** \brief returns whether a given mode is natively supported by the device or not + * \param[in] output_mode mode to be checked + * \return true if mode natively available, false otherwise + */ + bool + isDepthModeSupported (const XnMapOutputMode& output_mode) const throw (); + + /** \brief returns the default image mode, which is simply the first entry in the list of modes + * \return the default image mode + */ + const XnMapOutputMode& + getDefaultImageMode () const throw (); + + /** \brief returns the default depth mode, which is simply the first entry in the list of modes + * \return the default depth mode + */ + const XnMapOutputMode& + getDefaultDepthMode () const throw (); + + /** \brief returns the default IR mode, which is simply the first entry in the list of modes + * \return the default IR mode + */ + const XnMapOutputMode& + getDefaultIRMode () const throw (); + + /** \brief sets the output mode of the image stream + * \param[in] output_mode the desired output mode + */ + void + setImageOutputMode (const XnMapOutputMode& output_mode); + + /** \brief sets the output mode of the depth stream + * \param[in] output_mode the desired output mode + */ + void + setDepthOutputMode (const XnMapOutputMode& output_mode); + + /** \brief sets the output mode of the IR stream + * \param[in] output_mode the desired output mode + */ + void + setIROutputMode (const XnMapOutputMode& output_mode); + + /** \return the current output mode of the image stream */ + XnMapOutputMode + getImageOutputMode () const; + + /** \return the current output mode of the depth stream */ + XnMapOutputMode + getDepthOutputMode () const; + + /** \return the current output mode of the IR stream */ + XnMapOutputMode + getIROutputMode () const; + + /** \brief set the depth stream registration on or off + * \param[in] on_off + */ + void + setDepthRegistration (bool on_off); + + /** \return whether the depth stream is registered to the RGB camera fram or not. */ + bool + isDepthRegistered () const throw (); + + /** \return whether a registration of the depth stream to the RGB camera frame is supported or not. */ + bool + isDepthRegistrationSupported () const throw (); + + /** \brief set the hardware synchronization between Depth and RGB stream on or off. + * \param[in] on_off + */ + void + setSynchronization (bool on_off); + + /** \return true if Depth stream is synchronized to RGB stream, false otherwise. */ + bool + isSynchronized () const throw (); + + /** \return true if the Device supports hardware synchronization between Depth and RGB streams or not. */ + virtual bool + isSynchronizationSupported () const throw (); + + /** \return true if depth stream is a cropped version of the native depth stream, false otherwise. */ + bool + isDepthCropped () const; + + /** \brief turn on cropping for the depth stream. + * \param[in] x x-position of the rectangular subregion. + * \param[in] y y-position of the rectangular subregion. + * \param[in] width width of the rectangular subregion. + * \param[in] height height of the rectangular subregion. + */ + void + setDepthCropping (unsigned x, unsigned y, unsigned width, unsigned height); + + /** \return true if cropping of the depth stream is supported, false otherwise. */ + bool + isDepthCroppingSupported () const throw (); + + /** \brief returns the focal length for the color camera in pixels. The pixels are assumed to be square. + * Result depends on the output resolution of the image. + */ + inline float + getImageFocalLength (int output_x_resolution = 0) const throw (); + + /** \brief returns the focal length for the IR camera in pixels. The pixels are assumed to be square. + * Result depends on the output resolution of the depth image. + */ + inline float + getDepthFocalLength (int output_x_resolution = 0) const throw (); + + /** \return Baseline of the "stereo" frame. i.e. for PSDK compatible devices its the distance between the Projector and the IR camera. */ + inline float + getBaseline () const throw (); + + /** \brief starts the image stream. */ + virtual void + startImageStream (); + + /** \brief stops the image stream. */ + virtual void + stopImageStream (); + + /** \brief starts the depth stream. */ + virtual void + startDepthStream (); + + /** \brief stops the depth stream. */ + virtual void + stopDepthStream (); + + /** \brief starts the IR stream. */ + virtual void + startIRStream (); + + /** \brief stops the IR stream. */ + virtual void + stopIRStream (); + + /** \return true if the device supports an image stream, false otherwise. */ + bool + hasImageStream () const throw (); + + /** \return true if the device supports a depth stream, false otherwise. */ + bool + hasDepthStream () const throw (); + + /** \return true if the device supports an IR stream, false otherwise. */ + bool + hasIRStream () const throw (); + + /** \return true if the image stream is running / started, false otherwise. */ + virtual bool + isImageStreamRunning () const throw (); + + /** \return true if the depth stream is running / started, false otherwise. */ + virtual bool + isDepthStreamRunning () const throw (); + + /** \return true if the IR stream is running / started, false otherwise. */ + virtual bool + isIRStreamRunning () const throw (); + + /** \brief registers a callback function of boost::function type for the image stream with an optional user defined parameter. + * The callback will always be called with a new image and the user data "cookie". + * \param[in] callback the user callback to be called if a new image is available + * \param[in] cookie the cookie that needs to be passed to the callback together with the new image. + * \return a callback handler that can be used to remove the user callback from list of image-stream callbacks. + */ + CallbackHandle + registerImageCallback (const ImageCallbackFunction& callback, void* cookie = NULL) throw (); + + /** \brief registers a callback function for the image stream with an optional user defined parameter. + * This version is used to register a member function of any class. + * The callback will always be called with a new image and the user data "cookie". + * \param[in] callback the user callback to be called if a new image is available + * \param instance + * \param[in] cookie the cookie that needs to be passed to the callback together with the new image. + * \return a callback handler that can be used to remove the user callback from list of image-stream callbacks. + */ + template CallbackHandle + registerImageCallback (void (T::*callback)(boost::shared_ptr, void* cookie), T& instance, void* cookie = NULL) throw (); + + /** \brief unregisters a callback function. i.e. removes that function from the list of image stream callbacks. + * \param[in] callbackHandle the handle of the callback to unregister. + * \return true, if callback was in list and could be unregistered, false otherwise. + */ + bool + unregisterImageCallback (const CallbackHandle& callbackHandle) throw (); + + + /** \brief registers a callback function of boost::function type for the depth stream with an optional user defined parameter. + * The callback will always be called with a new depth image and the user data "cookie". + * \param[in] callback the user callback to be called if a new depth image is available + * \param[in] cookie the cookie that needs to be passed to the callback together with the new depth image. + * \return a callback handler that can be used to remove the user callback from list of depth-stream callbacks. + */ + CallbackHandle + registerDepthCallback (const DepthImageCallbackFunction& callback, void* cookie = NULL) throw (); + + /** \brief registers a callback function for the depth stream with an optional user defined parameter. + * This version is used to register a member function of any class. + * The callback will always be called with a new depth image and the user data "cookie". + * \param[in] callback the user callback to be called if a new depth image is available + * \param instance + * \param[in] cookie the cookie that needs to be passed to the callback together with the new depth image. + * \return a callback handler that can be used to remove the user callback from list of depth-stream callbacks. + */ + template CallbackHandle + registerDepthCallback (void (T::*callback)(boost::shared_ptr, void* cookie), T& instance, void* cookie = NULL) throw (); + + /** \brief unregisters a callback function. i.e. removes that function from the list of depth stream callbacks. + * \param[in] callbackHandle the handle of the callback to unregister. + * \return true, if callback was in list and could be unregistered, false otherwise. + */ + bool + unregisterDepthCallback (const CallbackHandle& callbackHandle) throw (); + + /** \brief registers a callback function of boost::function type for the IR stream with an optional user defined parameter. + * The callback will always be called with a new IR image and the user data "cookie". + * \param[in] callback the user callback to be called if a new IR image is available + * \param[in] cookie the cookie that needs to be passed to the callback together with the new IR image. + * \return a callback handler that can be used to remove the user callback from list of IR-stream callbacks. + */ + CallbackHandle + registerIRCallback (const IRImageCallbackFunction& callback, void* cookie = NULL) throw (); + + /** \brief registers a callback function for the IR stream with an optional user defined parameter. + * This version is used to register a member function of any class. + * The callback will always be called with a new IR image and the user data "cookie". + * \param[in] callback the user callback to be called if a new IR image is available + * \param instance + * \param[in] cookie the cookie that needs to be passed to the callback together with the new IR image. + * \return a callback handler that can be used to remove the user callback from list of IR-stream callbacks. + */ + template CallbackHandle + registerIRCallback (void (T::*callback)(boost::shared_ptr, void* cookie), T& instance, void* cookie = NULL) throw (); + + /** \brief unregisters a callback function. i.e. removes that function from the list of IR stream callbacks. + * \param[in] callbackHandle the handle of the callback to unregister. + * \return true, if callback was in list and could be unregistered, false otherwise. + */ + bool + unregisterIRCallback (const CallbackHandle& callbackHandle) throw (); + + /** \brief returns the serial number for device. + * \attention This might be an empty string!!! + */ + const char* + getSerialNumber () const throw (); + + /** \brief returns the connection string for current device, which has following format vendorID/productID\@BusID/DeviceID. */ + const char* + getConnectionString () const throw (); + + /** \return the Vendor name of the USB device. */ + const char* + getVendorName () const throw (); + + /** \return the product name of the USB device. */ + const char* + getProductName () const throw (); + + /** \return the vendor ID of the USB device. */ + unsigned short + getVendorID () const throw (); + + /** \return the product ID of the USB device. */ + unsigned short + getProductID () const throw (); + + /** \return the USB bus on which the device is connected. */ + unsigned char + getBus () const throw (); + + /** \return the USB Address of the device. */ + unsigned char + getAddress () const throw (); + + /** \brief Set the RGB image focal length. + * \param[in] focal_length the RGB image focal length + */ + inline void + setRGBFocalLength (float focal_length) + { + rgb_focal_length_SXGA_ = focal_length; + } + + /** \brief Set the depth image focal length. + * \param[in] focal_length the depth image focal length + */ + inline void + setDepthFocalLength (float focal_length) + { + depth_focal_length_SXGA_ = focal_length; + } + + /** \brief Set the depth output format. Use 12bit depth values or shift values. + * \param[in] depth_mode the depth output format + */ + void + setDepthOutputFormat (const DepthMode& depth_mode = OpenNI_12_bit_depth); + + /** \brief Get the depth output format as set by the user. */ + XnUInt64 + getDepthOutputFormat () const; + + + /** \brief Convert shift to depth value. */ + pcl::uint16_t + shiftToDepth (pcl::uint16_t shift_value) const + { + assert (shift_conversion_parameters_.init_); + + pcl::uint16_t ret = 0; + + // lookup depth value in shift lookup table + if (shift_value) > ActualImageCallbackFunction; + typedef boost::function) > ActualDepthImageCallbackFunction; + typedef boost::function) > ActualIRImageCallbackFunction; + + OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node); + OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node); + OpenNIDevice (xn::Context& context); + static void __stdcall NewDepthDataAvailable (xn::ProductionNode& node, void* cookie) throw (); + static void __stdcall NewImageDataAvailable (xn::ProductionNode& node, void* cookie) throw (); + static void __stdcall NewIRDataAvailable (xn::ProductionNode& node, void* cookie) throw (); + + // This is a workaround, since in the NewDepthDataAvailable function WaitAndUpdateData leads to a dead-lock behaviour + // and retrieving image data without WaitAndUpdateData leads to incomplete images!!! + void + ImageDataThreadFunction (); + + void + DepthDataThreadFunction (); + + void + IRDataThreadFunction (); + + virtual bool + isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () = 0; + + void + setRegistration (bool on_off); + + virtual boost::shared_ptr + getCurrentImage (boost::shared_ptr image_data) const throw () = 0; + + void + Init (); + + void InitShiftToDepthConversion(); + void ReadDeviceParametersFromSensorNode(); + + struct ShiftConversion + { + ShiftConversion() : init_(false) {} + + XnUInt16 zero_plane_distance_; + XnFloat zero_plane_pixel_size_; + XnFloat emitter_dcmos_distace_; + XnUInt32 max_shift_; + XnUInt32 device_max_shift_; + XnUInt32 const_shift_; + XnUInt32 pixel_size_factor_; + XnUInt32 param_coeff_; + XnUInt32 shift_scale_; + XnUInt32 min_depth_; + XnUInt32 max_depth_; + bool init_; + + } shift_conversion_parameters_; + + std::vector shift_to_depth_table_; + + // holds the callback functions together with custom data + // since same callback function can be registered multiple times with e.g. different custom data + // we use a map structure with a handle as the key + std::map image_callback_; + std::map depth_callback_; + std::map ir_callback_; + + std::vector available_image_modes_; + std::vector available_depth_modes_; + + /** \brief context to OpenNI driver*/ + xn::Context& context_; + /** \brief node object for current device */ + xn::NodeInfo device_node_info_; + + /** \brief Depth generator object. */ + xn::DepthGenerator depth_generator_; + /** \brief Image generator object. */ + xn::ImageGenerator image_generator_; + /** \brief IR generator object. */ + xn::IRGenerator ir_generator_; + + XnCallbackHandle depth_callback_handle_; + XnCallbackHandle image_callback_handle_; + XnCallbackHandle ir_callback_handle_; + + /** \brief focal length for IR camera producing depth information in native SXGA mode */ + float depth_focal_length_SXGA_; + /** \brief distance between the projector and the IR camera*/ + float baseline_; + /** \brief focal length for regular camera producing color images in native SXGA mode */ + float rgb_focal_length_SXGA_; + + /** the value for shadow (occluded pixels) */ + XnUInt64 shadow_value_; + /** the value for pixels without a valid disparity measurement */ + XnUInt64 no_sample_value_; + + OpenNIDevice::CallbackHandle image_callback_handle_counter_; + OpenNIDevice::CallbackHandle depth_callback_handle_counter_; + OpenNIDevice::CallbackHandle ir_callback_handle_counter_; + + bool quit_; + mutable boost::mutex image_mutex_; + mutable boost::mutex depth_mutex_; + mutable boost::mutex ir_mutex_; + boost::condition_variable image_condition_; + boost::condition_variable depth_condition_; + boost::condition_variable ir_condition_; + boost::thread image_thread_; + boost::thread depth_thread_; + boost::thread ir_thread_; + }; + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + float + OpenNIDevice::getImageFocalLength (int output_x_resolution) const throw () + { + if (output_x_resolution == 0) + output_x_resolution = getImageOutputMode ().nXRes; + + float scale = static_cast (output_x_resolution) / static_cast (XN_SXGA_X_RES); + return (rgb_focal_length_SXGA_ * scale); + } + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + float + OpenNIDevice::getDepthFocalLength (int output_x_resolution) const throw () + { + if (output_x_resolution == 0) + output_x_resolution = getDepthOutputMode ().nXRes; + + float scale = static_cast (output_x_resolution) / static_cast (XN_SXGA_X_RES); + if (isDepthRegistered ()) + return (rgb_focal_length_SXGA_ * scale); + else + return (depth_focal_length_SXGA_ * scale); + } + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + float + OpenNIDevice::getBaseline () const throw () + { + return (baseline_); + } + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template OpenNIDevice::CallbackHandle + OpenNIDevice::registerImageCallback (void (T::*callback)(boost::shared_ptr, void* cookie), T& instance, void* custom_data) throw () + { + image_callback_[image_callback_handle_counter_] = boost::bind (callback, boost::ref (instance), _1, custom_data); + return (image_callback_handle_counter_++); + } + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template OpenNIDevice::CallbackHandle + OpenNIDevice::registerDepthCallback (void (T::*callback)(boost::shared_ptr, void* cookie), T& instance, void* custom_data) throw () + { + depth_callback_[depth_callback_handle_counter_] = boost::bind ( callback, boost::ref (instance), _1, custom_data); + return (depth_callback_handle_counter_++); + } + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template OpenNIDevice::CallbackHandle + OpenNIDevice::registerIRCallback (void (T::*callback)(boost::shared_ptr, void* cookie), T& instance, void* custom_data) throw () + { + ir_callback_[ir_callback_handle_counter_] = boost::bind ( callback, boost::ref (instance), _1, custom_data); + return (ir_callback_handle_counter_++); + } + +} +#endif // __OPENNI_IDEVICE_H__ +#endif // HAVE_OPENNI diff --git a/pcl-1.7/pcl/io/openni_camera/openni_device_kinect.h b/pcl-1.7/pcl/io/openni_camera/openni_device_kinect.h new file mode 100644 index 0000000..0a80d45 --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni_device_kinect.h @@ -0,0 +1,89 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#include +#ifdef HAVE_OPENNI + +#ifndef __OPENNI_DEVICE_KINECT__ +#define __OPENNI_DEVICE_KINECT__ + +#include "openni_device.h" +#include "openni_driver.h" +#include "openni_image_bayer_grbg.h" + +namespace openni_wrapper +{ + + /** + * @brief Concrete implementation of the interface OpenNIDevice for a MS Kinect device. + * @author Suat Gedikli + * @date 02.january 2011 + * @ingroup io + */ + class DeviceKinect : public OpenNIDevice + { + friend class OpenNIDriver; + public: + DeviceKinect (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node); + virtual ~DeviceKinect () throw (); + + inline void setDebayeringMethod (const ImageBayerGRBG::DebayeringMethod& debayering_method) throw (); + inline const ImageBayerGRBG::DebayeringMethod& getDebayeringMethod () const throw (); + + virtual bool isSynchronizationSupported () const throw (); + + protected: + virtual boost::shared_ptr getCurrentImage (boost::shared_ptr image_meta_data) const throw (); + void enumAvailableModes () throw (); + virtual bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw (); + ImageBayerGRBG::DebayeringMethod debayering_method_; + } ; + + void + DeviceKinect::setDebayeringMethod (const ImageBayerGRBG::DebayeringMethod& debayering_method) throw () + { + debayering_method_ = debayering_method; + } + + const ImageBayerGRBG::DebayeringMethod& + DeviceKinect::getDebayeringMethod () const throw () + { + return debayering_method_; + } +} // namespace + +#endif +#endif // __OPENNI_DEVICE_KINECT__ diff --git a/pcl-1.7/pcl/io/openni_camera/openni_device_oni.h b/pcl-1.7/pcl/io/openni_camera/openni_device_oni.h new file mode 100644 index 0000000..4058a60 --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni_device_oni.h @@ -0,0 +1,112 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#include +#ifdef HAVE_OPENNI + +#ifndef __OPENNI_DEVICE_ONI__ +#define __OPENNI_DEVICE_ONI__ + +#include "openni_device.h" +#include "openni_driver.h" + +namespace openni_wrapper +{ + + /** + * @brief Concrete implementation of the interface OpenNIDevice for a virtual device playing back an ONI file. + * @author Suat Gedikli + * @date 19. june 2011 + * @ingroup io + */ + class DeviceONI : public OpenNIDevice + { + friend class OpenNIDriver; + public: + DeviceONI (xn::Context& context, const std::string& file_name, bool repeat = false, bool streaming = true); + virtual ~DeviceONI () throw (); + + virtual void startImageStream (); + virtual void stopImageStream (); + + virtual void startDepthStream (); + virtual void stopDepthStream (); + + virtual void startIRStream (); + virtual void stopIRStream (); + + virtual bool isImageStreamRunning () const throw (); + virtual bool isDepthStreamRunning () const throw (); + virtual bool isIRStreamRunning () const throw (); + + virtual bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw (); + + /** \brief Trigger a new frame in the ONI stream. + * \param[in] relative_offset the relative offset in case we want to seek in the file + */ + bool + trigger (int relative_offset = 0); + + bool isStreaming () const throw (); + + /** \brief Check if there is any data left in the ONI file to process. */ + inline bool + hasDataLeft () + { + return (!player_.IsEOF ()); + } + + protected: + virtual boost::shared_ptr getCurrentImage (boost::shared_ptr image_meta_data) const throw (); + + void PlayerThreadFunction (); + static void __stdcall NewONIDepthDataAvailable (xn::ProductionNode& node, void* cookie) throw (); + static void __stdcall NewONIImageDataAvailable (xn::ProductionNode& node, void* cookie) throw (); + static void __stdcall NewONIIRDataAvailable (xn::ProductionNode& node, void* cookie) throw (); + + xn::Player player_; + boost::thread player_thread_; + mutable boost::mutex player_mutex_; + boost::condition_variable player_condition_; + bool streaming_; + bool depth_stream_running_; + bool image_stream_running_; + bool ir_stream_running_; + }; +} //namespace openni_wrapper +#endif //__OPENNI_DEVICE_ONI__ +#endif //HAVE_OPENNI + diff --git a/pcl-1.7/pcl/io/openni_camera/openni_device_primesense.h b/pcl-1.7/pcl/io/openni_camera/openni_device_primesense.h new file mode 100644 index 0000000..1547e98 --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni_device_primesense.h @@ -0,0 +1,73 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#include +#ifdef HAVE_OPENNI + +#ifndef __OPENNI_DEVICE_PRIMESENSE__ +#define __OPENNI_DEVICE_PRIMESENSE__ + +#include "openni_device.h" +#include "openni_driver.h" + +namespace openni_wrapper +{ +/** + * @brief Concrete implementation of the interface OpenNIDevice for a Primesense device. + * @author Suat Gedikli + * @date 02.january 2011 + * @ingroup io + */ +class DevicePrimesense : public OpenNIDevice +{ + friend class OpenNIDriver; +public: + DevicePrimesense (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node); + virtual ~DevicePrimesense () throw (); + //virtual void setImageOutputMode (const XnMapOutputMode& output_mode); + +protected: + virtual boost::shared_ptr getCurrentImage (boost::shared_ptr image_meta_data) const throw (); + void enumAvailableModes () throw (); + virtual bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw (); + + virtual void startImageStream (); + virtual void startDepthStream (); +}; +} // namespace + +#endif +#endif // __OPENNI_DEVICE_PRIMESENSE__ diff --git a/pcl-1.7/pcl/io/openni_camera/openni_device_xtion.h b/pcl-1.7/pcl/io/openni_camera/openni_device_xtion.h new file mode 100644 index 0000000..17b43d0 --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni_device_xtion.h @@ -0,0 +1,74 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#include +#ifdef HAVE_OPENNI + +#ifndef __OPENNI_DEVICE_XTION_PRO__ +#define __OPENNI_DEVICE_XTION_PRO__ + +#include "openni_device.h" +#include "openni_driver.h" +#include "openni_image_yuv_422.h" + +namespace openni_wrapper +{ + + /** + * @brief Concrete implementation of the interface OpenNIDevice for a Asus Xtion Pro device. + * @author Suat Gedikli + * @date 02.january 2011 + * @ingroup io + */ + class DeviceXtionPro : public OpenNIDevice + { + friend class OpenNIDriver; + public: + DeviceXtionPro (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node); + virtual ~DeviceXtionPro () throw (); + //virtual void setImageOutputMode (const XnMapOutputMode& output_mode); + + protected: + virtual boost::shared_ptr getCurrentImage (boost::shared_ptr image_meta_data) const throw (); + void enumAvailableModes () throw (); + virtual bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw (); + + virtual void startDepthStream (); + } ; +} // namespace + +#endif +#endif // __OPENNI_DEVICE_PRIMESENSE__ diff --git a/pcl-1.7/pcl/io/openni_camera/openni_driver.h b/pcl-1.7/pcl/io/openni_camera/openni_driver.h new file mode 100644 index 0000000..797549b --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni_driver.h @@ -0,0 +1,251 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#include +#ifdef HAVE_OPENNI + +#ifndef OPENNI_OPENNI_H_ +#define OPENNI_OPENNI_H_ +#include +#include +#include +#include "openni.h" +#include "openni_exception.h" +#include "openni_device.h" +#include +#include + +namespace openni_wrapper +{ + //class OpenNIDevice; + + /** + * @brief Driver class implemented as Singleton. This class contains the xn::Context object used by all devices. It \ + * provides methods for enumerating and accessing devices. + * @author Suat Gedikli + * @date 02.january 2011 + * @ingroup io + */ + class PCL_EXPORTS OpenNIDriver + { + public: + /** + * @author Suat Gedikli + * @brief virtual Destructor that never throws an exception + */ + ~OpenNIDriver () throw (); + + /** + * @author Suat Gedikli + * @brief static access method to the only instance. + * @return the only instance of this class. + */ + inline static OpenNIDriver& getInstance (); + + /** + * @author Suat Gedikli + * @brief enumerates all devices and updates the list of available devices. + * @return the number of devices found. + */ + unsigned updateDeviceList (); + + /** + * @author Suat Gedikli + * @return the number of available devices. + */ + inline unsigned getNumberDevices () const throw (); + + /** + * @author Suat Gedikli + * @brief creates a virtual device from an ONI file. + * @param[in] path the path to the ONI file + * @param[in] repeat whether the ONI playback should be repeated in an infinite loop or not. + * @param[in] stream whether the device should be created as a streaming or trigger-based device. + * @return the shared_ptr to the newly created virtual device. + */ + boost::shared_ptr createVirtualDevice (const std::string& path, bool repeat, bool stream) const; + + /** + * @author Suat Gedikli + * @brief returns the device with a given index, where the index is its position in the device list. + * @param[in] index index of the device to be retrieved. + * @return shared_ptr to the device, null if no matching device found. + */ + boost::shared_ptr getDeviceByIndex (unsigned index) const; + + /** + * @author Suat Gedikli + * @brief returns the device with the given serial number. + * @param[in] serial_number the serial number of the device to be retrieved. + * @return shared_ptr to the device, null if no matching device found. + */ + boost::shared_ptr getDeviceBySerialNumber (const std::string& serial_number) const; + +#ifndef _WIN32 + /** + * @author Suat Gedikli + * @brief returns the device that is given by the USB bus/address combination. + * @param[in] bus the USB bus id + * @param[in] address the USB address + * @return shared_ptr to the device, null if no matching device found. + */ + boost::shared_ptr getDeviceByAddress (unsigned char bus, unsigned char address) const; +#endif + + /** + * @author Suat Gedikli + * @brief method to retrieve the serial number of a device without creating it. + * @param[in] index the index of the device in the device list. + * @return the serial number of the device. + */ + const char* getSerialNumber (unsigned index) const throw (); + + /** + * @author Suat Gedikli + * @brief method to retrieve the connection string of a device without creating it. + * @param[in] index the index of the device in the device list. + * @return the connection string of the device. + */ + const char* getConnectionString (unsigned index) const throw (); + + /** + * @author Suat Gedikli + * @brief method to retrieve the vendor name of the USB device without creating it. + * @param[in] index the index of the device in the device list. + * @return the vendor name of the USB device. + */ + const char* getVendorName (unsigned index) const throw (); + + /** + * @author Suat Gedikli + * @brief method to retrieve the product name of the USB device without creating it. + * @param[in] index the index of the device in the device list. + * @return the product name of the USB device. + */ + const char* getProductName (unsigned index) const throw (); + + /** + * @author Suat Gedikli + * @brief method to retrieve the vendor id of the USB device without creating it. + * @param[in] index the index of the device in the device list. + * @return the vendor id of the USB device. + */ + unsigned short getVendorID (unsigned index) const throw (); + + /** + * @author Suat Gedikli + * @brief method to retrieve the product id of the USB device without creating it. + * @param[in] index the index of the device in the device list. + * @return the product id of the USB device. + */ + unsigned short getProductID (unsigned index) const throw (); + + /** + * @author Suat Gedikli + * @brief method to retrieve the bus id of the USB device without creating it. + * @param[in] index the index of the device in the device list. + * @return the bus id of the USB device. + */ + unsigned char getBus (unsigned index) const throw (); + + /** + * @author Suat Gedikli + * @brief method to retrieve the vaddress of the USB device without creating it. + * @param[in] index the index of the device in the device list. + * @return the address of the USB device. + */ + unsigned char getAddress (unsigned index) const throw (); + + /** + * @author Suat Gedikli + * @brief stops all streams from all devices. + */ + void stopAll (); + + /** + * @author Suat Gedikli + * @brief decomposes the connection string into vendor id and product id. + * @param[in] connection_string the string containing teh connection information + * @param[out] vendorId the vendor id + * @param[out] productId the product id + */ + static void + getDeviceType (const std::string& connection_string, unsigned short& vendorId, unsigned short& productId); + protected: + + struct PCL_EXPORTS DeviceContext + { + DeviceContext (const xn::NodeInfo& device_node, xn::NodeInfo* image_node, xn::NodeInfo* depth_node, xn::NodeInfo * ir_node); + DeviceContext (const xn::NodeInfo & device_node); + DeviceContext (const DeviceContext&); + xn::NodeInfo device_node; + boost::shared_ptr image_node; + boost::shared_ptr depth_node; + boost::shared_ptr ir_node; + boost::weak_ptr device; + } ; + + OpenNIDriver (); + boost::shared_ptr getDevice (unsigned index) const; + +#ifndef _WIN32 + // workaround to get additional device nformation like serial number, vendor and product name, until Primesense fix this + void getDeviceInfos () throw (); +#endif + + mutable std::vector device_context_; + mutable xn::Context context_; + + std::map< unsigned char, std::map > bus_map_; + std::map< std::string, unsigned > serial_map_; + std::map< std::string, unsigned > connection_string_map_; + } ; + + OpenNIDriver& + OpenNIDriver::getInstance () + { + static OpenNIDriver driver; + return driver; + } + + unsigned + OpenNIDriver::getNumberDevices () const throw () + { + return static_cast (device_context_.size ()); + } +} // namespace +#endif +#endif diff --git a/pcl-1.7/pcl/io/openni_camera/openni_exception.h b/pcl-1.7/pcl/io/openni_camera/openni_exception.h new file mode 100644 index 0000000..933839c --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni_exception.h @@ -0,0 +1,140 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#include +#ifdef HAVE_OPENNI + +#ifndef __OPENNI_EXCEPTION__ +#define __OPENNI_EXCEPTION__ + +#include +#include +#include +#include +//#include <-- because current header is included in NVCC-compiled code and contains . Consider + + +//fom +#if defined _WIN32 && defined _MSC_VER && !defined __PRETTY_FUNCTION__ + #define __PRETTY_FUNCTION__ __FUNCTION__ +#endif + + +#define THROW_OPENNI_EXCEPTION(format,...) throwOpenNIException( __PRETTY_FUNCTION__, __FILE__, __LINE__, format , ##__VA_ARGS__ ) + + +namespace openni_wrapper +{ + + /** + * @brief General exception class + * @author Suat Gedikli + * @date 02.january 2011 + * @ingroup io + */ + class OpenNIException : public std::exception + { + public: + /** + * @brief Constructor + * @note use the MACRO THROW_OPENNI_EXCEPTION, that takes care about the parameters function_name, file_name and line_number + * @param[in] function_name the function in which this exception was created. + * @param[in] file_name the file name in which this exception was created. + * @param[in] line_number the line number where this exception was created. + * @param[in] message the message of the exception + */ + OpenNIException (const std::string& function_name, const std::string& file_name, unsigned line_number, const std::string& message) throw (); + + /** + * @brief virtual Destructor that never throws an exception + */ + virtual ~OpenNIException () throw (); + + /** + * @brief Assignment operator to allow copying the message of another exception variable. + * @param[in] exception left hand side + * @return + */ + OpenNIException & operator= (const OpenNIException& exception) throw (); + + /** + * @brief virtual method, derived from std::exception + * @return the message of the exception. + */ + virtual const char* what () const throw (); + + /** + * @return the function name in which the exception was created. + */ + const std::string& getFunctionName () const throw (); + + /** + * @return the filename in which the exception was created. + */ + const std::string& getFileName () const throw (); + + /** + * @return the line number where the exception was created. + */ + unsigned getLineNumber () const throw (); + protected: + std::string function_name_; + std::string file_name_; + unsigned line_number_; + std::string message_; + std::string message_long_; + } ; + + /** + * @brief inline function used by the macro THROW_OPENNI_EXCEPTION to create an instance of OpenNIException with correct values for function, file and line_number + * @param[in] function_name the function name. Will be filled in by the macro THROW_OPENNI_EXCEPTION + * @param[in] file_name the file name. Will be filled in by the macro THROW_OPENNI_EXCEPTION + * @param[in] line_number the line number. Will be filled in by the macro THROW_OPENNI_EXCEPTION + * @param[in] format the printf-style format string + * @param[in] ... optional arguments for the printf style format. + */ + inline void + throwOpenNIException (const char* function_name, const char* file_name, unsigned line_number, const char* format, ...) + { + static char msg[1024]; + va_list args; + va_start (args, format); + vsprintf (msg, format, args); + throw OpenNIException (function_name, file_name, line_number, msg); + } +} // namespace openni_camera +#endif +#endif diff --git a/pcl-1.7/pcl/io/openni_camera/openni_image.h b/pcl-1.7/pcl/io/openni_camera/openni_image.h new file mode 100644 index 0000000..5f4333d --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni_image.h @@ -0,0 +1,209 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#include +#ifdef HAVE_OPENNI + +#ifndef __OPENNI_IMAGE__ +#define __OPENNI_IMAGE__ + +#include +#include "openni.h" +#include "openni_exception.h" +#include + +namespace openni_wrapper +{ + + /** + * @brief Image class containing just a reference to image meta data. Thus this class + * just provides an interface to fill a RGB or Grayscale image buffer. + * @author Suat Gedikli + * @date 02.january 2011 + * @param[in] image_meta_data + * @ingroup io + */ + class PCL_EXPORTS Image + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef enum + { + BAYER_GRBG, + YUV422, + RGB + } Encoding; + + /** + * @author Suat Gedikli + * @brief Constructor + * @param[in] image_meta_data the actual image data from the OpenNI driver + */ + inline Image (boost::shared_ptr image_meta_data) throw (); + + /** + * @author Suat Gedikli + * @brief virtual Destructor that never throws an exception. + */ + inline virtual ~Image () throw (); + + /** + * @author Suat Gedikli + * @param[in] input_width width of input image + * @param[in] input_height height of input image + * @param[in] output_width width of desired output image + * @param[in] output_height height of desired output image + * @return wheter the resizing is supported or not. + */ + virtual bool isResizingSupported (unsigned input_width, unsigned input_height, + unsigned output_width, unsigned output_height) const = 0; + + /** + * @author Suat Gedikli + * @brief fills a user given buffer with the RGB values, with an optional nearest-neighbor down sampling and an optional subregion + * @param[in] width desired width of output image. + * @param[in] height desired height of output image. + * @param[in,out] rgb_buffer the output RGB buffer. + * @param[in] rgb_line_step optional line step in bytes to allow the output in a rectangular subregion of the output buffer. + */ + virtual void fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, + unsigned rgb_line_step = 0) const = 0; + + /** + * @author Suat Gedikli + * @brief returns the encoding of the native data. + * @return encoding + */ + virtual Encoding getEncoding () const = 0; + + /** + * @author Suat Gedikli + * @brief fills a user given buffer with the raw values. + * @param[in,out] rgb_buffer + */ + inline void + fillRaw (unsigned char* rgb_buffer) const throw () + { + memcpy (rgb_buffer, image_md_->Data (), image_md_->DataSize ()); + } + + /** + * @author Suat Gedikli + * @brief fills a user given buffer with the gray values, with an optional nearest-neighbor down sampling and an optional subregion + * @param[in] width desired width of output image. + * @param[in] height desired height of output image. + * @param[in,out] gray_buffer the output gray buffer. + * @param[in] gray_line_step optional line step in bytes to allow the output in a rectangular subregion of the output buffer. + */ + virtual void fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, + unsigned gray_line_step = 0) const = 0; + + /** + * @author Suat Gedikli + * @return width of the image + */ + inline unsigned getWidth () const throw (); + + /** + * @author Suat Gedikli + * @return height of the image + */ + inline unsigned getHeight () const throw (); + + /** + * @author Suat Gedikli + * @return frame id of the image. + * @note frame ids are ascending, but not necessarily synch'ed with other streams + */ + inline unsigned getFrameID () const throw (); + + /** + * @author Suat Gedikli + * @return the time stamp of the image + * @note the time value is not synche'ed with the system time + */ + inline unsigned long getTimeStamp () const throw (); + + /** + * @author Suat Gedikli + * @return the actual data in native OpenNI format. + */ + inline const xn::ImageMetaData& getMetaData () const throw (); + + protected: + boost::shared_ptr image_md_; + } ; + + Image::Image (boost::shared_ptr image_meta_data) throw () + : image_md_ (image_meta_data) + { + } + + Image::~Image () throw () { } + + unsigned + Image::getWidth () const throw () + { + return image_md_->XRes (); + } + + unsigned + Image::getHeight () const throw () + { + return image_md_->YRes (); + } + + unsigned + Image::getFrameID () const throw () + { + return image_md_->FrameID (); + } + + unsigned long + Image::getTimeStamp () const throw () + { + return static_cast (image_md_->Timestamp ()); + } + + const xn::ImageMetaData& + Image::getMetaData () const throw () + { + return *image_md_; + } +} // namespace +#endif +#endif //__OPENNI_IMAGE__ diff --git a/pcl-1.7/pcl/io/openni_camera/openni_image_bayer_grbg.h b/pcl-1.7/pcl/io/openni_camera/openni_image_bayer_grbg.h new file mode 100644 index 0000000..a76a4eb --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni_image_bayer_grbg.h @@ -0,0 +1,103 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#include +#ifdef HAVE_OPENNI + +#ifndef __OPENNI_IMAGE_BAYER_GRBG__ +#define __OPENNI_IMAGE_BAYER_GRBG__ +#include +#include "openni_image.h" + +namespace openni_wrapper +{ + /** \brief This class provides methods to fill a RGB or Grayscale image buffer from underlying Bayer pattern image. + * \author Suat Gedikli + * \ingroup io + */ + class PCL_EXPORTS ImageBayerGRBG : public Image + { + public: + typedef enum + { + Bilinear = 0, + EdgeAware, + EdgeAwareWeighted + } DebayeringMethod; + + ImageBayerGRBG (boost::shared_ptr image_meta_data, DebayeringMethod method) throw (); + virtual ~ImageBayerGRBG () throw (); + + inline virtual Encoding + getEncoding () const + { + return (BAYER_GRBG); + } + + virtual void fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const; + virtual void fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const; + virtual bool isResizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const; + inline void setDebayeringMethod (const DebayeringMethod& method) throw (); + inline DebayeringMethod getDebayeringMethod () const throw (); + inline static bool resizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height); + + + protected: + DebayeringMethod debayering_method_; + }; + + void + ImageBayerGRBG::setDebayeringMethod (const ImageBayerGRBG::DebayeringMethod& method) throw () + { + debayering_method_ = method; + } + + ImageBayerGRBG::DebayeringMethod + ImageBayerGRBG::getDebayeringMethod () const throw () + { + return debayering_method_; + } + + bool + ImageBayerGRBG::resizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) + { + return (output_width <= input_width && output_height <= input_height && input_width % output_width == 0 && input_height % output_height == 0 ); + } +} // namespace + +#endif +#endif // __OPENNI_IMAGE__ diff --git a/pcl-1.7/pcl/io/openni_camera/openni_image_rgb24.h b/pcl-1.7/pcl/io/openni_camera/openni_image_rgb24.h new file mode 100644 index 0000000..2739766 --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni_image_rgb24.h @@ -0,0 +1,82 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#include +#ifdef HAVE_OPENNI + +#ifndef __OPENNI_IMAGE_RGB__ +#define __OPENNI_IMAGE_RGB__ +#include "openni_image.h" +#include + +namespace openni_wrapper +{ + + /** + * @brief This class provides methods to fill a RGB or Grayscale image buffer from underlying RGB24 image. + * @author Suat Gedikli + * @date 19. June 2011 + * @ingroup io + */ + class PCL_EXPORTS ImageRGB24 : public Image + { + public: + + ImageRGB24 (boost::shared_ptr image_meta_data) throw (); + virtual ~ImageRGB24 () throw (); + + inline virtual Encoding + getEncoding () const + { + return (RGB); + } + + virtual void fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const; + virtual void fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const; + virtual bool isResizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const; + inline static bool resizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height); + } ; + + bool + ImageRGB24::resizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) + { + return (output_width <= input_width && output_height <= input_height && input_width % output_width == 0 && input_height % output_height == 0 ); + } + +} // namespace openni_wrapper + +#endif // __OPENNI_IMAGE_RGB__ +#endif // HAVE_OPENNI + diff --git a/pcl-1.7/pcl/io/openni_camera/openni_image_yuv_422.h b/pcl-1.7/pcl/io/openni_camera/openni_image_yuv_422.h new file mode 100644 index 0000000..e2622e3 --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni_image_yuv_422.h @@ -0,0 +1,79 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#include +#ifdef HAVE_OPENNI + +#ifndef __OPENNI_IMAGE_YUV422__ +#define __OPENNI_IMAGE_YUV422__ +#include +#include "openni_image.h" + +namespace openni_wrapper +{ + + /** + * @brief Concrete implementation of the interface Image for a YUV 422 image used by Primesense devices. + * @author Suat Gedikli + * @date 02.january 2011 + * @ingroup io + */ + class PCL_EXPORTS ImageYUV422 : public Image + { + public: + ImageYUV422 (boost::shared_ptr image_meta_data) throw (); + virtual ~ImageYUV422 () throw (); + + inline virtual Encoding + getEncoding () const + { + return (YUV422); + } + + virtual bool isResizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const; + virtual void fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const; + virtual void fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const; + inline static bool resizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height); + } ; + + bool + ImageYUV422::resizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) + { + return (output_width <= input_width && output_height <= input_height && input_width % output_width == 0 && input_height % output_height == 0); + } +} // namespace + +#endif +#endif // __OPENNI_IMAGE__ diff --git a/pcl-1.7/pcl/io/openni_camera/openni_ir_image.h b/pcl-1.7/pcl/io/openni_camera/openni_ir_image.h new file mode 100644 index 0000000..2c4945e --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni_ir_image.h @@ -0,0 +1,106 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011 Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef __OPENNI_IR_IMAGE__ +#define __OPENNI_IR_IMAGE__ + +#include +#include "openni.h" +#include "openni_exception.h" +#include + +namespace openni_wrapper +{ + +/** + * @brief Class containing just a reference to IR meta data. + * @author Patrick Mihelich , Suat Gedikli + */ +class PCL_EXPORTS IRImage +{ +public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + inline IRImage (boost::shared_ptr ir_meta_data) throw (); + inline virtual ~IRImage () throw (); + + void fillRaw (unsigned width, unsigned height, unsigned short* ir_buffer, unsigned line_step = 0) const; + + inline unsigned getWidth () const throw (); + inline unsigned getHeight () const throw (); + inline unsigned getFrameID () const throw (); + inline unsigned long getTimeStamp () const throw (); + inline const xn::IRMetaData& getMetaData () const throw (); + +protected: + boost::shared_ptr ir_md_; +}; + +IRImage::IRImage (boost::shared_ptr ir_meta_data) throw () +: ir_md_ (ir_meta_data) +{ +} + +IRImage::~IRImage () throw () +{ +} + +unsigned IRImage::getWidth () const throw () +{ + return ir_md_->XRes (); +} + +unsigned IRImage::getHeight () const throw () +{ + return ir_md_->YRes (); +} + +unsigned IRImage::getFrameID () const throw () +{ + return ir_md_->FrameID (); +} + +unsigned long IRImage::getTimeStamp () const throw () +{ + return static_cast (ir_md_->Timestamp ()); +} + +const xn::IRMetaData& IRImage::getMetaData () const throw () +{ + return *ir_md_; +} +} // namespace +#endif //__OPENNI_IR_IMAGE__ diff --git a/pcl-1.7/pcl/io/openni_camera/openni_shift_to_depth_conversion.h b/pcl-1.7/pcl/io/openni_camera/openni_shift_to_depth_conversion.h new file mode 100644 index 0000000..6290b5e --- /dev/null +++ b/pcl-1.7/pcl/io/openni_camera/openni_shift_to_depth_conversion.h @@ -0,0 +1,125 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011 Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#include +#ifdef HAVE_OPENNI + +#ifndef __OPENNI_SHIFT_TO_DEPTH_CONVERSION +#define __OPENNI_SHIFT_TO_DEPTH_CONVERSION + +#include +#include +#include + +namespace openni_wrapper +{ + /** \brief This class provides conversion of the openni 11-bit shift data to depth; + */ + class PCL_EXPORTS ShiftToDepthConverter + { + public: + /** \brief Constructor. */ + ShiftToDepthConverter () : init_(false) {} + + /** \brief Destructor. */ + virtual ~ShiftToDepthConverter () {}; + + /** \brief This method generates a look-up table to convert openni shift values to depth + */ + void + generateLookupTable () + { + // lookup of 11 bit shift values + const std::size_t table_size = 1<<10; + + lookupTable_.clear(); + lookupTable_.resize(table_size); + + // constants taken from openni driver + static const int16_t nConstShift = 800; + static const double nParamCoeff = 4.000000; + static const double dPlanePixelSize = 0.104200; + static const double nShiftScale = 10.000000; + static const double dPlaneDsr = 120.000000; + static const double dPlaneDcl = 7.500000; + + std::size_t i; + double dFixedRefX; + double dMetric; + + for (i=0; i(i - nConstShift) / nParamCoeff)-0.375; + dMetric = dFixedRefX * dPlanePixelSize; + lookupTable_[i] = static_cast((nShiftScale * ((dMetric * dPlaneDsr / (dPlaneDcl - dMetric)) + dPlaneDsr) ) / 1000.0f); + } + + init_ = true; + } + + /** \brief Generate a look-up table for converting openni shift values to depth + */ + inline float + shiftToDepth (uint16_t shift_val) + { + assert (init_); + + static const float bad_point = std::numeric_limits::quiet_NaN (); + + float ret = bad_point; + + // lookup depth value in shift lookup table + if (shift_val lookupTable_; + bool init_; + } ; +} + +#endif +#endif //__OPENNI_SHIFT_TO_DEPTH_CONVERSION diff --git a/pcl-1.7/pcl/io/openni_grabber.h b/pcl-1.7/pcl/io/openni_grabber.h new file mode 100644 index 0000000..03ba27a --- /dev/null +++ b/pcl-1.7/pcl/io/openni_grabber.h @@ -0,0 +1,507 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#include +#ifdef HAVE_OPENNI + +#ifndef __PCL_IO_OPENNI_GRABBER__ +#define __PCL_IO_OPENNI_GRABBER__ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + struct PointXYZ; + struct PointXYZRGB; + struct PointXYZRGBA; + struct PointXYZI; + template class PointCloud; + + /** \brief Grabber for OpenNI devices (i.e., Primesense PSDK, Microsoft Kinect, Asus XTion Pro/Live) + * \author Nico Blodow , Suat Gedikli + * \ingroup io + */ + class PCL_EXPORTS OpenNIGrabber : public Grabber + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef enum + { + OpenNI_Default_Mode = 0, // This can depend on the device. For now all devices (PSDK, Xtion, Kinect) its VGA@30Hz + OpenNI_SXGA_15Hz = 1, // Only supported by the Kinect + OpenNI_VGA_30Hz = 2, // Supported by PSDK, Xtion and Kinect + OpenNI_VGA_25Hz = 3, // Supportged by PSDK and Xtion + OpenNI_QVGA_25Hz = 4, // Supported by PSDK and Xtion + OpenNI_QVGA_30Hz = 5, // Supported by PSDK, Xtion and Kinect + OpenNI_QVGA_60Hz = 6, // Supported by PSDK and Xtion + OpenNI_QQVGA_25Hz = 7, // Not supported -> using software downsampling (only for integer scale factor and only NN) + OpenNI_QQVGA_30Hz = 8, // Not supported -> using software downsampling (only for integer scale factor and only NN) + OpenNI_QQVGA_60Hz = 9 // Not supported -> using software downsampling (only for integer scale factor and only NN) + } Mode; + + //define callback signature typedefs + typedef void (sig_cb_openni_image) (const boost::shared_ptr&); + typedef void (sig_cb_openni_depth_image) (const boost::shared_ptr&); + typedef void (sig_cb_openni_ir_image) (const boost::shared_ptr&); + typedef void (sig_cb_openni_image_depth_image) (const boost::shared_ptr&, const boost::shared_ptr&, float constant) ; + typedef void (sig_cb_openni_ir_depth_image) (const boost::shared_ptr&, const boost::shared_ptr&, float constant) ; + typedef void (sig_cb_openni_point_cloud) (const boost::shared_ptr >&); + typedef void (sig_cb_openni_point_cloud_rgb) (const boost::shared_ptr >&); + typedef void (sig_cb_openni_point_cloud_rgba) (const boost::shared_ptr >&); + typedef void (sig_cb_openni_point_cloud_i) (const boost::shared_ptr >&); + + public: + /** \brief Constructor + * \param[in] device_id ID of the device, which might be a serial number, bus\@address or the index of the device. + * \param[in] depth_mode the mode of the depth stream + * \param[in] image_mode the mode of the image stream + */ + OpenNIGrabber (const std::string& device_id = "", + const Mode& depth_mode = OpenNI_Default_Mode, + const Mode& image_mode = OpenNI_Default_Mode); + + /** \brief virtual Destructor inherited from the Grabber interface. It never throws. */ + virtual ~OpenNIGrabber () throw (); + + /** \brief Start the data acquisition. */ + virtual void + start (); + + /** \brief Stop the data acquisition. */ + virtual void + stop (); + + /** \brief Check if the data acquisition is still running. */ + virtual bool + isRunning () const; + + virtual std::string + getName () const; + + /** \brief Obtain the number of frames per second (FPS). */ + virtual float + getFramesPerSecond () const; + + /** \brief Get a boost shared pointer to the \ref pcl::openni_wrapper::OpenNIDevice object. */ + inline boost::shared_ptr + getDevice () const; + + /** \brief Obtain a list of the available depth modes that this device supports. */ + std::vector > + getAvailableDepthModes () const; + + /** \brief Obtain a list of the available image modes that this device supports. */ + std::vector > + getAvailableImageModes () const; + + /** \brief Set the RGB camera parameters (fx, fy, cx, cy) + * \param[in] rgb_focal_length_x the RGB focal length (fx) + * \param[in] rgb_focal_length_y the RGB focal length (fy) + * \param[in] rgb_principal_point_x the RGB principal point (cx) + * \param[in] rgb_principal_point_y the RGB principal point (cy) + * Setting the parameters to non-finite values (e.g., NaN, Inf) invalidates them + * and the grabber will use the default values from the camera instead. + */ + inline void + setRGBCameraIntrinsics (const double rgb_focal_length_x, + const double rgb_focal_length_y, + const double rgb_principal_point_x, + const double rgb_principal_point_y) + { + rgb_focal_length_x_ = rgb_focal_length_x; + rgb_focal_length_y_ = rgb_focal_length_y; + rgb_principal_point_x_ = rgb_principal_point_x; + rgb_principal_point_y_ = rgb_principal_point_y; + } + + /** \brief Get the RGB camera parameters (fx, fy, cx, cy) + * \param[out] rgb_focal_length_x the RGB focal length (fx) + * \param[out] rgb_focal_length_y the RGB focal length (fy) + * \param[out] rgb_principal_point_x the RGB principal point (cx) + * \param[out] rgb_principal_point_y the RGB principal point (cy) + */ + inline void + getRGBCameraIntrinsics (double &rgb_focal_length_x, + double &rgb_focal_length_y, + double &rgb_principal_point_x, + double &rgb_principal_point_y) const + { + rgb_focal_length_x = rgb_focal_length_x_; + rgb_focal_length_y = rgb_focal_length_y_; + rgb_principal_point_x = rgb_principal_point_x_; + rgb_principal_point_y = rgb_principal_point_y_; + } + + + /** \brief Set the RGB image focal length (fx = fy). + * \param[in] rgb_focal_length the RGB focal length (assumes fx = fy) + * Setting the parameter to a non-finite value (e.g., NaN, Inf) invalidates it + * and the grabber will use the default values from the camera instead. + * These parameters will be used for XYZRGBA clouds. + */ + inline void + setRGBFocalLength (const double rgb_focal_length) + { + rgb_focal_length_x_ = rgb_focal_length_y_ = rgb_focal_length; + } + + /** \brief Set the RGB image focal length + * \param[in] rgb_focal_length_x the RGB focal length (fx) + * \param[in] rgb_focal_length_y the RGB focal length (fy) + * Setting the parameters to non-finite values (e.g., NaN, Inf) invalidates them + * and the grabber will use the default values from the camera instead. + * These parameters will be used for XYZRGBA clouds. + */ + inline void + setRGBFocalLength (const double rgb_focal_length_x, const double rgb_focal_length_y) + { + rgb_focal_length_x_ = rgb_focal_length_x; + rgb_focal_length_y_ = rgb_focal_length_y; + } + + /** \brief Return the RGB focal length parameters (fx, fy) + * \param[out] rgb_focal_length_x the RGB focal length (fx) + * \param[out] rgb_focal_length_y the RGB focal length (fy) + */ + inline void + getRGBFocalLength (double &rgb_focal_length_x, double &rgb_focal_length_y) const + { + rgb_focal_length_x = rgb_focal_length_x_; + rgb_focal_length_y = rgb_focal_length_y_; + } + + /** \brief Set the Depth camera parameters (fx, fy, cx, cy) + * \param[in] depth_focal_length_x the Depth focal length (fx) + * \param[in] depth_focal_length_y the Depth focal length (fy) + * \param[in] depth_principal_point_x the Depth principal point (cx) + * \param[in] depth_principal_point_y the Depth principal point (cy) + * Setting the parameters to non-finite values (e.g., NaN, Inf) invalidates them + * and the grabber will use the default values from the camera instead. + */ + inline void + setDepthCameraIntrinsics (const double depth_focal_length_x, + const double depth_focal_length_y, + const double depth_principal_point_x, + const double depth_principal_point_y) + { + depth_focal_length_x_ = depth_focal_length_x; + depth_focal_length_y_ = depth_focal_length_y; + depth_principal_point_x_ = depth_principal_point_x; + depth_principal_point_y_ = depth_principal_point_y; + } + + /** \brief Get the Depth camera parameters (fx, fy, cx, cy) + * \param[out] depth_focal_length_x the Depth focal length (fx) + * \param[out] depth_focal_length_y the Depth focal length (fy) + * \param[out] depth_principal_point_x the Depth principal point (cx) + * \param[out] depth_principal_point_y the Depth principal point (cy) + */ + inline void + getDepthCameraIntrinsics (double &depth_focal_length_x, + double &depth_focal_length_y, + double &depth_principal_point_x, + double &depth_principal_point_y) const + { + depth_focal_length_x = depth_focal_length_x_; + depth_focal_length_y = depth_focal_length_y_; + depth_principal_point_x = depth_principal_point_x_; + depth_principal_point_y = depth_principal_point_y_; + } + + /** \brief Set the Depth image focal length (fx = fy). + * \param[in] depth_focal_length the Depth focal length (assumes fx = fy) + * Setting the parameter to a non-finite value (e.g., NaN, Inf) invalidates it + * and the grabber will use the default values from the camera instead. + */ + inline void + setDepthFocalLength (const double depth_focal_length) + { + depth_focal_length_x_ = depth_focal_length_y_ = depth_focal_length; + } + + + /** \brief Set the Depth image focal length + * \param[in] depth_focal_length_x the Depth focal length (fx) + * \param[in] depth_focal_length_y the Depth focal length (fy) + * Setting the parameter to non-finite values (e.g., NaN, Inf) invalidates them + * and the grabber will use the default values from the camera instead. + */ + inline void + setDepthFocalLength (const double depth_focal_length_x, const double depth_focal_length_y) + { + depth_focal_length_x_ = depth_focal_length_x; + depth_focal_length_y_ = depth_focal_length_y; + } + + /** \brief Return the Depth focal length parameters (fx, fy) + * \param[out] depth_focal_length_x the Depth focal length (fx) + * \param[out] depth_focal_length_y the Depth focal length (fy) + */ + inline void + getDepthFocalLength (double &depth_focal_length_x, double &depth_focal_length_y) const + { + depth_focal_length_x = depth_focal_length_x_; + depth_focal_length_y = depth_focal_length_y_; + } + + /** \brief Convert vector of raw shift values to depth values + * \param[in] shift_data_ptr input shift data + * \param[out] depth_data_ptr generated depth data + * \param[in] size of shift and depth buffer + */ + inline void + convertShiftToDepth ( + const uint16_t* shift_data_ptr, + uint16_t* depth_data_ptr, + std::size_t size) const + { + // get openni device instance + boost::shared_ptr openni_device = + this->getDevice (); + + const uint16_t* shift_data_it = shift_data_ptr; + uint16_t* depth_data_it = depth_data_ptr; + + // shift-to-depth lookup + for (std::size_t i=0; ishiftToDepth(*shift_data_it); + + shift_data_it++; + depth_data_it++; + } + + } + + + protected: + /** \brief On initialization processing. */ + void + onInit (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode); + + /** \brief Sets up an OpenNI device. */ + void + setupDevice (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode); + + /** \brief Update mode maps. */ + void + updateModeMaps (); + + /** \brief Start synchronization. */ + void + startSynchronization (); + + /** \brief Stop synchronization. */ + void + stopSynchronization (); + + /** \brief Map config modes. */ + bool + mapConfigMode2XnMode (int mode, XnMapOutputMode &xnmode) const; + + // callback methods + /** \brief RGB image callback. */ + virtual void + imageCallback (boost::shared_ptr image, void* cookie); + + /** \brief Depth image callback. */ + virtual void + depthCallback (boost::shared_ptr depth_image, void* cookie); + + /** \brief IR image callback. */ + virtual void + irCallback (boost::shared_ptr ir_image, void* cookie); + + /** \brief RGB + Depth image callback. */ + virtual void + imageDepthImageCallback (const boost::shared_ptr &image, + const boost::shared_ptr &depth_image); + + /** \brief IR + Depth image callback. */ + virtual void + irDepthImageCallback (const boost::shared_ptr &image, + const boost::shared_ptr &depth_image); + + /** \brief Process changed signals. */ + virtual void + signalsChanged (); + + // helper methods + + /** \brief Check if the RGB and Depth images are required to be synchronized or not. */ + virtual void + checkImageAndDepthSynchronizationRequired (); + + /** \brief Check if the RGB image stream is required or not. */ + virtual void + checkImageStreamRequired (); + + /** \brief Check if the depth stream is required or not. */ + virtual void + checkDepthStreamRequired (); + + /** \brief Check if the IR image stream is required or not. */ + virtual void + checkIRStreamRequired (); + + + /** \brief Convert a Depth image to a pcl::PointCloud + * \param[in] depth the depth image to convert + */ + boost::shared_ptr > + convertToXYZPointCloud (const boost::shared_ptr &depth) const; + + /** \brief Convert a Depth + RGB image pair to a pcl::PointCloud + * \param[in] image the RGB image to convert + * \param[in] depth_image the depth image to convert + */ + template typename pcl::PointCloud::Ptr + convertToXYZRGBPointCloud (const boost::shared_ptr &image, + const boost::shared_ptr &depth_image) const; + + /** \brief Convert a Depth + Intensity image pair to a pcl::PointCloud + * \param[in] image the IR image to convert + * \param[in] depth_image the depth image to convert + */ + boost::shared_ptr > + convertToXYZIPointCloud (const boost::shared_ptr &image, + const boost::shared_ptr &depth_image) const; + + + Synchronizer, boost::shared_ptr > rgb_sync_; + Synchronizer, boost::shared_ptr > ir_sync_; + + /** \brief The actual openni device. */ + boost::shared_ptr device_; + + std::string rgb_frame_id_; + std::string depth_frame_id_; + unsigned image_width_; + unsigned image_height_; + unsigned depth_width_; + unsigned depth_height_; + + bool image_required_; + bool depth_required_; + bool ir_required_; + bool sync_required_; + + boost::signals2::signal* image_signal_; + boost::signals2::signal* depth_image_signal_; + boost::signals2::signal* ir_image_signal_; + boost::signals2::signal* image_depth_image_signal_; + boost::signals2::signal* ir_depth_image_signal_; + boost::signals2::signal* point_cloud_signal_; + boost::signals2::signal* point_cloud_i_signal_; + boost::signals2::signal* point_cloud_rgb_signal_; + boost::signals2::signal* point_cloud_rgba_signal_; + + struct modeComp + { + + bool operator () (const XnMapOutputMode& mode1, const XnMapOutputMode & mode2) const + { + if (mode1.nXRes < mode2.nXRes) + return true; + else if (mode1.nXRes > mode2.nXRes) + return false; + else if (mode1.nYRes < mode2.nYRes) + return true; + else if (mode1.nYRes > mode2.nYRes) + return false; + else if (mode1.nFPS < mode2.nFPS) + return true; + else + return false; + } + } ; + std::map config2xn_map_; + + openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle; + openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle; + openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle; + bool running_; + + mutable unsigned rgb_array_size_; + mutable unsigned depth_buffer_size_; + mutable boost::shared_array rgb_array_; + mutable boost::shared_array depth_buffer_; + mutable boost::shared_array ir_buffer_; + + /** \brief The RGB image focal length (fx). */ + double rgb_focal_length_x_; + /** \brief The RGB image focal length (fy). */ + double rgb_focal_length_y_; + /** \brief The RGB image principal point (cx). */ + double rgb_principal_point_x_; + /** \brief The RGB image principal point (cy). */ + double rgb_principal_point_y_; + /** \brief The depth image focal length (fx). */ + double depth_focal_length_x_; + /** \brief The depth image focal length (fy). */ + double depth_focal_length_y_; + /** \brief The depth image principal point (cx). */ + double depth_principal_point_x_; + /** \brief The depth image principal point (cy). */ + double depth_principal_point_y_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + boost::shared_ptr + OpenNIGrabber::getDevice () const + { + return device_; + } + +} // namespace pcl +#endif // __PCL_IO_OPENNI_GRABBER__ +#endif // HAVE_OPENNI diff --git a/pcl-1.7/pcl/io/pcd_grabber.h b/pcl-1.7/pcl/io/pcd_grabber.h new file mode 100644 index 0000000..9dc4737 --- /dev/null +++ b/pcl-1.7/pcl/io/pcd_grabber.h @@ -0,0 +1,302 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#include + +#ifndef PCL_IO_PCD_GRABBER_H_ +#define PCL_IO_PCD_GRABBER_H_ + +#include +#include +#include +#include +#include +#include +#include + +#ifdef HAVE_OPENNI +#include +#include +#include +#endif + +namespace pcl +{ + /** \brief Base class for PCD file grabber. + * \ingroup io + */ + class PCL_EXPORTS PCDGrabberBase : public Grabber + { + public: + /** \brief Constructor taking just one PCD file or one TAR file containing multiple PCD files. + * \param[in] pcd_file path to the PCD file + * \param[in] frames_per_second frames per second. If 0, start() functions like a trigger, publishing the next PCD in the list. + * \param[in] repeat whether to play PCD file in an endless loop or not. + */ + PCDGrabberBase (const std::string& pcd_file, float frames_per_second, bool repeat); + + /** \brief Constructor taking a list of paths to PCD files, that are played in the order they appear in the list. + * \param[in] pcd_files vector of paths to PCD files. + * \param[in] frames_per_second frames per second. If 0, start() functions like a trigger, publishing the next PCD in the list. + * \param[in] repeat whether to play PCD file in an endless loop or not. + */ + PCDGrabberBase (const std::vector& pcd_files, float frames_per_second, bool repeat); + + /** \brief Copy constructor. + * \param[in] src the PCD Grabber base object to copy into this + */ + PCDGrabberBase (const PCDGrabberBase &src) : Grabber (), impl_ () + { + *this = src; + } + + /** \brief Copy operator. + * \param[in] src the PCD Grabber base object to copy into this + */ + PCDGrabberBase& + operator = (const PCDGrabberBase &src) + { + impl_ = src.impl_; + return (*this); + } + + /** \brief Virtual destructor. */ + virtual ~PCDGrabberBase () throw (); + + /** \brief Starts playing the list of PCD files if frames_per_second is > 0. Otherwise it works as a trigger: publishes only the next PCD file in the list. */ + virtual void + start (); + + /** \brief Stops playing the list of PCD files if frames_per_second is > 0. Otherwise the method has no effect. */ + virtual void + stop (); + + /** \brief Triggers a callback with new data */ + virtual void + trigger (); + + /** \brief Indicates whether the grabber is streaming or not. + * \return true if grabber is started and hasn't run out of PCD files. + */ + virtual bool + isRunning () const; + + /** \return The name of the grabber */ + virtual std::string + getName () const; + + /** \brief Rewinds to the first PCD file in the list.*/ + virtual void + rewind (); + + /** \brief Returns the frames_per_second. 0 if grabber is trigger-based */ + virtual float + getFramesPerSecond () const; + + /** \brief Returns whether the repeat flag is on */ + bool + isRepeatOn () const; + + /** \brief Get cloud (in ROS form) at a particular location */ + bool + getCloudAt (size_t idx, + pcl::PCLPointCloud2 &blob, + Eigen::Vector4f &origin, + Eigen::Quaternionf &orientation) const; + + /** \brief Returns the size */ + size_t + numFrames () const; + + private: + virtual void + publish (const pcl::PCLPointCloud2& blob, const Eigen::Vector4f& origin, const Eigen::Quaternionf& orientation) const = 0; + + // to separate and hide the implementation from interface: PIMPL + struct PCDGrabberImpl; + PCDGrabberImpl* impl_; + }; + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template class PointCloud; + template class PCDGrabber : public PCDGrabberBase, public FileGrabber + { + public: + PCDGrabber (const std::string& pcd_path, float frames_per_second = 0, bool repeat = false); + PCDGrabber (const std::vector& pcd_files, float frames_per_second = 0, bool repeat = false); + + /** \brief Virtual destructor. */ + virtual ~PCDGrabber () throw () {} + + // Inherited from FileGrabber + const boost::shared_ptr< const pcl::PointCloud > + operator[] (size_t idx) const; + + // Inherited from FileGrabber + size_t + size () const; + protected: + + virtual void + publish (const pcl::PCLPointCloud2& blob, const Eigen::Vector4f& origin, const Eigen::Quaternionf& orientation) const; + + boost::signals2::signal >&)>* signal_; + +#ifdef HAVE_OPENNI + boost::signals2::signal&)>* depth_image_signal_; + boost::signals2::signal&)>* image_signal_; + boost::signals2::signal&, const boost::shared_ptr&, float constant)>* image_depth_image_signal_; +#endif + }; + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template + PCDGrabber::PCDGrabber (const std::string& pcd_path, float frames_per_second, bool repeat) + : PCDGrabberBase (pcd_path, frames_per_second, repeat) + { + signal_ = createSignal >&)>(); +#ifdef HAVE_OPENNI + depth_image_signal_ = createSignal &)> (); + image_signal_ = createSignal &)> (); + image_depth_image_signal_ = createSignal &, const boost::shared_ptr&, float constant)> (); +#endif + } + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template + PCDGrabber::PCDGrabber (const std::vector& pcd_files, float frames_per_second, bool repeat) + : PCDGrabberBase (pcd_files, frames_per_second, repeat), signal_ () + { + signal_ = createSignal >&)>(); +#ifdef HAVE_OPENNI + depth_image_signal_ = createSignal &)> (); + image_signal_ = createSignal &)> (); + image_depth_image_signal_ = createSignal &, const boost::shared_ptr&, float constant)> (); +#endif + } + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template const boost::shared_ptr< const pcl::PointCloud > + PCDGrabber::operator[] (size_t idx) const + { + pcl::PCLPointCloud2 blob; + Eigen::Vector4f origin; + Eigen::Quaternionf orientation; + getCloudAt (idx, blob, origin, orientation); + typename pcl::PointCloud::Ptr cloud (new pcl::PointCloud ()); + pcl::fromPCLPointCloud2 (blob, *cloud); + cloud->sensor_origin_ = origin; + cloud->sensor_orientation_ = orientation; + return (cloud); + } + + /////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template size_t + PCDGrabber::size () const + { + return (numFrames ()); + } + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template void + PCDGrabber::publish (const pcl::PCLPointCloud2& blob, const Eigen::Vector4f& origin, const Eigen::Quaternionf& orientation) const + { + typename pcl::PointCloud::Ptr cloud (new pcl::PointCloud ()); + pcl::fromPCLPointCloud2 (blob, *cloud); + cloud->sensor_origin_ = origin; + cloud->sensor_orientation_ = orientation; + + signal_->operator () (cloud); + +#ifdef HAVE_OPENNI + // If dataset is not organized, return + if (!cloud->isOrganized ()) + return; + + boost::shared_ptr depth_meta_data (new xn::DepthMetaData); + depth_meta_data->AllocateData (cloud->width, cloud->height); + XnDepthPixel* depth_map = depth_meta_data->WritableData (); + uint32_t k = 0; + for (uint32_t i = 0; i < cloud->height; ++i) + for (uint32_t j = 0; j < cloud->width; ++j) + { + depth_map[k] = static_cast ((*cloud)[k].z * 1000); + ++k; + } + + boost::shared_ptr depth_image (new openni_wrapper::DepthImage (depth_meta_data, 0.075f, 525, 0, 0)); + if (depth_image_signal_->num_slots() > 0) + depth_image_signal_->operator()(depth_image); + + // ---[ RGB special case + std::vector fields; + int rgba_index = pcl::getFieldIndex (*cloud, "rgb", fields); + if (rgba_index == -1) + rgba_index = pcl::getFieldIndex (*cloud, "rgba", fields); + if (rgba_index >= 0) + { + rgba_index = fields[rgba_index].offset; + + boost::shared_ptr image_meta_data (new xn::ImageMetaData); + image_meta_data->AllocateData (cloud->width, cloud->height, XN_PIXEL_FORMAT_RGB24); + XnRGB24Pixel* image_map = image_meta_data->WritableRGB24Data (); + k = 0; + for (uint32_t i = 0; i < cloud->height; ++i) + { + for (uint32_t j = 0; j < cloud->width; ++j) + { + // Fill r/g/b data, assuming that the order is BGRA + pcl::RGB rgb; + memcpy (&rgb, reinterpret_cast (&cloud->points[k]) + rgba_index, sizeof (RGB)); + image_map[k].nRed = static_cast (rgb.r); + image_map[k].nGreen = static_cast (rgb.g); + image_map[k].nBlue = static_cast (rgb.b); + ++k; + } + } + + boost::shared_ptr image (new openni_wrapper::ImageRGB24 (image_meta_data)); + if (image_signal_->num_slots() > 0) + image_signal_->operator()(image); + + if (image_depth_image_signal_->num_slots() > 0) + image_depth_image_signal_->operator()(image, depth_image, 1.0f / 525.0f); + } +#endif + } +} +#endif diff --git a/pcl-1.7/pcl/io/pcd_io.h b/pcl-1.7/pcl/io/pcd_io.h new file mode 100644 index 0000000..25e54c8 --- /dev/null +++ b/pcl-1.7/pcl/io/pcd_io.h @@ -0,0 +1,682 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_IO_PCD_IO_H_ +#define PCL_IO_PCD_IO_H_ + +#include +#include + +namespace pcl +{ + /** \brief Point Cloud Data (PCD) file format reader. + * \author Radu B. Rusu + * \ingroup io + */ + class PCL_EXPORTS PCDReader : public FileReader + { + public: + /** Empty constructor */ + PCDReader () : FileReader () {} + /** Empty destructor */ + ~PCDReader () {} + + /** \brief Various PCD file versions. + * + * PCD_V6 represents PCD files with version 0.6, which contain the following fields: + * - lines beginning with # are treated as comments + * - FIELDS ... + * - SIZE ... + * - TYPE ... + * - COUNT ... + * - WIDTH ... + * - HEIGHT ... + * - POINTS ... + * - DATA ascii/binary + * + * Everything that follows \b DATA is intepreted as data points and + * will be read accordingly. + * + * PCD_V7 represents PCD files with version 0.7 and has an important + * addon: it adds sensor origin/orientation (aka viewpoint) information + * to a dataset through the use of a new header field: + * - VIEWPOINT tx ty tz qw qx qy qz + */ + enum + { + PCD_V6 = 0, + PCD_V7 = 1 + }; + + /** \brief Read a point cloud data header from a PCD file. + * + * Load only the meta information (number of points, their types, etc), + * and not the points themselves, from a given PCD file. Useful for fast + * evaluation of the underlying data structure. + * + * \attention The PCD data is \b always stored in ROW major format! The + * read/write PCD methods will detect column major input and automatically convert it. + * + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant point cloud dataset (only the header will be filled) + * \param[out] origin the sensor acquisition origin (only for > PCD_V7 - null if not present) + * \param[out] orientation the sensor acquisition orientation (only for > PCD_V7 - identity if not present) + * \param[out] pcd_version the PCD version of the file (i.e., PCD_V6, PCD_V7) + * \param[out] data_type the type of data (0 = ASCII, 1 = Binary, 2 = Binary compressed) + * \param[out] data_idx the offset of cloud data within the file + * \param[in] offset the offset of where to expect the PCD Header in the + * file (optional parameter). One usage example for setting the offset + * parameter is for reading data from a TAR "archive containing multiple + * PCD files: TAR files always add a 512 byte header in front of the + * actual file, so set the offset to the next byte after the header + * (e.g., 513). + * + * \return + * * < 0 (-1) on error + * * == 0 on success + */ + int + readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version, + int &data_type, unsigned int &data_idx, const int offset = 0); + + + /** \brief Read a point cloud data header from a PCD file. + * + * Load only the meta information (number of points, their types, etc), + * and not the points themselves, from a given PCD file. Useful for fast + * evaluation of the underlying data structure. + * + * \attention The PCD data is \b always stored in ROW major format! The + * read/write PCD methods will detect column major input and automatically convert it. + * + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant point cloud dataset (only the header will be filled) + * \param[in] offset the offset of where to expect the PCD Header in the + * file (optional parameter). One usage example for setting the offset + * parameter is for reading data from a TAR "archive containing multiple + * PCD files: TAR files always add a 512 byte header in front of the + * actual file, so set the offset to the next byte after the header + * (e.g., 513). + * + * \return + * * < 0 (-1) on error + * * == 0 on success + */ + int + readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud, const int offset = 0); + + /** \brief Read a point cloud data from a PCD file and store it into a pcl/PCLPointCloud2. + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * \param[out] origin the sensor acquisition origin (only for > PCD_V7 - null if not present) + * \param[out] orientation the sensor acquisition orientation (only for > PCD_V7 - identity if not present) + * \param[out] pcd_version the PCD version of the file (either PCD_V6 or PCD_V7) + * \param[in] offset the offset of where to expect the PCD Header in the + * file (optional parameter). One usage example for setting the offset + * parameter is for reading data from a TAR "archive containing multiple + * PCD files: TAR files always add a 512 byte header in front of the + * actual file, so set the offset to the next byte after the header + * (e.g., 513). + * + * \return + * * < 0 (-1) on error + * * == 0 on success + */ + int + read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version, const int offset = 0); + + /** \brief Read a point cloud data from a PCD (PCD_V6) and store it into a pcl/PCLPointCloud2. + * + * \note This function is provided for backwards compatibility only and + * it can only read PCD_V6 files correctly, as pcl::PCLPointCloud2 + * does not contain a sensor origin/orientation. Reading any file + * > PCD_V6 will generate a warning. + * + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * \param[in] offset the offset of where to expect the PCD Header in the + * file (optional parameter). One usage example for setting the offset + * parameter is for reading data from a TAR "archive containing multiple + * PCD files: TAR files always add a 512 byte header in front of the + * actual file, so set the offset to the next byte after the header + * (e.g., 513). + * + * \return + * * < 0 (-1) on error + * * == 0 on success + */ + int + read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, const int offset = 0); + + /** \brief Read a point cloud data from any PCD file, and convert it to the given template format. + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * \param[in] offset the offset of where to expect the PCD Header in the + * file (optional parameter). One usage example for setting the offset + * parameter is for reading data from a TAR "archive containing multiple + * PCD files: TAR files always add a 512 byte header in front of the + * actual file, so set the offset to the next byte after the header + * (e.g., 513). + * + * \return + * * < 0 (-1) on error + * * == 0 on success + */ + template int + read (const std::string &file_name, pcl::PointCloud &cloud, const int offset = 0) + { + pcl::PCLPointCloud2 blob; + int pcd_version; + int res = read (file_name, blob, cloud.sensor_origin_, cloud.sensor_orientation_, + pcd_version, offset); + + // If no error, convert the data + if (res == 0) + pcl::fromPCLPointCloud2 (blob, cloud); + return (res); + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + /** \brief Point Cloud Data (PCD) file format writer. + * \author Radu Bogdan Rusu + * \ingroup io + */ + class PCL_EXPORTS PCDWriter : public FileWriter + { + public: + PCDWriter() : FileWriter(), map_synchronization_(false) {} + ~PCDWriter() {} + + /** \brief Set whether mmap() synchornization via msync() is desired before munmap() calls. + * Setting this to true could prevent NFS data loss (see + * http://www.pcl-developers.org/PCD-IO-consistency-on-NFS-msync-needed-td4885942.html). + * Default: false + * \note This option should be used by advanced users only! + * \note Please note that using msync() on certain systems can reduce the I/O performance by up to 80%! + * \param[in] sync set to true if msync() should be called before munmap() + */ + void + setMapSynchronization (bool sync) + { + map_synchronization_ = sync; + } + + /** \brief Generate the header of a PCD file format + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + */ + std::string + generateHeaderBinary (const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin, + const Eigen::Quaternionf &orientation); + + /** \brief Generate the header of a BINARY_COMPRESSED PCD file format + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + */ + std::string + generateHeaderBinaryCompressed (const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin, + const Eigen::Quaternionf &orientation); + + /** \brief Generate the header of a PCD file format + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + */ + std::string + generateHeaderASCII (const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin, + const Eigen::Quaternionf &orientation); + + /** \brief Generate the header of a PCD file format + * \param[in] cloud the point cloud data message + * \param[in] nr_points if given, use this to fill in WIDTH, HEIGHT (=1), and POINTS in the header + * By default, nr_points is set to INTMAX, and the data in the header is used instead. + */ + template static std::string + generateHeader (const pcl::PointCloud &cloud, + const int nr_points = std::numeric_limits::max ()); + + /** \brief Save point cloud data to a PCD file containing n-D points, in ASCII format + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + * \param[in] precision the specified output numeric stream precision (default: 8) + * + * Caution: PointCloud structures containing an RGB field have + * traditionally used packed float values to store RGB data. Storing a + * float as ASCII can introduce variations to the smallest bits, and + * thus significantly alter the data. This is a known issue, and the fix + * involves switching RGB data to be stored as a packed integer in + * future versions of PCL. + * + * As an intermediary solution, precision 8 is used, which guarantees lossless storage for RGB. + */ + int + writeASCII (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), + const int precision = 8); + + /** \brief Save point cloud data to a PCD file containing n-D points, in BINARY format + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + */ + int + writeBinary (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity ()); + + /** \brief Save point cloud data to a PCD file containing n-D points, in BINARY_COMPRESSED format + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + */ + int + writeBinaryCompressed (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity ()); + + /** \brief Save point cloud data to a PCD file containing n-D points + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + * \param[in] binary set to true if the file is to be written in a binary + * PCD format, false (default) for ASCII + * + * Caution: PointCloud structures containing an RGB field have + * traditionally used packed float values to store RGB data. Storing a + * float as ASCII can introduce variations to the smallest bits, and + * thus significantly alter the data. This is a known issue, and the fix + * involves switching RGB data to be stored as a packed integer in + * future versions of PCL. + * + * As an intermediary solution, precision 8 is used, which guarantees lossless storage for RGB. + */ + inline int + write (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), + const bool binary = false) + { + if (binary) + return (writeBinary (file_name, cloud, origin, orientation)); + else + return (writeASCII (file_name, cloud, origin, orientation, 8)); + } + + /** \brief Save point cloud data to a PCD file containing n-D points + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message (boost shared pointer) + * \param[in] binary set to true if the file is to be written in a binary PCD format, + * false (default) for ASCII + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + * + * Caution: PointCloud structures containing an RGB field have + * traditionally used packed float values to store RGB data. Storing a + * float as ASCII can introduce variations to the smallest bits, and + * thus significantly alter the data. This is a known issue, and the fix + * involves switching RGB data to be stored as a packed integer in + * future versions of PCL. + */ + inline int + write (const std::string &file_name, const pcl::PCLPointCloud2::ConstPtr &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), + const bool binary = false) + { + return (write (file_name, *cloud, origin, orientation, binary)); + } + + /** \brief Save point cloud data to a PCD file containing n-D points, in BINARY format + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + */ + template int + writeBinary (const std::string &file_name, + const pcl::PointCloud &cloud); + + /** \brief Save point cloud data to a binary comprssed PCD file + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + */ + template int + writeBinaryCompressed (const std::string &file_name, + const pcl::PointCloud &cloud); + + /** \brief Save point cloud data to a PCD file containing n-D points, in BINARY format + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] indices the set of point indices that we want written to disk + */ + template int + writeBinary (const std::string &file_name, + const pcl::PointCloud &cloud, + const std::vector &indices); + + /** \brief Save point cloud data to a PCD file containing n-D points, in ASCII format + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] precision the specified output numeric stream precision (default: 8) + */ + template int + writeASCII (const std::string &file_name, + const pcl::PointCloud &cloud, + const int precision = 8); + + /** \brief Save point cloud data to a PCD file containing n-D points, in ASCII format + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] indices the set of point indices that we want written to disk + * \param[in] precision the specified output numeric stream precision (default: 8) + */ + template int + writeASCII (const std::string &file_name, + const pcl::PointCloud &cloud, + const std::vector &indices, + const int precision = 8); + + /** \brief Save point cloud data to a PCD file containing n-D points + * \param[in] file_name the output file name + * \param[in] cloud the pcl::PointCloud data + * \param[in] binary set to true if the file is to be written in a binary + * PCD format, false (default) for ASCII + * + * Caution: PointCloud structures containing an RGB field have + * traditionally used packed float values to store RGB data. Storing a + * float as ASCII can introduce variations to the smallest bits, and + * thus significantly alter the data. This is a known issue, and the fix + * involves switching RGB data to be stored as a packed integer in + * future versions of PCL. + */ + template inline int + write (const std::string &file_name, + const pcl::PointCloud &cloud, + const bool binary = false) + { + if (binary) + return (writeBinary (file_name, cloud)); + else + return (writeASCII (file_name, cloud)); + } + + /** \brief Save point cloud data to a PCD file containing n-D points + * \param[in] file_name the output file name + * \param[in] cloud the pcl::PointCloud data + * \param[in] indices the set of point indices that we want written to disk + * \param[in] binary set to true if the file is to be written in a binary + * PCD format, false (default) for ASCII + * + * Caution: PointCloud structures containing an RGB field have + * traditionally used packed float values to store RGB data. Storing a + * float as ASCII can introduce variations to the smallest bits, and + * thus significantly alter the data. This is a known issue, and the fix + * involves switching RGB data to be stored as a packed integer in + * future versions of PCL. + */ + template inline int + write (const std::string &file_name, + const pcl::PointCloud &cloud, + const std::vector &indices, + bool binary = false) + { + if (binary) + return (writeBinary (file_name, cloud, indices)); + else + return (writeASCII (file_name, cloud, indices)); + } + + protected: + /** \brief Set permissions for file locking (Boost 1.49+). + * \param[in] file_name the file name to set permission for file locking + * \param[in,out] lock the file lock + */ + void + setLockingPermissions (const std::string &file_name, + boost::interprocess::file_lock &lock); + + /** \brief Reset permissions for file locking (Boost 1.49+). + * \param[in] file_name the file name to reset permission for file locking + * \param[in,out] lock the file lock + */ + void + resetLockingPermissions (const std::string &file_name, + boost::interprocess::file_lock &lock); + + private: + /** \brief Set to true if msync() should be called before munmap(). Prevents data loss on NFS systems. */ + bool map_synchronization_; + }; + + namespace io + { + /** \brief Load a PCD v.6 file into a templated PointCloud type. + * + * Any PCD files > v.6 will generate a warning as a + * pcl/PCLPointCloud2 message cannot hold the sensor origin. + * + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant templated point cloud + * \ingroup io + */ + inline int + loadPCDFile (const std::string &file_name, pcl::PCLPointCloud2 &cloud) + { + pcl::PCDReader p; + return (p.read (file_name, cloud)); + } + + /** \brief Load any PCD file into a templated PointCloud type. + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant templated point cloud + * \param[out] origin the sensor acquisition origin (only for > PCD_V7 - null if not present) + * \param[out] orientation the sensor acquisition orientation (only for > + * PCD_V7 - identity if not present) + * \ingroup io + */ + inline int + loadPCDFile (const std::string &file_name, pcl::PCLPointCloud2 &cloud, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation) + { + pcl::PCDReader p; + int pcd_version; + return (p.read (file_name, cloud, origin, orientation, pcd_version)); + } + + /** \brief Load any PCD file into a templated PointCloud type + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant templated point cloud + * \ingroup io + */ + template inline int + loadPCDFile (const std::string &file_name, pcl::PointCloud &cloud) + { + pcl::PCDReader p; + return (p.read (file_name, cloud)); + } + + /** \brief Save point cloud data to a PCD file containing n-D points + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + * \param[in] binary_mode true for binary mode, false (default) for ASCII + * + * Caution: PointCloud structures containing an RGB field have + * traditionally used packed float values to store RGB data. Storing a + * float as ASCII can introduce variations to the smallest bits, and + * thus significantly alter the data. This is a known issue, and the fix + * involves switching RGB data to be stored as a packed integer in + * future versions of PCL. + * \ingroup io + */ + inline int + savePCDFile (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), + const bool binary_mode = false) + { + PCDWriter w; + return (w.write (file_name, cloud, origin, orientation, binary_mode)); + } + + /** \brief Templated version for saving point cloud data to a PCD file + * containing a specific given cloud format + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] binary_mode true for binary mode, false (default) for ASCII + * + * Caution: PointCloud structures containing an RGB field have + * traditionally used packed float values to store RGB data. Storing a + * float as ASCII can introduce variations to the smallest bits, and + * thus significantly alter the data. This is a known issue, and the fix + * involves switching RGB data to be stored as a packed integer in + * future versions of PCL. + * \ingroup io + */ + template inline int + savePCDFile (const std::string &file_name, const pcl::PointCloud &cloud, bool binary_mode = false) + { + PCDWriter w; + return (w.write (file_name, cloud, binary_mode)); + } + + /** + * \brief Templated version for saving point cloud data to a PCD file + * containing a specific given cloud format. + * + * This version is to retain backwards compatibility. + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * + * Caution: PointCloud structures containing an RGB field have + * traditionally used packed float values to store RGB data. Storing a + * float as ASCII can introduce variations to the smallest bits, and + * thus significantly alter the data. This is a known issue, and the fix + * involves switching RGB data to be stored as a packed integer in + * future versions of PCL. + * \ingroup io + */ + template inline int + savePCDFileASCII (const std::string &file_name, const pcl::PointCloud &cloud) + { + PCDWriter w; + return (w.write (file_name, cloud, false)); + } + + /** + * \brief Templated version for saving point cloud data to a PCD file + * containing a specific given cloud format. The resulting file will be an uncompressed binary. + * + * This version is to retain backwards compatibility. + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \ingroup io + */ + template inline int + savePCDFileBinary (const std::string &file_name, const pcl::PointCloud &cloud) + { + PCDWriter w; + return (w.write (file_name, cloud, true)); + } + + /** + * \brief Templated version for saving point cloud data to a PCD file + * containing a specific given cloud format + * + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] indices the set of indices to save + * \param[in] binary_mode true for binary mode, false (default) for ASCII + * + * Caution: PointCloud structures containing an RGB field have + * traditionally used packed float values to store RGB data. Storing a + * float as ASCII can introduce variations to the smallest bits, and + * thus significantly alter the data. This is a known issue, and the fix + * involves switching RGB data to be stored as a packed integer in + * future versions of PCL. + * \ingroup io + */ + template int + savePCDFile (const std::string &file_name, + const pcl::PointCloud &cloud, + const std::vector &indices, + const bool binary_mode = false) + { + // Save the data + PCDWriter w; + return (w.write (file_name, cloud, indices, binary_mode)); + } + + + /** + * \brief Templated version for saving point cloud data to a PCD file + * containing a specific given cloud format. This method will write a compressed binary file. + * + * This version is to retain backwards compatibility. + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \ingroup io + */ + template inline int + savePCDFileBinaryCompressed (const std::string &file_name, const pcl::PointCloud &cloud) + { + PCDWriter w; + return (w.writeBinaryCompressed (file_name, cloud)); + } + + } +} + +#include + +#endif //#ifndef PCL_IO_PCD_IO_H_ diff --git a/pcl-1.7/pcl/io/ply/byte_order.h b/pcl-1.7/pcl/io/ply/byte_order.h new file mode 100644 index 0000000..4fff118 --- /dev/null +++ b/pcl-1.7/pcl/io/ply/byte_order.h @@ -0,0 +1,109 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2007-2012, Ares Lagae + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_IO_PLY_BYTE_ORDER_H +#define PCL_IO_PLY_BYTE_ORDER_H + +#include + +namespace pcl +{ + namespace io + { + namespace ply + { + /** \file byte_order.h + * defines byte shift operations and endianess. + * \author Ares Lagae as part of libply, Nizar Sallem + * \ingroup io + */ + + enum byte_order + { + little_endian_byte_order, + big_endian_byte_order, +#if defined(BOOST_BIG_ENDIAN) + host_byte_order = big_endian_byte_order, +#elif defined(BOOST_LITTLE_ENDIAN) + host_byte_order = little_endian_byte_order, +#else +#error "unable to determine system endianness" +#endif + network_byte_order = big_endian_byte_order + }; + + template + void swap_byte_order (char* bytes); + + template <> + inline void swap_byte_order<1> (char*) {} + + template <> + inline void swap_byte_order<2> (char* bytes) + { + std::swap (bytes[0], bytes[1]); + } + + template <> + inline void swap_byte_order<4> (char* bytes) + { + std::swap (bytes[0], bytes[3]); + std::swap (bytes[1], bytes[2]); + } + + template <> + inline void swap_byte_order<8> (char* bytes) + { + std::swap (bytes[0], bytes[7]); + std::swap (bytes[1], bytes[6]); + std::swap (bytes[2], bytes[5]); + std::swap (bytes[3], bytes[4]); + } + + template + void swap_byte_order (T& value) + { + swap_byte_order (reinterpret_cast (&value)); + } + + } // namespace ply + } // namespace io +} // namespace pcl + +#endif // PLY_BYTE_ORDER_H diff --git a/pcl-1.7/pcl/io/ply/io_operators.h b/pcl-1.7/pcl/io/ply/io_operators.h new file mode 100644 index 0000000..24e1670 --- /dev/null +++ b/pcl-1.7/pcl/io/ply/io_operators.h @@ -0,0 +1,102 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2007-2012, Ares Lagae + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_IO_PLY_IO_OPERATORS_H +#define PCL_IO_PLY_IO_OPERATORS_H + +#include +#include +#include + +namespace pcl +{ + namespace io + { + namespace ply + { + /** \file io_operators.h + * defines output operators for int8 and uint8 + * \author Ares Lagae as part of libply, Nizar Sallem + * \ingroup io + */ + namespace io_operators + { + + inline std::istream& operator>> (std::istream& istream, int8 &value) + { + int16 tmp; + if (istream >> tmp) + { + if (tmp <= std::numeric_limits::max ()) + value = static_cast (tmp); + else + istream.setstate (std::ios_base::failbit); + } + return (istream); + } + + inline std::istream& operator>> (std::istream& istream, uint8 &value) + { + uint16 tmp; + if (istream >> tmp) + { + if (tmp <= std::numeric_limits::max ()) + value = static_cast (tmp); + else + istream.setstate (std::ios_base::failbit); + } + return (istream); + } + + inline std::ostream& operator<<(std::ostream& ostream, int8 value) + { + return (ostream << static_cast (value)); + } + + inline std::ostream& operator<<(std::ostream& ostream, uint8 value) + { + return (ostream << static_cast (value)); + } + + } // namespace io_operators + } // namespace ply + } // namespace io +} // namespace pcl + +#endif // PLY_IO_OPERATORS_H diff --git a/pcl-1.7/pcl/io/ply/ply.h b/pcl-1.7/pcl/io/ply/ply.h new file mode 100644 index 0000000..1c65d26 --- /dev/null +++ b/pcl-1.7/pcl/io/ply/ply.h @@ -0,0 +1,101 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2007-2012, Ares Lagae + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PLY_PLY_H +#define PLY_PLY_H + +#include +#include + +/** \file ply.h contains standard typedefs and generic type traits + * \author Ares Lagae as part of libply, Nizar Sallem + * Ported with agreement from the author under the terms of the BSD + * license. + * \ingroup io + */ +namespace pcl +{ + namespace io + { + namespace ply + { + typedef boost::int8_t int8; + typedef boost::int16_t int16; + typedef boost::int32_t int32; + typedef boost::uint8_t uint8; + typedef boost::uint16_t uint16; + typedef boost::uint32_t uint32; + + typedef float float32; + typedef double float64; + + template + struct type_traits; + +#ifdef PLY_TYPE_TRAITS +# error +#endif + +#define PLY_TYPE_TRAITS(TYPE, NAME, OLD_NAME) \ + template <> \ + struct type_traits \ + { \ + typedef TYPE type; \ + static const char* name() { return NAME; } \ + static const char* old_name() { return OLD_NAME; } \ + } + + PLY_TYPE_TRAITS(int8, "int8", "char"); + PLY_TYPE_TRAITS(int16, "int16", "short"); + PLY_TYPE_TRAITS(int32, "int32", "int"); + PLY_TYPE_TRAITS(uint8, "uint8", "uchar"); + PLY_TYPE_TRAITS(uint16, "uint16", "ushort"); + PLY_TYPE_TRAITS(uint32, "uint32", "uint"); + PLY_TYPE_TRAITS(float32, "float32", "float"); + PLY_TYPE_TRAITS(float64, "float64", "double"); + +#undef PLY_TYPE_TRAITS + + typedef int format_type; + enum format { ascii_format, binary_little_endian_format, binary_big_endian_format, unknown }; + } // namespace ply + } // namespace io +} // namespace pcl +#endif // PCL_IO_PLY_PLY_H diff --git a/pcl-1.7/pcl/io/ply/ply_parser.h b/pcl-1.7/pcl/io/ply/ply_parser.h new file mode 100644 index 0000000..6fef257 --- /dev/null +++ b/pcl-1.7/pcl/io/ply/ply_parser.h @@ -0,0 +1,713 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2007-2012, Ares Lagae + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_IO_PLY_PLY_PARSER_H +#define PCL_IO_PLY_PLY_PARSER_H + +#include +#include +#include +#include +#include +#include + +#ifdef BUILD_Maintainer +# if defined __GNUC__ +# if __GNUC__ == 4 && __GNUC_MINOR__ > 3 +# pragma GCC diagnostic ignored "-Weffc++" +# pragma GCC diagnostic ignored "-pedantic" +# else +# pragma GCC system_header +# endif +# elif defined _MSC_VER +# pragma warning(push, 1) +# endif +#endif + +#include + +#include +#include +#include + +namespace pcl +{ + namespace io + { + namespace ply + { + /** Class ply_parser parses a PLY file and generates appropriate atomic + * parsers for the body. + * \author Ares Lagae as part of libply, Nizar Sallem + * Ported with agreement from the author under the terms of the BSD + * license. + */ + class PCL_EXPORTS ply_parser + { + public: + + typedef boost::function info_callback_type; + typedef boost::function warning_callback_type; + typedef boost::function error_callback_type; + + typedef boost::function magic_callback_type; + typedef boost::function format_callback_type; + typedef boost::function comment_callback_type; + typedef boost::function obj_info_callback_type; + typedef boost::function end_header_callback_type; + + typedef boost::function begin_element_callback_type; + typedef boost::function end_element_callback_type; + typedef boost::tuple element_callbacks_type; + typedef boost::function element_definition_callback_type; + + template + struct scalar_property_callback_type + { + typedef boost::function type; + }; + + template + struct scalar_property_definition_callback_type + { + typedef typename scalar_property_callback_type::type scalar_property_callback_type; + typedef boost::function type; + }; + + typedef boost::mpl::vector scalar_types; + + class scalar_property_definition_callbacks_type + { + private: + template + struct callbacks_element + { +// callbacks_element () : callback (); + typedef T scalar_type; + typename scalar_property_definition_callback_type::type callback; + }; + + typedef boost::mpl::inherit_linearly< + scalar_types, + boost::mpl::inherit< + boost::mpl::_1, + callbacks_element + > + >::type callbacks; + callbacks callbacks_; + + public: + template + const typename scalar_property_definition_callback_type::type& + get () const + { + return (static_cast&> (callbacks_).callback); + } + + template + typename scalar_property_definition_callback_type::type& + get () + { + return (static_cast&> (callbacks_).callback); + } + + template + friend typename scalar_property_definition_callback_type::type& + at (scalar_property_definition_callbacks_type& scalar_property_definition_callbacks); + + template + friend const typename scalar_property_definition_callback_type::type& + at (const scalar_property_definition_callbacks_type& scalar_property_definition_callbacks); + }; + + template static + typename scalar_property_definition_callback_type::type& + at (scalar_property_definition_callbacks_type& scalar_property_definition_callbacks) + { + return (scalar_property_definition_callbacks.get ()); + } + + + template static + const typename scalar_property_definition_callback_type::type& + at (const scalar_property_definition_callbacks_type& scalar_property_definition_callbacks) + { + return (scalar_property_definition_callbacks.get ()); + } + + template + struct list_property_begin_callback_type + { + typedef boost::function type; + }; + + template + struct list_property_element_callback_type + { + typedef boost::function type; + }; + + template + struct list_property_end_callback_type + { + typedef boost::function type; + }; + + template + struct list_property_definition_callback_type + { + typedef typename list_property_begin_callback_type::type list_property_begin_callback_type; + typedef typename list_property_element_callback_type::type list_property_element_callback_type; + typedef typename list_property_end_callback_type::type list_property_end_callback_type; + typedef boost::function< + boost::tuple< + list_property_begin_callback_type, + list_property_element_callback_type, + list_property_end_callback_type + > (const std::string&, const std::string&)> type; + }; + + typedef boost::mpl::vector size_types; + + class list_property_definition_callbacks_type + { + private: + template struct pair_with : boost::mpl::pair {}; + template + + struct sequence_product : + boost::mpl::fold, + boost::mpl::joint_view< + boost::mpl::_1,boost::mpl::transform > > > + {}; + + template + struct callbacks_element + { + typedef typename T::first size_type; + typedef typename T::second scalar_type; + typename list_property_definition_callback_type::type callback; + }; + + typedef boost::mpl::inherit_linearly::type, boost::mpl::inherit > >::type callbacks; + callbacks callbacks_; + + public: + template + typename list_property_definition_callback_type::type& + get () + { + return (static_cast >&> (callbacks_).callback); + } + + template + const typename list_property_definition_callback_type::type& + get () const + { + return (static_cast >&> (callbacks_).callback); + } + + template + friend typename list_property_definition_callback_type::type& + at (list_property_definition_callbacks_type& list_property_definition_callbacks); + + template + friend const typename list_property_definition_callback_type::type& + at (const list_property_definition_callbacks_type& list_property_definition_callbacks); + }; + + template static + typename list_property_definition_callback_type::type& + at (list_property_definition_callbacks_type& list_property_definition_callbacks) + { + return (list_property_definition_callbacks.get ()); + } + + template static + const typename list_property_definition_callback_type::type& + at (const list_property_definition_callbacks_type& list_property_definition_callbacks) + { + return (list_property_definition_callbacks.get ()); + } + + + inline void + info_callback (const info_callback_type& info_callback); + + inline void + warning_callback (const warning_callback_type& warning_callback); + + inline void + error_callback (const error_callback_type& error_callback); + + inline void + magic_callback (const magic_callback_type& magic_callback); + + inline void + format_callback (const format_callback_type& format_callback); + + inline void + element_definition_callback (const element_definition_callback_type& element_definition_callback); + + inline void + scalar_property_definition_callbacks (const scalar_property_definition_callbacks_type& scalar_property_definition_callbacks); + + inline void + list_property_definition_callbacks (const list_property_definition_callbacks_type& list_property_definition_callbacks); + + inline void + comment_callback (const comment_callback_type& comment_callback); + + inline void + obj_info_callback (const obj_info_callback_type& obj_info_callback); + + inline void + end_header_callback (const end_header_callback_type& end_header_callback); + + typedef int flags_type; + enum flags { }; + + ply_parser (flags_type flags = 0) : + flags_ (flags), + comment_callback_ (), obj_info_callback_ (), end_header_callback_ (), + line_number_ (0), current_element_ () + {} + + bool parse (const std::string& filename); + //inline bool parse (const std::string& filename); + + private: + + struct property + { + property (const std::string& name) : name (name) {} + virtual ~property () {} + virtual bool parse (class ply_parser& ply_parser, format_type format, std::istream& istream) = 0; + std::string name; + }; + + template + struct scalar_property : public property + { + typedef ScalarType scalar_type; + typedef typename scalar_property_callback_type::type callback_type; + scalar_property (const std::string& name, callback_type callback) + : property (name) + , callback (callback) + {} + bool parse (class ply_parser& ply_parser, + format_type format, + std::istream& istream) + { + return ply_parser.parse_scalar_property (format, istream, callback); + } + callback_type callback; + }; + + template + struct list_property : public property + { + typedef SizeType size_type; + typedef ScalarType scalar_type; + typedef typename list_property_begin_callback_type::type begin_callback_type; + typedef typename list_property_element_callback_type::type element_callback_type; + typedef typename list_property_end_callback_type::type end_callback_type; + list_property (const std::string& name, + begin_callback_type begin_callback, + element_callback_type element_callback, + end_callback_type end_callback) + : property (name) + , begin_callback (begin_callback) + , element_callback (element_callback) + , end_callback (end_callback) + {} + bool parse (class ply_parser& ply_parser, + format_type format, + std::istream& istream) + { + return ply_parser.parse_list_property (format, + istream, + begin_callback, + element_callback, + end_callback); + } + begin_callback_type begin_callback; + element_callback_type element_callback; + end_callback_type end_callback; + }; + + struct element + { + element (const std::string& name, + std::size_t count, + const begin_element_callback_type& begin_element_callback, + const end_element_callback_type& end_element_callback) + : name (name) + , count (count) + , begin_element_callback (begin_element_callback) + , end_element_callback (end_element_callback) + , properties () + {} + std::string name; + std::size_t count; + begin_element_callback_type begin_element_callback; + end_element_callback_type end_element_callback; + std::vector > properties; + }; + + flags_type flags_; + + info_callback_type info_callback_; + warning_callback_type warning_callback_; + error_callback_type error_callback_; + + magic_callback_type magic_callback_; + format_callback_type format_callback_; + element_definition_callback_type element_definition_callbacks_; + scalar_property_definition_callbacks_type scalar_property_definition_callbacks_; + list_property_definition_callbacks_type list_property_definition_callbacks_; + comment_callback_type comment_callback_; + obj_info_callback_type obj_info_callback_; + end_header_callback_type end_header_callback_; + + template inline void + parse_scalar_property_definition (const std::string& property_name); + + template inline void + parse_list_property_definition (const std::string& property_name); + + template inline bool + parse_scalar_property (format_type format, + std::istream& istream, + const typename scalar_property_callback_type::type& scalar_property_callback); + + template inline bool + parse_list_property (format_type format, + std::istream& istream, + const typename list_property_begin_callback_type::type& list_property_begin_callback, + const typename list_property_element_callback_type::type& list_property_element_callback, + const typename list_property_end_callback_type::type& list_property_end_callback); + + std::size_t line_number_; + element* current_element_; + }; + } // namespace ply + } // namespace io +} // namespace pcl + +/* inline bool pcl::io::ply::ply_parser::parse (const std::string& filename) */ +/* { */ +/* std::ifstream ifstream (filename.c_str ()); */ +/* return (parse (ifstream)); */ +/* } */ + +inline void pcl::io::ply::ply_parser::info_callback (const info_callback_type& info_callback) +{ + info_callback_ = info_callback; +} + +inline void pcl::io::ply::ply_parser::warning_callback (const warning_callback_type& warning_callback) +{ + warning_callback_ = warning_callback; +} + +inline void pcl::io::ply::ply_parser::error_callback (const error_callback_type& error_callback) +{ + error_callback_ = error_callback; +} + +inline void pcl::io::ply::ply_parser::magic_callback (const magic_callback_type& magic_callback) +{ + magic_callback_ = magic_callback; +} + +inline void pcl::io::ply::ply_parser::format_callback (const format_callback_type& format_callback) +{ + format_callback_ = format_callback; +} + +inline void pcl::io::ply::ply_parser::element_definition_callback (const element_definition_callback_type& element_definition_callback) +{ + element_definition_callbacks_ = element_definition_callback; +} + +inline void pcl::io::ply::ply_parser::scalar_property_definition_callbacks (const scalar_property_definition_callbacks_type& scalar_property_definition_callbacks) +{ + scalar_property_definition_callbacks_ = scalar_property_definition_callbacks; +} + +inline void pcl::io::ply::ply_parser::list_property_definition_callbacks (const list_property_definition_callbacks_type& list_property_definition_callbacks) +{ + list_property_definition_callbacks_ = list_property_definition_callbacks; +} + +inline void pcl::io::ply::ply_parser::comment_callback (const comment_callback_type& comment_callback) +{ + comment_callback_ = comment_callback; +} + +inline void pcl::io::ply::ply_parser::obj_info_callback (const obj_info_callback_type& obj_info_callback) +{ + obj_info_callback_ = obj_info_callback; +} + +inline void pcl::io::ply::ply_parser::end_header_callback (const end_header_callback_type& end_header_callback) +{ + end_header_callback_ = end_header_callback; +} + +template +inline void pcl::io::ply::ply_parser::parse_scalar_property_definition (const std::string& property_name) +{ + typedef ScalarType scalar_type; + typename scalar_property_definition_callback_type::type& scalar_property_definition_callback = + scalar_property_definition_callbacks_.get (); + typename scalar_property_callback_type::type scalar_property_callback; + if (scalar_property_definition_callback) + { + scalar_property_callback = scalar_property_definition_callback (current_element_->name, property_name); + } + if (!scalar_property_callback) + { + if (warning_callback_) + { + warning_callback_ (line_number_, + "property '" + std::string (type_traits::name ()) + " " + + property_name + "' of element '" + current_element_->name + "' is not handled"); + } + } + current_element_->properties.push_back (boost::shared_ptr (new scalar_property (property_name, scalar_property_callback))); +} + +template +inline void pcl::io::ply::ply_parser::parse_list_property_definition (const std::string& property_name) +{ + typedef SizeType size_type; + typedef ScalarType scalar_type; + typedef typename list_property_definition_callback_type::type list_property_definition_callback_type; + list_property_definition_callback_type& list_property_definition_callback = list_property_definition_callbacks_.get (); + typedef typename list_property_begin_callback_type::type list_property_begin_callback_type; + typedef typename list_property_element_callback_type::type list_property_element_callback_type; + typedef typename list_property_end_callback_type::type list_property_end_callback_type; + boost::tuple list_property_callbacks; + if (list_property_definition_callback) + { + list_property_callbacks = list_property_definition_callback (current_element_->name, property_name); + } + if (!boost::get<0> (list_property_callbacks) || !boost::get<1> (list_property_callbacks) || !boost::get<2> (list_property_callbacks)) + { + if (warning_callback_) + { + warning_callback_ (line_number_, + "property 'list " + std::string (type_traits::name ()) + " " + + std::string (type_traits::name ()) + " " + + property_name + "' of element '" + + current_element_->name + "' is not handled"); + } + } + current_element_->properties.push_back (boost::shared_ptr ( + new list_property ( + property_name, + boost::get<0> (list_property_callbacks), + boost::get<1> (list_property_callbacks), + boost::get<2> (list_property_callbacks)))); +} + +template +inline bool pcl::io::ply::ply_parser::parse_scalar_property (format_type format, + std::istream& istream, + const typename scalar_property_callback_type::type& scalar_property_callback) +{ + using namespace io_operators; + typedef ScalarType scalar_type; + if (format == ascii_format) + { + scalar_type value = std::numeric_limits::quiet_NaN (); + char space = ' '; + istream >> value; + if (!istream.eof ()) + istream >> space >> std::ws; + if (!istream || !isspace (space)) + { + if (error_callback_) + error_callback_ (line_number_, "parse error"); + return (false); + } + if (scalar_property_callback) + scalar_property_callback (value); + return (true); + } + else + { + scalar_type value = std::numeric_limits::quiet_NaN (); + istream.read (reinterpret_cast (&value), sizeof (scalar_type)); + if (!istream) + { + if (error_callback_) + error_callback_ (line_number_, "parse error"); + return (false); + } + if (((format == binary_big_endian_format) && (host_byte_order == little_endian_byte_order)) || + ((format == binary_little_endian_format) && (host_byte_order == big_endian_byte_order))) + swap_byte_order (value); + if (scalar_property_callback) + scalar_property_callback (value); + return (true); + } +} + +template +inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, std::istream& istream, + const typename list_property_begin_callback_type::type& list_property_begin_callback, + const typename list_property_element_callback_type::type& list_property_element_callback, + const typename list_property_end_callback_type::type& list_property_end_callback) +{ + using namespace io_operators; + typedef SizeType size_type; + typedef ScalarType scalar_type; + if (format == ascii_format) + { + size_type size = std::numeric_limits::infinity (); + char space = ' '; + istream >> size; + if (!istream.eof ()) + { + istream >> space >> std::ws; + } + if (!istream || !isspace (space)) + { + if (error_callback_) + { + error_callback_ (line_number_, "parse error"); + } + return (false); + } + if (list_property_begin_callback) + { + list_property_begin_callback (size); + } + for (std::size_t index = 0; index < size; ++index) + { + scalar_type value = std::numeric_limits::quiet_NaN (); + char space = ' '; + istream >> value; + if (!istream.eof ()) + { + istream >> space >> std::ws; + } + if (!istream || !isspace (space)) + { + if (error_callback_) + { + error_callback_ (line_number_, "parse error"); + } + return (false); + } + if (list_property_element_callback) + { + list_property_element_callback (value); + } + } + if (list_property_end_callback) + { + list_property_end_callback (); + } + return (true); + } + else + { + size_type size = std::numeric_limits::infinity (); + istream.read (reinterpret_cast (&size), sizeof (size_type)); + if (((format == binary_big_endian_format) && (host_byte_order == little_endian_byte_order)) || + ((format == binary_little_endian_format) && (host_byte_order == big_endian_byte_order))) + { + swap_byte_order (size); + } + if (!istream) + { + if (error_callback_) + { + error_callback_ (line_number_, "parse error"); + } + return (false); + } + if (list_property_begin_callback) + { + list_property_begin_callback (size); + } + for (std::size_t index = 0; index < size; ++index) { + scalar_type value = std::numeric_limits::quiet_NaN (); + istream.read (reinterpret_cast (&value), sizeof (scalar_type)); + if (!istream) { + if (error_callback_) { + error_callback_ (line_number_, "parse error"); + } + return (false); + } + if (((format == binary_big_endian_format) && (host_byte_order == little_endian_byte_order)) || + ((format == binary_little_endian_format) && (host_byte_order == big_endian_byte_order))) + { + swap_byte_order (value); + } + if (list_property_element_callback) + { + list_property_element_callback (value); + } + } + if (list_property_end_callback) + { + list_property_end_callback (); + } + return (true); + } +} + +#ifdef BUILD_Maintainer +# if defined __GNUC__ +# if __GNUC__ == 4 && __GNUC_MINOR__ > 3 +# pragma GCC diagnostic warning "-Weffc++" +# pragma GCC diagnostic warning "-pedantic" +# endif +# elif defined _MSC_VER +# pragma warning(pop) +# endif +#endif + +#endif // PCL_IO_PLY_PLY_PARSER_H diff --git a/pcl-1.7/pcl/io/ply_io.h b/pcl-1.7/pcl/io/ply_io.h new file mode 100644 index 0000000..7f33998 --- /dev/null +++ b/pcl-1.7/pcl/io/ply_io.h @@ -0,0 +1,890 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_IO_PLY_IO_H_ +#define PCL_IO_PLY_IO_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Point Cloud Data (PLY) file format reader. + * + * The PLY data format is organized in the following way: + * lines beginning with "comment" are treated as comments + * - ply + * - format [ascii|binary_little_endian|binary_big_endian] 1.0 + * - element vertex COUNT + * - property float x + * - property float y + * - [property float z] + * - [property float normal_x] + * - [property float normal_y] + * - [property float normal_z] + * - [property uchar red] + * - [property uchar green] + * - [property uchar blue] ... + * - ascii/binary point coordinates + * - [element camera 1] + * - [property float view_px] ... + * - [element range_grid COUNT] + * - [property list uchar int vertex_indices] + * - end header + * + * \author Nizar Sallem + * \ingroup io + */ + class PCL_EXPORTS PLYReader : public FileReader + { + public: + enum + { + PLY_V0 = 0, + PLY_V1 = 1 + }; + + PLYReader () + : FileReader () + , parser_ () + , origin_ (Eigen::Vector4f::Zero ()) + , orientation_ (Eigen::Matrix3f::Zero ()) + , cloud_ () + , vertex_count_ (0) + , vertex_offset_before_ (0) + , range_grid_ (0) + , rgb_offset_before_ (0) + , do_resize_ (false) + , polygons_ (0) + {} + + PLYReader (const PLYReader &p) + : FileReader () + , parser_ () + , origin_ (Eigen::Vector4f::Zero ()) + , orientation_ (Eigen::Matrix3f::Zero ()) + , cloud_ () + , vertex_count_ (0) + , vertex_offset_before_ (0) + , range_grid_ (0) + , rgb_offset_before_ (0) + , do_resize_ (false) + , polygons_ (0) + { + *this = p; + } + + PLYReader& + operator = (const PLYReader &p) + { + origin_ = p.origin_; + orientation_ = p.orientation_; + range_grid_ = p.range_grid_; + polygons_ = p.polygons_; + return (*this); + } + + ~PLYReader () { delete range_grid_; } + /** \brief Read a point cloud data header from a PLY file. + * + * Load only the meta information (number of points, their types, etc), + * and not the points themselves, from a given PLY file. Useful for fast + * evaluation of the underlying data structure. + * + * Returns: + * * < 0 (-1) on error + * * > 0 on success + * \param[in] file_name the name of the file to load + * \param[out] cloud the resultant point cloud dataset (only the header will be filled) + * \param[in] origin the sensor data acquisition origin (translation) + * \param[in] orientation the sensor data acquisition origin (rotation) + * \param[out] ply_version the PLY version read from the file + * \param[out] data_type the type of PLY data stored in the file + * \param[out] data_idx the data index + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + */ + int + readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, + int &ply_version, int &data_type, unsigned int &data_idx, const int offset = 0); + + /** \brief Read a point cloud data from a PLY file and store it into a pcl/PCLPointCloud2. + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * \param[in] origin the sensor data acquisition origin (translation) + * \param[in] orientation the sensor data acquisition origin (rotation) + * \param[out] ply_version the PLY version read from the file + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + */ + int + read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int& ply_version, const int offset = 0); + + /** \brief Read a point cloud data from a PLY file and store it into a pcl/PCLPointCloud2. + * \note This function is provided for backwards compatibility only + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + */ + inline int + read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, const int offset = 0) + { + Eigen::Vector4f origin; + Eigen::Quaternionf orientation; + int ply_version; + return read (file_name, cloud, origin, orientation, ply_version, offset); + } + + /** \brief Read a point cloud data from any PLY file, and convert it to the given template format. + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] cloud the resultant PointCloud message read from disk + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + */ + template inline int + read (const std::string &file_name, pcl::PointCloud &cloud, const int offset = 0) + { + pcl::PCLPointCloud2 blob; + int ply_version; + int res = read (file_name, blob, cloud.sensor_origin_, cloud.sensor_orientation_, + ply_version, offset); + + // Exit in case of error + if (res < 0) + return (res); + pcl::fromPCLPointCloud2 (blob, cloud); + return (0); + } + + /** \brief Read a point cloud data from a PLY file and store it into a pcl/PolygonMesh. + * + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] mesh the resultant PolygonMesh message read from disk + * \param[in] origin the sensor data acquisition origin (translation) + * \param[in] orientation the sensor data acquisition origin (rotation) + * \param[out] ply_version the PLY version read from the file + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + */ + int + read (const std::string &file_name, pcl::PolygonMesh &mesh, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, + int& ply_version, const int offset = 0); + + /** \brief Read a point cloud data from a PLY file and store it into a pcl/PolygonMesh. + * + * \param[in] file_name the name of the file containing the actual PointCloud data + * \param[out] mesh the resultant PolygonMesh message read from disk + * \param[in] offset the offset in the file where to expect the true header to begin. + * One usage example for setting the offset parameter is for reading + * data from a TAR "archive containing multiple files: TAR files always + * add a 512 byte header in front of the actual file, so set the offset + * to the next byte after the header (e.g., 513). + */ + int + read (const std::string &file_name, pcl::PolygonMesh &mesh, const int offset = 0); + + private: + ::pcl::io::ply::ply_parser parser_; + + bool + parse (const std::string& istream_filename); + + /** \brief Info callback function + * \param[in] filename PLY file read + * \param[in] line_number line triggering the callback + * \param[in] message information message + */ + void + infoCallback (const std::string& filename, std::size_t line_number, const std::string& message) + { + PCL_DEBUG ("[pcl::PLYReader] %s:%lu: %s\n", filename.c_str (), line_number, message.c_str ()); + } + + /** \brief Warning callback function + * \param[in] filename PLY file read + * \param[in] line_number line triggering the callback + * \param[in] message warning message + */ + void + warningCallback (const std::string& filename, std::size_t line_number, const std::string& message) + { + PCL_WARN ("[pcl::PLYReader] %s:%lu: %s\n", filename.c_str (), line_number, message.c_str ()); + } + + /** \brief Error callback function + * \param[in] filename PLY file read + * \param[in] line_number line triggering the callback + * \param[in] message error message + */ + void + errorCallback (const std::string& filename, std::size_t line_number, const std::string& message) + { + PCL_ERROR ("[pcl::PLYReader] %s:%lu: %s\n", filename.c_str (), line_number, message.c_str ()); + } + + /** \brief function called when the keyword element is parsed + * \param[in] element_name element name + * \param[in] count number of instances + */ + boost::tuple, boost::function > + elementDefinitionCallback (const std::string& element_name, std::size_t count); + + bool + endHeaderCallback (); + + /** \brief function called when a scalar property is parsed + * \param[in] element_name element name to which the property belongs + * \param[in] property_name property name + */ + template boost::function + scalarPropertyDefinitionCallback (const std::string& element_name, const std::string& property_name); + + /** \brief function called when a list property is parsed + * \param[in] element_name element name to which the property belongs + * \param[in] property_name list property name + */ + template + boost::tuple, boost::function, boost::function > + listPropertyDefinitionCallback (const std::string& element_name, const std::string& property_name); + + /** \brief function called at the beginning of a list property parsing. + * \param[in] size number of elements in the list + */ + template void + vertexListPropertyBeginCallback (const std::string& property_name, SizeType size); + + /** \brief function called when a list element is parsed. + * \param[in] value the list's element value + */ + template void + vertexListPropertyContentCallback (ContentType value); + + /** \brief function called at the end of a list property parsing */ + inline void + vertexListPropertyEndCallback (); + + /** Callback function for an anonymous vertex scalar property. + * Writes down a double value in cloud data. + * param[in] value double value parsed + */ + template void + vertexScalarPropertyCallback (Scalar value); + + /** Callback function for vertex RGB color. + * This callback is in charge of packing red green and blue in a single int + * before writing it down in cloud data. + * param[in] color_name color name in {red, green, blue} + * param[in] color value of {red, green, blue} property + */ + inline void + vertexColorCallback (const std::string& color_name, pcl::io::ply::uint8 color); + + /** Callback function for vertex intensity. + * converts intensity from int to float before writing it down in cloud data. + * param[in] intensity + */ + inline void + vertexIntensityCallback (pcl::io::ply::uint8 intensity); + + /** Callback function for vertex alpha. + * extracts RGB value, append alpha and put it back + * param[in] alpha + */ + inline void + vertexAlphaCallback (pcl::io::ply::uint8 alpha); + + /** Callback function for origin x component. + * param[in] value origin x value + */ + inline void + originXCallback (const float& value) { origin_[0] = value; } + + /** Callback function for origin y component. + * param[in] value origin y value + */ + inline void + originYCallback (const float& value) { origin_[1] = value; } + + /** Callback function for origin z component. + * param[in] value origin z value + */ + inline void + originZCallback (const float& value) { origin_[2] = value; } + + /** Callback function for orientation x axis x component. + * param[in] value orientation x axis x value + */ + inline void + orientationXaxisXCallback (const float& value) { orientation_ (0,0) = value; } + + /** Callback function for orientation x axis y component. + * param[in] value orientation x axis y value + */ + inline void + orientationXaxisYCallback (const float& value) { orientation_ (0,1) = value; } + + /** Callback function for orientation x axis z component. + * param[in] value orientation x axis z value + */ + inline void + orientationXaxisZCallback (const float& value) { orientation_ (0,2) = value; } + + /** Callback function for orientation y axis x component. + * param[in] value orientation y axis x value + */ + inline void + orientationYaxisXCallback (const float& value) { orientation_ (1,0) = value; } + + /** Callback function for orientation y axis y component. + * param[in] value orientation y axis y value + */ + inline void + orientationYaxisYCallback (const float& value) { orientation_ (1,1) = value; } + + /** Callback function for orientation y axis z component. + * param[in] value orientation y axis z value + */ + inline void + orientationYaxisZCallback (const float& value) { orientation_ (1,2) = value; } + + /** Callback function for orientation z axis x component. + * param[in] value orientation z axis x value + */ + inline void + orientationZaxisXCallback (const float& value) { orientation_ (2,0) = value; } + + /** Callback function for orientation z axis y component. + * param[in] value orientation z axis y value + */ + inline void + orientationZaxisYCallback (const float& value) { orientation_ (2,1) = value; } + + /** Callback function for orientation z axis z component. + * param[in] value orientation z axis z value + */ + inline void + orientationZaxisZCallback (const float& value) { orientation_ (2,2) = value; } + + /** Callback function to set the cloud height + * param[in] height cloud height + */ + inline void + cloudHeightCallback (const int &height) { cloud_->height = height; } + + /** Callback function to set the cloud width + * param[in] width cloud width + */ + inline void + cloudWidthCallback (const int &width) { cloud_->width = width; } + + /** Append a scalar property to the cloud fields. + * param[in] name property name + * param[in] count property count: 1 for scalar properties and higher for a + * list property. + */ + template void + appendScalarProperty (const std::string& name, const size_t& count = 1); + + /** Amend property from cloud fields identified by \a old_name renaming + * it \a new_name. + * param[in] old_name property old name + * param[in] new_name property new name + */ + void + amendProperty (const std::string& old_name, const std::string& new_name, uint8_t datatype = 0); + + /** Callback function for the begin of vertex line */ + void + vertexBeginCallback (); + + /** Callback function for the end of vertex line */ + void + vertexEndCallback (); + + /** Callback function for the begin of range_grid line */ + void + rangeGridBeginCallback (); + + /** Callback function for the begin of range_grid vertex_indices property + * param[in] size vertex_indices list size + */ + void + rangeGridVertexIndicesBeginCallback (pcl::io::ply::uint8 size); + + /** Callback function for each range_grid vertex_indices element + * param[in] vertex_index index of the vertex in vertex_indices + */ + void + rangeGridVertexIndicesElementCallback (pcl::io::ply::int32 vertex_index); + + /** Callback function for the end of a range_grid vertex_indices property */ + void + rangeGridVertexIndicesEndCallback (); + + /** Callback function for the end of a range_grid element end */ + void + rangeGridEndCallback (); + + /** Callback function for obj_info */ + void + objInfoCallback (const std::string& line); + + /** Callback function for the begin of face line */ + void + faceBeginCallback (); + + /** Callback function for the begin of face vertex_indices property + * param[in] size vertex_indices list size + */ + void + faceVertexIndicesBeginCallback (pcl::io::ply::uint8 size); + + /** Callback function for each face vertex_indices element + * param[in] vertex_index index of the vertex in vertex_indices + */ + void + faceVertexIndicesElementCallback (pcl::io::ply::int32 vertex_index); + + /** Callback function for the end of a face vertex_indices property */ + void + faceVertexIndicesEndCallback (); + + /** Callback function for the end of a face element end */ + void + faceEndCallback (); + + /// origin + Eigen::Vector4f origin_; + + /// orientation + Eigen::Matrix3f orientation_; + + //vertex element artifacts + pcl::PCLPointCloud2 *cloud_; + size_t vertex_count_; + int vertex_offset_before_; + //range element artifacts + std::vector > *range_grid_; + size_t rgb_offset_before_; + bool do_resize_; + //face element artifact + std::vector *polygons_; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + /** \brief Point Cloud Data (PLY) file format writer. + * \author Nizar Sallem + * \ingroup io + */ + class PCL_EXPORTS PLYWriter : public FileWriter + { + public: + ///Constructor + PLYWriter () : FileWriter () {}; + + ///Destructor + ~PLYWriter () {}; + + /** \brief Generate the header of a PLY v.7 file format + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor data acquisition origin (translation) + * \param[in] orientation the sensor data acquisition origin (rotation) + * \param[in] valid_points number of valid points (finite ones for range_grid and + * all of them for camer) + * \param[in] use_camera if set to true then PLY file will use element camera else + * element range_grid will be used. + */ + inline std::string + generateHeaderBinary (const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin, + const Eigen::Quaternionf &orientation, + int valid_points, + bool use_camera = true) + { + return (generateHeader (cloud, origin, orientation, true, use_camera, valid_points)); + } + + /** \brief Generate the header of a PLY v.7 file format + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor data acquisition origin (translation) + * \param[in] orientation the sensor data acquisition origin (rotation) + * \param[in] valid_points number of valid points (finite ones for range_grid and + * all of them for camer) + * \param[in] use_camera if set to true then PLY file will use element camera else + * element range_grid will be used. + */ + inline std::string + generateHeaderASCII (const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin, + const Eigen::Quaternionf &orientation, + int valid_points, + bool use_camera = true) + { + return (generateHeader (cloud, origin, orientation, false, use_camera, valid_points)); + } + + /** \brief Save point cloud data to a PLY file containing n-D points, in ASCII format + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor data acquisition origin (translation) + * \param[in] orientation the sensor data acquisition origin (rotation) + * \param[in] precision the specified output numeric stream precision (default: 8) + * \param[in] use_camera if set to true then PLY file will use element camera else + * element range_grid will be used. + */ + int + writeASCII (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), + int precision = 8, + bool use_camera = true); + + /** \brief Save point cloud data to a PLY file containing n-D points, in BINARY format + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor data acquisition origin (translation) + * \param[in] orientation the sensor data acquisition origin (rotation) + * \param[in] use_camera if set to true then PLY file will use element camera else + * element range_grid will be used + */ + int + writeBinary (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), + bool use_camera = true); + + /** \brief Save point cloud data to a PLY file containing n-D points + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + * \param[in] binary set to true if the file is to be written in a binary + * PLY format, false (default) for ASCII + */ + inline int + write (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), + const bool binary = false) + { + if (binary) + return (this->writeBinary (file_name, cloud, origin, orientation, true)); + else + return (this->writeASCII (file_name, cloud, origin, orientation, 8, true)); + } + + /** \brief Save point cloud data to a PLY file containing n-D points + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + * \param[in] binary set to true if the file is to be written in a binary + * PLY format, false (default) for ASCII + * \param[in] use_camera set to true to use camera element and false to + * use range_grid element + */ + inline int + write (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), + bool binary = false, + bool use_camera = true) + { + if (binary) + return (this->writeBinary (file_name, cloud, origin, orientation, use_camera)); + else + return (this->writeASCII (file_name, cloud, origin, orientation, 8, use_camera)); + } + + /** \brief Save point cloud data to a PLY file containing n-D points + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message (boost shared pointer) + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + * \param[in] binary set to true if the file is to be written in a binary + * PLY format, false (default) for ASCII + * \param[in] use_camera set to true to use camera element and false to + * use range_grid element + */ + inline int + write (const std::string &file_name, const pcl::PCLPointCloud2::ConstPtr &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), + bool binary = false, + bool use_camera = true) + { + return (write (file_name, *cloud, origin, orientation, binary, use_camera)); + } + + /** \brief Save point cloud data to a PLY file containing n-D points + * \param[in] file_name the output file name + * \param[in] cloud the pcl::PointCloud data + * \param[in] binary set to true if the file is to be written in a binary + * PLY format, false (default) for ASCII + * \param[in] use_camera set to true to use camera element and false to + * use range_grid element + */ + template inline int + write (const std::string &file_name, + const pcl::PointCloud &cloud, + bool binary = false, + bool use_camera = true) + { + Eigen::Vector4f origin = cloud.sensor_origin_; + Eigen::Quaternionf orientation = cloud.sensor_orientation_; + + pcl::PCLPointCloud2 blob; + pcl::toPCLPointCloud2 (cloud, blob); + + // Save the data + return (this->write (file_name, blob, origin, orientation, binary, use_camera)); + } + + private: + /** \brief Generate a PLY header. + * \param[in] cloud the input point cloud + * \param[in] binary whether the PLY file should be saved as binary data (true) or ascii (false) + */ + std::string + generateHeader (const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin, + const Eigen::Quaternionf &orientation, + bool binary, + bool use_camera, + int valid_points); + + void + writeContentWithCameraASCII (int nr_points, + int point_size, + const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin, + const Eigen::Quaternionf &orientation, + std::ofstream& fs); + + void + writeContentWithRangeGridASCII (int nr_points, + int point_size, + const pcl::PCLPointCloud2 &cloud, + std::ostringstream& fs, + int& nb_valid_points); + }; + + namespace io + { + /** \brief Load a PLY v.6 file into a templated PointCloud type. + * + * Any PLY files containg sensor data will generate a warning as a + * pcl/PCLPointCloud2 message cannot hold the sensor origin. + * + * \param[in] file_name the name of the file to load + * \param[in] cloud the resultant templated point cloud + * \ingroup io + */ + inline int + loadPLYFile (const std::string &file_name, pcl::PCLPointCloud2 &cloud) + { + pcl::PLYReader p; + return (p.read (file_name, cloud)); + } + + /** \brief Load any PLY file into a templated PointCloud type. + * \param[in] file_name the name of the file to load + * \param[in] cloud the resultant templated point cloud + * \param[in] origin the sensor acquisition origin (only for > PLY_V7 - null if not present) + * \param[in] orientation the sensor acquisition orientation if availble, + * identity if not present + * \ingroup io + */ + inline int + loadPLYFile (const std::string &file_name, pcl::PCLPointCloud2 &cloud, + Eigen::Vector4f &origin, Eigen::Quaternionf &orientation) + { + pcl::PLYReader p; + int ply_version; + return (p.read (file_name, cloud, origin, orientation, ply_version)); + } + + /** \brief Load any PLY file into a templated PointCloud type + * \param[in] file_name the name of the file to load + * \param[in] cloud the resultant templated point cloud + * \ingroup io + */ + template inline int + loadPLYFile (const std::string &file_name, pcl::PointCloud &cloud) + { + pcl::PLYReader p; + return (p.read (file_name, cloud)); + } + + /** \brief Load a PLY file into a PolygonMesh type. + * + * Any PLY files containg sensor data will generate a warning as a + * pcl/PolygonMesh message cannot hold the sensor origin. + * + * \param[in] file_name the name of the file to load + * \param[in] mesh the resultant polygon mesh + * \ingroup io + */ + inline int + loadPLYFile (const std::string &file_name, pcl::PolygonMesh &mesh) + { + pcl::PLYReader p; + return (p.read (file_name, mesh)); + } + + /** \brief Save point cloud data to a PLY file containing n-D points + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor data acquisition origin (translation) + * \param[in] orientation the sensor data acquisition origin (rotation) + * \param[in] binary_mode true for binary mode, false (default) for ASCII + * \param[in] use_camera + * \ingroup io + */ + inline int + savePLYFile (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), + bool binary_mode = false, bool use_camera = true) + { + PLYWriter w; + return (w.write (file_name, cloud, origin, orientation, binary_mode, use_camera)); + } + + /** \brief Templated version for saving point cloud data to a PLY file + * containing a specific given cloud format + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] binary_mode true for binary mode, false (default) for ASCII + * \ingroup io + */ + template inline int + savePLYFile (const std::string &file_name, const pcl::PointCloud &cloud, bool binary_mode = false) + { + PLYWriter w; + return (w.write (file_name, cloud, binary_mode)); + } + + /** \brief Templated version for saving point cloud data to a PLY file + * containing a specific given cloud format. + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \ingroup io + */ + template inline int + savePLYFileASCII (const std::string &file_name, const pcl::PointCloud &cloud) + { + PLYWriter w; + return (w.write (file_name, cloud, false)); + } + + /** \brief Templated version for saving point cloud data to a PLY file containing a specific given cloud format. + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \ingroup io + */ + template inline int + savePLYFileBinary (const std::string &file_name, const pcl::PointCloud &cloud) + { + PLYWriter w; + return (w.write (file_name, cloud, true)); + } + + /** \brief Templated version for saving point cloud data to a PLY file containing a specific given cloud format + * \param[in] file_name the output file name + * \param[in] cloud the point cloud data message + * \param[in] indices the set of indices to save + * \param[in] binary_mode true for binary mode, false (default) for ASCII + * \ingroup io + */ + template int + savePLYFile (const std::string &file_name, const pcl::PointCloud &cloud, + const std::vector &indices, bool binary_mode = false) + { + // Copy indices to a new point cloud + pcl::PointCloud cloud_out; + copyPointCloud (cloud, indices, cloud_out); + // Save the data + PLYWriter w; + return (w.write (file_name, cloud_out, binary_mode)); + } + + /** \brief Saves a PolygonMesh in ascii PLY format. + * \param[in] file_name the name of the file to write to disk + * \param[in] mesh the polygonal mesh to save + * \param[in] precision the output ASCII precision default 5 + * \ingroup io + */ + PCL_EXPORTS int + savePLYFile (const std::string &file_name, const pcl::PolygonMesh &mesh, unsigned precision = 5); + + /** \brief Saves a PolygonMesh in binary PLY format. + * \param[in] file_name the name of the file to write to disk + * \param[in] mesh the polygonal mesh to save + * \ingroup io + */ + PCL_EXPORTS int + savePLYFileBinary (const std::string &file_name, const pcl::PolygonMesh &mesh); + } +} + +#endif //#ifndef PCL_IO_PLY_IO_H_ diff --git a/pcl-1.7/pcl/io/png_io.h b/pcl-1.7/pcl/io/png_io.h new file mode 100644 index 0000000..a30b140 --- /dev/null +++ b/pcl-1.7/pcl/io/png_io.h @@ -0,0 +1,203 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * Authors: Anatoly Baksheev + */ + +#ifndef PCL_IO_PNG_IO_H_ +#define PCL_IO_PNG_IO_H_ + +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace io + { + /** \brief Saves 8-bit encoded image to PNG file. + * \param[in] file_name the name of the file to write to disk + * \param[in] mono_image image grayscale data + * \param[in] width image width + * \param[in] height image height + * \param[in] channels number of channels + * \ingroup io + */ + PCL_EXPORTS void + saveCharPNGFile (const std::string& file_name, const unsigned char *mono_image, int width, int height, int channels); + + /** \brief Saves 16-bit encoded image to PNG file. + * \param[in] file_name the name of the file to write to disk + * \param[in] short_image image short data + * \param[in] width image width + * \param[in] height image height + * \param[in] channels number of channels + * \ingroup io + */ + PCL_EXPORTS void + saveShortPNGFile (const std::string& file_name, const unsigned short *short_image, int width, int height, int channels); + + /** \brief Saves 8-bit encoded RGB image to PNG file. + * \param[in] file_name the name of the file to write to disk + * \param[in] rgb_image image rgb data + * \param[in] width image width + * \param[in] height image height + * \ingroup io + */ + PCL_EXPORTS void + saveRgbPNGFile (const std::string& file_name, const unsigned char *rgb_image, int width, int height); + + /** \brief Saves 8-bit grayscale cloud as image to PNG file. + * \param[in] file_name the name of the file to write to disk + * \param[in] cloud point cloud to save + * \ingroup io + */ + PCL_EXPORTS void + savePNGFile (const std::string& file_name, const pcl::PointCloud& cloud); + + /** \brief Saves 16-bit grayscale cloud as image to PNG file. + * \param[in] file_name the name of the file to write to disk + * \param[in] cloud point cloud to save + * \ingroup io + */ + PCL_EXPORTS void + savePNGFile (const std::string& file_name, const pcl::PointCloud& cloud); + + /** \brief Saves a PCLImage (formely ROS sensor_msgs::Image) to PNG file. + * \param[in] file_name the name of the file to write to disk + * \param[in] image image to save + * \ingroup io + * \note Currently only "rgb8", "mono8", and "mono16" image encodings are supported. + */ + PCL_EXPORTS void + savePNGFile (const std::string& file_name, const pcl::PCLImage& image); + + /** \brief Saves RGB fields of cloud as image to PNG file. + * \param[in] file_name the name of the file to write to disk + * \param[in] cloud point cloud to save + * \ingroup io + */ + template + PCL_DEPRECATED ( + "pcl::io::savePNGFile (file_name, cloud) is deprecated, please use a new generic " + "function pcl::io::savePNGFile (file_name, cloud, field_name) with \"rgb\" as the field name." + ) + void + savePNGFile (const std::string& file_name, const pcl::PointCloud& cloud) + { + std::vector data(cloud.width * cloud.height * 3); + + for (size_t i = 0; i < cloud.points.size (); ++i) + { + data[i*3 + 0] = cloud.points[i].r; + data[i*3 + 1] = cloud.points[i].g; + data[i*3 + 2] = cloud.points[i].b; + } + saveRgbPNGFile(file_name, &data[0], cloud.width, cloud.height); + } + + /** \brief Saves Labeled Point cloud as image to PNG file. + * \param[in] file_name the name of the file to write to disk + * \param[in] cloud point cloud to save + * \ingroup io + * Warning: Converts to 16 bit (for png), labels using more than 16 bits will cause problems + */ + PCL_EXPORTS PCL_DEPRECATED ( + "savePNGFile (file_name, cloud) is deprecated, please use a new generic function " + "savePNGFile (file_name, cloud, field_name) with \"label\" as the field name." + ) + void + savePNGFile (const std::string& file_name, const pcl::PointCloud& cloud); + + /** \brief Saves the data from the specified field of the point cloud as image to PNG file. + * \param[in] file_name the name of the file to write to disk + * \param[in] cloud point cloud to save + * \param[in] field_name the name of the field to extract data from + * \ingroup io + */ + template void + savePNGFile (const std::string& file_name, const pcl::PointCloud& cloud, const std::string& field_name) + { + typedef typename PointCloudImageExtractor::Ptr PointCloudImageExtractorPtr; + PointCloudImageExtractorPtr pcie; + if (field_name == "normal") + { + pcie = PointCloudImageExtractorPtr (new PointCloudImageExtractorFromNormalField); + } + else if (field_name == "rgb") + { + pcie = PointCloudImageExtractorPtr (new PointCloudImageExtractorFromRGBField); + } + else if (field_name == "label") + { + pcie = PointCloudImageExtractorPtr (new PointCloudImageExtractorFromLabelField); + } + else if (field_name == "z") + { + pcie = PointCloudImageExtractorPtr (new PointCloudImageExtractorFromZField); + } + else if (field_name == "curvature") + { + pcie = PointCloudImageExtractorPtr (new PointCloudImageExtractorFromCurvatureField); + } + else if (field_name == "intensity") + { + pcie = PointCloudImageExtractorPtr (new PointCloudImageExtractorFromIntensityField); + } + else + { + PCL_ERROR ("[pcl::io::savePNGFile] Unsupported field \"%s\".\n", field_name.c_str ()); + return; + } + pcl::PCLImage image; + if (pcie->extract (cloud, image)) + { + savePNGFile(file_name, image); + } + else + { + PCL_ERROR ("[pcl::io::savePNGFile] Failed to extract an image from \"%s\" field.\n", field_name.c_str()); + } + } + + } +} + +#endif //#ifndef PCL_IO_PNG_IO_H_ diff --git a/pcl-1.7/pcl/io/point_cloud_image_extractors.h b/pcl-1.7/pcl/io/point_cloud_image_extractors.h new file mode 100644 index 0000000..e7213b1 --- /dev/null +++ b/pcl-1.7/pcl/io/point_cloud_image_extractors.h @@ -0,0 +1,437 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_POINT_CLOUD_IMAGE_EXTRACTORS_H_ +#define PCL_POINT_CLOUD_IMAGE_EXTRACTORS_H_ + +#include +#include + +namespace pcl +{ + namespace io + { + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Base Image Extractor class for organized point clouds. + * + * This is an abstract class that declares an interface for image extraction from + * organized point clouds. The family of its subclasses provide functionality to + * extract images from particular fields. + * + * The following piece of code demonstrates typical usage of a PointCloudImageExtractor + * subclass. Here the data are extracted from the "label" field and are saved as a + * PNG image file. + * + * \code + * // Source point cloud (needs to be filled with data of course) + * pcl::PointCloud cloud; + * // Target image + * pcl::PCLImage image; + * // Create PointCloudImageExtractor subclass that can handle "label" field + * pcl::io::PointCloudImageExtractorFromLabelField pcie; + * // Set it up if not happy with the defaults + * pcie.setColorMode(pcie.COLORS_RGB_RANDOM); + * // Try to extract an image + * bool success = pcie.extract(cloud, image); + * // Save to file if succeeded + * if (success) + * pcl::io::saveImage ("filename.png", image); + * \endcode + * + * \author Sergey Alexandrov + * \ingroup io + */ + template + class PointCloudImageExtractor + { + public: + typedef pcl::PointCloud PointCloud; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudImageExtractor () + : paint_nans_with_black_ (false) + {} + + /** \brief Destructor. */ + virtual ~PointCloudImageExtractor () {} + + /** \brief Obtain the image from the given cloud. + * \param[in] cloud organized point cloud to extract image from + * \param[out] image the output image + * \return true if the operation was successful, false otherwise + */ + bool + extract (const PointCloud& cloud, pcl::PCLImage& image) const; + + /** \brief Set a flag that controls if image pixels corresponding to + * NaN (infinite) points should be painted black. + */ + inline void + setPaintNaNsWithBlack (bool flag) + { + paint_nans_with_black_ = flag; + } + + protected: + + /** \brief Implementation of the extract() function, has to be + * implemented in deriving classes. + */ + virtual bool + extractImpl (const PointCloud& cloud, pcl::PCLImage& image) const = 0; + + /// A flag that controls if image pixels corresponding to NaN (infinite) + /// points should be painted black. + bool paint_nans_with_black_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Image Extractor extension which provides functionality to apply scaling to + * the values extracted from a field. + * \author Sergey Alexandrov + * \ingroup io + */ + template + class PointCloudImageExtractorWithScaling : public PointCloudImageExtractor + { + typedef typename PointCloudImageExtractor::PointCloud PointCloud; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Different scaling methods. + *
    + *
  • SCALING_NO - no scaling.
  • + *
  • SCALING_FULL_RANGE - scales to full range of the output value.
  • + *
  • SCASING_FIXED_FACTOR - scales by a given fixed factor.
  • + *
+ */ + enum ScalingMethod + { + SCALING_NO, + SCALING_FULL_RANGE, + SCALING_FIXED_FACTOR + }; + + /** \brief Constructor. */ + PointCloudImageExtractorWithScaling (const std::string& field_name, const ScalingMethod scaling_method) + : field_name_ (field_name) + , scaling_method_ (scaling_method) + , scaling_factor_ (1.0f) + { + } + + /** \brief Constructor. */ + PointCloudImageExtractorWithScaling (const std::string& field_name, const float scaling_factor) + : field_name_ (field_name) + , scaling_method_ (SCALING_FIXED_FACTOR) + , scaling_factor_ (scaling_factor) + { + } + + /** \brief Destructor. */ + virtual ~PointCloudImageExtractorWithScaling () {} + + /** \brief Set scaling method. */ + inline void + setScalingMethod (const ScalingMethod scaling_method) + { + scaling_method_ = scaling_method; + } + + /** \brief Set fixed scaling factor. */ + inline void + setScalingFactor (const float scaling_factor) + { + scaling_factor_ = scaling_factor; + } + + protected: + + virtual bool + extractImpl (const PointCloud& cloud, pcl::PCLImage& image) const; + + std::string field_name_; + ScalingMethod scaling_method_; + float scaling_factor_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Image Extractor which uses the data present in the "normal" field. Normal + * vector components (x, y, z) are mapped to color channels (r, g, b respectively). + * \author Sergey Alexandrov + * \ingroup io + */ + template + class PointCloudImageExtractorFromNormalField : public PointCloudImageExtractor + { + typedef typename PointCloudImageExtractor::PointCloud PointCloud; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudImageExtractorFromNormalField () {} + + /** \brief Destructor. */ + virtual ~PointCloudImageExtractorFromNormalField () {} + + protected: + + virtual bool + extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Image Extractor which uses the data present in the "rgb" or "rgba" fields + * to produce a color image with rgb8 encoding. + * \author Sergey Alexandrov + * \ingroup io + */ + template + class PointCloudImageExtractorFromRGBField : public PointCloudImageExtractor + { + typedef typename PointCloudImageExtractor::PointCloud PointCloud; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudImageExtractorFromRGBField () {} + + /** \brief Destructor. */ + virtual ~PointCloudImageExtractorFromRGBField () {} + + protected: + + virtual bool + extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Image Extractor which uses the data present in the "label" field to produce + * either monochrome or RGB image where different labels correspond to different + * colors. + * See the documentation for ColorMode to learn about available coloring options. + * \author Sergey Alexandrov + * \ingroup io + */ + template + class PointCloudImageExtractorFromLabelField : public PointCloudImageExtractor + { + typedef typename PointCloudImageExtractor::PointCloud PointCloud; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Different modes for color mapping. */ + enum ColorMode + { + /// Shades of gray (according to label id) + /// \note Labels using more than 16 bits will cause problems + COLORS_MONO, + /// Randomly generated RGB colors + COLORS_RGB_RANDOM, + /// Fixed RGB colors from the [Glasbey lookup table](http://fiji.sc/Glasbey), + /// assigned in the ascending order of label id + COLORS_RGB_GLASBEY, + }; + + /** \brief Constructor. */ + PointCloudImageExtractorFromLabelField (const ColorMode color_mode = COLORS_MONO) + : color_mode_ (color_mode) + { + } + + /** \brief Destructor. */ + virtual ~PointCloudImageExtractorFromLabelField () {} + + /** \brief Set color mapping mode. */ + inline void + setColorMode (const ColorMode color_mode) + { + color_mode_ = color_mode; + } + + protected: + + virtual bool + extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const; + + private: + + ColorMode color_mode_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Image Extractor which uses the data present in the "z" field to produce a + * depth map (as a monochrome image with mono16 encoding). + * \author Sergey Alexandrov + * \ingroup io + */ + template + class PointCloudImageExtractorFromZField : public PointCloudImageExtractorWithScaling + { + typedef typename PointCloudImageExtractor::PointCloud PointCloud; + typedef typename PointCloudImageExtractorWithScaling::ScalingMethod ScalingMethod; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. + * \param[in] scaling_factor a scaling factor to apply to each depth value (default 10000) + */ + PointCloudImageExtractorFromZField (const float scaling_factor = 10000) + : PointCloudImageExtractorWithScaling ("z", scaling_factor) + { + } + + /** \brief Constructor. + * \param[in] scaling_method a scaling method to use + */ + PointCloudImageExtractorFromZField (const ScalingMethod scaling_method) + : PointCloudImageExtractorWithScaling ("z", scaling_method) + { + } + + /** \brief Destructor. */ + virtual ~PointCloudImageExtractorFromZField () {} + + protected: + // Members derived from the base class + using PointCloudImageExtractorWithScaling::field_name_; + using PointCloudImageExtractorWithScaling::scaling_method_; + using PointCloudImageExtractorWithScaling::scaling_factor_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Image Extractor which uses the data present in the "curvature" field to + * produce a curvature map (as a monochrome image with mono16 encoding). + * \author Sergey Alexandrov + * \ingroup io + */ + template + class PointCloudImageExtractorFromCurvatureField : public PointCloudImageExtractorWithScaling + { + typedef typename PointCloudImageExtractor::PointCloud PointCloud; + typedef typename PointCloudImageExtractorWithScaling::ScalingMethod ScalingMethod; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. + * \param[in] scaling_method a scaling method to use (default SCALING_FULL_RANGE) + */ + PointCloudImageExtractorFromCurvatureField (const ScalingMethod scaling_method = PointCloudImageExtractorWithScaling::SCALING_FULL_RANGE) + : PointCloudImageExtractorWithScaling ("curvature", scaling_method) + { + } + + /** \brief Constructor. + * \param[in] scaling_factor a scaling factor to apply to each curvature value + */ + PointCloudImageExtractorFromCurvatureField (const float scaling_factor) + : PointCloudImageExtractorWithScaling ("curvature", scaling_factor) + { + } + + /** \brief Destructor. */ + virtual ~PointCloudImageExtractorFromCurvatureField () {} + + protected: + // Members derived from the base class + using PointCloudImageExtractorWithScaling::field_name_; + using PointCloudImageExtractorWithScaling::scaling_method_; + using PointCloudImageExtractorWithScaling::scaling_factor_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Image Extractor which uses the data present in the "intensity" field to produce a + * monochrome intensity image (with mono16 encoding). + * \author Sergey Alexandrov + * \ingroup io + */ + template + class PointCloudImageExtractorFromIntensityField : public PointCloudImageExtractorWithScaling + { + typedef typename PointCloudImageExtractor::PointCloud PointCloud; + typedef typename PointCloudImageExtractorWithScaling::ScalingMethod ScalingMethod; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. + * \param[in] scaling_method a scaling method to use (default SCALING_NO) + */ + PointCloudImageExtractorFromIntensityField (const ScalingMethod scaling_method = PointCloudImageExtractorWithScaling::SCALING_NO) + : PointCloudImageExtractorWithScaling ("intensity", scaling_method) + { + } + + /** \brief Constructor. + * \param[in] scaling_factor a scaling factor to apply to each intensity value + */ + PointCloudImageExtractorFromIntensityField (const float scaling_factor) + : PointCloudImageExtractorWithScaling ("intensity", scaling_factor) + { + } + + /** \brief Destructor. */ + virtual ~PointCloudImageExtractorFromIntensityField () {} + + protected: + // Members derived from the base class + using PointCloudImageExtractorWithScaling::field_name_; + using PointCloudImageExtractorWithScaling::scaling_method_; + using PointCloudImageExtractorWithScaling::scaling_factor_; + }; + + } +} + +#include + +#endif //#ifndef PCL_POINT_CLOUD_IMAGE_EXTRACTORS_H_ diff --git a/pcl-1.7/pcl/io/robot_eye_grabber.h b/pcl-1.7/pcl/io/robot_eye_grabber.h new file mode 100644 index 0000000..6045bfd --- /dev/null +++ b/pcl-1.7/pcl/io/robot_eye_grabber.h @@ -0,0 +1,149 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#include "pcl/pcl_config.h" + +#ifndef PCL_IO_ROBOT_EYE_GRABBER_H_ +#define PCL_IO_ROBOT_EYE_GRABBER_H_ + +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + + /** \brief Grabber for the Ocular Robotics RobotEye sensor. + * \ingroup io + */ + class PCL_EXPORTS RobotEyeGrabber : public Grabber + { + public: + + /** \brief Signal used for the point cloud callback. + * This signal is sent when the accumulated number of points reaches + * the limit specified by setSignalPointCloudSize(). + */ + typedef void (sig_cb_robot_eye_point_cloud_xyzi) ( + const boost::shared_ptr >&); + + /** \brief RobotEyeGrabber default constructor. */ + RobotEyeGrabber (); + + /** \brief RobotEyeGrabber constructor taking a specified IP address and data port. */ + RobotEyeGrabber (const boost::asio::ip::address& ipAddress, unsigned short port=443); + + /** \brief virtual Destructor inherited from the Grabber interface. It never throws. */ + virtual ~RobotEyeGrabber () throw (); + + /** \brief Starts the RobotEye grabber. + * The grabber runs on a separate thread, this call will return without blocking. */ + virtual void start (); + + /** \brief Stops the RobotEye grabber. */ + virtual void stop (); + + /** \brief Obtains the name of this I/O Grabber + * \return The name of the grabber + */ + virtual std::string getName () const; + + /** \brief Check if the grabber is still running. + * \return TRUE if the grabber is running, FALSE otherwise + */ + virtual bool isRunning () const; + + /** \brief Returns the number of frames per second. + */ + virtual float getFramesPerSecond () const; + + /** \brief Set/get ip address of the sensor that sends the data. + * The default is address_v4::any (). + */ + void setSensorAddress (const boost::asio::ip::address& ipAddress); + const boost::asio::ip::address& getSensorAddress () const; + + /** \brief Set/get the port number which receives data from the sensor. + * The default is 443. + */ + void setDataPort (unsigned short port); + unsigned short getDataPort () const; + + /** \brief Set/get the number of points to accumulate before the grabber + * callback is signaled. The default is 1000. + */ + void setSignalPointCloudSize (std::size_t numerOfPoints); + std::size_t getSignalPointCloudSize () const; + + /** \brief Returns the point cloud with point accumulated by the grabber. + * It is not safe to access this point cloud except if the grabber is + * stopped or during the grabber callback. + */ + boost::shared_ptr > getPointCloud() const; + + private: + + bool terminate_thread_; + size_t signal_point_cloud_size_; + unsigned short data_port_; + unsigned char receive_buffer_[500]; + + boost::asio::ip::address sensor_address_; + boost::asio::ip::udp::endpoint sender_endpoint_; + boost::asio::io_service io_service_; + boost::shared_ptr socket_; + boost::shared_ptr socket_thread_; + boost::shared_ptr consumer_thread_; + + pcl::SynchronizedQueue > packet_queue_; + boost::shared_ptr > point_cloud_xyzi_; + boost::signals2::signal* point_cloud_signal_; + + void consumerThreadLoop (); + void socketThreadLoop (); + void asyncSocketReceive (); + void resetPointCloud (); + void socketCallback (const boost::system::error_code& error, std::size_t numberOfBytes); + void convertPacketData (unsigned char *dataPacket, size_t length); + void computeXYZI (pcl::PointXYZI& pointXYZI, unsigned char* pointData); + }; +} + +#endif /* PCL_IO_ROBOT_EYE_GRABBER_H_ */ diff --git a/pcl-1.7/pcl/io/tar.h b/pcl-1.7/pcl/io/tar.h new file mode 100644 index 0000000..18e95fd --- /dev/null +++ b/pcl-1.7/pcl/io/tar.h @@ -0,0 +1,102 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_IO_TAR_H_ +#define PCL_IO_TAR_H_ + +#include + +namespace pcl +{ + namespace io + { + /** \brief A TAR file's header, as described on + * http://en.wikipedia.org/wiki/Tar_%28file_format%29. + */ + struct TARHeader + { + char file_name[100]; + char file_mode[8]; + char uid[8]; + char gid[8]; + char file_size[12]; + char mtime[12]; + char chksum[8]; + char file_type[1]; + char link_file_name[100]; + char ustar[6]; + char ustar_version[2]; + char uname[32]; + char gname[32]; + char dev_major[8]; + char dev_minor[8]; + char file_name_prefix[155]; + char _padding[12]; + + /** \brief get file size */ + unsigned int + getFileSize () + { + unsigned int output = 0; + char *str = file_size; + for (int i = 0; i < 11; i++) + { + output = output * 8 + *str - '0'; + str++; + } + return (output); + } + }; + + /** \brief Save a PointCloud dataset into a TAR file. + * Append if the file exists, or create a new one if not. + * \remark till implemented will return FALSE + */ + // param[in] tar_filename the name of the TAR file to save the cloud to + // param[in] cloud the point cloud dataset to save + // param[in] pcd_filename the internal name of the PCD file that should be stored in the TAR header + template bool + saveTARPointCloud (const std::string& /*tar_filename*/, + const PointCloud& /*cloud*/, + const std::string& /*pcd_filename*/) + { + return (false); + } + } +} +#endif // PCL_IO_TAR_H_ + diff --git a/pcl-1.7/pcl/io/vtk_io.h b/pcl-1.7/pcl/io/vtk_io.h new file mode 100644 index 0000000..ee02cce --- /dev/null +++ b/pcl-1.7/pcl/io/vtk_io.h @@ -0,0 +1,75 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_IO_VTK_IO_H_ +#define PCL_IO_VTK_IO_H_ + +#include +#include +#include + +// Please do not add any functions tha depend on VTK structures to this file! +// Use vtk_io_lib.h instead. + +namespace pcl +{ + namespace io + { + /** \brief Saves a PolygonMesh in ascii VTK format. + * \param[in] file_name the name of the file to write to disk + * \param[in] triangles the polygonal mesh to save + * \param[in] precision the output ASCII precision + * \ingroup io + */ + PCL_EXPORTS int + saveVTKFile (const std::string &file_name, const pcl::PolygonMesh &triangles, unsigned precision = 5); + + /** \brief Saves a PointCloud in ascii VTK format. + * \param[in] file_name the name of the file to write to disk + * \param[in] cloud the point cloud to save + * \param[in] precision the output ASCII precision + * \ingroup io + */ + PCL_EXPORTS int + saveVTKFile (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, unsigned precision = 5); + } +} + +#endif //#ifndef PCL_IO_VTK_IO_H_ diff --git a/pcl-1.7/pcl/io/vtk_lib_io.h b/pcl-1.7/pcl/io/vtk_lib_io.h new file mode 100644 index 0000000..f5cbd23 --- /dev/null +++ b/pcl-1.7/pcl/io/vtk_lib_io.h @@ -0,0 +1,262 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Dirk Holz, University of Bonn. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_IO_VTK_LIB_IO_H_ +#define PCL_IO_VTK_LIB_IO_H_ + +#include +#include +#include +#include +#include +#include +#include +#include + +// Ignore warnings in the above headers +#ifdef __GNUC__ +#pragma GCC system_header +#endif +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace io + { + /** \brief Convert vtkPolyData object to a PCL PolygonMesh + * \param[in] poly_data Pointer (vtkSmartPointer) to a vtkPolyData object + * \param[out] mesh PCL Polygon Mesh to fill + * \return Number of points in the point cloud of mesh. + */ + PCL_EXPORTS int + vtk2mesh (const vtkSmartPointer& poly_data, + pcl::PolygonMesh& mesh); + + /** \brief Convert vtkPolyData object to a PCL TextureMesh + * \note In addition to the vtk2mesh (const vtkSmartPointer&, pcl::PolygonMesh&) + * method, it fills the mesh with the uv-coordinates. + * \param[in] poly_data Pointer (vtkSmartPointer) to a vtkPolyData object + * \param[out] mesh PCL TextureMesh to fill + * \return Number of points in the point cloud of mesh. + */ + PCL_EXPORTS int + vtk2mesh (const vtkSmartPointer& poly_data, + pcl::TextureMesh& mesh); + + + /** \brief Convert a PCL PolygonMesh to a vtkPolyData object + * \param[in] mesh Reference to PCL Polygon Mesh + * \param[out] poly_data Pointer (vtkSmartPointer) to a vtkPolyData object + * \return Number of points in the point cloud of mesh. + */ + PCL_EXPORTS int + mesh2vtk (const pcl::PolygonMesh& mesh, + vtkSmartPointer& poly_data); + + /** \brief Load a \ref PolygonMesh object given an input file name, based on the file extension + * \param[in] file_name the name of the file containing the polygon data + * \param[out] mesh the object that we want to load the data in + * \ingroup io + */ + PCL_EXPORTS int + loadPolygonFile (const std::string &file_name, + pcl::PolygonMesh& mesh); + + /** \brief Save a \ref PolygonMesh object given an input file name, based on the file extension + * \param[in] file_name the name of the file to save the data to + * \param[in] mesh the object that contains the data + * \ingroup io + */ + PCL_EXPORTS int + savePolygonFile (const std::string &file_name, + const pcl::PolygonMesh& mesh); + + /** \brief Load a VTK file into a \ref PolygonMesh object + * \param[in] file_name the name of the file that contains the data + * \param[out] mesh the object that we want to load the data in + * \ingroup io + */ + PCL_EXPORTS int + loadPolygonFileVTK (const std::string &file_name, + pcl::PolygonMesh& mesh); + + /** \brief Load a PLY file into a \ref PolygonMesh object + * \param[in] file_name the name of the file that contains the data + * \param[out] mesh the object that we want to load the data in + * \ingroup io + */ + PCL_EXPORTS int + loadPolygonFilePLY (const std::string &file_name, + pcl::PolygonMesh& mesh); + + /** \brief Load an OBJ file into a \ref PolygonMesh object + * \param[in] file_name the name of the file that contains the data + * \param[out] mesh the object that we want to load the data in + * \ingroup io + */ + PCL_EXPORTS int + loadPolygonFileOBJ (const std::string &file_name, + pcl::PolygonMesh& mesh); + + /** \brief Load an OBJ file into a \ref TextureMesh object. + * \note In addition to the loadPolygonFileOBJ (const std::string, pcl::PolygonMesh&) + * method, this method also loads the uv-coordinates from the file. It does not + * load the material information. + * \param[in] file_name the name of the file that contains the data + * \param[out] mesh the object that we want to load the data in + * \ingroup io + */ + PCL_EXPORTS int + loadPolygonFileOBJ (const std::string &file_name, + pcl::TextureMesh& mesh); + + + /** \brief Load an STL file into a \ref PolygonMesh object + * \param[in] file_name the name of the file that contains the data + * \param[out] mesh the object that we want to load the data in + * \ingroup io + */ + PCL_EXPORTS int + loadPolygonFileSTL (const std::string &file_name, + pcl::PolygonMesh& mesh); + + /** \brief Save a \ref PolygonMesh object into a VTK file + * \param[in] file_name the name of the file to save the data to + * \param[in] mesh the object that contains the data + * \ingroup io + */ + PCL_EXPORTS int + savePolygonFileVTK (const std::string &file_name, + const pcl::PolygonMesh& mesh); + + /** \brief Save a \ref PolygonMesh object into a PLY file + * \param[in] file_name the name of the file to save the data to + * \param[in] mesh the object that contains the data + * \ingroup io + */ + PCL_EXPORTS int + savePolygonFilePLY (const std::string &file_name, + const pcl::PolygonMesh& mesh); + + /** \brief Save a \ref PolygonMesh object into an STL file + * \param[in] file_name the name of the file to save the data to + * \param[in] mesh the object that contains the data + * \ingroup io + */ + PCL_EXPORTS int + savePolygonFileSTL (const std::string &file_name, + const pcl::PolygonMesh& mesh); + + /** \brief Write a \ref RangeImagePlanar object to a PNG file + * \param[in] file_name the name of the file to save the data to + * \param[in] range_image the object that contains the data + * \ingroup io + */ + PCL_EXPORTS void + saveRangeImagePlanarFilePNG (const std::string &file_name, + const pcl::RangeImagePlanar& range_image); + + /** \brief Convert a pcl::PointCloud object to a VTK PolyData one. + * \param[in] cloud the input pcl::PointCloud object + * \param[out] polydata the resultant VTK PolyData object + * \ingroup io + */ + template void + pointCloudTovtkPolyData (const pcl::PointCloud& cloud, + vtkPolyData* const polydata); + + /** \brief Convert a PCLPointCloud2 object to a VTK PolyData object. + * \param[in] cloud the input PCLPointCloud2Ptr object + * \param[out] poly_data the resultant VTK PolyData object + * \ingroup io + */ + PCL_EXPORTS void + pointCloudTovtkPolyData(const pcl::PCLPointCloud2Ptr& cloud, vtkSmartPointer& poly_data); + + /** \brief Convert a pcl::PointCloud object to a VTK StructuredGrid one. + * \param[in] cloud the input pcl::PointCloud object + * \param[out] structured_grid the resultant VTK StructuredGrid object + * \ingroup io + */ + template void + pointCloudTovtkStructuredGrid (const pcl::PointCloud& cloud, + vtkStructuredGrid* const structured_grid); + + /** \brief Convert a VTK PolyData object to a pcl::PointCloud one. + * \param[in] polydata the input VTK PolyData object + * \param[out] cloud the resultant pcl::PointCloud object + * \ingroup io + */ + template void + vtkPolyDataToPointCloud (vtkPolyData* const polydata, + pcl::PointCloud& cloud); + + /** \brief Convert a VTK StructuredGrid object to a pcl::PointCloud one. + * \param[in] structured_grid the input VTK StructuredGrid object + * \param[out] cloud the resultant pcl::PointCloud object + * \ingroup io + */ + template void + vtkStructuredGridToPointCloud (vtkStructuredGrid* const structured_grid, + pcl::PointCloud& cloud); + + } +} + +#include + +#endif /* PLC_IO_VTK_LIB_IO_H_ */ diff --git a/pcl-1.7/pcl/kdtree/flann.h b/pcl-1.7/pcl/kdtree/flann.h new file mode 100644 index 0000000..7e9d1f6 --- /dev/null +++ b/pcl-1.7/pcl/kdtree/flann.h @@ -0,0 +1,59 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_KDTREE_FLANN_H_ +#define PCL_KDTREE_FLANN_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#if defined _MSC_VER +# pragma warning(disable: 4267 4244) +#endif + +// #define FLANN_USE_CUDA +#include + +#if defined _MSC_VER +# pragma warning(default: 4267) +#endif + +#endif // PCL_KDTREE_FLANN_H_ + + diff --git a/pcl-1.7/pcl/kdtree/impl/io.hpp b/pcl-1.7/pcl/kdtree/impl/io.hpp new file mode 100644 index 0000000..abf4db8 --- /dev/null +++ b/pcl-1.7/pcl/kdtree/impl/io.hpp @@ -0,0 +1,87 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_KDTREE_IO_IMPL_HPP_ +#define PCL_KDTREE_IO_IMPL_HPP_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::getApproximateIndices ( + const typename pcl::PointCloud::ConstPtr &cloud_in, + const typename pcl::PointCloud::ConstPtr &cloud_ref, + std::vector &indices) +{ + pcl::KdTreeFLANN tree; + tree.setInputCloud (cloud_ref); + + std::vector nn_idx (1); + std::vector nn_dists (1); + indices.resize (cloud_in->points.size ()); + for (size_t i = 0; i < cloud_in->points.size (); ++i) + { + tree.nearestKSearchT ((*cloud_in)[i], 1, nn_idx, nn_dists); + indices[i] = nn_idx[0]; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::getApproximateIndices ( + const typename pcl::PointCloud::ConstPtr &cloud_in, + const typename pcl::PointCloud::ConstPtr &cloud_ref, + std::vector &indices) +{ + pcl::KdTreeFLANN tree; + tree.setInputCloud (cloud_ref); + + std::vector nn_idx (1); + std::vector nn_dists (1); + indices.resize (cloud_in->points.size ()); + for (size_t i = 0; i < cloud_in->points.size (); ++i) + { + tree.nearestKSearch (*cloud_in, i, 1, nn_idx, nn_dists); + indices[i] = nn_idx[0]; + } +} + +#endif // PCL_KDTREE_IO_IMPL_H_ + diff --git a/pcl-1.7/pcl/kdtree/impl/kdtree_flann.hpp b/pcl-1.7/pcl/kdtree/impl/kdtree_flann.hpp new file mode 100644 index 0000000..e10c452 --- /dev/null +++ b/pcl-1.7/pcl/kdtree/impl/kdtree_flann.hpp @@ -0,0 +1,333 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_KDTREE_KDTREE_IMPL_FLANN_H_ +#define PCL_KDTREE_KDTREE_IMPL_FLANN_H_ + +#include +#include +#include +#include + +#include +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::KdTreeFLANN::KdTreeFLANN (bool sorted) + : pcl::KdTree (sorted) + , flann_index_ (), cloud_ () + , index_mapping_ (), identity_mapping_ (false) + , dim_ (0), total_nr_points_ (0) + , param_k_ (::flann::SearchParams (-1 , epsilon_)) + , param_radius_ (::flann::SearchParams (-1, epsilon_, sorted)) + , tree_type_(0) +{ + + // PCL_ERROR ("(kdtree_flann.hpp) KdTreeFLANN()\n"); +} + +// /////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::KdTreeFLANN::KdTreeFLANN (const KdTreeFLANN &k) + : pcl::KdTree (false) + , flann_index_ (), cloud_ () + , index_mapping_ (), identity_mapping_ (false) + , dim_ (0), total_nr_points_ (0) + , param_k_ (::flann::SearchParams (-1 , epsilon_)) + , param_radius_ (::flann::SearchParams (-1, epsilon_, false)) + , tree_type_(0) +{ + *this = k; + + // PCL_ERROR ("KdTreeFLANN (const KdTreeFLANN &k)\n"); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::KdTreeFLANN::setEpsilon (float eps) +{ + epsilon_ = eps; + param_k_ = ::flann::SearchParams (-1 , epsilon_); + param_radius_ = ::flann::SearchParams (-1 , epsilon_, sorted_); +} + +///////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::KdTreeFLANN::setSortedResults (bool sorted) +{ + sorted_ = sorted; + param_k_ = ::flann::SearchParams (-1, epsilon_); + param_radius_ = ::flann::SearchParams (-1, epsilon_, sorted_); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::KdTreeFLANN::setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices) +{ + cleanup (); // Perform an automatic cleanup of structures + + epsilon_ = 0.0f; // default error bound value + dim_ = point_representation_->getNumberOfDimensions (); // Number of dimensions - default is 3 = xyz + + input_ = cloud; + indices_ = indices; + + // Allocate enough data + if (!input_) + { + // PCL_ERROR ("[pcl::KdTreeFLANN::setInputCloud] Invalid input!\n"); + return; + } + if (indices != NULL) + { + convertCloudToArray (*input_, *indices_); + } + else + { + convertCloudToArray (*input_); + } + total_nr_points_ = static_cast (index_mapping_.size ()); + if (total_nr_points_ == 0) + { + PCL_ERROR ("[pcl::KdTreeFLANN::setInputCloud] Cannot create a KDTree with an empty input cloud!\n"); + return; + } + + if (tree_type_ == 0) + { + flann_index_.reset (new FLANNIndex (::flann::Matrix (cloud_.get (), + index_mapping_.size (), + dim_), + ::flann::KDTreeSingleIndexParams (16))); + // ::flann::KDTreeCuda3dIndexParams ())); + } + + flann_index_->buildIndex (); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::KdTreeFLANN::nearestKSearch (const PointT &point, int k, + std::vector &k_indices, + std::vector &k_distances) const +{ + assert (point_representation_->isValid (point) && "Invalid (NaN, Inf) point coordinates given to nearestKSearch!"); + + // PCL_ERROR("Nearest K Search!!!\n"); + + if (k > total_nr_points_) + k = total_nr_points_; + + k_indices.resize (k); + k_distances.resize (k); + + std::vector query (dim_); + point_representation_->vectorize (static_cast (point), query); + + ::flann::Matrix k_indices_mat (&k_indices[0], 1, k); + ::flann::Matrix k_distances_mat (&k_distances[0], 1, k); + // Wrap the k_indices and k_distances vectors (no data copy) + flann_index_->knnSearch (::flann::Matrix (&query[0], 1, dim_), + k_indices_mat, k_distances_mat, + k, param_k_); + + // Do mapping to original point cloud + if (!identity_mapping_) + { + for (size_t i = 0; i < static_cast (k); ++i) + { + int& neighbor_index = k_indices[i]; + neighbor_index = index_mapping_[neighbor_index]; + } + } + + return (k); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::KdTreeFLANN::radiusSearch (const PointT &point, double radius, std::vector &k_indices, + std::vector &k_sqr_dists, unsigned int max_nn) const +{ + assert (point_representation_->isValid (point) && "Invalid (NaN, Inf) point coordinates given to radiusSearch!"); + + std::vector query (dim_); + point_representation_->vectorize (static_cast (point), query); + + // Has max_nn been set properly? + if (max_nn == 0 || max_nn > static_cast (total_nr_points_)) + max_nn = total_nr_points_; + + std::vector > indices(1); + std::vector > dists(1); + + ::flann::SearchParams params (param_radius_); + if (max_nn == static_cast(total_nr_points_)) + params.max_neighbors = -1; // return all neighbors in radius + else + params.max_neighbors = max_nn; + + int neighbors_in_radius = flann_index_->radiusSearch (::flann::Matrix (&query[0], 1, dim_), + indices, + dists, + static_cast (radius * radius), + params); + + // int neighbors_in_radius = flann_index_->radiusSearch (::flann::Matrix (&query[0], 1, dim_), + // indices, + // dists, + // static_cast (radius), + // params); + + //std::cout << "radius: " << radius << std::endl; + + k_indices = indices[0]; + k_sqr_dists = dists[0]; + + // Do mapping to original point cloud + if (!identity_mapping_) + { + for (int i = 0; i < neighbors_in_radius; ++i) + { + int& neighbor_index = k_indices[i]; + neighbor_index = index_mapping_[neighbor_index]; + } + } + + return (neighbors_in_radius); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::KdTreeFLANN::cleanup () +{ + // Data array cleanup + index_mapping_.clear (); + + if (indices_) + indices_.reset (); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::KdTreeFLANN::convertCloudToArray (const PointCloud &cloud) +{ + // PCL_ERROR("(kdtree_flann.hpp) convertCloudToArray(cloud)\n"); + // No point in doing anything if the array is empty + if (cloud.points.empty ()) + { + cloud_.reset (); + return; + } + + int original_no_of_points = static_cast (cloud.points.size ()); + + cloud_.reset (new float[original_no_of_points * dim_]); + float* cloud_ptr = cloud_.get (); + index_mapping_.reserve (original_no_of_points); + identity_mapping_ = true; + + for (int cloud_index = 0; cloud_index < original_no_of_points; ++cloud_index) + { + // Check if the point is invalid + if (!point_representation_->isValid (cloud.points[cloud_index])) + { + identity_mapping_ = false; + continue; + } + + index_mapping_.push_back (cloud_index); + + point_representation_->vectorize (cloud.points[cloud_index], cloud_ptr); + cloud_ptr += dim_; + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::KdTreeFLANN::convertCloudToArray (const PointCloud &cloud, const std::vector &indices) +{ + // PCL_ERROR("(kdtree_flann.hpp) convertCloudToArray(cloud, indice)\n"); + + // No point in doing anything if the array is empty + if (cloud.points.empty ()) + { + cloud_.reset (); + return; + } + + int original_no_of_points = static_cast (indices.size ()); + + cloud_.reset (new float[original_no_of_points * dim_]); + float* cloud_ptr = cloud_.get (); + index_mapping_.reserve (original_no_of_points); + // its a subcloud -> false + // true only identity: + // - indices size equals cloud size + // - indices only contain values between 0 and cloud.size - 1 + // - no index is multiple times in the list + // => index is complete + // But we can not guarantee that => identity_mapping_ = false + identity_mapping_ = false; + + for (std::vector::const_iterator iIt = indices.begin (); iIt != indices.end (); ++iIt) + { + // Check if the point is invalid + if (!point_representation_->isValid (cloud.points[*iIt])) + continue; + + // map from 0 - N -> indices [0] - indices [N] + index_mapping_.push_back (*iIt); // If the returned index should be for the indices vector + + point_representation_->vectorize (cloud.points[*iIt], cloud_ptr); + cloud_ptr += dim_; + } +} + +// template void +// pcl::KdTreeFLANN::setTreeType(int tree_type) +// { +// tree_type_ = tree_type; +// } + +#define PCL_INSTANTIATE_KdTreeFLANN(T) template class PCL_EXPORTS pcl::KdTreeFLANN; + +#endif //#ifndef _PCL_KDTREE_KDTREE_IMPL_FLANN_H_ + diff --git a/pcl-1.7/pcl/kdtree/io.h b/pcl-1.7/pcl/kdtree/io.h new file mode 100644 index 0000000..68a2a2f --- /dev/null +++ b/pcl-1.7/pcl/kdtree/io.h @@ -0,0 +1,79 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: io.h 2413 2011-09-07 07:01:00Z rusu $ + * + */ + +#ifndef PCL_KDTREE_IO_H_ +#define PCL_KDTREE_IO_H_ + +#include + +namespace pcl +{ + /** \brief Get a set of approximate indices for a given point cloud into a reference point cloud. + * The coordinates of the two point clouds can differ. The method uses an internal KdTree for + * finding the closest neighbors from \a cloud_in in \a cloud_ref. + * + * \param[in] cloud_in the input point cloud dataset + * \param[in] cloud_ref the reference point cloud dataset + * \param[out] indices the resultant set of nearest neighbor indices of \a cloud_in in \a cloud_ref + * \ingroup kdtree + */ + template void + getApproximateIndices (const typename pcl::PointCloud::ConstPtr &cloud_in, + const typename pcl::PointCloud::ConstPtr &cloud_ref, + std::vector &indices); + + /** \brief Get a set of approximate indices for a given point cloud into a reference point cloud. + * The coordinates of the two point clouds can differ. The method uses an internal KdTree for + * finding the closest neighbors from \a cloud_in in \a cloud_ref. + * + * \param[in] cloud_in the input point cloud dataset + * \param[in] cloud_ref the reference point cloud dataset + * \param[out] indices the resultant set of nearest neighbor indices of \a cloud_in in \a cloud_ref + * \ingroup kdtree + */ + template void + getApproximateIndices (const typename pcl::PointCloud::ConstPtr &cloud_in, + const typename pcl::PointCloud::ConstPtr &cloud_ref, + std::vector &indices); +} + +#include + +#endif //#ifndef PCL_KDTREE_IO_H_ + diff --git a/pcl-1.7/pcl/kdtree/kdtree.h b/pcl-1.7/pcl/kdtree/kdtree.h new file mode 100644 index 0000000..0739991 --- /dev/null +++ b/pcl-1.7/pcl/kdtree/kdtree.h @@ -0,0 +1,368 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_KDTREE_KDTREE_H_ +#define PCL_KDTREE_KDTREE_H_ + +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief KdTree represents the base spatial locator class for kd-tree implementations. + * \author Radu B Rusu, Bastian Steder, Michael Dixon + * \ingroup kdtree + */ + template + class KdTree + { + public: + typedef boost::shared_ptr > IndicesPtr; + typedef boost::shared_ptr > IndicesConstPtr; + + typedef pcl::PointCloud PointCloud; + typedef boost::shared_ptr PointCloudPtr; + typedef boost::shared_ptr PointCloudConstPtr; + + typedef pcl::PointRepresentation PointRepresentation; + //typedef boost::shared_ptr PointRepresentationPtr; + typedef boost::shared_ptr PointRepresentationConstPtr; + + // Boost shared pointers + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Empty constructor for KdTree. Sets some internal values to their defaults. + * \param[in] sorted set to true if the application that the tree will be used for requires sorted nearest neighbor indices (default). False otherwise. + */ + KdTree (bool sorted = true) : input_(), indices_(), + epsilon_(0.0f), min_pts_(1), sorted_(sorted), + point_representation_ (new DefaultPointRepresentation) + { + // PCL_ERROR ("Base Class: kdtree in pcl/kdtree\n"); + }; + + /** \brief Provide a pointer to the input dataset. + * \param[in] cloud the const boost shared pointer to a PointCloud message + * \param[in] indices the point indices subset that is to be used from \a cloud - if NULL the whole cloud is used + */ + virtual void + setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices = IndicesConstPtr ()) + { + input_ = cloud; + indices_ = indices; + } + + /** \brief Get a pointer to the vector of indices used. */ + inline IndicesConstPtr + getIndices () const + { + return (indices_); + } + + /** \brief Get a pointer to the input point cloud dataset. */ + inline PointCloudConstPtr + getInputCloud () const + { + return (input_); + } + + /** \brief Provide a pointer to the point representation to use to convert points into k-D vectors. + * \param[in] point_representation the const boost shared pointer to a PointRepresentation + */ + inline void + setPointRepresentation (const PointRepresentationConstPtr &point_representation) + { + point_representation_ = point_representation; + if (!input_) return; + setInputCloud (input_, indices_); // Makes sense in derived classes to reinitialize the tree + } + + /** \brief Get a pointer to the point representation used when converting points into k-D vectors. */ + inline PointRepresentationConstPtr + getPointRepresentation () const + { + return (point_representation_); + } + + /** \brief Destructor for KdTree. Deletes all allocated data arrays and destroys the kd-tree structures. */ + virtual ~KdTree () {}; + + /** \brief Search for k-nearest neighbors for the given query point. + * \param[in] p_q the given query point + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + */ + virtual int + nearestKSearch (const PointT &p_q, int k, + std::vector &k_indices, std::vector &k_sqr_distances) const = 0; + + /** \brief Search for k-nearest neighbors for the given query point. + * + * \attention This method does not do any bounds checking for the input index + * (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data. + * + * \param[in] cloud the point cloud data + * \param[in] index a \a valid index in \a cloud representing a \a valid (i.e., finite) query point + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * + * \return number of neighbors found + * + * \exception asserts in debug mode if the index is not between 0 and the maximum number of points + */ + virtual int + nearestKSearch (const PointCloud &cloud, int index, int k, + std::vector &k_indices, std::vector &k_sqr_distances) const + { + assert (index >= 0 && index < static_cast (cloud.points.size ()) && "Out-of-bounds error in nearestKSearch!"); + return (nearestKSearch (cloud.points[index], k, k_indices, k_sqr_distances)); + } + + /** \brief Search for k-nearest neighbors for the given query point. + * This method accepts a different template parameter for the point type. + * \param[in] point the given query point + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + */ + template inline int + nearestKSearchT (const PointTDiff &point, int k, + std::vector &k_indices, std::vector &k_sqr_distances) const + { + PointT p; + copyPoint (point, p); + return (nearestKSearch (p, k, k_indices, k_sqr_distances)); + } + + /** \brief Search for k-nearest neighbors for the given query point (zero-copy). + * + * \attention This method does not do any bounds checking for the input index + * (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data. + * + * \param[in] index a \a valid index representing a \a valid query point in the dataset given + * by \a setInputCloud. If indices were given in setInputCloud, index will be the position in + * the indices vector. + * + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + * + * \exception asserts in debug mode if the index is not between 0 and the maximum number of points + */ + virtual int + nearestKSearch (int index, int k, + std::vector &k_indices, std::vector &k_sqr_distances) const + { + if (indices_ == NULL) + { + assert (index >= 0 && index < static_cast (input_->points.size ()) && "Out-of-bounds error in nearestKSearch!"); + return (nearestKSearch (input_->points[index], k, k_indices, k_sqr_distances)); + } + else + { + assert (index >= 0 && index < static_cast (indices_->size ()) && "Out-of-bounds error in nearestKSearch!"); + return (nearestKSearch (input_->points[(*indices_)[index]], k, k_indices, k_sqr_distances)); + } + } + + /** \brief Search for all the nearest neighbors of the query point in a given radius. + * \param[in] p_q the given query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + * \return number of neighbors found in radius + */ + virtual int + radiusSearch (const PointT &p_q, double radius, std::vector &k_indices, + std::vector &k_sqr_distances, unsigned int max_nn = 0) const = 0; + + /** \brief Search for all the nearest neighbors of the query point in a given radius. + * + * \attention This method does not do any bounds checking for the input index + * (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data. + * + * \param[in] cloud the point cloud data + * \param[in] index a \a valid index in \a cloud representing a \a valid (i.e., finite) query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + * \return number of neighbors found in radius + * + * \exception asserts in debug mode if the index is not between 0 and the maximum number of points + */ + virtual int + radiusSearch (const PointCloud &cloud, int index, double radius, + std::vector &k_indices, std::vector &k_sqr_distances, + unsigned int max_nn = 0) const + { + assert (index >= 0 && index < static_cast (cloud.points.size ()) && "Out-of-bounds error in radiusSearch!"); + return (radiusSearch(cloud.points[index], radius, k_indices, k_sqr_distances, max_nn)); + } + + /** \brief Search for all the nearest neighbors of the query point in a given radius. + * \param[in] point the given query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + * \return number of neighbors found in radius + */ + template inline int + radiusSearchT (const PointTDiff &point, double radius, std::vector &k_indices, + std::vector &k_sqr_distances, unsigned int max_nn = 0) const + { + PointT p; + copyPoint (point, p); + return (radiusSearch (p, radius, k_indices, k_sqr_distances, max_nn)); + } + + /** \brief Search for all the nearest neighbors of the query point in a given radius (zero-copy). + * + * \attention This method does not do any bounds checking for the input index + * (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data. + * + * \param[in] index a \a valid index representing a \a valid query point in the dataset given + * by \a setInputCloud. If indices were given in setInputCloud, index will be the position in + * the indices vector. + * + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + * \return number of neighbors found in radius + * + * \exception asserts in debug mode if the index is not between 0 and the maximum number of points + */ + virtual int + radiusSearch (int index, double radius, std::vector &k_indices, + std::vector &k_sqr_distances, unsigned int max_nn = 0) const + { + if (indices_ == NULL) + { + assert (index >= 0 && index < static_cast (input_->points.size ()) && "Out-of-bounds error in radiusSearch!"); + return (radiusSearch (input_->points[index], radius, k_indices, k_sqr_distances, max_nn)); + } + else + { + assert (index >= 0 && index < static_cast (indices_->size ()) && "Out-of-bounds error in radiusSearch!"); + return (radiusSearch (input_->points[(*indices_)[index]], radius, k_indices, k_sqr_distances, max_nn)); + } + } + + /** \brief Set the search epsilon precision (error bound) for nearest neighbors searches. + * \param[in] eps precision (error bound) for nearest neighbors searches + */ + virtual inline void + setEpsilon (float eps) + { + epsilon_ = eps; + } + + /** \brief Get the search epsilon precision (error bound) for nearest neighbors searches. */ + inline float + getEpsilon () const + { + return (epsilon_); + } + + /** \brief Minimum allowed number of k nearest neighbors points that a viable result must contain. + * \param[in] min_pts the minimum number of neighbors in a viable neighborhood + */ + inline void + setMinPts (int min_pts) + { + min_pts_ = min_pts; + } + + /** \brief Get the minimum allowed number of k nearest neighbors points that a viable result must contain. */ + inline int + getMinPts () const + { + return (min_pts_); + } + + protected: + /** \brief The input point cloud dataset containing the points we need to use. */ + PointCloudConstPtr input_; + + /** \brief A pointer to the vector of point indices to use. */ + IndicesConstPtr indices_; + + /** \brief Epsilon precision (error bound) for nearest neighbors searches. */ + float epsilon_; + + /** \brief Minimum allowed number of k nearest neighbors points that a viable result must contain. */ + int min_pts_; + + /** \brief Return the radius search neighbours sorted **/ + bool sorted_; + + /** \brief For converting different point structures into k-dimensional vectors for nearest-neighbor search. */ + PointRepresentationConstPtr point_representation_; + + /** \brief Class getName method. */ + virtual std::string + getName () const = 0; + }; +} + +#endif //#ifndef _PCL_KDTREE_KDTREE_H_ diff --git a/pcl-1.7/pcl/kdtree/kdtree_flann.h b/pcl-1.7/pcl/kdtree/kdtree_flann.h new file mode 100644 index 0000000..3b581ca --- /dev/null +++ b/pcl-1.7/pcl/kdtree/kdtree_flann.h @@ -0,0 +1,262 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: kdtree_flann.h 36261 2011-02-26 01:34:42Z mariusm $ + * + */ + +#ifndef PCL_KDTREE_KDTREE_FLANN_H_ +#define PCL_KDTREE_KDTREE_FLANN_H_ + +#include +#include + +#include + +#include + +// Forward declarations +namespace flann +{ + struct SearchParams; + template struct L2_Simple; + template class Index; +} + +namespace pcl +{ + // Forward declarations + template class PointRepresentation; + + /** \brief KdTreeFLANN is a generic type of 3D spatial locator using kD-tree structures. The class is making use of + * the FLANN (Fast Library for Approximate Nearest Neighbor) project by Marius Muja and David Lowe. + * + * \author Radu B. Rusu, Marius Muja + * \ingroup kdtree + */ + template > + class KdTreeFLANN : public pcl::KdTree + { + public: + using KdTree::input_; + using KdTree::indices_; + using KdTree::epsilon_; + using KdTree::sorted_; + using KdTree::point_representation_; + using KdTree::nearestKSearch; + using KdTree::radiusSearch; + + typedef typename KdTree::PointCloud PointCloud; + typedef typename KdTree::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr > IndicesPtr; + typedef boost::shared_ptr > IndicesConstPtr; + + typedef ::flann::Index FLANNIndex; + + // Boost shared pointers + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Default Constructor for KdTreeFLANN. + * \param[in] sorted set to true if the application that the tree will be used for requires sorted nearest neighbor indices (default). False otherwise. + * + * By setting sorted to false, the \ref radiusSearch operations will be faster. + */ + KdTreeFLANN (bool sorted = true); + // KdTreeFLANN () + // { + // PCL_ERROR("kdtree flann\n"); + // if (sorted_ == true) + // PCL_ERROR("true"); + // else + // PCL_ERROR("false"); + // } + + /** \brief Copy constructor + * \param[in] k the tree to copy into this + */ + KdTreeFLANN (const KdTreeFLANN &k); + + /** \brief Copy operator + * \param[in] k the tree to copy into this + */ + inline KdTreeFLANN& + operator = (const KdTreeFLANN& k) + { + KdTree::operator=(k); + flann_index_ = k.flann_index_; + cloud_ = k.cloud_; + index_mapping_ = k.index_mapping_; + identity_mapping_ = k.identity_mapping_; + dim_ = k.dim_; + total_nr_points_ = k.total_nr_points_; + param_k_ = k.param_k_; + param_radius_ = k.param_radius_; + // modification + tree_type_ = k.tree_type_; + return (*this); + } + + /** \brief Set the search epsilon precision (error bound) for nearest neighbors searches. + * \param[in] eps precision (error bound) for nearest neighbors searches + */ + void + setEpsilon (float eps); + + void + setSortedResults (bool sorted); + + inline Ptr makeShared () { return Ptr (new KdTreeFLANN (*this)); } + + /** \brief Destructor for KdTreeFLANN. + * Deletes all allocated data arrays and destroys the kd-tree structures. + */ + virtual ~KdTreeFLANN () + { + cleanup (); + // PCL_ERROR("Destructor: kdtree flann\n"); + } + + /** \brief Provide a pointer to the input dataset. + * \param[in] cloud the const boost shared pointer to a PointCloud message + * \param[in] indices the point indices subset that is to be used from \a cloud - if NULL the whole cloud is used + */ + void + // setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices = IndicesConstPtr ()); + setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices = IndicesConstPtr ()); + + /** \brief Search for k-nearest neighbors for the given query point. + * + * \attention This method does not do any bounds checking for the input index + * (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data. + * + * \param[in] point a given \a valid (i.e., finite) query point + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + * + * \exception asserts in debug mode if the index is not between 0 and the maximum number of points + */ + int + nearestKSearch (const PointT &point, int k, + std::vector &k_indices, std::vector &k_sqr_distances) const; + + /** \brief Search for all the nearest neighbors of the query point in a given radius. + * + * \attention This method does not do any bounds checking for the input index + * (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data. + * + * \param[in] point a given \a valid (i.e., finite) query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + * \return number of neighbors found in radius + * + * \exception asserts in debug mode if the index is not between 0 and the maximum number of points + */ + int + radiusSearch (const PointT &point, double radius, std::vector &k_indices, + std::vector &k_sqr_distances, unsigned int max_nn = 0) const; + + // modification + // set kdtree type + void setTreeType(int tree_type); + + private: + /** \brief Internal cleanup method. */ + void + cleanup (); + + /** \brief Converts a PointCloud to the internal FLANN point array representation. Returns the number + * of points. + * \param cloud the PointCloud + */ + void + convertCloudToArray (const PointCloud &cloud); + + /** \brief Converts a PointCloud with a given set of indices to the internal FLANN point array + * representation. Returns the number of points. + * \param[in] cloud the PointCloud data + * \param[in] indices the point cloud indices + */ + void + convertCloudToArray (const PointCloud &cloud, const std::vector &indices); + + private: + /** \brief Class getName method. */ + virtual std::string + getName () const { return ("KdTreeFLANN"); } + + /** \brief A FLANN index object. */ + boost::shared_ptr flann_index_; + + /** \brief Internal pointer to data. */ + boost::shared_array cloud_; + + /** \brief mapping between internal and external indices. */ + std::vector index_mapping_; + + /** \brief whether the mapping bwwteen internal and external indices is identity */ + bool identity_mapping_; + + /** \brief Tree dimensionality (i.e. the number of dimensions per point). */ + int dim_; + + /** \brief The total size of the data (either equal to the number of points in the input cloud or to the number of indices - if passed). */ + int total_nr_points_; + + /* tree type */ + int tree_type_; + + /** \brief The KdTree search parameters for K-nearest neighbors. */ + ::flann::SearchParams param_k_; + + /** \brief The KdTree search parameters for radius search. */ + ::flann::SearchParams param_radius_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/keypoints/agast_2d.h b/pcl-1.7/pcl/keypoints/agast_2d.h new file mode 100644 index 0000000..051fc56 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/agast_2d.h @@ -0,0 +1,842 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_KEYPOINTS_AGAST_KEYPOINT_2D_H_ +#define PCL_KEYPOINTS_AGAST_KEYPOINT_2D_H_ + +#include +#include +#include +#include + +namespace pcl +{ + namespace keypoints + { + namespace agast + { + + /** \brief Abstract detector class for AGAST corner point detectors. + * + * Adapted from the C++ implementation of Elmar Mair + * (http://www6.in.tum.de/Main/ResearchAgast). + * + * \author Stefan Holzer + * \ingroup keypoints + */ + class PCL_EXPORTS AbstractAgastDetector + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Constructor. + * \param[in] width the width of the image to process + * \param[in] height the height of the image to process + * \param[in] threshold the corner detection threshold + * \param[in] bmax the max image value (default: 255) + */ + AbstractAgastDetector (const size_t width, + const size_t height, + const double threshold, + const double bmax) + : width_ (width) + , height_ (height) + , threshold_ (threshold) + , nr_max_keypoints_ (std::numeric_limits::max ()) + , bmax_ (bmax) + {} + + /** \brief Destructor. */ + virtual ~AbstractAgastDetector () {} + + /** \brief Detects corner points. + * \param intensity_data + * \param output + */ + void + detectKeypoints (const std::vector &intensity_data, + pcl::PointCloud &output); + + /** \brief Detects corner points. + * \param intensity_data + * \param output + */ + void + detectKeypoints (const std::vector &intensity_data, + pcl::PointCloud &output); + + /** \brief Applies non-max-suppression. + * \param[in] intensity_data the image data + * \param[in] input the keypoint positions + * \param[out] output the resultant keypoints after non-max-supression + */ + void + applyNonMaxSuppression (const std::vector& intensity_data, + const pcl::PointCloud &input, + pcl::PointCloud &output); + + /** \brief Applies non-max-suppression. + * \param[in] intensity_data the image data + * \param[in] input the keypoint positions + * \param[out] output the resultant keypoints after non-max-supression + */ + void + applyNonMaxSuppression (const std::vector& intensity_data, + const pcl::PointCloud &input, + pcl::PointCloud &output); + + /** \brief Computes corner score. + * \param[in] im the pixels to compute the score at + */ + virtual int + computeCornerScore (const unsigned char* im) const = 0; + + /** \brief Computes corner score. + * \param[in] im the pixels to compute the score at + */ + virtual int + computeCornerScore (const float* im) const = 0; + + /** \brief Sets the threshold for corner detection. + * \param[in] threshold the threshold used for corner detection. + */ + inline void + setThreshold (const double threshold) + { + threshold_ = threshold; + } + + /** \brief Get the threshold for corner detection, as set by the user. */ + inline double + getThreshold () + { + return (threshold_); + } + + /** \brief Sets the maximum number of keypoints to return. The + * estimated keypoints are sorted by their internal score. + * \param[in] nr_max_keypoints set the maximum number of keypoints to return + */ + inline void + setMaxKeypoints (const unsigned int nr_max_keypoints) + { + nr_max_keypoints_ = nr_max_keypoints; + } + + /** \brief Get the maximum nuber of keypoints to return, as set by the user. */ + inline unsigned int + getMaxKeypoints () + { + return (nr_max_keypoints_); + } + + /** \brief Detects points of interest (i.e., keypoints) in the given image + * \param[in] im the image to detect keypoints in + * \param[out] corners_all the resultant set of keypoints detected + */ + virtual void + detect (const unsigned char* im, + std::vector > &corners_all) const = 0; + + /** \brief Detects points of interest (i.e., keypoints) in the given image + * \param[in] im the image to detect keypoints in + */ + virtual void + detect (const float* im, + std::vector > &) const = 0; + + protected: + + /** \brief Structure holding an index and the associated keypoint score. */ + struct ScoreIndex + { + int idx; + int score; + }; + + /** \brief Score index comparator. */ + struct CompareScoreIndex + { + /** \brief Comparator + * \param[in] i1 the first score index + * \param[in] i2 the second score index + */ + inline bool + operator() (const ScoreIndex &i1, const ScoreIndex &i2) + { + return (i1.score > i2.score); + } + }; + + /** \brief Initializes the sample pattern. */ + virtual void + initPattern () = 0; + + /** \brief Non-max-suppression helper method. + * \param[in] input the keypoint positions + * \param[in] scores the keypoint scores computed on the image data + * \param[out] output the resultant keypoints after non-max-supression + */ + void + applyNonMaxSuppression (const pcl::PointCloud &input, + const std::vector& scores, + pcl::PointCloud &output); + + /** \brief Computes corner scores for the specified points. + * \param im + * \param corners_all + * \param scores + */ + void + computeCornerScores (const unsigned char* im, + const std::vector > & corners_all, + std::vector & scores); + + /** \brief Computes corner scores for the specified points. + * \param im + * \param corners_all + * \param scores + */ + void + computeCornerScores (const float* im, + const std::vector > & corners_all, + std::vector & scores); + + /** \brief Width of the image to process. */ + size_t width_; + /** \brief Height of the image to process. */ + size_t height_; + + /** \brief Threshold for corner detection. */ + double threshold_; + + /** \brief The maximum number of keypoints to return. */ + unsigned int nr_max_keypoints_; + + /** \brief Max image value. */ + double bmax_; + }; + + /** \brief Detector class for AGAST corner point detector (7_12s). + * + * Adapted from the C++ implementation of Elmar Mair + * (http://www6.in.tum.de/Main/ResearchAgast). + * + * \author Stefan Holzer + * \ingroup keypoints + */ + class PCL_EXPORTS AgastDetector7_12s : public AbstractAgastDetector + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Constructor. + * \param[in] width the width of the image to process + * \param[in] height the height of the image to process + * \param[in] threshold the corner detection threshold + * \param[in] bmax the max image value (default: 255) + */ + AgastDetector7_12s (const size_t width, + const size_t height, + const double threshold, + const double bmax = 255) + : AbstractAgastDetector (width, height, threshold, bmax) + { + initPattern (); + } + + /** \brief Destructor. */ + ~AgastDetector7_12s () {} + + /** \brief Computes corner score. + * \param im + */ + int + computeCornerScore (const unsigned char* im) const; + + /** \brief Computes corner score. + * \param im + */ + int + computeCornerScore (const float* im) const; + + /** \brief Detects points of interest (i.e., keypoints) in the given image + * \param[in] im the image to detect keypoints in + * \param[out] corners_all the resultant set of keypoints detected + */ + void + detect (const unsigned char* im, std::vector > &corners_all) const; + + /** \brief Detects points of interest (i.e., keypoints) in the given image + * \param[in] im the image to detect keypoints in + * \param[out] corners_all the resultant set of keypoints detected + */ + void + detect (const float* im, std::vector > &corners_all) const; + + protected: + /** \brief Initializes the sample pattern. */ + void + initPattern (); + + private: + /** \brief Border width. */ + static const int border_width_ = 2; + + // offsets defining the sample pattern + int_fast16_t s_offset0_; + int_fast16_t s_offset1_; + int_fast16_t s_offset2_; + int_fast16_t s_offset3_; + int_fast16_t s_offset4_; + int_fast16_t s_offset5_; + int_fast16_t s_offset6_; + int_fast16_t s_offset7_; + int_fast16_t s_offset8_; + int_fast16_t s_offset9_; + int_fast16_t s_offset10_; + int_fast16_t s_offset11_; + }; + + /** \brief Detector class for AGAST corner point detector (5_8). + * + * Adapted from the C++ implementation of Elmar Mair + * (http://www6.in.tum.de/Main/ResearchAgast). + * + * \author Stefan Holzer + * \ingroup keypoints + */ + class PCL_EXPORTS AgastDetector5_8 : public AbstractAgastDetector + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Constructor. + * \param[in] width the width of the image to process + * \param[in] height the height of the image to process + * \param[in] threshold the corner detection threshold + * \param[in] bmax the max image value (default: 255) + */ + AgastDetector5_8 (const size_t width, + const size_t height, + const double threshold, + const double bmax = 255) + : AbstractAgastDetector (width, height, threshold, bmax) + { + initPattern (); + } + + /** \brief Destructor. */ + ~AgastDetector5_8 () {} + + /** \brief Computes corner score. + * \param im + */ + int + computeCornerScore (const unsigned char* im) const; + + /** \brief Computes corner score. + * \param im + */ + int + computeCornerScore (const float* im) const; + + /** \brief Detects points of interest (i.e., keypoints) in the given image + * \param[in] im the image to detect keypoints in + * \param[out] corners_all the resultant set of keypoints detected + */ + void + detect (const unsigned char* im, std::vector > &corners_all) const; + + /** \brief Detects points of interest (i.e., keypoints) in the given image + * \param[in] im the image to detect keypoints in + * \param[out] corners_all the resultant set of keypoints detected + */ + void + detect (const float* im, std::vector > &corners_all) const; + + protected: + /** \brief Initializes the sample pattern. */ + void + initPattern (); + + private: + /** \brief Border width. */ + static const int border_width_ = 1; + + // offsets defining the sample pattern + int_fast16_t s_offset0_; + int_fast16_t s_offset1_; + int_fast16_t s_offset2_; + int_fast16_t s_offset3_; + int_fast16_t s_offset4_; + int_fast16_t s_offset5_; + int_fast16_t s_offset6_; + int_fast16_t s_offset7_; + }; + + /** \brief Detector class for AGAST corner point detector (OAST 9_16). + * + * Adapted from the C++ implementation of Elmar Mair + * (http://www6.in.tum.de/Main/ResearchAgast). + * + * \author Stefan Holzer + * \ingroup keypoints + */ + class PCL_EXPORTS OastDetector9_16 : public AbstractAgastDetector + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Constructor. + * \param[in] width the width of the image to process + * \param[in] height the height of the image to process + * \param[in] threshold the corner detection threshold + * \param[in] bmax the max image value (default: 255) + */ + OastDetector9_16 (const size_t width, + const size_t height, + const double threshold, + const double bmax = 255) + : AbstractAgastDetector (width, height, threshold, bmax) + { + initPattern (); + } + + /** \brief Destructor. */ + ~OastDetector9_16 () {} + + /** \brief Computes corner score. + * \param im + */ + int + computeCornerScore (const unsigned char* im) const; + + /** \brief Computes corner score. + * \param im + */ + int + computeCornerScore (const float* im) const; + + /** \brief Detects points of interest (i.e., keypoints) in the given image + * \param[in] im the image to detect keypoints in + * \param[out] corners_all the resultant set of keypoints detected + */ + void + detect (const unsigned char* im, std::vector > &corners_all) const; + + /** \brief Detects points of interest (i.e., keypoints) in the given image + * \param[in] im the image to detect keypoints in + * \param[out] corners_all the resultant set of keypoints detected + */ + void + detect (const float* im, std::vector > &corners_all) const; + + protected: + /** \brief Initializes the sample pattern. */ + void + initPattern (); + + private: + /** \brief Border width. */ + static const int border_width_ = 3; + + // offsets defining the sample pattern + int_fast16_t s_offset0_; + int_fast16_t s_offset1_; + int_fast16_t s_offset2_; + int_fast16_t s_offset3_; + int_fast16_t s_offset4_; + int_fast16_t s_offset5_; + int_fast16_t s_offset6_; + int_fast16_t s_offset7_; + int_fast16_t s_offset8_; + int_fast16_t s_offset9_; + int_fast16_t s_offset10_; + int_fast16_t s_offset11_; + int_fast16_t s_offset12_; + int_fast16_t s_offset13_; + int_fast16_t s_offset14_; + int_fast16_t s_offset15_; + }; + } // namespace agast + } // namespace keypoints + + ///////////////////////////////////////////////////////////////////////////////////////// + ///////////////////////////////////////////////////////////////////////////////////////// + ///////////////////////////////////////////////////////////////////////////////////////// + namespace keypoints + { + namespace internal + { + ///////////////////////////////////////////////////////////////////////////////////// + template + struct AgastApplyNonMaxSuppresion + { + AgastApplyNonMaxSuppresion ( + const std::vector &image_data, + const pcl::PointCloud &tmp_cloud, + const pcl::keypoints::agast::AbstractAgastDetector::Ptr &detector, + pcl::PointCloud &output) + { + pcl::PointCloud output_temp; + detector->applyNonMaxSuppression (image_data, tmp_cloud, output_temp); + pcl::copyPointCloud (output_temp, output); + } + }; + + ///////////////////////////////////////////////////////////////////////////////////// + template <> + struct AgastApplyNonMaxSuppresion + { + AgastApplyNonMaxSuppresion ( + const std::vector &image_data, + const pcl::PointCloud &tmp_cloud, + const pcl::keypoints::agast::AbstractAgastDetector::Ptr &detector, + pcl::PointCloud &output) + { + detector->applyNonMaxSuppression (image_data, tmp_cloud, output); + } + }; + ///////////////////////////////////////////////////////////////////////////////////// + template + struct AgastDetector + { + AgastDetector ( + const std::vector &image_data, + const pcl::keypoints::agast::AbstractAgastDetector::Ptr &detector, + pcl::PointCloud &output) + { + pcl::PointCloud output_temp; + detector->detectKeypoints (image_data, output_temp); + pcl::copyPointCloud (output_temp, output); + } + }; + + ///////////////////////////////////////////////////////////////////////////////////// + template <> + struct AgastDetector + { + AgastDetector ( + const std::vector &image_data, + const pcl::keypoints::agast::AbstractAgastDetector::Ptr &detector, + pcl::PointCloud &output) + { + detector->detectKeypoints (image_data, output); + } + }; + } // namespace agast + } // namespace keypoints + + ///////////////////////////////////////////////////////////////////////////////////////// + ///////////////////////////////////////////////////////////////////////////////////////// + ///////////////////////////////////////////////////////////////////////////////////////// + /** \brief Detects 2D AGAST corner points. Based on the original work and + * paper reference by + * + * \par + * Elmar Mair, Gregory D. Hager, Darius Burschka, Michael Suppa, and Gerhard Hirzinger. + * Adaptive and generic corner detection based on the accelerated segment test. + * In Proceedings of the European Conference on Computer Vision (ECCV'10), September 2010. + * + * \note This is an abstract base class. All children must implement a detectKeypoints method, based on the type of AGAST keypoint to be used. + * + * \author Stefan Holzer, Radu B. Rusu + * \ingroup keypoints + */ + template > + class AgastKeypoint2DBase : public Keypoint + { + public: + typedef typename Keypoint::PointCloudIn PointCloudIn; + typedef typename Keypoint::PointCloudOut PointCloudOut; + typedef typename Keypoint::KdTree KdTree; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + typedef pcl::keypoints::agast::AbstractAgastDetector::Ptr AgastDetectorPtr; + + using Keypoint::name_; + using Keypoint::input_; + using Keypoint::indices_; + using Keypoint::k_; + + /** \brief Constructor */ + AgastKeypoint2DBase () + : threshold_ (10) + , apply_non_max_suppression_ (true) + , bmax_ (255) + , detector_ () + , nr_max_keypoints_ (std::numeric_limits::max ()) + { + k_ = 1; + } + + /** \brief Destructor. */ + virtual ~AgastKeypoint2DBase () + { + } + + /** \brief Sets the threshold for corner detection. + * \param[in] threshold the threshold used for corner detection. + */ + inline void + setThreshold (const double threshold) + { + threshold_ = threshold; + } + + /** \brief Get the threshold for corner detection, as set by the user. */ + inline double + getThreshold () + { + return (threshold_); + } + + /** \brief Sets the maximum number of keypoints to return. The + * estimated keypoints are sorted by their internal score. + * \param[in] nr_max_keypoints set the maximum number of keypoints to return + */ + inline void + setMaxKeypoints (const unsigned int nr_max_keypoints) + { + nr_max_keypoints_ = nr_max_keypoints; + } + + /** \brief Get the maximum nuber of keypoints to return, as set by the user. */ + inline unsigned int + getMaxKeypoints () + { + return (nr_max_keypoints_); + } + + /** \brief Sets the max image data value (affects how many iterations AGAST does) + * \param[in] bmax the max image data value + */ + inline void + setMaxDataValue (const double bmax) + { + bmax_ = bmax; + } + + /** \brief Get the bmax image value, as set by the user. */ + inline double + getMaxDataValue () + { + return (bmax_); + } + + /** \brief Sets whether non-max-suppression is applied or not. + * \param[in] enabled determines whether non-max-suppression is enabled. + */ + inline void + setNonMaxSuppression (const bool enabled) + { + apply_non_max_suppression_ = enabled; + } + + /** \brief Returns whether non-max-suppression is applied or not. */ + inline bool + getNonMaxSuppression () + { + return (apply_non_max_suppression_); + } + + inline void + setAgastDetector (const AgastDetectorPtr &detector) + { + detector_ = detector; + } + + inline AgastDetectorPtr + getAgastDetector () + { + return (detector_); + } + protected: + + /** \brief Initializes everything and checks whether input data is fine. */ + bool + initCompute (); + + /** \brief Detects the keypoints. + * \param[out] output the resultant keypoints + */ + virtual void + detectKeypoints (PointCloudOut &output) = 0; + + /** \brief Intensity field accessor. */ + IntensityT intensity_; + + /** \brief Threshold for corner detection. */ + double threshold_; + + /** \brief Determines whether non-max-suppression is activated. */ + bool apply_non_max_suppression_; + + /** \brief Max image value. */ + double bmax_; + + /** \brief The Agast detector to use. */ + AgastDetectorPtr detector_; + + /** \brief The maximum number of keypoints to return. */ + unsigned int nr_max_keypoints_; + }; + + /** \brief Detects 2D AGAST corner points. Based on the original work and + * paper reference by + * + * \par + * Elmar Mair, Gregory D. Hager, Darius Burschka, Michael Suppa, and Gerhard Hirzinger. + * Adaptive and generic corner detection based on the accelerated segment test. + * In Proceedings of the European Conference on Computer Vision (ECCV'10), September 2010. + * + * Code example: + * + * \code + * pcl::PointCloud cloud; + * pcl::AgastKeypoint2D agast; + * agast.setThreshold (30); + * agast.setInputCloud (cloud); + * + * PointCloud keypoints; + * agast.compute (keypoints); + * \endcode + * + * \note The AGAST keypoint type used is 7_12s. + * + * \author Stefan Holzer, Radu B. Rusu + * \ingroup keypoints + */ + template + class AgastKeypoint2D : public AgastKeypoint2DBase > + { + public: + typedef typename Keypoint::PointCloudOut PointCloudOut; + + using Keypoint::name_; + using Keypoint::input_; + using Keypoint::indices_; + using Keypoint::k_; + using AgastKeypoint2DBase >::intensity_; + using AgastKeypoint2DBase >::threshold_; + using AgastKeypoint2DBase >::bmax_; + using AgastKeypoint2DBase >::apply_non_max_suppression_; + using AgastKeypoint2DBase >::detector_; + using AgastKeypoint2DBase >::nr_max_keypoints_; + + /** \brief Constructor */ + AgastKeypoint2D () + { + name_ = "AgastKeypoint2D"; + } + + /** \brief Destructor. */ + virtual ~AgastKeypoint2D () + { + } + + protected: + /** \brief Detects the keypoints. + * \param[out] output the resultant keypoints + */ + virtual void + detectKeypoints (PointCloudOut &output); + }; + + /** \brief Detects 2D AGAST corner points. Based on the original work and + * paper reference by + * + * \par + * Elmar Mair, Gregory D. Hager, Darius Burschka, Michael Suppa, and Gerhard Hirzinger. + * Adaptive and generic corner detection based on the accelerated segment test. + * In Proceedings of the European Conference on Computer Vision (ECCV'10), September 2010. + * + * Code example: + * + * \code + * pcl::PointCloud cloud; + * pcl::AgastKeypoint2D agast; + * agast.setThreshold (30); + * agast.setInputCloud (cloud); + * + * PointCloud keypoints; + * agast.compute (keypoints); + * \endcode + * + * \note This is a specialized version for PointXYZ clouds, and operates on depth (z) as float. The output keypoints are of the PointXY type. + * \note The AGAST keypoint type used is 7_12s. + * + * \author Stefan Holzer, Radu B. Rusu + * \ingroup keypoints + */ + template <> + class AgastKeypoint2D + : public AgastKeypoint2DBase > + { + public: + /** \brief Constructor */ + AgastKeypoint2D () + { + name_ = "AgastKeypoint2D"; + bmax_ = 4; // max data value for an OpenNI camera + } + + /** \brief Destructor. */ + virtual ~AgastKeypoint2D () + { + } + + protected: + /** \brief Detects the keypoints. + * \param[out] output the resultant keypoints + */ + virtual void + detectKeypoints (pcl::PointCloud &output); + }; + +} + +#include + +#endif + diff --git a/pcl-1.7/pcl/keypoints/harris_3d.h b/pcl-1.7/pcl/keypoints/harris_3d.h new file mode 100644 index 0000000..b037155 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/harris_3d.h @@ -0,0 +1,186 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_HARRIS_KEYPOINT_3D_H_ +#define PCL_HARRIS_KEYPOINT_3D_H_ + +#include + +namespace pcl +{ + /** \brief HarrisKeypoint3D uses the idea of 2D Harris keypoints, but instead of using image gradients, it uses + * surface normals. + * + * \author Suat Gedikli + * \ingroup keypoints + */ + template + class HarrisKeypoint3D : public Keypoint + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename Keypoint::PointCloudIn PointCloudIn; + typedef typename Keypoint::PointCloudOut PointCloudOut; + typedef typename Keypoint::KdTree KdTree; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + + using Keypoint::name_; + using Keypoint::input_; + using Keypoint::indices_; + using Keypoint::surface_; + using Keypoint::tree_; + using Keypoint::k_; + using Keypoint::search_radius_; + using Keypoint::search_parameter_; + using Keypoint::keypoints_indices_; + using Keypoint::initCompute; + using PCLBase::setInputCloud; + + typedef enum {HARRIS = 1, NOBLE, LOWE, TOMASI, CURVATURE} ResponseMethod; + + /** \brief Constructor + * \param[in] method the method to be used to determine the corner responses + * \param[in] radius the radius for normal estimation as well as for non maxima suppression + * \param[in] threshold the threshold to filter out weak corners + */ + HarrisKeypoint3D (ResponseMethod method = HARRIS, float radius = 0.01f, float threshold = 0.0f) + : threshold_ (threshold) + , refine_ (true) + , nonmax_ (true) + , method_ (method) + , threads_ (0) + { + name_ = "HarrisKeypoint3D"; + search_radius_ = radius; + } + + /** \brief Empty destructor */ + virtual ~HarrisKeypoint3D () {} + + /** \brief Provide a pointer to the input dataset + * \param[in] cloud the const boost shared pointer to a PointCloud message + */ + virtual void + setInputCloud (const PointCloudInConstPtr &cloud); + + /** \brief Set the method of the response to be calculated. + * \param[in] type + */ + void + setMethod (ResponseMethod type); + + /** \brief Set the radius for normal estimation and non maxima supression. + * \param[in] radius + */ + void + setRadius (float radius); + + /** \brief Set the threshold value for detecting corners. This is only evaluated if non maxima suppression is turned on. + * \brief note non maxima suppression needs to be activated in order to use this feature. + * \param[in] threshold + */ + void + setThreshold (float threshold); + + /** \brief Whether non maxima suppression should be applied or the response for each point should be returned + * \note this value needs to be turned on in order to apply thresholding and refinement + * \param[in] nonmax default is false + */ + void + setNonMaxSupression (bool = false); + + /** \brief Whether the detected key points should be refined or not. If turned of, the key points are a subset of the original point cloud. Otherwise the key points may be arbitrary. + * \brief note non maxima supression needs to be on in order to use this feature. + * \param[in] do_refine + */ + void + setRefine (bool do_refine); + + /** \brief Set normals if precalculated normals are available. + * \param normals + */ + void + setNormals (const PointCloudNConstPtr &normals); + + /** \brief Provide a pointer to a dataset to add additional information + * to estimate the features for every point in the input dataset. This + * is optional, if this is not set, it will only use the data in the + * input cloud to estimate the features. This is useful when you only + * need to compute the features for a downsampled cloud. + * \param[in] cloud a pointer to a PointCloud message + */ + virtual void + setSearchSurface (const PointCloudInConstPtr &cloud) { surface_ = cloud; normals_.reset(); } + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + protected: + bool + initCompute (); + void detectKeypoints (PointCloudOut &output); + /** \brief gets the corner response for valid input points*/ + void responseHarris (PointCloudOut &output) const; + void responseNoble (PointCloudOut &output) const; + void responseLowe (PointCloudOut &output) const; + void responseTomasi (PointCloudOut &output) const; + void responseCurvature (PointCloudOut &output) const; + void refineCorners (PointCloudOut &corners) const; + /** \brief calculates the upper triangular part of unnormalized covariance matrix over the normals given by the indices.*/ + void calculateNormalCovar (const std::vector& neighbors, float* coefficients) const; + private: + float threshold_; + bool refine_; + bool nonmax_; + ResponseMethod method_; + PointCloudNConstPtr normals_; + unsigned int threads_; + }; +} + +#include + +#endif // #ifndef PCL_HARRIS_KEYPOINT_3D_H_ + diff --git a/pcl-1.7/pcl/keypoints/harris_6d.h b/pcl-1.7/pcl/keypoints/harris_6d.h new file mode 100644 index 0000000..37c0e72 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/harris_6d.h @@ -0,0 +1,144 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * @author Suat Gedikli + */ + +#ifndef PCL_HARRIS_KEYPOINT_6D_H_ +#define PCL_HARRIS_KEYPOINT_6D_H_ + +#include + +namespace pcl +{ + + /** \brief Keypoint detector for detecting corners in 3D (XYZ), 2D (intensity) AND mixed versions of these. + * \author Suat Gedikli + * \ingroup keypoints + */ + template + class HarrisKeypoint6D : public Keypoint + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename Keypoint::PointCloudIn PointCloudIn; + typedef typename Keypoint::PointCloudOut PointCloudOut; + typedef typename Keypoint::KdTree KdTree; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + using Keypoint::name_; + using Keypoint::input_; + using Keypoint::indices_; + using Keypoint::surface_; + using Keypoint::tree_; + using Keypoint::k_; + using Keypoint::search_radius_; + using Keypoint::search_parameter_; + using Keypoint::keypoints_indices_; + + /** + * @brief Constructor + * @param radius the radius for normal estimation as well as for non maxima suppression + * @param threshold the threshold to filter out weak corners + */ + HarrisKeypoint6D (float radius = 0.01, float threshold = 0.0) + : threshold_ (threshold) + , refine_ (true) + , nonmax_ (true) + , threads_ (0) + , normals_ (new pcl::PointCloud) + , intensity_gradients_ (new pcl::PointCloud) + { + name_ = "HarrisKeypoint6D"; + search_radius_ = radius; + } + + /** \brief Empty destructor */ + virtual ~HarrisKeypoint6D () {} + + /** + * @brief set the radius for normal estimation and non maxima supression. + * @param radius + */ + void setRadius (float radius); + + /** + * @brief set the threshold value for detecting corners. This is only evaluated if non maxima suppression is turned on. + * @brief note non maxima suppression needs to be activated in order to use this feature. + * @param threshold + */ + void setThreshold (float threshold); + + /** + * @brief whether non maxima suppression should be applied or the response for each point should be returned + * @note this value needs to be turned on in order to apply thresholding and refinement + * @param nonmax default is false + */ + void setNonMaxSupression (bool = false); + + /** + * @brief whether the detected key points should be refined or not. If turned of, the key points are a subset of the original point cloud. Otherwise the key points may be arbitrary. + * @brief note non maxima supression needs to be on in order to use this feature. + * @param do_refine + */ + void setRefine (bool do_refine); + + virtual void + setSearchSurface (const PointCloudInConstPtr &cloud) { surface_ = cloud; normals_->clear (); intensity_gradients_->clear ();} + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + protected: + void detectKeypoints (PointCloudOut &output); + void responseTomasi (PointCloudOut &output) const; + void refineCorners (PointCloudOut &corners) const; + void calculateCombinedCovar (const std::vector& neighbors, float* coefficients) const; + private: + float threshold_; + bool refine_; + bool nonmax_; + unsigned int threads_; + boost::shared_ptr > normals_; + boost::shared_ptr > intensity_gradients_; + } ; +} + +#include + +#endif // #ifndef PCL_HARRIS_KEYPOINT_6D_H_ + diff --git a/pcl-1.7/pcl/keypoints/impl/agast_2d.hpp b/pcl-1.7/pcl/keypoints/impl/agast_2d.hpp new file mode 100644 index 0000000..8e787ff --- /dev/null +++ b/pcl-1.7/pcl/keypoints/impl/agast_2d.hpp @@ -0,0 +1,102 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_KEYPOINTS_AGAST_KEYPOINT_2D_IMPL_H_ +#define PCL_KEYPOINTS_AGAST_KEYPOINT_2D_IMPL_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::AgastKeypoint2DBase::initCompute () +{ + if (!pcl::Keypoint::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] init failed.!\n", name_.c_str ()); + return (false); + } + + if (!input_->isOrganized ()) + { + PCL_ERROR ("[pcl::%s::initCompute] %s doesn't support non organized clouds!\n", name_.c_str ()); + return (false); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::AgastKeypoint2D::detectKeypoints (PointCloudOut &output) +{ + // image size + const size_t width = input_->width; + const size_t height = input_->height; + + // destination for intensity data; will be forwarded to AGAST + std::vector image_data (width*height); + + for (size_t i = 0; i < image_data.size (); ++i) + image_data[i] = static_cast (intensity_ ((*input_)[i])); + + if (!detector_) + detector_.reset (new pcl::keypoints::agast::AgastDetector7_12s (width, height, threshold_, bmax_)); + + detector_->setMaxKeypoints (nr_max_keypoints_); + + if (apply_non_max_suppression_) + { + pcl::PointCloud tmp_cloud; + detector_->detectKeypoints (image_data, tmp_cloud); + + pcl::keypoints::internal::AgastApplyNonMaxSuppresion anms ( + image_data, tmp_cloud, detector_, output); + } + else + { + pcl::keypoints::internal::AgastDetector dec ( + image_data, detector_, output); + } + + // we do not change the denseness + output.is_dense = true; +} + + +#define AgastKeypoint2D(T,I) template class PCL_EXPORTS pcl::AgastKeypoint2D; +#endif diff --git a/pcl-1.7/pcl/keypoints/impl/harris_3d.hpp b/pcl-1.7/pcl/keypoints/impl/harris_3d.hpp new file mode 100644 index 0000000..82e2c48 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/impl/harris_3d.hpp @@ -0,0 +1,541 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_HARRIS_KEYPOINT_3D_IMPL_H_ +#define PCL_HARRIS_KEYPOINT_3D_IMPL_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#ifdef __SSE__ +#include +#endif + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::setInputCloud (const PointCloudInConstPtr &cloud) +{ + if (normals_ && input_ && (cloud != input_)) + normals_.reset (); + input_ = cloud; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::setMethod (ResponseMethod method) +{ + method_ = method; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::setThreshold (float threshold) +{ + threshold_= threshold; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::setRadius (float radius) +{ + search_radius_ = radius; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::setRefine (bool do_refine) +{ + refine_ = do_refine; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::setNonMaxSupression (bool nonmax) +{ + nonmax_ = nonmax; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::setNormals (const PointCloudNConstPtr &normals) +{ + normals_ = normals; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::calculateNormalCovar (const std::vector& neighbors, float* coefficients) const +{ + unsigned count = 0; + // indices 0 1 2 3 4 5 6 7 + // coefficients: xx xy xz ?? yx yy yz ?? +#ifdef __SSE__ + // accumulator for xx, xy, xz + __m128 vec1 = _mm_setzero_ps(); + // accumulator for yy, yz, zz + __m128 vec2 = _mm_setzero_ps(); + + __m128 norm1; + + __m128 norm2; + + float zz = 0; + + for (std::vector::const_iterator iIt = neighbors.begin(); iIt != neighbors.end(); ++iIt) + { + if (pcl_isfinite (normals_->points[*iIt].normal_x)) + { + // nx, ny, nz, h + norm1 = _mm_load_ps (&(normals_->points[*iIt].normal_x)); + + // nx, nx, nx, nx + norm2 = _mm_set1_ps (normals_->points[*iIt].normal_x); + + // nx * nx, nx * ny, nx * nz, nx * h + norm2 = _mm_mul_ps (norm1, norm2); + + // accumulate + vec1 = _mm_add_ps (vec1, norm2); + + // ny, ny, ny, ny + norm2 = _mm_set1_ps (normals_->points[*iIt].normal_y); + + // ny * nx, ny * ny, ny * nz, ny * h + norm2 = _mm_mul_ps (norm1, norm2); + + // accumulate + vec2 = _mm_add_ps (vec2, norm2); + + zz += normals_->points[*iIt].normal_z * normals_->points[*iIt].normal_z; + ++count; + } + } + if (count > 0) + { + norm2 = _mm_set1_ps (float(count)); + vec1 = _mm_div_ps (vec1, norm2); + vec2 = _mm_div_ps (vec2, norm2); + _mm_store_ps (coefficients, vec1); + _mm_store_ps (coefficients + 4, vec2); + coefficients [7] = zz / float(count); + } + else + memset (coefficients, 0, sizeof (float) * 8); +#else + memset (coefficients, 0, sizeof (float) * 8); + for (std::vector::const_iterator iIt = neighbors.begin(); iIt != neighbors.end(); ++iIt) + { + if (pcl_isfinite (normals_->points[*iIt].normal_x)) + { + coefficients[0] += normals_->points[*iIt].normal_x * normals_->points[*iIt].normal_x; + coefficients[1] += normals_->points[*iIt].normal_x * normals_->points[*iIt].normal_y; + coefficients[2] += normals_->points[*iIt].normal_x * normals_->points[*iIt].normal_z; + + coefficients[5] += normals_->points[*iIt].normal_y * normals_->points[*iIt].normal_y; + coefficients[6] += normals_->points[*iIt].normal_y * normals_->points[*iIt].normal_z; + coefficients[7] += normals_->points[*iIt].normal_z * normals_->points[*iIt].normal_z; + + ++count; + } + } + if (count > 0) + { + float norm = 1.0 / float (count); + coefficients[0] *= norm; + coefficients[1] *= norm; + coefficients[2] *= norm; + coefficients[5] *= norm; + coefficients[6] *= norm; + coefficients[7] *= norm; + } +#endif +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::HarrisKeypoint3D::initCompute () +{ + if (!Keypoint::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] init failed!\n", name_.c_str ()); + return (false); + } + + if (method_ < 1 || method_ > 5) + { + PCL_ERROR ("[pcl::%s::initCompute] method (%d) must be in [1..5]!\n", name_.c_str (), method_); + return (false); + } + + if (!normals_) + { + PointCloudNPtr normals (new PointCloudN ()); + normals->reserve (normals->size ()); + if (!surface_->isOrganized ()) + { + pcl::NormalEstimation normal_estimation; + normal_estimation.setInputCloud (surface_); + normal_estimation.setRadiusSearch (search_radius_); + normal_estimation.compute (*normals); + } + else + { + IntegralImageNormalEstimation normal_estimation; + normal_estimation.setNormalEstimationMethod (pcl::IntegralImageNormalEstimation::SIMPLE_3D_GRADIENT); + normal_estimation.setInputCloud (surface_); + normal_estimation.setNormalSmoothingSize (5.0); + normal_estimation.compute (*normals); + } + normals_ = normals; + } + if (normals_->size () != surface_->size ()) + { + PCL_ERROR ("[pcl::%s::initCompute] normals given, but the number of normals does not match the number of input points!\n", name_.c_str (), method_); + return (false); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::detectKeypoints (PointCloudOut &output) +{ + boost::shared_ptr > response (new pcl::PointCloud ()); + + response->points.reserve (input_->points.size()); + + switch (method_) + { + case HARRIS: + responseHarris(*response); + break; + case NOBLE: + responseNoble(*response); + break; + case LOWE: + responseLowe(*response); + break; + case CURVATURE: + responseCurvature(*response); + break; + case TOMASI: + responseTomasi(*response); + break; + } + + if (!nonmax_) + { + output = *response; + // we do not change the denseness in this case + output.is_dense = input_->is_dense; + for (size_t i = 0; i < response->size (); ++i) + keypoints_indices_->indices.push_back (i); + } + else + { + output.points.clear (); + output.points.reserve (response->points.size()); + +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads(threads_) +#endif + for (int idx = 0; idx < static_cast (response->points.size ()); ++idx) + { + if (!isFinite (response->points[idx]) || + !pcl_isfinite (response->points[idx].intensity) || + response->points[idx].intensity < threshold_) + continue; + + std::vector nn_indices; + std::vector nn_dists; + tree_->radiusSearch (idx, search_radius_, nn_indices, nn_dists); + bool is_maxima = true; + for (std::vector::const_iterator iIt = nn_indices.begin(); iIt != nn_indices.end(); ++iIt) + { + if (response->points[idx].intensity < response->points[*iIt].intensity) + { + is_maxima = false; + break; + } + } + if (is_maxima) +#ifdef _OPENMP +#pragma omp critical +#endif + { + output.points.push_back (response->points[idx]); + keypoints_indices_->indices.push_back (idx); + } + } + + if (refine_) + refineCorners (output); + + output.height = 1; + output.width = static_cast (output.points.size()); + output.is_dense = true; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::responseHarris (PointCloudOut &output) const +{ + PCL_ALIGN (16) float covar [8]; + output.resize (input_->size ()); +#ifdef _OPENMP + #pragma omp parallel for shared (output) private (covar) num_threads(threads_) +#endif + for (int pIdx = 0; pIdx < static_cast (input_->size ()); ++pIdx) + { + const PointInT& pointIn = input_->points [pIdx]; + output [pIdx].intensity = 0.0; //std::numeric_limits::quiet_NaN (); + if (isFinite (pointIn)) + { + std::vector nn_indices; + std::vector nn_dists; + tree_->radiusSearch (pointIn, search_radius_, nn_indices, nn_dists); + calculateNormalCovar (nn_indices, covar); + + float trace = covar [0] + covar [5] + covar [7]; + if (trace != 0) + { + float det = covar [0] * covar [5] * covar [7] + 2.0f * covar [1] * covar [2] * covar [6] + - covar [2] * covar [2] * covar [5] + - covar [1] * covar [1] * covar [7] + - covar [6] * covar [6] * covar [0]; + + output [pIdx].intensity = 0.04f + det - 0.04f * trace * trace; + } + } + output [pIdx].x = pointIn.x; + output [pIdx].y = pointIn.y; + output [pIdx].z = pointIn.z; + } + output.height = input_->height; + output.width = input_->width; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::responseNoble (PointCloudOut &output) const +{ + PCL_ALIGN (16) float covar [8]; + output.resize (input_->size ()); +#ifdef _OPENMP + #pragma omp parallel for shared (output) private (covar) num_threads(threads_) +#endif + for (int pIdx = 0; pIdx < static_cast (input_->size ()); ++pIdx) + { + const PointInT& pointIn = input_->points [pIdx]; + output [pIdx].intensity = 0.0; + if (isFinite (pointIn)) + { + std::vector nn_indices; + std::vector nn_dists; + tree_->radiusSearch (pointIn, search_radius_, nn_indices, nn_dists); + calculateNormalCovar (nn_indices, covar); + float trace = covar [0] + covar [5] + covar [7]; + if (trace != 0) + { + float det = covar [0] * covar [5] * covar [7] + 2.0f * covar [1] * covar [2] * covar [6] + - covar [2] * covar [2] * covar [5] + - covar [1] * covar [1] * covar [7] + - covar [6] * covar [6] * covar [0]; + + output [pIdx].intensity = det / trace; + } + } + output [pIdx].x = pointIn.x; + output [pIdx].y = pointIn.y; + output [pIdx].z = pointIn.z; + } + output.height = input_->height; + output.width = input_->width; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::responseLowe (PointCloudOut &output) const +{ + PCL_ALIGN (16) float covar [8]; + output.resize (input_->size ()); +#ifdef _OPENMP + #pragma omp parallel for shared (output) private (covar) num_threads(threads_) +#endif + for (int pIdx = 0; pIdx < static_cast (input_->size ()); ++pIdx) + { + const PointInT& pointIn = input_->points [pIdx]; + output [pIdx].intensity = 0.0; + if (isFinite (pointIn)) + { + std::vector nn_indices; + std::vector nn_dists; + tree_->radiusSearch (pointIn, search_radius_, nn_indices, nn_dists); + calculateNormalCovar (nn_indices, covar); + float trace = covar [0] + covar [5] + covar [7]; + if (trace != 0) + { + float det = covar [0] * covar [5] * covar [7] + 2.0f * covar [1] * covar [2] * covar [6] + - covar [2] * covar [2] * covar [5] + - covar [1] * covar [1] * covar [7] + - covar [6] * covar [6] * covar [0]; + + output [pIdx].intensity = det / (trace * trace); + } + } + output [pIdx].x = pointIn.x; + output [pIdx].y = pointIn.y; + output [pIdx].z = pointIn.z; + } + output.height = input_->height; + output.width = input_->width; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::responseCurvature (PointCloudOut &output) const +{ + PointOutT point; + for (unsigned idx = 0; idx < input_->points.size(); ++idx) + { + point.x = input_->points[idx].x; + point.y = input_->points[idx].y; + point.z = input_->points[idx].z; + point.intensity = normals_->points[idx].curvature; + output.points.push_back(point); + } + // does not change the order + output.height = input_->height; + output.width = input_->width; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::responseTomasi (PointCloudOut &output) const +{ + PCL_ALIGN (16) float covar [8]; + Eigen::Matrix3f covariance_matrix; + output.resize (input_->size ()); +#ifdef _OPENMP + #pragma omp parallel for shared (output) private (covar, covariance_matrix) num_threads(threads_) +#endif + for (int pIdx = 0; pIdx < static_cast (input_->size ()); ++pIdx) + { + const PointInT& pointIn = input_->points [pIdx]; + output [pIdx].intensity = 0.0; + if (isFinite (pointIn)) + { + std::vector nn_indices; + std::vector nn_dists; + tree_->radiusSearch (pointIn, search_radius_, nn_indices, nn_dists); + calculateNormalCovar (nn_indices, covar); + float trace = covar [0] + covar [5] + covar [7]; + if (trace != 0) + { + covariance_matrix.coeffRef (0) = covar [0]; + covariance_matrix.coeffRef (1) = covariance_matrix.coeffRef (3) = covar [1]; + covariance_matrix.coeffRef (2) = covariance_matrix.coeffRef (6) = covar [2]; + covariance_matrix.coeffRef (4) = covar [5]; + covariance_matrix.coeffRef (5) = covariance_matrix.coeffRef (7) = covar [6]; + covariance_matrix.coeffRef (8) = covar [7]; + + EIGEN_ALIGN16 Eigen::Vector3f eigen_values; + pcl::eigen33(covariance_matrix, eigen_values); + output [pIdx].intensity = eigen_values[0]; + } + } + output [pIdx].x = pointIn.x; + output [pIdx].y = pointIn.y; + output [pIdx].z = pointIn.z; + } + output.height = input_->height; + output.width = input_->width; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint3D::refineCorners (PointCloudOut &corners) const +{ + Eigen::Matrix3f nnT; + Eigen::Matrix3f NNT; + Eigen::Matrix3f NNTInv; + Eigen::Vector3f NNTp; + float diff; + const unsigned max_iterations = 10; +#ifdef _OPENMP + #pragma omp parallel for shared (corners) private (nnT, NNT, NNTInv, NNTp, diff) num_threads(threads_) +#endif + for (int cIdx = 0; cIdx < static_cast (corners.size ()); ++cIdx) + { + unsigned iterations = 0; + do { + NNT.setZero(); + NNTp.setZero(); + PointInT corner; + corner.x = corners[cIdx].x; + corner.y = corners[cIdx].y; + corner.z = corners[cIdx].z; + std::vector nn_indices; + std::vector nn_dists; + tree_->radiusSearch (corner, search_radius_, nn_indices, nn_dists); + for (std::vector::const_iterator iIt = nn_indices.begin(); iIt != nn_indices.end(); ++iIt) + { + if (!pcl_isfinite (normals_->points[*iIt].normal_x)) + continue; + + nnT = normals_->points[*iIt].getNormalVector3fMap () * normals_->points[*iIt].getNormalVector3fMap ().transpose(); + NNT += nnT; + NNTp += nnT * surface_->points[*iIt].getVector3fMap (); + } + if (invert3x3SymMatrix (NNT, NNTInv) != 0) + corners[cIdx].getVector3fMap () = NNTInv * NNTp; + + diff = (corners[cIdx].getVector3fMap () - corner.getVector3fMap()).squaredNorm (); + } while (diff > 1e-6 && ++iterations < max_iterations); + } +} + +#define PCL_INSTANTIATE_HarrisKeypoint3D(T,U,N) template class PCL_EXPORTS pcl::HarrisKeypoint3D; +#endif // #ifndef PCL_HARRIS_KEYPOINT_3D_IMPL_H_ + diff --git a/pcl-1.7/pcl/keypoints/impl/harris_6d.hpp b/pcl-1.7/pcl/keypoints/impl/harris_6d.hpp new file mode 100644 index 0000000..fe97851 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/impl/harris_6d.hpp @@ -0,0 +1,407 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_HARRIS_KEYPOINT_6D_IMPL_H_ +#define PCL_HARRIS_KEYPOINT_6D_IMPL_H_ + +#include +#include +#include +#include +#include +//#include +#include +#include + +template void +pcl::HarrisKeypoint6D::setThreshold (float threshold) +{ + threshold_= threshold; +} + +template void +pcl::HarrisKeypoint6D::setRadius (float radius) +{ + search_radius_ = radius; +} + +template void +pcl::HarrisKeypoint6D::setRefine (bool do_refine) +{ + refine_ = do_refine; +} + +template void +pcl::HarrisKeypoint6D::setNonMaxSupression (bool nonmax) +{ + nonmax_ = nonmax; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint6D::calculateCombinedCovar (const std::vector& neighbors, float* coefficients) const +{ + memset (coefficients, 0, sizeof (float) * 21); + unsigned count = 0; + for (std::vector::const_iterator iIt = neighbors.begin(); iIt != neighbors.end(); ++iIt) + { + if (pcl_isfinite (normals_->points[*iIt].normal_x) && pcl_isfinite (intensity_gradients_->points[*iIt].gradient [0])) + { + coefficients[ 0] += normals_->points[*iIt].normal_x * normals_->points[*iIt].normal_x; + coefficients[ 1] += normals_->points[*iIt].normal_x * normals_->points[*iIt].normal_y; + coefficients[ 2] += normals_->points[*iIt].normal_x * normals_->points[*iIt].normal_z; + coefficients[ 3] += normals_->points[*iIt].normal_x * intensity_gradients_->points[*iIt].gradient [0]; + coefficients[ 4] += normals_->points[*iIt].normal_x * intensity_gradients_->points[*iIt].gradient [1]; + coefficients[ 5] += normals_->points[*iIt].normal_x * intensity_gradients_->points[*iIt].gradient [2]; + + coefficients[ 6] += normals_->points[*iIt].normal_y * normals_->points[*iIt].normal_y; + coefficients[ 7] += normals_->points[*iIt].normal_y * normals_->points[*iIt].normal_z; + coefficients[ 8] += normals_->points[*iIt].normal_y * intensity_gradients_->points[*iIt].gradient [0]; + coefficients[ 9] += normals_->points[*iIt].normal_y * intensity_gradients_->points[*iIt].gradient [1]; + coefficients[10] += normals_->points[*iIt].normal_y * intensity_gradients_->points[*iIt].gradient [2]; + + coefficients[11] += normals_->points[*iIt].normal_z * normals_->points[*iIt].normal_z; + coefficients[12] += normals_->points[*iIt].normal_z * intensity_gradients_->points[*iIt].gradient [0]; + coefficients[13] += normals_->points[*iIt].normal_z * intensity_gradients_->points[*iIt].gradient [1]; + coefficients[14] += normals_->points[*iIt].normal_z * intensity_gradients_->points[*iIt].gradient [2]; + + coefficients[15] += intensity_gradients_->points[*iIt].gradient [0] * intensity_gradients_->points[*iIt].gradient [0]; + coefficients[16] += intensity_gradients_->points[*iIt].gradient [0] * intensity_gradients_->points[*iIt].gradient [1]; + coefficients[17] += intensity_gradients_->points[*iIt].gradient [0] * intensity_gradients_->points[*iIt].gradient [2]; + + coefficients[18] += intensity_gradients_->points[*iIt].gradient [1] * intensity_gradients_->points[*iIt].gradient [1]; + coefficients[19] += intensity_gradients_->points[*iIt].gradient [1] * intensity_gradients_->points[*iIt].gradient [2]; + + coefficients[20] += intensity_gradients_->points[*iIt].gradient [2] * intensity_gradients_->points[*iIt].gradient [2]; + + ++count; + } + } + if (count > 0) + { + float norm = 1.0 / float (count); + coefficients[ 0] *= norm; + coefficients[ 1] *= norm; + coefficients[ 2] *= norm; + coefficients[ 3] *= norm; + coefficients[ 4] *= norm; + coefficients[ 5] *= norm; + coefficients[ 6] *= norm; + coefficients[ 7] *= norm; + coefficients[ 8] *= norm; + coefficients[ 9] *= norm; + coefficients[10] *= norm; + coefficients[11] *= norm; + coefficients[12] *= norm; + coefficients[13] *= norm; + coefficients[14] *= norm; + coefficients[15] *= norm; + coefficients[16] *= norm; + coefficients[17] *= norm; + coefficients[18] *= norm; + coefficients[19] *= norm; + coefficients[20] *= norm; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::HarrisKeypoint6D::detectKeypoints (PointCloudOut &output) +{ + if (normals_->empty ()) + { + normals_->reserve (surface_->size ()); + if (!surface_->isOrganized ()) + { + pcl::NormalEstimation normal_estimation; + normal_estimation.setInputCloud (surface_); + normal_estimation.setRadiusSearch (search_radius_); + normal_estimation.compute (*normals_); + } + else + { + IntegralImageNormalEstimation normal_estimation; + normal_estimation.setNormalEstimationMethod (pcl::IntegralImageNormalEstimation::SIMPLE_3D_GRADIENT); + normal_estimation.setInputCloud (surface_); + normal_estimation.setNormalSmoothingSize (5.0); + normal_estimation.compute (*normals_); + } + } + + pcl::PointCloud::Ptr cloud (new pcl::PointCloud); + cloud->resize (surface_->size ()); +#ifdef _OPENMP + #pragma omp parallel for num_threads(threads_) default(shared) +#endif + for (unsigned idx = 0; idx < surface_->size (); ++idx) + { + cloud->points [idx].x = surface_->points [idx].x; + cloud->points [idx].y = surface_->points [idx].y; + cloud->points [idx].z = surface_->points [idx].z; + //grayscale = 0.2989 * R + 0.5870 * G + 0.1140 * B + + cloud->points [idx].intensity = 0.00390625 * (0.114 * float(surface_->points [idx].b) + 0.5870 * float(surface_->points [idx].g) + 0.2989 * float(surface_->points [idx].r)); + } + pcl::copyPointCloud (*surface_, *cloud); + + IntensityGradientEstimation grad_est; + grad_est.setInputCloud (cloud); + grad_est.setInputNormals (normals_); + grad_est.setRadiusSearch (search_radius_); + grad_est.compute (*intensity_gradients_); + +#ifdef _OPENMP + #pragma omp parallel for num_threads(threads_) default (shared) +#endif + for (unsigned idx = 0; idx < intensity_gradients_->size (); ++idx) + { + float len = intensity_gradients_->points [idx].gradient_x * intensity_gradients_->points [idx].gradient_x + + intensity_gradients_->points [idx].gradient_y * intensity_gradients_->points [idx].gradient_y + + intensity_gradients_->points [idx].gradient_z * intensity_gradients_->points [idx].gradient_z ; + + // Suat: ToDo: remove this magic number or expose using set/get + if (len > 200.0) + { + len = 1.0 / sqrt (len); + intensity_gradients_->points [idx].gradient_x *= len; + intensity_gradients_->points [idx].gradient_y *= len; + intensity_gradients_->points [idx].gradient_z *= len; + } + else + { + intensity_gradients_->points [idx].gradient_x = 0; + intensity_gradients_->points [idx].gradient_y = 0; + intensity_gradients_->points [idx].gradient_z = 0; + } + } + + boost::shared_ptr > response (new pcl::PointCloud ()); + response->points.reserve (input_->points.size()); + responseTomasi(*response); + + // just return the response + if (!nonmax_) + { + output = *response; + // we do not change the denseness in this case + output.is_dense = input_->is_dense; + for (size_t i = 0; i < response->size (); ++i) + keypoints_indices_->indices.push_back (i); + } + else + { + output.points.clear (); + output.points.reserve (response->points.size()); + +#ifdef _OPENMP + #pragma omp parallel for num_threads(threads_) default(shared) +#endif + for (size_t idx = 0; idx < response->points.size (); ++idx) + { + if (!isFinite (response->points[idx]) || response->points[idx].intensity < threshold_) + continue; + + std::vector nn_indices; + std::vector nn_dists; + tree_->radiusSearch (idx, search_radius_, nn_indices, nn_dists); + bool is_maxima = true; + for (std::vector::const_iterator iIt = nn_indices.begin(); iIt != nn_indices.end(); ++iIt) + { + if (response->points[idx].intensity < response->points[*iIt].intensity) + { + is_maxima = false; + break; + } + } + if (is_maxima) +#ifdef _OPENMP + #pragma omp critical +#endif + { + output.points.push_back (response->points[idx]); + keypoints_indices_->indices.push_back (idx); + } + } + + if (refine_) + refineCorners (output); + + output.height = 1; + output.width = static_cast (output.points.size()); + output.is_dense = true; + } +} + +template void +pcl::HarrisKeypoint6D::responseTomasi (PointCloudOut &output) const +{ + // get the 6x6 covar-mat + PointOutT pointOut; + PCL_ALIGN (16) float covar [21]; + Eigen::SelfAdjointEigenSolver > solver; + Eigen::Matrix covariance; + +#ifdef _OPENMP + #pragma omp parallel for default (shared) private (pointOut, covar, covariance, solver) num_threads(threads_) +#endif + for (unsigned pIdx = 0; pIdx < input_->size (); ++pIdx) + { + const PointInT& pointIn = input_->points [pIdx]; + pointOut.intensity = 0.0; //std::numeric_limits::quiet_NaN (); + if (isFinite (pointIn)) + { + std::vector nn_indices; + std::vector nn_dists; + tree_->radiusSearch (pointIn, search_radius_, nn_indices, nn_dists); + calculateCombinedCovar (nn_indices, covar); + + float trace = covar [0] + covar [6] + covar [11] + covar [15] + covar [18] + covar [20]; + if (trace != 0) + { + covariance.coeffRef ( 0) = covar [ 0]; + covariance.coeffRef ( 1) = covar [ 1]; + covariance.coeffRef ( 2) = covar [ 2]; + covariance.coeffRef ( 3) = covar [ 3]; + covariance.coeffRef ( 4) = covar [ 4]; + covariance.coeffRef ( 5) = covar [ 5]; + + covariance.coeffRef ( 7) = covar [ 6]; + covariance.coeffRef ( 8) = covar [ 7]; + covariance.coeffRef ( 9) = covar [ 8]; + covariance.coeffRef (10) = covar [ 9]; + covariance.coeffRef (11) = covar [10]; + + covariance.coeffRef (14) = covar [11]; + covariance.coeffRef (15) = covar [12]; + covariance.coeffRef (16) = covar [13]; + covariance.coeffRef (17) = covar [14]; + + covariance.coeffRef (21) = covar [15]; + covariance.coeffRef (22) = covar [16]; + covariance.coeffRef (23) = covar [17]; + + covariance.coeffRef (28) = covar [18]; + covariance.coeffRef (29) = covar [19]; + + covariance.coeffRef (35) = covar [20]; + + covariance.coeffRef ( 6) = covar [ 1]; + + covariance.coeffRef (12) = covar [ 2]; + covariance.coeffRef (13) = covar [ 7]; + + covariance.coeffRef (18) = covar [ 3]; + covariance.coeffRef (19) = covar [ 8]; + covariance.coeffRef (20) = covar [12]; + + covariance.coeffRef (24) = covar [ 4]; + covariance.coeffRef (25) = covar [ 9]; + covariance.coeffRef (26) = covar [13]; + covariance.coeffRef (27) = covar [16]; + + covariance.coeffRef (30) = covar [ 5]; + covariance.coeffRef (31) = covar [10]; + covariance.coeffRef (32) = covar [14]; + covariance.coeffRef (33) = covar [17]; + covariance.coeffRef (34) = covar [19]; + + solver.compute (covariance); + pointOut.intensity = solver.eigenvalues () [3]; + } + } + + pointOut.x = pointIn.x; + pointOut.y = pointIn.y; + pointOut.z = pointIn.z; +#ifdef _OPENMP + #pragma omp critical +#endif + + output.points.push_back(pointOut); + } + output.height = input_->height; + output.width = input_->width; +} + +template void +pcl::HarrisKeypoint6D::refineCorners (PointCloudOut &corners) const +{ + pcl::search::KdTree search; + search.setInputCloud(surface_); + + Eigen::Matrix3f nnT; + Eigen::Matrix3f NNT; + Eigen::Vector3f NNTp; + const Eigen::Vector3f* normal; + const Eigen::Vector3f* point; + float diff; + const unsigned max_iterations = 10; + for (typename PointCloudOut::iterator cornerIt = corners.begin(); cornerIt != corners.end(); ++cornerIt) + { + unsigned iterations = 0; + do { + NNT.setZero(); + NNTp.setZero(); + PointInT corner; + corner.x = cornerIt->x; + corner.y = cornerIt->y; + corner.z = cornerIt->z; + std::vector nn_indices; + std::vector nn_dists; + search.radiusSearch (corner, search_radius_, nn_indices, nn_dists); + for (std::vector::const_iterator iIt = nn_indices.begin(); iIt != nn_indices.end(); ++iIt) + { + normal = reinterpret_cast (&(normals_->points[*iIt].normal_x)); + point = reinterpret_cast (&(surface_->points[*iIt].x)); + nnT = (*normal) * (normal->transpose()); + NNT += nnT; + NNTp += nnT * (*point); + } + if (NNT.determinant() != 0) + *(reinterpret_cast(&(cornerIt->x))) = NNT.inverse () * NNTp; + + diff = (cornerIt->x - corner.x) * (cornerIt->x - corner.x) + + (cornerIt->y - corner.y) * (cornerIt->y - corner.y) + + (cornerIt->z - corner.z) * (cornerIt->z - corner.z); + + } while (diff > 1e-6 && ++iterations < max_iterations); + } +} + +#define PCL_INSTANTIATE_HarrisKeypoint6D(T,U,N) template class PCL_EXPORTS pcl::HarrisKeypoint6D; +#endif // #ifndef PCL_HARRIS_KEYPOINT_6D_IMPL_H_ + diff --git a/pcl-1.7/pcl/keypoints/impl/iss_3d.hpp b/pcl-1.7/pcl/keypoints/impl/iss_3d.hpp new file mode 100644 index 0000000..d1e86f5 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/impl/iss_3d.hpp @@ -0,0 +1,460 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_ISS_KEYPOINT3D_IMPL_H_ +#define PCL_ISS_KEYPOINT3D_IMPL_H_ + +#include +#include +#include + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ISSKeypoint3D::setSalientRadius (double salient_radius) +{ + salient_radius_ = salient_radius; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ISSKeypoint3D::setNonMaxRadius (double non_max_radius) +{ + non_max_radius_ = non_max_radius; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ISSKeypoint3D::setNormalRadius (double normal_radius) +{ + normal_radius_ = normal_radius; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ISSKeypoint3D::setBorderRadius (double border_radius) +{ + border_radius_ = border_radius; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ISSKeypoint3D::setThreshold21 (double gamma_21) +{ + gamma_21_ = gamma_21; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ISSKeypoint3D::setThreshold32 (double gamma_32) +{ + gamma_32_ = gamma_32; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ISSKeypoint3D::setMinNeighbors (int min_neighbors) +{ + min_neighbors_ = min_neighbors; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ISSKeypoint3D::setNormals (const PointCloudNConstPtr &normals) +{ + normals_ = normals; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool* +pcl::ISSKeypoint3D::getBoundaryPoints (PointCloudIn &input, double border_radius, float angle_threshold) +{ + bool* edge_points = new bool [input.size ()]; + + Eigen::Vector4f u = Eigen::Vector4f::Zero (); + Eigen::Vector4f v = Eigen::Vector4f::Zero (); + + pcl::BoundaryEstimation boundary_estimator; + boundary_estimator.setInputCloud (input_); + + int index; +#ifdef _OPENMP +#pragma omp parallel for private(u, v) num_threads(threads_) +#endif + for (index = 0; index < int (input.points.size ()); index++) + { + edge_points[index] = false; + PointInT current_point = input.points[index]; + + if (pcl::isFinite(current_point)) + { + std::vector nn_indices; + std::vector nn_distances; + int n_neighbors; + + this->searchForNeighbors (static_cast (index), border_radius, nn_indices, nn_distances); + + n_neighbors = static_cast (nn_indices.size ()); + + if (n_neighbors >= min_neighbors_) + { + boundary_estimator.getCoordinateSystemOnPlane (normals_->points[index], u, v); + + if (boundary_estimator.isBoundaryPoint (input, static_cast (index), nn_indices, u, v, angle_threshold)) + edge_points[index] = true; + } + } + } + + return (edge_points); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ISSKeypoint3D::getScatterMatrix (const int& current_index, Eigen::Matrix3d &cov_m) +{ + const PointInT& current_point = (*input_).points[current_index]; + + double central_point[3]; + memset(central_point, 0, sizeof(double) * 3); + + central_point[0] = current_point.x; + central_point[1] = current_point.y; + central_point[2] = current_point.z; + + cov_m = Eigen::Matrix3d::Zero (); + + std::vector nn_indices; + std::vector nn_distances; + int n_neighbors; + + this->searchForNeighbors (current_index, salient_radius_, nn_indices, nn_distances); + + n_neighbors = static_cast (nn_indices.size ()); + + if (n_neighbors < min_neighbors_) + return; + + double cov[9]; + memset(cov, 0, sizeof(double) * 9); + + for (int n_idx = 0; n_idx < n_neighbors; n_idx++) + { + const PointInT& n_point = (*input_).points[nn_indices[n_idx]]; + + double neigh_point[3]; + memset(neigh_point, 0, sizeof(double) * 3); + + neigh_point[0] = n_point.x; + neigh_point[1] = n_point.y; + neigh_point[2] = n_point.z; + + for (int i = 0; i < 3; i++) + for (int j = 0; j < 3; j++) + cov[i * 3 + j] += (neigh_point[i] - central_point[i]) * (neigh_point[j] - central_point[j]); + } + + cov_m << cov[0], cov[1], cov[2], + cov[3], cov[4], cov[5], + cov[6], cov[7], cov[8]; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::ISSKeypoint3D::initCompute () +{ + if (!Keypoint::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] init failed!\n", name_.c_str ()); + return (false); + } + if (salient_radius_ <= 0) + { + PCL_ERROR ("[pcl::%s::initCompute] : the salient radius (%f) must be strict positive!\n", + name_.c_str (), salient_radius_); + return (false); + } + if (non_max_radius_ <= 0) + { + PCL_ERROR ("[pcl::%s::initCompute] : the non maxima radius (%f) must be strict positive!\n", + name_.c_str (), non_max_radius_); + return (false); + } + if (gamma_21_ <= 0) + { + PCL_ERROR ("[pcl::%s::initCompute] : the threshold on the ratio between the 2nd and the 1rst eigenvalue (%f) must be strict positive!\n", + name_.c_str (), gamma_21_); + return (false); + } + if (gamma_32_ <= 0) + { + PCL_ERROR ("[pcl::%s::initCompute] : the threshold on the ratio between the 3rd and the 2nd eigenvalue (%f) must be strict positive!\n", + name_.c_str (), gamma_32_); + return (false); + } + if (min_neighbors_ <= 0) + { + PCL_ERROR ("[pcl::%s::initCompute] : the minimum number of neighbors (%f) must be strict positive!\n", + name_.c_str (), min_neighbors_); + return (false); + } + + if (third_eigen_value_) + delete[] third_eigen_value_; + + third_eigen_value_ = new double[input_->size ()]; + memset(third_eigen_value_, 0, sizeof(double) * input_->size ()); + + if (edge_points_) + delete[] edge_points_; + + if (border_radius_ > 0.0) + { + if (normals_->empty ()) + { + if (normal_radius_ <= 0.) + { + PCL_ERROR ("[pcl::%s::initCompute] : the radius used to estimate surface normals (%f) must be positive!\n", + name_.c_str (), normal_radius_); + return (false); + } + + PointCloudNPtr normal_ptr (new PointCloudN ()); + if (input_->height == 1 ) + { + pcl::NormalEstimation normal_estimation; + normal_estimation.setInputCloud (surface_); + normal_estimation.setRadiusSearch (normal_radius_); + normal_estimation.compute (*normal_ptr); + } + else + { + pcl::IntegralImageNormalEstimation normal_estimation; + normal_estimation.setNormalEstimationMethod (pcl::IntegralImageNormalEstimation::SIMPLE_3D_GRADIENT); + normal_estimation.setInputCloud (surface_); + normal_estimation.setNormalSmoothingSize (5.0); + normal_estimation.compute (*normal_ptr); + } + normals_ = normal_ptr; + } + if (normals_->size () != surface_->size ()) + { + PCL_ERROR ("[pcl::%s::initCompute] normals given, but the number of normals does not match the number of input points!\n", name_.c_str ()); + return (false); + } + } + else if (border_radius_ < 0.0) + { + PCL_ERROR ("[pcl::%s::initCompute] : the border radius used to estimate boundary points (%f) must be positive!\n", + name_.c_str (), border_radius_); + return (false); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ISSKeypoint3D::detectKeypoints (PointCloudOut &output) +{ + // Make sure the output cloud is empty + output.points.clear (); + + if (border_radius_ > 0.0) + edge_points_ = getBoundaryPoints (*(input_->makeShared ()), border_radius_, angle_threshold_); + + bool* borders = new bool [input_->size()]; + + int index; +#ifdef _OPENMP + #pragma omp parallel for num_threads(threads_) +#endif + for (index = 0; index < int (input_->size ()); index++) + { + borders[index] = false; + PointInT current_point = input_->points[index]; + + if ((border_radius_ > 0.0) && (pcl::isFinite(current_point))) + { + std::vector nn_indices; + std::vector nn_distances; + + this->searchForNeighbors (static_cast (index), border_radius_, nn_indices, nn_distances); + + for (size_t j = 0 ; j < nn_indices.size (); j++) + { + if (edge_points_[nn_indices[j]]) + { + borders[index] = true; + break; + } + } + } + } + + Eigen::Vector3d *omp_mem = new Eigen::Vector3d[threads_]; + + for (size_t i = 0; i < threads_; i++) + omp_mem[i].setZero (3); + + double *prg_local_mem = new double[input_->size () * 3]; + double **prg_mem = new double * [input_->size ()]; + + for (size_t i = 0; i < input_->size (); i++) + prg_mem[i] = prg_local_mem + 3 * i; + +#ifdef _OPENMP + #pragma omp parallel for num_threads(threads_) +#endif + for (index = 0; index < static_cast (input_->size ()); index++) + { +#ifdef _OPENMP + int tid = omp_get_thread_num (); +#else + int tid = 0; +#endif + PointInT current_point = input_->points[index]; + + if ((!borders[index]) && pcl::isFinite(current_point)) + { + //if the considered point is not a border point and the point is "finite", then compute the scatter matrix + Eigen::Matrix3d cov_m = Eigen::Matrix3d::Zero (); + getScatterMatrix (static_cast (index), cov_m); + + Eigen::SelfAdjointEigenSolver solver (cov_m); + + const double& e1c = solver.eigenvalues ()[2]; + const double& e2c = solver.eigenvalues ()[1]; + const double& e3c = solver.eigenvalues ()[0]; + + if (!pcl_isfinite (e1c) || !pcl_isfinite (e2c) || !pcl_isfinite (e3c)) + continue; + + if (e3c < 0) + { + PCL_WARN ("[pcl::%s::detectKeypoints] : The third eigenvalue is negative! Skipping the point with index %i.\n", + name_.c_str (), index); + continue; + } + + omp_mem[tid][0] = e2c / e1c; + omp_mem[tid][1] = e3c / e2c;; + omp_mem[tid][2] = e3c; + } + + for (int d = 0; d < omp_mem[tid].size (); d++) + prg_mem[index][d] = omp_mem[tid][d]; + } + + for (index = 0; index < int (input_->size ()); index++) + { + if (!borders[index]) + { + if ((prg_mem[index][0] < gamma_21_) && (prg_mem[index][1] < gamma_32_)) + third_eigen_value_[index] = prg_mem[index][2]; + } + } + + bool* feat_max = new bool [input_->size()]; + bool is_max; + +#ifdef _OPENMP + #pragma omp parallel for private(is_max) num_threads(threads_) +#endif + for (index = 0; index < int (input_->size ()); index++) + { + feat_max [index] = false; + PointInT current_point = input_->points[index]; + + if ((third_eigen_value_[index] > 0.0) && (pcl::isFinite(current_point))) + { + std::vector nn_indices; + std::vector nn_distances; + int n_neighbors; + + this->searchForNeighbors (static_cast (index), non_max_radius_, nn_indices, nn_distances); + + n_neighbors = static_cast (nn_indices.size ()); + + if (n_neighbors >= min_neighbors_) + { + is_max = true; + + for (int j = 0 ; j < n_neighbors; j++) + if (third_eigen_value_[index] < third_eigen_value_[nn_indices[j]]) + is_max = false; + if (is_max) + feat_max[index] = true; + } + } + } + +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads(threads_) +#endif + for (index = 0; index < int (input_->size ()); index++) + { + if (feat_max[index]) +#ifdef _OPENMP +#pragma omp critical +#endif + { + PointOutT p; + p.getVector3fMap () = input_->points[index].getVector3fMap (); + output.points.push_back(p); + keypoints_indices_->indices.push_back (index); + } + } + + output.header = input_->header; + output.width = static_cast (output.points.size ()); + output.height = 1; + + // Clear the contents of variables and arrays before the beginning of the next computation. + if (border_radius_ > 0.0) + normals_.reset (new pcl::PointCloud); + + delete[] borders; + delete[] prg_mem; + delete[] prg_local_mem; + delete[] feat_max; +} + +#define PCL_INSTANTIATE_ISSKeypoint3D(T,U,N) template class PCL_EXPORTS pcl::ISSKeypoint3D; + +#endif /* PCL_ISS_3D_IMPL_H_ */ diff --git a/pcl-1.7/pcl/keypoints/impl/keypoint.hpp b/pcl-1.7/pcl/keypoints/impl/keypoint.hpp new file mode 100644 index 0000000..4b84f08 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/impl/keypoint.hpp @@ -0,0 +1,143 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_KEYPOINT_IMPL_H_ +#define PCL_KEYPOINT_IMPL_H_ + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::Keypoint::initCompute () +{ + if (!PCLBase::initCompute ()) + return (false); + + // Initialize the spatial locator + if (!tree_) + { + if (input_->isOrganized ()) + tree_.reset (new pcl::search::OrganizedNeighbor ()); + else + tree_.reset (new pcl::search::KdTree (false)); + } + + // If no search surface has been defined, use the input dataset as the search surface itself + if (!surface_) + surface_ = input_; + + // Send the surface dataset to the spatial locator + tree_->setInputCloud (surface_); + + // Do a fast check to see if the search parameters are well defined + if (search_radius_ != 0.0) + { + if (k_ != 0) + { + PCL_ERROR ("[pcl::%s::initCompute] Both radius (%f) and K (%d) defined! Set one of them to zero first and then re-run compute ().\n", getClassName ().c_str (), search_radius_, k_); + return (false); + } + else // Use the radiusSearch () function + { + search_parameter_ = search_radius_; + if (surface_ == input_) // if the two surfaces are the same + { + // Declare the search locator definition + int (KdTree::*radiusSearch)(int index, double radius, std::vector &k_indices, + std::vector &k_distances, unsigned int max_nn) const = &KdTree::radiusSearch; + search_method_ = boost::bind (radiusSearch, boost::ref (tree_), _1, _2, _3, _4, 0); + } + else + { + // Declare the search locator definition + int (KdTree::*radiusSearchSurface)(const PointCloudIn &cloud, int index, double radius, std::vector &k_indices, + std::vector &k_distances, unsigned int max_nn) const = &KdTree::radiusSearch; + search_method_surface_ = boost::bind (radiusSearchSurface, boost::ref (tree_), _1, _2, _3, _4, _5, 0); + } + } + } + else + { + if (k_ != 0) // Use the nearestKSearch () function + { + search_parameter_ = k_; + if (surface_ == input_) // if the two surfaces are the same + { + // Declare the search locator definition + int (KdTree::*nearestKSearch)(int index, int k, std::vector &k_indices, std::vector &k_distances) const = &KdTree::nearestKSearch; + search_method_ = boost::bind (nearestKSearch, boost::ref (tree_), _1, _2, _3, _4); + } + else + { + // Declare the search locator definition + int (KdTree::*nearestKSearchSurface)(const PointCloudIn &cloud, int index, int k, std::vector &k_indices, std::vector &k_distances) const = &KdTree::nearestKSearch; + search_method_surface_ = boost::bind (nearestKSearchSurface, boost::ref (tree_), _1, _2, _3, _4, _5); + } + } + else + { + PCL_ERROR ("[pcl::%s::initCompute] Neither radius nor K defined! Set one of them to a positive number first and then re-run compute ().\n", getClassName ().c_str ()); + return (false); + } + } + + keypoints_indices_.reset (new pcl::PointIndices); + keypoints_indices_->indices.reserve (input_->size ()); + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::Keypoint::compute (PointCloudOut &output) +{ + if (!initCompute ()) + { + PCL_ERROR ("[pcl::%s::compute] initCompute failed!\n", getClassName ().c_str ()); + return; + } + + // Perform the actual computation + detectKeypoints (output); + + deinitCompute (); + + // Reset the surface + if (input_ == surface_) + surface_.reset (); +} + +#endif //#ifndef PCL_KEYPOINT_IMPL_H_ + diff --git a/pcl-1.7/pcl/keypoints/impl/sift_keypoint.hpp b/pcl-1.7/pcl/keypoints/impl/sift_keypoint.hpp new file mode 100644 index 0000000..014a634 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/impl/sift_keypoint.hpp @@ -0,0 +1,324 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SIFT_KEYPOINT_IMPL_H_ +#define PCL_SIFT_KEYPOINT_IMPL_H_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SIFTKeypoint::setScales (float min_scale, int nr_octaves, int nr_scales_per_octave) +{ + min_scale_ = min_scale; + nr_octaves_ = nr_octaves; + nr_scales_per_octave_ = nr_scales_per_octave; +} + + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SIFTKeypoint::setMinimumContrast (float min_contrast) +{ + min_contrast_ = min_contrast; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SIFTKeypoint::initCompute () +{ + if (min_scale_ <= 0) + { + PCL_ERROR ("[pcl::%s::initCompute] : Minimum scale (%f) must be strict positive!\n", + name_.c_str (), min_scale_); + return (false); + } + if (nr_octaves_ < 1) + { + PCL_ERROR ("[pcl::%s::initCompute] : Number of octaves (%d) must be at least 1!\n", + name_.c_str (), nr_octaves_); + return (false); + } + if (nr_scales_per_octave_ < 1) + { + PCL_ERROR ("[pcl::%s::initCompute] : Number of scales per octave (%d) must be at least 1!\n", + name_.c_str (), nr_scales_per_octave_); + return (false); + } + if (min_contrast_ < 0) + { + PCL_ERROR ("[pcl::%s::initCompute] : Minimum contrast (%f) must be non-negative!\n", + name_.c_str (), min_contrast_); + return (false); + } + + this->setKSearch (1); + tree_.reset (new pcl::search::KdTree (true)); + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SIFTKeypoint::detectKeypoints (PointCloudOut &output) +{ + if (surface_ && surface_ != input_) + { + PCL_WARN ("[pcl::%s::detectKeypoints] : ", name_.c_str ()); + PCL_WARN ("A search surface has been set by setSearchSurface, but this SIFT keypoint detection algorithm does "); + PCL_WARN ("not support search surfaces other than the input cloud. "); + PCL_WARN ("The cloud provided in setInputCloud is being used instead.\n"); + } + + // Check if the output has a "scale" field + scale_idx_ = pcl::getFieldIndex (output, "scale", out_fields_); + + // Make sure the output cloud is empty + output.points.clear (); + + // Create a local copy of the input cloud that will be resized for each octave + boost::shared_ptr > cloud (new pcl::PointCloud (*input_)); + + VoxelGrid voxel_grid; + // Search for keypoints at each octave + float scale = min_scale_; + for (int i_octave = 0; i_octave < nr_octaves_; ++i_octave) + { + // Downsample the point cloud + const float s = 1.0f * scale; // note: this can be adjusted + voxel_grid.setLeafSize (s, s, s); + voxel_grid.setInputCloud (cloud); + boost::shared_ptr > temp (new pcl::PointCloud); + voxel_grid.filter (*temp); + cloud = temp; + + // Make sure the downsampled cloud still has enough points + const size_t min_nr_points = 25; + if (cloud->points.size () < min_nr_points) + break; + + // Update the KdTree with the downsampled points + tree_->setInputCloud (cloud); + + // Detect keypoints for the current scale + detectKeypointsForOctave (*cloud, *tree_, scale, nr_scales_per_octave_, output); + + // Increase the scale by another octave + scale *= 2; + } + + output.height = 1; + output.width = static_cast (output.points.size ()); +} + + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SIFTKeypoint::detectKeypointsForOctave ( + const PointCloudIn &input, KdTree &tree, float base_scale, int nr_scales_per_octave, + PointCloudOut &output) +{ + // Compute the difference of Gaussians (DoG) scale space + std::vector scales (nr_scales_per_octave + 3); + for (int i_scale = 0; i_scale <= nr_scales_per_octave + 2; ++i_scale) + { + scales[i_scale] = base_scale * powf (2.0f, (1.0f * static_cast (i_scale) - 1.0f) / static_cast (nr_scales_per_octave)); + } + Eigen::MatrixXf diff_of_gauss; + computeScaleSpace (input, tree, scales, diff_of_gauss); + + // Find extrema in the DoG scale space + std::vector extrema_indices, extrema_scales; + findScaleSpaceExtrema (input, tree, diff_of_gauss, extrema_indices, extrema_scales); + + output.points.reserve (output.points.size () + extrema_indices.size ()); + // Save scale? + if (scale_idx_ != -1) + { + // Add keypoints to output + for (size_t i_keypoint = 0; i_keypoint < extrema_indices.size (); ++i_keypoint) + { + PointOutT keypoint; + const int &keypoint_index = extrema_indices[i_keypoint]; + + keypoint.x = input.points[keypoint_index].x; + keypoint.y = input.points[keypoint_index].y; + keypoint.z = input.points[keypoint_index].z; + memcpy (reinterpret_cast (&keypoint) + out_fields_[scale_idx_].offset, + &scales[extrema_scales[i_keypoint]], sizeof (float)); + output.points.push_back (keypoint); + } + } + else + { + // Add keypoints to output + for (size_t i_keypoint = 0; i_keypoint < extrema_indices.size (); ++i_keypoint) + { + PointOutT keypoint; + const int &keypoint_index = extrema_indices[i_keypoint]; + + keypoint.x = input.points[keypoint_index].x; + keypoint.y = input.points[keypoint_index].y; + keypoint.z = input.points[keypoint_index].z; + + output.points.push_back (keypoint); + } + } +} + + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +void pcl::SIFTKeypoint::computeScaleSpace ( + const PointCloudIn &input, KdTree &tree, const std::vector &scales, + Eigen::MatrixXf &diff_of_gauss) +{ + diff_of_gauss.resize (input.size (), scales.size () - 1); + + // For efficiency, we will only filter over points within 3 standard deviations + const float max_radius = 3.0f * scales.back (); + + for (int i_point = 0; i_point < static_cast (input.size ()); ++i_point) + { + std::vector nn_indices; + std::vector nn_dist; + tree.radiusSearch (i_point, max_radius, nn_indices, nn_dist); // * + // * note: at this stage of the algorithm, we must find all points within a radius defined by the maximum scale, + // regardless of the configurable search method specified by the user, so we directly employ tree.radiusSearch + // here instead of using searchForNeighbors. + + // For each scale, compute the Gaussian "filter response" at the current point + float filter_response = 0.0f; + float previous_filter_response; + for (size_t i_scale = 0; i_scale < scales.size (); ++i_scale) + { + float sigma_sqr = powf (scales[i_scale], 2.0f); + + float numerator = 0.0f; + float denominator = 0.0f; + for (size_t i_neighbor = 0; i_neighbor < nn_indices.size (); ++i_neighbor) + { + const float &value = getFieldValue_ (input.points[nn_indices[i_neighbor]]); + const float &dist_sqr = nn_dist[i_neighbor]; + if (dist_sqr <= 9*sigma_sqr) + { + float w = expf (-0.5f * dist_sqr / sigma_sqr); + numerator += value * w; + denominator += w; + } + else break; // i.e. if dist > 3 standard deviations, then terminate early + } + previous_filter_response = filter_response; + filter_response = numerator / denominator; + + // Compute the difference between adjacent scales + if (i_scale > 0) + diff_of_gauss (i_point, i_scale - 1) = filter_response - previous_filter_response; + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SIFTKeypoint::findScaleSpaceExtrema ( + const PointCloudIn &input, KdTree &tree, const Eigen::MatrixXf &diff_of_gauss, + std::vector &extrema_indices, std::vector &extrema_scales) +{ + const int k = 25; + std::vector nn_indices (k); + std::vector nn_dist (k); + + const int nr_scales = static_cast (diff_of_gauss.cols ()); + std::vector min_val (nr_scales), max_val (nr_scales); + + for (int i_point = 0; i_point < static_cast (input.size ()); ++i_point) + { + // Define the local neighborhood around the current point + const size_t nr_nn = tree.nearestKSearch (i_point, k, nn_indices, nn_dist); //* + // * note: the neighborhood for finding local extrema is best defined as a small fixed-k neighborhood, regardless of + // the configurable search method specified by the user, so we directly employ tree.nearestKSearch here instead + // of using searchForNeighbors + + // At each scale, find the extreme values of the DoG within the current neighborhood + for (int i_scale = 0; i_scale < nr_scales; ++i_scale) + { + min_val[i_scale] = std::numeric_limits::max (); + max_val[i_scale] = -std::numeric_limits::max (); + + for (size_t i_neighbor = 0; i_neighbor < nr_nn; ++i_neighbor) + { + const float &d = diff_of_gauss (nn_indices[i_neighbor], i_scale); + + min_val[i_scale] = (std::min) (min_val[i_scale], d); + max_val[i_scale] = (std::max) (max_val[i_scale], d); + } + } + + // If the current point is an extreme value with high enough contrast, add it as a keypoint + for (int i_scale = 1; i_scale < nr_scales - 1; ++i_scale) + { + const float &val = diff_of_gauss (i_point, i_scale); + + // Does the point have sufficient contrast? + if (fabs (val) >= min_contrast_) + { + // Is it a local minimum? + if ((val == min_val[i_scale]) && + (val < min_val[i_scale - 1]) && + (val < min_val[i_scale + 1])) + { + extrema_indices.push_back (i_point); + extrema_scales.push_back (i_scale); + } + // Is it a local maximum? + else if ((val == max_val[i_scale]) && + (val > max_val[i_scale - 1]) && + (val > max_val[i_scale + 1])) + { + extrema_indices.push_back (i_point); + extrema_scales.push_back (i_scale); + } + } + } + } +} + +#define PCL_INSTANTIATE_SIFTKeypoint(T,U) template class PCL_EXPORTS pcl::SIFTKeypoint; + +#endif // #ifndef PCL_SIFT_KEYPOINT_IMPL_H_ + diff --git a/pcl-1.7/pcl/keypoints/impl/smoothed_surfaces_keypoint.hpp b/pcl-1.7/pcl/keypoints/impl/smoothed_surfaces_keypoint.hpp new file mode 100644 index 0000000..e3eab6c --- /dev/null +++ b/pcl-1.7/pcl/keypoints/impl/smoothed_surfaces_keypoint.hpp @@ -0,0 +1,251 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Willow Garage, Inc + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_KEYPOINTS_IMPL_SMOOTHEDSURFACESKEYPOINT_H_ +#define PCL_KEYPOINTS_IMPL_SMOOTHEDSURFACESKEYPOINT_H_ + +#include +#include + +//#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SmoothedSurfacesKeypoint::addSmoothedPointCloud (const PointCloudTConstPtr &cloud, + const PointCloudNTConstPtr &normals, + KdTreePtr &kdtree, + float &scale) +{ + clouds_.push_back (cloud); + cloud_normals_.push_back (normals); + cloud_trees_.push_back (kdtree); + scales_.push_back (std::pair (scale, scales_.size ())); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SmoothedSurfacesKeypoint::resetClouds () +{ + clouds_.clear (); + cloud_normals_.clear (); + scales_.clear (); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SmoothedSurfacesKeypoint::detectKeypoints (PointCloudT &output) +{ + // Calculate differences for each cloud + std::vector > diffs (scales_.size ()); + + // The cloud with the smallest scale has no differences + std::vector aux_diffs (input_->points.size (), 0.0f); + diffs[scales_[0].second] = aux_diffs; + + cloud_trees_[scales_[0].second]->setInputCloud (clouds_[scales_[0].second]); + for (size_t scale_i = 1; scale_i < clouds_.size (); ++scale_i) + { + size_t cloud_i = scales_[scale_i].second, + cloud_i_minus_one = scales_[scale_i - 1].second; + diffs[cloud_i].resize (input_->points.size ()); + PCL_INFO ("cloud_i %u cloud_i_minus_one %u\n", cloud_i, cloud_i_minus_one); + for (size_t point_i = 0; point_i < input_->points.size (); ++point_i) + diffs[cloud_i][point_i] = cloud_normals_[cloud_i]->points[point_i].getNormalVector3fMap ().dot ( + clouds_[cloud_i]->points[point_i].getVector3fMap () - clouds_[cloud_i_minus_one]->points[point_i].getVector3fMap ()); + + // Setup kdtree for this cloud + cloud_trees_[cloud_i]->setInputCloud (clouds_[cloud_i]); + } + + + // Find minima and maxima in differences inside the input cloud + typename pcl::search::Search::Ptr input_tree = cloud_trees_.back (); + for (int point_i = 0; point_i < static_cast (input_->points.size ()); ++point_i) + { + std::vector nn_indices; + std::vector nn_distances; + input_tree->radiusSearch (point_i, input_scale_ * neighborhood_constant_, nn_indices, nn_distances); + + bool is_min = true, is_max = true; + for (std::vector::iterator nn_it = nn_indices.begin (); nn_it != nn_indices.end (); ++nn_it) + if (*nn_it != point_i) + { + if (diffs[input_index_][point_i] < diffs[input_index_][*nn_it]) + is_max = false; + else if (diffs[input_index_][point_i] > diffs[input_index_][*nn_it]) + is_min = false; + } + + // If the point is a local minimum/maximum, check if it is the same over all the scales + if (is_min || is_max) + { + bool passed_min = true, passed_max = true; + for (size_t scale_i = 0; scale_i < scales_.size (); ++scale_i) + { + size_t cloud_i = scales_[scale_i].second; + // skip input cloud + if (cloud_i == clouds_.size () - 1) + continue; + + nn_indices.clear (); nn_distances.clear (); + cloud_trees_[cloud_i]->radiusSearch (point_i, scales_[scale_i].first * neighborhood_constant_, nn_indices, nn_distances); + + bool is_min_other_scale = true, is_max_other_scale = true; + for (std::vector::iterator nn_it = nn_indices.begin (); nn_it != nn_indices.end (); ++nn_it) + if (*nn_it != point_i) + { + if (diffs[input_index_][point_i] < diffs[cloud_i][*nn_it]) + is_max_other_scale = false; + else if (diffs[input_index_][point_i] > diffs[cloud_i][*nn_it]) + is_min_other_scale = false; + } + + if (is_min == true && is_min_other_scale == false) + passed_min = false; + if (is_max == true && is_max_other_scale == false) + passed_max = false; + + if (!passed_min && !passed_max) + break; + } + + // check if point was minimum/maximum over all the scales + if (passed_min || passed_max) + { + output.points.push_back (input_->points[point_i]); + keypoints_indices_->indices.push_back (point_i); + } + } + } + + output.header = input_->header; + output.width = static_cast (output.points.size ()); + output.height = 1; + + // debug stuff +// for (size_t scale_i = 0; scale_i < scales_.size (); ++scale_i) +// { +// PointCloud::Ptr debug_cloud (new PointCloud ()); +// debug_cloud->points.resize (input_->points.size ()); +// debug_cloud->width = input_->width; +// debug_cloud->height = input_->height; +// for (size_t point_i = 0; point_i < input_->points.size (); ++point_i) +// { +// debug_cloud->points[point_i].intensity = diffs[scales_[scale_i].second][point_i]; +// debug_cloud->points[point_i].x = input_->points[point_i].x; +// debug_cloud->points[point_i].y = input_->points[point_i].y; +// debug_cloud->points[point_i].z = input_->points[point_i].z; +// } + +// char str[512]; sprintf (str, "diffs_%2d.pcd", scale_i); +// io::savePCDFile (str, *debug_cloud); +// } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SmoothedSurfacesKeypoint::initCompute () +{ + PCL_INFO ("SmoothedSurfacesKeypoint initCompute () called\n"); + if ( !Keypoint::initCompute ()) + { + PCL_ERROR ("[pcl::SmoothedSurfacesKeypoints::initCompute] Keypoint::initCompute failed\n"); + return false; + } + + if (!normals_) + { + PCL_ERROR ("[pcl::SmoothedSurfacesKeypoints::initCompute] Input normals were not set\n"); + return false; + } + if (clouds_.size () == 0) + { + PCL_ERROR ("[pcl::SmoothedSurfacesKeypoints::initCompute] No other clouds were set apart from the input\n"); + return false; + } + + if (input_->points.size () != normals_->points.size ()) + { + PCL_ERROR ("[pcl::SmoothedSurfacesKeypoints::initCompute] The input cloud and the input normals differ in size\n"); + return false; + } + + for (size_t cloud_i = 0; cloud_i < clouds_.size (); ++cloud_i) + { + if (clouds_[cloud_i]->points.size () != input_->points.size ()) + { + PCL_ERROR ("[pcl::SmoothedSurfacesKeypoints::initCompute] Cloud %d does not have the same number of points as the input cloud\n", cloud_i); + return false; + } + + if (cloud_normals_[cloud_i]->points.size () != input_->points.size ()) + { + PCL_ERROR ("[pcl::SmoothedSurfacesKeypoints::initCompute] Normals for cloud %d do not have the same number of points as the input cloud\n", cloud_i); + return false; + } + } + + // Add the input cloud as the last index + scales_.push_back (std::pair (input_scale_, scales_.size ())); + clouds_.push_back (input_); + cloud_normals_.push_back (normals_); + cloud_trees_.push_back (tree_); + // Sort the clouds by their scales + sort (scales_.begin (), scales_.end (), compareScalesFunction); + + // Find the index of the input after sorting + for (size_t i = 0; i < scales_.size (); ++i) + if (scales_[i].second == scales_.size () - 1) + { + input_index_ = i; + break; + } + + PCL_INFO ("Scales: "); + for (size_t i = 0; i < scales_.size (); ++i) PCL_INFO ("(%d %f), ", scales_[i].second, scales_[i].first); + PCL_INFO ("\n"); + + return (true); +} + + +#define PCL_INSTANTIATE_SmoothedSurfacesKeypoint(T,NT) template class PCL_EXPORTS pcl::SmoothedSurfacesKeypoint; + + +#endif /* PCL_KEYPOINTS_IMPL_SMOOTHEDSURFACESKEYPOINT_H_ */ diff --git a/pcl-1.7/pcl/keypoints/impl/susan.hpp b/pcl-1.7/pcl/keypoints/impl/susan.hpp new file mode 100644 index 0000000..7b98923 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/impl/susan.hpp @@ -0,0 +1,471 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SUSAN_IMPL_HPP_ +#define PCL_SUSAN_IMPL_HPP_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SUSANKeypoint::setNonMaxSupression (bool nonmax) +{ + nonmax_ = nonmax; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SUSANKeypoint::setGeometricValidation (bool validate) +{ + geometric_validation_ = validate; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SUSANKeypoint::setRadius (float radius) +{ + search_radius_ = radius; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SUSANKeypoint::setDistanceThreshold (float distance_threshold) +{ + distance_threshold_ = distance_threshold; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SUSANKeypoint::setAngularThreshold (float angular_threshold) +{ + angular_threshold_ = angular_threshold; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SUSANKeypoint::setIntensityThreshold (float intensity_threshold) +{ + intensity_threshold_ = intensity_threshold; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SUSANKeypoint::setNormals (const PointCloudNConstPtr &normals) +{ + normals_ = normals; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SUSANKeypoint::setSearchSurface (const PointCloudInConstPtr &cloud) +{ + surface_ = cloud; + normals_.reset (new pcl::PointCloud); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SUSANKeypoint::setNumberOfThreads (unsigned int nr_threads) +{ + threads_ = nr_threads; +} + + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +// template void +// pcl::SUSANKeypoint::USAN (const PointInT& nucleus, +// const NormalT& nucleus_normal, +// const std::vector& neighbors, +// const float& t, +// float& response, +// Eigen::Vector3f& centroid) const +// { +// float area = 0; +// response = 0; +// float x0 = nucleus.x; +// float y0 = nucleus.y; +// float z0 = nucleus.z; +// //xx xy xz yy yz zz +// std::vector coefficients(6); +// memset (&coefficients[0], 0, sizeof (float) * 6); +// for (std::vector::const_iterator index = neighbors.begin(); index != neighbors.end(); ++index) +// { +// if (pcl_isfinite (normals_->points[*index].normal_x)) +// { +// Eigen::Vector3f diff = normals_->points[*index].getNormal3fMap () - nucleus_normal.getNormal3fMap (); +// float c = diff.norm () / t; +// c = -1 * pow (c, 6.0); +// c = exp (c); +// Eigen::Vector3f xyz = surface_->points[*index].getVector3fMap (); +// centroid += c * xyz; +// area += c; +// coefficients[0] += c * (x0 - xyz.x) * (x0 - xyz.x); +// coefficients[1] += c * (x0 - xyz.x) * (y0 - xyz.y); +// coefficients[2] += c * (x0 - xyz.x) * (z0 - xyz.z); +// coefficients[3] += c * (y0 - xyz.y) * (y0 - xyz.y); +// coefficients[4] += c * (y0 - xyz.y) * (z0 - xyz.z); +// coefficients[5] += c * (z0 - xyz.z) * (z0 - xyz.z); +// } +// } + +// if (area > 0) +// { +// centroid /= area; +// if (area < geometric_threshold) +// response = geometric_threshold - area; +// // Look for edge direction +// // X direction +// if ((coefficients[3]/coefficients[0]) < 1 && (coefficients[5]/coefficients[0]) < 1) +// direction = Eigen::Vector3f (1, 0, 0); +// else +// { +// // Y direction +// if ((coefficients[0]/coefficients[3]) < 1 && (coefficients[5]/coefficients[3]) < 1) +// direction = Eigen::Vector3f (0, 1, 0); +// else +// { +// // Z direction +// if ((coefficients[0]/coefficients[5]) < 1 && (coefficients[3]/coefficients[5]) < 1) +// direction = Eigen::Vector3f (0, 1, 0); +// // Diagonal edge +// else +// { +// //XY direction +// if ((coefficients[2]/coeffcients[1]) < 1 && (coeffcients[4]/coeffcients[1]) < 1) +// { +// if (coeffcients[1] > 0) +// direction = Eigen::Vector3f (1,1,0); +// else +// direction = Eigen::Vector3f (-1,1,0); +// } +// else +// { +// //XZ direction +// if ((coefficients[1]/coeffcients[2]) > 1 && (coeffcients[4]/coeffcients[2]) < 1) +// { +// if (coeffcients[2] > 0) +// direction = Eigen::Vector3f (1,0,1); +// else +// direction = Eigen::Vector3f (-1,0,1); +// } +// //YZ direction +// else +// { +// if (coeffcients[4] > 0) +// direction = Eigen::Vector3f (0,1,1); +// else +// direction = Eigen::Vector3f (0,-1,1); +// } +// } +// } +// } +// } + +// // std::size_t max_index = std::distance (coefficients.begin (), max); +// // switch (max_index) +// // { +// // case 0 : direction = Eigen::Vector3f (1, 0, 0); break; +// // case 1 : direction = Eigen::Vector3f (1, 1, 0); break; +// // case 2 : direction = Eigen::Vector3f (1, 0, 1); break; +// // case 3 : direction = Eigen::Vector3f (0, 1, 0); break; +// // case 4 : direction = Eigen::Vector3f (0, 1, 1); break; +// // case 5 : direction = Eigen::Vector3f (0, 0, 1); break; +// // } +// } +// } + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SUSANKeypoint::initCompute () +{ + if (!Keypoint::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] init failed!\n", name_.c_str ()); + return (false); + } + + if (normals_->empty ()) + { + PointCloudNPtr normals (new PointCloudN ()); + normals->reserve (normals->size ()); + if (!surface_->isOrganized ()) + { + pcl::NormalEstimation normal_estimation; + normal_estimation.setInputCloud (surface_); + normal_estimation.setRadiusSearch (search_radius_); + normal_estimation.compute (*normals); + } + else + { + IntegralImageNormalEstimation normal_estimation; + normal_estimation.setNormalEstimationMethod (pcl::IntegralImageNormalEstimation::SIMPLE_3D_GRADIENT); + normal_estimation.setInputCloud (surface_); + normal_estimation.setNormalSmoothingSize (5.0); + normal_estimation.compute (*normals); + } + normals_ = normals; + } + if (normals_->size () != surface_->size ()) + { + PCL_ERROR ("[pcl::%s::initCompute] normals given, but the number of normals does not match the number of input points!\n", name_.c_str ()); + return (false); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SUSANKeypoint::isWithinNucleusCentroid (const Eigen::Vector3f& nucleus, + const Eigen::Vector3f& centroid, + const Eigen::Vector3f& nc, + const PointInT& point) const +{ + Eigen::Vector3f pc = centroid - point.getVector3fMap (); + Eigen::Vector3f pn = nucleus - point.getVector3fMap (); + Eigen::Vector3f pc_cross_nc = pc.cross (nc); + return ((pc_cross_nc.norm () <= tolerance_) && (pc.dot (nc) >= 0) && (pn.dot (nc) <= 0)); +} + +// template bool +// pcl::SUSANKeypoint::isValidQueryPoint3D (int point_index) const +// { +// return (isFinite (surface_->points [point_index]) && +// isFinite (normals_->points [point_index])); +// } + +// template bool +// pcl::SUSANKeypoint::isValidQueryPoint2D (int point_index) const +// { +// return (isFinite (surface_->points [point_index])); +// } + +// template bool +// pcl::SUSANKeypoint::isWithinSusan2D (int nucleus, int neighbor) const +// { +// return (fabs (intensity_ (surface_->points[nucleus]) - +// intensity_ (surface_->points[neighbor])) <= intensity_threshold_); +// } + +// template bool +// pcl::SUSANKeypoint::isWithinSusan3D (int nucleus, int neighbor) const +// { +// Eigen::Vector3f nucleus_normal = normals_->point[nucleus].getVector3fMap (); +// return (1 - nucleus_normal.dot (normals_->points[*index].getNormalVector3fMap ()) <= angular_threshold_); +// } + +// template bool +// pcl::SUSANKeypoint::isWithinSusanH (int nucleus, int neighbor) const +// { +// Eigen::Vector3f nucleus_normal = normals_->point[nucleus].getVector3fMap (); +// return ((1 - nucleus_normal.dot (normals_->points[*index].getNormalVector3fMap ()) <= angular_threshold_) || +// (fabs (intensity_ (surface_->points[nucleus]) - intensity_ (surface_->points[neighbor])) <= intensity_threshold_)); +// } + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SUSANKeypoint::detectKeypoints (PointCloudOut &output) +{ + boost::shared_ptr > response (new pcl::PointCloud ()); + response->reserve (surface_->size ()); + + // Check if the output has a "label" field + label_idx_ = pcl::getFieldIndex (output, "label", out_fields_); + + const int input_size = static_cast (input_->size ()); +//#ifdef _OPENMP +//#pragma omp parallel for shared (response) num_threads(threads_) +//#endif + for (int point_index = 0; point_index < input_size; ++point_index) + { + const PointInT& point_in = input_->points [point_index]; + const NormalT& normal_in = normals_->points [point_index]; + if (!isFinite (point_in) || !isFinite (normal_in)) + continue; + else + { + Eigen::Vector3f nucleus = point_in.getVector3fMap (); + Eigen::Vector3f nucleus_normal = normals_->points [point_index].getNormalVector3fMap (); + float nucleus_intensity = intensity_ (point_in); + std::vector nn_indices; + std::vector nn_dists; + tree_->radiusSearch (point_in, search_radius_, nn_indices, nn_dists); + float area = 0; + Eigen::Vector3f centroid = Eigen::Vector3f::Zero (); + // Exclude nucleus from the usan + std::vector usan; usan.reserve (nn_indices.size () - 1); + for (std::vector::const_iterator index = nn_indices.begin(); index != nn_indices.end(); ++index) + { + if ((*index != point_index) && pcl_isfinite (normals_->points[*index].normal_x)) + { + // if the point fulfill condition + if ((fabs (nucleus_intensity - intensity_ (input_->points[*index])) <= intensity_threshold_) || + (1 - nucleus_normal.dot (normals_->points[*index].getNormalVector3fMap ()) <= angular_threshold_)) + { + ++area; + centroid += input_->points[*index].getVector3fMap (); + usan.push_back (*index); + } + } + } + + float geometric_threshold = 0.5f * (static_cast (nn_indices.size () - 1)); + if ((area > 0) && (area < geometric_threshold)) + { + // if no geometric validation required add the point to the response + if (!geometric_validation_) + { + PointOutT point_out; + point_out.getVector3fMap () = point_in.getVector3fMap (); + //point_out.intensity = geometric_threshold - area; + intensity_out_.set (point_out, geometric_threshold - area); + // if a label field is found use it to save the index + if (label_idx_ != -1) + { + // save the index in the cloud + uint32_t label = static_cast (point_index); + memcpy (reinterpret_cast (&point_out) + out_fields_[label_idx_].offset, + &label, sizeof (uint32_t)); + } +//#ifdef _OPENMP +//#pragma omp critical +//#endif + response->push_back (point_out); + } + else + { + centroid /= area; + Eigen::Vector3f dist = nucleus - centroid; + // Check the distance <= distance_threshold_ + if (dist.norm () >= distance_threshold_) + { + // point is valid from distance point of view + Eigen::Vector3f nc = centroid - nucleus; + // Check the contiguity + std::vector::const_iterator usan_it = usan.begin (); + for (; usan_it != usan.end (); ++usan_it) + { + if (!isWithinNucleusCentroid (nucleus, centroid, nc, input_->points[*usan_it])) + break; + } + // All points within usan lies on the segment [nucleus centroid] + if (usan_it == usan.end ()) + { + PointOutT point_out; + point_out.getVector3fMap () = point_in.getVector3fMap (); + // point_out.intensity = geometric_threshold - area; + intensity_out_.set (point_out, geometric_threshold - area); + // if a label field is found use it to save the index + if (label_idx_ != -1) + { + // save the index in the cloud + uint32_t label = static_cast (point_index); + memcpy (reinterpret_cast (&point_out) + out_fields_[label_idx_].offset, + &label, sizeof (uint32_t)); + } +//#ifdef _OPENMP +//#pragma omp critical +//#endif + response->push_back (point_out); + } + } + } + } + } + } + + response->height = 1; + response->width = static_cast (response->size ()); + + if (!nonmax_) + { + output = *response; + for (size_t i = 0; i < response->size (); ++i) + keypoints_indices_->indices.push_back (i); + // we don not change the denseness + output.is_dense = input_->is_dense; + } + else + { + output.points.clear (); + output.points.reserve (response->points.size()); + +//#ifdef _OPENMP +//#pragma omp parallel for shared (output) num_threads(threads_) +//#endif + for (int idx = 0; idx < static_cast (response->points.size ()); ++idx) + { + const PointOutT& point_in = response->points [idx]; + const NormalT& normal_in = normals_->points [idx]; + //const float intensity = response->points[idx].intensity; + const float intensity = intensity_out_ (response->points[idx]); + if (!isFinite (point_in) || !isFinite (normal_in) || (intensity == 0)) + continue; + std::vector nn_indices; + std::vector nn_dists; + tree_->radiusSearch (idx, search_radius_, nn_indices, nn_dists); + bool is_minima = true; + for (std::vector::const_iterator nn_it = nn_indices.begin(); nn_it != nn_indices.end(); ++nn_it) + { +// if (intensity > response->points[*nn_it].intensity) + if (intensity > intensity_out_ (response->points[*nn_it])) + { + is_minima = false; + break; + } + } + if (is_minima) +//#ifdef _OPENMP +//#pragma omp critical +//#endif + { + output.points.push_back (response->points[idx]); + keypoints_indices_->indices.push_back (idx); + } + } + + output.height = 1; + output.width = static_cast (output.points.size()); + output.is_dense = true; + } +} + +#define PCL_INSTANTIATE_SUSAN(T,U,N) template class PCL_EXPORTS pcl::SUSANKeypoint; +#endif // #ifndef PCL_HARRIS_KEYPOINT_3D_IMPL_H_ + diff --git a/pcl-1.7/pcl/keypoints/impl/uniform_sampling.hpp b/pcl-1.7/pcl/keypoints/impl/uniform_sampling.hpp new file mode 100644 index 0000000..d7c1878 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/impl/uniform_sampling.hpp @@ -0,0 +1,128 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_KEYPOINTS_UNIFORM_SAMPLING_IMPL_H_ +#define PCL_KEYPOINTS_UNIFORM_SAMPLING_IMPL_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::UniformSampling::detectKeypoints (PointCloudOut &output) +{ + // Has the input dataset been set already? + if (!input_) + { + PCL_WARN ("[pcl::%s::detectKeypoints] No input dataset given!\n", getClassName ().c_str ()); + output.width = output.height = 0; + output.points.clear (); + return; + } + + output.height = 1; // downsampling breaks the organized structure + output.is_dense = true; // we filter out invalid points + + Eigen::Vector4f min_p, max_p; + // Get the minimum and maximum dimensions + pcl::getMinMax3D(*input_, min_p, max_p); + + // Compute the minimum and maximum bounding box values + min_b_[0] = static_cast (floor (min_p[0] * inverse_leaf_size_[0])); + max_b_[0] = static_cast (floor (max_p[0] * inverse_leaf_size_[0])); + min_b_[1] = static_cast (floor (min_p[1] * inverse_leaf_size_[1])); + max_b_[1] = static_cast (floor (max_p[1] * inverse_leaf_size_[1])); + min_b_[2] = static_cast (floor (min_p[2] * inverse_leaf_size_[2])); + max_b_[2] = static_cast (floor (max_p[2] * inverse_leaf_size_[2])); + + // Compute the number of divisions needed along all axis + div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones (); + div_b_[3] = 0; + + // Clear the leaves + leaves_.clear (); + + // Set up the division multiplier + divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0); + + // First pass: build a set of leaves with the point index closest to the leaf center + for (size_t cp = 0; cp < indices_->size (); ++cp) + { + if (!input_->is_dense) + // Check if the point is invalid + if (!pcl_isfinite (input_->points[(*indices_)[cp]].x) || + !pcl_isfinite (input_->points[(*indices_)[cp]].y) || + !pcl_isfinite (input_->points[(*indices_)[cp]].z)) + continue; + + Eigen::Vector4i ijk = Eigen::Vector4i::Zero (); + ijk[0] = static_cast (floor (input_->points[(*indices_)[cp]].x * inverse_leaf_size_[0])); + ijk[1] = static_cast (floor (input_->points[(*indices_)[cp]].y * inverse_leaf_size_[1])); + ijk[2] = static_cast (floor (input_->points[(*indices_)[cp]].z * inverse_leaf_size_[2])); + + // Compute the leaf index + int idx = (ijk - min_b_).dot (divb_mul_); + Leaf& leaf = leaves_[idx]; + // First time we initialize the index + if (leaf.idx == -1) + { + leaf.idx = (*indices_)[cp]; + continue; + } + + // Check to see if this point is closer to the leaf center than the previous one we saved + float diff_cur = (input_->points[(*indices_)[cp]].getVector4fMap () - ijk.cast ()).squaredNorm (); + float diff_prev = (input_->points[leaf.idx].getVector4fMap () - ijk.cast ()).squaredNorm (); + + // If current point is closer, copy its index instead + if (diff_cur < diff_prev) + leaf.idx = (*indices_)[cp]; + } + + // Second pass: go over all leaves and copy data + output.points.resize (leaves_.size ()); + int cp = 0; + + for (typename boost::unordered_map::const_iterator it = leaves_.begin (); it != leaves_.end (); ++it) + output.points[cp++] = it->second.idx; + output.width = static_cast (output.points.size ()); +} + +#define PCL_INSTANTIATE_UniformSampling(T) template class PCL_EXPORTS pcl::UniformSampling; + +#endif // PCL_KEYPOINTS_UNIFORM_SAMPLING_IMPL_H_ + diff --git a/pcl-1.7/pcl/keypoints/iss_3d.h b/pcl-1.7/pcl/keypoints/iss_3d.h new file mode 100644 index 0000000..de2b8d8 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/iss_3d.h @@ -0,0 +1,269 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_ISS_3D_H_ +#define PCL_ISS_3D_H_ + +#include + +namespace pcl +{ + /** \brief ISSKeypoint3D detects the Intrinsic Shape Signatures keypoints for a given + * point cloud. This class is based on a particular implementation made by Federico + * Tombari and Samuele Salti and it has been explicitly adapted to PCL. + * + * For more information about the original ISS detector, see: + * + *\par + * Yu Zhong, “Intrinsic shape signatures: A shape descriptor for 3D object recognition,†+ * Computer Vision Workshops (ICCV Workshops), 2009 IEEE 12th International Conference on , + * vol., no., pp.689-696, Sept. 27 2009-Oct. 4 2009 + * + * Code example: + * + * \code + * pcl::PointCloud::Ptr model (new pcl::PointCloud ());; + * pcl::PointCloud::Ptr model_keypoints (new pcl::PointCloud ()); + * pcl::search::KdTree::Ptr tree (new pcl::search::KdTree ()); + * + * // Fill in the model cloud + * + * double model_resolution; + * + * // Compute model_resolution + * + * pcl::ISSKeypoint3D iss_detector; + * + * iss_detector.setSearchMethod (tree); + * iss_detector.setSalientRadius (6 * model_resolution); + * iss_detector.setNonMaxRadius (4 * model_resolution); + * iss_detector.setThreshold21 (0.975); + * iss_detector.setThreshold32 (0.975); + * iss_detector.setMinNeighbors (5); + * iss_detector.setNumberOfThreads (4); + * iss_detector.setInputCloud (model); + * iss_detector.compute (*model_keypoints); + * \endcode + * + * \author Gioia Ballin + * \ingroup keypoints + */ + + template + class ISSKeypoint3D : public Keypoint + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename Keypoint::PointCloudIn PointCloudIn; + typedef typename Keypoint::PointCloudOut PointCloudOut; + + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + + typedef typename pcl::octree::OctreePointCloudSearch OctreeSearchIn; + typedef typename OctreeSearchIn::Ptr OctreeSearchInPtr; + + using Keypoint::name_; + using Keypoint::input_; + using Keypoint::surface_; + using Keypoint::tree_; + using Keypoint::search_radius_; + using Keypoint::search_parameter_; + using Keypoint::keypoints_indices_; + + /** \brief Constructor. + * \param[in] salient_radius the radius of the spherical neighborhood used to compute the scatter matrix. + */ + ISSKeypoint3D (double salient_radius = 0.0001) + : salient_radius_ (salient_radius) + , non_max_radius_ (0.0) + , normal_radius_ (0.0) + , border_radius_ (0.0) + , gamma_21_ (0.975) + , gamma_32_ (0.975) + , third_eigen_value_ (0) + , edge_points_ (0) + , min_neighbors_ (5) + , normals_ (new pcl::PointCloud) + , angle_threshold_ (static_cast (M_PI) / 2.0f) + , threads_ (0) + { + name_ = "ISSKeypoint3D"; + search_radius_ = salient_radius_; + } + + /** \brief Set the radius of the spherical neighborhood used to compute the scatter matrix. + * \param[in] salient_radius the radius of the spherical neighborhood + */ + void + setSalientRadius (double salient_radius); + + /** \brief Set the radius for the application of the non maxima supression algorithm. + * \param[in] non_max_radius the non maxima suppression radius + */ + void + setNonMaxRadius (double non_max_radius); + + /** \brief Set the radius used for the estimation of the surface normals of the input cloud. If the radius is + * too large, the temporal performances of the detector may degrade significantly. + * \param[in] normal_radius the radius used to estimate surface normals + */ + void + setNormalRadius (double normal_radius); + + /** \brief Set the radius used for the estimation of the boundary points. If the radius is too large, + * the temporal performances of the detector may degrade significantly. + * \param[in] border_radius the radius used to compute the boundary points + */ + void + setBorderRadius (double border_radius); + + /** \brief Set the upper bound on the ratio between the second and the first eigenvalue. + * \param[in] gamma_21 the upper bound on the ratio between the second and the first eigenvalue + */ + void + setThreshold21 (double gamma_21); + + /** \brief Set the upper bound on the ratio between the third and the second eigenvalue. + * \param[in] gamma_32 the upper bound on the ratio between the third and the second eigenvalue + */ + void + setThreshold32 (double gamma_32); + + /** \brief Set the minimum number of neighbors that has to be found while applying the non maxima suppression algorithm. + * \param[in] min_neighbors the minimum number of neighbors required + */ + void + setMinNeighbors (int min_neighbors); + + /** \brief Set the normals if pre-calculated normals are available. + * \param[in] normals the given cloud of normals + */ + void + setNormals (const PointCloudNConstPtr &normals); + + /** \brief Set the decision boundary (angle threshold) that marks points as boundary or regular. + * (default \f$\pi / 2.0\f$) + * \param[in] angle the angle threshold + */ + inline void + setAngleThreshold (float angle) + { + angle_threshold_ = angle; + } + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param[in] nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + + protected: + + /** \brief Compute the boundary points for the given input cloud. + * \param[in] input the input cloud + * \param[in] border_radius the radius used to compute the boundary points + * \param[in] angle_threshold the decision boundary that marks the points as boundary + * \return the vector of boolean values in which the information about the boundary points is stored + */ + bool* + getBoundaryPoints (PointCloudIn &input, double border_radius, float angle_threshold); + + /** \brief Compute the scatter matrix for a point index. + * \param[in] current_index the index of the point + * \param[out] cov_m the point scatter matrix + */ + void + getScatterMatrix (const int ¤t_index, Eigen::Matrix3d &cov_m); + + /** \brief Perform the initial checks before computing the keypoints. + * \return true if all the checks are passed, false otherwise + */ + bool + initCompute (); + + /** \brief Detect the keypoints by performing the EVD of the scatter matrix. + * \param[out] output the resultant cloud of keypoints + */ + void + detectKeypoints (PointCloudOut &output); + + + /** \brief The radius of the spherical neighborhood used to compute the scatter matrix.*/ + double salient_radius_; + + /** \brief The non maxima suppression radius. */ + double non_max_radius_; + + /** \brief The radius used to compute the normals of the input cloud. */ + double normal_radius_; + + /** \brief The radius used to compute the boundary points of the input cloud. */ + double border_radius_; + + /** \brief The upper bound on the ratio between the second and the first eigenvalue returned by the EVD. */ + double gamma_21_; + + /** \brief The upper bound on the ratio between the third and the second eigenvalue returned by the EVD. */ + double gamma_32_; + + /** \brief Store the third eigen value associated to each point in the input cloud. */ + double *third_eigen_value_; + + /** \brief Store the information about the boundary points of the input cloud. */ + bool *edge_points_; + + /** \brief Minimum number of neighbors that has to be found while applying the non maxima suppression algorithm. */ + int min_neighbors_; + + /** \brief The cloud of normals related to the input surface. */ + PointCloudNConstPtr normals_; + + /** \brief The decision boundary (angle threshold) that marks points as boundary or regular. (default \f$\pi / 2.0\f$) */ + float angle_threshold_; + + /** \brief The number of threads that has to be used by the scheduler. */ + unsigned int threads_; + + }; + +} + +#include + +#endif /* PCL_ISS_3D_H_ */ diff --git a/pcl-1.7/pcl/keypoints/keypoint.h b/pcl-1.7/pcl/keypoints/keypoint.h new file mode 100644 index 0000000..52fdb28 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/keypoint.h @@ -0,0 +1,211 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_KEYPOINT_H_ +#define PCL_KEYPOINT_H_ + +// PCL includes +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief @b Keypoint represents the base class for key points. + * \author Bastian Steder + * \ingroup keypoints + */ + template + class Keypoint : public PCLBase + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using PCLBase::indices_; + using PCLBase::input_; + + typedef PCLBase BaseClass; + typedef typename pcl::search::Search KdTree; + typedef typename pcl::search::Search::Ptr KdTreePtr; + typedef pcl::PointCloud PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + typedef pcl::PointCloud PointCloudOut; + typedef boost::function &, std::vector &)> SearchMethod; + typedef boost::function &, std::vector &)> SearchMethodSurface; + + public: + /** \brief Empty constructor. */ + Keypoint () : + BaseClass (), + name_ (), + search_method_ (), + search_method_surface_ (), + surface_ (), + tree_ (), + search_parameter_ (0), + search_radius_ (0), + k_ (0) + {}; + + /** \brief Empty destructor */ + virtual ~Keypoint () {} + + /** \brief Provide a pointer to the input dataset that we need to estimate features at every point for. + * \param cloud the const boost shared pointer to a PointCloud message + */ + virtual void + setSearchSurface (const PointCloudInConstPtr &cloud) { surface_ = cloud; } + + /** \brief Get a pointer to the surface point cloud dataset. */ + inline PointCloudInConstPtr + getSearchSurface () { return (surface_); } + + /** \brief Provide a pointer to the search object. + * \param tree a pointer to the spatial search object. + */ + inline void + setSearchMethod (const KdTreePtr &tree) { tree_ = tree; } + + /** \brief Get a pointer to the search method used. */ + inline KdTreePtr + getSearchMethod () { return (tree_); } + + /** \brief Get the internal search parameter. */ + inline double + getSearchParameter () { return (search_parameter_); } + + /** \brief Set the number of k nearest neighbors to use for the feature estimation. + * \param k the number of k-nearest neighbors + */ + inline void + setKSearch (int k) { k_ = k; } + + /** \brief get the number of k nearest neighbors used for the feature estimation. */ + inline int + getKSearch () { return (k_); } + + /** \brief Set the sphere radius that is to be used for determining the nearest neighbors used for the + * key point detection + * \param radius the sphere radius used as the maximum distance to consider a point a neighbor + */ + inline void + setRadiusSearch (double radius) { search_radius_ = radius; } + + /** \brief Get the sphere radius used for determining the neighbors. */ + inline double + getRadiusSearch () { return (search_radius_); } + + /** \brief \return the keypoints indices in the input cloud. + * \note not all the daughter classes populate the keypoints indices so check emptiness before use. + */ + pcl::PointIndicesConstPtr + getKeypointsIndices () { return (keypoints_indices_); } + + /** \brief Base method for key point detection for all points given in using + * the surface in setSearchSurface () and the spatial locator in setSearchMethod () + * \param output the resultant point cloud model dataset containing the estimated features + */ + inline void + compute (PointCloudOut &output); + + /** \brief Search for k-nearest neighbors using the spatial locator from \a setSearchmethod, and the given surface + * from \a setSearchSurface. + * \param index the index of the query point + * \param parameter the search parameter (either k or radius) + * \param indices the resultant vector of indices representing the k-nearest neighbors + * \param distances the resultant vector of distances representing the distances from the query point to the + * k-nearest neighbors + */ + inline int + searchForNeighbors (int index, double parameter, std::vector &indices, std::vector &distances) const + { + if (surface_ == input_) // if the two surfaces are the same + return (search_method_ (index, parameter, indices, distances)); + else + return (search_method_surface_ (*input_, index, parameter, indices, distances)); + } + + protected: + using PCLBase::deinitCompute; + + virtual bool + initCompute (); + + /** \brief The key point detection method's name. */ + std::string name_; + + /** \brief The search method template for indices. */ + SearchMethod search_method_; + + /** \brief The search method template for points. */ + SearchMethodSurface search_method_surface_; + + /** \brief An input point cloud describing the surface that is to be used for nearest neighbors estimation. */ + PointCloudInConstPtr surface_; + + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + + /** \brief The actual search parameter (casted from either \a search_radius_ or \a k_). */ + double search_parameter_; + + /** \brief The nearest neighbors search radius for each point. */ + double search_radius_; + + /** \brief The number of K nearest neighbors to use for each point. */ + int k_; + + /** \brief Indices of the keypoints in the input cloud. */ + pcl::PointIndicesPtr keypoints_indices_; + + /** \brief Get a string representation of the name of this class. */ + inline const std::string& + getClassName () const { return (name_); } + + /** \brief Abstract key point detection method. */ + virtual void + detectKeypoints (PointCloudOut &output) = 0; + }; +} + +#include + +#endif //#ifndef PCL_KEYPOINT_H_ diff --git a/pcl-1.7/pcl/keypoints/narf_keypoint.h b/pcl-1.7/pcl/keypoints/narf_keypoint.h new file mode 100644 index 0000000..d481518 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/narf_keypoint.h @@ -0,0 +1,206 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +/* \author Bastian Steder */ + +#ifndef PCL_NARF_KEYPOINT_H_ +#define PCL_NARF_KEYPOINT_H_ + +#include +#include +#include +#include + +namespace pcl { + +// Forward declarations +class RangeImage; +class RangeImageBorderExtractor; + +/** \brief @b NARF (Normal Aligned Radial Feature) keypoints. Input is a range image, + * output the indices of the keypoints + * See B. Steder, R. B. Rusu, K. Konolige, and W. Burgard + * Point Feature Extraction on 3D Range Scans Taking into Account Object Boundaries + * In Proc. of the IEEE Int. Conf. on Robotics &Automation (ICRA). 2011. + * \author Bastian Steder + * \ingroup keypoints + */ +class PCL_EXPORTS NarfKeypoint : public Keypoint +{ + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + // =====TYPEDEFS===== + typedef Keypoint BaseClass; + + typedef Keypoint::PointCloudOut PointCloudOut; + + // =====PUBLIC STRUCTS===== + //! Parameters used in this class + struct Parameters + { + Parameters() : support_size(-1.0f), max_no_of_interest_points(-1), min_distance_between_interest_points(0.25f), + optimal_distance_to_high_surface_change(0.25), min_interest_value(0.45f), + min_surface_change_score(0.2f), optimal_range_image_patch_size(10), + distance_for_additional_points(0.0f), add_points_on_straight_edges(false), + do_non_maximum_suppression(true), no_of_polynomial_approximations_per_point(0), + max_no_of_threads(1), use_recursive_scale_reduction(false), + calculate_sparse_interest_image(true) {} + + float support_size; //!< This defines the area 'covered' by an interest point (in meters) + int max_no_of_interest_points; //!< The maximum number of interest points that will be returned + float min_distance_between_interest_points; /**< Minimum distance between maximas + * (this is a factor for support_size, i.e. the distance is + * min_distance_between_interest_points*support_size) */ + float optimal_distance_to_high_surface_change; /**< The distance we want keep between keypoints and areas + * of high surface change + * (this is a factor for support_size, i.e., the distance is + * optimal_distance_to_high_surface_change*support_size) */ + float min_interest_value; //!< The minimum value to consider a point as an interest point + float min_surface_change_score; //!< The minimum value of the surface change score to consider a point + int optimal_range_image_patch_size; /**< The size (in pixels) of the image patches from which the interest value + * should be computed. This influences, which range image is selected from + * the scale space to compute the interest value of a pixel at a certain + * distance. */ + // TODO: + float distance_for_additional_points; /**< All points in this distance to a found maximum, that + * are above min_interest_value are also added as interest points + * (this is a factor for support_size, i.e. the distance is + * distance_for_additional_points*support_size) */ + bool add_points_on_straight_edges; /**< If this is set to true, there will also be interest points on + * straight edges, e.g., just indicating an area of high surface change */ + bool do_non_maximum_suppression; /**< If this is set to false there will be much more points + * (can be used to spread points over the whole scene + * (combined with a low min_interest_value)) */ + bool no_of_polynomial_approximations_per_point; /**< If this is >0, the exact position of the interest point is + determined using bivariate polynomial approximations of the + interest values of the area. */ + int max_no_of_threads; //!< The maximum number of threads this code is allowed to use with OPNEMP + bool use_recursive_scale_reduction; /**< Try to decrease runtime by extracting interest points at lower reolution + * in areas that contain enough points, i.e., have lower range. */ + bool calculate_sparse_interest_image; /**< Use some heuristics to decide which areas of the interest image + can be left out to improve the runtime. */ + }; + + // =====CONSTRUCTOR & DESTRUCTOR===== + NarfKeypoint (RangeImageBorderExtractor* range_image_border_extractor=NULL, float support_size=-1.0f); + virtual ~NarfKeypoint (); + + // =====PUBLIC METHODS===== + //! Erase all data calculated for the current range image + void + clearData (); + + //! Set the RangeImageBorderExtractor member (required) + void + setRangeImageBorderExtractor (RangeImageBorderExtractor* range_image_border_extractor); + + //! Get the RangeImageBorderExtractor member + RangeImageBorderExtractor* + getRangeImageBorderExtractor () { return range_image_border_extractor_; } + + //! Set the RangeImage member of the RangeImageBorderExtractor + void + setRangeImage (const RangeImage* range_image); + + /** Extract interest value per image point */ + float* + getInterestImage () { calculateInterestImage(); return interest_image_;} + + //! Extract maxima from an interest image + const ::pcl::PointCloud& + getInterestPoints () { calculateInterestPoints(); return *interest_points_;} + + //! Set all points in the image that are interest points to true, the rest to false + const std::vector& + getIsInterestPointImage () { calculateInterestPoints(); return is_interest_point_image_;} + + //! Getter for the parameter struct + Parameters& + getParameters () { return parameters_;} + + //! Getter for the range image of range_image_border_extractor_ + const RangeImage& + getRangeImage (); + + //! Overwrite the compute function of the base class + void + compute (PointCloudOut& output); + + protected: + // =====PROTECTED METHODS===== + void + calculateScaleSpace (); + void + calculateInterestImage (); + void + calculateCompleteInterestImage (); + void + calculateSparseInterestImage (); + void + calculateInterestPoints (); + //void + //blurInterestImage (); + //! Detect key points + virtual void + detectKeypoints (PointCloudOut& output); + + // =====PROTECTED MEMBER VARIABLES===== + using BaseClass::name_; + RangeImageBorderExtractor* range_image_border_extractor_; + Parameters parameters_; + float* interest_image_; + ::pcl::PointCloud* interest_points_; + std::vector is_interest_point_image_; + std::vector range_image_scale_space_; + std::vector border_extractor_scale_space_; + std::vector interest_image_scale_space_; +}; + +/** + * \ingroup keypoints + */ +inline std::ostream& + operator << (std::ostream& os, const NarfKeypoint::Parameters& p) +{ + os << PVARC(p.support_size) << PVARC(p.min_distance_between_interest_points) + << PVARC(p.min_interest_value) << PVARN(p.distance_for_additional_points); + return (os); +} + +} // end namespace pcl + +#endif //#ifndef PCL_NARF_KEYPOINT_H_ diff --git a/pcl-1.7/pcl/keypoints/sift_keypoint.h b/pcl-1.7/pcl/keypoints/sift_keypoint.h new file mode 100644 index 0000000..636f3ba --- /dev/null +++ b/pcl-1.7/pcl/keypoints/sift_keypoint.h @@ -0,0 +1,206 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SIFT_KEYPOINT_H_ +#define PCL_SIFT_KEYPOINT_H_ + +#include + +namespace pcl +{ + template + struct SIFTKeypointFieldSelector + { + inline float + operator () (const PointT & p) const + { + return p.intensity; + } + }; + template<> + struct SIFTKeypointFieldSelector + { + inline float + operator () (const PointNormal & p) const + { + return p.curvature; + } + }; + template<> + struct SIFTKeypointFieldSelector + { + inline float + operator () (const PointXYZRGB & p) const + { + return (static_cast (299*p.r + 587*p.g + 114*p.b) / 1000.0f); + } + }; + template<> + struct SIFTKeypointFieldSelector + { + inline float + operator () (const PointXYZRGBA & p) const + { + return (static_cast (299*p.r + 587*p.g + 114*p.b) / 1000.0f); + } + }; + + /** \brief @b SIFTKeypoint detects the Scale Invariant Feature Transform + * keypoints for a given point cloud dataset containing points and intensity. + * This implementation adapts the original algorithm from images to point + * clouds. + * + * For more information about the image-based SIFT interest operator, see: + * + * David G. Lowe, "Distinctive image features from scale-invariant keypoints," + * International Journal of Computer Vision, 60, 2 (2004), pp. 91-110. + * + * \author Michael Dixon + * \ingroup keypoints + */ + template + class SIFTKeypoint : public Keypoint + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename Keypoint::PointCloudIn PointCloudIn; + typedef typename Keypoint::PointCloudOut PointCloudOut; + typedef typename Keypoint::KdTree KdTree; + + using Keypoint::name_; + using Keypoint::input_; + using Keypoint::indices_; + using Keypoint::surface_; + using Keypoint::tree_; + using Keypoint::initCompute; + + /** \brief Empty constructor. */ + SIFTKeypoint () : min_scale_ (0.0), nr_octaves_ (0), nr_scales_per_octave_ (0), + min_contrast_ (-std::numeric_limits::max ()), scale_idx_ (-1), + out_fields_ (), getFieldValue_ () + { + name_ = "SIFTKeypoint"; + } + + /** \brief Specify the range of scales over which to search for keypoints + * \param min_scale the standard deviation of the smallest scale in the scale space + * \param nr_octaves the number of octaves (i.e. doublings of scale) to compute + * \param nr_scales_per_octave the number of scales to compute within each octave + */ + void + setScales (float min_scale, int nr_octaves, int nr_scales_per_octave); + + /** \brief Provide a threshold to limit detection of keypoints without sufficient contrast + * \param min_contrast the minimum contrast required for detection + */ + void + setMinimumContrast (float min_contrast); + + protected: + bool + initCompute (); + + /** \brief Detect the SIFT keypoints for a set of points given in setInputCloud () using the spatial locator in + * setSearchMethod (). + * \param output the resultant cloud of keypoints + */ + void + detectKeypoints (PointCloudOut &output); + + private: + /** \brief Detect the SIFT keypoints for a given point cloud for a single octave. + * \param input the point cloud to detect keypoints in + * \param tree a k-D tree of the points in \a input + * \param base_scale the first (smallest) scale in the octave + * \param nr_scales_per_octave the number of scales to to compute + * \param output the resultant point cloud containing the SIFT keypoints + */ + void + detectKeypointsForOctave (const PointCloudIn &input, KdTree &tree, + float base_scale, int nr_scales_per_octave, + PointCloudOut &output); + + /** \brief Compute the difference-of-Gaussian (DoG) scale space for the given input and scales + * \param input the point cloud for which the DoG scale space will be computed + * \param tree a k-D tree of the points in \a input + * \param scales a vector containing the scales over which to compute the DoG scale space + * \param diff_of_gauss the resultant DoG scale space (in a number-of-points by number-of-scales matrix) + */ + void + computeScaleSpace (const PointCloudIn &input, KdTree &tree, + const std::vector &scales, + Eigen::MatrixXf &diff_of_gauss); + + /** \brief Find the local minima and maxima in the provided difference-of-Gaussian (DoG) scale space + * \param input the input point cloud + * \param tree a k-D tree of the points in \a input + * \param diff_of_gauss the DoG scale space (in a number-of-points by number-of-scales matrix) + * \param extrema_indices the resultant vector containing the point indices of each keypoint + * \param extrema_scales the resultant vector containing the scale indices of each keypoint + */ + void + findScaleSpaceExtrema (const PointCloudIn &input, KdTree &tree, + const Eigen::MatrixXf &diff_of_gauss, + std::vector &extrema_indices, std::vector &extrema_scales); + + + /** \brief The standard deviation of the smallest scale in the scale space.*/ + float min_scale_; + + /** \brief The number of octaves (i.e. doublings of scale) over which to search for keypoints.*/ + int nr_octaves_; + + /** \brief The number of scales to be computed for each octave.*/ + int nr_scales_per_octave_; + + /** \brief The minimum contrast required for detection.*/ + float min_contrast_; + + /** \brief Set to a value different than -1 if the output cloud has a "scale" field and we have to save + * the keypoints scales. */ + int scale_idx_; + + /** \brief The list of fields present in the output point cloud data. */ + std::vector out_fields_; + + SIFTKeypointFieldSelector getFieldValue_; + }; +} + +#include + +#endif // #ifndef PCL_SIFT_KEYPOINT_H_ diff --git a/pcl-1.7/pcl/keypoints/smoothed_surfaces_keypoint.h b/pcl-1.7/pcl/keypoints/smoothed_surfaces_keypoint.h new file mode 100644 index 0000000..489e9bd --- /dev/null +++ b/pcl-1.7/pcl/keypoints/smoothed_surfaces_keypoint.h @@ -0,0 +1,136 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Willow Garage, Inc + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_SMOOTHEDSURFACESKEYPOINT_H_ +#define PCL_SMOOTHEDSURFACESKEYPOINT_H_ + +#include + +namespace pcl +{ + /** \brief + * Based on the paper: + * Xinju Li and Igor Guskov + * Multi-scale features for approximate alignment of point-based surfaces + * Proceedings of the third Eurographics symposium on Geometry processing + * July 2005, Vienna, Austria + * + * \author Alexandru-Eugen Ichim + */ + template + class SmoothedSurfacesKeypoint : public Keypoint + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using PCLBase::input_; + using Keypoint::name_; + using Keypoint::tree_; + using Keypoint::keypoints_indices_; + using Keypoint::initCompute; + + typedef pcl::PointCloud PointCloudT; + typedef typename PointCloudT::ConstPtr PointCloudTConstPtr; + typedef pcl::PointCloud PointCloudNT; + typedef typename PointCloudNT::ConstPtr PointCloudNTConstPtr; + typedef typename PointCloudT::Ptr PointCloudTPtr; + typedef typename Keypoint::KdTreePtr KdTreePtr; + + SmoothedSurfacesKeypoint () + : Keypoint (), + neighborhood_constant_ (0.5f), + clouds_ (), + cloud_normals_ (), + cloud_trees_ (), + normals_ (), + scales_ (), + input_scale_ (0.0f), + input_index_ () + { + name_ = "SmoothedSurfacesKeypoint"; + + // hack to pass the initCompute () check of Keypoint - although it is never used in SmoothedSurfacesKeypoint + Keypoint::search_radius_ = 0.1; + } + + void + addSmoothedPointCloud (const PointCloudTConstPtr &cloud, + const PointCloudNTConstPtr &normals, + KdTreePtr &kdtree, + float &scale); + + + void + resetClouds (); + + inline void + setNeighborhoodConstant (float neighborhood_constant) { neighborhood_constant_ = neighborhood_constant; } + + inline float + getNeighborhoodConstant () { return neighborhood_constant_; } + + inline void + setInputNormals (const PointCloudNTConstPtr &normals) { normals_ = normals; } + + inline void + setInputScale (float input_scale) { input_scale_ = input_scale; } + + void + detectKeypoints (PointCloudT &output); + + protected: + bool + initCompute (); + + private: + float neighborhood_constant_; + std::vector clouds_; + std::vector cloud_normals_; + std::vector cloud_trees_; + PointCloudNTConstPtr normals_; + std::vector > scales_; + float input_scale_; + size_t input_index_; + + static bool + compareScalesFunction (const std::pair &a, + const std::pair &b) { return a.first < b.first; } + }; +} + +#endif /* PCL_SMOOTHEDSURFACESKEYPOINT_H_ */ diff --git a/pcl-1.7/pcl/keypoints/susan.h b/pcl-1.7/pcl/keypoints/susan.h new file mode 100644 index 0000000..1613f47 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/susan.h @@ -0,0 +1,204 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_SUSAN_KEYPOINT_H_ +#define PCL_SUSAN_KEYPOINT_H_ + +#include +#include + +namespace pcl +{ + /** \brief SUSANKeypoint implements a RGB-D extension of the SUSAN detector inluding normal + * directions variation in top of intensity variation. + * It is different from Harris in that it exploits normals directly so it is faster. + * Original paper "SUSAN — A New Approach to Low Level Image Processing", Smith, + * Stephen M. and Brady, J. Michael + * + * \author Nizar Sallem + * \ingroup keypoints + */ + template > + class SUSANKeypoint : public Keypoint + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename Keypoint::PointCloudIn PointCloudIn; + typedef typename Keypoint::PointCloudOut PointCloudOut; + typedef typename Keypoint::KdTree KdTree; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + + using Keypoint::name_; + using Keypoint::input_; + using Keypoint::indices_; + using Keypoint::surface_; + using Keypoint::tree_; + using Keypoint::k_; + using Keypoint::search_radius_; + using Keypoint::search_parameter_; + using Keypoint::keypoints_indices_; + using Keypoint::initCompute; + + /** \brief Constructor + * \param[in] radius the radius for normal estimation as well as for non maxima suppression + * \param[in] distance_threshold to test if the nucleus is far enough from the centroid + * \param[in] angular_threshold to test if normals are parallel + * \param[in] intensity_threshold to test if points are of same color + */ + SUSANKeypoint (float radius = 0.01f, + float distance_threshold = 0.001f, + float angular_threshold = 0.0001f, + float intensity_threshold = 7.0f) + : distance_threshold_ (distance_threshold) + , angular_threshold_ (angular_threshold) + , intensity_threshold_ (intensity_threshold) + , normals_ (new pcl::PointCloud) + , threads_ (0) + , label_idx_ (-1) + , out_fields_ () + { + name_ = "SUSANKeypoint"; + search_radius_ = radius; + geometric_validation_ = false; + tolerance_ = 2 * distance_threshold_; + } + + /** \brief Empty destructor */ + virtual ~SUSANKeypoint () {} + + /** \brief set the radius for normal estimation and non maxima supression. + * \param[in] radius + */ + void + setRadius (float radius); + + void + setDistanceThreshold (float distance_threshold); + + /** \brief set the angular_threshold value for detecting corners. Normals are considered as + * parallel if 1 - angular_threshold <= (Ni.Nj) <= 1 + * \param[in] angular_threshold + */ + void + setAngularThreshold (float angular_threshold); + + /** \brief set the intensity_threshold value for detecting corners. + * \param[in] intensity_threshold + */ + void + setIntensityThreshold (float intensity_threshold); + + /** + * \brief set normals if precalculated normals are available. + * \param normals + */ + void + setNormals (const PointCloudNConstPtr &normals); + + virtual void + setSearchSurface (const PointCloudInConstPtr &cloud); + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + void + setNumberOfThreads (unsigned int nr_threads); + + /** \brief Apply non maxima suppression to the responses to keep strongest corners. + * \note in SUSAN points with less response or stronger corners + */ + void + setNonMaxSupression (bool nonmax); + + /** \brief Filetr false positive using geometric criteria. + * The nucleus and the centroid should at least distance_threshold_ from each other AND all the + * points belonging to the USAN must be within the segment [nucleus centroid]. + * \param[in] validate + */ + void + setGeometricValidation (bool validate); + + protected: + bool + initCompute (); + + void + detectKeypoints (PointCloudOut &output); + /** \brief return true if a point lies within the line between the nucleus and the centroid + * \param[in] nucleus coordinate of the nucleus + * \param[in] centroid of the SUSAN + * \param[in] nc to centroid vector (used to speed up since it is constant for a given + * neighborhood) + * \param[in] point the query point to test against + * \return true if the point lies within [nucleus centroid] + */ + bool + isWithinNucleusCentroid (const Eigen::Vector3f& nucleus, + const Eigen::Vector3f& centroid, + const Eigen::Vector3f& nc, + const PointInT& point) const; + private: + float distance_threshold_; + float angular_threshold_; + float intensity_threshold_; + float tolerance_; + PointCloudNConstPtr normals_; + unsigned int threads_; + bool geometric_validation_; + bool nonmax_; + /// intensity field accessor + IntensityT intensity_; + /** \brief Set to a value different than -1 if the output cloud has a "label" field and we have + * to save the keypoints indices. + */ + int label_idx_; + /** \brief The list of fields present in the output point cloud data. */ + std::vector out_fields_; + pcl::common::IntensityFieldAccessor intensity_out_; + }; +} + +#include + +#endif // #ifndef PCL_SUSAN_KEYPOINT_H_ diff --git a/pcl-1.7/pcl/keypoints/uniform_sampling.h b/pcl-1.7/pcl/keypoints/uniform_sampling.h new file mode 100644 index 0000000..09afd81 --- /dev/null +++ b/pcl-1.7/pcl/keypoints/uniform_sampling.h @@ -0,0 +1,143 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_KEYPOINTS_UNIFORM_SAMPLING_H_ +#define PCL_KEYPOINTS_UNIFORM_SAMPLING_H_ + +#include +#include + +namespace pcl +{ + /** \brief @b UniformSampling assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. + * + * The @b UniformSampling class creates a *3D voxel grid* (think about a voxel + * grid as a set of tiny 3D boxes in space) over the input point cloud data. + * Then, in each *voxel* (i.e., 3D box), all the points present will be + * approximated (i.e., *downsampled*) with their centroid. This approach is + * a bit slower than approximating them with the center of the voxel, but it + * represents the underlying surface more accurately. + * + * \author Radu Bogdan Rusu + * \ingroup keypoints + */ + template + class UniformSampling: public Keypoint + { + typedef typename Keypoint::PointCloudIn PointCloudIn; + typedef typename Keypoint::PointCloudOut PointCloudOut; + + using Keypoint::name_; + using Keypoint::input_; + using Keypoint::indices_; + using Keypoint::search_radius_; + using Keypoint::getClassName; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Empty constructor. */ + UniformSampling () : + leaves_ (), + leaf_size_ (Eigen::Vector4f::Zero ()), + inverse_leaf_size_ (Eigen::Vector4f::Zero ()), + min_b_ (Eigen::Vector4i::Zero ()), + max_b_ (Eigen::Vector4i::Zero ()), + div_b_ (Eigen::Vector4i::Zero ()), + divb_mul_ (Eigen::Vector4i::Zero ()) + { + name_ = "UniformSampling"; + } + + /** \brief Destructor. */ + virtual ~UniformSampling () + { + leaves_.clear(); + } + + /** \brief Set the 3D grid leaf size. + * \param radius the 3D grid leaf size + */ + virtual inline void + setRadiusSearch (double radius) + { + leaf_size_[0] = leaf_size_[1] = leaf_size_[2] = static_cast (radius); + // Avoid division errors + if (leaf_size_[3] == 0) + leaf_size_[3] = 1; + // Use multiplications instead of divisions + inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array (); + search_radius_ = radius; + } + + protected: + /** \brief Simple structure to hold an nD centroid and the number of points in a leaf. */ + struct Leaf + { + Leaf () : idx (-1) { } + int idx; + }; + + /** \brief The 3D grid leaves. */ + boost::unordered_map leaves_; + + /** \brief The size of a leaf. */ + Eigen::Vector4f leaf_size_; + + /** \brief Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons. */ + Eigen::Array4f inverse_leaf_size_; + + /** \brief The minimum and maximum bin coordinates, the number of divisions, and the division multiplier. */ + Eigen::Vector4i min_b_, max_b_, div_b_, divb_mul_; + + /** \brief Downsample a Point Cloud using a voxelized grid approach + * \param output the resultant point cloud message + */ + void + detectKeypoints (PointCloudOut &output); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_KEYPOINTS_UNIFORM_SAMPLING_H_ + diff --git a/pcl-1.7/pcl/modeler/abstract_item.h b/pcl-1.7/pcl/modeler/abstract_item.h new file mode 100644 index 0000000..6d98737 --- /dev/null +++ b/pcl-1.7/pcl/modeler/abstract_item.h @@ -0,0 +1,86 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_ABSTRACT_ITEM_H_ +#define PCL_MODELER_ABSTRACT_ITEM_H_ + +#include + +class QMenu; +class QPoint; +namespace Ui +{ + class MainWindow; +} + +namespace pcl +{ + namespace modeler + { + class ParameterDialog; + + class AbstractItem + { + public: + AbstractItem(void); + ~AbstractItem(void); + + void + showContextMenu(const QPoint* position); + + virtual std::string + getItemName() const = 0; + + void + showPropertyEditor(); + + protected: + Ui::MainWindow* ui() const; + + virtual void + prepareContextMenu(QMenu* menu) const = 0; + + virtual void + prepareProperties(ParameterDialog* parameter_dialog) = 0; + + virtual void + setProperties() = 0; + }; + + } +} + +#endif // PCL_MODELER_ABSTRACT_ITEM_H_ diff --git a/pcl-1.7/pcl/modeler/abstract_worker.h b/pcl-1.7/pcl/modeler/abstract_worker.h new file mode 100644 index 0000000..20c8f5b --- /dev/null +++ b/pcl-1.7/pcl/modeler/abstract_worker.h @@ -0,0 +1,95 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_ABSTRACT_WORKER_H_ +#define PCL_MODELER_ABSTRACT_WORKER_H_ + +#include + +namespace pcl +{ + namespace modeler + { + class CloudMeshItem; + class ParameterDialog; + + class AbstractWorker : public QObject + { + Q_OBJECT + + public: + AbstractWorker(const QList& cloud_mesh_items, QWidget* parent=0); + ~AbstractWorker(void); + + int + exec(); + + public slots: + void + process(); + + signals: + void + dataUpdated(CloudMeshItem* cloud_mesh_item); + + void + finished(); + + protected: + void + emitDataUpdated(CloudMeshItem* cloud_mesh_item); + + virtual std::string + getName () const {return ("");} + + virtual void + initParameters(CloudMeshItem* cloud_mesh_item) = 0; + + virtual void + setupParameters() = 0; + + virtual void + processImpl(CloudMeshItem* cloud_mesh_item) = 0; + + protected: + QList cloud_mesh_items_; + ParameterDialog* parameter_dialog_; + }; + + } +} + +#endif // PCL_MODELER_ABSTRACT_WORKER_H_ diff --git a/pcl-1.7/pcl/modeler/channel_actor_item.h b/pcl-1.7/pcl/modeler/channel_actor_item.h new file mode 100644 index 0000000..e7f6c39 --- /dev/null +++ b/pcl-1.7/pcl/modeler/channel_actor_item.h @@ -0,0 +1,104 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ +#ifndef PCL_MODELER_CHANNEL_ACTOR_ITEM_H_ +#define PCL_MODELER_CHANNEL_ACTOR_ITEM_H_ + +#include +#include +#include +#include +#include + +class vtkActor; +class vtkPolyData; +class vtkMatrix4x4; +class vtkRenderWindow; + + +namespace pcl +{ + namespace modeler + { + class CloudMesh; + + class ChannelActorItem : public QTreeWidgetItem, public AbstractItem + { + public: + ChannelActorItem(QTreeWidgetItem* parent, + const boost::shared_ptr& cloud_mesh, + const vtkSmartPointer& render_window, + const vtkSmartPointer& actor, + const std::string& channel_name); + ~ChannelActorItem(); + + void + init(); + + void + update(); + + void + switchRenderWindow(vtkRenderWindow* render_window); + + protected: + void + attachActor(); + + void + detachActor(); + + virtual void + initImpl() = 0; + + virtual void + updateImpl() = 0; + + virtual void + prepareContextMenu(QMenu* menu) const; + + boost::shared_ptr cloud_mesh_; + vtkSmartPointer poly_data_; + vtkSmartPointer render_window_; + std::string color_scheme_; + vtkSmartPointer actor_; + double r_, g_, b_; + + private: + }; + } +} + +#endif // PCL_MODELER_CHANNEL_ACTOR_ITEM_H_ diff --git a/pcl-1.7/pcl/modeler/cloud_mesh.h b/pcl-1.7/pcl/modeler/cloud_mesh.h new file mode 100644 index 0000000..c5929e6 --- /dev/null +++ b/pcl-1.7/pcl/modeler/cloud_mesh.h @@ -0,0 +1,121 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ +#ifndef PCL_MODELER_CLOUD_MESH_H_ +#define PCL_MODELER_CLOUD_MESH_H_ + +#include +#include +#include +#include + +class vtkPoints; +class vtkCellArray; +class vtkDataArray; + +namespace pcl +{ + namespace modeler + { + class CloudMesh + { + public: + typedef pcl::PointSurfel PointT; + typedef pcl::PointCloud PointCloud; + typedef PointCloud::Ptr PointCloudPtr; + typedef PointCloud::ConstPtr PointCloudConstPtr; + + CloudMesh (); + CloudMesh (PointCloudPtr cloud); + ~CloudMesh (); + + PointCloudPtr& + getCloud() {return cloud_;} + PointCloudConstPtr + getCloud() const {return cloud_;} + + std::vector& + getPolygons() {return polygons_;} + const std::vector& + getPolygons() const {return polygons_;} + + vtkSmartPointer& + getVtkPoints() {return vtk_points_;} + const vtkSmartPointer& + getVtkPoints() const {return vtk_points_;} + + vtkSmartPointer& + getVtkPolygons() {return vtk_polygons_;} + const vtkSmartPointer& + getVtkPolygons() const {return vtk_polygons_;} + + std::vector + getAvaiableFieldNames() const; + + bool + open(const std::string& filename); + + bool + save(const std::string& filename) const; + + static bool + save(const std::vector& cloud_meshes, const std::string& filename); + + void + getColorScalarsFromField(vtkSmartPointer &scalars, const std::string& field) const; + + void + updateVtkPoints(); + + void + updateVtkPolygons(); + + void + transform(double tx, double ty, double tz, double rx, double ry, double rz); + + protected: + + + private: + PointCloudPtr cloud_; + std::vector polygons_; + + vtkSmartPointer vtk_points_; + vtkSmartPointer vtk_polygons_; + }; + } +} + +#endif // PCL_MODELER_CLOUD_MESH_H_ \ No newline at end of file diff --git a/pcl-1.7/pcl/modeler/cloud_mesh_item.h b/pcl-1.7/pcl/modeler/cloud_mesh_item.h new file mode 100644 index 0000000..5f6ea96 --- /dev/null +++ b/pcl-1.7/pcl/modeler/cloud_mesh_item.h @@ -0,0 +1,112 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ +#ifndef PCL_MODELER_CLOUD_MESH_ITEM_H_ +#define PCL_MODELER_CLOUD_MESH_ITEM_H_ + +#include +#include +#include +#include + +namespace pcl +{ + namespace modeler + { + class CloudMesh; + class DoubleParameter; + + class CloudMeshItem : public QTreeWidgetItem, public AbstractItem + { + public: + CloudMeshItem(QTreeWidgetItem* parent, const std::string& filename); + CloudMeshItem(QTreeWidgetItem* parent, CloudMesh::PointCloudPtr cloud); + CloudMeshItem(QTreeWidgetItem* parent, const CloudMeshItem& cloud_mesh_item); + ~CloudMeshItem(); + + inline boost::shared_ptr& + getCloudMesh() + { + return cloud_mesh_; + } + inline const boost::shared_ptr& + getCloudMesh() const + { + return cloud_mesh_; + } + + static bool + savePointCloud(const QList& items, const QString& filename); + + bool + open(); + + void + createChannels(); + + void + updateChannels(); + + virtual std::string + getItemName() const {return "Cloud Mesh Item";} + + void + updateRenderWindow(); + + protected: + virtual void + prepareContextMenu(QMenu* menu) const; + + virtual void + prepareProperties(ParameterDialog* parameter_dialog); + + virtual void + setProperties(); + + private: + std::string filename_; + boost::shared_ptr cloud_mesh_; + + DoubleParameter* translation_x_; + DoubleParameter* translation_y_; + DoubleParameter* translation_z_; + DoubleParameter* rotation_x_; + DoubleParameter* rotation_y_; + DoubleParameter* rotation_z_; + }; + } +} + +#endif // PCL_MODELER_CLOUD_MESH_ITEM_H_ diff --git a/pcl-1.7/pcl/modeler/cloud_mesh_item_updater.h b/pcl-1.7/pcl/modeler/cloud_mesh_item_updater.h new file mode 100644 index 0000000..c1d1daa --- /dev/null +++ b/pcl-1.7/pcl/modeler/cloud_mesh_item_updater.h @@ -0,0 +1,65 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ +#ifndef PCL_MODELER_CLOUD_MESH_ITEM_UPDATER_H_ +#define PCL_MODELER_CLOUD_MESH_ITEM_UPDATER_H_ + +#include + +namespace pcl +{ + namespace modeler + { + class CloudMeshItem; + + class CloudMeshItemUpdater : public QObject + { + Q_OBJECT + + public: + CloudMeshItemUpdater (CloudMeshItem* cloud_mesh_item); + ~CloudMeshItemUpdater (); + + public slots: + void + updateCloudMeshItem(); + + private: + CloudMeshItem* cloud_mesh_item_; + }; + } +} + +#endif // PCL_MODELER_CLOUD_MESH_ITEM_UPDATER_H_ diff --git a/pcl-1.7/pcl/modeler/dock_widget.h b/pcl-1.7/pcl/modeler/dock_widget.h new file mode 100644 index 0000000..280da30 --- /dev/null +++ b/pcl-1.7/pcl/modeler/dock_widget.h @@ -0,0 +1,64 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_DOCK_WIDGET_H_ +#define PCL_MODELER_DOCK_WIDGET_H_ + +#include + +namespace pcl +{ + namespace modeler + { + class DockWidget : public QDockWidget + { + public: + explicit DockWidget(const QString &title, QWidget *parent = 0, Qt::WindowFlags flags = 0); + explicit DockWidget(QWidget *parent = 0, Qt::WindowFlags flags = 0); + ~DockWidget(); + + void + setFocusBasedStyle(bool focused); + protected: + virtual void + focusInEvent ( QFocusEvent * event ); + + private: + }; + } +} + +#endif // PCL_MODELER_DOCK_WIDGET_H_ diff --git a/pcl-1.7/pcl/modeler/icp_registration_worker.h b/pcl-1.7/pcl/modeler/icp_registration_worker.h new file mode 100644 index 0000000..6733034 --- /dev/null +++ b/pcl-1.7/pcl/modeler/icp_registration_worker.h @@ -0,0 +1,85 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_ICP_REGISTRATION_WORKER_H_ +#define PCL_MODELER_ICP_REGISTRATION_WORKER_H_ + +#include +#include + +namespace pcl +{ + namespace modeler + { + class IntParameter; + class DoubleParameter; + + class ICPRegistrationWorker : public AbstractWorker + { + public: + ICPRegistrationWorker(CloudMesh::PointCloudPtr cloud, const QList& cloud_mesh_items, QWidget* parent=0); + ~ICPRegistrationWorker(void); + + protected: + virtual std::string + getName () const {return ("Normal Estimation");} + + virtual void + initParameters(CloudMeshItem* cloud_mesh_item); + + virtual void + setupParameters(); + + virtual void + processImpl(CloudMeshItem* cloud_mesh_item); + + private: + CloudMesh::PointCloudPtr cloud_; + + double x_min_, x_max_; + double y_min_, y_max_; + double z_min_, z_max_; + + DoubleParameter* max_correspondence_distance_; + IntParameter* max_iterations_; + DoubleParameter* transformation_epsilon_; + DoubleParameter* euclidean_fitness_epsilon_; + }; + + } +} + +#endif // PCL_MODELER_ICP_REGISTRATION_WORKER_H_ diff --git a/pcl-1.7/pcl/modeler/impl/parameter.hpp b/pcl-1.7/pcl/modeler/impl/parameter.hpp new file mode 100644 index 0000000..8d84102 --- /dev/null +++ b/pcl-1.7/pcl/modeler/impl/parameter.hpp @@ -0,0 +1,120 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2010, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* +*/ +#ifndef PCL_MODELER_PARAMETER_IMPL_H_ +#define PCL_MODELER_PARAMETER_IMPL_H_ + +#include + + +namespace pcl +{ + namespace modeler + { +////////////////////////////////////////////////////////////////////////////////////////////// + template std::string + EnumParameter::valueTip() + { + std::string tip("possible values: {"); + typename std::map::const_iterator it = candidates_.begin(); + do + { + tip += it->second; + ++ it; + if (it != candidates_.end()) + tip += ", "; + } while(it != candidates_.end()); + tip += "}"; + + return (tip); + } + +////////////////////////////////////////////////////////////////////////////////////////////// + template QWidget * + EnumParameter::createEditor(QWidget *parent) + { + QComboBox* editor = new QComboBox(parent); + for (typename std::map::const_iterator it = candidates_.begin(); + it != candidates_.end(); + ++ it) + { + editor->addItem(it->second.c_str()); + } + + return (editor); + } + +////////////////////////////////////////////////////////////////////////////////////////////// + template void + EnumParameter::setEditorData(QWidget *editor) + { + QComboBox *comboBox = static_cast(editor); + + T value = T (*this); + comboBox->setCurrentIndex(value); + } + +////////////////////////////////////////////////////////////////////////////////////////////// + template void + EnumParameter::getEditorData(QWidget *editor) + { + QComboBox *comboBox = static_cast(editor); + T value = T (comboBox->currentIndex()); + current_value_ = value; + } + +////////////////////////////////////////////////////////////////////////////////////////////// + template std::pair + EnumParameter::toModelData() + { + std::pair model_data; + for (typename std::map::const_iterator it = candidates_.begin(); + it != candidates_.end(); + ++ it) + { + if (it->first == value) + { + model_data.first = it->second; + break; + } + } + model_data.second = Qt::EditRole; + + return (model_data); + } + } +} + +#endif // PCL_MODELER_PARAMETER_IMPL_H_ diff --git a/pcl-1.7/pcl/modeler/impl/scene_tree.hpp b/pcl-1.7/pcl/modeler/impl/scene_tree.hpp new file mode 100644 index 0000000..bf6d68a --- /dev/null +++ b/pcl-1.7/pcl/modeler/impl/scene_tree.hpp @@ -0,0 +1,67 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_SCENE_TREE_IMPL_H_ +#define PCL_MODELER_SCENE_TREE_IMPL_H_ + +#include + +namespace pcl +{ + namespace modeler + { + ///////////////////////////////////////////////////////////////////////////////////////////// + template QList + pcl::modeler::SceneTree::selectedTypeItems() const + { + QList selected_items = selectedItems(); + QList selected_t_items; + for (QList::iterator selected_items_it = selected_items.begin(); + selected_items_it != selected_items.end(); + ++ selected_items_it) + { + T* t_item = dynamic_cast(*selected_items_it); + if(t_item != NULL) + selected_t_items.push_back(t_item); + } + + return (selected_t_items); + } + } +} + + +#endif // PCL_MODELER_SCENE_TREE_IMPL_H_ \ No newline at end of file diff --git a/pcl-1.7/pcl/modeler/main_window.h b/pcl-1.7/pcl/modeler/main_window.h new file mode 100644 index 0000000..3486e6c --- /dev/null +++ b/pcl-1.7/pcl/modeler/main_window.h @@ -0,0 +1,149 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_MAIN_WINDOW_H_ +#define PCL_MODELER_MAIN_WINDOW_H_ + +#include +#include + +#include + + +namespace pcl +{ + namespace modeler + { + class SceneTree; + class AbstractItem; + + class MainWindow : public QMainWindow + { + Q_OBJECT + + public: + static MainWindow& getInstance() { + static MainWindow theSingleton; + return theSingleton; + } + + QString + getRecentFolder(); + + RenderWindowItem* + createRenderWindow(); + + public slots: + // slots for file menu + void + slotOpenProject(); + void + slotSaveProject(); + void + slotCloseProject(); + void + slotExit(); + void + slotUpdateRecentFile(const QString& filename); + + // slots for view menu + void + slotCreateRenderWindow(); + + void + slotOnWorkerStarted(); + + void + slotOnWorkerFinished(); + + private: + // methods for file Menu + void + connectFileMenuActions(); + void + createRecentPointCloudActions(); + void + updateRecentPointCloudActions(); + void + createRecentProjectActions(); + void + updateRecentProjectActions(); + bool + openProjectImpl(const QString& filename); + static void + updateRecentActions(std::vector >& recent_actions, QStringList& recent_items); + + // methods for view menu + void + connectViewMenuActions(); + + // methods for edit menu + void + connectEditMenuActions(); + + // methods for global settings + void + loadGlobalSettings(); + void + saveGlobalSettings(); + + private slots: + void + slotOpenRecentPointCloud(); + void + slotOpenRecentProject(); + + private: + friend class AbstractItem; + + MainWindow(); + MainWindow(const MainWindow &) : QMainWindow () {} // copy ctor hidden + MainWindow& operator=(const MainWindow &) { return (*this); } // assign op. hidden + ~MainWindow(); + + Ui::MainWindow *ui_; // Designer form + + // shortcuts for recent point clouds/projects + QStringList recent_files_; + QStringList recent_projects_; + static const size_t MAX_RECENT_NUMBER = 8; + std::vector > recent_pointcloud_actions_; + std::vector > recent_project_actions_; + }; + } +} + +#endif // PCL_MODELER_MAIN_WINDOW_H_ diff --git a/pcl-1.7/pcl/modeler/normal_estimation_worker.h b/pcl-1.7/pcl/modeler/normal_estimation_worker.h new file mode 100644 index 0000000..e594da2 --- /dev/null +++ b/pcl-1.7/pcl/modeler/normal_estimation_worker.h @@ -0,0 +1,78 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_NORMAL_ESTIMATION_WORKER_H_ +#define PCL_MODELER_NORMAL_ESTIMATION_WORKER_H_ + +#include + +namespace pcl +{ + namespace modeler + { + class DoubleParameter; + + class NormalEstimationWorker : public AbstractWorker + { + public: + NormalEstimationWorker(const QList& cloud_mesh_items, QWidget* parent = 0); + ~NormalEstimationWorker(void); + + protected: + virtual std::string + getName () const { return ("Normal Estimation"); } + + virtual void + initParameters(CloudMeshItem* cloud_mesh_item); + + virtual void + setupParameters(); + + virtual void + processImpl(CloudMeshItem* cloud_mesh_item); + + private: + double x_min_, x_max_; + double y_min_, y_max_; + double z_min_, z_max_; + + DoubleParameter* search_radius_; + }; + + } +} + +#endif // PCL_MODELER_NORMAL_ESTIMATION_WORKER_H_ diff --git a/pcl-1.7/pcl/modeler/normals_actor_item.h b/pcl-1.7/pcl/modeler/normals_actor_item.h new file mode 100644 index 0000000..da0fe1d --- /dev/null +++ b/pcl-1.7/pcl/modeler/normals_actor_item.h @@ -0,0 +1,85 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ +#ifndef PCL_MODELER_NORMALS_ACTOR_ITEM_H_ +#define PCL_MODELER_NORMALS_ACTOR_ITEM_H_ + +#include +#include + +class vtkIdTypeArray; + +namespace pcl +{ + namespace modeler + { + class NormalsActorItem : public ChannelActorItem + { + public: + NormalsActorItem(QTreeWidgetItem* parent, + const boost::shared_ptr& cloud_mesh, + const vtkSmartPointer& render_window); + ~NormalsActorItem (); + + virtual std::string + getItemName() const {return "Points Actor Item";} + + protected: + void + createNormalLines(); + + virtual void + initImpl(); + + virtual void + updateImpl(); + + virtual void + prepareContextMenu(QMenu* menu) const; + + virtual void + prepareProperties(ParameterDialog* parameter_dialog); + + virtual void + setProperties(); + + private: + double level_; + double scale_; + }; + } +} + +#endif // PCL_MODELER_NORMALS_ACTOR_ITEM_H_ \ No newline at end of file diff --git a/pcl-1.7/pcl/modeler/parameter.h b/pcl-1.7/pcl/modeler/parameter.h new file mode 100644 index 0000000..d45f1c1 --- /dev/null +++ b/pcl-1.7/pcl/modeler/parameter.h @@ -0,0 +1,277 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2010, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* +*/ +#ifndef PCL_MODELER_PARAMETER_H_ +#define PCL_MODELER_PARAMETER_H_ + +#include +#include + +#include +#include + + +namespace pcl +{ + namespace modeler + { + class Parameter + { + public: + Parameter(const std::string& name, const std::string& description, const boost::any& value): + name_(name), description_(description), default_value_(value), current_value_(value){} + ~Parameter(void) {} + + const std::string& + getName() const {return name_;} + + const std::string& + getDescription()const {return description_;} + + void + setDefaultValue(const boost::any& value) + { + default_value_ = value; + } + + void + reset() {current_value_ = default_value_;} + + virtual std::string + valueTip() = 0; + + virtual QWidget* + createEditor(QWidget *parent) = 0; + + virtual void + setEditorData(QWidget *editor) = 0; + + virtual void + setModelData(QWidget *editor, QAbstractItemModel *model, const QModelIndex &index); + + virtual std::pair + toModelData() = 0; + + protected: + virtual void + getEditorData(QWidget *editor) = 0; + + std::string name_; + std::string description_; + boost::any default_value_; + boost::any current_value_; + }; + + class BoolParameter : public Parameter + { + public: + BoolParameter(const std::string& name, const std::string& description, bool value): + Parameter(name, description, value){} + ~BoolParameter(){} + + operator bool() const {return boost::any_cast(current_value_);} + + virtual std::string + valueTip(); + + virtual QWidget* + createEditor(QWidget *parent); + + virtual void + setEditorData(QWidget *editor); + + virtual std::pair + toModelData(); + + protected: + virtual void + getEditorData(QWidget *editor); + }; + + class IntParameter : public Parameter + { + public: + IntParameter(const std::string& name, const std::string& description, int value, int low, int high, int step=1): + Parameter(name, description, value), low_(low), high_(high), step_(step){} + virtual ~IntParameter(){} + + operator int() const {return boost::any_cast(current_value_);} + + virtual std::string + valueTip(); + + virtual QWidget* + createEditor(QWidget *parent); + + virtual void + setEditorData(QWidget *editor); + + virtual std::pair + toModelData(); + + void + setLow(int low) + { + low_ = low; + } + + void + setHigh(int high) + { + high_ = high; + } + + void + setStep(int step) + { + step_ = step; + } + + protected: + virtual void + getEditorData(QWidget *editor); + + int low_; + int high_; + int step_; + }; + + template + class EnumParameter : public Parameter + { + public: + EnumParameter(const std::string& name, const std::string& description, T value, const std::map& candidates): + Parameter(name, description, value), candidates_(candidates){} + ~EnumParameter(){} + + operator T() const {return boost::any_cast(current_value_);} + + virtual std::string + valueTip(); + + virtual QWidget* + createEditor(QWidget *parent); + + virtual void + setEditorData(QWidget *editor); + + virtual std::pair + toModelData(); + + protected: + virtual void + getEditorData(QWidget *editor); + + const std::map candidates_; + }; + + class DoubleParameter : public Parameter + { + public: + DoubleParameter(const std::string& name, const std::string& description, double value, double low, double high, double step=0.01): + Parameter(name, description, value), low_(low), high_(high), step_(step){} + virtual ~DoubleParameter(){} + + operator double() const {return boost::any_cast(current_value_);} + + virtual std::string + valueTip(); + + virtual QWidget* + createEditor(QWidget *parent); + + virtual void + setEditorData(QWidget *editor); + + virtual std::pair + toModelData(); + + void + setLow(double low) + { + low_ = low; + } + + void + setHigh(double high) + { + high_ = high; + } + + void + setStep(double step) + { + step_ = step; + } + + protected: + virtual void + getEditorData(QWidget *editor); + + double low_; + double high_; + double step_; + }; + + class ColorParameter : public Parameter + { + public: + ColorParameter(const std::string& name, const std::string& description, QColor value): + Parameter(name, description, value){} + ~ColorParameter(){} + + operator QColor() const {return boost::any_cast(current_value_);} + + virtual std::string + valueTip(); + + virtual QWidget* + createEditor(QWidget *parent); + + virtual void + setEditorData(QWidget *editor); + + virtual std::pair + toModelData(); + + protected: + virtual void + getEditorData(QWidget *editor); + + }; + } +} + +#endif // PCL_MODELER_PARAMETER_H_ diff --git a/pcl-1.7/pcl/modeler/parameter_dialog.h b/pcl-1.7/pcl/modeler/parameter_dialog.h new file mode 100644 index 0000000..2a383fc --- /dev/null +++ b/pcl-1.7/pcl/modeler/parameter_dialog.h @@ -0,0 +1,115 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2010, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* +*/ +#ifndef PCL_MODELER_PARAMETER_DIALOG_H_ +#define PCL_MODELER_PARAMETER_DIALOG_H_ + +#include + +namespace pcl +{ + namespace modeler + { + class Parameter; + + class ParameterModel: public QStandardItemModel + { + public: + ParameterModel(QObject * parent = 0) : QStandardItemModel(parent){} + ParameterModel(int rows, int columns, QObject * parent = 0) : QStandardItemModel(rows, columns, parent){} + ~ParameterModel() {} + + Qt::ItemFlags + flags ( const QModelIndex & index ) const + { + return (index.column() == 0)?(Qt::ItemIsEnabled | Qt::ItemIsSelectable):QStandardItemModel::flags(index); + } + }; + + class ParameterDialog : public QDialog + { + Q_OBJECT + public: + ParameterDialog(const std::string& title, QWidget* parent=0); + ~ParameterDialog(void){} + + void + addParameter(Parameter* parameter); + + virtual int + exec(); + + protected: + std::map name_parameter_map_; + ParameterModel* parameter_model_; + + protected slots: + void + reset(); + }; + + class ParameterDelegate : public QStyledItemDelegate + { + Q_OBJECT + public: + ParameterDelegate(std::map& parameterMap, QObject *parent = 0); + + QWidget * + createEditor(QWidget *parent, const QStyleOptionViewItem &option, const QModelIndex &index) const; + + void + setEditorData(QWidget *editor, const QModelIndex &index) const; + + void + setModelData(QWidget *editor, QAbstractItemModel *model, const QModelIndex &index) const; + + void + updateEditorGeometry(QWidget *editor, const QStyleOptionViewItem &option, const QModelIndex &index) const; + + protected: + void + initStyleOption(QStyleOptionViewItem *option, const QModelIndex &index) const; + + private: + Parameter* + getCurrentParameter(const QModelIndex &index) const; + + std::map& parameter_map_; + }; + + } +} + +#endif // PCL_MODELER_PARAMETER_DIALOG_H_ diff --git a/pcl-1.7/pcl/modeler/points_actor_item.h b/pcl-1.7/pcl/modeler/points_actor_item.h new file mode 100644 index 0000000..f6ed4a2 --- /dev/null +++ b/pcl-1.7/pcl/modeler/points_actor_item.h @@ -0,0 +1,81 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ +#ifndef PCL_MODELER_POINTS_ACTOR_ITEM_H_ +#define PCL_MODELER_POINTS_ACTOR_ITEM_H_ + +#include +#include + +class vtkIdTypeArray; + +namespace pcl +{ + namespace modeler + { + class PointsActorItem : public ChannelActorItem + { + public: + PointsActorItem(QTreeWidgetItem* parent, + const boost::shared_ptr& cloud_mesh, + const vtkSmartPointer& render_window); + ~PointsActorItem (); + + virtual std::string + getItemName() const {return "Points Actor Item";} + + protected: + virtual void + initImpl(); + + virtual void + updateImpl(); + + virtual void + prepareContextMenu(QMenu* menu) const; + + virtual void + prepareProperties(ParameterDialog* parameter_dialog); + + virtual void + setProperties(); + + private: + + }; + } +} + +#endif // PCL_MODELER_POINTS_ACTOR_ITEM_H_ \ No newline at end of file diff --git a/pcl-1.7/pcl/modeler/poisson_worker.h b/pcl-1.7/pcl/modeler/poisson_worker.h new file mode 100644 index 0000000..be39909 --- /dev/null +++ b/pcl-1.7/pcl/modeler/poisson_worker.h @@ -0,0 +1,80 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_POISSON_WORKER_H_ +#define PCL_MODELER_POISSON_WORKER_H_ + +#include + +namespace pcl +{ + namespace modeler + { + class IntParameter; + class DoubleParameter; + + class PoissonReconstructionWorker : public AbstractWorker + { + public: + PoissonReconstructionWorker(const QList& cloud_mesh_items, QWidget* parent=0); + ~PoissonReconstructionWorker(void); + + protected: + virtual std::string + getName () const {return ("Poisson Reconstruction");} + + virtual void + initParameters (CloudMeshItem*) {} + + virtual void + setupParameters(); + + virtual void + processImpl(CloudMeshItem* cloud_mesh_item); + + private: + IntParameter* depth_; + IntParameter* solver_divide_; + IntParameter* iso_divide_; + IntParameter* degree_; + DoubleParameter* scale_; + DoubleParameter* samples_per_node_; + }; + + } +} + +#endif // PCL_MODELER_POISSON_WORKER_H_ diff --git a/pcl-1.7/pcl/modeler/qt.h b/pcl-1.7/pcl/modeler/qt.h new file mode 100644 index 0000000..6ba5002 --- /dev/null +++ b/pcl-1.7/pcl/modeler/qt.h @@ -0,0 +1,91 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_QT_H_ +#define PCL_MODELER_QT_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#include + +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#endif // PCL_MODELER_QT_H_ diff --git a/pcl-1.7/pcl/modeler/render_window.h b/pcl-1.7/pcl/modeler/render_window.h new file mode 100644 index 0000000..8b30581 --- /dev/null +++ b/pcl-1.7/pcl/modeler/render_window.h @@ -0,0 +1,98 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_RENDER_WINDOW_H_ +#define PCL_MODELER_RENDER_WINDOW_H_ + +#include +#include + +class vtkCubeAxesActor; + +namespace pcl +{ + namespace modeler + { + class RenderWindowItem; + + class RenderWindow : public QVTKWidget + { + public: + RenderWindow(RenderWindowItem* render_window_item, QWidget *parent = 0, Qt::WindowFlags flags = 0); + ~RenderWindow(); + + virtual QSize + sizeHint() const {return QSize(512, 512);} + + void + setActive(bool flag); + + void + setTitle(const QString& title); + + void + render(); + + void + resetCamera(); + + void + updateAxes(); + + void + getBackground(double& r, double& g, double& b); + + void + setBackground(double r, double g, double b); + + void + setShowAxes(bool flag); + + protected: + void + focusInEvent(QFocusEvent * event); + + private: + void + initRenderer(); + + vtkSmartPointer axes_; + RenderWindowItem* render_window_item_; + }; + } +} + +#endif // PCL_MODELER_RENDER_WINDOW_H_ diff --git a/pcl-1.7/pcl/modeler/render_window_item.h b/pcl-1.7/pcl/modeler/render_window_item.h new file mode 100644 index 0000000..a94374b --- /dev/null +++ b/pcl-1.7/pcl/modeler/render_window_item.h @@ -0,0 +1,98 @@ + /* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_RENDER_WINDOW_ITEM_H_ +#define PCL_MODELER_RENDER_WINDOW_ITEM_H_ + +#include +#include +#include + + +namespace pcl +{ + namespace modeler + { + class RenderWindow; + class CloudMeshItem; + class ColorParameter; + class BoolParameter; + + class RenderWindowItem : public QTreeWidgetItem, public AbstractItem + { + public: + RenderWindowItem(QTreeWidget * parent); + ~RenderWindowItem(); + + inline RenderWindow* + getRenderWindow() + { + return render_window_; + } + inline const RenderWindow* + getRenderWindow() const + { + return render_window_; + } + + bool + openPointCloud(const QString& filename); + + CloudMeshItem* + addPointCloud(CloudMesh::PointCloudPtr cloud); + + virtual std::string + getItemName() const {return "Render Window Item";} + + protected: + virtual void + prepareContextMenu(QMenu* menu) const; + + virtual void + prepareProperties(ParameterDialog* parameter_dialog); + + virtual void + setProperties(); + + private: + RenderWindow* render_window_; + ColorParameter* background_color_; + BoolParameter* show_axes_; + }; + } +} + +#endif // PCL_MODELER_RENDER_WINDOW_ITEM_H_ diff --git a/pcl-1.7/pcl/modeler/scene_tree.h b/pcl-1.7/pcl/modeler/scene_tree.h new file mode 100644 index 0000000..1f8c365 --- /dev/null +++ b/pcl-1.7/pcl/modeler/scene_tree.h @@ -0,0 +1,144 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_SCENE_TREE_H_ +#define PCL_MODELER_SCENE_TREE_H_ + +#include + +namespace pcl +{ + namespace modeler + { + class CloudMeshItem; + class RenderWindowItem; + + class SceneTree : public QTreeWidget + { + Q_OBJECT + + public: + SceneTree(QWidget * parent = 0); + ~SceneTree(); + + virtual QSize + sizeHint() const; + + bool + openPointCloud(const QString& filename); + + bool + savePointCloud(const QString& filename); + + void + selectRenderWindowItem(RenderWindowItem* render_window_item); + + void + addTopLevelItem(RenderWindowItem* render_window_item); + + public slots: + // slots for file menu + void + slotOpenPointCloud(); + + void + slotImportPointCloud(); + + void + slotSavePointCloud(); + + void + slotClosePointCloud(); + + // slots for edit menu + void + slotICPRegistration(); + void + slotVoxelGridDownsampleFilter(); + void + slotStatisticalOutlierRemovalFilter(); + void + slotEstimateNormal(); + void + slotPoissonReconstruction(); + + // slots for view menu + void + slotCloseRenderWindow(); + + signals: + void + fileOpened(const QString& filename); + + void + itemInsertedOrRemoved(); + + protected: + virtual void + dropEvent(QDropEvent * event); + + virtual bool + dropMimeData(QTreeWidgetItem * parent, int index, const QMimeData * data, Qt::DropAction action); + + private slots: + void + slotUpdateOnSelectionChange(const QItemSelection& selected, const QItemSelection& deselected); + + void + slotUpdateOnInsertOrRemove(); + + void + slotOnItemDoubleClicked(QTreeWidgetItem * item); + + private: + template QList + selectedTypeItems() const; + + QList + selectedRenderWindowItems() const; + + static void + closePointCloud(const QList& items); + + virtual void + contextMenuEvent(QContextMenuEvent *event); + }; + } +} + +#include + +#endif // PCL_MODELER_SCENE_TREE_H_ diff --git a/pcl-1.7/pcl/modeler/statistical_outlier_removal_worker.h b/pcl-1.7/pcl/modeler/statistical_outlier_removal_worker.h new file mode 100644 index 0000000..7992a89 --- /dev/null +++ b/pcl-1.7/pcl/modeler/statistical_outlier_removal_worker.h @@ -0,0 +1,77 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_STATISTICAL_OUTLIER_REMOVAL_WORKER_H_ +#define PCL_MODELER_STATISTICAL_OUTLIER_REMOVAL_WORKER_H_ + +#include + +namespace pcl +{ + namespace modeler + { + class IntParameter; + class DoubleParameter; + + class StatisticalOutlierRemovalWorker : public AbstractWorker + { + public: + StatisticalOutlierRemovalWorker(const QList& cloud_mesh_items, QWidget* parent=0); + ~StatisticalOutlierRemovalWorker(void); + + protected: + virtual std::string + getName () const {return ("Statistical Outlier Removal");} + + virtual void + initParameters(CloudMeshItem* cloud_mesh_item); + + virtual void + setupParameters(); + + virtual void + processImpl(CloudMeshItem* cloud_mesh_item); + + private: + IntParameter* mean_k_; + DoubleParameter* stddev_mul_thresh_; + + }; + + } +} + +#endif // PCL_MODELER_STATISTICAL_OUTLIER_REMOVAL_WORKER_H_ diff --git a/pcl-1.7/pcl/modeler/surface_actor_item.h b/pcl-1.7/pcl/modeler/surface_actor_item.h new file mode 100644 index 0000000..43a1a44 --- /dev/null +++ b/pcl-1.7/pcl/modeler/surface_actor_item.h @@ -0,0 +1,88 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ +#ifndef PCL_MODELER_SURFACE_ACTOR_ITEM_H_ +#define PCL_MODELER_SURFACE_ACTOR_ITEM_H_ + +#include +#include + +class vtkIdTypeArray; + +namespace pcl +{ + namespace modeler + { + class SurfaceActorItem : public ChannelActorItem + { + public: + typedef pcl::visualization::PointCloudGeometryHandler GeometryHandler; + typedef GeometryHandler::Ptr GeometryHandlerPtr; + typedef GeometryHandler::ConstPtr GeometryHandlerConstPtr; + + typedef pcl::visualization::PointCloudColorHandler ColorHandler; + typedef ColorHandler::Ptr ColorHandlerPtr; + typedef ColorHandler::ConstPtr ColorHandlerConstPtr; + + SurfaceActorItem(QTreeWidgetItem* parent, + const boost::shared_ptr& cloud_mesh, + const vtkSmartPointer& render_window); + ~SurfaceActorItem (); + + virtual std::string + getItemName() const {return "Points Actor Item";} + + protected: + virtual void + initImpl(); + + virtual void + updateImpl(); + + virtual void + prepareContextMenu(QMenu* menu) const; + + virtual void + prepareProperties(ParameterDialog* parameter_dialog); + + virtual void + setProperties(); + + private: + }; + } +} + +#endif // PCL_MODELER_SURFACE_ACTOR_ITEM_H_ \ No newline at end of file diff --git a/pcl-1.7/pcl/modeler/thread_controller.h b/pcl-1.7/pcl/modeler/thread_controller.h new file mode 100644 index 0000000..aa278ba --- /dev/null +++ b/pcl-1.7/pcl/modeler/thread_controller.h @@ -0,0 +1,72 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_THREAD_CONTROLLER_H_ +#define PCL_MODELER_THREAD_CONTROLLER_H_ + +#include + +namespace pcl +{ + namespace modeler + { + class CloudMeshItem; + class AbstractWorker; + + class ThreadController : public QObject + { + Q_OBJECT + + public: + ThreadController(); + ~ThreadController(void); + + bool + runWorker(AbstractWorker* worker); + + signals: + void + prepared(); + + private slots: + void + slotOnCloudMeshItemUpdate(CloudMeshItem* cloud_mesh_item); + }; + + } +} + +#endif // PCL_MODELER_THREAD_CONTROLLER_H_ diff --git a/pcl-1.7/pcl/modeler/voxel_grid_downsample_worker.h b/pcl-1.7/pcl/modeler/voxel_grid_downsample_worker.h new file mode 100644 index 0000000..c68133d --- /dev/null +++ b/pcl-1.7/pcl/modeler/voxel_grid_downsample_worker.h @@ -0,0 +1,81 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_MODELER_DOWNSAMPLE_WORKER_H_ +#define PCL_MODELER_DOWNSAMPLE_WORKER_H_ + +#include + +namespace pcl +{ + namespace modeler + { + class DoubleParameter; + + class VoxelGridDownampleWorker : public AbstractWorker + { + public: + VoxelGridDownampleWorker(const QList& cloud_mesh_items, QWidget* parent=0); + ~VoxelGridDownampleWorker(void); + + protected: + virtual std::string + getName () const {return ("Down Sample");} + + virtual void + initParameters(CloudMeshItem* cloud_mesh_item); + + virtual void + setupParameters(); + + virtual void + processImpl(CloudMeshItem* cloud_mesh_item); + + private: + double x_min_, x_max_; + double y_min_, y_max_; + double z_min_, z_max_; + + DoubleParameter* leaf_size_x_; + DoubleParameter* leaf_size_y_; + DoubleParameter* leaf_size_z_; + + }; + + } +} + +#endif // PCL_MODELER_DOWNSAMPLE_WORKER_H_ diff --git a/pcl-1.7/pcl/octree/boost.h b/pcl-1.7/pcl/octree/boost.h new file mode 100644 index 0000000..f1c8c18 --- /dev/null +++ b/pcl-1.7/pcl/octree/boost.h @@ -0,0 +1,50 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_OCTREE_BOOST_H_ +#define PCL_OCTREE_BOOST_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +// Marking all Boost headers as system headers to remove warnings +#include +#include +#endif // PCL_OCTREE_BOOST_H_ diff --git a/pcl-1.7/pcl/octree/impl/octree2buf_base.hpp b/pcl-1.7/pcl/octree/impl/octree2buf_base.hpp new file mode 100644 index 0000000..522ddfe --- /dev/null +++ b/pcl-1.7/pcl/octree/impl/octree2buf_base.hpp @@ -0,0 +1,846 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_2BUF_BASE_HPP +#define PCL_OCTREE_2BUF_BASE_HPP + +namespace pcl +{ + namespace octree + { + ////////////////////////////////////////////////////////////////////////////////////////////// + template + Octree2BufBase::Octree2BufBase () : + leaf_count_ (0), + branch_count_ (1), + root_node_ (new BranchNode ()), + depth_mask_ (0), + max_key_ (), + buffer_selector_ (0), + tree_dirty_flag_ (false), + octree_depth_ (0), + dynamic_depth_enabled_(false) + { + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + Octree2BufBase::~Octree2BufBase () + { + // deallocate tree structure + deleteTree (); + delete (root_node_); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + Octree2BufBase::setMaxVoxelIndex (unsigned int max_voxel_index_arg) + { + unsigned int treeDepth; + + assert (max_voxel_index_arg > 0); + + // tree depth == amount of bits of maxVoxels + treeDepth = std::max ((std::min (static_cast (OctreeKey::maxDepth), + static_cast (std::ceil (Log2 (max_voxel_index_arg))))), + static_cast (0)); + + // define depthMask_ by setting a single bit to 1 at bit position == tree depth + depth_mask_ = (1 << (treeDepth - 1)); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + Octree2BufBase::setTreeDepth (unsigned int depth_arg) + { + assert (depth_arg > 0); + + // set octree depth + octree_depth_ = depth_arg; + + // define depthMask_ by setting a single bit to 1 at bit position == tree depth + depth_mask_ = (1 << (depth_arg - 1)); + + // define max. keys + max_key_.x = max_key_.y = max_key_.z = (1 << depth_arg) - 1; + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template LeafContainerT* + Octree2BufBase::findLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg) + { + // generate key + OctreeKey key (idx_x_arg, idx_y_arg, idx_z_arg); + + // check if key exist in octree + return ( findLeaf (key)); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template LeafContainerT* + Octree2BufBase::createLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg) + { + // generate key + OctreeKey key (idx_x_arg, idx_y_arg, idx_z_arg); + + // check if key exist in octree + return ( createLeaf (key)); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template bool + Octree2BufBase::existLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg) const + { + // generate key + OctreeKey key (idx_x_arg, idx_y_arg, idx_z_arg); + + // check if key exist in octree + return existLeaf (key); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + Octree2BufBase::removeLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg) + { + // generate key + OctreeKey key (idx_x_arg, idx_y_arg, idx_z_arg); + + // free voxel at key + return (this->removeLeaf (key)); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + Octree2BufBase::deleteTree () + { + if (root_node_) + { + // reset octree + deleteBranch (*root_node_); + leaf_count_ = 0; + branch_count_ = 1; + + tree_dirty_flag_ = false; + depth_mask_ = 0; + octree_depth_ = 0; + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + Octree2BufBase::switchBuffers () + { + if (tree_dirty_flag_) + { + // make sure that all unused branch nodes from previous buffer are deleted + treeCleanUpRecursive (root_node_); + } + + // switch butter selector + buffer_selector_ = !buffer_selector_; + + // reset flags + tree_dirty_flag_ = true; + leaf_count_ = 0; + branch_count_ = 1; + + unsigned char child_idx; + // we can safely remove children references of root node + for (child_idx = 0; child_idx < 8; child_idx++) + { + root_node_->setChildPtr(buffer_selector_, child_idx, 0); + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + Octree2BufBase::serializeTree (std::vector& binary_tree_out_arg, + bool do_XOR_encoding_arg) + { + OctreeKey new_key; + + // clear binary vector + binary_tree_out_arg.clear (); + binary_tree_out_arg.reserve (this->branch_count_); + + serializeTreeRecursive (root_node_, new_key, &binary_tree_out_arg, 0, do_XOR_encoding_arg, false); + + // serializeTreeRecursive cleans-up unused octree nodes in previous octree + tree_dirty_flag_ = false; + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + Octree2BufBase::serializeTree (std::vector& binary_tree_out_arg, + std::vector& leaf_container_vector_arg, + bool do_XOR_encoding_arg) + { + OctreeKey new_key; + + // clear output vectors + binary_tree_out_arg.clear (); + leaf_container_vector_arg.clear (); + + leaf_container_vector_arg.reserve (leaf_count_); + binary_tree_out_arg.reserve (this->branch_count_); + + serializeTreeRecursive (root_node_, new_key, &binary_tree_out_arg, &leaf_container_vector_arg, do_XOR_encoding_arg, false); + + // serializeTreeRecursive cleans-up unused octree nodes in previous octree + tree_dirty_flag_ = false; + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + Octree2BufBase::serializeLeafs (std::vector& leaf_container_vector_arg) + { + OctreeKey new_key; + + // clear output vector + leaf_container_vector_arg.clear (); + + leaf_container_vector_arg.reserve (leaf_count_); + + serializeTreeRecursive (root_node_, new_key, 0, &leaf_container_vector_arg, false, false); + + // serializeLeafsRecursive cleans-up unused octree nodes in previous octree + tree_dirty_flag_ = false; + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + Octree2BufBase::deserializeTree (std::vector& binary_tree_in_arg, + bool do_XOR_decoding_arg) + { + OctreeKey new_key; + + // we will rebuild an octree -> reset leafCount + leaf_count_ = 0; + + // iterator for binary tree structure vector + std::vector::const_iterator binary_tree_in_it = binary_tree_in_arg.begin (); + std::vector::const_iterator binary_tree_in_it_end = binary_tree_in_arg.end (); + + deserializeTreeRecursive (root_node_, depth_mask_, new_key, + binary_tree_in_it, binary_tree_in_it_end, 0, 0, false, + do_XOR_decoding_arg); + + // we modified the octree structure -> clean-up/tree-reset might be required + tree_dirty_flag_ = false; + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + Octree2BufBase::deserializeTree (std::vector& binary_tree_in_arg, + std::vector& leaf_container_vector_arg, + bool do_XOR_decoding_arg) + { + OctreeKey new_key; + + // set data iterator to first element + typename std::vector::const_iterator leaf_container_vector_it = leaf_container_vector_arg.begin (); + + // set data iterator to last element + typename std::vector::const_iterator leaf_container_vector_it_end = leaf_container_vector_arg.end (); + + // we will rebuild an octree -> reset leafCount + leaf_count_ = 0; + + // iterator for binary tree structure vector + std::vector::const_iterator binary_tree_in_it = binary_tree_in_arg.begin (); + std::vector::const_iterator binary_tree_in_it_end = binary_tree_in_arg.end (); + + deserializeTreeRecursive (root_node_, + depth_mask_, + new_key, + binary_tree_in_it, + binary_tree_in_it_end, + &leaf_container_vector_it, + &leaf_container_vector_it_end, + false, + do_XOR_decoding_arg); + + + // we modified the octree structure -> clean-up/tree-reset might be required + tree_dirty_flag_ = false; + } + + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + Octree2BufBase::serializeNewLeafs (std::vector& leaf_container_vector_arg) + { + OctreeKey new_key; + + // clear output vector + leaf_container_vector_arg.clear (); + leaf_container_vector_arg.reserve (leaf_count_); + + serializeTreeRecursive (root_node_, new_key, 0, &leaf_container_vector_arg, false, true); + + // serializeLeafsRecursive cleans-up unused octree nodes in previous octree buffer + tree_dirty_flag_ = false; + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + unsigned int + Octree2BufBase::createLeafRecursive (const OctreeKey& key_arg, + unsigned int depth_mask_arg, + BranchNode* branch_arg, + LeafNode*& return_leaf_arg, + BranchNode*& parent_of_leaf_arg, + bool branch_reset_arg) + { + // index to branch child + unsigned char child_idx; + + // branch reset -> this branch has been taken from previous buffer + if (branch_reset_arg) + { + // we can safely remove children references + for (child_idx = 0; child_idx < 8; child_idx++) + { + branch_arg->setChildPtr(buffer_selector_, child_idx, 0); + } + } + + // find branch child from key + child_idx = key_arg.getChildIdxWithDepthMask (depth_mask_arg); + + if (depth_mask_arg > 1) + { + // we have not reached maximum tree depth + BranchNode* child_branch; + bool doNodeReset; + + doNodeReset = false; + + // if required branch does not exist + if (!branch_arg->hasChild(buffer_selector_, child_idx)) + { + // check if we find a branch node reference in previous buffer + + if (branch_arg->hasChild(!buffer_selector_, child_idx)) + { + OctreeNode* child_node = branch_arg->getChildPtr(!buffer_selector_,child_idx); + + if (child_node->getNodeType()==BRANCH_NODE) { + child_branch = static_cast (child_node); + branch_arg->setChildPtr(buffer_selector_, child_idx, child_node); + } else { + // depth has changed.. child in preceeding buffer is a leaf node. + deleteBranchChild (*branch_arg, !buffer_selector_, child_idx); + child_branch = createBranchChild (*branch_arg, child_idx); + } + + // take child branch from previous buffer + doNodeReset = true; // reset the branch pointer array of stolen child node + + } + else + { + // if required branch does not exist -> create it + child_branch = createBranchChild (*branch_arg, child_idx); + } + + branch_count_++; + } + // required branch node already exists - use it + else + child_branch = static_cast (branch_arg->getChildPtr(buffer_selector_,child_idx)); + + // recursively proceed with indexed child branch + return createLeafRecursive (key_arg, depth_mask_arg / 2, child_branch, return_leaf_arg, parent_of_leaf_arg, doNodeReset); + } + else + { + // branch childs are leaf nodes + LeafNode* child_leaf; + if (!branch_arg->hasChild(buffer_selector_, child_idx)) + { + // leaf node at child_idx does not exist + + // check if we can take copy a reference from previous buffer + if (branch_arg->hasChild(!buffer_selector_, child_idx)) + { + + OctreeNode * child_node = branch_arg->getChildPtr(!buffer_selector_,child_idx); + if (child_node->getNodeType () == LEAF_NODE) + { + child_leaf = static_cast (child_node); + branch_arg->setChildPtr(buffer_selector_, child_idx, child_node); + } else { + // depth has changed.. child in preceeding buffer is a leaf node. + deleteBranchChild (*branch_arg, !buffer_selector_, child_idx); + child_leaf = createLeafChild (*branch_arg, child_idx); + } + leaf_count_++; + } + else + { + // if required leaf does not exist -> create it + child_leaf = createLeafChild (*branch_arg, child_idx); + leaf_count_++; + } + + // return leaf node + return_leaf_arg = child_leaf; + parent_of_leaf_arg = branch_arg; + } + else + { + // leaf node already exist + return_leaf_arg = static_cast (branch_arg->getChildPtr(buffer_selector_,child_idx));; + parent_of_leaf_arg = branch_arg; + } + } + + return depth_mask_arg; + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + Octree2BufBase::findLeafRecursive (const OctreeKey& key_arg, + unsigned int depth_mask_arg, + BranchNode* branch_arg, + LeafContainerT*& result_arg) const + { + // return leaf node + unsigned char child_idx; + + // find branch child from key + child_idx = key_arg.getChildIdxWithDepthMask (depth_mask_arg); + + if (depth_mask_arg > 1) + { + // we have not reached maximum tree depth + BranchNode* child_branch; + child_branch = static_cast (branch_arg->getChildPtr(buffer_selector_,child_idx)); + + if (child_branch) + // recursively proceed with indexed child branch + findLeafRecursive (key_arg, depth_mask_arg / 2, child_branch, result_arg); + } + else + { + // we reached leaf node level + if (branch_arg->hasChild(buffer_selector_, child_idx)) + { + // return existing leaf node + LeafNode* leaf_node = static_cast (branch_arg->getChildPtr(buffer_selector_,child_idx)); + result_arg = leaf_node->getContainerPtr();; + } + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template bool + Octree2BufBase::deleteLeafRecursive (const OctreeKey& key_arg, + unsigned int depth_mask_arg, + BranchNode* branch_arg) + { + // index to branch child + unsigned char child_idx; + // indicates if branch is empty and can be safely removed + bool bNoChilds; + + // find branch child from key + child_idx = key_arg.getChildIdxWithDepthMask (depth_mask_arg); + + if (depth_mask_arg > 1) + { + // we have not reached maximum tree depth + BranchNode* child_branch; + bool bBranchOccupied; + + // next branch child on our path through the tree + child_branch = static_cast (branch_arg->getChildPtr(buffer_selector_,child_idx)); + + if (child_branch) + { + // recursively explore the indexed child branch + bBranchOccupied = deleteLeafRecursive (key_arg, depth_mask_arg / 2, child_branch); + + if (!bBranchOccupied) + { + // child branch does not own any sub-child nodes anymore -> delete child branch + deleteBranchChild (*branch_arg, buffer_selector_, child_idx); + branch_count_--; + } + } + } + else + { + // our child is a leaf node -> delete it + deleteBranchChild (*branch_arg, buffer_selector_, child_idx); + leaf_count_--; + } + + // check if current branch still owns childs + bNoChilds = false; + for (child_idx = 0; child_idx < 8; child_idx++) + { + bNoChilds = branch_arg->hasChild(buffer_selector_, child_idx); + if (bNoChilds) + break; + } + + // return true if current branch can be deleted + return (bNoChilds); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void Octree2BufBase< + LeafContainerT, BranchContainerT>::serializeTreeRecursive (BranchNode* branch_arg, + OctreeKey& key_arg, + std::vector* binary_tree_out_arg, + typename std::vector* leaf_container_vector_arg, + bool do_XOR_encoding_arg, + bool new_leafs_filter_arg) + { + // child iterator + unsigned char child_idx; + + // bit pattern + char branch_bit_pattern_curr_buffer; + char branch_bit_pattern_prev_buffer; + char node_XOR_bit_pattern; + + // occupancy bit patterns of branch node (current and previous octree buffer) + branch_bit_pattern_curr_buffer = getBranchBitPattern (*branch_arg, buffer_selector_); + branch_bit_pattern_prev_buffer = getBranchBitPattern (*branch_arg, !buffer_selector_); + + // XOR of current and previous occupancy bit patterns + node_XOR_bit_pattern = branch_bit_pattern_curr_buffer ^ branch_bit_pattern_prev_buffer; + + if (binary_tree_out_arg) + { + if (do_XOR_encoding_arg) + { + // write XOR bit pattern to output vector + binary_tree_out_arg->push_back (node_XOR_bit_pattern); + } + else + { + // write bit pattern of current buffer to output vector + binary_tree_out_arg->push_back (branch_bit_pattern_curr_buffer); + } + } + + // iterate over all children + for (child_idx = 0; child_idx < 8; child_idx++) + { + if (branch_arg->hasChild(buffer_selector_, child_idx)) + { + // add current branch voxel to key + key_arg.pushBranch(child_idx); + + OctreeNode *child_node = branch_arg->getChildPtr(buffer_selector_,child_idx); + + switch (child_node->getNodeType ()) + { + case BRANCH_NODE: + { + // recursively proceed with indexed child branch + serializeTreeRecursive (static_cast (child_node), key_arg, binary_tree_out_arg, + leaf_container_vector_arg, do_XOR_encoding_arg, new_leafs_filter_arg); + break; + } + case LEAF_NODE: + { + LeafNode* child_leaf = static_cast (child_node); + + if (new_leafs_filter_arg) + { + if (!branch_arg->hasChild (!buffer_selector_, child_idx)) + { + if (leaf_container_vector_arg) + leaf_container_vector_arg->push_back(child_leaf->getContainerPtr()); + + serializeTreeCallback (**child_leaf, key_arg); + } + } else + { + + if (leaf_container_vector_arg) + leaf_container_vector_arg->push_back(child_leaf->getContainerPtr()); + + serializeTreeCallback (**child_leaf, key_arg); + } + + break; + } + default: + break; + } + + // pop current branch voxel from key + key_arg.popBranch(); + } + else if (branch_arg->hasChild (!buffer_selector_, child_idx)) + { + // delete branch, free memory + deleteBranchChild (*branch_arg, !buffer_selector_, child_idx); + + } + + } + } + + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + Octree2BufBase::deserializeTreeRecursive (BranchNode* branch_arg, + unsigned int depth_mask_arg, OctreeKey& key_arg, + typename std::vector::const_iterator& binaryTreeIT_arg, + typename std::vector::const_iterator& binaryTreeIT_End_arg, + typename std::vector::const_iterator* dataVectorIterator_arg, + typename std::vector::const_iterator* dataVectorEndIterator_arg, + bool branch_reset_arg, bool do_XOR_decoding_arg) + { + // child iterator + unsigned char child_idx; + + // node bits + char nodeBits; + char recoveredNodeBits; + + // branch reset -> this branch has been taken from previous buffer + if (branch_reset_arg) + { + // we can safely remove children references + for (child_idx = 0; child_idx < 8; child_idx++) + { + branch_arg->setChildPtr(buffer_selector_, child_idx, 0); + } + } + + if (binaryTreeIT_arg!=binaryTreeIT_End_arg) { + // read branch occupancy bit pattern from vector + nodeBits = *binaryTreeIT_arg++; + + + // recover branch occupancy bit pattern + if (do_XOR_decoding_arg) + { + recoveredNodeBits = getBranchBitPattern (*branch_arg, !buffer_selector_) ^ nodeBits; + } + else + { + recoveredNodeBits = nodeBits; + } + + // iterate over all children + for (child_idx = 0; child_idx < 8; child_idx++) + { + // if occupancy bit for child_idx is set.. + if (recoveredNodeBits & (1 << child_idx)) + { + // add current branch voxel to key + key_arg.pushBranch(child_idx); + + bool doNodeReset; + + doNodeReset = false; + + if (depth_mask_arg > 1) + { + // we have not reached maximum tree depth + + BranchNode* child_branch; + + // check if we find a branch node reference in previous buffer + if (!branch_arg->hasChild(buffer_selector_, child_idx)) + { + + if (branch_arg->hasChild(!buffer_selector_, child_idx)) + { + OctreeNode* child_node = branch_arg->getChildPtr(!buffer_selector_,child_idx); + + if (child_node->getNodeType()==BRANCH_NODE) { + child_branch = static_cast (child_node); + branch_arg->setChildPtr(buffer_selector_, child_idx, child_node); + } else { + // depth has changed.. child in preceeding buffer is a leaf node. + deleteBranchChild (*branch_arg, !buffer_selector_, child_idx); + child_branch = createBranchChild (*branch_arg, child_idx); + } + + // take child branch from previous buffer + doNodeReset = true; // reset the branch pointer array of stolen child node + } + else + { + // if required branch does not exist -> create it + child_branch = createBranchChild (*branch_arg, child_idx); + } + + branch_count_++; + + } + else + { + // required branch node already exists - use it + child_branch = static_cast (branch_arg->getChildPtr(buffer_selector_,child_idx)); + } + + // recursively proceed with indexed child branch + deserializeTreeRecursive (child_branch, depth_mask_arg / 2, key_arg, + binaryTreeIT_arg, binaryTreeIT_End_arg, + dataVectorIterator_arg, dataVectorEndIterator_arg, + doNodeReset, do_XOR_decoding_arg); + + } + else + { + // branch childs are leaf nodes + LeafNode* child_leaf; + + // check if we can take copy a reference pointer from previous buffer + if (branch_arg->hasChild(!buffer_selector_, child_idx)) + { + // take child leaf node from previous buffer + OctreeNode* child_node = branch_arg->getChildPtr(!buffer_selector_,child_idx); + if (child_node->getNodeType()==LEAF_NODE) { + child_leaf = static_cast (child_node); + branch_arg->setChildPtr(buffer_selector_, child_idx, child_node); + } else { + // depth has changed.. child in preceeding buffer is a leaf node. + deleteBranchChild (*branch_arg, !buffer_selector_, child_idx); + child_leaf = createLeafChild (*branch_arg, child_idx); + } + } + else + { + // if required leaf does not exist -> create it + child_leaf = createLeafChild (*branch_arg, child_idx); + } + + // we reached leaf node level + + if (dataVectorIterator_arg + && (*dataVectorIterator_arg != *dataVectorEndIterator_arg)) + { + LeafContainerT& container = **child_leaf; + container = ***dataVectorIterator_arg; + ++*dataVectorIterator_arg; + } + + leaf_count_++; + + // execute deserialization callback + deserializeTreeCallback (**child_leaf, key_arg); + + } + + // pop current branch voxel from key + key_arg.popBranch(); + } + else if (branch_arg->hasChild (!buffer_selector_, child_idx)) + { + // remove old branch pointer information in current branch + branch_arg->setChildPtr(buffer_selector_, child_idx, 0); + + // remove unused branches in previous buffer + deleteBranchChild (*branch_arg, !buffer_selector_, child_idx); + } + } + } + + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template void + Octree2BufBase::treeCleanUpRecursive (BranchNode* branch_arg) + { + // child iterator + unsigned char child_idx; + + // bit pattern + char occupied_children_bit_pattern_prev_buffer; + char node_XOR_bit_pattern; + char unused_branches_bit_pattern; + + // occupancy bit pattern of branch node (previous octree buffer) + occupied_children_bit_pattern_prev_buffer = getBranchBitPattern (*branch_arg, !buffer_selector_); + + // XOR of current and previous occupancy bit patterns + node_XOR_bit_pattern = getBranchXORBitPattern (*branch_arg); + + // bit pattern indicating unused octree nodes in previous branch + unused_branches_bit_pattern = node_XOR_bit_pattern & occupied_children_bit_pattern_prev_buffer; + + // iterate over all children + for (child_idx = 0; child_idx < 8; child_idx++) + { + if (branch_arg->hasChild(buffer_selector_, child_idx)) + { + OctreeNode *child_node = branch_arg->getChildPtr(buffer_selector_,child_idx); + + switch (child_node->getNodeType ()) + { + case BRANCH_NODE: + { + // recursively proceed with indexed child branch + treeCleanUpRecursive (static_cast (child_node)); + break; + } + case LEAF_NODE: + // leaf level - nothing to do.. + break; + default: + break; + } + } + + // check for unused branches in previous buffer + if (unused_branches_bit_pattern & (1 << child_idx)) + { + // delete branch, free memory + deleteBranchChild (*branch_arg, !buffer_selector_, child_idx); + } + } + } + } +} + +#define PCL_INSTANTIATE_Octree2BufBase(T) template class PCL_EXPORTS pcl::octree::Octree2BufBase; + +#endif + diff --git a/pcl-1.7/pcl/octree/impl/octree_base.hpp b/pcl-1.7/pcl/octree/impl/octree_base.hpp new file mode 100644 index 0000000..c49de27 --- /dev/null +++ b/pcl-1.7/pcl/octree/impl/octree_base.hpp @@ -0,0 +1,574 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_BASE_HPP +#define PCL_OCTREE_BASE_HPP + +#include + +#include +#include +#include + +namespace pcl +{ + namespace octree + { + ////////////////////////////////////////////////////////////////////////////////////////////// + template + OctreeBase::OctreeBase () : + leaf_count_ (0), + branch_count_ (1), + root_node_ (new BranchNode ()), + depth_mask_ (0), + octree_depth_ (0), + dynamic_depth_enabled_ (false), + max_key_ () + { + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + OctreeBase::~OctreeBase () + { + // deallocate tree structure + deleteTree (); + delete (root_node_); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void + OctreeBase::setMaxVoxelIndex (unsigned int max_voxel_index_arg) + { + unsigned int tree_depth; + + assert(max_voxel_index_arg>0); + + // tree depth == bitlength of maxVoxels + tree_depth = std::max ( (std::min (static_cast (OctreeKey::maxDepth), static_cast (std::ceil (Log2 (max_voxel_index_arg))))), 0u); + + // define depthMask_ by setting a single bit to 1 at bit position == tree depth + depth_mask_ = (1 << (tree_depth - 1)); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void + OctreeBase::setTreeDepth (unsigned int depth_arg) + { + assert(depth_arg>0); + + // set octree depth + octree_depth_ = depth_arg; + + // define depthMask_ by setting a single bit to 1 at bit position == tree depth + depth_mask_ = (1 << (depth_arg - 1)); + + // define max. keys + max_key_.x = max_key_.y = max_key_.z = (1 << depth_arg) - 1; + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + LeafContainerT* + OctreeBase::findLeaf (unsigned int idx_x_arg, + unsigned int idx_y_arg, + unsigned int idx_z_arg) + { + // generate key + OctreeKey key (idx_x_arg, idx_y_arg, idx_z_arg); + + // check if key exist in octree + return (findLeaf (key)); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + LeafContainerT* + OctreeBase::createLeaf (unsigned int idx_x_arg, + unsigned int idx_y_arg, + unsigned int idx_z_arg) + { + // generate key + OctreeKey key (idx_x_arg, idx_y_arg, idx_z_arg); + + // check if key exist in octree + return (createLeaf (key)); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + bool + OctreeBase::existLeaf (unsigned int idx_x_arg, + unsigned int idx_y_arg, + unsigned int idx_z_arg) const + { + // generate key + OctreeKey key (idx_x_arg, idx_y_arg, idx_z_arg); + + // check if key exist in octree + return (existLeaf (key)); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void + OctreeBase::removeLeaf (unsigned int idx_x_arg, + unsigned int idx_y_arg, + unsigned int idx_z_arg) + { + // generate key + OctreeKey key (idx_x_arg, idx_y_arg, idx_z_arg); + + // check if key exist in octree + deleteLeafRecursive (key, depth_mask_, root_node_); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void + OctreeBase::deleteTree () + { + + if (root_node_) + { + // reset octree + deleteBranch (*root_node_); + leaf_count_ = 0; + branch_count_ = 1; + } + + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void + OctreeBase::serializeTree (std::vector& binary_tree_out_arg) + { + + OctreeKey new_key; + + // clear binary vector + binary_tree_out_arg.clear (); + binary_tree_out_arg.reserve (this->branch_count_); + + serializeTreeRecursive (root_node_, new_key, &binary_tree_out_arg, 0); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void + OctreeBase::serializeTree (std::vector& binary_tree_out_arg, + std::vector& leaf_container_vector_arg) + { + + OctreeKey new_key; + + // clear output vectors + binary_tree_out_arg.clear (); + leaf_container_vector_arg.clear (); + + binary_tree_out_arg.reserve (this->branch_count_); + leaf_container_vector_arg.reserve (this->leaf_count_); + + serializeTreeRecursive (root_node_, new_key, &binary_tree_out_arg, &leaf_container_vector_arg); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void + OctreeBase::serializeLeafs (std::vector& leaf_container_vector_arg) + { + OctreeKey new_key; + + // clear output vector + leaf_container_vector_arg.clear (); + + leaf_container_vector_arg.reserve (this->leaf_count_); + + serializeTreeRecursive (root_node_, new_key, 0, &leaf_container_vector_arg); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void + OctreeBase::deserializeTree (std::vector& binary_tree_out_arg) + { + OctreeKey new_key; + + // free existing tree before tree rebuild + deleteTree (); + + //iterator for binary tree structure vector + std::vector::const_iterator binary_tree_out_it = binary_tree_out_arg.begin (); + std::vector::const_iterator binary_tree_out_it_end = binary_tree_out_arg.end (); + + deserializeTreeRecursive (root_node_, + depth_mask_, + new_key, + binary_tree_out_it, + binary_tree_out_it_end, + 0, + 0); + + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void + OctreeBase::deserializeTree (std::vector& binary_tree_in_arg, + std::vector& leaf_container_vector_arg) + { + OctreeKey new_key; + + // set data iterator to first element + typename std::vector::const_iterator leaf_vector_it = leaf_container_vector_arg.begin (); + + // set data iterator to last element + typename std::vector::const_iterator leaf_vector_it_end = leaf_container_vector_arg.end (); + + // free existing tree before tree rebuild + deleteTree (); + + //iterator for binary tree structure vector + std::vector::const_iterator binary_tree_input_it = binary_tree_in_arg.begin (); + std::vector::const_iterator binary_tree_input_it_end = binary_tree_in_arg.end (); + + deserializeTreeRecursive (root_node_, + depth_mask_, + new_key, + binary_tree_input_it, + binary_tree_input_it_end, + &leaf_vector_it, + &leaf_vector_it_end); + + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + unsigned int + OctreeBase::createLeafRecursive (const OctreeKey& key_arg, + unsigned int depth_mask_arg, + BranchNode* branch_arg, + LeafNode*& return_leaf_arg, + BranchNode*& parent_of_leaf_arg) + { + // index to branch child + unsigned char child_idx; + + // find branch child from key + child_idx = key_arg.getChildIdxWithDepthMask (depth_mask_arg); + + OctreeNode* child_node = (*branch_arg)[child_idx]; + + if (!child_node) + { + if ((!dynamic_depth_enabled_) && (depth_mask_arg > 1)) + { + // if required branch does not exist -> create it + BranchNode* childBranch = createBranchChild (*branch_arg, child_idx); + + branch_count_++; + + // recursively proceed with indexed child branch + return createLeafRecursive (key_arg, depth_mask_arg / 2, childBranch, return_leaf_arg, parent_of_leaf_arg); + + } + else + { + // if leaf node at child_idx does not exist + LeafNode* leaf_node = createLeafChild (*branch_arg, child_idx); + return_leaf_arg = leaf_node; + parent_of_leaf_arg = branch_arg; + this->leaf_count_++; + } + } + else + { + // Node exists already + switch (child_node->getNodeType ()) + { + case BRANCH_NODE: + // recursively proceed with indexed child branch + return createLeafRecursive (key_arg, depth_mask_arg / 2, static_cast (child_node), + return_leaf_arg, parent_of_leaf_arg); + break; + + case LEAF_NODE: + return_leaf_arg = static_cast (child_node);; + parent_of_leaf_arg = branch_arg; + break; + } + + } + + return (depth_mask_arg >> 1); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void + OctreeBase::findLeafRecursive (const OctreeKey& key_arg, + unsigned int depth_mask_arg, + BranchNode* branch_arg, + LeafContainerT*& result_arg) const + { + // index to branch child + unsigned char child_idx; + + // find branch child from key + child_idx = key_arg.getChildIdxWithDepthMask (depth_mask_arg); + + OctreeNode* child_node = (*branch_arg)[child_idx]; + + if (child_node) + { + switch (child_node->getNodeType ()) + { + case BRANCH_NODE: + // we have not reached maximum tree depth + BranchNode* child_branch; + child_branch = static_cast (child_node); + + findLeafRecursive (key_arg, depth_mask_arg / 2, child_branch, result_arg); + break; + + case LEAF_NODE: + // return existing leaf node + LeafNode* child_leaf; + child_leaf = static_cast (child_node); + + result_arg = child_leaf->getContainerPtr (); + break; + } + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + bool + OctreeBase::deleteLeafRecursive (const OctreeKey& key_arg, + unsigned int depth_mask_arg, + BranchNode* branch_arg) + { + // index to branch child + unsigned char child_idx; + // indicates if branch is empty and can be safely removed + bool b_no_children; + + // find branch child from key + child_idx = key_arg.getChildIdxWithDepthMask (depth_mask_arg); + + OctreeNode* child_node = (*branch_arg)[child_idx]; + + if (child_node) + { + switch (child_node->getNodeType ()) + { + + case BRANCH_NODE: + BranchNode* child_branch; + child_branch = static_cast (child_node); + + // recursively explore the indexed child branch + b_no_children = deleteLeafRecursive (key_arg, depth_mask_arg / 2, child_branch); + + if (!b_no_children) + { + // child branch does not own any sub-child nodes anymore -> delete child branch + deleteBranchChild (*branch_arg, child_idx); + branch_count_--; + } + break; + + case LEAF_NODE: + // return existing leaf node + + // our child is a leaf node -> delete it + deleteBranchChild (*branch_arg, child_idx); + this->leaf_count_--; + break; + } + } + + // check if current branch still owns children + b_no_children = false; + for (child_idx = 0; (!b_no_children) && (child_idx < 8); child_idx++) + { + b_no_children = branch_arg->hasChild (child_idx); + } + // return true if current branch can be deleted + return (b_no_children); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void + OctreeBase::serializeTreeRecursive (const BranchNode* branch_arg, + OctreeKey& key_arg, + std::vector* binary_tree_out_arg, + typename std::vector* leaf_container_vector_arg) const + { + + // child iterator + unsigned char child_idx; + char node_bit_pattern; + + // branch occupancy bit pattern + node_bit_pattern = getBranchBitPattern (*branch_arg); + + // write bit pattern to output vector + if (binary_tree_out_arg) + binary_tree_out_arg->push_back (node_bit_pattern); + + // iterate over all children + for (child_idx = 0; child_idx < 8; child_idx++) + { + + // if child exist + if (branch_arg->hasChild (child_idx)) + { + // add current branch voxel to key + key_arg.pushBranch (child_idx); + + OctreeNode *childNode = branch_arg->getChildPtr (child_idx); + + switch (childNode->getNodeType ()) + { + case BRANCH_NODE: + { + // recursively proceed with indexed child branch + serializeTreeRecursive (static_cast (childNode), key_arg, binary_tree_out_arg, + leaf_container_vector_arg); + break; + } + case LEAF_NODE: + { + LeafNode* child_leaf = static_cast (childNode); + + if (leaf_container_vector_arg) + leaf_container_vector_arg->push_back (child_leaf->getContainerPtr ()); + + // we reached a leaf node -> execute serialization callback + serializeTreeCallback (**child_leaf, key_arg); + break; + } + default: + break; + } + + // pop current branch voxel from key + key_arg.popBranch (); + } + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void + OctreeBase::deserializeTreeRecursive (BranchNode* branch_arg, unsigned int depth_mask_arg, OctreeKey& key_arg, + typename std::vector::const_iterator& binary_tree_input_it_arg, + typename std::vector::const_iterator& binary_tree_input_it_end_arg, + typename std::vector::const_iterator* leaf_container_vector_it_arg, + typename std::vector::const_iterator* leaf_container_vector_it_end_arg) + { + // child iterator + unsigned char child_idx; + char node_bits; + + if (binary_tree_input_it_arg != binary_tree_input_it_end_arg) + { + // read branch occupancy bit pattern from input vector + node_bits = (*binary_tree_input_it_arg); + binary_tree_input_it_arg++; + + // iterate over all children + for (child_idx = 0; child_idx < 8; child_idx++) + { + // if occupancy bit for child_idx is set.. + if (node_bits & (1 << child_idx)) + { + // add current branch voxel to key + key_arg.pushBranch (child_idx); + + if (depth_mask_arg > 1) + { + // we have not reached maximum tree depth + BranchNode * newBranch = createBranchChild (*branch_arg, child_idx); + + branch_count_++; + + // recursively proceed with new child branch + deserializeTreeRecursive (newBranch, depth_mask_arg / 2, key_arg, + binary_tree_input_it_arg, binary_tree_input_it_end_arg, + leaf_container_vector_it_arg, leaf_container_vector_it_end_arg); + } + else + { + // we reached leaf node level + + LeafNode* child_leaf = createLeafChild (*branch_arg, child_idx); + + if (leaf_container_vector_it_arg && (*leaf_container_vector_it_arg != *leaf_container_vector_it_end_arg)) + { + LeafContainerT& container = **child_leaf; + container = ***leaf_container_vector_it_arg; + ++*leaf_container_vector_it_arg; + } + + leaf_count_++; + + // execute deserialization callback + deserializeTreeCallback (**child_leaf, key_arg); + } + + // pop current branch voxel from key + key_arg.popBranch (); + } + } + } + } + + } +} + +#define PCL_INSTANTIATE_OctreeBase(T) template class PCL_EXPORTS pcl::octree::OctreeBase; + +#endif + diff --git a/pcl-1.7/pcl/octree/impl/octree_iterator.hpp b/pcl-1.7/pcl/octree/impl/octree_iterator.hpp new file mode 100644 index 0000000..5d95a02 --- /dev/null +++ b/pcl-1.7/pcl/octree/impl/octree_iterator.hpp @@ -0,0 +1,292 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_ITERATOR_HPP_ +#define PCL_OCTREE_ITERATOR_HPP_ + +#include +#include + +#include + +namespace pcl +{ + namespace octree + { + ////////////////////////////////////////////////////////////////////////////////////////////// + template + OctreeDepthFirstIterator::OctreeDepthFirstIterator (unsigned int max_depth_arg) : + OctreeIteratorBase (max_depth_arg), stack_ () + { + // initialize iterator + this->reset (); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + OctreeDepthFirstIterator::OctreeDepthFirstIterator (OctreeT* octree_arg, unsigned int max_depth_arg) : + OctreeIteratorBase (octree_arg, max_depth_arg), stack_ () + { + // initialize iterator + this->reset (); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + OctreeDepthFirstIterator::~OctreeDepthFirstIterator () + { + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void OctreeDepthFirstIterator::reset () + { + OctreeIteratorBase::reset (); + + if (this->octree_) + { + // allocate stack + stack_.reserve (this->max_octree_depth_); + + // empty stack + stack_.clear (); + + // pushing root node to stack + IteratorState stack_entry; + stack_entry.node_ = this->octree_->getRootNode (); + stack_entry.depth_ = 0; + stack_entry.key_.x = stack_entry.key_.y = stack_entry.key_.z = 0; + + stack_.push_back(stack_entry); + + this->current_state_ = &stack_.back(); + } + + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void OctreeDepthFirstIterator::skipChildVoxels () + { + + if (stack_.size ()) + { + // current depth + unsigned char current_depth = stack_.back ().depth_; + + // pop from stack as long as we find stack elements with depth >= current depth + while (stack_.size () && (stack_.back ().depth_ >= current_depth)) + stack_.pop_back (); + + if (stack_.size ()) + { + this->current_state_ = &stack_.back(); + } else + { + this->current_state_ = 0; + } + } + + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + OctreeDepthFirstIterator& + OctreeDepthFirstIterator::operator++ () + { + + if (stack_.size ()) + { + // get stack element + IteratorState stack_entry = stack_.back (); + stack_.pop_back (); + + stack_entry.depth_ ++; + OctreeKey& current_key = stack_entry.key_; + + if ( (this->max_octree_depth_>=stack_entry.depth_) && + (stack_entry.node_->getNodeType () == BRANCH_NODE) ) + { + unsigned char child_idx; + + // current node is a branch node + BranchNode* current_branch = + static_cast (stack_entry.node_); + + // add all children to stack + for (child_idx = 0; child_idx < 8; ++child_idx) + { + + // if child exist + + if (this->octree_->branchHasChild(*current_branch, child_idx)) + { + // add child to stack + current_key.pushBranch (child_idx); + + stack_entry.node_ = this->octree_->getBranchChildPtr(*current_branch, child_idx); + + stack_.push_back(stack_entry); + + current_key.popBranch(); + } + } + } + + if (stack_.size ()) + { + this->current_state_ = &stack_.back(); + } else + { + this->current_state_ = 0; + } + } + + return (*this); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + OctreeBreadthFirstIterator::OctreeBreadthFirstIterator (unsigned int max_depth_arg) : + OctreeIteratorBase (max_depth_arg), FIFO_ () + { + OctreeIteratorBase::reset (); + + // initialize iterator + this->reset (); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + OctreeBreadthFirstIterator::OctreeBreadthFirstIterator (OctreeT* octree_arg, unsigned int max_depth_arg) : + OctreeIteratorBase (octree_arg, max_depth_arg), FIFO_ () + { + OctreeIteratorBase::reset (); + + // initialize iterator + this->reset (); + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + OctreeBreadthFirstIterator::~OctreeBreadthFirstIterator () + { + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + void OctreeBreadthFirstIterator::reset () + { + OctreeIteratorBase::reset (); + + // init FIFO + FIFO_.clear (); + + if (this->octree_) + { + // pushing root node to stack + IteratorState FIFO_entry; + FIFO_entry.node_ = this->octree_->getRootNode (); + FIFO_entry.depth_ = 0; + FIFO_entry.key_.x = FIFO_entry.key_.y = FIFO_entry.key_.z = 0; + + FIFO_.push_back(FIFO_entry); + + this->current_state_ = &FIFO_.front(); + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////// + template + OctreeBreadthFirstIterator& + OctreeBreadthFirstIterator::operator++ () + { + + if (FIFO_.size ()) + { + // get stack element + IteratorState FIFO_entry = FIFO_.front (); + FIFO_.pop_front (); + + FIFO_entry.depth_ ++; + OctreeKey& current_key = FIFO_entry.key_; + + if ( (this->max_octree_depth_>=FIFO_entry.depth_) && + (FIFO_entry.node_->getNodeType () == BRANCH_NODE) ) + { + unsigned char child_idx; + + // current node is a branch node + BranchNode* current_branch = + static_cast (FIFO_entry.node_); + + // iterate over all children + for (child_idx = 0; child_idx < 8 ; ++child_idx) + { + + // if child exist + if (this->octree_->branchHasChild(*current_branch, child_idx)) + { + // add child to stack + current_key.pushBranch (static_cast (child_idx)); + + FIFO_entry.node_ = this->octree_->getBranchChildPtr(*current_branch, child_idx); + + FIFO_.push_back(FIFO_entry); + + current_key.popBranch(); + } + } + } + + if (FIFO_.size ()) + { + this->current_state_ = &FIFO_.front(); + } else + { + this->current_state_ = 0; + } + + } + + return (*this); + } + } +} + +#endif diff --git a/pcl-1.7/pcl/octree/impl/octree_pointcloud.hpp b/pcl-1.7/pcl/octree/impl/octree_pointcloud.hpp new file mode 100644 index 0000000..3191a20 --- /dev/null +++ b/pcl-1.7/pcl/octree/impl/octree_pointcloud.hpp @@ -0,0 +1,834 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_POINTCLOUD_HPP_ +#define PCL_OCTREE_POINTCLOUD_HPP_ + +#include +#include + +#include + + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::octree::OctreePointCloud::OctreePointCloud (const double resolution) : + OctreeT (), input_ (PointCloudConstPtr ()), indices_ (IndicesConstPtr ()), + epsilon_ (0), resolution_ (resolution), min_x_ (0.0f), max_x_ (resolution), min_y_ (0.0f), + max_y_ (resolution), min_z_ (0.0f), max_z_ (resolution), bounding_box_defined_ (false), max_objs_per_leaf_(0) +{ + assert (resolution > 0.0f); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::octree::OctreePointCloud::~OctreePointCloud () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::addPointsFromInputCloud () +{ + size_t i; + + if (indices_) + { + for (std::vector::const_iterator current = indices_->begin (); current != indices_->end (); ++current) + { + assert( (*current>=0) && (*current < static_cast (input_->points.size ()))); + + if (isFinite (input_->points[*current])) + { + // add points to octree + this->addPointIdx (*current); + } + } + } + else + { + for (i = 0; i < input_->points.size (); i++) + { + if (isFinite (input_->points[i])) + { + // add points to octree + this->addPointIdx (static_cast (i)); + } + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::addPointFromCloud (const int point_idx_arg, IndicesPtr indices_arg) +{ + this->addPointIdx (point_idx_arg); + if (indices_arg) + indices_arg->push_back (point_idx_arg); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::addPointToCloud (const PointT& point_arg, PointCloudPtr cloud_arg) +{ + assert (cloud_arg==input_); + + cloud_arg->push_back (point_arg); + + this->addPointIdx (static_cast (cloud_arg->points.size ()) - 1); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::addPointToCloud (const PointT& point_arg, PointCloudPtr cloud_arg, + IndicesPtr indices_arg) +{ + assert (cloud_arg==input_); + assert (indices_arg==indices_); + + cloud_arg->push_back (point_arg); + + this->addPointFromCloud (static_cast (cloud_arg->points.size ()) - 1, indices_arg); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::octree::OctreePointCloud::isVoxelOccupiedAtPoint (const PointT& point_arg) const +{ + OctreeKey key; + + // generate key for point + this->genOctreeKeyforPoint (point_arg, key); + + // search for key in octree + return (isPointWithinBoundingBox (point_arg) && this->existLeaf (key)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::octree::OctreePointCloud::isVoxelOccupiedAtPoint (const int& point_idx_arg) const +{ + // retrieve point from input cloud + const PointT& point = this->input_->points[point_idx_arg]; + + // search for voxel at point in octree + return (this->isVoxelOccupiedAtPoint (point)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::octree::OctreePointCloud::isVoxelOccupiedAtPoint ( + const double point_x_arg, const double point_y_arg, const double point_z_arg) const +{ + OctreeKey key; + + // generate key for point + this->genOctreeKeyforPoint (point_x_arg, point_y_arg, point_z_arg, key); + + return (this->existLeaf (key)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::deleteVoxelAtPoint (const PointT& point_arg) +{ + OctreeKey key; + + // generate key for point + this->genOctreeKeyforPoint (point_arg, key); + + this->removeLeaf (key); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::deleteVoxelAtPoint (const int& point_idx_arg) +{ + // retrieve point from input cloud + const PointT& point = this->input_->points[point_idx_arg]; + + // delete leaf at point + this->deleteVoxelAtPoint (point); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::octree::OctreePointCloud::getOccupiedVoxelCenters ( + AlignedPointTVector &voxel_center_list_arg) const +{ + OctreeKey key; + key.x = key.y = key.z = 0; + + voxel_center_list_arg.clear (); + + return getOccupiedVoxelCentersRecursive (this->root_node_, key, voxel_center_list_arg); + +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::octree::OctreePointCloud::getApproxIntersectedVoxelCentersBySegment ( + const Eigen::Vector3f& origin, + const Eigen::Vector3f& end, + AlignedPointTVector &voxel_center_list, + float precision) +{ + Eigen::Vector3f direction = end - origin; + float norm = direction.norm (); + direction.normalize (); + + const float step_size = static_cast (resolution_) * precision; + // Ensure we get at least one step for the first voxel. + const int nsteps = std::max (1, static_cast (norm / step_size)); + + OctreeKey prev_key; + + bool bkeyDefined = false; + + // Walk along the line segment with small steps. + for (int i = 0; i < nsteps; ++i) + { + Eigen::Vector3f p = origin + (direction * step_size * static_cast (i)); + + PointT octree_p; + octree_p.x = p.x (); + octree_p.y = p.y (); + octree_p.z = p.z (); + + OctreeKey key; + this->genOctreeKeyforPoint (octree_p, key); + + // Not a new key, still the same voxel. + if ((key == prev_key) && (bkeyDefined) ) + continue; + + prev_key = key; + bkeyDefined = true; + + PointT center; + genLeafNodeCenterFromOctreeKey (key, center); + voxel_center_list.push_back (center); + } + + OctreeKey end_key; + PointT end_p; + end_p.x = end.x (); + end_p.y = end.y (); + end_p.z = end.z (); + this->genOctreeKeyforPoint (end_p, end_key); + if (!(end_key == prev_key)) + { + PointT center; + genLeafNodeCenterFromOctreeKey (end_key, center); + voxel_center_list.push_back (center); + } + + return (static_cast (voxel_center_list.size ())); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::defineBoundingBox () +{ + + double minX, minY, minZ, maxX, maxY, maxZ; + + PointT min_pt; + PointT max_pt; + + // bounding box cannot be changed once the octree contains elements + assert (this->leaf_count_ == 0); + + pcl::getMinMax3D (*input_, min_pt, max_pt); + + float minValue = std::numeric_limits::epsilon () * 512.0f; + + minX = min_pt.x; + minY = min_pt.y; + minZ = min_pt.z; + + maxX = max_pt.x + minValue; + maxY = max_pt.y + minValue; + maxZ = max_pt.z + minValue; + + // generate bit masks for octree + defineBoundingBox (minX, minY, minZ, maxX, maxY, maxZ); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::defineBoundingBox (const double min_x_arg, + const double min_y_arg, + const double min_z_arg, + const double max_x_arg, + const double max_y_arg, + const double max_z_arg) +{ + // bounding box cannot be changed once the octree contains elements + assert (this->leaf_count_ == 0); + + assert (max_x_arg >= min_x_arg); + assert (max_y_arg >= min_y_arg); + assert (max_z_arg >= min_z_arg); + + min_x_ = min_x_arg; + max_x_ = max_x_arg; + + min_y_ = min_y_arg; + max_y_ = max_y_arg; + + min_z_ = min_z_arg; + max_z_ = max_z_arg; + + min_x_ = std::min (min_x_, max_x_); + min_y_ = std::min (min_y_, max_y_); + min_z_ = std::min (min_z_, max_z_); + + max_x_ = std::max (min_x_, max_x_); + max_y_ = std::max (min_y_, max_y_); + max_z_ = std::max (min_z_, max_z_); + + // generate bit masks for octree + getKeyBitSize (); + + bounding_box_defined_ = true; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::defineBoundingBox ( + const double max_x_arg, const double max_y_arg, const double max_z_arg) +{ + // bounding box cannot be changed once the octree contains elements + assert (this->leaf_count_ == 0); + + assert (max_x_arg >= 0.0f); + assert (max_y_arg >= 0.0f); + assert (max_z_arg >= 0.0f); + + min_x_ = 0.0f; + max_x_ = max_x_arg; + + min_y_ = 0.0f; + max_y_ = max_y_arg; + + min_z_ = 0.0f; + max_z_ = max_z_arg; + + min_x_ = std::min (min_x_, max_x_); + min_y_ = std::min (min_y_, max_y_); + min_z_ = std::min (min_z_, max_z_); + + max_x_ = std::max (min_x_, max_x_); + max_y_ = std::max (min_y_, max_y_); + max_z_ = std::max (min_z_, max_z_); + + // generate bit masks for octree + getKeyBitSize (); + + bounding_box_defined_ = true; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::defineBoundingBox (const double cubeLen_arg) +{ + // bounding box cannot be changed once the octree contains elements + assert (this->leaf_count_ == 0); + + assert (cubeLen_arg >= 0.0f); + + min_x_ = 0.0f; + max_x_ = cubeLen_arg; + + min_y_ = 0.0f; + max_y_ = cubeLen_arg; + + min_z_ = 0.0f; + max_z_ = cubeLen_arg; + + min_x_ = std::min (min_x_, max_x_); + min_y_ = std::min (min_y_, max_y_); + min_z_ = std::min (min_z_, max_z_); + + max_x_ = std::max (min_x_, max_x_); + max_y_ = std::max (min_y_, max_y_); + max_z_ = std::max (min_z_, max_z_); + + // generate bit masks for octree + getKeyBitSize (); + + bounding_box_defined_ = true; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::getBoundingBox ( + double& min_x_arg, double& min_y_arg, double& min_z_arg, + double& max_x_arg, double& max_y_arg, double& max_z_arg) const +{ + min_x_arg = min_x_; + min_y_arg = min_y_; + min_z_arg = min_z_; + + max_x_arg = max_x_; + max_y_arg = max_y_; + max_z_arg = max_z_; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::octree::OctreePointCloud::adoptBoundingBoxToPoint (const PointT& point_idx_arg) +{ + + const float minValue = std::numeric_limits::epsilon (); + + // increase octree size until point fits into bounding box + while (true) + { + bool bLowerBoundViolationX = (point_idx_arg.x < min_x_); + bool bLowerBoundViolationY = (point_idx_arg.y < min_y_); + bool bLowerBoundViolationZ = (point_idx_arg.z < min_z_); + + bool bUpperBoundViolationX = (point_idx_arg.x >= max_x_); + bool bUpperBoundViolationY = (point_idx_arg.y >= max_y_); + bool bUpperBoundViolationZ = (point_idx_arg.z >= max_z_); + + // do we violate any bounds? + if (bLowerBoundViolationX || bLowerBoundViolationY || bLowerBoundViolationZ || bUpperBoundViolationX + || bUpperBoundViolationY || bUpperBoundViolationZ || (!bounding_box_defined_) ) + { + + if (bounding_box_defined_) + { + + double octreeSideLen; + unsigned char child_idx; + + // octree not empty - we add another tree level and thus increase its size by a factor of 2*2*2 + child_idx = static_cast (((!bUpperBoundViolationX) << 2) | ((!bUpperBoundViolationY) << 1) + | ((!bUpperBoundViolationZ))); + + BranchNode* newRootBranch; + + newRootBranch = new BranchNode(); + this->branch_count_++; + + this->setBranchChildPtr (*newRootBranch, child_idx, this->root_node_); + + this->root_node_ = newRootBranch; + + octreeSideLen = static_cast (1 << this->octree_depth_) * resolution_; + + if (!bUpperBoundViolationX) + min_x_ -= octreeSideLen; + + if (!bUpperBoundViolationY) + min_y_ -= octreeSideLen; + + if (!bUpperBoundViolationZ) + min_z_ -= octreeSideLen; + + // configure tree depth of octree + this->octree_depth_++; + this->setTreeDepth (this->octree_depth_); + + // recalculate bounding box width + octreeSideLen = static_cast (1 << this->octree_depth_) * resolution_ - minValue; + + // increase octree bounding box + max_x_ = min_x_ + octreeSideLen; + max_y_ = min_y_ + octreeSideLen; + max_z_ = min_z_ + octreeSideLen; + + } + // bounding box is not defined - set it to point position + else + { + // octree is empty - we set the center of the bounding box to our first pixel + this->min_x_ = point_idx_arg.x - this->resolution_ / 2; + this->min_y_ = point_idx_arg.y - this->resolution_ / 2; + this->min_z_ = point_idx_arg.z - this->resolution_ / 2; + + this->max_x_ = point_idx_arg.x + this->resolution_ / 2; + this->max_y_ = point_idx_arg.y + this->resolution_ / 2; + this->max_z_ = point_idx_arg.z + this->resolution_ / 2; + + getKeyBitSize (); + + bounding_box_defined_ = true; + } + + } + else + // no bound violations anymore - leave while loop + break; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::expandLeafNode (LeafNode* leaf_node, BranchNode* parent_branch, unsigned char child_idx, unsigned int depth_mask) +{ + + if (depth_mask) + { + // get amount of objects in leaf container + size_t leaf_obj_count = (*leaf_node)->getSize (); + + // copy leaf data + std::vector leafIndices; + leafIndices.reserve(leaf_obj_count); + + (*leaf_node)->getPointIndices(leafIndices); + + // delete current leaf node + this->deleteBranchChild(*parent_branch, child_idx); + this->leaf_count_ --; + + // create new branch node + BranchNode* childBranch = this->createBranchChild (*parent_branch, child_idx); + this->branch_count_ ++; + + typename std::vector::iterator it = leafIndices.begin(); + typename std::vector::const_iterator it_end = leafIndices.end(); + + // add data to new branch + OctreeKey new_index_key; + + for (it = leafIndices.begin(); it!=it_end; ++it) + { + + const PointT& point_from_index = input_->points[*it]; + // generate key + genOctreeKeyforPoint (point_from_index, new_index_key); + + LeafNode* newLeaf; + BranchNode* newBranchParent; + this->createLeafRecursive (new_index_key, depth_mask, childBranch, newLeaf, newBranchParent); + + (*newLeaf)->addPointIndex(*it); + } + } + + +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::addPointIdx (const int point_idx_arg) +{ + OctreeKey key; + + assert (point_idx_arg < static_cast (input_->points.size ())); + + const PointT& point = input_->points[point_idx_arg]; + + // make sure bounding box is big enough + adoptBoundingBoxToPoint (point); + + // generate key + genOctreeKeyforPoint (point, key); + + LeafNode* leaf_node; + BranchNode* parent_branch_of_leaf_node; + unsigned int depth_mask = this->createLeafRecursive (key, this->depth_mask_ ,this->root_node_, leaf_node, parent_branch_of_leaf_node); + + if (this->dynamic_depth_enabled_ && depth_mask) + { + // get amount of objects in leaf container + size_t leaf_obj_count = (*leaf_node)->getSize (); + + while (leaf_obj_count>=max_objs_per_leaf_ && depth_mask) + { + // index to branch child + unsigned char child_idx = key.getChildIdxWithDepthMask (depth_mask*2); + + expandLeafNode (leaf_node, + parent_branch_of_leaf_node, + child_idx, + depth_mask); + + depth_mask = this->createLeafRecursive (key, this->depth_mask_ ,this->root_node_, leaf_node, parent_branch_of_leaf_node); + leaf_obj_count = (*leaf_node)->getSize (); + } + + } + + (*leaf_node)->addPointIndex (point_idx_arg); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template const PointT& +pcl::octree::OctreePointCloud::getPointByIndex (const unsigned int index_arg) const +{ + // retrieve point from input cloud + assert (index_arg < static_cast (input_->points.size ())); + return (this->input_->points[index_arg]); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::getKeyBitSize () +{ + unsigned int max_voxels; + + unsigned int max_key_x; + unsigned int max_key_y; + unsigned int max_key_z; + + double octree_side_len; + + const float minValue = std::numeric_limits::epsilon(); + + // find maximum key values for x, y, z + max_key_x = static_cast ((max_x_ - min_x_) / resolution_); + max_key_y = static_cast ((max_y_ - min_y_) / resolution_); + max_key_z = static_cast ((max_z_ - min_z_) / resolution_); + + // find maximum amount of keys + max_voxels = std::max (std::max (std::max (max_key_x, max_key_y), max_key_z), static_cast (2)); + + + // tree depth == amount of bits of max_voxels + this->octree_depth_ = std::max ((std::min (static_cast (OctreeKey::maxDepth), static_cast (ceil (this->Log2 (max_voxels)-minValue)))), + static_cast (0)); + + octree_side_len = static_cast (1 << this->octree_depth_) * resolution_-minValue; + + if (this->leaf_count_ == 0) + { + double octree_oversize_x; + double octree_oversize_y; + double octree_oversize_z; + + octree_oversize_x = (octree_side_len - (max_x_ - min_x_)) / 2.0; + octree_oversize_y = (octree_side_len - (max_y_ - min_y_)) / 2.0; + octree_oversize_z = (octree_side_len - (max_z_ - min_z_)) / 2.0; + + min_x_ -= octree_oversize_x; + min_y_ -= octree_oversize_y; + min_z_ -= octree_oversize_z; + + max_x_ += octree_oversize_x; + max_y_ += octree_oversize_y; + max_z_ += octree_oversize_z; + } + else + { + max_x_ = min_x_ + octree_side_len; + max_y_ = min_y_ + octree_side_len; + max_z_ = min_z_ + octree_side_len; + } + + // configure tree depth of octree + this->setTreeDepth (this->octree_depth_); + +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::genOctreeKeyforPoint (const PointT& point_arg, + OctreeKey & key_arg) const + { + // calculate integer key for point coordinates + key_arg.x = static_cast ((point_arg.x - this->min_x_) / this->resolution_); + key_arg.y = static_cast ((point_arg.y - this->min_y_) / this->resolution_); + key_arg.z = static_cast ((point_arg.z - this->min_z_) / this->resolution_); + } + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::genOctreeKeyforPoint ( + const double point_x_arg, const double point_y_arg, + const double point_z_arg, OctreeKey & key_arg) const +{ + PointT temp_point; + + temp_point.x = static_cast (point_x_arg); + temp_point.y = static_cast (point_y_arg); + temp_point.z = static_cast (point_z_arg); + + // generate key for point + genOctreeKeyforPoint (temp_point, key_arg); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::octree::OctreePointCloud::genOctreeKeyForDataT (const int& data_arg, OctreeKey & key_arg) const +{ + const PointT temp_point = getPointByIndex (data_arg); + + // generate key for point + genOctreeKeyforPoint (temp_point, key_arg); + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::genLeafNodeCenterFromOctreeKey (const OctreeKey & key, PointT & point) const +{ + // define point to leaf node voxel center + point.x = static_cast ((static_cast (key.x) + 0.5f) * this->resolution_ + this->min_x_); + point.y = static_cast ((static_cast (key.y) + 0.5f) * this->resolution_ + this->min_y_); + point.z = static_cast ((static_cast (key.z) + 0.5f) * this->resolution_ + this->min_z_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::genVoxelCenterFromOctreeKey ( + const OctreeKey & key_arg, + unsigned int tree_depth_arg, + PointT& point_arg) const +{ + // generate point for voxel center defined by treedepth (bitLen) and key + point_arg.x = static_cast ((static_cast (key_arg.x) + 0.5f) * (this->resolution_ * static_cast (1 << (this->octree_depth_ - tree_depth_arg))) + this->min_x_); + point_arg.y = static_cast ((static_cast (key_arg.y) + 0.5f) * (this->resolution_ * static_cast (1 << (this->octree_depth_ - tree_depth_arg))) + this->min_y_); + point_arg.z = static_cast ((static_cast (key_arg.z) + 0.5f) * (this->resolution_ * static_cast (1 << (this->octree_depth_ - tree_depth_arg))) + this->min_z_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloud::genVoxelBoundsFromOctreeKey ( + const OctreeKey & key_arg, + unsigned int tree_depth_arg, + Eigen::Vector3f &min_pt, + Eigen::Vector3f &max_pt) const +{ + // calculate voxel size of current tree depth + double voxel_side_len = this->resolution_ * static_cast (1 << (this->octree_depth_ - tree_depth_arg)); + + // calculate voxel bounds + min_pt (0) = static_cast (static_cast (key_arg.x) * voxel_side_len + this->min_x_); + min_pt (1) = static_cast (static_cast (key_arg.y) * voxel_side_len + this->min_y_); + min_pt (2) = static_cast (static_cast (key_arg.z) * voxel_side_len + this->min_z_); + + max_pt (0) = static_cast (static_cast (key_arg.x + 1) * voxel_side_len + this->min_x_); + max_pt (1) = static_cast (static_cast (key_arg.y + 1) * voxel_side_len + this->min_y_); + max_pt (2) = static_cast (static_cast (key_arg.z + 1) * voxel_side_len + this->min_z_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::octree::OctreePointCloud::getVoxelSquaredSideLen (unsigned int tree_depth_arg) const +{ + double side_len; + + // side length of the voxel cube increases exponentially with the octree depth + side_len = this->resolution_ * static_cast(1 << (this->octree_depth_ - tree_depth_arg)); + + // squared voxel side length + side_len *= side_len; + + return (side_len); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::octree::OctreePointCloud::getVoxelSquaredDiameter (unsigned int tree_depth_arg) const +{ + // return the squared side length of the voxel cube as a function of the octree depth + return (getVoxelSquaredSideLen (tree_depth_arg) * 3); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::octree::OctreePointCloud::getOccupiedVoxelCentersRecursive ( + const BranchNode* node_arg, + const OctreeKey& key_arg, + AlignedPointTVector &voxel_center_list_arg) const +{ + // child iterator + unsigned char child_idx; + + int voxel_count = 0; + + // iterate over all children + for (child_idx = 0; child_idx < 8; child_idx++) + { + if (!this->branchHasChild (*node_arg, child_idx)) + continue; + + const OctreeNode * child_node; + child_node = this->getBranchChildPtr (*node_arg, child_idx); + + // generate new key for current branch voxel + OctreeKey new_key; + new_key.x = (key_arg.x << 1) | (!!(child_idx & (1 << 2))); + new_key.y = (key_arg.y << 1) | (!!(child_idx & (1 << 1))); + new_key.z = (key_arg.z << 1) | (!!(child_idx & (1 << 0))); + + switch (child_node->getNodeType ()) + { + case BRANCH_NODE: + { + // recursively proceed with indexed child branch + voxel_count += getOccupiedVoxelCentersRecursive (static_cast (child_node), new_key, voxel_center_list_arg); + break; + } + case LEAF_NODE: + { + PointT new_point; + + genLeafNodeCenterFromOctreeKey (new_key, new_point); + voxel_center_list_arg.push_back (new_point); + + voxel_count++; + break; + } + default: + break; + } + } + return (voxel_count); +} + +#define PCL_INSTANTIATE_OctreePointCloudSingleBufferWithLeafDataTVector(T) template class PCL_EXPORTS pcl::octree::OctreePointCloud >; +#define PCL_INSTANTIATE_OctreePointCloudDoubleBufferWithLeafDataTVector(T) template class PCL_EXPORTS pcl::octree::OctreePointCloud >; + +#define PCL_INSTANTIATE_OctreePointCloudSingleBufferWithLeafDataT(T) template class PCL_EXPORTS pcl::octree::OctreePointCloud >; +#define PCL_INSTANTIATE_OctreePointCloudDoubleBufferWithLeafDataT(T) template class PCL_EXPORTS pcl::octree::OctreePointCloud >; + +#define PCL_INSTANTIATE_OctreePointCloudSingleBufferWithEmptyLeaf(T) template class PCL_EXPORTS pcl::octree::OctreePointCloud >; +#define PCL_INSTANTIATE_OctreePointCloudDoubleBufferWithEmptyLeaf(T) template class PCL_EXPORTS pcl::octree::OctreePointCloud >; + +#endif /* OCTREE_POINTCLOUD_HPP_ */ diff --git a/pcl-1.7/pcl/octree/impl/octree_pointcloud_adjacency.hpp b/pcl-1.7/pcl/octree/impl/octree_pointcloud_adjacency.hpp new file mode 100644 index 0000000..9628890 --- /dev/null +++ b/pcl-1.7/pcl/octree/impl/octree_pointcloud_adjacency.hpp @@ -0,0 +1,313 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Jeremie Papon + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_OCTREE_POINTCLOUD_ADJACENCY_HPP_ +#define PCL_OCTREE_POINTCLOUD_ADJACENCY_HPP_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::octree::OctreePointCloudAdjacency::OctreePointCloudAdjacency (const double resolution_arg) +: OctreePointCloud > (resolution_arg) +{ + +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloudAdjacency::addPointsFromInputCloud () +{ + //double t1,t2; + float minX = std::numeric_limits::max (), minY = std::numeric_limits::max (), minZ = std::numeric_limits::max (); + float maxX = -std::numeric_limits::max(), maxY = -std::numeric_limits::max(), maxZ = -std::numeric_limits::max(); + + for (size_t i = 0; i < input_->size (); ++i) + { + PointT temp (input_->points[i]); + if (transform_func_) //Search for point with + transform_func_ (temp); + if (!pcl::isFinite (temp)) //Check to make sure transform didn't make point not finite + continue; + if (temp.x < minX) + minX = temp.x; + if (temp.y < minY) + minY = temp.y; + if (temp.z < minZ) + minZ = temp.z; + if (temp.x > maxX) + maxX = temp.x; + if (temp.y > maxY) + maxY = temp.y; + if (temp.z > maxZ) + maxZ = temp.z; + } + this->defineBoundingBox (minX, minY, minZ, maxX, maxY, maxZ); + + OctreePointCloud::addPointsFromInputCloud (); + + LeafContainerT *leaf_container; + typename OctreeAdjacencyT::LeafNodeIterator leaf_itr; + leaf_vector_.reserve (this->getLeafCount ()); + for ( leaf_itr = this->leaf_begin () ; leaf_itr != this->leaf_end (); ++leaf_itr) + { + OctreeKey leaf_key = leaf_itr.getCurrentOctreeKey (); + leaf_container = &(leaf_itr.getLeafContainer ()); + + //Run the leaf's compute function + leaf_container->computeData (); + + computeNeighbors (leaf_key, leaf_container); + + leaf_vector_.push_back (leaf_container); + } + //Make sure our leaf vector is correctly sized + assert (leaf_vector_.size () == this->getLeafCount ()); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloudAdjacency::genOctreeKeyforPoint (const PointT& point_arg,OctreeKey & key_arg) const +{ + if (transform_func_) + { + PointT temp (point_arg); + transform_func_ (temp); + // calculate integer key for transformed point coordinates + if (pcl::isFinite (temp)) //Make sure transformed point is finite - if it is not, it gets default key + { + key_arg.x = static_cast ((temp.x - this->min_x_) / this->resolution_); + key_arg.y = static_cast ((temp.y - this->min_y_) / this->resolution_); + key_arg.z = static_cast ((temp.z - this->min_z_) / this->resolution_); + } + else + { + key_arg = OctreeKey (); + } + } + else + { + // calculate integer key for point coordinates + key_arg.x = static_cast ((point_arg.x - this->min_x_) / this->resolution_); + key_arg.y = static_cast ((point_arg.y - this->min_y_) / this->resolution_); + key_arg.z = static_cast ((point_arg.z - this->min_z_) / this->resolution_); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloudAdjacency::addPointIdx (const int pointIdx_arg) +{ + OctreeKey key; + + assert (pointIdx_arg < static_cast (this->input_->points.size ())); + + const PointT& point = this->input_->points[pointIdx_arg]; + if (!pcl::isFinite (point)) + return; + + // generate key + this->genOctreeKeyforPoint (point, key); + // add point to octree at key + LeafContainerT* container = this->createLeaf(key); + container->addPoint (point); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloudAdjacency::computeNeighbors (OctreeKey &key_arg, LeafContainerT* leaf_container) +{ + //Make sure requested key is valid + if (key_arg.x > this->max_key_.x || key_arg.y > this->max_key_.y || key_arg.z > this->max_key_.z) + { + PCL_ERROR ("OctreePointCloudAdjacency::computeNeighbors Requested neighbors for invalid octree key\n"); + return; + } + + OctreeKey neighbor_key; + int dx_min = (key_arg.x > 0) ? -1 : 0; + int dy_min = (key_arg.y > 0) ? -1 : 0; + int dz_min = (key_arg.z > 0) ? -1 : 0; + int dx_max = (key_arg.x == this->max_key_.x) ? 0 : 1; + int dy_max = (key_arg.y == this->max_key_.y) ? 0 : 1; + int dz_max = (key_arg.z == this->max_key_.z) ? 0 : 1; + + for (int dx = dx_min; dx <= dx_max; ++dx) + { + for (int dy = dy_min; dy <= dy_max; ++dy) + { + for (int dz = dz_min; dz <= dz_max; ++dz) + { + neighbor_key.x = static_cast (key_arg.x + dx); + neighbor_key.y = static_cast (key_arg.y + dy); + neighbor_key.z = static_cast (key_arg.z + dz); + LeafContainerT *neighbor = this->findLeaf (neighbor_key); + if (neighbor) + { + leaf_container->addNeighbor (neighbor); + } + } + } + } +} + + + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template LeafContainerT* +pcl::octree::OctreePointCloudAdjacency::getLeafContainerAtPoint ( + const PointT& point_arg) const +{ + OctreeKey key; + LeafContainerT* leaf = 0; + // generate key + this->genOctreeKeyforPoint (point_arg, key); + + leaf = this->findLeaf (key); + + return leaf; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloudAdjacency::computeVoxelAdjacencyGraph (VoxelAdjacencyList &voxel_adjacency_graph) +{ + //TODO Change this to use leaf centers, not centroids! + + voxel_adjacency_graph.clear (); + //Add a vertex for each voxel, store ids in map + std::map leaf_vertex_id_map; + for (typename OctreeAdjacencyT::LeafNodeIterator leaf_itr = this->leaf_begin () ; leaf_itr != this->leaf_end (); ++leaf_itr) + { + OctreeKey leaf_key = leaf_itr.getCurrentOctreeKey (); + PointT centroid_point; + this->genLeafNodeCenterFromOctreeKey (leaf_key, centroid_point); + VoxelID node_id = add_vertex (voxel_adjacency_graph); + + voxel_adjacency_graph[node_id] = centroid_point; + LeafContainerT* leaf_container = &(leaf_itr.getLeafContainer ()); + leaf_vertex_id_map[leaf_container] = node_id; + } + + //Iterate through and add edges to adjacency graph + for ( typename std::vector::iterator leaf_itr = leaf_vector_.begin (); leaf_itr != leaf_vector_.end (); ++leaf_itr) + { + typename LeafContainerT::iterator neighbor_itr = (*leaf_itr)->begin (); + typename LeafContainerT::iterator neighbor_end = (*leaf_itr)->end (); + LeafContainerT* neighbor_container; + VoxelID u = (leaf_vertex_id_map.find (*leaf_itr))->second; + PointT p_u = voxel_adjacency_graph[u]; + for ( ; neighbor_itr != neighbor_end; ++neighbor_itr) + { + neighbor_container = *neighbor_itr; + EdgeID edge; + bool edge_added; + VoxelID v = (leaf_vertex_id_map.find (neighbor_container))->second; + boost::tie (edge, edge_added) = add_edge (u,v,voxel_adjacency_graph); + + PointT p_v = voxel_adjacency_graph[v]; + float dist = (p_v.getVector3fMap () - p_u.getVector3fMap ()).norm (); + voxel_adjacency_graph[edge] = dist; + + } + + } + +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::octree::OctreePointCloudAdjacency::testForOcclusion (const PointT& point_arg, const PointXYZ &camera_pos) +{ + OctreeKey key; + this->genOctreeKeyforPoint (point_arg, key); + // This code follows the method in Octree::PointCloud + Eigen::Vector3f sensor(camera_pos.x, + camera_pos.y, + camera_pos.z); + + Eigen::Vector3f leaf_centroid(static_cast ((static_cast (key.x) + 0.5f) * this->resolution_ + this->min_x_), + static_cast ((static_cast (key.y) + 0.5f) * this->resolution_ + this->min_y_), + static_cast ((static_cast (key.z) + 0.5f) * this->resolution_ + this->min_z_)); + Eigen::Vector3f direction = sensor - leaf_centroid; + + float norm = direction.norm (); + direction.normalize (); + float precision = 1.0f; + const float step_size = static_cast (resolution_) * precision; + const int nsteps = std::max (1, static_cast (norm / step_size)); + + OctreeKey prev_key = key; + // Walk along the line segment with small steps. + Eigen::Vector3f p = leaf_centroid; + PointT octree_p; + for (int i = 0; i < nsteps; ++i) + { + //Start at the leaf voxel, and move back towards sensor. + p += (direction * step_size); + + octree_p.x = p.x (); + octree_p.y = p.y (); + octree_p.z = p.z (); + // std::cout << octree_p<< "\n"; + OctreeKey key; + this->genOctreeKeyforPoint (octree_p, key); + + // Not a new key, still the same voxel (starts at self). + if ((key == prev_key)) + continue; + + prev_key = key; + + LeafContainerT *leaf = this->findLeaf (key); + //If the voxel is occupied, there is a possible occlusion + if (leaf) + { + return true; + } + } + + //If we didn't run into a voxel on the way to this camera, it can't be occluded. + return false; + +} + +#define PCL_INSTANTIATE_OctreePointCloudAdjacency(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudAdjacency; + +#endif + diff --git a/pcl-1.7/pcl/octree/impl/octree_pointcloud_voxelcentroid.hpp b/pcl-1.7/pcl/octree/impl/octree_pointcloud_voxelcentroid.hpp new file mode 100644 index 0000000..d6a5cf8 --- /dev/null +++ b/pcl-1.7/pcl/octree/impl/octree_pointcloud_voxelcentroid.hpp @@ -0,0 +1,137 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: octree_pointcloud_voxelcentroid.hpp 6459 2012-07-18 07:50:37Z dpb $ + */ + +#ifndef PCL_OCTREE_VOXELCENTROID_HPP +#define PCL_OCTREE_VOXELCENTROID_HPP + +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::octree::OctreePointCloudVoxelCentroid::getVoxelCentroidAtPoint ( + const PointT& point_arg, PointT& voxel_centroid_arg) const +{ + OctreeKey key; + LeafNode* leaf = 0; + + // generate key + genOctreeKeyforPoint (point_arg, key); + + leaf = this->findLeaf (key); + + if (leaf) + { + LeafContainerT* container = leaf; + container->getCentroid (voxel_centroid_arg); + } + + return (leaf != 0); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template size_t +pcl::octree::OctreePointCloudVoxelCentroid::getVoxelCentroids ( + typename OctreePointCloud::AlignedPointTVector &voxel_centroid_list_arg) const +{ + OctreeKey new_key; + + // reset output vector + voxel_centroid_list_arg.clear (); + voxel_centroid_list_arg.reserve (this->leaf_count_); + + getVoxelCentroidsRecursive (this->root_node_, new_key, voxel_centroid_list_arg ); + + // return size of centroid vector + return (voxel_centroid_list_arg.size ()); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloudVoxelCentroid::getVoxelCentroidsRecursive ( + const BranchNode* branch_arg, OctreeKey& key_arg, + typename OctreePointCloud::AlignedPointTVector &voxel_centroid_list_arg) const +{ + // child iterator + unsigned char child_idx; + + // iterate over all children + for (child_idx = 0; child_idx < 8; child_idx++) + { + // if child exist + if (branch_arg->hasChild (child_idx)) + { + // add current branch voxel to key + key_arg.pushBranch (child_idx); + + OctreeNode *child_node = branch_arg->getChildPtr (child_idx); + + switch (child_node->getNodeType ()) + { + case BRANCH_NODE: + { + // recursively proceed with indexed child branch + getVoxelCentroidsRecursive (static_cast (child_node), key_arg, voxel_centroid_list_arg); + break; + } + case LEAF_NODE: + { + PointT new_centroid; + + LeafNode* container = static_cast (child_node); + + container->getContainer().getCentroid (new_centroid); + + voxel_centroid_list_arg.push_back (new_centroid); + break; + } + default: + break; + } + + // pop current branch voxel from key + key_arg.popBranch (); + } + } +} + + +#define PCL_INSTANTIATE_OctreePointCloudVoxelCentroid(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudVoxelCentroid; + +#endif + diff --git a/pcl-1.7/pcl/octree/impl/octree_search.hpp b/pcl-1.7/pcl/octree/impl/octree_search.hpp new file mode 100644 index 0000000..51d28f8 --- /dev/null +++ b/pcl-1.7/pcl/octree/impl/octree_search.hpp @@ -0,0 +1,867 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_SEARCH_IMPL_H_ +#define PCL_OCTREE_SEARCH_IMPL_H_ + +#include +#include + +#include +#include + + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::octree::OctreePointCloudSearch::voxelSearch (const PointT& point, + std::vector& point_idx_data) +{ + assert (isFinite (point) && "Invalid (NaN, Inf) point coordinates given to nearestKSearch!"); + OctreeKey key; + bool b_success = false; + + // generate key + this->genOctreeKeyforPoint (point, key); + + LeafContainerT* leaf = this->findLeaf (key); + + if (leaf) + { + (*leaf).getPointIndices (point_idx_data); + b_success = true; + } + + return (b_success); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::octree::OctreePointCloudSearch::voxelSearch (const int index, + std::vector& point_idx_data) +{ + const PointT search_point = this->getPointByIndex (index); + return (this->voxelSearch (search_point, point_idx_data)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::octree::OctreePointCloudSearch::nearestKSearch (const PointT &p_q, int k, + std::vector &k_indices, + std::vector &k_sqr_distances) +{ + assert(this->leaf_count_>0); + assert (isFinite (p_q) && "Invalid (NaN, Inf) point coordinates given to nearestKSearch!"); + + k_indices.clear (); + k_sqr_distances.clear (); + + if (k < 1) + return 0; + + unsigned int i; + unsigned int result_count; + + prioPointQueueEntry point_entry; + std::vector point_candidates; + + OctreeKey key; + key.x = key.y = key.z = 0; + + // initalize smallest point distance in search with high value + double smallest_dist = std::numeric_limits::max (); + + getKNearestNeighborRecursive (p_q, k, this->root_node_, key, 1, smallest_dist, point_candidates); + + result_count = static_cast (point_candidates.size ()); + + k_indices.resize (result_count); + k_sqr_distances.resize (result_count); + + for (i = 0; i < result_count; ++i) + { + k_indices [i] = point_candidates [i].point_idx_; + k_sqr_distances [i] = point_candidates [i].point_distance_; + } + + return static_cast (k_indices.size ()); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::octree::OctreePointCloudSearch::nearestKSearch (int index, int k, + std::vector &k_indices, + std::vector &k_sqr_distances) +{ + const PointT search_point = this->getPointByIndex (index); + return (nearestKSearch (search_point, k, k_indices, k_sqr_distances)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloudSearch::approxNearestSearch (const PointT &p_q, + int &result_index, + float &sqr_distance) +{ + assert(this->leaf_count_>0); + assert (isFinite (p_q) && "Invalid (NaN, Inf) point coordinates given to nearestKSearch!"); + + OctreeKey key; + key.x = key.y = key.z = 0; + + approxNearestSearchRecursive (p_q, this->root_node_, key, 1, result_index, sqr_distance); + + return; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloudSearch::approxNearestSearch (int query_index, int &result_index, + float &sqr_distance) +{ + const PointT search_point = this->getPointByIndex (query_index); + + return (approxNearestSearch (search_point, result_index, sqr_distance)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::octree::OctreePointCloudSearch::radiusSearch (const PointT &p_q, const double radius, + std::vector &k_indices, + std::vector &k_sqr_distances, + unsigned int max_nn) const +{ + assert (isFinite (p_q) && "Invalid (NaN, Inf) point coordinates given to nearestKSearch!"); + OctreeKey key; + key.x = key.y = key.z = 0; + + k_indices.clear (); + k_sqr_distances.clear (); + + getNeighborsWithinRadiusRecursive (p_q, radius * radius, this->root_node_, key, 1, k_indices, k_sqr_distances, + max_nn); + + return (static_cast (k_indices.size ())); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::octree::OctreePointCloudSearch::radiusSearch (int index, const double radius, + std::vector &k_indices, + std::vector &k_sqr_distances, + unsigned int max_nn) const +{ + const PointT search_point = this->getPointByIndex (index); + + return (radiusSearch (search_point, radius, k_indices, k_sqr_distances, max_nn)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::octree::OctreePointCloudSearch::boxSearch (const Eigen::Vector3f &min_pt, + const Eigen::Vector3f &max_pt, + std::vector &k_indices) const +{ + + OctreeKey key; + key.x = key.y = key.z = 0; + + k_indices.clear (); + + boxSearchRecursive (min_pt, max_pt, this->root_node_, key, 1, k_indices); + + return (static_cast (k_indices.size ())); + +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::octree::OctreePointCloudSearch::getKNearestNeighborRecursive ( + const PointT & point, unsigned int K, const BranchNode* node, const OctreeKey& key, unsigned int tree_depth, + const double squared_search_radius, std::vector& point_candidates) const +{ + std::vector search_heap; + search_heap.resize (8); + + unsigned char child_idx; + + OctreeKey new_key; + + double smallest_squared_dist = squared_search_radius; + + // get spatial voxel information + double voxelSquaredDiameter = this->getVoxelSquaredDiameter (tree_depth); + + // iterate over all children + for (child_idx = 0; child_idx < 8; child_idx++) + { + if (this->branchHasChild (*node, child_idx)) + { + PointT voxel_center; + + search_heap[child_idx].key.x = (key.x << 1) + (!!(child_idx & (1 << 2))); + search_heap[child_idx].key.y = (key.y << 1) + (!!(child_idx & (1 << 1))); + search_heap[child_idx].key.z = (key.z << 1) + (!!(child_idx & (1 << 0))); + + // generate voxel center point for voxel at key + this->genVoxelCenterFromOctreeKey (search_heap[child_idx].key, tree_depth, voxel_center); + + // generate new priority queue element + search_heap[child_idx].node = this->getBranchChildPtr (*node, child_idx); + search_heap[child_idx].point_distance = pointSquaredDist (voxel_center, point); + } + else + { + search_heap[child_idx].point_distance = std::numeric_limits::infinity (); + } + } + + std::sort (search_heap.begin (), search_heap.end ()); + + // iterate over all children in priority queue + // check if the distance to search candidate is smaller than the best point distance (smallest_squared_dist) + while ((!search_heap.empty ()) && (search_heap.back ().point_distance < + smallest_squared_dist + voxelSquaredDiameter / 4.0 + sqrt (smallest_squared_dist * voxelSquaredDiameter) - this->epsilon_)) + { + const OctreeNode* child_node; + + // read from priority queue element + child_node = search_heap.back ().node; + new_key = search_heap.back ().key; + + if (tree_depth < this->octree_depth_) + { + // we have not reached maximum tree depth + smallest_squared_dist = getKNearestNeighborRecursive (point, K, static_cast (child_node), new_key, tree_depth + 1, + smallest_squared_dist, point_candidates); + } + else + { + // we reached leaf node level + + float squared_dist; + size_t i; + std::vector decoded_point_vector; + + const LeafNode* child_leaf = static_cast (child_node); + + // decode leaf node into decoded_point_vector + (*child_leaf)->getPointIndices (decoded_point_vector); + + // Linearly iterate over all decoded (unsorted) points + for (i = 0; i < decoded_point_vector.size (); i++) + { + + const PointT& candidate_point = this->getPointByIndex (decoded_point_vector[i]); + + // calculate point distance to search point + squared_dist = pointSquaredDist (candidate_point, point); + + // check if a closer match is found + if (squared_dist < smallest_squared_dist) + { + prioPointQueueEntry point_entry; + + point_entry.point_distance_ = squared_dist; + point_entry.point_idx_ = decoded_point_vector[i]; + point_candidates.push_back (point_entry); + } + } + + std::sort (point_candidates.begin (), point_candidates.end ()); + + if (point_candidates.size () > K) + point_candidates.resize (K); + + if (point_candidates.size () == K) + smallest_squared_dist = point_candidates.back ().point_distance_; + } + // pop element from priority queue + search_heap.pop_back (); + } + + return (smallest_squared_dist); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloudSearch::getNeighborsWithinRadiusRecursive ( + const PointT & point, const double radiusSquared, const BranchNode* node, const OctreeKey& key, + unsigned int tree_depth, std::vector& k_indices, std::vector& k_sqr_distances, + unsigned int max_nn) const +{ + // child iterator + unsigned char child_idx; + + // get spatial voxel information + double voxel_squared_diameter = this->getVoxelSquaredDiameter (tree_depth); + + // iterate over all children + for (child_idx = 0; child_idx < 8; child_idx++) + { + if (!this->branchHasChild (*node, child_idx)) + continue; + + const OctreeNode* child_node; + child_node = this->getBranchChildPtr (*node, child_idx); + + OctreeKey new_key; + PointT voxel_center; + float squared_dist; + + // generate new key for current branch voxel + new_key.x = (key.x << 1) + (!!(child_idx & (1 << 2))); + new_key.y = (key.y << 1) + (!!(child_idx & (1 << 1))); + new_key.z = (key.z << 1) + (!!(child_idx & (1 << 0))); + + // generate voxel center point for voxel at key + this->genVoxelCenterFromOctreeKey (new_key, tree_depth, voxel_center); + + // calculate distance to search point + squared_dist = pointSquaredDist (static_cast (voxel_center), point); + + // if distance is smaller than search radius + if (squared_dist + this->epsilon_ + <= voxel_squared_diameter / 4.0 + radiusSquared + sqrt (voxel_squared_diameter * radiusSquared)) + { + + if (tree_depth < this->octree_depth_) + { + // we have not reached maximum tree depth + getNeighborsWithinRadiusRecursive (point, radiusSquared, static_cast (child_node), new_key, tree_depth + 1, + k_indices, k_sqr_distances, max_nn); + if (max_nn != 0 && k_indices.size () == static_cast (max_nn)) + return; + } + else + { + // we reached leaf node level + + size_t i; + const LeafNode* child_leaf = static_cast (child_node); + std::vector decoded_point_vector; + + // decode leaf node into decoded_point_vector + (*child_leaf)->getPointIndices (decoded_point_vector); + + // Linearly iterate over all decoded (unsorted) points + for (i = 0; i < decoded_point_vector.size (); i++) + { + const PointT& candidate_point = this->getPointByIndex (decoded_point_vector[i]); + + // calculate point distance to search point + squared_dist = pointSquaredDist (candidate_point, point); + + // check if a match is found + if (squared_dist > radiusSquared) + continue; + + // add point to result vector + k_indices.push_back (decoded_point_vector[i]); + k_sqr_distances.push_back (squared_dist); + + if (max_nn != 0 && k_indices.size () == static_cast (max_nn)) + return; + } + } + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloudSearch::approxNearestSearchRecursive (const PointT & point, + const BranchNode* node, + const OctreeKey& key, + unsigned int tree_depth, + int& result_index, + float& sqr_distance) +{ + unsigned char child_idx; + unsigned char min_child_idx; + double min_voxel_center_distance; + + OctreeKey minChildKey; + OctreeKey new_key; + + const OctreeNode* child_node; + + // set minimum voxel distance to maximum value + min_voxel_center_distance = std::numeric_limits::max (); + + min_child_idx = 0xFF; + + // iterate over all children + for (child_idx = 0; child_idx < 8; child_idx++) + { + if (!this->branchHasChild (*node, child_idx)) + continue; + + PointT voxel_center; + double voxelPointDist; + + new_key.x = (key.x << 1) + (!!(child_idx & (1 << 2))); + new_key.y = (key.y << 1) + (!!(child_idx & (1 << 1))); + new_key.z = (key.z << 1) + (!!(child_idx & (1 << 0))); + + // generate voxel center point for voxel at key + this->genVoxelCenterFromOctreeKey (new_key, tree_depth, voxel_center); + + voxelPointDist = pointSquaredDist (voxel_center, point); + + // search for child voxel with shortest distance to search point + if (voxelPointDist >= min_voxel_center_distance) + continue; + + min_voxel_center_distance = voxelPointDist; + min_child_idx = child_idx; + minChildKey = new_key; + } + + // make sure we found at least one branch child + assert(min_child_idx<8); + + child_node = this->getBranchChildPtr (*node, min_child_idx); + + if (tree_depth < this->octree_depth_) + { + // we have not reached maximum tree depth + approxNearestSearchRecursive (point, static_cast (child_node), minChildKey, tree_depth + 1, result_index, + sqr_distance); + } + else + { + // we reached leaf node level + + double squared_dist; + double smallest_squared_dist; + size_t i; + std::vector decoded_point_vector; + + const LeafNode* child_leaf = static_cast (child_node); + + smallest_squared_dist = std::numeric_limits::max (); + + // decode leaf node into decoded_point_vector + (**child_leaf).getPointIndices (decoded_point_vector); + + // Linearly iterate over all decoded (unsorted) points + for (i = 0; i < decoded_point_vector.size (); i++) + { + const PointT& candidate_point = this->getPointByIndex (decoded_point_vector[i]); + + // calculate point distance to search point + squared_dist = pointSquaredDist (candidate_point, point); + + // check if a closer match is found + if (squared_dist >= smallest_squared_dist) + continue; + + result_index = decoded_point_vector[i]; + smallest_squared_dist = squared_dist; + sqr_distance = static_cast (squared_dist); + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::octree::OctreePointCloudSearch::pointSquaredDist (const PointT & point_a, + const PointT & point_b) const +{ + return (point_a.getVector3fMap () - point_b.getVector3fMap ()).squaredNorm (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::octree::OctreePointCloudSearch::boxSearchRecursive (const Eigen::Vector3f &min_pt, + const Eigen::Vector3f &max_pt, + const BranchNode* node, + const OctreeKey& key, + unsigned int tree_depth, + std::vector& k_indices) const +{ + // child iterator + unsigned char child_idx; + + // iterate over all children + for (child_idx = 0; child_idx < 8; child_idx++) + { + + const OctreeNode* child_node; + child_node = this->getBranchChildPtr (*node, child_idx); + + if (!child_node) + continue; + + OctreeKey new_key; + // generate new key for current branch voxel + new_key.x = (key.x << 1) + (!!(child_idx & (1 << 2))); + new_key.y = (key.y << 1) + (!!(child_idx & (1 << 1))); + new_key.z = (key.z << 1) + (!!(child_idx & (1 << 0))); + + // voxel corners + Eigen::Vector3f lower_voxel_corner; + Eigen::Vector3f upper_voxel_corner; + // get voxel coordinates + this->genVoxelBoundsFromOctreeKey (new_key, tree_depth, lower_voxel_corner, upper_voxel_corner); + + // test if search region overlap with voxel space + + if ( !( (lower_voxel_corner (0) > max_pt (0)) || (min_pt (0) > upper_voxel_corner(0)) || + (lower_voxel_corner (1) > max_pt (1)) || (min_pt (1) > upper_voxel_corner(1)) || + (lower_voxel_corner (2) > max_pt (2)) || (min_pt (2) > upper_voxel_corner(2)) ) ) + { + + if (tree_depth < this->octree_depth_) + { + // we have not reached maximum tree depth + boxSearchRecursive (min_pt, max_pt, static_cast (child_node), new_key, tree_depth + 1, k_indices); + } + else + { + // we reached leaf node level + size_t i; + std::vector decoded_point_vector; + bool bInBox; + + const LeafNode* child_leaf = static_cast (child_node); + + // decode leaf node into decoded_point_vector + (**child_leaf).getPointIndices (decoded_point_vector); + + // Linearly iterate over all decoded (unsorted) points + for (i = 0; i < decoded_point_vector.size (); i++) + { + const PointT& candidate_point = this->getPointByIndex (decoded_point_vector[i]); + + // check if point falls within search box + bInBox = ( (candidate_point.x >= min_pt (0)) && (candidate_point.x <= max_pt (0)) && + (candidate_point.y >= min_pt (1)) && (candidate_point.y <= max_pt (1)) && + (candidate_point.z >= min_pt (2)) && (candidate_point.z <= max_pt (2)) ); + + if (bInBox) + // add to result vector + k_indices.push_back (decoded_point_vector[i]); + } + } + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::octree::OctreePointCloudSearch::getIntersectedVoxelCenters ( + Eigen::Vector3f origin, Eigen::Vector3f direction, AlignedPointTVector &voxel_center_list, + int max_voxel_count) const +{ + OctreeKey key; + key.x = key.y = key.z = 0; + + voxel_center_list.clear (); + + // Voxel child_idx remapping + unsigned char a = 0; + + double min_x, min_y, min_z, max_x, max_y, max_z; + + initIntersectedVoxel (origin, direction, min_x, min_y, min_z, max_x, max_y, max_z, a); + + if (std::max (std::max (min_x, min_y), min_z) < std::min (std::min (max_x, max_y), max_z)) + return getIntersectedVoxelCentersRecursive (min_x, min_y, min_z, max_x, max_y, max_z, a, this->root_node_, key, + voxel_center_list, max_voxel_count); + + return (0); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::octree::OctreePointCloudSearch::getIntersectedVoxelIndices ( + Eigen::Vector3f origin, Eigen::Vector3f direction, std::vector &k_indices, + int max_voxel_count) const +{ + OctreeKey key; + key.x = key.y = key.z = 0; + + k_indices.clear (); + + // Voxel child_idx remapping + unsigned char a = 0; + double min_x, min_y, min_z, max_x, max_y, max_z; + + initIntersectedVoxel (origin, direction, min_x, min_y, min_z, max_x, max_y, max_z, a); + + if (std::max (std::max (min_x, min_y), min_z) < std::min (std::min (max_x, max_y), max_z)) + return getIntersectedVoxelIndicesRecursive (min_x, min_y, min_z, max_x, max_y, max_z, a, this->root_node_, key, + k_indices, max_voxel_count); + return (0); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::octree::OctreePointCloudSearch::getIntersectedVoxelCentersRecursive ( + double min_x, double min_y, double min_z, double max_x, double max_y, double max_z, unsigned char a, + const OctreeNode* node, const OctreeKey& key, AlignedPointTVector &voxel_center_list, int max_voxel_count) const +{ + if (max_x < 0.0 || max_y < 0.0 || max_z < 0.0) + return (0); + + // If leaf node, get voxel center and increment intersection count + if (node->getNodeType () == LEAF_NODE) + { + PointT newPoint; + + this->genLeafNodeCenterFromOctreeKey (key, newPoint); + + voxel_center_list.push_back (newPoint); + + return (1); + } + + // Voxel intersection count for branches children + int voxel_count = 0; + + // Voxel mid lines + double mid_x = 0.5 * (min_x + max_x); + double mid_y = 0.5 * (min_y + max_y); + double mid_z = 0.5 * (min_z + max_z); + + // First voxel node ray will intersect + int curr_node = getFirstIntersectedNode (min_x, min_y, min_z, mid_x, mid_y, mid_z); + + // Child index, node and key + unsigned char child_idx; + const OctreeNode *child_node; + OctreeKey child_key; + + do + { + if (curr_node != 0) + child_idx = static_cast (curr_node ^ a); + else + child_idx = a; + + // child_node == 0 if child_node doesn't exist + child_node = this->getBranchChildPtr (static_cast (*node), child_idx); + + // Generate new key for current branch voxel + child_key.x = (key.x << 1) | (!!(child_idx & (1 << 2))); + child_key.y = (key.y << 1) | (!!(child_idx & (1 << 1))); + child_key.z = (key.z << 1) | (!!(child_idx & (1 << 0))); + + // Recursively call each intersected child node, selecting the next + // node intersected by the ray. Children that do not intersect will + // not be traversed. + + switch (curr_node) + { + case 0: + if (child_node) + voxel_count += getIntersectedVoxelCentersRecursive (min_x, min_y, min_z, mid_x, mid_y, mid_z, a, child_node, + child_key, voxel_center_list, max_voxel_count); + curr_node = getNextIntersectedNode (mid_x, mid_y, mid_z, 4, 2, 1); + break; + + case 1: + if (child_node) + voxel_count += getIntersectedVoxelCentersRecursive (min_x, min_y, mid_z, mid_x, mid_y, max_z, a, child_node, + child_key, voxel_center_list, max_voxel_count); + curr_node = getNextIntersectedNode (mid_x, mid_y, max_z, 5, 3, 8); + break; + + case 2: + if (child_node) + voxel_count += getIntersectedVoxelCentersRecursive (min_x, mid_y, min_z, mid_x, max_y, mid_z, a, child_node, + child_key, voxel_center_list, max_voxel_count); + curr_node = getNextIntersectedNode (mid_x, max_y, mid_z, 6, 8, 3); + break; + + case 3: + if (child_node) + voxel_count += getIntersectedVoxelCentersRecursive (min_x, mid_y, mid_z, mid_x, max_y, max_z, a, child_node, + child_key, voxel_center_list, max_voxel_count); + curr_node = getNextIntersectedNode (mid_x, max_y, max_z, 7, 8, 8); + break; + + case 4: + if (child_node) + voxel_count += getIntersectedVoxelCentersRecursive (mid_x, min_y, min_z, max_x, mid_y, mid_z, a, child_node, + child_key, voxel_center_list, max_voxel_count); + curr_node = getNextIntersectedNode (max_x, mid_y, mid_z, 8, 6, 5); + break; + + case 5: + if (child_node) + voxel_count += getIntersectedVoxelCentersRecursive (mid_x, min_y, mid_z, max_x, mid_y, max_z, a, child_node, + child_key, voxel_center_list, max_voxel_count); + curr_node = getNextIntersectedNode (max_x, mid_y, max_z, 8, 7, 8); + break; + + case 6: + if (child_node) + voxel_count += getIntersectedVoxelCentersRecursive (mid_x, mid_y, min_z, max_x, max_y, mid_z, a, child_node, + child_key, voxel_center_list, max_voxel_count); + curr_node = getNextIntersectedNode (max_x, max_y, mid_z, 8, 8, 7); + break; + + case 7: + if (child_node) + voxel_count += getIntersectedVoxelCentersRecursive (mid_x, mid_y, mid_z, max_x, max_y, max_z, a, child_node, + child_key, voxel_center_list, max_voxel_count); + curr_node = 8; + break; + } + } while ((curr_node < 8) && (max_voxel_count <= 0 || voxel_count < max_voxel_count)); + return (voxel_count); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::octree::OctreePointCloudSearch::getIntersectedVoxelIndicesRecursive ( + double min_x, double min_y, double min_z, double max_x, double max_y, double max_z, unsigned char a, + const OctreeNode* node, const OctreeKey& key, std::vector &k_indices, int max_voxel_count) const +{ + if (max_x < 0.0 || max_y < 0.0 || max_z < 0.0) + return (0); + + // If leaf node, get voxel center and increment intersection count + if (node->getNodeType () == LEAF_NODE) + { + const LeafNode* leaf = static_cast (node); + + // decode leaf node into k_indices + (*leaf)->getPointIndices (k_indices); + + return (1); + } + + // Voxel intersection count for branches children + int voxel_count = 0; + + // Voxel mid lines + double mid_x = 0.5 * (min_x + max_x); + double mid_y = 0.5 * (min_y + max_y); + double mid_z = 0.5 * (min_z + max_z); + + // First voxel node ray will intersect + int curr_node = getFirstIntersectedNode (min_x, min_y, min_z, mid_x, mid_y, mid_z); + + // Child index, node and key + unsigned char child_idx; + const OctreeNode *child_node; + OctreeKey child_key; + do + { + if (curr_node != 0) + child_idx = static_cast (curr_node ^ a); + else + child_idx = a; + + // child_node == 0 if child_node doesn't exist + child_node = this->getBranchChildPtr (static_cast (*node), child_idx); + // Generate new key for current branch voxel + child_key.x = (key.x << 1) | (!!(child_idx & (1 << 2))); + child_key.y = (key.y << 1) | (!!(child_idx & (1 << 1))); + child_key.z = (key.z << 1) | (!!(child_idx & (1 << 0))); + + // Recursively call each intersected child node, selecting the next + // node intersected by the ray. Children that do not intersect will + // not be traversed. + switch (curr_node) + { + case 0: + if (child_node) + voxel_count += getIntersectedVoxelIndicesRecursive (min_x, min_y, min_z, mid_x, mid_y, mid_z, a, child_node, + child_key, k_indices, max_voxel_count); + curr_node = getNextIntersectedNode (mid_x, mid_y, mid_z, 4, 2, 1); + break; + + case 1: + if (child_node) + voxel_count += getIntersectedVoxelIndicesRecursive (min_x, min_y, mid_z, mid_x, mid_y, max_z, a, child_node, + child_key, k_indices, max_voxel_count); + curr_node = getNextIntersectedNode (mid_x, mid_y, max_z, 5, 3, 8); + break; + + case 2: + if (child_node) + voxel_count += getIntersectedVoxelIndicesRecursive (min_x, mid_y, min_z, mid_x, max_y, mid_z, a, child_node, + child_key, k_indices, max_voxel_count); + curr_node = getNextIntersectedNode (mid_x, max_y, mid_z, 6, 8, 3); + break; + + case 3: + if (child_node) + voxel_count += getIntersectedVoxelIndicesRecursive (min_x, mid_y, mid_z, mid_x, max_y, max_z, a, child_node, + child_key, k_indices, max_voxel_count); + curr_node = getNextIntersectedNode (mid_x, max_y, max_z, 7, 8, 8); + break; + + case 4: + if (child_node) + voxel_count += getIntersectedVoxelIndicesRecursive (mid_x, min_y, min_z, max_x, mid_y, mid_z, a, child_node, + child_key, k_indices, max_voxel_count); + curr_node = getNextIntersectedNode (max_x, mid_y, mid_z, 8, 6, 5); + break; + + case 5: + if (child_node) + voxel_count += getIntersectedVoxelIndicesRecursive (mid_x, min_y, mid_z, max_x, mid_y, max_z, a, child_node, + child_key, k_indices, max_voxel_count); + curr_node = getNextIntersectedNode (max_x, mid_y, max_z, 8, 7, 8); + break; + + case 6: + if (child_node) + voxel_count += getIntersectedVoxelIndicesRecursive (mid_x, mid_y, min_z, max_x, max_y, mid_z, a, child_node, + child_key, k_indices, max_voxel_count); + curr_node = getNextIntersectedNode (max_x, max_y, mid_z, 8, 8, 7); + break; + + case 7: + if (child_node) + voxel_count += getIntersectedVoxelIndicesRecursive (mid_x, mid_y, mid_z, max_x, max_y, max_z, a, child_node, + child_key, k_indices, max_voxel_count); + curr_node = 8; + break; + } + } while ((curr_node < 8) && (max_voxel_count <= 0 || voxel_count < max_voxel_count)); + + return (voxel_count); +} + +#endif // PCL_OCTREE_SEARCH_IMPL_H_ diff --git a/pcl-1.7/pcl/octree/octree.h b/pcl-1.7/pcl/octree/octree.h new file mode 100644 index 0000000..15309d8 --- /dev/null +++ b/pcl-1.7/pcl/octree/octree.h @@ -0,0 +1,57 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_H +#define PCL_OCTREE_H + + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#endif diff --git a/pcl-1.7/pcl/octree/octree2buf_base.h b/pcl-1.7/pcl/octree/octree2buf_base.h new file mode 100644 index 0000000..2d6b21a --- /dev/null +++ b/pcl-1.7/pcl/octree/octree2buf_base.h @@ -0,0 +1,926 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_TREE_2BUF_BASE_H +#define PCL_OCTREE_TREE_2BUF_BASE_H + +#include + +#include "octree_nodes.h" +#include "octree_container.h" +#include "octree_key.h" +#include "octree_iterator.h" + +#include +#include + +namespace pcl +{ + namespace octree + { + + template + class BufferedBranchNode : public OctreeNode + { + + public: + /** \brief Empty constructor. */ + BufferedBranchNode () : OctreeNode() + { + reset (); + } + + /** \brief Copy constructor. */ + BufferedBranchNode (const BufferedBranchNode& source) : OctreeNode() + { + *this = source; + } + + /** \brief Copy operator. */ + inline BufferedBranchNode& + operator = (const BufferedBranchNode &source_arg) + { + + unsigned char i, b; + + memset (child_node_array_, 0, sizeof(child_node_array_)); + + for (b = 0; b < 2; ++b) + for (i = 0; i < 8; ++i) + if (source_arg.child_node_array_[b][i]) + child_node_array_[b][i] = source_arg.child_node_array_[b][i]->deepCopy (); + + return (*this); + + } + + /** \brief Empty constructor. */ + virtual ~BufferedBranchNode () + { + } + + /** \brief Method to perform a deep copy of the octree */ + virtual BufferedBranchNode* + deepCopy () const + { + return new BufferedBranchNode (*this); + } + + /** \brief Get child pointer in current branch node + * \param buffer_arg: buffer selector + * \param index_arg: index of child in node + * \return pointer to child node + * */ + inline OctreeNode* + getChildPtr (unsigned char buffer_arg, unsigned char index_arg) const + { + assert( (buffer_arg<2) && (index_arg<8)); + return child_node_array_[buffer_arg][index_arg]; + } + + /** \brief Set child pointer in current branch node + * \param buffer_arg: buffer selector + * \param index_arg: index of child in node + * \param newNode_arg: pointer to new child node + * */ + inline void setChildPtr (unsigned char buffer_arg, unsigned char index_arg, + OctreeNode* newNode_arg) + { + assert( (buffer_arg<2) && (index_arg<8)); + child_node_array_[buffer_arg][index_arg] = newNode_arg; + } + + /** \brief Check if branch is pointing to a particular child node + * \param buffer_arg: buffer selector + * \param index_arg: index of child in node + * \return "true" if pointer to child node exists; "false" otherwise + * */ + inline bool hasChild (unsigned char buffer_arg, unsigned char index_arg) const + { + assert( (buffer_arg<2) && (index_arg<8)); + return (child_node_array_[buffer_arg][index_arg] != 0); + } + + /** \brief Get the type of octree node. Returns LEAVE_NODE type */ + virtual node_type_t getNodeType () const + { + return BRANCH_NODE; + } + + /** \brief Reset branch node container for every branch buffer. */ + inline void reset () + { + memset (&child_node_array_[0][0], 0, sizeof(OctreeNode*) * 8 * 2); + } + + /** \brief Get const pointer to container */ + const ContainerT* + operator->() const + { + return &container_; + } + + /** \brief Get pointer to container */ + ContainerT* + operator-> () + { + return &container_; + } + + /** \brief Get const reference to container */ + const ContainerT& + operator* () const + { + return container_; + } + + /** \brief Get reference to container */ + ContainerT& + operator* () + { + return container_; + } + + /** \brief Get const reference to container */ + const ContainerT& + getContainer () const + { + return container_; + } + + /** \brief Get reference to container */ + ContainerT& + getContainer () + { + return container_; + } + + /** \brief Get const pointer to container */ + const ContainerT* + getContainerPtr() const + { + return &container_; + } + + /** \brief Get pointer to container */ + ContainerT* + getContainerPtr () + { + return &container_; + } + + protected: + ContainerT container_; + + OctreeNode* child_node_array_[2][8]; + }; + + /** \brief @b Octree double buffer class + * + * \note This octree implementation keeps two separate octree structures + * in memory. + * + * \note This allows for differentially compare the octree structures (change detection, differential encoding). + * \note The tree depth defines the maximum amount of octree voxels / leaf nodes (should be initially defined). + * \note All leaf nodes are addressed by integer indices. + * \note Note: The tree depth equates to the bit length of the voxel indices. + * \ingroup octree + * \author Julius Kammerl (julius@kammerl.de) + */ + template + class Octree2BufBase + { + + public: + + typedef Octree2BufBase OctreeT; + + // iterators are friends + friend class OctreeIteratorBase ; + friend class OctreeDepthFirstIterator ; + friend class OctreeBreadthFirstIterator ; + friend class OctreeLeafNodeIterator ; + + typedef BufferedBranchNode BranchNode; + typedef OctreeLeafNode LeafNode; + + typedef BranchContainerT BranchContainer; + typedef LeafContainerT LeafContainer; + + // Octree default iterators + typedef OctreeDepthFirstIterator Iterator; + typedef const OctreeDepthFirstIterator ConstIterator; + Iterator begin(unsigned int max_depth_arg = 0) {return Iterator(this, max_depth_arg);}; + const Iterator end() {return Iterator();}; + + // Octree leaf node iterators + typedef OctreeLeafNodeIterator LeafNodeIterator; + typedef const OctreeLeafNodeIterator ConstLeafNodeIterator; + LeafNodeIterator leaf_begin(unsigned int max_depth_arg = 0) {return LeafNodeIterator(this, max_depth_arg);}; + const LeafNodeIterator leaf_end() {return LeafNodeIterator();}; + + // Octree depth-first iterators + typedef OctreeDepthFirstIterator DepthFirstIterator; + typedef const OctreeDepthFirstIterator ConstDepthFirstIterator; + DepthFirstIterator depth_begin(unsigned int maxDepth_arg = 0) {return DepthFirstIterator(this, maxDepth_arg);}; + const DepthFirstIterator depth_end() {return DepthFirstIterator();}; + + // Octree breadth-first iterators + typedef OctreeBreadthFirstIterator BreadthFirstIterator; + typedef const OctreeBreadthFirstIterator ConstBreadthFirstIterator; + BreadthFirstIterator breadth_begin(unsigned int max_depth_arg = 0) {return BreadthFirstIterator(this, max_depth_arg);}; + const BreadthFirstIterator breadth_end() {return BreadthFirstIterator();}; + + /** \brief Empty constructor. */ + Octree2BufBase (); + + /** \brief Empty deconstructor. */ + virtual + ~Octree2BufBase (); + + /** \brief Copy constructor. */ + Octree2BufBase (const Octree2BufBase& source) : + leaf_count_ (source.leaf_count_), + branch_count_ (source.branch_count_), + root_node_ (new (BranchNode) (*(source.root_node_))), + depth_mask_ (source.depth_mask_), + max_key_ (source.max_key_), + buffer_selector_ (source.buffer_selector_), + tree_dirty_flag_ (source.tree_dirty_flag_), + octree_depth_ (source.octree_depth_), + dynamic_depth_enabled_(source.dynamic_depth_enabled_) + { + } + + /** \brief Copy constructor. */ + inline Octree2BufBase& + operator = (const Octree2BufBase& source) + { + leaf_count_ = source.leaf_count_; + branch_count_ = source.branch_count_; + root_node_ = new (BranchNode) (* (source.root_node_)); + depth_mask_ = source.depth_mask_; + max_key_ = source.max_key_; + buffer_selector_ = source.buffer_selector_; + tree_dirty_flag_ = source.tree_dirty_flag_; + octree_depth_ = source.octree_depth_; + dynamic_depth_enabled_ = source.dynamic_depth_enabled_; + return (*this); + } + + /** \brief Set the maximum amount of voxels per dimension. + * \param max_voxel_index_arg: maximum amount of voxels per dimension + * */ + void + setMaxVoxelIndex (unsigned int max_voxel_index_arg); + + /** \brief Set the maximum depth of the octree. + * \param depth_arg: maximum depth of octree + * */ + void + setTreeDepth (unsigned int depth_arg); + + /** \brief Get the maximum depth of the octree. + * \return depth_arg: maximum depth of octree + * */ + inline unsigned int getTreeDepth () const + { + return this->octree_depth_; + } + + /** \brief Create new leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). + * \note If leaf node already exist, this method returns the existing node + * \param idx_x_arg: index of leaf node in the X axis. + * \param idx_y_arg: index of leaf node in the Y axis. + * \param idx_z_arg: index of leaf node in the Z axis. + * \return pointer to new leaf node container. + * */ + LeafContainerT* + createLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg); + + /** \brief Find leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). + * \note If leaf node already exist, this method returns the existing node + * \param idx_x_arg: index of leaf node in the X axis. + * \param idx_y_arg: index of leaf node in the Y axis. + * \param idx_z_arg: index of leaf node in the Z axis. + * \return pointer to leaf node container if found, null pointer otherwise. + * */ + LeafContainerT* + findLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg); + + /** \brief Check for the existence of leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). + * \param idx_x_arg: index of leaf node in the X axis. + * \param idx_y_arg: index of leaf node in the Y axis. + * \param idx_z_arg: index of leaf node in the Z axis. + * \return "true" if leaf node search is successful, otherwise it returns "false". + * */ + bool + existLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg) const; + + /** \brief Remove leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). + * \param idx_x_arg: index of leaf node in the X axis. + * \param idx_y_arg: index of leaf node in the Y axis. + * \param idx_z_arg: index of leaf node in the Z axis. + * */ + void + removeLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg); + + /** \brief Return the amount of existing leafs in the octree. + * \return amount of registered leaf nodes. + * */ + inline std::size_t getLeafCount () const + { + return (leaf_count_); + } + + /** \brief Return the amount of existing branches in the octree. + * \return amount of branch nodes. + * */ + inline std::size_t getBranchCount () const + { + return (branch_count_); + } + + /** \brief Delete the octree structure and its leaf nodes. + * */ + void + deleteTree (); + + /** \brief Delete octree structure of previous buffer. */ + inline void deletePreviousBuffer () + { + treeCleanUpRecursive (root_node_); + } + + /** \brief Delete the octree structure in the current buffer. */ + inline void deleteCurrentBuffer () + { + buffer_selector_ = !buffer_selector_; + treeCleanUpRecursive (root_node_); + leaf_count_ = 0; + } + + /** \brief Switch buffers and reset current octree structure. */ + void + switchBuffers (); + + /** \brief Serialize octree into a binary output vector describing its branch node structure. + * \param binary_tree_out_arg: reference to output vector for writing binary tree structure. + * \param do_XOR_encoding_arg: select if binary tree structure should be generated based on current octree (false) of based on a XOR comparison between current and previous octree + * */ + void + serializeTree (std::vector& binary_tree_out_arg, + bool do_XOR_encoding_arg = false); + + /** \brief Serialize octree into a binary output vector describing its branch node structure and and push all DataT elements stored in the octree to a vector. + * \param binary_tree_out_arg: reference to output vector for writing binary tree structure. + * \param leaf_container_vector_arg: pointer to all LeafContainerT objects in the octree + * \param do_XOR_encoding_arg: select if binary tree structure should be generated based on current octree (false) of based on a XOR comparison between current and previous octree + * */ + void + serializeTree (std::vector& binary_tree_out_arg, + std::vector& leaf_container_vector_arg, + bool do_XOR_encoding_arg = false); + + /** \brief Outputs a vector of all DataT elements that are stored within the octree leaf nodes. + * \param leaf_container_vector_arg: vector of pointers to all LeafContainerT objects in the octree + * */ + void + serializeLeafs (std::vector& leaf_container_vector_arg); + + /** \brief Outputs a vector of all DataT elements from leaf nodes, that do not exist in the previous octree buffer. + * \param leaf_container_vector_arg: vector of pointers to all LeafContainerT objects in the octree + * */ + void + serializeNewLeafs (std::vector& leaf_container_vector_arg); + + /** \brief Deserialize a binary octree description vector and create a corresponding octree structure. Leaf nodes are initialized with getDataTByKey(..). + * \param binary_tree_in_arg: reference to input vector for reading binary tree structure. + * \param do_XOR_decoding_arg: select if binary tree structure is based on current octree (false) of based on a XOR comparison between current and previous octree + * */ + void + deserializeTree (std::vector& binary_tree_in_arg, + bool do_XOR_decoding_arg = false); + + /** \brief Deserialize a binary octree description and create a corresponding octree structure. Leaf nodes are initialized with DataT elements from the dataVector. + * \param binary_tree_in_arg: reference to inpvectoream for reading binary tree structure. + * \param leaf_container_vector_arg: vector of pointers to all LeafContainerT objects in the octree + * \param do_XOR_decoding_arg: select if binary tree structure is based on current octree (false) of based on a XOR comparison between current and previous octree + * */ + void + deserializeTree (std::vector& binary_tree_in_arg, + std::vector& leaf_container_vector_arg, + bool do_XOR_decoding_arg = false); + + protected: + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Protected octree methods based on octree keys + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Retrieve root node */ + OctreeNode* + getRootNode () const + { + return (this->root_node_); + } + + /** \brief Find leaf node + * \param key_arg: octree key addressing a leaf node. + * \return pointer to leaf container. If leaf node is not found, this pointer returns 0. + * */ + inline LeafContainerT* + findLeaf (const OctreeKey& key_arg) const + { + LeafContainerT* result = 0; + findLeafRecursive (key_arg, depth_mask_, root_node_, result); + return result; + } + + /** \brief Create a leaf node. + * \note If the leaf node at the given octree node does not exist, it will be created and added to the tree. + * \param key_arg: octree key addressing a leaf node. + * \return pointer to an existing or created leaf container. + * */ + inline LeafContainerT* + createLeaf (const OctreeKey& key_arg) + { + LeafNode* leaf_node; + BranchNode* leaf_node_parent; + + createLeafRecursive (key_arg, depth_mask_ ,root_node_, leaf_node, leaf_node_parent, false); + + LeafContainerT* ret = leaf_node->getContainerPtr(); + + return ret; + } + + /** \brief Check for leaf not existance in the octree + * \param key_arg: octree key addressing a leaf node. + * \return "true" if leaf node is found; "false" otherwise + * */ + inline bool existLeaf (const OctreeKey& key_arg) const + { + return (findLeaf(key_arg) != 0); + } + + /** \brief Remove leaf node from octree + * \param key_arg: octree key addressing a leaf node. + * */ + inline void removeLeaf (const OctreeKey& key_arg) + { + if (key_arg <= max_key_) + { + deleteLeafRecursive (key_arg, depth_mask_, root_node_); + + // we changed the octree structure -> dirty + tree_dirty_flag_ = true; + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Branch node accessor inline functions + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Check if branch is pointing to a particular child node + * \param branch_arg: reference to octree branch class + * \param child_idx_arg: index to child node + * \return "true" if pointer to child node exists; "false" otherwise + * */ + inline bool + branchHasChild (const BranchNode& branch_arg, unsigned char child_idx_arg) const + { + // test occupancyByte for child existence + return (branch_arg.getChildPtr(buffer_selector_, child_idx_arg) != 0); + } + + /** \brief Retrieve a child node pointer for child node at child_idx. + * \param branch_arg: reference to octree branch class + * \param child_idx_arg: index to child node + * \return pointer to octree child node class + */ + inline OctreeNode* + getBranchChildPtr (const BranchNode& branch_arg, + unsigned char child_idx_arg) const + { + return branch_arg.getChildPtr(buffer_selector_, child_idx_arg); + } + + /** \brief Assign new child node to branch + * \param branch_arg: reference to octree branch class + * \param child_idx_arg: index to child node + * \param new_child_arg: pointer to new child node + * */ + inline void + setBranchChildPtr (BranchNode& branch_arg, unsigned char child_idx_arg, OctreeNode* new_child_arg) + { + branch_arg.setChildPtr (buffer_selector_, child_idx_arg, new_child_arg); + } + + /** \brief Generate bit pattern reflecting the existence of child node pointers for current buffer + * \param branch_arg: reference to octree branch class + * \return a single byte with 8 bits of child node information + * */ + inline char getBranchBitPattern (const BranchNode& branch_arg) const + { + unsigned char i; + char node_bits; + + // create bit pattern + node_bits = 0; + for (i = 0; i < 8; i++) + { + const OctreeNode* child = branch_arg.getChildPtr(buffer_selector_, i); + node_bits |= static_cast ( (!!child) << i); + } + + return (node_bits); + } + + /** \brief Generate bit pattern reflecting the existence of child node pointers in specific buffer + * \param branch_arg: reference to octree branch class + * \param bufferSelector_arg: buffer selector + * \return a single byte with 8 bits of child node information + * */ + inline char getBranchBitPattern (const BranchNode& branch_arg, + unsigned char bufferSelector_arg) const + { + unsigned char i; + char node_bits; + + // create bit pattern + node_bits = 0; + for (i = 0; i < 8; i++) + { + const OctreeNode* child = branch_arg.getChildPtr(bufferSelector_arg, i); + node_bits |= static_cast ( (!!child) << i); + } + + return (node_bits); + } + + /** \brief Generate XOR bit pattern reflecting differences between the two octree buffers + * \param branch_arg: reference to octree branch class + * \return a single byte with 8 bits of child node XOR difference information + * */ + inline char getBranchXORBitPattern ( + const BranchNode& branch_arg) const + { + unsigned char i; + char node_bits[2]; + + // create bit pattern for both buffers + node_bits[0] = node_bits[1] = 0; + + for (i = 0; i < 8; i++) + { + const OctreeNode* childA = branch_arg.getChildPtr(0, i); + const OctreeNode* childB = branch_arg.getChildPtr(1, i); + + node_bits[0] |= static_cast ( (!!childA) << i); + node_bits[1] |= static_cast ( (!!childB) << i); + } + + return node_bits[0] ^ node_bits[1]; + } + + /** \brief Test if branch changed between previous and current buffer + * \param branch_arg: reference to octree branch class + * \return "true", if child node information differs between current and previous octree buffer + * */ + inline bool hasBranchChanges (const BranchNode& branch_arg) const + { + return (getBranchXORBitPattern (branch_arg) > 0); + } + + /** \brief Delete child node and all its subchilds from octree in specific buffer + * \param branch_arg: reference to octree branch class + * \param buffer_selector_arg: buffer selector + * \param child_idx_arg: index to child node + * */ + inline void deleteBranchChild (BranchNode& branch_arg, + unsigned char buffer_selector_arg, + unsigned char child_idx_arg) + { + if (branch_arg.hasChild(buffer_selector_arg, child_idx_arg)) + { + OctreeNode* branchChild = branch_arg.getChildPtr(buffer_selector_arg, child_idx_arg); + + switch (branchChild->getNodeType ()) + { + case BRANCH_NODE: + { + // free child branch recursively + deleteBranch (*static_cast (branchChild)); + + // delete unused branch + delete (branchChild); + break; + } + + case LEAF_NODE: + { + // push unused leaf to branch pool + delete (branchChild); + break; + } + default: + break; + } + + // set branch child pointer to 0 + branch_arg.setChildPtr(buffer_selector_arg, child_idx_arg, 0); + } + } + + /** \brief Delete child node and all its subchilds from octree in current buffer + * \param branch_arg: reference to octree branch class + * \param child_idx_arg: index to child node + * */ + inline void deleteBranchChild (BranchNode& branch_arg, unsigned char child_idx_arg) + { + deleteBranchChild(branch_arg, buffer_selector_, child_idx_arg); + } + + /** \brief Delete branch and all its subchilds from octree (both buffers) + * \param branch_arg: reference to octree branch class + * */ + inline void deleteBranch (BranchNode& branch_arg) + { + char i; + + // delete all branch node children + for (i = 0; i < 8; i++) + { + + if (branch_arg.getChildPtr(0, i) == branch_arg.getChildPtr(1, i)) + { + // reference was copied - there is only one child instance to be deleted + deleteBranchChild (branch_arg, 0, i); + + // remove pointers from both buffers + branch_arg.setChildPtr(0, i, 0); + branch_arg.setChildPtr(1, i, 0); + } + else + { + deleteBranchChild (branch_arg, 0, i); + deleteBranchChild (branch_arg, 1, i); + } + } + } + + /** \brief Fetch and add a new branch child to a branch class in current buffer + * \param branch_arg: reference to octree branch class + * \param child_idx_arg: index to child node + * \return pointer of new branch child to this reference + * */ + inline BranchNode* createBranchChild (BranchNode& branch_arg, + unsigned char child_idx_arg) + { + BranchNode* new_branch_child = new BranchNode(); + + branch_arg.setChildPtr (buffer_selector_, child_idx_arg, + static_cast (new_branch_child)); + + return new_branch_child; + } + + /** \brief Fetch and add a new leaf child to a branch class + * \param branch_arg: reference to octree branch class + * \param child_idx_arg: index to child node + * \return pointer of new leaf child to this reference + * */ + inline LeafNode* + createLeafChild (BranchNode& branch_arg, unsigned char child_idx_arg) + { + LeafNode* new_leaf_child = new LeafNode(); + + branch_arg.setChildPtr(buffer_selector_, child_idx_arg, new_leaf_child); + + return new_leaf_child; + } + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Recursive octree methods + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Create a leaf node at octree key. If leaf node does already exist, it is returned. + * \param key_arg: reference to an octree key + * \param depth_mask_arg: depth mask used for octree key analysis and for branch depth indicator + * \param branch_arg: current branch node + * \param return_leaf_arg: return pointer to leaf container + * \param parent_of_leaf_arg: return pointer to parent of leaf node + * \param branch_reset_arg: Reset pointer array of current branch + * \return depth mask at which leaf node was created/found + **/ + unsigned int + createLeafRecursive (const OctreeKey& key_arg, + unsigned int depth_mask_arg, + BranchNode* branch_arg, + LeafNode*& return_leaf_arg, + BranchNode*& parent_of_leaf_arg, + bool branch_reset_arg = false); + + + /** \brief Recursively search for a given leaf node and return a pointer. + * \note If leaf node does not exist, a 0 pointer is returned. + * \param key_arg: reference to an octree key + * \param depth_mask_arg: depth mask used for octree key analysis and for branch depth indicator + * \param branch_arg: current branch node + * \param result_arg: pointer to leaf container class + **/ + void + findLeafRecursive (const OctreeKey& key_arg, + unsigned int depth_mask_arg, + BranchNode* branch_arg, + LeafContainerT*& result_arg) const; + + + /** \brief Recursively search and delete leaf node + * \param key_arg: reference to an octree key + * \param depth_mask_arg: depth mask used for octree key analysis and branch depth indicator + * \param branch_arg: current branch node + * \return "true" if branch does not contain any childs; "false" otherwise. This indicates if current branch can be deleted. + **/ + bool + deleteLeafRecursive (const OctreeKey& key_arg, + unsigned int depth_mask_arg, + BranchNode* branch_arg); + + /** \brief Recursively explore the octree and output binary octree description together with a vector of leaf node DataT content. + * \param branch_arg: current branch node + * \param key_arg: reference to an octree key + * \param binary_tree_out_arg: binary output vector + * \param leaf_container_vector_arg: vector to return pointers to all leaf container in the tree. + * \param do_XOR_encoding_arg: select if binary tree structure should be generated based on current octree (false) of based on a XOR comparison between current and previous octree + * \param new_leafs_filter_arg: execute callback only for leaf nodes that did not exist in preceding buffer + **/ + void + serializeTreeRecursive (BranchNode* branch_arg, + OctreeKey& key_arg, + std::vector* binary_tree_out_arg, + typename std::vector* leaf_container_vector_arg, + bool do_XOR_encoding_arg = false, + bool new_leafs_filter_arg = false); + + /** \brief Rebuild an octree based on binary XOR octree description and DataT objects for leaf node initialization. + * \param branch_arg: current branch node + * \param depth_mask_arg: depth mask used for octree key analysis and branch depth indicator + * \param key_arg: reference to an octree key + * \param binary_tree_in_it_arg iterator of binary input data + * \param binary_tree_in_it_end_arg + * \param leaf_container_vector_it_arg: iterator pointing to leaf containter pointers to be added to a leaf node + * \param leaf_container_vector_it_end_arg: iterator pointing to leaf containter pointers pointing to last object in input container. + * \param branch_reset_arg: Reset pointer array of current branch + * \param do_XOR_decoding_arg: select if binary tree structure is based on current octree (false) of based on a XOR comparison between current and previous octree + **/ + void + deserializeTreeRecursive (BranchNode* branch_arg, + unsigned int depth_mask_arg, + OctreeKey& key_arg, + typename std::vector::const_iterator& binary_tree_in_it_arg, + typename std::vector::const_iterator& binary_tree_in_it_end_arg, + typename std::vector::const_iterator* leaf_container_vector_it_arg, + typename std::vector::const_iterator* leaf_container_vector_it_end_arg, + bool branch_reset_arg = false, + bool do_XOR_decoding_arg = false); + + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Serialization callbacks + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Callback executed for every leaf node data during serialization + **/ + virtual void serializeTreeCallback (LeafContainerT &, const OctreeKey &) + { + + } + + /** \brief Callback executed for every leaf node data during deserialization + **/ + virtual void deserializeTreeCallback (LeafContainerT&, const OctreeKey&) + { + + } + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Helpers + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Recursively explore the octree and remove unused branch and leaf nodes + * \param branch_arg: current branch node + **/ + void + treeCleanUpRecursive (BranchNode* branch_arg); + + /** \brief Helper function to calculate the binary logarithm + * \param n_arg: some value + * \return binary logarithm (log2) of argument n_arg + */ + inline double Log2 (double n_arg) + { + return log (n_arg) / log (2.0); + } + + /** \brief Test if octree is able to dynamically change its depth. This is required for adaptive bounding box adjustment. + * \return "false" - not resizeable due to XOR serialization + **/ + inline bool octreeCanResize () + { + return (false); + } + + /** \brief Prints binary representation of a byte - used for debugging + * \param data_arg - byte to be printed to stdout + **/ + inline void printBinary (char data_arg) + { + unsigned char mask = 1; // Bit mask + + // Extract the bits + for (int i = 0; i < 8; i++) + { + // Mask each bit in the byte and print it + std::cout << ((data_arg & (mask << i)) ? "1" : "0"); + } + std::cout << std::endl; + } + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Globals + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Amount of leaf nodes **/ + std::size_t leaf_count_; + + /** \brief Amount of branch nodes **/ + std::size_t branch_count_; + + /** \brief Pointer to root branch node of octree **/ + BranchNode* root_node_; + + /** \brief Depth mask based on octree depth **/ + unsigned int depth_mask_; + + /** \brief key range */ + OctreeKey max_key_; + + /** \brief Currently active octree buffer **/ + unsigned char buffer_selector_; + + // flags indicating if unused branches and leafs might exist in previous buffer + bool tree_dirty_flag_; + + /** \brief Octree depth */ + unsigned int octree_depth_; + + /** \brief Enable dynamic_depth + * \note Note that this parameter is ignored in octree2buf! */ + bool dynamic_depth_enabled_; + + }; + } +} + +//#include "impl/octree2buf_base.hpp" + +#endif + diff --git a/pcl-1.7/pcl/octree/octree_base.h b/pcl-1.7/pcl/octree/octree_base.h new file mode 100644 index 0000000..21c3d16 --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_base.h @@ -0,0 +1,600 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_TREE_BASE_H +#define PCL_OCTREE_TREE_BASE_H + +#include +#include + +#include "octree_nodes.h" +#include "octree_container.h" +#include "octree_key.h" +#include "octree_iterator.h" + +namespace pcl +{ + namespace octree + { + /** \brief Octree class + * \note The tree depth defines the maximum amount of octree voxels / leaf nodes (should be initially defined). + * \note All leaf nodes are addressed by integer indices. + * \note Note: The tree depth equates to the bit length of the voxel indices. + * \ingroup octree + * \author Julius Kammerl (julius@kammerl.de) + */ + template + class OctreeBase + { + + public: + + typedef OctreeBase OctreeT; + + typedef OctreeBranchNode BranchNode; + typedef OctreeLeafNode LeafNode; + + typedef BranchContainerT BranchContainer; + typedef LeafContainerT LeafContainer; + + // iterators are friends + friend class OctreeIteratorBase ; + friend class OctreeDepthFirstIterator ; + friend class OctreeBreadthFirstIterator ; + friend class OctreeLeafNodeIterator ; + + // Octree default iterators + typedef OctreeDepthFirstIterator Iterator; + typedef const OctreeDepthFirstIterator ConstIterator; + Iterator begin(unsigned int max_depth_arg = 0) {return Iterator(this, max_depth_arg);}; + const Iterator end() {return Iterator();}; + + // Octree leaf node iterators + typedef OctreeLeafNodeIterator LeafNodeIterator; + typedef const OctreeLeafNodeIterator ConstLeafNodeIterator; + LeafNodeIterator leaf_begin(unsigned int max_depth_arg = 0) {return LeafNodeIterator(this, max_depth_arg);}; + const LeafNodeIterator leaf_end() {return LeafNodeIterator();}; + + // Octree depth-first iterators + typedef OctreeDepthFirstIterator DepthFirstIterator; + typedef const OctreeDepthFirstIterator ConstDepthFirstIterator; + DepthFirstIterator depth_begin(unsigned int max_depth_arg = 0) {return DepthFirstIterator(this, max_depth_arg);}; + const DepthFirstIterator depth_end() {return DepthFirstIterator();}; + + // Octree breadth-first iterators + typedef OctreeBreadthFirstIterator BreadthFirstIterator; + typedef const OctreeBreadthFirstIterator ConstBreadthFirstIterator; + BreadthFirstIterator breadth_begin(unsigned int max_depth_arg = 0) {return BreadthFirstIterator(this, max_depth_arg);}; + const BreadthFirstIterator breadth_end() {return BreadthFirstIterator();}; + + + /** \brief Empty constructor. */ + OctreeBase (); + + /** \brief Empty deconstructor. */ + virtual + ~OctreeBase (); + + /** \brief Copy constructor. */ + OctreeBase (const OctreeBase& source) : + leaf_count_ (source.leaf_count_), + branch_count_ (source.branch_count_), + root_node_ (new (BranchNode) (*(source.root_node_))), + depth_mask_ (source.depth_mask_), + octree_depth_ (source.octree_depth_), + dynamic_depth_enabled_(source.dynamic_depth_enabled_), + max_key_ (source.max_key_) + { + } + + /** \brief Copy operator. */ + OctreeBase& + operator = (const OctreeBase &source) + { + leaf_count_ = source.leaf_count_; + branch_count_ = source.branch_count_; + root_node_ = new (BranchNode) (*(source.root_node_)); + depth_mask_ = source.depth_mask_; + max_key_ = source.max_key_; + octree_depth_ = source.octree_depth_; + return (*this); + } + + /** \brief Set the maximum amount of voxels per dimension. + * \param[in] max_voxel_index_arg maximum amount of voxels per dimension + */ + void + setMaxVoxelIndex (unsigned int max_voxel_index_arg); + + /** \brief Set the maximum depth of the octree. + * \param max_depth_arg: maximum depth of octree + * */ + void + setTreeDepth (unsigned int max_depth_arg); + + /** \brief Get the maximum depth of the octree. + * \return depth_arg: maximum depth of octree + * */ + unsigned int + getTreeDepth () const + { + return this->octree_depth_; + } + + /** \brief Create new leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). + * \note If leaf node already exist, this method returns the existing node + * \param idx_x_arg: index of leaf node in the X axis. + * \param idx_y_arg: index of leaf node in the Y axis. + * \param idx_z_arg: index of leaf node in the Z axis. + * \return pointer to new leaf node container. + * */ + LeafContainerT* + createLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg); + + /** \brief Find leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). + * \note If leaf node already exist, this method returns the existing node + * \param idx_x_arg: index of leaf node in the X axis. + * \param idx_y_arg: index of leaf node in the Y axis. + * \param idx_z_arg: index of leaf node in the Z axis. + * \return pointer to leaf node container if found, null pointer otherwise. + * */ + LeafContainerT* + findLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg); + + /** \brief idx_x_arg for the existence of leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). + * \param idx_x_arg: index of leaf node in the X axis. + * \param idx_y_arg: index of leaf node in the Y axis. + * \param idx_z_arg: index of leaf node in the Z axis. + * \return "true" if leaf node search is successful, otherwise it returns "false". + * */ + bool + existLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg) const ; + + /** \brief Remove leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). + * \param idx_x_arg: index of leaf node in the X axis. + * \param idx_y_arg: index of leaf node in the Y axis. + * \param idx_z_arg: index of leaf node in the Z axis. + * */ + void + removeLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg); + + /** \brief Return the amount of existing leafs in the octree. + * \return amount of registered leaf nodes. + * */ + std::size_t + getLeafCount () const + { + return leaf_count_; + } + + /** \brief Return the amount of existing branch nodes in the octree. + * \return amount of branch nodes. + * */ + std::size_t + getBranchCount () const + { + return branch_count_; + } + + /** \brief Delete the octree structure and its leaf nodes. + * */ + void + deleteTree ( ); + + /** \brief Serialize octree into a binary output vector describing its branch node structure. + * \param binary_tree_out_arg: reference to output vector for writing binary tree structure. + * */ + void + serializeTree (std::vector& binary_tree_out_arg); + + /** \brief Serialize octree into a binary output vector describing its branch node structure and push all LeafContainerT elements stored in the octree to a vector. + * \param binary_tree_out_arg: reference to output vector for writing binary tree structure. + * \param leaf_container_vector_arg: pointer to all LeafContainerT objects in the octree + * */ + void + serializeTree (std::vector& binary_tree_out_arg, std::vector& leaf_container_vector_arg); + + /** \brief Outputs a vector of all LeafContainerT elements that are stored within the octree leaf nodes. + * \param leaf_container_vector_arg: pointers to LeafContainerT vector that receives a copy of all LeafContainerT objects in the octree. + * */ + void + serializeLeafs (std::vector& leaf_container_vector_arg); + + /** \brief Deserialize a binary octree description vector and create a corresponding octree structure. Leaf nodes are initialized with getDataTByKey(..). + * \param binary_tree_input_arg: reference to input vector for reading binary tree structure. + * */ + void + deserializeTree (std::vector& binary_tree_input_arg); + + /** \brief Deserialize a binary octree description and create a corresponding octree structure. Leaf nodes are initialized with LeafContainerT elements from the dataVector. + * \param binary_tree_input_arg: reference to input vector for reading binary tree structure. + * \param leaf_container_vector_arg: pointer to container vector. + * */ + void + deserializeTree (std::vector& binary_tree_input_arg, std::vector& leaf_container_vector_arg); + + protected: + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Protected octree methods based on octree keys + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Create a leaf node + * \param key_arg: octree key addressing a leaf node. + * \return pointer to leaf node + * */ + LeafContainerT* + createLeaf (const OctreeKey& key_arg) + { + + LeafNode* leaf_node; + BranchNode* leaf_node_parent; + + createLeafRecursive (key_arg, depth_mask_ ,root_node_, leaf_node, leaf_node_parent); + + LeafContainerT* ret = leaf_node->getContainerPtr(); + + return ret; + } + + /** \brief Find leaf node + * \param key_arg: octree key addressing a leaf node. + * \return pointer to leaf node. If leaf node is not found, this pointer returns 0. + * */ + LeafContainerT* + findLeaf (const OctreeKey& key_arg) const + { + LeafContainerT* result = 0; + findLeafRecursive (key_arg, depth_mask_, root_node_, result); + return result; + } + + /** \brief Check for existance of a leaf node in the octree + * \param key_arg: octree key addressing a leaf node. + * \return "true" if leaf node is found; "false" otherwise + * */ + bool + existLeaf (const OctreeKey& key_arg) const + { + return (findLeaf(key_arg) != 0); + } + + /** \brief Remove leaf node from octree + * \param key_arg: octree key addressing a leaf node. + * */ + void + removeLeaf (const OctreeKey& key_arg) + { + if (key_arg <= max_key_) + deleteLeafRecursive (key_arg, depth_mask_, root_node_); + } + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Branch node access functions + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Retrieve root node */ + OctreeNode* + getRootNode () const + { + return this->root_node_; + } + + /** \brief Check if branch is pointing to a particular child node + * \param branch_arg: reference to octree branch class + * \param child_idx_arg: index to child node + * \return "true" if pointer to child node exists; "false" otherwise + * */ + bool + branchHasChild (const BranchNode& branch_arg, + unsigned char child_idx_arg) const + { + // test occupancyByte for child existence + return (branch_arg.getChildPtr(child_idx_arg) != 0); + } + + /** \brief Retrieve a child node pointer for child node at child_idx. + * \param branch_arg: reference to octree branch class + * \param child_idx_arg: index to child node + * \return pointer to octree child node class + */ + OctreeNode* + getBranchChildPtr (const BranchNode& branch_arg, + unsigned char child_idx_arg) const + { + return branch_arg.getChildPtr(child_idx_arg); + } + + /** \brief Assign new child node to branch + * \param branch_arg: reference to octree branch class + * \param child_idx_arg: index to child node + * \param new_child_arg: pointer to new child node + * */ + void setBranchChildPtr (BranchNode& branch_arg, + unsigned char child_idx_arg, + OctreeNode* new_child_arg) + { + branch_arg[child_idx_arg] = new_child_arg; + } + + /** \brief Generate bit pattern reflecting the existence of child node pointers + * \param branch_arg: reference to octree branch class + * \return a single byte with 8 bits of child node information + * */ + char + getBranchBitPattern (const BranchNode& branch_arg) const + { + unsigned char i; + char node_bits; + + // create bit pattern + node_bits = 0; + for (i = 0; i < 8; i++) { + const OctreeNode* child = branch_arg.getChildPtr(i); + node_bits |= static_cast ((!!child) << i); + } + + return (node_bits); + } + + /** \brief Delete child node and all its subchilds from octree + * \param branch_arg: reference to octree branch class + * \param child_idx_arg: index to child node + * */ + void + deleteBranchChild (BranchNode& branch_arg, unsigned char child_idx_arg) + { + if (branch_arg.hasChild(child_idx_arg)) + { + OctreeNode* branch_child = branch_arg[child_idx_arg]; + + switch (branch_child->getNodeType ()) + { + case BRANCH_NODE: + { + // free child branch recursively + deleteBranch (*static_cast (branch_child)); + // delete branch node + delete branch_child; + } + break; + + case LEAF_NODE: + { + // delete leaf node + delete branch_child; + break; + } + default: + break; + } + + // set branch child pointer to 0 + branch_arg[child_idx_arg] = 0; + } + } + + /** \brief Delete branch and all its subchilds from octree + * \param branch_arg: reference to octree branch class + * */ + void + deleteBranch (BranchNode& branch_arg) + { + char i; + + // delete all branch node children + for (i = 0; i < 8; i++) + deleteBranchChild (branch_arg, i); + } + + /** \brief Create and add a new branch child to a branch class + * \param branch_arg: reference to octree branch class + * \param child_idx_arg: index to child node + * \return pointer of new branch child to this reference + * */ + BranchNode* createBranchChild (BranchNode& branch_arg, + unsigned char child_idx_arg) + { + BranchNode* new_branch_child = new BranchNode(); + branch_arg[child_idx_arg] = static_cast (new_branch_child); + + return new_branch_child; + } + + /** \brief Create and add a new leaf child to a branch class + * \param branch_arg: reference to octree branch class + * \param child_idx_arg: index to child node + * \return pointer of new leaf child to this reference + * */ + LeafNode* + createLeafChild (BranchNode& branch_arg, unsigned char child_idx_arg) + { + LeafNode* new_leaf_child = new LeafNode(); + branch_arg[child_idx_arg] = static_cast (new_leaf_child); + + return new_leaf_child; + } + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Recursive octree methods + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Create a leaf node at octree key. If leaf node does already exist, it is returned. + * \param key_arg: reference to an octree key + * \param depth_mask_arg: depth mask used for octree key analysis and for branch depth indicator + * \param branch_arg: current branch node + * \param return_leaf_arg: return pointer to leaf node + * \param parent_of_leaf_arg: return pointer to parent of leaf node + * \return depth mask at which leaf node was created + **/ + unsigned int + createLeafRecursive (const OctreeKey& key_arg, + unsigned int depth_mask_arg, + BranchNode* branch_arg, + LeafNode*& return_leaf_arg, + BranchNode*& parent_of_leaf_arg); + + /** \brief Recursively search for a given leaf node and return a pointer. + * \note If leaf node does not exist, a 0 pointer is returned. + * \param key_arg: reference to an octree key + * \param depth_mask_arg: depth mask used for octree key analysis and for branch depth indicator + * \param branch_arg: current branch node + * \param result_arg: pointer to leaf node class + **/ + void + findLeafRecursive (const OctreeKey& key_arg, + unsigned int depth_mask_arg, + BranchNode* branch_arg, + LeafContainerT*& result_arg) const; + + /** \brief Recursively search and delete leaf node + * \param key_arg: reference to an octree key + * \param depth_mask_arg: depth mask used for octree key analysis and branch depth indicator + * \param branch_arg: current branch node + * \return "true" if branch does not contain any childs; "false" otherwise. This indicates if current branch can be deleted, too. + **/ + bool + deleteLeafRecursive (const OctreeKey& key_arg, + unsigned int depth_mask_arg, + BranchNode* branch_arg); + + /** \brief Recursively explore the octree and output binary octree description together with a vector of leaf node LeafContainerTs. + * \param branch_arg: current branch node + * \param key_arg: reference to an octree key + * \param binary_tree_out_arg: binary output vector + * \param leaf_container_vector_arg: writes LeafContainerT pointers to this LeafContainerT* vector. + **/ + void + serializeTreeRecursive (const BranchNode* branch_arg, + OctreeKey& key_arg, + std::vector* binary_tree_out_arg, + typename std::vector* leaf_container_vector_arg) const; + + /** \brief Recursive method for deserializing octree structure + * \param branch_arg: current branch node + * \param depth_mask_arg: depth mask used for octree key analysis and branch depth indicator + * \param key_arg: reference to an octree key + * \param binary_tree_input_it_arg: iterator to binary input vector + * \param binary_tree_input_it_end_arg: end iterator of binary input vector + * \param leaf_container_vector_it_arg: iterator pointing to current LeafContainerT object to be added to a leaf node + * \param leaf_container_vector_it_end_arg: iterator pointing to last object in LeafContainerT input vector. + **/ + void + deserializeTreeRecursive (BranchNode* branch_arg, unsigned int depth_mask_arg, OctreeKey& key_arg, + typename std::vector::const_iterator& binary_tree_input_it_arg, + typename std::vector::const_iterator& binary_tree_input_it_end_arg, + typename std::vector::const_iterator* leaf_container_vector_it_arg, + typename std::vector::const_iterator* leaf_container_vector_it_end_arg); + + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Serialization callbacks + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Callback executed for every leaf node during serialization + **/ + virtual void + serializeTreeCallback (LeafContainerT&, const OctreeKey &) const + { + + } + + /** \brief Callback executed for every leaf node during deserialization + **/ + virtual void + deserializeTreeCallback (LeafContainerT&, const OctreeKey&) + { + + } + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Helpers + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Helper function to calculate the binary logarithm + * \param n_arg: some value + * \return binary logarithm (log2) of argument n_arg + */ + double + Log2 (double n_arg) + { + return log( n_arg ) / log( 2.0 ); + } + + /** \brief Test if octree is able to dynamically change its depth. This is required for adaptive bounding box adjustment. + * \return "true" + **/ + bool + octreeCanResize () + { + return (true); + } + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Globals + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Amount of leaf nodes **/ + std::size_t leaf_count_; + + /** \brief Amount of branch nodes **/ + std::size_t branch_count_; + + /** \brief Pointer to root branch node of octree **/ + BranchNode* root_node_; + + /** \brief Depth mask based on octree depth **/ + unsigned int depth_mask_; + + /** \brief Octree depth */ + unsigned int octree_depth_; + + /** \brief Enable dynamic_depth **/ + bool dynamic_depth_enabled_; + + /** \brief key range */ + OctreeKey max_key_; + }; + } +} + +//#include "impl/octree_base.hpp" + +#endif + diff --git a/pcl-1.7/pcl/octree/octree_container.h b/pcl-1.7/pcl/octree/octree_container.h new file mode 100644 index 0000000..3b06f72 --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_container.h @@ -0,0 +1,400 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: octree_nodes.h 5596 2012-04-17 15:09:31Z jkammerl $ + */ + +#ifndef PCL_OCTREE_CONTAINER_H +#define PCL_OCTREE_CONTAINER_H + +#include +#include +#include + +#include + +namespace pcl +{ + namespace octree + { + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Octree container class that can serve as a base to construct own leaf node container classes. + * \author Julius Kammerl (julius@kammerl.de) + */ + class OctreeContainerBase + { + public: + /** \brief Empty constructor. */ + OctreeContainerBase () + { + } + + /** \brief Empty constructor. */ + OctreeContainerBase (const OctreeContainerBase&) + { + } + + /** \brief Empty deconstructor. */ + virtual + ~OctreeContainerBase () + { + } + + /** \brief Equal comparison operator + */ + virtual bool + operator== (const OctreeContainerBase&) const + { + return false; + } + + /** \brief Inequal comparison operator + * \param[in] other OctreeContainerBase to compare with + */ + bool + operator!= (const OctreeContainerBase& other) const + { + return (!operator== (other)); + } + + /** \brief Pure abstract method to get size of container (number of indices) + * \return number of points/indices stored in leaf node container. + */ + virtual size_t + getSize () const + { + return 0u; + } + + /** \brief Pure abstract reset leaf node implementation. */ + virtual void + reset () = 0; + + /** \brief Empty addPointIndex implementation. This leaf node does not store any point indices. + */ + void + addPointIndex (const int&) + { + } + + /** \brief Empty getPointIndex implementation as this leaf node does not store any point indices. + */ + void + getPointIndex (int&) const + { + } + + /** \brief Empty getPointIndices implementation as this leaf node does not store any data. \ + */ + void + getPointIndices (std::vector&) const + { + } + + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Octree container class that does not store any information. + * \note Can be used for occupancy trees that are used for checking only the existence of leaf nodes in the tree + * \author Julius Kammerl (julius@kammerl.de) + */ + + class OctreeContainerEmpty : public OctreeContainerBase + { + public: + /** \brief Empty constructor. */ + OctreeContainerEmpty () : + OctreeContainerBase () + { + } + + /** \brief Empty constructor. */ + OctreeContainerEmpty (const OctreeContainerEmpty&) : + OctreeContainerBase () + { + } + + /** \brief Empty deconstructor. */ + virtual + ~OctreeContainerEmpty () + { + } + + /** \brief Octree deep copy method */ + virtual OctreeContainerEmpty * + deepCopy () const + { + return (new OctreeContainerEmpty (*this)); + } + + /** \brief Abstract get size of container (number of DataT objects) + * \return number of DataT elements in leaf node container. + */ + virtual size_t + getSize () const + { + return 0; + } + + /** \brief Abstract reset leaf node implementation. */ + virtual void + reset () + { + + } + + /** \brief Empty addPointIndex implementation. This leaf node does not store any point indices. + */ + void + addPointIndex (int) + { + } + + /** \brief Empty getPointIndex implementation as this leaf node does not store any point indices. + */ + int + getPointIndex () const + { + assert("getPointIndex: undefined point index"); + return -1; + } + + /** \brief Empty getPointIndices implementation as this leaf node does not store any data. \ + */ + void + getPointIndices (std::vector&) const + { + } + + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Octree container class that does store a single point index. + * \note Enables the octree to store a single DataT element within its leaf nodes. + * \author Julius Kammerl (julius@kammerl.de) + */ + class OctreeContainerPointIndex : public OctreeContainerBase + { + public: + /** \brief Empty constructor. */ + OctreeContainerPointIndex () : + OctreeContainerBase (), data_ () + { + reset (); + } + + /** \brief Empty constructor. */ + OctreeContainerPointIndex (const OctreeContainerPointIndex& source) : + OctreeContainerBase (), data_ (source.data_) + { + } + + /** \brief Empty deconstructor. */ + virtual + ~OctreeContainerPointIndex () + { + } + + /** \brief Octree deep copy method */ + virtual OctreeContainerPointIndex* + deepCopy () const + { + return (new OctreeContainerPointIndex (*this)); + } + + /** \brief Equal comparison operator + * \param[in] other OctreeContainerBase to compare with + */ + virtual bool + operator== (const OctreeContainerBase& other) const + { + const OctreeContainerPointIndex* otherConDataT = dynamic_cast (&other); + + return (this->data_ == otherConDataT->data_); + } + + /** \brief Add point index to container memory. This container stores a only a single point index. + * \param[in] data_arg index to be stored within leaf node. + */ + void + addPointIndex (int data_arg) + { + data_ = data_arg; + } + + /** \brief Retrieve point index from container. This container stores a only a single point index + * \return index stored within container. + */ + int + getPointIndex () const + { + return data_; + } + + /** \brief Retrieve point indices from container. This container stores only a single point index + * \param[out] data_vector_arg vector of point indices to be stored within data vector + */ + void + getPointIndices (std::vector& data_vector_arg) const + { + if (data_>=0) + data_vector_arg.push_back (data_); + } + + /** \brief Get size of container (number of DataT objects) + * \return number of DataT elements in leaf node container. + */ + size_t + getSize () const + { + return data_<0 ? 0 : 1; + } + + /** \brief Reset leaf node memory to zero. */ + virtual void + reset () + { + data_ = -1; + } + protected: + /** \brief Point index stored in octree. */ + int data_; + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Octree container class that does store a vector of point indices. + * \note Enables the octree to store multiple DataT elements within its leaf nodes. + * \author Julius Kammerl (julius@kammerl.de) + */ + class OctreeContainerPointIndices : public OctreeContainerBase + { + public: + /** \brief Empty constructor. */ + OctreeContainerPointIndices () : + OctreeContainerBase (), leafDataTVector_ () + { + } + + /** \brief Empty constructor. */ + OctreeContainerPointIndices (const OctreeContainerPointIndices& source) : + OctreeContainerBase (), leafDataTVector_ (source.leafDataTVector_) + { + } + + /** \brief Empty deconstructor. */ + virtual + ~OctreeContainerPointIndices () + { + } + + /** \brief Octree deep copy method */ + virtual OctreeContainerPointIndices * + deepCopy () const + { + return (new OctreeContainerPointIndices (*this)); + } + + /** \brief Equal comparison operator + * \param[in] other OctreeContainerDataTVector to compare with + */ + virtual bool + operator== (const OctreeContainerBase& other) const + { + const OctreeContainerPointIndices* otherConDataTVec = dynamic_cast (&other); + + return (this->leafDataTVector_ == otherConDataTVec->leafDataTVector_); + } + + /** \brief Add point index to container memory. This container stores a vector of point indices. + * \param[in] data_arg index to be stored within leaf node. + */ + void + addPointIndex (int data_arg) + { + leafDataTVector_.push_back (data_arg); + } + + /** \brief Retrieve point index from container. This container stores a vector of point indices. + * \return index stored within container. + */ + int + getPointIndex ( ) const + { + return leafDataTVector_.back (); + } + + /** \brief Retrieve point indices from container. This container stores a vector of point indices. + * \param[out] data_vector_arg vector of point indices to be stored within data vector + */ + void + getPointIndices (std::vector& data_vector_arg) const + { + data_vector_arg.insert (data_vector_arg.end (), leafDataTVector_.begin (), leafDataTVector_.end ()); + } + + /** \brief Retrieve reference to point indices vector. This container stores a vector of point indices. + * \return reference to vector of point indices to be stored within data vector + */ + std::vector& + getPointIndicesVector () + { + return leafDataTVector_; + } + + /** \brief Get size of container (number of indices) + * \return number of point indices in container. + */ + size_t + getSize () const + { + return leafDataTVector_.size (); + } + + /** \brief Reset leaf node. Clear DataT vector.*/ + virtual void + reset () + { + leafDataTVector_.clear (); + } + + protected: + /** \brief Leaf node DataT vector. */ + std::vector leafDataTVector_; + }; + + } +} + +#endif diff --git a/pcl-1.7/pcl/octree/octree_impl.h b/pcl-1.7/pcl/octree/octree_impl.h new file mode 100644 index 0000000..54a495c --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_impl.h @@ -0,0 +1,50 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_IMPL_H +#define PCL_OCTREE_IMPL_H + +#include + +#include +#include +#include +#include +#include + +#endif diff --git a/pcl-1.7/pcl/octree/octree_iterator.h b/pcl-1.7/pcl/octree/octree_iterator.h new file mode 100644 index 0000000..0bcb565 --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_iterator.h @@ -0,0 +1,621 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_ITERATOR_H +#define PCL_OCTREE_ITERATOR_H + +#include +#include +#include + +#include "octree_nodes.h" +#include "octree_key.h" + +#include +#include + +#include + +// Ignore warnings in the above headers +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +namespace pcl +{ + namespace octree + { + + // Octree iterator state pushed on stack/list + struct IteratorState{ + OctreeNode* node_; + OctreeKey key_; + unsigned char depth_; + }; + + + /** \brief @b Abstract octree iterator class + * \note Octree iterator base class + * \ingroup octree + * \author Julius Kammerl (julius@kammerl.de) + */ + template + class OctreeIteratorBase : public std::iterator + { + public: + + typedef typename OctreeT::LeafNode LeafNode; + typedef typename OctreeT::BranchNode BranchNode; + + typedef typename OctreeT::LeafContainer LeafContainer; + typedef typename OctreeT::BranchContainer BranchContainer; + + /** \brief Empty constructor. + */ + explicit + OctreeIteratorBase (unsigned int max_depth_arg = 0) : + octree_ (0), current_state_(0), max_octree_depth_(max_depth_arg) + { + this->reset (); + } + + /** \brief Constructor. + * \param[in] octree_arg Octree to be iterated. Initially the iterator is set to its root node. + * \param[in] max_depth_arg Depth limitation during traversal + */ + explicit + OctreeIteratorBase (OctreeT* octree_arg, unsigned int max_depth_arg = 0) : + octree_ (octree_arg), current_state_(0), max_octree_depth_(max_depth_arg) + { + this->reset (); + } + + /** \brief Copy constructor. + * \param[in] src the iterator to copy into this + * \param[in] max_depth_arg Depth limitation during traversal + */ + OctreeIteratorBase (const OctreeIteratorBase& src, unsigned int max_depth_arg = 0) : + octree_ (src.octree_), current_state_(0), max_octree_depth_(max_depth_arg) + { + } + + /** \brief Copy operator. + * \param[in] src the iterator to copy into this + */ + inline OctreeIteratorBase& + operator = (const OctreeIteratorBase& src) + { + octree_ = src.octree_; + current_state_ = src.current_state_; + max_octree_depth_ = src.max_octree_depth_; + return (*this); + } + + /** \brief Empty deconstructor. */ + virtual + ~OctreeIteratorBase () + { + } + + /** \brief Equal comparison operator + * \param[in] other OctreeIteratorBase to compare with + */ + bool operator==(const OctreeIteratorBase& other) const + { + return (( octree_ ==other.octree_) && + ( current_state_ == other.current_state_) && + ( max_octree_depth_ == other.max_octree_depth_) ); + } + + /** \brief Inequal comparison operator + * \param[in] other OctreeIteratorBase to compare with + */ + bool operator!=(const OctreeIteratorBase& other) const + { + return (( octree_ !=other.octree_) && + ( current_state_ != other.current_state_) && + ( max_octree_depth_ != other.max_octree_depth_) ); + } + + /** \brief Reset iterator */ + inline void reset () + { + current_state_ = 0; + if (octree_ && (!max_octree_depth_)) + { + max_octree_depth_ = octree_->getTreeDepth(); + } + } + + /** \brief Get octree key for the current iterator octree node + * \return octree key of current node + */ + inline const OctreeKey& + getCurrentOctreeKey () const + { + assert(octree_!=0); + assert(current_state_!=0); + + return (current_state_->key_); + } + + /** \brief Get the current depth level of octree + * \return depth level + */ + inline unsigned int + getCurrentOctreeDepth () const + { + assert(octree_!=0); + assert(current_state_!=0); + + return (current_state_->depth_); + } + + /** \brief Get the current octree node + * \return pointer to current octree node + */ + inline OctreeNode* + getCurrentOctreeNode () const + { + assert(octree_!=0); + assert(current_state_!=0); + + return (current_state_->node_); + } + + + /** \brief check if current node is a branch node + * \return true if current node is a branch node, false otherwise + */ + inline bool + isBranchNode () const + { + assert(octree_!=0); + assert(current_state_!=0); + + return (current_state_->node_->getNodeType () == BRANCH_NODE); + } + + /** \brief check if current node is a branch node + * \return true if current node is a branch node, false otherwise + */ + inline bool + isLeafNode () const + { + assert(octree_!=0); + assert(current_state_!=0); + + return (current_state_->node_->getNodeType () == LEAF_NODE); + } + + /** \brief *operator. + * \return pointer to the current octree node + */ + inline OctreeNode* + operator* () const + { // return designated object + if (octree_ && current_state_) + { + return (current_state_->node_); + } else + { + return 0; + } + } + + /** \brief Get bit pattern of children configuration of current node + * \return bit pattern (byte) describing the existence of 8 children of the current node + */ + inline char + getNodeConfiguration () const + { + char ret = 0; + + assert(octree_!=0); + assert(current_state_!=0); + + if (isBranchNode ()) + { + + // current node is a branch node + const BranchNode* current_branch = static_cast (current_state_->node_); + + // get child configuration bit pattern + ret = octree_->getBranchBitPattern (*current_branch); + + } + + return (ret); + } + + /** \brief Method for retrieving a single leaf container from the octree leaf node + * \return Reference to container class of leaf node. + */ + const LeafContainer& + getLeafContainer () const + { + assert(octree_!=0); + assert(current_state_!=0); + assert(this->isLeafNode()); + + LeafNode* leaf_node = static_cast(current_state_->node_); + + return leaf_node->getContainer(); + } + + /** \brief Method for retrieving a single leaf container from the octree leaf node + * \return Reference to container class of leaf node. + */ + LeafContainer& + getLeafContainer () + { + assert(octree_!=0); + assert(current_state_!=0); + assert(this->isLeafNode()); + + LeafNode* leaf_node = static_cast(current_state_->node_); + + return leaf_node->getContainer(); + } + + /** \brief Method for retrieving the container from an octree branch node + * \return BranchContainer. + */ + const BranchContainer& + getBranchContainer () const + { + assert(octree_!=0); + assert(current_state_!=0); + assert(this->isBranchNode()); + + BranchNode* branch_node = static_cast(current_state_->node_); + + return branch_node->getContainer(); + } + + /** \brief Method for retrieving the container from an octree branch node + * \return BranchContainer. + */ + BranchContainer& + getBranchContainer () + { + assert(octree_!=0); + assert(current_state_!=0); + assert(this->isBranchNode()); + + BranchNode* branch_node = static_cast(current_state_->node_); + + return branch_node->getContainer(); + } + + /** \brief get a integer identifier for current node (note: identifier depends on tree depth). + * \return node id. + */ + virtual unsigned long + getNodeID () const + { + unsigned long id = 0; + + assert(octree_!=0); + assert(current_state_!=0); + + if (current_state_) + { + const OctreeKey& key = getCurrentOctreeKey(); + // calculate integer id with respect to octree key + unsigned int depth = octree_->getTreeDepth (); + id = key.x << (depth * 2) | key.y << (depth * 1) | key.z << (depth * 0); + } + + return id; + } + + protected: + /** \brief Reference to octree class. */ + OctreeT* octree_; + + /** \brief Pointer to current iterator state. */ + IteratorState* current_state_; + + /** \brief Maximum octree depth */ + unsigned int max_octree_depth_; + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Octree iterator class + * \note This class implements a forward iterator for traversing octrees in a depth-first manner. + * \ingroup octree + * \author Julius Kammerl (julius@kammerl.de) + */ + template + class OctreeDepthFirstIterator : public OctreeIteratorBase + { + + public: + + typedef typename OctreeIteratorBase::LeafNode LeafNode; + typedef typename OctreeIteratorBase::BranchNode BranchNode; + + /** \brief Empty constructor. + * \param[in] max_depth_arg Depth limitation during traversal + */ + explicit + OctreeDepthFirstIterator (unsigned int max_depth_arg = 0); + + /** \brief Constructor. + * \param[in] octree_arg Octree to be iterated. Initially the iterator is set to its root node. + * \param[in] max_depth_arg Depth limitation during traversal + */ + explicit + OctreeDepthFirstIterator (OctreeT* octree_arg, unsigned int max_depth_arg = 0); + + /** \brief Empty deconstructor. */ + virtual + ~OctreeDepthFirstIterator (); + + /** \brief Copy operator. + * \param[in] src the iterator to copy into this + */ + inline OctreeDepthFirstIterator& + operator = (const OctreeDepthFirstIterator& src) + { + + OctreeIteratorBase::operator=(src); + + stack_ = src.stack_; + + if (stack_.size()) + { + this->current_state_ = &stack_.back(); + } else + { + this->current_state_ = 0; + } + + return (*this); + } + + /** \brief Reset the iterator to the root node of the octree + */ + virtual void + reset (); + + /** \brief Preincrement operator. + * \note recursively step to next octree node + */ + OctreeDepthFirstIterator& + operator++ (); + + /** \brief postincrement operator. + * \note recursively step to next octree node + */ + inline OctreeDepthFirstIterator + operator++ (int) + { + OctreeDepthFirstIterator _Tmp = *this; + ++*this; + return (_Tmp); + } + + /** \brief Skip all child voxels of current node and return to parent node. + */ + void + skipChildVoxels (); + + protected: + /** Stack structure. */ + std::vector stack_; + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Octree iterator class + * \note This class implements a forward iterator for traversing octrees in a breadth-first manner. + * \ingroup octree + * \author Julius Kammerl (julius@kammerl.de) + */ + template + class OctreeBreadthFirstIterator : public OctreeIteratorBase + { + // public typedefs + typedef typename OctreeIteratorBase::BranchNode BranchNode; + typedef typename OctreeIteratorBase::LeafNode LeafNode; + + + public: + /** \brief Empty constructor. + * \param[in] max_depth_arg Depth limitation during traversal + */ + explicit + OctreeBreadthFirstIterator (unsigned int max_depth_arg = 0); + + /** \brief Constructor. + * \param[in] octree_arg Octree to be iterated. Initially the iterator is set to its root node. + * \param[in] max_depth_arg Depth limitation during traversal + */ + explicit + OctreeBreadthFirstIterator (OctreeT* octree_arg, unsigned int max_depth_arg = 0); + + /** \brief Empty deconstructor. */ + virtual + ~OctreeBreadthFirstIterator (); + + /** \brief Copy operator. + * \param[in] src the iterator to copy into this + */ + inline OctreeBreadthFirstIterator& + operator = (const OctreeBreadthFirstIterator& src) + { + + OctreeIteratorBase::operator=(src); + + FIFO_ = src.FIFO_; + + if (FIFO_.size()) + { + this->current_state_ = &FIFO_.front(); + } else + { + this->current_state_ = 0; + } + + return (*this); + } + + /** \brief Reset the iterator to the root node of the octree + */ + void + reset (); + + /** \brief Preincrement operator. + * \note step to next octree node + */ + OctreeBreadthFirstIterator& + operator++ (); + + /** \brief postincrement operator. + * \note step to next octree node + */ + inline OctreeBreadthFirstIterator + operator++ (int) + { + OctreeBreadthFirstIterator _Tmp = *this; + ++*this; + return (_Tmp); + } + + protected: + /** FIFO list */ + std::deque FIFO_; + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Octree leaf node iterator class + * \note This class implements a forward iterator for traversing the leaf nodes of an octree data structure. + * \ingroup octree + * \author Julius Kammerl (julius@kammerl.de) + */ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template + class OctreeLeafNodeIterator : public OctreeDepthFirstIterator + { + typedef typename OctreeDepthFirstIterator::BranchNode BranchNode; + typedef typename OctreeDepthFirstIterator::LeafNode LeafNode; + + public: + /** \brief Empty constructor. + * \param[in] max_depth_arg Depth limitation during traversal + */ + explicit + OctreeLeafNodeIterator (unsigned int max_depth_arg = 0) : + OctreeDepthFirstIterator (max_depth_arg) + { + reset (); + } + + /** \brief Constructor. + * \param[in] octree_arg Octree to be iterated. Initially the iterator is set to its root node. + * \param[in] max_depth_arg Depth limitation during traversal + */ + explicit + OctreeLeafNodeIterator (OctreeT* octree_arg, unsigned int max_depth_arg = 0) : + OctreeDepthFirstIterator (octree_arg, max_depth_arg) + { + reset (); + } + + /** \brief Empty deconstructor. */ + virtual + ~OctreeLeafNodeIterator () + { + } + + /** \brief Reset the iterator to the root node of the octree + */ + inline void + reset () + { + OctreeDepthFirstIterator::reset (); + this->operator++ (); + } + + /** \brief Preincrement operator. + * \note recursively step to next octree leaf node + */ + inline OctreeLeafNodeIterator& + operator++ () + { + do + { + OctreeDepthFirstIterator::operator++ (); + } while ((this->current_state_) && (this->current_state_->node_->getNodeType () != LEAF_NODE)); + + return (*this); + } + + /** \brief postincrement operator. + * \note step to next octree node + */ + inline OctreeLeafNodeIterator + operator++ (int) + { + OctreeLeafNodeIterator _Tmp = *this; + ++*this; + return (_Tmp); + } + + /** \brief *operator. + * \return pointer to the current octree leaf node + */ + OctreeNode* + operator* () const + { + // return designated object + OctreeNode* ret = 0; + + if (this->current_state_ && (this->current_state_->node_->getNodeType () == LEAF_NODE)) + ret = this->current_state_->node_; + return (ret); + } + }; + + } +} + +#endif + diff --git a/pcl-1.7/pcl/octree/octree_key.h b/pcl-1.7/pcl/octree/octree_key.h new file mode 100644 index 0000000..704323c --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_key.h @@ -0,0 +1,156 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_OCTREE_KEY_H +#define PCL_OCTREE_KEY_H + +#include + +namespace pcl +{ + namespace octree + { + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Octree key class + * \note Octree keys contain integer indices for each coordinate axis in order to address an octree leaf node. + * \author Julius Kammerl (julius@kammerl.de) + */ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + class OctreeKey + { + public: + + /** \brief Empty constructor. */ + OctreeKey () : + x (0), y (0), z (0) + { + } + + /** \brief Constructor for key initialization. */ + OctreeKey (unsigned int keyX, unsigned int keyY, unsigned int keyZ) : + x (keyX), y (keyY), z (keyZ) + { + } + + /** \brief Copy constructor. */ + OctreeKey (const OctreeKey& source) + { + memcpy(key_, source.key_, sizeof(key_)); + } + + /** \brief Operator== for comparing octree keys with each other. + * \return "true" if leaf node indices are identical; "false" otherwise. + * */ + bool + operator == (const OctreeKey& b) const + { + return ((b.x == this->x) && (b.y == this->y) && (b.z == this->z)); + } + + /** \brief Operator<= for comparing octree keys with each other. + * \return "true" if key indices are not greater than the key indices of b ; "false" otherwise. + * */ + bool + operator <= (const OctreeKey& b) const + { + return ((b.x >= this->x) && (b.y >= this->y) && (b.z >= this->z)); + } + + /** \brief Operator>= for comparing octree keys with each other. + * \return "true" if key indices are not smaller than the key indices of b ; "false" otherwise. + * */ + bool + operator >= (const OctreeKey& b) const + { + return ((b.x <= this->x) && (b.y <= this->y) && (b.z <= this->z)); + } + + /** \brief push a child node to the octree key + * \param[in] childIndex index of child node to be added (0-7) + * */ + inline void + pushBranch (unsigned char childIndex) + { + this->x = (this->x << 1) | (!!(childIndex & (1 << 2))); + this->y = (this->y << 1) | (!!(childIndex & (1 << 1))); + this->z = (this->z << 1) | (!!(childIndex & (1 << 0))); + } + + /** \brief pop child node from octree key + * */ + inline void + popBranch () + { + this->x >>= 1; + this->y >>= 1; + this->z >>= 1; + } + + /** \brief get child node index using depthMask + * \param[in] depthMask bit mask with single bit set at query depth + * \return child node index + * */ + inline unsigned char + getChildIdxWithDepthMask (unsigned int depthMask) const + { + return static_cast (((!!(this->x & depthMask)) << 2) + | ((!!(this->y & depthMask)) << 1) + | (!!(this->z & depthMask))); + } + + /* \brief maximum depth that can be addressed */ + static const unsigned char maxDepth = static_cast(sizeof(uint32_t)*8); + + // Indices addressing a voxel at (X, Y, Z) + + union + { + struct + { + uint32_t x; + uint32_t y; + uint32_t z; + }; + uint32_t key_[3]; + }; + + + }; + } +} + +#endif diff --git a/pcl-1.7/pcl/octree/octree_nodes.h b/pcl-1.7/pcl/octree/octree_nodes.h new file mode 100644 index 0000000..d9b2689 --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_nodes.h @@ -0,0 +1,403 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_NODE_H +#define PCL_OCTREE_NODE_H + +#include + +#include +#include + +#include + +#include + +#include + +#include "octree_container.h" + +namespace pcl +{ + namespace octree + { + + // enum of node types within the octree + enum node_type_t + { + BRANCH_NODE, LEAF_NODE + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Abstract octree node class + * \note Every octree node should implement the getNodeType () method + * \author Julius Kammerl (julius@kammerl.de) + */ + class PCL_EXPORTS OctreeNode + { + public: + + OctreeNode () + { + } + + virtual + ~OctreeNode () + { + } + /** \brief Pure virtual method for receiving the type of octree node (branch or leaf) */ + virtual node_type_t + getNodeType () const = 0; + + /** \brief Pure virtual method to perform a deep copy of the octree */ + virtual OctreeNode* + deepCopy () const = 0; + + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Abstract octree leaf class + * \note Octree leafs may collect data of type DataT + * \author Julius Kammerl (julius@kammerl.de) + */ + + template + class OctreeLeafNode : public OctreeNode + { + public: + + /** \brief Empty constructor. */ + OctreeLeafNode () : + OctreeNode () + { + } + + /** \brief Copy constructor. */ + OctreeLeafNode (const OctreeLeafNode& source) : + OctreeNode () + { + container_ = source.container_; + } + + /** \brief Empty deconstructor. */ + virtual + ~OctreeLeafNode () + { + } + + /** \brief Method to perform a deep copy of the octree */ + virtual OctreeLeafNode* + deepCopy () const + { + return new OctreeLeafNode (*this); + } + + /** \brief Get the type of octree node. Returns LEAVE_NODE type */ + virtual node_type_t + getNodeType () const + { + return LEAF_NODE; + } + + /** \brief Get const pointer to container */ + const ContainerT* + operator->() const + { + return &container_; + } + + /** \brief Get pointer to container */ + ContainerT* + operator-> () + { + return &container_; + } + + /** \brief Get const reference to container */ + const ContainerT& + operator* () const + { + return container_; + } + + /** \brief Get reference to container */ + ContainerT& + operator* () + { + return container_; + } + + /** \brief Get const reference to container */ + const ContainerT& + getContainer () const + { + return container_; + } + + /** \brief Get reference to container */ + ContainerT& + getContainer () + { + return container_; + } + + /** \brief Get const pointer to container */ + const ContainerT* + getContainerPtr() const + { + return &container_; + } + + /** \brief Get pointer to container */ + ContainerT* + getContainerPtr () + { + return &container_; + } + + protected: + ContainerT container_; + + public: + //Type ContainerT may have fixed-size Eigen objects inside + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Abstract octree branch class + * \note Octree branch classes may collect data of type DataT + * \author Julius Kammerl (julius@kammerl.de) + */ + template + class OctreeBranchNode : public OctreeNode + { + public: + + /** \brief Empty constructor. */ + OctreeBranchNode () : + OctreeNode() + { + // reset pointer to child node vectors + memset (child_node_array_, 0, sizeof(child_node_array_)); + } + + /** \brief Empty constructor. */ + OctreeBranchNode (const OctreeBranchNode& source) : + OctreeNode() + { + unsigned char i; + + memset (child_node_array_, 0, sizeof(child_node_array_)); + + for (i = 0; i < 8; ++i) + if (source.child_node_array_[i]) + child_node_array_[i] = source.child_node_array_[i]->deepCopy (); + } + + /** \brief Copy operator. */ + inline OctreeBranchNode& + operator = (const OctreeBranchNode &source) + { + unsigned char i; + + memset (child_node_array_, 0, sizeof(child_node_array_)); + + for (i = 0; i < 8; ++i) + if (source.child_node_array_[i]) + child_node_array_[i] = source.child_node_array_[i]->deepCopy (); + return (*this); + } + + /** \brief Octree deep copy method */ + virtual OctreeBranchNode* + deepCopy () const + { + return (new OctreeBranchNode (*this)); + } + + /** \brief Empty deconstructor. */ + virtual + ~OctreeBranchNode () + { + } + + /** \brief Access operator. + * \param child_idx_arg: index to child node + * \return OctreeNode pointer + * */ + inline OctreeNode*& + operator[] (unsigned char child_idx_arg) + { + assert(child_idx_arg < 8); + return child_node_array_[child_idx_arg]; + } + + /** \brief Get pointer to child + * \param child_idx_arg: index to child node + * \return OctreeNode pointer + * */ + inline OctreeNode* + getChildPtr (unsigned char child_idx_arg) const + { + assert(child_idx_arg < 8); + return child_node_array_[child_idx_arg]; + } + + /** \brief Get pointer to child + * \return OctreeNode pointer + * */ + inline void setChildPtr (OctreeNode* child, unsigned char index) + { + assert(index < 8); + child_node_array_[index] = child; + } + + + /** \brief Check if branch is pointing to a particular child node + * \param child_idx_arg: index to child node + * \return "true" if pointer to child node exists; "false" otherwise + * */ + inline bool hasChild (unsigned char child_idx_arg) const + { + return (child_node_array_[child_idx_arg] != 0); + } + + + /** \brief Check if branch can be pruned + * \note if all children are leaf nodes AND contain identical containers, branch can be pruned + * \return "true" if branch can be pruned; "false" otherwise + * */ + /* inline bool isPrunable () const + { + const OctreeNode* firstChild = child_node_array_[0]; + if (!firstChild || firstChild->getNodeType()==BRANCH_NODE) + return false; + + bool prunable = true; + for (unsigned char i = 1; i < 8 && prunable; ++i) + { + const OctreeNode* child = child_node_array_[i]; + if ( (!child) || + (child->getNodeType()==BRANCH_NODE) || + ((*static_cast(child)) == (*static_cast(child)) ) ) + prunable = false; + } + + return prunable; + }*/ + + /** \brief Get the type of octree node. Returns LEAVE_NODE type */ + virtual node_type_t + getNodeType () const + { + return BRANCH_NODE; + } + + // reset node + void reset() + { + memset(child_node_array_, 0, sizeof(child_node_array_)); + container_.reset(); + } + + + /** \brief Get const pointer to container */ + const ContainerT* + operator->() const + { + return &container_; + } + + /** \brief Get pointer to container */ + ContainerT* + operator-> () + { + return &container_; + } + + /** \brief Get const reference to container */ + const ContainerT& + operator* () const + { + return container_; + } + + /** \brief Get reference to container */ + ContainerT& + operator* () + { + return container_; + } + + /** \brief Get const reference to container */ + const ContainerT& + getContainer () const + { + return container_; + } + + /** \brief Get reference to container */ + ContainerT& + getContainer () + { + return container_; + } + + /** \brief Get const pointer to container */ + const ContainerT* + getContainerPtr() const + { + return &container_; + } + + /** \brief Get pointer to container */ + ContainerT* + getContainerPtr () + { + return &container_; + } + + protected: + OctreeNode* child_node_array_[8]; + + ContainerT container_; + }; + } +} + +#endif diff --git a/pcl-1.7/pcl/octree/octree_pointcloud.h b/pcl-1.7/pcl/octree/octree_pointcloud.h new file mode 100644 index 0000000..6f424b4 --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_pointcloud.h @@ -0,0 +1,581 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_POINTCLOUD_H +#define PCL_OCTREE_POINTCLOUD_H + +#include "octree_base.h" +//#include "octree2buf_base.h" + +#include +#include + +#include +#include +#include +#include + +namespace pcl +{ + namespace octree + { + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Octree pointcloud class + * \note Octree implementation for pointclouds. Only indices are stored by the octree leaf nodes (zero-copy). + * \note The octree pointcloud class needs to be initialized with its voxel resolution. Its bounding box is automatically adjusted + * \note according to the pointcloud dimension or it can be predefined. + * \note Note: The tree depth equates to the resolution and the bounding box dimensions of the octree. + * \note + * \note typename: PointT: type of point used in pointcloud + * \note typename: LeafContainerT: leaf node container ( + * \note typename: BranchContainerT: branch node container + * \note typename: OctreeT: octree implementation () + * \ingroup octree + * \author Julius Kammerl (julius@kammerl.de) + */ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template > + + class OctreePointCloud : public OctreeT + { + // iterators are friends + friend class OctreeIteratorBase ; + friend class OctreeDepthFirstIterator ; + friend class OctreeBreadthFirstIterator ; + friend class OctreeLeafNodeIterator ; + + public: + typedef OctreeT Base; + + typedef typename OctreeT::LeafNode LeafNode; + typedef typename OctreeT::BranchNode BranchNode; + + // Octree default iterators + typedef OctreeDepthFirstIterator Iterator; + typedef const OctreeDepthFirstIterator ConstIterator; + + // Octree leaf node iterators + typedef OctreeLeafNodeIterator LeafNodeIterator; + typedef const OctreeLeafNodeIterator ConstLeafNodeIterator; + + // Octree depth-first iterators + typedef OctreeDepthFirstIterator DepthFirstIterator; + typedef const OctreeDepthFirstIterator ConstDepthFirstIterator; + + // Octree breadth-first iterators + typedef OctreeBreadthFirstIterator BreadthFirstIterator; + typedef const OctreeBreadthFirstIterator ConstBreadthFirstIterator; + + /** \brief Octree pointcloud constructor. + * \param[in] resolution_arg octree resolution at lowest octree level + */ + OctreePointCloud (const double resolution_arg); + + /** \brief Empty deconstructor. */ + virtual + ~OctreePointCloud (); + + // public typedefs + typedef boost::shared_ptr > IndicesPtr; + typedef boost::shared_ptr > IndicesConstPtr; + + typedef pcl::PointCloud PointCloud; + typedef boost::shared_ptr PointCloudPtr; + typedef boost::shared_ptr PointCloudConstPtr; + + // public typedefs for single/double buffering + typedef OctreePointCloud > SingleBuffer; + // typedef OctreePointCloud > DoubleBuffer; + + // Boost shared pointers + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + // Eigen aligned allocator + typedef std::vector > AlignedPointTVector; + typedef std::vector > AlignedPointXYZVector; + + /** \brief Provide a pointer to the input data set. + * \param[in] cloud_arg the const boost shared pointer to a PointCloud message + * \param[in] indices_arg the point indices subset that is to be used from \a cloud - if 0 the whole point cloud is used + */ + inline void setInputCloud (const PointCloudConstPtr &cloud_arg, + const IndicesConstPtr &indices_arg = IndicesConstPtr ()) + { + input_ = cloud_arg; + indices_ = indices_arg; + } + + /** \brief Get a pointer to the vector of indices used. + * \return pointer to vector of indices used. + */ + inline IndicesConstPtr const getIndices () const + { + return (indices_); + } + + /** \brief Get a pointer to the input point cloud dataset. + * \return pointer to pointcloud input class. + */ + inline PointCloudConstPtr getInputCloud () const + { + return (input_); + } + + /** \brief Set the search epsilon precision (error bound) for nearest neighbors searches. + * \param[in] eps precision (error bound) for nearest neighbors searches + */ + inline void setEpsilon (double eps) + { + epsilon_ = eps; + } + + /** \brief Get the search epsilon precision (error bound) for nearest neighbors searches. */ + inline double getEpsilon () const + { + return (epsilon_); + } + + /** \brief Set/change the octree voxel resolution + * \param[in] resolution_arg side length of voxels at lowest tree level + */ + inline void setResolution (double resolution_arg) + { + // octree needs to be empty to change its resolution + assert( this->leaf_count_ == 0); + + resolution_ = resolution_arg; + + getKeyBitSize (); + } + + /** \brief Get octree voxel resolution + * \return voxel resolution at lowest tree level + */ + inline double getResolution () const + { + return (resolution_); + } + + /** \brief Get the maximum depth of the octree. + * \return depth_arg: maximum depth of octree + * */ + inline unsigned int getTreeDepth () const + { + return this->octree_depth_; + } + + /** \brief Add points from input point cloud to octree. */ + void + addPointsFromInputCloud (); + + /** \brief Add point at given index from input point cloud to octree. Index will be also added to indices vector. + * \param[in] point_idx_arg index of point to be added + * \param[in] indices_arg pointer to indices vector of the dataset (given by \a setInputCloud) + */ + void + addPointFromCloud (const int point_idx_arg, IndicesPtr indices_arg); + + /** \brief Add point simultaneously to octree and input point cloud. + * \param[in] point_arg point to be added + * \param[in] cloud_arg pointer to input point cloud dataset (given by \a setInputCloud) + */ + void + addPointToCloud (const PointT& point_arg, PointCloudPtr cloud_arg); + + /** \brief Add point simultaneously to octree and input point cloud. A corresponding index will be added to the indices vector. + * \param[in] point_arg point to be added + * \param[in] cloud_arg pointer to input point cloud dataset (given by \a setInputCloud) + * \param[in] indices_arg pointer to indices vector of the dataset (given by \a setInputCloud) + */ + void + addPointToCloud (const PointT& point_arg, PointCloudPtr cloud_arg, IndicesPtr indices_arg); + + /** \brief Check if voxel at given point exist. + * \param[in] point_arg point to be checked + * \return "true" if voxel exist; "false" otherwise + */ + bool + isVoxelOccupiedAtPoint (const PointT& point_arg) const; + + /** \brief Delete the octree structure and its leaf nodes. + * */ + void deleteTree () + { + // reset bounding box + min_x_ = min_y_ = max_y_ = min_z_ = max_z_ = 0; + this->bounding_box_defined_ = false; + + OctreeT::deleteTree (); + } + + /** \brief Check if voxel at given point coordinates exist. + * \param[in] point_x_arg X coordinate of point to be checked + * \param[in] point_y_arg Y coordinate of point to be checked + * \param[in] point_z_arg Z coordinate of point to be checked + * \return "true" if voxel exist; "false" otherwise + */ + bool + isVoxelOccupiedAtPoint (const double point_x_arg, const double point_y_arg, const double point_z_arg) const; + + /** \brief Check if voxel at given point from input cloud exist. + * \param[in] point_idx_arg point to be checked + * \return "true" if voxel exist; "false" otherwise + */ + bool + isVoxelOccupiedAtPoint (const int& point_idx_arg) const; + + /** \brief Get a PointT vector of centers of all occupied voxels. + * \param[out] voxel_center_list_arg results are written to this vector of PointT elements + * \return number of occupied voxels + */ + int + getOccupiedVoxelCenters (AlignedPointTVector &voxel_center_list_arg) const; + + /** \brief Get a PointT vector of centers of voxels intersected by a line segment. + * This returns a approximation of the actual intersected voxels by walking + * along the line with small steps. Voxels are ordered, from closest to + * furthest w.r.t. the origin. + * \param[in] origin origin of the line segment + * \param[in] end end of the line segment + * \param[out] voxel_center_list results are written to this vector of PointT elements + * \param[in] precision determines the size of the steps: step_size = octree_resolution x precision + * \return number of intersected voxels + */ + int + getApproxIntersectedVoxelCentersBySegment ( + const Eigen::Vector3f& origin, const Eigen::Vector3f& end, + AlignedPointTVector &voxel_center_list, float precision = 0.2); + + /** \brief Delete leaf node / voxel at given point + * \param[in] point_arg point addressing the voxel to be deleted. + */ + void + deleteVoxelAtPoint (const PointT& point_arg); + + /** \brief Delete leaf node / voxel at given point from input cloud + * \param[in] point_idx_arg index of point addressing the voxel to be deleted. + */ + void + deleteVoxelAtPoint (const int& point_idx_arg); + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Bounding box methods + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Investigate dimensions of pointcloud data set and define corresponding bounding box for octree. */ + void + defineBoundingBox (); + + /** \brief Define bounding box for octree + * \note Bounding box cannot be changed once the octree contains elements. + * \param[in] min_x_arg X coordinate of lower bounding box corner + * \param[in] min_y_arg Y coordinate of lower bounding box corner + * \param[in] min_z_arg Z coordinate of lower bounding box corner + * \param[in] max_x_arg X coordinate of upper bounding box corner + * \param[in] max_y_arg Y coordinate of upper bounding box corner + * \param[in] max_z_arg Z coordinate of upper bounding box corner + */ + void + defineBoundingBox (const double min_x_arg, const double min_y_arg, const double min_z_arg, + const double max_x_arg, const double max_y_arg, const double max_z_arg); + + /** \brief Define bounding box for octree + * \note Lower bounding box point is set to (0, 0, 0) + * \note Bounding box cannot be changed once the octree contains elements. + * \param[in] max_x_arg X coordinate of upper bounding box corner + * \param[in] max_y_arg Y coordinate of upper bounding box corner + * \param[in] max_z_arg Z coordinate of upper bounding box corner + */ + void + defineBoundingBox (const double max_x_arg, const double max_y_arg, const double max_z_arg); + + /** \brief Define bounding box cube for octree + * \note Lower bounding box corner is set to (0, 0, 0) + * \note Bounding box cannot be changed once the octree contains elements. + * \param[in] cubeLen_arg side length of bounding box cube. + */ + void + defineBoundingBox (const double cubeLen_arg); + + /** \brief Get bounding box for octree + * \note Bounding box cannot be changed once the octree contains elements. + * \param[in] min_x_arg X coordinate of lower bounding box corner + * \param[in] min_y_arg Y coordinate of lower bounding box corner + * \param[in] min_z_arg Z coordinate of lower bounding box corner + * \param[in] max_x_arg X coordinate of upper bounding box corner + * \param[in] max_y_arg Y coordinate of upper bounding box corner + * \param[in] max_z_arg Z coordinate of upper bounding box corner + */ + void + getBoundingBox (double& min_x_arg, double& min_y_arg, double& min_z_arg, + double& max_x_arg, double& max_y_arg, double& max_z_arg) const; + + /** \brief Calculates the squared diameter of a voxel at given tree depth + * \param[in] tree_depth_arg depth/level in octree + * \return squared diameter + */ + double + getVoxelSquaredDiameter (unsigned int tree_depth_arg) const; + + /** \brief Calculates the squared diameter of a voxel at leaf depth + * \return squared diameter + */ + inline double + getVoxelSquaredDiameter () const + { + return getVoxelSquaredDiameter (this->octree_depth_); + } + + /** \brief Calculates the squared voxel cube side length at given tree depth + * \param[in] tree_depth_arg depth/level in octree + * \return squared voxel cube side length + */ + double + getVoxelSquaredSideLen (unsigned int tree_depth_arg) const; + + /** \brief Calculates the squared voxel cube side length at leaf level + * \return squared voxel cube side length + */ + inline double getVoxelSquaredSideLen () const + { + return getVoxelSquaredSideLen (this->octree_depth_); + } + + /** \brief Generate bounds of the current voxel of an octree iterator + * \param[in] iterator: octree iterator + * \param[out] min_pt lower bound of voxel + * \param[out] max_pt upper bound of voxel + */ + inline void + getVoxelBounds (OctreeIteratorBase& iterator, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt) + { + this->genVoxelBoundsFromOctreeKey (iterator.getCurrentOctreeKey (), + iterator.getCurrentOctreeDepth (), min_pt, max_pt); + } + + /** \brief Enable dynamic octree structure + * \note Leaf nodes are kept as close to the root as possible and are only expanded if the number of DataT objects within a leaf node exceeds a fixed limit. + * \param maxObjsPerLeaf: maximum number of DataT objects per leaf + * */ + inline void + enableDynamicDepth ( size_t maxObjsPerLeaf ) + { + assert(this->leaf_count_==0); + max_objs_per_leaf_ = maxObjsPerLeaf; + + this->dynamic_depth_enabled_ = static_cast (max_objs_per_leaf_>0); + } + + + protected: + + /** \brief Add point at index from input pointcloud dataset to octree + * \param[in] point_idx_arg the index representing the point in the dataset given by \a setInputCloud to be added + */ + virtual void + addPointIdx (const int point_idx_arg); + + /** \brief Add point at index from input pointcloud dataset to octree + * \param[in] leaf_node to be expanded + * \param[in] parent_branch parent of leaf node to be expanded + * \param[in] child_idx child index of leaf node (in parent branch) + * \param[in] depth_mask of leaf node to be expanded + */ + void + expandLeafNode (LeafNode* leaf_node, BranchNode* parent_branch, unsigned char child_idx, unsigned int depth_mask); + + /** \brief Get point at index from input pointcloud dataset + * \param[in] index_arg index representing the point in the dataset given by \a setInputCloud + * \return PointT from input pointcloud dataset + */ + const PointT& + getPointByIndex (const unsigned int index_arg) const; + + /** \brief Find octree leaf node at a given point + * \param[in] point_arg query point + * \return pointer to leaf node. If leaf node does not exist, pointer is 0. + */ + LeafContainerT* + findLeafAtPoint (const PointT& point_arg) const + { + OctreeKey key; + + // generate key for point + this->genOctreeKeyforPoint (point_arg, key); + + return (this->findLeaf (key)); + } + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Protected octree methods based on octree keys + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Define octree key setting and octree depth based on defined bounding box. */ + void + getKeyBitSize (); + + /** \brief Grow the bounding box/octree until point fits + * \param[in] point_idx_arg point that should be within bounding box; + */ + void + adoptBoundingBoxToPoint (const PointT& point_idx_arg); + + /** \brief Checks if given point is within the bounding box of the octree + * \param[in] point_idx_arg point to be checked for bounding box violations + * \return "true" - no bound violation + */ + inline bool isPointWithinBoundingBox (const PointT& point_idx_arg) const + { + return (! ( (point_idx_arg.x < min_x_) || (point_idx_arg.y < min_y_) + || (point_idx_arg.z < min_z_) || (point_idx_arg.x >= max_x_) + || (point_idx_arg.y >= max_y_) || (point_idx_arg.z >= max_z_))); + } + + /** \brief Generate octree key for voxel at a given point + * \param[in] point_arg the point addressing a voxel + * \param[out] key_arg write octree key to this reference + */ + void + genOctreeKeyforPoint (const PointT & point_arg, + OctreeKey &key_arg) const; + + /** \brief Generate octree key for voxel at a given point + * \param[in] point_x_arg X coordinate of point addressing a voxel + * \param[in] point_y_arg Y coordinate of point addressing a voxel + * \param[in] point_z_arg Z coordinate of point addressing a voxel + * \param[out] key_arg write octree key to this reference + */ + void + genOctreeKeyforPoint (const double point_x_arg, const double point_y_arg, const double point_z_arg, + OctreeKey & key_arg) const; + + /** \brief Virtual method for generating octree key for a given point index. + * \note This method enables to assign indices to leaf nodes during octree deserialization. + * \param[in] data_arg index value representing a point in the dataset given by \a setInputCloud + * \param[out] key_arg write octree key to this reference + * \return "true" - octree keys are assignable + */ + virtual bool + genOctreeKeyForDataT (const int& data_arg, OctreeKey & key_arg) const; + + /** \brief Generate a point at center of leaf node voxel + * \param[in] key_arg octree key addressing a leaf node. + * \param[out] point_arg write leaf node voxel center to this point reference + */ + void + genLeafNodeCenterFromOctreeKey (const OctreeKey & key_arg, + PointT& point_arg) const; + + /** \brief Generate a point at center of octree voxel at given tree level + * \param[in] key_arg octree key addressing an octree node. + * \param[in] tree_depth_arg octree depth of query voxel + * \param[out] point_arg write leaf node center point to this reference + */ + void + genVoxelCenterFromOctreeKey (const OctreeKey & key_arg, + unsigned int tree_depth_arg, PointT& point_arg) const; + + /** \brief Generate bounds of an octree voxel using octree key and tree depth arguments + * \param[in] key_arg octree key addressing an octree node. + * \param[in] tree_depth_arg octree depth of query voxel + * \param[out] min_pt lower bound of voxel + * \param[out] max_pt upper bound of voxel + */ + void + genVoxelBoundsFromOctreeKey (const OctreeKey & key_arg, + unsigned int tree_depth_arg, Eigen::Vector3f &min_pt, + Eigen::Vector3f &max_pt) const; + + /** \brief Recursively search the tree for all leaf nodes and return a vector of voxel centers. + * \param[in] node_arg current octree node to be explored + * \param[in] key_arg octree key addressing a leaf node. + * \param[out] voxel_center_list_arg results are written to this vector of PointT elements + * \return number of voxels found + */ + int + getOccupiedVoxelCentersRecursive (const BranchNode* node_arg, + const OctreeKey& key_arg, + AlignedPointTVector &voxel_center_list_arg) const; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Globals + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Pointer to input point cloud dataset. */ + PointCloudConstPtr input_; + + /** \brief A pointer to the vector of point indices to use. */ + IndicesConstPtr indices_; + + /** \brief Epsilon precision (error bound) for nearest neighbors searches. */ + double epsilon_; + + /** \brief Octree resolution. */ + double resolution_; + + // Octree bounding box coordinates + double min_x_; + double max_x_; + + double min_y_; + double max_y_; + + double min_z_; + double max_z_; + + /** \brief Flag indicating if octree has defined bounding box. */ + bool bounding_box_defined_; + + /** \brief Amount of DataT objects per leafNode before expanding branch + * \note zero indicates a fixed/maximum depth octree structure + * **/ + std::size_t max_objs_per_leaf_; + }; + + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif + diff --git a/pcl-1.7/pcl/octree/octree_pointcloud_adjacency.h b/pcl-1.7/pcl/octree/octree_pointcloud_adjacency.h new file mode 100644 index 0000000..b0bb330 --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_pointcloud_adjacency.h @@ -0,0 +1,254 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Jeremie Papon + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : jpapon@gmail.com + * Email : jpapon@gmail.com + */ + +#ifndef PCL_OCTREE_POINTCLOUD_ADJACENCY_H_ +#define PCL_OCTREE_POINTCLOUD_ADJACENCY_H_ + +#include +#include +#include +#include +#include + +#include +#include + +namespace pcl +{ + + namespace octree + { + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Octree pointcloud voxel class which maintains adjacency information for its voxels. + * + * This pointcloud octree class generates an octree from a point cloud (zero-copy). The octree pointcloud is + * initialized with its voxel resolution. Its bounding box is automatically adjusted or can be predefined. + * + * The OctreePointCloudAdjacencyContainer class can be used to store data in leaf nodes. + * + * An optional transform function can be provided which changes how the voxel grid is computed - this can be used to, + * for example, make voxel bins larger as they increase in distance from the origin (camera). + * \note See SupervoxelClustering for an example of how to provide a transform function. + * + * If used in academic work, please cite: + * + * - J. Papon, A. Abramov, M. Schoeler, F. Woergoetter + * Voxel Cloud Connectivity Segmentation - Supervoxels from PointClouds + * In Proceedings of the IEEE Conference on Computer Vision and Pattern Recognition (CVPR) 2013 + * + * \ingroup octree + * \author Jeremie Papon (jpapon@gmail.com) */ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template , + typename BranchContainerT = OctreeContainerEmpty> + class OctreePointCloudAdjacency : public OctreePointCloud + { + + public: + + typedef OctreeBase OctreeBaseT; + + typedef OctreePointCloudAdjacency OctreeAdjacencyT; + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef OctreePointCloud OctreePointCloudT; + typedef typename OctreePointCloudT::LeafNode LeafNode; + typedef typename OctreePointCloudT::BranchNode BranchNode; + + typedef pcl::PointCloud PointCloud; + typedef boost::shared_ptr PointCloudPtr; + typedef boost::shared_ptr PointCloudConstPtr; + + // Iterators are friends + friend class OctreeIteratorBase; + friend class OctreeDepthFirstIterator; + friend class OctreeBreadthFirstIterator; + friend class OctreeLeafNodeIterator; + + // Octree default iterators + typedef OctreeDepthFirstIterator Iterator; + typedef const OctreeDepthFirstIterator ConstIterator; + + Iterator depth_begin (unsigned int max_depth_arg = 0) { return Iterator (this, max_depth_arg); } + const Iterator depth_end () { return Iterator (); } + + // Octree leaf node iterators + typedef OctreeLeafNodeIterator LeafNodeIterator; + typedef const OctreeLeafNodeIterator ConstLeafNodeIterator; + + LeafNodeIterator leaf_begin (unsigned int max_depth_arg = 0) { return LeafNodeIterator (this, max_depth_arg); } + const LeafNodeIterator leaf_end () { return LeafNodeIterator (); } + + // BGL graph + typedef boost::adjacency_list VoxelAdjacencyList; + typedef typename VoxelAdjacencyList::vertex_descriptor VoxelID; + typedef typename VoxelAdjacencyList::edge_descriptor EdgeID; + + // Leaf vector - pointers to all leaves + typedef std::vector LeafVectorT; + + // Fast leaf iterators that don't require traversing tree + typedef typename LeafVectorT::iterator iterator; + typedef typename LeafVectorT::const_iterator const_iterator; + + inline iterator begin () { return (leaf_vector_.begin ()); } + inline iterator end () { return (leaf_vector_.end ()); } + + // Size of neighbors + inline size_t size () const { return leaf_vector_.size (); } + + /** \brief Constructor. + * + * \param[in] resolution_arg Octree resolution at lowest octree level (voxel size) */ + OctreePointCloudAdjacency (const double resolution_arg); + + /** \brief Empty class destructor. */ + virtual ~OctreePointCloudAdjacency () + { + } + + /** \brief Adds points from cloud to the octree. + * + * \note This overrides addPointsFromInputCloud() from the OctreePointCloud class. */ + void + addPointsFromInputCloud (); + + /** \brief Gets the leaf container for a given point. + * + * \param[in] point_arg Point to search for + * + * \returns Pointer to the leaf container - null if no leaf container found. */ + LeafContainerT* + getLeafContainerAtPoint (const PointT& point_arg) const; + + /** \brief Computes an adjacency graph of voxel relations. + * + * \warning This slows down rapidly as cloud size increases due to the number of edges. + * + * \param[out] voxel_adjacency_graph Boost Graph Library Adjacency graph of the voxel touching relationships. + * Vertices are PointT, edges represent touching, and edge lengths are the distance between the points. */ + void + computeVoxelAdjacencyGraph (VoxelAdjacencyList &voxel_adjacency_graph); + + /** \brief Sets a point transform (and inverse) used to transform the space of the input cloud. + * + * This is useful for changing how adjacency is calculated - such as relaxing the adjacency criterion for + * points further from the camera. + * + * \param[in] transform_func A boost:function pointer to the transform to be used. The transform must have one + * parameter (a point) which it modifies in place. */ + void + setTransformFunction (boost::function transform_func) + { + transform_func_ = transform_func; + } + + /** \brief Tests whether input point is occluded from specified camera point by other voxels. + * + * \param[in] point_arg Point to test for + * \param[in] camera_pos Position of camera, defaults to origin + * + * \returns True if path to camera is blocked by a voxel, false otherwise. */ + bool + testForOcclusion (const PointT& point_arg, const PointXYZ &camera_pos = PointXYZ (0, 0, 0)); + + protected: + + /** \brief Add point at index from input pointcloud dataset to octree. + * + * \param[in] point_idx_arg The index representing the point in the dataset given by setInputCloud() to be added + * + * \note This virtual implementation allows the use of a transform function to compute keys. */ + virtual void + addPointIdx (const int point_idx_arg); + + /** \brief Fills in the neighbors fields for new voxels. + * + * \param[in] key_arg Key of the voxel to check neighbors for + * \param[in] leaf_container Pointer to container of the leaf to check neighbors for */ + void + computeNeighbors (OctreeKey &key_arg, LeafContainerT* leaf_container); + + /** \brief Generates octree key for specified point (uses transform if provided). + * + * \param[in] point_arg Point to generate key for + * \param[out] key_arg Resulting octree key */ + void + genOctreeKeyforPoint (const PointT& point_arg, OctreeKey& key_arg) const; + + private: + + /** \brief Add point at given index from input point cloud to octree. + * + * Index will be also added to indices vector. This functionality is not enabled for adjacency octree. */ + using OctreePointCloudT::addPointFromCloud; + + /** \brief Add point simultaneously to octree and input point cloud. + * + * This functionality is not enabled for adjacency octree. */ + using OctreePointCloudT::addPointToCloud; + + using OctreePointCloudT::input_; + using OctreePointCloudT::resolution_; + using OctreePointCloudT::min_x_; + using OctreePointCloudT::min_y_; + using OctreePointCloudT::min_z_; + using OctreePointCloudT::max_x_; + using OctreePointCloudT::max_y_; + using OctreePointCloudT::max_z_; + + /// Local leaf pointer vector used to make iterating through leaves fast. + LeafVectorT leaf_vector_; + + boost::function transform_func_; + + }; + + } + +} + +//#ifdef PCL_NO_PRECOMPILE +#include +//#endif + +#endif // PCL_OCTREE_POINTCLOUD_ADJACENCY_H_ + diff --git a/pcl-1.7/pcl/octree/octree_pointcloud_adjacency_container.h b/pcl-1.7/pcl/octree/octree_pointcloud_adjacency_container.h new file mode 100644 index 0000000..326c0f5 --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_pointcloud_adjacency_container.h @@ -0,0 +1,193 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Jeremie Papon + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : jpapon@gmail.com + * Email : jpapon@gmail.com + */ + +#ifndef PCL_OCTREE_POINTCLOUD_ADJACENCY_CONTAINER_H_ +#define PCL_OCTREE_POINTCLOUD_ADJACENCY_CONTAINER_H_ + +namespace pcl +{ + + namespace octree + { + /** \brief @b Octree adjacency leaf container class- stores set of pointers to neighbors, number of points added, and a DataT value + * \note This class implements a leaf node that stores pointers to neighboring leaves + * \note This class also has a virtual computeData function, which is called by octreePointCloudAdjacency::addPointsFromInputCloud. + * \note You should make explicit instantiations of it for your pointtype/datatype combo (if needed) see supervoxel_clustering.hpp for an example of this + */ + template + class OctreePointCloudAdjacencyContainer : public OctreeContainerBase + { + public: + typedef std::set NeighborSetT; + //iterators to neighbors + typedef typename NeighborSetT::iterator iterator; + typedef typename NeighborSetT::const_iterator const_iterator; + inline iterator begin () { return (neighbors_.begin ()); } + inline iterator end () { return (neighbors_.end ()); } + inline const_iterator begin () const { return (neighbors_.begin ()); } + inline const_iterator end () const { return (neighbors_.end ()); } + //size of neighbors + inline size_t size () const { return neighbors_.size (); } + //insert for neighbors + inline std::pair insert (OctreePointCloudAdjacencyContainer* neighbor) { return neighbors_.insert (neighbor); } + + /** \brief Class initialization. */ + OctreePointCloudAdjacencyContainer () : + OctreeContainerBase () + { + this->reset(); + } + + /** \brief Empty class deconstructor. */ + virtual ~OctreePointCloudAdjacencyContainer () + { + } + + /** \brief deep copy function */ + virtual OctreePointCloudAdjacencyContainer * + deepCopy () const + { + OctreePointCloudAdjacencyContainer *new_container = new OctreePointCloudAdjacencyContainer; + new_container->setNeighbors (this->neighbors_); + new_container->setPointCounter (this->num_points_); + return new_container; + } + + /** \brief Add new point to container- this just counts points + * \note To actually store data in the leaves, need to specialize this + * for your point and data type as in supervoxel_clustering.hpp + */ + // param[in] new_point the new point to add + void + addPoint (const PointInT& /*new_point*/) + { + using namespace pcl::common; + ++num_points_; + } + + /** \brief Function for working on data added. Base implementation does nothing + * */ + void + computeData () + { + } + + /** \brief Gets the number of points contributing to this leaf */ + int + getPointCounter () const { return num_points_; } + + /** \brief Sets the number of points contributing to this leaf */ + void + setPointCounter (int points_arg) { num_points_ = points_arg; } + + /** \brief Clear the voxel centroid */ + virtual void + reset () + { + neighbors_.clear (); + num_points_ = 0; + data_ = DataT (); + } + + /** \brief Add new neighbor to voxel. + * \param[in] neighbor the new neighbor to add + */ + void + addNeighbor (OctreePointCloudAdjacencyContainer *neighbor) + { + neighbors_.insert (neighbor); + } + + /** \brief Remove neighbor from neighbor set. + * \param[in] neighbor the neighbor to remove + */ + void + removeNeighbor (OctreePointCloudAdjacencyContainer *neighbor) + { + neighbors_.erase (neighbor); + + } + + /** \brief Returns the number of neighbors this leaf has + * \returns number of neighbors + */ + size_t + getNumNeighbors () const + { + return neighbors_.size (); + } + + /** \brief Sets the whole neighbor set + * \param[in] neighbor_arg the new set + */ + void + setNeighbors (const NeighborSetT &neighbor_arg) + { + neighbors_ = neighbor_arg; + } + + /** \brief Returns a reference to the data member to access it without copying */ + DataT& + getData () { return data_; } + + /** \brief Sets the data member + * \param[in] data_arg New value for data + */ + void + setData (const DataT& data_arg) { data_ = data_arg;} + + /** \brief virtual method to get size of container + * \return number of points added to leaf node container. + */ + virtual size_t + getSize () const + { + return num_points_; + } + + + private: + int num_points_; + NeighborSetT neighbors_; + DataT data_; + }; + } +} + +#endif diff --git a/pcl-1.7/pcl/octree/octree_pointcloud_changedetector.h b/pcl-1.7/pcl/octree/octree_pointcloud_changedetector.h new file mode 100644 index 0000000..cdacc07 --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_pointcloud_changedetector.h @@ -0,0 +1,114 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_CHANGEDETECTOR_H +#define PCL_OCTREE_CHANGEDETECTOR_H + +#include "octree_pointcloud.h" + +namespace pcl +{ + namespace octree + { + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Octree pointcloud change detector class + * \note This pointcloud octree class generate an octrees from a point cloud (zero-copy). It allows to detect new leaf nodes and serialize their point indices + * \note The octree pointcloud is initialized with its voxel resolution. Its bounding box is automatically adjusted or can be predefined. + * \note + * \note typename: PointT: type of point used in pointcloud + * \ingroup octree + * \author Julius Kammerl (julius@kammerl.de) + */ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template + + class OctreePointCloudChangeDetector : public OctreePointCloud > + + { + + public: + + /** \brief Constructor. + * \param resolution_arg: octree resolution at lowest octree level + * */ + OctreePointCloudChangeDetector (const double resolution_arg) : + OctreePointCloud > (resolution_arg) + { + } + + /** \brief Empty class constructor. */ + virtual ~OctreePointCloudChangeDetector () + { + } + + /** \brief Get a indices from all leaf nodes that did not exist in previous buffer. + * \param indicesVector_arg: results are written to this vector of int indices + * \param minPointsPerLeaf_arg: minimum amount of points required within leaf node to become serialized. + * \return number of point indices + */ + std::size_t getPointIndicesFromNewVoxels (std::vector &indicesVector_arg, + const int minPointsPerLeaf_arg = 0) + { + + std::vector leaf_containers; + this->serializeNewLeafs (leaf_containers); + + std::vector::iterator it; + std::vector::const_iterator it_end = leaf_containers.end(); + + for (it=leaf_containers.begin(); it!=it_end; ++it) + { + if (static_cast ((*it)->getSize ()) >= minPointsPerLeaf_arg) + (*it)->getPointIndices(indicesVector_arg); + } + + return (indicesVector_arg.size ()); + } + }; + } +} + +#define PCL_INSTANTIATE_OctreePointCloudChangeDetector(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudChangeDetector; + +#endif + diff --git a/pcl-1.7/pcl/octree/octree_pointcloud_density.h b/pcl-1.7/pcl/octree/octree_pointcloud_density.h new file mode 100644 index 0000000..667011e --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_pointcloud_density.h @@ -0,0 +1,162 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_DENSITY_H +#define PCL_OCTREE_DENSITY_H + +#include "octree_pointcloud.h" + +namespace pcl +{ + namespace octree + { + /** \brief @b Octree pointcloud density leaf node class + * \note This class implements a leaf node that counts the amount of points which fall into its voxel space. + * \author Julius Kammerl (julius@kammerl.de) + */ + class OctreePointCloudDensityContainer : public OctreeContainerBase + { + public: + /** \brief Class initialization. */ + OctreePointCloudDensityContainer () : point_counter_ (0) + { + } + + /** \brief Empty class deconstructor. */ + virtual ~OctreePointCloudDensityContainer () + { + } + + /** \brief deep copy function */ + virtual OctreePointCloudDensityContainer * + deepCopy () const + { + return (new OctreePointCloudDensityContainer (*this)); + } + + /** \brief Equal comparison operator + * \param[in] other OctreePointCloudDensityContainer to compare with + */ + virtual bool operator==(const OctreeContainerBase& other) const + { + const OctreePointCloudDensityContainer* otherContainer = + dynamic_cast(&other); + + return (this->point_counter_==otherContainer->point_counter_); + } + + /** \brief Read input data. Only an internal counter is increased. + */ + void + addPointIndex (int) + { + point_counter_++; + } + + /** \brief Return point counter. + * \return Amount of points + */ + unsigned int + getPointCounter () + { + return (point_counter_); + } + + /** \brief Reset leaf node. */ + virtual void + reset () + { + point_counter_ = 0; + } + + private: + unsigned int point_counter_; + + }; + + /** \brief @b Octree pointcloud density class + * \note This class generate an octrees from a point cloud (zero-copy). Only the amount of points that fall into the leaf node voxel are stored. + * \note The octree pointcloud is initialized with its voxel resolution. Its bounding box is automatically adjusted or can be predefined. + * \note + * \note typename: PointT: type of point used in pointcloud + * \ingroup octree + * \author Julius Kammerl (julius@kammerl.de) + */ + template + class OctreePointCloudDensity : public OctreePointCloud + { + public: + + /** \brief OctreePointCloudDensity class constructor. + * \param resolution_arg: octree resolution at lowest octree level + * */ + OctreePointCloudDensity (const double resolution_arg) : + OctreePointCloud (resolution_arg) + { + } + + /** \brief Empty class deconstructor. */ + virtual + ~OctreePointCloudDensity () + { + } + + /** \brief Get the amount of points within a leaf node voxel which is addressed by a point + * \param[in] point_arg: a point addressing a voxel + * \return amount of points that fall within leaf node voxel + */ + unsigned int + getVoxelDensityAtPoint (const PointT& point_arg) const + { + unsigned int point_count = 0; + + OctreePointCloudDensityContainer* leaf = this->findLeafAtPoint (point_arg); + + if (leaf) + point_count = leaf->getPointCounter (); + + return (point_count); + } + }; + } +} + +#define PCL_INSTANTIATE_OctreePointCloudDensity(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudDensity; + +#endif + diff --git a/pcl-1.7/pcl/octree/octree_pointcloud_occupancy.h b/pcl-1.7/pcl/octree/octree_pointcloud_occupancy.h new file mode 100644 index 0000000..53413c4 --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_pointcloud_occupancy.h @@ -0,0 +1,132 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_OCCUPANCY_H +#define PCL_OCTREE_OCCUPANCY_H + +#include "octree_pointcloud.h" + +namespace pcl +{ + namespace octree + { + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Octree pointcloud occupancy class + * \note This pointcloud octree class generate an octrees from a point cloud (zero-copy). No information is stored at the lead nodes. It can be used of occupancy checks. + * \note The octree pointcloud is initialized with its voxel resolution. Its bounding box is automatically adjusted or can be predefined. + * \note + * \note typename: PointT: type of point used in pointcloud + * \ingroup octree + * \author Julius Kammerl (julius@kammerl.de) + */ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template + class OctreePointCloudOccupancy : public OctreePointCloud > + + { + + public: + // public typedefs for single/double buffering + typedef OctreePointCloudOccupancy SingleBuffer; + typedef OctreePointCloudOccupancy DoubleBuffer; + + // public point cloud typedefs + typedef typename OctreePointCloud::PointCloud PointCloud; + typedef typename OctreePointCloud::PointCloudPtr PointCloudPtr; + typedef typename OctreePointCloud::PointCloudConstPtr PointCloudConstPtr; + + /** \brief Constructor. + * \param resolution_arg: octree resolution at lowest octree level + * */ + OctreePointCloudOccupancy (const double resolution_arg) : + OctreePointCloud > (resolution_arg) + { + } + + /** \brief Empty class constructor. */ + virtual + ~OctreePointCloudOccupancy () + { + } + + /** \brief Set occupied voxel at point. + * \param point_arg: input point + * */ + void setOccupiedVoxelAtPoint( const PointT& point_arg ) { + OctreeKey key; + + // make sure bounding box is big enough + adoptBoundingBoxToPoint (point_arg); + + // generate key + genOctreeKeyforPoint (point_arg, key); + + // add point to octree at key + this->createLeaf (key); + } + + /** \brief Set occupied voxels at all points from point cloud. + * \param cloud_arg: input point cloud + * */ + void setOccupiedVoxelsAtPointsFromCloud( PointCloudPtr cloud_arg ) { + size_t i; + + for (i = 0; i < cloud_arg->points.size (); i++) + { + // check for NaNs + if (isFinite(cloud_arg->points[i])) { + // set voxel at point + this->setOccupiedVoxelAtPoint (cloud_arg->points[i]); + } + } + } + + }; + } + +} + +#define PCL_INSTANTIATE_OctreePointCloudOccupancy(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudOccupancy; + +#endif + diff --git a/pcl-1.7/pcl/octree/octree_pointcloud_pointvector.h b/pcl-1.7/pcl/octree/octree_pointcloud_pointvector.h new file mode 100644 index 0000000..41038de --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_pointcloud_pointvector.h @@ -0,0 +1,92 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_POINT_VECTOR_H +#define PCL_OCTREE_POINT_VECTOR_H + +#include "octree_pointcloud.h" + +namespace pcl +{ + namespace octree + { + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Octree pointcloud point vector class + * \note This pointcloud octree class generate an octrees from a point cloud (zero-copy). Every leaf node contains a list of point indices of the dataset given by \a setInputCloud. + * \note The octree pointcloud is initialized with its voxel resolution. Its bounding box is automatically adjusted or can be predefined. + * \note + * \note typename: PointT: type of point used in pointcloud + * \ingroup octree + * \author Julius Kammerl (julius@kammerl.de) + */ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template > + class OctreePointCloudPointVector : public OctreePointCloud + { + + public: + // public typedefs for single/double buffering + typedef OctreePointCloudPointVector > SingleBuffer; + // typedef OctreePointCloudPointVector > DoubleBuffer; + + /** \brief Constructor. + * \param resolution_arg: octree resolution at lowest octree level + * */ + OctreePointCloudPointVector (const double resolution_arg) : + OctreePointCloud (resolution_arg) + { + } + + /** \brief Empty class constructor. */ + virtual ~OctreePointCloudPointVector () + { + } + + }; + } +} + +#define PCL_INSTANTIATE_OctreePointCloudPointVector(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudPointVector; + +#endif diff --git a/pcl-1.7/pcl/octree/octree_pointcloud_singlepoint.h b/pcl-1.7/pcl/octree/octree_pointcloud_singlepoint.h new file mode 100644 index 0000000..917be16 --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_pointcloud_singlepoint.h @@ -0,0 +1,93 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_SINGLE_POINT_H +#define PCL_OCTREE_SINGLE_POINT_H + +#include "octree_pointcloud.h" + +namespace pcl +{ + namespace octree + { + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Octree pointcloud single point class + * \note This pointcloud octree class generate an octrees from a point cloud (zero-copy). Every leaf node contains a single point index from the dataset given by \a setInputCloud. + * \note The octree pointcloud is initialized with its voxel resolution. Its bounding box is automatically adjusted or can be predefined. + * \note + * \note typename: PointT: type of point used in pointcloud + * \ingroup octree + * \author Julius Kammerl (julius@kammerl.de) + */ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template > + + class OctreePointCloudSinglePoint : public OctreePointCloud + { + + public: + // public typedefs for single/double buffering + typedef OctreePointCloudSinglePoint > SingleBuffer; + // typedef OctreePointCloudSinglePoint > DoubleBuffer; + + /** \brief Constructor. + * \param resolution_arg: octree resolution at lowest octree level + * */ + OctreePointCloudSinglePoint (const double resolution_arg) : + OctreePointCloud (resolution_arg) + { + } + + /** \brief Empty class constructor. */ + virtual ~OctreePointCloudSinglePoint () + { + } + + }; + + } +} + +#define PCL_INSTANTIATE_OctreePointCloudSinglePoint(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudSinglePoint; + +#endif diff --git a/pcl-1.7/pcl/octree/octree_pointcloud_voxelcentroid.h b/pcl-1.7/pcl/octree/octree_pointcloud_voxelcentroid.h new file mode 100644 index 0000000..10cddad --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_pointcloud_voxelcentroid.h @@ -0,0 +1,238 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_VOXELCENTROID_H +#define PCL_OCTREE_VOXELCENTROID_H + +#include "octree_pointcloud.h" + +#include +#include +#include + +namespace pcl +{ + namespace octree + { + /** \brief @b Octree pointcloud voxel centroid leaf node class + * \note This class implements a leaf node that calculates the mean centroid of all points added this octree container. + * \author Julius Kammerl (julius@kammerl.de) + */ + template + class OctreePointCloudVoxelCentroidContainer : public OctreeContainerBase + { + public: + /** \brief Class initialization. */ + OctreePointCloudVoxelCentroidContainer () + { + this->reset(); + } + + /** \brief Empty class deconstructor. */ + virtual ~OctreePointCloudVoxelCentroidContainer () + { + } + + /** \brief deep copy function */ + virtual OctreePointCloudVoxelCentroidContainer * + deepCopy () const + { + return (new OctreePointCloudVoxelCentroidContainer (*this)); + } + + /** \brief Equal comparison operator - set to false + */ + // param[in] OctreePointCloudVoxelCentroidContainer to compare with + virtual bool operator==(const OctreeContainerBase&) const + { + return ( false ); + } + + /** \brief Add new point to voxel. + * \param[in] new_point the new point to add + */ + void + addPoint (const PointT& new_point) + { + using namespace pcl::common; + + ++point_counter_; + + point_sum_ += new_point; + } + + /** \brief Calculate centroid of voxel. + * \param[out] centroid_arg the resultant centroid of the voxel + */ + void + getCentroid (PointT& centroid_arg) const + { + using namespace pcl::common; + + if (point_counter_) + { + centroid_arg = point_sum_; + centroid_arg /= static_cast (point_counter_); + } + else + { + centroid_arg *= 0.0f; + } + } + + /** \brief Reset leaf container. */ + virtual void + reset () + { + using namespace pcl::common; + + point_counter_ = 0; + point_sum_ *= 0.0f; + } + + private: + unsigned int point_counter_; + PointT point_sum_; + }; + + /** \brief @b Octree pointcloud voxel centroid class + * \note This class generate an octrees from a point cloud (zero-copy). It provides a vector of centroids for all occupied voxels. + * \note The octree pointcloud is initialized with its voxel resolution. Its bounding box is automatically adjusted or can be predefined. + * \note + * \note typename: PointT: type of point used in pointcloud + * + * \ingroup octree + * \author Julius Kammerl (julius@kammerl.de) + */ + template , + typename BranchContainerT = OctreeContainerEmpty > + class OctreePointCloudVoxelCentroid : public OctreePointCloud + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef OctreePointCloud OctreeT; + typedef typename OctreeT::LeafNode LeafNode; + typedef typename OctreeT::BranchNode BranchNode; + + /** \brief OctreePointCloudVoxelCentroids class constructor. + * \param[in] resolution_arg octree resolution at lowest octree level + */ + OctreePointCloudVoxelCentroid (const double resolution_arg) : + OctreePointCloud (resolution_arg) + { + } + + /** \brief Empty class deconstructor. */ + virtual + ~OctreePointCloudVoxelCentroid () + { + } + + /** \brief Add DataT object to leaf node at octree key. + * \param pointIdx_arg + */ + virtual void + addPointIdx (const int pointIdx_arg) + { + OctreeKey key; + + assert (pointIdx_arg < static_cast (this->input_->points.size ())); + + const PointT& point = this->input_->points[pointIdx_arg]; + + // make sure bounding box is big enough + this->adoptBoundingBoxToPoint (point); + + // generate key + this->genOctreeKeyforPoint (point, key); + + // add point to octree at key + LeafContainerT* container = this->createLeaf(key); + container->addPoint (point); + + } + + /** \brief Get centroid for a single voxel addressed by a PointT point. + * \param[in] point_arg point addressing a voxel in octree + * \param[out] voxel_centroid_arg centroid is written to this PointT reference + * \return "true" if voxel is found; "false" otherwise + */ + bool + getVoxelCentroidAtPoint (const PointT& point_arg, PointT& voxel_centroid_arg) const; + + /** \brief Get centroid for a single voxel addressed by a PointT point from input cloud. + * \param[in] point_idx_arg point index from input cloud addressing a voxel in octree + * \param[out] voxel_centroid_arg centroid is written to this PointT reference + * \return "true" if voxel is found; "false" otherwise + */ + inline bool + getVoxelCentroidAtPoint (const int& point_idx_arg, PointT& voxel_centroid_arg) const + { + // get centroid at point + return (this->getVoxelCentroidAtPoint (this->input_->points[point_idx_arg], voxel_centroid_arg)); + } + + /** \brief Get PointT vector of centroids for all occupied voxels. + * \param[out] voxel_centroid_list_arg results are written to this vector of PointT elements + * \return number of occupied voxels + */ + size_t + getVoxelCentroids (typename OctreePointCloud::AlignedPointTVector &voxel_centroid_list_arg) const; + + /** \brief Recursively explore the octree and output a PointT vector of centroids for all occupied voxels. + * \param[in] branch_arg: current branch node + * \param[in] key_arg: current key + * \param[out] voxel_centroid_list_arg results are written to this vector of PointT elements + */ + void + getVoxelCentroidsRecursive (const BranchNode* branch_arg, + OctreeKey& key_arg, + typename OctreePointCloud::AlignedPointTVector &voxel_centroid_list_arg) const; + + }; + } +} + +#include + +#endif + diff --git a/pcl-1.7/pcl/octree/octree_search.h b/pcl-1.7/pcl/octree/octree_search.h new file mode 100644 index 0000000..5c039bf --- /dev/null +++ b/pcl-1.7/pcl/octree/octree_search.h @@ -0,0 +1,609 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OCTREE_SEARCH_H_ +#define PCL_OCTREE_SEARCH_H_ + +#include +#include + +#include "octree_pointcloud.h" + +namespace pcl +{ + namespace octree + { + /** \brief @b Octree pointcloud search class + * \note This class provides several methods for spatial neighbor search based on octree structure + * \note typename: PointT: type of point used in pointcloud + * \ingroup octree + * \author Julius Kammerl (julius@kammerl.de) + */ + template + class OctreePointCloudSearch : public OctreePointCloud + { + public: + // public typedefs + typedef boost::shared_ptr > IndicesPtr; + typedef boost::shared_ptr > IndicesConstPtr; + + typedef pcl::PointCloud PointCloud; + typedef boost::shared_ptr PointCloudPtr; + typedef boost::shared_ptr PointCloudConstPtr; + + // Boost shared pointers + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + // Eigen aligned allocator + typedef std::vector > AlignedPointTVector; + + typedef OctreePointCloud OctreeT; + typedef typename OctreeT::LeafNode LeafNode; + typedef typename OctreeT::BranchNode BranchNode; + + /** \brief Constructor. + * \param[in] resolution octree resolution at lowest octree level + */ + OctreePointCloudSearch (const double resolution) : + OctreePointCloud (resolution) + { + } + + /** \brief Empty class constructor. */ + virtual + ~OctreePointCloudSearch () + { + } + + /** \brief Search for neighbors within a voxel at given point + * \param[in] point point addressing a leaf node voxel + * \param[out] point_idx_data the resultant indices of the neighboring voxel points + * \return "true" if leaf node exist; "false" otherwise + */ + bool + voxelSearch (const PointT& point, std::vector& point_idx_data); + + /** \brief Search for neighbors within a voxel at given point referenced by a point index + * \param[in] index the index in input cloud defining the query point + * \param[out] point_idx_data the resultant indices of the neighboring voxel points + * \return "true" if leaf node exist; "false" otherwise + */ + bool + voxelSearch (const int index, std::vector& point_idx_data); + + /** \brief Search for k-nearest neighbors at the query point. + * \param[in] cloud the point cloud data + * \param[in] index the index in \a cloud representing the query point + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + */ + inline int + nearestKSearch (const PointCloud &cloud, int index, int k, std::vector &k_indices, + std::vector &k_sqr_distances) + { + return (nearestKSearch (cloud[index], k, k_indices, k_sqr_distances)); + } + + /** \brief Search for k-nearest neighbors at given query point. + * \param[in] p_q the given query point + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to k a priori!) + * \return number of neighbors found + */ + int + nearestKSearch (const PointT &p_q, int k, std::vector &k_indices, + std::vector &k_sqr_distances); + + /** \brief Search for k-nearest neighbors at query point + * \param[in] index index representing the query point in the dataset given by \a setInputCloud. + * If indices were given in setInputCloud, index will be the position in the indices vector. + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + */ + int + nearestKSearch (int index, int k, std::vector &k_indices, std::vector &k_sqr_distances); + + /** \brief Search for approx. nearest neighbor at the query point. + * \param[in] cloud the point cloud data + * \param[in] query_index the index in \a cloud representing the query point + * \param[out] result_index the resultant index of the neighbor point + * \param[out] sqr_distance the resultant squared distance to the neighboring point + * \return number of neighbors found + */ + inline void + approxNearestSearch (const PointCloud &cloud, int query_index, int &result_index, float &sqr_distance) + { + return (approxNearestSearch (cloud.points[query_index], result_index, sqr_distance)); + } + + /** \brief Search for approx. nearest neighbor at the query point. + * \param[in] p_q the given query point + * \param[out] result_index the resultant index of the neighbor point + * \param[out] sqr_distance the resultant squared distance to the neighboring point + */ + void + approxNearestSearch (const PointT &p_q, int &result_index, float &sqr_distance); + + /** \brief Search for approx. nearest neighbor at the query point. + * \param[in] query_index index representing the query point in the dataset given by \a setInputCloud. + * If indices were given in setInputCloud, index will be the position in the indices vector. + * \param[out] result_index the resultant index of the neighbor point + * \param[out] sqr_distance the resultant squared distance to the neighboring point + * \return number of neighbors found + */ + void + approxNearestSearch (int query_index, int &result_index, float &sqr_distance); + + /** \brief Search for all neighbors of query point that are within a given radius. + * \param[in] cloud the point cloud data + * \param[in] index the index in \a cloud representing the query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value + * \return number of neighbors found in radius + */ + int + radiusSearch (const PointCloud &cloud, int index, double radius, std::vector &k_indices, + std::vector &k_sqr_distances, unsigned int max_nn = 0) + { + return (radiusSearch (cloud.points[index], radius, k_indices, k_sqr_distances, max_nn)); + } + + /** \brief Search for all neighbors of query point that are within a given radius. + * \param[in] p_q the given query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value + * \return number of neighbors found in radius + */ + int + radiusSearch (const PointT &p_q, const double radius, std::vector &k_indices, + std::vector &k_sqr_distances, unsigned int max_nn = 0) const; + + /** \brief Search for all neighbors of query point that are within a given radius. + * \param[in] index index representing the query point in the dataset given by \a setInputCloud. + * If indices were given in setInputCloud, index will be the position in the indices vector + * \param[in] radius radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value + * \return number of neighbors found in radius + */ + int + radiusSearch (int index, const double radius, std::vector &k_indices, + std::vector &k_sqr_distances, unsigned int max_nn = 0) const; + + /** \brief Get a PointT vector of centers of all voxels that intersected by a ray (origin, direction). + * \param[in] origin ray origin + * \param[in] direction ray direction vector + * \param[out] voxel_center_list results are written to this vector of PointT elements + * \param[in] max_voxel_count stop raycasting when this many voxels intersected (0: disable) + * \return number of intersected voxels + */ + int + getIntersectedVoxelCenters (Eigen::Vector3f origin, Eigen::Vector3f direction, + AlignedPointTVector &voxel_center_list, int max_voxel_count = 0) const; + + /** \brief Get indices of all voxels that are intersected by a ray (origin, direction). + * \param[in] origin ray origin + * \param[in] direction ray direction vector + * \param[out] k_indices resulting point indices from intersected voxels + * \param[in] max_voxel_count stop raycasting when this many voxels intersected (0: disable) + * \return number of intersected voxels + */ + int + getIntersectedVoxelIndices (Eigen::Vector3f origin, Eigen::Vector3f direction, + std::vector &k_indices, + int max_voxel_count = 0) const; + + + /** \brief Search for points within rectangular search area + * \param[in] min_pt lower corner of search area + * \param[in] max_pt upper corner of search area + * \param[out] k_indices the resultant point indices + * \return number of points found within search area + */ + int + boxSearch (const Eigen::Vector3f &min_pt, const Eigen::Vector3f &max_pt, std::vector &k_indices) const; + + protected: + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Octree-based search routines & helpers + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Priority queue entry for branch nodes + * \note This class defines priority queue entries for the nearest neighbor search. + * \author Julius Kammerl (julius@kammerl.de) + */ + class prioBranchQueueEntry + { + public: + /** \brief Empty constructor */ + prioBranchQueueEntry () : + node (), point_distance (0), key () + { + } + + /** \brief Constructor for initializing priority queue entry. + * \param _node pointer to octree node + * \param _key octree key addressing voxel in octree structure + * \param[in] _point_distance distance of query point to voxel center + */ + prioBranchQueueEntry (OctreeNode* _node, OctreeKey& _key, float _point_distance) : + node (_node), point_distance (_point_distance), key (_key) + { + } + + /** \brief Operator< for comparing priority queue entries with each other. + * \param[in] rhs the priority queue to compare this against + */ + bool + operator < (const prioBranchQueueEntry rhs) const + { + return (this->point_distance > rhs.point_distance); + } + + /** \brief Pointer to octree node. */ + const OctreeNode* node; + + /** \brief Distance to query point. */ + float point_distance; + + /** \brief Octree key. */ + OctreeKey key; + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b Priority queue entry for point candidates + * \note This class defines priority queue entries for the nearest neighbor point candidates. + * \author Julius Kammerl (julius@kammerl.de) + */ + class prioPointQueueEntry + { + public: + + /** \brief Empty constructor */ + prioPointQueueEntry () : + point_idx_ (0), point_distance_ (0) + { + } + + /** \brief Constructor for initializing priority queue entry. + * \param[in] point_idx an index representing a point in the dataset given by \a setInputCloud + * \param[in] point_distance distance of query point to voxel center + */ + prioPointQueueEntry (unsigned int& point_idx, float point_distance) : + point_idx_ (point_idx), point_distance_ (point_distance) + { + } + + /** \brief Operator< for comparing priority queue entries with each other. + * \param[in] rhs priority queue to compare this against + */ + bool + operator< (const prioPointQueueEntry& rhs) const + { + return (this->point_distance_ < rhs.point_distance_); + } + + /** \brief Index representing a point in the dataset given by \a setInputCloud. */ + int point_idx_; + + /** \brief Distance to query point. */ + float point_distance_; + }; + + /** \brief Helper function to calculate the squared distance between two points + * \param[in] point_a point A + * \param[in] point_b point B + * \return squared distance between point A and point B + */ + float + pointSquaredDist (const PointT& point_a, const PointT& point_b) const; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + // Recursive search routine methods + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /** \brief Recursive search method that explores the octree and finds neighbors within a given radius + * \param[in] point query point + * \param[in] radiusSquared squared search radius + * \param[in] node current octree node to be explored + * \param[in] key octree key addressing a leaf node. + * \param[in] tree_depth current depth/level in the octree + * \param[out] k_indices vector of indices found to be neighbors of query point + * \param[out] k_sqr_distances squared distances of neighbors to query point + * \param[in] max_nn maximum of neighbors to be found + */ + void + getNeighborsWithinRadiusRecursive (const PointT& point, const double radiusSquared, + const BranchNode* node, const OctreeKey& key, + unsigned int tree_depth, std::vector& k_indices, + std::vector& k_sqr_distances, unsigned int max_nn) const; + + /** \brief Recursive search method that explores the octree and finds the K nearest neighbors + * \param[in] point query point + * \param[in] K amount of nearest neighbors to be found + * \param[in] node current octree node to be explored + * \param[in] key octree key addressing a leaf node. + * \param[in] tree_depth current depth/level in the octree + * \param[in] squared_search_radius squared search radius distance + * \param[out] point_candidates priority queue of nearest neigbor point candidates + * \return squared search radius based on current point candidate set found + */ + double + getKNearestNeighborRecursive (const PointT& point, unsigned int K, const BranchNode* node, + const OctreeKey& key, unsigned int tree_depth, + const double squared_search_radius, + std::vector& point_candidates) const; + + /** \brief Recursive search method that explores the octree and finds the approximate nearest neighbor + * \param[in] point query point + * \param[in] node current octree node to be explored + * \param[in] key octree key addressing a leaf node. + * \param[in] tree_depth current depth/level in the octree + * \param[out] result_index result index is written to this reference + * \param[out] sqr_distance squared distance to search + */ + void + approxNearestSearchRecursive (const PointT& point, const BranchNode* node, const OctreeKey& key, + unsigned int tree_depth, int& result_index, float& sqr_distance); + + /** \brief Recursively search the tree for all intersected leaf nodes and return a vector of voxel centers. + * This algorithm is based off the paper An Efficient Parametric Algorithm for Octree Traversal: + * http://wscg.zcu.cz/wscg2000/Papers_2000/X31.pdf + * \param[in] min_x octree nodes X coordinate of lower bounding box corner + * \param[in] min_y octree nodes Y coordinate of lower bounding box corner + * \param[in] min_z octree nodes Z coordinate of lower bounding box corner + * \param[in] max_x octree nodes X coordinate of upper bounding box corner + * \param[in] max_y octree nodes Y coordinate of upper bounding box corner + * \param[in] max_z octree nodes Z coordinate of upper bounding box corner + * \param[in] a + * \param[in] node current octree node to be explored + * \param[in] key octree key addressing a leaf node. + * \param[out] voxel_center_list results are written to this vector of PointT elements + * \param[in] max_voxel_count stop raycasting when this many voxels intersected (0: disable) + * \return number of voxels found + */ + int + getIntersectedVoxelCentersRecursive (double min_x, double min_y, double min_z, double max_x, double max_y, + double max_z, unsigned char a, const OctreeNode* node, + const OctreeKey& key, AlignedPointTVector &voxel_center_list, + int max_voxel_count) const; + + + /** \brief Recursive search method that explores the octree and finds points within a rectangular search area + * \param[in] min_pt lower corner of search area + * \param[in] max_pt upper corner of search area + * \param[in] node current octree node to be explored + * \param[in] key octree key addressing a leaf node. + * \param[in] tree_depth current depth/level in the octree + * \param[out] k_indices the resultant point indices + */ + void + boxSearchRecursive (const Eigen::Vector3f &min_pt, const Eigen::Vector3f &max_pt, const BranchNode* node, + const OctreeKey& key, unsigned int tree_depth, std::vector& k_indices) const; + + /** \brief Recursively search the tree for all intersected leaf nodes and return a vector of indices. + * This algorithm is based off the paper An Efficient Parametric Algorithm for Octree Traversal: + * http://wscg.zcu.cz/wscg2000/Papers_2000/X31.pdf + * \param[in] min_x octree nodes X coordinate of lower bounding box corner + * \param[in] min_y octree nodes Y coordinate of lower bounding box corner + * \param[in] min_z octree nodes Z coordinate of lower bounding box corner + * \param[in] max_x octree nodes X coordinate of upper bounding box corner + * \param[in] max_y octree nodes Y coordinate of upper bounding box corner + * \param[in] max_z octree nodes Z coordinate of upper bounding box corner + * \param[in] a + * \param[in] node current octree node to be explored + * \param[in] key octree key addressing a leaf node. + * \param[out] k_indices resulting indices + * \param[in] max_voxel_count stop raycasting when this many voxels intersected (0: disable) + * \return number of voxels found + */ + int + getIntersectedVoxelIndicesRecursive (double min_x, double min_y, double min_z, + double max_x, double max_y, double max_z, + unsigned char a, const OctreeNode* node, const OctreeKey& key, + std::vector &k_indices, + int max_voxel_count) const; + + /** \brief Initialize raytracing algorithm + * \param origin + * \param direction + * \param[in] min_x octree nodes X coordinate of lower bounding box corner + * \param[in] min_y octree nodes Y coordinate of lower bounding box corner + * \param[in] min_z octree nodes Z coordinate of lower bounding box corner + * \param[in] max_x octree nodes X coordinate of upper bounding box corner + * \param[in] max_y octree nodes Y coordinate of upper bounding box corner + * \param[in] max_z octree nodes Z coordinate of upper bounding box corner + * \param a + */ + inline void + initIntersectedVoxel (Eigen::Vector3f &origin, Eigen::Vector3f &direction, + double &min_x, double &min_y, double &min_z, + double &max_x, double &max_y, double &max_z, + unsigned char &a) const + { + // Account for division by zero when direction vector is 0.0 + const float epsilon = 1e-10f; + if (direction.x () == 0.0) + direction.x () = epsilon; + if (direction.y () == 0.0) + direction.y () = epsilon; + if (direction.z () == 0.0) + direction.z () = epsilon; + + // Voxel childIdx remapping + a = 0; + + // Handle negative axis direction vector + if (direction.x () < 0.0) + { + origin.x () = static_cast (this->min_x_) + static_cast (this->max_x_) - origin.x (); + direction.x () = -direction.x (); + a |= 4; + } + if (direction.y () < 0.0) + { + origin.y () = static_cast (this->min_y_) + static_cast (this->max_y_) - origin.y (); + direction.y () = -direction.y (); + a |= 2; + } + if (direction.z () < 0.0) + { + origin.z () = static_cast (this->min_z_) + static_cast (this->max_z_) - origin.z (); + direction.z () = -direction.z (); + a |= 1; + } + min_x = (this->min_x_ - origin.x ()) / direction.x (); + max_x = (this->max_x_ - origin.x ()) / direction.x (); + min_y = (this->min_y_ - origin.y ()) / direction.y (); + max_y = (this->max_y_ - origin.y ()) / direction.y (); + min_z = (this->min_z_ - origin.z ()) / direction.z (); + max_z = (this->max_z_ - origin.z ()) / direction.z (); + } + + /** \brief Find first child node ray will enter + * \param[in] min_x octree nodes X coordinate of lower bounding box corner + * \param[in] min_y octree nodes Y coordinate of lower bounding box corner + * \param[in] min_z octree nodes Z coordinate of lower bounding box corner + * \param[in] mid_x octree nodes X coordinate of bounding box mid line + * \param[in] mid_y octree nodes Y coordinate of bounding box mid line + * \param[in] mid_z octree nodes Z coordinate of bounding box mid line + * \return the first child node ray will enter + */ + inline int + getFirstIntersectedNode (double min_x, double min_y, double min_z, double mid_x, double mid_y, double mid_z) const + { + int currNode = 0; + + if (min_x > min_y) + { + if (min_x > min_z) + { + // max(min_x, min_y, min_z) is min_x. Entry plane is YZ. + if (mid_y < min_x) + currNode |= 2; + if (mid_z < min_x) + currNode |= 1; + } + else + { + // max(min_x, min_y, min_z) is min_z. Entry plane is XY. + if (mid_x < min_z) + currNode |= 4; + if (mid_y < min_z) + currNode |= 2; + } + } + else + { + if (min_y > min_z) + { + // max(min_x, min_y, min_z) is min_y. Entry plane is XZ. + if (mid_x < min_y) + currNode |= 4; + if (mid_z < min_y) + currNode |= 1; + } + else + { + // max(min_x, min_y, min_z) is min_z. Entry plane is XY. + if (mid_x < min_z) + currNode |= 4; + if (mid_y < min_z) + currNode |= 2; + } + } + + return currNode; + } + + /** \brief Get the next visited node given the current node upper + * bounding box corner. This function accepts three float values, and + * three int values. The function returns the ith integer where the + * ith float value is the minimum of the three float values. + * \param[in] x current nodes X coordinate of upper bounding box corner + * \param[in] y current nodes Y coordinate of upper bounding box corner + * \param[in] z current nodes Z coordinate of upper bounding box corner + * \param[in] a next node if exit Plane YZ + * \param[in] b next node if exit Plane XZ + * \param[in] c next node if exit Plane XY + * \return the next child node ray will enter or 8 if exiting + */ + inline int + getNextIntersectedNode (double x, double y, double z, int a, int b, int c) const + { + if (x < y) + { + if (x < z) + return a; + else + return c; + } + else + { + if (y < z) + return b; + else + return c; + } + + return 0; + } + + }; + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#else +#define PCL_INSTANTIATE_OctreePointCloudSearch(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudSearch; +#endif // PCL_NO_PRECOMPILE + +#endif // PCL_OCTREE_SEARCH_H_ diff --git a/pcl-1.7/pcl/outofcore/boost.h b/pcl-1.7/pcl/outofcore/boost.h new file mode 100644 index 0000000..951fffb --- /dev/null +++ b/pcl-1.7/pcl/outofcore/boost.h @@ -0,0 +1,58 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: boost.h 6913 2012-08-22 09:37:26Z stfox88 $ + */ + +#ifndef PCL_OUTOFCORE_BOOST_H_ +#define PCL_OUTOFCORE_BOOST_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#endif //PCL_OUTOFCORE_BOOST_H_ diff --git a/pcl-1.7/pcl/outofcore/cJSON.h b/pcl-1.7/pcl/outofcore/cJSON.h new file mode 100644 index 0000000..89f6a08 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/cJSON.h @@ -0,0 +1,136 @@ +/* + Copyright (c) 2009 Dave Gamble + + Permission is hereby granted, free of charge, to any person obtaining a copy + of this software and associated documentation files (the "Software"), to deal + in the Software without restriction, including without limitation the rights + to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in + all copies or substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + THE SOFTWARE. +*/ + +#ifndef cJSON__h +#define cJSON__h + +#include + +//make interop with c++ string easier +#include + +#ifdef __cplusplus +extern "C" +{ +#endif + +/* cJSON Types: */ +#define cJSON_False 0 +#define cJSON_True 1 +#define cJSON_NULL 2 +#define cJSON_Number 3 +#define cJSON_String 4 +#define cJSON_Array 5 +#define cJSON_Object 6 + +#define cJSON_IsReference 256 + +/* The cJSON structure: */ +typedef struct cJSON { + struct cJSON *next,*prev; /* next/prev allow you to walk array/object chains. Alternatively, use GetArraySize/GetArrayItem/GetObjectItem */ + struct cJSON *child; /* An array or object item will have a child pointer pointing to a chain of the items in the array/object. */ + + int type; /* The type of the item, as above. */ + + char *valuestring; /* The item's string, if type==cJSON_String */ + int valueint; /* The item's number, if type==cJSON_Number */ + double valuedouble; /* The item's number, if type==cJSON_Number */ + + char *string; /* The item's name string, if this item is the child of, or is in the list of subitems of an object. */ +} cJSON; + +typedef struct cJSON_Hooks { + void *(*malloc_fn)(size_t sz); + void (*free_fn)(void *ptr); +} cJSON_Hooks; + +/* Supply malloc, realloc and free functions to cJSON */ +PCLAPI(void) cJSON_InitHooks(cJSON_Hooks* hooks); + + +/* Supply a block of JSON, and this returns a cJSON object you can interrogate. Call cJSON_Delete when finished. */ +PCLAPI(cJSON *) cJSON_Parse(const char *value); +/* Render a cJSON entity to text for transfer/storage. Free the char* when finished. */ +PCLAPI(char *) cJSON_Print(cJSON *item); +/* Render a cJSON entity to text for transfer/storage without any formatting. Free the char* when finished. */ +PCLAPI(char *) cJSON_PrintUnformatted(cJSON *item); +/* Delete a cJSON entity and all subentities. */ +PCLAPI(void) cJSON_Delete(cJSON *c); +/* Render a cJSON entity to text for transfer/storage. */ +PCLAPI(void) cJSON_PrintStr(cJSON *item, std::string& s); +/* Render a cJSON entity to text for transfer/storage without any formatting. */ +PCLAPI(void) cJSON_PrintUnformattedStr(cJSON *item, std::string& s); + +/* Returns the number of items in an array (or object). */ +PCLAPI(int) cJSON_GetArraySize(cJSON *array); +/* Retrieve item number "item" from array "array". Returns NULL if unsuccessful. */ +PCLAPI(cJSON *) cJSON_GetArrayItem(cJSON *array,int item); +/* Get item "string" from object. Case insensitive. */ +PCLAPI(cJSON *) cJSON_GetObjectItem(cJSON *object,const char *string); + +/* For analysing failed parses. This returns a pointer to the parse error. You'll probably need to look a few chars back to make sense of it. Defined when cJSON_Parse() returns 0. 0 when cJSON_Parse() succeeds. */ +PCLAPI(const char *) cJSON_GetErrorPtr(); + +/* These calls create a cJSON item of the appropriate type. */ +PCLAPI(cJSON *) cJSON_CreateNull(); +PCLAPI(cJSON *) cJSON_CreateTrue(); +PCLAPI(cJSON *) cJSON_CreateFalse(); +PCLAPI(cJSON *) cJSON_CreateBool(int b); +PCLAPI(cJSON *) cJSON_CreateNumber(double num); +PCLAPI(cJSON *) cJSON_CreateString(const char *string); +PCLAPI(cJSON *) cJSON_CreateArray(); +PCLAPI(cJSON *) cJSON_CreateObject(); + +/* These utilities create an Array of count items. */ +PCLAPI(cJSON *) cJSON_CreateIntArray(int *numbers,int count); +PCLAPI(cJSON *) cJSON_CreateFloatArray(float *numbers,int count); +PCLAPI(cJSON *) cJSON_CreateDoubleArray(double *numbers,int count); +PCLAPI(cJSON *) cJSON_CreateStringArray(const char **strings,int count); + +/* Append item to the specified array/object. */ +PCLAPI(void) cJSON_AddItemToArray(cJSON *array, cJSON *item); +PCLAPI(void) cJSON_AddItemToObject(cJSON *object,const char *string,cJSON *item); +/* Append reference to item to the specified array/object. Use this when you want to add an existing cJSON to a new cJSON, but don't want to corrupt your existing cJSON. */ +PCLAPI(void) cJSON_AddItemReferenceToArray(cJSON *array, cJSON *item); +PCLAPI(void) cJSON_AddItemReferenceToObject(cJSON *object,const char *string,cJSON *item); + +/* Remove/Detatch items from Arrays/Objects. */ +PCLAPI(cJSON *) cJSON_DetachItemFromArray(cJSON *array,int which); +PCLAPI(void) cJSON_DeleteItemFromArray(cJSON *array,int which); +PCLAPI(cJSON *) cJSON_DetachItemFromObject(cJSON *object,const char *string); +PCLAPI(void) cJSON_DeleteItemFromObject(cJSON *object,const char *string); + +/* Update array items. */ +PCLAPI(void) cJSON_ReplaceItemInArray(cJSON *array,int which,cJSON *newitem); +PCLAPI(void) cJSON_ReplaceItemInObject(cJSON *object,const char *string,cJSON *newitem); + +#define cJSON_AddNullToObject(object,name) cJSON_AddItemToObject(object, name, cJSON_CreateNull()) +#define cJSON_AddTrueToObject(object,name) cJSON_AddItemToObject(object, name, cJSON_CreateTrue()) +#define cJSON_AddFalseToObject(object,name) cJSON_AddItemToObject(object, name, cJSON_CreateFalse()) +#define cJSON_AddNumberToObject(object,name,n) cJSON_AddItemToObject(object, name, cJSON_CreateNumber(n)) +#define cJSON_AddStringToObject(object,name,s) cJSON_AddItemToObject(object, name, cJSON_CreateString(s)) + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/pcl-1.7/pcl/outofcore/impl/lru_cache.hpp b/pcl-1.7/pcl/outofcore/impl/lru_cache.hpp new file mode 100644 index 0000000..a4784c8 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/impl/lru_cache.hpp @@ -0,0 +1,178 @@ + +#ifndef __PCL_OUTOFCORE_LRU_CACHE__ +#define __PCL_OUTOFCORE_LRU_CACHE__ + +#include +#include + +template +class LRUCacheItem +{ +public: + + virtual size_t + sizeOf () const + { + return sizeof (item); + } + + virtual + ~LRUCacheItem () { } + + T item; + size_t timestamp; +}; + +template +class LRUCache +{ +public: + + typedef std::list KeyIndex; + typedef typename KeyIndex::iterator KeyIndexIterator; + + typedef std::map > Cache; + typedef typename Cache::iterator CacheIterator; + + LRUCache (size_t c) : + capacity_ (c), size_ (0) + { + assert(capacity_ != 0); + } + + bool + hasKey (const KeyT& k) + { + return (cache_.find (k) != cache_.end ()); + } + + CacheItemT& + get (const KeyT& k) + { + // Get existing key + const CacheIterator it = cache_.find (k); + assert(it != cache_.end ()); + + // Move key to MRU key index + key_index_.splice (key_index_.end (), key_index_, (*it).second.second); + + // Return the retrieved item + return it->second.first; + } + + void + touch (const KeyT& key) + { + // Get existing key + const CacheIterator it = cache_.find (key); + assert(it != cache_.end ()); + + // Move key to MRU key index + key_index_.splice (key_index_.end (), key_index_, it->second.second); + } + + // Record a fresh key-value pair in the cache + bool + insert (const KeyT& key, const CacheItemT& value) + { + if (cache_.find (key) != cache_.end ()) + { + touch (key); + return true; + } + + size_t size = size_; + size_t item_size = value.sizeOf (); + int evict_count = 0; + + // Get LRU key iterator + KeyIndexIterator key_it = key_index_.begin (); + + while (size + item_size >= capacity_) + { + const CacheIterator cache_it = cache_.find (*key_it); + + // Get tail item (Least Recently Used) + size_t tail_timestamp = cache_it->second.first.timestamp; + size_t tail_size = cache_it->second.first.sizeOf (); + + // Check timestamp to see if we've completely filled the cache in one go + if (value.timestamp == tail_timestamp) + { + return false; + } + + size -= tail_size; + key_it++; + evict_count++; + } + + // Evict enough items to make room for the new item + evict (evict_count); + + size_ += item_size; + + // Insert most-recently-used key at the end of our key index + KeyIndexIterator it = key_index_.insert (key_index_.end (), key); + + // Add to cache + cache_.insert (std::make_pair (key, std::make_pair (value, it))); + + return true; + } + + void + setCapacity (size_t capacity) + { + capacity_ = capacity; + } + + CacheItemT& + tailItem () + { + const CacheIterator it = cache_.find (key_index_.front ()); + return it->second.first; + } + + size_t + sizeOf (const CacheItemT& value) + { + return value.sizeOf (); + } + + // Evict the least-recently-used item from the cache + bool + evict (int item_count=1) + { + for (int i=0; i < item_count; i++) + { + if (key_index_.empty ()) + return false; + + // Get LRU item + const CacheIterator it = cache_.find (key_index_.front ()); + assert(it != cache_.end()); + + // Remove LRU item from cache and key index + size_ -= it->second.first.sizeOf (); + cache_.erase (it); + key_index_.pop_front (); + } + + return true; + } + + // Cache capacity in kilobytes + size_t capacity_; + + // Current cache size in kilobytes + size_t size_; + + // LRU key index LRU[0] ... MRU[N] + KeyIndex key_index_; + + // LRU cache + Cache cache_; +}; + +#endif //__PCL_OUTOFCORE_LRU_CACHE__ diff --git a/pcl-1.7/pcl/outofcore/impl/monitor_queue.hpp b/pcl-1.7/pcl/outofcore/impl/monitor_queue.hpp new file mode 100644 index 0000000..e2a268f --- /dev/null +++ b/pcl-1.7/pcl/outofcore/impl/monitor_queue.hpp @@ -0,0 +1,42 @@ +//http://www.paulbridger.com/monitor_object/#ixzz2CeN1rr4P + +#ifndef PCL_OUTOFCORE_MONITOR_QUEUE_IMPL_H_ +#define PCL_OUTOFCORE_MONITOR_QUEUE_IMPL_H_ + +#include + +template +class MonitorQueue : boost::noncopyable +{ +public: + void + push (const DataT& newData) + { + boost::mutex::scoped_lock lock (monitor_mutex_); + queue_.push (newData); + item_available_.notify_one (); + } + + DataT + pop () + { + boost::mutex::scoped_lock lock (monitor_mutex_); + + if (queue_.empty ()) + { + item_available_.wait (lock); + } + + DataT temp (queue_.front ()); + queue_.pop (); + + return temp; + } + +private: + std::queue queue_; + boost::mutex monitor_mutex_; + boost::condition item_available_; +}; + +#endif //PCL_OUTOFCORE_MONITOR_QUEUE_IMPL_H_ diff --git a/pcl-1.7/pcl/outofcore/impl/octree_base.hpp b/pcl-1.7/pcl/outofcore/impl/octree_base.hpp new file mode 100644 index 0000000..3002f00 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/impl/octree_base.hpp @@ -0,0 +1,745 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012, Urban Robotics, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OUTOFCORE_OCTREE_BASE_IMPL_H_ +#define PCL_OUTOFCORE_OCTREE_BASE_IMPL_H_ + + +#include + +// JSON +#include + +#include +#include + +// C++ +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace outofcore + { + + //////////////////////////////////////////////////////////////////////////////// + //Static constants + //////////////////////////////////////////////////////////////////////////////// + + template + const std::string OutofcoreOctreeBase::TREE_EXTENSION_ = ".octree"; + + template + const int OutofcoreOctreeBase::OUTOFCORE_VERSION_ = static_cast(3); + + //////////////////////////////////////////////////////////////////////////////// + + template + OutofcoreOctreeBase::OutofcoreOctreeBase (const boost::filesystem::path& root_name, const bool load_all) + : root_node_ () + , read_write_mutex_ () + , metadata_ (new OutofcoreOctreeBaseMetadata ()) + , sample_percent_ (0.125) + , lod_filter_ptr_ (new pcl::RandomSample ()) + { + //validate the root filename + if (!this->checkExtension (root_name)) + { + PCL_THROW_EXCEPTION (PCLException, "[pcl::outofcore::OutofcoreOctreeBase] Bad extension. Outofcore Octrees must have a root node ending in .oct_idx\n"); + } + + // Create root_node_node + root_node_ = new OutofcoreOctreeBaseNode (root_name, NULL, load_all); + // Set root_node_nodes tree to the newly created tree + root_node_->m_tree_ = this; + + // Set the path to the outofcore octree metadata (unique to the root folder) ending in .octree + boost::filesystem::path treepath = root_name.parent_path () / (boost::filesystem::basename (root_name) + TREE_EXTENSION_); + + //Load the JSON metadata + metadata_->loadMetadataFromDisk (treepath); + } + + //////////////////////////////////////////////////////////////////////////////// + + template + OutofcoreOctreeBase::OutofcoreOctreeBase (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const double resolution_arg, const boost::filesystem::path& root_node_name, const std::string& coord_sys) + : root_node_() + , read_write_mutex_ () + , metadata_ (new OutofcoreOctreeBaseMetadata ()) + , sample_percent_ (0.125) + , lod_filter_ptr_ (new pcl::RandomSample ()) + { + //Enlarge the bounding box to a cube so our voxels will be cubes + Eigen::Vector3d tmp_min = min; + Eigen::Vector3d tmp_max = max; + this->enlargeToCube (tmp_min, tmp_max); + + //Compute the depth of the tree given the resolution + boost::uint64_t depth = this->calculateDepth (tmp_min, tmp_max, resolution_arg); + + //Create a new outofcore tree + this->init (depth, tmp_min, tmp_max, root_node_name, coord_sys); + } + + //////////////////////////////////////////////////////////////////////////////// + + template + OutofcoreOctreeBase::OutofcoreOctreeBase (const boost::uint64_t max_depth, const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::filesystem::path& root_node_name, const std::string& coord_sys) + : root_node_() + , read_write_mutex_ () + , metadata_ (new OutofcoreOctreeBaseMetadata ()) + , sample_percent_ (0.125) + , lod_filter_ptr_ (new pcl::RandomSample ()) + { + //Create a new outofcore tree + this->init (max_depth, min, max, root_node_name, coord_sys); + } + + //////////////////////////////////////////////////////////////////////////////// + template void + OutofcoreOctreeBase::init (const uint64_t& depth, const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::filesystem::path& root_name, const std::string& coord_sys) + { + //Validate the extension of the pathname + if (!this->checkExtension (root_name)) + { + PCL_THROW_EXCEPTION (PCLException, "[pcl::outofcore::OutofcoreOctreeBase] Bad extension. Outofcore Octrees must have a root node ending in .oct_idx\n"); + } + + //Check to make sure that we are not overwriting existing data + if (boost::filesystem::exists (root_name.parent_path ())) + { + PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeBase] A dir named %s already exists. Overwriting an existing tree is not supported.\n", root_name.parent_path ().c_str () ); + PCL_THROW_EXCEPTION ( PCLException, "[pcl::outofcore::OutofcoreOctreeBase] Directory exists; Overwriting an existing tree is not supported\n"); + } + + // Get fullpath and recreate directories + boost::filesystem::path dir = root_name.parent_path (); + + if (!boost::filesystem::exists (dir)) + { + boost::filesystem::create_directory (dir); + } + + Eigen::Vector3d tmp_min = min; + Eigen::Vector3d tmp_max = max; + this->enlargeToCube (tmp_min, tmp_max); + + // Create root node + root_node_= new OutofcoreOctreeBaseNode (tmp_min, tmp_max, this, root_name); + root_node_->m_tree_ = this; + + // Set root nodes file path + boost::filesystem::path treepath = dir / (boost::filesystem::basename (root_name) + TREE_EXTENSION_); + + //fill the fields of the metadata + metadata_->setCoordinateSystem (coord_sys); + metadata_->setDepth (depth); + metadata_->setLODPoints (depth+1); + metadata_->setMetadataFilename (treepath); + metadata_->setOutofcoreVersion (OUTOFCORE_VERSION_); + //metadata_->setPointType ( ); + + //save to disk + metadata_->serializeMetadataToDisk (); + } + + + //////////////////////////////////////////////////////////////////////////////// + template + OutofcoreOctreeBase::~OutofcoreOctreeBase () + { + root_node_->flushToDiskRecursive (); + + saveToFile (); + delete (root_node_); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::saveToFile () + { + this->metadata_->serializeMetadataToDisk (); + } + + //////////////////////////////////////////////////////////////////////////////// + + template boost::uint64_t + OutofcoreOctreeBase::addDataToLeaf (const AlignedPointTVector& p) + { + boost::unique_lock < boost::shared_mutex > lock (read_write_mutex_); + + const bool _FORCE_BB_CHECK = true; + + uint64_t pt_added = root_node_->addDataToLeaf (p, _FORCE_BB_CHECK); + + assert (p.size () == pt_added); + + return (pt_added); + } + + //////////////////////////////////////////////////////////////////////////////// + + template boost::uint64_t + OutofcoreOctreeBase::addPointCloud (PointCloudConstPtr point_cloud) + { + return (addDataToLeaf (point_cloud->points)); + } + + //////////////////////////////////////////////////////////////////////////////// + + template boost::uint64_t + OutofcoreOctreeBase::addPointCloud (pcl::PCLPointCloud2::Ptr &input_cloud, const bool skip_bb_check) + { + uint64_t pt_added = this->root_node_->addPointCloud (input_cloud, skip_bb_check) ; +// assert (input_cloud->width*input_cloud->height == pt_added); + return (pt_added); + } + + + //////////////////////////////////////////////////////////////////////////////// + + template boost::uint64_t + OutofcoreOctreeBase::addPointCloud_and_genLOD (PointCloudConstPtr point_cloud) + { + // Lock the tree while writing + boost::unique_lock < boost::shared_mutex > lock (read_write_mutex_); + boost::uint64_t pt_added = root_node_->addDataToLeaf_and_genLOD (point_cloud->points, false); + return (pt_added); + } + + //////////////////////////////////////////////////////////////////////////////// + + template boost::uint64_t + OutofcoreOctreeBase::addPointCloud_and_genLOD (pcl::PCLPointCloud2::Ptr &input_cloud) + { + // Lock the tree while writing + boost::unique_lock < boost::shared_mutex > lock (read_write_mutex_); + boost::uint64_t pt_added = root_node_->addPointCloud_and_genLOD (input_cloud); + + PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBase::%s] Points added %lu, points in input cloud, %lu\n",__FUNCTION__, pt_added, input_cloud->width*input_cloud->height ); + + assert ( input_cloud->width*input_cloud->height == pt_added ); + + return (pt_added); + } + + //////////////////////////////////////////////////////////////////////////////// + + template boost::uint64_t + OutofcoreOctreeBase::addDataToLeaf_and_genLOD (AlignedPointTVector& src) + { + // Lock the tree while writing + boost::unique_lock < boost::shared_mutex > lock (read_write_mutex_); + boost::uint64_t pt_added = root_node_->addDataToLeaf_and_genLOD (src, false); + return (pt_added); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::queryFrustum (const double planes[24], std::list& file_names) const + { + boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_); + root_node_->queryFrustum (planes, file_names, this->getTreeDepth()); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::queryFrustum(const double *planes, std::list& file_names, const boost::uint32_t query_depth) const + { + boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_); + root_node_->queryFrustum (planes, file_names, query_depth); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::queryFrustum ( + const double *planes, + const Eigen::Vector3d &eye, + const Eigen::Matrix4d &view_projection_matrix, + std::list& file_names, + const boost::uint32_t query_depth) const + { + boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_); + root_node_->queryFrustum (planes, eye, view_projection_matrix, file_names, query_depth); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::queryBBIncludes (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::uint64_t query_depth, AlignedPointTVector& dst) const + { + boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_); + dst.clear (); + PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBaseNode] Querying Bounding Box %.2lf %.2lf %.2lf, %.2lf %.2lf %.2lf", min[0], min[1], min[2], max[0], max[1], max[2]); + root_node_->queryBBIncludes (min, max, query_depth, dst); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::queryBBIncludes (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::uint64_t query_depth, const pcl::PCLPointCloud2::Ptr& dst_blob) const + { + boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_); + + dst_blob->data.clear (); + dst_blob->width = 0; + dst_blob->height =1; + + root_node_->queryBBIncludes ( min, max, query_depth, dst_blob ); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::queryBBIncludes_subsample (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::uint64_t query_depth, const double percent, AlignedPointTVector& dst) const + { + boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_); + dst.clear (); + root_node_->queryBBIncludes_subsample (min, max, query_depth, percent, dst); + } + + //////////////////////////////////////////////////////////////////////////////// + template void + OutofcoreOctreeBase::queryBoundingBox (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const int query_depth, const pcl::PCLPointCloud2::Ptr &dst_blob, double percent) + { + if (percent==1.0) + { + root_node_->queryBBIncludes (min, max, query_depth, dst_blob); + } + else + { + root_node_->queryBBIncludes_subsample (min, max, query_depth, dst_blob, percent); + } + } + + //////////////////////////////////////////////////////////////////////////////// + + template bool + OutofcoreOctreeBase::getBoundingBox (Eigen::Vector3d &min, Eigen::Vector3d &max) const + { + if (root_node_!= NULL) + { + root_node_->getBoundingBox (min, max); + return true; + } + return false; + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::printBoundingBox(const size_t query_depth) const + { + boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_); + root_node_->printBoundingBox (query_depth); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::getOccupiedVoxelCenters(AlignedPointTVector &voxel_centers, const size_t query_depth) const + { + boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_); + if (query_depth > metadata_->getDepth ()) + { + root_node_->getOccupiedVoxelCentersRecursive (voxel_centers, metadata_->getDepth ()); + } + else + { + root_node_->getOccupiedVoxelCentersRecursive (voxel_centers, query_depth); + } + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::getOccupiedVoxelCenters(std::vector > &voxel_centers, const size_t query_depth) const + { + boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_); + if (query_depth > metadata_->getDepth ()) + { + root_node_->getOccupiedVoxelCentersRecursive (voxel_centers, metadata_->getDepth ()); + } + else + { + root_node_->getOccupiedVoxelCentersRecursive (voxel_centers, query_depth); + } + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::queryBBIntersects (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::uint32_t query_depth, std::list& bin_name) const + { + boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_); + bin_name.clear (); +#if defined _MSC_VER + #pragma warning(push) + #pragma warning(disable : 4267) +#endif + root_node_->queryBBIntersects (min, max, query_depth, bin_name); +#if defined _MSC_VER + #pragma warning(pop) +#endif + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::writeVPythonVisual (const boost::filesystem::path filename) + { + std::ofstream f (filename.c_str ()); + + f << "from visual import *\n\n"; + + root_node_->writeVPythonVisual (f); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::flushToDisk () + { + root_node_->flushToDisk (); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::flushToDiskLazy () + { + root_node_->flushToDiskLazy (); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::convertToXYZ () + { + saveToFile (); + root_node_->convertToXYZ (); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::DeAllocEmptyNodeCache () + { + DeAllocEmptyNodeCache (root_node_); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::DeAllocEmptyNodeCache (OutofcoreOctreeBaseNode* current) + { + if (current->size () == 0) + { + current->flush_DeAlloc_this_only (); + } + + for (int i = 0; i < current->numchildren (); i++) + { + DeAllocEmptyNodeCache (current->children[i]); + } + + } + + //////////////////////////////////////////////////////////////////////////////// + template OutofcoreOctreeBaseNode* + OutofcoreOctreeBase::getBranchChildPtr (const BranchNode& branch_arg, unsigned char childIdx_arg) const + { + return (branch_arg.getChildPtr (childIdx_arg)); + } + + //////////////////////////////////////////////////////////////////////////////// + template pcl::Filter::Ptr + OutofcoreOctreeBase::getLODFilter () + { + return (lod_filter_ptr_); + } + + //////////////////////////////////////////////////////////////////////////////// + + template const pcl::Filter::ConstPtr + OutofcoreOctreeBase::getLODFilter () const + { + return (lod_filter_ptr_); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::setLODFilter (const pcl::Filter::Ptr& filter_arg) + { + lod_filter_ptr_ = filter_arg; + } + + //////////////////////////////////////////////////////////////////////////////// + + template bool + OutofcoreOctreeBase::getBinDimension (double& x, double& y) const + { + if (root_node_== NULL) + { + x = 0; + y = 0; + return (false); + } + + Eigen::Vector3d min, max; + this->getBoundingBox (min, max); + + double depth = static_cast (metadata_->getDepth ()); + Eigen::Vector3d diff = max-min; + + y = diff[1] * pow (.5, depth); + x = diff[0] * pow (.5, depth); + + return (true); + } + + //////////////////////////////////////////////////////////////////////////////// + + template double + OutofcoreOctreeBase::getVoxelSideLength (const boost::uint64_t& depth) const + { + Eigen::Vector3d min, max; + this->getBoundingBox (min, max); + double result = (max[0] - min[0]) * pow (.5, static_cast (metadata_->getDepth ())) * static_cast (1 << (metadata_->getDepth () - depth)); + return (result); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::buildLOD () + { + if (root_node_== NULL) + { + PCL_ERROR ("Root node is null; aborting buildLOD.\n"); + return; + } + + boost::unique_lock < boost::shared_mutex > lock (read_write_mutex_); + + const int number_of_nodes = 1; + + std::vector current_branch (number_of_nodes, static_cast(0)); + current_branch[0] = root_node_; + assert (current_branch.back () != 0); + this->buildLODRecursive (current_branch); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::printBoundingBox (OutofcoreOctreeBaseNode& node) const + { + Eigen::Vector3d min, max; + node.getBoundingBox (min,max); + PCL_INFO ("[pcl::outofcore::OutofcoreOctreeBase::%s] min(%lf,%lf,%lf), max(%lf,%lf,%lf)\n", __FUNCTION__, min[0], min[1], min[2], max[0], max[1], max[2]); + } + + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::buildLODRecursive (const std::vector& current_branch) + { + PCL_DEBUG ("%s Building LOD at depth %d",__PRETTY_FUNCTION__, current_branch.size ()); + + if (!current_branch.back ()) + { + return; + } + + if (current_branch.back ()->getNodeType () == pcl::octree::LEAF_NODE) + { + assert (current_branch.back ()->getDepth () == this->getDepth ()); + + BranchNode* leaf = current_branch.back (); + + pcl::PCLPointCloud2::Ptr leaf_input_cloud (new pcl::PCLPointCloud2 ()); + //read the data from the PCD file associated with the leaf; it is full resolution + leaf->read (leaf_input_cloud); + assert (leaf_input_cloud->width*leaf_input_cloud->height > 0); + + //go up the tree, re-downsampling the full resolution leaf cloud at lower and lower resolution + for (int64_t level = static_cast(current_branch.size ()-1); level >= 1; level--) + { + BranchNode* target_parent = current_branch[level-1]; + assert (target_parent != 0); + double exponent = static_cast(current_branch.size () - target_parent->getDepth ()); + double current_depth_sample_percent = pow (sample_percent_, exponent); + + assert (current_depth_sample_percent > 0.0); + //------------------------------------------------------------ + //subsample data: + // 1. Get indices from a random sample + // 2. Extract those indices with the extract indices class (in order to also get the complement) + //------------------------------------------------------------ + + lod_filter_ptr_->setInputCloud (leaf_input_cloud); + + //set sample size to 1/8 of total points (12.5%) + uint64_t sample_size = static_cast (static_cast (leaf_input_cloud->width*leaf_input_cloud->height) * current_depth_sample_percent); + + if (sample_size == 0) + sample_size = 1; + + lod_filter_ptr_->setSample (static_cast(sample_size)); + + //create our destination + pcl::PCLPointCloud2::Ptr downsampled_cloud (new pcl::PCLPointCloud2 ()); + + //create destination for indices + pcl::IndicesPtr downsampled_cloud_indices (new std::vector< int > ()); + lod_filter_ptr_->filter (*downsampled_cloud_indices); + + //extract the "random subset", size by setSampleSize + pcl::ExtractIndices extractor; + extractor.setInputCloud (leaf_input_cloud); + extractor.setIndices (downsampled_cloud_indices); + extractor.filter (*downsampled_cloud); + + //write to the target + if (downsampled_cloud->width*downsampled_cloud->height > 0) + { + target_parent->payload_->insertRange (downsampled_cloud); + this->incrementPointsInLOD (target_parent->getDepth (), downsampled_cloud->width*downsampled_cloud->height); + } + } + } + else//not at leaf, keep going down + { + //clear this node while walking down the tree in case we are updating the LOD + current_branch.back ()->clearData (); + + std::vector next_branch (current_branch); + + if (current_branch.back ()->hasUnloadedChildren ()) + { + current_branch.back ()->loadChildren (false); + } + + for (size_t i = 0; i < 8; i++) + { + next_branch.push_back (current_branch.back ()->getChildPtr (i)); + //skip that child if it doesn't exist + if (next_branch.back () != 0) + buildLODRecursive (next_branch); + + next_branch.pop_back (); + } + } + } + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::incrementPointsInLOD (boost::uint64_t depth, boost::uint64_t new_point_count) + { + if (std::numeric_limits::max () - metadata_->getLODPoints (depth) < new_point_count) + { + PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeBase::incrementPointsInLOD] Overflow error. Too many points in depth %d of outofcore octree with root at %s\n", depth, metadata_->getMetadataFilename().c_str()); + PCL_THROW_EXCEPTION (PCLException, "Overflow error"); + } + + metadata_->setLODPoints (depth, new_point_count, true /*true->increment*/); + } + + //////////////////////////////////////////////////////////////////////////////// + + template bool + OutofcoreOctreeBase::checkExtension (const boost::filesystem::path& path_name) + { + if (boost::filesystem::extension (path_name) != OutofcoreOctreeBaseNode::node_index_extension) + { + PCL_ERROR ( "[pcl::outofcore::OutofcoreOctreeBase] Wrong root node file extension: %s. The tree must have a root node ending in %s\n", boost::filesystem::extension (path_name).c_str (), OutofcoreOctreeBaseNode::node_index_extension.c_str () ); + return (0); + } + + return (1); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBase::enlargeToCube (Eigen::Vector3d& bb_min, Eigen::Vector3d& bb_max) + { + Eigen::Vector3d diff = bb_max - bb_min; + assert (diff[0] > 0); + assert (diff[1] > 0); + assert (diff[2] > 0); + Eigen::Vector3d center = (bb_max + bb_min)/2.0; + + double max_sidelength = std::max (std::max (fabs (diff[0]), fabs (diff[1])), fabs (diff[2])); + assert (max_sidelength > 0); + bb_min = center - Eigen::Vector3d (1.0, 1.0, 1.0)*(max_sidelength/2.0); + bb_max = center + Eigen::Vector3d (1.0, 1.0, 1.0)*(max_sidelength/2.0); + } + + //////////////////////////////////////////////////////////////////////////////// + + template boost::uint64_t + OutofcoreOctreeBase::calculateDepth (const Eigen::Vector3d& min_bb, const Eigen::Vector3d& max_bb, const double leaf_resolution) + { + //Assume cube + double side_length = max_bb[0] - min_bb[0]; + + if (side_length < leaf_resolution) + return (0); + + boost::uint64_t res = static_cast (std::ceil (log2f (static_cast (side_length / leaf_resolution)))); + + PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBase::calculateDepth] Setting depth to %d\n",res); + return (res); + } + }//namespace outofcore +}//namespace pcl + +#endif //PCL_OUTOFCORE_OCTREE_BASE_IMPL_H_ diff --git a/pcl-1.7/pcl/outofcore/impl/octree_base_node.hpp b/pcl-1.7/pcl/outofcore/impl/octree_base_node.hpp new file mode 100644 index 0000000..dacaeb1 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/impl/octree_base_node.hpp @@ -0,0 +1,2208 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012, Urban Robotics, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_OUTOFCORE_OCTREE_BASE_NODE_IMPL_H_ +#define PCL_OUTOFCORE_OCTREE_BASE_NODE_IMPL_H_ + +// C++ +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +// JSON +#include + +namespace pcl +{ + namespace outofcore + { + + template + const std::string OutofcoreOctreeBaseNode::node_index_basename = "node"; + + template + const std::string OutofcoreOctreeBaseNode::node_container_basename = "node"; + + template + const std::string OutofcoreOctreeBaseNode::node_index_extension = ".oct_idx"; + + template + const std::string OutofcoreOctreeBaseNode::node_container_extension = ".oct_dat"; + + template + boost::mutex OutofcoreOctreeBaseNode::rng_mutex_; + + template + boost::mt19937 OutofcoreOctreeBaseNode::rand_gen_; + + template + const double OutofcoreOctreeBaseNode::sample_percent_ = .125; + + template + const std::string OutofcoreOctreeBaseNode::pcd_extension = ".pcd"; + + template + OutofcoreOctreeBaseNode::OutofcoreOctreeBaseNode () + : m_tree_ () + , root_node_ (NULL) + , parent_ (NULL) + , depth_ (0) + , children_ (std::vector *> (8,static_cast*>(0))) + , num_children_ (0) + , num_loaded_children_ (0) + , payload_ () + , node_metadata_ () + { + node_metadata_ = boost::shared_ptr (new OutofcoreOctreeNodeMetadata ()); + node_metadata_->setOutofcoreVersion (3); + } + + //////////////////////////////////////////////////////////////////////////////// + + template + OutofcoreOctreeBaseNode::OutofcoreOctreeBaseNode (const boost::filesystem::path& directory_path, OutofcoreOctreeBaseNode* super, bool load_all) + : m_tree_ () + , root_node_ () + , parent_ (super) + , depth_ () + , children_ (std::vector *> (8,static_cast*>(0))) + , num_children_ (0) + , num_loaded_children_ (0) + , payload_ () + , node_metadata_ () + { + node_metadata_ = boost::shared_ptr (new OutofcoreOctreeNodeMetadata ()); + node_metadata_->setOutofcoreVersion (3); + + //Check if this is the first node created/loaded (this is true if super, i.e. node's parent is NULL) + if (super == NULL) + { + node_metadata_->setDirectoryPathname (directory_path.parent_path ()); + node_metadata_->setMetadataFilename (directory_path); + depth_ = 0; + root_node_ = this; + + //Check if the specified directory to load currently exists; if not, don't continue + if (!boost::filesystem::exists (node_metadata_->getDirectoryPathname ())) + { + PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeBaseNode] Could not find dir %s\n", node_metadata_->getDirectoryPathname ().c_str ()); + PCL_THROW_EXCEPTION (PCLException, "[pcl::outofcore::OutofcoreOctreeBaseNode] Outofcore Exception: missing directory"); + } + } + else + { + node_metadata_->setDirectoryPathname (directory_path); + depth_ = super->getDepth () + 1; + root_node_ = super->root_node_; + + boost::filesystem::directory_iterator directory_it_end; //empty constructor creates end of iterator + + //flag to test if the desired metadata file was found + bool b_loaded = 0; + + for (boost::filesystem::directory_iterator directory_it (node_metadata_->getDirectoryPathname ()); directory_it != directory_it_end; ++directory_it) + { + const boost::filesystem::path& file = *directory_it; + + if (!boost::filesystem::is_directory (file)) + { + if (boost::filesystem::extension (file) == node_index_extension) + { + b_loaded = node_metadata_->loadMetadataFromDisk (file); + break; + } + } + } + + if (!b_loaded) + { + PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeBaseNode] Could not find index\n"); + PCL_THROW_EXCEPTION (PCLException, "[pcl::outofcore::OutofcoreOctreeBaseNode] Outofcore: Could not find node index"); + } + } + + //load the metadata + loadFromFile (node_metadata_->getMetadataFilename (), super); + + //set the number of children in this node + num_children_ = this->countNumChildren (); + + if (load_all) + { + loadChildren (true); + } + } +//////////////////////////////////////////////////////////////////////////////// + + template + OutofcoreOctreeBaseNode::OutofcoreOctreeBaseNode (const Eigen::Vector3d& bb_min, const Eigen::Vector3d& bb_max, OutofcoreOctreeBase * const tree, const boost::filesystem::path& root_name) + : m_tree_ (tree) + , root_node_ () + , parent_ () + , depth_ () + , children_ (std::vector *> (8,static_cast*> (0))) + , num_children_ (0) + , num_loaded_children_ (0) + , payload_ () + , node_metadata_ (new OutofcoreOctreeNodeMetadata ()) + { + assert (tree != NULL); + node_metadata_->setOutofcoreVersion (3); + init_root_node (bb_min, bb_max, tree, root_name); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::init_root_node (const Eigen::Vector3d& bb_min, const Eigen::Vector3d& bb_max, OutofcoreOctreeBase * const tree, const boost::filesystem::path& root_name) + { + assert (tree != NULL); + + parent_ = NULL; + root_node_ = this; + m_tree_ = tree; + depth_ = 0; + + //Mark the children as unallocated + num_children_ = 0; + + Eigen::Vector3d tmp_max = bb_max; + Eigen::Vector3d tmp_min = bb_min; + + // Need to make the bounding box slightly bigger so points that fall on the max side aren't excluded + double epsilon = 1e-8; + tmp_max = tmp_max + epsilon*Eigen::Vector3d (1.0, 1.0, 1.0); + + node_metadata_->setBoundingBox (tmp_min, tmp_max); + node_metadata_->setDirectoryPathname (root_name.parent_path ()); + node_metadata_->setOutofcoreVersion (3); + + // If the root directory doesn't exist create it + if (!boost::filesystem::exists (node_metadata_->getDirectoryPathname ())) + { + boost::filesystem::create_directory (node_metadata_->getDirectoryPathname ()); + } + // If the root directory is a file, do not continue + else if (!boost::filesystem::is_directory (node_metadata_->getDirectoryPathname ())) + { + PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeBaseNode] Need empty directory structure. Dir %s exists and is a file.\n",node_metadata_->getDirectoryPathname ().c_str ()); + PCL_THROW_EXCEPTION (PCLException, "[pcl::outofcore::OutofcoreOctreeBaseNode] Bad Path: Directory Already Exists"); + } + + // Create a unique id for node file name + std::string uuid; + + OutofcoreOctreeDiskContainer::getRandomUUIDString (uuid); + + std::string node_container_name; + + node_container_name = uuid + std::string ("_") + node_container_basename + pcd_extension; + + node_metadata_->setMetadataFilename (node_metadata_->getDirectoryPathname () / root_name.filename ()); + node_metadata_->setPCDFilename (node_metadata_->getDirectoryPathname () / boost::filesystem::path (node_container_name)); + + boost::filesystem::create_directory (node_metadata_->getDirectoryPathname ()); + node_metadata_->serializeMetadataToDisk (); + + // Create data container, ie octree_disk_container, octree_ram_container + payload_ = boost::shared_ptr (new ContainerT (node_metadata_->getPCDFilename ())); + } + + //////////////////////////////////////////////////////////////////////////////// + + template + OutofcoreOctreeBaseNode::~OutofcoreOctreeBaseNode () + { + // Recursively delete all children and this nodes data + recFreeChildren (); + } + + //////////////////////////////////////////////////////////////////////////////// + + template size_t + OutofcoreOctreeBaseNode::countNumChildren () const + { + size_t child_count = 0; + + for(size_t i=0; i<8; i++) + { + boost::filesystem::path child_path = this->node_metadata_->getDirectoryPathname () / boost::filesystem::path (boost::lexical_cast (i)); + if (boost::filesystem::exists (child_path)) + child_count++; + } + return (child_count); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::saveIdx (bool recursive) + { + node_metadata_->serializeMetadataToDisk (); + + if (recursive) + { + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + children_[i]->saveIdx (true); + } + } + } + + //////////////////////////////////////////////////////////////////////////////// + + template bool + OutofcoreOctreeBaseNode::hasUnloadedChildren () const + { + if (this->getNumLoadedChildren () < this->getNumChildren ()) + return (true); + else + return (false); + } + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::loadChildren (bool recursive) + { + //if we have fewer children loaded than exist on disk, load them + if (num_loaded_children_ < this->getNumChildren ()) + { + //check all 8 possible child directories + for (int i = 0; i < 8; i++) + { + boost::filesystem::path child_dir = node_metadata_->getDirectoryPathname () / boost::filesystem::path (boost::lexical_cast (i)); + //if the directory exists and the child hasn't been created (set to 0 by this node's constructor) + if (boost::filesystem::exists (child_dir) && this->children_[i] == 0) + { + //load the child node + this->children_[i] = new OutofcoreOctreeBaseNode (child_dir, this, recursive); + //keep track of the children loaded + num_loaded_children_++; + } + } + } + assert (num_loaded_children_ == this->getNumChildren ()); + } + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::recFreeChildren () + { + if (num_children_ == 0) + { + return; + } + + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + { + OutofcoreOctreeBaseNode* current = children_[i]; + delete (current); + } + } + children_.resize (8, static_cast* > (0)); + num_children_ = 0; + } + //////////////////////////////////////////////////////////////////////////////// + + template uint64_t + OutofcoreOctreeBaseNode::addDataToLeaf (const AlignedPointTVector& p, const bool skip_bb_check) + { + //quit if there are no points to add + if (p.empty ()) + { + return (0); + } + + //if this depth is the max depth of the tree, then add the points + if (this->depth_ == this->root_node_->m_tree_->getDepth ()) + return (addDataAtMaxDepth( p, skip_bb_check)); + + if (hasUnloadedChildren ()) + loadChildren (false); + + std::vector < std::vector > c; + c.resize (8); + for (size_t i = 0; i < 8; i++) + { + c[i].reserve (p.size () / 8); + } + + const size_t len = p.size (); + for (size_t i = 0; i < len; i++) + { + const PointT& pt = p[i]; + + if (!skip_bb_check) + { + if (!this->pointInBoundingBox (pt)) + { + PCL_ERROR ( "[pcl::outofcore::OutofcoreOctreeBaseNode::%s] Failed to place point within bounding box\n", __FUNCTION__ ); + continue; + } + } + + uint8_t box = 0; + Eigen::Vector3d mid_xyz = node_metadata_->getVoxelCenter (); + + box = static_cast(((pt.z >= mid_xyz[2]) << 2) | ((pt.y >= mid_xyz[1]) << 1) | ((pt.x >= mid_xyz[0]) << 0)); + c[static_cast(box)].push_back (&pt); + } + + boost::uint64_t points_added = 0; + for (size_t i = 0; i < 8; i++) + { + if (c[i].empty ()) + continue; + if (!children_[i]) + createChild (i); + points_added += children_[i]->addDataToLeaf (c[i], true); + c[i].clear (); + } + return (points_added); + } + //////////////////////////////////////////////////////////////////////////////// + + + template boost::uint64_t + OutofcoreOctreeBaseNode::addDataToLeaf (const std::vector& p, const bool skip_bb_check) + { + if (p.empty ()) + { + return (0); + } + + if (this->depth_ == this->root_node_->m_tree_->getDepth ()) + { + //trust me, just add the points + if (skip_bb_check) + { + root_node_->m_tree_->incrementPointsInLOD (this->depth_, p.size ()); + + payload_->insertRange (p.data (), p.size ()); + + return (p.size ()); + } + else//check which points belong to this node, throw away the rest + { + std::vector buff; + BOOST_FOREACH(const PointT* pt, p) + { + if(pointInBoundingBox(*pt)) + { + buff.push_back(pt); + } + } + + if (!buff.empty ()) + { + root_node_->m_tree_->incrementPointsInLOD (this->depth_, buff.size ()); + payload_->insertRange (buff.data (), buff.size ()); +// payload_->insertRange ( buff ); + + } + return (buff.size ()); + } + } + else + { + if (this->hasUnloadedChildren ()) + { + loadChildren (false); + } + + std::vector < std::vector > c; + c.resize (8); + for (size_t i = 0; i < 8; i++) + { + c[i].reserve (p.size () / 8); + } + + const size_t len = p.size (); + for (size_t i = 0; i < len; i++) + { + //const PointT& pt = p[i]; + if (!skip_bb_check) + { + if (!this->pointInBoundingBox (*p[i])) + { + // std::cerr << "failed to place point!!!" << std::endl; + continue; + } + } + + uint8_t box = 00; + Eigen::Vector3d mid_xyz = node_metadata_->getVoxelCenter (); + //hash each coordinate to the appropriate octant + box = static_cast (((p[i]->z >= mid_xyz[2]) << 2) | ((p[i]->y >= mid_xyz[1]) << 1) | ((p[i]->x >= mid_xyz[0] ))); + //3 bit, 8 octants + c[box].push_back (p[i]); + } + + boost::uint64_t points_added = 0; + for (size_t i = 0; i < 8; i++) + { + if (c[i].empty ()) + continue; + if (!children_[i]) + createChild (i); + points_added += children_[i]->addDataToLeaf (c[i], true); + c[i].clear (); + } + return (points_added); + } + // std::cerr << "failed to place point!!!" << std::endl; + return (0); + } + //////////////////////////////////////////////////////////////////////////////// + + + template boost::uint64_t + OutofcoreOctreeBaseNode::addPointCloud (const typename pcl::PCLPointCloud2::Ptr& input_cloud, const bool skip_bb_check) + { + assert (this->root_node_->m_tree_ != NULL); + + if (input_cloud->height*input_cloud->width == 0) + return (0); + + if (this->depth_ == this->root_node_->m_tree_->getDepth ()) + return (addDataAtMaxDepth (input_cloud, true)); + + if( num_children_ < 8 ) + if(hasUnloadedChildren ()) + loadChildren (false); + + if( skip_bb_check == false ) + { + + //indices to store the points for each bin + //these lists will be used to copy data to new point clouds and pass down recursively + std::vector < std::vector > indices; + indices.resize (8); + + this->sortOctantIndices (input_cloud, indices, node_metadata_->getVoxelCenter ()); + + for(size_t k=0; kaddPointCloud (dst_cloud, false); + indices[i].clear (); + } + + return (points_added); + } + + PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeBaseNode] Skipped bounding box check. Points not inserted\n"); + + return 0; + } + + + //////////////////////////////////////////////////////////////////////////////// + template void + OutofcoreOctreeBaseNode::randomSample(const AlignedPointTVector& p, AlignedPointTVector& insertBuff, const bool skip_bb_check) + { + assert (this->root_node_->m_tree_ != NULL); + + AlignedPointTVector sampleBuff; + if (!skip_bb_check) + { + BOOST_FOREACH (const PointT& pt, p) + if(pointInBoundingBox(pt)) + sampleBuff.push_back(pt); + } + else + { + sampleBuff = p; + } + + // Derive percentage from specified sample_percent and tree depth + const double percent = pow(sample_percent_, double((this->root_node_->m_tree_->getDepth () - depth_))); + const uint64_t samplesize = static_cast(percent * static_cast(sampleBuff.size())); + const uint64_t inputsize = sampleBuff.size(); + + if(samplesize > 0) + { + // Resize buffer to sample size + insertBuff.resize(samplesize); + + // Create random number generator + boost::mutex::scoped_lock lock(rng_mutex_); + boost::uniform_int buffdist(0, inputsize-1); + boost::variate_generator > buffdie(rand_gen_, buffdist); + + // Randomly pick sampled points + for(boost::uint64_t i = 0; i < samplesize; ++i) + { + boost::uint64_t buffstart = buffdie(); + insertBuff[i] = ( sampleBuff[buffstart] ); + } + } + // Have to do it the slow way + else + { + boost::mutex::scoped_lock lock(rng_mutex_); + boost::bernoulli_distribution buffdist(percent); + boost::variate_generator > buffcoin(rand_gen_, buffdist); + + for(boost::uint64_t i = 0; i < inputsize; ++i) + if(buffcoin()) + insertBuff.push_back( p[i] ); + } + } + //////////////////////////////////////////////////////////////////////////////// + + template boost::uint64_t + OutofcoreOctreeBaseNode::addDataAtMaxDepth (const AlignedPointTVector& p, const bool skip_bb_check) + { + assert (this->root_node_->m_tree_ != NULL); + + // Trust me, just add the points + if (skip_bb_check) + { + // Increment point count for node + root_node_->m_tree_->incrementPointsInLOD (this->depth_, p.size ()); + + // Insert point data + payload_->insertRange ( p ); + + return (p.size ()); + } + + // Add points found within the current node's bounding box + else + { + AlignedPointTVector buff; + const size_t len = p.size (); + + for (size_t i = 0; i < len; i++) + { + if (pointInBoundingBox (p[i])) + { + buff.push_back (p[i]); + } + } + + if (!buff.empty ()) + { + root_node_->m_tree_->incrementPointsInLOD (this->depth_, buff.size ()); + payload_->insertRange ( buff ); + + } + return (buff.size ()); + } + } + //////////////////////////////////////////////////////////////////////////////// + template boost::uint64_t + OutofcoreOctreeBaseNode::addDataAtMaxDepth (const pcl::PCLPointCloud2::Ptr input_cloud, const bool skip_bb_check) + { + //this assumes data is already in the correct bin + if(skip_bb_check == true) + { + PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBaseNode::%s] Adding %u points at max depth, %u\n",__FUNCTION__, input_cloud->width*input_cloud->height, this->depth_); + + this->root_node_->m_tree_->incrementPointsInLOD (this->depth_, input_cloud->width*input_cloud->height ); + payload_->insertRange (input_cloud); + + return (input_cloud->width*input_cloud->height); + } + else + { + PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeBaseNode] Not implemented\n"); + return (0); + } + } + + + //////////////////////////////////////////////////////////////////////////////// + template void + OutofcoreOctreeBaseNode::subdividePoints (const AlignedPointTVector &p, std::vector< AlignedPointTVector > &c, const bool skip_bb_check) + { + // Reserve space for children nodes + c.resize(8); + for(size_t i = 0; i < 8; i++) + c[i].reserve(p.size() / 8); + + const size_t len = p.size(); + for(size_t i = 0; i < len; i++) + { + const PointT& pt = p[i]; + + if(!skip_bb_check) + if(!this->pointInBoundingBox(pt)) + continue; + + subdividePoint (pt, c); + } + } + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::subdividePoint (const PointT& point, std::vector< AlignedPointTVector >& c) + { + Eigen::Vector3d mid_xyz = node_metadata_->getVoxelCenter (); + size_t octant = 0; + octant = ((point.z >= mid_xyz[2]) << 2) | ((point.y >= mid_xyz[1]) << 1) | ((point.x >= mid_xyz[0]) << 0); + c[octant].push_back (point); + } + + //////////////////////////////////////////////////////////////////////////////// + template boost::uint64_t + OutofcoreOctreeBaseNode::addPointCloud_and_genLOD (const pcl::PCLPointCloud2::Ptr input_cloud) //, const bool skip_bb_check = false ) + { + boost::uint64_t points_added = 0; + + if ( input_cloud->width * input_cloud->height == 0 ) + { + return (0); + } + + if ( this->depth_ == this->root_node_->m_tree_->getDepth () || input_cloud->width*input_cloud->height < 8 ) + { + uint64_t points_added = addDataAtMaxDepth (input_cloud, true); + assert (points_added > 0); + return (points_added); + } + + if (num_children_ < 8 ) + { + if ( hasUnloadedChildren () ) + { + loadChildren (false); + } + } + + //------------------------------------------------------------ + //subsample data: + // 1. Get indices from a random sample + // 2. Extract those indices with the extract indices class (in order to also get the complement) + //------------------------------------------------------------ + pcl::RandomSample random_sampler; + random_sampler.setInputCloud (input_cloud); + + //set sample size to 1/8 of total points (12.5%) + uint64_t sample_size = input_cloud->width*input_cloud->height / 8; + random_sampler.setSample (static_cast (sample_size)); + + //create our destination + pcl::PCLPointCloud2::Ptr downsampled_cloud ( new pcl::PCLPointCloud2 () ); + + //create destination for indices + pcl::IndicesPtr downsampled_cloud_indices ( new std::vector< int > () ); + random_sampler.filter (*downsampled_cloud_indices); + + //extract the "random subset", size by setSampleSize + pcl::ExtractIndices extractor; + extractor.setInputCloud (input_cloud); + extractor.setIndices (downsampled_cloud_indices); + extractor.filter (*downsampled_cloud); + + //extract the complement of those points (i.e. everything remaining) + pcl::PCLPointCloud2::Ptr remaining_points ( new pcl::PCLPointCloud2 () ); + extractor.setNegative (true); + extractor.filter (*remaining_points); + + PCL_DEBUG ( "[pcl::outofcore::OutofcoreOctreeBaseNode::%s] Random sampled: %lu of %lu\n", __FUNCTION__, downsampled_cloud->width * downsampled_cloud->height, input_cloud->width * input_cloud->height ); + + //insert subsampled data to the node's disk container payload + if ( downsampled_cloud->width * downsampled_cloud->height != 0 ) + { + root_node_->m_tree_->incrementPointsInLOD ( this->depth_, downsampled_cloud->width * downsampled_cloud->height ); + payload_->insertRange (downsampled_cloud); + points_added += downsampled_cloud->width*downsampled_cloud->height ; + } + + PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBaseNode::%s] Remaining points are %u\n",__FUNCTION__, remaining_points->width*remaining_points->height); + + //subdivide remaining data by destination octant + std::vector > indices; + indices.resize (8); + + this->sortOctantIndices (remaining_points, indices, node_metadata_->getVoxelCenter ()); + + //pass each set of points to the appropriate child octant + for(size_t i=0; i<8; i++) + { + + if(indices[i].empty ()) + continue; + + if( children_[i] == false ) + { + assert (i < 8); + createChild (i); + } + + //copy correct indices into a temporary cloud + pcl::PCLPointCloud2::Ptr tmp_local_point_cloud (new pcl::PCLPointCloud2 ()); + pcl::copyPointCloud (*remaining_points, indices[i], *tmp_local_point_cloud); + + //recursively add points and keep track of how many were successfully added to the tree + points_added += children_[i]->addPointCloud_and_genLOD (tmp_local_point_cloud); + PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBaseNode::%s] points_added: %lu, indices[i].size: %lu, tmp_local_point_cloud size: %lu\n", __FUNCTION__, points_added, indices[i].size (), tmp_local_point_cloud->width*tmp_local_point_cloud->height); + + } + assert (points_added == input_cloud->width*input_cloud->height); + return (points_added); + } + //////////////////////////////////////////////////////////////////////////////// + + template boost::uint64_t + OutofcoreOctreeBaseNode::addDataToLeaf_and_genLOD (const AlignedPointTVector& p, const bool skip_bb_check) + { + // If there are no points return + if (p.empty ()) + return (0); + + // when adding data and generating sampled LOD + // If the max depth has been reached + assert (this->root_node_->m_tree_ != NULL ); + + if (this->depth_ == this->root_node_->m_tree_->getDepth ()) + { + PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBaseNode::addDataToLeaf_and_genLOD] Adding data to the leaves\n"); + return (addDataAtMaxDepth(p, false)); + } + + // Create child nodes of the current node but not grand children+ + if (this->hasUnloadedChildren ()) + loadChildren (false /*no recursive loading*/); + + // Randomly sample data + AlignedPointTVector insertBuff; + randomSample(p, insertBuff, skip_bb_check); + + if(!insertBuff.empty()) + { + // Increment point count for node + root_node_->m_tree_->incrementPointsInLOD (this->depth_, insertBuff.size()); + // Insert sampled point data + payload_->insertRange (insertBuff); + + } + + //subdivide vec to pass data down lower + std::vector c; + subdividePoints(p, c, skip_bb_check); + + boost::uint64_t points_added = 0; + for(size_t i = 0; i < 8; i++) + { + // If child doesn't have points + if(c[i].empty()) + continue; + + // If child doesn't exist + if(!children_[i]) + createChild(i); + + // Recursively build children + points_added += children_[i]->addDataToLeaf_and_genLOD(c[i], true); + c[i].clear(); + } + + return (points_added); + } + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::createChild (const size_t idx) + { + assert (idx < 8); + + //if already has 8 children, return + if (children_[idx] || (num_children_ == 8)) + { + PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeBaseNode::createChild] Not allowed to create a 9th child of %s",this->node_metadata_->getMetadataFilename ().c_str ()); + return; + } + + Eigen::Vector3d start = node_metadata_->getBoundingBoxMin (); + Eigen::Vector3d step = (node_metadata_->getBoundingBoxMax () - start)/static_cast(2.0); + + Eigen::Vector3d childbb_min; + Eigen::Vector3d childbb_max; + + int x, y, z; + if (idx > 3) + { + x = ((idx == 5) || (idx == 7)) ? 1 : 0; + y = ((idx == 6) || (idx == 7)) ? 1 : 0; + z = 1; + } + else + { + x = ((idx == 1) || (idx == 3)) ? 1 : 0; + y = ((idx == 2) || (idx == 3)) ? 1 : 0; + z = 0; + } + + childbb_min[2] = start[2] + static_cast (z) * step[2]; + childbb_max[2] = start[2] + static_cast (z + 1) * step[2]; + + childbb_min[1] = start[1] + static_cast (y) * step[1]; + childbb_max[1] = start[1] + static_cast (y + 1) * step[1]; + + childbb_min[0] = start[0] + static_cast (x) * step[0]; + childbb_max[0] = start[0] + static_cast (x + 1) * step[0]; + + boost::filesystem::path childdir = node_metadata_->getDirectoryPathname () / boost::filesystem::path (boost::lexical_cast (idx)); + children_[idx] = new OutofcoreOctreeBaseNode (childbb_min, childbb_max, childdir.string ().c_str (), this); + + num_children_++; + } + //////////////////////////////////////////////////////////////////////////////// + + template bool + pointInBoundingBox (const Eigen::Vector3d& min_bb, const Eigen::Vector3d& max_bb, const Eigen::Vector3d& point) + { + if (((min_bb[0] <= point[0]) && (point[0] < max_bb[0])) && + ((min_bb[1] <= point[1]) && (point[1] < max_bb[1])) && + ((min_bb[2] <= point[2]) && (point[2] < max_bb[2]))) + { + return (true); + + } + return (false); + } + + + //////////////////////////////////////////////////////////////////////////////// + template bool + OutofcoreOctreeBaseNode::pointInBoundingBox (const PointT& p) const + { + const Eigen::Vector3d& min = node_metadata_->getBoundingBoxMin (); + const Eigen::Vector3d& max = node_metadata_->getBoundingBoxMax (); + + if (((min[0] <= p.x) && (p.x < max[0])) && + ((min[1] <= p.y) && (p.y < max[1])) && + ((min[2] <= p.z) && (p.z < max[2]))) + { + return (true); + + } + return (false); + } + + //////////////////////////////////////////////////////////////////////////////// + template void + OutofcoreOctreeBaseNode::printBoundingBox (const size_t query_depth) const + { + Eigen::Vector3d min; + Eigen::Vector3d max; + node_metadata_->getBoundingBox (min, max); + + if (this->depth_ < query_depth){ + for (size_t i = 0; i < this->depth_; i++) + std::cout << " "; + + std::cout << "[" << min[0] << ", " << min[1] << ", " << min[2] << "] - "; + std::cout << "[" << max[0] << ", " << max[1] << ", " << max[2] << "] - "; + std::cout << "[" << max[0] - min[0] << ", " << max[1] - min[1]; + std::cout << ", " << max[2] - min[2] << "]" << std::endl; + + if (num_children_ > 0) + { + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + children_[i]->printBoundingBox (query_depth); + } + } + } + } + + //////////////////////////////////////////////////////////////////////////////// + template void + OutofcoreOctreeBaseNode::getOccupiedVoxelCentersRecursive (AlignedPointTVector &voxel_centers, const size_t query_depth) + { + if (this->depth_ < query_depth){ + if (num_children_ > 0) + { + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + children_[i]->getOccupiedVoxelCentersRecursive (voxel_centers, query_depth); + } + } + } + else + { + PointT voxel_center; + Eigen::Vector3d mid_xyz = node_metadata_->getVoxelCenter (); + voxel_center.x = static_cast(mid_xyz[0]); + voxel_center.y = static_cast(mid_xyz[1]); + voxel_center.z = static_cast(mid_xyz[2]); + + voxel_centers.push_back(voxel_center); + } + } + + //////////////////////////////////////////////////////////////////////////////// +// Eigen::Vector3d cornerOffsets[] = +// { +// Eigen::Vector3d(-1.0, -1.0, -1.0), // - - - +// Eigen::Vector3d( 1.0, -1.0, -1.0), // - - + +// Eigen::Vector3d(-1.0, 1.0, -1.0), // - + - +// Eigen::Vector3d( 1.0, 1.0, -1.0), // - + + +// Eigen::Vector3d(-1.0, -1.0, 1.0), // + - - +// Eigen::Vector3d( 1.0, -1.0, 1.0), // + - + +// Eigen::Vector3d(-1.0, 1.0, 1.0), // + + - +// Eigen::Vector3d( 1.0, 1.0, 1.0) // + + + +// }; +// +// // Note that the input vector must already be negated when using this code for halfplane tests +// int +// vectorToIndex(Eigen::Vector3d normal) +// { +// int index = 0; +// +// if (normal.z () >= 0) index |= 1; +// if (normal.y () >= 0) index |= 2; +// if (normal.x () >= 0) index |= 4; +// +// return index; +// } +// +// void +// get_np_vertices(Eigen::Vector3d normal, Eigen::Vector3d &p_vertex, Eigen::Vector3d &n_vertex, Eigen::Vector3d min_bb, Eigen::Vector3d max_bb) +// { +// +// p_vertex = min_bb; +// n_vertex = max_bb; +// +// if (normal.x () >= 0) +// { +// n_vertex.x () = min_bb.x (); +// p_vertex.x () = max_bb.x (); +// } +// +// if (normal.y () >= 0) +// { +// n_vertex.y () = min_bb.y (); +// p_vertex.y () = max_bb.y (); +// } +// +// if (normal.z () >= 0) +// { +// p_vertex.z () = max_bb.z (); +// n_vertex.z () = min_bb.z (); +// } +// } + + template void + OutofcoreOctreeBaseNode::queryFrustum (const double planes[24], std::list& file_names) + { + queryFrustum(planes, file_names, this->m_tree_->getTreeDepth()); + } + + template void + OutofcoreOctreeBaseNode::queryFrustum (const double planes[24], std::list& file_names, const boost::uint32_t query_depth, const bool skip_vfc_check) + { + + enum {INSIDE, INTERSECT, OUTSIDE}; + + int result = INSIDE; + + if (this->depth_ > query_depth) + { + return; + } + +// if (this->depth_ > query_depth) +// return; + + if (!skip_vfc_check) + { + for(int i =0; i < 6; i++){ + double a = planes[(i*4)]; + double b = planes[(i*4)+1]; + double c = planes[(i*4)+2]; + double d = planes[(i*4)+3]; + + //cout << i << ": " << a << "x + " << b << "y + " << c << "z + " << d << endl; + + Eigen::Vector3d normal(a, b, c); + + Eigen::Vector3d min_bb; + Eigen::Vector3d max_bb; + node_metadata_->getBoundingBox(min_bb, max_bb); + + // Basic VFC algorithm + Eigen::Vector3d center = node_metadata_->getVoxelCenter(); + Eigen::Vector3d radius (fabs (static_cast (max_bb.x () - center.x ())), + fabs (static_cast (max_bb.y () - center.y ())), + fabs (static_cast (max_bb.z () - center.z ()))); + + double m = (center.x () * a) + (center.y () * b) + (center.z () * c) + d; + double n = (radius.x () * fabs(a)) + (radius.y () * fabs(b)) + (radius.z () * fabs(c)); + + if (m + n < 0){ + result = OUTSIDE; + break; + } + + if (m - n < 0) result = INTERSECT; + + // // n-p implementation + // Eigen::Vector3d p_vertex; //pos vertex + // Eigen::Vector3d n_vertex; //neg vertex + // get_np_vertices(normal, p_vertex, n_vertex, min_bb, max_bb); + // + // cout << "n_vertex: " << n_vertex.x () << ", " << n_vertex.y () << ", " << n_vertex.z () << endl; + // cout << "p_vertex: " << p_vertex.x () << ", " << p_vertex.y () << ", " << p_vertex.z () << endl; + + // is the positive vertex outside? + // if (pl[i].distance(b.getVertexP(pl[i].normal)) < 0) + // { + // result = OUTSIDE; + // } + // // is the negative vertex outside? + // else if (pl[i].distance(b.getVertexN(pl[i].normal)) < 0) + // { + // result = INTERSECT; + // } + + // + // + // // This should be the same as below + // if (normal.dot(n_vertex) + d > 0) + // { + // result = OUTSIDE; + // } + // + // if (normal.dot(p_vertex) + d >= 0) + // { + // result = INTERSECT; + // } + + // This should be the same as above + // double m = (a * n_vertex.x ()) + (b * n_vertex.y ()) + (c * n_vertex.z ()); + // cout << "m = " << m << endl; + // if (m > -d) + // { + // result = OUTSIDE; + // } + // + // double n = (a * p_vertex.x ()) + (b * p_vertex.y ()) + (c * p_vertex.z ()); + // cout << "n = " << n << endl; + // if (n > -d) + // { + // result = INTERSECT; + // } + } + } + + if (result == OUTSIDE) + { + return; + } + +// switch(result){ +// case OUTSIDE: +// //cout << this->depth_ << " [OUTSIDE]: " << node_metadata_->getPCDFilename() << endl; +// return; +// case INTERSECT: +// //cout << this->depth_ << " [INTERSECT]: " << node_metadata_->getPCDFilename() << endl; +// break; +// case INSIDE: +// //cout << this->depth_ << " [INSIDE]: " << node_metadata_->getPCDFilename() << endl; +// break; +// } + + // Add files breadth first + if (this->depth_ == query_depth && payload_->getDataSize () > 0) + //if (payload_->getDataSize () > 0) + { + file_names.push_back (this->node_metadata_->getMetadataFilename ().string ()); + } + + if (hasUnloadedChildren ()) + { + loadChildren (false); + } + + if (this->getNumChildren () > 0) + { + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + children_[i]->queryFrustum (planes, file_names, query_depth, (result == INSIDE) /*skip_vfc_check*/); + } + } +// else if (hasUnloadedChildren ()) +// { +// loadChildren (false); +// +// for (size_t i = 0; i < 8; i++) +// { +// if (children_[i]) +// children_[i]->queryFrustum (planes, file_names, query_depth); +// } +// } + //} + } + +//////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::queryFrustum (const double planes[24], const Eigen::Vector3d &eye, const Eigen::Matrix4d &view_projection_matrix, std::list& file_names, const boost::uint32_t query_depth, const bool skip_vfc_check) + { + + // If we're above our query depth + if (this->depth_ > query_depth) + { + return; + } + + // Bounding Box + Eigen::Vector3d min_bb; + Eigen::Vector3d max_bb; + node_metadata_->getBoundingBox(min_bb, max_bb); + + // Frustum Culling + enum {INSIDE, INTERSECT, OUTSIDE}; + + int result = INSIDE; + + if (!skip_vfc_check) + { + for(int i =0; i < 6; i++){ + double a = planes[(i*4)]; + double b = planes[(i*4)+1]; + double c = planes[(i*4)+2]; + double d = planes[(i*4)+3]; + + //cout << i << ": " << a << "x + " << b << "y + " << c << "z + " << d << endl; + + Eigen::Vector3d normal(a, b, c); + + // Basic VFC algorithm + Eigen::Vector3d center = node_metadata_->getVoxelCenter(); + Eigen::Vector3d radius (fabs (static_cast (max_bb.x () - center.x ())), + fabs (static_cast (max_bb.y () - center.y ())), + fabs (static_cast (max_bb.z () - center.z ()))); + + double m = (center.x () * a) + (center.y () * b) + (center.z () * c) + d; + double n = (radius.x () * fabs(a)) + (radius.y () * fabs(b)) + (radius.z () * fabs(c)); + + if (m + n < 0){ + result = OUTSIDE; + break; + } + + if (m - n < 0) result = INTERSECT; + + } + } + + if (result == OUTSIDE) + { + return; + } + + // Bounding box projection + // 3--------2 + // /| /| Y 0 = xmin, ymin, zmin + // / | / | | 6 = xmax, ymax. zmax + // 7--------6 | | + // | | | | | + // | 0-----|--1 +------X + // | / | / / + // |/ |/ / + // 4--------5 Z + +// bounding_box[0] = Eigen::Vector4d(min_bb.x (), min_bb.y (), min_bb.z (), 1.0); +// bounding_box[1] = Eigen::Vector4d(max_bb.x (), min_bb.y (), min_bb.z (), 1.0); +// bounding_box[2] = Eigen::Vector4d(max_bb.x (), max_bb.y (), min_bb.z (), 1.0); +// bounding_box[3] = Eigen::Vector4d(min_bb.x (), max_bb.y (), min_bb.z (), 1.0); +// bounding_box[4] = Eigen::Vector4d(min_bb.x (), min_bb.y (), max_bb.z (), 1.0); +// bounding_box[5] = Eigen::Vector4d(max_bb.x (), min_bb.y (), max_bb.z (), 1.0); +// bounding_box[6] = Eigen::Vector4d(max_bb.x (), max_bb.y (), max_bb.z (), 1.0); +// bounding_box[7] = Eigen::Vector4d(min_bb.x (), max_bb.y (), max_bb.z (), 1.0); + + int width = 500; + int height = 500; + + float coverage = pcl::visualization::viewScreenArea(eye, min_bb, max_bb, view_projection_matrix, width, height); + //float coverage = pcl::visualization::viewScreenArea(eye, bounding_box, view_projection_matrix); + +// for (int i=0; i < this->depth_; i++) std::cout << " "; +// std::cout << this->depth_ << ": " << coverage << std::endl; + + // Add files breadth first + if (this->depth_ <= query_depth && payload_->getDataSize () > 0) + //if (payload_->getDataSize () > 0) + { + file_names.push_back (this->node_metadata_->getMetadataFilename ().string ()); + } + + //if (coverage <= 0.075) + if (coverage <= 10000) + return; + + if (hasUnloadedChildren ()) + { + loadChildren (false); + } + + if (this->getNumChildren () > 0) + { + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + children_[i]->queryFrustum (planes, eye, view_projection_matrix, file_names, query_depth, (result == INSIDE) /*skip_vfc_check*/); + } + } + } + +//////////////////////////////////////////////////////////////////////////////// + template void + OutofcoreOctreeBaseNode::getOccupiedVoxelCentersRecursive (std::vector > &voxel_centers, const size_t query_depth) + { + if (this->depth_ < query_depth){ + if (num_children_ > 0) + { + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + children_[i]->getOccupiedVoxelCentersRecursive (voxel_centers, query_depth); + } + } + } + else + { + Eigen::Vector3d voxel_center = node_metadata_->getVoxelCenter (); + voxel_centers.push_back(voxel_center); + } + } + + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::queryBBIntersects (const Eigen::Vector3d& min_bb, const Eigen::Vector3d& max_bb, const boost::uint32_t query_depth, std::list& file_names) + { + + Eigen::Vector3d my_min = min_bb; + Eigen::Vector3d my_max = max_bb; + + if (intersectsWithBoundingBox (my_min, my_max)) + { + if (this->depth_ < query_depth) + { + if (this->getNumChildren () > 0) + { + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + children_[i]->queryBBIntersects (my_min, my_max, query_depth, file_names); + } + } + else if (hasUnloadedChildren ()) + { + loadChildren (false); + + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + children_[i]->queryBBIntersects (my_min, my_max, query_depth, file_names); + } + } + return; + } + + if (payload_->getDataSize () > 0) + { + file_names.push_back (this->node_metadata_->getMetadataFilename ().string ()); + } + } + } + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::queryBBIncludes (const Eigen::Vector3d& min_bb, const Eigen::Vector3d& max_bb, size_t query_depth, const pcl::PCLPointCloud2::Ptr& dst_blob) + { + uint64_t startingSize = dst_blob->width*dst_blob->height; + PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBaseNode::%s] Starting points in destination blob: %ul\n", __FUNCTION__, startingSize ); + + // If the queried bounding box has any intersection with this node's bounding box + if (intersectsWithBoundingBox (min_bb, max_bb)) + { + // If we aren't at the max desired depth + if (this->depth_ < query_depth) + { + //if this node doesn't have any children, we are at the max depth for this query + if ((num_children_ == 0) && (hasUnloadedChildren ())) + loadChildren (false); + + //if this node has children + if (num_children_ > 0) + { + //recursively store any points that fall into the queried bounding box into v and return + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + children_[i]->queryBBIncludes (min_bb, max_bb, query_depth, dst_blob); + } + PCL_DEBUG ( "[pcl::outofcore::OutofcoreOctreeBaseNode::%s] Points in dst_blob: %ul\n", __FUNCTION__, dst_blob->width*dst_blob->height ); + return; + } + } + else //otherwise if we are at the max depth + { + //get all the points from the payload and return (easy with PCLPointCloud2) + pcl::PCLPointCloud2::Ptr tmp_blob (new pcl::PCLPointCloud2 ()); + pcl::PCLPointCloud2::Ptr tmp_dst_blob (new pcl::PCLPointCloud2 ()); + //load all the data in this node from disk + payload_->readRange (0, payload_->size (), tmp_blob); + + if( tmp_blob->width*tmp_blob->height == 0 ) + return; + + //if this node's bounding box falls completely within the queried bounding box, keep all the points + if (inBoundingBox (min_bb, max_bb)) + { + //concatenate all of what was just read into the main dst_blob + //(is it safe to do in place?) + + //if there is already something in the destination blob (remember this method is recursive) + if( dst_blob->width*dst_blob->height != 0 ) + { + PCL_DEBUG ("[pcl::outofocre::OutofcoreOctreeBaseNode::%s] Size of cloud before: %lu\n", __FUNCTION__, dst_blob->width*dst_blob->height ); + PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBaseNode::%s] Concatenating point cloud\n", __FUNCTION__); + int res = pcl::concatenatePointCloud (*dst_blob, *tmp_blob, *dst_blob); + (void)res; + assert (res == 1); + + PCL_DEBUG ("[pcl::outofocre::OutofcoreOctreeBaseNode::%s] Size of cloud after: %lu\n", __FUNCTION__, dst_blob->width*dst_blob->height ); + } + //otherwise, just copy the tmp_blob into the dst_blob + else + { + PCL_DEBUG ( "[pcl::outofcore::OutofcoreOctreeBaseNode] Copying point cloud into the destination blob\n"); + pcl::copyPointCloud (*tmp_blob, *dst_blob); + assert (tmp_blob->width*tmp_blob->height == dst_blob->width*dst_blob->height); + } + PCL_DEBUG ( "[pcl::outofcore::OutofcoreOctreeBaseNode::%s] Points in dst_blob: %ul\n", __FUNCTION__, dst_blob->width*dst_blob->height ); + return; + } + else + { + //otherwise queried bounding box only partially intersects this + //node's bounding box, so we have to check all the points in + //this box for intersection with queried bounding box + + +// PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBaseNode::%s] Partial extraction of points in bounding box. Desired: %.2lf %.2lf %2lf, %.2lf %.2lf %.2lf; This node BB: %.2lf %.2lf %.2lf, %.2lf %.2lf %.2lf\n", __FUNCTION__, min_bb[0], min_bb[1], min_bb[2], max_bb[0], max_bb[1], max_bb[2], min_[0], min_[1], min_[2], max_[0], max_[1], max_[2] ); + + //put the ros message into a pointxyz point cloud (just to get the indices by using getPointsInBox) + typename pcl::PointCloud::Ptr tmp_cloud ( new pcl::PointCloud () ); + pcl::fromPCLPointCloud2 ( *tmp_blob, *tmp_cloud ); + assert (tmp_blob->width*tmp_blob->height == tmp_cloud->width*tmp_cloud->height ); + + Eigen::Vector4f min_pt ( static_cast ( min_bb[0] ), static_cast ( min_bb[1] ), static_cast ( min_bb[2] ), 1.0f); + Eigen::Vector4f max_pt ( static_cast ( max_bb[0] ), static_cast ( max_bb[1] ) , static_cast( max_bb[2] ), 1.0f ); + + std::vector indices; + + pcl::getPointsInBox ( *tmp_cloud, min_pt, max_pt, indices ); + PCL_DEBUG ( "[pcl::outofcore::OutofcoreOctreeBaseNode::%s] Points in box: %d\n", __FUNCTION__, indices.size () ); + PCL_DEBUG ( "[pcl::outofcore::OutofcoreOctreeBaseNode::%s] Points remaining: %d\n", __FUNCTION__, tmp_cloud->width*tmp_cloud->height - indices.size () ); + + if ( indices.size () > 0 ) + { + if( dst_blob->width*dst_blob->height > 0 ) + { + //need a new tmp destination with extracted points within BB + pcl::PCLPointCloud2::Ptr tmp_blob_within_bb (new pcl::PCLPointCloud2 ()); + + //copy just the points marked in indices + pcl::copyPointCloud ( *tmp_blob, indices, *tmp_blob_within_bb ); + assert ( tmp_blob_within_bb->width*tmp_blob_within_bb->height == indices.size () ); + assert ( tmp_blob->fields.size () == tmp_blob_within_bb->fields.size () ); + //concatenate those points into the returned dst_blob + PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBaseNode::%s] Concatenating point cloud in place\n", __FUNCTION__); + boost::uint64_t orig_points_in_destination = dst_blob->width*dst_blob->height; + (void)orig_points_in_destination; + int res = pcl::concatenatePointCloud (*dst_blob, *tmp_blob_within_bb, *dst_blob); + (void)res; + assert (res == 1); + assert (dst_blob->width*dst_blob->height == indices.size () + orig_points_in_destination); + + } + else + { + pcl::copyPointCloud ( *tmp_blob, indices, *dst_blob ); + assert ( dst_blob->width*dst_blob->height == indices.size () ); + } + } + } + } + } + + PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBaseNode::%s] Points added by function call: %ul\n", __FUNCTION__, dst_blob->width*dst_blob->height - startingSize ); + } + + template void + OutofcoreOctreeBaseNode::queryBBIncludes (const Eigen::Vector3d& min_bb, const Eigen::Vector3d& max_bb, size_t query_depth, AlignedPointTVector& v) + { + + //if the queried bounding box has any intersection with this node's bounding box + if (intersectsWithBoundingBox (min_bb, max_bb)) + { + //if we aren't at the max desired depth + if (this->depth_ < query_depth) + { + //if this node doesn't have any children, we are at the max depth for this query + if (this->hasUnloadedChildren ()) + { + this->loadChildren (false); + } + + //if this node has children + if (getNumChildren () > 0) + { + if(hasUnloadedChildren ()) + loadChildren (false); + + //recursively store any points that fall into the queried bounding box into v and return + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + children_[i]->queryBBIncludes (min_bb, max_bb, query_depth, v); + } + return; + } + } + //otherwise if we are at the max depth + else + { + //if this node's bounding box falls completely within the queried bounding box + if (inBoundingBox (min_bb, max_bb)) + { + //get all the points from the payload and return + AlignedPointTVector payload_cache; + payload_->readRange (0, payload_->size (), payload_cache); + v.insert (v.end (), payload_cache.begin (), payload_cache.end ()); + return; + } + //otherwise queried bounding box only partially intersects this + //node's bounding box, so we have to check all the points in + //this box for intersection with queried bounding box + else + { + //read _all_ the points in from the disk container + AlignedPointTVector payload_cache; + payload_->readRange (0, payload_->size (), payload_cache); + + uint64_t len = payload_->size (); + //iterate through each of them + for (uint64_t i = 0; i < len; i++) + { + const PointT& p = payload_cache[i]; + //if it falls within this bounding box + if (pointInBoundingBox (min_bb, max_bb, p)) + { + //store it in the list + v.push_back (p); + } + else + { + PCL_DEBUG ("[pcl::outofcore::queryBBIncludes] Point %.2lf %.2lf %.2lf not in bounding box %.2lf %.2lf %.2lf", p.x, p.y, p.z, min_bb[0], min_bb[1], min_bb[2], max_bb[0], max_bb[1], max_bb[2]); + } + } + } + } + } + } + + //////////////////////////////////////////////////////////////////////////////// + template void + OutofcoreOctreeBaseNode::queryBBIncludes_subsample (const Eigen::Vector3d& min_bb, const Eigen::Vector3d& max_bb, boost::uint64_t query_depth, const pcl::PCLPointCloud2::Ptr& dst_blob, double percent) + { + if (intersectsWithBoundingBox (min_bb, max_bb)) + { + if (this->depth_ < query_depth) + { + if (this->hasUnloadedChildren ()) + this->loadChildren (false); + + if (this->getNumChildren () > 0) + { + for (size_t i=0; i<8; i++) + { + //recursively traverse (depth first) + if (children_[i]!=0) + children_[i]->queryBBIncludes_subsample (min_bb, max_bb, query_depth, dst_blob, percent); + } + return; + } + } + //otherwise, at max depth --> read from disk, subsample, concatenate + else + { + + if (inBoundingBox (min_bb, max_bb)) + { + pcl::PCLPointCloud2::Ptr tmp_blob; + this->payload_->read (tmp_blob); + uint64_t num_pts = tmp_blob->width*tmp_blob->height; + + double sample_points = static_cast(num_pts) * percent; + if (num_pts > 0) + { + //always sample at least one point + sample_points = sample_points > 0 ? sample_points : 1; + } + else + { + return; + } + + + pcl::RandomSample random_sampler; + random_sampler.setInputCloud (tmp_blob); + + pcl::PCLPointCloud2::Ptr downsampled_points (new pcl::PCLPointCloud2 ()); + + //set sample size as percent * number of points read + random_sampler.setSample (static_cast (sample_points)); + + pcl::ExtractIndices extractor; + + pcl::IndicesPtr downsampled_cloud_indices (new std::vector ()); + random_sampler.filter (*downsampled_cloud_indices); + extractor.setIndices (downsampled_cloud_indices); + extractor.filter (*downsampled_points); + + //concatenate the result into the destination cloud + pcl::concatenatePointCloud (*dst_blob, *downsampled_points, *dst_blob); + } + } + } + } + + + //////////////////////////////////////////////////////////////////////////////// + template void + OutofcoreOctreeBaseNode::queryBBIncludes_subsample (const Eigen::Vector3d& min_bb, const Eigen::Vector3d& max_bb, boost::uint64_t query_depth, const double percent, AlignedPointTVector& dst) + { + //check if the queried bounding box has any intersection with this node's bounding box + if (intersectsWithBoundingBox (min_bb, max_bb)) + { + //if we are not at the max depth for queried nodes + if (this->depth_ < query_depth) + { + //check if we don't have children + if ((num_children_ == 0) && (hasUnloadedChildren ())) + { + loadChildren (false); + } + //if we do have children + if (num_children_ > 0) + { + //recursively add their valid points within the queried bounding box to the list v + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + children_[i]->queryBBIncludes_subsample (min_bb, max_bb, query_depth, percent, dst); + } + return; + } + } + //otherwise we are at the max depth, so we add all our points or some of our points + else + { + //if this node's bounding box falls completely within the queried bounding box + if (inBoundingBox (min_bb, max_bb)) + { + //add a random sample of all the points + AlignedPointTVector payload_cache; + payload_->readRangeSubSample (0, payload_->size (), percent, payload_cache); + dst.insert (dst.end (), payload_cache.begin (), payload_cache.end ()); + return; + } + //otherwise the queried bounding box only partially intersects with this node's bounding box + else + { + //brute force selection of all valid points + AlignedPointTVector payload_cache_within_region; + { + AlignedPointTVector payload_cache; + payload_->readRange (0, payload_->size (), payload_cache); + for (size_t i = 0; i < payload_->size (); i++) + { + const PointT& p = payload_cache[i]; + if (pointInBoundingBox (min_bb, max_bb, p)) + { + payload_cache_within_region.push_back (p); + } + } + }//force the payload cache to deconstruct here + + //use STL random_shuffle and push back a random selection of the points onto our list + std::random_shuffle (payload_cache_within_region.begin (), payload_cache_within_region.end ()); + size_t numpick = static_cast (percent * static_cast (payload_cache_within_region.size ()));; + + for (size_t i = 0; i < numpick; i++) + { + dst.push_back (payload_cache_within_region[i]); + } + } + } + } + } + //////////////////////////////////////////////////////////////////////////////// + +//dir is current level. we put this nodes files into it + template + OutofcoreOctreeBaseNode::OutofcoreOctreeBaseNode (const Eigen::Vector3d& bb_min, const Eigen::Vector3d& bb_max, const char* dir, OutofcoreOctreeBaseNode* super) + : m_tree_ () + , root_node_ () + , parent_ () + , depth_ () + , children_ (std::vector *> (8,static_cast*>(0))) + , num_children_ () + , num_loaded_children_ (0) + , payload_ () + , node_metadata_ () + { + node_metadata_ = boost::shared_ptr (new OutofcoreOctreeNodeMetadata ()); + node_metadata_->setOutofcoreVersion (3); + + if (super == NULL) + { + PCL_ERROR ( "[pc::outofcore::OutofcoreOctreeBaseNode] Super is null - don't make a root node this way!\n" ); + PCL_THROW_EXCEPTION (PCLException, "[pcl::outofcore::OutofcoreOctreeBaseNode] Outofcore Exception: Bad parent"); + } + + this->parent_ = super; + root_node_ = super->root_node_; + m_tree_ = super->root_node_->m_tree_; + assert (m_tree_ != NULL); + + depth_ = super->depth_ + 1; + num_children_ = 0; + + node_metadata_->setBoundingBox (bb_min, bb_max); + + std::string uuid_idx; + std::string uuid_cont; + OutofcoreOctreeDiskContainer::getRandomUUIDString (uuid_idx); + OutofcoreOctreeDiskContainer::getRandomUUIDString (uuid_cont); + + std::string node_index_name = uuid_idx + std::string ("_") + node_index_basename + node_index_extension; + + std::string node_container_name; + node_container_name = uuid_cont + std::string ("_") + node_container_basename + pcd_extension; + + node_metadata_->setDirectoryPathname (boost::filesystem::path (dir)); + node_metadata_->setPCDFilename (node_metadata_->getDirectoryPathname () / boost::filesystem::path (node_container_name)); + node_metadata_->setMetadataFilename ( node_metadata_->getDirectoryPathname ()/boost::filesystem::path (node_index_name)); + + boost::filesystem::create_directory (node_metadata_->getDirectoryPathname ()); + + payload_ = boost::shared_ptr (new ContainerT (node_metadata_->getPCDFilename ())); + this->saveIdx (false); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::copyAllCurrentAndChildPointsRec (std::list& v) + { + if ((num_children_ == 0) && (hasUnloadedChildren ())) + { + loadChildren (false); + } + + for (size_t i = 0; i < num_children_; i++) + { + children_[i]->copyAllCurrentAndChildPointsRec (v); + } + + AlignedPointTVector payload_cache; + payload_->readRange (0, payload_->size (), payload_cache); + + { + //boost::mutex::scoped_lock lock(queryBBIncludes_vector_mutex); + v.insert (v.end (), payload_cache.begin (), payload_cache.end ()); + } + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::copyAllCurrentAndChildPointsRec_sub (std::list& v, const double percent) + { + if ((num_children_ == 0) && (hasUnloadedChildren ())) + { + loadChildren (false); + } + + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + children_[i]->copyAllCurrentAndChildPointsRec_sub (v, percent); + } + + std::vector payload_cache; + payload_->readRangeSubSample (0, payload_->size (), percent, payload_cache); + + for (size_t i = 0; i < payload_cache.size (); i++) + { + v.push_back (payload_cache[i]); + } + } + + //////////////////////////////////////////////////////////////////////////////// + + template inline bool + OutofcoreOctreeBaseNode::intersectsWithBoundingBox (const Eigen::Vector3d& min_bb, const Eigen::Vector3d& max_bb) const + { + Eigen::Vector3d min, max; + node_metadata_->getBoundingBox (min, max); + + //Check whether any portion of min_bb, max_bb falls within min,max + if (((min[0] <= min_bb[0]) && (min_bb[0] <= max[0])) || ((min_bb[0] <= min[0]) && (min[0] <= max_bb[0]))) + { + if (((min[1] <= min_bb[1]) && (min_bb[1] <= max[1])) || ((min_bb[1] <= min[1]) && (min[1] <= max_bb[1]))) + { + if (((min[2] <= min_bb[2]) && (min_bb[2] <= max[2])) || ((min_bb[2] <= min[2]) && (min[2] <= max_bb[2]))) + { + return (true); + } + } + } + + return (false); + } + //////////////////////////////////////////////////////////////////////////////// + + template inline bool + OutofcoreOctreeBaseNode::inBoundingBox (const Eigen::Vector3d& min_bb, const Eigen::Vector3d& max_bb) const + { + Eigen::Vector3d min, max; + + node_metadata_->getBoundingBox (min, max); + + if ((min_bb[0] <= min[0]) && (max[0] <= max_bb[0])) + { + if ((min_bb[1] <= min[1]) && (max[1] <= max_bb[1])) + { + if ((min_bb[2] <= min[2]) && (max[2] <= max_bb[2])) + { + return (true); + } + } + } + + return (false); + } + //////////////////////////////////////////////////////////////////////////////// + + template inline bool + OutofcoreOctreeBaseNode::pointInBoundingBox (const Eigen::Vector3d& min_bb, const Eigen::Vector3d& max_bb, + const PointT& p) + { + //by convention, minimum boundary is included; maximum boundary is not + if ((min_bb[0] <= p.x) && (p.x < max_bb[0])) + { + if ((min_bb[1] <= p.y) && (p.y < max_bb[1])) + { + if ((min_bb[2] <= p.z) && (p.z < max_bb[2])) + { + return (true); + } + } + } + return (false); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::writeVPythonVisual (std::ofstream& file) + { + Eigen::Vector3d min; + Eigen::Vector3d max; + node_metadata_->getBoundingBox (min, max); + + double l = max[0] - min[0]; + double h = max[1] - min[1]; + double w = max[2] - min[2]; + file << "box( pos=(" << min[0] << ", " << min[1] << ", " << min[2] << "), length=" << l << ", height=" << h + << ", width=" << w << " )\n"; + + for (size_t i = 0; i < num_children_; i++) + { + children_[i]->writeVPythonVisual (file); + } + } + + //////////////////////////////////////////////////////////////////////////////// + + template int + OutofcoreOctreeBaseNode::read (pcl::PCLPointCloud2::Ptr &output_cloud) + { + return (this->payload_->read (output_cloud)); + } + + //////////////////////////////////////////////////////////////////////////////// + + template OutofcoreOctreeBaseNode* + OutofcoreOctreeBaseNode::getChildPtr (size_t index_arg) const + { + PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBaseNode::%s] %d", __FUNCTION__, index_arg); + return (children_[index_arg]); + } + + //////////////////////////////////////////////////////////////////////////////// + template boost::uint64_t + OutofcoreOctreeBaseNode::getDataSize () const + { + return (this->payload_->getDataSize ()); + } + + //////////////////////////////////////////////////////////////////////////////// + + template size_t + OutofcoreOctreeBaseNode::countNumLoadedChildren () const + { + size_t loaded_children_count = 0; + + for (size_t i=0; i<8; i++) + { + if (children_[i] != 0) + loaded_children_count++; + } + + return (loaded_children_count); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::loadFromFile (const boost::filesystem::path& path, OutofcoreOctreeBaseNode* super) + { + PCL_DEBUG ("[pcl:outofcore::OutofcoreOctreeBaseNode] Loading metadata from %s\n", path.filename ().c_str ()); + node_metadata_->loadMetadataFromDisk (path); + + //this shouldn't be part of 'loadFromFile' + this->parent_ = super; + + if (num_children_ > 0) + recFreeChildren (); + + this->num_children_ = 0; + this->payload_ = boost::shared_ptr (new ContainerT (node_metadata_->getPCDFilename ())); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::convertToXYZRecursive () + { + std::string fname = boost::filesystem::basename (node_metadata_->getPCDFilename ()) + std::string (".dat.xyz"); + boost::filesystem::path xyzfile = node_metadata_->getDirectoryPathname () / fname; + payload_->convertToXYZ (xyzfile); + + if (hasUnloadedChildren ()) + { + loadChildren (false); + } + + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + children_[i]->convertToXYZ (); + } + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::flushToDiskRecursive () + { + for (size_t i = 0; i < 8; i++) + { + if (children_[i]) + children_[i]->flushToDiskRecursive (); + } + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeBaseNode::sortOctantIndices (const pcl::PCLPointCloud2::Ptr &input_cloud, std::vector< std::vector > &indices, const Eigen::Vector3d &mid_xyz) + { + if (indices.size () < 8) + indices.resize (8); + + int x_idx = pcl::getFieldIndex (*input_cloud , std::string ("x") ); + int y_idx = pcl::getFieldIndex (*input_cloud, std::string ("y") ); + int z_idx = pcl::getFieldIndex (*input_cloud, std::string ("z") ); + + int x_offset = input_cloud->fields[x_idx].offset; + int y_offset = input_cloud->fields[y_idx].offset; + int z_offset = input_cloud->fields[z_idx].offset; + + for ( size_t point_idx =0; point_idx < input_cloud->data.size (); point_idx +=input_cloud->point_step ) + { + PointT local_pt; + + local_pt.x = * (reinterpret_cast(&input_cloud->data[point_idx + x_offset])); + local_pt.y = * (reinterpret_cast(&input_cloud->data[point_idx + y_offset])); + local_pt.z = * (reinterpret_cast(&input_cloud->data[point_idx + z_offset])); + + if (!pcl_isfinite (local_pt.x) || !pcl_isfinite (local_pt.y) || !pcl_isfinite (local_pt.z)) + continue; + + if(!this->pointInBoundingBox (local_pt)) + { + PCL_ERROR ("pcl::outofcore::OutofcoreOctreeBaseNode::%s] Point %2.lf %.2lf %.2lf not in bounding box", __FUNCTION__, local_pt.x, local_pt.y, local_pt.z); + } + + assert (this->pointInBoundingBox (local_pt) == true); + + //compute the box we are in + size_t box = 0; + box = ((local_pt.z >= mid_xyz[2]) << 2) | ((local_pt.y >= mid_xyz[1]) << 1) | ((local_pt.x >= mid_xyz[0]) << 0); + assert (box < 8); + + //insert to the vector of indices + indices[box].push_back (static_cast (point_idx/input_cloud->point_step)); + } + } + //////////////////////////////////////////////////////////////////////////////// + +#if 0 //A bunch of non-class methods left from the Urban Robotics code that has been deactivated + template OutofcoreOctreeBaseNode* + makenode_norec (const boost::filesystem::path& path, OutofcoreOctreeBaseNode* super) + { + OutofcoreOctreeBaseNode* thisnode = new OutofcoreOctreeBaseNode , PointT > (); +//octree_disk_node (); + + if (super == NULL) + { + thisnode->thisdir_ = path.parent_path (); + + if (!boost::filesystem::exists (thisnode->thisdir_)) + { + PCL_ERROR ( "[pcl::outofcore::OutofcoreOctreeBaseNode] could not find dir %s\n",thisnode->thisdir_.c_str () ); + PCL_THROW_EXCEPTION (PCLException, "[pcl::outofcore::OutofcoreOctreeBaseNode] Outofcore Octree Exception: Could not find directory"); + } + + thisnode->thisnodeindex_ = path; + + thisnode->depth_ = 0; + thisnode->root_node_ = thisnode; + } + else + { + thisnode->thisdir_ = path; + thisnode->depth_ = super->depth_ + 1; + thisnode->root_node_ = super->root_node_; + + if (thisnode->depth_ > thisnode->root->max_depth_) + { + thisnode->root->max_depth_ = thisnode->depth_; + } + + boost::filesystem::directory_iterator diterend; + bool loaded = false; + for (boost::filesystem::directory_iterator diter (thisnode->thisdir_); diter != diterend; ++diter) + { + const boost::filesystem::path& file = *diter; + if (!boost::filesystem::is_directory (file)) + { + if (boost::filesystem::extension (file) == OutofcoreOctreeBaseNode::node_index_extension) + { + thisnode->thisnodeindex_ = file; + loaded = true; + break; + } + } + } + + if (!loaded) + { + PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeBaseNode] Could not find index!\n"); + PCL_THROW_EXCEPTION (PCLException, "[pcl::outofcore::OutofcoreOctreeBaseNode] Could not find node metadata index file"); + } + + } + thisnode->max_depth_ = 0; + + { + std::ifstream f (thisnode->thisnodeindex_.string ().c_str (), std::ios::in); + + f >> thisnode->min_[0]; + f >> thisnode->min_[1]; + f >> thisnode->min_[2]; + f >> thisnode->max_[0]; + f >> thisnode->max_[1]; + f >> thisnode->max_[2]; + + std::string filename; + f >> filename; + thisnode->thisnodestorage_ = thisnode->thisdir_ / filename; + + f.close (); + + thisnode->payload_ = boost::shared_ptr (new ContainerT (thisnode->thisnodestorage_)); + } + + thisnode->parent_ = super; + children_.clear (); + children_.resize (8, static_cast* > (0)); + thisnode->num_children_ = 0; + + return (thisnode); + } + + //////////////////////////////////////////////////////////////////////////////// + +//accelerate search + template void + queryBBIntersects_noload (const boost::filesystem::path& root_node, const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::uint32_t query_depth, std::list& bin_name) + { + OutofcoreOctreeBaseNode* root = makenode_norec (root_node, NULL); + if (root == NULL) + { + std::cout << "test"; + } + if (root->intersectsWithBoundingBox (min, max)) + { + if (query_depth == root->max_depth_) + { + if (!root->payload_->empty ()) + { + bin_name.push_back (root->thisnodestorage_.string ()); + } + return; + } + + for (int i = 0; i < 8; i++) + { + boost::filesystem::path child_dir = root->thisdir_ + / boost::filesystem::path (boost::lexical_cast (i)); + if (boost::filesystem::exists (child_dir)) + { + root->children_[i] = makenode_norec (child_dir, root); + root->num_children_++; + queryBBIntersects_noload (root->children_[i], min, max, root->max_depth_ - query_depth, bin_name); + } + } + } + delete root; + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + queryBBIntersects_noload (OutofcoreOctreeBaseNode* current, const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::uint32_t query_depth, std::list& bin_name) + { + if (current->intersectsWithBoundingBox (min, max)) + { + if (current->depth_ == query_depth) + { + if (!current->payload_->empty ()) + { + bin_name.push_back (current->thisnodestorage_.string ()); + } + } + else + { + for (int i = 0; i < 8; i++) + { + boost::filesystem::path child_dir = current->thisdir_ / boost::filesystem::path (boost::lexical_cast (i)); + if (boost::filesystem::exists (child_dir)) + { + current->children_[i] = makenode_norec (child_dir, current); + current->num_children_++; + queryBBIntersects_noload (current->children_[i], min, max, query_depth, bin_name); + } + } + } + } + } +#endif + //////////////////////////////////////////////////////////////////////////////// + + }//namespace outofcore +}//namespace pcl + +//#define PCL_INSTANTIATE.... + +#endif //PCL_OUTOFCORE_OCTREE_BASE_NODE_IMPL_H_ diff --git a/pcl-1.7/pcl/outofcore/impl/octree_disk_container.hpp b/pcl-1.7/pcl/outofcore/impl/octree_disk_container.hpp new file mode 100644 index 0000000..bd4fe59 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/impl/octree_disk_container.hpp @@ -0,0 +1,695 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012, Urban Robotics, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: octree_disk_container.hpp 6927M 2012-08-24 17:01:57Z (local) $ + */ + +#ifndef PCL_OUTOFCORE_OCTREE_DISK_CONTAINER_IMPL_H_ +#define PCL_OUTOFCORE_OCTREE_DISK_CONTAINER_IMPL_H_ + +// C++ +#include +#include +#include + +// Boost +#include + +// PCL +#include +#include +#include + +// PCL (Urban Robotics) +#include + +//allows operation on POSIX +#if !defined WIN32 +#define _fseeki64 fseeko +#elif defined __MINGW32__ +#define _fseeki64 fseeko64 +#endif + +namespace pcl +{ + namespace outofcore + { + template + boost::mutex OutofcoreOctreeDiskContainer::rng_mutex_; + + template boost::mt19937 + OutofcoreOctreeDiskContainer::rand_gen_ (static_cast (std::time(NULL))); + + template + boost::uuids::random_generator OutofcoreOctreeDiskContainer::uuid_gen_ (&rand_gen_); + + template + const uint64_t OutofcoreOctreeDiskContainer::READ_BLOCK_SIZE_ = static_cast (2e12); + template + const uint64_t OutofcoreOctreeDiskContainer::WRITE_BUFF_MAX_ = static_cast (2e12); + + template void + OutofcoreOctreeDiskContainer::getRandomUUIDString (std::string& s) + { + boost::uuids::uuid u; + { + boost::mutex::scoped_lock lock (rng_mutex_); + u = uuid_gen_ (); + } + + std::stringstream ss; + ss << u; + s = ss.str (); + } + //////////////////////////////////////////////////////////////////////////////// + + template + OutofcoreOctreeDiskContainer::OutofcoreOctreeDiskContainer () + : disk_storage_filename_ () + , filelen_ (0) + , writebuff_ (0) + { + std::string temp; + getRandomUUIDString (temp); + disk_storage_filename_ = boost::shared_ptr (new std::string (temp)); + filelen_ = 0; + } + //////////////////////////////////////////////////////////////////////////////// + + template + OutofcoreOctreeDiskContainer::OutofcoreOctreeDiskContainer (const boost::filesystem::path& path) + : disk_storage_filename_ () + , filelen_ (0) + , writebuff_ (0) + { + if (boost::filesystem::exists (path)) + { + if (boost::filesystem::is_directory (path)) + { + std::string uuid; + getRandomUUIDString (uuid); + boost::filesystem::path filename (uuid); + boost::filesystem::path file = path / filename; + + disk_storage_filename_ = boost::shared_ptr (new std::string (file.string ())); + } + else + { + uint64_t len = boost::filesystem::file_size (path); + + disk_storage_filename_ = boost::shared_ptr (new std::string (path.string ())); + + filelen_ = len / sizeof(PointT); + + pcl::PCLPointCloud2 cloud_info; + Eigen::Vector4f origin; + Eigen::Quaternionf orientation; + int pcd_version; + int data_type; + unsigned int data_index; + + //read the header of the pcd file and get the number of points + PCDReader reader; + reader.readHeader (*disk_storage_filename_, cloud_info, origin, orientation, pcd_version, data_type, data_index, 0); + + filelen_ = cloud_info.width * cloud_info.height; + } + } + else //path doesn't exist + { + disk_storage_filename_ = boost::shared_ptr (new std::string (path.string ())); + filelen_ = 0; + } + } + //////////////////////////////////////////////////////////////////////////////// + + template + OutofcoreOctreeDiskContainer::~OutofcoreOctreeDiskContainer () + { + flushWritebuff (true); + } + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeDiskContainer::flushWritebuff (const bool force_cache_dealloc) + { + if (writebuff_.size () > 0) + { + //construct the point cloud for this node + typename pcl::PointCloud::Ptr cloud (new pcl::PointCloud); + + cloud->width = static_cast (writebuff_.size ()); + cloud->height = 1; + + cloud->points = writebuff_; + + //write data to a pcd file + pcl::PCDWriter writer; + + + PCL_WARN ("[pcl::outofcore::OutofcoreOctreeDiskContainer::%s] Flushing writebuffer in a dangerous way to file %s. This might overwrite data in destination file\n", __FUNCTION__, disk_storage_filename_->c_str ()); + + // Write ascii for now to debug + int res = writer.writeBinaryCompressed (*disk_storage_filename_, *cloud); + (void)res; + assert (res == 0); + if (force_cache_dealloc) + { + writebuff_.resize (0); + } + } + } + //////////////////////////////////////////////////////////////////////////////// + + template PointT + OutofcoreOctreeDiskContainer::operator[] (uint64_t idx) const + { + PCL_THROW_EXCEPTION (PCLException, "[pcl::outofcore::OutofcoreOctreeDiskContainer] Not implemented for use with PCL library\n"); + + //if the index is on disk + if (idx < filelen_) + { + + PointT temp; + //open our file + FILE* f = fopen (disk_storage_filename_->c_str (), "rb"); + assert (f != NULL); + + //seek the right length; + int seekret = _fseeki64 (f, idx * sizeof(PointT), SEEK_SET); + (void)seekret; + assert (seekret == 0); + + size_t readlen = fread (&temp, 1, sizeof(PointT), f); + (void)readlen; + assert (readlen == sizeof (PointT)); + + int res = fclose (f); + (void)res; + assert (res == 0); + + return (temp); + } + //otherwise if the index is still in the write buffer + if (idx < (filelen_ + writebuff_.size ())) + { + idx -= filelen_; + return (writebuff_[idx]); + } + + //else, throw out of range exception + PCL_THROW_EXCEPTION (PCLException, "[pcl::outofcore:OutofcoreOctreeDiskContainer] Index is out of range"); + } + + //////////////////////////////////////////////////////////////////////////////// + template void + OutofcoreOctreeDiskContainer::readRange (const uint64_t start, const uint64_t count, AlignedPointTVector& dst) + { + if (count == 0) + { + return; + } + + if ((start + count) > size ()) + { + PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeDiskContainer::%s] Indicies out of range; start + count exceeds the size of the stored points\n", __FUNCTION__); + PCL_THROW_EXCEPTION (PCLException, "[pcl::outofcore::OutofcoreOctreeDiskContainer] Outofcore Octree Exception: Read indices exceed range"); + } + + pcl::PCDReader reader; + typename pcl::PointCloud::Ptr cloud (new pcl::PointCloud ()); + + int res = reader.read (*disk_storage_filename_, *cloud); + (void)res; + assert (res == 0); + + for (size_t i=0; i < cloud->points.size (); i++) + dst.push_back (cloud->points[i]); + + } + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeDiskContainer::readRangeSubSample_bernoulli (const uint64_t start, const uint64_t count, const double percent, AlignedPointTVector& dst) + { + if (count == 0) + { + return; + } + + dst.clear (); + + uint64_t filestart = 0; + uint64_t filecount = 0; + + int64_t buffstart = -1; + int64_t buffcount = -1; + + if (start < filelen_) + { + filestart = start; + } + + if ((start + count) <= filelen_) + { + filecount = count; + } + else + { + filecount = filelen_ - start; + + buffstart = 0; + buffcount = count - filecount; + } + + if (buffcount > 0) + { + { + boost::mutex::scoped_lock lock (rng_mutex_); + boost::bernoulli_distribution buffdist (percent); + boost::variate_generator > buffcoin (rand_gen_, buffdist); + + for (size_t i = buffstart; i < static_cast (buffcount); i++) + { + if (buffcoin ()) + { + dst.push_back (writebuff_[i]); + } + } + } + } + + if (filecount > 0) + { + //pregen and then sort the offsets to reduce the amount of seek + std::vector < uint64_t > offsets; + { + boost::mutex::scoped_lock lock (rng_mutex_); + + boost::bernoulli_distribution filedist (percent); + boost::variate_generator > filecoin (rand_gen_, filedist); + for (uint64_t i = filestart; i < (filestart + filecount); i++) + { + if (filecoin ()) + { + offsets.push_back (i); + } + } + } + std::sort (offsets.begin (), offsets.end ()); + + FILE* f = fopen (disk_storage_filename_->c_str (), "rb"); + assert (f != NULL); + PointT p; + char* loc = reinterpret_cast (&p); + + uint64_t filesamp = offsets.size (); + for (uint64_t i = 0; i < filesamp; i++) + { + int seekret = _fseeki64 (f, offsets[i] * static_cast (sizeof(PointT)), SEEK_SET); + (void)seekret; + assert (seekret == 0); + size_t readlen = fread (loc, sizeof(PointT), 1, f); + (void)readlen; + assert (readlen == 1); + + dst.push_back (p); + } + + fclose (f); + } + } + //////////////////////////////////////////////////////////////////////////////// + +//change this to use a weighted coin flip, to allow sparse sampling of small clouds (eg the bernoulli above) + template void + OutofcoreOctreeDiskContainer::readRangeSubSample (const uint64_t start, const uint64_t count, const double percent, AlignedPointTVector& dst) + { + if (count == 0) + { + return; + } + + dst.clear (); + + uint64_t filestart = 0; + uint64_t filecount = 0; + + int64_t buffcount = -1; + + if (start < filelen_) + { + filestart = start; + } + + if ((start + count) <= filelen_) + { + filecount = count; + } + else + { + filecount = filelen_ - start; + buffcount = count - filecount; + } + + uint64_t filesamp = static_cast (percent * static_cast (filecount)); + + uint64_t buffsamp = (buffcount > 0) ? (static_cast (percent * static_cast (buffcount))) : 0; + + if ((filesamp == 0) && (buffsamp == 0) && (size () > 0)) + { + //std::cerr << "would not add points to LOD, falling back to bernoulli"; + readRangeSubSample_bernoulli (start, count, percent, dst); + return; + } + + if (buffcount > 0) + { + { + boost::mutex::scoped_lock lock (rng_mutex_); + + boost::uniform_int < uint64_t > buffdist (0, buffcount - 1); + boost::variate_generator > buffdie (rand_gen_, buffdist); + + for (uint64_t i = 0; i < buffsamp; i++) + { + uint64_t buffstart = buffdie (); + dst.push_back (writebuff_[buffstart]); + } + } + } + + if (filesamp > 0) + { + //pregen and then sort the offsets to reduce the amount of seek + std::vector < uint64_t > offsets; + { + boost::mutex::scoped_lock lock (rng_mutex_); + + offsets.resize (filesamp); + boost::uniform_int < uint64_t > filedist (filestart, filestart + filecount - 1); + boost::variate_generator > filedie (rand_gen_, filedist); + for (uint64_t i = 0; i < filesamp; i++) + { + uint64_t _filestart = filedie (); + offsets[i] = _filestart; + } + } + std::sort (offsets.begin (), offsets.end ()); + + FILE* f = fopen (disk_storage_filename_->c_str (), "rb"); + assert (f != NULL); + PointT p; + char* loc = reinterpret_cast (&p); + for (uint64_t i = 0; i < filesamp; i++) + { + int seekret = _fseeki64 (f, offsets[i] * static_cast (sizeof(PointT)), SEEK_SET); + (void)seekret; + assert (seekret == 0); + size_t readlen = fread (loc, sizeof(PointT), 1, f); + (void)readlen; + assert (readlen == 1); + + dst.push_back (p); + } + int res = fclose (f); + (void)res; + assert (res == 0); + } + } + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeDiskContainer::push_back (const PointT& p) + { + writebuff_.push_back (p); + if (writebuff_.size () > WRITE_BUFF_MAX_) + { + flushWritebuff (false); + } + } + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeDiskContainer::insertRange (const AlignedPointTVector& src) + { + const uint64_t count = src.size (); + + typename pcl::PointCloud::Ptr tmp_cloud (new pcl::PointCloud ()); + + // If there's a pcd file with data + if (boost::filesystem::exists (*disk_storage_filename_)) + { + // Open the existing file + pcl::PCDReader reader; + int res = reader.read (*disk_storage_filename_, *tmp_cloud); + (void)res; + assert (res == 0); + } + // Otherwise create the point cloud which will be saved to the pcd file for the first time + else + { + tmp_cloud->width = static_cast (count + writebuff_.size ()); + tmp_cloud->height = 1; + } + + for (size_t i = 0; i < src.size (); i++) + tmp_cloud->points.push_back (src[i]); + + // If there are any points in the write cache writebuff_, a different write cache than this one, concatenate + for (size_t i = 0; i < writebuff_.size (); i++) + { + tmp_cloud->points.push_back (writebuff_[i]); + } + + //assume unorganized point cloud + tmp_cloud->width = static_cast (tmp_cloud->points.size ()); + + //save and close + PCDWriter writer; + + int res = writer.writeBinaryCompressed (*disk_storage_filename_, *tmp_cloud); + (void)res; + assert (res == 0); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeDiskContainer::insertRange (const pcl::PCLPointCloud2::Ptr& input_cloud) + { + pcl::PCLPointCloud2::Ptr tmp_cloud (new pcl::PCLPointCloud2 ()); + + //if there's a pcd file with data associated with this node, read the data, concatenate, and resave + if (boost::filesystem::exists (*disk_storage_filename_)) + { + //open the existing file + pcl::PCDReader reader; + int res = reader.read (*disk_storage_filename_, *tmp_cloud); + (void)res; + assert (res == 0); + pcl::PCDWriter writer; + PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeDiskContainer::%s] Concatenating point cloud from %s to new cloud\n", __FUNCTION__, disk_storage_filename_->c_str ()); + + size_t previous_num_pts = tmp_cloud->width*tmp_cloud->height + input_cloud->width*input_cloud->height; + //Concatenate will fail if the fields in input_cloud do not match the fields in the PCD file. + pcl::concatenatePointCloud (*tmp_cloud, *input_cloud, *tmp_cloud); + size_t res_pts = tmp_cloud->width*tmp_cloud->height; + + (void)previous_num_pts; + (void)res_pts; + + assert (previous_num_pts == res_pts); + + writer.writeBinaryCompressed (*disk_storage_filename_, *tmp_cloud); + + } + else //otherwise create the point cloud which will be saved to the pcd file for the first time + { + pcl::PCDWriter writer; + int res = writer.writeBinaryCompressed (*disk_storage_filename_, *input_cloud); + (void)res; + assert (res == 0); + } + + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeDiskContainer::readRange (const uint64_t, const uint64_t, pcl::PCLPointCloud2::Ptr& dst) + { + pcl::PCDReader reader; + + Eigen::Vector4f origin; + Eigen::Quaternionf orientation; + int pcd_version; + + if (boost::filesystem::exists (*disk_storage_filename_)) + { +// PCL_INFO ("[pcl::outofcore::OutofcoreOctreeDiskContainer::%s] Reading points from disk from %s.\n", __FUNCTION__ , disk_storage_filename_->c_str ()); + int res = reader.read (*disk_storage_filename_, *dst, origin, orientation, pcd_version); + (void)res; + assert (res != -1); + } + else + { + PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeDiskContainer::%s] File %s does not exist in node.\n", __FUNCTION__, disk_storage_filename_->c_str ()); + } + } + + //////////////////////////////////////////////////////////////////////////////// + + template int + OutofcoreOctreeDiskContainer::read (pcl::PCLPointCloud2::Ptr& output_cloud) + { + pcl::PCLPointCloud2::Ptr temp_output_cloud (new pcl::PCLPointCloud2 ()); + + if (boost::filesystem::exists (*disk_storage_filename_)) + { +// PCL_INFO ("[pcl::outofcore::OutofcoreOctreeDiskContainer::%s] Reading points from disk from %s.\n", __FUNCTION__ , disk_storage_filename_->c_str ()); + int res = pcl::io::loadPCDFile (*disk_storage_filename_, *temp_output_cloud); + (void)res; + assert (res != -1); + if(res == -1) + return (-1); + } + else + { + PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeDiskContainer::%s] File %s does not exist in node.\n", __FUNCTION__, disk_storage_filename_->c_str ()); + return (-1); + } + + if(output_cloud.get () != 0) + { + pcl::concatenatePointCloud (*output_cloud, *temp_output_cloud, *output_cloud); + } + else + { + output_cloud = temp_output_cloud; + } + return (0); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeDiskContainer::insertRange (const PointT* const * start, const uint64_t count) + { +// PCL_THROW_EXCEPTION (PCLException, "[pcl::outofcore::OutofcoreOctreeDiskContainer] Deprecated\n"); + //copy the handles to a continuous block + PointT* arr = new PointT[count]; + + //copy from start of array, element by element + for (size_t i = 0; i < count; i++) + { + arr[i] = *(start[i]); + } + + insertRange (arr, count); + delete[] arr; + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeDiskContainer::insertRange (const PointT* start, const uint64_t count) + { + typename pcl::PointCloud::Ptr tmp_cloud (new pcl::PointCloud ()); + + // If there's a pcd file with data, read it in from disk for appending + if (boost::filesystem::exists (*disk_storage_filename_)) + { + pcl::PCDReader reader; + // Open it + int res = reader.read (disk_storage_filename_->c_str (), *tmp_cloud); + (void)res; + assert (res == 0); + } + else //otherwise create the pcd file + { + tmp_cloud->width = static_cast (count) + static_cast (writebuff_.size ()); + tmp_cloud->height = 1; + } + + // Add any points in the cache + for (size_t i = 0; i < writebuff_.size (); i++) + { + tmp_cloud->points.push_back (writebuff_ [i]); + } + + //add the new points passed with this function + for (size_t i = 0; i < count; i++) + { + tmp_cloud->points.push_back (*(start + i)); + } + + tmp_cloud->width = static_cast (tmp_cloud->points.size ()); + tmp_cloud->height = 1; + + //save and close + PCDWriter writer; + + int res = writer.writeBinaryCompressed (*disk_storage_filename_, *tmp_cloud); + (void)res; + assert (res == 0); + } + //////////////////////////////////////////////////////////////////////////////// + + template boost::uint64_t + OutofcoreOctreeDiskContainer::getDataSize () const + { + pcl::PCLPointCloud2 cloud_info; + Eigen::Vector4f origin; + Eigen::Quaternionf orientation; + int pcd_version; + int data_type; + unsigned int data_index; + + //read the header of the pcd file and get the number of points + PCDReader reader; + reader.readHeader (*disk_storage_filename_, cloud_info, origin, orientation, pcd_version, data_type, data_index, 0); + + boost::uint64_t total_points = cloud_info.width * cloud_info.height + writebuff_.size (); + + return (total_points); + } + //////////////////////////////////////////////////////////////////////////////// + + }//namespace outofcore +}//namespace pcl + +#endif //PCL_OUTOFCORE_OCTREE_DISK_CONTAINER_IMPL_H_ diff --git a/pcl-1.7/pcl/outofcore/impl/octree_ram_container.hpp b/pcl-1.7/pcl/outofcore/impl/octree_ram_container.hpp new file mode 100644 index 0000000..8679ace --- /dev/null +++ b/pcl-1.7/pcl/outofcore/impl/octree_ram_container.hpp @@ -0,0 +1,143 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012, Urban Robotics, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: octree_ram_container.hpp 6927 2012-08-23 02:34:54Z stfox88 $ + */ + +#ifndef PCL_OUTOFCORE_RAM_CONTAINER_IMPL_H_ +#define PCL_OUTOFCORE_RAM_CONTAINER_IMPL_H_ + +// C++ +#include + +// PCL (Urban Robotics) +#include + +namespace pcl +{ + namespace outofcore + { + + template + boost::mutex OutofcoreOctreeRamContainer::rng_mutex_; + + template + boost::mt19937 OutofcoreOctreeRamContainer::rand_gen_ (static_cast(std::time( NULL))); + + template void + OutofcoreOctreeRamContainer::convertToXYZ (const boost::filesystem::path& path) + { + if (!container_.empty ()) + { + FILE* fxyz = fopen (path.string ().c_str (), "w"); + + boost::uint64_t num = size (); + for (boost::uint64_t i = 0; i < num; i++) + { + const PointT& p = container_[i]; + + std::stringstream ss; + ss << std::fixed; + ss.precision (16); + ss << p.x << "\t" << p.y << "\t" << p.z << "\n"; + + fwrite (ss.str ().c_str (), 1, ss.str ().size (), fxyz); + } + + assert ( fclose (fxyz) == 0 ); + } + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeRamContainer::insertRange (const PointT* start, const boost::uint64_t count) + { + container_.insert (container_.end (), start, start + count); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeRamContainer::insertRange (const PointT* const * start, const boost::uint64_t count) + { + AlignedPointTVector temp; + temp.resize (count); + for (boost::uint64_t i = 0; i < count; i++) + { + temp[i] = *start[i]; + } + container_.insert (container_.end (), temp.begin (), temp.end ()); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeRamContainer::readRange (const boost::uint64_t start, const boost::uint64_t count, + AlignedPointTVector& v) + { + v.resize (count); + memcpy (v.data (), container_.data () + start, count * sizeof(PointT)); + } + + //////////////////////////////////////////////////////////////////////////////// + + template void + OutofcoreOctreeRamContainer::readRangeSubSample (const boost::uint64_t start, + const boost::uint64_t count, + const double percent, + AlignedPointTVector& v) + { + boost::uint64_t samplesize = static_cast (percent * static_cast (count)); + + boost::mutex::scoped_lock lock (rng_mutex_); + + boost::uniform_int < boost::uint64_t > buffdist (start, start + count); + boost::variate_generator > buffdie (rand_gen_, buffdist); + + for (boost::uint64_t i = 0; i < samplesize; i++) + { + boost::uint64_t buffstart = buffdie (); + v.push_back (container_[buffstart]); + } + } + + //////////////////////////////////////////////////////////////////////////////// + + }//namespace outofcore +}//namespace pcl + +#endif //PCL_OUTOFCORE_RAM_CONTAINER_IMPL_H_ diff --git a/pcl-1.7/pcl/outofcore/impl/outofcore_breadth_first_iterator.hpp b/pcl-1.7/pcl/outofcore/impl/outofcore_breadth_first_iterator.hpp new file mode 100644 index 0000000..7265cb3 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/impl/outofcore_breadth_first_iterator.hpp @@ -0,0 +1,115 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: outofcore_depth_first_iterator.hpp 7938 2012-11-14 06:27:39Z jrosen $ + */ + +#ifndef PCL_OUTOFCORE_BREADTH_FIRST_ITERATOR_IMPL_H_ +#define PCL_OUTOFCORE_BREADTH_FIRST_ITERATOR_IMPL_H_ + +namespace pcl +{ + namespace outofcore + { + + template + OutofcoreBreadthFirstIterator::OutofcoreBreadthFirstIterator (OutofcoreOctreeBase& octree_arg) + : OutofcoreIteratorBase (octree_arg) + { + reset(); + } + + //////////////////////////////////////////////////////////////////////////////// + + template + OutofcoreBreadthFirstIterator::~OutofcoreBreadthFirstIterator () + { + } + + //////////////////////////////////////////////////////////////////////////////// + + template + OutofcoreBreadthFirstIterator& + OutofcoreBreadthFirstIterator::operator++ () + { + if (FIFO_.size ()) + { + // Get the first entry from the FIFO queue + OctreeDiskNode *node = FIFO_.front (); + FIFO_.pop_front (); + + // If not skipping children, not at the max specified depth and we're a branch then iterate over children + if (!skip_child_voxels_ && node->getDepth () < this->max_depth_ && node->getNodeType () == pcl::octree::BRANCH_NODE) + { + // Get the branch node + BranchNode* branch = static_cast (node); + OctreeDiskNode* child = 0; + + // Iterate over the branches children + for (unsigned char child_idx = 0; child_idx < 8 ; child_idx++) + { + // If child/index exists add it to FIFO queue + child = this->octree_.getBranchChildPtr (*branch, child_idx); + if (child) + { + FIFO_.push_back (child); + } + } + } + } + + // Reset skipped children + skip_child_voxels_ = false; + + // If there's a queue, set the current node to the first entry + if (FIFO_.size ()) + { + this->currentNode_ = FIFO_.front (); + } + else + { + this->currentNode_ = NULL; + } + + return (*this); + } + + //////////////////////////////////////////////////////////////////////////////// + + }//namesapce pcl +}//namespace outofcore + +#endif //PCL_OUTOFCORE_BREADTH_FIRST_ITERATOR_IMPL_H_ + diff --git a/pcl-1.7/pcl/outofcore/impl/outofcore_depth_first_iterator.hpp b/pcl-1.7/pcl/outofcore/impl/outofcore_depth_first_iterator.hpp new file mode 100644 index 0000000..4d6caf0 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/impl/outofcore_depth_first_iterator.hpp @@ -0,0 +1,151 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OUTOFCORE_DEPTH_FIRST_ITERATOR_IMPL_H_ +#define PCL_OUTOFCORE_DEPTH_FIRST_ITERATOR_IMPL_H_ + +namespace pcl +{ + namespace outofcore + { + + template + OutofcoreDepthFirstIterator::OutofcoreDepthFirstIterator (OutofcoreOctreeBase& octree_arg) + : OutofcoreIteratorBase (octree_arg) + , currentChildIdx_ (0) + , stack_ (0) + { + stack_.reserve (this->octree_.getTreeDepth ()); + OutofcoreIteratorBase::reset (); + } + + //////////////////////////////////////////////////////////////////////////////// + + template + OutofcoreDepthFirstIterator::~OutofcoreDepthFirstIterator () + { + } + + //////////////////////////////////////////////////////////////////////////////// + + template + OutofcoreDepthFirstIterator& + OutofcoreDepthFirstIterator::operator++ () + { + //when currentNode_ is 0, skip incrementing because it is already at the end + if (this->currentNode_) + { + bool bTreeUp = false; + OutofcoreOctreeBaseNode* itNode = 0; + + if (this->currentNode_->getNodeType () == pcl::octree::BRANCH_NODE) + { + BranchNode* currentBranch = static_cast (this->currentNode_); + + if (currentChildIdx_ < 8) + { + itNode = this->octree_.getBranchChildPtr (*currentBranch, currentChildIdx_); + + //keep looking for a valid child until we've run out of children or a valid one is found + while ((currentChildIdx_ < 7) && !(itNode)) + { + //find next existing child node + currentChildIdx_++; + itNode = this->octree_.getBranchChildPtr (*currentBranch, currentChildIdx_); + } + //if no valid one was found, set flag to move back up the tree to the parent node + if (!itNode) + { + bTreeUp = true; + } + } + else + { + bTreeUp = true; + } + } + else + { + bTreeUp = true; + } + + if (bTreeUp) + { + if (stack_.size () > 0) + { + std::pair*, unsigned char>& stackEntry = stack_.back (); + stack_.pop_back (); + + this->currentNode_ = stackEntry.first; + currentChildIdx_ = stackEntry.second; + + //don't do anything with the keys here... + this->currentOctreeDepth_--; + } + else + { + this->currentNode_ = NULL; + } + + } + else + { + std::pair*, unsigned char> newStackEntry; + newStackEntry.first = this->currentNode_; + newStackEntry.second = static_cast (currentChildIdx_+1); + + stack_.push_back (newStackEntry); + + //don't do anything with the keys here... + + this->currentOctreeDepth_++; + currentChildIdx_= 0; + this->currentNode_ = itNode; + } + } + + return (*this); + } + + //////////////////////////////////////////////////////////////////////////////// + + }//namesapce pcl +}//namespace outofcore + +#endif //PCL_OUTOFCORE_DEPTH_FIRST_ITERATOR_IMPL_H_ + diff --git a/pcl-1.7/pcl/outofcore/metadata.h b/pcl-1.7/pcl/outofcore/metadata.h new file mode 100644 index 0000000..6f68d8a --- /dev/null +++ b/pcl-1.7/pcl/outofcore/metadata.h @@ -0,0 +1,98 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + + +#ifndef PCL_OUTOFCORE_METADATA_H_ +#define PCL_OUTOFCORE_METADATA_H_ + +#include +#include +#include + +namespace pcl +{ + namespace outofcore + { + + /** \class AbstractMetadata + * + * \brief Abstract interface for outofcore metadata file types + * + * \ingroup outofcore + * \author Stephen Fox (foxstephend@gmail.com) + */ + + class PCL_EXPORTS OutofcoreAbstractMetadata + { + public: + + /** \brief Empty constructor */ + OutofcoreAbstractMetadata () + { + } + + virtual + ~OutofcoreAbstractMetadata () + {} + + /** \brief Write the metadata in the on-disk format, e.g. JSON. */ + virtual void + serializeMetadataToDisk () = 0; + + /** \brief Method which should read and parse metadata and store + * it in variables that have public getters and setters*/ + virtual int + loadMetadataFromDisk (const boost::filesystem::path& path_to_metadata) = 0; + + /** \brief Should write the same ascii metadata that is saved on + * disk, or a human readable format of the metadata in case a binary format is being used */ + friend std::ostream& + operator<<(std::ostream& os, const OutofcoreAbstractMetadata& metadata_arg); + + protected: + + /** \brief Constructs the metadata ascii which can be written to disk or piped to stdout */ + virtual void + writeMetadataString (std::vector& buf) =0; + + }; + + }//namespace outofcore +}//namespace pcl + +#endif //PCL_OUTOFCORE_METADATA_H_ diff --git a/pcl-1.7/pcl/outofcore/octree_abstract_node_container.h b/pcl-1.7/pcl/outofcore/octree_abstract_node_container.h new file mode 100644 index 0000000..8aeef7a --- /dev/null +++ b/pcl-1.7/pcl/outofcore/octree_abstract_node_container.h @@ -0,0 +1,105 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: octree_abstract_node_container.h 6802M 2012-08-25 00:11:05Z (local) $ + */ + +#ifndef PCL_OUTOFCORE_OCTREE_ABSTRACT_NODE_CONTAINER_H_ +#define PCL_OUTOFCORE_OCTREE_ABSTRACT_NODE_CONTAINER_H_ + +#include +#include + +#include + +namespace pcl +{ + namespace outofcore + { + template + class OutofcoreAbstractNodeContainer + { + + public: + typedef std::vector > AlignedPointTVector; + + OutofcoreAbstractNodeContainer () + : container_ () + {} + + OutofcoreAbstractNodeContainer (const boost::filesystem::path&) {} + + virtual + ~OutofcoreAbstractNodeContainer () {} + + virtual void + insertRange (const PointT* start, const uint64_t count)=0; + + virtual void + insertRange (const PointT* const* start, const uint64_t count)=0; + + virtual void + readRange (const uint64_t start, const uint64_t count, AlignedPointTVector& v)=0; + + virtual void + readRangeSubSample (const uint64_t start, const uint64_t count, const double percent, AlignedPointTVector& v) =0; + + virtual bool + empty () const=0; + + virtual uint64_t + size () const =0; + + virtual void + clear ()=0; + + virtual void + convertToXYZ (const boost::filesystem::path& path)=0; + + virtual PointT + operator[] (uint64_t idx) const=0; + + protected: + OutofcoreAbstractNodeContainer (const OutofcoreAbstractNodeContainer& rval); + + AlignedPointTVector container_; + + static boost::mutex rng_mutex_; + static boost::mt19937 rand_gen_; + }; + }//namespace outofcore +}//namespace pcl + +#endif //PCL_OUTOFCORE_OCTREE_ABSTRACT_CONTAINER_H_ diff --git a/pcl-1.7/pcl/outofcore/octree_base.h b/pcl-1.7/pcl/outofcore/octree_base.h new file mode 100644 index 0000000..f29fdd7 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/octree_base.h @@ -0,0 +1,666 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012, Urban Robotics, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OUTOFCORE_OUTOFCOREOCTREEBASE_H_ +#define PCL_OUTOFCORE_OUTOFCOREOCTREEBASE_H_ + +#include +#include + +//outofcore classes +#include +#include +#include + +//outofcore iterators +#include +#include +#include +#include +#include + +//outofcore metadata +#include +#include + +#include +#include + +#include + +namespace pcl +{ + namespace outofcore + { + struct OutofcoreParams + { + std::string node_index_basename_; + std::string node_container_basename_; + std::string node_index_extension_; + std::string node_container_extension_; + double sample_percent; + }; + + /** \class OutofcoreOctreeBase + * \brief This code defines the octree used for point storage at Urban Robotics. + * + * \note Code was adapted from the Urban Robotics out of core octree implementation. + * Contact Jacob Schloss with any questions. + * http://www.urbanrobotics.net/. This code was integrated for the Urban Robotics + * Code Sprint (URCS) by Stephen Fox (foxstephend@gmail.com). Additional development notes can be found at + * http://www.pointclouds.org/blog/urcs/. + * + * The primary purpose of this class is an interface to the + * recursive traversal (recursion handled by \ref pcl::outofcore::OutofcoreOctreeBaseNode) of the + * in-memory/top-level octree structure. The metadata in each node + * can be loaded entirely into main memory, from which the tree can be traversed + * recursively in this state. This class provides an the interface + * for: + * -# Point/Region insertion methods + * -# Frustrum/box/region queries + * -# Parameterization of resolution, container type, etc... + * + * For lower-level node access, there is a Depth-First iterator + * for traversing the trees with direct access to the nodes. This + * can be used for implementing other algorithms, and other + * iterators can be written in a similar fashion. + * + * The format of the octree is stored on disk in a hierarchical + * octree structure, where .oct_idx are the JSON-based node + * metadata files managed by \ref pcl::outofcore::OutofcoreOctreeNodeMetadata, + * and .octree is the JSON-based octree metadata file managed by + * \ref pcl::outofcore::OutofcoreOctreeBaseMetadata. Children of each node live + * in up to eight subdirectories named from 0 to 7, where a + * metadata and optionally a pcd file will exist. The PCD files + * are stored in compressed binary PCD format, containing all of + * the fields existing in the PCLPointCloud2 objects originally + * inserted into the out of core object. + * + * A brief outline of the out of core octree can be seen + * below. The files in [brackets] exist only when the LOD are + * built. + * + * At this point in time, there is not support for multiple trees + * existing in a single directory hierarchy. + * + * \verbatim + tree_name/ + tree_name.oct_idx + tree_name.octree + [tree_name-uuid.pcd] + 0/ + tree_name.oct_idx + [tree_name-uuid.pcd] + 0/ + ... + 1/ + ... + ... + 0/ + tree_name.oct_idx + tree_name.pcd + 1/ + ... + 7/ + \endverbatim + * + * \ingroup outofcore + * \author Jacob Schloss (jacob.schloss@urbanrobotics.net) + * \author Stephen Fox, Urban Robotics Code Sprint (foxstephend@gmail.com) + * + */ + template, typename PointT = pcl::PointXYZ> + class OutofcoreOctreeBase + { + friend class OutofcoreOctreeBaseNode; + friend class pcl::outofcore::OutofcoreIteratorBase; + + public: + + // public typedefs + typedef OutofcoreOctreeBase, PointT > octree_disk; + typedef OutofcoreOctreeBaseNode, PointT > octree_disk_node; + + typedef OutofcoreOctreeBase, PointT> octree_ram; + typedef OutofcoreOctreeBaseNode, PointT> octree_ram_node; + + typedef OutofcoreOctreeBaseNode OutofcoreNodeType; + + typedef OutofcoreOctreeBaseNode BranchNode; + typedef OutofcoreOctreeBaseNode LeafNode; + + typedef OutofcoreDepthFirstIterator Iterator; + typedef const OutofcoreDepthFirstIterator ConstIterator; + + typedef OutofcoreBreadthFirstIterator BreadthFirstIterator; + typedef const OutofcoreBreadthFirstIterator BreadthFirstConstIterator; + + typedef OutofcoreDepthFirstIterator DepthFirstIterator; + typedef const OutofcoreDepthFirstIterator DepthFirstConstIterator; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef pcl::PointCloud PointCloud; + + typedef boost::shared_ptr > IndicesPtr; + typedef boost::shared_ptr > IndicesConstPtr; + + typedef boost::shared_ptr PointCloudPtr; + typedef boost::shared_ptr PointCloudConstPtr; + + typedef std::vector > AlignedPointTVector; + + // Constructors + // ----------------------------------------------------------------------- + + /** \brief Load an existing tree + * + * If load_all is set, the BB and point count for every node is loaded, + * otherwise only the root node is actually created, and the rest will be + * generated on insertion or query. + * + * \param root_node_name Path to the top-level tree/tree.oct_idx metadata file + * \param load_all Load entire tree metadata (does not load any points from disk) + * \throws PCLException for bad extension (root node metadata must be .oct_idx extension) + */ + OutofcoreOctreeBase (const boost::filesystem::path &root_node_name, const bool load_all); + + /** \brief Create a new tree + * + * Create a new tree rootname with specified bounding box; will remove and overwrite existing tree with the same name + * + * Computes the depth of the tree based on desired leaf , then calls the other constructor. + * + * \param min Bounding box min + * \param max Bounding box max + * \param resolution_arg Node dimension in meters (assuming your point data is in meters) + * \param root_node_name must end in ".oct_idx" + * \param coord_sys Coordinate system which is stored in the JSON metadata + * \throws PCLException if root file extension does not match \ref pcl::outofcore::OutofcoreOctreeBaseNode::node_index_extension + */ + OutofcoreOctreeBase (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const double resolution_arg, const boost::filesystem::path &root_node_name, const std::string &coord_sys); + + /** \brief Create a new tree; will not overwrite existing tree of same name + * + * Create a new tree rootname with specified bounding box; will not overwrite an existing tree + * + * \param max_depth Specifies a fixed number of LODs to generate, which is the depth of the tree + * \param min Bounding box min + * \param max Bounding box max + * \note Bounding box of the tree must be set before inserting any points. The tree \b cannot be resized at this time. + * \param root_node_name must end in ".oct_idx" + * \param coord_sys Coordinate system which is stored in the JSON metadata + * \throws PCLException if the parent directory has existing children (detects an existing tree) + * \throws PCLException if file extension is not ".oct_idx" + */ + OutofcoreOctreeBase (const boost::uint64_t max_depth, const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::filesystem::path &root_node_name, const std::string &coord_sys); + + virtual + ~OutofcoreOctreeBase (); + + // Point/Region INSERTION methods + // -------------------------------------------------------------------------------- + /** \brief Recursively add points to the tree + * \note shared read_write_mutex lock occurs + */ + boost::uint64_t + addDataToLeaf (const AlignedPointTVector &p); + + /** \brief Copies the points from the point_cloud falling within the bounding box of the octree to the + * out-of-core octree; this is an interface to addDataToLeaf and can be used multiple times. + * \param point_cloud Pointer to the point cloud data to copy to the outofcore octree; Assumes templated + * PointT matches for each. + * \return Number of points successfully copied from the point cloud to the octree. + */ + boost::uint64_t + addPointCloud (PointCloudConstPtr point_cloud); + + /** \brief Recursively copies points from input_cloud into the leaf nodes of the out-of-core octree, and stores them to disk. + * + * \param[in] input_cloud The cloud of points to be inserted into the out-of-core octree. Note if multiple PCLPointCloud2 objects are added to the tree, this assumes that they all have exactly the same fields. + * \param[in] skip_bb_check (default=false) whether to skip the bounding box check on insertion. Note the bounding box check is never skipped in the current implementation. + * \return Number of poitns successfully copied from the point cloud to the octree + */ + boost::uint64_t + addPointCloud (pcl::PCLPointCloud2::Ptr &input_cloud, const bool skip_bb_check = false); + + /** \brief Recursively add points to the tree. + * + * Recursively add points to the tree. 1/8 of the remaining + * points at each LOD are stored at each internal node of the + * octree until either (a) runs out of points, in which case + * the leaf is not at the maximum depth of the tree, or (b) + * a larger set of points falls in the leaf at the maximum depth. + * Note unlike the old implementation, multiple + * copies of the same point will \b not be added at multiple + * LODs as it walks the tree. Once the point is added to the + * octree, it is no longer propagated further down the tree. + * + *\param[in] input_cloud The input cloud of points which will + * be copied into the sorted nodes of the out-of-core octree + * \return The total number of points added to the out-of-core + * octree. + */ + boost::uint64_t + addPointCloud_and_genLOD (pcl::PCLPointCloud2::Ptr &input_cloud); + + boost::uint64_t + addPointCloud (pcl::PCLPointCloud2::Ptr &input_cloud); + + boost::uint64_t + addPointCloud_and_genLOD (PointCloudConstPtr point_cloud); + + /** \brief Recursively add points to the tree subsampling LODs on the way. + * + * shared read_write_mutex lock occurs + */ + boost::uint64_t + addDataToLeaf_and_genLOD (AlignedPointTVector &p); + + // Frustrum/Box/Region REQUESTS/QUERIES: DB Accessors + // ----------------------------------------------------------------------- + void + queryFrustum (const double *planes, std::list& file_names) const; + + void + queryFrustum (const double *planes, std::list& file_names, const boost::uint32_t query_depth) const; + + void + queryFrustum (const double *planes, const Eigen::Vector3d &eye, const Eigen::Matrix4d &view_projection_matrix, + std::list& file_names, const boost::uint32_t query_depth) const; + + //-------------------------------------------------------------------------------- + //templated PointT methods + //-------------------------------------------------------------------------------- + + /** \brief Get a list of file paths at query_depth that intersect with your bounding box specified by \c min and \c max. + * When querying with this method, you may be stuck with extra data (some outside of your query bounds) that reside in the files. + * + * \param[in] min The minimum corner of the bounding box + * \param[in] max The maximum corner of the bounding box + * \param[in] query_depth 0 is root, (this->depth) is full + * \param[out] bin_name List of paths to point data files (PCD currently) which satisfy the query + */ + void + queryBBIntersects (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::uint32_t query_depth, std::list &bin_name) const; + + /** \brief Get Points in BB, only points inside BB. The query + * processes the data at each node, filtering points that fall + * out of the query bounds, and returns a single, concatenated + * point cloud. + * + * \param[in] min The minimum corner of the bounding box for querying + * \param[in] max The maximum corner of the bounding box for querying + * \param[in] query_depth The depth from which point data will be taken + * \note If the LODs of the tree have not been built, you must specify the maximum depth in order to retrieve any data + * \param[out] dst The destination vector of points + */ + void + queryBBIncludes (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::uint64_t query_depth, AlignedPointTVector &dst) const; + + /** \brief Query all points falling within the input bounding box at \c query_depth and return a PCLPointCloud2 object in \c dst_blob. + * + * \param[in] min The minimum corner of the input bounding box. + * \param[in] max The maximum corner of the input bounding box. + * \param[in] query_depth The query depth at which to search for points; only points at this depth are returned + * \param[out] dst_blob Storage location for the points satisfying the query. + **/ + void + queryBBIncludes (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::uint64_t query_depth, const pcl::PCLPointCloud2::Ptr &dst_blob) const; + + /** \brief Returns a random subsample of points within the given bounding box at \c query_depth. + * + * \param[in] min The minimum corner of the boudning box to query. + * \param[out] max The maximum corner of the bounding box to query. + * \param[in] query_depth The depth in the tree at which to look for the points. Only returns points within the given bounding box at the specified \c query_depth. + * \param[out] dst The destination in which to return the points. + * + */ + void + queryBBIncludes_subsample (const Eigen::Vector3d &min, const Eigen::Vector3d &max, uint64_t query_depth, const double percent, AlignedPointTVector &dst) const; + + //-------------------------------------------------------------------------------- + //PCLPointCloud2 methods + //-------------------------------------------------------------------------------- + + /** \brief Query all points falling within the input bounding box at \c query_depth and return a PCLPointCloud2 object in \c dst_blob. + * If the optional argument for filter is given, points are processed by that filter before returning. + * \param[in] min The minimum corner of the input bounding box. + * \param[in] max The maximum corner of the input bounding box. + * \param[in] query_depth The depth of tree at which to query; only points at this depth are returned + * \param[out] dst_blob The destination in which points within the bounding box are stored. + * \param[in] percent optional sampling percentage which is applied after each time data are read from disk + */ + virtual void + queryBoundingBox (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const int query_depth, const pcl::PCLPointCloud2::Ptr &dst_blob, double percent = 1.0); + + /** \brief Returns list of pcd files from nodes whose bounding boxes intersect with the input bounding box. + * \param[in] min The minimum corner of the input bounding box. + * \param[in] max The maximum corner of the input bounding box. + * \param query_depth + * \param[out] filenames The list of paths to the PCD files which can be loaded and processed. + */ + inline virtual void + queryBoundingBox (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const int query_depth, std::list &filenames) const + { + boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_); + filenames.clear (); + this->root_node_->queryBBIntersects (min, max, query_depth, filenames); + } + + // Parameterization: getters and setters + // -------------------------------------------------------------------------------- + + /** \brief Get the overall bounding box of the outofcore + * octree; this is the same as the bounding box of the \c root_node_ node + * \param min + * \param max + */ + bool + getBoundingBox (Eigen::Vector3d &min, Eigen::Vector3d &max) const; + + /** \brief Get number of points at specified LOD + * \param[in] depth_index the level of detail at which we want the number of points (0 is root, 1, 2,...) + * \return number of points in the tree at \b depth + */ + inline boost::uint64_t + getNumPointsAtDepth (const boost::uint64_t& depth_index) const + { + return (metadata_->getLODPoints (depth_index)); + } + + /** \brief Queries the number of points in a bounding box + * + * \param[in] min The minimum corner of the input bounding box + * \param[out] max The maximum corner of the input bounding box + * \param[in] query_depth The depth of the nodes to restrict the search to (only this depth is searched) + * \param[in] load_from_disk (default true) Whether to load PCD files to count exactly the number of points within the bounding box; setting this to false will return an upper bound by just reading the number of points from the PCD header, even if there may be some points in that node do not fall within the query bounding box. + * \return Number of points in the bounding box at depth \b query_depth + **/ + boost::uint64_t + queryBoundingBoxNumPoints (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const int query_depth, bool load_from_disk = true); + + + /** \brief Get number of points at each LOD + * \return vector of number of points in each LOD indexed by each level of depth, 0 to the depth of the tree. + */ + inline const std::vector& + getNumPointsVector () const + { + return (metadata_->getLODPoints ()); + } + + /** \brief Get number of LODs, which is the height of the tree + */ + inline boost::uint64_t + getDepth () const + { + return (metadata_->getDepth ()); + } + + inline boost::uint64_t + getTreeDepth () const + { + return (this->getDepth ()); + } + + /** \brief Computes the expected voxel dimensions at the leaves + */ + bool + getBinDimension (double &x, double &y) const; + + /** \brief gets the side length of an (assumed) perfect cubic voxel. + * \note If the initial bounding box specified in constructing the octree is not square, then this method does not return a sensible value + * \return the side length of the cubic voxel size at the specified depth + */ + double + getVoxelSideLength (const boost::uint64_t& depth) const; + + /** \brief Gets the smallest (assumed) cubic voxel side lengths. The smallest voxels are located at the max depth of the tree. + * \return The side length of a the cubic voxel located at the leaves + */ + double + getVoxelSideLength () const + { + return (this->getVoxelSideLength (metadata_->getDepth ())); + } + + /** \brief Get coordinate system tag from the JSON metadata file + */ + const std::string& + getCoordSystem () const + { + return (metadata_->getCoordinateSystem ()); + } + + // Mutators + // ----------------------------------------------------------------------- + + /** \brief Generate multi-resolution LODs for the tree, which are a uniform random sampling all child leafs below the node. + */ + void + buildLOD (); + + /** \brief Prints size of BBox to stdout + */ + void + printBoundingBox (const size_t query_depth) const; + + /** \brief Prints the coordinates of the bounding box of the node to stdout */ + void + printBoundingBox (OutofcoreNodeType& node) const; + + /** \brief Prints size of the bounding boxes to stdou + */ + inline void + printBoundingBox() const + { + this->printBoundingBox (metadata_->getDepth ()); + } + + /** \brief Returns the voxel centers of all existing voxels at \c query_depth + \param[out] voxel_centers Vector of PointXYZ voxel centers for nodes that exist at that depth + \param[in] query_depth the depth of the tree at which to retrieve occupied/existing voxels + */ + void + getOccupiedVoxelCenters(AlignedPointTVector &voxel_centers, size_t query_depth) const; + + /** \brief Returns the voxel centers of all existing voxels at \c query_depth + \param[out] voxel_centers Vector of PointXYZ voxel centers for nodes that exist at that depth + \param[in] query_depth the depth of the tree at which to retrieve occupied/existing voxels + */ + void + getOccupiedVoxelCenters(std::vector > &voxel_centers, size_t query_depth) const; + + /** \brief Gets the voxel centers of all occupied/existing leaves of the tree */ + void + getOccupiedVoxelCenters(AlignedPointTVector &voxel_centers) const + { + getOccupiedVoxelCenters(voxel_centers, metadata_->getDepth ()); + } + + /** \brief Returns the voxel centers of all occupied/existing leaves of the tree + * \param[out] voxel_centers std::vector of the centers of all occupied leaves of the octree + */ + void + getOccupiedVoxelCenters(std::vector > &voxel_centers) const + { + getOccupiedVoxelCenters(voxel_centers, metadata_->getDepth ()); + } + + // Serializers + // ----------------------------------------------------------------------- + + /** \brief Save each .bin file as an XYZ file */ + void + convertToXYZ (); + + /** \brief Write a python script using the vpython module containing all + * the bounding boxes */ + void + writeVPythonVisual (const boost::filesystem::path filename); + + OutofcoreNodeType* + getBranchChildPtr (const BranchNode& branch_arg, unsigned char childIdx_arg) const; + + pcl::Filter::Ptr + getLODFilter (); + + const pcl::Filter::ConstPtr + getLODFilter () const; + + /** \brief Sets the filter to use when building the levels of depth. Recommended filters are pcl::RandomSample or pcl::VoxelGrid */ + void + setLODFilter (const pcl::Filter::Ptr& filter_arg); + + /** \brief Returns the sample_percent_ used when constructing the LOD. */ + double + getSamplePercent () const + { + return (sample_percent_); + } + + /** \brief Sets the sampling percent for constructing LODs. Each LOD gets sample_percent^d points. + * \param[in] sample_percent_arg Percentage between 0 and 1. */ + inline void + setSamplePercent (const double sample_percent_arg) + { + this->sample_percent_ = std::fabs (sample_percent_arg) > 1.0 ? 1.0 : std::fabs (sample_percent_arg); + } + + protected: + void + init (const boost::uint64_t& depth, const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::filesystem::path& root_name, const std::string& coord_sys); + + OutofcoreOctreeBase (OutofcoreOctreeBase &rval); + + OutofcoreOctreeBase (const OutofcoreOctreeBase &rval); + + OutofcoreOctreeBase& + operator= (OutofcoreOctreeBase &rval); + + OutofcoreOctreeBase& + operator= (const OutofcoreOctreeBase &rval); + + inline OutofcoreNodeType* + getRootNode () + { + return (this->root_node_); + } + + /** \brief flush empty nodes only */ + void + DeAllocEmptyNodeCache (OutofcoreNodeType* current); + + /** \brief Write octree definition ".octree" (defined by octree_extension_) to disk */ + void + saveToFile (); + + /** \brief recursive portion of lod builder */ + void + buildLODRecursive (const std::vector& current_branch); + + /** \brief Increment current depths (LOD for branch nodes) point count; called by addDataAtMaxDepth in OutofcoreOctreeBaseNode + */ + inline void + incrementPointsInLOD (boost::uint64_t depth, boost::uint64_t inc); + + /** \brief Auxiliary function to validate path_name extension is .octree + * + * \return 0 if bad; 1 if extension is .oct_idx + */ + bool + checkExtension (const boost::filesystem::path& path_name); + + + /** \brief DEPRECATED - Flush all nodes' cache + * \deprecated this was moved to the octree_node class + */ + void + flushToDisk (); + + /** \brief DEPRECATED - Flush all non leaf nodes' cache + * \deprecated + */ + void + flushToDiskLazy (); + + /** \brief DEPRECATED - Flush empty nodes only + * \deprecated + */ + void + DeAllocEmptyNodeCache (); + + /** \brief Pointer to the root node of the octree data structure */ + OutofcoreNodeType* root_node_; + + /** \brief shared mutex for controlling read/write access to disk */ + mutable boost::shared_mutex read_write_mutex_; + + boost::shared_ptr metadata_; + + /** \brief defined as ".octree" to append to treepath files + * \note this might change + */ + const static std::string TREE_EXTENSION_; + const static int OUTOFCORE_VERSION_; + + const static uint64_t LOAD_COUNT_ = static_cast(2e9); + + private: + + /** \brief Auxiliary function to enlarge a bounding box to a cube. */ + void + enlargeToCube (Eigen::Vector3d &bb_min, Eigen::Vector3d &bb_max); + + /** \brief Auxiliary function to compute the depth of the tree given the bounding box and the desired size of the leaf voxels */ + boost::uint64_t + calculateDepth (const Eigen::Vector3d& min_bb, const Eigen::Vector3d& max_bb, const double leaf_resolution); + + double sample_percent_; + + pcl::RandomSample::Ptr lod_filter_ptr_; + + }; + } +} + + +#endif // PCL_OUTOFCORE_OUTOFCOREOCTREEBASE_H_ diff --git a/pcl-1.7/pcl/outofcore/octree_base_node.h b/pcl-1.7/pcl/outofcore/octree_base_node.h new file mode 100644 index 0000000..fff4700 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/octree_base_node.h @@ -0,0 +1,577 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012, Urban Robotics, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OUTOFCORE_OCTREE_BASE_NODE_H_ +#define PCL_OUTOFCORE_OCTREE_BASE_NODE_H_ + +#include +#include + +#include +#include +#include +#include + +#include + +namespace pcl +{ + namespace outofcore + { + // Forward Declarations + template + class OutofcoreOctreeBaseNode; + + template + class OutofcoreOctreeBase; + + /** \brief Non-class function which creates a single child leaf; used with \ref queryBBIntersects_noload to avoid loading the data from disk */ + template OutofcoreOctreeBaseNode* + makenode_norec (const boost::filesystem::path &path, OutofcoreOctreeBaseNode* super); + + /** \brief Non-class method which performs a bounding box query without loading any of the point cloud data from disk */ + template void + queryBBIntersects_noload (const boost::filesystem::path &root_node, const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::uint32_t query_depth, std::list &bin_name); + + /** \brief Non-class method overload */ + template void + queryBBIntersects_noload (OutofcoreOctreeBaseNode* current, const Eigen::Vector3d&, const Eigen::Vector3d &max, const boost::uint32_t query_depth, std::list &bin_name); + + /** \class OutofcoreOctreeBaseNode + * + * \note Code was adapted from the Urban Robotics out of core octree implementation. + * Contact Jacob Schloss with any questions. + * http://www.urbanrobotics.net/ + * + * \brief OutofcoreOctreeBaseNode Class internally representing nodes of an + * outofcore octree, with accessors to its data via the \ref + * pcl::outofcore::OutofcoreOctreeDiskContainer class or \ref pcl::outofcore::OutofcoreOctreeRamContainer class, + * whichever it is templated against. + * + * \ingroup outofcore + * \author Jacob Schloss (jacob.schloss@urbanrobotics.net) + * + */ + template, typename PointT = pcl::PointXYZ> + class OutofcoreOctreeBaseNode : public pcl::octree::OctreeNode + { + friend class OutofcoreOctreeBase ; + + //these methods can be rewritten with the iterators. + friend OutofcoreOctreeBaseNode* + makenode_norec (const boost::filesystem::path &path, OutofcoreOctreeBaseNode* super); + + friend void + queryBBIntersects_noload (const boost::filesystem::path &rootnode, const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::uint32_t query_depth, std::list &bin_name); + + friend void + queryBBIntersects_noload (OutofcoreOctreeBaseNode* current, const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::uint32_t query_depth, std::list &bin_name); + + public: + typedef OutofcoreOctreeBase , PointT > octree_disk; + typedef OutofcoreOctreeBaseNode , PointT > octree_disk_node; + + typedef std::vector > AlignedPointTVector; + + typedef pcl::octree::node_type_t node_type_t; + + const static std::string node_index_basename; + const static std::string node_container_basename; + const static std::string node_index_extension; + const static std::string node_container_extension; + const static double sample_percent_; + + /** \brief Empty constructor; sets pointers for children and for bounding boxes to 0 + */ + OutofcoreOctreeBaseNode (); + + /** \brief Create root node and directory */ + OutofcoreOctreeBaseNode (const Eigen::Vector3d &bb_min, const Eigen::Vector3d &bb_max, OutofcoreOctreeBase * const tree, const boost::filesystem::path &root_name); + + /** \brief Will recursively delete all children calling recFreeChildrein */ + virtual + ~OutofcoreOctreeBaseNode (); + + //query + /** \brief gets the minimum and maximum corner of the bounding box represented by this node + * \param[out] min_bb returns the minimum corner of the bounding box indexed by 0-->X, 1-->Y, 2-->Z + * \param[out] max_bb returns the maximum corner of the bounding box indexed by 0-->X, 1-->Y, 2-->Z + */ + virtual inline void + getBoundingBox (Eigen::Vector3d &min_bb, Eigen::Vector3d &max_bb) const + { + node_metadata_->getBoundingBox (min_bb, max_bb); + } + + + const boost::filesystem::path& + getPCDFilename () const + { + return node_metadata_->getPCDFilename (); + } + + const boost::filesystem::path& + getMetadataFilename () const + { + return node_metadata_->getMetadataFilename (); + } + + void + queryFrustum (const double planes[24], std::list& file_names); + + void + queryFrustum (const double planes[24], std::list& file_names, const boost::uint32_t query_depth, const bool skip_vfc_check = false); + + void + queryFrustum (const double planes[24], const Eigen::Vector3d &eye, const Eigen::Matrix4d &view_projection_matrix, std::list& file_names, const boost::uint32_t query_depth, const bool skip_vfc_check = false); + + //point extraction + /** \brief Recursively add points that fall into the queried bounding box up to the \b query_depth + * + * \param[in] min_bb the minimum corner of the bounding box, indexed by X,Y,Z coordinates + * \param[in] max_bb the maximum corner of the bounding box, indexed by X,Y,Z coordinates + * \param[in] query_depth the maximum depth to query in the octree for points within the bounding box + * \param[out] dst destion of points returned by the queries + */ + virtual void + queryBBIncludes (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, size_t query_depth, AlignedPointTVector &dst); + + /** \brief Recursively add points that fall into the queried bounding box up to the \b query_depth + * + * \param[in] min_bb the minimum corner of the bounding box, indexed by X,Y,Z coordinates + * \param[in] max_bb the maximum corner of the bounding box, indexed by X,Y,Z coordinates + * \param[in] query_depth the maximum depth to query in the octree for points within the bounding box + * \param[out] dst_blob destion of points returned by the queries + */ + virtual void + queryBBIncludes (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, size_t query_depth, const pcl::PCLPointCloud2::Ptr &dst_blob); + + /** \brief Recursively add points that fall into the queried bounding box up to the \b query_depth + * + * \param[in] min_bb the minimum corner of the bounding box, indexed by X,Y,Z coordinates + * \param[in] max_bb the maximum corner of the bounding box, indexed by X,Y,Z coordinates + * \param[in] query_depth + * \param percent + * \param[out] v std::list of points returned by the query + */ + virtual void + queryBBIncludes_subsample (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, boost::uint64_t query_depth, const double percent, AlignedPointTVector &v); + + virtual void + queryBBIncludes_subsample (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, boost::uint64_t query_depth, const pcl::PCLPointCloud2::Ptr& dst_blob, double percent = 1.0); + + /** \brief Recursive acquires PCD paths to any node with which the queried bounding box intersects (at query_depth only). + */ + virtual void + queryBBIntersects (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, const boost::uint32_t query_depth, std::list &file_names); + + /** \brief Write the voxel size to stdout at \c query_depth + * \param[in] query_depth The depth at which to print the size of the voxel/bounding boxes + */ + virtual void + printBoundingBox (const size_t query_depth) const; + + /** \brief add point to this node if we are a leaf, or find the leaf below us that is supposed to take the point + * \param[in] p vector of points to add to the leaf + * \param[in] skip_bb_check whether to check if the point's coordinates fall within the bounding box + */ + virtual boost::uint64_t + addDataToLeaf (const AlignedPointTVector &p, const bool skip_bb_check = true); + + virtual boost::uint64_t + addDataToLeaf (const std::vector &p, const bool skip_bb_check = true); + + /** \brief Add a single PCLPointCloud2 object into the octree. + * + * \param[in] input_cloud + * \param[in] skip_bb_check (default = false) + */ + virtual boost::uint64_t + addPointCloud (const pcl::PCLPointCloud2::Ptr &input_cloud, const bool skip_bb_check = false); + + /** \brief Add a single PCLPointCloud2 into the octree and build the subsampled LOD during construction; this method of LOD construction is not multiresolution. Rather, there are no redundant data. */ + virtual boost::uint64_t + addPointCloud_and_genLOD (const pcl::PCLPointCloud2::Ptr input_cloud); //, const bool skip_bb_check); + + /** \brief Recursively add points to the leaf and children subsampling LODs + * on the way down. + * + * \note rng_mutex_ lock occurs + */ + virtual boost::uint64_t + addDataToLeaf_and_genLOD (const AlignedPointTVector &p, const bool skip_bb_check); + + /** \brief Write a python visual script to @b file + * \param[in] file output file stream to write the python visual script + */ + void + writeVPythonVisual (std::ofstream &file); + + virtual int + read (pcl::PCLPointCloud2::Ptr &output_cloud); + + virtual inline node_type_t + getNodeType () const + { + if(this->getNumChildren () > 0) + { + return (pcl::octree::BRANCH_NODE); + } + else + { + return (pcl::octree::LEAF_NODE); + } + } + + virtual + OutofcoreOctreeBaseNode* + deepCopy () const + { + OutofcoreOctreeBaseNode* res = NULL; + PCL_THROW_EXCEPTION (PCLException, "Not implemented\n"); + return (res); + } + + virtual inline size_t + getDepth () const + { + return (this->depth_); + } + + /** \brief Returns the total number of children on disk */ + virtual size_t + getNumChildren () const + { + size_t res = this->countNumChildren (); + return (res); + } + + /** \brief Count loaded chilren */ + virtual size_t + getNumLoadedChildren () const + { + size_t res = this->countNumLoadedChildren (); + return (res); + } + + /** \brief Returns a pointer to the child in octant index_arg */ + virtual OutofcoreOctreeBaseNode* + getChildPtr (size_t index_arg) const; + + /** \brief Gets the number of points available in the PCD file */ + virtual boost::uint64_t + getDataSize () const; + + inline virtual void + clearData () + { + //clears write cache and removes PCD file from disk + this->payload_->clear (); + } + + /////////////////////////////////////////////////////////////////////////////// + // PROTECTED METHODS + //////////////////////////////////////////////////////////////////////////////// + protected: + /** \brief Load from disk + * If creating root, path is full name. If creating any other + * node, path is dir; throws exception if directory or metadata not found + * + * \param[in] directory_path pathname + * \param[in] super + * \param[in] load_all + * \throws PCLException if directory is missing + * \throws PCLException if node index is missing + */ + OutofcoreOctreeBaseNode (const boost::filesystem::path &directory_path, OutofcoreOctreeBaseNode* super, bool load_all); + + /** \brief Create root node and directory + * + * Initializes the root node and performs initial filesystem checks for the octree; + * throws OctreeException::OCT_BAD_PATH if root directory is an existing file + * + * \param bb_min triple of x,y,z minima for bounding box + * \param bb_max triple of x,y,z maxima for bounding box + * \param tree adress of the tree data structure that will hold this initial root node + * \param rootname Root directory for location of on-disk octree storage; if directory + * doesn't exist, it is created; if "rootname" is an existing file, + * + * \throws PCLException if the specified path already exists + */ + void init_root_node (const Eigen::Vector3d &bb_min, const Eigen::Vector3d &bb_max, OutofcoreOctreeBase * const tree, const boost::filesystem::path &rootname); + + /** \brief no copy construction right now */ + OutofcoreOctreeBaseNode (const OutofcoreOctreeBaseNode &rval); + + /** \brief Operator= is not implemented */ + OutofcoreOctreeBaseNode& + operator= (const OutofcoreOctreeBaseNode &rval); + + /** \brief Counts the number of child directories on disk; used to update num_children_ */ + virtual size_t + countNumChildren () const; + + /** \brief Counts the number of loaded chilren by testing the \c children_ array; + * used to update num_loaded_chilren_ internally + */ + virtual size_t + countNumLoadedChildren () const; + + /** \brief Save node's metadata to file + * \param[in] recursive if false, save only this node's metadata to file; if true, recursively + * save all children's metadata to files as well + */ + void + saveIdx (bool recursive); + + /** \brief Randomly sample point data + */ + void + randomSample (const AlignedPointTVector &p, AlignedPointTVector &insertBuff, const bool skip_bb_check); + + /** \brief Subdivide points to pass to child nodes */ + void + subdividePoints (const AlignedPointTVector &p, std::vector< AlignedPointTVector > &c, const bool skip_bb_check); + /** \brief Subdivide a single point into a specific child node */ + void + subdividePoint (const PointT &point, std::vector< AlignedPointTVector > &c); + + /** \brief Add data to the leaf when at max depth of tree. If + * skip_bb_check is true, adds to the node regardless of the + * bounding box it represents; otherwise only adds points that + * fall within the bounding box + * + * \param[in] p vector of points to attempt to add to the tree + * \param[in] skip_bb_check if @b true, doesn't check that points + * are in the proper bounding box; if @b false, only adds the + * points that fall into the bounding box to this node + * \return number of points successfully added + */ + boost::uint64_t + addDataAtMaxDepth (const AlignedPointTVector &p, const bool skip_bb_check = true); + + /** \brief Add data to the leaf when at max depth of tree. If + * \c skip_bb_check is true, adds to the node regardless of the + * bounding box it represents; otherwise only adds points that + * fall within the bounding box + * + * \param[in] input_cloud PCLPointCloud2 points to attempt to add to the tree; + * \warning PCLPointCloud2 inserted into the tree must have x,y,z fields, and must be of same type of any other points inserted in the tree + * \param[in] skip_bb_check (default true) if @b true, doesn't check that points + * are in the proper bounding box; if @b false, only adds the + * points that fall into the bounding box to this node + * \return number of points successfully added + */ + boost::uint64_t + addDataAtMaxDepth (const pcl::PCLPointCloud2::Ptr input_cloud, const bool skip_bb_check = true); + + /** \brief Tests whether the input bounding box intersects with the current node's bounding box + * \param[in] min_bb The minimum corner of the input bounding box + * \param[in] max_bb The maximum corner of the input bounding box + * \return bool True if any portion of the bounding box intersects with this node's bounding box; false otherwise + */ + inline bool + intersectsWithBoundingBox (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb) const; + + /** \brief Tests whether the input bounding box falls inclusively within this node's bounding box + * \param[in] min_bb The minimum corner of the input bounding box + * \param[in] max_bb The maximum corner of the input bounding box + * \return bool True if the input bounding box falls inclusively within the boundaries of this node's bounding box + **/ + inline bool + inBoundingBox (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb) const; + + /** \brief Tests whether \c point falls within the input bounding box + * \param[in] min_bb The minimum corner of the input bounding box + * \param[in] max_bb The maximum corner of the input bounding box + * \param[in] point The test point + */ + bool + pointInBoundingBox (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, const Eigen::Vector3d &point); + + /** \brief Tests whether \c p falls within the input bounding box + * \param[in] min_bb The minimum corner of the input bounding box + * \param[in] max_bb The maximum corner of the input bounding box + * \param[in] p The point to be tested + **/ + static bool + pointInBoundingBox (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, const PointT &p); + + /** \brief Tests whether \c x, \c y, and \c z fall within the input bounding box + * \param[in] min_bb The minimum corner of the input bounding box + * \param[in] max_bb The maximum corner of the input bounding box + * \param x + * \param y + * \param z + **/ + static bool + pointInBoundingBox (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, const double x, const double y, const double z); + + /** \brief Tests if specified point is within bounds of current node's bounding box */ + inline bool + pointInBoundingBox (const PointT &p) const; + + /** \brief Creates child node \c idx + * \param[in] idx Index (0-7) of the child node + */ + void + createChild (const std::size_t idx); + + /** \brief Write JSON metadata for this node to file */ + void + saveMetadataToFile (const boost::filesystem::path &path); + + /** \brief Method which recursively free children of this node + */ + void + recFreeChildren (); + + /** \brief Number of points in the payload */ + inline boost::uint64_t + size () const + { + return (payload_->size ()); + } + + void + flushToDiskRecursive (); + + /** \brief Loads the nodes metadata from the JSON file + */ + void + loadFromFile (const boost::filesystem::path &path, OutofcoreOctreeBaseNode* super); + + /** \brief Recursively converts data files to ascii XZY files + * \note This will be deprecated soon + */ + void + convertToXYZRecursive (); + + /** \brief Private constructor used for children + */ + OutofcoreOctreeBaseNode (const Eigen::Vector3d &bb_min, const Eigen::Vector3d &bb_max, const char* dir, OutofcoreOctreeBaseNode* super); + + /** \brief Copies points from this and all children into a single point container (std::list) + */ + void + copyAllCurrentAndChildPointsRec (std::list &v); + + void + copyAllCurrentAndChildPointsRec_sub (std::list &v, const double percent); + + /** \brief Returns whether or not a node has unloaded children data */ + bool + hasUnloadedChildren () const; + + /** \brief Load nodes child data creating new nodes for each */ + virtual void + loadChildren (bool recursive); + + /** \brief Gets a vector of occupied voxel centers + * \param[out] voxel_centers + * \param[in] query_depth + */ + void + getOccupiedVoxelCentersRecursive (AlignedPointTVector &voxel_centers, const size_t query_depth); + + /** \brief Gets a vector of occupied voxel centers + * \param[out] voxel_centers + * \param[in] query_depth + */ + void + getOccupiedVoxelCentersRecursive (std::vector > &voxel_centers, const size_t query_depth); + + /** \brief Sorts the indices based on x,y,z fields and pushes the index into the proper octant's vector; + * This could be overloaded with a parallelized implementation + */ + void + sortOctantIndices (const pcl::PCLPointCloud2::Ptr &input_cloud, std::vector< std::vector > &indices, const Eigen::Vector3d &mid_xyz); + + /** \brief Enlarges the shortest two sidelengths of the + * bounding box to a cubic shape; operation is done in + * place. + */ + void + enlargeToCube (Eigen::Vector3d &bb_min, Eigen::Vector3d &bb_max); + + /** \brief The tree we belong to */ + OutofcoreOctreeBase* m_tree_;// + /** \brief The root node of the tree we belong to */ + OutofcoreOctreeBaseNode* root_node_;// + /** \brief super-node */ + OutofcoreOctreeBaseNode* parent_; + /** \brief Depth in the tree, root is 0, root's children are 1, ... */ + size_t depth_; + /** \brief The children of this node */ + std::vector children_; + + /** \brief Number of children on disk. This is only changed when a new node is created */ + uint64_t num_children_; + + /** \brief Number of loaded children this node has + * + * "Loaded" means child OctreeBaseNodes have been allocated, + * and their metadata files have been loaded into + * memory. num_loaded_children_ <= num_children_ + */ + uint64_t num_loaded_children_; + + /** \brief what holds the points. currently a custom class, but in theory + * you could use an stl container if you rewrote some of this class. I used + * to use deques for this... */ + boost::shared_ptr payload_; + + /** \brief Random number generator mutex */ + static boost::mutex rng_mutex_; + + /** \brief Mersenne Twister: A 623-dimensionally equidistributed uniform + * pseudo-random number generator */ + static boost::mt19937 rand_gen_; + + /** \brief Random number generator seed */ + const static boost::uint32_t rngseed = 0xAABBCCDD; + /** \brief Extension for this class to find the pcd files on disk */ + const static std::string pcd_extension; + + OutofcoreOctreeNodeMetadata::Ptr node_metadata_; + }; + }//namespace outofcore +}//namespace pcl + +#endif //PCL_OUTOFCORE_OCTREE_BASE_NODE_H_ diff --git a/pcl-1.7/pcl/outofcore/octree_disk_container.h b/pcl-1.7/pcl/outofcore/octree_disk_container.h new file mode 100644 index 0000000..9978b9c --- /dev/null +++ b/pcl-1.7/pcl/outofcore/octree_disk_container.h @@ -0,0 +1,305 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012, Urban Robotics, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: octree_disk_container.h 6927M 2012-08-24 13:26:40Z (local) $ + */ + +#ifndef PCL_OUTOFCORE_OCTREE_DISK_CONTAINER_H_ +#define PCL_OUTOFCORE_OCTREE_DISK_CONTAINER_H_ + +// C++ +#include +#include + +#include +#include +#include +#include + +//allows operation on POSIX +#if !defined WIN32 +#define _fseeki64 fseeko +#elif defined __MINGW32__ +#define _fseeki64 fseeko64 +#endif + +namespace pcl +{ + namespace outofcore + { + /** \class OutofcoreOctreeDiskContainer + * \note Code was adapted from the Urban Robotics out of core octree implementation. + * Contact Jacob Schloss with any questions. + * http://www.urbanrobotics.net/ + * + * \brief Class responsible for serialization and deserialization of out of core point data + * \ingroup outofcore + * \author Jacob Schloss (jacob.schloss@urbanrobotics.net) + */ + template + class OutofcoreOctreeDiskContainer : public OutofcoreAbstractNodeContainer + { + + public: + typedef typename OutofcoreAbstractNodeContainer::AlignedPointTVector AlignedPointTVector; + + /** \brief Empty constructor creates disk container and sets filename from random uuid string*/ + OutofcoreOctreeDiskContainer (); + + /** \brief Creates uuid named file or loads existing file + * + * If \b dir is a directory, this constructor will create a new + * uuid named file; if \b dir is an existing file, it will load the + * file metadata for accessing the tree. + * + * \param[in] dir Path to the tree. If it is a directory, it + * will create the metadata. If it is a file, it will load the metadata into memory. + */ + OutofcoreOctreeDiskContainer (const boost::filesystem::path &dir); + + /** \brief flushes write buffer, then frees memory */ + ~OutofcoreOctreeDiskContainer (); + + /** \brief provides random access to points based on a linear index + */ + inline PointT + operator[] (uint64_t idx) const; + + /** \brief Adds a single point to the buffer to be written to disk when the buffer grows sufficiently large, the object is destroyed, or the write buffer is manually flushed */ + inline void + push_back (const PointT& p); + + /** \brief Inserts a vector of points into the disk data structure */ + void + insertRange (const AlignedPointTVector& src); + + /** \brief Inserts a PCLPointCloud2 object directly into the disk container */ + void + insertRange (const pcl::PCLPointCloud2::Ptr &input_cloud); + + void + insertRange (const PointT* const * start, const uint64_t count); + + /** \brief This is the primary method for serialization of + * blocks of point data. This is called by the outofcore + * octree interface, opens the binary file for appending data, + * and writes it to disk. + * + * \param[in] start address of the first point to insert + * \param[in] count offset from start of the last point to insert + */ + void + insertRange (const PointT* start, const uint64_t count); + + /** \brief Reads \b count points into memory from the disk container + * + * Reads \b count points into memory from the disk container, reading at most 2 million elements at a time + * + * \param[in] start index of first point to read from disk + * \param[in] count offset of last point to read from disk + * \param[out] dst std::vector as destination for points read from disk into memory + */ + void + readRange (const uint64_t start, const uint64_t count, AlignedPointTVector &dst); + + void + readRange (const uint64_t, const uint64_t, pcl::PCLPointCloud2::Ptr &dst); + + /** \brief Reads the entire point contents from disk into \c output_cloud + * \param[out] output_cloud + */ + int + read (pcl::PCLPointCloud2::Ptr &output_cloud); + + /** \brief grab percent*count random points. points are \b not guaranteed to be + * unique (could have multiple identical points!) + * + * \param[in] start The starting index of points to select + * \param[in] count The length of the range of points from which to randomly sample + * (i.e. from start to start+count) + * \param[in] percent The percentage of count that is enough points to make up this random sample + * \param[out] dst std::vector as destination for randomly sampled points; size will + * be percentage*count + */ + void + readRangeSubSample (const uint64_t start, const uint64_t count, const double percent, + AlignedPointTVector &dst); + + /** \brief Use bernoulli trials to select points. All points selected will be unique. + * + * \param[in] start The starting index of points to select + * \param[in] count The length of the range of points from which to randomly sample + * (i.e. from start to start+count) + * \param[in] percent The percentage of count that is enough points to make up this random sample + * \param[out] dst std::vector as destination for randomly sampled points; size will + * be percentage*count + */ + void + readRangeSubSample_bernoulli (const uint64_t start, const uint64_t count, + const double percent, AlignedPointTVector& dst); + + /** \brief Returns the total number of points for which this container is responsible, \c filelen_ + points in \c writebuff_ that have not yet been flushed to the disk + */ + uint64_t + size () const + { + return (filelen_ + writebuff_.size ()); + } + + /** \brief STL-like empty test + * \return true if container has no data on disk or waiting to be written in \c writebuff_ */ + inline bool + empty () const + { + return ((filelen_ == 0) && writebuff_.empty ()); + } + + /** \brief Exposed functionality for manually flushing the write buffer during tree creation */ + void + flush (const bool force_cache_dealloc) + { + flushWritebuff (force_cache_dealloc); + } + + /** \brief Returns this objects path name */ + inline std::string& + path () + { + return (*disk_storage_filename_); + } + + inline void + clear () + { + //clear elements that have not yet been written to disk + writebuff_.clear (); + //remove the binary data in the directory + PCL_DEBUG ("[Octree Disk Container] Removing the point data from disk, in file %s\n",disk_storage_filename_->c_str ()); + boost::filesystem::remove (boost::filesystem::path (disk_storage_filename_->c_str ())); + //reset the size-of-file counter + filelen_ = 0; + } + + /** \brief write points to disk as ascii + * + * \param[in] path + */ + void + convertToXYZ (const boost::filesystem::path &path) + { + if (boost::filesystem::exists (*disk_storage_filename_)) + { + FILE* fxyz = fopen (path.string ().c_str (), "w"); + + FILE* f = fopen (disk_storage_filename_->c_str (), "rb"); + assert (f != NULL); + + uint64_t num = size (); + PointT p; + char* loc = reinterpret_cast ( &p ); + + for (uint64_t i = 0; i < num; i++) + { + int seekret = _fseeki64 (f, i * sizeof (PointT), SEEK_SET); + (void)seekret; + assert (seekret == 0); + size_t readlen = fread (loc, sizeof (PointT), 1, f); + (void)readlen; + assert (readlen == 1); + + //of << p.x << "\t" << p.y << "\t" << p.z << "\n"; + std::stringstream ss; + ss << std::fixed; + ss.precision (16); + ss << p.x << "\t" << p.y << "\t" << p.z << "\n"; + + fwrite (ss.str ().c_str (), 1, ss.str ().size (), fxyz); + } + int res = fclose (f); + (void)res; + assert (res == 0); + res = fclose (fxyz); + assert (res == 0); + } + } + + /** \brief Generate a universally unique identifier (UUID) + * + * A mutex lock happens to ensure uniquness + * + */ + static void + getRandomUUIDString (std::string &s); + + /** \brief Returns the number of points in the PCD file by reading the PCD header. */ + boost::uint64_t + getDataSize () const; + + private: + //no copy construction + OutofcoreOctreeDiskContainer (const OutofcoreOctreeDiskContainer& /*rval*/) { } + + + OutofcoreOctreeDiskContainer& + operator= (const OutofcoreOctreeDiskContainer& /*rval*/) { } + + void + flushWritebuff (const bool force_cache_dealloc); + + /** \brief Name of the storage file on disk (i.e., the PCD file) */ + boost::shared_ptr disk_storage_filename_; + + //--- possibly deprecated parameter variables --// + + //number of elements in file + uint64_t filelen_; + + /** \brief elements [0,...,size()-1] map to [filelen, ..., filelen + size()-1] */ + AlignedPointTVector writebuff_; + + const static uint64_t READ_BLOCK_SIZE_; + + static const uint64_t WRITE_BUFF_MAX_; + + static boost::mutex rng_mutex_; + static boost::mt19937 rand_gen_; + static boost::uuids::random_generator uuid_gen_; + + }; + } //namespace outofcore +} //namespace pcl + +#endif //PCL_OUTOFCORE_OCTREE_DISK_CONTAINER_H_ diff --git a/pcl-1.7/pcl/outofcore/octree_ram_container.h b/pcl-1.7/pcl/outofcore/octree_ram_container.h new file mode 100644 index 0000000..d898818 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/octree_ram_container.h @@ -0,0 +1,174 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012, Urban Robotics, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OUTOFCORE_OCTREE_RAM_CONTAINER_H_ +#define PCL_OUTOFCORE_OCTREE_RAM_CONTAINER_H_ + +// C++ +#include + +#include +#include + +namespace pcl +{ + namespace outofcore + { + /** \class OutofcoreOctreeRamContainer + * \brief Storage container class which the outofcore octree base is templated against + * \note Code was adapted from the Urban Robotics out of core octree implementation. + * Contact Jacob Schloss with any questions. + * http://www.urbanrobotics.net/ + * + * \ingroup outofcore + * \author Jacob Schloss (jacob.scloss@urbanrobotics.net) + */ + template + class OutofcoreOctreeRamContainer : public OutofcoreAbstractNodeContainer + { + public: + typedef typename OutofcoreAbstractNodeContainer::AlignedPointTVector AlignedPointTVector; + + /** \brief empty contructor (with a path parameter?) + */ + OutofcoreOctreeRamContainer (const boost::filesystem::path&) : container_ () { } + + /** \brief inserts count number of points into container; uses the container_ type's insert function + * \param[in] start - address of first point in array + * \param[in] count - the maximum offset from start of points inserted + */ + void + insertRange (const PointT* start, const uint64_t count); + + /** \brief inserts count points into container + * \param[in] start - address of first point in array + * \param[in] count - the maximum offset from start of points inserted + */ + void + insertRange (const PointT* const * start, const uint64_t count); + + void + insertRange (AlignedPointTVector& /*p*/) + { + PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeRamContainer] Inserting eigen-aligned point vectors is not implemented using the ram containers\n"); + //insertRange (&(p.begin ()), p.size ()); + } + + void + insertRange (const AlignedPointTVector& /*p*/) + { + PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeRamContainer] Inserting eigen-aligned point vectors is not implemented using the ram containers\n"); + } + + /** \brief + * \param[in] start Index of first point to return from container + * \param[in] count Offset (start + count) of the last point to return from container + * \param[out] v Array of points read from the input range + */ + void + readRange (const uint64_t start, const uint64_t count, AlignedPointTVector &v); + + /** \brief grab percent*count random points. points are NOT + * guaranteed to be unique (could have multiple identical points!) + * + * \param[in] start Index of first point in range to subsample + * \param[in] count Offset (start+count) of last point in range to subsample + * \param[in] percent Percentage of range to return + * \param[out] v Vector with percent*count uniformly random sampled + * points from given input rangerange + */ + void + readRangeSubSample (const uint64_t start, const uint64_t count, const double percent, AlignedPointTVector &v); + + /** \brief returns the size of the vector of points stored in this class */ + inline uint64_t + size () const + { + return container_.size (); + } + + inline bool + empty () const + { + return container_.empty (); + } + + + /** \brief clears the vector of points in this class */ + inline void + clear () + { + //clear the elements in the vector of points + container_.clear (); + } + + /** \brief Writes ascii x,y,z point data to path.string().c_str() + * \param path The path/filename destination of the ascii xyz data + */ + void + convertToXYZ (const boost::filesystem::path &path); + + inline PointT + operator[] (uint64_t index) const + { + assert ( index < container_.size () ); + return ( container_[index] ); + } + + + protected: + //no copy construction + OutofcoreOctreeRamContainer (const OutofcoreOctreeRamContainer& /*rval*/) { } + + OutofcoreOctreeRamContainer& + operator= (const OutofcoreOctreeRamContainer& /*rval*/) { } + + //the actual container + //std::deque container; + + /** \brief linear container to hold the points */ + AlignedPointTVector container_; + + static boost::mutex rng_mutex_; + static boost::mt19937 rand_gen_; + }; + } +} + +#endif //PCL_OUTOFCORE_OCTREE_RAM_CONTAINER_H_ diff --git a/pcl-1.7/pcl/outofcore/outofcore.h b/pcl-1.7/pcl/outofcore/outofcore.h new file mode 100644 index 0000000..5eede43 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/outofcore.h @@ -0,0 +1,58 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012, Urban Robotics, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef OUTOFCORE_H_ +#define OUTOFCORE_H_ + +#include +#include + +#include +#include + +#include + +#include +#include + +#include +#include +#include + +#endif // OUTOFCORE_H_ diff --git a/pcl-1.7/pcl/outofcore/outofcore_base_data.h b/pcl-1.7/pcl/outofcore/outofcore_base_data.h new file mode 100644 index 0000000..8c2fd70 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/outofcore_base_data.h @@ -0,0 +1,223 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OUTOFCORE_OCTREE_BASE_METADATA_H_ +#define PCL_OUTOFCORE_OCTREE_BASE_METADATA_H_ + +#include +#include +#include + +#include + +#include + +//standard library +#include + +namespace pcl +{ + namespace outofcore + { + /** \class OutofcoreOctreeBaseMetadata + * + * \brief Encapsulated class to read JSON metadata into memory, + * and write the JSON metadata associated with the octree root + * node. This is global information that is not the same as the + * metadata for the root node. Inherits OutofcoreAbstractMetadata + * interface for metadata in \b pcl_outofcore. + + * + * This class encapsulates the outofcore base metadata + * serialization/deserialization. At the time it was written, + * this depended on cJSON to write JSON objects to disk. This + * class can be extended to have arbitrary JSON ascii metadata + * fields saved to the metadata object file on disk. The class + * has been encapuslated to abstract the detailso of the on-disk + * format from the outofcore implementation. For example, the + * format could be changed to XML/YAML, or any dynamic format at + * some point. + * + * The JSON file is formatted in the following way: + * \verbatim + { + "name": "nameoftree", + "version": 3, + "pointtype": "urp", #(needs to be changed*) + "lod": 3, #(depth of the tree + "numpts": [X0, X1, X2, ..., XD], #total number of points at each LOD + "coord_system": "ECEF" #the tree is not affected by this value + } + \endverbatim + * + * Any properties not stored in the metadata file are computed + * when the file is loaded. By convention, and for historical + * reasons from the original Urban Robotics implementation, the + * JSON file representing the overall tree is a JSON file named + * with the ".octree" extension. + * + * \ingroup outofcore + * \author Stephen Fox (foxstephend@gmail.com) + */ + class PCL_EXPORTS OutofcoreOctreeBaseMetadata : public OutofcoreAbstractMetadata + { + public: + /** \brief Empty constructor */ + OutofcoreOctreeBaseMetadata (); + /** \brief Load metadata from disk + * + * \param[in] path_arg Location of JSON metadata file to load from disk + */ + OutofcoreOctreeBaseMetadata (const boost::filesystem::path& path_arg); + /** \brief Default destructor*/ + ~OutofcoreOctreeBaseMetadata (); + + /** \brief Copy constructor */ + OutofcoreOctreeBaseMetadata (const OutofcoreOctreeBaseMetadata& orig); + + /** \brief et the outofcore version read from the "version" field of the JSON object */ + int + getOutofcoreVersion () const; + /** \brief Set the outofcore version stored in the "version" field of the JSON object */ + void + setOutofcoreVersion (const int version); + + /** \brief Gets the name of the JSON file */ + boost::filesystem::path + getMetadataFilename () const; + /** \brief Sets the name of the JSON file */ + void + setMetadataFilename (const boost::filesystem::path& path_to_metadata); + + /** \brief Writes the data to a JSON file located at \ref metadata_filename_ */ + virtual void + serializeMetadataToDisk (); + + /** \brief Loads the data from a JSON file located at \ref metadata_filename_ */ + virtual int + loadMetadataFromDisk (); + /** \brief Loads the data from a JSON file located at \ref metadata_filename_ */ + + virtual int + loadMetadataFromDisk (const boost::filesystem::path& path_to_metadata); + + /** \brief Returns the name of the tree; this is not the same as the filename */ + virtual std::string + getOctreeName (); + /** \brief Sets the name of the tree */ + virtual void + setOctreeName (const std::string& name_arg); + + virtual std::string + getPointType (); + /** \brief Sets a single string identifying the point type of this tree */ + virtual void + setPointType (const std::string& point_type_arg); + + virtual std::vector& + getLODPoints (); + virtual std::vector + getLODPoints () const; + /** \brief Get the number of points at the given depth */ + virtual boost::uint64_t + getLODPoints (const boost::uint64_t& depth_index) const; + + /** \brief Initialize the LOD vector with points all 0 */ + virtual void + setLODPoints (const boost::uint64_t& depth); + /** \brief Copy a vector of LOD points into this metadata (dangerous!)*/ + virtual void + setLODPoints (std::vector& lod_points_arg); + + /** \brief Set the number of points at lod_index_arg manually + * \param[in] lod_index_arg the depth at which this increments the number of LOD points + * \param[in] num_points_arg The number of points to store at that LOD + * \param[in] increment If true, increments the number of points at the LOD rather than overwriting the number of points + */ + virtual void + setLODPoints (const boost::uint64_t& lod_index_arg, const boost::uint64_t& num_points_arg, const bool increment=true); + + /** \brief Set information about the coordinate system */ + virtual void + setCoordinateSystem (const std::string& coordinate_system); + /** \brief Get metadata information about the coordinate system */ + virtual std::string + getCoordinateSystem () const; + + /** \brief Set the depth of the tree corresponding to JSON "lod:number". This should always be equal to LOD_num_points_.size()-1 */ + virtual void + setDepth (const boost::uint64_t& depth_arg); + virtual boost::uint64_t + getDepth () const; + + /** \brief Provide operator overload to stream ascii file data*/ + friend std::ostream& + operator<<(std::ostream& os, const OutofcoreOctreeBaseMetadata& metadata_arg); + + protected: + /** \brief Metadata (JSON) file pathname (octree extension JSON file) */ + boost::filesystem::path metadata_filename_; + + /** \brief Outofcore library version identifier; maps to JSON "version":int */ + int outofcore_version_; + + /** \brief Coordinate system; maps to JSON "coord_sys":string */ + std::string coordinate_system_; + + /** \brief Name of the tree (which could be used, for example, as the name of a layer); maps to JSON "name":string*/ + std::string tree_name_; + + /** \brief Delineates the point types of the field; maps to JSON "pointtype":string: + * \note This is inconsistent with "point type" fields used in PCLPointCloud2 and in other places in PCL + */ + std::string point_type_; + + /** \brief Depth of the tree (which is the number of levels of depth); maps to JSON "lod":int*/ + boost::uint64_t levels_of_depth_; + + /** \brief Vector of number of points at each LOD. For a tree with no LOD, all fields will be zero except for the field indexed by LOD_points_[levels_of_depth]; maps to JSON "numpts":int array*/ + std::vector LOD_num_points_; + + /** \brief Writes the JSON metadata to a string */ + virtual void + writeMetadataString (std::vector& buf); + }; + }//namespace outofcore +}//namespace pcl + +#endif // PCL_OUTOFCORE_OCTREE_BASE_METADATA_H_ diff --git a/pcl-1.7/pcl/outofcore/outofcore_breadth_first_iterator.h b/pcl-1.7/pcl/outofcore/outofcore_breadth_first_iterator.h new file mode 100644 index 0000000..3961519 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/outofcore_breadth_first_iterator.h @@ -0,0 +1,109 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: outofcore_depth_first_iterator.h 7938 2012-11-14 06:27:39Z jrosen $ + */ + +#ifndef PCL_OUTOFCORE_BREADTH_FIRST_ITERATOR_H_ +#define PCL_OUTOFCORE_BREADTH_FIRST_ITERATOR_H_ + +#include +namespace pcl +{ + namespace outofcore + { + + /** \class OutofcoreBreadthFirstIterator + * + * \ingroup outofcore + * \author Justin Rosen (jmylesrosen@gmail.com) + * \note Code adapted from \ref octree_iterator.h in Module \ref pcl::octree written by Julius Kammerl + */ + template > + class OutofcoreBreadthFirstIterator : public OutofcoreIteratorBase + { + public: + typedef typename pcl::outofcore::OutofcoreOctreeBase OctreeDisk; + typedef typename pcl::outofcore::OutofcoreOctreeBaseNode OctreeDiskNode; + + typedef typename pcl::outofcore::OutofcoreOctreeBaseNode LeafNode; + typedef typename pcl::outofcore::OutofcoreOctreeBaseNode BranchNode; + + + explicit + OutofcoreBreadthFirstIterator (OctreeDisk& octree_arg); + + virtual + ~OutofcoreBreadthFirstIterator (); + + OutofcoreBreadthFirstIterator& + operator++ (); + + inline OutofcoreBreadthFirstIterator + operator++ (int) + { + OutofcoreBreadthFirstIterator _Tmp = *this; + ++*this; + return (_Tmp); + } + + virtual inline void + reset () + { + OutofcoreIteratorBase::reset(); + + // Clear the FIFO queue and add the root as the first node + FIFO_.clear (); + FIFO_.push_back(this->currentNode_); + + // Don't skip children + skip_child_voxels_ = false; + } + + void + skipChildVoxels () + { + skip_child_voxels_ = true; + } + + protected: + /** FIFO list */ + std::deque FIFO_; + bool skip_child_voxels_; + }; + } +} + +#endif //PCL_OUTOFCORE_BREADTH_FIRST_ITERATOR_H_ diff --git a/pcl-1.7/pcl/outofcore/outofcore_depth_first_iterator.h b/pcl-1.7/pcl/outofcore/outofcore_depth_first_iterator.h new file mode 100644 index 0000000..e110fb5 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/outofcore_depth_first_iterator.h @@ -0,0 +1,90 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OUTOFCORE_DEPTH_FIRST_ITERATOR_H_ +#define PCL_OUTOFCORE_DEPTH_FIRST_ITERATOR_H_ + +#include +namespace pcl +{ + namespace outofcore + { + /** \class OutofcoreDepthFirstIterator + * + * \ingroup outofcore + * \author Stephen Fox (foxstephend@gmail.com) + * \note Code adapted from \ref octree_iterator.h in Module \ref pcl::octree written by Julius Kammerl + */ + template > + class OutofcoreDepthFirstIterator : public OutofcoreIteratorBase + { + public: + typedef typename pcl::outofcore::OutofcoreOctreeBase OctreeDisk; + typedef typename pcl::outofcore::OutofcoreOctreeBaseNode OctreeDiskNode; + + typedef typename pcl::outofcore::OutofcoreOctreeBaseNode LeafNode; + typedef typename pcl::outofcore::OutofcoreOctreeBaseNode BranchNode; + + explicit + OutofcoreDepthFirstIterator (OctreeDisk& octree_arg); + + virtual + ~OutofcoreDepthFirstIterator (); + + OutofcoreDepthFirstIterator& + operator++ (); + + inline OutofcoreDepthFirstIterator + operator++ (int) + { + OutofcoreDepthFirstIterator _Tmp = *this; + ++*this; + return (_Tmp); + } + + void + skipChildVoxels (); + + protected: + unsigned char currentChildIdx_; + std::vector > stack_; + }; + } +} + +#endif //PCL_OUTOFCORE_DEPTH_FIRST_ITERATOR_H_ diff --git a/pcl-1.7/pcl/outofcore/outofcore_impl.h b/pcl-1.7/pcl/outofcore/outofcore_impl.h new file mode 100644 index 0000000..778f812 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/outofcore_impl.h @@ -0,0 +1,54 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012, Urban Robotics, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef OUTOFCORE_IMPL_H_ +#define OUTOFCORE_IMPL_H_ + +#include + +#include + +#include +#include + +#include +#include + + +#endif //OUTOFCORE_IMPL_H_ diff --git a/pcl-1.7/pcl/outofcore/outofcore_iterator_base.h b/pcl-1.7/pcl/outofcore/outofcore_iterator_base.h new file mode 100644 index 0000000..a409395 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/outofcore_iterator_base.h @@ -0,0 +1,159 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_OUTOFCORE_ITERATOR_BASE_H_ +#define PCL_OUTOFCORE_ITERATOR_BASE_H_ + +#include + +#include + +#include +#include +#include + +namespace pcl +{ + namespace outofcore + { + /** \brief Abstract octree iterator class + * \note This class is based on the octree_iterator written by Julius Kammerl adapted to the outofcore octree. The interface is very similar, but it does \b not inherit the \ref pcl::octree iterator base. + * \ingroup outofcore + * \author Stephen Fox (foxstephend@gmail.com) + */ + template + class OutofcoreIteratorBase : public std::iterator, + void, /*no defined distance between iterator*/ + const OutofcoreOctreeBaseNode*,/*Pointer type*/ + const OutofcoreOctreeBaseNode&>/*Reference type*/ + { + public: + typedef typename pcl::outofcore::OutofcoreOctreeBase OctreeDisk; + typedef typename pcl::outofcore::OutofcoreOctreeBaseNode OctreeDiskNode; + + typedef typename pcl::outofcore::OutofcoreOctreeBase::BranchNode BranchNode; + typedef typename pcl::outofcore::OutofcoreOctreeBase::LeafNode LeafNode; + + typedef typename OctreeDisk::OutofcoreNodeType OutofcoreNodeType; + + explicit + OutofcoreIteratorBase (OctreeDisk& octree_arg) + : octree_ (octree_arg), currentNode_ (NULL) + { + reset (); + } + + virtual + ~OutofcoreIteratorBase () + { + } + + OutofcoreIteratorBase (const OutofcoreIteratorBase& src) + : octree_ (src.octree_), currentNode_ (src.currentNode_) + { + } + + inline OutofcoreIteratorBase& + operator = (const OutofcoreIteratorBase& src) + { + octree_ = src.octree_; + currentNode_ = src.currentNode_; + currentOctreeDepth_ = src.currentOctreeDepth_; + } + + + inline OutofcoreNodeType* + operator* () const + { + return (this->getCurrentOctreeNode ()); + } + + virtual inline OutofcoreNodeType* + getCurrentOctreeNode () const + { + return (currentNode_); + } + + virtual inline void + reset () + { + currentNode_ = static_cast (octree_.getRootNode ()); + currentOctreeDepth_ = 0; + max_depth_ = static_cast (octree_.getDepth ()); + } + + inline void + setMaxDepth (unsigned int max_depth) + { + if (max_depth > static_cast (octree_.getDepth ())) + { + max_depth = static_cast (octree_.getDepth ()); + } + + max_depth_ = max_depth; + } + + protected: + OctreeDisk& octree_; + OctreeDiskNode* currentNode_; + unsigned int currentOctreeDepth_; + unsigned int max_depth_; + }; + + +#if 0 + class PCL_EXPORTS OutofcoreBreadthFirstIterator : public OutofcoreIteratorBase + { + + + + + }; + + class PCL_EXPORTS OutofcoreLeafIterator : public OutofcoreIteratorBase + { + + + + }; +#endif + } +} + +#endif //PCL_OUTOFCORE_ITERATOR_BASE_H_ diff --git a/pcl-1.7/pcl/outofcore/outofcore_node_data.h b/pcl-1.7/pcl/outofcore/outofcore_node_data.h new file mode 100644 index 0000000..0e3febb --- /dev/null +++ b/pcl-1.7/pcl/outofcore/outofcore_node_data.h @@ -0,0 +1,190 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: outofcore_node_data.h 6915 2012-08-22 10:54:21Z stfox88 $ + */ + +#ifndef PCL_OUTOFCORE_OCTREE_NODE_METADATA_H_ +#define PCL_OUTOFCORE_OCTREE_NODE_METADATA_H_ + +#include +#include +#include + +#include + +#include + +namespace pcl +{ + namespace outofcore + { + /** \class OutofcoreOctreeNodeMetadata + * + * \brief Encapsulated class to read JSON metadata into memory, and write the JSON metadata for each + * node. + * + * This class encapsulates the outofcore node metadata + * serialization/deserialization. At the time it was written, + * this depended on cJSON to write JSON objects to disk. This + * class can be extended to have arbitrary ascii metadata fields + * saved to the metadata object file on disk. + * + * The JSON file is formatted in the following way: + * \verbatim + { + "version": 3, + "bb_min": [xxx,yyy,zzz], + "bb_max": [xxx,yyy,zzz], + "bin": "path_to_data.pcd" + } + \endverbatim + * + * Any properties not stored in the metadata file are computed + * when the file is loaded (e.g. \ref midpoint_xyz_). By + * convention, the JSON files are stored on disk with .oct_idx + * extension. + * + * \ingroup outofcore + * \author Stephen Fox (foxstephend@gmail.com) + */ + class PCL_EXPORTS OutofcoreOctreeNodeMetadata + { + + public: + //public typedefs + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Empty constructor */ + OutofcoreOctreeNodeMetadata (); + ~OutofcoreOctreeNodeMetadata (); + + /** \brief Copy constructor */ + OutofcoreOctreeNodeMetadata (const OutofcoreOctreeNodeMetadata& orig); + + /** \brief Get the lower bounding box corner */ + const Eigen::Vector3d& + getBoundingBoxMin () const; + /** \brief Set the lower bounding box corner */ + void + setBoundingBoxMin (const Eigen::Vector3d& min_bb); + /** \brief Get the upper bounding box corner */ + const Eigen::Vector3d& + getBoundingBoxMax () const; + /** \brief Set the upper bounding box corner */ + void + setBoundingBoxMax (const Eigen::Vector3d& max_bb); + + /** \brief Get the lower and upper corners of the bounding box enclosing this node */ + void + getBoundingBox (Eigen::Vector3d &min_bb, Eigen::Vector3d &max_bb) const; + /** \brief Set the lower and upper corners of the bounding box */ + void + setBoundingBox (const Eigen::Vector3d& min_bb, const Eigen::Vector3d& max_bb); + + /** \brief Get the directory path name; this is the parent_path of */ + const boost::filesystem::path& + getDirectoryPathname () const; + /** \brief Set the directory path name */ + void + setDirectoryPathname (const boost::filesystem::path& directory_pathname); + + /** \brief Get the path to the PCD file */ + const boost::filesystem::path& + getPCDFilename () const; + /** \brief Set the point filename; extension .pcd */ + void + setPCDFilename (const boost::filesystem::path& point_filename); + + /** \brief et the outofcore version read from the "version" field of the JSON object */ + int + getOutofcoreVersion () const; + /** \brief Set the outofcore version stored in the "version" field of the JSON object */ + void + setOutofcoreVersion (const int version); + + /** \brief Sets the name of the JSON file */ + const boost::filesystem::path& + getMetadataFilename () const; + /** \brief Gets the name of the JSON file */ + void + setMetadataFilename (const boost::filesystem::path& path_to_metadata); + + /** \brief Get the midpoint of this node's bounding box */ + const Eigen::Vector3d& + getVoxelCenter () const; + + /** \brief Writes the data to a JSON file located at \ref metadata_filename_ */ + void + serializeMetadataToDisk (); + + /** \brief Loads the data from a JSON file located at \ref metadata_filename_ */ + int + loadMetadataFromDisk (); + /** \brief Loads the data from a JSON file located at \ref metadata_filename_ */ + int + loadMetadataFromDisk (const boost::filesystem::path& path_to_metadata); + + friend + std::ostream& operator<<(std::ostream& os, const OutofcoreOctreeNodeMetadata& metadata_arg); + + protected: + /** \brief The X,Y,Z axes-aligned minimum corner for the bounding box */ + Eigen::Vector3d min_bb_; + /** \brief The X,Y,Z axes-aligned maximum corner for the bounding box */ + Eigen::Vector3d max_bb_; + /** \brief Path to PCD file (i.e. "bin"ary point data) */ + boost::filesystem::path binary_point_filename_; + /** \brief Voxel center; not stored on disk */ + Eigen::Vector3d midpoint_xyz_; + /** \brief Directory this metadata belongs in */ + boost::filesystem::path directory_; + /** \brief Metadata (JSON) file pathname (oct_idx extension JSON file) */ + boost::filesystem::path metadata_filename_; + /** \brief Outofcore library version identifier */ + int outofcore_version_; + + /** \brief Computes the midpoint; used when bounding box is changed */ + inline void + updateVoxelCenter () + { + midpoint_xyz_ = (this->max_bb_ + this->min_bb_)/static_cast(2.0); + } + }; + }//namespace outofcore +}//namespace pcl + +#endif // PCL_OUTOFCORE_OCTREE_NODE_METADATA_H_ diff --git a/pcl-1.7/pcl/outofcore/visualization/axes.h b/pcl-1.7/pcl/outofcore/visualization/axes.h new file mode 100644 index 0000000..e4c2bf7 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/visualization/axes.h @@ -0,0 +1,98 @@ +#ifndef PCL_OUTOFCORE_AXES_H_ +#define PCL_OUTOFCORE_AXES_H_ + +// C++ +#include +#include + +// PCL +#include "object.h" + +// VTK +#include +#include +#include +#include +//#include +#include +#include +#include +#include +#include + +class Axes : public Object +{ +public: + + // Operators + // ----------------------------------------------------------------------------- + Axes (std::string name, float size = 1.0) : + Object (name) + { + axes_ = vtkSmartPointer::New (); + axes_->SetOrigin (0, 0, 0); + axes_->SetScaleFactor (size); + axes_->Update (); + + vtkSmartPointer axes_colors = vtkSmartPointer::New (); + axes_colors->Allocate (6); + axes_colors->InsertNextValue (0.0); + axes_colors->InsertNextValue (0.0); + axes_colors->InsertNextValue (0.5); + axes_colors->InsertNextValue (0.5); + axes_colors->InsertNextValue (1.0); + axes_colors->InsertNextValue (1.0); + + vtkSmartPointer axes_data = axes_->GetOutput (); + axes_data->GetPointData ()->SetScalars (axes_colors); + + vtkSmartPointer axes_tubes = vtkSmartPointer::New (); +#if VTK_MAJOR_VERSION < 6 + axes_tubes->SetInput (axes_data); +#else + axes_tubes->SetInputData (axes_data); +#endif + axes_tubes->SetRadius (axes_->GetScaleFactor () / 100.0); + axes_tubes->SetNumberOfSides (6); + + vtkSmartPointer axes_mapper = vtkSmartPointer::New (); + axes_mapper->SetScalarModeToUsePointData (); +#if VTK_MAJOR_VERSION < 6 + axes_mapper->SetInput (axes_tubes->GetOutput ()); +#else + axes_mapper->SetInputData (axes_tubes->GetOutput ()); +#endif + + axes_actor_ = vtkSmartPointer::New (); + axes_actor_->GetProperty ()->SetLighting (false); + axes_actor_->SetMapper (axes_mapper); + + addActor (axes_actor_); + } + //~Axes () { } + + // Accessors + // ----------------------------------------------------------------------------- + inline vtkSmartPointer + getAxes () const + { + return axes_; + } + + vtkSmartPointer + getAxesActor () const + { + return axes_actor_; + } + +private: + + // Members + // ----------------------------------------------------------------------------- + vtkSmartPointer axes_; + vtkSmartPointer axes_actor_; + +}; + +#endif + diff --git a/pcl-1.7/pcl/outofcore/visualization/camera.h b/pcl-1.7/pcl/outofcore/visualization/camera.h new file mode 100644 index 0000000..53dde35 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/visualization/camera.h @@ -0,0 +1,153 @@ +#ifndef PCL_OUTOFCORE_CAMERA_H_ +#define PCL_OUTOFCORE_CAMERA_H_ + +// C++ +#include +#include + +// PCL +#include +#include + +// VTK +#include +#include +#include +#include +#include + +class Camera : public Object +{ +public: + + // Operators + // ----------------------------------------------------------------------------- + Camera (std::string name); + Camera (std::string name, vtkSmartPointer camera); + +private: +// friend std::ostream & operator<<(std::ostream &os, const Camera& camera); + +public: + + // Accessors + // ----------------------------------------------------------------------------- + inline vtkSmartPointer + getCamera () const + { + return camera_; + } + + inline vtkSmartPointer + getCameraActor () const + { + return camera_actor_; + } + + inline vtkSmartPointer + getHullActor () const + { + return hull_actor_; + } + + inline bool + getDisplay () const + { + return display_; + } + + void + setDisplay (bool display) + { + this->display_ = display; + } + + void + getFrustum (double frustum[]) + { + for (int i = 0; i < 24; i++) + frustum[i] = frustum_[i]; + } + + void + setProjectionMatrix (const Eigen::Matrix4d &projection_matrix) + { + projection_matrix_ = projection_matrix; + } + + Eigen::Matrix4d + getProjectionMatrix () + { + return projection_matrix_; + } + + void + setModelViewMatrix (const Eigen::Matrix4d &model_view_matrix) + { + model_view_matrix_ = model_view_matrix; + } + + Eigen::Matrix4d + getModelViewMatrix () + { + return model_view_matrix_; + } + + Eigen::Matrix4d + getViewProjectionMatrix () + { + return Eigen::Matrix4d (projection_matrix_ * model_view_matrix_); + } + + Eigen::Vector3d + getPosition () + { + //Compute eye or position from model view matrix + Eigen::Matrix4d inverse_model_view_matrix = model_view_matrix_.inverse (); + Eigen::Vector3d position; + for (int i = 0; i < 3; i++) + { + position (i) = inverse_model_view_matrix (i, 3); + } + + return position; + } + + inline void + setClippingRange (float near_value = 0.0001f, float far_value = 100000.f) + { + camera_->SetClippingRange (near_value, far_value); + } + + virtual void + render (vtkRenderer* renderer); + + // Methods + // ----------------------------------------------------------------------------- + //void computeFrustum(double aspect); + void + computeFrustum (); + //computeFrustum(double aspect); + void + printFrustum (); + +private: + + // Members + // ----------------------------------------------------------------------------- + vtkSmartPointer camera_; + vtkSmartPointer camera_actor_; + vtkSmartPointer hull_actor_; + + bool display_; + + double frustum_[24]; + Eigen::Matrix4d projection_matrix_; + Eigen::Matrix4d model_view_matrix_; + + double prevUp_[3]; + double prevFocal_[3]; + double prevPos_[3]; +}; + +#endif diff --git a/pcl-1.7/pcl/outofcore/visualization/common.h b/pcl-1.7/pcl/outofcore/visualization/common.h new file mode 100644 index 0000000..aec5e58 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/visualization/common.h @@ -0,0 +1,11 @@ +#ifndef PCL_OUTOFCORE_COMMON_H_ +#define PCL_OUTOFCORE_COMMON_H_ + +// VTK +#include +#include + +vtkSmartPointer +getVtkCube (double x_min, double x_max, double y_min, double y_max, double z_min, double z_max); + +#endif diff --git a/pcl-1.7/pcl/outofcore/visualization/geometry.h b/pcl-1.7/pcl/outofcore/visualization/geometry.h new file mode 100644 index 0000000..7990384 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/visualization/geometry.h @@ -0,0 +1,43 @@ +#ifndef PCL_OUTOFCORE_GEOMETRY_H_ +#define PCL_OUTOFCORE_GEOMETRY_H_ + +// C++ +#include + +// PCL +#include "object.h" + +// VTK +#include +#include + +class Geometry : public Object +{ +protected: + + // Operators + // ----------------------------------------------------------------------------- + Geometry (std::string name) : + Object (name) + { + } + +public: + + virtual + ~Geometry () { } + +public: + + // Accessors + // ----------------------------------------------------------------------------- + virtual vtkSmartPointer + getActor () const + { + std::cout << "Get Geometry Actor" << std::endl; + return NULL; + } + +}; + +#endif diff --git a/pcl-1.7/pcl/outofcore/visualization/grid.h b/pcl-1.7/pcl/outofcore/visualization/grid.h new file mode 100644 index 0000000..b9aa344 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/visualization/grid.h @@ -0,0 +1,54 @@ +#ifndef PCL_OUTOFCORE_GRID_H_ +#define PCL_OUTOFCORE_GRID_H_ + +// C++ +#include +#include + +// PCL +#include "geometry.h" +#include "object.h" + +// VTK +#include +#include +#include +#include +#include +#include + +//class Grid : public Geometry +class Grid : public Object +{ +public: + + // Operators + // ----------------------------------------------------------------------------- + Grid (std::string name, int size = 10, double spacing = 1.0); + ~Grid () { } + + // Accessors + // ----------------------------------------------------------------------------- + inline vtkSmartPointer + getGrid () const + { + return grid_; + } + +// virtual vtkSmartPointer + vtkSmartPointer + getGridActor () const + { + return grid_actor_; + } + +private: + + // Members + // ----------------------------------------------------------------------------- + vtkSmartPointer grid_; + vtkSmartPointer grid_actor_; + +}; + +#endif diff --git a/pcl-1.7/pcl/outofcore/visualization/object.h b/pcl-1.7/pcl/outofcore/visualization/object.h new file mode 100644 index 0000000..c6cf208 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/visualization/object.h @@ -0,0 +1,71 @@ +#ifndef PCL_OUTOFCORE_OBJECT_H_ +#define PCL_OUTOFCORE_OBJECT_H_ + +// C++ +#include +#include +#include + +// VTK +#include +#include +#include +#include + +// Boost +//#include +//#include +#include + +//Forward Declaration +class Scene; + +class Object +{ +public: + + // Operators + // ----------------------------------------------------------------------------- + Object (std::string name); + + virtual + ~Object () { } + + + // Accessors + // ----------------------------------------------------------------------------- + std::string + getName () const; + + void + setName (std::string name); + + virtual void + render (vtkRenderer* renderer); + + bool + hasActor (vtkActor *actor); + + void + addActor (vtkActor *actor); + + void + removeActor (vtkActor *actor); + + vtkSmartPointer + getActors (); + +protected: + vtkSmartPointer actors_; + boost::mutex actors_mutex_; + +private: + + // Members + // ----------------------------------------------------------------------------- + std::string name_; + std::map > associated_renderers_; + +}; + +#endif diff --git a/pcl-1.7/pcl/outofcore/visualization/outofcore_cloud.h b/pcl-1.7/pcl/outofcore/visualization/outofcore_cloud.h new file mode 100644 index 0000000..ee65e14 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/visualization/outofcore_cloud.h @@ -0,0 +1,296 @@ +#ifndef PCL_OUTOFCORE_OUTOFCORE_CLOUD_H_ +#define PCL_OUTOFCORE_OUTOFCORE_CLOUD_H_ + +#include + +// PCL +//#include +//#include +#include + +// PCL - outofcore +#include +#include +//#include +#include + +// PCL +#include "camera.h" +//#include + +// VTK +#include +#include +#include +#include +//#include +//#include +//#include +//#include +#include +//#include +//#include +#include + +//class Camera; + +class OutofcoreCloud : public Object +{ + // Typedefs + // ----------------------------------------------------------------------------- + typedef pcl::PointXYZ PointT; +// typedef pcl::outofcore::OutofcoreOctreeBase, PointT> octree_disk; +// typedef pcl::outofcore::OutofcoreOctreeBaseNode, PointT> octree_disk_node; + + typedef pcl::outofcore::OutofcoreOctreeBase<> OctreeDisk; + typedef pcl::outofcore::OutofcoreOctreeBaseNode<> OctreeDiskNode; +// typedef pcl::outofcore::OutofcoreBreadthFirstIterator<> OctreeBreadthFirstIterator; + + typedef boost::shared_ptr OctreeDiskPtr; + typedef Eigen::aligned_allocator AlignedPointT; + + + + typedef std::map > CloudActorMap; + + public: + +// typedef std::map > CloudDataCache; +// typedef std::map >::iterator CloudDataCacheIterator; + + + static boost::shared_ptr pcd_reader_thread; + //static MonitorQueue pcd_queue; + + struct PcdQueueItem + { + PcdQueueItem (std::string pcd_file, float coverage) + { + this->pcd_file = pcd_file; + this->coverage = coverage; + } + + bool operator< (const PcdQueueItem& rhs) const + { + if (coverage < rhs.coverage) + { + return true; + } + return false; + } + + std::string pcd_file; + float coverage; + }; + + typedef std::priority_queue PcdQueue; + static PcdQueue pcd_queue; + static boost::mutex pcd_queue_mutex; + static boost::condition pcd_queue_ready; + + class CloudDataCacheItem : public LRUCacheItem< vtkSmartPointer > + { + public: + + CloudDataCacheItem (std::string pcd_file, float coverage, vtkSmartPointer cloud_data, size_t timestamp) + { + this->pcd_file = pcd_file; + this->coverage = coverage; + this->item = cloud_data; + this->timestamp = timestamp; + } + + virtual size_t + sizeOf() const + { + return item->GetActualMemorySize(); + } + + std::string pcd_file; + float coverage; + }; + + +// static CloudDataCache cloud_data_map; +// static boost::mutex cloud_data_map_mutex; + typedef LRUCache CloudDataCache; + static CloudDataCache cloud_data_cache; + static boost::mutex cloud_data_cache_mutex; + + static void pcdReaderThread(); + + // Operators + // ----------------------------------------------------------------------------- + OutofcoreCloud (std::string name, boost::filesystem::path& tree_root); + + // Methods + // ----------------------------------------------------------------------------- + void + updateVoxelData (); + + // Accessors + // ----------------------------------------------------------------------------- + OctreeDiskPtr + getOctree () + { + return octree_; + } + + inline vtkSmartPointer + getVoxelActor () const + { + return voxel_actor_; + } + + inline vtkSmartPointer + getCloudActors () const + { + return cloud_actors_; + } + + void + setDisplayDepth (int displayDepth) + { + if (displayDepth < 0) + { + displayDepth = 0; + } + else if (static_cast (displayDepth) > octree_->getDepth ()) + { + displayDepth = octree_->getDepth (); + } + + if (display_depth_ != static_cast (displayDepth)) + { + display_depth_ = displayDepth; + updateVoxelData (); + //updateCloudData(); + } + } + + int + getDisplayDepth () + { + return display_depth_; + } + + uint64_t + getPointsLoaded () + { + return points_loaded_; + } + + uint64_t + getDataLoaded () + { + return data_loaded_; + } + + Eigen::Vector3d + getBoundingBoxMin () + { + return bbox_min_; + } + + Eigen::Vector3d + getBoundingBoxMax () + { + return bbox_max_; + } + + void + setDisplayVoxels (bool display_voxels) + { + voxel_actor_->SetVisibility (display_voxels); + } + + bool + getDisplayVoxels() + { + return voxel_actor_->GetVisibility (); + } + + void + setRenderCamera(Camera *render_camera) + { + render_camera_ = render_camera; + } + + int + getLodPixelThreshold () + { + return lod_pixel_threshold_; + } + + void + setLodPixelThreshold (int lod_pixel_threshold) + { + if (lod_pixel_threshold <= 1000) + lod_pixel_threshold = 1000; + + lod_pixel_threshold_ = lod_pixel_threshold; + } + + void + increaseLodPixelThreshold () + { + int value = 1000; + + if (lod_pixel_threshold_ >= 50000) + value = 10000; + if (lod_pixel_threshold_ >= 10000) + value = 5000; + else if (lod_pixel_threshold_ >= 1000) + value = 100; + + lod_pixel_threshold_ += value; + std::cout << "Increasing lod pixel threshold: " << lod_pixel_threshold_ << endl; + } + + void + decreaseLodPixelThreshold () + { + int value = 1000; + if (lod_pixel_threshold_ > 50000) + value = 10000; + else if (lod_pixel_threshold_ > 10000) + value = 5000; + else if (lod_pixel_threshold_ > 1000) + value = 100; + + lod_pixel_threshold_ -= value; + + if (lod_pixel_threshold_ < 100) + lod_pixel_threshold_ = 100; + std::cout << "Decreasing lod pixel threshold: " << lod_pixel_threshold_ << endl; + } + + virtual void + render (vtkRenderer* renderer); + + private: + + // Members + // ----------------------------------------------------------------------------- + OctreeDiskPtr octree_; + + uint64_t display_depth_; + uint64_t points_loaded_; + uint64_t data_loaded_; + + Eigen::Vector3d bbox_min_, bbox_max_; + + Camera *render_camera_; + + int lod_pixel_threshold_; + + vtkSmartPointer voxel_actor_; + + std::map > cloud_actors_map_; + vtkSmartPointer cloud_actors_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +#endif diff --git a/pcl-1.7/pcl/outofcore/visualization/scene.h b/pcl-1.7/pcl/outofcore/visualization/scene.h new file mode 100644 index 0000000..438a3ce --- /dev/null +++ b/pcl-1.7/pcl/outofcore/visualization/scene.h @@ -0,0 +1,90 @@ +#ifndef PCL_OUTOFCORE_SCENE_H_ +#define PCL_OUTOFCORE_SCENE_H_ + +// PCL +#include "camera.h" +#include "object.h" +#include "outofcore_cloud.h" +#include "viewport.h" + +class Object; + +class Scene +{ +private: + + static Scene *instance_; + + Scene (); + Scene (const Scene& op); + Scene& + operator= (const Scene& op); + +public: + + // Singleton + static Scene* + instance () + { + if (!Scene::instance_) + Scene::instance_ = new Scene (); + + return Scene::instance_; + } + + // Accessors - Cameras + // ----------------------------------------------------------------------------- + void + addCamera (Camera *camera); + + std::vector + getCameras (); + + Camera* + getCamera (vtkCamera *camera); + + Camera* + getCamera (std::string name); + + // Accessors - Objects + // ----------------------------------------------------------------------------- + void + addObject (Object *object); + + Object* + getObjectByName (std::string name); + + std::vector + getObjects (); + + // Accessors - Viewports + // ----------------------------------------------------------------------------- + + void + addViewport (Viewport *viewport); + + std::vector + getViewports (); + + void + lock () + { + render_mutex_.lock (); + } + + void + unlock () + { + render_mutex_.unlock (); + } + +private: + std::vector cameras_; + std::vector viewports_; + std::vector objects_; + + boost::mutex render_mutex_; + +}; + +#endif diff --git a/pcl-1.7/pcl/outofcore/visualization/viewport.h b/pcl-1.7/pcl/outofcore/visualization/viewport.h new file mode 100644 index 0000000..2072567 --- /dev/null +++ b/pcl-1.7/pcl/outofcore/visualization/viewport.h @@ -0,0 +1,82 @@ +#ifndef PCL_OUTOFCORE_VIEWPORT_H_ +#define PCL_OUTOFCORE_VIEWPORT_H_ + +// C++ +#include +#include + +// PCL +#include "camera.h" + +// VTK +#include +#include +#include +#include +#include +#include +#include + +class Viewport +{ +public: + + // Operators + // ----------------------------------------------------------------------------- + Viewport (vtkSmartPointer window, double xmin = 0.0, double ymin = 0.0, double xmax = 1.0, + double ymax = 1.0); + + // Accessors + // ----------------------------------------------------------------------------- + inline vtkSmartPointer + getRenderer () const + { + return renderer_; + } + + void + setCamera (Camera* camera) + { + renderer_->SetActiveCamera (vtkCamera::SafeDownCast (camera->getCamera ())); + camera_hud_actor_->SetInput (camera->getName ().c_str ()); + renderer_->ResetCamera (); + } + +private: + + // Callbacks + // ----------------------------------------------------------------------------- + static void + viewportModifiedCallback (vtkObject* caller, unsigned long int vtkNotUsed(eventId), void* vtkNotUsed(clientData), + void* vtkNotUsed(callData)); + + void + viewportModified (); + + static void + viewportActorUpdateCallback (vtkObject* caller, unsigned long int vtkNotUsed(eventId), void* vtkNotUsed(clientData), + void* vtkNotUsed(callData)); + + void + viewportActorUpdate (); + + static void + viewportHudUpdateCallback (vtkObject* caller, unsigned long int vtkNotUsed(eventId), void* vtkNotUsed(clientData), + void* vtkNotUsed(callData)); + + void + viewportHudUpdate (); + + // Members + // ----------------------------------------------------------------------------- + vtkSmartPointer renderer_; + vtkSmartPointer viewport_modified_callback_; + vtkSmartPointer viewport_actor_update_callback_; + vtkSmartPointer viewport_hud_callback_; + + vtkSmartPointer camera_hud_actor_; + vtkSmartPointer fps_hud_actor_; + vtkSmartPointer points_hud_actor_; +}; + +#endif diff --git a/pcl-1.7/pcl/pcl_base.h b/pcl-1.7/pcl/pcl_base.h new file mode 100644 index 0000000..f678d99 --- /dev/null +++ b/pcl-1.7/pcl/pcl_base.h @@ -0,0 +1,263 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_PCL_BASE_H_ +#define PCL_PCL_BASE_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +// Include PCL macros such as PCL_ERROR, etc +#include + +#include +#include +#include + +// Point Cloud message includes. Needed everywhere. +#include +#include +#include + +namespace pcl +{ + // definitions used everywhere + typedef boost::shared_ptr > IndicesPtr; + typedef boost::shared_ptr > IndicesConstPtr; + + ///////////////////////////////////////////////////////////////////////////////////////// + /** \brief PCL base class. Implements methods that are used by most PCL algorithms. + * \ingroup common + */ + template + class PCLBase + { + public: + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr PointIndicesPtr; + typedef boost::shared_ptr PointIndicesConstPtr; + + /** \brief Empty constructor. */ + PCLBase (); + + /** \brief Copy constructor. */ + PCLBase (const PCLBase& base); + + /** \brief Destructor. */ + virtual ~PCLBase () + { + input_.reset (); + indices_.reset (); + } + + /** \brief Provide a pointer to the input dataset + * \param[in] cloud the const boost shared pointer to a PointCloud message + */ + virtual void + setInputCloud (const PointCloudConstPtr &cloud); + + /** \brief Get a pointer to the input point cloud dataset. */ + inline PointCloudConstPtr const + getInputCloud () const { return (input_); } + + /** \brief Provide a pointer to the vector of indices that represents the input data. + * \param[in] indices a pointer to the indices that represent the input data. + */ + virtual void + setIndices (const IndicesPtr &indices); + + /** \brief Provide a pointer to the vector of indices that represents the input data. + * \param[in] indices a pointer to the indices that represent the input data. + */ + virtual void + setIndices (const IndicesConstPtr &indices); + + /** \brief Provide a pointer to the vector of indices that represents the input data. + * \param[in] indices a pointer to the indices that represent the input data. + */ + virtual void + setIndices (const PointIndicesConstPtr &indices); + + /** \brief Set the indices for the points laying within an interest region of + * the point cloud. + * \note you shouldn't call this method on unorganized point clouds! + * \param[in] row_start the offset on rows + * \param[in] col_start the offset on columns + * \param[in] nb_rows the number of rows to be considered row_start included + * \param[in] nb_cols the number of columns to be considered col_start included + */ + virtual void + setIndices (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols); + + /** \brief Get a pointer to the vector of indices used. */ + inline IndicesPtr const + getIndices () { return (indices_); } + + /** \brief Get a pointer to the vector of indices used. */ + inline IndicesConstPtr const + getIndices () const { return (indices_); } + + /** \brief Override PointCloud operator[] to shorten code + * \note this method can be called instead of (*input_)[(*indices_)[pos]] + * or input_->points[(*indices_)[pos]] + * \param[in] pos position in indices_ vector + */ + inline const PointT& operator[] (size_t pos) const + { + return ((*input_)[(*indices_)[pos]]); + } + + protected: + /** \brief The input point cloud dataset. */ + PointCloudConstPtr input_; + + /** \brief A pointer to the vector of point indices to use. */ + IndicesPtr indices_; + + /** \brief Set to true if point indices are used. */ + bool use_indices_; + + /** \brief If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. */ + bool fake_indices_; + + /** \brief This method should get called before starting the actual computation. + * + * Internally, initCompute() does the following: + * - checks if an input dataset is given, and returns false otherwise + * - checks whether a set of input indices has been given. Returns true if yes. + * - if no input indices have been given, a fake set is created, which will be used until: + * - either a new set is given via setIndices(), or + * - a new cloud is given that has a different set of points. This will trigger an update on the set of fake indices + */ + bool + initCompute (); + + /** \brief This method should get called after finishing the actual computation. + */ + bool + deinitCompute (); + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + ///////////////////////////////////////////////////////////////////////////////////////// + template <> + class PCL_EXPORTS PCLBase + { + public: + typedef pcl::PCLPointCloud2 PCLPointCloud2; + typedef boost::shared_ptr PCLPointCloud2Ptr; + typedef boost::shared_ptr PCLPointCloud2ConstPtr; + + typedef boost::shared_ptr PointIndicesPtr; + typedef boost::shared_ptr PointIndicesConstPtr; + + /** \brief Empty constructor. */ + PCLBase (); + + /** \brief destructor. */ + virtual ~PCLBase() + { + input_.reset (); + indices_.reset (); + } + + /** \brief Provide a pointer to the input dataset + * \param cloud the const boost shared pointer to a PointCloud message + */ + void + setInputCloud (const PCLPointCloud2ConstPtr &cloud); + + /** \brief Get a pointer to the input point cloud dataset. */ + inline PCLPointCloud2ConstPtr const + getInputCloud () { return (input_); } + + /** \brief Provide a pointer to the vector of indices that represents the input data. + * \param[in] indices a pointer to the indices that represent the input data. + */ + void + setIndices (const IndicesPtr &indices); + + /** \brief Provide a pointer to the vector of indices that represents the input data. + * \param[in] indices a pointer to the indices that represent the input data. + */ + void + setIndices (const PointIndicesConstPtr &indices); + + /** \brief Get a pointer to the vector of indices used. */ + inline IndicesPtr const + getIndices () { return (indices_); } + + protected: + /** \brief The input point cloud dataset. */ + PCLPointCloud2ConstPtr input_; + + /** \brief A pointer to the vector of point indices to use. */ + IndicesPtr indices_; + + /** \brief Set to true if point indices are used. */ + bool use_indices_; + + /** \brief If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. */ + bool fake_indices_; + + /** \brief The size of each individual field. */ + std::vector field_sizes_; + + /** \brief The x-y-z fields indices. */ + int x_idx_, y_idx_, z_idx_; + + /** \brief The desired x-y-z field names. */ + std::string x_field_name_, y_field_name_, z_field_name_; + + bool initCompute (); + bool deinitCompute (); + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_PCL_BASE_H_ diff --git a/pcl-1.7/pcl/pcl_config.h b/pcl-1.7/pcl/pcl_config.h new file mode 100644 index 0000000..9a8a189 --- /dev/null +++ b/pcl-1.7/pcl/pcl_config.h @@ -0,0 +1,67 @@ +/* pcl_config.h. Generated by CMake for PCL. */ + +#define BUILD_None +/* PCL version information */ +#define PCL_MAJOR_VERSION 1 +#define PCL_MINOR_VERSION 7 +#define PCL_REVISION_VERSION 2 +#define PCL_VERSION_PRETTY "1.7.2" +#define PCL_VERSION_CALC(MAJ, MIN, PATCH) (MAJ*100000+MIN*100+PATCH) +#define PCL_VERSION \ + PCL_VERSION_CALC(PCL_MAJOR_VERSION,PCL_MINOR_VERSION,PCL_REVISION_VERSION) +#define PCL_VERSION_COMPARE(OP,MAJ,MIN,PATCH) \ + (PCL_VERSION OP PCL_VERSION_CALC(MAJ,MIN,PATCH)) + +/* #undef HAVE_TBB */ + +#define HAVE_OPENNI 1 + +/* #undef HAVE_OPENNI2 */ + +#define HAVE_QHULL 1 + +#define HAVE_QHULL_2011 1 + +/* #undef HAVE_CUDA */ + +/* #undef HAVE_FZAPI */ + +// SSE macros +#define HAVE_POSIX_MEMALIGN +#define HAVE_MM_MALLOC +#define HAVE_SSE4_1_EXTENSIONS +#define HAVE_SSE3_EXTENSIONS +#define HAVE_SSE2_EXTENSIONS +#define HAVE_SSE_EXTENSIONS + +#define HAVE_PNG + +/* Precompile for a minimal set of point types instead of all. */ +/* #undef PCL_ONLY_CORE_POINT_TYPES */ + +/* Do not precompile for any point types at all. */ +/* #undef PCL_NO_PRECOMPILE */ + +#ifdef DISABLE_OPENNI +#undef HAVE_OPENNI +#endif + +#ifdef DISABLE_OPENNI2 +#undef HAVE_OPENNI2 +#endif + +#ifdef DISABLE_QHULL +#undef HAVE_QHULL +#endif + +/* Verbosity level defined by user through ccmake. */ +/* #undef VERBOSITY_LEVEL_ALWAYS */ +/* #undef VERBOSITY_LEVEL_ERROR */ +/* #undef VERBOSITY_LEVEL_WARN */ +#define VERBOSITY_LEVEL_INFO +/* #undef VERBOSITY_LEVEL_DEBUG */ +/* #undef VERBOSITY_LEVEL_VERBOSE */ + +/* Address the cases where on MacOS and OpenGL and GLUT are not frameworks */ +/* #undef OPENGL_IS_A_FRAMEWORK */ +/* #undef GLUT_IS_A_FRAMEWORK */ diff --git a/pcl-1.7/pcl/pcl_exports.h b/pcl-1.7/pcl/pcl_exports.h new file mode 100644 index 0000000..f231c7a --- /dev/null +++ b/pcl-1.7/pcl/pcl_exports.h @@ -0,0 +1,52 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_EXPORTS_H_ +#define PCL_EXPORTS_H_ + +// This header is created to include to NVCC compiled sources. +// Header 'pcl_macros' is not suitable since it inludes , +// which can't be eaten by nvcc (it's too weak) + +#if defined WIN32 || defined _WIN32 || defined WINCE || defined __MINGW32__ + #ifdef PCLAPI_EXPORTS + #define PCL_EXPORTS __declspec(dllexport) + #else + #define PCL_EXPORTS + #endif +#else + #define PCL_EXPORTS +#endif + +#endif //#ifndef PCL_EXPORTS_H_ diff --git a/pcl-1.7/pcl/pcl_macros.h b/pcl-1.7/pcl/pcl_macros.h new file mode 100644 index 0000000..10969f9 --- /dev/null +++ b/pcl-1.7/pcl/pcl_macros.h @@ -0,0 +1,416 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_MACROS_H_ +#define PCL_MACROS_H_ + +#include +#include +#include + +namespace pcl +{ + using boost::uint8_t; + using boost::int8_t; + using boost::int16_t; + using boost::uint16_t; + using boost::int32_t; + using boost::uint32_t; + using boost::int64_t; + using boost::uint64_t; + using boost::int_fast16_t; +} + +#if defined __INTEL_COMPILER + #pragma warning disable 2196 2536 279 +#endif + +#if defined _MSC_VER + // 4244 : conversion from 'type1' to 'type2', possible loss of data + // 4661 : no suitable definition provided for explicit template instantiation reques + // 4503 : decorated name length exceeded, name was truncated + // 4146 : unary minus operator applied to unsigned type, result still unsigned + #pragma warning (disable: 4018 4244 4267 4521 4251 4661 4305 4503 4146) +#endif + +#include +#include +#include +#define _USE_MATH_DEFINES +#include + +// MSCV doesn't have std::{isnan,isfinite} +#if defined _WIN32 && defined _MSC_VER + +// If M_PI is not defined, then probably all of them are undefined +#ifndef M_PI +// Copied from math.h +# define M_PI 3.14159265358979323846 // pi +# define M_PI_2 1.57079632679489661923 // pi/2 +# define M_PI_4 0.78539816339744830962 // pi/4 +# define M_PIl 3.1415926535897932384626433832795029L // pi +# define M_PI_2l 1.5707963267948966192313216916397514L // pi/2 +# define M_PI_4l 0.7853981633974483096156608458198757L // pi/4 +#endif + +// Stupid. This should be removed when all the PCL dependencies have min/max fixed. +#ifndef NOMINMAX +# define NOMINMAX +#endif + +# define pcl_isnan(x) _isnan(x) +# define pcl_isfinite(x) (_finite(x) != 0) +# define pcl_isinf(x) (_finite(x) == 0) + +# define __PRETTY_FUNCTION__ __FUNCTION__ +# define __func__ __FUNCTION__ + +#elif ANDROID +// Use the math.h macros +# include +# define pcl_isnan(x) std::isnan(x) +# define pcl_isfinite(x) std::isfinite(x) +# define pcl_isinf(x) std::isinf(x) + +#elif _GLIBCXX_USE_C99_MATH +// Are the C++ cmath functions enabled? +# include +# define pcl_isnan(x) std::isnan(x) +# define pcl_isfinite(x) std::isfinite(x) +# define pcl_isinf(x) std::isinf(x) + +#elif __PATHCC__ +# include +# include +template int +pcl_isnan (T &val) +{ + return (val != val); +} +//# define pcl_isnan(x) std::isnan(x) +# define pcl_isfinite(x) std::isfinite(x) +# define pcl_isinf(x) std::isinf(x) + +#else +// Use the math.h macros +# include +# define pcl_isnan(x) isnan(x) +# define pcl_isfinite(x) isfinite(x) +# define pcl_isinf(x) isinf(x) + +#endif + +#ifndef DEG2RAD +#define DEG2RAD(x) ((x)*0.017453293) +#endif + +#ifndef RAD2DEG +#define RAD2DEG(x) ((x)*57.29578) +#endif + +/** \brief Macro that maps version information given by major.minor.patch to a linear integer value to enable easy comparison + */ +#define PCL_LINEAR_VERSION(major,minor,patch) ((major)<<16|(minor)<<8|(patch)) + +/** Win32 doesn't seem to have rounding functions. + * Therefore implement our own versions of these functions here. + */ + +__inline double +pcl_round (double number) +{ + return (number < 0.0 ? ceil (number - 0.5) : floor (number + 0.5)); +} +__inline float +pcl_round (float number) +{ + return (number < 0.0f ? ceilf (number - 0.5f) : floorf (number + 0.5f)); +} + +#ifdef __GNUC__ +#define pcl_lrint(x) (lrint(static_cast (x))) +#define pcl_lrintf(x) (lrintf(static_cast (x))) +#else +#define pcl_lrint(x) (static_cast(pcl_round(x))) +#define pcl_lrintf(x) (static_cast(pcl_round(x))) +#endif + + +#ifdef _WIN32 +__inline float +log2f (float x) +{ + return (static_cast (logf (x) * M_LOG2E)); +} +#endif + +#ifdef WIN32 +#define pcl_sleep(x) Sleep(1000*(x)) +#else +#define pcl_sleep(x) sleep(x) +#endif + +#ifndef PVAR + #define PVAR(s) \ + #s << " = " << (s) << std::flush +#endif +#ifndef PVARN +#define PVARN(s) \ + #s << " = " << (s) << "\n" +#endif +#ifndef PVARC +#define PVARC(s) \ + #s << " = " << (s) << ", " << std::flush +#endif +#ifndef PVARS +#define PVARS(s) \ + #s << " = " << (s) << " " << std::flush +#endif +#ifndef PVARA +#define PVARA(s) \ + #s << " = " << RAD2DEG(s) << "deg" << std::flush +#endif +#ifndef PVARAN +#define PVARAN(s) \ + #s << " = " << RAD2DEG(s) << "deg\n" +#endif +#ifndef PVARAC +#define PVARAC(s) \ + #s << " = " << RAD2DEG(s) << "deg, " << std::flush +#endif +#ifndef PVARAS +#define PVARAS(s) \ + #s << " = " << RAD2DEG(s) << "deg " << std::flush +#endif + +#define FIXED(s) \ + std::fixed << s << std::resetiosflags(std::ios_base::fixed) + +#ifndef ERASE_STRUCT +#define ERASE_STRUCT(var) memset(&var, 0, sizeof(var)) +#endif + +#ifndef ERASE_ARRAY +#define ERASE_ARRAY(var, size) memset(var, 0, size*sizeof(*var)) +#endif + +#ifndef SET_ARRAY +#define SET_ARRAY(var, value, size) { for (int i = 0; i < static_cast (size); ++i) var[i]=value; } +#endif + +/* //This is copy/paste from http://gcc.gnu.org/wiki/Visibility */ +/* #if defined _WIN32 || defined __CYGWIN__ */ +/* #ifdef BUILDING_DLL */ +/* #ifdef __GNUC__ */ +/* #define DLL_PUBLIC __attribute__((dllexport)) */ +/* #else */ +/* #define DLL_PUBLIC __declspec(dllexport) // Note: actually gcc seems to also supports this syntax. */ +/* #endif */ +/* #else */ +/* #ifdef __GNUC__ */ +/* #define DLL_PUBLIC __attribute__((dllimport)) */ +/* #else */ +/* #define DLL_PUBLIC __declspec(dllimport) // Note: actually gcc seems to also supports this syntax. */ +/* #endif */ +/* #endif */ +/* #define DLL_LOCAL */ +/* #else */ +/* #if __GNUC__ >= 4 */ +/* #define DLL_PUBLIC __attribute__ ((visibility("default"))) */ +/* #define DLL_LOCAL __attribute__ ((visibility("hidden"))) */ +/* #else */ +/* #define DLL_PUBLIC */ +/* #define DLL_LOCAL */ +/* #endif */ +/* #endif */ + +#ifndef PCL_EXTERN_C + #ifdef __cplusplus + #define PCL_EXTERN_C extern "C" + #else + #define PCL_EXTERN_C + #endif +#endif + +#if defined WIN32 || defined _WIN32 || defined WINCE || defined __MINGW32__ + #ifdef PCLAPI_EXPORTS + #define PCL_EXPORTS __declspec(dllexport) + #else + #define PCL_EXPORTS + #endif +#else + #define PCL_EXPORTS +#endif + +#if defined WIN32 || defined _WIN32 + #define PCL_CDECL __cdecl + #define PCL_STDCALL __stdcall +#else + #define PCL_CDECL + #define PCL_STDCALL +#endif + +#ifndef PCLAPI + #define PCLAPI(rettype) PCL_EXTERN_C PCL_EXPORTS rettype PCL_CDECL +#endif + +// Macro to deprecate old functions +// +// Usage: +// don't use me any more +// PCL_DEPRECATED(void OldFunc(int a, float b), "Use newFunc instead, this functions will be gone in the next major release"); +// use me instead +// void NewFunc(int a, double b); + +//for clang cf. http://clang.llvm.org/docs/LanguageExtensions.html +#ifndef __has_extension + #define __has_extension(x) 0 // Compatibility with pre-3.0 compilers. +#endif + +#if (defined(__GNUC__) && PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) < PCL_LINEAR_VERSION(4,5,0) && ! defined(__clang__)) || defined(__INTEL_COMPILER) +#define PCL_DEPRECATED(message) __attribute__ ((deprecated)) +#endif + +// gcc supports this starting from 4.5 : http://gcc.gnu.org/bugzilla/show_bug.cgi?id=43666 +#if (defined(__GNUC__) && PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) >= PCL_LINEAR_VERSION(4,5,0)) || (defined(__clang__) && __has_extension(attribute_deprecated_with_message)) +#define PCL_DEPRECATED(message) __attribute__ ((deprecated(message))) +#endif + +#ifdef _MSC_VER +#define PCL_DEPRECATED(message) __declspec(deprecated(message)) +#endif + +#ifndef PCL_DEPRECATED +#pragma message("WARNING: You need to implement PCL_DEPRECATED for this compiler") +#define PCL_DEPRECATED(message) +#endif + + +// Macro to deprecate old classes/structs +// +// Usage: +// don't use me any more +// class PCL_DEPRECATED_CLASS(OldClass, "Use newClass instead, this class will be gone in the next major release") +// { +// public: +// OldClass() {} +// }; +// use me instead +// class NewFunc +// { +// public: +// NewClass() {} +// }; + +#if (defined(__GNUC__) && PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) < PCL_LINEAR_VERSION(4,5,0) && ! defined(__clang__)) || defined(__INTEL_COMPILER) +#define PCL_DEPRECATED_CLASS(func, message) __attribute__ ((deprecated)) func +#endif + +// gcc supports this starting from 4.5 : http://gcc.gnu.org/bugzilla/show_bug.cgi?id=43666 +#if (defined(__GNUC__) && PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) >= PCL_LINEAR_VERSION(4,5,0)) || (defined(__clang__) && __has_extension(attribute_deprecated_with_message)) +#define PCL_DEPRECATED_CLASS(func, message) __attribute__ ((deprecated(message))) func +#endif + +#ifdef _MSC_VER +#define PCL_DEPRECATED_CLASS(func, message) __declspec(deprecated(message)) func +#endif + +#ifndef PCL_DEPRECATED_CLASS +#pragma message("WARNING: You need to implement PCL_DEPRECATED_CLASS for this compiler") +#define PCL_DEPRECATED_CLASS(func) func +#endif + +#if defined (__GNUC__) || defined (__PGI) || defined (__IBMCPP__) || defined (__SUNPRO_CC) + #define PCL_ALIGN(alignment) __attribute__((aligned(alignment))) +#elif defined (_MSC_VER) + #define PCL_ALIGN(alignment) __declspec(align(alignment)) +#else + #error Alignment not supported on your platform +#endif + +#if defined(__GLIBC__) && PCL_LINEAR_VERSION(__GLIBC__,__GLIBC_MINOR__,0)>PCL_LINEAR_VERSION(2,8,0) + #define GLIBC_MALLOC_ALIGNED 1 +#else + #define GLIBC_MALLOC_ALIGNED 0 +#endif + +#if defined(__FreeBSD__) && !defined(__arm__) && !defined(__mips__) + #define FREEBSD_MALLOC_ALIGNED 1 +#else + #define FREEBSD_MALLOC_ALIGNED 0 +#endif + +#if defined(__APPLE__) || defined(_WIN64) || GLIBC_MALLOC_ALIGNED || FREEBSD_MALLOC_ALIGNED + #define MALLOC_ALIGNED 1 +#else + #define MALLOC_ALIGNED 0 +#endif + +inline void* +aligned_malloc (size_t size) +{ + void *ptr; +#if defined (MALLOC_ALIGNED) + ptr = std::malloc (size); +#elif defined (HAVE_POSIX_MEMALIGN) + if (posix_memalign (&ptr, 16, size)) + ptr = 0; +#elif defined (HAVE_MM_MALLOC) + ptr = _mm_malloc (size, 16); +#elif defined (_MSC_VER) + ptr = _aligned_malloc (size, 16); +#else + #error aligned_malloc not supported on your platform + ptr = 0; +#endif + return (ptr); +} + +inline void +aligned_free (void* ptr) +{ +#if defined (MALLOC_ALIGNED) || defined (HAVE_POSIX_MEMALIGN) + std::free (ptr); +#elif defined (HAVE_MM_MALLOC) + ptr = _mm_free (ptr); +#elif defined (_MSC_VER) + _aligned_free (ptr); +#else + #error aligned_free not supported on your platform +#endif +} + +#endif //#ifndef PCL_MACROS_H_ diff --git a/pcl-1.7/pcl/pcl_tests.h b/pcl-1.7/pcl/pcl_tests.h new file mode 100644 index 0000000..f9b8f13 --- /dev/null +++ b/pcl-1.7/pcl/pcl_tests.h @@ -0,0 +1,271 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + + +#ifndef PCL_TEST_MACROS +#define PCL_TEST_MACROS + +#include + +/** \file pcl_tests.h + * Helper macros for testing equality of various data fields in PCL points */ + +namespace pcl +{ + + /** test_macros.h provide helper macros for testing vectors, matrices etc. + * We took some liberty with upcasing names to make them look like googletest + * macros names so that reader is not confused. + * + * This file also provides a family of googletest-style macros for asserting + * equality or nearness of xyz, normal, and rgba fields. + * + * \author Nizar Sallem, Sergey Alexandrov + */ + + namespace test + { + + template + void EXPECT_EQ_VECTORS (const V1& v1, const V2& v2) + { + SCOPED_TRACE("EXPECT_EQ_VECTORS failed"); + EXPECT_EQ (v1.size (), v2.size ()); + size_t length = v1.size (); + for (size_t i = 0; i < length; ++i) + EXPECT_EQ (v1[i], v2[i]); + } + + template + void EXPECT_NEAR_VECTORS (const V1& v1, const V2& v2, const Scalar& epsilon) + { + SCOPED_TRACE("EXPECT_NEAR_VECTORS failed"); + EXPECT_EQ (v1.size (), v2.size ()); + size_t length = v1.size (); + for (size_t i = 0; i < length; ++i) + EXPECT_NEAR (v1[i], v2[i], epsilon); + } + + namespace internal + { + + template + ::testing::AssertionResult XYZEQ (const char* expr1, + const char* expr2, + const Point1T& p1, + const Point2T& p2) + { + if ((p1).getVector3fMap ().cwiseEqual ((p2).getVector3fMap ()).all ()) + return ::testing::AssertionSuccess (); + return ::testing::AssertionFailure () + << "Value of: " << expr2 << ".getVector3fMap ()" << std::endl + << " Actual: " << p2.getVector3fMap ().transpose () << std::endl + << "Expected: " << expr1 << ".getVector3fMap ()" << std::endl + << "Which is: " << p1.getVector3fMap ().transpose (); + } + + template + ::testing::AssertionResult XYZNear (const char* expr1, + const char* expr2, + const char* abs_error_expr, + const Point1T& p1, + const Point2T& p2, + double abs_error) + { + const Eigen::Vector3f diff = ((p1).getVector3fMap () - + (p2).getVector3fMap ()).cwiseAbs (); + if ((diff.array () < abs_error).all ()) + return ::testing::AssertionSuccess (); + return ::testing::AssertionFailure () + << "Some of the element-wise differences exceed " << abs_error_expr + << " (which evaluates to " << abs_error << ")" << std::endl + << "Difference: " << diff.transpose () << std::endl + << " Value of: " << expr2 << ".getVector3fMap ()" << std::endl + << " Actual: " << p2.getVector3fMap ().transpose () << std::endl + << " Expected: " << expr1 << ".getVector3fMap ()" << std::endl + << " Which is: " << p1.getVector3fMap ().transpose (); + } + + template + ::testing::AssertionResult NormalEQ (const char* expr1, + const char* expr2, + const Point1T& p1, + const Point2T& p2) + { + if ((p1).getNormalVector3fMap ().cwiseEqual ((p2).getNormalVector3fMap ()).all ()) + return ::testing::AssertionSuccess (); + return ::testing::AssertionFailure () + << "Value of: " << expr2 << ".getNormalVector3fMap ()" << std::endl + << " Actual: " << p2.getNormalVector3fMap ().transpose () << std::endl + << "Expected: " << expr1 << ".getNormalVector3fMap ()" << std::endl + << "Which is: " << p1.getNormalVector3fMap ().transpose (); + } + + template + ::testing::AssertionResult NormalNear (const char* expr1, + const char* expr2, + const char* abs_error_expr, + const Point1T& p1, + const Point2T& p2, + double abs_error) + { + const Eigen::Vector3f diff = ((p1).getNormalVector3fMap () - + (p2).getNormalVector3fMap ()).cwiseAbs (); + if ((diff.array () < abs_error).all ()) + return ::testing::AssertionSuccess (); + return ::testing::AssertionFailure () + << "Some of the element-wise differences exceed " << abs_error_expr + << " (which evaluates to " << abs_error << ")" << std::endl + << "Difference: " << diff.transpose () << std::endl + << " Value of: " << expr2 << ".getNormalVector3fMap ()" << std::endl + << " Actual: " << p2.getNormalVector3fMap ().transpose () << std::endl + << " Expected: " << expr1 << ".getNormalVector3fMap ()" << std::endl + << " Which is: " << p1.getNormalVector3fMap ().transpose (); + } + + template + ::testing::AssertionResult RGBEQ (const char* expr1, + const char* expr2, + const Point1T& p1, + const Point2T& p2) + { + if ((p1).getRGBVector3i ().cwiseEqual ((p2).getRGBVector3i ()).all ()) + return ::testing::AssertionSuccess (); + return ::testing::AssertionFailure () + << "Value of: " << expr2 << ".getRGBVector3i ()" << std::endl + << " Actual: " << p2.getRGBVector3i ().transpose () << std::endl + << "Expected: " << expr1 << ".getRGBVector3i ()" << std::endl + << "Which is: " << p1.getRGBVector3i ().transpose (); + } + + template + ::testing::AssertionResult RGBAEQ (const char* expr1, + const char* expr2, + const Point1T& p1, + const Point2T& p2) + { + if ((p1).getRGBAVector4i ().cwiseEqual ((p2).getRGBAVector4i ()).all ()) + return ::testing::AssertionSuccess (); + return ::testing::AssertionFailure () + << "Value of: " << expr2 << ".getRGBAVector4i ()" << std::endl + << " Actual: " << p2.getRGBAVector4i ().transpose () << std::endl + << "Expected: " << expr1 << ".getRGBAVector4i ()" << std::endl + << "Which is: " << p1.getRGBAVector4i ().transpose (); + } + + } + + } + +} + +/// Expect that each of x, y, and z fields are equal in +/// two points. +#define EXPECT_XYZ_EQ(expected, actual) \ + EXPECT_PRED_FORMAT2(::pcl::test::internal::XYZEQ, \ + (expected), (actual)) + +/// Assert that each of x, y, and z fields are equal in +/// two points. +#define ASSERT_XYZ_EQ(expected, actual) \ + ASSERT_PRED_FORMAT2(::pcl::test::internal::XYZEQ, \ + (expected), (actual)) + +/// Expect that differences between x, y, and z fields in +/// two points are each within abs_error. +#define EXPECT_XYZ_NEAR(expected, actual, abs_error) \ + EXPECT_PRED_FORMAT3(::pcl::test::internal::XYZNear, \ + (expected), (actual), abs_error) + +/// Assert that differences between x, y, and z fields in +/// two points are each within abs_error. +#define ASSERT_XYZ_NEAR(expected, actual, abs_error) \ + EXPECT_PRED_FORMAT3(::pcl::test::internal::XYZNear, \ + (expected), (actual), abs_error) + +/// Expect that each of normal_x, normal_y, and normal_z +/// fields are equal in two points. +#define EXPECT_NORMAL_EQ(expected, actual) \ + EXPECT_PRED_FORMAT2(::pcl::test::internal::NormalEQ, \ + (expected), (actual)) + +/// Assert that each of normal_x, normal_y, and normal_z +/// fields are equal in two points. +#define ASSERT_NORMAL_EQ(expected, actual) \ + ASSERT_PRED_FORMAT2(::pcl::test::internal::NormalEQ, \ + (expected), (actual)) + +/// Expect that differences between normal_x, normal_y, +/// and normal_z fields in two points are each within +/// abs_error. +#define EXPECT_NORMAL_NEAR(expected, actual, abs_error) \ + EXPECT_PRED_FORMAT3(::pcl::test::internal::NormalNear, \ + (expected), (actual), abs_error) + +/// Assert that differences between normal_x, normal_y, +/// and normal_z fields in two points are each within +/// abs_error. +#define ASSERT_NORMAL_NEAR(expected, actual, abs_error) \ + EXPECT_PRED_FORMAT3(::pcl::test::internal::NormalNear, \ + (expected), (actual), abs_error) + +/// Expect that each of r, g, and b fields are equal in +/// two points. +#define EXPECT_RGB_EQ(expected, actual) \ + EXPECT_PRED_FORMAT2(::pcl::test::internal::RGBEQ, \ + (expected), (actual)) + +/// Assert that each of r, g, and b fields are equal in +/// two points. +#define ASSERT_RGB_EQ(expected, actual) \ + ASSERT_PRED_FORMAT2(::pcl::test::internal::RGBEQ, \ + (expected), (actual)) + +/// Expect that each of r, g, b, and a fields are equal +/// in two points. +#define EXPECT_RGBA_EQ(expected, actual) \ + EXPECT_PRED_FORMAT2(::pcl::test::internal::RGBAEQ, \ + (expected), (actual)) + +/// Assert that each of r, g, b, and a fields are equal +/// in two points. +#define ASSERT_RGBA_EQ(expected, actual) \ + ASSERT_PRED_FORMAT2(::pcl::test::internal::RGBAEQ, \ + (expected), (actual)) + +#endif diff --git a/pcl-1.7/pcl/people/ground_based_people_detection_app.h b/pcl-1.7/pcl/people/ground_based_people_detection_app.h new file mode 100644 index 0000000..a4672c4 --- /dev/null +++ b/pcl-1.7/pcl/people/ground_based_people_detection_app.h @@ -0,0 +1,376 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * ground_based_people_detection_app.h + * Created on: Nov 30, 2012 + * Author: Matteo Munaro + */ + +#ifndef PCL_PEOPLE_GROUND_BASED_PEOPLE_DETECTION_APP_H_ +#define PCL_PEOPLE_GROUND_BASED_PEOPLE_DETECTION_APP_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace people + { + /** \brief GroundBasedPeopleDetectionApp performs people detection on RGB-D data having as input the ground plane coefficients. + * It implements the people detection algorithm described here: + * M. Munaro, F. Basso and E. Menegatti, + * Tracking people within groups with RGB-D data, + * In Proceedings of the International Conference on Intelligent Robots and Systems (IROS) 2012, Vilamoura (Portugal), 2012. + * + * \author Matteo Munaro + * \ingroup people + */ + template class GroundBasedPeopleDetectionApp; + + template + class GroundBasedPeopleDetectionApp + { + public: + + typedef pcl::PointCloud PointCloud; + typedef boost::shared_ptr PointCloudPtr; + typedef boost::shared_ptr PointCloudConstPtr; + + /** \brief Constructor. */ + GroundBasedPeopleDetectionApp (); + + /** \brief Destructor. */ + virtual ~GroundBasedPeopleDetectionApp (); + + /** + * \brief Set the pointer to the input cloud. + * + * \param[in] cloud A pointer to the input cloud. + */ + void + setInputCloud (PointCloudPtr& cloud); + + /** + * \brief Set the ground coefficients. + * + * \param[in] ground_coeffs Vector containing the four plane coefficients. + */ + void + setGround (Eigen::VectorXf& ground_coeffs); + + /** + * \brief Set the transformation matrix, which is used in order to transform the given point cloud, the ground plane and the intrinsics matrix to the internal coordinate frame. + * + * \param[in] cloud A pointer to the input cloud. + */ + void + setTransformation (const Eigen::Matrix3f& transformation); + + /** + * \brief Set sampling factor. + * + * \param[in] sampling_factor Value of the downsampling factor (in each dimension) which is applied to the raw point cloud (default = 1.). + */ + void + setSamplingFactor (int sampling_factor); + + /** + * \brief Set voxel size. + * + * \param[in] voxel_size Value of the voxel dimension (default = 0.06m.). + */ + void + setVoxelSize (float voxel_size); + + /** + * \brief Set intrinsic parameters of the RGB camera. + * + * \param[in] intrinsics_matrix RGB camera intrinsic parameters matrix. + */ + void + setIntrinsics (Eigen::Matrix3f intrinsics_matrix); + + /** + * \brief Set SVM-based person classifier. + * + * \param[in] person_classifier Needed for people detection on RGB data. + */ + void + setClassifier (pcl::people::PersonClassifier person_classifier); + + /** + * \brief Set the field of view of the point cloud in z direction. + * + * \param[in] min The beginning of the field of view in z-direction, should be usually set to zero. + * \param[in] max The end of the field of view in z-direction. + */ + void + setFOV (float min, float max); + + /** + * \brief Set sensor orientation (vertical = true means portrait mode, vertical = false means landscape mode). + * + * \param[in] vertical Set landscape/portait camera orientation (default = false). + */ + void + setSensorPortraitOrientation (bool vertical); + + /** + * \brief Set head_centroid_ to true (person centroid is in the head) or false (person centroid is the whole body centroid). + * + * \param[in] head_centroid Set the location of the person centroid (head or body center) (default = true). + */ + void + setHeadCentroid (bool head_centroid); + + /** + * \brief Set minimum and maximum allowed height and width for a person cluster. + * + * \param[in] min_height Minimum allowed height for a person cluster (default = 1.3). + * \param[in] max_height Maximum allowed height for a person cluster (default = 2.3). + * \param[in] min_width Minimum width for a person cluster (default = 0.1). + * \param[in] max_width Maximum width for a person cluster (default = 8.0). + */ + void + setPersonClusterLimits (float min_height, float max_height, float min_width, float max_width); + + /** + * \brief Set minimum distance between persons' heads. + * + * \param[in] heads_minimum_distance Minimum allowed distance between persons' heads (default = 0.3). + */ + void + setMinimumDistanceBetweenHeads (float heads_minimum_distance); + + /** + * \brief Get the minimum and maximum allowed height and width for a person cluster. + * + * \param[out] min_height Minimum allowed height for a person cluster. + * \param[out] max_height Maximum allowed height for a person cluster. + * \param[out] min_width Minimum width for a person cluster. + * \param[out] max_width Maximum width for a person cluster. + */ + void + getPersonClusterLimits (float& min_height, float& max_height, float& min_width, float& max_width); + + /** + * \brief Get minimum and maximum allowed number of points for a person cluster. + * + * \param[out] min_points Minimum allowed number of points for a person cluster. + * \param[out] max_points Maximum allowed number of points for a person cluster. + */ + void + getDimensionLimits (int& min_points, int& max_points); + + /** + * \brief Get minimum distance between persons' heads. + */ + float + getMinimumDistanceBetweenHeads (); + + /** + * \brief Get floor coefficients. + */ + Eigen::VectorXf + getGround (); + + /** + * \brief Get the filtered point cloud. + */ + PointCloudPtr + getFilteredCloud (); + + /** + * \brief Get pointcloud after voxel grid filtering and ground removal. + */ + PointCloudPtr + getNoGroundCloud (); + + /** + * \brief Extract RGB information from a point cloud and output the corresponding RGB point cloud. + * + * \param[in] input_cloud A pointer to a point cloud containing also RGB information. + * \param[out] output_cloud A pointer to a RGB point cloud. + */ + void + extractRGBFromPointCloud (PointCloudPtr input_cloud, pcl::PointCloud::Ptr& output_cloud); + + /** + * \brief Swap rows/cols dimensions of a RGB point cloud (90 degrees counterclockwise rotation). + * + * \param[in,out] cloud A pointer to a RGB point cloud. + */ + void + swapDimensions (pcl::PointCloud::Ptr& cloud); + + /** + * \brief Estimates min_points_ and max_points_ based on the minimal and maximal cluster size and the voxel size. + */ + void + updateMinMaxPoints (); + + /** + * \brief Applies the transformation to the input point cloud. + */ + void + applyTransformationPointCloud (); + + /** + * \brief Applies the transformation to the ground plane. + */ + void + applyTransformationGround (); + + /** + * \brief Applies the transformation to the intrinsics matrix. + */ + void + applyTransformationIntrinsics (); + + /** + * \brief Reduces the input cloud to one point per voxel and limits the field of view. + */ + void + filter (); + + /** + * \brief Perform people detection on the input data and return people clusters information. + * + * \param[out] clusters Vector of PersonCluster. + * + * \return true if the compute operation is successful, false otherwise. + */ + bool + compute (std::vector >& clusters); + + protected: + /** \brief sampling factor used to downsample the point cloud */ + int sampling_factor_; + + /** \brief voxel size */ + float voxel_size_; + + /** \brief ground plane coefficients */ + Eigen::VectorXf ground_coeffs_; + + /** \brief flag stating whether the ground coefficients have been set or not */ + bool ground_coeffs_set_; + + /** \brief the transformed ground coefficients */ + Eigen::VectorXf ground_coeffs_transformed_; + + /** \brief ground plane normalization factor */ + float sqrt_ground_coeffs_; + + /** \brief rotation matrix which transforms input point cloud to internal people tracker coordinate frame */ + Eigen::Matrix3f transformation_; + + /** \brief flag stating whether the transformation matrix has been set or not */ + bool transformation_set_; + + /** \brief pointer to the input cloud */ + PointCloudPtr cloud_; + + /** \brief pointer to the filtered cloud */ + PointCloudPtr cloud_filtered_; + + /** \brief pointer to the cloud after voxel grid filtering and ground removal */ + PointCloudPtr no_ground_cloud_; + + /** \brief pointer to a RGB cloud corresponding to cloud_ */ + pcl::PointCloud::Ptr rgb_image_; + + /** \brief person clusters maximum height from the ground plane */ + float max_height_; + + /** \brief person clusters minimum height from the ground plane */ + float min_height_; + + /** \brief person clusters maximum width, used to estimate how many points maximally represent a person cluster */ + float max_width_; + + /** \brief person clusters minimum width, used to estimate how many points minimally represent a person cluster */ + float min_width_; + + /** \brief the beginning of the field of view in z-direction, should be usually set to zero */ + float min_fov_; + + /** \brief the end of the field of view in z-direction */ + float max_fov_; + + /** \brief if true, the sensor is considered to be vertically placed (portrait mode) */ + bool vertical_; + + /** \brief if true, the person centroid is computed as the centroid of the cluster points belonging to the head; + * if false, the person centroid is computed as the centroid of the whole cluster points (default = true) */ + bool head_centroid_; // if true, the person centroid is computed as the centroid of the cluster points belonging to the head (default = true) + // if false, the person centroid is computed as the centroid of the whole cluster points + /** \brief maximum number of points for a person cluster */ + int max_points_; + + /** \brief minimum number of points for a person cluster */ + int min_points_; + + /** \brief minimum distance between persons' heads */ + float heads_minimum_distance_; + + /** \brief intrinsic parameters matrix of the RGB camera */ + Eigen::Matrix3f intrinsics_matrix_; + + /** \brief flag stating whether the intrinsics matrix has been set or not */ + bool intrinsics_matrix_set_; + + /** \brief the transformed intrinsics matrix */ + Eigen::Matrix3f intrinsics_matrix_transformed_; + + /** \brief SVM-based person classifier */ + pcl::people::PersonClassifier person_classifier_; + + /** \brief flag stating if the classifier has been set or not */ + bool person_classifier_set_flag_; + }; + } /* namespace people */ +} /* namespace pcl */ +#include +#endif /* PCL_PEOPLE_GROUND_BASED_PEOPLE_DETECTION_APP_H_ */ diff --git a/pcl-1.7/pcl/people/head_based_subcluster.h b/pcl-1.7/pcl/people/head_based_subcluster.h new file mode 100644 index 0000000..0a60bbc --- /dev/null +++ b/pcl-1.7/pcl/people/head_based_subcluster.h @@ -0,0 +1,231 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * head_based_subcluster.h + * Created on: Nov 30, 2012 + * Author: Matteo Munaro + */ + +#ifndef PCL_PEOPLE_HEAD_BASED_SUBCLUSTER_H_ +#define PCL_PEOPLE_HEAD_BASED_SUBCLUSTER_H_ + +#include +#include +#include + +namespace pcl +{ + namespace people + { + /** \brief @b HeadBasedSubclustering represents a class for searching for people inside a HeightMap2D based on a 3D head detection algorithm + * \author Matteo Munaro + * \ingroup people + */ + template class HeadBasedSubclustering; + + template + class HeadBasedSubclustering + { + public: + + typedef pcl::PointCloud PointCloud; + typedef boost::shared_ptr PointCloudPtr; + typedef boost::shared_ptr PointCloudConstPtr; + + /** \brief Constructor. */ + HeadBasedSubclustering (); + + /** \brief Destructor. */ + virtual ~HeadBasedSubclustering (); + + /** + * \brief Compute subclusters and return them into a vector of PersonCluster. + * + * \param[in] clusters Vector of PersonCluster. + */ + void + subcluster (std::vector >& clusters); + + /** + * \brief Merge clusters close in floor coordinates. + * + * \param[in] input_clusters Input vector of PersonCluster. + * \param[in] output_clusters Output vector of PersonCluster (after merging). + */ + void + mergeClustersCloseInFloorCoordinates (std::vector >& input_clusters, + std::vector >& output_clusters); + + /** + * \brief Create subclusters centered on the heads position from the current cluster. + * + * \param[in] cluster A PersonCluster. + * \param[in] maxima_number_after_filtering Number of local maxima to use as centers of the new cluster. + * \param[in] maxima_cloud_indices_filtered Cloud indices of local maxima to use as centers of the new cluster. + * \param[out] subclusters Output vector of PersonCluster objects derived from the input cluster. + */ + void + createSubClusters (pcl::people::PersonCluster& cluster, int maxima_number_after_filtering, std::vector& maxima_cloud_indices_filtered, + std::vector >& subclusters); + + /** + * \brief Set input cloud. + * + * \param[in] cloud A pointer to the input point cloud. + */ + void + setInputCloud (PointCloudPtr& cloud); + + /** + * \brief Set the ground coefficients. + * + * \param[in] ground_coeffs The ground plane coefficients. + */ + void + setGround (Eigen::VectorXf& ground_coeffs); + + /** + * \brief Set sensor orientation to landscape mode (false) or portrait mode (true). + * + * \param[in] vertical Landscape (false) or portrait (true) mode (default = false). + */ + void + setSensorPortraitOrientation (bool vertical); + + /** + * \brief Set head_centroid_ to true (person centroid is in the head) or false (person centroid is the whole body centroid). + * + * \param[in] head_centroid Set the location of the person centroid (head or body center) (default = true). + */ + void + setHeadCentroid (bool head_centroid); + + /** + * \brief Set initial cluster indices. + * + * \param[in] cluster_indices Point cloud indices corresponding to the initial clusters (before subclustering). + */ + void + setInitialClusters (std::vector& cluster_indices); + + /** + * \brief Set minimum and maximum allowed height for a person cluster. + * + * \param[in] min_height Minimum allowed height for a person cluster (default = 1.3). + * \param[in] max_height Maximum allowed height for a person cluster (default = 2.3). + */ + void + setHeightLimits (float min_height, float max_height); + + /** + * \brief Set minimum and maximum allowed number of points for a person cluster. + * + * \param[in] min_points Minimum allowed number of points for a person cluster. + * \param[in] max_points Maximum allowed number of points for a person cluster. + */ + void + setDimensionLimits (int min_points, int max_points); + + /** + * \brief Set minimum distance between persons' heads. + * + * \param[in] heads_minimum_distance Minimum allowed distance between persons' heads (default = 0.3). + */ + void + setMinimumDistanceBetweenHeads (float heads_minimum_distance); + + /** + * \brief Get minimum and maximum allowed height for a person cluster. + * + * \param[out] min_height Minimum allowed height for a person cluster. + * \param[out] max_height Maximum allowed height for a person cluster. + */ + void + getHeightLimits (float& min_height, float& max_height); + + /** + * \brief Get minimum and maximum allowed number of points for a person cluster. + * + * \param[out] min_points Minimum allowed number of points for a person cluster. + * \param[out] max_points Maximum allowed number of points for a person cluster. + */ + void + getDimensionLimits (int& min_points, int& max_points); + + /** + * \brief Get minimum distance between persons' heads. + */ + float + getMinimumDistanceBetweenHeads (); + + protected: + /** \brief ground plane coefficients */ + Eigen::VectorXf ground_coeffs_; + + /** \brief ground plane normalization factor */ + float sqrt_ground_coeffs_; + + /** \brief initial clusters indices */ + std::vector cluster_indices_; + + /** \brief pointer to the input cloud */ + PointCloudPtr cloud_; + + /** \brief person clusters maximum height from the ground plane */ + float max_height_; + + /** \brief person clusters minimum height from the ground plane */ + float min_height_; + + /** \brief if true, the sensor is considered to be vertically placed (portrait mode) */ + bool vertical_; + + /** \brief if true, the person centroid is computed as the centroid of the cluster points belonging to the head + if false, the person centroid is computed as the centroid of the whole cluster points (default = true) */ + bool head_centroid_; + + /** \brief maximum number of points for a person cluster */ + int max_points_; + + /** \brief minimum number of points for a person cluster */ + int min_points_; + + /** \brief minimum distance between persons' heads */ + float heads_minimum_distance_; + }; + } /* namespace people */ +} /* namespace pcl */ +#include +#endif /* PCL_PEOPLE_HEAD_BASED_SUBCLUSTER_H_ */ diff --git a/pcl-1.7/pcl/people/height_map_2d.h b/pcl-1.7/pcl/people/height_map_2d.h new file mode 100644 index 0000000..4f8c1af --- /dev/null +++ b/pcl-1.7/pcl/people/height_map_2d.h @@ -0,0 +1,209 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * height_map_2d.h + * Created on: Nov 30, 2012 + * Author: Matteo Munaro + */ + +#ifndef PCL_PEOPLE_HEIGHT_MAP_2D_H_ +#define PCL_PEOPLE_HEIGHT_MAP_2D_H_ + +#include +#include + +namespace pcl +{ + namespace people + { + /** \brief @b HeightMap2D represents a class for creating a 2D height map from a point cloud and searching for its local maxima + * \author Matteo Munaro + * \ingroup people + */ + template class HeightMap2D; + + template + class HeightMap2D + { + public: + + typedef pcl::PointCloud PointCloud; + typedef boost::shared_ptr PointCloudPtr; + typedef boost::shared_ptr PointCloudConstPtr; + + /** \brief Constructor. */ + HeightMap2D(); + + /** \brief Destructor. */ + virtual ~HeightMap2D (); + + /** + * \brief Compute the height map with the projection of cluster points onto the ground plane. + * + * \param[in] cluster The PersonCluster used to compute the height map. + */ + void + compute (pcl::people::PersonCluster& cluster); + + /** + * \brief Compute local maxima of the height map. + */ + void + searchLocalMaxima (); + + /** + * \brief Filter maxima of the height map by imposing a minimum distance between them. + */ + void + filterMaxima (); + + /** + * \brief Set initial cluster indices. + * + * \param[in] cloud A pointer to the input cloud. + */ + void + setInputCloud (PointCloudPtr& cloud); + + /** + * \brief Set the ground coefficients. + * + * \param[in] ground_coeffs The ground plane coefficients. + */ + void + setGround (Eigen::VectorXf& ground_coeffs); + + /** + * \brief Set bin size for the height map. + * + * \param[in] bin_size Bin size for the height map (default = 0.06). + */ + void + setBinSize (float bin_size); + + /** + * \brief Set minimum distance between maxima. + * + * \param[in] minimum_distance_between_maxima Minimum allowed distance between maxima (default = 0.3). + */ + void + setMinimumDistanceBetweenMaxima (float minimum_distance_between_maxima); + + /** + * \brief Set sensor orientation to landscape mode (false) or portrait mode (true). + * + * \param[in] vertical Landscape (false) or portrait (true) mode (default = false). + */ + void + setSensorPortraitOrientation (bool vertical); + + /** + * \brief Get the height map as a vector of int. + */ + std::vector& + getHeightMap (); + + /** + * \brief Get bin size for the height map. + */ + float + getBinSize (); + + /** + * \brief Get minimum distance between maxima of the height map. + */ + float + getMinimumDistanceBetweenMaxima (); + + /** + * \brief Return the maxima number after the filterMaxima method. + */ + int& + getMaximaNumberAfterFiltering (); + + /** + * \brief Return the point cloud indices corresponding to the maxima computed after the filterMaxima method. + */ + std::vector& + getMaximaCloudIndicesFiltered (); + + protected: + /** \brief ground plane coefficients */ + Eigen::VectorXf ground_coeffs_; + + /** \brief ground plane normalization factor */ + float sqrt_ground_coeffs_; + + /** \brief pointer to the input cloud */ + PointCloudPtr cloud_; + + /** \brief if true, the sensor is considered to be vertically placed (portrait mode) */ + bool vertical_; + + /** \brief vector with maximum height values for every bin (height map) */ + std::vector buckets_; + + /** \brief indices of the pointcloud points with maximum height for every bin */ + std::vector buckets_cloud_indices_; + + /** \brief bin dimension */ + float bin_size_; + + /** \brief number of local maxima in the height map */ + int maxima_number_; + + /** \brief contains the position of the maxima in the buckets vector */ + std::vector maxima_indices_; + + /** \brief contains the point cloud position of the maxima (indices of the point cloud) */ + std::vector maxima_cloud_indices_; + + /** \brief number of local maxima after filtering */ + int maxima_number_after_filtering_; + + /** \brief contains the position of the maxima in the buckets array after filtering */ + std::vector maxima_indices_filtered_; + + /** \brief contains the point cloud position of the maxima after filtering */ + std::vector maxima_cloud_indices_filtered_; + + /** \brief minimum allowed distance between maxima */ + float min_dist_between_maxima_; + }; + + } /* namespace people */ +} /* namespace pcl */ +#include +#endif /* PCL_PEOPLE_HEIGHT_MAP_2D_H_ */ diff --git a/pcl-1.7/pcl/people/hog.h b/pcl-1.7/pcl/people/hog.h new file mode 100644 index 0000000..9802551 --- /dev/null +++ b/pcl-1.7/pcl/people/hog.h @@ -0,0 +1,189 @@ +/* + * Software License Agreement (Simplified BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013-, Open Perception, Inc. + * Copyright (c) 2012, Piotr Dollar & Ron Appel. [pdollar-at-caltech.edu] + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + * The views and conclusions contained in the software and documentation are those + * of the authors and should not be interpreted as representing official policies, + * either expressed or implied, of the FreeBSD Project. + * + * hog.h + * Created on: Nov 30, 2012 + * Derived from Piotr Dollar's MATLAB Image&Video Toolbox Version 3.00. + * Non-SSE version of the code provided by Matteo Munaro, Stefano Ghidoni and Stefano Michieletto + */ + +#ifndef PCL_PEOPLE_HOG_H_ +#define PCL_PEOPLE_HOG_H_ + +#include + +namespace pcl +{ + namespace people + { + /** \brief @b HOG represents a class for computing the HOG descriptor described in + * Dalal, N. and Triggs, B., "Histograms of oriented gradients for human detection", CVPR 2005. + * \author Matteo Munaro, Stefano Ghidoni, Stefano Michieletto + * \ingroup people + */ + class PCL_EXPORTS HOG + { + public: + + /** \brief Constructor. */ + HOG (); + + /** \brief Destructor. */ + virtual ~HOG (); + + /** + * \brief Compute gradient magnitude and orientation at each location (uses sse). + * + * \param[in] I Image as array of float. + * \param[in] h Image height. + * \param[in] w Image width. + * \param[in] d Image number of channels. + * \param[out] M Gradient magnitude for each image point. + * \param[out] O Gradient orientation for each image point. + */ + void + gradMag ( float *I, int h, int w, int d, float *M, float *O ) const; + + /** + * \brief Compute n_orients gradient histograms per bin_size x bin_size block of pixels. + * + * \param[in] M Gradient magnitude for each image point. + * \param[in] O Gradient orientation for each image point. + * \param[in] h Image height. + * \param[in] w Image width. + * \param[in] bin_size Spatial bin size. + * \param[in] n_orients Number of orientation bins. + * \param[in] soft_bin If true, each pixel can contribute to multiple spatial bins (using bilinear interpolation). + * \param[out] H Gradient histograms. + */ + void + gradHist ( float *M, float *O, int h, int w, int bin_size, int n_orients, bool soft_bin, float *H) const; + + /** + * \brief Normalize histogram of gradients. + * + * \param[in] H Gradient histograms. + * \param[in] h Image height. + * \param[in] w Image width. + * \param[in] bin_size Spatial bin size. + * \param[in] n_orients Number of orientation bins. + * \param[in] clip Value at which to clip histogram bins. + * \param[out] G Normalized gradient histograms. + */ + void + normalization ( float *H, int h, int w, int bin_size, int n_orients, float clip, float *G ) const; + + /** + * \brief Compute HOG descriptor. + * + * \param[in] I Image as array of float between 0 and 1. + * \param[in] h Image height. + * \param[in] w Image width. + * \param[in] n_channels Image number of channels. + * \param[in] bin_size Spatial bin size. + * \param[in] n_orients Number of orientation bins. + * \param[in] soft_bin If true, each pixel can contribute to multiple spatial bins (using bilinear interpolation). + * \param[out] descriptor HOG descriptor. + */ + void + compute (float *I, int h, int w, int n_channels, int bin_size, int n_orients, bool soft_bin, float *descriptor); + + /** + * \brief Compute HOG descriptor with default parameters. + * + * \param[in] I Image as array of float between 0 and 1. + * \param[out] descriptor HOG descriptor. + */ + void + compute (float *I, float *descriptor) const; + + private: + + /** + * \brief Compute x and y gradients for just one column (uses sse). + */ + void + grad1 ( float *I, float *Gx, float *Gy, int h, int w, int x ) const; + + /** + * \brief Build lookup table a[] s.t. a[dx/2.02*n]~=acos(dx). + */ + float* + acosTable () const; + + /** + * \brief Helper for gradHist, quantize O and M into O0, O1 and M0, M1 (uses sse). + */ + void + gradQuantize ( float *O, float *M, int *O0, int *O1, float *M0, float *M1, int n_orients, int nb, int n, float norm ) const; + + /** + * \brief Platform independent aligned memory allocation (see also alFree). + */ + void* + alMalloc ( size_t size, int alignment ) const; + + /** + * \brief Platform independent aligned memory de-allocation (see also alMalloc). + */ + void + alFree (void* aligned) const; + + protected: + + /** \brief image height (default = 128) */ + int h_; + + /** \brief image width (default = 64) */ + int w_; + + /** \brief image number of channels (default = 3) */ + int n_channels_; + + /** \brief spatial bin size (default = 8) */ + int bin_size_; + + /** \brief number of orientation bins (default = 9) */ + int n_orients_; + + /** \brief if true, each pixel can contribute to multiple spatial bins (using bilinear interpolation) (default = true) */ + bool soft_bin_; + + /** \brief value at which to clip histogram bins (default = 0.2) */ + float clip_; + + }; + } /* namespace people */ +} /* namespace pcl */ +#endif /* PCL_PEOPLE_HOG_H_ */ diff --git a/pcl-1.7/pcl/people/impl/ground_based_people_detection_app.hpp b/pcl-1.7/pcl/people/impl/ground_based_people_detection_app.hpp new file mode 100644 index 0000000..bade476 --- /dev/null +++ b/pcl-1.7/pcl/people/impl/ground_based_people_detection_app.hpp @@ -0,0 +1,420 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * ground_based_people_detection_app.hpp + * Created on: Nov 30, 2012 + * Author: Matteo Munaro + */ + +#ifndef PCL_PEOPLE_GROUND_BASED_PEOPLE_DETECTION_APP_HPP_ +#define PCL_PEOPLE_GROUND_BASED_PEOPLE_DETECTION_APP_HPP_ + +#include + +template +pcl::people::GroundBasedPeopleDetectionApp::GroundBasedPeopleDetectionApp () +{ + rgb_image_ = pcl::PointCloud::Ptr(new pcl::PointCloud); + + // set default values for optional parameters: + sampling_factor_ = 1; + voxel_size_ = 0.06; + vertical_ = false; + head_centroid_ = true; + min_fov_ = 0; + max_fov_ = 50; + min_height_ = 1.3; + max_height_ = 2.3; + min_width_ = 0.1; + max_width_ = 8.0; + updateMinMaxPoints (); + heads_minimum_distance_ = 0.3; + + // set flag values for mandatory parameters: + sqrt_ground_coeffs_ = std::numeric_limits::quiet_NaN(); + ground_coeffs_set_ = false; + intrinsics_matrix_set_ = false; + person_classifier_set_flag_ = false; + + // set other flags + transformation_set_ = false; +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::setInputCloud (PointCloudPtr& cloud) +{ + cloud_ = cloud; +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::setTransformation (const Eigen::Matrix3f& transformation) +{ + if (!transformation.isUnitary()) + { + PCL_ERROR ("[pcl::people::GroundBasedPeopleDetectionApp::setCloudTransform] The cloud transformation matrix must be an orthogonal matrix!\n"); + } + + transformation_ = transformation; + transformation_set_ = true; + applyTransformationGround(); + applyTransformationIntrinsics(); +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::setGround (Eigen::VectorXf& ground_coeffs) +{ + ground_coeffs_ = ground_coeffs; + ground_coeffs_set_ = true; + sqrt_ground_coeffs_ = (ground_coeffs - Eigen::Vector4f(0.0f, 0.0f, 0.0f, ground_coeffs(3))).norm(); + applyTransformationGround(); +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::setSamplingFactor (int sampling_factor) +{ + sampling_factor_ = sampling_factor; +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::setVoxelSize (float voxel_size) +{ + voxel_size_ = voxel_size; + updateMinMaxPoints (); +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::setIntrinsics (Eigen::Matrix3f intrinsics_matrix) +{ + intrinsics_matrix_ = intrinsics_matrix; + intrinsics_matrix_set_ = true; + applyTransformationIntrinsics(); +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::setClassifier (pcl::people::PersonClassifier person_classifier) +{ + person_classifier_ = person_classifier; + person_classifier_set_flag_ = true; +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::setFOV (float min_fov, float max_fov) +{ + min_fov_ = min_fov; + max_fov_ = max_fov; +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::setSensorPortraitOrientation (bool vertical) +{ + vertical_ = vertical; +} + +template +void pcl::people::GroundBasedPeopleDetectionApp::updateMinMaxPoints () +{ + min_points_ = (int) (min_height_ * min_width_ / voxel_size_ / voxel_size_); + max_points_ = (int) (max_height_ * max_width_ / voxel_size_ / voxel_size_); +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::setPersonClusterLimits (float min_height, float max_height, float min_width, float max_width) +{ + min_height_ = min_height; + max_height_ = max_height; + min_width_ = min_width; + max_width_ = max_width; + updateMinMaxPoints (); +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::setMinimumDistanceBetweenHeads (float heads_minimum_distance) +{ + heads_minimum_distance_= heads_minimum_distance; +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::setHeadCentroid (bool head_centroid) +{ + head_centroid_ = head_centroid; +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::getPersonClusterLimits (float& min_height, float& max_height, float& min_width, float& max_width) +{ + min_height = min_height_; + max_height = max_height_; + min_width = min_width_; + max_width = max_width_; +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::getDimensionLimits (int& min_points, int& max_points) +{ + min_points = min_points_; + max_points = max_points_; +} + +template float +pcl::people::GroundBasedPeopleDetectionApp::getMinimumDistanceBetweenHeads () +{ + return (heads_minimum_distance_); +} + +template Eigen::VectorXf +pcl::people::GroundBasedPeopleDetectionApp::getGround () +{ + if (!ground_coeffs_set_) + { + PCL_ERROR ("[pcl::people::GroundBasedPeopleDetectionApp::getGround] Floor parameters have not been set or they are not valid!\n"); + } + return (ground_coeffs_); +} + +template typename pcl::people::GroundBasedPeopleDetectionApp::PointCloudPtr +pcl::people::GroundBasedPeopleDetectionApp::getFilteredCloud () +{ + return (cloud_filtered_); +} + +template typename pcl::people::GroundBasedPeopleDetectionApp::PointCloudPtr +pcl::people::GroundBasedPeopleDetectionApp::getNoGroundCloud () +{ + return (no_ground_cloud_); +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::extractRGBFromPointCloud (PointCloudPtr input_cloud, pcl::PointCloud::Ptr& output_cloud) +{ + // Extract RGB information from a point cloud and output the corresponding RGB point cloud + output_cloud->points.resize(input_cloud->height*input_cloud->width); + output_cloud->width = input_cloud->width; + output_cloud->height = input_cloud->height; + + pcl::RGB rgb_point; + for (uint32_t j = 0; j < input_cloud->width; j++) + { + for (uint32_t i = 0; i < input_cloud->height; i++) + { + rgb_point.r = (*input_cloud)(j,i).r; + rgb_point.g = (*input_cloud)(j,i).g; + rgb_point.b = (*input_cloud)(j,i).b; + (*output_cloud)(j,i) = rgb_point; + } + } +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::swapDimensions (pcl::PointCloud::Ptr& cloud) +{ + pcl::PointCloud::Ptr output_cloud(new pcl::PointCloud); + output_cloud->points.resize(cloud->height*cloud->width); + output_cloud->width = cloud->height; + output_cloud->height = cloud->width; + for (uint32_t i = 0; i < cloud->width; i++) + { + for (uint32_t j = 0; j < cloud->height; j++) + { + (*output_cloud)(j,i) = (*cloud)(cloud->width - i - 1, j); + } + } + cloud = output_cloud; +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::applyTransformationPointCloud () +{ + if (transformation_set_) + { + Eigen::Transform transform; + transform = transformation_; + pcl::transformPointCloud(*cloud_, *cloud_, transform); + } +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::applyTransformationGround () +{ + if (transformation_set_ && ground_coeffs_set_) + { + Eigen::Transform transform; + transform = transformation_; + ground_coeffs_transformed_ = transform.matrix() * ground_coeffs_; + } + else + { + ground_coeffs_transformed_ = ground_coeffs_; + } +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::applyTransformationIntrinsics () +{ + if (transformation_set_ && intrinsics_matrix_set_) + { + intrinsics_matrix_transformed_ = intrinsics_matrix_ * transformation_.transpose(); + } + else + { + intrinsics_matrix_transformed_ = intrinsics_matrix_; + } +} + +template void +pcl::people::GroundBasedPeopleDetectionApp::filter () +{ + cloud_filtered_ = PointCloudPtr (new PointCloud); + pcl::VoxelGrid grid; + grid.setInputCloud(cloud_); + grid.setLeafSize(voxel_size_, voxel_size_, voxel_size_); + grid.setFilterFieldName("z"); + grid.setFilterLimits(min_fov_, max_fov_); + grid.filter(*cloud_filtered_); +} + +template bool +pcl::people::GroundBasedPeopleDetectionApp::compute (std::vector >& clusters) +{ + // Check if all mandatory variables have been set: + if (!ground_coeffs_set_) + { + PCL_ERROR ("[pcl::people::GroundBasedPeopleDetectionApp::compute] Floor parameters have not been set or they are not valid!\n"); + return (false); + } + if (cloud_ == NULL) + { + PCL_ERROR ("[pcl::people::GroundBasedPeopleDetectionApp::compute] Input cloud has not been set!\n"); + return (false); + } + if (!intrinsics_matrix_set_) + { + PCL_ERROR ("[pcl::people::GroundBasedPeopleDetectionApp::compute] Camera intrinsic parameters have not been set!\n"); + return (false); + } + if (!person_classifier_set_flag_) + { + PCL_ERROR ("[pcl::people::GroundBasedPeopleDetectionApp::compute] Person classifier has not been set!\n"); + return (false); + } + + // Fill rgb image: + rgb_image_->points.clear(); // clear RGB pointcloud + extractRGBFromPointCloud(cloud_, rgb_image_); // fill RGB pointcloud + + // Downsample of sampling_factor in every dimension: + if (sampling_factor_ != 1) + { + PointCloudPtr cloud_downsampled(new PointCloud); + cloud_downsampled->width = (cloud_->width)/sampling_factor_; + cloud_downsampled->height = (cloud_->height)/sampling_factor_; + cloud_downsampled->points.resize(cloud_downsampled->height*cloud_downsampled->width); + cloud_downsampled->is_dense = cloud_->is_dense; + for (uint32_t j = 0; j < cloud_downsampled->width; j++) + { + for (uint32_t i = 0; i < cloud_downsampled->height; i++) + { + (*cloud_downsampled)(j,i) = (*cloud_)(sampling_factor_*j,sampling_factor_*i); + } + } + (*cloud_) = (*cloud_downsampled); + } + + applyTransformationPointCloud(); + + filter(); + + // Ground removal and update: + pcl::IndicesPtr inliers(new std::vector); + boost::shared_ptr > ground_model(new pcl::SampleConsensusModelPlane(cloud_filtered_)); + ground_model->selectWithinDistance(ground_coeffs_transformed_, 2 * voxel_size_, *inliers); + no_ground_cloud_ = PointCloudPtr (new PointCloud); + pcl::ExtractIndices extract; + extract.setInputCloud(cloud_filtered_); + extract.setIndices(inliers); + extract.setNegative(true); + extract.filter(*no_ground_cloud_); + if (inliers->size () >= (300 * 0.06 / voxel_size_ / std::pow (static_cast (sampling_factor_), 2))) + ground_model->optimizeModelCoefficients (*inliers, ground_coeffs_transformed_, ground_coeffs_transformed_); + else + PCL_INFO ("No groundplane update!\n"); + + // Euclidean Clustering: + std::vector cluster_indices; + typename pcl::search::KdTree::Ptr tree (new pcl::search::KdTree); + tree->setInputCloud(no_ground_cloud_); + pcl::EuclideanClusterExtraction ec; + ec.setClusterTolerance(2 * voxel_size_); + ec.setMinClusterSize(min_points_); + ec.setMaxClusterSize(max_points_); + ec.setSearchMethod(tree); + ec.setInputCloud(no_ground_cloud_); + ec.extract(cluster_indices); + + // Head based sub-clustering // + pcl::people::HeadBasedSubclustering subclustering; + subclustering.setInputCloud(no_ground_cloud_); + subclustering.setGround(ground_coeffs_transformed_); + subclustering.setInitialClusters(cluster_indices); + subclustering.setHeightLimits(min_height_, max_height_); + subclustering.setMinimumDistanceBetweenHeads(heads_minimum_distance_); + subclustering.setSensorPortraitOrientation(vertical_); + subclustering.subcluster(clusters); + + // Person confidence evaluation with HOG+SVM: + if (vertical_) // Rotate the image if the camera is vertical + { + swapDimensions(rgb_image_); + } + for(typename std::vector >::iterator it = clusters.begin(); it != clusters.end(); ++it) + { + //Evaluate confidence for the current PersonCluster: + Eigen::Vector3f centroid = intrinsics_matrix_transformed_ * (it->getTCenter()); + centroid /= centroid(2); + Eigen::Vector3f top = intrinsics_matrix_transformed_ * (it->getTTop()); + top /= top(2); + Eigen::Vector3f bottom = intrinsics_matrix_transformed_ * (it->getTBottom()); + bottom /= bottom(2); + it->setPersonConfidence(person_classifier_.evaluate(rgb_image_, bottom, top, centroid, vertical_)); + } + + return (true); +} + +template +pcl::people::GroundBasedPeopleDetectionApp::~GroundBasedPeopleDetectionApp () +{ + // TODO Auto-generated destructor stub +} +#endif /* PCL_PEOPLE_GROUND_BASED_PEOPLE_DETECTION_APP_HPP_ */ diff --git a/pcl-1.7/pcl/people/impl/head_based_subcluster.hpp b/pcl-1.7/pcl/people/impl/head_based_subcluster.hpp new file mode 100644 index 0000000..0c624c7 --- /dev/null +++ b/pcl-1.7/pcl/people/impl/head_based_subcluster.hpp @@ -0,0 +1,340 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * head_based_subcluster.hpp + * Created on: Nov 30, 2012 + * Author: Matteo Munaro + */ + +#ifndef PCL_PEOPLE_HEAD_BASED_SUBCLUSTER_HPP_ +#define PCL_PEOPLE_HEAD_BASED_SUBCLUSTER_HPP_ + +#include + +template +pcl::people::HeadBasedSubclustering::HeadBasedSubclustering () +{ + // set default values for optional parameters: + vertical_ = false; + head_centroid_ = true; + min_height_ = 1.3; + max_height_ = 2.3; + min_points_ = 30; + max_points_ = 5000; + heads_minimum_distance_ = 0.3; + + // set flag values for mandatory parameters: + sqrt_ground_coeffs_ = std::numeric_limits::quiet_NaN(); +} + +template void +pcl::people::HeadBasedSubclustering::setInputCloud (PointCloudPtr& cloud) +{ + cloud_ = cloud; +} + +template void +pcl::people::HeadBasedSubclustering::setGround (Eigen::VectorXf& ground_coeffs) +{ + ground_coeffs_ = ground_coeffs; + sqrt_ground_coeffs_ = (ground_coeffs - Eigen::Vector4f(0.0f, 0.0f, 0.0f, ground_coeffs(3))).norm(); +} + +template void +pcl::people::HeadBasedSubclustering::setInitialClusters (std::vector& cluster_indices) +{ + cluster_indices_ = cluster_indices; +} + +template void +pcl::people::HeadBasedSubclustering::setSensorPortraitOrientation (bool vertical) +{ + vertical_ = vertical; +} + +template void +pcl::people::HeadBasedSubclustering::setHeightLimits (float min_height, float max_height) +{ + min_height_ = min_height; + max_height_ = max_height; +} + +template void +pcl::people::HeadBasedSubclustering::setDimensionLimits (int min_points, int max_points) +{ + min_points_ = min_points; + max_points_ = max_points; +} + +template void +pcl::people::HeadBasedSubclustering::setMinimumDistanceBetweenHeads (float heads_minimum_distance) +{ + heads_minimum_distance_= heads_minimum_distance; +} + +template void +pcl::people::HeadBasedSubclustering::setHeadCentroid (bool head_centroid) +{ + head_centroid_ = head_centroid; +} + +template void +pcl::people::HeadBasedSubclustering::getHeightLimits (float& min_height, float& max_height) +{ + min_height = min_height_; + max_height = max_height_; +} + +template void +pcl::people::HeadBasedSubclustering::getDimensionLimits (int& min_points, int& max_points) +{ + min_points = min_points_; + max_points = max_points_; +} + +template float +pcl::people::HeadBasedSubclustering::getMinimumDistanceBetweenHeads () +{ + return (heads_minimum_distance_); +} + +template void +pcl::people::HeadBasedSubclustering::mergeClustersCloseInFloorCoordinates (std::vector >& input_clusters, + std::vector >& output_clusters) +{ + float min_distance_between_cluster_centers = 0.4; // meters + float normalize_factor = std::pow(sqrt_ground_coeffs_, 2); // sqrt_ground_coeffs ^ 2 (precomputed for speed) + Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head(3); // ground plane normal (precomputed for speed) + std::vector > connected_clusters; + connected_clusters.resize(input_clusters.size()); + std::vector used_clusters; // 0 in correspondence of clusters remained to process, 1 for already used clusters + used_clusters.resize(input_clusters.size()); + for(unsigned int i = 0; i < input_clusters.size(); i++) // for every cluster + { + Eigen::Vector3f theoretical_center = input_clusters[i].getTCenter(); + float t = theoretical_center.dot(head_ground_coeffs) / normalize_factor; // height from the ground + Eigen::Vector3f current_cluster_center_projection = theoretical_center - head_ground_coeffs * t; // projection of the point on the groundplane + for(unsigned int j = i+1; j < input_clusters.size(); j++) // for every remaining cluster + { + theoretical_center = input_clusters[j].getTCenter(); + float t = theoretical_center.dot(head_ground_coeffs) / normalize_factor; // height from the ground + Eigen::Vector3f new_cluster_center_projection = theoretical_center - head_ground_coeffs * t; // projection of the point on the groundplane + if (((new_cluster_center_projection - current_cluster_center_projection).norm()) < min_distance_between_cluster_centers) + { + connected_clusters[i].push_back(j); + } + } + } + + for(unsigned int i = 0; i < connected_clusters.size(); i++) // for every cluster + { + if (!used_clusters[i]) // if this cluster has not been used yet + { + used_clusters[i] = true; + if (connected_clusters[i].empty()) // no other clusters to merge + { + output_clusters.push_back(input_clusters[i]); + } + else + { + // Copy cluster points into new cluster: + pcl::PointIndices point_indices; + point_indices = input_clusters[i].getIndices(); + for(unsigned int j = 0; j < connected_clusters[i].size(); j++) + { + if (!used_clusters[connected_clusters[i][j]]) // if this cluster has not been used yet + { + used_clusters[connected_clusters[i][j]] = true; + for(std::vector::const_iterator points_iterator = input_clusters[connected_clusters[i][j]].getIndices().indices.begin(); + points_iterator != input_clusters[connected_clusters[i][j]].getIndices().indices.end(); points_iterator++) + { + point_indices.indices.push_back(*points_iterator); + } + } + } + pcl::people::PersonCluster cluster(cloud_, point_indices, ground_coeffs_, sqrt_ground_coeffs_, head_centroid_, vertical_); + output_clusters.push_back(cluster); + } + } + } + } + +template void +pcl::people::HeadBasedSubclustering::createSubClusters (pcl::people::PersonCluster& cluster, int maxima_number, + std::vector& maxima_cloud_indices, std::vector >& subclusters) +{ + // create new clusters from the current cluster and put corresponding indices into sub_clusters_indices: + float normalize_factor = std::pow(sqrt_ground_coeffs_, 2); // sqrt_ground_coeffs ^ 2 (precomputed for speed) + Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head(3); // ground plane normal (precomputed for speed) + Eigen::Matrix3Xf maxima_projected(3,maxima_number); // matrix containing the projection of maxima onto the ground plane + Eigen::VectorXi subclusters_number_of_points(maxima_number); // subclusters number of points + std::vector > sub_clusters_indices; // vector of vectors with the cluster indices for every maximum + sub_clusters_indices.resize(maxima_number); // resize to number of maxima + + // Project maxima on the ground plane: + for(int i = 0; i < maxima_number; i++) // for every maximum + { + PointT* current_point = &cloud_->points[maxima_cloud_indices[i]]; // current maximum point cloud point + Eigen::Vector3f p_current_eigen(current_point->x, current_point->y, current_point->z); // conversion to eigen + float t = p_current_eigen.dot(head_ground_coeffs) / normalize_factor; // height from the ground + maxima_projected.col(i).matrix () = p_current_eigen - head_ground_coeffs * t; // projection of the point on the groundplane + subclusters_number_of_points(i) = 0; // intialize number of points + } + + // Associate cluster points to one of the maximum: + for(std::vector::const_iterator points_iterator = cluster.getIndices().indices.begin(); points_iterator != cluster.getIndices().indices.end(); points_iterator++) + { + PointT* current_point = &cloud_->points[*points_iterator]; // current point cloud point + Eigen::Vector3f p_current_eigen(current_point->x, current_point->y, current_point->z); // conversion to eigen + float t = p_current_eigen.dot(head_ground_coeffs) / normalize_factor; // height from the ground + p_current_eigen = p_current_eigen - head_ground_coeffs * t; // projection of the point on the groundplane + + int i = 0; + bool correspondence_detected = false; + while ((!correspondence_detected) && (i < maxima_number)) + { + if (((p_current_eigen - maxima_projected.col(i)).norm()) < heads_minimum_distance_) + { + correspondence_detected = true; + sub_clusters_indices[i].push_back(*points_iterator); + subclusters_number_of_points(i)++; + } + else + i++; + } + } + + // Create a subcluster if the number of points associated to a maximum is over a threshold: + for(int i = 0; i < maxima_number; i++) // for every maximum + { + if (subclusters_number_of_points(i) > min_points_) + { + pcl::PointIndices point_indices; + point_indices.indices = sub_clusters_indices[i]; // indices associated to the i-th maximum + + pcl::people::PersonCluster cluster(cloud_, point_indices, ground_coeffs_, sqrt_ground_coeffs_, head_centroid_, vertical_); + subclusters.push_back(cluster); + //std::cout << "Cluster number of points: " << subclusters_number_of_points(i) << std::endl; + } + } +} + +template void +pcl::people::HeadBasedSubclustering::subcluster (std::vector >& clusters) +{ + // Check if all mandatory variables have been set: + if (sqrt_ground_coeffs_ != sqrt_ground_coeffs_) + { + PCL_ERROR ("[pcl::people::pcl::people::HeadBasedSubclustering::subcluster] Floor parameters have not been set or they are not valid!\n"); + return; + } + if (cluster_indices_.size() == 0) + { + PCL_ERROR ("[pcl::people::pcl::people::HeadBasedSubclustering::subcluster] Cluster indices have not been set!\n"); + return; + } + if (cloud_ == NULL) + { + PCL_ERROR ("[pcl::people::pcl::people::HeadBasedSubclustering::subcluster] Input cloud has not been set!\n"); + return; + } + + // Person clusters creation from clusters indices: + for(std::vector::const_iterator it = cluster_indices_.begin(); it != cluster_indices_.end(); ++it) + { + pcl::people::PersonCluster cluster(cloud_, *it, ground_coeffs_, sqrt_ground_coeffs_, head_centroid_, vertical_); // PersonCluster creation + clusters.push_back(cluster); + } + + // Remove clusters with too high height from the ground plane: + std::vector > new_clusters; + for(unsigned int i = 0; i < clusters.size(); i++) // for every cluster + { + if (clusters[i].getHeight() <= max_height_) + new_clusters.push_back(clusters[i]); + } + clusters = new_clusters; + new_clusters.clear(); + + // Merge clusters close in floor coordinates: + mergeClustersCloseInFloorCoordinates(clusters, new_clusters); + clusters = new_clusters; + + std::vector > subclusters; + int cluster_min_points_sub = int(float(min_points_) * 1.5); + // int cluster_max_points_sub = max_points_; + + // create HeightMap2D object: + pcl::people::HeightMap2D height_map_obj; + height_map_obj.setGround(ground_coeffs_); + height_map_obj.setInputCloud(cloud_); + height_map_obj.setSensorPortraitOrientation(vertical_); + height_map_obj.setMinimumDistanceBetweenMaxima(heads_minimum_distance_); + for(typename std::vector >::iterator it = clusters.begin(); it != clusters.end(); ++it) // for every cluster + { + float height = it->getHeight(); + int number_of_points = it->getNumberPoints(); + if(height > min_height_ && height < max_height_) + { + if (number_of_points > cluster_min_points_sub) // && number_of_points < cluster_max_points_sub) + { + // Compute height map associated to the current cluster and its local maxima (heads): + height_map_obj.compute(*it); + if (height_map_obj.getMaximaNumberAfterFiltering() > 1) // if more than one maximum + { + // create new clusters from the current cluster and put corresponding indices into sub_clusters_indices: + createSubClusters(*it, height_map_obj.getMaximaNumberAfterFiltering(), height_map_obj.getMaximaCloudIndicesFiltered(), subclusters); + } + else + { // Only one maximum --> copy original cluster: + subclusters.push_back(*it); + } + } + else + { + // Cluster properties not good for sub-clustering --> copy original cluster: + subclusters.push_back(*it); + } + } + } + clusters = subclusters; // substitute clusters with subclusters +} + +template +pcl::people::HeadBasedSubclustering::~HeadBasedSubclustering () +{ + // TODO Auto-generated destructor stub +} +#endif /* PCL_PEOPLE_HEAD_BASED_SUBCLUSTER_HPP_ */ diff --git a/pcl-1.7/pcl/people/impl/height_map_2d.hpp b/pcl-1.7/pcl/people/impl/height_map_2d.hpp new file mode 100644 index 0000000..427b495 --- /dev/null +++ b/pcl-1.7/pcl/people/impl/height_map_2d.hpp @@ -0,0 +1,313 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * height_map_2d.hpp + * Created on: Nov 30, 2012 + * Author: Matteo Munaro + */ + +#include + +#ifndef PCL_PEOPLE_HEIGHT_MAP_2D_HPP_ +#define PCL_PEOPLE_HEIGHT_MAP_2D_HPP_ + +template +pcl::people::HeightMap2D::HeightMap2D () +{ + // set default values for optional parameters: + vertical_ = false; + min_dist_between_maxima_ = 0.3; + bin_size_ = 0.06; + + // set flag values for mandatory parameters: + sqrt_ground_coeffs_ = std::numeric_limits::quiet_NaN(); +} + +template void +pcl::people::HeightMap2D::compute (pcl::people::PersonCluster& cluster) +{ + // Check if all mandatory variables have been set: + if (sqrt_ground_coeffs_ != sqrt_ground_coeffs_) + { + PCL_ERROR ("[pcl::people::HeightMap2D::compute] Floor parameters have not been set or they are not valid!\n"); + return; + } + if (cloud_ == NULL) + { + PCL_ERROR ("[pcl::people::HeightMap2D::compute] Input cloud has not been set!\n"); + return; + } + + // Reset variables: + buckets_.clear(); + buckets_cloud_indices_.clear(); + maxima_indices_.clear(); + maxima_cloud_indices_.clear(); + maxima_indices_filtered_.clear(); + maxima_cloud_indices_filtered_.clear(); + + // Create a height map with the projection of cluster points onto the ground plane: + if (!vertical_) // camera horizontal + buckets_.resize(size_t((cluster.getMax()(0) - cluster.getMin()(0)) / bin_size_) + 1, 0); + else // camera vertical + buckets_.resize(size_t((cluster.getMax()(1) - cluster.getMin()(1)) / bin_size_) + 1, 0); + buckets_cloud_indices_.resize(buckets_.size(), 0); + + for(std::vector::const_iterator pit = cluster.getIndices().indices.begin(); pit != cluster.getIndices().indices.end(); pit++) + { + PointT* p = &cloud_->points[*pit]; + int index; + if (!vertical_) // camera horizontal + index = int((p->x - cluster.getMin()(0)) / bin_size_); + else // camera vertical + index = int((p->y - cluster.getMin()(1)) / bin_size_); + if (index > (static_cast (buckets_.size ()) - 1)) + std::cout << "Error: out of array - " << index << " of " << buckets_.size() << std::endl; + else + { + Eigen::Vector4f new_point(p->x, p->y, p->z, 1.0f); // select point from cluster + float heightp = std::fabs(new_point.dot(ground_coeffs_)); // compute point height from the groundplane + heightp /= sqrt_ground_coeffs_; + if ((heightp * 60) > buckets_[index]) // compare the height of the new point with the existing one + { + buckets_[index] = heightp * 60; // maximum height + buckets_cloud_indices_[index] = *pit; // point cloud index of the point with maximum height + } + } + } + + // Compute local maxima of the height map: + searchLocalMaxima(); + + // Filter maxima by imposing a minimum distance between them (minimum distance between people heads): + filterMaxima(); +} + +template void +pcl::people::HeightMap2D::searchLocalMaxima () +{ + // Search for local maxima: + maxima_number_ = 0; + int left = buckets_[0]; // current left element + int right = 0; // current right element + float offset = 0; // used to center the maximum to the right place + maxima_indices_.resize(size_t(buckets_.size()), 0); + maxima_cloud_indices_.resize(size_t(buckets_.size()), 0); + + // Handle first element: + if (buckets_[0] > buckets_[1]) + { + maxima_indices_[maxima_number_] = 0; + maxima_cloud_indices_[maxima_number_] = buckets_cloud_indices_[maxima_indices_[maxima_number_]]; + maxima_number_++; + } + + // Main loop: + int i = 1; + while (i < (static_cast (buckets_.size()) - 1)) + { + right = buckets_[i+1]; + if ((buckets_[i] > left) && (buckets_[i] > right)) + { + // Search where to insert the new element (in an ordered array): + int t = 0; // position of the new element + while ((t < maxima_number_) && (buckets_[i] < buckets_[maxima_indices_[t]])) + { + t++; + } + // Move forward the smaller elements: + for (int m = maxima_number_; m > t; m--) + { + maxima_indices_[m] = maxima_indices_[m-1]; + maxima_cloud_indices_[m] = maxima_cloud_indices_[m-1]; + } + // Insert the new element: + maxima_indices_[t] = i - int(offset/2 + 0.5); + maxima_cloud_indices_[t] = buckets_cloud_indices_[maxima_indices_[t]]; + left = buckets_[i+1]; + i = i+2; + offset = 0; + maxima_number_++; + } + else + { + if (buckets_[i] == right) + { + offset++; + } + else + { + left = buckets_[i]; + offset = 0; + } + i++; + } + } + + // Handle last element: + if (buckets_[buckets_.size()-1] > left) + { + // Search where to insert the new element (in an ordered array): + int t = 0; // position of the new element + while ((t < maxima_number_) && (buckets_[buckets_.size()-1] < buckets_[maxima_indices_[t]])) + { + t++; + } + // Move forward the smaller elements: + for (int m = maxima_number_; m > t; m--) + { + maxima_indices_[m] = maxima_indices_[m-1]; + maxima_cloud_indices_[m] = maxima_cloud_indices_[m-1]; + } + // Insert the new element: + maxima_indices_[t] = i - int(offset/2 + 0.5); + maxima_cloud_indices_[t] = buckets_cloud_indices_[maxima_indices_[t]]; + + maxima_number_++; + } +} + +template void +pcl::people::HeightMap2D::filterMaxima () +{ + // Filter maxima according to their distance when projected on the ground plane: + maxima_number_after_filtering_ = 0; + maxima_indices_filtered_.resize(maxima_number_, 0); + maxima_cloud_indices_filtered_.resize(maxima_number_, 0); + if (maxima_number_ > 0) + { + for (int i = 0; i < maxima_number_; i++) + { + bool good_maximum = true; + float distance = 0; + + PointT* p_current = &cloud_->points[maxima_cloud_indices_[i]]; // pointcloud point referring to the current maximum + Eigen::Vector3f p_current_eigen(p_current->x, p_current->y, p_current->z); // conversion to eigen + float t = p_current_eigen.dot(ground_coeffs_.head(3)) / std::pow(sqrt_ground_coeffs_, 2); // height from the ground + p_current_eigen = p_current_eigen - ground_coeffs_.head(3) * t; // projection of the point on the groundplane + + int j = i-1; + while ((j >= 0) && (good_maximum)) + { + PointT* p_previous = &cloud_->points[maxima_cloud_indices_[j]]; // pointcloud point referring to an already validated maximum + Eigen::Vector3f p_previous_eigen(p_previous->x, p_previous->y, p_previous->z); // conversion to eigen + float t = p_previous_eigen.dot(ground_coeffs_.head(3)) / std::pow(sqrt_ground_coeffs_, 2); // height from the ground + p_previous_eigen = p_previous_eigen - ground_coeffs_.head(3) * t; // projection of the point on the groundplane + + // distance of the projection of the points on the groundplane: + distance = (p_current_eigen-p_previous_eigen).norm(); + if (distance < min_dist_between_maxima_) + { + good_maximum = false; + } + j--; + } + if (good_maximum) + { + maxima_indices_filtered_[maxima_number_after_filtering_] = maxima_indices_[i]; + maxima_cloud_indices_filtered_[maxima_number_after_filtering_] = maxima_cloud_indices_[i]; + maxima_number_after_filtering_++; + } + } + } +} + +template void +pcl::people::HeightMap2D::setInputCloud (PointCloudPtr& cloud) +{ + cloud_ = cloud; +} + +template +void pcl::people::HeightMap2D::setGround(Eigen::VectorXf& ground_coeffs) +{ + ground_coeffs_ = ground_coeffs; + sqrt_ground_coeffs_ = (ground_coeffs - Eigen::Vector4f(0.0f, 0.0f, 0.0f, ground_coeffs(3))).norm(); +} + +template void +pcl::people::HeightMap2D::setBinSize (float bin_size) +{ + bin_size_ = bin_size; +} + +template void +pcl::people::HeightMap2D::setMinimumDistanceBetweenMaxima (float minimum_distance_between_maxima) +{ + min_dist_between_maxima_ = minimum_distance_between_maxima; +} + +template void +pcl::people::HeightMap2D::setSensorPortraitOrientation (bool vertical) +{ + vertical_ = vertical; +} + +template std::vector& +pcl::people::HeightMap2D::getHeightMap () +{ + return (buckets_); +} + +template float +pcl::people::HeightMap2D::getBinSize () +{ + return (bin_size_); +} + +template float +pcl::people::HeightMap2D::getMinimumDistanceBetweenMaxima () +{ + return (min_dist_between_maxima_); +} + +template int& +pcl::people::HeightMap2D::getMaximaNumberAfterFiltering () +{ + return (maxima_number_after_filtering_); +} + +template std::vector& +pcl::people::HeightMap2D::getMaximaCloudIndicesFiltered () +{ + return (maxima_cloud_indices_filtered_); +} + +template +pcl::people::HeightMap2D::~HeightMap2D () +{ + // TODO Auto-generated destructor stub +} +#endif /* PCL_PEOPLE_HEIGHT_MAP_2D_HPP_ */ diff --git a/pcl-1.7/pcl/people/impl/person_classifier.hpp b/pcl-1.7/pcl/people/impl/person_classifier.hpp new file mode 100644 index 0000000..970dcba --- /dev/null +++ b/pcl-1.7/pcl/people/impl/person_classifier.hpp @@ -0,0 +1,313 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * person_classifier.hpp + * Created on: Nov 30, 2012 + * Author: Matteo Munaro + */ + +#include + +#ifndef PCL_PEOPLE_PERSON_CLASSIFIER_HPP_ +#define PCL_PEOPLE_PERSON_CLASSIFIER_HPP_ + +template +pcl::people::PersonClassifier::PersonClassifier () {} + +template +pcl::people::PersonClassifier::~PersonClassifier () {} + +template bool +pcl::people::PersonClassifier::loadSVMFromFile (std::string svm_filename) +{ + std::string line; + std::ifstream SVM_file; + SVM_file.open(svm_filename.c_str()); + + getline (SVM_file,line); // read window_height line + size_t tok_pos = line.find_first_of(":", 0); // search for token ":" + window_height_ = std::atoi(line.substr(tok_pos+1, line.npos - tok_pos-1).c_str()); + + getline (SVM_file,line); // read window_width line + tok_pos = line.find_first_of(":", 0); // search for token ":" + window_width_ = std::atoi(line.substr(tok_pos+1, line.npos - tok_pos-1).c_str()); + + getline (SVM_file,line); // read SVM_offset line + tok_pos = line.find_first_of(":", 0); // search for token ":" + SVM_offset_ = std::atof(line.substr(tok_pos+1, line.npos - tok_pos-1).c_str()); + + getline (SVM_file,line); // read SVM_weights line + tok_pos = line.find_first_of("[", 0); // search for token "[" + size_t tok_end_pos = line.find_first_of("]", 0); // search for token "]" , end of SVM weights + size_t prev_tok_pos; + while (tok_pos < tok_end_pos) // while end of SVM_weights is not reached + { + prev_tok_pos = tok_pos; + tok_pos = line.find_first_of(",", prev_tok_pos+1); // search for token "," + SVM_weights_.push_back(std::atof(line.substr(prev_tok_pos+1, tok_pos-prev_tok_pos-1).c_str())); + } + SVM_file.close(); + + if (SVM_weights_.size() == 0) + { + PCL_ERROR ("[pcl::people::PersonClassifier::loadSVMFromFile] Invalid SVM file!\n"); + return (false); + } + else + { + return (true); + } +} + +template void +pcl::people::PersonClassifier::setSVM (int window_height, int window_width, std::vector SVM_weights, float SVM_offset) +{ + window_height_ = window_height; + window_width_ = window_width; + SVM_weights_ = SVM_weights; + SVM_offset_ = SVM_offset; +} + +template void +pcl::people::PersonClassifier::getSVM (int& window_height, int& window_width, std::vector& SVM_weights, float& SVM_offset) +{ + window_height = window_height_; + window_width = window_width_; + SVM_weights = SVM_weights_; + SVM_offset = SVM_offset_; +} + +template void +pcl::people::PersonClassifier::resize (PointCloudPtr& input_image, + PointCloudPtr& output_image, + int width, + int height) +{ + PointT new_point; + new_point.r = 0; + new_point.g = 0; + new_point.b = 0; + + // Allocate the vector of points: + output_image->points.resize(width*height, new_point); + output_image->height = height; + output_image->width = width; + + // Compute scale factor: + float scale1 = float(height) / float(input_image->height); + float scale2 = float(width) / float(input_image->width); + + Eigen::Matrix3f T_inv; + T_inv << 1/scale1, 0, 0, + 0, 1/scale2, 0, + 0, 0, 1; + + Eigen::Vector3f A; + int c1, c2, f1, f2; + PointT g1, g2, g3, g4; + float w1, w2; + for (int i = 0; i < height; i++) // for every row + { + for (int j = 0; j < width; j++) // for every column + { + A = T_inv * Eigen::Vector3f(i, j, 1); + c1 = ceil(A(0)); + f1 = floor(A(0)); + c2 = ceil(A(1)); + f2 = floor(A(1)); + + if ( (f1 < 0) || + (c1 < 0) || + (f1 >= static_cast (input_image->height)) || + (c1 >= static_cast (input_image->height)) || + (f2 < 0) || + (c2 < 0) || + (f2 >= static_cast (input_image->width)) || + (c2 >= static_cast (input_image->width))) + { // if out of range, continue + continue; + } + + g1 = (*input_image)(f2, c1); + g3 = (*input_image)(f2, f1); + g4 = (*input_image)(c2, f1); + g2 = (*input_image)(c2, c1); + + w1 = (A(0) - f1); + w2 = (A(1) - f2); + new_point.r = int((1 - w1) * ((1 - w2) * g1.r + w2 * g4.r) + w1 * ((1 - w2) * g3.r + w2 * g4.r)); + new_point.g = int((1 - w1) * ((1 - w2) * g1.g + w2 * g4.g) + w1 * ((1 - w2) * g3.g + w2 * g4.g)); + new_point.b = int((1 - w1) * ((1 - w2) * g1.b + w2 * g4.b) + w1 * ((1 - w2) * g3.b + w2 * g4.b)); + + // Insert the point in the output image: + (*output_image)(j,i) = new_point; + } + } +} + +template void +pcl::people::PersonClassifier::copyMakeBorder (PointCloudPtr& input_image, + PointCloudPtr& output_image, + int xmin, + int ymin, + int width, + int height) +{ + PointT black_point; + black_point.r = 0; + black_point.g = 0; + black_point.b = 0; + output_image->points.resize(height*width, black_point); + output_image->width = width; + output_image->height = height; + + int x_start_in = std::max(0, xmin); + int x_end_in = std::min(int(input_image->width-1), xmin+width-1); + int y_start_in = std::max(0, ymin); + int y_end_in = std::min(int(input_image->height-1), ymin+height-1); + + int x_start_out = std::max(0, -xmin); + //int x_end_out = x_start_out + (x_end_in - x_start_in); + int y_start_out = std::max(0, -ymin); + //int y_end_out = y_start_out + (y_end_in - y_start_in); + + for (int i = 0; i < (y_end_in - y_start_in + 1); i++) + { + for (int j = 0; j < (x_end_in - x_start_in + 1); j++) + { + (*output_image)(x_start_out + j, y_start_out + i) = (*input_image)(x_start_in + j, y_start_in + i); + } + } +} + +template double +pcl::people::PersonClassifier::evaluate (float height_person, + float xc, + float yc, + PointCloudPtr& image) +{ + if (SVM_weights_.size() == 0) + { + PCL_ERROR ("[pcl::people::PersonClassifier::evaluate] SVM has not been set!\n"); + return (-1000); + } + + int height = floor((height_person * window_height_) / (0.75 * window_height_) + 0.5); // floor(i+0.5) = round(i) + int width = floor((height_person * window_width_) / (0.75 * window_height_) + 0.5); + int xmin = floor(xc - width / 2 + 0.5); + int ymin = floor(yc - height / 2 + 0.5); + double confidence; + + if (height > 0) + { + // If near the border, fill with black: + PointCloudPtr box(new PointCloud); + copyMakeBorder(image, box, xmin, ymin, width, height); + + // Make the image match the correct size (used in the training stage): + PointCloudPtr sample(new PointCloud); + resize(box, sample, window_width_, window_height_); + + // Convert the image to array of float: + float* sample_float = new float[sample->width * sample->height * 3]; + int delta = sample->height * sample->width; + for (uint32_t row = 0; row < sample->height; row++) + { + for (uint32_t col = 0; col < sample->width; col++) + { + sample_float[row + sample->height * col] = ((float) ((*sample)(col, row).r))/255; //ptr[col * 3 + 2]; + sample_float[row + sample->height * col + delta] = ((float) ((*sample)(col, row).g))/255; //ptr[col * 3 + 1]; + sample_float[row + sample->height * col + delta * 2] = (float) (((*sample)(col, row).b))/255; //ptr[col * 3]; + } + } + + // Calculate HOG descriptor: + pcl::people::HOG hog; + float *descriptor = (float*) calloc(SVM_weights_.size(), sizeof(float)); + hog.compute(sample_float, descriptor); + + // Calculate confidence value by dot product: + confidence = 0.0; + for(unsigned int i = 0; i < SVM_weights_.size(); i++) + { + confidence += SVM_weights_[i] * descriptor[i]; + } + // Confidence correction: + confidence -= SVM_offset_; + + delete[] descriptor; + delete[] sample_float; + } + else + { + confidence = std::numeric_limits::quiet_NaN(); + } + + return confidence; +} + +template double +pcl::people::PersonClassifier::evaluate (PointCloudPtr& image, + Eigen::Vector3f& bottom, + Eigen::Vector3f& top, + Eigen::Vector3f& centroid, + bool vertical) +{ + float pixel_height; + float pixel_width; + + if (!vertical) + { + pixel_height = bottom(1) - top(1); + pixel_width = pixel_height / 2.0f; + } + else + { + pixel_width = top(0) - bottom(0); + pixel_height = pixel_width / 2.0f; + } + float pixel_xc = centroid(0); + float pixel_yc = centroid(1); + + if (!vertical) + { + return (evaluate(pixel_height, pixel_xc, pixel_yc, image)); + } + else + { + return (evaluate(pixel_width, pixel_yc, image->height-pixel_xc+1, image)); + } +} +#endif /* PCL_PEOPLE_PERSON_CLASSIFIER_HPP_ */ diff --git a/pcl-1.7/pcl/people/impl/person_cluster.hpp b/pcl-1.7/pcl/people/impl/person_cluster.hpp new file mode 100644 index 0000000..a958396 --- /dev/null +++ b/pcl-1.7/pcl/people/impl/person_cluster.hpp @@ -0,0 +1,433 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * person_cluster.hpp + * Created on: Nov 30, 2012 + * Author: Matteo Munaro + */ + +#ifndef PCL_PEOPLE_PERSON_CLUSTER_HPP_ +#define PCL_PEOPLE_PERSON_CLUSTER_HPP_ + +#include + +template +pcl::people::PersonCluster::PersonCluster ( + const PointCloudPtr& input_cloud, + const pcl::PointIndices& indices, + const Eigen::VectorXf& ground_coeffs, + float sqrt_ground_coeffs, + bool head_centroid, + bool vertical) + { + init(input_cloud, indices, ground_coeffs, sqrt_ground_coeffs, head_centroid, vertical); + } + +template void +pcl::people::PersonCluster::init ( + const PointCloudPtr& input_cloud, + const pcl::PointIndices& indices, + const Eigen::VectorXf& ground_coeffs, + float sqrt_ground_coeffs, + bool head_centroid, + bool vertical) +{ + + vertical_ = vertical; + head_centroid_ = head_centroid; + person_confidence_ = std::numeric_limits::quiet_NaN(); + + min_x_ = 1000.0f; + min_y_ = 1000.0f; + min_z_ = 1000.0f; + + max_x_ = -1000.0f; + max_y_ = -1000.0f; + max_z_ = -1000.0f; + + sum_x_ = 0.0f; + sum_y_ = 0.0f; + sum_z_ = 0.0f; + + n_ = 0; + + points_indices_.indices = indices.indices; + + for (std::vector::const_iterator pit = points_indices_.indices.begin(); pit != points_indices_.indices.end(); pit++) + { + PointT* p = &input_cloud->points[*pit]; + + min_x_ = std::min(p->x, min_x_); + max_x_ = std::max(p->x, max_x_); + sum_x_ += p->x; + + min_y_ = std::min(p->y, min_y_); + max_y_ = std::max(p->y, max_y_); + sum_y_ += p->y; + + min_z_ = std::min(p->z, min_z_); + max_z_ = std::max(p->z, max_z_); + sum_z_ += p->z; + + n_++; + } + + c_x_ = sum_x_ / n_; + c_y_ = sum_y_ / n_; + c_z_ = sum_z_ / n_; + + + Eigen::Vector4f height_point(c_x_, c_y_, c_z_, 1.0f); + if(!vertical_) + { + height_point(1) = min_y_; + distance_ = std::sqrt(c_x_ * c_x_ + c_z_ * c_z_); + } + else + { + height_point(0) = max_x_; + distance_ = std::sqrt(c_y_ * c_y_ + c_z_ * c_z_); + } + + float height = std::fabs(height_point.dot(ground_coeffs)); + height /= sqrt_ground_coeffs; + height_ = height; + + if(head_centroid_) + { + float sum_x = 0.0f; + float sum_y = 0.0f; + float sum_z = 0.0f; + int n = 0; + + float head_threshold_value; // vertical coordinate of the lowest head point + if (!vertical_) + { + head_threshold_value = min_y_ + height_ / 8.0f; // head is suppose to be 1/8 of the human height + for (std::vector::const_iterator pit = points_indices_.indices.begin(); pit != points_indices_.indices.end(); pit++) + { + PointT* p = &input_cloud->points[*pit]; + + if(p->y < head_threshold_value) + { + sum_x += p->x; + sum_y += p->y; + sum_z += p->z; + n++; + } + } + } + else + { + head_threshold_value = max_x_ - height_ / 8.0f; // head is suppose to be 1/8 of the human height + for (std::vector::const_iterator pit = points_indices_.indices.begin(); pit != points_indices_.indices.end(); pit++) + { + PointT* p = &input_cloud->points[*pit]; + + if(p->x > head_threshold_value) + { + sum_x += p->x; + sum_y += p->y; + sum_z += p->z; + n++; + } + } + } + + c_x_ = sum_x / n; + c_y_ = sum_y / n; + c_z_ = sum_z / n; + } + + if(!vertical_) + { + float min_x = c_x_; + float min_z = c_z_; + float max_x = c_x_; + float max_z = c_z_; + for (std::vector::const_iterator pit = points_indices_.indices.begin(); pit != points_indices_.indices.end(); pit++) + { + PointT* p = &input_cloud->points[*pit]; + + min_x = std::min(p->x, min_x); + max_x = std::max(p->x, max_x); + min_z = std::min(p->z, min_z); + max_z = std::max(p->z, max_z); + } + + angle_ = std::atan2(c_z_, c_x_); + angle_max_ = std::max(std::atan2(min_z, min_x), std::atan2(max_z, min_x)); + angle_min_ = std::min(std::atan2(min_z, max_x), std::atan2(max_z, max_x)); + + Eigen::Vector4f c_point(c_x_, c_y_, c_z_, 1.0f); + float t = c_point.dot(ground_coeffs) / std::pow(sqrt_ground_coeffs, 2); + float bottom_x = c_x_ - ground_coeffs(0) * t; + float bottom_y = c_y_ - ground_coeffs(1) * t; + float bottom_z = c_z_ - ground_coeffs(2) * t; + + tbottom_ = Eigen::Vector3f(bottom_x, bottom_y, bottom_z); + Eigen::Vector3f v = Eigen::Vector3f(c_x_, c_y_, c_z_) - tbottom_; + + ttop_ = v * height / v.norm() + tbottom_; + tcenter_ = v * height * 0.5 / v.norm() + tbottom_; + top_ = Eigen::Vector3f(c_x_, min_y_, c_z_); + bottom_ = Eigen::Vector3f(c_x_, max_y_, c_z_); + center_ = Eigen::Vector3f(c_x_, c_y_, c_z_); + + min_ = Eigen::Vector3f(min_x_, min_y_, min_z_); + + max_ = Eigen::Vector3f(max_x_, max_y_, max_z_); + } + else + { + float min_y = c_y_; + float min_z = c_z_; + float max_y = c_y_; + float max_z = c_z_; + for (std::vector::const_iterator pit = points_indices_.indices.begin(); pit != points_indices_.indices.end(); pit++) + { + PointT* p = &input_cloud->points[*pit]; + + min_y = std::min(p->y, min_y); + max_y = std::max(p->y, max_y); + min_z = std::min(p->z, min_z); + max_z = std::max(p->z, max_z); + } + + angle_ = std::atan2(c_z_, c_y_); + angle_max_ = std::max(std::atan2(min_z_, min_y_), std::atan2(max_z_, min_y_)); + angle_min_ = std::min(std::atan2(min_z_, max_y_), std::atan2(max_z_, max_y_)); + + Eigen::Vector4f c_point(c_x_, c_y_, c_z_, 1.0f); + float t = c_point.dot(ground_coeffs) / std::pow(sqrt_ground_coeffs, 2); + float bottom_x = c_x_ - ground_coeffs(0) * t; + float bottom_y = c_y_ - ground_coeffs(1) * t; + float bottom_z = c_z_ - ground_coeffs(2) * t; + + tbottom_ = Eigen::Vector3f(bottom_x, bottom_y, bottom_z); + Eigen::Vector3f v = Eigen::Vector3f(c_x_, c_y_, c_z_) - tbottom_; + + ttop_ = v * height / v.norm() + tbottom_; + tcenter_ = v * height * 0.5 / v.norm() + tbottom_; + top_ = Eigen::Vector3f(max_x_, c_y_, c_z_); + bottom_ = Eigen::Vector3f(min_x_, c_y_, c_z_); + center_ = Eigen::Vector3f(c_x_, c_y_, c_z_); + + min_ = Eigen::Vector3f(min_x_, min_y_, min_z_); + + max_ = Eigen::Vector3f(max_x_, max_y_, max_z_); + } +} + +template pcl::PointIndices& +pcl::people::PersonCluster::getIndices () +{ + return (points_indices_); +} + +template float +pcl::people::PersonCluster::getHeight () +{ + return (height_); +} + +template float +pcl::people::PersonCluster::updateHeight (const Eigen::VectorXf& ground_coeffs) +{ + float sqrt_ground_coeffs = (ground_coeffs - Eigen::Vector4f(0.0f, 0.0f, 0.0f, ground_coeffs(3))).norm(); + return (updateHeight(ground_coeffs, sqrt_ground_coeffs)); +} + +template float +pcl::people::PersonCluster::updateHeight (const Eigen::VectorXf& ground_coeffs, float sqrt_ground_coeffs) +{ + Eigen::Vector4f height_point; + if (!vertical_) + height_point << c_x_, min_y_, c_z_, 1.0f; + else + height_point << max_x_, c_y_, c_z_, 1.0f; + + float height = std::fabs(height_point.dot(ground_coeffs)); + height /= sqrt_ground_coeffs; + height_ = height; + return (height_); +} + +template float +pcl::people::PersonCluster::getDistance () +{ + return (distance_); +} + +template Eigen::Vector3f& +pcl::people::PersonCluster::getTTop () +{ + return (ttop_); +} + +template Eigen::Vector3f& +pcl::people::PersonCluster::getTBottom () +{ + return (tbottom_); +} + +template Eigen::Vector3f& +pcl::people::PersonCluster::getTCenter () +{ + return (tcenter_); +} + +template Eigen::Vector3f& +pcl::people::PersonCluster::getTop () +{ + return (top_); +} + +template Eigen::Vector3f& +pcl::people::PersonCluster::getBottom () +{ + return (bottom_); +} + +template Eigen::Vector3f& +pcl::people::PersonCluster::getCenter () +{ + return (center_); +} + +template Eigen::Vector3f& +pcl::people::PersonCluster::getMin () +{ + return (min_); +} + +template Eigen::Vector3f& +pcl::people::PersonCluster::getMax () +{ + return (max_); +} + +template float +pcl::people::PersonCluster::getAngle () +{ + return (angle_); +} + +template +float pcl::people::PersonCluster::getAngleMax () +{ + return (angle_max_); +} + +template +float pcl::people::PersonCluster::getAngleMin () +{ + return (angle_min_); +} + +template +int pcl::people::PersonCluster::getNumberPoints () +{ + return (n_); +} + +template +float pcl::people::PersonCluster::getPersonConfidence () +{ + return (person_confidence_); +} + +template +void pcl::people::PersonCluster::setPersonConfidence (float confidence) +{ + person_confidence_ = confidence; +} + +template +void pcl::people::PersonCluster::setHeight (float height) +{ + height_ = height; +} + +template +void pcl::people::PersonCluster::drawTBoundingBox (pcl::visualization::PCLVisualizer& viewer, int person_number) +{ + // draw theoretical person bounding box in the PCL viewer: + pcl::ModelCoefficients coeffs; + // translation + coeffs.values.push_back (tcenter_[0]); + coeffs.values.push_back (tcenter_[1]); + coeffs.values.push_back (tcenter_[2]); + // rotation + coeffs.values.push_back (0.0); + coeffs.values.push_back (0.0); + coeffs.values.push_back (0.0); + coeffs.values.push_back (1.0); + // size + if (vertical_) + { + coeffs.values.push_back (height_); + coeffs.values.push_back (0.5); + coeffs.values.push_back (0.5); + } + else + { + coeffs.values.push_back (0.5); + coeffs.values.push_back (height_); + coeffs.values.push_back (0.5); + } + + std::stringstream bbox_name; + bbox_name << "bbox_person_" << person_number; + viewer.removeShape (bbox_name.str()); + viewer.addCube (coeffs, bbox_name.str()); + viewer.setShapeRenderingProperties (pcl::visualization::PCL_VISUALIZER_COLOR, 0.0, 1.0, 0.0, bbox_name.str()); + viewer.setShapeRenderingProperties (pcl::visualization::PCL_VISUALIZER_LINE_WIDTH, 2, bbox_name.str()); + + // std::stringstream confid; + // confid << person_confidence_; + // PointT position; + // position.x = tcenter_[0]- 0.2; + // position.y = ttop_[1]; + // position.z = tcenter_[2]; + // viewer.addText3D(confid.str().substr(0, 4), position, 0.1); +} + +template +pcl::people::PersonCluster::~PersonCluster () +{ + // Auto-generated destructor stub +} +#endif /* PCL_PEOPLE_PERSON_CLUSTER_HPP_ */ diff --git a/pcl-1.7/pcl/people/person_classifier.h b/pcl-1.7/pcl/people/person_classifier.h new file mode 100644 index 0000000..910b46f --- /dev/null +++ b/pcl-1.7/pcl/people/person_classifier.h @@ -0,0 +1,167 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * person_classifier.h + * Created on: Nov 30, 2012 + * Author: Matteo Munaro + */ + +#ifndef PCL_PEOPLE_PERSON_CLASSIFIER_H_ +#define PCL_PEOPLE_PERSON_CLASSIFIER_H_ + +#include +#include + +namespace pcl +{ + namespace people + { + template class PersonClassifier; + + template + class PersonClassifier + { + protected: + + /** \brief Height of the image patch to classify. */ + int window_height_; + + /** \brief Width of the image patch to classify. */ + int window_width_; + + /** \brief SVM offset. */ + float SVM_offset_; + + /** \brief SVM weights vector. */ + std::vector SVM_weights_; + + public: + + typedef pcl::PointCloud PointCloud; + typedef boost::shared_ptr PointCloudPtr; + + /** \brief Constructor. */ + PersonClassifier (); + + /** \brief Destructor. */ + virtual ~PersonClassifier (); + + /** \brief Load SVM parameters from a text file. + * + * \param[in] svm_filename Filename containing SVM parameters. + * + * \return true if SVM has been correctly set, false otherwise. + */ + bool + loadSVMFromFile (std::string svm_filename); + + /** + * \brief Set trained SVM for person confidence estimation. + * + * \param[in] window_height Detection window height. + * \param[in] window_width Detection window width. + * \param[in] SVM_weights SVM weights vector. + * \param[in] SVM_offset SVM offset. + */ + void + setSVM (int window_height, int window_width, std::vector SVM_weights, float SVM_offset); + + /** + * \brief Get trained SVM for person confidence estimation. + * + * \param[out] window_height Detection window height. + * \param[out] window_width Detection window width. + * \param[out] SVM_weights SVM weights vector. + * \param[out] SVM_offset SVM offset. + */ + void + getSVM (int& window_height, int& window_width, std::vector& SVM_weights, float& SVM_offset); + + /** + * \brief Resize an image represented by a pointcloud containing RGB information. + * + * \param[in] input_image A pointer to a pointcloud containing RGB information. + * \param[out] output_image A pointer to the output pointcloud. + * \param[in] width Output width. + * \param[in] height Output height. + */ + void + resize (PointCloudPtr& input_image, PointCloudPtr& output_image, + int width, int height); + + /** + * \brief Copies an image and makes a black border around it, where the source image is not present. + * + * \param[in] input_image A pointer to a pointcloud containing RGB information. + * \param[out] output_image A pointer to the output pointcloud. + * \param[in] xmin x coordinate of the top-left point of the bbox to copy from the input image. + * \param[in] ymin y coordinate of the top-left point of the bbox to copy from the input image. + * \param[in] width Output width. + * \param[in] height Output height. + */ + void + copyMakeBorder (PointCloudPtr& input_image, PointCloudPtr& output_image, + int xmin, int ymin, int width, int height); + + /** + * \brief Classify the given portion of image. + * + * \param[in] height The height of the image patch to classify, in pixels. + * \param[in] xc The x-coordinate of the center of the image patch to classify, in pixels. + * \param[in] yc The y-coordinate of the center of the image patch to classify, in pixels. + * \param[in] image The whole image (pointer to a point cloud containing RGB information) containing the object to classify. + * \return The classification score given by the SVM. + */ + double + evaluate (float height, float xc, float yc, PointCloudPtr& image); + + /** + * \brief Compute person confidence for a given PersonCluster. + * + * \param[in] image The input image (pointer to a point cloud containing RGB information). + * \param[in] bottom Theoretical bottom point of the cluster projected to the image. + * \param[in] top Theoretical top point of the cluster projected to the image. + * \param[in] centroid Theoretical centroid point of the cluster projected to the image. + * \param[in] vertical If true, the sensor is considered to be vertically placed (portrait mode). + * \return The person confidence. + */ + double + evaluate (PointCloudPtr& image, Eigen::Vector3f& bottom, Eigen::Vector3f& top, Eigen::Vector3f& centroid, + bool vertical); + }; + } /* namespace people */ +} /* namespace pcl */ +#include +#endif /* PCL_PEOPLE_PERSON_CLASSIFIER_H_ */ diff --git a/pcl-1.7/pcl/people/person_cluster.h b/pcl-1.7/pcl/people/person_cluster.h new file mode 100644 index 0000000..13d2cbf --- /dev/null +++ b/pcl-1.7/pcl/people/person_cluster.h @@ -0,0 +1,331 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * person_cluster.h + * Created on: Nov 30, 2012 + * Author: Matteo Munaro + */ + +#ifndef PCL_PEOPLE_PERSON_CLUSTER_H_ +#define PCL_PEOPLE_PERSON_CLUSTER_H_ + +#include +#include + +namespace pcl +{ + namespace people + { + /** \brief @b PersonCluster represents a class for representing information about a cluster containing a person. + * \author Filippo Basso, Matteo Munaro + * \ingroup people + */ + template class PersonCluster; + template bool operator<(const PersonCluster& c1, const PersonCluster& c2); + + template + class PersonCluster + { + protected: + + bool head_centroid_; + + /** \brief Minimum x coordinate of the cluster points. */ + float min_x_; + /** \brief Minimum y coordinate of the cluster points. */ + float min_y_; + /** \brief Minimum z coordinate of the cluster points. */ + float min_z_; + + /** \brief Maximum x coordinate of the cluster points. */ + float max_x_; + /** \brief Maximum y coordinate of the cluster points. */ + float max_y_; + /** \brief Maximum z coordinate of the cluster points. */ + float max_z_; + + /** \brief Sum of x coordinates of the cluster points. */ + float sum_x_; + /** \brief Sum of y coordinates of the cluster points. */ + float sum_y_; + /** \brief Sum of z coordinates of the cluster points. */ + float sum_z_; + + /** \brief Number of cluster points. */ + int n_; + + /** \brief x coordinate of the cluster centroid. */ + float c_x_; + /** \brief y coordinate of the cluster centroid. */ + float c_y_; + /** \brief z coordinate of the cluster centroid. */ + float c_z_; + + /** \brief Cluster height from the ground plane. */ + float height_; + + /** \brief Cluster distance from the sensor. */ + float distance_; + /** \brief Cluster centroid horizontal angle with respect to z axis. */ + float angle_; + + /** \brief Maximum angle of the cluster points. */ + float angle_max_; + /** \brief Minimum angle of the cluster points. */ + float angle_min_; + + /** \brief Cluster top point. */ + Eigen::Vector3f top_; + /** \brief Cluster bottom point. */ + Eigen::Vector3f bottom_; + /** \brief Cluster centroid. */ + Eigen::Vector3f center_; + + /** \brief Theoretical cluster top. */ + Eigen::Vector3f ttop_; + /** \brief Theoretical cluster bottom (lying on the ground plane). */ + Eigen::Vector3f tbottom_; + /** \brief Theoretical cluster center (between ttop_ and tbottom_). */ + Eigen::Vector3f tcenter_; + + /** \brief Vector containing the minimum coordinates of the cluster. */ + Eigen::Vector3f min_; + /** \brief Vector containing the maximum coordinates of the cluster. */ + Eigen::Vector3f max_; + + /** \brief Point cloud indices of the cluster points. */ + pcl::PointIndices points_indices_; + + /** \brief If true, the sensor is considered to be vertically placed (portrait mode). */ + bool vertical_; + /** \brief PersonCluster HOG confidence. */ + float person_confidence_; + + public: + + typedef pcl::PointCloud PointCloud; + typedef boost::shared_ptr PointCloudPtr; + typedef boost::shared_ptr PointCloudConstPtr; + + /** \brief Constructor. */ + PersonCluster ( + const PointCloudPtr& input_cloud, + const pcl::PointIndices& indices, + const Eigen::VectorXf& ground_coeffs, + float sqrt_ground_coeffs, + bool head_centroid, + bool vertical = false); + + /** \brief Destructor. */ + virtual ~PersonCluster (); + + /** + * \brief Returns the height of the cluster. + * \return the height of the cluster. + */ + float + getHeight (); + + /** + * \brief Update the height of the cluster. + * \param[in] ground_coeffs The coefficients of the ground plane. + * \return the height of the cluster. + */ + float + updateHeight (const Eigen::VectorXf& ground_coeffs); + + /** + * \brief Update the height of the cluster. + * \param[in] ground_coeffs The coefficients of the ground plane. + * \param[in] sqrt_ground_coeffs The norm of the vector [a, b, c] where a, b and c are the first + * three coefficients of the ground plane (ax + by + cz + d = 0). + * \return the height of the cluster. + */ + float + updateHeight (const Eigen::VectorXf& ground_coeffs, float sqrt_ground_coeffs); + + /** + * \brief Returns the distance of the cluster from the sensor. + * \return the distance of the cluster (its centroid) from the sensor without considering the + * y dimension. + */ + float + getDistance (); + + /** + * \brief Returns the angle formed by the cluster's centroid with respect to the sensor (in radians). + * \return the angle formed by the cluster's centroid with respect to the sensor (in radians). + */ + float + getAngle (); + + /** + * \brief Returns the minimum angle formed by the cluster with respect to the sensor (in radians). + * \return the minimum angle formed by the cluster with respect to the sensor (in radians). + */ + float + getAngleMin (); + + /** + * \brief Returns the maximum angle formed by the cluster with respect to the sensor (in radians). + * \return the maximum angle formed by the cluster with respect to the sensor (in radians). + */ + float + getAngleMax (); + + /** + * \brief Returns the indices of the point cloud points corresponding to the cluster. + * \return the indices of the point cloud points corresponding to the cluster. + */ + pcl::PointIndices& + getIndices (); + + /** + * \brief Returns the theoretical top point. + * \return the theoretical top point. + */ + Eigen::Vector3f& + getTTop (); + + /** + * \brief Returns the theoretical bottom point. + * \return the theoretical bottom point. + */ + Eigen::Vector3f& + getTBottom (); + + /** + * \brief Returns the theoretical centroid (at half height). + * \return the theoretical centroid (at half height). + */ + Eigen::Vector3f& + getTCenter (); + + /** + * \brief Returns the top point. + * \return the top point. + */ + Eigen::Vector3f& + getTop (); + + /** + * \brief Returns the bottom point. + * \return the bottom point. + */ + Eigen::Vector3f& + getBottom (); + + /** + * \brief Returns the centroid. + * \return the centroid. + */ + Eigen::Vector3f& + getCenter (); + + //Eigen::Vector3f& getTMax(); + + /** + * \brief Returns the point formed by min x, min y and min z. + * \return the point formed by min x, min y and min z. + */ + Eigen::Vector3f& + getMin (); + + /** + * \brief Returns the point formed by max x, max y and max z. + * \return the point formed by max x, max y and max z. + */ + Eigen::Vector3f& + getMax (); + + /** + * \brief Returns the HOG confidence. + * \return the HOG confidence. + */ + float + getPersonConfidence (); + + /** + * \brief Returns the number of points of the cluster. + * \return the number of points of the cluster. + */ + int + getNumberPoints (); + + /** + * \brief Sets the cluster height. + * \param[in] height + */ + void + setHeight (float height); + + /** + * \brief Sets the HOG confidence. + * \param[in] confidence + */ + void + setPersonConfidence (float confidence); + + /** + * \brief Draws the theoretical 3D bounding box of the cluster in the PCL visualizer. + * \param[in] viewer PCL visualizer. + * \param[in] person_number progressive number representing the person. + */ + void + drawTBoundingBox (pcl::visualization::PCLVisualizer& viewer, int person_number); + + /** + * \brief For sorting purpose: sort by distance. + */ + friend bool operator< <>(const PersonCluster& c1, const PersonCluster& c2); + + protected: + + /** + * \brief PersonCluster initialization. + */ + void init( + const PointCloudPtr& input_cloud, + const pcl::PointIndices& indices, + const Eigen::VectorXf& ground_coeffs, + float sqrt_ground_coeffs, + bool head_centroid, + bool vertical); + + }; + } /* namespace people */ +} /* namespace pcl */ +#include +#endif /* PCL_PEOPLE_PERSON_CLUSTER_H_ */ diff --git a/pcl-1.7/pcl/point_cloud.h b/pcl-1.7/pcl/point_cloud.h new file mode 100644 index 0000000..12ab7d3 --- /dev/null +++ b/pcl-1.7/pcl/point_cloud.h @@ -0,0 +1,623 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_POINT_CLOUD_H_ +#define PCL_POINT_CLOUD_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace detail + { + struct FieldMapping + { + size_t serialized_offset; + size_t struct_offset; + size_t size; + }; + } // namespace detail + + // Forward declarations + template class PointCloud; + typedef std::vector MsgFieldMap; + + /** \brief Helper functor structure for copying data between an Eigen type and a PointT. */ + template + struct NdCopyEigenPointFunctor + { + typedef typename traits::POD::type Pod; + + /** \brief Constructor + * \param[in] p1 the input Eigen type + * \param[out] p2 the output Point type + */ + NdCopyEigenPointFunctor (const Eigen::VectorXf &p1, PointOutT &p2) + : p1_ (p1), + p2_ (reinterpret_cast(p2)), + f_idx_ (0) { } + + /** \brief Operator. Data copy happens here. */ + template inline void + operator() () + { + //boost::fusion::at_key (p2_) = p1_[f_idx_++]; + typedef typename pcl::traits::datatype::type T; + uint8_t* data_ptr = reinterpret_cast(&p2_) + pcl::traits::offset::value; + *reinterpret_cast(data_ptr) = static_cast (p1_[f_idx_++]); + } + + private: + const Eigen::VectorXf &p1_; + Pod &p2_; + int f_idx_; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + /** \brief Helper functor structure for copying data between an Eigen type and a PointT. */ + template + struct NdCopyPointEigenFunctor + { + typedef typename traits::POD::type Pod; + + /** \brief Constructor + * \param[in] p1 the input Point type + * \param[out] p2 the output Eigen type + */ + NdCopyPointEigenFunctor (const PointInT &p1, Eigen::VectorXf &p2) + : p1_ (reinterpret_cast(p1)), p2_ (p2), f_idx_ (0) { } + + /** \brief Operator. Data copy happens here. */ + template inline void + operator() () + { + //p2_[f_idx_++] = boost::fusion::at_key (p1_); + typedef typename pcl::traits::datatype::type T; + const uint8_t* data_ptr = reinterpret_cast(&p1_) + pcl::traits::offset::value; + p2_[f_idx_++] = static_cast (*reinterpret_cast(data_ptr)); + } + + private: + const Pod &p1_; + Eigen::VectorXf &p2_; + int f_idx_; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + namespace detail + { + template boost::shared_ptr& + getMapping (pcl::PointCloud& p); + } // namespace detail + + /** \brief PointCloud represents the base class in PCL for storing collections of 3D points. + * + * The class is templated, which means you need to specify the type of data + * that it should contain. For example, to create a point cloud that holds 4 + * random XYZ data points, use: + * + * \code + * pcl::PointCloud cloud; + * cloud.push_back (pcl::PointXYZ (rand (), rand (), rand ())); + * cloud.push_back (pcl::PointXYZ (rand (), rand (), rand ())); + * cloud.push_back (pcl::PointXYZ (rand (), rand (), rand ())); + * cloud.push_back (pcl::PointXYZ (rand (), rand (), rand ())); + * \endcode + * + * The PointCloud class contains the following elements: + * - \b width - specifies the width of the point cloud dataset in the number of points. WIDTH has two meanings: + * - it can specify the total number of points in the cloud (equal with POINTS see below) for unorganized datasets; + * - it can specify the width (total number of points in a row) of an organized point cloud dataset. + * \a Mandatory. + * - \b height - specifies the height of the point cloud dataset in the number of points. HEIGHT has two meanings: + * - it can specify the height (total number of rows) of an organized point cloud dataset; + * - it is set to 1 for unorganized datasets (thus used to check whether a dataset is organized or not). + * \a Mandatory. + * - \b points - the data array where all points of type PointT are stored. \a Mandatory. + * + * - \b is_dense - specifies if all the data in points is finite (true), or whether it might contain Inf/NaN values + * (false). \a Mandatory. + * + * - \b sensor_origin_ - specifies the sensor acquisition pose (origin/translation). \a Optional. + * - \b sensor_orientation_ - specifies the sensor acquisition pose (rotation). \a Optional. + * + * \author Patrick Mihelich, Radu B. Rusu + */ + template + class PointCloud + { + public: + /** \brief Default constructor. Sets \ref is_dense to true, \ref width + * and \ref height to 0, and the \ref sensor_origin_ and \ref + * sensor_orientation_ to identity. + */ + PointCloud () : + header (), points (), width (0), height (0), is_dense (true), + sensor_origin_ (Eigen::Vector4f::Zero ()), sensor_orientation_ (Eigen::Quaternionf::Identity ()), + mapping_ () + {} + + /** \brief Copy constructor (needed by compilers such as Intel C++) + * \param[in] pc the cloud to copy into this + */ + PointCloud (PointCloud &pc) : + header (), points (), width (0), height (0), is_dense (true), + sensor_origin_ (Eigen::Vector4f::Zero ()), sensor_orientation_ (Eigen::Quaternionf::Identity ()), + mapping_ () + { + *this = pc; + } + + /** \brief Copy constructor (needed by compilers such as Intel C++) + * \param[in] pc the cloud to copy into this + */ + PointCloud (const PointCloud &pc) : + header (), points (), width (0), height (0), is_dense (true), + sensor_origin_ (Eigen::Vector4f::Zero ()), sensor_orientation_ (Eigen::Quaternionf::Identity ()), + mapping_ () + { + *this = pc; + } + + /** \brief Copy constructor from point cloud subset + * \param[in] pc the cloud to copy into this + * \param[in] indices the subset to copy + */ + PointCloud (const PointCloud &pc, + const std::vector &indices) : + header (pc.header), points (indices.size ()), width (indices.size ()), height (1), is_dense (pc.is_dense), + sensor_origin_ (pc.sensor_origin_), sensor_orientation_ (pc.sensor_orientation_), + mapping_ () + { + // Copy the obvious + assert (indices.size () <= pc.size ()); + for (size_t i = 0; i < indices.size (); i++) + points[i] = pc.points[indices[i]]; + } + + /** \brief Allocate constructor from point cloud subset + * \param[in] width_ the cloud width + * \param[in] height_ the cloud height + * \param[in] value_ default value + */ + PointCloud (uint32_t width_, uint32_t height_, const PointT& value_ = PointT ()) + : header () + , points (width_ * height_, value_) + , width (width_) + , height (height_) + , is_dense (true) + , sensor_origin_ (Eigen::Vector4f::Zero ()) + , sensor_orientation_ (Eigen::Quaternionf::Identity ()) + , mapping_ () + {} + + /** \brief Destructor. */ + virtual ~PointCloud () {} + + /** \brief Add a point cloud to the current cloud. + * \param[in] rhs the cloud to add to the current cloud + * \return the new cloud as a concatenation of the current cloud and the new given cloud + */ + inline PointCloud& + operator += (const PointCloud& rhs) + { + // Make the resultant point cloud take the newest stamp + if (rhs.header.stamp > header.stamp) + header.stamp = rhs.header.stamp; + + size_t nr_points = points.size (); + points.resize (nr_points + rhs.points.size ()); + for (size_t i = nr_points; i < points.size (); ++i) + points[i] = rhs.points[i - nr_points]; + + width = static_cast(points.size ()); + height = 1; + if (rhs.is_dense && is_dense) + is_dense = true; + else + is_dense = false; + return (*this); + } + + /** \brief Add a point cloud to another cloud. + * \param[in] rhs the cloud to add to the current cloud + * \return the new cloud as a concatenation of the current cloud and the new given cloud + */ + inline const PointCloud + operator + (const PointCloud& rhs) + { + return (PointCloud (*this) += rhs); + } + + /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized + * datasets (those that have height != 1). + * \param[in] column the column coordinate + * \param[in] row the row coordinate + */ + inline const PointT& + at (int column, int row) const + { + if (this->height > 1) + return (points.at (row * this->width + column)); + else + throw IsNotDenseException ("Can't use 2D indexing with a unorganized point cloud"); + } + + /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized + * datasets (those that have height != 1). + * \param[in] column the column coordinate + * \param[in] row the row coordinate + */ + inline PointT& + at (int column, int row) + { + if (this->height > 1) + return (points.at (row * this->width + column)); + else + throw IsNotDenseException ("Can't use 2D indexing with a unorganized point cloud"); + } + + /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized + * datasets (those that have height != 1). + * \param[in] column the column coordinate + * \param[in] row the row coordinate + */ + inline const PointT& + operator () (size_t column, size_t row) const + { + return (points[row * this->width + column]); + } + + /** \brief Obtain the point given by the (column, row) coordinates. Only works on organized + * datasets (those that have height != 1). + * \param[in] column the column coordinate + * \param[in] row the row coordinate + */ + inline PointT& + operator () (size_t column, size_t row) + { + return (points[row * this->width + column]); + } + + /** \brief Return whether a dataset is organized (e.g., arranged in a structured grid). + * \note The height value must be different than 1 for a dataset to be organized. + */ + inline bool + isOrganized () const + { + return (height > 1); + } + + /** \brief Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud. + * \anchor getMatrixXfMap + * \note This method is for advanced users only! Use with care! + * + * \attention Since 1.4.0, Eigen matrices are forced to Row Major to increase the efficiency of the algorithms in PCL + * This means that the behavior of getMatrixXfMap changed, and is now correctly mapping 1-1 with a PointCloud structure, + * that is: number of points in a cloud = rows in a matrix, number of point dimensions = columns in a matrix + * + * \param[in] dim the number of dimensions to consider for each point + * \param[in] stride the number of values in each point (will be the number of values that separate two of the columns) + * \param[in] offset the number of dimensions to skip from the beginning of each point + * (stride = offset + dim + x, where x is the number of dimensions to skip from the end of each point) + * \note for getting only XYZ coordinates out of PointXYZ use dim=3, stride=4 and offset=0 due to the alignment. + * \attention PointT types are most of the time aligned, so the offsets are not continuous! + */ + inline Eigen::Map > + getMatrixXfMap (int dim, int stride, int offset) + { + if (Eigen::MatrixXf::Flags & Eigen::RowMajorBit) + return (Eigen::Map >(reinterpret_cast(&points[0])+offset, points.size (), dim, Eigen::OuterStride<> (stride))); + else + return (Eigen::Map >(reinterpret_cast(&points[0])+offset, dim, points.size (), Eigen::OuterStride<> (stride))); + } + + /** \brief Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud. + * \anchor getMatrixXfMap + * \note This method is for advanced users only! Use with care! + * + * \attention Since 1.4.0, Eigen matrices are forced to Row Major to increase the efficiency of the algorithms in PCL + * This means that the behavior of getMatrixXfMap changed, and is now correctly mapping 1-1 with a PointCloud structure, + * that is: number of points in a cloud = rows in a matrix, number of point dimensions = columns in a matrix + * + * \param[in] dim the number of dimensions to consider for each point + * \param[in] stride the number of values in each point (will be the number of values that separate two of the columns) + * \param[in] offset the number of dimensions to skip from the beginning of each point + * (stride = offset + dim + x, where x is the number of dimensions to skip from the end of each point) + * \note for getting only XYZ coordinates out of PointXYZ use dim=3, stride=4 and offset=0 due to the alignment. + * \attention PointT types are most of the time aligned, so the offsets are not continuous! + */ + inline const Eigen::Map > + getMatrixXfMap (int dim, int stride, int offset) const + { + if (Eigen::MatrixXf::Flags & Eigen::RowMajorBit) + return (Eigen::Map >(reinterpret_cast(const_cast(&points[0]))+offset, points.size (), dim, Eigen::OuterStride<> (stride))); + else + return (Eigen::Map >(reinterpret_cast(const_cast(&points[0]))+offset, dim, points.size (), Eigen::OuterStride<> (stride))); + } + + /** \brief Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud. + * \note This method is for advanced users only! Use with care! + * \attention PointT types are most of the time aligned, so the offsets are not continuous! + * See \ref getMatrixXfMap for more information. + */ + inline Eigen::Map > + getMatrixXfMap () + { + return (getMatrixXfMap (sizeof (PointT) / sizeof (float), sizeof (PointT) / sizeof (float), 0)); + } + + /** \brief Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud. + * \note This method is for advanced users only! Use with care! + * \attention PointT types are most of the time aligned, so the offsets are not continuous! + * See \ref getMatrixXfMap for more information. + */ + inline const Eigen::Map > + getMatrixXfMap () const + { + return (getMatrixXfMap (sizeof (PointT) / sizeof (float), sizeof (PointT) / sizeof (float), 0)); + } + + /** \brief The point cloud header. It contains information about the acquisition time. */ + pcl::PCLHeader header; + + /** \brief The point data. */ + std::vector > points; + + /** \brief The point cloud width (if organized as an image-structure). */ + uint32_t width; + /** \brief The point cloud height (if organized as an image-structure). */ + uint32_t height; + + /** \brief True if no points are invalid (e.g., have NaN or Inf values). */ + bool is_dense; + + /** \brief Sensor acquisition pose (origin/translation). */ + Eigen::Vector4f sensor_origin_; + /** \brief Sensor acquisition pose (rotation). */ + Eigen::Quaternionf sensor_orientation_; + + typedef PointT PointType; // Make the template class available from the outside + typedef std::vector > VectorType; + typedef std::vector, Eigen::aligned_allocator > > CloudVectorType; + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + // iterators + typedef typename VectorType::iterator iterator; + typedef typename VectorType::const_iterator const_iterator; + inline iterator begin () { return (points.begin ()); } + inline iterator end () { return (points.end ()); } + inline const_iterator begin () const { return (points.begin ()); } + inline const_iterator end () const { return (points.end ()); } + + //capacity + inline size_t size () const { return (points.size ()); } + inline void reserve (size_t n) { points.reserve (n); } + inline bool empty () const { return points.empty (); } + + /** \brief Resize the cloud + * \param[in] n the new cloud size + */ + inline void resize (size_t n) + { + points.resize (n); + if (width * height != n) + { + width = static_cast (n); + height = 1; + } + } + + //element access + inline const PointT& operator[] (size_t n) const { return (points[n]); } + inline PointT& operator[] (size_t n) { return (points[n]); } + inline const PointT& at (size_t n) const { return (points.at (n)); } + inline PointT& at (size_t n) { return (points.at (n)); } + inline const PointT& front () const { return (points.front ()); } + inline PointT& front () { return (points.front ()); } + inline const PointT& back () const { return (points.back ()); } + inline PointT& back () { return (points.back ()); } + + /** \brief Insert a new point in the cloud, at the end of the container. + * \note This breaks the organized structure of the cloud by setting the height to 1! + * \param[in] pt the point to insert + */ + inline void + push_back (const PointT& pt) + { + points.push_back (pt); + width = static_cast (points.size ()); + height = 1; + } + + /** \brief Insert a new point in the cloud, given an iterator. + * \note This breaks the organized structure of the cloud by setting the height to 1! + * \param[in] position where to insert the point + * \param[in] pt the point to insert + * \return returns the new position iterator + */ + inline iterator + insert (iterator position, const PointT& pt) + { + iterator it = points.insert (position, pt); + width = static_cast (points.size ()); + height = 1; + return (it); + } + + /** \brief Insert a new point in the cloud N times, given an iterator. + * \note This breaks the organized structure of the cloud by setting the height to 1! + * \param[in] position where to insert the point + * \param[in] n the number of times to insert the point + * \param[in] pt the point to insert + */ + inline void + insert (iterator position, size_t n, const PointT& pt) + { + points.insert (position, n, pt); + width = static_cast (points.size ()); + height = 1; + } + + /** \brief Insert a new range of points in the cloud, at a certain position. + * \note This breaks the organized structure of the cloud by setting the height to 1! + * \param[in] position where to insert the data + * \param[in] first where to start inserting the points from + * \param[in] last where to stop inserting the points from + */ + template inline void + insert (iterator position, InputIterator first, InputIterator last) + { + points.insert (position, first, last); + width = static_cast (points.size ()); + height = 1; + } + + /** \brief Erase a point in the cloud. + * \note This breaks the organized structure of the cloud by setting the height to 1! + * \param[in] position what data point to erase + * \return returns the new position iterator + */ + inline iterator + erase (iterator position) + { + iterator it = points.erase (position); + width = static_cast (points.size ()); + height = 1; + return (it); + } + + /** \brief Erase a set of points given by a (first, last) iterator pair + * \note This breaks the organized structure of the cloud by setting the height to 1! + * \param[in] first where to start erasing points from + * \param[in] last where to stop erasing points from + * \return returns the new position iterator + */ + inline iterator + erase (iterator first, iterator last) + { + iterator it = points.erase (first, last); + width = static_cast (points.size ()); + height = 1; + return (it); + } + + /** \brief Swap a point cloud with another cloud. + * \param[in,out] rhs point cloud to swap this with + */ + inline void + swap (PointCloud &rhs) + { + this->points.swap (rhs.points); + std::swap (width, rhs.width); + std::swap (height, rhs.height); + std::swap (is_dense, rhs.is_dense); + std::swap (sensor_origin_, rhs.sensor_origin_); + std::swap (sensor_orientation_, rhs.sensor_orientation_); + } + + /** \brief Removes all points in a cloud and sets the width and height to 0. */ + inline void + clear () + { + points.clear (); + width = 0; + height = 0; + } + + /** \brief Copy the cloud to the heap and return a smart pointer + * Note that deep copy is performed, so avoid using this function on non-empty clouds. + * The changes of the returned cloud are not mirrored back to this one. + * \return shared pointer to the copy of the cloud + */ + inline Ptr + makeShared () const { return Ptr (new PointCloud (*this)); } + + protected: + // This is motivated by ROS integration. Users should not need to access mapping_. + boost::shared_ptr mapping_; + + friend boost::shared_ptr& detail::getMapping(pcl::PointCloud &p); + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + namespace detail + { + template boost::shared_ptr& + getMapping (pcl::PointCloud& p) + { + return (p.mapping_); + } + } // namespace detail + + template std::ostream& + operator << (std::ostream& s, const pcl::PointCloud &p) + { + s << "points[]: " << p.points.size () << std::endl; + s << "width: " << p.width << std::endl; + s << "height: " << p.height << std::endl; + s << "is_dense: " << p.is_dense << std::endl; + s << "sensor origin (xyz): [" << + p.sensor_origin_.x () << ", " << + p.sensor_origin_.y () << ", " << + p.sensor_origin_.z () << "] / orientation (xyzw): [" << + p.sensor_orientation_.x () << ", " << + p.sensor_orientation_.y () << ", " << + p.sensor_orientation_.z () << ", " << + p.sensor_orientation_.w () << "]" << + std::endl; + return (s); + } +} + +#define PCL_INSTANTIATE_PointCloud(T) template class PCL_EXPORTS pcl::PointCloud; + +#endif //#ifndef PCL_POINT_CLOUD_H_ diff --git a/pcl-1.7/pcl/point_representation.h b/pcl-1.7/pcl/point_representation.h new file mode 100644 index 0000000..75faedb --- /dev/null +++ b/pcl-1.7/pcl/point_representation.h @@ -0,0 +1,549 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_POINT_REPRESENTATION_H_ +#define PCL_POINT_REPRESENTATION_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief @b PointRepresentation provides a set of methods for converting a point structs/object into an + * n-dimensional vector. + * \note This is an abstract class. Subclasses must set nr_dimensions_ to the appropriate value in the constructor + * and provide an implemention of the pure virtual copyToFloatArray method. + * \author Michael Dixon + */ + template + class PointRepresentation + { + protected: + /** \brief The number of dimensions in this point's vector (i.e. the "k" in "k-D") */ + int nr_dimensions_; + /** \brief A vector containing the rescale factor to apply to each dimension. */ + std::vector alpha_; + /** \brief Indicates whether this point representation is trivial. It is trivial if and only if the following + * conditions hold: + * - the relevant data consists only of float values + * - the vectorize operation directly copies the first nr_dimensions_ elements of PointT to the out array + * - sizeof(PointT) is a multiple of sizeof(float) + * In short, a trivial point representation converts the input point to a float array that is the same as if + * the point was reinterpret_casted to a float array of length nr_dimensions_ . This value says that this + * representation can be trivial; it is only trivial if setRescaleValues() has not been set. + */ + bool trivial_; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Empty constructor */ + PointRepresentation () : nr_dimensions_ (0), alpha_ (0), trivial_ (false) {} + + /** \brief Empty destructor */ + virtual ~PointRepresentation () {} + + /** \brief Copy point data from input point to a float array. This method must be overriden in all subclasses. + * \param[in] p The input point + * \param[out] out A pointer to a float array. + */ + virtual void copyToFloatArray (const PointT &p, float *out) const = 0; + + /** \brief Returns whether this point representation is trivial. It is trivial if and only if the following + * conditions hold: + * - the relevant data consists only of float values + * - the vectorize operation directly copies the first nr_dimensions_ elements of PointT to the out array + * - sizeof(PointT) is a multiple of sizeof(float) + * In short, a trivial point representation converts the input point to a float array that is the same as if + * the point was reinterpret_casted to a float array of length nr_dimensions_ . */ + inline bool isTrivial() const { return trivial_ && alpha_.empty (); } + + /** \brief Verify that the input point is valid. + * \param p The point to validate + */ + virtual bool + isValid (const PointT &p) const + { + bool is_valid = true; + + if (trivial_) + { + const float* temp = reinterpret_cast(&p); + + for (int i = 0; i < nr_dimensions_; ++i) + { + if (!pcl_isfinite (temp[i])) + { + is_valid = false; + break; + } + } + } + else + { + float *temp = new float[nr_dimensions_]; + copyToFloatArray (p, temp); + + for (int i = 0; i < nr_dimensions_; ++i) + { + if (!pcl_isfinite (temp[i])) + { + is_valid = false; + break; + } + } + delete [] temp; + } + return (is_valid); + } + + /** \brief Convert input point into a vector representation, rescaling by \a alpha. + * \param[in] p the input point + * \param[out] out The output vector. Can be of any type that implements the [] operator. + */ + template void + vectorize (const PointT &p, OutputType &out) const + { + float *temp = new float[nr_dimensions_]; + copyToFloatArray (p, temp); + if (alpha_.empty ()) + { + for (int i = 0; i < nr_dimensions_; ++i) + out[i] = temp[i]; + } + else + { + for (int i = 0; i < nr_dimensions_; ++i) + out[i] = temp[i] * alpha_[i]; + } + delete [] temp; + } + + /** \brief Set the rescale values to use when vectorizing points + * \param[in] rescale_array The array/vector of rescale values. Can be of any type that implements the [] operator. + */ + void + setRescaleValues (const float *rescale_array) + { + alpha_.resize (nr_dimensions_); + for (int i = 0; i < nr_dimensions_; ++i) + alpha_[i] = rescale_array[i]; + } + + /** \brief Return the number of dimensions in the point's vector representation. */ + inline int getNumberOfDimensions () const { return (nr_dimensions_); } + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b DefaultPointRepresentation extends PointRepresentation to define default behavior for common point types. + */ + template + class DefaultPointRepresentation : public PointRepresentation + { + using PointRepresentation ::nr_dimensions_; + using PointRepresentation ::trivial_; + + public: + // Boost shared pointers + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + DefaultPointRepresentation () + { + // If point type is unknown, assume it's a struct/array of floats, and compute the number of dimensions + nr_dimensions_ = sizeof (PointDefault) / sizeof (float); + // Limit the default representation to the first 3 elements + if (nr_dimensions_ > 3) nr_dimensions_ = 3; + + trivial_ = true; + } + + virtual ~DefaultPointRepresentation () {} + + inline Ptr + makeShared () const + { + return (Ptr (new DefaultPointRepresentation (*this))); + } + + virtual void + copyToFloatArray (const PointDefault &p, float * out) const + { + // If point type is unknown, treat it as a struct/array of floats + const float* ptr = reinterpret_cast (&p); + for (int i = 0; i < nr_dimensions_; ++i) + out[i] = ptr[i]; + } + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b DefaulFeatureRepresentation extends PointRepresentation and is intended to be used when defining the + * default behavior for feature descriptor types (i.e., copy each element of each field into a float array). + */ + template + class DefaultFeatureRepresentation : public PointRepresentation + { + protected: + using PointRepresentation ::nr_dimensions_; + + private: + struct IncrementFunctor + { + IncrementFunctor (int &n) : n_ (n) + { + n_ = 0; + } + + template inline void operator () () + { + n_ += pcl::traits::datatype::size; + } + + private: + int &n_; + }; + + struct NdCopyPointFunctor + { + typedef typename traits::POD::type Pod; + + NdCopyPointFunctor (const PointDefault &p1, float * p2) + : p1_ (reinterpret_cast(p1)), p2_ (p2), f_idx_ (0) { } + + template inline void operator() () + { + typedef typename pcl::traits::datatype::type FieldT; + const int NrDims = pcl::traits::datatype::size; + Helper::copyPoint (p1_, p2_, f_idx_); + } + + // Copy helper for scalar fields + template + struct Helper + { + static void copyPoint (const Pod &p1, float * p2, int &f_idx) + { + const uint8_t * data_ptr = reinterpret_cast (&p1) + + pcl::traits::offset::value; + p2[f_idx++] = *reinterpret_cast (data_ptr); + } + }; + // Copy helper for array fields + template + struct Helper + { + static void copyPoint (const Pod &p1, float * p2, int &f_idx) + { + const uint8_t * data_ptr = reinterpret_cast (&p1) + + pcl::traits::offset::value; + int nr_dims = NrDims; + const FieldT * array = reinterpret_cast (data_ptr); + for (int i = 0; i < nr_dims; ++i) + { + p2[f_idx++] = array[i]; + } + } + }; + + private: + const Pod &p1_; + float * p2_; + int f_idx_; + }; + + public: + // Boost shared pointers + typedef typename boost::shared_ptr > Ptr; + typedef typename boost::shared_ptr > ConstPtr; + typedef typename pcl::traits::fieldList::type FieldList; + + DefaultFeatureRepresentation () + { + nr_dimensions_ = 0; // zero-out the nr_dimensions_ before it gets incremented + pcl::for_each_type (IncrementFunctor (nr_dimensions_)); + } + + inline Ptr + makeShared () const + { + return (Ptr (new DefaultFeatureRepresentation (*this))); + } + + virtual void + copyToFloatArray (const PointDefault &p, float * out) const + { + pcl::for_each_type (NdCopyPointFunctor (p, out)); + } + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template <> + class DefaultPointRepresentation : public PointRepresentation + { + public: + DefaultPointRepresentation () + { + nr_dimensions_ = 3; + trivial_ = true; + } + + virtual void + copyToFloatArray (const PointXYZ &p, float * out) const + { + out[0] = p.x; + out[1] = p.y; + out[2] = p.z; + } + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template <> + class DefaultPointRepresentation : public PointRepresentation + { + public: + DefaultPointRepresentation () + { + nr_dimensions_ = 3; + trivial_ = true; + } + + virtual void + copyToFloatArray (const PointXYZI &p, float * out) const + { + out[0] = p.x; + out[1] = p.y; + out[2] = p.z; + // By default, p.intensity is not part of the PointXYZI vectorization + } + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template <> + class DefaultPointRepresentation : public PointRepresentation + { + public: + DefaultPointRepresentation () + { + nr_dimensions_ = 3; + trivial_ = true; + } + + virtual void + copyToFloatArray (const PointNormal &p, float * out) const + { + out[0] = p.x; + out[1] = p.y; + out[2] = p.z; + } + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template <> + class DefaultPointRepresentation : public DefaultFeatureRepresentation + {}; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template <> + class DefaultPointRepresentation : public DefaultFeatureRepresentation + {}; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template <> + class DefaultPointRepresentation : public DefaultFeatureRepresentation + { + public: + DefaultPointRepresentation () + { + nr_dimensions_ = 4; + trivial_ = true; + } + + virtual void + copyToFloatArray (const PPFSignature &p, float * out) const + { + out[0] = p.f1; + out[1] = p.f2; + out[2] = p.f3; + out[3] = p.f4; + } + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template <> + class DefaultPointRepresentation : public DefaultFeatureRepresentation + {}; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template <> + class DefaultPointRepresentation : public DefaultFeatureRepresentation + {}; + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template <> + class DefaultPointRepresentation : public PointRepresentation + { + public: + DefaultPointRepresentation () + { + nr_dimensions_ = 36; + trivial_=false; + } + + virtual void + copyToFloatArray (const Narf36 &p, float * out) const + { + for (int i = 0; i < nr_dimensions_; ++i) + out[i] = p.descriptor[i]; + } + }; + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template <> + class DefaultPointRepresentation : public DefaultFeatureRepresentation + {}; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template <> + class DefaultPointRepresentation : public PointRepresentation + { + public: + DefaultPointRepresentation () + { + nr_dimensions_ = 1980; + } + + virtual void + copyToFloatArray (const ShapeContext1980 &p, float * out) const + { + for (int i = 0; i < nr_dimensions_; ++i) + out[i] = p.descriptor[i]; + } + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template <> + class DefaultPointRepresentation : public PointRepresentation + { + public: + DefaultPointRepresentation () + { + nr_dimensions_ = 352; + } + + virtual void + copyToFloatArray (const SHOT352 &p, float * out) const + { + for (int i = 0; i < nr_dimensions_; ++i) + out[i] = p.descriptor[i]; + } + }; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template <> + class DefaultPointRepresentation : public PointRepresentation + { + public: + DefaultPointRepresentation () + { + nr_dimensions_ = 1344; + } + + virtual void + copyToFloatArray (const SHOT1344 &p, float * out) const + { + for (int i = 0; i < nr_dimensions_; ++i) + out[i] = p.descriptor[i]; + } + }; + + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b CustomPointRepresentation extends PointRepresentation to allow for sub-part selection on the point. + */ + template + class CustomPointRepresentation : public PointRepresentation + { + using PointRepresentation ::nr_dimensions_; + + public: + // Boost shared pointers + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor + * \param[in] max_dim the maximum number of dimensions to use + * \param[in] start_dim the starting dimension + */ + CustomPointRepresentation (const int max_dim = 3, const int start_dim = 0) + : max_dim_(max_dim), start_dim_(start_dim) + { + // If point type is unknown, assume it's a struct/array of floats, and compute the number of dimensions + nr_dimensions_ = static_cast (sizeof (PointDefault) / sizeof (float)) - start_dim_; + // Limit the default representation to the first 3 elements + if (nr_dimensions_ > max_dim_) + nr_dimensions_ = max_dim_; + } + + inline Ptr + makeShared () const + { + return Ptr (new CustomPointRepresentation (*this)); + } + + /** \brief Copy the point data into a float array + * \param[in] p the input point + * \param[out] out the resultant output array + */ + virtual void + copyToFloatArray (const PointDefault &p, float *out) const + { + // If point type is unknown, treat it as a struct/array of floats + const float *ptr = (reinterpret_cast (&p)) + start_dim_; + for (int i = 0; i < nr_dimensions_; ++i) + out[i] = ptr[i]; + } + + protected: + /** \brief Use at most this many dimensions (i.e. the "k" in "k-D" is at most max_dim_) -- \note float fields are assumed */ + int max_dim_; + /** \brief Use dimensions only starting with this one (i.e. the "k" in "k-D" is = dim - start_dim_) -- \note float fields are assumed */ + int start_dim_; + }; +} + +#endif // #ifndef PCL_POINT_REPRESENTATION_H_ diff --git a/pcl-1.7/pcl/point_traits.h b/pcl-1.7/pcl/point_traits.h new file mode 100644 index 0000000..7d3d97a --- /dev/null +++ b/pcl-1.7/pcl/point_traits.h @@ -0,0 +1,350 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_POINT_TRAITS_H_ +#define PCL_POINT_TRAITS_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#include "pcl/pcl_macros.h" + +#include +#include +#include +#include +#if PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) == PCL_LINEAR_VERSION(4,4,3) +#include +#endif + +// This is required for the workaround at line 109 +#ifdef _MSC_VER +#include +#include +#endif + +namespace pcl +{ + + namespace fields + { + // Tag types get put in this namespace + } + + namespace traits + { + // Metafunction to return enum value representing a type + template struct asEnum {}; + template<> struct asEnum { static const uint8_t value = pcl::PCLPointField::INT8; }; + template<> struct asEnum { static const uint8_t value = pcl::PCLPointField::UINT8; }; + template<> struct asEnum { static const uint8_t value = pcl::PCLPointField::INT16; }; + template<> struct asEnum { static const uint8_t value = pcl::PCLPointField::UINT16; }; + template<> struct asEnum { static const uint8_t value = pcl::PCLPointField::INT32; }; + template<> struct asEnum { static const uint8_t value = pcl::PCLPointField::UINT32; }; + template<> struct asEnum { static const uint8_t value = pcl::PCLPointField::FLOAT32; }; + template<> struct asEnum { static const uint8_t value = pcl::PCLPointField::FLOAT64; }; + + // Metafunction to return type of enum value + template struct asType {}; + template<> struct asType { typedef int8_t type; }; + template<> struct asType { typedef uint8_t type; }; + template<> struct asType { typedef int16_t type; }; + template<> struct asType { typedef uint16_t type; }; + template<> struct asType { typedef int32_t type; }; + template<> struct asType { typedef uint32_t type; }; + template<> struct asType { typedef float type; }; + template<> struct asType { typedef double type; }; + + // Metafunction to decompose a type (possibly of array of any number of dimensions) into + // its scalar type and total number of elements. + template struct decomposeArray + { + typedef typename boost::remove_all_extents::type type; + static const uint32_t value = sizeof (T) / sizeof (type); + }; + + // For non-POD point types, this is specialized to return the corresponding POD type. + template + struct POD + { + typedef PointT type; + }; + +#ifdef _MSC_VER + + /* Sometimes when calling functions like `copyPoint()` or `copyPointCloud` + * without explicitly specifying point types, MSVC deduces them to be e.g. + * `Eigen::internal::workaround_msvc_stl_support` instead of + * plain `pcl::PointXYZ`. Subsequently these types are passed to meta- + * functions like `has_field` or `fieldList` and make them choke. This hack + * makes use of the fact that internally `fieldList` always applies `POD` to + * its argument type. This specialization therefore allows to unwrap the + * contained point type. */ + template + struct POD > + { + typedef PointT type; + }; + +#endif + + // name + /* This really only depends on Tag, but we go through some gymnastics to avoid ODR violations. + We template it on the point type PointT to avoid ODR violations when registering multiple + point types with shared tags. + The dummy parameter is so we can partially specialize name on PointT and Tag but leave it + templated on dummy. Each specialization declares a static char array containing the tag + name. The definition of the static member would conflict when linking multiple translation + units that include the point type registration. But when the static member definition is + templated (on dummy), we sidestep the ODR issue. + */ + template + struct name : name::type, Tag, dummy> + { + // Contents of specialization: + // static const char value[]; + + // Avoid infinite compile-time recursion + BOOST_MPL_ASSERT_MSG((!boost::is_same::type>::value), + POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&)); + }; + + // offset + template + struct offset : offset::type, Tag> + { + // Contents of specialization: + // static const size_t value; + + // Avoid infinite compile-time recursion + BOOST_MPL_ASSERT_MSG((!boost::is_same::type>::value), + POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&)); + }; + + // datatype + template + struct datatype : datatype::type, Tag> + { + // Contents of specialization: + // typedef ... type; + // static const uint8_t value; + // static const uint32_t size; + + // Avoid infinite compile-time recursion + BOOST_MPL_ASSERT_MSG((!boost::is_same::type>::value), + POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&)); + }; + + // fields + template + struct fieldList : fieldList::type> + { + // Contents of specialization: + // typedef boost::mpl::vector<...> type; + + // Avoid infinite compile-time recursion + BOOST_MPL_ASSERT_MSG((!boost::is_same::type>::value), + POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&)); + }; +#if PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) == PCL_LINEAR_VERSION(4,4,3) + /* + At least on GCC 4.4.3, but not later versions, some valid usages of the above traits for + non-POD (but registered) point types fail with: + error: ‘!(bool)mpl_::bool_::value’ is not a valid template argument for type ‘bool’ because it is a non-constant expression + + "Priming the pump" with the trivial assertion below somehow fixes the problem... + */ + //BOOST_MPL_ASSERT_MSG((!bool (mpl_::bool_::value)), WTF_GCC443, (bool)); + BOOST_MPL_ASSERT_MSG((!bool (boost::mpl::bool_::value)), WTF_GCC443, (bool)); +#endif + } //namespace traits + + // Return true if the PCLPointField matches the expected name and data type. + // Written as a struct to allow partially specializing on Tag. + template + struct FieldMatches + { + bool operator() (const pcl::PCLPointField& field) + { + return (field.name == traits::name::value && + field.datatype == traits::datatype::value && + (field.count == traits::datatype::size || + field.count == 0 && traits::datatype::size == 1 /* see bug #821 */)); + } + }; + + /** \brief A helper functor that can copy a specific value if the given field exists. + * + * \note In order to actually copy the value an instance of this functor should be passed + * to a pcl::for_each_type loop. See the example below. + * + * \code + * PointInT p; + * bool exists; + * float value; + * typedef typename pcl::traits::fieldList::type FieldList; + * pcl::for_each_type (pcl::CopyIfFieldExists (p, "intensity", exists, value)); + * \endcode + */ + template + struct CopyIfFieldExists + { + typedef typename traits::POD::type Pod; + + /** \brief Constructor. + * \param[in] pt the input point + * \param[in] field the name of the field + * \param[out] exists set to true if the field exists, false otherwise + * \param[out] value the copied field value + */ + CopyIfFieldExists (const PointInT &pt, + const std::string &field, + bool &exists, + OutT &value) + : pt_ (reinterpret_cast(pt)), name_ (field), exists_ (exists), value_ (value) + { + exists_ = false; + } + + /** \brief Constructor. + * \param[in] pt the input point + * \param[in] field the name of the field + * \param[out] value the copied field value + */ + CopyIfFieldExists (const PointInT &pt, + const std::string &field, + OutT &value) + : pt_ (reinterpret_cast(pt)), name_ (field), exists_ (exists_tmp_), value_ (value) + { + } + + /** \brief Operator. Data copy happens here. */ + template inline void + operator() () + { + if (name_ == pcl::traits::name::value) + { + exists_ = true; + typedef typename pcl::traits::datatype::type T; + const uint8_t* data_ptr = reinterpret_cast(&pt_) + pcl::traits::offset::value; + value_ = static_cast (*reinterpret_cast(data_ptr)); + } + } + + private: + const Pod &pt_; + const std::string &name_; + bool &exists_; + // Bogus entry + bool exists_tmp_; + OutT &value_; + }; + + /** \brief A helper functor that can set a specific value in a field if the field exists. + * + * \note In order to actually set the value an instance of this functor should be passed + * to a pcl::for_each_type loop. See the example below. + * + * \code + * PointT p; + * typedef typename pcl::traits::fieldList::type FieldList; + * pcl::for_each_type (pcl::SetIfFieldExists (p, "intensity", 42.0f)); + * \endcode + */ + template + struct SetIfFieldExists + { + typedef typename traits::POD::type Pod; + + /** \brief Constructor. + * \param[in] pt the input point + * \param[in] field the name of the field + * \param[out] value the value to set + */ + SetIfFieldExists (PointOutT &pt, + const std::string &field, + const InT &value) + : pt_ (reinterpret_cast(pt)), name_ (field), value_ (value) + { + } + + /** \brief Operator. Data copy happens here. */ + template inline void + operator() () + { + if (name_ == pcl::traits::name::value) + { + typedef typename pcl::traits::datatype::type T; + uint8_t* data_ptr = reinterpret_cast(&pt_) + pcl::traits::offset::value; + *reinterpret_cast(data_ptr) = static_cast (value_); + } + } + + private: + Pod &pt_; + const std::string &name_; + const InT &value_; + }; + + /** \brief Set the value at a specified field in a point + * \param[out] pt the point to set the value to + * \param[in] field_offset the offset of the field + * \param[in] value the value to set + */ + template inline void + setFieldValue (PointT &pt, size_t field_offset, const ValT &value) + { + uint8_t* data_ptr = reinterpret_cast(&pt) + field_offset; + *reinterpret_cast(data_ptr) = value; + } + + /** \brief Get the value at a specified field in a point + * \param[in] pt the point to get the value from + * \param[in] field_offset the offset of the field + * \param[out] value the value to retreive + */ + template inline void + getFieldValue (const PointT &pt, size_t field_offset, ValT &value) + { + const uint8_t* data_ptr = reinterpret_cast(&pt) + field_offset; + value = *reinterpret_cast(data_ptr); + } +} + +#endif //#ifndef PCL_POINT_TRAITS_H_ diff --git a/pcl-1.7/pcl/point_types.h b/pcl-1.7/pcl/point_types.h new file mode 100644 index 0000000..0bce771 --- /dev/null +++ b/pcl-1.7/pcl/point_types.h @@ -0,0 +1,746 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_DATA_TYPES_H_ +#define PCL_DATA_TYPES_H_ + +#include +#include +#include +#include +#include +#include + +/** + * \file pcl/point_types.h + * Defines all the PCL implemented PointT point type structures + * \ingroup common + */ + +// We're doing a lot of black magic with Boost here, so disable warnings in Maintainer mode, as we will never +// be able to fix them anyway +#if defined _MSC_VER + #pragma warning(disable: 4201) +#endif +//#pragma warning(push, 1) +#if defined __GNUC__ +# pragma GCC system_header +#endif + +/** @{*/ +namespace pcl +{ + /** \brief Members: float x, y, z + * \ingroup common + */ + struct PointXYZ; + + /** \brief Members: rgba + * \ingroup common + */ + struct RGB; + + /** \brief Members: intensity (float) + * \ingroup common + */ + struct Intensity; + + /** \brief Members: intensity (uint8_t) + * \ingroup common + */ + struct Intensity8u; + + /** \brief Members: intensity (uint32_t) + * \ingroup common + */ + struct Intensity32u; + + /** \brief Members: float x, y, z, intensity + * \ingroup common + */ + struct PointXYZI; + + /** \brief Members: float x, y, z, uin32_t label + * \ingroup common + */ + struct PointXYZL; + + /** \brief Members: uint32_t label + * \ingroup common + */ + struct Label; + + /** \brief Members: float x, y, z; uint32_t rgba + * \ingroup common + */ + struct PointXYZRGBA; + + /** \brief Members: float x, y, z, rgb + * \ingroup common + */ + struct PointXYZRGB; + + /** \brief Members: float x, y, z, rgb, uint32_t label + * \ingroup common + */ + struct PointXYZRGBL; + + /** \brief Members: float x, y, z, h, s, v + * \ingroup common + */ + struct PointXYZHSV; + + /** \brief Members: float x, y + * \ingroup common + */ + struct PointXY; + + /** \brief Members: float u, v + * \ingroup common + */ + struct PointUV; + + /** \brief Members: float x, y, z, strength + * \ingroup common + */ + struct InterestPoint; + + /** \brief Members: float normal[3], curvature + * \ingroup common + */ + struct Normal; + + /** \brief Members: float normal[3] + * \ingroup common + */ + struct Axis; + + /** \brief Members: float x, y, z; float normal[3], curvature + * \ingroup common + */ + struct PointNormal; + + /** \brief Members: float x, y, z, rgb, normal[3], curvature + * \ingroup common + */ + struct PointXYZRGBNormal; + + /** \brief Members: float x, y, z, intensity, normal[3], curvature + * \ingroup common + */ + struct PointXYZINormal; + + /** \brief Members: float x, y, z (union with float point[4]), range + * \ingroup common + */ + struct PointWithRange; + + /** \brief Members: float x, y, z, vp_x, vp_y, vp_z + * \ingroup common + */ + struct PointWithViewpoint; + + /** \brief Members: float j1, j2, j3 + * \ingroup common + */ + struct MomentInvariants; + + /** \brief Members: float r_min, r_max + * \ingroup common + */ + struct PrincipalRadiiRSD; + + /** \brief Members: uint8_t boundary_point + * \ingroup common + */ + struct Boundary; + + /** \brief Members: float principal_curvature[3], pc1, pc2 + * \ingroup common + */ + struct PrincipalCurvatures; + + /** \brief Members: float descriptor[352], rf[9] + * \ingroup common + */ + struct SHOT352; + + /** \brief Members: float descriptor[1344], rf[9] + * \ingroup common + */ + struct SHOT1344; + + /** \brief Members: Axis x_axis, y_axis, z_axis + * \ingroup common + */ + struct ReferenceFrame; + + /** \brief Members: float descriptor[1980], rf[9] + * \ingroup common + */ + struct ShapeContext1980; + + /** \brief Members: float pfh[125] + * \ingroup common + */ + struct PFHSignature125; + + /** \brief Members: float pfhrgb[250] + * \ingroup common + */ + struct PFHRGBSignature250; + + /** \brief Members: float f1, f2, f3, f4, alpha_m + * \ingroup common + */ + struct PPFSignature; + + /** \brief Members: float f1, f2, f3, f4, f5, f6, f7, f8, f9, f10, alpha_m + * \ingroup common + */ + struct CPPFSignature; + + /** \brief Members: float f1, f2, f3, f4, r_ratio, g_ratio, b_ratio, alpha_m + * \ingroup common + */ + struct PPFRGBSignature; + + /** \brief Members: float values[12] + * \ingroup common + */ + struct NormalBasedSignature12; + + /** \brief Members: float fpfh[33] + * \ingroup common + */ + struct FPFHSignature33; + + /** \brief Members: float vfh[308] + * \ingroup common + */ + struct VFHSignature308; + + /** \brief Members: float esf[640] + * \ingroup common + */ + struct ESFSignature640; + + /** \brief Members: float histogram[16] + * \ingroup common + */ + struct GFPFHSignature16; + + /** \brief Members: float x, y, z, roll, pitch, yaw; float descriptor[36] + * \ingroup common + */ + struct Narf36; + + /** \brief Data type to store extended information about a transition from foreground to backgroundSpecification of the fields for BorderDescription::traits. + * \ingroup common + */ + typedef std::bitset<32> BorderTraits; + + /** \brief Specification of the fields for BorderDescription::traits. + * \ingroup common + */ + enum BorderTrait + { + BORDER_TRAIT__OBSTACLE_BORDER, BORDER_TRAIT__SHADOW_BORDER, BORDER_TRAIT__VEIL_POINT, + BORDER_TRAIT__SHADOW_BORDER_TOP, BORDER_TRAIT__SHADOW_BORDER_RIGHT, BORDER_TRAIT__SHADOW_BORDER_BOTTOM, + BORDER_TRAIT__SHADOW_BORDER_LEFT, BORDER_TRAIT__OBSTACLE_BORDER_TOP, BORDER_TRAIT__OBSTACLE_BORDER_RIGHT, + BORDER_TRAIT__OBSTACLE_BORDER_BOTTOM, BORDER_TRAIT__OBSTACLE_BORDER_LEFT, BORDER_TRAIT__VEIL_POINT_TOP, + BORDER_TRAIT__VEIL_POINT_RIGHT, BORDER_TRAIT__VEIL_POINT_BOTTOM, BORDER_TRAIT__VEIL_POINT_LEFT + }; + + /** \brief Members: int x, y; BorderTraits traits + * \ingroup common + */ + struct BorderDescription; + + /** \brief Members: float gradient[3] + * \ingroup common + */ + struct IntensityGradient; + + /** \brief Members: float histogram[N] + * \ingroup common + */ + template + struct Histogram; + + /** \brief Members: float x, y, z, scale, angle, response, octave + * \ingroup common + */ + struct PointWithScale; + + /** \brief Members: float x, y, z, normal[3], rgba, radius, confidence, curvature + * \ingroup common + */ + struct PointSurfel; +} + +/** @} */ + +#include // Include struct definitions + +// ============================== +// =====POINT_CLOUD_REGISTER===== +// ============================== + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_RGB, + (uint32_t, rgba, rgba) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::RGB, pcl::_RGB) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_Intensity, + (float, intensity, intensity) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::Intensity, pcl::_Intensity) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_Intensity8u, + (uint8_t, intensity, intensity) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::Intensity8u, pcl::_Intensity8u) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_Intensity32u, + (uint32_t, intensity, intensity) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::Intensity32u, pcl::_Intensity32u) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZ, + (float, x, x) + (float, y, y) + (float, z, z) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZ, pcl::_PointXYZ) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGBA, + (float, x, x) + (float, y, y) + (float, z, z) + (uint32_t, rgba, rgba) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGBA, pcl::_PointXYZRGBA) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGB, + (float, x, x) + (float, y, y) + (float, z, z) + (float, rgb, rgb) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGB, pcl::_PointXYZRGB) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGBL, + (float, x, x) + (float, y, y) + (float, z, z) + (uint32_t, rgba, rgba) + (uint32_t, label, label) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGBL, pcl::_PointXYZRGBL) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZHSV, + (float, x, x) + (float, y, y) + (float, z, z) + (float, h, h) + (float, s, s) + (float, v, v) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZHSV, pcl::_PointXYZHSV) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointXY, + (float, x, x) + (float, y, y) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointUV, + (float, u, u) + (float, v, v) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::InterestPoint, + (float, x, x) + (float, y, y) + (float, z, z) + (float, strength, strength) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZI, + (float, x, x) + (float, y, y) + (float, z, z) + (float, intensity, intensity) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZI, pcl::_PointXYZI) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointXYZL, + (float, x, x) + (float, y, y) + (float, z, z) + (uint32_t, label, label) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::Label, + (uint32_t, label, label) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_Normal, + (float, normal_x, normal_x) + (float, normal_y, normal_y) + (float, normal_z, normal_z) + (float, curvature, curvature) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::Normal, pcl::_Normal) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_Axis, + (float, normal_x, normal_x) + (float, normal_y, normal_y) + (float, normal_z, normal_z) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::Axis, pcl::_Axis) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointNormal, + (float, x, x) + (float, y, y) + (float, z, z) + (float, normal_x, normal_x) + (float, normal_y, normal_y) + (float, normal_z, normal_z) + (float, curvature, curvature) +) +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGBNormal, + (float, x, x) + (float, y, y) + (float, z, z) + (float, rgb, rgb) + (float, normal_x, normal_x) + (float, normal_y, normal_y) + (float, normal_z, normal_z) + (float, curvature, curvature) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGBNormal, pcl::_PointXYZRGBNormal) +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointXYZINormal, + (float, x, x) + (float, y, y) + (float, z, z) + (float, intensity, intensity) + (float, normal_x, normal_x) + (float, normal_y, normal_y) + (float, normal_z, normal_z) + (float, curvature, curvature) +) +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointWithRange, + (float, x, x) + (float, y, y) + (float, z, z) + (float, range, range) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointWithViewpoint, + (float, x, x) + (float, y, y) + (float, z, z) + (float, vp_x, vp_x) + (float, vp_y, vp_y) + (float, vp_z, vp_z) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointWithViewpoint, pcl::_PointWithViewpoint) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::MomentInvariants, + (float, j1, j1) + (float, j2, j2) + (float, j3, j3) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PrincipalRadiiRSD, + (float, r_min, r_min) + (float, r_max, r_max) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::Boundary, + (uint8_t, boundary_point, boundary_point) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PrincipalCurvatures, + (float, principal_curvature_x, principal_curvature_x) + (float, principal_curvature_y, principal_curvature_y) + (float, principal_curvature_z, principal_curvature_z) + (float, pc1, pc1) + (float, pc2, pc2) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PFHSignature125, + (float[125], histogram, pfh) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PFHRGBSignature250, + (float[250], histogram, pfhrgb) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PPFSignature, + (float, f1, f1) + (float, f2, f2) + (float, f3, f3) + (float, f4, f4) + (float, alpha_m, alpha_m) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::CPPFSignature, + (float, f1, f1) + (float, f2, f2) + (float, f3, f3) + (float, f4, f4) + (float, f5, f5) + (float, f6, f6) + (float, f7, f7) + (float, f8, f8) + (float, f9, f9) + (float, f10, f10) + (float, alpha_m, alpha_m) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PPFRGBSignature, + (float, f1, f1) + (float, f2, f2) + (float, f3, f3) + (float, f4, f4) + (float, r_ratio, r_ratio) + (float, g_ratio, g_ratio) + (float, b_ratio, b_ratio) + (float, alpha_m, alpha_m) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::NormalBasedSignature12, + (float[12], values, values) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::ShapeContext1980, + (float[1980], descriptor, shape_context) + (float[9], rf, rf) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::SHOT352, + (float[352], descriptor, shot) + (float[9], rf, rf) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::SHOT1344, + (float[1344], descriptor, shot) + (float[9], rf, rf) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::FPFHSignature33, + (float[33], histogram, fpfh) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::VFHSignature308, + (float[308], histogram, vfh) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::ESFSignature640, + (float[640], histogram, esf) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::Narf36, + (float[36], descriptor, descriptor) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::GFPFHSignature16, + (float[16], histogram, gfpfh) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::IntensityGradient, + (float, gradient_x, gradient_x) + (float, gradient_y, gradient_y) + (float, gradient_z, gradient_z) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointWithScale, + (float, x, x) + (float, y, y) + (float, z, z) + (float, scale, scale) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT(pcl::PointSurfel, + (float, x, x) + (float, y, y) + (float, z, z) + (float, normal_x, normal_x) + (float, normal_y, normal_y) + (float, normal_z, normal_z) + (uint32_t, rgba, rgba) + (float, radius, radius) + (float, confidence, confidence) + (float, curvature, curvature) +) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_ReferenceFrame, + (float[3], x_axis, x_axis) + (float[3], y_axis, y_axis) + (float[3], z_axis, z_axis) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::ReferenceFrame, pcl::_ReferenceFrame) + +namespace pcl +{ + // Allow float 'rgb' data to match to the newer uint32 'rgba' tag. This is so + // you can load old 'rgb' PCD files into e.g. a PointCloud. + template + struct FieldMatches + { + bool operator() (const pcl::PCLPointField& field) + { + if (field.name == "rgb") + { + return (field.datatype == pcl::PCLPointField::FLOAT32 && + field.count == 1); + } + else + { + return (field.name == traits::name::value && + field.datatype == traits::datatype::value && + field.count == traits::datatype::size); + } + } + }; + template + struct FieldMatches + { + bool operator() (const pcl::PCLPointField& field) + { + if (field.name == "rgba") + { + return (field.datatype == pcl::PCLPointField::UINT32 && + field.count == 1); + } + else + { + return (field.name == traits::name::value && + field.datatype == traits::datatype::value && + field.count == traits::datatype::size); + } + } + }; + + namespace traits + { + + /** \brief Metafunction to check if a given point type has a given field. + * + * Example usage at run-time: + * + * \code + * bool curvature_available = pcl::traits::has_field::value; + * \endcode + * + * Example usage at compile-time: + * + * \code + * BOOST_MPL_ASSERT_MSG ((pcl::traits::has_field::value), + * POINT_TYPE_SHOULD_HAVE_LABEL_FIELD, + * (PointT)); + * \endcode + */ + template + struct has_field : boost::mpl::contains::type, Field>::type + { }; + + /** Metafunction to check if a given point type has all given fields. */ + template + struct has_all_fields : boost::mpl::fold, + boost::mpl::and_ > >::type + { }; + + /** Metafunction to check if a given point type has any of the given fields. */ + template + struct has_any_field : boost::mpl::fold, + boost::mpl::or_ > >::type + { }; + + /** Metafunction to check if a given point type has x, y, and z fields. */ + template + struct has_xyz : has_all_fields > + { }; + + /** Metafunction to check if a given point type has normal_x, normal_y, and + * normal_z fields. */ + template + struct has_normal : has_all_fields > + { }; + + /** Metafunction to check if a given point type has curvature field. */ + template + struct has_curvature : has_field + { }; + + /** Metafunction to check if a given point type has intensity field. */ + template + struct has_intensity : has_field + { }; + + /** Metafunction to check if a given point type has either rgb or rgba field. */ + template + struct has_color : has_any_field > + { }; + + /** Metafunction to check if a given point type has label field. */ + template + struct has_label : has_field + { }; + + } + +} // namespace pcl + +#if defined _MSC_VER + #pragma warning(default: 4201) +#endif +//#pragma warning(pop) + +#endif //#ifndef PCL_DATA_TYPES_H_ diff --git a/pcl-1.7/pcl/point_types_conversion.h b/pcl-1.7/pcl/point_types_conversion.h new file mode 100644 index 0000000..1f445ca --- /dev/null +++ b/pcl-1.7/pcl/point_types_conversion.h @@ -0,0 +1,395 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_TYPE_CONVERSIONS_H +#define PCL_TYPE_CONVERSIONS_H + +#include + +namespace pcl +{ + // r,g,b, i values are from 0 to 1 + // h = [0,360] + // s, v values are from 0 to 1 + // if s = 0 > h = -1 (undefined) + + /** \brief Convert a XYZRGB point type to a XYZI + * \param[in] in the input XYZRGB point + * \param[out] out the output XYZI point + */ + inline void + PointXYZRGBtoXYZI (PointXYZRGB& in, + PointXYZI& out) + { + out.x = in.x; out.y = in.y; out.z = in.z; + out.intensity = 0.299f * static_cast (in.r) + 0.587f * static_cast (in.g) + 0.114f * static_cast (in.b); + } + + /** \brief Convert a RGB point type to a I + * \param[in] in the input RGB point + * \param[out] out the output Intensity point + */ + inline void + PointRGBtoI (RGB& in, + Intensity& out) + { + out.intensity = 0.299f * static_cast (in.r) + 0.587f * static_cast (in.g) + 0.114f * static_cast (in.b); + } + + /** \brief Convert a RGB point type to a I + * \param[in] in the input RGB point + * \param[out] out the output Intensity point + */ + inline void + PointRGBtoI (RGB& in, + Intensity8u& out) + { + out.intensity = static_cast(std::numeric_limits::max() * 0.299f * static_cast (in.r) + + 0.587f * static_cast (in.g) + 0.114f * static_cast (in.b)); + } + + /** \brief Convert a RGB point type to a I + * \param[in] in the input RGB point + * \param[out] out the output Intensity point + */ + inline void + PointRGBtoI (RGB& in, + Intensity32u& out) + { + out.intensity = static_cast(static_cast(std::numeric_limits::max()) * 0.299f * static_cast (in.r) + + 0.587f * static_cast (in.g) + 0.114f * static_cast (in.b)); + } + + /** \brief Convert a XYZRGB point type to a XYZHSV + * \param[in] in the input XYZRGB point + * \param[out] out the output XYZHSV point + */ + inline void + PointXYZRGBtoXYZHSV (PointXYZRGB& in, + PointXYZHSV& out) + { + const unsigned char max = std::max (in.r, std::max (in.g, in.b)); + const unsigned char min = std::min (in.r, std::min (in.g, in.b)); + + out.v = static_cast (max) / 255.f; + + if (max == 0) // division by zero + { + out.s = 0.f; + out.h = 0.f; // h = -1.f; + return; + } + + const float diff = static_cast (max - min); + out.s = diff / static_cast (max); + + if (min == max) // diff == 0 -> division by zero + { + out.h = 0; + return; + } + + if (max == in.r) out.h = 60.f * ( static_cast (in.g - in.b) / diff); + else if (max == in.g) out.h = 60.f * (2.f + static_cast (in.b - in.r) / diff); + else out.h = 60.f * (4.f + static_cast (in.r - in.g) / diff); // max == b + + if (out.h < 0.f) out.h += 360.f; + } + + /** \brief Convert a XYZRGB point type to a XYZHSV + * \param[in] in the input XYZRGB point + * \param[out] out the output XYZHSV point + * \todo include the A parameter but how? + */ + inline void + PointXYZRGBAtoXYZHSV (PointXYZRGBA& in, + PointXYZHSV& out) + { + const unsigned char max = std::max (in.r, std::max (in.g, in.b)); + const unsigned char min = std::min (in.r, std::min (in.g, in.b)); + + out.v = static_cast (max) / 255.f; + + if (max == 0) // division by zero + { + out.s = 0.f; + out.h = 0.f; // h = -1.f; + return; + } + + const float diff = static_cast (max - min); + out.s = diff / static_cast (max); + + if (min == max) // diff == 0 -> division by zero + { + out.h = 0; + return; + } + + if (max == in.r) out.h = 60.f * ( static_cast (in.g - in.b) / diff); + else if (max == in.g) out.h = 60.f * (2.f + static_cast (in.b - in.r) / diff); + else out.h = 60.f * (4.f + static_cast (in.r - in.g) / diff); // max == b + + if (out.h < 0.f) out.h += 360.f; + } + + /* \brief Convert a XYZHSV point type to a XYZRGB + * \param[in] in the input XYZHSV point + * \param[out] out the output XYZRGB point + */ + inline void + PointXYZHSVtoXYZRGB (PointXYZHSV& in, + PointXYZRGB& out) + { + out.x = in.x; out.y = in.y; out.z = in.z; + if (in.s == 0) + { + out.r = out.g = out.b = static_cast (255 * in.v); + return; + } + float a = in.h / 60; + int i = static_cast (floorf (a)); + float f = a - static_cast (i); + float p = in.v * (1 - in.s); + float q = in.v * (1 - in.s * f); + float t = in.v * (1 - in.s * (1 - f)); + + switch (i) + { + case 0: + { + out.r = static_cast (255 * in.v); + out.g = static_cast (255 * t); + out.b = static_cast (255 * p); + break; + } + case 1: + { + out.r = static_cast (255 * q); + out.g = static_cast (255 * in.v); + out.b = static_cast (255 * p); + break; + } + case 2: + { + out.r = static_cast (255 * p); + out.g = static_cast (255 * in.v); + out.b = static_cast (255 * t); + break; + } + case 3: + { + out.r = static_cast (255 * p); + out.g = static_cast (255 * q); + out.b = static_cast (255 * in.v); + break; + } + case 4: + { + out.r = static_cast (255 * t); + out.g = static_cast (255 * p); + out.b = static_cast (255 * in.v); + break; + } + default: + { + out.r = static_cast (255 * in.v); + out.g = static_cast (255 * p); + out.b = static_cast (255 * q); + break; + } + } + } + + /** \brief Convert a RGB point cloud to a Intensity + * \param[in] in the input RGB point cloud + * \param[out] out the output Intensity point cloud + */ + inline void + PointCloudRGBtoI (PointCloud& in, + PointCloud& out) + { + out.width = in.width; + out.height = in.height; + for (size_t i = 0; i < in.points.size (); i++) + { + Intensity p; + PointRGBtoI (in.points[i], p); + out.points.push_back (p); + } + } + + /** \brief Convert a RGB point cloud to a Intensity + * \param[in] in the input RGB point cloud + * \param[out] out the output Intensity point cloud + */ + inline void + PointCloudRGBtoI (PointCloud& in, + PointCloud& out) + { + out.width = in.width; + out.height = in.height; + for (size_t i = 0; i < in.points.size (); i++) + { + Intensity8u p; + PointRGBtoI (in.points[i], p); + out.points.push_back (p); + } + } + + /** \brief Convert a RGB point cloud to a Intensity + * \param[in] in the input RGB point cloud + * \param[out] out the output Intensity point cloud + */ + inline void + PointCloudRGBtoI (PointCloud& in, + PointCloud& out) + { + out.width = in.width; + out.height = in.height; + for (size_t i = 0; i < in.points.size (); i++) + { + Intensity32u p; + PointRGBtoI (in.points[i], p); + out.points.push_back (p); + } + } + + /** \brief Convert a XYZRGB point cloud to a XYZHSV + * \param[in] in the input XYZRGB point cloud + * \param[out] out the output XYZHSV point cloud + */ + inline void + PointCloudXYZRGBtoXYZHSV (PointCloud& in, + PointCloud& out) + { + out.width = in.width; + out.height = in.height; + for (size_t i = 0; i < in.points.size (); i++) + { + PointXYZHSV p; + PointXYZRGBtoXYZHSV (in.points[i], p); + out.points.push_back (p); + } + } + + /** \brief Convert a XYZRGB point cloud to a XYZHSV + * \param[in] in the input XYZRGB point cloud + * \param[out] out the output XYZHSV point cloud + */ + inline void + PointCloudXYZRGBAtoXYZHSV (PointCloud& in, + PointCloud& out) + { + out.width = in.width; + out.height = in.height; + for (size_t i = 0; i < in.points.size (); i++) + { + PointXYZHSV p; + PointXYZRGBAtoXYZHSV (in.points[i], p); + out.points.push_back (p); + } + } + + /** \brief Convert a XYZRGB point cloud to a XYZI + * \param[in] in the input XYZRGB point cloud + * \param[out] out the output XYZI point cloud + */ + inline void + PointCloudXYZRGBtoXYZI (PointCloud& in, + PointCloud& out) + { + out.width = in.width; + out.height = in.height; + for (size_t i = 0; i < in.points.size (); i++) + { + PointXYZI p; + PointXYZRGBtoXYZI (in.points[i], p); + out.points.push_back (p); + } + } + + /** \brief Convert registered Depth image and RGB image to PointCloudXYZRGBA + * \param[in] depth the input depth image as intensity points in float + * \param[in] image the input RGB image + * \param[in] focal the focal length + * \param[out] out the output pointcloud + * **/ + inline void + PointCloudDepthAndRGBtoXYZRGBA (PointCloud& depth, + PointCloud& image, + float& focal, + PointCloud& out) + { + float bad_point = std::numeric_limits::quiet_NaN(); + size_t width_ = depth.width; + size_t height_ = depth.height; + float constant_ = 1.0f / focal; + + for (size_t v = 0; v < height_; v++) + { + for (size_t u = 0; u < width_; u++) + { + PointXYZRGBA pt; + pt.a = 0; + float depth_ = depth.at (u, v).intensity; + + if (depth_ == 0) + { + pt.x = pt.y = pt.z = bad_point; + } + else + { + pt.z = depth_ * 0.001f; + pt.x = static_cast (u) * pt.z * constant_; + pt.y = static_cast (v) * pt.z * constant_; + } + pt.r = image.at (u, v).r; + pt.g = image.at (u, v).g; + pt.b = image.at (u, v).b; + + out.points.push_back (pt); + } + } + out.width = width_; + out.height = height_; + } +} + +#endif //#ifndef PCL_TYPE_CONVERSIONS_H + diff --git a/pcl-1.7/pcl/range_image/bearing_angle_image.h b/pcl-1.7/pcl/range_image/bearing_angle_image.h new file mode 100644 index 0000000..2245ea5 --- /dev/null +++ b/pcl-1.7/pcl/range_image/bearing_angle_image.h @@ -0,0 +1,89 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Intelligent Robotics Lab, DLUT. + * Author: Qinghua Li, Yan Zhuang, Fei Yan + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Intelligent Robotics Lab, DLUT. nor the names + * of its contributors may be used to endorse or promote products + * derived from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file bearing_angle_image.h + * \Created on: July 07, 2012 + */ + +#ifndef PCL_BEARING_ANGLE_IMAGE_H_ +#define PCL_BEARING_ANGLE_IMAGE_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief class BearingAngleImage is used as an interface to generate Bearing Angle(BA) image. + * \author: Qinghua Li (qinghua__li@163.com) + */ + class BearingAngleImage : public pcl::PointCloud + { + public: + // ===== TYPEDEFS ===== + typedef pcl::PointCloud BaseClass; + + // =====CONSTRUCTOR & DESTRUCTOR===== + /** Constructor */ + BearingAngleImage (); + /** Destructor */ + virtual ~BearingAngleImage (); + + public: + /** \brief Reset all values to an empty Bearing Angle image */ + void + reset (); + + /** \brief Calculate the angle between the laser beam and the segment joining two consecutive + * measurement points. + * \param point1 + * \param point2 + */ + double + getAngle (const PointXYZ &point1, const PointXYZ &point2); + + /** \brief Transform 3D point cloud into a 2D Bearing Angle(BA) image */ + void + generateBAImage (PointCloud& point_cloud); + + protected: + /**< This point is used to be able to return a reference to a unknown gray point */ + PointXYZRGBA unobserved_point_; + }; +} + +#endif // PCL_BEARING_ANGLE_IMAGE_H_ diff --git a/pcl-1.7/pcl/range_image/impl/range_image.hpp b/pcl-1.7/pcl/range_image/impl/range_image.hpp new file mode 100644 index 0000000..4a95a6e --- /dev/null +++ b/pcl-1.7/pcl/range_image/impl/range_image.hpp @@ -0,0 +1,1258 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RANGE_IMAGE_IMPL_HPP_ +#define PCL_RANGE_IMAGE_IMPL_HPP_ + +#include +#include + +namespace pcl +{ + +///////////////////////////////////////////////////////////////////////// +inline float +RangeImage::asinLookUp (float value) +{ + return (asin_lookup_table[ + static_cast ( + static_cast (pcl_lrintf ( (static_cast (lookup_table_size-1) / 2.0f) * value)) + + static_cast (lookup_table_size-1) / 2.0f)]); +} + +///////////////////////////////////////////////////////////////////////// +inline float +RangeImage::atan2LookUp (float y, float x) +{ + if (x==0 && y==0) + return 0; + float ret; + if (fabsf (x) < fabsf (y)) + { + ret = atan_lookup_table[ + static_cast ( + static_cast (pcl_lrintf ( (static_cast (lookup_table_size-1) / 2.0f) * (x / y))) + + static_cast (lookup_table_size-1) / 2.0f)]; + ret = static_cast (x*y > 0 ? M_PI/2-ret : -M_PI/2-ret); + } + else + ret = atan_lookup_table[ + static_cast ( + static_cast (pcl_lrintf ( (static_cast (lookup_table_size-1) / 2.0f) * (y / x))) + + static_cast (lookup_table_size-1)/2.0f)]; + if (x < 0) + ret = static_cast (y < 0 ? ret-M_PI : ret+M_PI); + + return (ret); +} + +///////////////////////////////////////////////////////////////////////// +inline float +RangeImage::cosLookUp (float value) +{ + int cell_idx = static_cast (pcl_lrintf ( (static_cast (lookup_table_size-1)) * fabsf (value) / (2.0f * static_cast (M_PI)))); + return (cos_lookup_table[cell_idx]); +} + +///////////////////////////////////////////////////////////////////////// +template void +RangeImage::createFromPointCloud (const PointCloudType& point_cloud, float angular_resolution, + float max_angle_width, float max_angle_height, + const Eigen::Affine3f& sensor_pose, RangeImage::CoordinateFrame coordinate_frame, + float noise_level, float min_range, int border_size) +{ + createFromPointCloud (point_cloud, angular_resolution, angular_resolution, max_angle_width, max_angle_height, + sensor_pose, coordinate_frame, noise_level, min_range, border_size); +} + +///////////////////////////////////////////////////////////////////////// +template void +RangeImage::createFromPointCloud (const PointCloudType& point_cloud, + float angular_resolution_x, float angular_resolution_y, + float max_angle_width, float max_angle_height, + const Eigen::Affine3f& sensor_pose, RangeImage::CoordinateFrame coordinate_frame, + float noise_level, float min_range, int border_size) +{ + setAngularResolution (angular_resolution_x, angular_resolution_y); + + width = static_cast (pcl_lrint (floor (max_angle_width*angular_resolution_x_reciprocal_))); + height = static_cast (pcl_lrint (floor (max_angle_height*angular_resolution_y_reciprocal_))); + + int full_width = static_cast (pcl_lrint (floor (pcl::deg2rad (360.0f)*angular_resolution_x_reciprocal_))), + full_height = static_cast (pcl_lrint (floor (pcl::deg2rad (180.0f)*angular_resolution_y_reciprocal_))); + image_offset_x_ = (full_width -static_cast (width) )/2; + image_offset_y_ = (full_height-static_cast (height))/2; + is_dense = false; + + getCoordinateFrameTransformation (coordinate_frame, to_world_system_); + to_world_system_ = sensor_pose * to_world_system_; + + to_range_image_system_ = to_world_system_.inverse (Eigen::Isometry); + //std::cout << "to_world_system_ is\n"< void +RangeImage::createFromPointCloudWithKnownSize (const PointCloudType& point_cloud, float angular_resolution, + const Eigen::Vector3f& point_cloud_center, float point_cloud_radius, + const Eigen::Affine3f& sensor_pose, RangeImage::CoordinateFrame coordinate_frame, + float noise_level, float min_range, int border_size) +{ + createFromPointCloudWithKnownSize (point_cloud, angular_resolution, angular_resolution, point_cloud_center, point_cloud_radius, + sensor_pose, coordinate_frame, noise_level, min_range, border_size); +} + +///////////////////////////////////////////////////////////////////////// +template void +RangeImage::createFromPointCloudWithKnownSize (const PointCloudType& point_cloud, + float angular_resolution_x, float angular_resolution_y, + const Eigen::Vector3f& point_cloud_center, float point_cloud_radius, + const Eigen::Affine3f& sensor_pose, RangeImage::CoordinateFrame coordinate_frame, + float noise_level, float min_range, int border_size) +{ + //MEASURE_FUNCTION_TIME; + + //std::cout << "Starting to create range image from "< void +RangeImage::createFromPointCloudWithViewpoints (const PointCloudTypeWithViewpoints& point_cloud, + float angular_resolution, + float max_angle_width, float max_angle_height, + RangeImage::CoordinateFrame coordinate_frame, + float noise_level, float min_range, int border_size) +{ + createFromPointCloudWithViewpoints (point_cloud, angular_resolution, angular_resolution, + max_angle_width, max_angle_height, coordinate_frame, + noise_level, min_range, border_size); +} + +///////////////////////////////////////////////////////////////////////// +template void +RangeImage::createFromPointCloudWithViewpoints (const PointCloudTypeWithViewpoints& point_cloud, + float angular_resolution_x, float angular_resolution_y, + float max_angle_width, float max_angle_height, + RangeImage::CoordinateFrame coordinate_frame, + float noise_level, float min_range, int border_size) +{ + Eigen::Vector3f average_viewpoint = getAverageViewPoint (point_cloud); + Eigen::Affine3f sensor_pose = static_cast (Eigen::Translation3f (average_viewpoint)); + createFromPointCloud (point_cloud, angular_resolution_x, angular_resolution_y, max_angle_width, max_angle_height, + sensor_pose, coordinate_frame, noise_level, min_range, border_size); +} + +///////////////////////////////////////////////////////////////////////// +template void +RangeImage::doZBuffer (const PointCloudType& point_cloud, float noise_level, float min_range, int& top, int& right, int& bottom, int& left) +{ + typedef typename PointCloudType::PointType PointType2; + const typename pcl::PointCloud::VectorType &points2 = point_cloud.points; + + unsigned int size = width*height; + int* counters = new int[size]; + ERASE_ARRAY (counters, size); + + top=height; right=-1; bottom=-1; left=width; + + float x_real, y_real, range_of_current_point; + int x, y; + for (typename pcl::PointCloud::VectorType::const_iterator it=points2.begin (); it!=points2.end (); ++it) + { + if (!isFinite (*it)) // Check for NAN etc + continue; + Vector3fMapConst current_point = it->getVector3fMap (); + + this->getImagePoint (current_point, x_real, y_real, range_of_current_point); + this->real2DToInt2D (x_real, y_real, x, y); + + if (range_of_current_point < min_range|| !isInImage (x, y)) + continue; + //std::cout << " ("< ("< "< "<::infinity (); + float image_point_range = getPoint (image_x, image_y).range; + if (pcl_isinf (image_point_range)) + { + if (image_point_range > 0.0f) + return std::numeric_limits::infinity (); + else + return -std::numeric_limits::infinity (); + } + return image_point_range - range; +} + +///////////////////////////////////////////////////////////////////////// +void +RangeImage::getImagePointFromAngles (float angle_x, float angle_y, float& image_x, float& image_y) const +{ + image_x = (angle_x*cosLookUp (angle_y) + static_cast (M_PI))*angular_resolution_x_reciprocal_ - static_cast (image_offset_x_); + image_y = (angle_y + 0.5f*static_cast (M_PI))*angular_resolution_y_reciprocal_ - static_cast (image_offset_y_); +} + +///////////////////////////////////////////////////////////////////////// +void +RangeImage::real2DToInt2D (float x, float y, int& xInt, int& yInt) const +{ + xInt = static_cast (pcl_lrintf (x)); + yInt = static_cast (pcl_lrintf (y)); +} + +///////////////////////////////////////////////////////////////////////// +bool +RangeImage::isInImage (int x, int y) const +{ + return (x >= 0 && x < static_cast (width) && y >= 0 && y < static_cast (height)); +} + +///////////////////////////////////////////////////////////////////////// +bool +RangeImage::isValid (int x, int y) const +{ + return isInImage (x,y) && pcl_isfinite (getPoint (x,y).range); +} + +///////////////////////////////////////////////////////////////////////// +bool +RangeImage::isValid (int index) const +{ + return pcl_isfinite (getPoint (index).range); +} + +///////////////////////////////////////////////////////////////////////// +bool +RangeImage::isObserved (int x, int y) const +{ + if (!isInImage (x,y) || (pcl_isinf (getPoint (x,y).range)&&getPoint (x,y).range<0.0f)) + return false; + return true; +} + +///////////////////////////////////////////////////////////////////////// +bool +RangeImage::isMaxRange (int x, int y) const +{ + float range = getPoint (x,y).range; + return pcl_isinf (range) && range>0.0f; +} + +///////////////////////////////////////////////////////////////////////// +const PointWithRange& +RangeImage::getPoint (int image_x, int image_y) const +{ + if (!isInImage (image_x, image_y)) + return unobserved_point; + return points[image_y*width + image_x]; +} + +///////////////////////////////////////////////////////////////////////// +const PointWithRange& +RangeImage::getPointNoCheck (int image_x, int image_y) const +{ + return points[image_y*width + image_x]; +} + +///////////////////////////////////////////////////////////////////////// +PointWithRange& +RangeImage::getPointNoCheck (int image_x, int image_y) +{ + return points[image_y*width + image_x]; +} + +///////////////////////////////////////////////////////////////////////// +PointWithRange& +RangeImage::getPoint (int image_x, int image_y) +{ + return points[image_y*width + image_x]; +} + + +///////////////////////////////////////////////////////////////////////// +const PointWithRange& +RangeImage::getPoint (int index) const +{ + return points[index]; +} + +///////////////////////////////////////////////////////////////////////// +const PointWithRange& +RangeImage::getPoint (float image_x, float image_y) const +{ + int x, y; + real2DToInt2D (image_x, image_y, x, y); + return getPoint (x, y); +} + +///////////////////////////////////////////////////////////////////////// +PointWithRange& +RangeImage::getPoint (float image_x, float image_y) +{ + int x, y; + real2DToInt2D (image_x, image_y, x, y); + return getPoint (x, y); +} + +///////////////////////////////////////////////////////////////////////// +void +RangeImage::getPoint (int image_x, int image_y, Eigen::Vector3f& point) const +{ + //std::cout << getPoint (image_x, image_y)<< " - " << getPoint (image_x, image_y).getVector3fMap ()<<"\n"; + point = getPoint (image_x, image_y).getVector3fMap (); +} + +///////////////////////////////////////////////////////////////////////// +void +RangeImage::getPoint (int index, Eigen::Vector3f& point) const +{ + point = getPoint (index).getVector3fMap (); +} + +///////////////////////////////////////////////////////////////////////// +const Eigen::Map +RangeImage::getEigenVector3f (int x, int y) const +{ + return getPoint (x, y).getVector3fMap (); +} + +///////////////////////////////////////////////////////////////////////// +const Eigen::Map +RangeImage::getEigenVector3f (int index) const +{ + return getPoint (index).getVector3fMap (); +} + +///////////////////////////////////////////////////////////////////////// +void +RangeImage::calculate3DPoint (float image_x, float image_y, float range, Eigen::Vector3f& point) const +{ + float angle_x, angle_y; + //std::cout << image_x<<","< (image_offset_y_))*angular_resolution_y_ - 0.5f*static_cast (M_PI); + float cos_angle_y = cosf (angle_y); + angle_x = (cos_angle_y==0.0f ? 0.0f : ( (image_x+ static_cast (image_offset_x_))*angular_resolution_x_ - static_cast (M_PI))/cos_angle_y); +} + +///////////////////////////////////////////////////////////////////////// +float +RangeImage::getImpactAngle (int x1, int y1, int x2, int y2) const +{ + if (!isInImage (x1, y1) || !isInImage (x2,y2)) + return -std::numeric_limits::infinity (); + return getImpactAngle (getPoint (x1,y1),getPoint (x2,y2)); +} + +///////////////////////////////////////////////////////////////////////// +float +RangeImage::getImpactAngle (const PointWithRange& point1, const PointWithRange& point2) const { + if ( (pcl_isinf (point1.range)&&point1.range<0) || (pcl_isinf (point2.range)&&point2.range<0)) + return -std::numeric_limits::infinity (); + + float r1 = (std::min) (point1.range, point2.range), + r2 = (std::max) (point1.range, point2.range); + float impact_angle = static_cast (0.5f * M_PI); + + if (pcl_isinf (r2)) + { + if (r2 > 0.0f && !pcl_isinf (r1)) + impact_angle = 0.0f; + } + else if (!pcl_isinf (r1)) + { + float r1Sqr = r1*r1, + r2Sqr = r2*r2, + dSqr = squaredEuclideanDistance (point1, point2), + d = sqrtf (dSqr); + float cos_impact_angle = (r2Sqr + dSqr - r1Sqr)/ (2.0f*r2*d); + cos_impact_angle = (std::max) (0.0f, (std::min) (1.0f, cos_impact_angle)); + impact_angle = acosf (cos_impact_angle); // Using the cosine rule + } + + if (point1.range > point2.range) + impact_angle = -impact_angle; + + return impact_angle; +} + +///////////////////////////////////////////////////////////////////////// +float +RangeImage::getAcutenessValue (const PointWithRange& point1, const PointWithRange& point2) const +{ + float impact_angle = getImpactAngle (point1, point2); + if (pcl_isinf (impact_angle)) + return -std::numeric_limits::infinity (); + float ret = 1.0f - float (fabs (impact_angle)/ (0.5f*M_PI)); + if (impact_angle < 0.0f) + ret = -ret; + //if (fabs (ret)>1) + //std::cout << PVARAC (impact_angle)<::infinity (); + return getAcutenessValue (getPoint (x1,y1), getPoint (x2,y2)); +} + +///////////////////////////////////////////////////////////////////////// +const Eigen::Vector3f +RangeImage::getSensorPos () const +{ + return Eigen::Vector3f (to_world_system_ (0,3), to_world_system_ (1,3), to_world_system_ (2,3)); +} + +///////////////////////////////////////////////////////////////////////// +void +RangeImage::getSurfaceAngleChange (int x, int y, int radius, float& angle_change_x, float& angle_change_y) const +{ + angle_change_x = angle_change_y = -std::numeric_limits::infinity (); + if (!isValid (x,y)) + return; + Eigen::Vector3f point; + getPoint (x, y, point); + Eigen::Affine3f transformation = getTransformationToViewerCoordinateFrame (point); + + if (isObserved (x-radius, y) && isObserved (x+radius, y)) + { + Eigen::Vector3f transformed_left; + if (isMaxRange (x-radius, y)) + transformed_left = Eigen::Vector3f (0.0f, 0.0f, -1.0f); + else + { + Eigen::Vector3f left; + getPoint (x-radius, y, left); + transformed_left = - (transformation * left); + //std::cout << PVARN (transformed_left[1]); + transformed_left[1] = 0.0f; + transformed_left.normalize (); + } + + Eigen::Vector3f transformed_right; + if (isMaxRange (x+radius, y)) + transformed_right = Eigen::Vector3f (0.0f, 0.0f, 1.0f); + else + { + Eigen::Vector3f right; + getPoint (x+radius, y, right); + transformed_right = transformation * right; + //std::cout << PVARN (transformed_right[1]); + transformed_right[1] = 0.0f; + transformed_right.normalize (); + } + angle_change_x = transformed_left.dot (transformed_right); + angle_change_x = (std::max) (0.0f, (std::min) (1.0f, angle_change_x)); + angle_change_x = acosf (angle_change_x); + } + + if (isObserved (x, y-radius) && isObserved (x, y+radius)) + { + Eigen::Vector3f transformed_top; + if (isMaxRange (x, y-radius)) + transformed_top = Eigen::Vector3f (0.0f, 0.0f, -1.0f); + else + { + Eigen::Vector3f top; + getPoint (x, y-radius, top); + transformed_top = - (transformation * top); + //std::cout << PVARN (transformed_top[0]); + transformed_top[0] = 0.0f; + transformed_top.normalize (); + } + + Eigen::Vector3f transformed_bottom; + if (isMaxRange (x, y+radius)) + transformed_bottom = Eigen::Vector3f (0.0f, 0.0f, 1.0f); + else + { + Eigen::Vector3f bottom; + getPoint (x, y+radius, bottom); + transformed_bottom = transformation * bottom; + //std::cout << PVARN (transformed_bottom[0]); + transformed_bottom[0] = 0.0f; + transformed_bottom.normalize (); + } + angle_change_y = transformed_top.dot (transformed_bottom); + angle_change_y = (std::max) (0.0f, (std::min) (1.0f, angle_change_y)); + angle_change_y = acosf (angle_change_y); + } +} + + +//inline float RangeImage::getSurfaceChange (const PointWithRange& point, const PointWithRange& neighbor1, const PointWithRange& neighbor2) const +//{ + //if (!pcl_isfinite (point.range) || (!pcl_isfinite (neighbor1.range)&&neighbor1.range<0) || (!pcl_isfinite (neighbor2.range)&&neighbor2.range<0)) + //return -std::numeric_limits::infinity (); + //if (pcl_isinf (neighbor1.range)) + //{ + //if (pcl_isinf (neighbor2.range)) + //return 0.0f; + //else + //return acosf ( (Eigen::Vector3f (point.x, point.y, point.z)-getSensorPos ()).normalized ().dot ( (Eigen::Vector3f (neighbor2.x, neighbor2.y, neighbor2.z)-Eigen::Vector3f (point.x, point.y, point.z)).normalized ())); + //} + //if (pcl_isinf (neighbor2.range)) + //return acosf ( (Eigen::Vector3f (point.x, point.y, point.z)-getSensorPos ()).normalized ().dot ( (Eigen::Vector3f (neighbor1.x, neighbor1.y, neighbor1.z)-Eigen::Vector3f (point.x, point.y, point.z)).normalized ())); + + //float d1_squared = squaredEuclideanDistance (point, neighbor1), + //d1 = sqrtf (d1_squared), + //d2_squared = squaredEuclideanDistance (point, neighbor2), + //d2 = sqrtf (d2_squared), + //d3_squared = squaredEuclideanDistance (neighbor1, neighbor2); + //float cos_surface_change = (d1_squared + d2_squared - d3_squared)/ (2.0f*d1*d2), + //surface_change = acosf (cos_surface_change); + //if (pcl_isnan (surface_change)) + //surface_change = static_cast (M_PI); + ////std::cout << PVARN (point)<0.0f) // The first point is max range -> return a max range point + return; + weight_sum = 0.0f; + average_point.x = average_point.y = average_point.z = average_point.range = 0.0f; + } + + int x2=x, y2=y; + Vector4fMap average_point_eigen = average_point.getVector4fMap (); + //std::cout << PVARN (no_of_points); + for (int step=1; step::infinity (); + const PointWithRange& point1 = getPoint (x1,y1), + & point2 = getPoint (x2,y2); + if (pcl_isinf (point1.range) && pcl_isinf (point2.range)) + return 0.0f; + if (pcl_isinf (point1.range) || pcl_isinf (point2.range)) + return std::numeric_limits::infinity (); + return squaredEuclideanDistance (point1, point2); +} + +///////////////////////////////////////////////////////////////////////// +float +RangeImage::getAverageEuclideanDistance (int x, int y, int offset_x, int offset_y, int max_steps) const +{ + float average_pixel_distance = 0.0f; + float weight=0.0f; + for (int i=0; i"<"< "<::infinity (); + const PointWithRange& point = getPoint (x, y); + int no_of_nearest_neighbors = static_cast (pow (static_cast ( (radius + 1.0)), 2.0)); + Eigen::Vector3f normal; + if (!getNormalForClosestNeighbors (x, y, radius, point, no_of_nearest_neighbors, normal, 1)) + return -std::numeric_limits::infinity (); + return deg2rad (90.0f) - acosf (normal.dot ( (getSensorPos ()-getEigenVector3f (point)).normalized ())); +} + + +///////////////////////////////////////////////////////////////////////// +bool +RangeImage::getNormal (int x, int y, int radius, Eigen::Vector3f& normal, int step_size) const +{ + VectorAverage3f vector_average; + for (int y2=y-radius; y2<=y+radius; y2+=step_size) + { + for (int x2=x-radius; x2<=x+radius; x2+=step_size) + { + if (!isInImage (x2, y2)) + continue; + const PointWithRange& point = getPoint (x2, y2); + if (!pcl_isfinite (point.range)) + continue; + vector_average.add (Eigen::Vector3f (point.x, point.y, point.z)); + } + } + if (vector_average.getNoOfSamples () < 3) + return false; + Eigen::Vector3f eigen_values, eigen_vector2, eigen_vector3; + vector_average.doPCA (eigen_values, normal, eigen_vector2, eigen_vector3); + if (normal.dot ( (getSensorPos ()-vector_average.getMean ()).normalized ()) < 0.0f) + normal *= -1.0f; + return true; +} + +///////////////////////////////////////////////////////////////////////// +float +RangeImage::getNormalBasedAcutenessValue (int x, int y, int radius) const +{ + float impact_angle = getImpactAngleBasedOnLocalNormal (x, y, radius); + if (pcl_isinf (impact_angle)) + return -std::numeric_limits::infinity (); + float ret = 1.0f - static_cast ( (impact_angle / (0.5f * M_PI))); + //std::cout << PVARAC (impact_angle)< (pow (static_cast (radius + 1.0), 2.0)); + return getNormalForClosestNeighbors (x, y, radius, getPoint (x,y).getVector3fMap (), no_of_nearest_neighbors, normal); +} + +namespace +{ // Anonymous namespace, so that this is only accessible in this file + struct NeighborWithDistance + { // local struct to help us with sorting + float distance; + const PointWithRange* neighbor; + bool operator < (const NeighborWithDistance& other) const { return distancesetZero (); + if (mean_all_neighbors!=NULL) + mean_all_neighbors->setZero (); + if (eigen_values_all_neighbors!=NULL) + eigen_values_all_neighbors->setZero (); + + int blocksize = static_cast (pow (static_cast ( (2.0 * radius + 1.0)), 2.0)); + + PointWithRange given_point; + given_point.x=point[0]; given_point.y=point[1]; given_point.z=point[2]; + + std::vector ordered_neighbors (blocksize); + int neighbor_counter = 0; + for (int y2=y-radius; y2<=y+radius; y2+=step_size) + { + for (int x2=x-radius; x2<=x+radius; x2+=step_size) + { + if (!isValid (x2, y2)) + continue; + NeighborWithDistance& neighbor_with_distance = ordered_neighbors[neighbor_counter]; + neighbor_with_distance.neighbor = &getPoint (x2, y2); + neighbor_with_distance.distance = squaredEuclideanDistance (given_point, *neighbor_with_distance.neighbor); + ++neighbor_counter; + } + } + no_of_closest_neighbors = (std::min) (neighbor_counter, no_of_closest_neighbors); + + std::sort (ordered_neighbors.begin (), ordered_neighbors.begin () + neighbor_counter); // Normal sort seems to be the fastest method (faster than partial_sort) + //std::stable_sort (ordered_neighbors, ordered_neighbors+neighbor_counter); + //std::partial_sort (ordered_neighbors, ordered_neighbors+no_of_closest_neighbors, ordered_neighbors+neighbor_counter); + + max_closest_neighbor_distance_squared = ordered_neighbors[no_of_closest_neighbors-1].distance; + //float max_distance_squared = max_closest_neighbor_distance_squared; + float max_distance_squared = max_closest_neighbor_distance_squared*4.0f; // Double the allowed distance value + //max_closest_neighbor_distance_squared = max_distance_squared; + + VectorAverage3f vector_average; + //for (int neighbor_idx=0; neighbor_idx max_distance_squared) + break; + //std::cout << ordered_neighbors[neighbor_idx].distance<<"\n"; + vector_average.add (ordered_neighbors[neighbor_idx].neighbor->getVector3fMap ()); + } + + if (vector_average.getNoOfSamples () < 3) + return false; + //std::cout << PVARN (vector_average.getNoOfSamples ()); + Eigen::Vector3f eigen_vector2, eigen_vector3; + vector_average.doPCA (eigen_values, normal, eigen_vector2, eigen_vector3); + Eigen::Vector3f viewing_direction = (getSensorPos ()-point).normalized (); + if (normal.dot (viewing_direction) < 0.0f) + normal *= -1.0f; + mean = vector_average.getMean (); + + if (normal_all_neighbors==NULL) + return true; + + // Add remaining neighbors + for (int neighbor_idx2=neighbor_idx; neighbor_idx2getVector3fMap ()); + + vector_average.doPCA (*eigen_values_all_neighbors, *normal_all_neighbors, eigen_vector2, eigen_vector3); + //std::cout << PVARN (vector_average.getNoOfSamples ())<<".\n"; + if (normal_all_neighbors->dot (viewing_direction) < 0.0f) + *normal_all_neighbors *= -1.0f; + *mean_all_neighbors = vector_average.getMean (); + + //std::cout << viewing_direction[0]<<","<::infinity (); + + int blocksize = static_cast (pow (static_cast (2.0 * radius + 1.0), 2.0)); + std::vector neighbor_distances (blocksize); + int neighbor_counter = 0; + for (int y2=y-radius; y2<=y+radius; y2+=step_size) + { + for (int x2=x-radius; x2<=x+radius; x2+=step_size) + { + if (!isValid (x2, y2) || (x2==x&&y2==y)) + continue; + const PointWithRange& neighbor = getPointNoCheck (x2,y2); + float& neighbor_distance = neighbor_distances[neighbor_counter++]; + neighbor_distance = squaredEuclideanDistance (point, neighbor); + } + } + std::sort (neighbor_distances.begin (), neighbor_distances.begin () + neighbor_counter); // Normal sort seems to be + // the fastest method (faster than partial_sort) + n = (std::min) (neighbor_counter, n); + return neighbor_distances[n-1]; +} + + +///////////////////////////////////////////////////////////////////////// +bool +RangeImage::getNormalForClosestNeighbors (int x, int y, int radius, const Eigen::Vector3f& point, int no_of_nearest_neighbors, + Eigen::Vector3f& normal, Eigen::Vector3f* point_on_plane, int step_size) const +{ + Eigen::Vector3f mean, eigen_values; + float used_squared_max_distance; + bool ret = getSurfaceInformation (x, y, radius, point, no_of_nearest_neighbors, step_size, used_squared_max_distance, + normal, mean, eigen_values); + + if (ret) + { + if (point_on_plane != NULL) + *point_on_plane = (normal.dot (mean) - normal.dot (point))*normal + point; + } + return ret; +} + + +///////////////////////////////////////////////////////////////////////// +float +RangeImage::getCurvature (int x, int y, int radius, int step_size) const +{ + VectorAverage3f vector_average; + for (int y2=y-radius; y2<=y+radius; y2+=step_size) + { + for (int x2=x-radius; x2<=x+radius; x2+=step_size) + { + if (!isInImage (x2, y2)) + continue; + const PointWithRange& point = getPoint (x2, y2); + if (!pcl_isfinite (point.range)) + continue; + vector_average.add (Eigen::Vector3f (point.x, point.y, point.z)); + } + } + if (vector_average.getNoOfSamples () < 3) + return false; + Eigen::Vector3f eigen_values; + vector_average.doPCA (eigen_values); + return eigen_values[0]/eigen_values.sum (); +} + + +///////////////////////////////////////////////////////////////////////// +template Eigen::Vector3f +RangeImage::getAverageViewPoint (const PointCloudTypeWithViewpoints& point_cloud) +{ + Eigen::Vector3f average_viewpoint (0,0,0); + int point_counter = 0; + for (unsigned int point_idx=0; point_idx void +RangeImage::integrateFarRanges (const PointCloudType& far_ranges) +{ + float x_real, y_real, range_of_current_point; + for (typename PointCloudType::const_iterator it = far_ranges.points.begin (); it != far_ranges.points.end (); ++it) + { + //if (!isFinite (*it)) // Check for NAN etc + //continue; + Vector3fMapConst current_point = it->getVector3fMap (); + + this->getImagePoint (current_point, x_real, y_real, range_of_current_point); + + int floor_x = static_cast (pcl_lrint (floor (x_real))), + floor_y = static_cast (pcl_lrint (floor (y_real))), + ceil_x = static_cast (pcl_lrint (ceil (x_real))), + ceil_y = static_cast (pcl_lrint (ceil (y_real))); + + int neighbor_x[4], neighbor_y[4]; + neighbor_x[0]=floor_x; neighbor_y[0]=floor_y; + neighbor_x[1]=floor_x; neighbor_y[1]=ceil_y; + neighbor_x[2]=ceil_x; neighbor_y[2]=floor_y; + neighbor_x[3]=ceil_x; neighbor_y[3]=ceil_y; + + for (int i=0; i<4; ++i) + { + int x=neighbor_x[i], y=neighbor_y[i]; + if (!isInImage (x, y)) + continue; + PointWithRange& image_point = getPoint (x, y); + if (!pcl_isfinite (image_point.range)) + image_point.range = std::numeric_limits::infinity (); + } + } +} + +} // namespace end +#endif + diff --git a/pcl-1.7/pcl/range_image/impl/range_image_planar.hpp b/pcl-1.7/pcl/range_image/impl/range_image_planar.hpp new file mode 100644 index 0000000..b508444 --- /dev/null +++ b/pcl-1.7/pcl/range_image/impl/range_image_planar.hpp @@ -0,0 +1,122 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RANGE_IMAGE_PLANAR_IMPL_HPP_ +#define PCL_RANGE_IMAGE_PLANAR_IMPL_HPP_ + +#include +#include + +namespace pcl +{ + +///////////////////////////////////////////////////////////////////////// +template void +RangeImagePlanar::createFromPointCloudWithFixedSize (const PointCloudType& point_cloud, + int di_width, int di_height, + float di_center_x, float di_center_y, + float di_focal_length_x, float di_focal_length_y, + const Eigen::Affine3f& sensor_pose, + CoordinateFrame coordinate_frame, float noise_level, + float min_range) +{ + //std::cout << "Starting to create range image from "< (image_offset_x_)-center_x_)*focal_length_x_reciprocal_, + delta_y = (image_y+static_cast (image_offset_y_)-center_y_)*focal_length_y_reciprocal_; + point[2] = range / (sqrtf (delta_x*delta_x + delta_y*delta_y + 1)); + point[0] = delta_x*point[2]; + point[1] = delta_y*point[2]; + point = to_world_system_ * point; +} + +///////////////////////////////////////////////////////////////////////// +inline void +RangeImagePlanar::getImagePoint (const Eigen::Vector3f& point, float& image_x, float& image_y, float& range) const +{ + Eigen::Vector3f transformedPoint = to_range_image_system_ * point; + if (transformedPoint[2]<=0) // Behind the observer? + { + image_x = image_y = range = -1.0f; + return; + } + range = transformedPoint.norm (); + + image_x = center_x_ + focal_length_x_*transformedPoint[0]/transformedPoint[2] - static_cast (image_offset_x_); + image_y = center_y_ + focal_length_y_*transformedPoint[1]/transformedPoint[2] - static_cast (image_offset_y_); +} + +} // namespace end + +#endif + diff --git a/pcl-1.7/pcl/range_image/impl/range_image_spherical.hpp b/pcl-1.7/pcl/range_image/impl/range_image_spherical.hpp new file mode 100644 index 0000000..4d77bb7 --- /dev/null +++ b/pcl-1.7/pcl/range_image/impl/range_image_spherical.hpp @@ -0,0 +1,78 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012-, Open Perception, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#include +#include + +namespace pcl +{ + +///////////////////////////////////////////////////////////////////////// +void +RangeImageSpherical::calculate3DPoint (float image_x, float image_y, float range, Eigen::Vector3f& point) const +{ + float angle_x, angle_y; + getAnglesFromImagePoint (image_x, image_y, angle_x, angle_y); + + float cosY = cosf (angle_y); + point = Eigen::Vector3f (range * sinf (angle_x) * cosY, range * sinf (angle_y), range * cosf (angle_x)*cosY); + point = to_world_system_ * point; +} + +///////////////////////////////////////////////////////////////////////// +inline void +RangeImageSpherical::getImagePoint (const Eigen::Vector3f& point, float& image_x, float& image_y, float& range) const +{ + Eigen::Vector3f transformedPoint = to_range_image_system_ * point; + range = transformedPoint.norm (); + float angle_x = atan2LookUp (transformedPoint[0], transformedPoint[2]), + angle_y = asinLookUp (transformedPoint[1]/range); + getImagePointFromAngles (angle_x, angle_y, image_x, image_y); +} +///////////////////////////////////////////////////////////////////////// +void +RangeImageSpherical::getAnglesFromImagePoint (float image_x, float image_y, float& angle_x, float& angle_y) const +{ + angle_y = (image_y+static_cast (image_offset_y_))*angular_resolution_y_ - 0.5f*static_cast (M_PI); + angle_x = ((image_x+ static_cast (image_offset_x_))*angular_resolution_x_ - static_cast (M_PI)); +} +///////////////////////////////////////////////////////////////////////// +void +RangeImageSpherical::getImagePointFromAngles (float angle_x, float angle_y, float& image_x, float& image_y) const +{ + image_x = (angle_x + static_cast (M_PI))*angular_resolution_x_reciprocal_ - static_cast (image_offset_x_); + image_y = (angle_y + 0.5f*static_cast (M_PI))*angular_resolution_y_reciprocal_ - static_cast (image_offset_y_); +} +} // namespace end diff --git a/pcl-1.7/pcl/range_image/range_image.h b/pcl-1.7/pcl/range_image/range_image.h new file mode 100644 index 0000000..79b1d65 --- /dev/null +++ b/pcl-1.7/pcl/range_image/range_image.h @@ -0,0 +1,844 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_RANGE_IMAGE_H_ +#define PCL_RANGE_IMAGE_H_ + +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief RangeImage is derived from pcl/PointCloud and provides functionalities with focus on situations where + * a 3D scene was captured from a specific view point. + * \author Bastian Steder + * \ingroup range_image + */ + class RangeImage : public pcl::PointCloud + { + public: + // =====TYPEDEFS===== + typedef pcl::PointCloud BaseClass; + typedef std::vector > VectorOfEigenVector3f; + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + enum CoordinateFrame + { + CAMERA_FRAME = 0, + LASER_FRAME = 1 + }; + + + // =====CONSTRUCTOR & DESTRUCTOR===== + /** Constructor */ + PCL_EXPORTS RangeImage (); + /** Destructor */ + PCL_EXPORTS virtual ~RangeImage (); + + // =====STATIC VARIABLES===== + /** The maximum number of openmp threads that can be used in this class */ + static int max_no_of_threads; + + // =====STATIC METHODS===== + /** \brief Get the size of a certain area when seen from the given pose + * \param viewer_pose an affine matrix defining the pose of the viewer + * \param center the center of the area + * \param radius the radius of the area + * \return the size of the area as viewed according to \a viewer_pose + */ + static inline float + getMaxAngleSize (const Eigen::Affine3f& viewer_pose, const Eigen::Vector3f& center, + float radius); + + /** \brief Get Eigen::Vector3f from PointWithRange + * \param point the input point + * \return an Eigen::Vector3f representation of the input point + */ + static inline Eigen::Vector3f + getEigenVector3f (const PointWithRange& point); + + /** \brief Get the transformation that transforms the given coordinate frame into CAMERA_FRAME + * \param coordinate_frame the input coordinate frame + * \param transformation the resulting transformation that warps \a coordinate_frame into CAMERA_FRAME + */ + PCL_EXPORTS static void + getCoordinateFrameTransformation (RangeImage::CoordinateFrame coordinate_frame, + Eigen::Affine3f& transformation); + + /** \brief Get the average viewpoint of a point cloud where each point carries viewpoint information as + * vp_x, vp_y, vp_z + * \param point_cloud the input point cloud + * \return the average viewpoint (as an Eigen::Vector3f) + */ + template static Eigen::Vector3f + getAverageViewPoint (const PointCloudTypeWithViewpoints& point_cloud); + + /** \brief Check if the provided data includes far ranges and add them to far_ranges + * \param point_cloud_data a PCLPointCloud2 message containing the input cloud + * \param far_ranges the resulting cloud containing those points with far ranges + */ + PCL_EXPORTS static void + extractFarRanges (const pcl::PCLPointCloud2& point_cloud_data, PointCloud& far_ranges); + + // =====METHODS===== + /** \brief Get a boost shared pointer of a copy of this */ + inline Ptr + makeShared () { return Ptr (new RangeImage (*this)); } + + /** \brief Reset all values to an empty range image */ + PCL_EXPORTS void + reset (); + + /** \brief Create the depth image from a point cloud + * \param point_cloud the input point cloud + * \param angular_resolution the angular difference (in radians) between the individual pixels in the image + * \param max_angle_width an angle (in radians) defining the horizontal bounds of the sensor + * \param max_angle_height an angle (in radians) defining the vertical bounds of the sensor + * \param sensor_pose an affine matrix defining the pose of the sensor (defaults to + * Eigen::Affine3f::Identity () ) + * \param coordinate_frame the coordinate frame (defaults to CAMERA_FRAME) + * \param noise_level - The distance in meters inside of which the z-buffer will not use the minimum, + * but the mean of the points. If 0.0 it is equivalent to a normal z-buffer and + * will always take the minimum per cell. + * \param min_range the minimum visible range (defaults to 0) + * \param border_size the border size (defaults to 0) + */ + template void + createFromPointCloud (const PointCloudType& point_cloud, float angular_resolution=pcl::deg2rad (0.5f), + float max_angle_width=pcl::deg2rad (360.0f), float max_angle_height=pcl::deg2rad (180.0f), + const Eigen::Affine3f& sensor_pose = Eigen::Affine3f::Identity (), + CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f, + float min_range=0.0f, int border_size=0); + + /** \brief Create the depth image from a point cloud + * \param point_cloud the input point cloud + * \param angular_resolution_x the angular difference (in radians) between the + * individual pixels in the image in the x-direction + * \param angular_resolution_y the angular difference (in radians) between the + * individual pixels in the image in the y-direction + * \param max_angle_width an angle (in radians) defining the horizontal bounds of the sensor + * \param max_angle_height an angle (in radians) defining the vertical bounds of the sensor + * \param sensor_pose an affine matrix defining the pose of the sensor (defaults to + * Eigen::Affine3f::Identity () ) + * \param coordinate_frame the coordinate frame (defaults to CAMERA_FRAME) + * \param noise_level - The distance in meters inside of which the z-buffer will not use the minimum, + * but the mean of the points. If 0.0 it is equivalent to a normal z-buffer and + * will always take the minimum per cell. + * \param min_range the minimum visible range (defaults to 0) + * \param border_size the border size (defaults to 0) + */ + template void + createFromPointCloud (const PointCloudType& point_cloud, + float angular_resolution_x=pcl::deg2rad (0.5f), float angular_resolution_y=pcl::deg2rad (0.5f), + float max_angle_width=pcl::deg2rad (360.0f), float max_angle_height=pcl::deg2rad (180.0f), + const Eigen::Affine3f& sensor_pose = Eigen::Affine3f::Identity (), + CoordinateFrame coordinate_frame=CAMERA_FRAME, + float noise_level=0.0f, float min_range=0.0f, int border_size=0); + + /** \brief Create the depth image from a point cloud, getting a hint about the size of the scene for + * faster calculation. + * \param point_cloud the input point cloud + * \param angular_resolution the angle (in radians) between each sample in the depth image + * \param point_cloud_center the center of bounding sphere + * \param point_cloud_radius the radius of the bounding sphere + * \param sensor_pose an affine matrix defining the pose of the sensor (defaults to + * Eigen::Affine3f::Identity () ) + * \param coordinate_frame the coordinate frame (defaults to CAMERA_FRAME) + * \param noise_level - The distance in meters inside of which the z-buffer will not use the minimum, + * but the mean of the points. If 0.0 it is equivalent to a normal z-buffer and + * will always take the minimum per cell. + * \param min_range the minimum visible range (defaults to 0) + * \param border_size the border size (defaults to 0) + */ + template void + createFromPointCloudWithKnownSize (const PointCloudType& point_cloud, float angular_resolution, + const Eigen::Vector3f& point_cloud_center, float point_cloud_radius, + const Eigen::Affine3f& sensor_pose = Eigen::Affine3f::Identity (), + CoordinateFrame coordinate_frame=CAMERA_FRAME, + float noise_level=0.0f, float min_range=0.0f, int border_size=0); + + /** \brief Create the depth image from a point cloud, getting a hint about the size of the scene for + * faster calculation. + * \param point_cloud the input point cloud + * \param angular_resolution_x the angular difference (in radians) between the + * individual pixels in the image in the x-direction + * \param angular_resolution_y the angular difference (in radians) between the + * individual pixels in the image in the y-direction + * \param point_cloud_center the center of bounding sphere + * \param point_cloud_radius the radius of the bounding sphere + * \param sensor_pose an affine matrix defining the pose of the sensor (defaults to + * Eigen::Affine3f::Identity () ) + * \param coordinate_frame the coordinate frame (defaults to CAMERA_FRAME) + * \param noise_level - The distance in meters inside of which the z-buffer will not use the minimum, + * but the mean of the points. If 0.0 it is equivalent to a normal z-buffer and + * will always take the minimum per cell. + * \param min_range the minimum visible range (defaults to 0) + * \param border_size the border size (defaults to 0) + */ + template void + createFromPointCloudWithKnownSize (const PointCloudType& point_cloud, + float angular_resolution_x, float angular_resolution_y, + const Eigen::Vector3f& point_cloud_center, float point_cloud_radius, + const Eigen::Affine3f& sensor_pose = Eigen::Affine3f::Identity (), + CoordinateFrame coordinate_frame=CAMERA_FRAME, + float noise_level=0.0f, float min_range=0.0f, int border_size=0); + + /** \brief Create the depth image from a point cloud, using the average viewpoint of the points + * (vp_x,vp_y,vp_z in the point type) in the point cloud as sensor pose (assuming a rotation of (0,0,0)). + * \param point_cloud the input point cloud + * \param angular_resolution the angle (in radians) between each sample in the depth image + * \param max_angle_width an angle (in radians) defining the horizontal bounds of the sensor + * \param max_angle_height an angle (in radians) defining the vertical bounds of the sensor + * \param coordinate_frame the coordinate frame (defaults to CAMERA_FRAME) + * \param noise_level - The distance in meters inside of which the z-buffer will not use the minimum, + * but the mean of the points. If 0.0 it is equivalent to a normal z-buffer and + * will always take the minimum per cell. + * \param min_range the minimum visible range (defaults to 0) + * \param border_size the border size (defaults to 0) + * \note If wrong_coordinate_system is true, the sensor pose will be rotated to change from a coordinate frame + * with x to the front, y to the left and z to the top to the coordinate frame we use here (x to the right, y + * to the bottom and z to the front) */ + template void + createFromPointCloudWithViewpoints (const PointCloudTypeWithViewpoints& point_cloud, float angular_resolution, + float max_angle_width, float max_angle_height, + CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f, + float min_range=0.0f, int border_size=0); + + /** \brief Create the depth image from a point cloud, using the average viewpoint of the points + * (vp_x,vp_y,vp_z in the point type) in the point cloud as sensor pose (assuming a rotation of (0,0,0)). + * \param point_cloud the input point cloud + * \param angular_resolution_x the angular difference (in radians) between the + * individual pixels in the image in the x-direction + * \param angular_resolution_y the angular difference (in radians) between the + * individual pixels in the image in the y-direction + * \param max_angle_width an angle (in radians) defining the horizontal bounds of the sensor + * \param max_angle_height an angle (in radians) defining the vertical bounds of the sensor + * \param coordinate_frame the coordinate frame (defaults to CAMERA_FRAME) + * \param noise_level - The distance in meters inside of which the z-buffer will not use the minimum, + * but the mean of the points. If 0.0 it is equivalent to a normal z-buffer and + * will always take the minimum per cell. + * \param min_range the minimum visible range (defaults to 0) + * \param border_size the border size (defaults to 0) + * \note If wrong_coordinate_system is true, the sensor pose will be rotated to change from a coordinate frame + * with x to the front, y to the left and z to the top to the coordinate frame we use here (x to the right, y + * to the bottom and z to the front) */ + template void + createFromPointCloudWithViewpoints (const PointCloudTypeWithViewpoints& point_cloud, + float angular_resolution_x, float angular_resolution_y, + float max_angle_width, float max_angle_height, + CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f, + float min_range=0.0f, int border_size=0); + + /** \brief Create an empty depth image (filled with unobserved points) + * \param[in] angular_resolution the angle (in radians) between each sample in the depth image + * \param[in] sensor_pose an affine matrix defining the pose of the sensor (defaults to Eigen::Affine3f::Identity () ) + * \param[in] coordinate_frame the coordinate frame (defaults to CAMERA_FRAME) + * \param[in] angle_width an angle (in radians) defining the horizontal bounds of the sensor (defaults to 2*pi (360deg)) + * \param[in] angle_height an angle (in radians) defining the vertical bounds of the sensor (defaults to pi (180deg)) + */ + void + createEmpty (float angular_resolution, const Eigen::Affine3f& sensor_pose=Eigen::Affine3f::Identity (), + RangeImage::CoordinateFrame coordinate_frame=CAMERA_FRAME, float angle_width=pcl::deg2rad (360.0f), + float angle_height=pcl::deg2rad (180.0f)); + + /** \brief Create an empty depth image (filled with unobserved points) + * \param angular_resolution_x the angular difference (in radians) between the + * individual pixels in the image in the x-direction + * \param angular_resolution_y the angular difference (in radians) between the + * individual pixels in the image in the y-direction + * \param[in] sensor_pose an affine matrix defining the pose of the sensor (defaults to Eigen::Affine3f::Identity () ) + * \param[in] coordinate_frame the coordinate frame (defaults to CAMERA_FRAME) + * \param[in] angle_width an angle (in radians) defining the horizontal bounds of the sensor (defaults to 2*pi (360deg)) + * \param[in] angle_height an angle (in radians) defining the vertical bounds of the sensor (defaults to pi (180deg)) + */ + void + createEmpty (float angular_resolution_x, float angular_resolution_y, + const Eigen::Affine3f& sensor_pose=Eigen::Affine3f::Identity (), + RangeImage::CoordinateFrame coordinate_frame=CAMERA_FRAME, float angle_width=pcl::deg2rad (360.0f), + float angle_height=pcl::deg2rad (180.0f)); + + /** \brief Integrate the given point cloud into the current range image using a z-buffer + * \param point_cloud the input point cloud + * \param noise_level - The distance in meters inside of which the z-buffer will not use the minimum, + * but the mean of the points. If 0.0 it is equivalent to a normal z-buffer and + * will always take the minimum per cell. + * \param min_range the minimum visible range + * \param top returns the minimum y pixel position in the image where a point was added + * \param right returns the maximum x pixel position in the image where a point was added + * \param bottom returns the maximum y pixel position in the image where a point was added + * \param top returns the minimum y position in the image where a point was added + * \param left returns the minimum x pixel position in the image where a point was added + */ + template void + doZBuffer (const PointCloudType& point_cloud, float noise_level, + float min_range, int& top, int& right, int& bottom, int& left); + + /** \brief Integrates the given far range measurements into the range image */ + template void + integrateFarRanges (const PointCloudType& far_ranges); + + /** \brief Cut the range image to the minimal size so that it still contains all actual range readings. + * \param border_size allows increase from the minimal size by the specified number of pixels (defaults to 0) + * \param top if positive, this value overrides the position of the top edge (defaults to -1) + * \param right if positive, this value overrides the position of the right edge (defaults to -1) + * \param bottom if positive, this value overrides the position of the bottom edge (defaults to -1) + * \param left if positive, this value overrides the position of the left edge (defaults to -1) + */ + PCL_EXPORTS void + cropImage (int border_size=0, int top=-1, int right=-1, int bottom=-1, int left=-1); + + /** \brief Get all the range values in one float array of size width*height + * \return a pointer to a new float array containing the range values + * \note This method allocates a new float array; the caller is responsible for freeing this memory. + */ + PCL_EXPORTS float* + getRangesArray () const; + + /** Getter for the transformation from the world system into the range image system + * (the sensor coordinate frame) */ + inline const Eigen::Affine3f& + getTransformationToRangeImageSystem () const { return (to_range_image_system_); } + + /** Setter for the transformation from the range image system + * (the sensor coordinate frame) into the world system */ + inline void + setTransformationToRangeImageSystem (const Eigen::Affine3f& to_range_image_system); + + /** Getter for the transformation from the range image system + * (the sensor coordinate frame) into the world system */ + inline const Eigen::Affine3f& + getTransformationToWorldSystem () const { return to_world_system_;} + + /** Getter for the angular resolution of the range image in x direction in radians per pixel. + * Provided for downwards compatability */ + inline float + getAngularResolution () const { return angular_resolution_x_;} + + /** Getter for the angular resolution of the range image in x direction in radians per pixel. */ + inline float + getAngularResolutionX () const { return angular_resolution_x_;} + + /** Getter for the angular resolution of the range image in y direction in radians per pixel. */ + inline float + getAngularResolutionY () const { return angular_resolution_y_;} + + /** Getter for the angular resolution of the range image in x and y direction (in radians). */ + inline void + getAngularResolution (float& angular_resolution_x, float& angular_resolution_y) const; + + /** \brief Set the angular resolution of the range image + * \param angular_resolution the new angular resolution in x and y direction (in radians per pixel) + */ + inline void + setAngularResolution (float angular_resolution); + + /** \brief Set the angular resolution of the range image + * \param angular_resolution_x the new angular resolution in x direction (in radians per pixel) + * \param angular_resolution_y the new angular resolution in y direction (in radians per pixel) + */ + inline void + setAngularResolution (float angular_resolution_x, float angular_resolution_y); + + + /** \brief Return the 3D point with range at the given image position + * \param image_x the x coordinate + * \param image_y the y coordinate + * \return the point at the specified location (returns unobserved_point if outside of the image bounds) + */ + inline const PointWithRange& + getPoint (int image_x, int image_y) const; + + /** \brief Non-const-version of getPoint */ + inline PointWithRange& + getPoint (int image_x, int image_y); + + /** Return the 3d point with range at the given image position */ + inline const PointWithRange& + getPoint (float image_x, float image_y) const; + + /** Non-const-version of the above */ + inline PointWithRange& + getPoint (float image_x, float image_y); + + /** \brief Return the 3D point with range at the given image position. This methd performs no error checking + * to make sure the specified image position is inside of the image! + * \param image_x the x coordinate + * \param image_y the y coordinate + * \return the point at the specified location (program may fail if the location is outside of the image bounds) + */ + inline const PointWithRange& + getPointNoCheck (int image_x, int image_y) const; + + /** Non-const-version of getPointNoCheck */ + inline PointWithRange& + getPointNoCheck (int image_x, int image_y); + + /** Same as above */ + inline void + getPoint (int image_x, int image_y, Eigen::Vector3f& point) const; + + /** Same as above */ + inline void + getPoint (int index, Eigen::Vector3f& point) const; + + /** Same as above */ + inline const Eigen::Map + getEigenVector3f (int x, int y) const; + + /** Same as above */ + inline const Eigen::Map + getEigenVector3f (int index) const; + + /** Return the 3d point with range at the given index (whereas index=y*width+x) */ + inline const PointWithRange& + getPoint (int index) const; + + /** Calculate the 3D point according to the given image point and range */ + inline void + calculate3DPoint (float image_x, float image_y, float range, PointWithRange& point) const; + /** Calculate the 3D point according to the given image point and the range value at the closest pixel */ + inline void + calculate3DPoint (float image_x, float image_y, PointWithRange& point) const; + + /** Calculate the 3D point according to the given image point and range */ + virtual inline void + calculate3DPoint (float image_x, float image_y, float range, Eigen::Vector3f& point) const; + /** Calculate the 3D point according to the given image point and the range value at the closest pixel */ + inline void + calculate3DPoint (float image_x, float image_y, Eigen::Vector3f& point) const; + + /** Recalculate all 3D point positions according to their pixel position and range */ + PCL_EXPORTS void + recalculate3DPointPositions (); + + /** Get imagePoint from 3D point in world coordinates */ + inline virtual void + getImagePoint (const Eigen::Vector3f& point, float& image_x, float& image_y, float& range) const; + + /** Same as above */ + inline void + getImagePoint (const Eigen::Vector3f& point, int& image_x, int& image_y, float& range) const; + + /** Same as above */ + inline void + getImagePoint (const Eigen::Vector3f& point, float& image_x, float& image_y) const; + + /** Same as above */ + inline void + getImagePoint (const Eigen::Vector3f& point, int& image_x, int& image_y) const; + + /** Same as above */ + inline void + getImagePoint (float x, float y, float z, float& image_x, float& image_y, float& range) const; + + /** Same as above */ + inline void + getImagePoint (float x, float y, float z, float& image_x, float& image_y) const; + + /** Same as above */ + inline void + getImagePoint (float x, float y, float z, int& image_x, int& image_y) const; + + /** point_in_image will be the point in the image at the position the given point would be. Returns + * the range of the given point. */ + inline float + checkPoint (const Eigen::Vector3f& point, PointWithRange& point_in_image) const; + + /** Returns the difference in range between the given point and the range of the point in the image + * at the position the given point would be. + * (Return value is point_in_image.range-given_point.range) */ + inline float + getRangeDifference (const Eigen::Vector3f& point) const; + + /** Get the image point corresponding to the given angles */ + inline void + getImagePointFromAngles (float angle_x, float angle_y, float& image_x, float& image_y) const; + + /** Get the angles corresponding to the given image point */ + inline void + getAnglesFromImagePoint (float image_x, float image_y, float& angle_x, float& angle_y) const; + + /** Transforms an image point in float values to an image point in int values */ + inline void + real2DToInt2D (float x, float y, int& xInt, int& yInt) const; + + /** Check if a point is inside of the image */ + inline bool + isInImage (int x, int y) const; + + /** Check if a point is inside of the image and has a finite range */ + inline bool + isValid (int x, int y) const; + + /** Check if a point has a finite range */ + inline bool + isValid (int index) const; + + /** Check if a point is inside of the image and has either a finite range or a max reading (range=INFINITY) */ + inline bool + isObserved (int x, int y) const; + + /** Check if a point is a max range (range=INFINITY) - please check isInImage or isObserved first! */ + inline bool + isMaxRange (int x, int y) const; + + /** Calculate the normal of an image point using the neighbors with a maximum pixel distance of radius. + * step_size determines how many pixels are used. 1 means all, 2 only every second, etc.. + * Returns false if it was unable to calculate a normal.*/ + inline bool + getNormal (int x, int y, int radius, Eigen::Vector3f& normal, int step_size=1) const; + + /** Same as above, but only the no_of_nearest_neighbors points closest to the given point are considered. */ + inline bool + getNormalForClosestNeighbors (int x, int y, int radius, const PointWithRange& point, + int no_of_nearest_neighbors, Eigen::Vector3f& normal, int step_size=1) const; + + /** Same as above */ + inline bool + getNormalForClosestNeighbors (int x, int y, int radius, const Eigen::Vector3f& point, + int no_of_nearest_neighbors, Eigen::Vector3f& normal, + Eigen::Vector3f* point_on_plane=NULL, int step_size=1) const; + + /** Same as above, using default values */ + inline bool + getNormalForClosestNeighbors (int x, int y, Eigen::Vector3f& normal, int radius=2) const; + + /** Same as above but extracts some more data and can also return the extracted + * information for all neighbors in radius if normal_all_neighbors is not NULL */ + inline bool + getSurfaceInformation (int x, int y, int radius, const Eigen::Vector3f& point, + int no_of_closest_neighbors, int step_size, + float& max_closest_neighbor_distance_squared, + Eigen::Vector3f& normal, Eigen::Vector3f& mean, Eigen::Vector3f& eigen_values, + Eigen::Vector3f* normal_all_neighbors=NULL, + Eigen::Vector3f* mean_all_neighbors=NULL, + Eigen::Vector3f* eigen_values_all_neighbors=NULL) const; + + // Return the squared distance to the n-th neighbors of the point at x,y + inline float + getSquaredDistanceOfNthNeighbor (int x, int y, int radius, int n, int step_size) const; + + /** Calculate the impact angle based on the sensor position and the two given points - will return + * -INFINITY if one of the points is unobserved */ + inline float + getImpactAngle (const PointWithRange& point1, const PointWithRange& point2) const; + //! Same as above + inline float + getImpactAngle (int x1, int y1, int x2, int y2) const; + + /** Extract a local normal (with a heuristic not to include background points) and calculate the impact + * angle based on this */ + inline float + getImpactAngleBasedOnLocalNormal (int x, int y, int radius) const; + /** Uses the above function for every point in the image */ + PCL_EXPORTS float* + getImpactAngleImageBasedOnLocalNormals (int radius) const; + + /** Calculate a score [0,1] that tells how acute the impact angle is (1.0f - getImpactAngle/90deg) + * This uses getImpactAngleBasedOnLocalNormal + * Will return -INFINITY if no normal could be calculated */ + inline float + getNormalBasedAcutenessValue (int x, int y, int radius) const; + + /** Calculate a score [0,1] that tells how acute the impact angle is (1.0f - getImpactAngle/90deg) + * will return -INFINITY if one of the points is unobserved */ + inline float + getAcutenessValue (const PointWithRange& point1, const PointWithRange& point2) const; + //! Same as above + inline float + getAcutenessValue (int x1, int y1, int x2, int y2) const; + + /** Calculate getAcutenessValue for every point */ + PCL_EXPORTS void + getAcutenessValueImages (int pixel_distance, float*& acuteness_value_image_x, + float*& acuteness_value_image_y) const; + + /** Calculates, how much the surface changes at a point. Pi meaning a flat suface and 0.0f + * would be a needle point */ + //inline float + // getSurfaceChange (const PointWithRange& point, const PointWithRange& neighbor1, + // const PointWithRange& neighbor2) const; + + /** Calculates, how much the surface changes at a point. 1 meaning a 90deg angle and 0 a flat suface */ + PCL_EXPORTS float + getSurfaceChange (int x, int y, int radius) const; + + /** Uses the above function for every point in the image */ + PCL_EXPORTS float* + getSurfaceChangeImage (int radius) const; + + /** Calculates, how much the surface changes at a point. Returns an angle [0.0f, PI] for x and y direction. + * A return value of -INFINITY means that a point was unobserved. */ + inline void + getSurfaceAngleChange (int x, int y, int radius, float& angle_change_x, float& angle_change_y) const; + + /** Uses the above function for every point in the image */ + PCL_EXPORTS void + getSurfaceAngleChangeImages (int radius, float*& angle_change_image_x, float*& angle_change_image_y) const; + + /** Calculates the curvature in a point using pca */ + inline float + getCurvature (int x, int y, int radius, int step_size) const; + + //! Get the sensor position + inline const Eigen::Vector3f + getSensorPos () const; + + /** Sets all -INFINITY values to INFINITY */ + PCL_EXPORTS void + setUnseenToMaxRange (); + + //! Getter for image_offset_x_ + inline int + getImageOffsetX () const { return image_offset_x_;} + //! Getter for image_offset_y_ + inline int + getImageOffsetY () const { return image_offset_y_;} + + //! Setter for image offsets + inline void + setImageOffsets (int offset_x, int offset_y) { image_offset_x_=offset_x; image_offset_y_=offset_y;} + + + + /** Get a sub part of the complete image as a new range image. + * \param sub_image_image_offset_x - The x coordinate of the top left pixel of the sub image. + * This is always according to absolute 0,0 meaning -180°,-90° + * and it is already in the system of the new image, so the + * actual pixel used in the original image is + * combine_pixels* (image_offset_x-image_offset_x_) + * \param sub_image_image_offset_y - Same as image_offset_x for the y coordinate + * \param sub_image_width - width of the new image + * \param sub_image_height - height of the new image + * \param combine_pixels - shrinking factor, meaning the new angular resolution + * is combine_pixels times the old one + * \param sub_image - the output image + */ + virtual void + getSubImage (int sub_image_image_offset_x, int sub_image_image_offset_y, int sub_image_width, + int sub_image_height, int combine_pixels, RangeImage& sub_image) const; + + //! Get a range image with half the resolution + virtual void + getHalfImage (RangeImage& half_image) const; + + //! Find the minimum and maximum range in the image + PCL_EXPORTS void + getMinMaxRanges (float& min_range, float& max_range) const; + + //! This function sets the sensor pose to 0 and transforms all point positions to this local coordinate frame + PCL_EXPORTS void + change3dPointsToLocalCoordinateFrame (); + + /** Calculate a range patch as the z values of the coordinate frame given by pose. + * The patch will have size pixel_size x pixel_size and each pixel + * covers world_size/pixel_size meters in the world + * You are responsible for deleting the structure afterwards! */ + PCL_EXPORTS float* + getInterpolatedSurfaceProjection (const Eigen::Affine3f& pose, int pixel_size, float world_size) const; + + //! Same as above, but using the local coordinate frame defined by point and the viewing direction + PCL_EXPORTS float* + getInterpolatedSurfaceProjection (const Eigen::Vector3f& point, int pixel_size, float world_size) const; + + //! Get the local coordinate frame with 0,0,0 in point, upright and Z as the viewing direction + inline Eigen::Affine3f + getTransformationToViewerCoordinateFrame (const Eigen::Vector3f& point) const; + //! Same as above, using a reference for the retrurn value + inline void + getTransformationToViewerCoordinateFrame (const Eigen::Vector3f& point, + Eigen::Affine3f& transformation) const; + //! Same as above, but only returning the rotation + inline void + getRotationToViewerCoordinateFrame (const Eigen::Vector3f& point, Eigen::Affine3f& transformation) const; + + /** Get a local coordinate frame at the given point based on the normal. */ + PCL_EXPORTS bool + getNormalBasedUprightTransformation (const Eigen::Vector3f& point, + float max_dist, Eigen::Affine3f& transformation) const; + + /** Get the integral image of the range values (used for fast blur operations). + * You are responsible for deleting it after usage! */ + PCL_EXPORTS void + getIntegralImage (float*& integral_image, int*& valid_points_num_image) const; + + /** Get a blurred version of the range image using box filters on the provided integral image*/ + PCL_EXPORTS void // Template necessary so that this function also works in derived classes + getBlurredImageUsingIntegralImage (int blur_radius, float* integral_image, int* valid_points_num_image, + RangeImage& range_image) const; + + /** Get a blurred version of the range image using box filters */ + PCL_EXPORTS virtual void // Template necessary so that this function also works in derived classes + getBlurredImage (int blur_radius, RangeImage& range_image) const; + + /** Get the squared euclidean distance between the two image points. + * Returns -INFINITY if one of the points was not observed */ + inline float + getEuclideanDistanceSquared (int x1, int y1, int x2, int y2) const; + //! Doing the above for some steps in the given direction and averaging + inline float + getAverageEuclideanDistance (int x, int y, int offset_x, int offset_y, int max_steps) const; + + //! Project all points on the local plane approximation, thereby smoothing the surface of the scan + PCL_EXPORTS void + getRangeImageWithSmoothedSurface (int radius, RangeImage& smoothed_range_image) const; + //void getLocalNormals (int radius) const; + + /** Calculates the average 3D position of the no_of_points points described by the start + * point x,y in the direction delta. + * Returns a max range point (range=INFINITY) if the first point is max range and an + * unobserved point (range=-INFINITY) if non of the points is observed. */ + inline void + get1dPointAverage (int x, int y, int delta_x, int delta_y, int no_of_points, + PointWithRange& average_point) const; + + /** Calculates the overlap of two range images given the relative transformation + * (from the given image to *this) */ + PCL_EXPORTS float + getOverlap (const RangeImage& other_range_image, const Eigen::Affine3f& relative_transformation, + int search_radius, float max_distance, int pixel_step=1) const; + + /** Get the viewing direction for the given point */ + inline bool + getViewingDirection (int x, int y, Eigen::Vector3f& viewing_direction) const; + + /** Get the viewing direction for the given point */ + inline void + getViewingDirection (const Eigen::Vector3f& point, Eigen::Vector3f& viewing_direction) const; + + /** Return a newly created Range image. + * Can be reimplmented in derived classes like RangeImagePlanar to return an image of the same type. */ + PCL_EXPORTS virtual RangeImage* + getNew () const { return new RangeImage; } + + /** Copy other to *this. Necessary for use in virtual functions that need to copy derived RangeImage classes (like RangeImagePlanar) */ + PCL_EXPORTS virtual void + copyTo (RangeImage& other) const; + + + // =====MEMBER VARIABLES===== + // BaseClass: + // roslib::Header header; + // std::vector points; + // uint32_t width; + // uint32_t height; + // bool is_dense; + + static bool debug; /**< Just for... well... debugging purposes. :-) */ + + protected: + // =====PROTECTED MEMBER VARIABLES===== + Eigen::Affine3f to_range_image_system_; /**< Inverse of to_world_system_ */ + Eigen::Affine3f to_world_system_; /**< Inverse of to_range_image_system_ */ + float angular_resolution_x_; /**< Angular resolution of the range image in x direction in radians per pixel */ + float angular_resolution_y_; /**< Angular resolution of the range image in y direction in radians per pixel */ + float angular_resolution_x_reciprocal_; /**< 1.0/angular_resolution_x_ - provided for better performace of + * multiplication compared to division */ + float angular_resolution_y_reciprocal_; /**< 1.0/angular_resolution_y_ - provided for better performace of + * multiplication compared to division */ + int image_offset_x_, image_offset_y_; /**< Position of the top left corner of the range image compared to + * an image of full size (360x180 degrees) */ + PointWithRange unobserved_point; /**< This point is used to be able to return + * a reference to a non-existing point */ + + // =====PROTECTED METHODS===== + + + // =====STATIC PROTECTED===== + static const int lookup_table_size; + static std::vector asin_lookup_table; + static std::vector atan_lookup_table; + static std::vector cos_lookup_table; + /** Create lookup tables for trigonometric functions */ + static void + createLookupTables (); + + /** Query the asin lookup table */ + static inline float + asinLookUp (float value); + + /** Query the atan2 lookup table */ + static inline float + atan2LookUp (float y, float x); + + /** Query the cos lookup table */ + static inline float + cosLookUp (float value); + + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + /** + * /ingroup range_image + */ + inline std::ostream& + operator<< (std::ostream& os, const RangeImage& r) + { + os << "header: " << std::endl; + os << r.header; + os << "points[]: " << r.points.size () << std::endl; + os << "width: " << r.width << std::endl; + os << "height: " << r.height << std::endl; + os << "sensor_origin_: " + << r.sensor_origin_[0] << ' ' + << r.sensor_origin_[1] << ' ' + << r.sensor_origin_[2] << std::endl; + os << "sensor_orientation_: " + << r.sensor_orientation_.x () << ' ' + << r.sensor_orientation_.y () << ' ' + << r.sensor_orientation_.z () << ' ' + << r.sensor_orientation_.w () << std::endl; + os << "is_dense: " << r.is_dense << std::endl; + os << "angular resolution: " + << RAD2DEG (r.getAngularResolutionX ()) << "deg/pixel in x and " + << RAD2DEG (r.getAngularResolutionY ()) << "deg/pixel in y.\n" << std::endl; + return (os); + } + +} // namespace end + + +#include // Definitions of templated and inline functions + +#endif //#ifndef PCL_RANGE_IMAGE_H_ diff --git a/pcl-1.7/pcl/range_image/range_image_planar.h b/pcl-1.7/pcl/range_image/range_image_planar.h new file mode 100644 index 0000000..90b96bf --- /dev/null +++ b/pcl-1.7/pcl/range_image/range_image_planar.h @@ -0,0 +1,219 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_RANGE_IMAGE_PLANAR_H_ +#define PCL_RANGE_IMAGE_PLANAR_H_ + +#include + +namespace pcl +{ + /** \brief @b RangeImagePlanar is derived from the original range image and differs from it because it's not a + * spherical projection, but using a projection plane (as normal cameras do), therefore being better applicable + * for range sensors that already provide a range image by themselves (stereo cameras, ToF-cameras), so that + * a conversion to point cloud and then to a spherical range image becomes unnecessary. + * \author Bastian Steder + * \ingroup range_image + */ + class RangeImagePlanar : public RangeImage + { + public: + // =====TYPEDEFS===== + typedef RangeImage BaseClass; + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + // =====CONSTRUCTOR & DESTRUCTOR===== + /** Constructor */ + PCL_EXPORTS RangeImagePlanar (); + /** Destructor */ + PCL_EXPORTS virtual ~RangeImagePlanar (); + + /** Return a newly created RangeImagePlanar. + * Reimplmentation to return an image of the same type. */ + virtual RangeImage* + getNew () const { return new RangeImagePlanar; } + + /** Copy *this to other. Derived version - also copying additonal RangeImagePlanar members */ + PCL_EXPORTS virtual void + copyTo (RangeImage& other) const; + + // =====PUBLIC METHODS===== + /** \brief Get a boost shared pointer of a copy of this */ + inline Ptr + makeShared () { return Ptr (new RangeImagePlanar (*this)); } + + /** \brief Create the image from an existing disparity image. + * \param disparity_image the input disparity image data + * \param di_width the disparity image width + * \param di_height the disparity image height + * \param focal_length the focal length of the primary camera that generated the disparity image + * \param base_line the baseline of the stereo pair that generated the disparity image + * \param desired_angular_resolution If this is set, the system will skip as many pixels as necessary to get as + * close to this angular resolution as possible while not going over this value (the density will not be + * lower than this value). The value is in radians per pixel. + */ + PCL_EXPORTS void + setDisparityImage (const float* disparity_image, int di_width, int di_height, + float focal_length, float base_line, float desired_angular_resolution=-1); + + /** Create the image from an existing depth image. + * \param depth_image the input depth image data as float values + * \param di_width the disparity image width + * \param di_height the disparity image height + * \param di_center_x the x-coordinate of the camera's center of projection + * \param di_center_y the y-coordinate of the camera's center of projection + * \param di_focal_length_x the camera's focal length in the horizontal direction + * \param di_focal_length_y the camera's focal length in the vertical direction + * \param desired_angular_resolution If this is set, the system will skip as many pixels as necessary to get as + * close to this angular resolution as possible while not going over this value (the density will not be + * lower than this value). The value is in radians per pixel. + */ + PCL_EXPORTS void + setDepthImage (const float* depth_image, int di_width, int di_height, float di_center_x, float di_center_y, + float di_focal_length_x, float di_focal_length_y, float desired_angular_resolution=-1); + + /** Create the image from an existing depth image. + * \param depth_image the input disparity image data as short values describing millimeters + * \param di_width the disparity image width + * \param di_height the disparity image height + * \param di_center_x the x-coordinate of the camera's center of projection + * \param di_center_y the y-coordinate of the camera's center of projection + * \param di_focal_length_x the camera's focal length in the horizontal direction + * \param di_focal_length_y the camera's focal length in the vertical direction + * \param desired_angular_resolution If this is set, the system will skip as many pixels as necessary to get as + * close to this angular resolution as possible while not going over this value (the density will not be + * lower than this value). The value is in radians per pixel. + */ + PCL_EXPORTS void + setDepthImage (const unsigned short* depth_image, int di_width, int di_height, float di_center_x, float di_center_y, + float di_focal_length_x, float di_focal_length_y, float desired_angular_resolution=-1); + + /** Create the image from an existing point cloud. + * \param point_cloud the source point cloud + * \param di_width the disparity image width + * \param di_height the disparity image height + * \param di_center_x the x-coordinate of the camera's center of projection + * \param di_center_y the y-coordinate of the camera's center of projection + * \param di_focal_length_x the camera's focal length in the horizontal direction + * \param di_focal_length_y the camera's focal length in the vertical direction + * \param sensor_pose the pose of the virtual depth camera + * \param coordinate_frame the used coordinate frame of the point cloud + * \param noise_level what is the typical noise of the sensor - is used for averaging in the z-buffer + * \param min_range minimum range to consifder points + */ + template void + createFromPointCloudWithFixedSize (const PointCloudType& point_cloud, + int di_width, int di_height, float di_center_x, float di_center_y, + float di_focal_length_x, float di_focal_length_y, + const Eigen::Affine3f& sensor_pose, + CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f, + float min_range=0.0f); + + // Since we reimplement some of these overloaded functions, we have to do the following: + using RangeImage::calculate3DPoint; + using RangeImage::getImagePoint; + + /** \brief Calculate the 3D point according to the given image point and range + * \param image_x the x image position + * \param image_y the y image position + * \param range the range + * \param point the resulting 3D point + * \note Implementation according to planar range images (compared to spherical as in the original) + */ + virtual inline void + calculate3DPoint (float image_x, float image_y, float range, Eigen::Vector3f& point) const; + + /** \brief Calculate the image point and range from the given 3D point + * \param point the resulting 3D point + * \param image_x the resulting x image position + * \param image_y the resulting y image position + * \param range the resulting range + * \note Implementation according to planar range images (compared to spherical as in the original) + */ + virtual inline void + getImagePoint (const Eigen::Vector3f& point, float& image_x, float& image_y, float& range) const; + + /** Get a sub part of the complete image as a new range image. + * \param sub_image_image_offset_x - The x coordinate of the top left pixel of the sub image. + * This is always according to absolute 0,0 meaning -180°,-90° + * and it is already in the system of the new image, so the + * actual pixel used in the original image is + * combine_pixels* (image_offset_x-image_offset_x_) + * \param sub_image_image_offset_y - Same as image_offset_x for the y coordinate + * \param sub_image_width - width of the new image + * \param sub_image_height - height of the new image + * \param combine_pixels - shrinking factor, meaning the new angular resolution + * is combine_pixels times the old one + * \param sub_image - the output image + */ + PCL_EXPORTS virtual void + getSubImage (int sub_image_image_offset_x, int sub_image_image_offset_y, int sub_image_width, + int sub_image_height, int combine_pixels, RangeImage& sub_image) const; + + //! Get a range image with half the resolution + PCL_EXPORTS virtual void + getHalfImage (RangeImage& half_image) const; + + //! Getter for the focal length in X + inline float + getFocalLengthX () const { return focal_length_x_; } + + //! Getter for the focal length in Y + inline float + getFocalLengthY () const { return focal_length_y_; } + + //! Getter for the principal point in X + inline float + getCenterX () const { return center_x_; } + + //! Getter for the principal point in Y + inline float + getCenterY () const { return center_y_; } + + + protected: + float focal_length_x_, focal_length_y_; //!< The focal length of the image in pixels + float focal_length_x_reciprocal_, focal_length_y_reciprocal_; //!< 1/focal_length -> for internal use + float center_x_, center_y_; //!< The principle point of the image + }; +} // namespace end + + +#include // Definitions of templated and inline functions + +#endif //#ifndef PCL_RANGE_IMAGE_H_ diff --git a/pcl-1.7/pcl/range_image/range_image_spherical.h b/pcl-1.7/pcl/range_image/range_image_spherical.h new file mode 100644 index 0000000..dfba4d4 --- /dev/null +++ b/pcl-1.7/pcl/range_image/range_image_spherical.h @@ -0,0 +1,114 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012-, Open Perception, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_RANGE_IMAGE_SPHERICAL_H_ +#define PCL_RANGE_IMAGE_SPHERICAL_H_ + +#include + +namespace pcl +{ + /** \brief @b RangeImageSpherical is derived from the original range image and uses a slightly different + * spherical projection. In the original range image, the image will appear more and more + * "scaled down" along the y axis, the further away from the mean line of the image a point is. + * This class removes this scaling, which makes it especially suitable for spinning LIDAR sensors + * that capure a 360° view, since a rotation of the sensor will now simply correspond to a shift of the + * range image. (This class is similar to RangeImagePlanar, but changes less of the behaviour of the base class.) + * \author Andreas Muetzel + * \ingroup range_image + */ + class RangeImageSpherical : public RangeImage + { + public: + // =====TYPEDEFS===== + typedef RangeImage BaseClass; + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + // =====CONSTRUCTOR & DESTRUCTOR===== + /** Constructor */ + PCL_EXPORTS RangeImageSpherical () {} + /** Destructor */ + PCL_EXPORTS virtual ~RangeImageSpherical () {} + + /** Return a newly created RangeImagePlanar. + * Reimplmentation to return an image of the same type. */ + virtual RangeImage* + getNew () const { return new RangeImageSpherical; } + + // =====PUBLIC METHODS===== + /** \brief Get a boost shared pointer of a copy of this */ + inline Ptr + makeShared () { return Ptr (new RangeImageSpherical (*this)); } + + + // Since we reimplement some of these overloaded functions, we have to do the following: + using RangeImage::calculate3DPoint; + using RangeImage::getImagePoint; + + /** \brief Calculate the 3D point according to the given image point and range + * \param image_x the x image position + * \param image_y the y image position + * \param range the range + * \param point the resulting 3D point + * \note Implementation according to planar range images (compared to spherical as in the original) + */ + virtual inline void + calculate3DPoint (float image_x, float image_y, float range, Eigen::Vector3f& point) const; + + /** \brief Calculate the image point and range from the given 3D point + * \param point the resulting 3D point + * \param image_x the resulting x image position + * \param image_y the resulting y image position + * \param range the resulting range + * \note Implementation according to planar range images (compared to spherical as in the original) + */ + virtual inline void + getImagePoint (const Eigen::Vector3f& point, float& image_x, float& image_y, float& range) const; + + /** Get the angles corresponding to the given image point */ + inline void + getAnglesFromImagePoint (float image_x, float image_y, float& angle_x, float& angle_y) const; + + /** Get the image point corresponding to the given ranges */ + inline void + getImagePointFromAngles (float angle_x, float angle_y, float& image_x, float& image_y) const; + + }; +} // namespace end + + +#include // Definitions of templated and inline functions + +#endif //#ifndef PCL_RANGE_IMAGE_SPHERICAL_H_ diff --git a/pcl-1.7/pcl/recognition/auxiliary.h b/pcl-1.7/pcl/recognition/auxiliary.h new file mode 100644 index 0000000..91e775c --- /dev/null +++ b/pcl-1.7/pcl/recognition/auxiliary.h @@ -0,0 +1,467 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RECOGNITION_RANSAC_BASED_AUX_H_ +#define PCL_RECOGNITION_RANSAC_BASED_AUX_H_ + +#include +#include +#include +#include + +#define AUX_PI_FLOAT 3.14159265358979323846f +#define AUX_HALF_PI 1.57079632679489661923f +#define AUX_DEG_TO_RADIANS (3.14159265358979323846f/180.0f) + +namespace pcl +{ + namespace recognition + { + namespace aux + { + template bool + compareOrderedPairs (const std::pair& a, const std::pair& b) + { + if ( a.first == b.first ) + return static_cast (a.second < b.second); + + return static_cast (a.first < b.first); + } + + template T + sqr (T a) + { + return (a*a); + } + + template T + clamp (T value, T min, T max) + { + if ( value < min ) + return min; + else if ( value > max ) + return max; + + return value; + } + + /** \brief Expands the destination bounding box 'dst' such that it contains 'src'. */ + template void + expandBoundingBox (T dst[6], const T src[6]) + { + if ( src[0] < dst[0] ) dst[0] = src[0]; + if ( src[2] < dst[2] ) dst[2] = src[2]; + if ( src[4] < dst[4] ) dst[4] = src[4]; + + if ( src[1] > dst[1] ) dst[1] = src[1]; + if ( src[3] > dst[3] ) dst[3] = src[3]; + if ( src[5] > dst[5] ) dst[5] = src[5]; + } + + /** \brief Expands the bounding box 'bbox' such that it contains the point 'p'. */ + template void + expandBoundingBoxToContainPoint (T bbox[6], const T p[3]) + { + if ( p[0] < bbox[0] ) bbox[0] = p[0]; + else if ( p[0] > bbox[1] ) bbox[1] = p[0]; + + if ( p[1] < bbox[2] ) bbox[2] = p[1]; + else if ( p[1] > bbox[3] ) bbox[3] = p[1]; + + if ( p[2] < bbox[4] ) bbox[4] = p[2]; + else if ( p[2] > bbox[5] ) bbox[5] = p[2]; + } + + /** \brief v[0] = v[1] = v[2] = value */ + template void + set3 (T v[3], T value) + { + v[0] = v[1] = v[2] = value; + } + + /** \brief dst = src */ + template void + copy3 (const T src[3], T dst[3]) + { + dst[0] = src[0]; + dst[1] = src[1]; + dst[2] = src[2]; + } + + /** \brief dst = src */ + template void + copy3 (const T src[3], pcl::PointXYZ& dst) + { + dst.x = src[0]; + dst.y = src[1]; + dst.z = src[2]; + } + + /** \brief a = -a */ + template void + flip3 (T a[3]) + { + a[0] = -a[0]; + a[1] = -a[1]; + a[2] = -a[2]; + } + + /** \brief a = b */ + template bool + equal3 (const T a[3], const T b[3]) + { + return (a[0] == b[0] && a[1] == b[1] && a[2] == b[2]); + } + + /** \brief a += b */ + template void + add3 (T a[3], const T b[3]) + { + a[0] += b[0]; + a[1] += b[1]; + a[2] += b[2]; + } + + /** \brief c = a + b */ + template void + sum3 (const T a[3], const T b[3], T c[3]) + { + c[0] = a[0] + b[0]; + c[1] = a[1] + b[1]; + c[2] = a[2] + b[2]; + } + + /** \brief c = a - b */ + template void + diff3 (const T a[3], const T b[3], T c[3]) + { + c[0] = a[0] - b[0]; + c[1] = a[1] - b[1]; + c[2] = a[2] - b[2]; + } + + template void + cross3 (const T v1[3], const T v2[3], T out[3]) + { + out[0] = v1[1]*v2[2] - v1[2]*v2[1]; + out[1] = v1[2]*v2[0] - v1[0]*v2[2]; + out[2] = v1[0]*v2[1] - v1[1]*v2[0]; + } + + /** \brief Returns the length of v. */ + template T + length3 (const T v[3]) + { + return (std::sqrt (v[0]*v[0] + v[1]*v[1] + v[2]*v[2])); + } + + /** \brief Returns the Euclidean distance between a and b. */ + template T + distance3 (const T a[3], const T b[3]) + { + T l[3] = {a[0]-b[0], a[1]-b[1], a[2]-b[2]}; + return (length3 (l)); + } + + /** \brief Returns the squared Euclidean distance between a and b. */ + template T + sqrDistance3 (const T a[3], const T b[3]) + { + return (aux::sqr (a[0]-b[0]) + aux::sqr (a[1]-b[1]) + aux::sqr (a[2]-b[2])); + } + + /** \brief Returns the dot product a*b */ + template T + dot3 (const T a[3], const T b[3]) + { + return (a[0]*b[0] + a[1]*b[1] + a[2]*b[2]); + } + + /** \brief Returns the dot product (x, y, z)*(u, v, w) = x*u + y*v + z*w */ + template T + dot3 (T x, T y, T z, T u, T v, T w) + { + return (x*u + y*v + z*w); + } + + /** \brief v = scalar*v. */ + template void + mult3 (T* v, T scalar) + { + v[0] *= scalar; + v[1] *= scalar; + v[2] *= scalar; + } + + /** \brief out = scalar*v. */ + template void + mult3 (const T* v, T scalar, T* out) + { + out[0] = v[0]*scalar; + out[1] = v[1]*scalar; + out[2] = v[2]*scalar; + } + + /** \brief Normalize v */ + template void + normalize3 (T v[3]) + { + T inv_len = (static_cast (1.0))/aux::length3 (v); + v[0] *= inv_len; + v[1] *= inv_len; + v[2] *= inv_len; + } + + /** \brief Returns the square length of v. */ + template T + sqrLength3 (const T v[3]) + { + return (v[0]*v[0] + v[1]*v[1] + v[2]*v[2]); + } + + /** Projects 'x' on the plane through 0 and with normal 'planeNormal' and saves the result in 'out'. */ + template void + projectOnPlane3 (const T x[3], const T planeNormal[3], T out[3]) + { + T dot = aux::dot3 (planeNormal, x); + // Project 'x' on the plane normal + T nproj[3] = {-dot*planeNormal[0], -dot*planeNormal[1], -dot*planeNormal[2]}; + aux::sum3 (x, nproj, out); + } + + /** \brief Sets 'm' to the 3x3 identity matrix. */ + template void + identity3x3 (T m[9]) + { + m[0] = m[4] = m[8] = 1.0; + m[1] = m[2] = m[3] = m[5] = m[6] = m[7] = 0.0; + } + + /** \brief out = mat*v. 'm' is an 1D array of 9 elements treated as a 3x3 matrix (row major order). */ + template void + mult3x3(const T m[9], const T v[3], T out[3]) + { + out[0] = v[0]*m[0] + v[1]*m[1] + v[2]*m[2]; + out[1] = v[0]*m[3] + v[1]*m[4] + v[2]*m[5]; + out[2] = v[0]*m[6] + v[1]*m[7] + v[2]*m[8]; + } + + /** Let x, y, z be the columns of the matrix a = [x|y|z]. The method computes out = a*m. + * Note that 'out' is a 1D array of 9 elements and the resulting matrix is stored in row + * major order, i.e., the first matrix row is (out[0] out[1] out[2]), the second + * (out[3] out[4] out[5]) and the third (out[6] out[7] out[8]). */ + template void + mult3x3 (const T x[3], const T y[3], const T z[3], const T m[3][3], T out[9]) + { + out[0] = x[0]*m[0][0] + y[0]*m[1][0] + z[0]*m[2][0]; + out[1] = x[0]*m[0][1] + y[0]*m[1][1] + z[0]*m[2][1]; + out[2] = x[0]*m[0][2] + y[0]*m[1][2] + z[0]*m[2][2]; + + out[3] = x[1]*m[0][0] + y[1]*m[1][0] + z[1]*m[2][0]; + out[4] = x[1]*m[0][1] + y[1]*m[1][1] + z[1]*m[2][1]; + out[5] = x[1]*m[0][2] + y[1]*m[1][2] + z[1]*m[2][2]; + + out[6] = x[2]*m[0][0] + y[2]*m[1][0] + z[2]*m[2][0]; + out[7] = x[2]*m[0][1] + y[2]*m[1][1] + z[2]*m[2][1]; + out[8] = x[2]*m[0][2] + y[2]*m[1][2] + z[2]*m[2][2]; + } + + /** \brief The first 9 elements of 't' are treated as a 3x3 matrix (row major order) and the last 3 as a translation. + * First, 'p' is multiplied by that matrix and then translated. The result is saved in 'out'. */ + template void + transform(const T t[12], const T p[3], T out[3]) + { + out[0] = t[0]*p[0] + t[1]*p[1] + t[2]*p[2] + t[9]; + out[1] = t[3]*p[0] + t[4]*p[1] + t[5]*p[2] + t[10]; + out[2] = t[6]*p[0] + t[7]*p[1] + t[8]*p[2] + t[11]; + } + + /** \brief The first 9 elements of 't' are treated as a 3x3 matrix (row major order) and the last 3 as a translation. + * First, (x, y, z) is multiplied by that matrix and then translated. The result is saved in 'out'. */ + template void + transform(const T t[12], T x, T y, T z, T out[3]) + { + out[0] = t[0]*x + t[1]*y + t[2]*z + t[9]; + out[1] = t[3]*x + t[4]*y + t[5]*z + t[10]; + out[2] = t[6]*x + t[7]*y + t[8]*z + t[11]; + } + + /** \brief Compute out = (upper left 3x3 of mat)*p + last column of mat. */ + template void + transform(const Eigen::Matrix& mat, const pcl::PointXYZ& p, pcl::PointXYZ& out) + { + out.x = mat(0,0)*p.x + mat(0,1)*p.y + mat(0,2)*p.z + mat(0,3); + out.y = mat(1,0)*p.x + mat(1,1)*p.y + mat(1,2)*p.z + mat(1,3); + out.z = mat(2,0)*p.x + mat(2,1)*p.y + mat(2,2)*p.z + mat(2,3); + } + + /** \brief The first 9 elements of 't' are treated as a 3x3 matrix (row major order) and the last 3 as a translation. + * First, 'p' is multiplied by that matrix and then translated. The result is saved in 'out'. */ + template void + transform(const T t[12], const pcl::PointXYZ& p, T out[3]) + { + out[0] = t[0]*p.x + t[1]*p.y + t[2]*p.z + t[9]; + out[1] = t[3]*p.x + t[4]*p.y + t[5]*p.z + t[10]; + out[2] = t[6]*p.x + t[7]*p.y + t[8]*p.z + t[11]; + } + + /** \brief Returns true if the points 'p1' and 'p2' are co-planar and false otherwise. The method assumes that 'n1' + * is a normal at 'p1' and 'n2' is a normal at 'p2'. 'max_angle' is the threshold used for the test. The bigger + * the value the larger the deviation between the normals can be which still leads to a positive test result. The + * angle has to be in radians. */ + template bool + pointsAreCoplanar (const T p1[3], const T n1[3], const T p2[3], const T n2[3], T max_angle) + { + // Compute the angle between 'n1' and 'n2' and compare it with 'max_angle' + if ( std::acos (aux::clamp (aux::dot3 (n1, n2), -1.0f, 1.0f)) > max_angle ) + return (false); + + T cl[3] = {p2[0] - p1[0], p2[1] - p1[1], p2[2] - p1[2]}; + aux::normalize3 (cl); + + // Compute the angle between 'cl' and 'n1' + T tmp_angle = std::acos (aux::clamp (aux::dot3 (n1, cl), -1.0f, 1.0f)); + + // 'tmp_angle' should not deviate too much from 90 degrees + if ( std::fabs (tmp_angle - AUX_HALF_PI) > max_angle ) + return (false); + + // All tests passed => the points are coplanar + return (true); + } + + template void + array12ToMatrix4x4 (const Scalar src[12], Eigen::Matrix& dst) + { + dst(0,0) = src[0]; dst(0,1) = src[1]; dst(0,2) = src[2]; dst(0,3) = src[9]; + dst(1,0) = src[3]; dst(1,1) = src[4]; dst(1,2) = src[5]; dst(1,3) = src[10]; + dst(2,0) = src[6]; dst(2,1) = src[7]; dst(2,2) = src[8]; dst(2,3) = src[11]; + dst(3,0) = dst(3,1) = dst(3,2) = 0.0; dst(3,3) = 1.0; + } + + template void + matrix4x4ToArray12 (const Eigen::Matrix& src, Scalar dst[12]) + { + dst[0] = src(0,0); dst[1] = src(0,1); dst[2] = src(0,2); dst[9] = src(0,3); + dst[3] = src(1,0); dst[4] = src(1,1); dst[5] = src(1,2); dst[10] = src(1,3); + dst[6] = src(2,0); dst[7] = src(2,1); dst[8] = src(2,2); dst[11] = src(2,3); + } + + /** \brief The method copies the input array 'src' to the eigen matrix 'dst' in row major order. + * dst[0] = src(0,0); dst[1] = src(0,1); dst[2] = src(0,2); + * dst[3] = src(1,0); dst[4] = src(1,1); dst[5] = src(1,2); + * dst[6] = src(2,0); dst[7] = src(2,1); dst[8] = src(2,2); + * */ + template void + eigenMatrix3x3ToArray9RowMajor (const Eigen::Matrix& src, T dst[9]) + { + dst[0] = src(0,0); dst[1] = src(0,1); dst[2] = src(0,2); + dst[3] = src(1,0); dst[4] = src(1,1); dst[5] = src(1,2); + dst[6] = src(2,0); dst[7] = src(2,1); dst[8] = src(2,2); + } + + /** \brief The method copies the input array 'src' to the eigen matrix 'dst' in row major order. + * dst(0,0) = src[0]; dst(0,1) = src[1]; dst(0,2) = src[2]; + * dst(1,0) = src[3]; dst(1,1) = src[4]; dst(1,2) = src[5]; + * dst(2,0) = src[6]; dst(2,1) = src[7]; dst(2,2) = src[8]; + * */ + template void + toEigenMatrix3x3RowMajor (const T src[9], Eigen::Matrix& dst) + { + dst(0,0) = src[0]; dst(0,1) = src[1]; dst(0,2) = src[2]; + dst(1,0) = src[3]; dst(1,1) = src[4]; dst(1,2) = src[5]; + dst(2,0) = src[6]; dst(2,1) = src[7]; dst(2,2) = src[8]; + } + + /** brief Computes a rotation matrix from the provided input vector 'axis_angle'. The direction of 'axis_angle' is the rotation axis + * and its magnitude is the angle of rotation about that axis. 'rotation_matrix' is the output rotation matrix saved in row major order. */ + template void + axisAngleToRotationMatrix (const T axis_angle[3], T rotation_matrix[9]) + { + // Get the angle of rotation + T angle = aux::length3 (axis_angle); + if ( angle == 0.0 ) + { + // Undefined rotation -> set to identity + aux::identity3x3 (rotation_matrix); + return; + } + + // Normalize the input + T normalized_axis_angle[3]; + aux::mult3 (axis_angle, static_cast (1.0)/angle, normalized_axis_angle); + + // The eigen objects + Eigen::Matrix mat_axis(normalized_axis_angle); + Eigen::AngleAxis eigen_angle_axis (angle, mat_axis); + + // Save the output + aux::eigenMatrix3x3ToArray9RowMajor (eigen_angle_axis.toRotationMatrix (), rotation_matrix); + } + + /** brief Extracts the angle-axis representation from 'rotation_matrix', i.e., computes a rotation 'axis' and an 'angle' + * of rotation about that axis from the provided input. The output 'angle' is in the range [0, pi] and 'axis' is normalized. */ + template void + rotationMatrixToAxisAngle (const T rotation_matrix[9], T axis[3], T& angle) + { + // The eigen objects + Eigen::AngleAxis angle_axis; + Eigen::Matrix rot_mat; + // Copy the input matrix to the eigen matrix in row major order + aux::toEigenMatrix3x3RowMajor (rotation_matrix, rot_mat); + + // Do the computation + angle_axis.fromRotationMatrix (rot_mat); + + // Save the result + axis[0] = angle_axis.axis () (0,0); + axis[1] = angle_axis.axis () (1,0); + axis[2] = angle_axis.axis () (2,0); + angle = angle_axis.angle (); + + // Make sure that 'angle' is in the range [0, pi] + if ( angle > AUX_PI_FLOAT ) + { + angle = 2.0f*AUX_PI_FLOAT - angle; + aux::flip3 (axis); + } + } + } // namespace aux + } // namespace recognition +} // namespace pcl + +#endif // AUX_H_ diff --git a/pcl-1.7/pcl/recognition/boost.h b/pcl-1.7/pcl/recognition/boost.h new file mode 100644 index 0000000..f3bb93d --- /dev/null +++ b/pcl-1.7/pcl/recognition/boost.h @@ -0,0 +1,51 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $ + * + */ + +#ifndef PCL_RECOGNITION_BOOST_H_ +#define PCL_RECOGNITION_BOOST_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include +//#include + +#endif // PCL_RECOGNITION_BOOST_H_ diff --git a/pcl-1.7/pcl/recognition/bvh.h b/pcl-1.7/pcl/recognition/bvh.h new file mode 100644 index 0000000..bf6e889 --- /dev/null +++ b/pcl-1.7/pcl/recognition/bvh.h @@ -0,0 +1,316 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/* + * bvh.h + * + * Created on: Mar 7, 2013 + * Author: papazov + */ + +#ifndef PCL_RECOGNITION_BVH_H_ +#define PCL_RECOGNITION_BVH_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace recognition + { + /** \brief This class is an implementation of bounding volume hierarchies. Use the build method to construct + * the data structure. To use the class, construct an std::vector of pointers to BVH::BoundedObject objects + * and pass it to the build method. BVH::BoundedObject is a template class, so you can save user-defined data + * in it. + * + * The tree is built such that each leaf contains exactly one object. */ + template + class PCL_EXPORTS BVH + { + public: + class BoundedObject + { + public: + BoundedObject (const UserData& data) + : data_ (data) + { + } + + virtual ~BoundedObject () + { + } + + /** \brief This method is for std::sort. */ + inline static bool + compareCentroidsXCoordinates (const BoundedObject* a, const BoundedObject* b) + { + return static_cast (a->getCentroid ()[0] < b->getCentroid ()[0]); + } + + float* + getBounds () + { + return (bounds_); + } + + float* + getCentroid () + { + return (centroid_); + } + + const float* + getCentroid () const + { + return (centroid_); + } + + UserData& + getData () + { + return (data_); + } + + protected: + /** These are the bounds of the object.*/ + float bounds_[6]; + /** This is the centroid. */ + float centroid_[3]; + /** This is the user-defined data object. */ + UserData data_; + }; + + protected: + class Node + { + public: + /** \brief 'sorted_objects' is a sorted vector of bounded objects. It has to be sorted in ascending order according + * to the objects' x-coordinates. The constructor recursively calls itself with the right 'first_id' and 'last_id' + * and with the same vector 'sorted_objects'. */ + Node (std::vector& sorted_objects, int first_id, int last_id) + { + // Initialize the bounds of the node + memcpy (bounds_, sorted_objects[first_id]->getBounds (), 6*sizeof (float)); + + // Expand the bounds of the node + for ( int i = first_id + 1 ; i <= last_id ; ++i ) + aux::expandBoundingBox(bounds_, sorted_objects[i]->getBounds()); + + // Shall we create children? + if ( first_id != last_id ) + { + // Division by 2 + int mid_id = (first_id + last_id) >> 1; + children_[0] = new Node(sorted_objects, first_id, mid_id); + children_[1] = new Node(sorted_objects, mid_id + 1, last_id); + } + else + { + // We reached a leaf + object_ = sorted_objects[first_id]; + children_[0] = children_[1] = 0; + } + } + + virtual ~Node () + { + if ( children_[0] ) + { + delete children_[0]; + delete children_[1]; + } + } + + bool + hasChildren () const + { + return static_cast(children_[0]); + } + + Node* + getLeftChild () + { + return children_[0]; + } + + Node* + getRightChild () + { + return children_[1]; + } + + BoundedObject* + getObject () + { + return object_; + } + + bool + isLeaf () const + { + return !static_cast(children_[0]); + } + + /** \brief Returns true if 'box' intersects or touches (with a side or a vertex) this node. */ + inline bool + intersect(const float box[6]) const + { + if ( box[1] < bounds_[0] || box[3] < bounds_[2] || box[5] < bounds_[4] || + box[0] > bounds_[1] || box[2] > bounds_[3] || box[4] > bounds_[5] ) + return false; + + return true; + } + + /** \brief Computes and returns the volume of the bounding box of this node. */ + double + computeBoundingBoxVolume() const + { + return (bounds_[1] - bounds_[0]) * (bounds_[3] - bounds_[2]) * (bounds_[5] - bounds_[4]); + } + + friend class BVH; + + protected: + float bounds_[6]; + Node* children_[2]; + BoundedObject* object_; + }; + + public: + BVH() + : root_ (0), + sorted_objects_ (0) + { + } + + virtual ~BVH() + { + this->clear (); + } + + /** \brief Creates the tree. No need to call clear, it's called within the method. 'objects' is a vector of + * pointers to bounded objects which have to have valid bounds and centroids. Use the getData method of + * BoundedObject to retrieve the user-defined data saved in the object. Note that vector will be sorted within + * the method! + * + * The tree is built such that each leaf contains exactly one object. */ + void + build(std::vector& objects) + { + this->clear(); + + if ( objects.size () == 0 ) + return; + + sorted_objects_ = &objects; + + // Now sort the objects according to the x-coordinates of their centroids + std::sort (objects.begin (), objects.end (), BoundedObject::compareCentroidsXCoordinates); + + // Create the root -> it recursively creates the children nodes until each leaf contains exactly one object + root_ = new Node (objects, 0, static_cast (objects.size () - 1)); + } + + /** \brief Frees the memory allocated by this object. After that, you have to call build to use the tree again. */ + void + clear() + { + if ( root_ ) + { + delete root_; + root_ = 0; + } + } + + inline const std::vector* + getInputObjects () const + { + return (sorted_objects_); + } + + /** \brief Pushes back in 'intersected_objects' the bounded objects intersected by the input 'box' and returns true. + * Returns false if no objects are intersected. */ + inline bool + intersect(const float box[6], std::list& intersected_objects) const + { + if ( !root_ ) + return false; + + bool got_intersection = false; + + // Start the intersection process at the root + std::list working_list; + working_list.push_back (root_); + + while ( !working_list.empty () ) + { + Node* node = working_list.front (); + working_list.pop_front (); + + // Is 'node' intersected by the box? + if ( node->intersect (box) ) + { + // We have to check the children of the intersected 'node' + if ( node->hasChildren () ) + { + working_list.push_back (node->getLeftChild ()); + working_list.push_back (node->getRightChild ()); + } + else // 'node' is a leaf -> save it's object in the output list + { + intersected_objects.push_back (node->getObject ()); + got_intersection = true; + } + } + } + + return (got_intersection); + } + + protected: + Node* root_; + std::vector* sorted_objects_; + }; + } // namespace recognition +} // namespace pcl + +#endif /* PCL_RECOGNITION_BVH_H_ */ diff --git a/pcl-1.7/pcl/recognition/cg/correspondence_grouping.h b/pcl-1.7/pcl/recognition/cg/correspondence_grouping.h new file mode 100644 index 0000000..e92a6f8 --- /dev/null +++ b/pcl-1.7/pcl/recognition/cg/correspondence_grouping.h @@ -0,0 +1,202 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_RECOGNITION_CORRESPONDENCE_GROUPING_H_ +#define PCL_RECOGNITION_CORRESPONDENCE_GROUPING_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief Abstract base class for Correspondence Grouping algorithms. + * + * \author Tommaso Cavallari, Federico Tombari, Aitor Aldoma + * \ingroup recognition + */ + template + class CorrespondenceGrouping : public PCLBase + { + public: + typedef pcl::PointCloud SceneCloud; + typedef typename SceneCloud::Ptr SceneCloudPtr; + typedef typename SceneCloud::ConstPtr SceneCloudConstPtr; + + /** \brief Empty constructor. */ + CorrespondenceGrouping () : scene_ (), model_scene_corrs_ () {} + + /** \brief destructor. */ + virtual ~CorrespondenceGrouping() + { + scene_.reset (); + model_scene_corrs_.reset (); + } + + /** \brief Provide a pointer to the scene dataset. + * + * \param[in] scene the const boost shared pointer to a PointCloud message. + */ + virtual inline void + setSceneCloud (const SceneCloudConstPtr &scene) + { + scene_ = scene; + } + + /** \brief Getter for the scene dataset. + * + * \return the const boost shared pointer to a PointCloud message. + */ + inline SceneCloudConstPtr + getSceneCloud () const + { + return (scene_); + } + + /** \brief Provide a pointer to the precomputed correspondences between points in the input dataset and + * points in the scene dataset. The correspondences are going to be clustered into different model hypotheses + * by the algorithm. + * + * \param[in] corrs the correspondences between the model and the scene. + */ + virtual inline void + setModelSceneCorrespondences (const CorrespondencesConstPtr &corrs) + { + model_scene_corrs_ = corrs; + } + + /** \brief Getter for the precomputed correspondences between points in the input dataset and + * points in the scene dataset. + * + * \return the correspondences between the model and the scene. + */ + inline CorrespondencesConstPtr + getModelSceneCorrespondences () const + { + return (model_scene_corrs_); + } + + /** \brief Getter for the vector of characteristic scales associated to each cluster + * + * \return the vector of characteristic scales (assuming scale = model / scene) + */ + inline std::vector + getCharacteristicScales () const + { + return (corr_group_scale_); + } + + /** \brief Clusters the input correspondences belonging to different model instances. + * + * \param[out] clustered_corrs a vector containing the correspondences for each instance of the model found within the input data. + */ + void + cluster (std::vector &clustered_corrs); + + protected: + /** \brief The scene cloud. */ + SceneCloudConstPtr scene_; + + using PCLBase::input_; + + /** \brief The correspondences between points in the input and the scene datasets. */ + CorrespondencesConstPtr model_scene_corrs_; + + /** \brief characteristic scale associated to each correspondence subset; + * if the cg algorithm can not handle scale invariance, the size of the vector will be 0. */ + std::vector corr_group_scale_; + + /** \brief The actual clustering method, should be implemented by each subclass. + * + * \param[out] clustered_corrs a vector containing the correspondences for each instance of the model found within the input data. + */ + virtual void + clusterCorrespondences (std::vector &clustered_corrs) = 0; + + /** \brief This method should get called before starting the actual computation. + * + * Internally, initCompute() does the following: + * - checks if an input dataset is given, and returns false otherwise + * - checks if a scene dataset is given, and returns false otherwise + * - checks if the model-scene correspondences have been given, and returns false otherwise + */ + inline bool + initCompute () + { + if (!PCLBase::initCompute ()) + { + return (false); + } + + if (!scene_) + { + PCL_ERROR ("[initCompute] Scene not set.\n"); + return (false); + } + + if (!input_) + { + PCL_ERROR ("[initCompute] Input not set.\n"); + return (false); + } + + if (!model_scene_corrs_) + { + PCL_ERROR ("[initCompute] Model-Scene Correspondences not set.\n"); + return (false); + } + + return (true); + } + + /** \brief This method should get called after finishing the actual computation. + * + */ + inline bool + deinitCompute () + { + return (true); + } + + }; +} + +#include + +#endif // PCL_RECOGNITION_CORRESPONDENCE_GROUPING_H_ diff --git a/pcl-1.7/pcl/recognition/cg/geometric_consistency.h b/pcl-1.7/pcl/recognition/cg/geometric_consistency.h new file mode 100644 index 0000000..4be2d36 --- /dev/null +++ b/pcl-1.7/pcl/recognition/cg/geometric_consistency.h @@ -0,0 +1,158 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_RECOGNITION_GEOMETRIC_CONSISTENCY_H_ +#define PCL_RECOGNITION_GEOMETRIC_CONSISTENCY_H_ + +#include +#include + +namespace pcl +{ + + /** \brief Class implementing a 3D correspondence grouping enforcing geometric consistency among feature correspondences + * + * \author Federico Tombari, Tommaso Cavallari, Aitor Aldoma + * \ingroup recognition + */ + template + class GeometricConsistencyGrouping : public CorrespondenceGrouping + { + public: + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename pcl::CorrespondenceGrouping::SceneCloudConstPtr SceneCloudConstPtr; + + /** \brief Constructor */ + GeometricConsistencyGrouping () + : gc_threshold_ (3) + , gc_size_ (1.0) + , found_transformations_ () + {} + + + /** \brief Sets the minimum cluster size + * \param[in] threshold the minimum cluster size + */ + inline void + setGCThreshold (int threshold) + { + gc_threshold_ = threshold; + } + + /** \brief Gets the minimum cluster size. + * + * \return the minimum cluster size used by GC. + */ + inline int + getGCThreshold () const + { + return (gc_threshold_); + } + + /** \brief Sets the consensus set resolution. This should be in metric units. + * + * \param[in] gc_size consensus set resolution. + */ + inline void + setGCSize (double gc_size) + { + gc_size_ = gc_size; + } + + /** \brief Gets the consensus set resolution. + * + * \return the consensus set resolution. + */ + inline double + getGCSize () const + { + return (gc_size_); + } + + /** \brief The main function, recognizes instances of the model into the scene set by the user. + * + * \param[out] transformations a vector containing one transformation matrix for each instance of the model recognized into the scene. + * + * \return true if the recognition had been successful or false if errors have occurred. + */ + bool + recognize (std::vector > &transformations); + + /** \brief The main function, recognizes instances of the model into the scene set by the user. + * + * \param[out] transformations a vector containing one transformation matrix for each instance of the model recognized into the scene. + * \param[out] clustered_corrs a vector containing the correspondences for each instance of the model found within the input data (the same output of clusterCorrespondences). + * + * \return true if the recognition had been successful or false if errors have occurred. + */ + bool + recognize (std::vector > &transformations, std::vector &clustered_corrs); + + protected: + using CorrespondenceGrouping::input_; + using CorrespondenceGrouping::scene_; + using CorrespondenceGrouping::model_scene_corrs_; + + /** \brief Minimum cluster size. It shouldn't be less than 3, since at least 3 correspondences are needed to compute the 6DOF pose */ + int gc_threshold_; + + /** \brief Resolution of the consensus set used to cluster correspondences together*/ + double gc_size_; + + /** \brief Transformations found by clusterCorrespondences method. */ + std::vector > found_transformations_; + + /** \brief Cluster the input correspondences in order to distinguish between different instances of the model into the scene. + * + * \param[out] model_instances a vector containing the clustered correspondences for each model found on the scene. + * \return true if the clustering had been successful or false if errors have occurred. + */ + void + clusterCorrespondences (std::vector &model_instances); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_RECOGNITION_GEOMETRIC_CONSISTENCY_H_ diff --git a/pcl-1.7/pcl/recognition/cg/hough_3d.h b/pcl-1.7/pcl/recognition/cg/hough_3d.h new file mode 100644 index 0000000..feb0c15 --- /dev/null +++ b/pcl-1.7/pcl/recognition/cg/hough_3d.h @@ -0,0 +1,517 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id:$ + * + */ + +#ifndef PCL_RECOGNITION_HOUGH_3D_H_ +#define PCL_RECOGNITION_HOUGH_3D_H_ + +#include +#include + +namespace pcl +{ + namespace recognition + { + /** \brief HoughSpace3D is a 3D voting space. Cast votes can be interpolated in order to better deal with approximations introduced by bin quantization. A weight can also be associated with each vote. + * \author Federico Tombari (original), Tommaso Cavallari (PCL port) + * \ingroup recognition + */ + class PCL_EXPORTS HoughSpace3D + { + + public: + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + /** \brief Constructor + * + * \param[in] min_coord minimum (x,y,z) coordinates of the Hough space + * \param[in] bin_size size of each bing of the Hough space. + * \param[in] max_coord maximum (x,y,z) coordinates of the Hough space. + */ + HoughSpace3D (const Eigen::Vector3d &min_coord, const Eigen::Vector3d &bin_size, const Eigen::Vector3d &max_coord); + + /** \brief Reset all cast votes. */ + void + reset (); + + /** \brief Casting a vote for a given position in the Hough space. + * + * \param[in] single_vote_coord coordinates of the vote being cast (in absolute coordinates) + * \param[in] weight weight associated with the vote. + * \param[in] voter_id the numeric id of the voter. Useful to trace back the voting correspondence, if the vote is returned by findMaxima as part of a maximum of the Hough Space. + * \return the index of the bin in which the vote has been cast. + */ + int + vote (const Eigen::Vector3d &single_vote_coord, double weight, int voter_id); + + /** \brief Vote for a given position in the 3D space. The weight is interpolated between the bin pointed by single_vote_coord and its neighbors. + * + * \param[in] single_vote_coord coordinates of the vote being cast. + * \param[in] weight weight associated with the vote. + * \param[in] voter_id the numeric id of the voter. Useful to trace back the voting correspondence, if the vote is returned by findMaxima as a part of a maximum of the Hough Space. + * \return the index of the bin in which the vote has been cast. + */ + int + voteInt (const Eigen::Vector3d &single_vote_coord, double weight, int voter_id); + + /** \brief Find the bins with most votes. + * + * \param[in] min_threshold the minimum number of votes to be included in a bin in order to have its value returned. + * If set to a value between -1 and 0 the Hough space maximum_vote is found and the returned values are all the votes greater than -min_threshold * maximum_vote. + * \param[out] maxima_values the list of Hough Space bin values greater than min_threshold. + * \param[out] maxima_voter_ids for each value returned, a list of the voter ids who cast a vote in that position. + * \return The min_threshold used, either set by the user or found by this method. + */ + double + findMaxima (double min_threshold, std::vector & maxima_values, std::vector > &maxima_voter_ids); + + protected: + + /** \brief Minimum coordinate in the Hough Space. */ + Eigen::Vector3d min_coord_; + + /** \brief Size of each bin in the Hough Space. */ + Eigen::Vector3d bin_size_; + + /** \brief Number of bins for each dimension. */ + Eigen::Vector3i bin_count_; + + /** \brief Used to access hough_space_ as if it was a matrix. */ + int partial_bin_products_[4]; + + /** \brief Total number of bins in the Hough Space. */ + int total_bins_count_; + + /** \brief The Hough Space. */ + std::vector hough_space_; + //boost::unordered_map hough_space_; + + /** \brief List of voters for each bin. */ + boost::unordered_map > voter_ids_; + }; + } + + /** \brief Class implementing a 3D correspondence grouping algorithm that can deal with multiple instances of a model template + * found into a given scene. Each correspondence casts a vote for a reference point in a 3D Hough Space. + * The remaining 3 DOF are taken into account by associating each correspondence with a local Reference Frame. + * The suggested PointModelRfT is pcl::ReferenceFrame + * + * \note If you use this code in any academic work, please cite the original paper: + * - F. Tombari, L. Di Stefano: + * Object recognition in 3D scenes with occlusions and clutter by Hough voting. + * 2010, Fourth Pacific-Rim Symposium on Image and Video Technology + * + * \author Federico Tombari (original), Tommaso Cavallari (PCL port) + * \ingroup recognition + */ + template + class Hough3DGrouping : public CorrespondenceGrouping + { + public: + typedef pcl::PointCloud ModelRfCloud; + typedef typename ModelRfCloud::Ptr ModelRfCloudPtr; + typedef typename ModelRfCloud::ConstPtr ModelRfCloudConstPtr; + + typedef pcl::PointCloud SceneRfCloud; + typedef typename SceneRfCloud::Ptr SceneRfCloudPtr; + typedef typename SceneRfCloud::ConstPtr SceneRfCloudConstPtr; + + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename pcl::CorrespondenceGrouping::SceneCloudConstPtr SceneCloudConstPtr; + + /** \brief Constructor */ + Hough3DGrouping () + : input_rf_ () + , scene_rf_ () + , needs_training_ (true) + , model_votes_ () + , hough_threshold_ (-1) + , hough_bin_size_ (1.0) + , use_interpolation_ (true) + , use_distance_weight_ (false) + , local_rf_normals_search_radius_ (0.0f) + , local_rf_search_radius_ (0.0f) + , hough_space_ () + , found_transformations_ () + , hough_space_initialized_ (false) + {} + + /** \brief Provide a pointer to the input dataset. + * \param[in] cloud the const boost shared pointer to a PointCloud message. + */ + inline void + setInputCloud (const PointCloudConstPtr &cloud) + { + PCLBase::setInputCloud (cloud); + needs_training_ = true; + hough_space_initialized_ = false; + input_rf_.reset(); + } + + /** \brief Provide a pointer to the input dataset's reference frames. + * Each point in the reference frame cloud should be the reference frame of + * the correspondent point in the input dataset. + * + * \param[in] input_rf the pointer to the input cloud's reference frames. + */ + inline void + setInputRf (const ModelRfCloudConstPtr &input_rf) + { + input_rf_ = input_rf; + needs_training_ = true; + hough_space_initialized_ = false; + } + + /** \brief Getter for the input dataset's reference frames. + * Each point in the reference frame cloud should be the reference frame of + * the correspondent point in the input dataset. + * + * \return the pointer to the input cloud's reference frames. + */ + inline ModelRfCloudConstPtr + getInputRf () const + { + return (input_rf_); + } + + /** \brief Provide a pointer to the scene dataset (i.e. the cloud in which the algorithm has to search for instances of the input model) + * + * \param[in] scene the const boost shared pointer to a PointCloud message. + */ + inline void + setSceneCloud (const SceneCloudConstPtr &scene) + { + scene_ = scene; + hough_space_initialized_ = false; + scene_rf_.reset(); + } + + /** \brief Provide a pointer to the scene dataset's reference frames. + * Each point in the reference frame cloud should be the reference frame of + * the correspondent point in the scene dataset. + * + * \param[in] scene_rf the pointer to the scene cloud's reference frames. + */ + inline void + setSceneRf (const SceneRfCloudConstPtr &scene_rf) + { + scene_rf_ = scene_rf; + hough_space_initialized_ = false; + } + + /** \brief Getter for the scene dataset's reference frames. + * Each point in the reference frame cloud should be the reference frame of + * the correspondent point in the scene dataset. + * + * \return the pointer to the scene cloud's reference frames. + */ + inline SceneRfCloudConstPtr + getSceneRf () const + { + return (scene_rf_); + } + + /** \brief Provide a pointer to the precomputed correspondences between points in the input dataset and + * points in the scene dataset. The correspondences are going to be clustered into different model instances + * by the algorithm. + * + * \param[in] corrs the correspondences between the model and the scene. + */ + inline void + setModelSceneCorrespondences (const CorrespondencesConstPtr &corrs) + { + model_scene_corrs_ = corrs; + hough_space_initialized_ = false; + } + + /** \brief Sets the minimum number of votes in the Hough space needed to infer the presence of a model instance into the scene cloud. + * + * \param[in] threshold the threshold for the Hough space voting, if set between -1 and 0 the maximum vote in the + * entire space is automatically calculated and -threshold the maximum value is used as a threshold. This means + * that a value between -1 and 0 should be used only if at least one instance of the model is always present in + * the scene, or if this false positive can be filtered later. + */ + inline void + setHoughThreshold (double threshold) + { + hough_threshold_ = threshold; + } + + /** \brief Gets the minimum number of votes in the Hough space needed to infer the presence of a model instance into the scene cloud. + * + * \return the threshold for the Hough space voting. + */ + inline double + getHoughThreshold () const + { + return (hough_threshold_); + } + + /** \brief Sets the size of each bin into the Hough space. + * + * \param[in] bin_size the size of each Hough space's bin. + */ + inline void + setHoughBinSize (double bin_size) + { + hough_bin_size_ = bin_size; + hough_space_initialized_ = false; + } + + /** \brief Gets the size of each bin into the Hough space. + * + * \return the size of each Hough space's bin. + */ + inline double + getHoughBinSize () const + { + return (hough_bin_size_); + } + + /** \brief Sets whether the vote casting procedure interpolates + * the score between neighboring bins of the Hough space or not. + * + * \param[in] use_interpolation the algorithm should interpolate the vote score between neighboring bins. + */ + inline void + setUseInterpolation (bool use_interpolation) + { + use_interpolation_ = use_interpolation; + hough_space_initialized_ = false; + } + + /** \brief Gets whether the vote casting procedure interpolates + * the score between neighboring bins of the Hough space or not. + * + * \return if the algorithm should interpolate the vote score between neighboring bins. + */ + inline bool + getUseInterpolation () const + { + return (use_interpolation_); + } + + /** \brief Sets whether the vote casting procedure uses the correspondence's distance as a score. + * + * \param[in] use_distance_weight the algorithm should use the weighted distance when calculating the Hough voting score. + */ + inline void + setUseDistanceWeight (bool use_distance_weight) + { + use_distance_weight_ = use_distance_weight; + hough_space_initialized_ = false; + } + + /** \brief Gets whether the vote casting procedure uses the correspondence's distance as a score. + * + * \return if the algorithm should use the weighted distance when calculating the Hough voting score. + */ + inline bool + getUseDistanceWeight () const + { + return (use_distance_weight_); + } + + /** \brief If the Local reference frame has not been set for either the model cloud or the scene cloud, + * this algorithm makes the computation itself but needs a suitable search radius to compute the normals + * in order to subsequently compute the RF (if not set a default 15 nearest neighbors search is performed). + * + * \param[in] local_rf_normals_search_radius the normals search radius for the local reference frame calculation. + */ + inline void + setLocalRfNormalsSearchRadius (float local_rf_normals_search_radius) + { + local_rf_normals_search_radius_ = local_rf_normals_search_radius; + needs_training_ = true; + hough_space_initialized_ = false; + } + + /** \brief If the Local reference frame has not been set for either the model cloud or the scene cloud, + * this algorithm makes the computation itself but needs a suitable search radius to compute the normals + * in order to subsequently compute the RF (if not set a default 15 nearest neighbors search is performed). + * + * \return the normals search radius for the local reference frame calculation. + */ + inline float + getLocalRfNormalsSearchRadius () const + { + return (local_rf_normals_search_radius_); + } + + /** \brief If the Local reference frame has not been set for either the model cloud or the scene cloud, + * this algorithm makes the computation itself but needs a suitable search radius to do so. + * \attention This parameter NEEDS to be set if the reference frames are not precomputed externally, + * otherwise the recognition results won't be correct. + * + * \param[in] local_rf_search_radius the search radius for the local reference frame calculation. + */ + inline void + setLocalRfSearchRadius (float local_rf_search_radius) + { + local_rf_search_radius_ = local_rf_search_radius; + needs_training_ = true; + hough_space_initialized_ = false; + } + + /** \brief If the Local reference frame has not been set for either the model cloud or the scene cloud, + * this algorithm makes the computation itself but needs a suitable search radius to do so. + * \attention This parameter NEEDS to be set if the reference frames are not precomputed externally, + * otherwise the recognition results won't be correct. + * + * \return the search radius for the local reference frame calculation. + */ + inline float + getLocalRfSearchRadius () const + { + return (local_rf_search_radius_); + } + + /** \brief Call this function after setting the input, the input_rf and the hough_bin_size parameters to perform an off line training of the algorithm. This might be useful if one wants to perform once and for all a pre-computation of votes that only concern the models, increasing the on-line efficiency of the grouping algorithm. + * The algorithm is automatically trained on the first invocation of the recognize method or the cluster method if this training function has not been manually invoked. + * + * \return true if the training had been successful or false if errors have occurred. + */ + bool + train (); + + /** \brief The main function, recognizes instances of the model into the scene set by the user. + * + * \param[out] transformations a vector containing one transformation matrix for each instance of the model recognized into the scene. + * + * \return true if the recognition had been successful or false if errors have occurred. + */ + bool + recognize (std::vector > &transformations); + + /** \brief The main function, recognizes instances of the model into the scene set by the user. + * + * \param[out] transformations a vector containing one transformation matrix for each instance of the model recognized into the scene. + * \param[out] clustered_corrs a vector containing the correspondences for each instance of the model found within the input data (the same output of clusterCorrespondences). + * + * \return true if the recognition had been successful or false if errors have occurred. + */ + bool + recognize (std::vector > &transformations, std::vector &clustered_corrs); + + protected: + using CorrespondenceGrouping::input_; + using CorrespondenceGrouping::scene_; + using CorrespondenceGrouping::model_scene_corrs_; + + /** \brief The input Rf cloud. */ + ModelRfCloudConstPtr input_rf_; + + /** \brief The scene Rf cloud. */ + SceneRfCloudConstPtr scene_rf_; + + /** \brief If the training of the Hough space is needed; set on change of either the input cloud or the input_rf. */ + bool needs_training_; + + /** \brief The result of the training. The vector between each model point and the centroid of the model adjusted by its local reference frame.*/ + std::vector model_votes_; + + /** \brief The minimum number of votes in the Hough space needed to infer the presence of a model instance into the scene cloud. */ + double hough_threshold_; + + /** \brief The size of each bin of the hough space. */ + double hough_bin_size_; + + /** \brief Use the interpolation between neighboring Hough bins when casting votes. */ + bool use_interpolation_; + + /** \brief Use the weighted correspondence distance when casting votes. */ + bool use_distance_weight_; + + /** \brief Normals search radius for the potential Rf calculation. */ + float local_rf_normals_search_radius_; + + /** \brief Search radius for the potential Rf calculation. */ + float local_rf_search_radius_; + + /** \brief The Hough space. */ + boost::shared_ptr hough_space_; + + /** \brief Transformations found by clusterCorrespondences method. */ + std::vector > found_transformations_; + + /** \brief Whether the Hough space already contains the correct votes for the current input parameters and so the cluster and recognize calls don't need to recompute each value. + * Reset on the change of any parameter except the hough_threshold. + */ + bool hough_space_initialized_; + + /** \brief Cluster the input correspondences in order to distinguish between different instances of the model into the scene. + * + * \param[out] model_instances a vector containing the clustered correspondences for each model found on the scene. + * \return true if the clustering had been successful or false if errors have occurred. + */ + void + clusterCorrespondences (std::vector &model_instances); + + /* \brief Finds the transformation matrix between the input and the scene cloud for a set of correspondences using a RANSAC algorithm. + * \param[in] the scene cloud in which the PointSceneT has been converted to PointModelT. + * \param[in] corrs a set of correspondences. + * \param[out] transform the transformation matrix between the input cloud and the scene cloud that aligns the found correspondences. + * \return true if the recognition had been successful or false if errors have occurred. + */ + //bool + //getTransformMatrix (const PointCloudConstPtr &scene_cloud, const Correspondences &corrs, Eigen::Matrix4f &transform); + + /** \brief The Hough space voting procedure. + * \return true if the voting had been successful or false if errors have occurred. + */ + bool + houghVoting (); + + /** \brief Computes the reference frame for an input cloud. + * \param[in] input the input cloud. + * \param[out] rf the resulting reference frame. + */ + template void + computeRf (const boost::shared_ptr > &input, pcl::PointCloud &rf); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_RECOGNITION_HOUGH_3D_H_ diff --git a/pcl-1.7/pcl/recognition/color_gradient_dot_modality.h b/pcl-1.7/pcl/recognition/color_gradient_dot_modality.h new file mode 100644 index 0000000..cc9cd20 --- /dev/null +++ b/pcl-1.7/pcl/recognition/color_gradient_dot_modality.h @@ -0,0 +1,765 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_COLOR_GRADIENT_DOT_MODALITY +#define PCL_FEATURES_COLOR_GRADIENT_DOT_MODALITY + +#include +#include +#include + +#include +#include + + +namespace pcl +{ + + /** \brief A point structure for representing RGB color + * \ingroup common + */ + struct EIGEN_ALIGN16 PointRGB + { + union + { + union + { + struct + { + uint8_t b; + uint8_t g; + uint8_t r; + uint8_t _unused; + }; + float rgb; + }; + uint32_t rgba; + }; + + inline PointRGB () + {} + + inline PointRGB (const uint8_t b, const uint8_t g, const uint8_t r) + : b (b), g (g), r (r), _unused (0) + {} + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + + /** \brief A point structure representing Euclidean xyz coordinates, and the intensity value. + * \ingroup common + */ + struct EIGEN_ALIGN16 GradientXY + { + union + { + struct + { + float x; + float y; + float angle; + float magnitude; + }; + float data[4]; + }; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + inline bool operator< (const GradientXY & rhs) + { + return (magnitude > rhs.magnitude); + } + }; + inline std::ostream & operator << (std::ostream & os, const GradientXY & p) + { + os << "(" << p.x << "," << p.y << " - " << p.magnitude << ")"; + return (os); + } + + // -------------------------------------------------------------------------- + + template + class ColorGradientDOTModality + : public DOTModality, public PCLBase + { + protected: + using PCLBase::input_; + + struct Candidate + { + GradientXY gradient; + + int x; + int y; + + bool operator< (const Candidate & rhs) + { + return (gradient.magnitude > rhs.gradient.magnitude); + } + }; + + public: + typedef typename pcl::PointCloud PointCloudIn; + + ColorGradientDOTModality (size_t bin_size); + + virtual ~ColorGradientDOTModality (); + + inline void + setGradientMagnitudeThreshold (const float threshold) + { + gradient_magnitude_threshold_ = threshold; + } + + //inline QuantizedMap & + //getDominantQuantizedMap () + //{ + // return (dominant_quantized_color_gradients_); + //} + + inline QuantizedMap & + getDominantQuantizedMap () + { + return (dominant_quantized_color_gradients_); + } + + QuantizedMap + computeInvariantQuantizedMap (const MaskMap & mask, + const RegionXY & region); + + /** \brief Provide a pointer to the input dataset (overwrites the PCLBase::setInputCloud method) + * \param cloud the const boost shared pointer to a PointCloud message + */ + virtual void + setInputCloud (const typename PointCloudIn::ConstPtr & cloud) + { + input_ = cloud; + //processInputData (); + } + + virtual void + processInputData (); + + protected: + + void + computeMaxColorGradients (); + + void + computeDominantQuantizedGradients (); + + //void + //computeInvariantQuantizedGradients (); + + private: + size_t bin_size_; + + float gradient_magnitude_threshold_; + pcl::PointCloud color_gradients_; + + pcl::QuantizedMap dominant_quantized_color_gradients_; + //pcl::QuantizedMap invariant_quantized_color_gradients_; + + }; + +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::ColorGradientDOTModality:: +ColorGradientDOTModality (const size_t bin_size) + : bin_size_ (bin_size), gradient_magnitude_threshold_ (80.0f), color_gradients_ (), dominant_quantized_color_gradients_ () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::ColorGradientDOTModality:: +~ColorGradientDOTModality () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::ColorGradientDOTModality:: +processInputData () +{ + // extract color gradients + computeMaxColorGradients (); + + // compute dominant quantized gradient map + computeDominantQuantizedGradients (); + + // compute invariant quantized gradient map + //computeInvariantQuantizedGradients (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::ColorGradientDOTModality:: +computeMaxColorGradients () +{ + const int width = input_->width; + const int height = input_->height; + + color_gradients_.points.resize (width*height); + color_gradients_.width = width; + color_gradients_.height = height; + + const float pi = tan(1.0f)*4; + for (int row_index = 0; row_index < height-2; ++row_index) + { + for (int col_index = 0; col_index < width-2; ++col_index) + { + const int index0 = row_index*width+col_index; + const int index_c = row_index*width+col_index+2; + const int index_r = (row_index+2)*width+col_index; + + //const int index_d = (row_index+1)*width+col_index+1; + + const unsigned char r0 = input_->points[index0].r; + const unsigned char g0 = input_->points[index0].g; + const unsigned char b0 = input_->points[index0].b; + + const unsigned char r_c = input_->points[index_c].r; + const unsigned char g_c = input_->points[index_c].g; + const unsigned char b_c = input_->points[index_c].b; + + const unsigned char r_r = input_->points[index_r].r; + const unsigned char g_r = input_->points[index_r].g; + const unsigned char b_r = input_->points[index_r].b; + + const float r_dx = static_cast (r_c) - static_cast (r0); + const float g_dx = static_cast (g_c) - static_cast (g0); + const float b_dx = static_cast (b_c) - static_cast (b0); + + const float r_dy = static_cast (r_r) - static_cast (r0); + const float g_dy = static_cast (g_r) - static_cast (g0); + const float b_dy = static_cast (b_r) - static_cast (b0); + + const float sqr_mag_r = r_dx*r_dx + r_dy*r_dy; + const float sqr_mag_g = g_dx*g_dx + g_dy*g_dy; + const float sqr_mag_b = b_dx*b_dx + b_dy*b_dy; + + GradientXY gradient; + gradient.x = col_index; + gradient.y = row_index; + if (sqr_mag_r > sqr_mag_g && sqr_mag_r > sqr_mag_b) + { + gradient.magnitude = sqrt (sqr_mag_r); + gradient.angle = atan2 (r_dy, r_dx) * 180.0f / pi; + } + else if (sqr_mag_g > sqr_mag_b) + { + //GradientXY gradient; + gradient.magnitude = sqrt (sqr_mag_g); + gradient.angle = atan2 (g_dy, g_dx) * 180.0f / pi; + //gradient.x = col_index; + //gradient.y = row_index; + + //color_gradients_ (col_index+1, row_index+1) = gradient; + } + else + { + //GradientXY gradient; + gradient.magnitude = sqrt (sqr_mag_b); + gradient.angle = atan2 (b_dy, b_dx) * 180.0f / pi; + //gradient.x = col_index; + //gradient.y = row_index; + + //color_gradients_ (col_index+1, row_index+1) = gradient; + } + + assert (color_gradients_ (col_index+1, row_index+1).angle >= -180 && + color_gradients_ (col_index+1, row_index+1).angle <= 180); + + color_gradients_ (col_index+1, row_index+1) = gradient; + } + } + + return; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +//template +//void +//pcl::ColorGradientDOTModality:: +//computeInvariantQuantizedGradients () +//{ +// const size_t input_width = input_->width; +// const size_t input_height = input_->height; +// +// const size_t output_width = input_width / bin_size; +// const size_t output_height = input_height / bin_size; +// +// invariant_quantized_color_gradients_.resize (output_width, output_height); +// +// size_t offset_x = 0; +// size_t offset_y = 0; +// +// const size_t num_gradient_bins = 7; +// const size_t max_num_of_gradients = 7; +// +// const float divisor = 180.0f / (num_gradient_bins - 1.0f); +// +// float global_max_gradient = 0.0f; +// float local_max_gradient = 0.0f; +// +// unsigned char * peak_pointer = dominant_quantized_color_gradients_.getData (); +// +// //int tmpCounter = 0; +// for (size_t row_bin_index = 0; row_bin_index < output_height; ++row_bin_index) +// { +// for (size_t col_bin_index = 0; col_bin_index < output_width; ++col_bin_index) +// { +// std::vector x_coordinates; +// std::vector y_coordinates; +// std::vector values; +// +// for (int row_pixel_index = -static_cast (bin_size)/2; +// row_pixel_index <= static_cast (bin_size)/2; +// row_pixel_index += static_cast (bin_size)/2) +// { +// const size_t y_position = offset_y + row_pixel_index; +// +// if (y_position < 0 || y_position >= input_height) continue; +// +// for (int col_pixel_index = -static_cast (bin_size)/2; +// col_pixel_index <= static_cast (bin_size)/2; +// col_pixel_index += static_cast (bin_size)/2) +// { +// const size_t x_position = offset_x + col_pixel_index; +// size_t counter = 0; +// +// if (x_position < 0 || x_position >= input_width) continue; +// +// // find maximum gradient magnitude in current bin +// { +// local_max_gradient = 0.0f; +// for (size_t row_sub_index = 0; row_sub_index < bin_size; ++row_sub_index) +// { +// for (size_t col_sub_index = 0; col_sub_index < bin_size; ++col_sub_index) +// { +// const float magnitude = color_gradients_ (col_sub_index + x_position, row_sub_index + y_position).magnitude; +// +// if (magnitude > local_max_gradient) +// local_max_gradient = magnitude; +// } +// } +// } +// +// //*stringPointer += localMaxGradient; +// +// if (local_max_gradient > global_max_gradient) +// { +// global_max_gradient = local_max_gradient; +// } +// +// // iteratively search for the largest gradients, set it to -1, search the next largest ... etc. +// while (true) +// { +// float max_gradient; +// size_t max_gradient_pos_x; +// size_t max_gradient_pos_y; +// +// // find next location and value of maximum gradient magnitude in current region +// { +// max_gradient = 0.0f; +// for (size_t row_sub_index = 0; row_sub_index < bin_size; ++row_sub_index) +// { +// for (size_t col_sub_index = 0; col_sub_index < bin_size; ++col_sub_index) +// { +// const float magnitude = color_gradients_ (col_sub_index + x_position, row_sub_index + y_position).magnitude; +// +// if (magnitude > max_gradient) +// { +// max_gradient = magnitude; +// max_gradient_pos_x = col_sub_index; +// max_gradient_pos_y = row_sub_index; +// } +// } +// } +// } +// +// // TODO: really localMaxGradient and not maxGradient??? +// if (local_max_gradient < gradient_magnitude_threshold_) +// { +// //*peakPointer |= 1 << (numOfGradientBins-1); +// break; +// } +// +// // TODO: replace gradient_magnitude_threshold_ here by a fixed ratio? +// if (max_gradient < (local_max_gradient * gradient_magnitude_threshold_) || +// counter >= max_num_of_gradients) +// { +// break; +// } +// +// ++counter; +// +// const size_t angle = static_cast (180 + color_gradients_ (max_gradient_pos_x + x_position, max_gradient_pos_y + y_position).angle + 0.5f); +// const size_t bin_index = static_cast ((angle >= 180 ? angle-180 : angle)/divisor); +// +// *peak_pointer |= 1 << bin_index; +// +// x_coordinates.push_back (max_gradient_pos_x + x_position); +// y_coordinates.push_back (max_gradient_pos_y + y_position); +// values.push_back (max_gradient); +// +// color_gradients_ (max_gradient_pos_x + x_position, max_gradient_pos_y + y_position).magnitude = -1.0f; +// } +// +// // reset values which have been set to -1 +// for (size_t value_index = 0; value_index < values.size (); ++value_index) +// { +// color_gradients_ (x_coordinates[value_index], y_coordinates[value_index]).magnitude = values[value_index]; +// } +// +// x_coordinates.clear (); +// y_coordinates.clear (); +// values.clear (); +// } +// } +// +// if (*peak_pointer == 0) +// { +// *peak_pointer |= 1 << 7; +// } +// +// //if (*peakPointer != 0) +// //{ +// // ++tmpCounter; +// //} +// +// //++stringPointer; +// ++peak_pointer; +// +// offset_x += bin_size; +// } +// +// offset_y += bin_size; +// offset_x = bin_size/2+1; +// } +//} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::ColorGradientDOTModality:: +computeDominantQuantizedGradients () +{ + const size_t input_width = input_->width; + const size_t input_height = input_->height; + + const size_t output_width = input_width / bin_size_; + const size_t output_height = input_height / bin_size_; + + dominant_quantized_color_gradients_.resize (output_width, output_height); + + //size_t offset_x = 0; + //size_t offset_y = 0; + + const size_t num_gradient_bins = 7; + const size_t max_num_of_gradients = 1; + + const float divisor = 180.0f / (num_gradient_bins - 1.0f); + + float global_max_gradient = 0.0f; + float local_max_gradient = 0.0f; + + unsigned char * peak_pointer = dominant_quantized_color_gradients_.getData (); + memset (peak_pointer, 0, output_width*output_height); + + //int tmpCounter = 0; + for (size_t row_bin_index = 0; row_bin_index < output_height; ++row_bin_index) + { + for (size_t col_bin_index = 0; col_bin_index < output_width; ++col_bin_index) + { + const size_t x_position = col_bin_index * bin_size_; + const size_t y_position = row_bin_index * bin_size_; + + //std::vector x_coordinates; + //std::vector y_coordinates; + //std::vector values; + + // iteratively search for the largest gradients, set it to -1, search the next largest ... etc. + //while (counter < max_num_of_gradients) + { + float max_gradient; + size_t max_gradient_pos_x; + size_t max_gradient_pos_y; + + // find next location and value of maximum gradient magnitude in current region + { + max_gradient = 0.0f; + for (size_t row_sub_index = 0; row_sub_index < bin_size_; ++row_sub_index) + { + for (size_t col_sub_index = 0; col_sub_index < bin_size_; ++col_sub_index) + { + const float magnitude = color_gradients_ (col_sub_index + x_position, row_sub_index + y_position).magnitude; + + if (magnitude > max_gradient) + { + max_gradient = magnitude; + max_gradient_pos_x = col_sub_index; + max_gradient_pos_y = row_sub_index; + } + } + } + } + + if (max_gradient >= gradient_magnitude_threshold_) + { + const size_t angle = static_cast (180 + color_gradients_ (max_gradient_pos_x + x_position, max_gradient_pos_y + y_position).angle + 0.5f); + const size_t bin_index = static_cast ((angle >= 180 ? angle-180 : angle)/divisor); + + *peak_pointer |= 1 << bin_index; + } + + //++counter; + + //x_coordinates.push_back (max_gradient_pos_x + x_position); + //y_coordinates.push_back (max_gradient_pos_y + y_position); + //values.push_back (max_gradient); + + //color_gradients_ (max_gradient_pos_x + x_position, max_gradient_pos_y + y_position).magnitude = -1.0f; + } + + //// reset values which have been set to -1 + //for (size_t value_index = 0; value_index < values.size (); ++value_index) + //{ + // color_gradients_ (x_coordinates[value_index], y_coordinates[value_index]).magnitude = values[value_index]; + //} + + + if (*peak_pointer == 0) + { + *peak_pointer |= 1 << 7; + } + + //if (*peakPointer != 0) + //{ + // ++tmpCounter; + //} + + //++stringPointer; + ++peak_pointer; + + //offset_x += bin_size; + } + + //offset_y += bin_size; + //offset_x = bin_size/2+1; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::QuantizedMap +pcl::ColorGradientDOTModality:: +computeInvariantQuantizedMap (const MaskMap & mask, + const RegionXY & region) +{ + const size_t input_width = input_->width; + const size_t input_height = input_->height; + + const size_t output_width = input_width / bin_size_; + const size_t output_height = input_height / bin_size_; + + const size_t sub_start_x = region.x / bin_size_; + const size_t sub_start_y = region.y / bin_size_; + const size_t sub_width = region.width / bin_size_; + const size_t sub_height = region.height / bin_size_; + + QuantizedMap map; + map.resize (sub_width, sub_height); + + //size_t offset_x = 0; + //size_t offset_y = 0; + + const size_t num_gradient_bins = 7; + const size_t max_num_of_gradients = 7; + + const float divisor = 180.0f / (num_gradient_bins - 1.0f); + + float global_max_gradient = 0.0f; + float local_max_gradient = 0.0f; + + unsigned char * peak_pointer = map.getData (); + + //int tmpCounter = 0; + for (size_t row_bin_index = 0; row_bin_index < sub_height; ++row_bin_index) + { + for (size_t col_bin_index = 0; col_bin_index < sub_width; ++col_bin_index) + { + std::vector x_coordinates; + std::vector y_coordinates; + std::vector values; + + for (int row_pixel_index = -static_cast (bin_size_)/2; + row_pixel_index <= static_cast (bin_size_)/2; + row_pixel_index += static_cast (bin_size_)/2) + { + const size_t y_position = /*offset_y +*/ row_pixel_index + (sub_start_y + row_bin_index)*bin_size_; + + if (y_position < 0 || y_position >= input_height) + continue; + + for (int col_pixel_index = -static_cast (bin_size_)/2; + col_pixel_index <= static_cast (bin_size_)/2; + col_pixel_index += static_cast (bin_size_)/2) + { + const size_t x_position = /*offset_x +*/ col_pixel_index + (sub_start_x + col_bin_index)*bin_size_; + size_t counter = 0; + + if (x_position < 0 || x_position >= input_width) + continue; + + // find maximum gradient magnitude in current bin + { + local_max_gradient = 0.0f; + for (size_t row_sub_index = 0; row_sub_index < bin_size_; ++row_sub_index) + { + for (size_t col_sub_index = 0; col_sub_index < bin_size_; ++col_sub_index) + { + const float magnitude = color_gradients_ (col_sub_index + x_position, row_sub_index + y_position).magnitude; + + if (magnitude > local_max_gradient) + local_max_gradient = magnitude; + } + } + } + + //*stringPointer += localMaxGradient; + + if (local_max_gradient > global_max_gradient) + { + global_max_gradient = local_max_gradient; + } + + // iteratively search for the largest gradients, set it to -1, search the next largest ... etc. + while (true) + { + float max_gradient; + size_t max_gradient_pos_x; + size_t max_gradient_pos_y; + + // find next location and value of maximum gradient magnitude in current region + { + max_gradient = 0.0f; + for (size_t row_sub_index = 0; row_sub_index < bin_size_; ++row_sub_index) + { + for (size_t col_sub_index = 0; col_sub_index < bin_size_; ++col_sub_index) + { + const float magnitude = color_gradients_ (col_sub_index + x_position, row_sub_index + y_position).magnitude; + + if (magnitude > max_gradient) + { + max_gradient = magnitude; + max_gradient_pos_x = col_sub_index; + max_gradient_pos_y = row_sub_index; + } + } + } + } + + // TODO: really localMaxGradient and not maxGradient??? + if (local_max_gradient < gradient_magnitude_threshold_) + { + //*peakPointer |= 1 << (numOfGradientBins-1); + break; + } + + // TODO: replace gradient_magnitude_threshold_ here by a fixed ratio? + if (/*max_gradient < (local_max_gradient * gradient_magnitude_threshold_) ||*/ + counter >= max_num_of_gradients) + { + break; + } + + ++counter; + + const size_t angle = static_cast (180 + color_gradients_ (max_gradient_pos_x + x_position, max_gradient_pos_y + y_position).angle + 0.5f); + const size_t bin_index = static_cast ((angle >= 180 ? angle-180 : angle)/divisor); + + *peak_pointer |= 1 << bin_index; + + x_coordinates.push_back (max_gradient_pos_x + x_position); + y_coordinates.push_back (max_gradient_pos_y + y_position); + values.push_back (max_gradient); + + color_gradients_ (max_gradient_pos_x + x_position, max_gradient_pos_y + y_position).magnitude = -1.0f; + } + + // reset values which have been set to -1 + for (size_t value_index = 0; value_index < values.size (); ++value_index) + { + color_gradients_ (x_coordinates[value_index], y_coordinates[value_index]).magnitude = values[value_index]; + } + + x_coordinates.clear (); + y_coordinates.clear (); + values.clear (); + } + } + + if (*peak_pointer == 0) + { + *peak_pointer |= 1 << 7; + } + + //if (*peakPointer != 0) + //{ + // ++tmpCounter; + //} + + //++stringPointer; + ++peak_pointer; + + //offset_x += bin_size; + } + + //offset_y += bin_size; + //offset_x = bin_size/2+1; + } + + return map; +} + +#endif diff --git a/pcl-1.7/pcl/recognition/color_gradient_modality.h b/pcl-1.7/pcl/recognition/color_gradient_modality.h new file mode 100644 index 0000000..1618711 --- /dev/null +++ b/pcl-1.7/pcl/recognition/color_gradient_modality.h @@ -0,0 +1,1124 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RECOGNITION_COLOR_GRADIENT_MODALITY +#define PCL_RECOGNITION_COLOR_GRADIENT_MODALITY + +#include + +#include +#include +#include +#include +#include + +#include + +namespace pcl +{ + + /** \brief Modality based on max-RGB gradients. + * \author Stefan Holzer + */ + template + class ColorGradientModality + : public QuantizableModality, public PCLBase + { + protected: + using PCLBase::input_; + + /** \brief Candidate for a feature (used in feature extraction methods). */ + struct Candidate + { + /** \brief The gradient. */ + GradientXY gradient; + + /** \brief The x-position. */ + int x; + /** \brief The y-position. */ + int y; + + /** \brief Operator for comparing to candidates (by magnitude of the gradient). + * \param[in] rhs the candidate to compare with. + */ + bool operator< (const Candidate & rhs) const + { + return (gradient.magnitude > rhs.gradient.magnitude); + } + }; + + public: + typedef typename pcl::PointCloud PointCloudIn; + + /** \brief Different methods for feature selection/extraction. */ + enum FeatureSelectionMethod + { + MASK_BORDER_HIGH_GRADIENTS, + MASK_BORDER_EQUALLY, // this gives templates most equally to the OpenCV implementation + DISTANCE_MAGNITUDE_SCORE + }; + + /** \brief Constructor. */ + ColorGradientModality (); + /** \brief Destructor. */ + virtual ~ColorGradientModality (); + + /** \brief Sets the threshold for the gradient magnitude which is used when quantizing the data. + * Gradients with a smaller magnitude are ignored. + * \param[in] threshold the new gradient magnitude threshold. + */ + inline void + setGradientMagnitudeThreshold (const float threshold) + { + gradient_magnitude_threshold_ = threshold; + } + + /** \brief Sets the threshold for the gradient magnitude which is used for feature extraction. + * Gradients with a smaller magnitude are ignored. + * \param[in] threshold the new gradient magnitude threshold. + */ + inline void + setGradientMagnitudeThresholdForFeatureExtraction (const float threshold) + { + gradient_magnitude_threshold_feature_extraction_ = threshold; + } + + /** \brief Sets the feature selection method. + * \param[in] method the feature selection method. + */ + inline void + setFeatureSelectionMethod (const FeatureSelectionMethod method) + { + feature_selection_method_ = method; + } + + /** \brief Sets the spreading size for spreading the quantized data. */ + inline void + setSpreadingSize (const size_t spreading_size) + { + spreading_size_ = spreading_size; + } + + /** \brief Sets whether variable feature numbers for feature extraction is enabled. + * \param[in] enabled enables/disables variable feature numbers for feature extraction. + */ + inline void + setVariableFeatureNr (const bool enabled) + { + variable_feature_nr_ = enabled; + } + + /** \brief Returns a reference to the internally computed quantized map. */ + inline QuantizedMap & + getQuantizedMap () + { + return (filtered_quantized_color_gradients_); + } + + /** \brief Returns a reference to the internally computed spreaded quantized map. */ + inline QuantizedMap & + getSpreadedQuantizedMap () + { + return (spreaded_filtered_quantized_color_gradients_); + } + + /** \brief Returns a point cloud containing the max-RGB gradients. */ + inline pcl::PointCloud & + getMaxColorGradients () + { + return (color_gradients_); + } + + /** \brief Extracts features from this modality within the specified mask. + * \param[in] mask defines the areas where features are searched in. + * \param[in] nr_features defines the number of features to be extracted + * (might be less if not sufficient information is present in the modality). + * \param[in] modalityIndex the index which is stored in the extracted features. + * \param[out] features the destination for the extracted features. + */ + void + extractFeatures (const MaskMap & mask, size_t nr_features, size_t modalityIndex, + std::vector & features) const; + + /** \brief Extracts all possible features from the modality within the specified mask. + * \param[in] mask defines the areas where features are searched in. + * \param[in] nr_features IGNORED (TODO: remove this parameter). + * \param[in] modalityIndex the index which is stored in the extracted features. + * \param[out] features the destination for the extracted features. + */ + void + extractAllFeatures (const MaskMap & mask, size_t nr_features, size_t modalityIndex, + std::vector & features) const; + + /** \brief Provide a pointer to the input dataset (overwrites the PCLBase::setInputCloud method) + * \param cloud the const boost shared pointer to a PointCloud message + */ + virtual void + setInputCloud (const typename PointCloudIn::ConstPtr & cloud) + { + input_ = cloud; + } + + /** \brief Processes the input data (smoothing, computing gradients, quantizing, filtering, spreading). */ + virtual void + processInputData (); + + /** \brief Processes the input data assuming that everything up to filtering is already done/available + * (so only spreading is performed). */ + virtual void + processInputDataFromFiltered (); + + protected: + + /** \brief Computes the Gaussian kernel used for smoothing. + * \param[in] kernel_size the size of the Gaussian kernel. + * \param[in] sigma the sigma. + * \param[out] kernel_values the destination for the values of the kernel. */ + void + computeGaussianKernel (const size_t kernel_size, const float sigma, std::vector & kernel_values); + + /** \brief Computes the max-RGB gradients for the specified cloud. + * \param[in] cloud the cloud for which the gradients are computed. + */ + void + computeMaxColorGradients (const typename pcl::PointCloud::ConstPtr & cloud); + + /** \brief Computes the max-RGB gradients for the specified cloud using sobel. + * \param[in] cloud the cloud for which the gradients are computed. + */ + void + computeMaxColorGradientsSobel (const typename pcl::PointCloud::ConstPtr & cloud); + + /** \brief Quantizes the color gradients. */ + void + quantizeColorGradients (); + + /** \brief Filters the quantized gradients. */ + void + filterQuantizedColorGradients (); + + /** \brief Erodes a mask. + * \param[in] mask_in the mask which will be eroded. + * \param[out] mask_out the destination for the eroded mask. + */ + static void + erode (const pcl::MaskMap & mask_in, pcl::MaskMap & mask_out); + + private: + + /** \brief Determines whether variable numbers of features are extracted or not. */ + bool variable_feature_nr_; + + /** \brief Stores a smoothed verion of the input cloud. */ + pcl::PointCloud::Ptr smoothed_input_; + + /** \brief Defines which feature selection method is used. */ + FeatureSelectionMethod feature_selection_method_; + + /** \brief The threshold applied on the gradient magnitudes (for quantization). */ + float gradient_magnitude_threshold_; + /** \brief The threshold applied on the gradient magnitudes for feature extraction. */ + float gradient_magnitude_threshold_feature_extraction_; + + /** \brief The point cloud which holds the max-RGB gradients. */ + pcl::PointCloud color_gradients_; + + /** \brief The spreading size. */ + size_t spreading_size_; + + /** \brief The map which holds the quantized max-RGB gradients. */ + pcl::QuantizedMap quantized_color_gradients_; + /** \brief The map which holds the filtered quantized data. */ + pcl::QuantizedMap filtered_quantized_color_gradients_; + /** \brief The map which holds the spreaded quantized data. */ + pcl::QuantizedMap spreaded_filtered_quantized_color_gradients_; + + }; + +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::ColorGradientModality:: +ColorGradientModality () + : variable_feature_nr_ (false) + , smoothed_input_ (new pcl::PointCloud ()) + , feature_selection_method_ (DISTANCE_MAGNITUDE_SCORE) + , gradient_magnitude_threshold_ (10.0f) + , gradient_magnitude_threshold_feature_extraction_ (55.0f) + , color_gradients_ () + , spreading_size_ (8) + , quantized_color_gradients_ () + , filtered_quantized_color_gradients_ () + , spreaded_filtered_quantized_color_gradients_ () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::ColorGradientModality:: +~ColorGradientModality () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ColorGradientModality:: +computeGaussianKernel (const size_t kernel_size, const float sigma, std::vector & kernel_values) +{ + // code taken from OpenCV + const int n = int (kernel_size); + const int SMALL_GAUSSIAN_SIZE = 7; + static const float small_gaussian_tab[][SMALL_GAUSSIAN_SIZE] = + { + {1.f}, + {0.25f, 0.5f, 0.25f}, + {0.0625f, 0.25f, 0.375f, 0.25f, 0.0625f}, + {0.03125f, 0.109375f, 0.21875f, 0.28125f, 0.21875f, 0.109375f, 0.03125f} + }; + + const float* fixed_kernel = n % 2 == 1 && n <= SMALL_GAUSSIAN_SIZE && sigma <= 0 ? + small_gaussian_tab[n>>1] : 0; + + //CV_Assert( ktype == CV_32F || ktype == CV_64F ); + /*Mat kernel(n, 1, ktype);*/ + kernel_values.resize (n); + float* cf = &(kernel_values[0]); + //double* cd = (double*)kernel.data; + + double sigmaX = sigma > 0 ? sigma : ((n-1)*0.5 - 1)*0.3 + 0.8; + double scale2X = -0.5/(sigmaX*sigmaX); + double sum = 0; + + int i; + for( i = 0; i < n; i++ ) + { + double x = i - (n-1)*0.5; + double t = fixed_kernel ? double (fixed_kernel[i]) : std::exp (scale2X*x*x); + + cf[i] = float (t); + sum += cf[i]; + } + + sum = 1./sum; + for (i = 0; i < n; i++ ) + { + cf[i] = float (cf[i]*sum); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::ColorGradientModality:: +processInputData () +{ + // compute gaussian kernel values + const size_t kernel_size = 7; + std::vector kernel_values; + computeGaussianKernel (kernel_size, 0.0f, kernel_values); + + // smooth input + pcl::filters::Convolution convolution; + Eigen::ArrayXf gaussian_kernel(kernel_size); + //gaussian_kernel << 1.f/16, 1.f/8, 3.f/16, 2.f/8, 3.f/16, 1.f/8, 1.f/16; + //gaussian_kernel << 16.f/1600.f, 32.f/1600.f, 64.f/1600.f, 128.f/1600.f, 256.f/1600.f, 128.f/1600.f, 64.f/1600.f, 32.f/1600.f, 16.f/1600.f; + gaussian_kernel << kernel_values[0], kernel_values[1], kernel_values[2], kernel_values[3], kernel_values[4], kernel_values[5], kernel_values[6]; + + pcl::PointCloud::Ptr rgb_input_ (new pcl::PointCloud()); + + const uint32_t width = input_->width; + const uint32_t height = input_->height; + + rgb_input_->resize (width*height); + rgb_input_->width = width; + rgb_input_->height = height; + rgb_input_->is_dense = input_->is_dense; + for (size_t row_index = 0; row_index < height; ++row_index) + { + for (size_t col_index = 0; col_index < width; ++col_index) + { + (*rgb_input_) (col_index, row_index).r = (*input_) (col_index, row_index).r; + (*rgb_input_) (col_index, row_index).g = (*input_) (col_index, row_index).g; + (*rgb_input_) (col_index, row_index).b = (*input_) (col_index, row_index).b; + } + } + + convolution.setInputCloud (rgb_input_); + convolution.setKernel (gaussian_kernel); + + convolution.convolve (*smoothed_input_); + + // extract color gradients + computeMaxColorGradientsSobel (smoothed_input_); + + // quantize gradients + quantizeColorGradients (); + + // filter quantized gradients to get only dominants one + thresholding + filterQuantizedColorGradients (); + + // spread filtered quantized gradients + //spreadFilteredQunatizedColorGradients (); + pcl::QuantizedMap::spreadQuantizedMap (filtered_quantized_color_gradients_, + spreaded_filtered_quantized_color_gradients_, + spreading_size_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::ColorGradientModality:: +processInputDataFromFiltered () +{ + // spread filtered quantized gradients + //spreadFilteredQunatizedColorGradients (); + pcl::QuantizedMap::spreadQuantizedMap (filtered_quantized_color_gradients_, + spreaded_filtered_quantized_color_gradients_, + spreading_size_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void pcl::ColorGradientModality:: +extractFeatures (const MaskMap & mask, const size_t nr_features, const size_t modality_index, + std::vector & features) const +{ + const size_t width = mask.getWidth (); + const size_t height = mask.getHeight (); + + std::list list1; + std::list list2; + + + if (feature_selection_method_ == DISTANCE_MAGNITUDE_SCORE) + { + for (size_t row_index = 0; row_index < height; ++row_index) + { + for (size_t col_index = 0; col_index < width; ++col_index) + { + if (mask (col_index, row_index) != 0) + { + const GradientXY & gradient = color_gradients_ (col_index, row_index); + if (gradient.magnitude > gradient_magnitude_threshold_feature_extraction_ + && filtered_quantized_color_gradients_ (col_index, row_index) != 0) + { + Candidate candidate; + candidate.gradient = gradient; + candidate.x = static_cast (col_index); + candidate.y = static_cast (row_index); + + list1.push_back (candidate); + } + } + } + } + + list1.sort(); + + if (variable_feature_nr_) + { + list2.push_back (*(list1.begin ())); + //while (list2.size () != nr_features) + bool feature_selection_finished = false; + while (!feature_selection_finished) + { + float best_score = 0.0f; + typename std::list::iterator best_iter = list1.end (); + for (typename std::list::iterator iter1 = list1.begin (); iter1 != list1.end (); ++iter1) + { + // find smallest distance + float smallest_distance = std::numeric_limits::max (); + for (typename std::list::iterator iter2 = list2.begin (); iter2 != list2.end (); ++iter2) + { + const float dx = static_cast (iter1->x) - static_cast (iter2->x); + const float dy = static_cast (iter1->y) - static_cast (iter2->y); + + const float distance = dx*dx + dy*dy; + + if (distance < smallest_distance) + { + smallest_distance = distance; + } + } + + const float score = smallest_distance * iter1->gradient.magnitude; + + if (score > best_score) + { + best_score = score; + best_iter = iter1; + } + } + + + float min_min_sqr_distance = std::numeric_limits::max (); + float max_min_sqr_distance = 0; + for (typename std::list::iterator iter2 = list2.begin (); iter2 != list2.end (); ++iter2) + { + float min_sqr_distance = std::numeric_limits::max (); + for (typename std::list::iterator iter3 = list2.begin (); iter3 != list2.end (); ++iter3) + { + if (iter2 == iter3) + continue; + + const float dx = static_cast (iter2->x) - static_cast (iter3->x); + const float dy = static_cast (iter2->y) - static_cast (iter3->y); + + const float sqr_distance = dx*dx + dy*dy; + + if (sqr_distance < min_sqr_distance) + { + min_sqr_distance = sqr_distance; + } + + //std::cerr << min_sqr_distance; + } + //std::cerr << std::endl; + + // check current feature + { + const float dx = static_cast (iter2->x) - static_cast (best_iter->x); + const float dy = static_cast (iter2->y) - static_cast (best_iter->y); + + const float sqr_distance = dx*dx + dy*dy; + + if (sqr_distance < min_sqr_distance) + { + min_sqr_distance = sqr_distance; + } + } + + if (min_sqr_distance < min_min_sqr_distance) + min_min_sqr_distance = min_sqr_distance; + if (min_sqr_distance > max_min_sqr_distance) + max_min_sqr_distance = min_sqr_distance; + + //std::cerr << min_sqr_distance << ", " << min_min_sqr_distance << ", " << max_min_sqr_distance << std::endl; + } + + if (best_iter != list1.end ()) + { + //std::cerr << "feature_index: " << list2.size () << std::endl; + //std::cerr << "min_min_sqr_distance: " << min_min_sqr_distance << std::endl; + //std::cerr << "max_min_sqr_distance: " << max_min_sqr_distance << std::endl; + + if (min_min_sqr_distance < 50) + { + feature_selection_finished = true; + break; + } + + list2.push_back (*best_iter); + } + } + } + else + { + if (list1.size () <= nr_features) + { + for (typename std::list::iterator iter1 = list1.begin (); iter1 != list1.end (); ++iter1) + { + QuantizedMultiModFeature feature; + + feature.x = iter1->x; + feature.y = iter1->y; + feature.modality_index = modality_index; + feature.quantized_value = filtered_quantized_color_gradients_ (iter1->x, iter1->y); + + features.push_back (feature); + } + return; + } + + list2.push_back (*(list1.begin ())); + while (list2.size () != nr_features) + { + float best_score = 0.0f; + typename std::list::iterator best_iter = list1.end (); + for (typename std::list::iterator iter1 = list1.begin (); iter1 != list1.end (); ++iter1) + { + // find smallest distance + float smallest_distance = std::numeric_limits::max (); + for (typename std::list::iterator iter2 = list2.begin (); iter2 != list2.end (); ++iter2) + { + const float dx = static_cast (iter1->x) - static_cast (iter2->x); + const float dy = static_cast (iter1->y) - static_cast (iter2->y); + + const float distance = dx*dx + dy*dy; + + if (distance < smallest_distance) + { + smallest_distance = distance; + } + } + + const float score = smallest_distance * iter1->gradient.magnitude; + + if (score > best_score) + { + best_score = score; + best_iter = iter1; + } + } + + if (best_iter != list1.end ()) + { + list2.push_back (*best_iter); + } + else + { + break; + } + } + } + } + else if (feature_selection_method_ == MASK_BORDER_HIGH_GRADIENTS || feature_selection_method_ == MASK_BORDER_EQUALLY) + { + MaskMap eroded_mask; + erode (mask, eroded_mask); + + MaskMap diff_mask; + MaskMap::getDifferenceMask (mask, eroded_mask, diff_mask); + + for (size_t row_index = 0; row_index < height; ++row_index) + { + for (size_t col_index = 0; col_index < width; ++col_index) + { + if (diff_mask (col_index, row_index) != 0) + { + const GradientXY & gradient = color_gradients_ (col_index, row_index); + if ((feature_selection_method_ == MASK_BORDER_EQUALLY || gradient.magnitude > gradient_magnitude_threshold_feature_extraction_) + && filtered_quantized_color_gradients_ (col_index, row_index) != 0) + { + Candidate candidate; + candidate.gradient = gradient; + candidate.x = static_cast (col_index); + candidate.y = static_cast (row_index); + + list1.push_back (candidate); + } + } + } + } + + list1.sort(); + + if (list1.size () <= nr_features) + { + for (typename std::list::iterator iter1 = list1.begin (); iter1 != list1.end (); ++iter1) + { + QuantizedMultiModFeature feature; + + feature.x = iter1->x; + feature.y = iter1->y; + feature.modality_index = modality_index; + feature.quantized_value = filtered_quantized_color_gradients_ (iter1->x, iter1->y); + + features.push_back (feature); + } + return; + } + + size_t distance = list1.size () / nr_features + 1; // ??? + while (list2.size () != nr_features) + { + const size_t sqr_distance = distance*distance; + for (typename std::list::iterator iter1 = list1.begin (); iter1 != list1.end (); ++iter1) + { + bool candidate_accepted = true; + + for (typename std::list::iterator iter2 = list2.begin (); iter2 != list2.end (); ++iter2) + { + const int dx = iter1->x - iter2->x; + const int dy = iter1->y - iter2->y; + const unsigned int tmp_distance = dx*dx + dy*dy; + + //if (tmp_distance < distance) + if (tmp_distance < sqr_distance) + { + candidate_accepted = false; + break; + } + } + + if (candidate_accepted) + list2.push_back (*iter1); + + if (list2.size () == nr_features) + break; + } + --distance; + } + } + + for (typename std::list::iterator iter2 = list2.begin (); iter2 != list2.end (); ++iter2) + { + QuantizedMultiModFeature feature; + + feature.x = iter2->x; + feature.y = iter2->y; + feature.modality_index = modality_index; + feature.quantized_value = filtered_quantized_color_gradients_ (iter2->x, iter2->y); + + features.push_back (feature); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ColorGradientModality:: +extractAllFeatures (const MaskMap & mask, const size_t, const size_t modality_index, + std::vector & features) const +{ + const size_t width = mask.getWidth (); + const size_t height = mask.getHeight (); + + std::list list1; + std::list list2; + + + for (size_t row_index = 0; row_index < height; ++row_index) + { + for (size_t col_index = 0; col_index < width; ++col_index) + { + if (mask (col_index, row_index) != 0) + { + const GradientXY & gradient = color_gradients_ (col_index, row_index); + if (gradient.magnitude > gradient_magnitude_threshold_feature_extraction_ + && filtered_quantized_color_gradients_ (col_index, row_index) != 0) + { + Candidate candidate; + candidate.gradient = gradient; + candidate.x = static_cast (col_index); + candidate.y = static_cast (row_index); + + list1.push_back (candidate); + } + } + } + } + + list1.sort(); + + for (typename std::list::iterator iter1 = list1.begin (); iter1 != list1.end (); ++iter1) + { + QuantizedMultiModFeature feature; + + feature.x = iter1->x; + feature.y = iter1->y; + feature.modality_index = modality_index; + feature.quantized_value = filtered_quantized_color_gradients_ (iter1->x, iter1->y); + + features.push_back (feature); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::ColorGradientModality:: +computeMaxColorGradients (const typename pcl::PointCloud::ConstPtr & cloud) +{ + const int width = cloud->width; + const int height = cloud->height; + + color_gradients_.points.resize (width*height); + color_gradients_.width = width; + color_gradients_.height = height; + + const float pi = tan (1.0f) * 2; + for (int row_index = 0; row_index < height-2; ++row_index) + { + for (int col_index = 0; col_index < width-2; ++col_index) + { + const int index0 = row_index*width+col_index; + const int index_c = row_index*width+col_index+2; + const int index_r = (row_index+2)*width+col_index; + + //const int index_d = (row_index+1)*width+col_index+1; + + const unsigned char r0 = cloud->points[index0].r; + const unsigned char g0 = cloud->points[index0].g; + const unsigned char b0 = cloud->points[index0].b; + + const unsigned char r_c = cloud->points[index_c].r; + const unsigned char g_c = cloud->points[index_c].g; + const unsigned char b_c = cloud->points[index_c].b; + + const unsigned char r_r = cloud->points[index_r].r; + const unsigned char g_r = cloud->points[index_r].g; + const unsigned char b_r = cloud->points[index_r].b; + + const float r_dx = static_cast (r_c) - static_cast (r0); + const float g_dx = static_cast (g_c) - static_cast (g0); + const float b_dx = static_cast (b_c) - static_cast (b0); + + const float r_dy = static_cast (r_r) - static_cast (r0); + const float g_dy = static_cast (g_r) - static_cast (g0); + const float b_dy = static_cast (b_r) - static_cast (b0); + + const float sqr_mag_r = r_dx*r_dx + r_dy*r_dy; + const float sqr_mag_g = g_dx*g_dx + g_dy*g_dy; + const float sqr_mag_b = b_dx*b_dx + b_dy*b_dy; + + if (sqr_mag_r > sqr_mag_g && sqr_mag_r > sqr_mag_b) + { + GradientXY gradient; + gradient.magnitude = sqrt (sqr_mag_r); + gradient.angle = atan2 (r_dy, r_dx) * 180.0f / pi; + gradient.x = static_cast (col_index); + gradient.y = static_cast (row_index); + + color_gradients_ (col_index+1, row_index+1) = gradient; + } + else if (sqr_mag_g > sqr_mag_b) + { + GradientXY gradient; + gradient.magnitude = sqrt (sqr_mag_g); + gradient.angle = atan2 (g_dy, g_dx) * 180.0f / pi; + gradient.x = static_cast (col_index); + gradient.y = static_cast (row_index); + + color_gradients_ (col_index+1, row_index+1) = gradient; + } + else + { + GradientXY gradient; + gradient.magnitude = sqrt (sqr_mag_b); + gradient.angle = atan2 (b_dy, b_dx) * 180.0f / pi; + gradient.x = static_cast (col_index); + gradient.y = static_cast (row_index); + + color_gradients_ (col_index+1, row_index+1) = gradient; + } + + assert (color_gradients_ (col_index+1, row_index+1).angle >= -180 && + color_gradients_ (col_index+1, row_index+1).angle <= 180); + } + } + + return; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::ColorGradientModality:: +computeMaxColorGradientsSobel (const typename pcl::PointCloud::ConstPtr & cloud) +{ + const int width = cloud->width; + const int height = cloud->height; + + color_gradients_.points.resize (width*height); + color_gradients_.width = width; + color_gradients_.height = height; + + const float pi = tanf (1.0f) * 2.0f; + for (int row_index = 1; row_index < height-1; ++row_index) + { + for (int col_index = 1; col_index < width-1; ++col_index) + { + const int r7 = static_cast (cloud->points[(row_index-1)*width + (col_index-1)].r); + const int g7 = static_cast (cloud->points[(row_index-1)*width + (col_index-1)].g); + const int b7 = static_cast (cloud->points[(row_index-1)*width + (col_index-1)].b); + const int r8 = static_cast (cloud->points[(row_index-1)*width + (col_index)].r); + const int g8 = static_cast (cloud->points[(row_index-1)*width + (col_index)].g); + const int b8 = static_cast (cloud->points[(row_index-1)*width + (col_index)].b); + const int r9 = static_cast (cloud->points[(row_index-1)*width + (col_index+1)].r); + const int g9 = static_cast (cloud->points[(row_index-1)*width + (col_index+1)].g); + const int b9 = static_cast (cloud->points[(row_index-1)*width + (col_index+1)].b); + const int r4 = static_cast (cloud->points[(row_index)*width + (col_index-1)].r); + const int g4 = static_cast (cloud->points[(row_index)*width + (col_index-1)].g); + const int b4 = static_cast (cloud->points[(row_index)*width + (col_index-1)].b); + const int r6 = static_cast (cloud->points[(row_index)*width + (col_index+1)].r); + const int g6 = static_cast (cloud->points[(row_index)*width + (col_index+1)].g); + const int b6 = static_cast (cloud->points[(row_index)*width + (col_index+1)].b); + const int r1 = static_cast (cloud->points[(row_index+1)*width + (col_index-1)].r); + const int g1 = static_cast (cloud->points[(row_index+1)*width + (col_index-1)].g); + const int b1 = static_cast (cloud->points[(row_index+1)*width + (col_index-1)].b); + const int r2 = static_cast (cloud->points[(row_index+1)*width + (col_index)].r); + const int g2 = static_cast (cloud->points[(row_index+1)*width + (col_index)].g); + const int b2 = static_cast (cloud->points[(row_index+1)*width + (col_index)].b); + const int r3 = static_cast (cloud->points[(row_index+1)*width + (col_index+1)].r); + const int g3 = static_cast (cloud->points[(row_index+1)*width + (col_index+1)].g); + const int b3 = static_cast (cloud->points[(row_index+1)*width + (col_index+1)].b); + + //const int r_tmp1 = - r7 + r3; + //const int r_tmp2 = - r1 + r9; + //const int g_tmp1 = - g7 + g3; + //const int g_tmp2 = - g1 + g9; + //const int b_tmp1 = - b7 + b3; + //const int b_tmp2 = - b1 + b9; + ////const int gx = - r7 - (r4<<2) - r1 + r3 + (r6<<2) + r9; + ////const int gy = - r7 - (r8<<2) - r9 + r1 + (r2<<2) + r3; + //const int r_dx = r_tmp1 + r_tmp2 - (r4<<2) + (r6<<2); + //const int r_dy = r_tmp1 - r_tmp2 - (r8<<2) + (r2<<2); + //const int g_dx = g_tmp1 + g_tmp2 - (g4<<2) + (g6<<2); + //const int g_dy = g_tmp1 - g_tmp2 - (g8<<2) + (g2<<2); + //const int b_dx = b_tmp1 + b_tmp2 - (b4<<2) + (b6<<2); + //const int b_dy = b_tmp1 - b_tmp2 - (b8<<2) + (b2<<2); + + //const int r_tmp1 = - r7 + r3; + //const int r_tmp2 = - r1 + r9; + //const int g_tmp1 = - g7 + g3; + //const int g_tmp2 = - g1 + g9; + //const int b_tmp1 = - b7 + b3; + //const int b_tmp2 = - b1 + b9; + //const int gx = - r7 - (r4<<2) - r1 + r3 + (r6<<2) + r9; + //const int gy = - r7 - (r8<<2) - r9 + r1 + (r2<<2) + r3; + const int r_dx = r9 + 2*r6 + r3 - (r7 + 2*r4 + r1); + const int r_dy = r1 + 2*r2 + r3 - (r7 + 2*r8 + r9); + const int g_dx = g9 + 2*g6 + g3 - (g7 + 2*g4 + g1); + const int g_dy = g1 + 2*g2 + g3 - (g7 + 2*g8 + g9); + const int b_dx = b9 + 2*b6 + b3 - (b7 + 2*b4 + b1); + const int b_dy = b1 + 2*b2 + b3 - (b7 + 2*b8 + b9); + + const int sqr_mag_r = r_dx*r_dx + r_dy*r_dy; + const int sqr_mag_g = g_dx*g_dx + g_dy*g_dy; + const int sqr_mag_b = b_dx*b_dx + b_dy*b_dy; + + if (sqr_mag_r > sqr_mag_g && sqr_mag_r > sqr_mag_b) + { + GradientXY gradient; + gradient.magnitude = sqrtf (static_cast (sqr_mag_r)); + gradient.angle = atan2f (static_cast (r_dy), static_cast (r_dx)) * 180.0f / pi; + if (gradient.angle < -180.0f) gradient.angle += 360.0f; + if (gradient.angle >= 180.0f) gradient.angle -= 360.0f; + gradient.x = static_cast (col_index); + gradient.y = static_cast (row_index); + + color_gradients_ (col_index, row_index) = gradient; + } + else if (sqr_mag_g > sqr_mag_b) + { + GradientXY gradient; + gradient.magnitude = sqrtf (static_cast (sqr_mag_g)); + gradient.angle = atan2f (static_cast (g_dy), static_cast (g_dx)) * 180.0f / pi; + if (gradient.angle < -180.0f) gradient.angle += 360.0f; + if (gradient.angle >= 180.0f) gradient.angle -= 360.0f; + gradient.x = static_cast (col_index); + gradient.y = static_cast (row_index); + + color_gradients_ (col_index, row_index) = gradient; + } + else + { + GradientXY gradient; + gradient.magnitude = sqrtf (static_cast (sqr_mag_b)); + gradient.angle = atan2f (static_cast (b_dy), static_cast (b_dx)) * 180.0f / pi; + if (gradient.angle < -180.0f) gradient.angle += 360.0f; + if (gradient.angle >= 180.0f) gradient.angle -= 360.0f; + gradient.x = static_cast (col_index); + gradient.y = static_cast (row_index); + + color_gradients_ (col_index, row_index) = gradient; + } + + assert (color_gradients_ (col_index, row_index).angle >= -180 && + color_gradients_ (col_index, row_index).angle <= 180); + } + } + + return; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::ColorGradientModality:: +quantizeColorGradients () +{ + //std::cerr << "quantize this, bastard!!!" << std::endl; + + //unsigned char quantization_map[16] = {0,1,2,3,4,5,6,7,0,1,2,3,4,5,6,7}; + //unsigned char quantization_map[16] = {1,2,3,4,5,6,7,8,1,2,3,4,5,6,7,8}; + + //for (float angle = 0.0f; angle < 360.0f; angle += 1.0f) + //{ + // const int quantized_value = quantization_map[static_cast (angle * angleScale)]; + // std::cerr << angle << ": " << quantized_value << std::endl; + //} + + + const size_t width = input_->width; + const size_t height = input_->height; + + quantized_color_gradients_.resize (width, height); + + const float angleScale = 16.0f/360.0f; + + //float min_angle = std::numeric_limits::max (); + //float max_angle = -std::numeric_limits::max (); + for (size_t row_index = 0; row_index < height; ++row_index) + { + for (size_t col_index = 0; col_index < width; ++col_index) + { + if (color_gradients_ (col_index, row_index).magnitude < gradient_magnitude_threshold_) + { + quantized_color_gradients_ (col_index, row_index) = 0; + continue; + } + + const float angle = 11.25f + color_gradients_ (col_index, row_index).angle + 180.0f; + const int quantized_value = (static_cast (angle * angleScale)) & 7; + quantized_color_gradients_ (col_index, row_index) = static_cast (quantized_value + 1); + + //const float angle = color_gradients_ (col_index, row_index).angle + 180.0f; + + //min_angle = std::min (min_angle, angle); + //max_angle = std::max (max_angle, angle); + + //if (angle < 0.0f || angle >= 360.0f) + //{ + // std::cerr << "angle shitty: " << angle << std::endl; + //} + + //const int quantized_value = quantization_map[static_cast (angle * angleScale)]; + //quantized_color_gradients_ (col_index, row_index) = static_cast (quantized_value); + + //assert (0 <= quantized_value && quantized_value < 16); + //quantized_color_gradients_ (col_index, row_index) = quantization_map[quantized_value]; + //quantized_color_gradients_ (col_index, row_index) = static_cast ((quantized_value & 7) + 1); // = (quantized_value % 8) + 1 + } + } + + //std::cerr << ">>>>> " << min_angle << ", " << max_angle << std::endl; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::ColorGradientModality:: +filterQuantizedColorGradients () +{ + const size_t width = input_->width; + const size_t height = input_->height; + + filtered_quantized_color_gradients_.resize (width, height); + + // filter data + for (size_t row_index = 1; row_index < height-1; ++row_index) + { + for (size_t col_index = 1; col_index < width-1; ++col_index) + { + unsigned char histogram[9] = {0,0,0,0,0,0,0,0,0}; + + { + const unsigned char * data_ptr = quantized_color_gradients_.getData () + (row_index-1)*width+col_index-1; + assert (data_ptr[0] < 9 && data_ptr[1] < 9 && data_ptr[2] < 9); + ++histogram[data_ptr[0]]; + ++histogram[data_ptr[1]]; + ++histogram[data_ptr[2]]; + } + { + const unsigned char * data_ptr = quantized_color_gradients_.getData () + row_index*width+col_index-1; + assert (data_ptr[0] < 9 && data_ptr[1] < 9 && data_ptr[2] < 9); + ++histogram[data_ptr[0]]; + ++histogram[data_ptr[1]]; + ++histogram[data_ptr[2]]; + } + { + const unsigned char * data_ptr = quantized_color_gradients_.getData () + (row_index+1)*width+col_index-1; + assert (data_ptr[0] < 9 && data_ptr[1] < 9 && data_ptr[2] < 9); + ++histogram[data_ptr[0]]; + ++histogram[data_ptr[1]]; + ++histogram[data_ptr[2]]; + } + + unsigned char max_hist_value = 0; + int max_hist_index = -1; + + // for (int i = 0; i < 8; ++i) + // { + // if (max_hist_value < histogram[i+1]) + // { + // max_hist_index = i; + // max_hist_value = histogram[i+1] + // } + // } + // Unrolled for performance optimization: + if (max_hist_value < histogram[1]) {max_hist_index = 0; max_hist_value = histogram[1];} + if (max_hist_value < histogram[2]) {max_hist_index = 1; max_hist_value = histogram[2];} + if (max_hist_value < histogram[3]) {max_hist_index = 2; max_hist_value = histogram[3];} + if (max_hist_value < histogram[4]) {max_hist_index = 3; max_hist_value = histogram[4];} + if (max_hist_value < histogram[5]) {max_hist_index = 4; max_hist_value = histogram[5];} + if (max_hist_value < histogram[6]) {max_hist_index = 5; max_hist_value = histogram[6];} + if (max_hist_value < histogram[7]) {max_hist_index = 6; max_hist_value = histogram[7];} + if (max_hist_value < histogram[8]) {max_hist_index = 7; max_hist_value = histogram[8];} + + if (max_hist_index != -1 && max_hist_value >= 5) + filtered_quantized_color_gradients_ (col_index, row_index) = static_cast (0x1 << max_hist_index); + else + filtered_quantized_color_gradients_ (col_index, row_index) = 0; + + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::ColorGradientModality:: +erode (const pcl::MaskMap & mask_in, + pcl::MaskMap & mask_out) +{ + const size_t width = mask_in.getWidth (); + const size_t height = mask_in.getHeight (); + + mask_out.resize (width, height); + + for (size_t row_index = 1; row_index < height-1; ++row_index) + { + for (size_t col_index = 1; col_index < width-1; ++col_index) + { + if (mask_in (col_index, row_index-1) == 0 || + mask_in (col_index-1, row_index) == 0 || + mask_in (col_index+1, row_index) == 0 || + mask_in (col_index, row_index+1) == 0) + { + mask_out (col_index, row_index) = 0; + } + else + { + mask_out (col_index, row_index) = 255; + } + } + } +} + +#endif diff --git a/pcl-1.7/pcl/recognition/color_modality.h b/pcl-1.7/pcl/recognition/color_modality.h new file mode 100644 index 0000000..9b704d8 --- /dev/null +++ b/pcl-1.7/pcl/recognition/color_modality.h @@ -0,0 +1,552 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RECOGNITION_COLOR_MODALITY +#define PCL_RECOGNITION_COLOR_MODALITY + +#include +#include + +#include +#include +#include +#include + + +namespace pcl +{ + + // -------------------------------------------------------------------------- + + template + class ColorModality + : public QuantizableModality, public PCLBase + { + protected: + using PCLBase::input_; + + struct Candidate + { + float distance; + + unsigned char bin_index; + + size_t x; + size_t y; + + bool + operator< (const Candidate & rhs) + { + return (distance > rhs.distance); + } + }; + + public: + typedef typename pcl::PointCloud PointCloudIn; + + ColorModality (); + + virtual ~ColorModality (); + + inline QuantizedMap & + getQuantizedMap () + { + return (filtered_quantized_colors_); + } + + inline QuantizedMap & + getSpreadedQuantizedMap () + { + return (spreaded_filtered_quantized_colors_); + } + + void + extractFeatures (const MaskMap & mask, size_t nr_features, size_t modalityIndex, + std::vector & features) const; + + /** \brief Provide a pointer to the input dataset (overwrites the PCLBase::setInputCloud method) + * \param cloud the const boost shared pointer to a PointCloud message + */ + virtual void + setInputCloud (const typename PointCloudIn::ConstPtr & cloud) + { + input_ = cloud; + } + + virtual void + processInputData (); + + protected: + + void + quantizeColors (); + + void + filterQuantizedColors (); + + static inline int + quantizeColorOnRGBExtrema (const float r, + const float g, + const float b); + + void + computeDistanceMap (const MaskMap & input, DistanceMap & output) const; + + private: + float feature_distance_threshold_; + + pcl::QuantizedMap quantized_colors_; + pcl::QuantizedMap filtered_quantized_colors_; + pcl::QuantizedMap spreaded_filtered_quantized_colors_; + + }; + +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::ColorModality::ColorModality () + : feature_distance_threshold_ (1.0f), quantized_colors_ (), filtered_quantized_colors_ (), spreaded_filtered_quantized_colors_ () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::ColorModality::~ColorModality () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::ColorModality::processInputData () +{ + // quantize gradients + quantizeColors (); + + // filter quantized gradients to get only dominants one + thresholding + filterQuantizedColors (); + + // spread filtered quantized gradients + //spreadFilteredQunatizedColorGradients (); + const int spreading_size = 8; + pcl::QuantizedMap::spreadQuantizedMap (filtered_quantized_colors_, + spreaded_filtered_quantized_colors_, spreading_size); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void pcl::ColorModality::extractFeatures (const MaskMap & mask, + const size_t nr_features, + const size_t modality_index, + std::vector & features) const +{ + const size_t width = mask.getWidth (); + const size_t height = mask.getHeight (); + + MaskMap mask_maps[8]; + for (size_t map_index = 0; map_index < 8; ++map_index) + mask_maps[map_index].resize (width, height); + + unsigned char map[255]; + memset(map, 0, 255); + + map[0x1<<0] = 0; + map[0x1<<1] = 1; + map[0x1<<2] = 2; + map[0x1<<3] = 3; + map[0x1<<4] = 4; + map[0x1<<5] = 5; + map[0x1<<6] = 6; + map[0x1<<7] = 7; + + QuantizedMap distance_map_indices (width, height); + //memset (distance_map_indices.data, 0, sizeof (distance_map_indices.data[0])*width*height); + + for (size_t row_index = 0; row_index < height; ++row_index) + { + for (size_t col_index = 0; col_index < width; ++col_index) + { + if (mask (col_index, row_index) != 0) + { + //const unsigned char quantized_value = quantized_surface_normals_ (row_index, col_index); + const unsigned char quantized_value = filtered_quantized_colors_ (col_index, row_index); + + if (quantized_value == 0) + continue; + const int dist_map_index = map[quantized_value]; + + distance_map_indices (col_index, row_index) = dist_map_index; + //distance_maps[dist_map_index].at(row_index, col_index) = 255; + mask_maps[dist_map_index] (col_index, row_index) = 255; + } + } + } + + DistanceMap distance_maps[8]; + for (int map_index = 0; map_index < 8; ++map_index) + computeDistanceMap (mask_maps[map_index], distance_maps[map_index]); + + std::list list1; + std::list list2; + + float weights[8] = {0,0,0,0,0,0,0,0}; + + const size_t off = 4; + for (size_t row_index = off; row_index < height-off; ++row_index) + { + for (size_t col_index = off; col_index < width-off; ++col_index) + { + if (mask (col_index, row_index) != 0) + { + //const unsigned char quantized_value = quantized_surface_normals_ (row_index, col_index); + const unsigned char quantized_value = filtered_quantized_colors_ (col_index, row_index); + + //const float nx = surface_normals_ (col_index, row_index).normal_x; + //const float ny = surface_normals_ (col_index, row_index).normal_y; + //const float nz = surface_normals_ (col_index, row_index).normal_z; + + if (quantized_value != 0) + { + const int distance_map_index = map[quantized_value]; + + //const float distance = distance_maps[distance_map_index].at (row_index, col_index); + const float distance = distance_maps[distance_map_index] (col_index, row_index); + + if (distance >= feature_distance_threshold_) + { + Candidate candidate; + + candidate.distance = distance; + candidate.x = col_index; + candidate.y = row_index; + candidate.bin_index = distance_map_index; + + list1.push_back (candidate); + + ++weights[distance_map_index]; + } + } + } + } + } + + for (typename std::list::iterator iter = list1.begin (); iter != list1.end (); ++iter) + iter->distance *= 1.0f / weights[iter->bin_index]; + + list1.sort (); + + if (list1.size () <= nr_features) + { + features.reserve (list1.size ()); + for (typename std::list::iterator iter = list1.begin (); iter != list1.end (); ++iter) + { + QuantizedMultiModFeature feature; + + feature.x = static_cast (iter->x); + feature.y = static_cast (iter->y); + feature.modality_index = modality_index; + feature.quantized_value = filtered_quantized_colors_ (iter->x, iter->y); + + features.push_back (feature); + } + + return; + } + + int distance = static_cast (list1.size () / nr_features + 1); // ??? @todo:!:!:!:!:!:! + while (list2.size () != nr_features) + { + const int sqr_distance = distance*distance; + for (typename std::list::iterator iter1 = list1.begin (); iter1 != list1.end (); ++iter1) + { + bool candidate_accepted = true; + + for (typename std::list::iterator iter2 = list2.begin (); iter2 != list2.end (); ++iter2) + { + const int dx = static_cast (iter1->x) - static_cast (iter2->x); + const int dy = static_cast (iter1->y) - static_cast (iter2->y); + const int tmp_distance = dx*dx + dy*dy; + + if (tmp_distance < sqr_distance) + { + candidate_accepted = false; + break; + } + } + + if (candidate_accepted) + list2.push_back (*iter1); + + if (list2.size () == nr_features) break; + } + --distance; + } + + for (typename std::list::iterator iter2 = list2.begin (); iter2 != list2.end (); ++iter2) + { + QuantizedMultiModFeature feature; + + feature.x = static_cast (iter2->x); + feature.y = static_cast (iter2->y); + feature.modality_index = modality_index; + feature.quantized_value = filtered_quantized_colors_ (iter2->x, iter2->y); + + features.push_back (feature); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::ColorModality::quantizeColors () +{ + const size_t width = input_->width; + const size_t height = input_->height; + + quantized_colors_.resize (width, height); + + for (size_t row_index = 0; row_index < height; ++row_index) + { + for (size_t col_index = 0; col_index < width; ++col_index) + { + const float r = static_cast ((*input_) (col_index, row_index).r); + const float g = static_cast ((*input_) (col_index, row_index).g); + const float b = static_cast ((*input_) (col_index, row_index).b); + + quantized_colors_ (col_index, row_index) = quantizeColorOnRGBExtrema (r, g, b); + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::ColorModality::filterQuantizedColors () +{ + const size_t width = input_->width; + const size_t height = input_->height; + + filtered_quantized_colors_.resize (width, height); + + // filter data + for (size_t row_index = 1; row_index < height-1; ++row_index) + { + for (size_t col_index = 1; col_index < width-1; ++col_index) + { + unsigned char histogram[8] = {0,0,0,0,0,0,0,0}; + + { + const unsigned char * data_ptr = quantized_colors_.getData () + (row_index-1)*width+col_index-1; + assert (0 <= data_ptr[0] && data_ptr[0] < 9 && + 0 <= data_ptr[1] && data_ptr[1] < 9 && + 0 <= data_ptr[2] && data_ptr[2] < 9); + ++histogram[data_ptr[0]]; + ++histogram[data_ptr[1]]; + ++histogram[data_ptr[2]]; + } + { + const unsigned char * data_ptr = quantized_colors_.getData () + row_index*width+col_index-1; + assert (0 <= data_ptr[0] && data_ptr[0] < 9 && + 0 <= data_ptr[1] && data_ptr[1] < 9 && + 0 <= data_ptr[2] && data_ptr[2] < 9); + ++histogram[data_ptr[0]]; + ++histogram[data_ptr[1]]; + ++histogram[data_ptr[2]]; + } + { + const unsigned char * data_ptr = quantized_colors_.getData () + (row_index+1)*width+col_index-1; + assert (0 <= data_ptr[0] && data_ptr[0] < 9 && + 0 <= data_ptr[1] && data_ptr[1] < 9 && + 0 <= data_ptr[2] && data_ptr[2] < 9); + ++histogram[data_ptr[0]]; + ++histogram[data_ptr[1]]; + ++histogram[data_ptr[2]]; + } + + unsigned char max_hist_value = 0; + int max_hist_index = -1; + + // for (int i = 0; i < 8; ++i) + // { + // if (max_hist_value < histogram[i+1]) + // { + // max_hist_index = i; + // max_hist_value = histogram[i+1] + // } + // } + // Unrolled for performance optimization: + if (max_hist_value < histogram[0]) {max_hist_index = 0; max_hist_value = histogram[0];} + if (max_hist_value < histogram[1]) {max_hist_index = 1; max_hist_value = histogram[1];} + if (max_hist_value < histogram[2]) {max_hist_index = 2; max_hist_value = histogram[2];} + if (max_hist_value < histogram[3]) {max_hist_index = 3; max_hist_value = histogram[3];} + if (max_hist_value < histogram[4]) {max_hist_index = 4; max_hist_value = histogram[4];} + if (max_hist_value < histogram[5]) {max_hist_index = 5; max_hist_value = histogram[5];} + if (max_hist_value < histogram[6]) {max_hist_index = 6; max_hist_value = histogram[6];} + if (max_hist_value < histogram[7]) {max_hist_index = 7; max_hist_value = histogram[7];} + + //if (max_hist_index != -1 && max_hist_value >= 5) + filtered_quantized_colors_ (col_index, row_index) = 0x1 << max_hist_index; + //else + // filtered_quantized_color_gradients_ (col_index, row_index) = 0; + + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +int +pcl::ColorModality::quantizeColorOnRGBExtrema (const float r, + const float g, + const float b) +{ + const float r_inv = 255.0f-r; + const float g_inv = 255.0f-g; + const float b_inv = 255.0f-b; + + const float dist_0 = (r*r + g*g + b*b)*2.0f; + const float dist_1 = r*r + g*g + b_inv*b_inv; + const float dist_2 = r*r + g_inv*g_inv+ b*b; + const float dist_3 = r*r + g_inv*g_inv + b_inv*b_inv; + const float dist_4 = r_inv*r_inv + g*g + b*b; + const float dist_5 = r_inv*r_inv + g*g + b_inv*b_inv; + const float dist_6 = r_inv*r_inv + g_inv*g_inv+ b*b; + const float dist_7 = (r_inv*r_inv + g_inv*g_inv + b_inv*b_inv)*1.5f; + + const float min_dist = std::min (std::min (std::min (dist_0, dist_1), std::min (dist_2, dist_3)), std::min (std::min (dist_4, dist_5), std::min (dist_6, dist_7))); + + if (min_dist == dist_0) + { + return 0; + } + if (min_dist == dist_1) + { + return 1; + } + if (min_dist == dist_2) + { + return 2; + } + if (min_dist == dist_3) + { + return 3; + } + if (min_dist == dist_4) + { + return 4; + } + if (min_dist == dist_5) + { + return 5; + } + if (min_dist == dist_6) + { + return 6; + } + return 7; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ColorModality::computeDistanceMap (const MaskMap & input, + DistanceMap & output) const +{ + const size_t width = input.getWidth (); + const size_t height = input.getHeight (); + + output.resize (width, height); + + // compute distance map + //float *distance_map = new float[input_->points.size ()]; + const unsigned char * mask_map = input.getData (); + float * distance_map = output.getData (); + for (size_t index = 0; index < width*height; ++index) + { + if (mask_map[index] == 0) + distance_map[index] = 0.0f; + else + distance_map[index] = static_cast (width + height); + } + + // first pass + float * previous_row = distance_map; + float * current_row = previous_row + width; + for (size_t ri = 1; ri < height; ++ri) + { + for (size_t ci = 1; ci < width; ++ci) + { + const float up_left = previous_row [ci - 1] + 1.4f; //distance_map[(ri-1)*input_->width + ci-1] + 1.4f; + const float up = previous_row [ci] + 1.0f; //distance_map[(ri-1)*input_->width + ci] + 1.0f; + const float up_right = previous_row [ci + 1] + 1.4f; //distance_map[(ri-1)*input_->width + ci+1] + 1.4f; + const float left = current_row [ci - 1] + 1.0f; //distance_map[ri*input_->width + ci-1] + 1.0f; + const float center = current_row [ci]; //distance_map[ri*input_->width + ci]; + + const float min_value = std::min (std::min (up_left, up), std::min (left, up_right)); + + if (min_value < center) + current_row[ci] = min_value; //distance_map[ri * input_->width + ci] = min_value; + } + previous_row = current_row; + current_row += width; + } + + // second pass + float * next_row = distance_map + width * (height - 1); + current_row = next_row - width; + for (int ri = static_cast (height)-2; ri >= 0; --ri) + { + for (int ci = static_cast (width)-2; ci >= 0; --ci) + { + const float lower_left = next_row [ci - 1] + 1.4f; //distance_map[(ri+1)*input_->width + ci-1] + 1.4f; + const float lower = next_row [ci] + 1.0f; //distance_map[(ri+1)*input_->width + ci] + 1.0f; + const float lower_right = next_row [ci + 1] + 1.4f; //distance_map[(ri+1)*input_->width + ci+1] + 1.4f; + const float right = current_row [ci + 1] + 1.0f; //distance_map[ri*input_->width + ci+1] + 1.0f; + const float center = current_row [ci]; //distance_map[ri*input_->width + ci]; + + const float min_value = std::min (std::min (lower_left, lower), std::min (right, lower_right)); + + if (min_value < center) + current_row[ci] = min_value; //distance_map[ri*input_->width + ci] = min_value; + } + next_row = current_row; + current_row -= width; + } +} + + +#endif diff --git a/pcl-1.7/pcl/recognition/crh_alignment.h b/pcl-1.7/pcl/recognition/crh_alignment.h new file mode 100644 index 0000000..8c678f6 --- /dev/null +++ b/pcl-1.7/pcl/recognition/crh_alignment.h @@ -0,0 +1,275 @@ +/* + * crh_recognition.h + * + * Created on: Mar 30, 2012 + * Author: aitor + */ + +#ifndef CRH_ALIGNMENT_H_ +#define CRH_ALIGNMENT_H_ + +#include +#include +#include +#include + +namespace pcl +{ + + /** \brief CRHAlignment uses two Camera Roll Histograms (CRH) to find the + * roll rotation that aligns both views. See: + * - CAD-Model Recognition and 6 DOF Pose Estimation + * A. Aldoma, N. Blodow, D. Gossow, S. Gedikli, R.B. Rusu, M. Vincze and G. Bradski + * ICCV 2011, 3D Representation and Recognition (3dRR11) workshop + * Barcelona, Spain, (2011) + * + * \author Aitor Aldoma + * \ingroup recognition + */ + + template + class PCL_EXPORTS CRHAlignment + { + private: + + /** \brief Sorts peaks */ + typedef struct + { + bool + operator() (std::pair const& a, std::pair const& b) + { + return a.first > b.first; + } + } peaks_ordering; + + typedef typename pcl::PointCloud::Ptr PointTPtr; + + /** \brief View of the model to be aligned to input_view_ */ + PointTPtr target_view_; + /** \brief View of the input */ + PointTPtr input_view_; + /** \brief Centroid of the model_view_ */ + Eigen::Vector3f centroid_target_; + /** \brief Centroid of the input_view_ */ + Eigen::Vector3f centroid_input_; + /** \brief transforms from model view to input view */ + std::vector > transforms_; + /** \brief Allowed maximum number of peaks */ + int max_peaks_; + /** \brief Quantile of peaks after sorting to be checked */ + float quantile_; + /** \brief Threshold for a peak to be accepted. + * If peak_i >= (max_peak * accept_threhsold_) => peak is accepted + */ + float accept_threshold_; + + /** \brief computes the transformation to the z-axis + * \param[in] centroid + * \param[out] trasnformation to z-axis + */ + void + computeTransformToZAxes (Eigen::Vector3f & centroid, Eigen::Affine3f & transform) + { + Eigen::Vector3f plane_normal; + plane_normal[0] = -centroid[0]; + plane_normal[1] = -centroid[1]; + plane_normal[2] = -centroid[2]; + Eigen::Vector3f z_vector = Eigen::Vector3f::UnitZ (); + plane_normal.normalize (); + Eigen::Vector3f axis = plane_normal.cross (z_vector); + double rotation = -asin (axis.norm ()); + axis.normalize (); + transform = Eigen::Affine3f (Eigen::AngleAxisf (static_cast(rotation), axis)); + } + + /** \brief computes the roll transformation + * \param[in] centroid input + * \param[in] centroid view + * \param[in] roll_angle + * \param[out] roll transformation + */ + void + computeRollTransform (Eigen::Vector3f & centroidInput, Eigen::Vector3f & centroidResult, double roll_angle, Eigen::Affine3f & final_trans) + { + Eigen::Affine3f transformInputToZ; + computeTransformToZAxes (centroidInput, transformInputToZ); + + transformInputToZ = transformInputToZ.inverse (); + Eigen::Affine3f transformRoll (Eigen::AngleAxisf (-static_cast(roll_angle * M_PI / 180), Eigen::Vector3f::UnitZ ())); + Eigen::Affine3f transformDBResultToZ; + computeTransformToZAxes (centroidResult, transformDBResultToZ); + + final_trans = transformInputToZ * transformRoll * transformDBResultToZ; + } + public: + + /** \brief Constructor. */ + CRHAlignment() { + max_peaks_ = 5; + quantile_ = 0.2f; + accept_threshold_ = 0.8f; + } + + /** \brief returns the computed transformations + * \param[out] transforms transformations + */ + void getTransforms(std::vector > & transforms) { + transforms = transforms_; + } + + /** \brief sets model and input views + * \param[in] input_view + * \param[in] target_view + */ + void + setInputAndTargetView (PointTPtr & input_view, PointTPtr & target_view) + { + target_view_ = target_view; + input_view_ = input_view; + } + + /** \brief sets model and input centroids + * \param[in] c1 model view centroid + * \param[in] c2 input view centroid + */ + void + setInputAndTargetCentroids (Eigen::Vector3f & c1, Eigen::Vector3f & c2) + { + centroid_target_ = c2; + centroid_input_ = c1; + } + + /** \brief Computes the transformation aligning model to input + * \param[in] input_ftt CRH histogram of the input cloud + * \param[in] target_ftt CRH histogram of the target cloud + */ + void + align (pcl::PointCloud > & input_ftt, pcl::PointCloud > & target_ftt) + { + + transforms_.clear(); //clear from last round... + + std::vector peaks; + computeRollAngle (input_ftt, target_ftt, peaks); + + //if the number of peaks is too big, we should try to reduce using siluette matching + + for (size_t i = 0; i < peaks.size(); i++) + { + Eigen::Affine3f rollToRot; + computeRollTransform (centroid_input_, centroid_target_, peaks[i], rollToRot); + + Eigen::Matrix4f rollHomMatrix = Eigen::Matrix4f (); + rollHomMatrix.setIdentity (4, 4); + rollHomMatrix = rollToRot.matrix (); + + Eigen::Matrix4f translation2; + translation2.setIdentity (4, 4); + Eigen::Vector3f centr = rollToRot * centroid_target_; + translation2 (0, 3) = centroid_input_[0] - centr[0]; + translation2 (1, 3) = centroid_input_[1] - centr[1]; + translation2 (2, 3) = centroid_input_[2] - centr[2]; + + Eigen::Matrix4f resultHom (translation2 * rollHomMatrix); + transforms_.push_back(resultHom.inverse()); + } + + } + + /** \brief Computes the roll angle that aligns input to modle. + * \param[in] input_ftt CRH histogram of the input cloud + * \param[in] target_ftt CRH histogram of the target cloud + * \param[out] peaks Vector containing angles where the histograms correlate + */ + void + computeRollAngle (pcl::PointCloud > & input_ftt, pcl::PointCloud > & target_ftt, + std::vector & peaks) + { + + pcl::PointCloud > input_ftt_negate (input_ftt); + + for (int i = 2; i < (nbins_); i += 2) + input_ftt_negate.points[0].histogram[i] = -input_ftt_negate.points[0].histogram[i]; + + int nr_bins_after_padding = 180; + int peak_distance = 5; + int cutoff = nbins_ - 1; + + kiss_fft_cpx * multAB = new kiss_fft_cpx[nr_bins_after_padding]; + for (int i = 0; i < nr_bins_after_padding; i++) + multAB[i].r = multAB[i].i = 0.f; + + int k = 0; + multAB[k].r = input_ftt_negate.points[0].histogram[0] * target_ftt.points[0].histogram[0]; + k++; + + float a, b, c, d; + for (int i = 1; i < cutoff; i += 2, k++) + { + a = input_ftt_negate.points[0].histogram[i]; + b = input_ftt_negate.points[0].histogram[i + 1]; + c = target_ftt.points[0].histogram[i]; + d = target_ftt.points[0].histogram[i + 1]; + multAB[k].r = a * c - b * d; + multAB[k].i = b * c + a * d; + + float tmp = sqrtf (multAB[k].r * multAB[k].r + multAB[k].i * multAB[k].i); + + multAB[k].r /= tmp; + multAB[k].i /= tmp; + } + + multAB[nbins_ - 1].r = input_ftt_negate.points[0].histogram[nbins_ - 1] * target_ftt.points[0].histogram[nbins_ - 1]; + + kiss_fft_cfg mycfg = kiss_fft_alloc (nr_bins_after_padding, 1, NULL, NULL); + kiss_fft_cpx * invAB = new kiss_fft_cpx[nr_bins_after_padding]; + kiss_fft (mycfg, multAB, invAB); + + std::vector < std::pair > scored_peaks (nr_bins_after_padding); + for (int i = 0; i < nr_bins_after_padding; i++) + scored_peaks[i] = std::make_pair (invAB[i].r, i); + + std::sort (scored_peaks.begin (), scored_peaks.end (), peaks_ordering ()); + + std::vector peaks_indices; + std::vector peaks_values; + + // we look at the upper quantile_ + float quantile = quantile_; + int max_inserted= max_peaks_; + + int inserted=0; + bool stop=false; + for (int i = 0; (i < static_cast (quantile * static_cast (nr_bins_after_padding))) && !stop; i++) + { + if (scored_peaks[i].first >= scored_peaks[0].first * accept_threshold_) + { + bool insert = true; + + for (size_t j = 0; j < peaks_indices.size (); j++) + { //check inserted peaks, first pick always inserted + if (std::abs (peaks_indices[j] - scored_peaks[i].second) <= peak_distance || std::abs ( + peaks_indices[j] - (scored_peaks[i].second + - nr_bins_after_padding)) <= peak_distance) + { + insert = false; + break; + } + } + + if (insert) + { + peaks_indices.push_back (scored_peaks[i].second); + peaks_values.push_back (scored_peaks[i].first); + peaks.push_back (static_cast (scored_peaks[i].second * (360 / nr_bins_after_padding))); + inserted++; + if(inserted >= max_inserted) + stop = true; + } + } + } + } + }; +} + +#endif /* CRH_ALIGNMENT_H_ */ diff --git a/pcl-1.7/pcl/recognition/dense_quantized_multi_mod_template.h b/pcl-1.7/pcl/recognition/dense_quantized_multi_mod_template.h new file mode 100644 index 0000000..b9f4ac7 --- /dev/null +++ b/pcl-1.7/pcl/recognition/dense_quantized_multi_mod_template.h @@ -0,0 +1,117 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_DENSE_QUANTIZED_MULTI_MOD_TEMPLATE +#define PCL_FEATURES_DENSE_QUANTIZED_MULTI_MOD_TEMPLATE + +#include + +#include + +namespace pcl +{ + + struct DenseQuantizedSingleModTemplate + { + std::vector features; + + void + serialize (std::ostream & stream) const + { + const size_t num_of_features = static_cast (features.size ()); + write (stream, num_of_features); + for (size_t feature_index = 0; feature_index < num_of_features; ++feature_index) + { + write (stream, features[feature_index]); + } + } + + void + deserialize (std::istream & stream) + { + features.clear (); + + size_t num_of_features; + read (stream, num_of_features); + features.resize (num_of_features); + for (size_t feature_index = 0; feature_index < num_of_features; ++feature_index) + { + read (stream, features[feature_index]); + } + } + }; + + struct DenseQuantizedMultiModTemplate + { + std::vector modalities; + float response_factor; + + RegionXY region; + + void + serialize (std::ostream & stream) const + { + const size_t num_of_modalities = static_cast (modalities.size ()); + write (stream, num_of_modalities); + for (size_t modality_index = 0; modality_index < num_of_modalities; ++modality_index) + { + modalities[modality_index].serialize (stream); + } + + region.serialize (stream); + } + + void + deserialize (std::istream & stream) + { + modalities.clear (); + + size_t num_of_modalities; + read (stream, num_of_modalities); + modalities.resize (num_of_modalities); + for (size_t modality_index = 0; modality_index < num_of_modalities; ++modality_index) + { + modalities[modality_index].deserialize (stream); + } + + region.deserialize (stream); + } + }; + +} + +#endif \ No newline at end of file diff --git a/pcl-1.7/pcl/recognition/distance_map.h b/pcl-1.7/pcl/recognition/distance_map.h new file mode 100644 index 0000000..ac68e5b --- /dev/null +++ b/pcl-1.7/pcl/recognition/distance_map.h @@ -0,0 +1,120 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RECOGNITION_DISTANCE_MAP +#define PCL_RECOGNITION_DISTANCE_MAP + +namespace pcl +{ + + /** \brief Represents a distance map obtained from a distance transformation. + * \author Stefan Holzer + */ + class DistanceMap + { + public: + /** \brief Constructor. */ + DistanceMap () : data_ (0), width_ (0), height_ (0) {} + /** \brief Destructor. */ + virtual ~DistanceMap () {} + + /** \brief Returns the width of the map. */ + inline size_t + getWidth () const + { + return (width_); + } + + /** \brief Returns the height of the map. */ + inline size_t + getHeight () const + { + return (height_); + } + + /** \brief Returns a pointer to the beginning of map. */ + inline float * + getData () + { + return (&data_[0]); + } + + /** \brief Resizes the map to the specified size. + * \param[in] width the new width of the map. + * \param[in] height the new height of the map. + */ + void + resize (const size_t width, const size_t height) + { + data_.resize (width*height); + width_ = width; + height_ = height; + } + + /** \brief Operator to access an element of the map. + * \param[in] col_index the column index of the element to access. + * \param[in] row_index the row index of the element to access. + */ + inline float & + operator() (const size_t col_index, const size_t row_index) + { + return (data_[row_index*width_ + col_index]); + } + + /** \brief Operator to access an element of the map. + * \param[in] col_index the column index of the element to access. + * \param[in] row_index the row index of the element to access. + */ + inline const float & + operator() (const size_t col_index, const size_t row_index) const + { + return (data_[row_index*width_ + col_index]); + } + + protected: + /** \brief The storage for the distance map data. */ + std::vector data_; + /** \brief The width of the map. */ + size_t width_; + /** \brief The height of the map. */ + size_t height_; + }; + +} + + +#endif diff --git a/pcl-1.7/pcl/recognition/dot_modality.h b/pcl-1.7/pcl/recognition/dot_modality.h new file mode 100644 index 0000000..bf2a84a --- /dev/null +++ b/pcl-1.7/pcl/recognition/dot_modality.h @@ -0,0 +1,68 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_QUANTIZABLE_MODALITY +#define PCL_FEATURES_QUANTIZABLE_MODALITY + +#include +#include +#include +#include +#include + +namespace pcl +{ + class PCL_EXPORTS DOTModality + { + public: + + virtual ~DOTModality () {}; + + //virtual QuantizedMap & + //getDominantQuantizedMap () = 0; + + virtual QuantizedMap & + getDominantQuantizedMap () = 0; + + virtual QuantizedMap + computeInvariantQuantizedMap (const MaskMap & mask, + const RegionXY & region) = 0; + + }; +} + +#endif // PCL_FEATURES_DOT_MODALITY diff --git a/pcl-1.7/pcl/recognition/dotmod.h b/pcl-1.7/pcl/recognition/dotmod.h new file mode 100644 index 0000000..96a0be4 --- /dev/null +++ b/pcl-1.7/pcl/recognition/dotmod.h @@ -0,0 +1,131 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RECOGNITION_DOTMOD +#define PCL_RECOGNITION_DOTMOD + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + + struct DOTMODDetection + { + size_t bin_x; + size_t bin_y; + size_t template_id; + float score; + }; + + /** + * \brief Template matching using the DOTMOD approach. + * \author Stefan Holzer, Stefan Hinterstoisser + */ + class PCL_EXPORTS DOTMOD + { + public: + /** \brief Constructor */ + DOTMOD (size_t template_width, + size_t template_height); + + /** \brief Destructor */ + virtual ~DOTMOD (); + + /** \brief Creates a template from the specified data and adds it to the matching queue. + * \param modalities + * \param masks + * \param template_anker_x + * \param template_anker_y + * \param region + */ + size_t + createAndAddTemplate (const std::vector & modalities, + const std::vector & masks, + size_t template_anker_x, + size_t template_anker_y, + const RegionXY & region); + + void + detectTemplates (const std::vector & modalities, + float template_response_threshold, + std::vector & detections, + const size_t bin_size) const; + + inline const DenseQuantizedMultiModTemplate & + getTemplate (size_t template_id) const + { + return (templates_[template_id]); + } + + inline size_t + getNumOfTemplates () + { + return (templates_.size ()); + } + + void + saveTemplates (const char * file_name) const; + + void + loadTemplates (const char * file_name); + + void + serialize (std::ostream & stream) const; + + void + deserialize (std::istream & stream); + + + private: + /** template width */ + size_t template_width_; + /** template height */ + size_t template_height_; + /** template storage */ + std::vector templates_; + }; + +} + +#endif diff --git a/pcl-1.7/pcl/recognition/hv/greedy_verification.h b/pcl-1.7/pcl/recognition/hv/greedy_verification.h new file mode 100644 index 0000000..03148bd --- /dev/null +++ b/pcl-1.7/pcl/recognition/hv/greedy_verification.h @@ -0,0 +1,184 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_RECOGNITION_HV_GREEDY_H_ +#define PCL_RECOGNITION_HV_GREEDY_H_ + +#include +#include +#include + +namespace pcl +{ + + /** + * \brief A greedy hypothesis verification method + * \author Aitor Aldoma + */ + + template + class PCL_EXPORTS GreedyVerification : public HypothesisVerification + { + using HypothesisVerification::mask_; + using HypothesisVerification::scene_cloud_downsampled_; + using HypothesisVerification::scene_downsampled_tree_; + using HypothesisVerification::visible_models_; + using HypothesisVerification::resolution_; + using HypothesisVerification::inliers_threshold_; + + /* + * \brief Recognition model using during the verification + */ + class RecognitionModel + { + public: + std::vector explained_; + typename pcl::PointCloud::Ptr cloud_; + int bad_information_; + int good_information_; + int id_; + float regularizer_; + }; + + /* + * \brief Sorts recognition models based on the number of explained scene points and visible outliers + */ + struct sortModelsClass + { + bool + operator() (const boost::shared_ptr & n1, const boost::shared_ptr & n2) + { + float val1 = static_cast(n1->good_information_) - static_cast(n1->bad_information_) * n1->regularizer_; + float val2 = static_cast(n2->good_information_) - static_cast(n2->bad_information_) * n2->regularizer_; + return val1 > val2; + } + } sortModelsOp; + + + /* + * \brief Recognition model indices to keep track of the sorted recognition hypotheses + */ + struct modelIndices + { + int index_; + boost::shared_ptr model_; + }; + + /* + * \brief Sorts model indices similar to sortModelsClass + */ + struct sortModelIndicesClass + { + bool + operator() (const modelIndices & n1, const modelIndices & n2) + { + float val1 = static_cast(n1.model_->good_information_) - static_cast(n1.model_->bad_information_) * n1.model_->regularizer_; + float val2 = static_cast(n2.model_->good_information_) - static_cast(n2.model_->bad_information_) * n2.model_->regularizer_; + return val1 > val2; + } + } sortModelsIndicesOp; + + /** \brief Recognition model and indices */ + std::vector indices_models_; + + /** \brief Recognition models (hypotheses to be verified) */ + std::vector > recognition_models_; + + /** \brief Recognition models that explain a scene points. */ + std::vector > > points_explained_by_rm_; + + /** \brief Weighting for outliers */ + float regularizer_; + + /** \brief Initialize the data structures */ + void + initialize (); + + /** \brief Sorts the hypotheses for the greedy approach */ + void + sortModels () + { + indices_models_.clear (); + for (size_t i = 0; i < recognition_models_.size (); i++) + { + modelIndices mi; + mi.index_ = static_cast (i); + mi.model_ = recognition_models_[i]; + indices_models_.push_back (mi); + } + + std::sort (indices_models_.begin (), indices_models_.end (), sortModelsIndicesOp); + //sort also recognition models + std::sort (recognition_models_.begin (), recognition_models_.end (), sortModelsOp); + } + + /** \brief Updates conflicting recognition hypotheses when a hypothesis is accepted */ + void + updateGoodInformation (int i) + { + for (size_t k = 0; k < recognition_models_[i]->explained_.size (); k++) + { + //update good_information_ for all hypotheses that were explaining the same points as hypothesis i + for (size_t kk = 0; kk < points_explained_by_rm_[recognition_models_[i]->explained_[k]].size (); kk++) + { + (points_explained_by_rm_[recognition_models_[i]->explained_[k]])[kk]->good_information_--; + (points_explained_by_rm_[recognition_models_[i]->explained_[k]])[kk]->bad_information_++; + } + } + } + + public: + + /** \brief Constructor + * \param[in] reg Regularizer value + **/ + GreedyVerification (float reg = 1.5f) : + HypothesisVerification () + { + regularizer_ = reg; + } + + /** \brief Starts verification */ + void + verify (); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif /* PCL_RECOGNITION_HV_GREEDY_H_ */ diff --git a/pcl-1.7/pcl/recognition/hv/hv_go.h b/pcl-1.7/pcl/recognition/hv/hv_go.h new file mode 100644 index 0000000..fa56fde --- /dev/null +++ b/pcl-1.7/pcl/recognition/hv/hv_go.h @@ -0,0 +1,492 @@ +/* + * go.h + * + * Created on: Jun 4, 2012 + * Author: aitor + */ + +#ifndef GO_H_ +#define GO_H_ + +#include +#include +#include +#include "metslib/mets.hh" +#include +#include +#include + +namespace pcl +{ + + /** \brief A hypothesis verification method proposed in + * "A Global Hypotheses Verification Method for 3D Object Recognition", A. Aldoma and F. Tombari and L. Di Stefano and Markus Vincze, ECCV 2012 + * \author Aitor Aldoma + */ + template + class PCL_EXPORTS GlobalHypothesesVerification: public HypothesisVerification + { + private: + + //Helper classes + struct RecognitionModel + { + public: + std::vector explained_; //indices vector referencing explained_by_RM_ + std::vector explained_distances_; //closest distances to the scene for point i + std::vector unexplained_in_neighborhood; //indices vector referencing unexplained_by_RM_neighboorhods + std::vector unexplained_in_neighborhood_weights; //weights for the points not being explained in the neighborhood of a hypothesis + std::vector outlier_indices_; //outlier indices of this model + std::vector complete_cloud_occupancy_indices_; + typename pcl::PointCloud::Ptr cloud_; + typename pcl::PointCloud::Ptr complete_cloud_; + int bad_information_; + float outliers_weight_; + pcl::PointCloud::Ptr normals_; + int id_; + }; + + typedef GlobalHypothesesVerification SAOptimizerT; + class SAModel: public mets::evaluable_solution + { + public: + std::vector solution_; + SAOptimizerT * opt_; + mets::gol_type cost_; + + //Evaluates the current solution + mets::gol_type cost_function() const + { + return cost_; + } + + void copy_from(const mets::copyable& o) + { + const SAModel& s = dynamic_cast (o); + solution_ = s.solution_; + opt_ = s.opt_; + cost_ = s.cost_; + } + + mets::gol_type what_if(int /*index*/, bool /*val*/) const + { + /*std::vector tmp (solution_); + tmp[index] = val; + mets::gol_type sol = opt_->evaluateSolution (solution_, index); //evaluate without updating status + return sol;*/ + return static_cast(0); + } + + mets::gol_type apply_and_evaluate(int index, bool val) + { + solution_[index] = val; + mets::gol_type sol = opt_->evaluateSolution (solution_, index); //this will update the state of the solution + cost_ = sol; + return sol; + } + + void apply(int /*index*/, bool /*val*/) + { + + } + + void unapply(int index, bool val) + { + solution_[index] = val; + //update optimizer solution + cost_ = opt_->evaluateSolution (solution_, index); //this will udpate the cost function in opt_ + } + void setSolution(std::vector & sol) + { + solution_ = sol; + } + + void setOptimizer(SAOptimizerT * opt) + { + opt_ = opt; + } + }; + + /* + * Represents a move, deactivate a hypothesis + */ + + class move: public mets::move + { + int index_; + public: + move(int i) : + index_ (i) + { + } + + mets::gol_type evaluate(const mets::feasible_solution& /*cs*/) const + { + return static_cast(0); + } + + mets::gol_type apply_and_evaluate(mets::feasible_solution& cs) + { + SAModel& model = dynamic_cast (cs); + return model.apply_and_evaluate (index_, !model.solution_[index_]); + } + + void apply(mets::feasible_solution& /*s*/) const + { + } + + void unapply(mets::feasible_solution& s) const + { + SAModel& model = dynamic_cast (s); + model.unapply (index_, !model.solution_[index_]); + } + }; + + class move_manager + { + public: + std::vector moves_m; + typedef typename std::vector::iterator iterator; + iterator begin() + { + return moves_m.begin (); + } + iterator end() + { + return moves_m.end (); + } + + move_manager(int problem_size) + { + for (int ii = 0; ii != problem_size; ++ii) + moves_m.push_back (new move (ii)); + } + + ~move_manager() + { + // delete all moves + for (iterator ii = begin (); ii != end (); ++ii) + delete (*ii); + } + + void refresh(mets::feasible_solution& /*s*/) + { + std::random_shuffle (moves_m.begin (), moves_m.end ()); + } + + }; + + //inherited class attributes + using HypothesisVerification::mask_; + using HypothesisVerification::scene_cloud_downsampled_; + using HypothesisVerification::scene_downsampled_tree_; + using HypothesisVerification::visible_models_; + using HypothesisVerification::complete_models_; + using HypothesisVerification::resolution_; + using HypothesisVerification::inliers_threshold_; + + //class attributes + typedef typename pcl::NormalEstimation NormalEstimator_; + pcl::PointCloud::Ptr scene_normals_; + pcl::PointCloud::Ptr clusters_cloud_; + + std::vector complete_cloud_occupancy_by_RM_; + float res_occupancy_grid_; + float w_occupied_multiple_cm_; + + std::vector explained_by_RM_; //represents the points of scene_cloud_ that are explained by the recognition models + std::vector explained_by_RM_distance_weighted; //represents the points of scene_cloud_ that are explained by the recognition models + std::vector unexplained_by_RM_neighboorhods; //represents the points of scene_cloud_ that are not explained by the active hypotheses in the neighboorhod of the recognition models + std::vector > recognition_models_; + std::vector indices_; + + float regularizer_; + float clutter_regularizer_; + bool detect_clutter_; + float radius_neighborhood_GO_; + float radius_normals_; + + float previous_explained_value; + int previous_duplicity_; + int previous_duplicity_complete_models_; + float previous_bad_info_; + float previous_unexplained_; + + int max_iterations_; //max iterations without improvement + SAModel best_seen_; + float initial_temp_; + + int n_cc_; + std::vector > cc_; + + void setPreviousBadInfo(float f) + { + previous_bad_info_ = f; + } + + float getPreviousBadInfo() + { + return previous_bad_info_; + } + + void setPreviousExplainedValue(float v) + { + previous_explained_value = v; + } + + void setPreviousDuplicity(int v) + { + previous_duplicity_ = v; + } + + void setPreviousDuplicityCM(int v) + { + previous_duplicity_complete_models_ = v; + } + + void setPreviousUnexplainedValue(float v) + { + previous_unexplained_ = v; + } + + float getPreviousUnexplainedValue() + { + return previous_unexplained_; + } + + float getExplainedValue() + { + return previous_explained_value; + } + + int getDuplicity() + { + return previous_duplicity_; + } + + int getDuplicityCM() + { + return previous_duplicity_complete_models_; + } + + void updateUnexplainedVector(std::vector & unexplained_, std::vector & unexplained_distances, std::vector & unexplained_by_RM, + std::vector & explained, std::vector & explained_by_RM, float val) + { + { + + float add_to_unexplained = 0.f; + + for (size_t i = 0; i < unexplained_.size (); i++) + { + + bool prev_unexplained = (unexplained_by_RM[unexplained_[i]] > 0) && (explained_by_RM[unexplained_[i]] == 0); + unexplained_by_RM[unexplained_[i]] += val * unexplained_distances[i]; + + if (val < 0) //the hypothesis is being removed + { + if (prev_unexplained) + { + //decrease by 1 + add_to_unexplained -= unexplained_distances[i]; + } + } else //the hypothesis is being added and unexplains unexplained_[i], so increase by 1 unless its explained by another hypothesis + { + if (explained_by_RM[unexplained_[i]] == 0) + add_to_unexplained += unexplained_distances[i]; + } + } + + for (size_t i = 0; i < explained.size (); i++) + { + if (val < 0) + { + //the hypothesis is being removed, check that there are no points that become unexplained and have clutter unexplained hypotheses + if ((explained_by_RM[explained[i]] == 0) && (unexplained_by_RM[explained[i]] > 0)) + { + add_to_unexplained += unexplained_by_RM[explained[i]]; //the points become unexplained + } + } else + { + //std::cout << "being added..." << add_to_unexplained << " " << unexplained_by_RM[explained[i]] << std::endl; + if ((explained_by_RM[explained[i]] == 1) && (unexplained_by_RM[explained[i]] > 0)) + { //the only hypothesis explaining that point + add_to_unexplained -= unexplained_by_RM[explained[i]]; //the points are not unexplained any longer because this hypothesis explains them + } + } + } + + //std::cout << add_to_unexplained << std::endl; + previous_unexplained_ += add_to_unexplained; + } + } + + void updateExplainedVector(std::vector & vec, std::vector & vec_float, std::vector & explained_, + std::vector & explained_by_RM_distance_weighted, float sign) + { + float add_to_explained = 0.f; + int add_to_duplicity_ = 0; + + for (size_t i = 0; i < vec.size (); i++) + { + bool prev_dup = explained_[vec[i]] > 1; + + explained_[vec[i]] += static_cast (sign); + explained_by_RM_distance_weighted[vec[i]] += vec_float[i] * sign; + + add_to_explained += vec_float[i] * sign; + + if ((explained_[vec[i]] > 1) && prev_dup) + { //its still a duplicate, we are adding + add_to_duplicity_ += static_cast (sign); //so, just add or remove one + } else if ((explained_[vec[i]] == 1) && prev_dup) + { //if was duplicate before, now its not, remove 2, we are removing the hypothesis + add_to_duplicity_ -= 2; + } else if ((explained_[vec[i]] > 1) && !prev_dup) + { //it was not a duplicate but it is now, add 2, we are adding a conflicting hypothesis for the point + add_to_duplicity_ += 2; + } + } + + //update explained and duplicity values... + previous_explained_value += add_to_explained; + previous_duplicity_ += add_to_duplicity_; + } + + void updateCMDuplicity(std::vector & vec, std::vector & occupancy_vec, float sign) { + int add_to_duplicity_ = 0; + for (size_t i = 0; i < vec.size (); i++) + { + bool prev_dup = occupancy_vec[vec[i]] > 1; + occupancy_vec[vec[i]] += static_cast (sign); + if ((occupancy_vec[vec[i]] > 1) && prev_dup) + { //its still a duplicate, we are adding + add_to_duplicity_ += static_cast (sign); //so, just add or remove one + } else if ((occupancy_vec[vec[i]] == 1) && prev_dup) + { //if was duplicate before, now its not, remove 2, we are removing the hypothesis + add_to_duplicity_ -= 2; + } else if ((occupancy_vec[vec[i]] > 1) && !prev_dup) + { //it was not a duplicate but it is now, add 2, we are adding a conflicting hypothesis for the point + add_to_duplicity_ += 2; + } + } + + previous_duplicity_complete_models_ += add_to_duplicity_; + } + + float getTotalExplainedInformation(std::vector & explained_, std::vector & explained_by_RM_distance_weighted, int * duplicity_) + { + float explained_info = 0; + int duplicity = 0; + + for (size_t i = 0; i < explained_.size (); i++) + { + if (explained_[i] > 0) + explained_info += explained_by_RM_distance_weighted[i]; + + if (explained_[i] > 1) + duplicity += explained_[i]; + } + + *duplicity_ = duplicity; + + return explained_info; + } + + float getTotalBadInformation(std::vector > & recog_models) + { + float bad_info = 0; + for (size_t i = 0; i < recog_models.size (); i++) + bad_info += recog_models[i]->outliers_weight_ * static_cast (recog_models[i]->bad_information_); + + return bad_info; + } + + float getUnexplainedInformationInNeighborhood(std::vector & unexplained, std::vector & explained) + { + float unexplained_sum = 0.f; + for (size_t i = 0; i < unexplained.size (); i++) + { + if (unexplained[i] > 0 && explained[i] == 0) + unexplained_sum += unexplained[i]; + } + + return unexplained_sum; + } + + //Performs smooth segmentation of the scene cloud and compute the model cues + void + initialize(); + + mets::gol_type + evaluateSolution(const std::vector & active, int changed); + + bool + addModel(typename pcl::PointCloud::ConstPtr & model, typename pcl::PointCloud::ConstPtr & complete_model, + boost::shared_ptr & recog_model); + + void + computeClutterCue(boost::shared_ptr & recog_model); + + void + SAOptimize(std::vector & cc_indices, std::vector & sub_solution); + + public: + GlobalHypothesesVerification() : HypothesisVerification() + { + resolution_ = 0.005f; + max_iterations_ = 5000; + regularizer_ = 1.f; + radius_normals_ = 0.01f; + initial_temp_ = 1000; + detect_clutter_ = true; + radius_neighborhood_GO_ = 0.03f; + clutter_regularizer_ = 5.f; + res_occupancy_grid_ = 0.01f; + w_occupied_multiple_cm_ = 4.f; + } + + void + verify(); + + void setRadiusNormals(float r) + { + radius_normals_ = r; + } + + void setMaxIterations(int i) + { + max_iterations_ = i; + } + + void setInitialTemp(float t) + { + initial_temp_ = t; + } + + void setRegularizer(float r) + { + regularizer_ = r; + } + + void setRadiusClutter(float r) + { + radius_neighborhood_GO_ = r; + } + + void setClutterRegularizer(float cr) + { + clutter_regularizer_ = cr; + } + + void setDetectClutter(bool d) + { + detect_clutter_ = d; + } + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif /* GO_H_ */ diff --git a/pcl-1.7/pcl/recognition/hv/hv_papazov.h b/pcl-1.7/pcl/recognition/hv/hv_papazov.h new file mode 100644 index 0000000..5d4db89 --- /dev/null +++ b/pcl-1.7/pcl/recognition/hv/hv_papazov.h @@ -0,0 +1,123 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_RECOGNITION_HV_PAPAZOV_H_ +#define PCL_RECOGNITION_HV_PAPAZOV_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + + /** \brief A hypothesis verification method proposed in + * "An Efficient RANSAC for 3D Object Recognition in Noisy and Occluded Scenes", C. Papazov and D. Burschka, ACCV 2010 + * \author Aitor Aldoma, Federico Tombari + */ + + template + class PCL_EXPORTS PapazovHV : public HypothesisVerification + { + using HypothesisVerification::mask_; + using HypothesisVerification::scene_cloud_downsampled_; + using HypothesisVerification::scene_downsampled_tree_; + using HypothesisVerification::visible_models_; + using HypothesisVerification::complete_models_; + using HypothesisVerification::resolution_; + using HypothesisVerification::inliers_threshold_; + + float conflict_threshold_size_; + float penalty_threshold_; + float support_threshold_; + + class RecognitionModel + { + public: + std::vector explained_; //indices vector referencing explained_by_RM_ + typename pcl::PointCloud::Ptr cloud_; + typename pcl::PointCloud::Ptr complete_cloud_; + int bad_information_; + int id_; + }; + + std::vector explained_by_RM_; //represents the points of scene_cloud_ that are explained by the recognition models + std::vector< boost::shared_ptr > recognition_models_; + std::vector< std::vector > > points_explained_by_rm_; //if inner size > 1, conflict + std::map > graph_id_model_map_; + + typedef boost::adjacency_list > Graph; + Graph conflict_graph_; + + //builds the conflict_graph + void buildConflictGraph(); + //non-maxima suppresion on the conflict graph + void nonMaximaSuppresion(); + //create recognition models + void initialize(); + + public: + PapazovHV() : HypothesisVerification() { + support_threshold_ = 0.1f; + penalty_threshold_ = 0.1f; + conflict_threshold_size_ = 0.02f; + } + + void setConflictThreshold(float t) { + conflict_threshold_size_ = t; + } + + void setSupportThreshold(float t) { + support_threshold_ = t; + } + + void setPenaltyThreshold(float t) { + penalty_threshold_ = t; + } + + //build conflict graph + //non-maxima supression + void verify(); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif /* PCL_RECOGNITION_HV_PAPAZOV_H_ */ diff --git a/pcl-1.7/pcl/recognition/hv/hypotheses_verification.h b/pcl-1.7/pcl/recognition/hv/hypotheses_verification.h new file mode 100644 index 0000000..bc8e20d --- /dev/null +++ b/pcl-1.7/pcl/recognition/hv/hypotheses_verification.h @@ -0,0 +1,330 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_RECOGNITION_HYPOTHESIS_VERIFICATION_H_ +#define PCL_RECOGNITION_HYPOTHESIS_VERIFICATION_H_ + +#include +#include "pcl/recognition/hv/occlusion_reasoning.h" +#include "pcl/recognition/impl/hv/occlusion_reasoning.hpp" +#include +#include +#include + +namespace pcl +{ + + /** + * \brief Abstract class for hypotheses verification methods + * \author Aitor Aldoma, Federico Tombari + */ + + template + class PCL_EXPORTS HypothesisVerification + { + + protected: + /* + * \brief Boolean vector indicating if a hypothesis is accepted/rejected (output of HV stage) + */ + std::vector mask_; + /* + * \brief Scene point cloud + */ + typename pcl::PointCloud::ConstPtr scene_cloud_; + + /* + * \brief Scene point cloud + */ + typename pcl::PointCloud::ConstPtr occlusion_cloud_; + + bool occlusion_cloud_set_; + + /* + * \brief Downsampled scene point cloud + */ + typename pcl::PointCloud::Ptr scene_cloud_downsampled_; + + /* + * \brief Scene tree of the downsampled cloud + */ + typename pcl::search::KdTree::Ptr scene_downsampled_tree_; + + /* + * \brief Vector of point clouds representing the 3D models after occlusion reasoning + * the 3D models are pruned of occluded points, and only visible points are left. + * the coordinate system is that of the scene cloud + */ + typename std::vector::ConstPtr> visible_models_; + + std::vector::ConstPtr> visible_normal_models_; + /* + * \brief Vector of point clouds representing the complete 3D model (in same coordinates as the scene cloud) + */ + typename std::vector::ConstPtr> complete_models_; + + std::vector::ConstPtr> complete_normal_models_; + /* + * \brief Resolutions in pixel for the depth scene buffer + */ + int zbuffer_scene_resolution_; + /* + * \brief Resolutions in pixel for the depth model self-occlusion buffer + */ + int zbuffer_self_occlusion_resolution_; + /* + * \brief The resolution of models and scene used to verify hypotheses (in meters) + */ + float resolution_; + + /* + * \brief Threshold for inliers + */ + float inliers_threshold_; + + /* + * \brief Threshold to consider a point being occluded + */ + float occlusion_thres_; + + /* + * \brief Whether the HV method requires normals or not, by default = false + */ + bool requires_normals_; + + /* + * \brief Whether the normals have been set + */ + bool normals_set_; + public: + + HypothesisVerification () + { + zbuffer_scene_resolution_ = 100; + zbuffer_self_occlusion_resolution_ = 150; + resolution_ = 0.005f; + inliers_threshold_ = static_cast(resolution_); + occlusion_cloud_set_ = false; + occlusion_thres_ = 0.005f; + normals_set_ = false; + requires_normals_ = false; + } + + bool getRequiresNormals() { + return requires_normals_; + } + + /* + * \brief Sets the resolution of scene cloud and models used to verify hypotheses + * mask r resolution + */ + void + setResolution(float r) { + resolution_ = r; + } + + /* + * \brief Sets the occlusion threshold + * mask t threshold + */ + void + setOcclusionThreshold(float t) { + occlusion_thres_ = t; + } + + /* + * \brief Sets the resolution of scene cloud and models used to verify hypotheses + * mask r resolution + */ + void + setInlierThreshold(float r) { + inliers_threshold_ = r; + } + + /* + * \brief Returns a vector of booleans representing which hypotheses have been accepted/rejected (true/false) + * mask vector of booleans + */ + + void + getMask (std::vector & mask) + { + mask = mask_; + } + + /* + * \brief Sets the 3D complete models. NOTE: If addModels is called with occlusion_reasoning=true, then + * there is no need to call this function. + * mask models Vector of point clouds representing the models (in same coordinates as the scene_cloud_) + */ + + void + addCompleteModels (std::vector::ConstPtr> & complete_models) + { + complete_models_ = complete_models; + } + + /* + * \brief Sets the normals of the 3D complete models and sets normals_set_ to true. + * Normals need to be added before calling the addModels method. + * complete_models The normals of the models. + */ + void + addNormalsClouds (std::vector::ConstPtr> & complete_models) + { + complete_normal_models_ = complete_models; + normals_set_ = true; + } + + /* + * \brief Sets the models (recognition hypotheses) - requires the scene_cloud_ to be set first if reasoning about occlusions + * mask models Vector of point clouds representing the models (in same coordinates as the scene_cloud_) + */ + void + addModels (std::vector::ConstPtr> & models, bool occlusion_reasoning = false) + { + + mask_.clear(); + if(!occlusion_cloud_set_) { + PCL_WARN("Occlusion cloud not set, using scene_cloud instead...\n"); + occlusion_cloud_ = scene_cloud_; + } + + if (!occlusion_reasoning) + visible_models_ = models; + else + { + //we need to reason about occlusions before setting the model + if (scene_cloud_ == 0) + { + PCL_ERROR("setSceneCloud should be called before adding the model if reasoning about occlusions..."); + } + + if (!occlusion_cloud_->isOrganized ()) + { + PCL_WARN("Scene not organized... filtering using computed depth buffer\n"); + } + + pcl::occlusion_reasoning::ZBuffering zbuffer_scene (zbuffer_scene_resolution_, zbuffer_scene_resolution_, 1.f); + if (!occlusion_cloud_->isOrganized ()) + { + zbuffer_scene.computeDepthMap (occlusion_cloud_, true); + } + + for (size_t i = 0; i < models.size (); i++) + { + + //self-occlusions + typename pcl::PointCloud::Ptr filtered (new pcl::PointCloud ()); + typename pcl::occlusion_reasoning::ZBuffering zbuffer_self_occlusion (75, 75, 1.f); + zbuffer_self_occlusion.computeDepthMap (models[i], true); + std::vector indices; + zbuffer_self_occlusion.filter (models[i], indices, 0.005f); + pcl::copyPointCloud (*models[i], indices, *filtered); + + if(normals_set_ && requires_normals_) { + pcl::PointCloud::Ptr filtered_normals (new pcl::PointCloud ()); + pcl::copyPointCloud(*complete_normal_models_[i], indices, *filtered_normals); + visible_normal_models_.push_back(filtered_normals); + } + + typename pcl::PointCloud::ConstPtr const_filtered(new pcl::PointCloud (*filtered)); + //typename pcl::PointCloud::ConstPtr const_filtered(new pcl::PointCloud (*models[i])); + //scene-occlusions + if (occlusion_cloud_->isOrganized ()) + { + filtered = pcl::occlusion_reasoning::filter (occlusion_cloud_, const_filtered, 525.f, occlusion_thres_); + } + else + { + zbuffer_scene.filter (const_filtered, filtered, occlusion_thres_); + } + + visible_models_.push_back (filtered); + } + + complete_models_ = models; + } + + occlusion_cloud_set_ = false; + normals_set_ = false; + } + + /* + * \brief Sets the scene cloud + * scene_cloud Point cloud representing the scene + */ + + void + setSceneCloud (const typename pcl::PointCloud::Ptr & scene_cloud) + { + + complete_models_.clear(); + visible_models_.clear(); + visible_normal_models_.clear(); + + scene_cloud_ = scene_cloud; + scene_cloud_downsampled_.reset(new pcl::PointCloud()); + + pcl::VoxelGrid voxel_grid; + voxel_grid.setInputCloud (scene_cloud); + voxel_grid.setLeafSize (resolution_, resolution_, resolution_); + voxel_grid.setDownsampleAllData(true); + voxel_grid.filter (*scene_cloud_downsampled_); + + //initialize kdtree for search + scene_downsampled_tree_.reset (new pcl::search::KdTree); + scene_downsampled_tree_->setInputCloud(scene_cloud_downsampled_); + } + + void setOcclusionCloud (const typename pcl::PointCloud::Ptr & occ_cloud) + { + occlusion_cloud_ = occ_cloud; + occlusion_cloud_set_ = true; + } + + /* + * \brief Function that performs the hypotheses verification, needs to be implemented in the subclasses + * This function modifies the values of mask_ and needs to be called after both scene and model have been added + */ + + virtual void + verify ()=0; + }; + +} + +#endif /* PCL_RECOGNITION_HYPOTHESIS_VERIFICATION_H_ */ diff --git a/pcl-1.7/pcl/recognition/hv/occlusion_reasoning.h b/pcl-1.7/pcl/recognition/hv/occlusion_reasoning.h new file mode 100644 index 0000000..09fbec4 --- /dev/null +++ b/pcl-1.7/pcl/recognition/hv/occlusion_reasoning.h @@ -0,0 +1,218 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_RECOGNITION_OCCLUSION_REASONING_H_ +#define PCL_RECOGNITION_OCCLUSION_REASONING_H_ + +#include +#include +#include + +namespace pcl +{ + + namespace occlusion_reasoning + { + /** + * \brief Class to reason about occlusions + * \author Aitor Aldoma + */ + + template + class ZBuffering + { + private: + float f_; + int cx_, cy_; + float * depth_; + + public: + + ZBuffering (); + ZBuffering (int resx, int resy, float f); + ~ZBuffering (); + void + computeDepthMap (typename pcl::PointCloud::ConstPtr & scene, bool compute_focal = false, bool smooth = false, int wsize = 3); + void + filter (typename pcl::PointCloud::ConstPtr & model, typename pcl::PointCloud::Ptr & filtered, float thres = 0.01); + void filter (typename pcl::PointCloud::ConstPtr & model, std::vector & indices, float thres = 0.01); + }; + + template typename pcl::PointCloud::Ptr + filter (typename pcl::PointCloud::ConstPtr & organized_cloud, typename pcl::PointCloud::ConstPtr & to_be_filtered, float f, + float threshold) + { + float cx = (static_cast (organized_cloud->width) / 2.f - 0.5f); + float cy = (static_cast (organized_cloud->height) / 2.f - 0.5f); + typename pcl::PointCloud::Ptr filtered (new pcl::PointCloud ()); + + std::vector indices_to_keep; + indices_to_keep.resize (to_be_filtered->points.size ()); + + int keep = 0; + for (size_t i = 0; i < to_be_filtered->points.size (); i++) + { + float x = to_be_filtered->points[i].x; + float y = to_be_filtered->points[i].y; + float z = to_be_filtered->points[i].z; + int u = static_cast (f * x / z + cx); + int v = static_cast (f * y / z + cy); + + //Not out of bounds + if ((u >= static_cast (organized_cloud->width)) || (v >= static_cast (organized_cloud->height)) || (u < 0) || (v < 0)) + continue; + + //Check for invalid depth + if (!pcl_isfinite (organized_cloud->at (u, v).x) || !pcl_isfinite (organized_cloud->at (u, v).y) + || !pcl_isfinite (organized_cloud->at (u, v).z)) + continue; + + float z_oc = organized_cloud->at (u, v).z; + + //Check if point depth (distance to camera) is greater than the (u,v) + if ((z - z_oc) > threshold) + continue; + + indices_to_keep[keep] = static_cast (i); + keep++; + } + + indices_to_keep.resize (keep); + pcl::copyPointCloud (*to_be_filtered, indices_to_keep, *filtered); + return filtered; + } + + template typename pcl::PointCloud::Ptr + filter (typename pcl::PointCloud::Ptr & organized_cloud, typename pcl::PointCloud::Ptr & to_be_filtered, float f, + float threshold, bool check_invalid_depth = true) + { + float cx = (static_cast (organized_cloud->width) / 2.f - 0.5f); + float cy = (static_cast (organized_cloud->height) / 2.f - 0.5f); + typename pcl::PointCloud::Ptr filtered (new pcl::PointCloud ()); + + std::vector indices_to_keep; + indices_to_keep.resize (to_be_filtered->points.size ()); + + int keep = 0; + for (size_t i = 0; i < to_be_filtered->points.size (); i++) + { + float x = to_be_filtered->points[i].x; + float y = to_be_filtered->points[i].y; + float z = to_be_filtered->points[i].z; + int u = static_cast (f * x / z + cx); + int v = static_cast (f * y / z + cy); + + //Not out of bounds + if ((u >= static_cast (organized_cloud->width)) || (v >= static_cast (organized_cloud->height)) || (u < 0) || (v < 0)) + continue; + + //Check for invalid depth + if (check_invalid_depth) + { + if (!pcl_isfinite (organized_cloud->at (u, v).x) || !pcl_isfinite (organized_cloud->at (u, v).y) + || !pcl_isfinite (organized_cloud->at (u, v).z)) + continue; + } + + float z_oc = organized_cloud->at (u, v).z; + + //Check if point depth (distance to camera) is greater than the (u,v) + if ((z - z_oc) > threshold) + continue; + + indices_to_keep[keep] = static_cast (i); + keep++; + } + + indices_to_keep.resize (keep); + pcl::copyPointCloud (*to_be_filtered, indices_to_keep, *filtered); + return filtered; + } + + template typename pcl::PointCloud::Ptr + getOccludedCloud (typename pcl::PointCloud::Ptr & organized_cloud, typename pcl::PointCloud::Ptr & to_be_filtered, float f, + float threshold, bool check_invalid_depth = true) + { + float cx = (static_cast (organized_cloud->width) / 2.f - 0.5f); + float cy = (static_cast (organized_cloud->height) / 2.f - 0.5f); + typename pcl::PointCloud::Ptr filtered (new pcl::PointCloud ()); + + std::vector indices_to_keep; + indices_to_keep.resize (to_be_filtered->points.size ()); + + int keep = 0; + for (size_t i = 0; i < to_be_filtered->points.size (); i++) + { + float x = to_be_filtered->points[i].x; + float y = to_be_filtered->points[i].y; + float z = to_be_filtered->points[i].z; + int u = static_cast (f * x / z + cx); + int v = static_cast (f * y / z + cy); + + //Out of bounds + if ((u >= static_cast (organized_cloud->width)) || (v >= static_cast (organized_cloud->height)) || (u < 0) || (v < 0)) + continue; + + //Check for invalid depth + if (check_invalid_depth) + { + if (!pcl_isfinite (organized_cloud->at (u, v).x) || !pcl_isfinite (organized_cloud->at (u, v).y) + || !pcl_isfinite (organized_cloud->at (u, v).z)) + continue; + } + + float z_oc = organized_cloud->at (u, v).z; + + //Check if point depth (distance to camera) is greater than the (u,v) + if ((z - z_oc) > threshold) + { + indices_to_keep[keep] = static_cast (i); + keep++; + } + } + + indices_to_keep.resize (keep); + pcl::copyPointCloud (*to_be_filtered, indices_to_keep, *filtered); + return filtered; + } + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif /* PCL_RECOGNITION_OCCLUSION_REASONING_H_ */ diff --git a/pcl-1.7/pcl/recognition/hypothesis.h b/pcl-1.7/pcl/recognition/hypothesis.h new file mode 100644 index 0000000..4ac961a --- /dev/null +++ b/pcl-1.7/pcl/recognition/hypothesis.h @@ -0,0 +1,160 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/* + * hypothesis.h + * + * Created on: Mar 12, 2013 + * Author: papazov + */ + +#ifndef PCL_RECOGNITION_HYPOTHESIS_H_ +#define PCL_RECOGNITION_HYPOTHESIS_H_ + +#include +#include + +namespace pcl +{ + namespace recognition + { + class HypothesisBase + { + public: + HypothesisBase (const ModelLibrary::Model* obj_model) + : obj_model_ (obj_model) + {} + + HypothesisBase (const ModelLibrary::Model* obj_model, const float* rigid_transform) + : obj_model_ (obj_model) + { + memcpy (rigid_transform_, rigid_transform, 12*sizeof (float)); + } + + virtual ~HypothesisBase (){} + + void + setModel (const ModelLibrary::Model* model) + { + obj_model_ = model; + } + + public: + float rigid_transform_[12]; + const ModelLibrary::Model* obj_model_; + }; + + class Hypothesis: public HypothesisBase + { + public: + Hypothesis (const ModelLibrary::Model* obj_model = NULL) + : HypothesisBase (obj_model), + match_confidence_ (-1.0f), + linear_id_ (-1) + { + } + + Hypothesis (const Hypothesis& src) + : HypothesisBase (src.obj_model_, src.rigid_transform_), + match_confidence_ (src.match_confidence_), + explained_pixels_ (src.explained_pixels_) + { + } + + virtual ~Hypothesis (){} + + const Hypothesis& + operator =(const Hypothesis& src) + { + memcpy (this->rigid_transform_, src.rigid_transform_, 12*sizeof (float)); + this->obj_model_ = src.obj_model_; + this->match_confidence_ = src.match_confidence_; + this->explained_pixels_ = src.explained_pixels_; + + return *this; + } + + void + setLinearId (int id) + { + linear_id_ = id; + } + + int + getLinearId () const + { + return (linear_id_); + } + + void + computeBounds (float bounds[6]) const + { + const float *b = obj_model_->getBoundsOfOctreePoints (); + float p[3]; + + // Initialize 'bounds' + aux::transform (rigid_transform_, b[0], b[2], b[4], p); + bounds[0] = bounds[1] = p[0]; + bounds[2] = bounds[3] = p[1]; + bounds[4] = bounds[5] = p[2]; + + // Expand 'bounds' to contain the other 7 points of the octree bounding box + aux::transform (rigid_transform_, b[0], b[2], b[5], p); aux::expandBoundingBoxToContainPoint (bounds, p); + aux::transform (rigid_transform_, b[0], b[3], b[4], p); aux::expandBoundingBoxToContainPoint (bounds, p); + aux::transform (rigid_transform_, b[0], b[3], b[5], p); aux::expandBoundingBoxToContainPoint (bounds, p); + aux::transform (rigid_transform_, b[1], b[2], b[4], p); aux::expandBoundingBoxToContainPoint (bounds, p); + aux::transform (rigid_transform_, b[1], b[2], b[5], p); aux::expandBoundingBoxToContainPoint (bounds, p); + aux::transform (rigid_transform_, b[1], b[3], b[4], p); aux::expandBoundingBoxToContainPoint (bounds, p); + aux::transform (rigid_transform_, b[1], b[3], b[5], p); aux::expandBoundingBoxToContainPoint (bounds, p); + } + + void + computeCenterOfMass (float center_of_mass[3]) const + { + aux::transform (rigid_transform_, obj_model_->getOctreeCenterOfMass (), center_of_mass); + } + + public: + float match_confidence_; + std::set explained_pixels_; + int linear_id_; + }; + } // namespace recognition +} // namespace pcl + +#endif /* PCL_RECOGNITION_HYPOTHESIS_H_ */ diff --git a/pcl-1.7/pcl/recognition/impl/cg/correspondence_grouping.hpp b/pcl-1.7/pcl/recognition/impl/cg/correspondence_grouping.hpp new file mode 100644 index 0000000..8df7502 --- /dev/null +++ b/pcl-1.7/pcl/recognition/impl/cg/correspondence_grouping.hpp @@ -0,0 +1,60 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_RECOGNITION_CORRESPONDENCE_GROUPING_IMPL_H_ +#define PCL_RECOGNITION_CORRESPONDENCE_GROUPING_IMPL_H_ + +template void +pcl::CorrespondenceGrouping::cluster (std::vector &clustered_corrs) +{ + clustered_corrs.clear (); + corr_group_scale_.clear (); + + if (!initCompute ()) + { + return; + } + + //Perform the actual clustering + clusterCorrespondences (clustered_corrs); + + deinitCompute (); +} + +#endif // PCL_RECOGNITION_CORRESPONDENCE_GROUPING_IMPL_H_ diff --git a/pcl-1.7/pcl/recognition/impl/cg/geometric_consistency.hpp b/pcl-1.7/pcl/recognition/impl/cg/geometric_consistency.hpp new file mode 100644 index 0000000..71ef840 --- /dev/null +++ b/pcl-1.7/pcl/recognition/impl/cg/geometric_consistency.hpp @@ -0,0 +1,183 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_RECOGNITION_GEOMETRIC_CONSISTENCY_IMPL_H_ +#define PCL_RECOGNITION_GEOMETRIC_CONSISTENCY_IMPL_H_ + +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +bool +gcCorrespSorter (pcl::Correspondence i, pcl::Correspondence j) +{ + return (i.distance < j.distance); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GeometricConsistencyGrouping::clusterCorrespondences (std::vector &model_instances) +{ + model_instances.clear (); + found_transformations_.clear (); + + if (!model_scene_corrs_) + { + PCL_ERROR( + "[pcl::GeometricConsistencyGrouping::clusterCorrespondences()] Error! Correspondences not set, please set them before calling again this function.\n"); + return; + } + + CorrespondencesPtr sorted_corrs (new Correspondences (*model_scene_corrs_)); + + std::sort (sorted_corrs->begin (), sorted_corrs->end (), gcCorrespSorter); + + model_scene_corrs_ = sorted_corrs; + + std::vector consensus_set; + std::vector taken_corresps (model_scene_corrs_->size (), false); + + Eigen::Vector3f dist_ref, dist_trg; + + //temp copy of scene cloud with the type cast to ModelT in order to use Ransac + PointCloudPtr temp_scene_cloud_ptr (new PointCloud ()); + pcl::copyPointCloud (*scene_, *temp_scene_cloud_ptr); + + pcl::registration::CorrespondenceRejectorSampleConsensus corr_rejector; + corr_rejector.setMaximumIterations (10000); + corr_rejector.setInlierThreshold (gc_size_); + corr_rejector.setInputSource(input_); + corr_rejector.setInputTarget (temp_scene_cloud_ptr); + + for (size_t i = 0; i < model_scene_corrs_->size (); ++i) + { + if (taken_corresps[i]) + continue; + + consensus_set.clear (); + consensus_set.push_back (static_cast (i)); + + for (size_t j = 0; j < model_scene_corrs_->size (); ++j) + { + if ( j != i && !taken_corresps[j]) + { + //Let's check if j fits into the current consensus set + bool is_a_good_candidate = true; + for (size_t k = 0; k < consensus_set.size (); ++k) + { + int scene_index_k = model_scene_corrs_->at (consensus_set[k]).index_match; + int model_index_k = model_scene_corrs_->at (consensus_set[k]).index_query; + int scene_index_j = model_scene_corrs_->at (j).index_match; + int model_index_j = model_scene_corrs_->at (j).index_query; + + const Eigen::Vector3f& scene_point_k = scene_->at (scene_index_k).getVector3fMap (); + const Eigen::Vector3f& model_point_k = input_->at (model_index_k).getVector3fMap (); + const Eigen::Vector3f& scene_point_j = scene_->at (scene_index_j).getVector3fMap (); + const Eigen::Vector3f& model_point_j = input_->at (model_index_j).getVector3fMap (); + + dist_ref = scene_point_k - scene_point_j; + dist_trg = model_point_k - model_point_j; + + double distance = fabs (dist_ref.norm () - dist_trg.norm ()); + + if (distance > gc_size_) + { + is_a_good_candidate = false; + break; + } + } + + if (is_a_good_candidate) + consensus_set.push_back (static_cast (j)); + } + } + + if (static_cast (consensus_set.size ()) > gc_threshold_) + { + Correspondences temp_corrs, filtered_corrs; + for (size_t j = 0; j < consensus_set.size (); j++) + { + temp_corrs.push_back (model_scene_corrs_->at (consensus_set[j])); + taken_corresps[ consensus_set[j] ] = true; + } + //ransac filtering + corr_rejector.getRemainingCorrespondences (temp_corrs, filtered_corrs); + //save transformations for recognize + found_transformations_.push_back (corr_rejector.getBestTransformation ()); + + model_instances.push_back (filtered_corrs); + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::GeometricConsistencyGrouping::recognize ( + std::vector > &transformations) +{ + std::vector model_instances; + return (this->recognize (transformations, model_instances)); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::GeometricConsistencyGrouping::recognize ( + std::vector > &transformations, std::vector &clustered_corrs) +{ + transformations.clear (); + if (!this->initCompute ()) + { + PCL_ERROR( + "[pcl::GeometricConsistencyGrouping::recognize()] Error! Model cloud or Scene cloud not set, please set them before calling again this function.\n"); + return (false); + } + + clusterCorrespondences (clustered_corrs); + + transformations = found_transformations_; + + this->deinitCompute (); + return (true); +} + +#define PCL_INSTANTIATE_GeometricConsistencyGrouping(T,ST) template class PCL_EXPORTS pcl::GeometricConsistencyGrouping; + +#endif // PCL_RECOGNITION_GEOMETRIC_CONSISTENCY_IMPL_H_ diff --git a/pcl-1.7/pcl/recognition/impl/cg/hough_3d.hpp b/pcl-1.7/pcl/recognition/impl/cg/hough_3d.hpp new file mode 100644 index 0000000..b80fdb1 --- /dev/null +++ b/pcl-1.7/pcl/recognition/impl/cg/hough_3d.hpp @@ -0,0 +1,374 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id:$ + * + */ + +#ifndef PCL_RECOGNITION_HOUGH_3D_IMPL_H_ +#define PCL_RECOGNITION_HOUGH_3D_IMPL_H_ + +#include +#include +#include +//#include +//#include +#include +#include + + +template +template void +pcl::Hough3DGrouping::computeRf (const boost::shared_ptr > &input, pcl::PointCloud &rf) +{ + if (local_rf_search_radius_ == 0) + { + PCL_WARN ("[pcl::Hough3DGrouping::computeRf()] Warning! Reference frame search radius not set. Computing with default value. Results might be incorrect, algorithm might be slow.\n"); + local_rf_search_radius_ = static_cast (hough_bin_size_); + } + pcl::PointCloud::Ptr normal_cloud (new pcl::PointCloud ()); + NormalEstimation norm_est; + norm_est.setInputCloud (input); + if (local_rf_normals_search_radius_ <= 0.0f) + { + norm_est.setKSearch (15); + } + else + { + norm_est.setRadiusSearch (local_rf_normals_search_radius_); + } + norm_est.compute (*normal_cloud); + + BOARDLocalReferenceFrameEstimation rf_est; + rf_est.setInputCloud (input); + rf_est.setInputNormals (normal_cloud); + rf_est.setFindHoles (true); + rf_est.setRadiusSearch (local_rf_search_radius_); + rf_est.compute (rf); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::Hough3DGrouping::train () +{ + if (!input_) + { + PCL_ERROR ("[pcl::Hough3DGrouping::train()] Error! Input cloud not set.\n"); + return (false); + } + + if (!input_rf_) + { + ModelRfCloudPtr new_input_rf (new ModelRfCloud ()); + computeRf (input_, *new_input_rf); + input_rf_ = new_input_rf; + //PCL_ERROR( + // "[pcl::Hough3DGrouping::train()] Error! Input reference frame not set.\n"); + //return (false); + } + + if (input_->size () != input_rf_->size ()) + { + PCL_ERROR ("[pcl::Hough3DGrouping::train()] Error! Input cloud size != Input RF cloud size.\n"); + return (false); + } + + model_votes_.clear (); + model_votes_.resize (input_->size ()); + + // compute model centroid + Eigen::Vector3f centroid (0, 0, 0); + for (size_t i = 0; i < input_->size (); ++i) + { + centroid += input_->at (i).getVector3fMap (); + } + centroid /= static_cast (input_->size ()); + + // compute model votes + for (size_t i = 0; i < input_->size (); ++i) + { + Eigen::Vector3f x_ax ((*input_rf_)[i].x_axis[0], (*input_rf_)[i].x_axis[1], (*input_rf_)[i].x_axis[2]); + Eigen::Vector3f y_ax ((*input_rf_)[i].y_axis[0], (*input_rf_)[i].y_axis[1], (*input_rf_)[i].y_axis[2]); + Eigen::Vector3f z_ax ((*input_rf_)[i].z_axis[0], (*input_rf_)[i].z_axis[1], (*input_rf_)[i].z_axis[2]); + + model_votes_[i].x () = x_ax.dot (centroid - input_->at (i).getVector3fMap ()); + model_votes_[i].y () = y_ax.dot (centroid - input_->at (i).getVector3fMap ()); + model_votes_[i].z () = z_ax.dot (centroid - input_->at (i).getVector3fMap ()); + } + + needs_training_ = false; + return (true); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::Hough3DGrouping::houghVoting () +{ + if (needs_training_) + { + if (!train ())//checks input and input_rf + return (false); + } + + //if (!scene_) + //{ + // PCL_ERROR( + // "[pcl::Hough3DGrouping::recognizeModelInstances()] Error! Scene cloud not set.\n"); + // return (false); + //} + + if (!scene_rf_) + { + ModelRfCloudPtr new_scene_rf (new ModelRfCloud ()); + computeRf (scene_, *new_scene_rf); + scene_rf_ = new_scene_rf; + //PCL_ERROR( + // "[pcl::Hough3DGrouping::recognizeModelInstances()] Error! Scene reference frame not set.\n"); + //return (false); + } + + if (scene_->size () != scene_rf_->size ()) + { + PCL_ERROR ("[pcl::Hough3DGrouping::recognizeModelInstances()] Error! Scene cloud size != Scene RF cloud size.\n"); + return (false); + } + + if (!model_scene_corrs_) + { + PCL_ERROR ("[pcl::Hough3DGrouping::recognizeModelInstances()] Error! Correspondences not set, please set them before calling again this function.\n"); + return (false); + } + + int n_matches = static_cast (model_scene_corrs_->size ()); + if (n_matches == 0) + { + return (false); + } + + std::vector scene_votes (n_matches); + Eigen::Vector3d d_min, d_max, bin_size; + + d_min.setConstant (std::numeric_limits::max ()); + d_max.setConstant (-std::numeric_limits::max ()); + bin_size.setConstant (hough_bin_size_); + + float max_distance = -std::numeric_limits::max (); + + // Calculating 3D Hough space dimensions and vote position for each match + for (int i=0; i< n_matches; ++i) + { + int scene_index = model_scene_corrs_->at (i).index_match; + int model_index = model_scene_corrs_->at (i).index_query; + + const Eigen::Vector3f& scene_point = scene_->at (scene_index).getVector3fMap (); + const PointSceneRfT& scene_point_rf = scene_rf_->at (scene_index); + + Eigen::Vector3f scene_point_rf_x (scene_point_rf.x_axis[0], scene_point_rf.x_axis[1], scene_point_rf.x_axis[2]); + Eigen::Vector3f scene_point_rf_y (scene_point_rf.y_axis[0], scene_point_rf.y_axis[1], scene_point_rf.y_axis[2]); + Eigen::Vector3f scene_point_rf_z (scene_point_rf.z_axis[0], scene_point_rf.z_axis[1], scene_point_rf.z_axis[2]); + + //const Eigen::Vector3f& model_point = input_->at (model_index).getVector3fMap (); + const Eigen::Vector3f& model_point_vote = model_votes_[model_index]; + + scene_votes[i].x () = scene_point_rf_x[0] * model_point_vote.x () + scene_point_rf_y[0] * model_point_vote.y () + scene_point_rf_z[0] * model_point_vote.z () + scene_point.x (); + scene_votes[i].y () = scene_point_rf_x[1] * model_point_vote.x () + scene_point_rf_y[1] * model_point_vote.y () + scene_point_rf_z[1] * model_point_vote.z () + scene_point.y (); + scene_votes[i].z () = scene_point_rf_x[2] * model_point_vote.x () + scene_point_rf_y[2] * model_point_vote.y () + scene_point_rf_z[2] * model_point_vote.z () + scene_point.z (); + + if (scene_votes[i].x () < d_min.x ()) + d_min.x () = scene_votes[i].x (); + if (scene_votes[i].x () > d_max.x ()) + d_max.x () = scene_votes[i].x (); + + if (scene_votes[i].y () < d_min.y ()) + d_min.y () = scene_votes[i].y (); + if (scene_votes[i].y () > d_max.y ()) + d_max.y () = scene_votes[i].y (); + + if (scene_votes[i].z () < d_min.z ()) + d_min.z () = scene_votes[i].z (); + if (scene_votes[i].z () > d_max.z ()) + d_max.z () = scene_votes[i].z (); + + // Calculate max distance for interpolated votes + if (use_interpolation_ && max_distance < model_scene_corrs_->at (i).distance) + { + max_distance = model_scene_corrs_->at (i).distance; + } + } + + // Hough Voting + hough_space_.reset (new pcl::recognition::HoughSpace3D (d_min, bin_size, d_max)); + + for (int i = 0; i < n_matches; ++i) + { + double weight = 1.0; + if (use_distance_weight_ && max_distance != 0) + { + weight = 1.0 - (model_scene_corrs_->at (i).distance / max_distance); + } + if (use_interpolation_) + { + hough_space_->voteInt (scene_votes[i], weight, i); + } + else + { + hough_space_->vote (scene_votes[i], weight, i); + } + } + + hough_space_initialized_ = true; + + return (true); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::Hough3DGrouping::clusterCorrespondences (std::vector &model_instances) +{ + model_instances.clear (); + found_transformations_.clear (); + + if (!hough_space_initialized_ && !houghVoting ()) + { + return; + } + + // Finding max bins and voters + std::vector max_values; + std::vector > max_ids; + + hough_space_->findMaxima (hough_threshold_, max_values, max_ids); + + // Insert maximas into result vector, after Ransac correspondence rejection + // Temp copy of scene cloud with the type cast to ModelT in order to use Ransac + PointCloudPtr temp_scene_cloud_ptr (new PointCloud); + pcl::copyPointCloud (*scene_, *temp_scene_cloud_ptr); + + pcl::registration::CorrespondenceRejectorSampleConsensus corr_rejector; + corr_rejector.setMaximumIterations (10000); + corr_rejector.setInlierThreshold (hough_bin_size_); + corr_rejector.setInputSource (input_); + corr_rejector.setInputTarget (temp_scene_cloud_ptr); + + for (size_t j = 0; j < max_values.size (); ++j) + { + Correspondences temp_corrs, filtered_corrs; + for (size_t i = 0; i < max_ids[j].size (); ++i) + { + temp_corrs.push_back (model_scene_corrs_->at (max_ids[j][i])); + } + // RANSAC filtering + corr_rejector.getRemainingCorrespondences (temp_corrs, filtered_corrs); + // Save transformations for recognize + found_transformations_.push_back (corr_rejector.getBestTransformation ()); + + model_instances.push_back (filtered_corrs); + } +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +//template bool +//pcl::Hough3DGrouping::getTransformMatrix (const PointCloudConstPtr &scene_cloud, const Correspondences &corrs, Eigen::Matrix4f &transform) +//{ +// std::vector model_indices; +// std::vector scene_indices; +// pcl::registration::getQueryIndices (corrs, model_indices); +// pcl::registration::getMatchIndices (corrs, scene_indices); +// +// typename pcl::SampleConsensusModelRegistration::Ptr model (new pcl::SampleConsensusModelRegistration (input_, model_indices)); +// model->setInputTarget (scene_cloud, scene_indices); +// +// pcl::RandomSampleConsensus ransac (model); +// ransac.setDistanceThreshold (hough_bin_size_); +// ransac.setMaxIterations (10000); +// if (!ransac.computeModel ()) +// return (false); +// +// // Transform model coefficients from vectorXf to matrix4f +// Eigen::VectorXf coeffs; +// ransac.getModelCoefficients (coeffs); +// +// transform.row (0) = coeffs.segment<4> (0); +// transform.row (1) = coeffs.segment<4> (4); +// transform.row (2) = coeffs.segment<4> (8); +// transform.row (3) = coeffs.segment<4> (12); +// +// return (true); +//} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::Hough3DGrouping::recognize ( + std::vector > &transformations) +{ + std::vector model_instances; + return (this->recognize (transformations, model_instances)); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::Hough3DGrouping::recognize ( + std::vector > &transformations, std::vector &clustered_corrs) +{ + transformations.clear (); + if (!this->initCompute ()) + { + PCL_ERROR ("[pcl::Hough3DGrouping::recognize()] Error! Model cloud or Scene cloud not set, please set them before calling again this function.\n"); + return (false); + } + + clusterCorrespondences (clustered_corrs); + + transformations = found_transformations_; + + //// Temp copy of scene cloud with the type cast to ModelT in order to use Ransac + //PointCloudPtr temp_scene_cloud_ptr (new PointCloud); + //pcl::copyPointCloud (*scene_, *temp_scene_cloud_ptr); + + //for (size_t i = 0; i < model_instances.size (); ++i) + //{ + // Eigen::Matrix4f curr_transf; + // if (getTransformMatrix (temp_scene_cloud_ptr, model_instances[i], curr_transf)) + // transformations.push_back (curr_transf); + //} + + this->deinitCompute (); + return (true); +} + + +#define PCL_INSTANTIATE_Hough3DGrouping(T,ST,RFT,SRFT) template class PCL_EXPORTS pcl::Hough3DGrouping; + +#endif // PCL_RECOGNITION_HOUGH_3D_IMPL_H_ diff --git a/pcl-1.7/pcl/recognition/impl/hv/greedy_verification.hpp b/pcl-1.7/pcl/recognition/impl/hv/greedy_verification.hpp new file mode 100644 index 0000000..9e2c4fe --- /dev/null +++ b/pcl-1.7/pcl/recognition/impl/hv/greedy_verification.hpp @@ -0,0 +1,143 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#pragma once +#include + +template + void + pcl::GreedyVerification::initialize () + { + //clear stuff + recognition_models_.clear (); + points_explained_by_rm_.clear (); + + // initialize mask... + mask_.resize (visible_models_.size ()); + for (size_t i = 0; i < visible_models_.size (); i++) + mask_[i] = false; + + // initialize explained_by_RM + points_explained_by_rm_.resize (scene_cloud_downsampled_->points.size ()); + + // initalize model + for (size_t m = 0; m < visible_models_.size (); m++) + { + boost::shared_ptr < RecognitionModel > recog_model (new RecognitionModel); + // voxelize model cloud + recog_model->cloud_.reset (new pcl::PointCloud); + recog_model->id_ = static_cast (m); + + pcl::VoxelGrid voxel_grid; + voxel_grid.setInputCloud (visible_models_[m]); + voxel_grid.setLeafSize (resolution_, resolution_, resolution_); + voxel_grid.filter (*(recog_model->cloud_)); + + std::vector explained_indices; + std::vector outliers; + std::vector nn_indices; + std::vector nn_distances; + + for (size_t i = 0; i < recog_model->cloud_->points.size (); i++) + { + if (!scene_downsampled_tree_->radiusSearch (recog_model->cloud_->points[i], inliers_threshold_, nn_indices, nn_distances, + std::numeric_limits::max ())) + { + outliers.push_back (static_cast (i)); + } + else + { + for (size_t k = 0; k < nn_distances.size (); k++) + { + explained_indices.push_back (nn_indices[k]); //nn_indices[k] points to the scene + } + } + } + + std::sort (explained_indices.begin (), explained_indices.end ()); + explained_indices.erase (std::unique (explained_indices.begin (), explained_indices.end ()), explained_indices.end ()); + + recog_model->bad_information_ = static_cast (outliers.size ()); + recog_model->explained_ = explained_indices; + recog_model->good_information_ = static_cast (explained_indices.size ()); + recog_model->regularizer_ = regularizer_; + + recognition_models_.push_back (recog_model); + + for (size_t i = 0; i < explained_indices.size (); i++) + { + points_explained_by_rm_[explained_indices[i]].push_back (recog_model); + } + } + + sortModels (); + } + +template + void + pcl::GreedyVerification::verify () + { + initialize (); + + std::vector best_solution_; + best_solution_.resize (recognition_models_.size ()); + + for (size_t i = 0; i < recognition_models_.size (); i++) + { + if (static_cast (recognition_models_[i]->good_information_) > (regularizer_ + * static_cast (recognition_models_[i]->bad_information_))) + { + best_solution_[i] = true; + updateGoodInformation (static_cast (i)); + } + else + best_solution_[i] = false; + } + + for (size_t i = 0; i < best_solution_.size (); i++) + { + if (best_solution_[i]) + { + mask_[indices_models_[i].index_] = true; + } + else + { + mask_[indices_models_[i].index_] = false; + } + } + } + +#define PCL_INSTANTIATE_GreedyVerification(T1,T2) template class PCL_EXPORTS pcl::GreedyVerification; diff --git a/pcl-1.7/pcl/recognition/impl/hv/hv_go.hpp b/pcl-1.7/pcl/recognition/impl/hv/hv_go.hpp new file mode 100644 index 0000000..118e514 --- /dev/null +++ b/pcl-1.7/pcl/recognition/impl/hv/hv_go.hpp @@ -0,0 +1,746 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012 Aitor Aldoma, Federico Tombari + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_RECOGNITION_IMPL_HV_GO_HPP_ +#define PCL_RECOGNITION_IMPL_HV_GO_HPP_ + +#include +#include +#include +#include + +template +inline void extractEuclideanClustersSmooth(const typename pcl::PointCloud &cloud, const typename pcl::PointCloud &normals, float tolerance, + const typename pcl::search::Search::Ptr &tree, std::vector &clusters, double eps_angle, float curvature_threshold, + unsigned int min_pts_per_cluster, unsigned int max_pts_per_cluster = (std::numeric_limits::max) ()) +{ + + if (tree->getInputCloud ()->points.size () != cloud.points.size ()) + { + PCL_ERROR("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset\n"); + return; + } + if (cloud.points.size () != normals.points.size ()) + { + PCL_ERROR("[pcl::extractEuclideanClusters] Number of points in the input point cloud different than normals!\n"); + return; + } + + // Create a bool vector of processed point indices, and initialize it to false + std::vector processed (cloud.points.size (), false); + + std::vector nn_indices; + std::vector nn_distances; + // Process all points in the indices vector + int size = static_cast (cloud.points.size ()); + for (int i = 0; i < size; ++i) + { + if (processed[i]) + continue; + + std::vector seed_queue; + int sq_idx = 0; + seed_queue.push_back (i); + + processed[i] = true; + + while (sq_idx < static_cast (seed_queue.size ())) + { + + if (normals.points[seed_queue[sq_idx]].curvature > curvature_threshold) + { + sq_idx++; + continue; + } + + // Search for sq_idx + if (!tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances)) + { + sq_idx++; + continue; + } + + for (size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx + { + if (processed[nn_indices[j]]) // Has this point been processed before ? + continue; + + if (normals.points[nn_indices[j]].curvature > curvature_threshold) + { + continue; + } + + //processed[nn_indices[j]] = true; + // [-1;1] + + double dot_p = normals.points[seed_queue[sq_idx]].normal[0] * normals.points[nn_indices[j]].normal[0] + + normals.points[seed_queue[sq_idx]].normal[1] * normals.points[nn_indices[j]].normal[1] + + normals.points[seed_queue[sq_idx]].normal[2] * normals.points[nn_indices[j]].normal[2]; + + if (fabs (acos (dot_p)) < eps_angle) + { + processed[nn_indices[j]] = true; + seed_queue.push_back (nn_indices[j]); + } + } + + sq_idx++; + } + + // If this queue is satisfactory, add to the clusters + if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster) + { + pcl::PointIndices r; + r.indices.resize (seed_queue.size ()); + for (size_t j = 0; j < seed_queue.size (); ++j) + r.indices[j] = seed_queue[j]; + + std::sort (r.indices.begin (), r.indices.end ()); + r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ()); + + r.header = cloud.header; + clusters.push_back (r); // We could avoid a copy by working directly in the vector + } + } +} + +template +mets::gol_type pcl::GlobalHypothesesVerification::evaluateSolution(const std::vector & active, int changed) +{ + float sign = 1.f; + //update explained_by_RM + if (active[changed]) + { + //it has been activated + updateExplainedVector (recognition_models_[changed]->explained_, recognition_models_[changed]->explained_distances_, explained_by_RM_, + explained_by_RM_distance_weighted, 1.f); + updateUnexplainedVector (recognition_models_[changed]->unexplained_in_neighborhood, recognition_models_[changed]->unexplained_in_neighborhood_weights, + unexplained_by_RM_neighboorhods, recognition_models_[changed]->explained_, explained_by_RM_, 1.f); + updateCMDuplicity(recognition_models_[changed]->complete_cloud_occupancy_indices_, complete_cloud_occupancy_by_RM_, 1.f); + } else + { + //it has been deactivated + updateExplainedVector (recognition_models_[changed]->explained_, recognition_models_[changed]->explained_distances_, explained_by_RM_, + explained_by_RM_distance_weighted, -1.f); + updateUnexplainedVector (recognition_models_[changed]->unexplained_in_neighborhood, recognition_models_[changed]->unexplained_in_neighborhood_weights, + unexplained_by_RM_neighboorhods, recognition_models_[changed]->explained_, explained_by_RM_, -1.f); + updateCMDuplicity(recognition_models_[changed]->complete_cloud_occupancy_indices_, complete_cloud_occupancy_by_RM_, -1.f); + sign = -1.f; + } + + int duplicity = getDuplicity (); + float good_info = getExplainedValue (); + + float unexplained_info = getPreviousUnexplainedValue (); + float bad_info = static_cast (getPreviousBadInfo ()) + + (recognition_models_[changed]->outliers_weight_ * static_cast (recognition_models_[changed]->bad_information_)) * sign; + + setPreviousBadInfo (bad_info); + + int n_active_hyp = 0; + for(size_t i=0; i < active.size(); i++) { + if(active[i]) + n_active_hyp++; + } + + float duplicity_cm = static_cast (getDuplicityCM ()) * w_occupied_multiple_cm_; + return static_cast ((good_info - bad_info - static_cast (duplicity) - unexplained_info - duplicity_cm - static_cast (n_active_hyp)) * -1.f); //return the dual to our max problem +} + +/////////////////////////////////////////////////////////////////////////////////////////////////// +template +void pcl::GlobalHypothesesVerification::initialize() +{ + //clear stuff + recognition_models_.clear (); + unexplained_by_RM_neighboorhods.clear (); + explained_by_RM_distance_weighted.clear (); + explained_by_RM_.clear (); + mask_.clear (); + indices_.clear (), + complete_cloud_occupancy_by_RM_.clear (); + + // initialize mask to false + mask_.resize (complete_models_.size ()); + for (size_t i = 0; i < complete_models_.size (); i++) + mask_[i] = false; + + indices_.resize (complete_models_.size ()); + + NormalEstimator_ n3d; + scene_normals_.reset (new pcl::PointCloud ()); + + typename pcl::search::KdTree::Ptr normals_tree (new pcl::search::KdTree); + normals_tree->setInputCloud (scene_cloud_downsampled_); + + n3d.setRadiusSearch (radius_normals_); + n3d.setSearchMethod (normals_tree); + n3d.setInputCloud (scene_cloud_downsampled_); + n3d.compute (*scene_normals_); + + //check nans... + int j = 0; + for (size_t i = 0; i < scene_normals_->points.size (); ++i) + { + if (!pcl_isfinite (scene_normals_->points[i].normal_x) || !pcl_isfinite (scene_normals_->points[i].normal_y) + || !pcl_isfinite (scene_normals_->points[i].normal_z)) + continue; + + scene_normals_->points[j] = scene_normals_->points[i]; + scene_cloud_downsampled_->points[j] = scene_cloud_downsampled_->points[i]; + + j++; + } + + scene_normals_->points.resize (j); + scene_normals_->width = j; + scene_normals_->height = 1; + + scene_cloud_downsampled_->points.resize (j); + scene_cloud_downsampled_->width = j; + scene_cloud_downsampled_->height = 1; + + explained_by_RM_.resize (scene_cloud_downsampled_->points.size (), 0); + explained_by_RM_distance_weighted.resize (scene_cloud_downsampled_->points.size (), 0.f); + unexplained_by_RM_neighboorhods.resize (scene_cloud_downsampled_->points.size (), 0.f); + + //compute segmentation of the scene if detect_clutter_ + if (detect_clutter_) + { + //initialize kdtree for search + scene_downsampled_tree_.reset (new pcl::search::KdTree); + scene_downsampled_tree_->setInputCloud (scene_cloud_downsampled_); + + std::vector clusters; + double eps_angle_threshold = 0.2; + int min_points = 20; + float curvature_threshold = 0.045f; + + extractEuclideanClustersSmooth (*scene_cloud_downsampled_, *scene_normals_, inliers_threshold_ * 2.f, scene_downsampled_tree_, + clusters, eps_angle_threshold, curvature_threshold, min_points); + + clusters_cloud_.reset (new pcl::PointCloud); + clusters_cloud_->points.resize (scene_cloud_downsampled_->points.size ()); + clusters_cloud_->width = scene_cloud_downsampled_->width; + clusters_cloud_->height = 1; + + for (size_t i = 0; i < scene_cloud_downsampled_->points.size (); i++) + { + pcl::PointXYZI p; + p.getVector3fMap () = scene_cloud_downsampled_->points[i].getVector3fMap (); + p.intensity = 0.f; + clusters_cloud_->points[i] = p; + } + + float intens_incr = 100.f / static_cast (clusters.size ()); + float intens = intens_incr; + for (size_t i = 0; i < clusters.size (); i++) + { + for (size_t j = 0; j < clusters[i].indices.size (); j++) + { + clusters_cloud_->points[clusters[i].indices[j]].intensity = intens; + } + + intens += intens_incr; + } + } + + //compute cues + { + pcl::ScopeTime tcues ("Computing cues"); + recognition_models_.resize (complete_models_.size ()); + int valid = 0; + for (int i = 0; i < static_cast (complete_models_.size ()); i++) + { + //create recognition model + recognition_models_[valid].reset (new RecognitionModel ()); + if(addModel (visible_models_[i], complete_models_[i], recognition_models_[valid])) { + indices_[valid] = i; + valid++; + } + } + + recognition_models_.resize(valid); + indices_.resize(valid); + } + + //compute the bounding boxes for the models + ModelT min_pt_all, max_pt_all; + min_pt_all.x = min_pt_all.y = min_pt_all.z = std::numeric_limits::max (); + max_pt_all.x = max_pt_all.y = max_pt_all.z = (std::numeric_limits::max () - 0.001f) * -1; + + for (size_t i = 0; i < recognition_models_.size (); i++) + { + ModelT min_pt, max_pt; + pcl::getMinMax3D (*complete_models_[indices_[i]], min_pt, max_pt); + if (min_pt.x < min_pt_all.x) + min_pt_all.x = min_pt.x; + + if (min_pt.y < min_pt_all.y) + min_pt_all.y = min_pt.y; + + if (min_pt.z < min_pt_all.z) + min_pt_all.z = min_pt.z; + + if (max_pt.x > max_pt_all.x) + max_pt_all.x = max_pt.x; + + if (max_pt.y > max_pt_all.y) + max_pt_all.y = max_pt.y; + + if (max_pt.z > max_pt_all.z) + max_pt_all.z = max_pt.z; + } + + int size_x, size_y, size_z; + size_x = static_cast (std::ceil (std::abs (max_pt_all.x - min_pt_all.x) / res_occupancy_grid_)) + 1; + size_y = static_cast (std::ceil (std::abs (max_pt_all.y - min_pt_all.y) / res_occupancy_grid_)) + 1; + size_z = static_cast (std::ceil (std::abs (max_pt_all.z - min_pt_all.z) / res_occupancy_grid_)) + 1; + + complete_cloud_occupancy_by_RM_.resize (size_x * size_y * size_z, 0); + + for (size_t i = 0; i < recognition_models_.size (); i++) + { + + std::map banned; + std::map::iterator banned_it; + + for (size_t j = 0; j < complete_models_[indices_[i]]->points.size (); j++) + { + int pos_x, pos_y, pos_z; + pos_x = static_cast (std::floor ((complete_models_[indices_[i]]->points[j].x - min_pt_all.x) / res_occupancy_grid_)); + pos_y = static_cast (std::floor ((complete_models_[indices_[i]]->points[j].y - min_pt_all.y) / res_occupancy_grid_)); + pos_z = static_cast (std::floor ((complete_models_[indices_[i]]->points[j].z - min_pt_all.z) / res_occupancy_grid_)); + + int idx = pos_z * size_x * size_y + pos_y * size_x + pos_x; + banned_it = banned.find (idx); + if (banned_it == banned.end ()) + { + complete_cloud_occupancy_by_RM_[idx]++; + recognition_models_[i]->complete_cloud_occupancy_indices_.push_back (idx); + banned[idx] = true; + } + } + } + + { + pcl::ScopeTime tcues ("Computing clutter cues"); +#pragma omp parallel for schedule(dynamic, 4) num_threads(omp_get_num_procs()) + for (int j = 0; j < static_cast (recognition_models_.size ()); j++) + computeClutterCue (recognition_models_[j]); + } + + cc_.clear (); + n_cc_ = 1; + cc_.resize (n_cc_); + for (size_t i = 0; i < recognition_models_.size (); i++) + cc_[0].push_back (static_cast (i)); + +} + +template +void pcl::GlobalHypothesesVerification::SAOptimize(std::vector & cc_indices, std::vector & initial_solution) +{ + + //temporal copy of recogniton_models_ + std::vector < boost::shared_ptr > recognition_models_copy; + recognition_models_copy = recognition_models_; + + recognition_models_.clear (); + + for (size_t j = 0; j < cc_indices.size (); j++) + { + recognition_models_.push_back (recognition_models_copy[cc_indices[j]]); + } + + for (size_t j = 0; j < recognition_models_.size (); j++) + { + boost::shared_ptr < RecognitionModel > recog_model = recognition_models_[j]; + for (size_t i = 0; i < recog_model->explained_.size (); i++) + { + explained_by_RM_[recog_model->explained_[i]]++; + explained_by_RM_distance_weighted[recog_model->explained_[i]] += recog_model->explained_distances_[i]; + } + + if (detect_clutter_) + { + for (size_t i = 0; i < recog_model->unexplained_in_neighborhood.size (); i++) + { + unexplained_by_RM_neighboorhods[recog_model->unexplained_in_neighborhood[i]] += recog_model->unexplained_in_neighborhood_weights[i]; + } + } + } + + int occupied_multiple = 0; + for(size_t i=0; i < complete_cloud_occupancy_by_RM_.size(); i++) { + if(complete_cloud_occupancy_by_RM_[i] > 1) { + occupied_multiple+=complete_cloud_occupancy_by_RM_[i]; + } + } + + setPreviousDuplicityCM(occupied_multiple); + //do optimization + //Define model SAModel, initial solution is all models activated + + int duplicity; + float good_information_ = getTotalExplainedInformation (explained_by_RM_, explained_by_RM_distance_weighted, &duplicity); + float bad_information_ = 0; + float unexplained_in_neighboorhod = getUnexplainedInformationInNeighborhood (unexplained_by_RM_neighboorhods, explained_by_RM_); + + for (size_t i = 0; i < initial_solution.size (); i++) + { + if (initial_solution[i]) + bad_information_ += recognition_models_[i]->outliers_weight_ * static_cast (recognition_models_[i]->bad_information_); + } + + setPreviousExplainedValue (good_information_); + setPreviousDuplicity (duplicity); + setPreviousBadInfo (bad_information_); + setPreviousUnexplainedValue (unexplained_in_neighboorhod); + + SAModel model; + model.cost_ = static_cast ((good_information_ - bad_information_ + - static_cast (duplicity) + - static_cast (occupied_multiple) * w_occupied_multiple_cm_ + - static_cast (recognition_models_.size ()) + - unexplained_in_neighboorhod) * -1.f); + + model.setSolution (initial_solution); + model.setOptimizer (this); + SAModel best (model); + + move_manager neigh (static_cast (cc_indices.size ())); + + mets::best_ever_solution best_recorder (best); + mets::noimprove_termination_criteria noimprove (max_iterations_); + mets::linear_cooling linear_cooling; + mets::simulated_annealing sa (model, best_recorder, neigh, noimprove, linear_cooling, initial_temp_, 1e-7, 2); + sa.setApplyAndEvaluate(true); + + { + pcl::ScopeTime t ("SA search..."); + sa.search (); + } + + best_seen_ = static_cast (best_recorder.best_seen ()); + for (size_t i = 0; i < best_seen_.solution_.size (); i++) + { + initial_solution[i] = best_seen_.solution_[i]; + } + + recognition_models_ = recognition_models_copy; + +} + +/////////////////////////////////////////////////////////////////////////////////////////////////// +template +void pcl::GlobalHypothesesVerification::verify() +{ + initialize (); + + //for each connected component, find the optimal solution + for (int c = 0; c < n_cc_; c++) + { + //TODO: Check for trivial case... + //TODO: Check also the number of hypotheses and use exhaustive enumeration if smaller than 10 + std::vector subsolution (cc_[c].size (), true); + SAOptimize (cc_[c], subsolution); + for (size_t i = 0; i < subsolution.size (); i++) + { + mask_[indices_[cc_[c][i]]] = (subsolution[i]); + } + } +} + +template +bool pcl::GlobalHypothesesVerification::addModel(typename pcl::PointCloud::ConstPtr & model, + typename pcl::PointCloud::ConstPtr & complete_model, boost::shared_ptr & recog_model) +{ + //voxelize model cloud + recog_model->cloud_.reset (new pcl::PointCloud ()); + recog_model->complete_cloud_.reset (new pcl::PointCloud ()); + + float size_model = resolution_; + pcl::VoxelGrid voxel_grid; + voxel_grid.setInputCloud (model); + voxel_grid.setLeafSize (size_model, size_model, size_model); + voxel_grid.filter (*(recog_model->cloud_)); + + pcl::VoxelGrid voxel_grid2; + voxel_grid2.setInputCloud (complete_model); + voxel_grid2.setLeafSize (size_model, size_model, size_model); + voxel_grid2.filter (*(recog_model->complete_cloud_)); + + { + //check nans... + int j = 0; + for (size_t i = 0; i < recog_model->cloud_->points.size (); ++i) + { + if (!pcl_isfinite (recog_model->cloud_->points[i].x) || !pcl_isfinite (recog_model->cloud_->points[i].y) + || !pcl_isfinite (recog_model->cloud_->points[i].z)) + continue; + + recog_model->cloud_->points[j] = recog_model->cloud_->points[i]; + j++; + } + + recog_model->cloud_->points.resize (j); + recog_model->cloud_->width = j; + recog_model->cloud_->height = 1; + } + + if (recog_model->cloud_->points.size () <= 0) + { + PCL_WARN("The model cloud has no points..\n"); + return false; + } + + //compute normals unless given (now do it always...) + typename pcl::search::KdTree::Ptr normals_tree (new pcl::search::KdTree); + typedef typename pcl::NormalEstimation NormalEstimator_; + NormalEstimator_ n3d; + recog_model->normals_.reset (new pcl::PointCloud ()); + normals_tree->setInputCloud (recog_model->cloud_); + n3d.setRadiusSearch (radius_normals_); + n3d.setSearchMethod (normals_tree); + n3d.setInputCloud ((recog_model->cloud_)); + n3d.compute (*(recog_model->normals_)); + + //check nans... + int j = 0; + for (size_t i = 0; i < recog_model->normals_->points.size (); ++i) + { + if (!pcl_isfinite (recog_model->normals_->points[i].normal_x) || !pcl_isfinite (recog_model->normals_->points[i].normal_y) + || !pcl_isfinite (recog_model->normals_->points[i].normal_z)) + continue; + + recog_model->normals_->points[j] = recog_model->normals_->points[i]; + recog_model->cloud_->points[j] = recog_model->cloud_->points[i]; + j++; + } + + recog_model->normals_->points.resize (j); + recog_model->normals_->width = j; + recog_model->normals_->height = 1; + + recog_model->cloud_->points.resize (j); + recog_model->cloud_->width = j; + recog_model->cloud_->height = 1; + + std::vector explained_indices; + std::vector outliers_weight; + std::vector explained_indices_distances; + std::vector unexplained_indices_weights; + + std::vector nn_indices; + std::vector nn_distances; + + std::map > > > model_explains_scene_points; //which point i from the scene is explained by a points j_k with dist d_k from the model + std::map > > >::iterator it; + + outliers_weight.resize (recog_model->cloud_->points.size ()); + recog_model->outlier_indices_.resize (recog_model->cloud_->points.size ()); + + size_t o = 0; + for (size_t i = 0; i < recog_model->cloud_->points.size (); i++) + { + if (!scene_downsampled_tree_->radiusSearch (recog_model->cloud_->points[i], inliers_threshold_, nn_indices, nn_distances, std::numeric_limits::max ())) + { + //outlier + outliers_weight[o] = regularizer_; + recog_model->outlier_indices_[o] = static_cast (i); + o++; + } else + { + for (size_t k = 0; k < nn_distances.size (); k++) + { + std::pair pair = std::make_pair (i, nn_distances[k]); //i is a index to a model point and then distance + it = model_explains_scene_points.find (nn_indices[k]); + if (it == model_explains_scene_points.end ()) + { + boost::shared_ptr < std::vector > > vec (new std::vector > ()); + vec->push_back (pair); + model_explains_scene_points[nn_indices[k]] = vec; + } else + { + it->second->push_back (pair); + } + } + } + } + + outliers_weight.resize (o); + recog_model->outlier_indices_.resize (o); + + recog_model->outliers_weight_ = (std::accumulate (outliers_weight.begin (), outliers_weight.end (), 0.f) / static_cast (outliers_weight.size ())); + if (outliers_weight.size () == 0) + recog_model->outliers_weight_ = 1.f; + + pcl::IndicesPtr indices_scene (new std::vector); + //go through the map and keep the closest model point in case that several model points explain a scene point + + int p = 0; + + for (it = model_explains_scene_points.begin (); it != model_explains_scene_points.end (); it++, p++) + { + size_t closest = 0; + float min_d = std::numeric_limits::min (); + for (size_t i = 0; i < it->second->size (); i++) + { + if (it->second->at (i).second > min_d) + { + min_d = it->second->at (i).second; + closest = i; + } + } + + float d = it->second->at (closest).second; + float d_weight = -(d * d / (inliers_threshold_)) + 1; + + //it->first is index to scene point + //using normals to weight inliers + Eigen::Vector3f scene_p_normal = scene_normals_->points[it->first].getNormalVector3fMap (); + Eigen::Vector3f model_p_normal = recog_model->normals_->points[it->second->at (closest).first].getNormalVector3fMap (); + float dotp = scene_p_normal.dot (model_p_normal) * 1.f; //[-1,1] from antiparallel trough perpendicular to parallel + + if (dotp < 0.f) + dotp = 0.f; + + explained_indices.push_back (it->first); + explained_indices_distances.push_back (d_weight * dotp); + + } + + recog_model->bad_information_ = static_cast (recog_model->outlier_indices_.size ()); + recog_model->explained_ = explained_indices; + recog_model->explained_distances_ = explained_indices_distances; + + return true; +} + +template +void pcl::GlobalHypothesesVerification::computeClutterCue(boost::shared_ptr & recog_model) +{ + if (detect_clutter_) + { + + float rn_sqr = radius_neighborhood_GO_ * radius_neighborhood_GO_; + std::vector nn_indices; + std::vector nn_distances; + + std::vector < std::pair > neighborhood_indices; //first is indices to scene point and second is indices to explained_ scene points + for (int i = 0; i < static_cast (recog_model->explained_.size ()); i++) + { + if (scene_downsampled_tree_->radiusSearch (scene_cloud_downsampled_->points[recog_model->explained_[i]], radius_neighborhood_GO_, nn_indices, + nn_distances, std::numeric_limits::max ())) + { + for (size_t k = 0; k < nn_distances.size (); k++) + { + if (nn_indices[k] != i) + neighborhood_indices.push_back (std::make_pair (nn_indices[k], i)); + } + } + } + + //sort neighborhood indices by id + std::sort (neighborhood_indices.begin (), neighborhood_indices.end (), + boost::bind (&std::pair::first, _1) < boost::bind (&std::pair::first, _2)); + + //erase duplicated unexplained points + neighborhood_indices.erase ( + std::unique (neighborhood_indices.begin (), neighborhood_indices.end (), + boost::bind (&std::pair::first, _1) == boost::bind (&std::pair::first, _2)), neighborhood_indices.end ()); + + //sort explained points + std::vector exp_idces (recog_model->explained_); + std::sort (exp_idces.begin (), exp_idces.end ()); + + recog_model->unexplained_in_neighborhood.resize (neighborhood_indices.size ()); + recog_model->unexplained_in_neighborhood_weights.resize (neighborhood_indices.size ()); + + size_t p = 0; + size_t j = 0; + for (size_t i = 0; i < neighborhood_indices.size (); i++) + { + if ((j < exp_idces.size ()) && (neighborhood_indices[i].first == exp_idces[j])) + { + //this index is explained by the hypothesis so ignore it, advance j + j++; + } else + { + //indices_in_nb[i] < exp_idces[j] + //recog_model->unexplained_in_neighborhood.push_back(neighborhood_indices[i]); + recog_model->unexplained_in_neighborhood[p] = neighborhood_indices[i].first; + + if (clusters_cloud_->points[recog_model->explained_[neighborhood_indices[i].second]].intensity != 0.f + && (clusters_cloud_->points[recog_model->explained_[neighborhood_indices[i].second]].intensity + == clusters_cloud_->points[neighborhood_indices[i].first].intensity)) + { + + recog_model->unexplained_in_neighborhood_weights[p] = clutter_regularizer_; + + } else + { + //neighborhood_indices[i].first gives the index to the scene point and second to the explained scene point by the model causing this... + //calculate weight of this clutter point based on the distance of the scene point and the model point causing it + float d = static_cast (pow ( + (scene_cloud_downsampled_->points[recog_model->explained_[neighborhood_indices[i].second]].getVector3fMap () + - scene_cloud_downsampled_->points[neighborhood_indices[i].first].getVector3fMap ()).norm (), 2)); + float d_weight = -(d / rn_sqr) + 1; //points that are close have a strong weight*/ + + //using normals to weight clutter points + Eigen::Vector3f scene_p_normal = scene_normals_->points[neighborhood_indices[i].first].getNormalVector3fMap (); + Eigen::Vector3f model_p_normal = scene_normals_->points[recog_model->explained_[neighborhood_indices[i].second]].getNormalVector3fMap (); + float dotp = scene_p_normal.dot (model_p_normal); //[-1,1] from antiparallel trough perpendicular to parallel + + if (dotp < 0) + dotp = 0.f; + + recog_model->unexplained_in_neighborhood_weights[p] = d_weight * dotp; + } + p++; + } + } + + recog_model->unexplained_in_neighborhood_weights.resize (p); + recog_model->unexplained_in_neighborhood.resize (p); + } +} + +#define PCL_INSTANTIATE_GoHV(T1,T2) template class PCL_EXPORTS pcl::GlobalHypothesesVerification; + +#endif /* PCL_RECOGNITION_IMPL_HV_GO_HPP_ */ + diff --git a/pcl-1.7/pcl/recognition/impl/hv/hv_papazov.hpp b/pcl-1.7/pcl/recognition/impl/hv/hv_papazov.hpp new file mode 100644 index 0000000..8e104bf --- /dev/null +++ b/pcl-1.7/pcl/recognition/impl/hv/hv_papazov.hpp @@ -0,0 +1,233 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#pragma once +#include + +/////////////////////////////////////////////////////////////////////////////////////////////////// +template + void + pcl::PapazovHV::initialize () + { + + //clear stuff + recognition_models_.clear (); + graph_id_model_map_.clear (); + conflict_graph_.clear (); + explained_by_RM_.clear (); + points_explained_by_rm_.clear (); + + // initialize mask... + mask_.resize (complete_models_.size ()); + for (size_t i = 0; i < complete_models_.size (); i++) + mask_[i] = true; + + // initialize explained_by_RM + explained_by_RM_.resize (scene_cloud_downsampled_->points.size ()); + points_explained_by_rm_.resize (scene_cloud_downsampled_->points.size ()); + + // initalize model + for (size_t m = 0; m < complete_models_.size (); m++) + { + boost::shared_ptr < RecognitionModel > recog_model (new RecognitionModel); + // voxelize model cloud + recog_model->cloud_.reset (new pcl::PointCloud); + recog_model->complete_cloud_.reset (new pcl::PointCloud); + recog_model->id_ = static_cast (m); + + pcl::VoxelGrid voxel_grid; + voxel_grid.setInputCloud (visible_models_[m]); + voxel_grid.setLeafSize (resolution_, resolution_, resolution_); + voxel_grid.filter (*(recog_model->cloud_)); + + pcl::VoxelGrid voxel_grid_complete; + voxel_grid_complete.setInputCloud (complete_models_[m]); + voxel_grid_complete.setLeafSize (resolution_, resolution_, resolution_); + voxel_grid_complete.filter (*(recog_model->complete_cloud_)); + + std::vector explained_indices; + std::vector outliers; + std::vector nn_indices; + std::vector nn_distances; + + for (size_t i = 0; i < recog_model->cloud_->points.size (); i++) + { + if (!scene_downsampled_tree_->radiusSearch (recog_model->cloud_->points[i], inliers_threshold_, nn_indices, nn_distances, + std::numeric_limits::max ())) + { + outliers.push_back (static_cast (i)); + } + else + { + for (size_t k = 0; k < nn_distances.size (); k++) + { + explained_indices.push_back (nn_indices[k]); //nn_indices[k] points to the scene + } + } + } + + std::sort (explained_indices.begin (), explained_indices.end ()); + explained_indices.erase (std::unique (explained_indices.begin (), explained_indices.end ()), explained_indices.end ()); + + recog_model->bad_information_ = static_cast (outliers.size ()); + + if ((static_cast (recog_model->bad_information_) / static_cast (recog_model->complete_cloud_->points.size ())) + <= penalty_threshold_ && (static_cast (explained_indices.size ()) + / static_cast (recog_model->complete_cloud_->points.size ())) >= support_threshold_) + { + recog_model->explained_ = explained_indices; + recognition_models_.push_back (recog_model); + + // update explained_by_RM_, add 1 + for (size_t i = 0; i < explained_indices.size (); i++) + { + explained_by_RM_[explained_indices[i]]++; + points_explained_by_rm_[explained_indices[i]].push_back (recog_model); + } + } + else + { + mask_[m] = false; // the model didnt survive the sequential check... + } + } + } + +/////////////////////////////////////////////////////////////////////////////////////////////////// +template + void + pcl::PapazovHV::nonMaximaSuppresion () + { + // iterate over all vertices of the graph and check if they have a better neighbour, then remove that vertex + typedef typename boost::graph_traits::vertex_iterator VertexIterator; + VertexIterator vi, vi_end, next; + boost::tie (vi, vi_end) = boost::vertices (conflict_graph_); + + for (next = vi; next != vi_end; next++) + { + const typename Graph::vertex_descriptor v = boost::vertex (*next, conflict_graph_); + typename boost::graph_traits::adjacency_iterator ai; + typename boost::graph_traits::adjacency_iterator ai_end; + + boost::shared_ptr < RecognitionModel > current = static_cast > (graph_id_model_map_[int (v)]); + + bool a_better_one = false; + for (boost::tie (ai, ai_end) = boost::adjacent_vertices (v, conflict_graph_); (ai != ai_end) && !a_better_one; ++ai) + { + boost::shared_ptr < RecognitionModel > neighbour = static_cast > (graph_id_model_map_[int (*ai)]); + if ((neighbour->explained_.size () >= current->explained_.size ()) && mask_[neighbour->id_]) + { + a_better_one = true; + } + } + + if (a_better_one) + { + mask_[current->id_] = false; + } + } + } + +/////////////////////////////////////////////////////////////////////////////////////////////////// +template + void + pcl::PapazovHV::buildConflictGraph () + { + // create vertices for the graph + for (size_t i = 0; i < (recognition_models_.size ()); i++) + { + const typename Graph::vertex_descriptor v = boost::add_vertex (recognition_models_[i], conflict_graph_); + graph_id_model_map_[int (v)] = static_cast > (recognition_models_[i]); + } + + // iterate over the remaining models and check for each one if there is a conflict with another one + for (size_t i = 0; i < recognition_models_.size (); i++) + { + for (size_t j = i; j < recognition_models_.size (); j++) + { + if (i != j) + { + float n_conflicts = 0.f; + // count scene points explained by both models + for (size_t k = 0; k < explained_by_RM_.size (); k++) + { + if (explained_by_RM_[k] > 1) + { + // this point could be a conflict + bool i_found = false; + bool j_found = false; + bool both_found = false; + for (size_t kk = 0; (kk < points_explained_by_rm_[k].size ()) && !both_found; kk++) + { + if (points_explained_by_rm_[k][kk]->id_ == recognition_models_[i]->id_) + i_found = true; + + if (points_explained_by_rm_[k][kk]->id_ == recognition_models_[j]->id_) + j_found = true; + + if (i_found && j_found) + both_found = true; + } + + if (both_found) + n_conflicts += 1.f; + } + } + + // check if number of points is big enough to create a conflict + bool add_conflict = false; + add_conflict = ((n_conflicts / static_cast (recognition_models_[i]->complete_cloud_->points.size ())) > conflict_threshold_size_) + || ((n_conflicts / static_cast (recognition_models_[j]->complete_cloud_->points.size ())) > conflict_threshold_size_); + + if (add_conflict) + { + boost::add_edge (i, j, conflict_graph_); + } + } + } + } + } + +/////////////////////////////////////////////////////////////////////////////////////////////////// +template + void + pcl::PapazovHV::verify () + { + initialize (); + buildConflictGraph (); + nonMaximaSuppresion (); + } + +#define PCL_INSTANTIATE_PapazovHV(T1,T2) template class PCL_EXPORTS pcl::PapazovHV; diff --git a/pcl-1.7/pcl/recognition/impl/hv/occlusion_reasoning.hpp b/pcl-1.7/pcl/recognition/impl/hv/occlusion_reasoning.hpp new file mode 100644 index 0000000..d6b1903 --- /dev/null +++ b/pcl-1.7/pcl/recognition/impl/hv/occlusion_reasoning.hpp @@ -0,0 +1,200 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_RECOGNITION_OCCLUSION_REASONING_HPP_ +#define PCL_RECOGNITION_OCCLUSION_REASONING_HPP_ + +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::occlusion_reasoning::ZBuffering::ZBuffering (int resx, int resy, float f) : + f_ (f), cx_ (resx), cy_ (resy), depth_ (NULL) +{ +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::occlusion_reasoning::ZBuffering::ZBuffering () : + f_ (), cx_ (), cy_ (), depth_ (NULL) +{ +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::occlusion_reasoning::ZBuffering::~ZBuffering () +{ + if (depth_ != NULL) + delete[] depth_; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::occlusion_reasoning::ZBuffering::filter (typename pcl::PointCloud::ConstPtr & model, + typename pcl::PointCloud::Ptr & filtered, float thres) +{ + std::vector indices_to_keep; + filter(model, indices_to_keep, thres); + pcl::copyPointCloud (*model, indices_to_keep, *filtered); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::occlusion_reasoning::ZBuffering::filter (typename pcl::PointCloud::ConstPtr & model, + std::vector & indices_to_keep, float thres) +{ + + float cx, cy; + cx = static_cast (cx_) / 2.f - 0.5f; + cy = static_cast (cy_) / 2.f - 0.5f; + + indices_to_keep.resize (model->points.size ()); + int keep = 0; + for (size_t i = 0; i < model->points.size (); i++) + { + float x = model->points[i].x; + float y = model->points[i].y; + float z = model->points[i].z; + int u = static_cast (f_ * x / z + cx); + int v = static_cast (f_ * y / z + cy); + + if (u >= cx_ || v >= cy_ || u < 0 || v < 0) + continue; + + //Check if point depth (distance to camera) is greater than the (u,v) meaning that the point is not visible + if ((z - thres) > depth_[u * cy_ + v] || !pcl_isfinite(depth_[u * cy_ + v])) + continue; + + indices_to_keep[keep] = static_cast (i); + keep++; + } + + indices_to_keep.resize (keep); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::occlusion_reasoning::ZBuffering::computeDepthMap (typename pcl::PointCloud::ConstPtr & scene, bool compute_focal, + bool smooth, int wsize) +{ + float cx, cy; + cx = static_cast (cx_) / 2.f - 0.5f; + cy = static_cast (cy_) / 2.f - 0.5f; + + //compute the focal length + if (compute_focal) + { + + float max_u, max_v, min_u, min_v; + max_u = max_v = std::numeric_limits::max () * -1; + min_u = min_v = std::numeric_limits::max (); + + for (size_t i = 0; i < scene->points.size (); i++) + { + float b_x = scene->points[i].x / scene->points[i].z; + if (b_x > max_u) + max_u = b_x; + if (b_x < min_u) + min_u = b_x; + + float b_y = scene->points[i].y / scene->points[i].z; + if (b_y > max_v) + max_v = b_y; + if (b_y < min_v) + min_v = b_y; + } + + float maxC = std::max (std::max (std::abs (max_u), std::abs (max_v)), std::max (std::abs (min_u), std::abs (min_v))); + f_ = (cx) / maxC; + } + + depth_ = new float[cx_ * cy_]; + for (int i = 0; i < (cx_ * cy_); i++) + depth_[i] = std::numeric_limits::quiet_NaN (); + + for (size_t i = 0; i < scene->points.size (); i++) + { + float x = scene->points[i].x; + float y = scene->points[i].y; + float z = scene->points[i].z; + int u = static_cast (f_ * x / z + cx); + int v = static_cast (f_ * y / z + cy); + + if (u >= cx_ || v >= cy_ || u < 0 || v < 0) + continue; + + if ((z < depth_[u * cy_ + v]) || (!pcl_isfinite(depth_[u * cy_ + v]))) + depth_[u * cx_ + v] = z; + } + + if (smooth) + { + //Dilate and smooth the depth map + int ws = wsize; + int ws2 = int (std::floor (static_cast (ws) / 2.f)); + float * depth_smooth = new float[cx_ * cy_]; + for (int i = 0; i < (cx_ * cy_); i++) + depth_smooth[i] = std::numeric_limits::quiet_NaN (); + + for (int u = ws2; u < (cx_ - ws2); u++) + { + for (int v = ws2; v < (cy_ - ws2); v++) + { + float min = std::numeric_limits::max (); + for (int j = (u - ws2); j <= (u + ws2); j++) + { + for (int i = (v - ws2); i <= (v + ws2); i++) + { + if (pcl_isfinite(depth_[j * cx_ + i]) && (depth_[j * cx_ + i] < min)) + { + min = depth_[j * cx_ + i]; + } + } + } + + if (min < (std::numeric_limits::max () - 0.1)) + { + depth_smooth[u * cx_ + v] = min; + } + } + } + + memcpy (depth_, depth_smooth, sizeof(float) * cx_ * cy_); + delete[] depth_smooth; + } +} + +#endif // PCL_RECOGNITION_OCCLUSION_REASONING_HPP_ diff --git a/pcl-1.7/pcl/recognition/impl/implicit_shape_model.hpp b/pcl-1.7/pcl/recognition/impl/implicit_shape_model.hpp new file mode 100644 index 0000000..efdbf84 --- /dev/null +++ b/pcl-1.7/pcl/recognition/impl/implicit_shape_model.hpp @@ -0,0 +1,1536 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + * Implementation of the ISM algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classication" + * by Jan Knopp, Mukta Prasad, Geert Willems, Radu Timofte, and Luc Van Gool + * + * Authors: Roman Shapovalov, Alexander Velizhev, Sergey Ushakov + */ + +#ifndef PCL_IMPLICIT_SHAPE_MODEL_HPP_ +#define PCL_IMPLICIT_SHAPE_MODEL_HPP_ + +#include "../implicit_shape_model.h" + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::features::ISMVoteList::ISMVoteList () : + votes_ (new pcl::PointCloud ()), + tree_is_valid_ (false), + votes_origins_ (new pcl::PointCloud ()), + votes_class_ (0), + tree_ (), + k_ind_ (0), + k_sqr_dist_ (0) +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::features::ISMVoteList::~ISMVoteList () +{ + votes_class_.clear (); + votes_origins_.reset (); + votes_.reset (); + k_ind_.clear (); + k_sqr_dist_.clear (); + tree_.reset (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::features::ISMVoteList::addVote ( + pcl::InterestPoint& vote, const PointT &vote_origin, int votes_class) +{ + tree_is_valid_ = false; + votes_->points.insert (votes_->points.end (), vote);// TODO: adjust height and width + + votes_origins_->points.push_back (vote_origin); + votes_class_.push_back (votes_class); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::PointCloud::Ptr +pcl::features::ISMVoteList::getColoredCloud (typename pcl::PointCloud::Ptr cloud) +{ + pcl::PointXYZRGB point; + pcl::PointCloud::Ptr colored_cloud = (new pcl::PointCloud)->makeShared (); + colored_cloud->height = 0; + colored_cloud->width = 1; + + if (cloud != 0) + { + colored_cloud->height += static_cast (cloud->points.size ()); + point.r = 255; + point.g = 255; + point.b = 255; + for (size_t i_point = 0; i_point < cloud->points.size (); i_point++) + { + point.x = cloud->points[i_point].x; + point.y = cloud->points[i_point].y; + point.z = cloud->points[i_point].z; + colored_cloud->points.push_back (point); + } + } + + point.r = 0; + point.g = 0; + point.b = 255; + for (size_t i_vote = 0; i_vote < votes_->points.size (); i_vote++) + { + point.x = votes_->points[i_vote].x; + point.y = votes_->points[i_vote].y; + point.z = votes_->points[i_vote].z; + colored_cloud->points.push_back (point); + } + colored_cloud->height += static_cast (votes_->points.size ()); + + return (colored_cloud); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::features::ISMVoteList::findStrongestPeaks ( + std::vector > &out_peaks, + int in_class_id, + double in_non_maxima_radius, + double in_sigma) +{ + validateTree (); + + const size_t n_vote_classes = votes_class_.size (); + if (n_vote_classes == 0) + return; + for (size_t i = 0; i < n_vote_classes ; i++) + assert ( votes_class_[i] == in_class_id ); + + // heuristic: start from NUM_INIT_PTS different locations selected uniformly + // on the votes. Intuitively, it is likely to get a good location in dense regions. + const int NUM_INIT_PTS = 100; + double SIGMA_DIST = in_sigma;// rule of thumb: 10% of the object radius + const double FINAL_EPS = SIGMA_DIST / 100;// another heuristic + + std::vector peaks (NUM_INIT_PTS); + std::vector peak_densities (NUM_INIT_PTS); + double max_density = -1.0; + for (int i = 0; i < NUM_INIT_PTS; i++) + { + Eigen::Vector3f old_center; + Eigen::Vector3f curr_center; + curr_center (0) = votes_->points[votes_->points.size () * i / NUM_INIT_PTS].x; + curr_center (1) = votes_->points[votes_->points.size () * i / NUM_INIT_PTS].y; + curr_center (2) = votes_->points[votes_->points.size () * i / NUM_INIT_PTS].z; + + do + { + old_center = curr_center; + curr_center = shiftMean (old_center, SIGMA_DIST); + } while ((old_center - curr_center).norm () > FINAL_EPS); + + pcl::PointXYZ point; + point.x = curr_center (0); + point.y = curr_center (1); + point.z = curr_center (2); + double curr_density = getDensityAtPoint (point, SIGMA_DIST); + assert (curr_density >= 0.0); + + peaks[i] = curr_center; + peak_densities[i] = curr_density; + + if ( max_density < curr_density ) + max_density = curr_density; + } + + //extract peaks + std::vector peak_flag (NUM_INIT_PTS, true); + for (int i_peak = 0; i_peak < NUM_INIT_PTS; i_peak++) + { + // find best peak with taking into consideration peak flags + double best_density = -1.0; + Eigen::Vector3f strongest_peak; + int best_peak_ind (-1); + int peak_counter (0); + for (int i = 0; i < NUM_INIT_PTS; i++) + { + if ( !peak_flag[i] ) + continue; + + if ( peak_densities[i] > best_density) + { + best_density = peak_densities[i]; + strongest_peak = peaks[i]; + best_peak_ind = i; + } + ++peak_counter; + } + + if( peak_counter == 0 ) + break;// no peaks + + pcl::ISMPeak peak; + peak.x = strongest_peak(0); + peak.y = strongest_peak(1); + peak.z = strongest_peak(2); + peak.density = best_density; + peak.class_id = in_class_id; + out_peaks.push_back ( peak ); + + // mark best peaks and all its neighbors + peak_flag[best_peak_ind] = false; + for (int i = 0; i < NUM_INIT_PTS; i++) + { + // compute distance between best peak and all unmarked peaks + if ( !peak_flag[i] ) + continue; + + double dist = (strongest_peak - peaks[i]).norm (); + if ( dist < in_non_maxima_radius ) + peak_flag[i] = false; + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::features::ISMVoteList::validateTree () +{ + if (!tree_is_valid_) + { + if (tree_ == 0) + tree_ = boost::shared_ptr > (new pcl::KdTreeFLANN ()); + tree_->setInputCloud (votes_); + k_ind_.resize ( votes_->points.size (), -1 ); + k_sqr_dist_.resize ( votes_->points.size (), 0.0f ); + tree_is_valid_ = true; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template Eigen::Vector3f +pcl::features::ISMVoteList::shiftMean (const Eigen::Vector3f& snap_pt, const double in_sigma_dist) +{ + validateTree (); + + Eigen::Vector3f wgh_sum (0.0, 0.0, 0.0); + double denom = 0.0; + + pcl::InterestPoint pt; + pt.x = snap_pt[0]; + pt.y = snap_pt[1]; + pt.z = snap_pt[2]; + size_t n_pts = tree_->radiusSearch (pt, 3*in_sigma_dist, k_ind_, k_sqr_dist_); + + for (size_t j = 0; j < n_pts; j++) + { + double kernel = votes_->points[k_ind_[j]].strength * exp (-k_sqr_dist_[j] / (in_sigma_dist * in_sigma_dist)); + Eigen::Vector3f vote_vec (votes_->points[k_ind_[j]].x, votes_->points[k_ind_[j]].y, votes_->points[k_ind_[j]].z); + wgh_sum += vote_vec * static_cast (kernel); + denom += kernel; + } + assert (denom > 0.0); // at least one point is close. In fact, this case should be handled too + + return (wgh_sum / static_cast (denom)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::features::ISMVoteList::getDensityAtPoint ( + const PointT &point, double sigma_dist) +{ + validateTree (); + + const size_t n_vote_classes = votes_class_.size (); + if (n_vote_classes == 0) + return (0.0); + + double sum_vote = 0.0; + + pcl::InterestPoint pt; + pt.x = point.x; + pt.y = point.y; + pt.z = point.z; + size_t num_of_pts = tree_->radiusSearch (pt, 3 * sigma_dist, k_ind_, k_sqr_dist_); + + for (size_t j = 0; j < num_of_pts; j++) + sum_vote += votes_->points[k_ind_[j]].strength * exp (-k_sqr_dist_[j] / (sigma_dist * sigma_dist)); + + return (sum_vote); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template unsigned int +pcl::features::ISMVoteList::getNumberOfVotes () +{ + return (static_cast (votes_->points.size ())); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +pcl::features::ISMModel::ISMModel () : + statistical_weights_ (0), + learned_weights_ (0), + classes_ (0), + sigmas_ (0), + directions_to_center_ (), + clusters_centers_ (), + clusters_ (0), + number_of_classes_ (0), + number_of_visual_words_ (0), + number_of_clusters_ (0), + descriptors_dimension_ (0) +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +pcl::features::ISMModel::ISMModel (ISMModel const & copy) +{ + reset (); + + this->number_of_classes_ = copy.number_of_classes_; + this->number_of_visual_words_ = copy.number_of_visual_words_; + this->number_of_clusters_ = copy.number_of_clusters_; + this->descriptors_dimension_ = copy.descriptors_dimension_; + + std::vector vec; + vec.resize (this->number_of_clusters_, 0.0f); + this->statistical_weights_.resize (this->number_of_classes_, vec); + for (unsigned int i_class = 0; i_class < this->number_of_classes_; i_class++) + for (unsigned int i_cluster = 0; i_cluster < this->number_of_clusters_; i_cluster++) + this->statistical_weights_[i_class][i_cluster] = copy.statistical_weights_[i_class][i_cluster]; + + this->learned_weights_.resize (this->number_of_visual_words_, 0.0f); + for (unsigned int i_visual_word = 0; i_visual_word < this->number_of_visual_words_; i_visual_word++) + this->learned_weights_[i_visual_word] = copy.learned_weights_[i_visual_word]; + + this->classes_.resize (this->number_of_visual_words_, 0); + for (unsigned int i_visual_word = 0; i_visual_word < this->number_of_visual_words_; i_visual_word++) + this->classes_[i_visual_word] = copy.classes_[i_visual_word]; + + this->sigmas_.resize (this->number_of_classes_, 0.0f); + for (unsigned int i_class = 0; i_class < this->number_of_classes_; i_class++) + this->sigmas_[i_class] = copy.sigmas_[i_class]; + + this->directions_to_center_.resize (this->number_of_visual_words_, 3); + for (unsigned int i_visual_word = 0; i_visual_word < this->number_of_visual_words_; i_visual_word++) + for (unsigned int i_dim = 0; i_dim < 3; i_dim++) + this->directions_to_center_ (i_visual_word, i_dim) = copy.directions_to_center_ (i_visual_word, i_dim); + + this->clusters_centers_.resize (this->number_of_clusters_, 3); + for (unsigned int i_cluster = 0; i_cluster < this->number_of_clusters_; i_cluster++) + for (unsigned int i_dim = 0; i_dim < this->descriptors_dimension_; i_dim++) + this->clusters_centers_ (i_cluster, i_dim) = copy.clusters_centers_ (i_cluster, i_dim); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +pcl::features::ISMModel::~ISMModel () +{ + reset (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +bool +pcl::features::ISMModel::saveModelToFile (std::string& file_name) +{ + std::ofstream output_file (file_name.c_str (), std::ios::trunc); + if (!output_file) + { + output_file.close (); + return (false); + } + + output_file << number_of_classes_ << " "; + output_file << number_of_visual_words_ << " "; + output_file << number_of_clusters_ << " "; + output_file << descriptors_dimension_ << " "; + + //write statistical weights + for (unsigned int i_class = 0; i_class < number_of_classes_; i_class++) + for (unsigned int i_cluster = 0; i_cluster < number_of_clusters_; i_cluster++) + output_file << statistical_weights_[i_class][i_cluster] << " "; + + //write learned weights + for (unsigned int i_visual_word = 0; i_visual_word < number_of_visual_words_; i_visual_word++) + output_file << learned_weights_[i_visual_word] << " "; + + //write classes + for (unsigned int i_visual_word = 0; i_visual_word < number_of_visual_words_; i_visual_word++) + output_file << classes_[i_visual_word] << " "; + + //write sigmas + for (unsigned int i_class = 0; i_class < number_of_classes_; i_class++) + output_file << sigmas_[i_class] << " "; + + //write directions to centers + for (unsigned int i_visual_word = 0; i_visual_word < number_of_visual_words_; i_visual_word++) + for (unsigned int i_dim = 0; i_dim < 3; i_dim++) + output_file << directions_to_center_ (i_visual_word, i_dim) << " "; + + //write clusters centers + for (unsigned int i_cluster = 0; i_cluster < number_of_clusters_; i_cluster++) + for (unsigned int i_dim = 0; i_dim < descriptors_dimension_; i_dim++) + output_file << clusters_centers_ (i_cluster, i_dim) << " "; + + //write clusters + for (unsigned int i_cluster = 0; i_cluster < number_of_clusters_; i_cluster++) + { + output_file << static_cast (clusters_[i_cluster].size ()) << " "; + for (unsigned int i_visual_word = 0; i_visual_word < static_cast (clusters_[i_cluster].size ()); i_visual_word++) + output_file << clusters_[i_cluster][i_visual_word] << " "; + } + + output_file.close (); + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +bool +pcl::features::ISMModel::loadModelFromfile (std::string& file_name) +{ + reset (); + std::ifstream input_file (file_name.c_str ()); + if (!input_file) + { + input_file.close (); + return (false); + } + + char line[256]; + + input_file.getline (line, 256, ' '); + number_of_classes_ = static_cast (strtol (line, 0, 10)); + input_file.getline (line, 256, ' '); number_of_visual_words_ = atoi (line); + input_file.getline (line, 256, ' '); number_of_clusters_ = atoi (line); + input_file.getline (line, 256, ' '); descriptors_dimension_ = atoi (line); + + //read statistical weights + std::vector vec; + vec.resize (number_of_clusters_, 0.0f); + statistical_weights_.resize (number_of_classes_, vec); + for (unsigned int i_class = 0; i_class < number_of_classes_; i_class++) + for (unsigned int i_cluster = 0; i_cluster < number_of_clusters_; i_cluster++) + input_file >> statistical_weights_[i_class][i_cluster]; + + //read learned weights + learned_weights_.resize (number_of_visual_words_, 0.0f); + for (unsigned int i_visual_word = 0; i_visual_word < number_of_visual_words_; i_visual_word++) + input_file >> learned_weights_[i_visual_word]; + + //read classes + classes_.resize (number_of_visual_words_, 0); + for (unsigned int i_visual_word = 0; i_visual_word < number_of_visual_words_; i_visual_word++) + input_file >> classes_[i_visual_word]; + + //read sigmas + sigmas_.resize (number_of_classes_, 0.0f); + for (unsigned int i_class = 0; i_class < number_of_classes_; i_class++) + input_file >> sigmas_[i_class]; + + //read directions to centers + directions_to_center_.resize (number_of_visual_words_, 3); + for (unsigned int i_visual_word = 0; i_visual_word < number_of_visual_words_; i_visual_word++) + for (unsigned int i_dim = 0; i_dim < 3; i_dim++) + input_file >> directions_to_center_ (i_visual_word, i_dim); + + //read clusters centers + clusters_centers_.resize (number_of_clusters_, descriptors_dimension_); + for (unsigned int i_cluster = 0; i_cluster < number_of_clusters_; i_cluster++) + for (unsigned int i_dim = 0; i_dim < descriptors_dimension_; i_dim++) + input_file >> clusters_centers_ (i_cluster, i_dim); + + //read clusters + std::vector vect; + clusters_.resize (number_of_clusters_, vect); + for (unsigned int i_cluster = 0; i_cluster < number_of_clusters_; i_cluster++) + { + unsigned int size_of_current_cluster = 0; + input_file >> size_of_current_cluster; + clusters_[i_cluster].resize (size_of_current_cluster, 0); + for (unsigned int i_visual_word = 0; i_visual_word < size_of_current_cluster; i_visual_word++) + input_file >> clusters_[i_cluster][i_visual_word]; + } + + input_file.close (); + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +void +pcl::features::ISMModel::reset () +{ + statistical_weights_.clear (); + learned_weights_.clear (); + classes_.clear (); + sigmas_.clear (); + directions_to_center_.resize (0, 0); + clusters_centers_.resize (0, 0); + clusters_.clear (); + number_of_classes_ = 0; + number_of_visual_words_ = 0; + number_of_clusters_ = 0; + descriptors_dimension_ = 0; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +pcl::features::ISMModel& +pcl::features::ISMModel::operator = (const pcl::features::ISMModel& other) +{ + if (this != &other) + { + this->reset (); + + this->number_of_classes_ = other.number_of_classes_; + this->number_of_visual_words_ = other.number_of_visual_words_; + this->number_of_clusters_ = other.number_of_clusters_; + this->descriptors_dimension_ = other.descriptors_dimension_; + + std::vector vec; + vec.resize (number_of_clusters_, 0.0f); + this->statistical_weights_.resize (this->number_of_classes_, vec); + for (unsigned int i_class = 0; i_class < this->number_of_classes_; i_class++) + for (unsigned int i_cluster = 0; i_cluster < this->number_of_clusters_; i_cluster++) + this->statistical_weights_[i_class][i_cluster] = other.statistical_weights_[i_class][i_cluster]; + + this->learned_weights_.resize (this->number_of_visual_words_, 0.0f); + for (unsigned int i_visual_word = 0; i_visual_word < this->number_of_visual_words_; i_visual_word++) + this->learned_weights_[i_visual_word] = other.learned_weights_[i_visual_word]; + + this->classes_.resize (this->number_of_visual_words_, 0); + for (unsigned int i_visual_word = 0; i_visual_word < this->number_of_visual_words_; i_visual_word++) + this->classes_[i_visual_word] = other.classes_[i_visual_word]; + + this->sigmas_.resize (this->number_of_classes_, 0.0f); + for (unsigned int i_class = 0; i_class < this->number_of_classes_; i_class++) + this->sigmas_[i_class] = other.sigmas_[i_class]; + + this->directions_to_center_.resize (this->number_of_visual_words_, 3); + for (unsigned int i_visual_word = 0; i_visual_word < this->number_of_visual_words_; i_visual_word++) + for (unsigned int i_dim = 0; i_dim < 3; i_dim++) + this->directions_to_center_ (i_visual_word, i_dim) = other.directions_to_center_ (i_visual_word, i_dim); + + this->clusters_centers_.resize (this->number_of_clusters_, 3); + for (unsigned int i_cluster = 0; i_cluster < this->number_of_clusters_; i_cluster++) + for (unsigned int i_dim = 0; i_dim < this->descriptors_dimension_; i_dim++) + this->clusters_centers_ (i_cluster, i_dim) = other.clusters_centers_ (i_cluster, i_dim); + } + return (*this); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::ism::ImplicitShapeModelEstimation::ImplicitShapeModelEstimation () : + training_clouds_ (0), + training_classes_ (0), + training_normals_ (0), + training_sigmas_ (0), + sampling_size_ (0.1f), + feature_estimator_ (), + number_of_clusters_ (184), + n_vot_ON_ (true) +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::ism::ImplicitShapeModelEstimation::~ImplicitShapeModelEstimation () +{ + training_clouds_.clear (); + training_classes_.clear (); + training_normals_.clear (); + training_sigmas_.clear (); + feature_estimator_.reset (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template std::vector::Ptr> +pcl::ism::ImplicitShapeModelEstimation::getTrainingClouds () +{ + return (training_clouds_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::setTrainingClouds ( + const std::vector< typename pcl::PointCloud::Ptr >& training_clouds) +{ + training_clouds_.clear (); + std::vector::Ptr > clouds ( training_clouds.begin (), training_clouds.end () ); + training_clouds_.swap (clouds); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template std::vector +pcl::ism::ImplicitShapeModelEstimation::getTrainingClasses () +{ + return (training_classes_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::setTrainingClasses (const std::vector& training_classes) +{ + training_classes_.clear (); + std::vector classes ( training_classes.begin (), training_classes.end () ); + training_classes_.swap (classes); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template std::vector::Ptr> +pcl::ism::ImplicitShapeModelEstimation::getTrainingNormals () +{ + return (training_normals_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::setTrainingNormals ( + const std::vector< typename pcl::PointCloud::Ptr >& training_normals) +{ + training_normals_.clear (); + std::vector::Ptr > normals ( training_normals.begin (), training_normals.end () ); + training_normals_.swap (normals); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::ism::ImplicitShapeModelEstimation::getSamplingSize () +{ + return (sampling_size_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::setSamplingSize (float sampling_size) +{ + if (sampling_size >= std::numeric_limits::epsilon ()) + sampling_size_ = sampling_size; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template boost::shared_ptr > > +pcl::ism::ImplicitShapeModelEstimation::getFeatureEstimator () +{ + return (feature_estimator_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::setFeatureEstimator ( + boost::shared_ptr > > feature) +{ + feature_estimator_ = feature; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template unsigned int +pcl::ism::ImplicitShapeModelEstimation::getNumberOfClusters () +{ + return (number_of_clusters_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::setNumberOfClusters (unsigned int num_of_clusters) +{ + if (num_of_clusters > 0) + number_of_clusters_ = num_of_clusters; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template std::vector +pcl::ism::ImplicitShapeModelEstimation::getSigmaDists () +{ + return (training_sigmas_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::setSigmaDists (const std::vector& training_sigmas) +{ + training_sigmas_.clear (); + std::vector sigmas ( training_sigmas.begin (), training_sigmas.end () ); + training_sigmas_.swap (sigmas); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::ism::ImplicitShapeModelEstimation::getNVotState () +{ + return (n_vot_ON_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::setNVotState (bool state) +{ + n_vot_ON_ = state; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::ism::ImplicitShapeModelEstimation::trainISM (ISMModelPtr& trained_model) +{ + bool success = true; + + if (trained_model == 0) + return (false); + trained_model->reset (); + + std::vector > histograms; + std::vector > locations; + success = extractDescriptors (histograms, locations); + if (!success) + return (false); + + Eigen::MatrixXi labels; + success = clusterDescriptors(histograms, labels, trained_model->clusters_centers_); + if (!success) + return (false); + + std::vector vec; + trained_model->clusters_.resize (number_of_clusters_, vec); + for (size_t i_label = 0; i_label < locations.size (); i_label++) + trained_model->clusters_[labels (i_label)].push_back (i_label); + + calculateSigmas (trained_model->sigmas_); + + calculateWeights( + locations, + labels, + trained_model->sigmas_, + trained_model->clusters_, + trained_model->statistical_weights_, + trained_model->learned_weights_); + + trained_model->number_of_classes_ = *std::max_element (training_classes_.begin (), training_classes_.end () ) + 1; + trained_model->number_of_visual_words_ = static_cast (histograms.size ()); + trained_model->number_of_clusters_ = number_of_clusters_; + trained_model->descriptors_dimension_ = FeatureSize; + + trained_model->directions_to_center_.resize (locations.size (), 3); + trained_model->classes_.resize (locations.size ()); + for (size_t i_dir = 0; i_dir < locations.size (); i_dir++) + { + trained_model->directions_to_center_(i_dir, 0) = locations[i_dir].dir_to_center_.x; + trained_model->directions_to_center_(i_dir, 1) = locations[i_dir].dir_to_center_.y; + trained_model->directions_to_center_(i_dir, 2) = locations[i_dir].dir_to_center_.z; + trained_model->classes_[i_dir] = training_classes_[locations[i_dir].model_num_]; + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template boost::shared_ptr > +pcl::ism::ImplicitShapeModelEstimation::findObjects ( + ISMModelPtr model, + typename pcl::PointCloud::Ptr in_cloud, + typename pcl::PointCloud::Ptr in_normals, + int in_class_of_interest) +{ + boost::shared_ptr > out_votes (new pcl::features::ISMVoteList ()); + + if (in_cloud->points.size () == 0) + return (out_votes); + + typename pcl::PointCloud::Ptr sampled_point_cloud (new pcl::PointCloud ()); + typename pcl::PointCloud::Ptr sampled_normal_cloud (new pcl::PointCloud ()); + simplifyCloud (in_cloud, in_normals, sampled_point_cloud, sampled_normal_cloud); + if (sampled_point_cloud->points.size () == 0) + return (out_votes); + + typename pcl::PointCloud >::Ptr feature_cloud (new pcl::PointCloud > ()); + estimateFeatures (sampled_point_cloud, sampled_normal_cloud, feature_cloud); + + //find nearest cluster + const unsigned int n_key_points = static_cast (sampled_point_cloud->size ()); + std::vector min_dist_inds (n_key_points, -1); + for (unsigned int i_point = 0; i_point < n_key_points; i_point++) + { + Eigen::VectorXf curr_descriptor (FeatureSize); + for (int i_dim = 0; i_dim < FeatureSize; i_dim++) + curr_descriptor (i_dim) = feature_cloud->points[i_point].histogram[i_dim]; + + float descriptor_sum = curr_descriptor.sum (); + if (descriptor_sum < std::numeric_limits::epsilon ()) + continue; + + unsigned int min_dist_idx = 0; + Eigen::VectorXf clusters_center (FeatureSize); + for (int i_dim = 0; i_dim < FeatureSize; i_dim++) + clusters_center (i_dim) = model->clusters_centers_ (min_dist_idx, i_dim); + + float best_dist = computeDistance (curr_descriptor, clusters_center); + for (unsigned int i_clust_cent = 0; i_clust_cent < number_of_clusters_; i_clust_cent++) + { + for (int i_dim = 0; i_dim < FeatureSize; i_dim++) + clusters_center (i_dim) = model->clusters_centers_ (i_clust_cent, i_dim); + float curr_dist = computeDistance (clusters_center, curr_descriptor); + if (curr_dist < best_dist) + { + min_dist_idx = i_clust_cent; + best_dist = curr_dist; + } + } + min_dist_inds[i_point] = min_dist_idx; + }//next keypoint + + for (size_t i_point = 0; i_point < n_key_points; i_point++) + { + int min_dist_idx = min_dist_inds[i_point]; + if (min_dist_idx == -1) + continue; + + const unsigned int n_words = static_cast (model->clusters_[min_dist_idx].size ()); + //compute coord system transform + Eigen::Matrix3f transform = alignYCoordWithNormal (sampled_normal_cloud->points[i_point]); + for (unsigned int i_word = 0; i_word < n_words; i_word++) + { + unsigned int index = model->clusters_[min_dist_idx][i_word]; + unsigned int i_class = model->classes_[index]; + if (static_cast (i_class) != in_class_of_interest) + continue;//skip this class + + //rotate dir to center as needed + Eigen::Vector3f direction ( + model->directions_to_center_(index, 0), + model->directions_to_center_(index, 1), + model->directions_to_center_(index, 2)); + applyTransform (direction, transform.transpose ()); + + pcl::InterestPoint vote; + Eigen::Vector3f vote_pos = sampled_point_cloud->points[i_point].getVector3fMap () + direction; + vote.x = vote_pos[0]; + vote.y = vote_pos[1]; + vote.z = vote_pos[2]; + float statistical_weight = model->statistical_weights_[in_class_of_interest][min_dist_idx]; + float learned_weight = model->learned_weights_[index]; + float power = statistical_weight * learned_weight; + vote.strength = power; + if (vote.strength > std::numeric_limits::epsilon ()) + out_votes->addVote (vote, sampled_point_cloud->points[i_point], i_class); + } + }//next point + + return (out_votes); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::ism::ImplicitShapeModelEstimation::extractDescriptors ( + std::vector< pcl::Histogram >& histograms, + std::vector< LocationInfo, Eigen::aligned_allocator >& locations) +{ + histograms.clear (); + locations.clear (); + + int n_key_points = 0; + + if (training_clouds_.size () == 0 || training_classes_.size () == 0 || feature_estimator_ == 0) + return (false); + + for (size_t i_cloud = 0; i_cloud < training_clouds_.size (); i_cloud++) + { + //compute the center of the training object + Eigen::Vector3f models_center (0.0f, 0.0f, 0.0f); + const size_t num_of_points = training_clouds_[i_cloud]->points.size (); + typename pcl::PointCloud::iterator point_j; + for (point_j = training_clouds_[i_cloud]->begin (); point_j != training_clouds_[i_cloud]->end (); point_j++) + models_center += point_j->getVector3fMap (); + models_center /= static_cast (num_of_points); + + //downsample the cloud + typename pcl::PointCloud::Ptr sampled_point_cloud (new pcl::PointCloud ()); + typename pcl::PointCloud::Ptr sampled_normal_cloud (new pcl::PointCloud ()); + simplifyCloud (training_clouds_[i_cloud], training_normals_[i_cloud], sampled_point_cloud, sampled_normal_cloud); + if (sampled_point_cloud->points.size () == 0) + continue; + + shiftCloud (training_clouds_[i_cloud], models_center); + shiftCloud (sampled_point_cloud, models_center); + + n_key_points += static_cast (sampled_point_cloud->size ()); + + typename pcl::PointCloud >::Ptr feature_cloud (new pcl::PointCloud > ()); + estimateFeatures (sampled_point_cloud, sampled_normal_cloud, feature_cloud); + + int point_index = 0; + typename pcl::PointCloud::iterator point_i; + for (point_i = sampled_point_cloud->points.begin (); point_i != sampled_point_cloud->points.end (); point_i++, point_index++) + { + float descriptor_sum = Eigen::VectorXf::Map (feature_cloud->points[point_index].histogram, FeatureSize).sum (); + if (descriptor_sum < std::numeric_limits::epsilon ()) + continue; + + histograms.insert ( histograms.end (), feature_cloud->begin () + point_index, feature_cloud->begin () + point_index + 1 ); + + int dist = static_cast (std::distance (sampled_point_cloud->points.begin (), point_i)); + Eigen::Matrix3f new_basis = alignYCoordWithNormal (sampled_normal_cloud->points[dist]); + Eigen::Vector3f zero; + zero (0) = 0.0; + zero (1) = 0.0; + zero (2) = 0.0; + Eigen::Vector3f new_dir = zero - point_i->getVector3fMap (); + applyTransform (new_dir, new_basis); + + PointT point (new_dir[0], new_dir[1], new_dir[2]); + LocationInfo info (static_cast (i_cloud), point, *point_i, sampled_normal_cloud->points[dist]); + locations.insert(locations.end (), info); + } + }//next training cloud + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::ism::ImplicitShapeModelEstimation::clusterDescriptors ( + std::vector< pcl::Histogram >& histograms, + Eigen::MatrixXi& labels, + Eigen::MatrixXf& clusters_centers) +{ + Eigen::MatrixXf points_to_cluster (histograms.size (), FeatureSize); + + for (unsigned int i_feature = 0; i_feature < histograms.size (); i_feature++) + for (int i_dim = 0; i_dim < FeatureSize; i_dim++) + points_to_cluster (i_feature, i_dim) = histograms[i_feature].histogram[i_dim]; + + labels.resize (histograms.size(), 1); + computeKMeansClustering ( + points_to_cluster, + number_of_clusters_, + labels, + TermCriteria(TermCriteria::EPS|TermCriteria::COUNT, 10, 0.01f),//1000 + 5, + PP_CENTERS, + clusters_centers); + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::calculateSigmas (std::vector& sigmas) +{ + if (training_sigmas_.size () != 0) + { + sigmas.resize (training_sigmas_.size (), 0.0f); + for (unsigned int i_sigma = 0; i_sigma < training_sigmas_.size (); i_sigma++) + sigmas[i_sigma] = training_sigmas_[i_sigma]; + return; + } + + sigmas.clear (); + unsigned int number_of_classes = *std::max_element (training_classes_.begin (), training_classes_.end () ) + 1; + sigmas.resize (number_of_classes, 0.0f); + + std::vector vec; + std::vector > objects_sigmas; + objects_sigmas.resize (number_of_classes, vec); + + unsigned int number_of_objects = static_cast (training_clouds_.size ()); + for (unsigned int i_object = 0; i_object < number_of_objects; i_object++) + { + float max_distance = 0.0f; + unsigned int number_of_points = static_cast (training_clouds_[i_object]->points.size ()); + for (unsigned int i_point = 0; i_point < number_of_points - 1; i_point++) + for (unsigned int j_point = i_point + 1; j_point < number_of_points; j_point++) + { + float curr_distance = 0.0f; + curr_distance += training_clouds_[i_object]->points[i_point].x * training_clouds_[i_object]->points[j_point].x; + curr_distance += training_clouds_[i_object]->points[i_point].y * training_clouds_[i_object]->points[j_point].y; + curr_distance += training_clouds_[i_object]->points[i_point].z * training_clouds_[i_object]->points[j_point].z; + if (curr_distance > max_distance) + max_distance = curr_distance; + } + max_distance = static_cast (sqrt (max_distance)); + unsigned int i_class = training_classes_[i_object]; + objects_sigmas[i_class].push_back (max_distance); + } + + for (unsigned int i_class = 0; i_class < number_of_classes; i_class++) + { + float sig = 0.0f; + unsigned int number_of_objects_in_class = static_cast (objects_sigmas[i_class].size ()); + for (unsigned int i_object = 0; i_object < number_of_objects_in_class; i_object++) + sig += objects_sigmas[i_class][i_object]; + sig /= (static_cast (number_of_objects_in_class) * 10.0f); + sigmas[i_class] = sig; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::calculateWeights ( + const std::vector< LocationInfo, Eigen::aligned_allocator >& locations, + const Eigen::MatrixXi &labels, + std::vector& sigmas, + std::vector >& clusters, + std::vector >& statistical_weights, + std::vector& learned_weights) +{ + unsigned int number_of_classes = *std::max_element (training_classes_.begin (), training_classes_.end () ) + 1; + //Temporary variable + std::vector vec; + vec.resize (number_of_clusters_, 0.0f); + statistical_weights.clear (); + learned_weights.clear (); + statistical_weights.resize (number_of_classes, vec); + learned_weights.resize (locations.size (), 0.0f); + + //Temporary variable + std::vector vect; + vect.resize (*std::max_element (training_classes_.begin (), training_classes_.end () ) + 1, 0); + + //Number of features from which c_i was learned + std::vector n_ftr; + + //Total number of votes from visual word v_j + std::vector n_vot; + + //Number of visual words that vote for class c_i + std::vector n_vw; + + //Number of votes for class c_i from v_j + std::vector > n_vot_2; + + n_vot_2.resize (number_of_clusters_, vect); + n_vot.resize (number_of_clusters_, 0); + n_ftr.resize (number_of_classes, 0); + for (size_t i_location = 0; i_location < locations.size (); i_location++) + { + int i_class = training_classes_[locations[i_location].model_num_]; + int i_cluster = labels (i_location); + n_vot_2[i_cluster][i_class] += 1; + n_vot[i_cluster] += 1; + n_ftr[i_class] += 1; + } + + n_vw.resize (number_of_classes, 0); + for (unsigned int i_class = 0; i_class < number_of_classes; i_class++) + for (unsigned int i_cluster = 0; i_cluster < number_of_clusters_; i_cluster++) + if (n_vot_2[i_cluster][i_class] > 0) + n_vw[i_class] += 1; + + //computing learned weights + learned_weights.resize (locations.size (), 0.0); + for (unsigned int i_cluster = 0; i_cluster < number_of_clusters_; i_cluster++) + { + unsigned int number_of_words_in_cluster = static_cast (clusters[i_cluster].size ()); + for (unsigned int i_visual_word = 0; i_visual_word < number_of_words_in_cluster; i_visual_word++) + { + unsigned int i_index = clusters[i_cluster][i_visual_word]; + int i_class = training_classes_[locations[i_index].model_num_]; + float square_sigma_dist = sigmas[i_class] * sigmas[i_class]; + if (square_sigma_dist < std::numeric_limits::epsilon ()) + { + std::vector calculated_sigmas; + calculateSigmas (calculated_sigmas); + square_sigma_dist = calculated_sigmas[i_class] * calculated_sigmas[i_class]; + if (square_sigma_dist < std::numeric_limits::epsilon ()) + continue; + } + Eigen::Matrix3f transform = alignYCoordWithNormal (locations[i_index].normal_); + Eigen::Vector3f direction = locations[i_index].dir_to_center_.getVector3fMap (); + applyTransform (direction, transform); + Eigen::Vector3f actual_center = locations[i_index].point_.getVector3fMap () + direction; + + //collect gaussian weighted distances + std::vector gauss_dists; + for (unsigned int j_visual_word = 0; j_visual_word < number_of_words_in_cluster; j_visual_word++) + { + unsigned int j_index = clusters[i_cluster][j_visual_word]; + int j_class = training_classes_[locations[j_index].model_num_]; + if (i_class != j_class) + continue; + //predict center + Eigen::Matrix3f transform_2 = alignYCoordWithNormal (locations[j_index].normal_); + Eigen::Vector3f direction_2 = locations[i_index].dir_to_center_.getVector3fMap (); + applyTransform (direction_2, transform_2); + Eigen::Vector3f predicted_center = locations[j_index].point_.getVector3fMap () + direction_2; + float residual = (predicted_center - actual_center).norm (); + float value = -residual * residual / square_sigma_dist; + gauss_dists.push_back (static_cast (exp (value))); + }//next word + //find median gaussian weighted distance + size_t mid_elem = (gauss_dists.size () - 1) / 2; + std::nth_element (gauss_dists.begin (), gauss_dists.begin () + mid_elem, gauss_dists.end ()); + learned_weights[i_index] = *(gauss_dists.begin () + mid_elem); + }//next word + }//next cluster + + //computing statistical weights + for (unsigned int i_cluster = 0; i_cluster < number_of_clusters_; i_cluster++) + { + for (unsigned int i_class = 0; i_class < number_of_classes; i_class++) + { + if (n_vot_2[i_cluster][i_class] == 0) + continue;//no votes per class of interest in this cluster + if (n_vw[i_class] == 0) + continue;//there were no objects of this class in the training dataset + if (n_vot[i_cluster] == 0) + continue;//this cluster has never been used + if (n_ftr[i_class] == 0) + continue;//there were no objects of this class in the training dataset + float part_1 = static_cast (n_vw[i_class]); + float part_2 = static_cast (n_vot[i_cluster]); + float part_3 = static_cast (n_vot_2[i_cluster][i_class]) / static_cast (n_ftr[i_class]); + float part_4 = 0.0f; + + if (!n_vot_ON_) + part_2 = 1.0f; + + for (unsigned int j_class = 0; j_class < number_of_classes; j_class++) + if (n_ftr[j_class] != 0) + part_4 += static_cast (n_vot_2[i_cluster][j_class]) / static_cast (n_ftr[j_class]); + + statistical_weights[i_class][i_cluster] = (1.0f / part_1) * (1.0f / part_2) * part_3 / part_4; + } + }//next cluster +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::simplifyCloud ( + typename pcl::PointCloud::ConstPtr in_point_cloud, + typename pcl::PointCloud::ConstPtr in_normal_cloud, + typename pcl::PointCloud::Ptr out_sampled_point_cloud, + typename pcl::PointCloud::Ptr out_sampled_normal_cloud) +{ + //create voxel grid + pcl::VoxelGrid grid; + grid.setLeafSize (sampling_size_, sampling_size_, sampling_size_); + grid.setSaveLeafLayout (true); + grid.setInputCloud (in_point_cloud); + + pcl::PointCloud temp_cloud; + grid.filter (temp_cloud); + + //extract indices of points from source cloud which are closest to grid points + const float max_value = std::numeric_limits::max (); + + const size_t num_source_points = in_point_cloud->points.size (); + const size_t num_sample_points = temp_cloud.points.size (); + + std::vector dist_to_grid_center (num_sample_points, max_value); + std::vector sampling_indices (num_sample_points, -1); + + for (size_t i_point = 0; i_point < num_source_points; i_point++) + { + int index = grid.getCentroidIndex (in_point_cloud->points[i_point]); + if (index == -1) + continue; + + PointT pt_1 = in_point_cloud->points[i_point]; + PointT pt_2 = temp_cloud.points[index]; + + float distance = (pt_1.x - pt_2.x) * (pt_1.x - pt_2.x) + (pt_1.y - pt_2.y) * (pt_1.y - pt_2.y) + (pt_1.z - pt_2.z) * (pt_1.z - pt_2.z); + if (distance < dist_to_grid_center[index]) + { + dist_to_grid_center[index] = distance; + sampling_indices[index] = static_cast (i_point); + } + } + + //extract source points + pcl::PointIndices::Ptr final_inliers_indices (new pcl::PointIndices ()); + pcl::ExtractIndices extract_points; + pcl::ExtractIndices extract_normals; + + final_inliers_indices->indices.reserve (num_sample_points); + for (size_t i_point = 0; i_point < num_sample_points; i_point++) + { + if (sampling_indices[i_point] != -1) + final_inliers_indices->indices.push_back ( sampling_indices[i_point] ); + } + + extract_points.setInputCloud (in_point_cloud); + extract_points.setIndices (final_inliers_indices); + extract_points.filter (*out_sampled_point_cloud); + + extract_normals.setInputCloud (in_normal_cloud); + extract_normals.setIndices (final_inliers_indices); + extract_normals.filter (*out_sampled_normal_cloud); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::shiftCloud ( + typename pcl::PointCloud::Ptr in_cloud, + Eigen::Vector3f shift_point) +{ + typename pcl::PointCloud::iterator point_it; + for (point_it = in_cloud->points.begin (); point_it != in_cloud->points.end (); point_it++) + { + point_it->x -= shift_point.x (); + point_it->y -= shift_point.y (); + point_it->z -= shift_point.z (); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template Eigen::Matrix3f +pcl::ism::ImplicitShapeModelEstimation::alignYCoordWithNormal (const NormalT& in_normal) +{ + Eigen::Matrix3f result; + Eigen::Matrix3f rotation_matrix_X; + Eigen::Matrix3f rotation_matrix_Z; + + float A = 0.0f; + float B = 0.0f; + float sign = -1.0f; + + float denom_X = static_cast (sqrt (in_normal.normal_z * in_normal.normal_z + in_normal.normal_y * in_normal.normal_y)); + A = in_normal.normal_y / denom_X; + B = sign * in_normal.normal_z / denom_X; + rotation_matrix_X << 1.0f, 0.0f, 0.0f, + 0.0f, A, -B, + 0.0f, B, A; + + float denom_Z = static_cast (sqrt (in_normal.normal_x * in_normal.normal_x + in_normal.normal_y * in_normal.normal_y)); + A = in_normal.normal_y / denom_Z; + B = sign * in_normal.normal_x / denom_Z; + rotation_matrix_Z << A, -B, 0.0f, + B, A, 0.0f, + 0.0f, 0.0f, 1.0f; + + result = rotation_matrix_X * rotation_matrix_Z; + + return (result); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::applyTransform (Eigen::Vector3f& io_vec, const Eigen::Matrix3f& in_transform) +{ + io_vec = in_transform * io_vec; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::estimateFeatures ( + typename pcl::PointCloud::Ptr sampled_point_cloud, + typename pcl::PointCloud::Ptr normal_cloud, + typename pcl::PointCloud >::Ptr feature_cloud) +{ + typename pcl::search::Search::Ptr tree = boost::shared_ptr > (new pcl::search::KdTree); +// tree->setInputCloud (point_cloud); + + feature_estimator_->setInputCloud (sampled_point_cloud->makeShared ()); +// feature_estimator_->setSearchSurface (point_cloud->makeShared ()); + feature_estimator_->setSearchMethod (tree); + +// typename pcl::SpinImageEstimation >::Ptr feat_est_norm = +// boost::dynamic_pointer_cast > > (feature_estimator_); +// feat_est_norm->setInputNormals (normal_cloud); + + typename pcl::FeatureFromNormals >::Ptr feat_est_norm = + boost::dynamic_pointer_cast > > (feature_estimator_); + feat_est_norm->setInputNormals (normal_cloud); + + feature_estimator_->compute (*feature_cloud); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::ism::ImplicitShapeModelEstimation::computeKMeansClustering ( + const Eigen::MatrixXf& points_to_cluster, + int number_of_clusters, + Eigen::MatrixXi& io_labels, + TermCriteria criteria, + int attempts, + int flags, + Eigen::MatrixXf& cluster_centers) +{ + const int spp_trials = 3; + size_t number_of_points = points_to_cluster.rows () > 1 ? points_to_cluster.rows () : points_to_cluster.cols (); + int feature_dimension = points_to_cluster.rows () > 1 ? FeatureSize : 1; + + attempts = std::max (attempts, 1); + srand (static_cast (time (0))); + + Eigen::MatrixXi labels (number_of_points, 1); + + if (flags & USE_INITIAL_LABELS) + labels = io_labels; + else + labels.setZero (); + + Eigen::MatrixXf centers (number_of_clusters, feature_dimension); + Eigen::MatrixXf old_centers (number_of_clusters, feature_dimension); + std::vector counters (number_of_clusters); + std::vector boxes (feature_dimension); + Eigen::Vector2f* box = &boxes[0]; + + double best_compactness = std::numeric_limits::max (); + double compactness = 0.0; + + if (criteria.type_ & TermCriteria::EPS) + criteria.epsilon_ = std::max (criteria.epsilon_, 0.0f); + else + criteria.epsilon_ = std::numeric_limits::epsilon (); + + criteria.epsilon_ *= criteria.epsilon_; + + if (criteria.type_ & TermCriteria::COUNT) + criteria.max_count_ = std::min (std::max (criteria.max_count_, 2), 100); + else + criteria.max_count_ = 100; + + if (number_of_clusters == 1) + { + attempts = 1; + criteria.max_count_ = 2; + } + + for (int i_dim = 0; i_dim < feature_dimension; i_dim++) + box[i_dim] = Eigen::Vector2f (points_to_cluster (0, i_dim), points_to_cluster (0, i_dim)); + + for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + for (int i_dim = 0; i_dim < feature_dimension; i_dim++) + { + float v = points_to_cluster (i_point, i_dim); + box[i_dim] (0) = std::min (box[i_dim] (0), v); + box[i_dim] (1) = std::max (box[i_dim] (1), v); + } + + for (int i_attempt = 0; i_attempt < attempts; i_attempt++) + { + float max_center_shift = std::numeric_limits::max (); + for (int iter = 0; iter < criteria.max_count_ && max_center_shift > criteria.epsilon_; iter++) + { + Eigen::MatrixXf temp (centers.rows (), centers.cols ()); + temp = centers; + centers = old_centers; + old_centers = temp; + + if ( iter == 0 && ( i_attempt > 0 || !(flags & USE_INITIAL_LABELS) ) ) + { + if (flags & PP_CENTERS) + generateCentersPP (points_to_cluster, centers, number_of_clusters, spp_trials); + else + { + for (int i_cl_center = 0; i_cl_center < number_of_clusters; i_cl_center++) + { + Eigen::VectorXf center (feature_dimension); + generateRandomCenter (boxes, center); + for (int i_dim = 0; i_dim < feature_dimension; i_dim++) + centers (i_cl_center, i_dim) = center (i_dim); + }//generate center for next cluster + }//end if-else random or PP centers + } + else + { + centers.setZero (); + for (int i_cluster = 0; i_cluster < number_of_clusters; i_cluster++) + counters[i_cluster] = 0; + for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + { + int i_label = labels (i_point, 0); + for (int i_dim = 0; i_dim < feature_dimension; i_dim++) + centers (i_label, i_dim) += points_to_cluster (i_point, i_dim); + counters[i_label]++; + } + if (iter > 0) + max_center_shift = 0.0f; + for (int i_cl_center = 0; i_cl_center < number_of_clusters; i_cl_center++) + { + if (counters[i_cl_center] != 0) + { + float scale = 1.0f / static_cast (counters[i_cl_center]); + for (int i_dim = 0; i_dim < feature_dimension; i_dim++) + centers (i_cl_center, i_dim) *= scale; + } + else + { + Eigen::VectorXf center (feature_dimension); + generateRandomCenter (boxes, center); + for(int i_dim = 0; i_dim < feature_dimension; i_dim++) + centers (i_cl_center, i_dim) = center (i_dim); + } + + if (iter > 0) + { + float dist = 0.0f; + for (int i_dim = 0; i_dim < feature_dimension; i_dim++) + { + float diff = centers (i_cl_center, i_dim) - old_centers (i_cl_center, i_dim); + dist += diff * diff; + } + max_center_shift = std::max (max_center_shift, dist); + } + } + } + compactness = 0.0f; + for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + { + Eigen::VectorXf sample (feature_dimension); + sample = points_to_cluster.row (i_point); + + int k_best = 0; + float min_dist = std::numeric_limits::max (); + + for (int i_cluster = 0; i_cluster < number_of_clusters; i_cluster++) + { + Eigen::VectorXf center (feature_dimension); + center = centers.row (i_cluster); + float dist = computeDistance (sample, center); + if (min_dist > dist) + { + min_dist = dist; + k_best = i_cluster; + } + } + compactness += min_dist; + labels (i_point, 0) = k_best; + } + }//next iteration + + if (compactness < best_compactness) + { + best_compactness = compactness; + cluster_centers = centers; + io_labels = labels; + } + }//next attempt + + return (best_compactness); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::generateCentersPP ( + const Eigen::MatrixXf& data, + Eigen::MatrixXf& out_centers, + int number_of_clusters, + int trials) +{ + size_t dimension = data.cols (); + unsigned int number_of_points = static_cast (data.rows ()); + std::vector centers_vec (number_of_clusters); + int* centers = ¢ers_vec[0]; + std::vector dist (number_of_points); + std::vector tdist (number_of_points); + std::vector tdist2 (number_of_points); + double sum0 = 0.0; + + unsigned int random_unsigned = rand (); + centers[0] = random_unsigned % number_of_points; + + for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + { + Eigen::VectorXf first (dimension); + Eigen::VectorXf second (dimension); + first = data.row (i_point); + second = data.row (centers[0]); + dist[i_point] = computeDistance (first, second); + sum0 += dist[i_point]; + } + + for (int i_cluster = 0; i_cluster < number_of_clusters; i_cluster++) + { + double best_sum = std::numeric_limits::max (); + int best_center = -1; + for (int i_trials = 0; i_trials < trials; i_trials++) + { + unsigned int random_integer = rand () - 1; + double random_double = static_cast (random_integer) / static_cast (std::numeric_limits::max ()); + double p = random_double * sum0; + + unsigned int i_point; + for (i_point = 0; i_point < number_of_points - 1; i_point++) + if ( (p -= dist[i_point]) <= 0.0) + break; + + int ci = i_point; + + double s = 0.0; + for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + { + Eigen::VectorXf first (dimension); + Eigen::VectorXf second (dimension); + first = data.row (i_point); + second = data.row (ci); + tdist2[i_point] = std::min (static_cast (computeDistance (first, second)), dist[i_point]); + s += tdist2[i_point]; + } + + if (s <= best_sum) + { + best_sum = s; + best_center = ci; + std::swap (tdist, tdist2); + } + } + + centers[i_cluster] = best_center; + sum0 = best_sum; + std::swap (dist, tdist); + } + + for (int i_cluster = 0; i_cluster < number_of_clusters; i_cluster++) + for (unsigned int i_dim = 0; i_dim < dimension; i_dim++) + out_centers (i_cluster, i_dim) = data (centers[i_cluster], i_dim); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ism::ImplicitShapeModelEstimation::generateRandomCenter (const std::vector& boxes, + Eigen::VectorXf& center) +{ + size_t dimension = boxes.size (); + float margin = 1.0f / static_cast (dimension); + + for (unsigned int i_dim = 0; i_dim < dimension; i_dim++) + { + unsigned int random_integer = rand () - 1; + float random_float = static_cast (random_integer) / static_cast (std::numeric_limits::max ()); + center (i_dim) = (random_float * (1.0f + margin * 2.0f)- margin) * (boxes[i_dim] (1) - boxes[i_dim] (0)) + boxes[i_dim] (0); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::ism::ImplicitShapeModelEstimation::computeDistance (Eigen::VectorXf& vec_1, Eigen::VectorXf& vec_2) +{ + size_t dimension = vec_1.rows () > 1 ? vec_1.rows () : vec_1.cols (); + float distance = 0.0f; + for(unsigned int i_dim = 0; i_dim < dimension; i_dim++) + { + float diff = vec_1 (i_dim) - vec_2 (i_dim); + distance += diff * diff; + } + + return (distance); +} + +#endif //#ifndef PCL_IMPLICIT_SHAPE_MODEL_HPP_ diff --git a/pcl-1.7/pcl/recognition/impl/line_rgbd.hpp b/pcl-1.7/pcl/recognition/impl/line_rgbd.hpp new file mode 100644 index 0000000..39e0399 --- /dev/null +++ b/pcl-1.7/pcl/recognition/impl/line_rgbd.hpp @@ -0,0 +1,990 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RECOGNITION_LINEMOD_LINE_RGBD_IMPL_HPP_ +#define PCL_RECOGNITION_LINEMOD_LINE_RGBD_IMPL_HPP_ + +//#include +#include +#include +#include +#include +#ifdef _WIN32 +# include +# include +# define pcl_open _open +# define pcl_close(fd) _close(fd) +# define pcl_lseek(fd,offset,origin) _lseek(fd,offset,origin) +#else +#include +# include +# define pcl_open open +# define pcl_close(fd) close(fd) +# define pcl_lseek(fd,offset,origin) lseek(fd,offset,origin) +#endif + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::LineRGBD::readLTMHeader (int fd, pcl::io::TARHeader &header) +{ + // Read in the header + int result = static_cast (::read (fd, reinterpret_cast (&header.file_name[0]), 512)); + if (result == -1) + return (false); + + // We only support regular files for now. + // Addional file types in TAR include: hard links, symbolic links, device/special files, block devices, + // directories, and named pipes. + if (header.file_type[0] != '0' && header.file_type[0] != '\0') + return (false); + + // We only support USTAR version 0 files for now + if (std::string (header.ustar).substr (0, 5) != "ustar") + return (false); + + if (header.getFileSize () == 0) + return (false); + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::LineRGBD::loadTemplates (const std::string &file_name, const size_t object_id) +{ + // Open the file + int ltm_fd = pcl_open (file_name.c_str (), O_RDONLY); + if (ltm_fd == -1) + return (false); + + int ltm_offset = 0; + + pcl::io::TARHeader ltm_header; + PCDReader pcd_reader; + + std::string pcd_ext (".pcd"); + std::string sqmmt_ext (".sqmmt"); + + // While there still is an LTM header to be read + while (readLTMHeader (ltm_fd, ltm_header)) + { + ltm_offset += 512; + + // Search for extension + std::string chunk_name (ltm_header.file_name); + + std::transform (chunk_name.begin (), chunk_name.end (), chunk_name.begin (), ::tolower); + std::string::size_type it; + + if ((it = chunk_name.find (pcd_ext)) != std::string::npos && + (pcd_ext.size () - (chunk_name.size () - it)) == 0) + { + PCL_DEBUG ("[pcl::LineRGBD::loadTemplates] Reading and parsing %s as a PCD file.\n", chunk_name.c_str ()); + // Read the next PCD file + template_point_clouds_.resize (template_point_clouds_.size () + 1); + pcd_reader.read (file_name, template_point_clouds_[template_point_clouds_.size () - 1], ltm_offset); + + // Increment the offset for the next file + ltm_offset += (ltm_header.getFileSize ()) + (512 - ltm_header.getFileSize () % 512); + } + else if ((it = chunk_name.find (sqmmt_ext)) != std::string::npos && + (sqmmt_ext.size () - (chunk_name.size () - it)) == 0) + { + PCL_DEBUG ("[pcl::LineRGBD::loadTemplates] Reading and parsing %s as a SQMMT file.\n", chunk_name.c_str ()); + + unsigned int fsize = ltm_header.getFileSize (); + char *buffer = new char[fsize]; + int result = static_cast (::read (ltm_fd, reinterpret_cast (&buffer[0]), fsize)); + if (result == -1) + { + delete [] buffer; + PCL_ERROR ("[pcl::LineRGBD::loadTemplates] Error reading SQMMT template from file!\n"); + break; + } + + // Read a SQMMT file + std::stringstream stream (std::stringstream::in | std::stringstream::out | std::stringstream::binary); + stream.write (buffer, fsize); + SparseQuantizedMultiModTemplate sqmmt; + sqmmt.deserialize (stream); + + linemod_.addTemplate (sqmmt); + object_ids_.push_back (object_id); + + // Increment the offset for the next file + ltm_offset += (ltm_header.getFileSize ()) + (512 - ltm_header.getFileSize () % 512); + + delete [] buffer; + } + + if (static_cast (pcl_lseek (ltm_fd, ltm_offset, SEEK_SET)) < 0) + break; + } + + // Close the file + pcl_close (ltm_fd); + + // Compute 3D bounding boxes from the template point clouds + bounding_boxes_.resize (template_point_clouds_.size ()); + for (size_t i = 0; i < template_point_clouds_.size (); ++i) + { + PointCloud & template_point_cloud = template_point_clouds_[i]; + BoundingBoxXYZ & bb = bounding_boxes_[i]; + bb.x = bb.y = bb.z = std::numeric_limits::max (); + bb.width = bb.height = bb.depth = 0.0f; + + float center_x = 0.0f; + float center_y = 0.0f; + float center_z = 0.0f; + float min_x = std::numeric_limits::max (); + float min_y = std::numeric_limits::max (); + float min_z = std::numeric_limits::max (); + float max_x = -std::numeric_limits::max (); + float max_y = -std::numeric_limits::max (); + float max_z = -std::numeric_limits::max (); + size_t counter = 0; + for (size_t j = 0; j < template_point_cloud.size (); ++j) + { + const PointXYZRGBA & p = template_point_cloud.points[j]; + + if (!pcl_isfinite (p.x) || !pcl_isfinite (p.y) || !pcl_isfinite (p.z)) + continue; + + min_x = std::min (min_x, p.x); + min_y = std::min (min_y, p.y); + min_z = std::min (min_z, p.z); + max_x = std::max (max_x, p.x); + max_y = std::max (max_y, p.y); + max_z = std::max (max_z, p.z); + + center_x += p.x; + center_y += p.y; + center_z += p.z; + + ++counter; + } + + center_x /= static_cast (counter); + center_y /= static_cast (counter); + center_z /= static_cast (counter); + + bb.width = max_x - min_x; + bb.height = max_y - min_y; + bb.depth = max_z - min_z; + + bb.x = (min_x + bb.width / 2.0f) - center_x - bb.width / 2.0f; + bb.y = (min_y + bb.height / 2.0f) - center_y - bb.height / 2.0f; + bb.z = (min_z + bb.depth / 2.0f) - center_z - bb.depth / 2.0f; + + for (size_t j = 0; j < template_point_cloud.size (); ++j) + { + PointXYZRGBA p = template_point_cloud.points[j]; + + if (!pcl_isfinite (p.x) || !pcl_isfinite (p.y) || !pcl_isfinite (p.z)) + continue; + + p.x -= center_x; + p.y -= center_y; + p.z -= center_z; + + template_point_cloud.points[j] = p; + } + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::LineRGBD::createAndAddTemplate ( + pcl::PointCloud & cloud, + const size_t object_id, + const MaskMap & mask_xyz, + const MaskMap & mask_rgb, + const RegionXY & region) +{ + // add point cloud + template_point_clouds_.resize (template_point_clouds_.size () + 1); + pcl::copyPointCloud (cloud, template_point_clouds_[template_point_clouds_.size () - 1]); + + // add template + object_ids_.push_back (object_id); + + // Compute 3D bounding boxes from the template point clouds + bounding_boxes_.resize (template_point_clouds_.size ()); + { + const size_t i = template_point_clouds_.size () - 1; + + PointCloud & template_point_cloud = template_point_clouds_[i]; + BoundingBoxXYZ & bb = bounding_boxes_[i]; + bb.x = bb.y = bb.z = std::numeric_limits::max (); + bb.width = bb.height = bb.depth = 0.0f; + + float center_x = 0.0f; + float center_y = 0.0f; + float center_z = 0.0f; + float min_x = std::numeric_limits::max (); + float min_y = std::numeric_limits::max (); + float min_z = std::numeric_limits::max (); + float max_x = -std::numeric_limits::max (); + float max_y = -std::numeric_limits::max (); + float max_z = -std::numeric_limits::max (); + size_t counter = 0; + for (size_t j = 0; j < template_point_cloud.size (); ++j) + { + const PointXYZRGBA & p = template_point_cloud.points[j]; + + if (!pcl_isfinite (p.x) || !pcl_isfinite (p.y) || !pcl_isfinite (p.z)) + continue; + + min_x = std::min (min_x, p.x); + min_y = std::min (min_y, p.y); + min_z = std::min (min_z, p.z); + max_x = std::max (max_x, p.x); + max_y = std::max (max_y, p.y); + max_z = std::max (max_z, p.z); + + center_x += p.x; + center_y += p.y; + center_z += p.z; + + ++counter; + } + + center_x /= static_cast (counter); + center_y /= static_cast (counter); + center_z /= static_cast (counter); + + bb.width = max_x - min_x; + bb.height = max_y - min_y; + bb.depth = max_z - min_z; + + bb.x = (min_x + bb.width / 2.0f) - center_x - bb.width / 2.0f; + bb.y = (min_y + bb.height / 2.0f) - center_y - bb.height / 2.0f; + bb.z = (min_z + bb.depth / 2.0f) - center_z - bb.depth / 2.0f; + + for (size_t j = 0; j < template_point_cloud.size (); ++j) + { + PointXYZRGBA p = template_point_cloud.points[j]; + + if (!pcl_isfinite (p.x) || !pcl_isfinite (p.y) || !pcl_isfinite (p.z)) + continue; + + p.x -= center_x; + p.y -= center_y; + p.z -= center_z; + + template_point_cloud.points[j] = p; + } + } + + std::vector modalities; + modalities.push_back (&color_gradient_mod_); + modalities.push_back (&surface_normal_mod_); + + std::vector masks; + masks.push_back (const_cast (&mask_rgb)); + masks.push_back (const_cast (&mask_xyz)); + + return (linemod_.createAndAddTemplate (modalities, masks, region)); +} + + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::LineRGBD::addTemplate (const SparseQuantizedMultiModTemplate & sqmmt, pcl::PointCloud & cloud, size_t object_id) +{ + // add point cloud + template_point_clouds_.resize (template_point_clouds_.size () + 1); + pcl::copyPointCloud (cloud, template_point_clouds_[template_point_clouds_.size () - 1]); + + // add template + linemod_.addTemplate (sqmmt); + object_ids_.push_back (object_id); + + // Compute 3D bounding boxes from the template point clouds + bounding_boxes_.resize (template_point_clouds_.size ()); + { + const size_t i = template_point_clouds_.size () - 1; + + PointCloud & template_point_cloud = template_point_clouds_[i]; + BoundingBoxXYZ & bb = bounding_boxes_[i]; + bb.x = bb.y = bb.z = std::numeric_limits::max (); + bb.width = bb.height = bb.depth = 0.0f; + + float center_x = 0.0f; + float center_y = 0.0f; + float center_z = 0.0f; + float min_x = std::numeric_limits::max (); + float min_y = std::numeric_limits::max (); + float min_z = std::numeric_limits::max (); + float max_x = -std::numeric_limits::max (); + float max_y = -std::numeric_limits::max (); + float max_z = -std::numeric_limits::max (); + size_t counter = 0; + for (size_t j = 0; j < template_point_cloud.size (); ++j) + { + const PointXYZRGBA & p = template_point_cloud.points[j]; + + if (!pcl_isfinite (p.x) || !pcl_isfinite (p.y) || !pcl_isfinite (p.z)) + continue; + + min_x = std::min (min_x, p.x); + min_y = std::min (min_y, p.y); + min_z = std::min (min_z, p.z); + max_x = std::max (max_x, p.x); + max_y = std::max (max_y, p.y); + max_z = std::max (max_z, p.z); + + center_x += p.x; + center_y += p.y; + center_z += p.z; + + ++counter; + } + + center_x /= static_cast (counter); + center_y /= static_cast (counter); + center_z /= static_cast (counter); + + bb.width = max_x - min_x; + bb.height = max_y - min_y; + bb.depth = max_z - min_z; + + bb.x = (min_x + bb.width / 2.0f) - center_x - bb.width / 2.0f; + bb.y = (min_y + bb.height / 2.0f) - center_y - bb.height / 2.0f; + bb.z = (min_z + bb.depth / 2.0f) - center_z - bb.depth / 2.0f; + + for (size_t j = 0; j < template_point_cloud.size (); ++j) + { + PointXYZRGBA p = template_point_cloud.points[j]; + + if (!pcl_isfinite (p.x) || !pcl_isfinite (p.y) || !pcl_isfinite (p.z)) + continue; + + p.x -= center_x; + p.y -= center_y; + p.z -= center_z; + + template_point_cloud.points[j] = p; + } + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LineRGBD::detect ( + std::vector::Detection> & detections) +{ + std::vector modalities; + modalities.push_back (&color_gradient_mod_); + modalities.push_back (&surface_normal_mod_); + + std::vector linemod_detections; + linemod_.detectTemplates (modalities, linemod_detections); + + detections_.clear (); + detections_.reserve (linemod_detections.size ()); + detections.clear (); + detections.reserve (linemod_detections.size ()); + for (size_t detection_id = 0; detection_id < linemod_detections.size (); ++detection_id) + { + pcl::LINEMODDetection & linemod_detection = linemod_detections[detection_id]; + + typename pcl::LineRGBD::Detection detection; + detection.template_id = linemod_detection.template_id; + detection.object_id = object_ids_[linemod_detection.template_id]; + detection.detection_id = detection_id; + detection.response = linemod_detection.score; + + // compute bounding box: + // we assume that the bounding boxes of the templates are relative to the center of mass + // of the template points; so we also compute the center of mass of the points + // covered by the + + const pcl::SparseQuantizedMultiModTemplate & linemod_template = + linemod_.getTemplate (linemod_detection.template_id); + + const size_t start_x = std::max (linemod_detection.x, 0); + const size_t start_y = std::max (linemod_detection.y, 0); + const size_t end_x = std::min (static_cast (start_x + linemod_template.region.width), + static_cast (cloud_xyz_->width)); + const size_t end_y = std::min (static_cast (start_y + linemod_template.region.height), + static_cast (cloud_xyz_->height)); + + detection.region.x = linemod_detection.x; + detection.region.y = linemod_detection.y; + detection.region.width = linemod_template.region.width; + detection.region.height = linemod_template.region.height; + + //std::cerr << "detection region: " << linemod_detection.x << ", " + // << linemod_detection.y << ", " + // << linemod_template.region.width << ", " + // << linemod_template.region.height << std::endl; + + float center_x = 0.0f; + float center_y = 0.0f; + float center_z = 0.0f; + size_t counter = 0; + for (size_t row_index = start_y; row_index < end_y; ++row_index) + { + for (size_t col_index = start_x; col_index < end_x; ++col_index) + { + const PointXYZT & point = (*cloud_xyz_) (col_index, row_index); + + if (pcl_isfinite (point.x) && pcl_isfinite (point.y) && pcl_isfinite (point.z)) + { + center_x += point.x; + center_y += point.y; + center_z += point.z; + ++counter; + } + } + } + const float inv_counter = 1.0f / static_cast (counter); + center_x *= inv_counter; + center_y *= inv_counter; + center_z *= inv_counter; + + pcl::BoundingBoxXYZ template_bounding_box = bounding_boxes_[detection.template_id]; + + detection.bounding_box = template_bounding_box; + detection.bounding_box.x += center_x; + detection.bounding_box.y += center_y; + detection.bounding_box.z += center_z; + + detections_.push_back (detection); + } + + // refine detections along depth + refineDetectionsAlongDepth (); + //applyprojectivedepthicpondetections(); + + // remove overlaps + removeOverlappingDetections (); + + for (size_t detection_index = 0; detection_index < detections_.size (); ++detection_index) + { + detections.push_back (detections_[detection_index]); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LineRGBD::detectSemiScaleInvariant ( + std::vector::Detection> & detections, + const float min_scale, + const float max_scale, + const float scale_multiplier) +{ + std::vector modalities; + modalities.push_back (&color_gradient_mod_); + modalities.push_back (&surface_normal_mod_); + + std::vector linemod_detections; + linemod_.detectTemplatesSemiScaleInvariant (modalities, linemod_detections, min_scale, max_scale, scale_multiplier); + + detections_.clear (); + detections_.reserve (linemod_detections.size ()); + detections.clear (); + detections.reserve (linemod_detections.size ()); + for (size_t detection_id = 0; detection_id < linemod_detections.size (); ++detection_id) + { + pcl::LINEMODDetection & linemod_detection = linemod_detections[detection_id]; + + typename pcl::LineRGBD::Detection detection; + detection.template_id = linemod_detection.template_id; + detection.object_id = object_ids_[linemod_detection.template_id]; + detection.detection_id = detection_id; + detection.response = linemod_detection.score; + + // compute bounding box: + // we assume that the bounding boxes of the templates are relative to the center of mass + // of the template points; so we also compute the center of mass of the points + // covered by the + + const pcl::SparseQuantizedMultiModTemplate & linemod_template = + linemod_.getTemplate (linemod_detection.template_id); + + const size_t start_x = std::max (linemod_detection.x, 0); + const size_t start_y = std::max (linemod_detection.y, 0); + const size_t end_x = std::min (static_cast (start_x + linemod_template.region.width * linemod_detection.scale), + static_cast (cloud_xyz_->width)); + const size_t end_y = std::min (static_cast (start_y + linemod_template.region.height * linemod_detection.scale), + static_cast (cloud_xyz_->height)); + + detection.region.x = linemod_detection.x; + detection.region.y = linemod_detection.y; + detection.region.width = linemod_template.region.width * linemod_detection.scale; + detection.region.height = linemod_template.region.height * linemod_detection.scale; + + //std::cerr << "detection region: " << linemod_detection.x << ", " + // << linemod_detection.y << ", " + // << linemod_template.region.width << ", " + // << linemod_template.region.height << std::endl; + + float center_x = 0.0f; + float center_y = 0.0f; + float center_z = 0.0f; + size_t counter = 0; + for (size_t row_index = start_y; row_index < end_y; ++row_index) + { + for (size_t col_index = start_x; col_index < end_x; ++col_index) + { + const PointXYZT & point = (*cloud_xyz_) (col_index, row_index); + + if (pcl_isfinite (point.x) && pcl_isfinite (point.y) && pcl_isfinite (point.z)) + { + center_x += point.x; + center_y += point.y; + center_z += point.z; + ++counter; + } + } + } + const float inv_counter = 1.0f / static_cast (counter); + center_x *= inv_counter; + center_y *= inv_counter; + center_z *= inv_counter; + + pcl::BoundingBoxXYZ template_bounding_box = bounding_boxes_[detection.template_id]; + + detection.bounding_box = template_bounding_box; + detection.bounding_box.x += center_x; + detection.bounding_box.y += center_y; + detection.bounding_box.z += center_z; + + detections_.push_back (detection); + } + + // refine detections along depth + //refineDetectionsAlongDepth (); + //applyProjectiveDepthICPOnDetections(); + + // remove overlaps + removeOverlappingDetections (); + + for (size_t detection_index = 0; detection_index < detections_.size (); ++detection_index) + { + detections.push_back (detections_[detection_index]); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LineRGBD::computeTransformedTemplatePoints ( + const size_t detection_id, pcl::PointCloud &cloud) +{ + if (detection_id >= detections_.size ()) + PCL_ERROR ("ERROR pcl::LineRGBD::computeTransformedTemplatePoints - detection_id is out of bounds\n"); + + const size_t template_id = detections_[detection_id].template_id; + const pcl::PointCloud & template_point_cloud = template_point_clouds_[template_id]; + + const pcl::BoundingBoxXYZ & template_bounding_box = bounding_boxes_[template_id]; + const pcl::BoundingBoxXYZ & detection_bounding_box = detections_[detection_id].bounding_box; + + //std::cerr << "detection: " + // << detection_bounding_box.x << ", " + // << detection_bounding_box.y << ", " + // << detection_bounding_box.z << std::endl; + //std::cerr << "template: " + // << template_bounding_box.x << ", " + // << template_bounding_box.y << ", " + // << template_bounding_box.z << std::endl; + const float translation_x = detection_bounding_box.x - template_bounding_box.x; + const float translation_y = detection_bounding_box.y - template_bounding_box.y; + const float translation_z = detection_bounding_box.z - template_bounding_box.z; + + //std::cerr << "translation: " + // << translation_x << ", " + // << translation_y << ", " + // << translation_z << std::endl; + + const size_t nr_points = template_point_cloud.size (); + cloud.resize (nr_points); + cloud.width = template_point_cloud.width; + cloud.height = template_point_cloud.height; + for (size_t point_index = 0; point_index < nr_points; ++point_index) + { + pcl::PointXYZRGBA point = template_point_cloud.points[point_index]; + + point.x += translation_x; + point.y += translation_y; + point.z += translation_z; + + cloud.points[point_index] = point; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LineRGBD::refineDetectionsAlongDepth () +{ + const size_t nr_detections = detections_.size (); + for (size_t detection_index = 0; detection_index < nr_detections; ++detection_index) + { + typename LineRGBD::Detection & detection = detections_[detection_index]; + + // find depth with most valid points + const size_t start_x = detection.region.x; + const size_t start_y = detection.region.y; + const size_t end_x = start_x + detection.region.width; + const size_t end_y = start_y + detection.region.height; + + + float min_depth = std::numeric_limits::max (); + float max_depth = -std::numeric_limits::max (); + for (size_t row_index = start_y; row_index < end_y; ++row_index) + { + for (size_t col_index = start_x; col_index < end_x; ++col_index) + { + const PointXYZT & point = (*cloud_xyz_) (col_index, row_index); + + if (/*pcl_isfinite (point.x) && pcl_isfinite (point.y) && */pcl_isfinite (point.z)) + { + min_depth = std::min (min_depth, point.z); + max_depth = std::max (max_depth, point.z); + } + } + } + + const size_t nr_bins = 1000; + const float step_size = (max_depth - min_depth) / static_cast (nr_bins-1); + std::vector depth_bins (nr_bins, 0); + for (size_t row_index = start_y; row_index < end_y; ++row_index) + { + for (size_t col_index = start_x; col_index < end_x; ++col_index) + { + const PointXYZT & point = (*cloud_xyz_) (col_index, row_index); + + if (/*pcl_isfinite (point.x) && pcl_isfinite (point.y) && */pcl_isfinite (point.z)) + { + const size_t bin_index = static_cast ((point.z - min_depth) / step_size); + ++depth_bins[bin_index]; + } + } + } + + std::vector integral_depth_bins (nr_bins, 0); + + integral_depth_bins[0] = depth_bins[0]; + for (size_t bin_index = 1; bin_index < nr_bins; ++bin_index) + { + integral_depth_bins[bin_index] = depth_bins[bin_index] + integral_depth_bins[bin_index-1]; + } + + const size_t bb_depth_range = static_cast (detection.bounding_box.depth / step_size); + + size_t max_nr_points = 0; + size_t max_index = 0; + for (size_t bin_index = 0; (bin_index+bb_depth_range) < nr_bins; ++bin_index) + { + const size_t nr_points_in_range = integral_depth_bins[bin_index+bb_depth_range] - integral_depth_bins[bin_index]; + + if (nr_points_in_range > max_nr_points) + { + max_nr_points = nr_points_in_range; + max_index = bin_index; + } + } + + const float z = static_cast (max_index) * step_size + min_depth; + + detection.bounding_box.z = z; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LineRGBD::applyProjectiveDepthICPOnDetections () +{ + const size_t nr_detections = detections_.size (); + for (size_t detection_index = 0; detection_index < nr_detections; ++detection_index) + { + typename pcl::LineRGBD::Detection & detection = detections_[detection_index]; + + const size_t template_id = detection.template_id; + pcl::PointCloud & point_cloud = template_point_clouds_[template_id]; + + const size_t start_x = detection.region.x; + const size_t start_y = detection.region.y; + const size_t pc_width = point_cloud.width; + const size_t pc_height = point_cloud.height; + + std::vector > depth_matches; + for (size_t row_index = 0; row_index < pc_height; ++row_index) + { + for (size_t col_index = 0; col_index < pc_width; ++col_index) + { + const pcl::PointXYZRGBA & point_template = point_cloud (col_index, row_index); + const PointXYZT & point_input = (*cloud_xyz_) (col_index + start_x, row_index + start_y); + + if (!pcl_isfinite (point_template.z) || !pcl_isfinite (point_input.z)) + continue; + + depth_matches.push_back (std::make_pair (point_template.z, point_input.z)); + } + } + + // apply ransac on matches + const size_t nr_matches = depth_matches.size (); + const size_t nr_iterations = 100; // todo: should be a parameter... + const float inlier_threshold = 0.01f; // 5cm // todo: should be a parameter... + size_t best_nr_inliers = 0; + float best_z_translation = 0.0f; + for (size_t iteration_index = 0; iteration_index < nr_iterations; ++iteration_index) + { + const size_t rand_index = (rand () * nr_matches) / RAND_MAX; + + const float z_translation = depth_matches[rand_index].second - depth_matches[rand_index].first; + + size_t nr_inliers = 0; + for (size_t match_index = 0; match_index < nr_matches; ++match_index) + { + const float error = fabsf (depth_matches[match_index].first + z_translation - depth_matches[match_index].second); + + if (error <= inlier_threshold) + { + ++nr_inliers; + } + } + + if (nr_inliers > best_nr_inliers) + { + best_nr_inliers = nr_inliers; + best_z_translation = z_translation; + } + } + + float average_depth = 0.0f; + size_t average_counter = 0; + for (size_t match_index = 0; match_index < nr_matches; ++match_index) + { + const float error = fabsf (depth_matches[match_index].first + best_z_translation - depth_matches[match_index].second); + + if (error <= inlier_threshold) + { + //average_depth += depth_matches[match_index].second; + average_depth += depth_matches[match_index].second - depth_matches[match_index].first; + ++average_counter; + } + } + average_depth /= static_cast (average_counter); + + detection.bounding_box.z = bounding_boxes_[template_id].z + average_depth;// - detection.bounding_box.depth/2.0f; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LineRGBD::removeOverlappingDetections () +{ + // compute overlap between each detection + const size_t nr_detections = detections_.size (); + Eigen::MatrixXf overlaps (nr_detections, nr_detections); + for (size_t detection_index_1 = 0; detection_index_1 < nr_detections; ++detection_index_1) + { + for (size_t detection_index_2 = detection_index_1+1; detection_index_2 < nr_detections; ++detection_index_2) + { + const float bounding_box_volume = detections_[detection_index_1].bounding_box.width + * detections_[detection_index_1].bounding_box.height + * detections_[detection_index_1].bounding_box.depth; + + if (detections_[detection_index_1].object_id != detections_[detection_index_2].object_id) + overlaps (detection_index_1, detection_index_2) = 0.0f; + else + overlaps (detection_index_1, detection_index_2) = computeBoundingBoxIntersectionVolume ( + detections_[detection_index_1].bounding_box, + detections_[detection_index_2].bounding_box) / bounding_box_volume; + } + } + + // create clusters of detections + std::vector detection_to_cluster_mapping (nr_detections, -1); + std::vector > clusters; + for (size_t detection_index = 0; detection_index < nr_detections; ++detection_index) + { + if (detection_to_cluster_mapping[detection_index] != -1) + continue; // already part of a cluster + + std::vector cluster; + const size_t cluster_id = clusters.size (); + + cluster.push_back (detection_index); + detection_to_cluster_mapping[detection_index] = static_cast (cluster_id); + + // check for detections which have sufficient overlap with a detection in the cluster + for (size_t cluster_index = 0; cluster_index < cluster.size (); ++cluster_index) + { + const size_t detection_index_1 = cluster[cluster_index]; + + for (size_t detection_index_2 = detection_index_1+1; detection_index_2 < nr_detections; ++detection_index_2) + { + if (detection_to_cluster_mapping[detection_index_2] != -1) + continue; // already part of a cluster + + if (overlaps (detection_index_1, detection_index_2) < intersection_volume_threshold_) + continue; // not enough overlap + + cluster.push_back (detection_index_2); + detection_to_cluster_mapping[detection_index_2] = static_cast (cluster_id); + } + } + + clusters.push_back (cluster); + } + + // compute detection representatives for every cluster + std::vector::Detection> clustered_detections; + + const size_t nr_clusters = clusters.size (); + for (size_t cluster_id = 0; cluster_id < nr_clusters; ++cluster_id) + { + std::vector & cluster = clusters[cluster_id]; + + float average_center_x = 0.0f; + float average_center_y = 0.0f; + float average_center_z = 0.0f; + float weight_sum = 0.0f; + + float best_response = 0.0f; + size_t best_detection_id = 0; + + float average_region_x = 0.0f; + float average_region_y = 0.0f; + + const size_t elements_in_cluster = cluster.size (); + for (size_t cluster_index = 0; cluster_index < elements_in_cluster; ++cluster_index) + { + const size_t detection_id = cluster[cluster_index]; + + const float weight = detections_[detection_id].response; + + if (weight > best_response) + { + best_response = weight; + best_detection_id = detection_id; + } + + const Detection & d = detections_[detection_id]; + const float p_center_x = d.bounding_box.x + d.bounding_box.width / 2.0f; + const float p_center_y = d.bounding_box.y + d.bounding_box.height / 2.0f; + const float p_center_z = d.bounding_box.z + d.bounding_box.depth / 2.0f; + + average_center_x += p_center_x * weight; + average_center_y += p_center_y * weight; + average_center_z += p_center_z * weight; + weight_sum += weight; + + average_region_x += float (detections_[detection_id].region.x) * weight; + average_region_y += float (detections_[detection_id].region.y) * weight; + } + + typename LineRGBD::Detection detection; + detection.template_id = detections_[best_detection_id].template_id; + detection.object_id = detections_[best_detection_id].object_id; + detection.detection_id = cluster_id; + detection.response = best_response; + + const float inv_weight_sum = 1.0f / weight_sum; + const float best_detection_bb_width = detections_[best_detection_id].bounding_box.width; + const float best_detection_bb_height = detections_[best_detection_id].bounding_box.height; + const float best_detection_bb_depth = detections_[best_detection_id].bounding_box.depth; + + detection.bounding_box.x = average_center_x * inv_weight_sum - best_detection_bb_width/2.0f; + detection.bounding_box.y = average_center_y * inv_weight_sum - best_detection_bb_height/2.0f; + detection.bounding_box.z = average_center_z * inv_weight_sum - best_detection_bb_depth/2.0f; + detection.bounding_box.width = best_detection_bb_width; + detection.bounding_box.height = best_detection_bb_height; + detection.bounding_box.depth = best_detection_bb_depth; + + detection.region.x = int (average_region_x * inv_weight_sum); + detection.region.y = int (average_region_y * inv_weight_sum); + detection.region.width = detections_[best_detection_id].region.width; + detection.region.height = detections_[best_detection_id].region.height; + + clustered_detections.push_back (detection); + } + + detections_ = clustered_detections; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::LineRGBD::computeBoundingBoxIntersectionVolume ( + const BoundingBoxXYZ &box1, const BoundingBoxXYZ &box2) +{ + const float x1_min = box1.x; + const float y1_min = box1.y; + const float z1_min = box1.z; + const float x1_max = box1.x + box1.width; + const float y1_max = box1.y + box1.height; + const float z1_max = box1.z + box1.depth; + + const float x2_min = box2.x; + const float y2_min = box2.y; + const float z2_min = box2.z; + const float x2_max = box2.x + box2.width; + const float y2_max = box2.y + box2.height; + const float z2_max = box2.z + box2.depth; + + const float xi_min = std::max (x1_min, x2_min); + const float yi_min = std::max (y1_min, y2_min); + const float zi_min = std::max (z1_min, z2_min); + + const float xi_max = std::min (x1_max, x2_max); + const float yi_max = std::min (y1_max, y2_max); + const float zi_max = std::min (z1_max, z2_max); + + const float intersection_width = xi_max - xi_min; + const float intersection_height = yi_max - yi_min; + const float intersection_depth = zi_max - zi_min; + + if (intersection_width <= 0.0f || intersection_height <= 0.0f || intersection_depth <= 0.0f) + return 0.0f; + + const float intersection_volume = intersection_width * intersection_height * intersection_depth; + + return (intersection_volume); +} + + +#endif // PCL_RECOGNITION_LINEMOD_LINE_RGBD_IMPL_HPP_ + diff --git a/pcl-1.7/pcl/recognition/impl/linemod/line_rgbd.hpp b/pcl-1.7/pcl/recognition/impl/linemod/line_rgbd.hpp new file mode 100644 index 0000000..39e0399 --- /dev/null +++ b/pcl-1.7/pcl/recognition/impl/linemod/line_rgbd.hpp @@ -0,0 +1,990 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RECOGNITION_LINEMOD_LINE_RGBD_IMPL_HPP_ +#define PCL_RECOGNITION_LINEMOD_LINE_RGBD_IMPL_HPP_ + +//#include +#include +#include +#include +#include +#ifdef _WIN32 +# include +# include +# define pcl_open _open +# define pcl_close(fd) _close(fd) +# define pcl_lseek(fd,offset,origin) _lseek(fd,offset,origin) +#else +#include +# include +# define pcl_open open +# define pcl_close(fd) close(fd) +# define pcl_lseek(fd,offset,origin) lseek(fd,offset,origin) +#endif + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::LineRGBD::readLTMHeader (int fd, pcl::io::TARHeader &header) +{ + // Read in the header + int result = static_cast (::read (fd, reinterpret_cast (&header.file_name[0]), 512)); + if (result == -1) + return (false); + + // We only support regular files for now. + // Addional file types in TAR include: hard links, symbolic links, device/special files, block devices, + // directories, and named pipes. + if (header.file_type[0] != '0' && header.file_type[0] != '\0') + return (false); + + // We only support USTAR version 0 files for now + if (std::string (header.ustar).substr (0, 5) != "ustar") + return (false); + + if (header.getFileSize () == 0) + return (false); + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::LineRGBD::loadTemplates (const std::string &file_name, const size_t object_id) +{ + // Open the file + int ltm_fd = pcl_open (file_name.c_str (), O_RDONLY); + if (ltm_fd == -1) + return (false); + + int ltm_offset = 0; + + pcl::io::TARHeader ltm_header; + PCDReader pcd_reader; + + std::string pcd_ext (".pcd"); + std::string sqmmt_ext (".sqmmt"); + + // While there still is an LTM header to be read + while (readLTMHeader (ltm_fd, ltm_header)) + { + ltm_offset += 512; + + // Search for extension + std::string chunk_name (ltm_header.file_name); + + std::transform (chunk_name.begin (), chunk_name.end (), chunk_name.begin (), ::tolower); + std::string::size_type it; + + if ((it = chunk_name.find (pcd_ext)) != std::string::npos && + (pcd_ext.size () - (chunk_name.size () - it)) == 0) + { + PCL_DEBUG ("[pcl::LineRGBD::loadTemplates] Reading and parsing %s as a PCD file.\n", chunk_name.c_str ()); + // Read the next PCD file + template_point_clouds_.resize (template_point_clouds_.size () + 1); + pcd_reader.read (file_name, template_point_clouds_[template_point_clouds_.size () - 1], ltm_offset); + + // Increment the offset for the next file + ltm_offset += (ltm_header.getFileSize ()) + (512 - ltm_header.getFileSize () % 512); + } + else if ((it = chunk_name.find (sqmmt_ext)) != std::string::npos && + (sqmmt_ext.size () - (chunk_name.size () - it)) == 0) + { + PCL_DEBUG ("[pcl::LineRGBD::loadTemplates] Reading and parsing %s as a SQMMT file.\n", chunk_name.c_str ()); + + unsigned int fsize = ltm_header.getFileSize (); + char *buffer = new char[fsize]; + int result = static_cast (::read (ltm_fd, reinterpret_cast (&buffer[0]), fsize)); + if (result == -1) + { + delete [] buffer; + PCL_ERROR ("[pcl::LineRGBD::loadTemplates] Error reading SQMMT template from file!\n"); + break; + } + + // Read a SQMMT file + std::stringstream stream (std::stringstream::in | std::stringstream::out | std::stringstream::binary); + stream.write (buffer, fsize); + SparseQuantizedMultiModTemplate sqmmt; + sqmmt.deserialize (stream); + + linemod_.addTemplate (sqmmt); + object_ids_.push_back (object_id); + + // Increment the offset for the next file + ltm_offset += (ltm_header.getFileSize ()) + (512 - ltm_header.getFileSize () % 512); + + delete [] buffer; + } + + if (static_cast (pcl_lseek (ltm_fd, ltm_offset, SEEK_SET)) < 0) + break; + } + + // Close the file + pcl_close (ltm_fd); + + // Compute 3D bounding boxes from the template point clouds + bounding_boxes_.resize (template_point_clouds_.size ()); + for (size_t i = 0; i < template_point_clouds_.size (); ++i) + { + PointCloud & template_point_cloud = template_point_clouds_[i]; + BoundingBoxXYZ & bb = bounding_boxes_[i]; + bb.x = bb.y = bb.z = std::numeric_limits::max (); + bb.width = bb.height = bb.depth = 0.0f; + + float center_x = 0.0f; + float center_y = 0.0f; + float center_z = 0.0f; + float min_x = std::numeric_limits::max (); + float min_y = std::numeric_limits::max (); + float min_z = std::numeric_limits::max (); + float max_x = -std::numeric_limits::max (); + float max_y = -std::numeric_limits::max (); + float max_z = -std::numeric_limits::max (); + size_t counter = 0; + for (size_t j = 0; j < template_point_cloud.size (); ++j) + { + const PointXYZRGBA & p = template_point_cloud.points[j]; + + if (!pcl_isfinite (p.x) || !pcl_isfinite (p.y) || !pcl_isfinite (p.z)) + continue; + + min_x = std::min (min_x, p.x); + min_y = std::min (min_y, p.y); + min_z = std::min (min_z, p.z); + max_x = std::max (max_x, p.x); + max_y = std::max (max_y, p.y); + max_z = std::max (max_z, p.z); + + center_x += p.x; + center_y += p.y; + center_z += p.z; + + ++counter; + } + + center_x /= static_cast (counter); + center_y /= static_cast (counter); + center_z /= static_cast (counter); + + bb.width = max_x - min_x; + bb.height = max_y - min_y; + bb.depth = max_z - min_z; + + bb.x = (min_x + bb.width / 2.0f) - center_x - bb.width / 2.0f; + bb.y = (min_y + bb.height / 2.0f) - center_y - bb.height / 2.0f; + bb.z = (min_z + bb.depth / 2.0f) - center_z - bb.depth / 2.0f; + + for (size_t j = 0; j < template_point_cloud.size (); ++j) + { + PointXYZRGBA p = template_point_cloud.points[j]; + + if (!pcl_isfinite (p.x) || !pcl_isfinite (p.y) || !pcl_isfinite (p.z)) + continue; + + p.x -= center_x; + p.y -= center_y; + p.z -= center_z; + + template_point_cloud.points[j] = p; + } + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::LineRGBD::createAndAddTemplate ( + pcl::PointCloud & cloud, + const size_t object_id, + const MaskMap & mask_xyz, + const MaskMap & mask_rgb, + const RegionXY & region) +{ + // add point cloud + template_point_clouds_.resize (template_point_clouds_.size () + 1); + pcl::copyPointCloud (cloud, template_point_clouds_[template_point_clouds_.size () - 1]); + + // add template + object_ids_.push_back (object_id); + + // Compute 3D bounding boxes from the template point clouds + bounding_boxes_.resize (template_point_clouds_.size ()); + { + const size_t i = template_point_clouds_.size () - 1; + + PointCloud & template_point_cloud = template_point_clouds_[i]; + BoundingBoxXYZ & bb = bounding_boxes_[i]; + bb.x = bb.y = bb.z = std::numeric_limits::max (); + bb.width = bb.height = bb.depth = 0.0f; + + float center_x = 0.0f; + float center_y = 0.0f; + float center_z = 0.0f; + float min_x = std::numeric_limits::max (); + float min_y = std::numeric_limits::max (); + float min_z = std::numeric_limits::max (); + float max_x = -std::numeric_limits::max (); + float max_y = -std::numeric_limits::max (); + float max_z = -std::numeric_limits::max (); + size_t counter = 0; + for (size_t j = 0; j < template_point_cloud.size (); ++j) + { + const PointXYZRGBA & p = template_point_cloud.points[j]; + + if (!pcl_isfinite (p.x) || !pcl_isfinite (p.y) || !pcl_isfinite (p.z)) + continue; + + min_x = std::min (min_x, p.x); + min_y = std::min (min_y, p.y); + min_z = std::min (min_z, p.z); + max_x = std::max (max_x, p.x); + max_y = std::max (max_y, p.y); + max_z = std::max (max_z, p.z); + + center_x += p.x; + center_y += p.y; + center_z += p.z; + + ++counter; + } + + center_x /= static_cast (counter); + center_y /= static_cast (counter); + center_z /= static_cast (counter); + + bb.width = max_x - min_x; + bb.height = max_y - min_y; + bb.depth = max_z - min_z; + + bb.x = (min_x + bb.width / 2.0f) - center_x - bb.width / 2.0f; + bb.y = (min_y + bb.height / 2.0f) - center_y - bb.height / 2.0f; + bb.z = (min_z + bb.depth / 2.0f) - center_z - bb.depth / 2.0f; + + for (size_t j = 0; j < template_point_cloud.size (); ++j) + { + PointXYZRGBA p = template_point_cloud.points[j]; + + if (!pcl_isfinite (p.x) || !pcl_isfinite (p.y) || !pcl_isfinite (p.z)) + continue; + + p.x -= center_x; + p.y -= center_y; + p.z -= center_z; + + template_point_cloud.points[j] = p; + } + } + + std::vector modalities; + modalities.push_back (&color_gradient_mod_); + modalities.push_back (&surface_normal_mod_); + + std::vector masks; + masks.push_back (const_cast (&mask_rgb)); + masks.push_back (const_cast (&mask_xyz)); + + return (linemod_.createAndAddTemplate (modalities, masks, region)); +} + + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::LineRGBD::addTemplate (const SparseQuantizedMultiModTemplate & sqmmt, pcl::PointCloud & cloud, size_t object_id) +{ + // add point cloud + template_point_clouds_.resize (template_point_clouds_.size () + 1); + pcl::copyPointCloud (cloud, template_point_clouds_[template_point_clouds_.size () - 1]); + + // add template + linemod_.addTemplate (sqmmt); + object_ids_.push_back (object_id); + + // Compute 3D bounding boxes from the template point clouds + bounding_boxes_.resize (template_point_clouds_.size ()); + { + const size_t i = template_point_clouds_.size () - 1; + + PointCloud & template_point_cloud = template_point_clouds_[i]; + BoundingBoxXYZ & bb = bounding_boxes_[i]; + bb.x = bb.y = bb.z = std::numeric_limits::max (); + bb.width = bb.height = bb.depth = 0.0f; + + float center_x = 0.0f; + float center_y = 0.0f; + float center_z = 0.0f; + float min_x = std::numeric_limits::max (); + float min_y = std::numeric_limits::max (); + float min_z = std::numeric_limits::max (); + float max_x = -std::numeric_limits::max (); + float max_y = -std::numeric_limits::max (); + float max_z = -std::numeric_limits::max (); + size_t counter = 0; + for (size_t j = 0; j < template_point_cloud.size (); ++j) + { + const PointXYZRGBA & p = template_point_cloud.points[j]; + + if (!pcl_isfinite (p.x) || !pcl_isfinite (p.y) || !pcl_isfinite (p.z)) + continue; + + min_x = std::min (min_x, p.x); + min_y = std::min (min_y, p.y); + min_z = std::min (min_z, p.z); + max_x = std::max (max_x, p.x); + max_y = std::max (max_y, p.y); + max_z = std::max (max_z, p.z); + + center_x += p.x; + center_y += p.y; + center_z += p.z; + + ++counter; + } + + center_x /= static_cast (counter); + center_y /= static_cast (counter); + center_z /= static_cast (counter); + + bb.width = max_x - min_x; + bb.height = max_y - min_y; + bb.depth = max_z - min_z; + + bb.x = (min_x + bb.width / 2.0f) - center_x - bb.width / 2.0f; + bb.y = (min_y + bb.height / 2.0f) - center_y - bb.height / 2.0f; + bb.z = (min_z + bb.depth / 2.0f) - center_z - bb.depth / 2.0f; + + for (size_t j = 0; j < template_point_cloud.size (); ++j) + { + PointXYZRGBA p = template_point_cloud.points[j]; + + if (!pcl_isfinite (p.x) || !pcl_isfinite (p.y) || !pcl_isfinite (p.z)) + continue; + + p.x -= center_x; + p.y -= center_y; + p.z -= center_z; + + template_point_cloud.points[j] = p; + } + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LineRGBD::detect ( + std::vector::Detection> & detections) +{ + std::vector modalities; + modalities.push_back (&color_gradient_mod_); + modalities.push_back (&surface_normal_mod_); + + std::vector linemod_detections; + linemod_.detectTemplates (modalities, linemod_detections); + + detections_.clear (); + detections_.reserve (linemod_detections.size ()); + detections.clear (); + detections.reserve (linemod_detections.size ()); + for (size_t detection_id = 0; detection_id < linemod_detections.size (); ++detection_id) + { + pcl::LINEMODDetection & linemod_detection = linemod_detections[detection_id]; + + typename pcl::LineRGBD::Detection detection; + detection.template_id = linemod_detection.template_id; + detection.object_id = object_ids_[linemod_detection.template_id]; + detection.detection_id = detection_id; + detection.response = linemod_detection.score; + + // compute bounding box: + // we assume that the bounding boxes of the templates are relative to the center of mass + // of the template points; so we also compute the center of mass of the points + // covered by the + + const pcl::SparseQuantizedMultiModTemplate & linemod_template = + linemod_.getTemplate (linemod_detection.template_id); + + const size_t start_x = std::max (linemod_detection.x, 0); + const size_t start_y = std::max (linemod_detection.y, 0); + const size_t end_x = std::min (static_cast (start_x + linemod_template.region.width), + static_cast (cloud_xyz_->width)); + const size_t end_y = std::min (static_cast (start_y + linemod_template.region.height), + static_cast (cloud_xyz_->height)); + + detection.region.x = linemod_detection.x; + detection.region.y = linemod_detection.y; + detection.region.width = linemod_template.region.width; + detection.region.height = linemod_template.region.height; + + //std::cerr << "detection region: " << linemod_detection.x << ", " + // << linemod_detection.y << ", " + // << linemod_template.region.width << ", " + // << linemod_template.region.height << std::endl; + + float center_x = 0.0f; + float center_y = 0.0f; + float center_z = 0.0f; + size_t counter = 0; + for (size_t row_index = start_y; row_index < end_y; ++row_index) + { + for (size_t col_index = start_x; col_index < end_x; ++col_index) + { + const PointXYZT & point = (*cloud_xyz_) (col_index, row_index); + + if (pcl_isfinite (point.x) && pcl_isfinite (point.y) && pcl_isfinite (point.z)) + { + center_x += point.x; + center_y += point.y; + center_z += point.z; + ++counter; + } + } + } + const float inv_counter = 1.0f / static_cast (counter); + center_x *= inv_counter; + center_y *= inv_counter; + center_z *= inv_counter; + + pcl::BoundingBoxXYZ template_bounding_box = bounding_boxes_[detection.template_id]; + + detection.bounding_box = template_bounding_box; + detection.bounding_box.x += center_x; + detection.bounding_box.y += center_y; + detection.bounding_box.z += center_z; + + detections_.push_back (detection); + } + + // refine detections along depth + refineDetectionsAlongDepth (); + //applyprojectivedepthicpondetections(); + + // remove overlaps + removeOverlappingDetections (); + + for (size_t detection_index = 0; detection_index < detections_.size (); ++detection_index) + { + detections.push_back (detections_[detection_index]); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LineRGBD::detectSemiScaleInvariant ( + std::vector::Detection> & detections, + const float min_scale, + const float max_scale, + const float scale_multiplier) +{ + std::vector modalities; + modalities.push_back (&color_gradient_mod_); + modalities.push_back (&surface_normal_mod_); + + std::vector linemod_detections; + linemod_.detectTemplatesSemiScaleInvariant (modalities, linemod_detections, min_scale, max_scale, scale_multiplier); + + detections_.clear (); + detections_.reserve (linemod_detections.size ()); + detections.clear (); + detections.reserve (linemod_detections.size ()); + for (size_t detection_id = 0; detection_id < linemod_detections.size (); ++detection_id) + { + pcl::LINEMODDetection & linemod_detection = linemod_detections[detection_id]; + + typename pcl::LineRGBD::Detection detection; + detection.template_id = linemod_detection.template_id; + detection.object_id = object_ids_[linemod_detection.template_id]; + detection.detection_id = detection_id; + detection.response = linemod_detection.score; + + // compute bounding box: + // we assume that the bounding boxes of the templates are relative to the center of mass + // of the template points; so we also compute the center of mass of the points + // covered by the + + const pcl::SparseQuantizedMultiModTemplate & linemod_template = + linemod_.getTemplate (linemod_detection.template_id); + + const size_t start_x = std::max (linemod_detection.x, 0); + const size_t start_y = std::max (linemod_detection.y, 0); + const size_t end_x = std::min (static_cast (start_x + linemod_template.region.width * linemod_detection.scale), + static_cast (cloud_xyz_->width)); + const size_t end_y = std::min (static_cast (start_y + linemod_template.region.height * linemod_detection.scale), + static_cast (cloud_xyz_->height)); + + detection.region.x = linemod_detection.x; + detection.region.y = linemod_detection.y; + detection.region.width = linemod_template.region.width * linemod_detection.scale; + detection.region.height = linemod_template.region.height * linemod_detection.scale; + + //std::cerr << "detection region: " << linemod_detection.x << ", " + // << linemod_detection.y << ", " + // << linemod_template.region.width << ", " + // << linemod_template.region.height << std::endl; + + float center_x = 0.0f; + float center_y = 0.0f; + float center_z = 0.0f; + size_t counter = 0; + for (size_t row_index = start_y; row_index < end_y; ++row_index) + { + for (size_t col_index = start_x; col_index < end_x; ++col_index) + { + const PointXYZT & point = (*cloud_xyz_) (col_index, row_index); + + if (pcl_isfinite (point.x) && pcl_isfinite (point.y) && pcl_isfinite (point.z)) + { + center_x += point.x; + center_y += point.y; + center_z += point.z; + ++counter; + } + } + } + const float inv_counter = 1.0f / static_cast (counter); + center_x *= inv_counter; + center_y *= inv_counter; + center_z *= inv_counter; + + pcl::BoundingBoxXYZ template_bounding_box = bounding_boxes_[detection.template_id]; + + detection.bounding_box = template_bounding_box; + detection.bounding_box.x += center_x; + detection.bounding_box.y += center_y; + detection.bounding_box.z += center_z; + + detections_.push_back (detection); + } + + // refine detections along depth + //refineDetectionsAlongDepth (); + //applyProjectiveDepthICPOnDetections(); + + // remove overlaps + removeOverlappingDetections (); + + for (size_t detection_index = 0; detection_index < detections_.size (); ++detection_index) + { + detections.push_back (detections_[detection_index]); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LineRGBD::computeTransformedTemplatePoints ( + const size_t detection_id, pcl::PointCloud &cloud) +{ + if (detection_id >= detections_.size ()) + PCL_ERROR ("ERROR pcl::LineRGBD::computeTransformedTemplatePoints - detection_id is out of bounds\n"); + + const size_t template_id = detections_[detection_id].template_id; + const pcl::PointCloud & template_point_cloud = template_point_clouds_[template_id]; + + const pcl::BoundingBoxXYZ & template_bounding_box = bounding_boxes_[template_id]; + const pcl::BoundingBoxXYZ & detection_bounding_box = detections_[detection_id].bounding_box; + + //std::cerr << "detection: " + // << detection_bounding_box.x << ", " + // << detection_bounding_box.y << ", " + // << detection_bounding_box.z << std::endl; + //std::cerr << "template: " + // << template_bounding_box.x << ", " + // << template_bounding_box.y << ", " + // << template_bounding_box.z << std::endl; + const float translation_x = detection_bounding_box.x - template_bounding_box.x; + const float translation_y = detection_bounding_box.y - template_bounding_box.y; + const float translation_z = detection_bounding_box.z - template_bounding_box.z; + + //std::cerr << "translation: " + // << translation_x << ", " + // << translation_y << ", " + // << translation_z << std::endl; + + const size_t nr_points = template_point_cloud.size (); + cloud.resize (nr_points); + cloud.width = template_point_cloud.width; + cloud.height = template_point_cloud.height; + for (size_t point_index = 0; point_index < nr_points; ++point_index) + { + pcl::PointXYZRGBA point = template_point_cloud.points[point_index]; + + point.x += translation_x; + point.y += translation_y; + point.z += translation_z; + + cloud.points[point_index] = point; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LineRGBD::refineDetectionsAlongDepth () +{ + const size_t nr_detections = detections_.size (); + for (size_t detection_index = 0; detection_index < nr_detections; ++detection_index) + { + typename LineRGBD::Detection & detection = detections_[detection_index]; + + // find depth with most valid points + const size_t start_x = detection.region.x; + const size_t start_y = detection.region.y; + const size_t end_x = start_x + detection.region.width; + const size_t end_y = start_y + detection.region.height; + + + float min_depth = std::numeric_limits::max (); + float max_depth = -std::numeric_limits::max (); + for (size_t row_index = start_y; row_index < end_y; ++row_index) + { + for (size_t col_index = start_x; col_index < end_x; ++col_index) + { + const PointXYZT & point = (*cloud_xyz_) (col_index, row_index); + + if (/*pcl_isfinite (point.x) && pcl_isfinite (point.y) && */pcl_isfinite (point.z)) + { + min_depth = std::min (min_depth, point.z); + max_depth = std::max (max_depth, point.z); + } + } + } + + const size_t nr_bins = 1000; + const float step_size = (max_depth - min_depth) / static_cast (nr_bins-1); + std::vector depth_bins (nr_bins, 0); + for (size_t row_index = start_y; row_index < end_y; ++row_index) + { + for (size_t col_index = start_x; col_index < end_x; ++col_index) + { + const PointXYZT & point = (*cloud_xyz_) (col_index, row_index); + + if (/*pcl_isfinite (point.x) && pcl_isfinite (point.y) && */pcl_isfinite (point.z)) + { + const size_t bin_index = static_cast ((point.z - min_depth) / step_size); + ++depth_bins[bin_index]; + } + } + } + + std::vector integral_depth_bins (nr_bins, 0); + + integral_depth_bins[0] = depth_bins[0]; + for (size_t bin_index = 1; bin_index < nr_bins; ++bin_index) + { + integral_depth_bins[bin_index] = depth_bins[bin_index] + integral_depth_bins[bin_index-1]; + } + + const size_t bb_depth_range = static_cast (detection.bounding_box.depth / step_size); + + size_t max_nr_points = 0; + size_t max_index = 0; + for (size_t bin_index = 0; (bin_index+bb_depth_range) < nr_bins; ++bin_index) + { + const size_t nr_points_in_range = integral_depth_bins[bin_index+bb_depth_range] - integral_depth_bins[bin_index]; + + if (nr_points_in_range > max_nr_points) + { + max_nr_points = nr_points_in_range; + max_index = bin_index; + } + } + + const float z = static_cast (max_index) * step_size + min_depth; + + detection.bounding_box.z = z; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LineRGBD::applyProjectiveDepthICPOnDetections () +{ + const size_t nr_detections = detections_.size (); + for (size_t detection_index = 0; detection_index < nr_detections; ++detection_index) + { + typename pcl::LineRGBD::Detection & detection = detections_[detection_index]; + + const size_t template_id = detection.template_id; + pcl::PointCloud & point_cloud = template_point_clouds_[template_id]; + + const size_t start_x = detection.region.x; + const size_t start_y = detection.region.y; + const size_t pc_width = point_cloud.width; + const size_t pc_height = point_cloud.height; + + std::vector > depth_matches; + for (size_t row_index = 0; row_index < pc_height; ++row_index) + { + for (size_t col_index = 0; col_index < pc_width; ++col_index) + { + const pcl::PointXYZRGBA & point_template = point_cloud (col_index, row_index); + const PointXYZT & point_input = (*cloud_xyz_) (col_index + start_x, row_index + start_y); + + if (!pcl_isfinite (point_template.z) || !pcl_isfinite (point_input.z)) + continue; + + depth_matches.push_back (std::make_pair (point_template.z, point_input.z)); + } + } + + // apply ransac on matches + const size_t nr_matches = depth_matches.size (); + const size_t nr_iterations = 100; // todo: should be a parameter... + const float inlier_threshold = 0.01f; // 5cm // todo: should be a parameter... + size_t best_nr_inliers = 0; + float best_z_translation = 0.0f; + for (size_t iteration_index = 0; iteration_index < nr_iterations; ++iteration_index) + { + const size_t rand_index = (rand () * nr_matches) / RAND_MAX; + + const float z_translation = depth_matches[rand_index].second - depth_matches[rand_index].first; + + size_t nr_inliers = 0; + for (size_t match_index = 0; match_index < nr_matches; ++match_index) + { + const float error = fabsf (depth_matches[match_index].first + z_translation - depth_matches[match_index].second); + + if (error <= inlier_threshold) + { + ++nr_inliers; + } + } + + if (nr_inliers > best_nr_inliers) + { + best_nr_inliers = nr_inliers; + best_z_translation = z_translation; + } + } + + float average_depth = 0.0f; + size_t average_counter = 0; + for (size_t match_index = 0; match_index < nr_matches; ++match_index) + { + const float error = fabsf (depth_matches[match_index].first + best_z_translation - depth_matches[match_index].second); + + if (error <= inlier_threshold) + { + //average_depth += depth_matches[match_index].second; + average_depth += depth_matches[match_index].second - depth_matches[match_index].first; + ++average_counter; + } + } + average_depth /= static_cast (average_counter); + + detection.bounding_box.z = bounding_boxes_[template_id].z + average_depth;// - detection.bounding_box.depth/2.0f; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::LineRGBD::removeOverlappingDetections () +{ + // compute overlap between each detection + const size_t nr_detections = detections_.size (); + Eigen::MatrixXf overlaps (nr_detections, nr_detections); + for (size_t detection_index_1 = 0; detection_index_1 < nr_detections; ++detection_index_1) + { + for (size_t detection_index_2 = detection_index_1+1; detection_index_2 < nr_detections; ++detection_index_2) + { + const float bounding_box_volume = detections_[detection_index_1].bounding_box.width + * detections_[detection_index_1].bounding_box.height + * detections_[detection_index_1].bounding_box.depth; + + if (detections_[detection_index_1].object_id != detections_[detection_index_2].object_id) + overlaps (detection_index_1, detection_index_2) = 0.0f; + else + overlaps (detection_index_1, detection_index_2) = computeBoundingBoxIntersectionVolume ( + detections_[detection_index_1].bounding_box, + detections_[detection_index_2].bounding_box) / bounding_box_volume; + } + } + + // create clusters of detections + std::vector detection_to_cluster_mapping (nr_detections, -1); + std::vector > clusters; + for (size_t detection_index = 0; detection_index < nr_detections; ++detection_index) + { + if (detection_to_cluster_mapping[detection_index] != -1) + continue; // already part of a cluster + + std::vector cluster; + const size_t cluster_id = clusters.size (); + + cluster.push_back (detection_index); + detection_to_cluster_mapping[detection_index] = static_cast (cluster_id); + + // check for detections which have sufficient overlap with a detection in the cluster + for (size_t cluster_index = 0; cluster_index < cluster.size (); ++cluster_index) + { + const size_t detection_index_1 = cluster[cluster_index]; + + for (size_t detection_index_2 = detection_index_1+1; detection_index_2 < nr_detections; ++detection_index_2) + { + if (detection_to_cluster_mapping[detection_index_2] != -1) + continue; // already part of a cluster + + if (overlaps (detection_index_1, detection_index_2) < intersection_volume_threshold_) + continue; // not enough overlap + + cluster.push_back (detection_index_2); + detection_to_cluster_mapping[detection_index_2] = static_cast (cluster_id); + } + } + + clusters.push_back (cluster); + } + + // compute detection representatives for every cluster + std::vector::Detection> clustered_detections; + + const size_t nr_clusters = clusters.size (); + for (size_t cluster_id = 0; cluster_id < nr_clusters; ++cluster_id) + { + std::vector & cluster = clusters[cluster_id]; + + float average_center_x = 0.0f; + float average_center_y = 0.0f; + float average_center_z = 0.0f; + float weight_sum = 0.0f; + + float best_response = 0.0f; + size_t best_detection_id = 0; + + float average_region_x = 0.0f; + float average_region_y = 0.0f; + + const size_t elements_in_cluster = cluster.size (); + for (size_t cluster_index = 0; cluster_index < elements_in_cluster; ++cluster_index) + { + const size_t detection_id = cluster[cluster_index]; + + const float weight = detections_[detection_id].response; + + if (weight > best_response) + { + best_response = weight; + best_detection_id = detection_id; + } + + const Detection & d = detections_[detection_id]; + const float p_center_x = d.bounding_box.x + d.bounding_box.width / 2.0f; + const float p_center_y = d.bounding_box.y + d.bounding_box.height / 2.0f; + const float p_center_z = d.bounding_box.z + d.bounding_box.depth / 2.0f; + + average_center_x += p_center_x * weight; + average_center_y += p_center_y * weight; + average_center_z += p_center_z * weight; + weight_sum += weight; + + average_region_x += float (detections_[detection_id].region.x) * weight; + average_region_y += float (detections_[detection_id].region.y) * weight; + } + + typename LineRGBD::Detection detection; + detection.template_id = detections_[best_detection_id].template_id; + detection.object_id = detections_[best_detection_id].object_id; + detection.detection_id = cluster_id; + detection.response = best_response; + + const float inv_weight_sum = 1.0f / weight_sum; + const float best_detection_bb_width = detections_[best_detection_id].bounding_box.width; + const float best_detection_bb_height = detections_[best_detection_id].bounding_box.height; + const float best_detection_bb_depth = detections_[best_detection_id].bounding_box.depth; + + detection.bounding_box.x = average_center_x * inv_weight_sum - best_detection_bb_width/2.0f; + detection.bounding_box.y = average_center_y * inv_weight_sum - best_detection_bb_height/2.0f; + detection.bounding_box.z = average_center_z * inv_weight_sum - best_detection_bb_depth/2.0f; + detection.bounding_box.width = best_detection_bb_width; + detection.bounding_box.height = best_detection_bb_height; + detection.bounding_box.depth = best_detection_bb_depth; + + detection.region.x = int (average_region_x * inv_weight_sum); + detection.region.y = int (average_region_y * inv_weight_sum); + detection.region.width = detections_[best_detection_id].region.width; + detection.region.height = detections_[best_detection_id].region.height; + + clustered_detections.push_back (detection); + } + + detections_ = clustered_detections; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::LineRGBD::computeBoundingBoxIntersectionVolume ( + const BoundingBoxXYZ &box1, const BoundingBoxXYZ &box2) +{ + const float x1_min = box1.x; + const float y1_min = box1.y; + const float z1_min = box1.z; + const float x1_max = box1.x + box1.width; + const float y1_max = box1.y + box1.height; + const float z1_max = box1.z + box1.depth; + + const float x2_min = box2.x; + const float y2_min = box2.y; + const float z2_min = box2.z; + const float x2_max = box2.x + box2.width; + const float y2_max = box2.y + box2.height; + const float z2_max = box2.z + box2.depth; + + const float xi_min = std::max (x1_min, x2_min); + const float yi_min = std::max (y1_min, y2_min); + const float zi_min = std::max (z1_min, z2_min); + + const float xi_max = std::min (x1_max, x2_max); + const float yi_max = std::min (y1_max, y2_max); + const float zi_max = std::min (z1_max, z2_max); + + const float intersection_width = xi_max - xi_min; + const float intersection_height = yi_max - yi_min; + const float intersection_depth = zi_max - zi_min; + + if (intersection_width <= 0.0f || intersection_height <= 0.0f || intersection_depth <= 0.0f) + return 0.0f; + + const float intersection_volume = intersection_width * intersection_height * intersection_depth; + + return (intersection_volume); +} + + +#endif // PCL_RECOGNITION_LINEMOD_LINE_RGBD_IMPL_HPP_ + diff --git a/pcl-1.7/pcl/recognition/impl/ransac_based/simple_octree.hpp b/pcl-1.7/pcl/recognition/impl/ransac_based/simple_octree.hpp new file mode 100644 index 0000000..9aa87e8 --- /dev/null +++ b/pcl-1.7/pcl/recognition/impl/ransac_based/simple_octree.hpp @@ -0,0 +1,403 @@ +/* + * simple_octree.hpp + * + * Created on: Mar 12, 2013 + * Author: papazov + */ + +#ifndef SIMPLE_OCTREE_HPP_ +#define SIMPLE_OCTREE_HPP_ + +//=============================================================================================================================== + +template inline +pcl::recognition::SimpleOctree::Node::Node () +: data_ (0), + parent_ (0), + children_(0) +{} + +//=============================================================================================================================== + +template inline +pcl::recognition::SimpleOctree::Node::~Node () +{ + this->deleteChildren (); + this->deleteData (); +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::Node::setCenter (const Scalar *c) +{ + center_[0] = c[0]; + center_[1] = c[1]; + center_[2] = c[2]; +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::Node::setBounds (const Scalar *b) +{ + bounds_[0] = b[0]; + bounds_[1] = b[1]; + bounds_[2] = b[2]; + bounds_[3] = b[3]; + bounds_[4] = b[4]; + bounds_[5] = b[5]; +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::Node::computeRadius () +{ + Scalar v[3] = {static_cast (0.5)*(bounds_[1]-bounds_[0]), + static_cast (0.5)*(bounds_[3]-bounds_[2]), + static_cast (0.5)*(bounds_[5]-bounds_[4])}; + + radius_ = static_cast (std::sqrt (v[0]*v[0] + v[1]*v[1] + v[2]*v[2])); +} + +//=============================================================================================================================== + +template inline bool +pcl::recognition::SimpleOctree::Node::createChildren () +{ + if ( children_ ) + return (false); + + Scalar bounds[6], center[3], childside = static_cast (0.5)*(bounds_[1]-bounds_[0]); + children_ = new Node[8]; + + // Compute bounds and center for child 0, i.e., for (0,0,0) + bounds[0] = bounds_[0]; bounds[1] = center_[0]; + bounds[2] = bounds_[2]; bounds[3] = center_[1]; + bounds[4] = bounds_[4]; bounds[5] = center_[2]; + // Compute the center of the new child + center[0] = 0.5f*(bounds[0] + bounds[1]); + center[1] = 0.5f*(bounds[2] + bounds[3]); + center[2] = 0.5f*(bounds[4] + bounds[5]); + // Save the results + children_[0].setBounds(bounds); + children_[0].setCenter(center); + + // Compute bounds and center for child 1, i.e., for (0,0,1) + bounds[4] = center_[2]; bounds[5] = bounds_[5]; + // Update the center + center[2] += childside; + // Save the results + children_[1].setBounds(bounds); + children_[1].setCenter(center); + + // Compute bounds and center for child 3, i.e., for (0,1,1) + bounds[2] = center_[1]; bounds[3] = bounds_[3]; + // Update the center + center[1] += childside; + // Save the results + children_[3].setBounds(bounds); + children_[3].setCenter(center); + + // Compute bounds and center for child 2, i.e., for (0,1,0) + bounds[4] = bounds_[4]; bounds[5] = center_[2]; + // Update the center + center[2] -= childside; + // Save the results + children_[2].setBounds(bounds); + children_[2].setCenter(center); + + // Compute bounds and center for child 6, i.e., for (1,1,0) + bounds[0] = center_[0]; bounds[1] = bounds_[1]; + // Update the center + center[0] += childside; + // Save the results + children_[6].setBounds(bounds); + children_[6].setCenter(center); + + // Compute bounds and center for child 7, i.e., for (1,1,1) + bounds[4] = center_[2]; bounds[5] = bounds_[5]; + // Update the center + center[2] += childside; + // Save the results + children_[7].setBounds(bounds); + children_[7].setCenter(center); + + // Compute bounds and center for child 5, i.e., for (1,0,1) + bounds[2] = bounds_[2]; bounds[3] = center_[1]; + // Update the center + center[1] -= childside; + // Save the results + children_[5].setBounds(bounds); + children_[5].setCenter(center); + + // Compute bounds and center for child 4, i.e., for (1,0,0) + bounds[4] = bounds_[4]; bounds[5] = center_[2]; + // Update the center + center[2] -= childside; + // Save the results + children_[4].setBounds(bounds); + children_[4].setCenter(center); + + for ( int i = 0 ; i < 8 ; ++i ) + { + children_[i].computeRadius(); + children_[i].setParent(this); + } + + return (true); +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::Node::deleteChildren () +{ + if ( children_ ) + { + delete[] children_; + children_ = 0; + } +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::Node::deleteData () +{ + if ( data_ ) + { + delete data_; + data_ = 0; + } +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::Node::makeNeighbors (Node* node) +{ + if ( !this->hasData () || !node->hasData () ) + return; + + this->full_leaf_neighbors_.insert (node); + node->full_leaf_neighbors_.insert (this); +} + +//=============================================================================================================================== + +template inline +pcl::recognition::SimpleOctree::SimpleOctree () +: tree_levels_ (0), + root_ (0) +{ +} + +//=============================================================================================================================== + +template inline +pcl::recognition::SimpleOctree::~SimpleOctree () +{ + this->clear (); +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::clear () +{ + if ( root_ ) + { + delete root_; + root_ = 0; + } + + full_leaves_.clear(); +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::build (const Scalar* bounds, Scalar voxel_size, + NodeDataCreator* node_data_creator) +{ + if ( voxel_size <= 0 ) + return; + + this->clear(); + + voxel_size_ = voxel_size; + node_data_creator_ = node_data_creator; + + Scalar extent = std::max (std::max (bounds[1]-bounds[0], bounds[3]-bounds[2]), bounds[5]-bounds[4]); + Scalar center[3] = {static_cast (0.5)*(bounds[0]+bounds[1]), + static_cast (0.5)*(bounds[2]+bounds[3]), + static_cast (0.5)*(bounds[4]+bounds[5])}; + + Scalar arg = extent/voxel_size; + + // Compute the number of tree levels + if ( arg > 1 ) + tree_levels_ = static_cast (ceil (log (arg)/log (2.0)) + 0.5); + else + tree_levels_ = 0; + + // Compute the number of octree levels and the bounds of the root + Scalar half_root_side = static_cast (0.5f*pow (2.0, tree_levels_)*voxel_size); + + // Determine the bounding box of the octree + bounds_[0] = center[0] - half_root_side; + bounds_[1] = center[0] + half_root_side; + bounds_[2] = center[1] - half_root_side; + bounds_[3] = center[1] + half_root_side; + bounds_[4] = center[2] - half_root_side; + bounds_[5] = center[2] + half_root_side; + + // Create and initialize the root + root_ = new Node (); + root_->setCenter (center); + root_->setBounds (bounds_); + root_->setParent (NULL); + root_->computeRadius (); +} + +//=============================================================================================================================== + +template inline +typename pcl::recognition::SimpleOctree::Node* +pcl::recognition::SimpleOctree::createLeaf (Scalar x, Scalar y, Scalar z) +{ + // Make sure that the input point is within the octree bounds + if ( x < bounds_[0] || x > bounds_[1] || + y < bounds_[2] || y > bounds_[3] || + z < bounds_[4] || z > bounds_[5] ) + { + return (NULL); + } + + Node* node = root_; + const Scalar *c; + int id; + + // Go down to the right leaf + for ( int l = 0 ; l < tree_levels_ ; ++l ) + { + node->createChildren (); + c = node->getCenter (); + id = 0; + + if ( x >= c[0] ) id |= 4; + if ( y >= c[1] ) id |= 2; + if ( z >= c[2] ) id |= 1; + + node = node->getChild (id); + } + + if ( !node->hasData () ) + { + node->setData (node_data_creator_->create (node)); + this->insertNeighbors (node); + full_leaves_.push_back (node); + } + + return (node); +} + +//=============================================================================================================================== + +template inline +typename pcl::recognition::SimpleOctree::Node* +pcl::recognition::SimpleOctree::getFullLeaf (int i, int j, int k) +{ + Scalar offset = 0.5f*voxel_size_; + Scalar p[3] = {bounds_[0] + offset + static_cast (i)*voxel_size_, + bounds_[2] + offset + static_cast (j)*voxel_size_, + bounds_[4] + offset + static_cast (k)*voxel_size_}; + + return (this->getFullLeaf (p[0], p[1], p[2])); +} + +//=============================================================================================================================== + +template inline +typename pcl::recognition::SimpleOctree::Node* +pcl::recognition::SimpleOctree::getFullLeaf (Scalar x, Scalar y, Scalar z) +{ + // Make sure that the input point is within the octree bounds + if ( x < bounds_[0] || x > bounds_[1] || + y < bounds_[2] || y > bounds_[3] || + z < bounds_[4] || z > bounds_[5] ) + { + return (NULL); + } + + Node* node = root_; + const Scalar *c; + int id; + + // Go down to the right leaf + for ( int l = 0 ; l < tree_levels_ ; ++l ) + { + if ( !node->hasChildren () ) + return (NULL); + + c = node->getCenter (); + id = 0; + + if ( x >= c[0] ) id |= 4; + if ( y >= c[1] ) id |= 2; + if ( z >= c[2] ) id |= 1; + + node = node->getChild (id); + } + + if ( !node->hasData () ) + return (NULL); + + return (node); +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::insertNeighbors (Node* node) +{ + const Scalar* c = node->getCenter (); + Scalar s = static_cast (0.5)*voxel_size_; + Node *neigh; + + neigh = this->getFullLeaf (c[0]+s, c[1]+s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1]+s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1]+s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1] , c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1] , c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1] , c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1]-s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1]-s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1]-s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + + neigh = this->getFullLeaf (c[0] , c[1]+s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0] , c[1]+s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0] , c[1]+s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0] , c[1] , c[2]+s); if ( neigh ) node->makeNeighbors (neigh); +//neigh = this->getFullLeaf (c[0] , c[1] , c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0] , c[1] , c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0] , c[1]-s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0] , c[1]-s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0] , c[1]-s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + + neigh = this->getFullLeaf (c[0]-s, c[1]+s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1]+s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1]+s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1] , c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1] , c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1] , c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1]-s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1]-s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1]-s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); +} + +//=============================================================================================================================== + +#endif /* SIMPLE_OCTREE_HPP_ */ diff --git a/pcl-1.7/pcl/recognition/impl/ransac_based/voxel_structure.hpp b/pcl-1.7/pcl/recognition/impl/ransac_based/voxel_structure.hpp new file mode 100644 index 0000000..3a142f0 --- /dev/null +++ b/pcl-1.7/pcl/recognition/impl/ransac_based/voxel_structure.hpp @@ -0,0 +1,156 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_RECOGNITION_VOXEL_STRUCTURE_HPP_ +#define PCL_RECOGNITION_VOXEL_STRUCTURE_HPP_ + +template inline void +pcl::recognition::VoxelStructure::build (const REAL bounds[6], int num_of_voxels[3]) +{ + this->clear(); + + // Copy the bounds + bounds_[0] = bounds[0]; + bounds_[1] = bounds[1]; + bounds_[2] = bounds[2]; + bounds_[3] = bounds[3]; + bounds_[4] = bounds[4]; + bounds_[5] = bounds[5]; + + num_of_voxels_[0] = num_of_voxels[0]; + num_of_voxels_[1] = num_of_voxels[1]; + num_of_voxels_[2] = num_of_voxels[2]; + num_of_voxels_xy_plane_ = num_of_voxels[0]*num_of_voxels[1]; + total_num_of_voxels_ = num_of_voxels_xy_plane_*num_of_voxels[2]; + + // Allocate memory for the voxels + voxels_ = new T[total_num_of_voxels_]; + + // Compute the spacing between the voxels in x, y and z direction + spacing_[0] = (bounds[1]-bounds[0])/static_cast (num_of_voxels[0]); + spacing_[1] = (bounds[3]-bounds[2])/static_cast (num_of_voxels[1]); + spacing_[2] = (bounds[5]-bounds[4])/static_cast (num_of_voxels[2]); + + // Compute the center of the voxel with integer coordinates (0, 0, 0) + min_center_[0] = bounds_[0] + static_cast (0.5)*spacing_[0]; + min_center_[1] = bounds_[2] + static_cast (0.5)*spacing_[1]; + min_center_[2] = bounds_[4] + static_cast (0.5)*spacing_[2]; +} + +//================================================================================================================================ + +template inline T* +pcl::recognition::VoxelStructure::getVoxel (const REAL p[3]) +{ + if ( p[0] < bounds_[0] || p[0] >= bounds_[1] || p[1] < bounds_[2] || p[1] >= bounds_[3] || p[2] < bounds_[4] || p[2] >= bounds_[5] ) + return NULL; + + int x = static_cast ((p[0] - bounds_[0])/spacing_[0]); + int y = static_cast ((p[1] - bounds_[2])/spacing_[1]); + int z = static_cast ((p[2] - bounds_[4])/spacing_[2]); + + return &voxels_[z*num_of_voxels_xy_plane_ + y*num_of_voxels_[0] + x]; +} + +//================================================================================================================================ + +template inline T* +pcl::recognition::VoxelStructure::getVoxel (int x, int y, int z) const +{ + if ( x < 0 || x >= num_of_voxels_[0] ) return NULL; + if ( y < 0 || y >= num_of_voxels_[1] ) return NULL; + if ( z < 0 || z >= num_of_voxels_[2] ) return NULL; + + return &voxels_[z*num_of_voxels_xy_plane_ + y*num_of_voxels_[0] + x]; +} + +//================================================================================================================================ + +template inline int +pcl::recognition::VoxelStructure::getNeighbors (const REAL* p, T **neighs) const +{ + if ( p[0] < bounds_[0] || p[0] >= bounds_[1] || p[1] < bounds_[2] || p[1] >= bounds_[3] || p[2] < bounds_[4] || p[2] >= bounds_[5] ) + return 0; + + const int x = static_cast ((p[0] - bounds_[0])/spacing_[0]); + const int y = static_cast ((p[1] - bounds_[2])/spacing_[1]); + const int z = static_cast ((p[2] - bounds_[4])/spacing_[2]); + + const int x_m1 = x-1, x_p1 = x+1; + const int y_m1 = y-1, y_p1 = y+1; + const int z_m1 = z-1, z_p1 = z+1; + + T* voxel; + int num_neighs = 0; + + voxel = this->getVoxel (x_p1, y_p1, z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y_p1, z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y_p1, z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y , z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y , z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y , z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y_m1, z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y_m1, z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y_m1, z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + + voxel = this->getVoxel (x , y_p1, z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y_p1, z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y_p1, z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y , z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y , z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y , z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y_m1, z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y_m1, z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y_m1, z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + + voxel = this->getVoxel (x_m1, y_p1, z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y_p1, z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y_p1, z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y , z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y , z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y , z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y_m1, z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y_m1, z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y_m1, z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + + return num_neighs; +} + +//================================================================================================================================ + +#endif // PCL_RECOGNITION_VOXEL_STRUCTURE_HPP_ diff --git a/pcl-1.7/pcl/recognition/impl/simple_octree.hpp b/pcl-1.7/pcl/recognition/impl/simple_octree.hpp new file mode 100644 index 0000000..9aa87e8 --- /dev/null +++ b/pcl-1.7/pcl/recognition/impl/simple_octree.hpp @@ -0,0 +1,403 @@ +/* + * simple_octree.hpp + * + * Created on: Mar 12, 2013 + * Author: papazov + */ + +#ifndef SIMPLE_OCTREE_HPP_ +#define SIMPLE_OCTREE_HPP_ + +//=============================================================================================================================== + +template inline +pcl::recognition::SimpleOctree::Node::Node () +: data_ (0), + parent_ (0), + children_(0) +{} + +//=============================================================================================================================== + +template inline +pcl::recognition::SimpleOctree::Node::~Node () +{ + this->deleteChildren (); + this->deleteData (); +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::Node::setCenter (const Scalar *c) +{ + center_[0] = c[0]; + center_[1] = c[1]; + center_[2] = c[2]; +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::Node::setBounds (const Scalar *b) +{ + bounds_[0] = b[0]; + bounds_[1] = b[1]; + bounds_[2] = b[2]; + bounds_[3] = b[3]; + bounds_[4] = b[4]; + bounds_[5] = b[5]; +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::Node::computeRadius () +{ + Scalar v[3] = {static_cast (0.5)*(bounds_[1]-bounds_[0]), + static_cast (0.5)*(bounds_[3]-bounds_[2]), + static_cast (0.5)*(bounds_[5]-bounds_[4])}; + + radius_ = static_cast (std::sqrt (v[0]*v[0] + v[1]*v[1] + v[2]*v[2])); +} + +//=============================================================================================================================== + +template inline bool +pcl::recognition::SimpleOctree::Node::createChildren () +{ + if ( children_ ) + return (false); + + Scalar bounds[6], center[3], childside = static_cast (0.5)*(bounds_[1]-bounds_[0]); + children_ = new Node[8]; + + // Compute bounds and center for child 0, i.e., for (0,0,0) + bounds[0] = bounds_[0]; bounds[1] = center_[0]; + bounds[2] = bounds_[2]; bounds[3] = center_[1]; + bounds[4] = bounds_[4]; bounds[5] = center_[2]; + // Compute the center of the new child + center[0] = 0.5f*(bounds[0] + bounds[1]); + center[1] = 0.5f*(bounds[2] + bounds[3]); + center[2] = 0.5f*(bounds[4] + bounds[5]); + // Save the results + children_[0].setBounds(bounds); + children_[0].setCenter(center); + + // Compute bounds and center for child 1, i.e., for (0,0,1) + bounds[4] = center_[2]; bounds[5] = bounds_[5]; + // Update the center + center[2] += childside; + // Save the results + children_[1].setBounds(bounds); + children_[1].setCenter(center); + + // Compute bounds and center for child 3, i.e., for (0,1,1) + bounds[2] = center_[1]; bounds[3] = bounds_[3]; + // Update the center + center[1] += childside; + // Save the results + children_[3].setBounds(bounds); + children_[3].setCenter(center); + + // Compute bounds and center for child 2, i.e., for (0,1,0) + bounds[4] = bounds_[4]; bounds[5] = center_[2]; + // Update the center + center[2] -= childside; + // Save the results + children_[2].setBounds(bounds); + children_[2].setCenter(center); + + // Compute bounds and center for child 6, i.e., for (1,1,0) + bounds[0] = center_[0]; bounds[1] = bounds_[1]; + // Update the center + center[0] += childside; + // Save the results + children_[6].setBounds(bounds); + children_[6].setCenter(center); + + // Compute bounds and center for child 7, i.e., for (1,1,1) + bounds[4] = center_[2]; bounds[5] = bounds_[5]; + // Update the center + center[2] += childside; + // Save the results + children_[7].setBounds(bounds); + children_[7].setCenter(center); + + // Compute bounds and center for child 5, i.e., for (1,0,1) + bounds[2] = bounds_[2]; bounds[3] = center_[1]; + // Update the center + center[1] -= childside; + // Save the results + children_[5].setBounds(bounds); + children_[5].setCenter(center); + + // Compute bounds and center for child 4, i.e., for (1,0,0) + bounds[4] = bounds_[4]; bounds[5] = center_[2]; + // Update the center + center[2] -= childside; + // Save the results + children_[4].setBounds(bounds); + children_[4].setCenter(center); + + for ( int i = 0 ; i < 8 ; ++i ) + { + children_[i].computeRadius(); + children_[i].setParent(this); + } + + return (true); +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::Node::deleteChildren () +{ + if ( children_ ) + { + delete[] children_; + children_ = 0; + } +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::Node::deleteData () +{ + if ( data_ ) + { + delete data_; + data_ = 0; + } +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::Node::makeNeighbors (Node* node) +{ + if ( !this->hasData () || !node->hasData () ) + return; + + this->full_leaf_neighbors_.insert (node); + node->full_leaf_neighbors_.insert (this); +} + +//=============================================================================================================================== + +template inline +pcl::recognition::SimpleOctree::SimpleOctree () +: tree_levels_ (0), + root_ (0) +{ +} + +//=============================================================================================================================== + +template inline +pcl::recognition::SimpleOctree::~SimpleOctree () +{ + this->clear (); +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::clear () +{ + if ( root_ ) + { + delete root_; + root_ = 0; + } + + full_leaves_.clear(); +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::build (const Scalar* bounds, Scalar voxel_size, + NodeDataCreator* node_data_creator) +{ + if ( voxel_size <= 0 ) + return; + + this->clear(); + + voxel_size_ = voxel_size; + node_data_creator_ = node_data_creator; + + Scalar extent = std::max (std::max (bounds[1]-bounds[0], bounds[3]-bounds[2]), bounds[5]-bounds[4]); + Scalar center[3] = {static_cast (0.5)*(bounds[0]+bounds[1]), + static_cast (0.5)*(bounds[2]+bounds[3]), + static_cast (0.5)*(bounds[4]+bounds[5])}; + + Scalar arg = extent/voxel_size; + + // Compute the number of tree levels + if ( arg > 1 ) + tree_levels_ = static_cast (ceil (log (arg)/log (2.0)) + 0.5); + else + tree_levels_ = 0; + + // Compute the number of octree levels and the bounds of the root + Scalar half_root_side = static_cast (0.5f*pow (2.0, tree_levels_)*voxel_size); + + // Determine the bounding box of the octree + bounds_[0] = center[0] - half_root_side; + bounds_[1] = center[0] + half_root_side; + bounds_[2] = center[1] - half_root_side; + bounds_[3] = center[1] + half_root_side; + bounds_[4] = center[2] - half_root_side; + bounds_[5] = center[2] + half_root_side; + + // Create and initialize the root + root_ = new Node (); + root_->setCenter (center); + root_->setBounds (bounds_); + root_->setParent (NULL); + root_->computeRadius (); +} + +//=============================================================================================================================== + +template inline +typename pcl::recognition::SimpleOctree::Node* +pcl::recognition::SimpleOctree::createLeaf (Scalar x, Scalar y, Scalar z) +{ + // Make sure that the input point is within the octree bounds + if ( x < bounds_[0] || x > bounds_[1] || + y < bounds_[2] || y > bounds_[3] || + z < bounds_[4] || z > bounds_[5] ) + { + return (NULL); + } + + Node* node = root_; + const Scalar *c; + int id; + + // Go down to the right leaf + for ( int l = 0 ; l < tree_levels_ ; ++l ) + { + node->createChildren (); + c = node->getCenter (); + id = 0; + + if ( x >= c[0] ) id |= 4; + if ( y >= c[1] ) id |= 2; + if ( z >= c[2] ) id |= 1; + + node = node->getChild (id); + } + + if ( !node->hasData () ) + { + node->setData (node_data_creator_->create (node)); + this->insertNeighbors (node); + full_leaves_.push_back (node); + } + + return (node); +} + +//=============================================================================================================================== + +template inline +typename pcl::recognition::SimpleOctree::Node* +pcl::recognition::SimpleOctree::getFullLeaf (int i, int j, int k) +{ + Scalar offset = 0.5f*voxel_size_; + Scalar p[3] = {bounds_[0] + offset + static_cast (i)*voxel_size_, + bounds_[2] + offset + static_cast (j)*voxel_size_, + bounds_[4] + offset + static_cast (k)*voxel_size_}; + + return (this->getFullLeaf (p[0], p[1], p[2])); +} + +//=============================================================================================================================== + +template inline +typename pcl::recognition::SimpleOctree::Node* +pcl::recognition::SimpleOctree::getFullLeaf (Scalar x, Scalar y, Scalar z) +{ + // Make sure that the input point is within the octree bounds + if ( x < bounds_[0] || x > bounds_[1] || + y < bounds_[2] || y > bounds_[3] || + z < bounds_[4] || z > bounds_[5] ) + { + return (NULL); + } + + Node* node = root_; + const Scalar *c; + int id; + + // Go down to the right leaf + for ( int l = 0 ; l < tree_levels_ ; ++l ) + { + if ( !node->hasChildren () ) + return (NULL); + + c = node->getCenter (); + id = 0; + + if ( x >= c[0] ) id |= 4; + if ( y >= c[1] ) id |= 2; + if ( z >= c[2] ) id |= 1; + + node = node->getChild (id); + } + + if ( !node->hasData () ) + return (NULL); + + return (node); +} + +//=============================================================================================================================== + +template inline void +pcl::recognition::SimpleOctree::insertNeighbors (Node* node) +{ + const Scalar* c = node->getCenter (); + Scalar s = static_cast (0.5)*voxel_size_; + Node *neigh; + + neigh = this->getFullLeaf (c[0]+s, c[1]+s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1]+s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1]+s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1] , c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1] , c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1] , c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1]-s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1]-s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]+s, c[1]-s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + + neigh = this->getFullLeaf (c[0] , c[1]+s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0] , c[1]+s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0] , c[1]+s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0] , c[1] , c[2]+s); if ( neigh ) node->makeNeighbors (neigh); +//neigh = this->getFullLeaf (c[0] , c[1] , c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0] , c[1] , c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0] , c[1]-s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0] , c[1]-s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0] , c[1]-s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + + neigh = this->getFullLeaf (c[0]-s, c[1]+s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1]+s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1]+s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1] , c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1] , c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1] , c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1]-s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1]-s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getFullLeaf (c[0]-s, c[1]-s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); +} + +//=============================================================================================================================== + +#endif /* SIMPLE_OCTREE_HPP_ */ diff --git a/pcl-1.7/pcl/recognition/impl/voxel_structure.hpp b/pcl-1.7/pcl/recognition/impl/voxel_structure.hpp new file mode 100644 index 0000000..3a142f0 --- /dev/null +++ b/pcl-1.7/pcl/recognition/impl/voxel_structure.hpp @@ -0,0 +1,156 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_RECOGNITION_VOXEL_STRUCTURE_HPP_ +#define PCL_RECOGNITION_VOXEL_STRUCTURE_HPP_ + +template inline void +pcl::recognition::VoxelStructure::build (const REAL bounds[6], int num_of_voxels[3]) +{ + this->clear(); + + // Copy the bounds + bounds_[0] = bounds[0]; + bounds_[1] = bounds[1]; + bounds_[2] = bounds[2]; + bounds_[3] = bounds[3]; + bounds_[4] = bounds[4]; + bounds_[5] = bounds[5]; + + num_of_voxels_[0] = num_of_voxels[0]; + num_of_voxels_[1] = num_of_voxels[1]; + num_of_voxels_[2] = num_of_voxels[2]; + num_of_voxels_xy_plane_ = num_of_voxels[0]*num_of_voxels[1]; + total_num_of_voxels_ = num_of_voxels_xy_plane_*num_of_voxels[2]; + + // Allocate memory for the voxels + voxels_ = new T[total_num_of_voxels_]; + + // Compute the spacing between the voxels in x, y and z direction + spacing_[0] = (bounds[1]-bounds[0])/static_cast (num_of_voxels[0]); + spacing_[1] = (bounds[3]-bounds[2])/static_cast (num_of_voxels[1]); + spacing_[2] = (bounds[5]-bounds[4])/static_cast (num_of_voxels[2]); + + // Compute the center of the voxel with integer coordinates (0, 0, 0) + min_center_[0] = bounds_[0] + static_cast (0.5)*spacing_[0]; + min_center_[1] = bounds_[2] + static_cast (0.5)*spacing_[1]; + min_center_[2] = bounds_[4] + static_cast (0.5)*spacing_[2]; +} + +//================================================================================================================================ + +template inline T* +pcl::recognition::VoxelStructure::getVoxel (const REAL p[3]) +{ + if ( p[0] < bounds_[0] || p[0] >= bounds_[1] || p[1] < bounds_[2] || p[1] >= bounds_[3] || p[2] < bounds_[4] || p[2] >= bounds_[5] ) + return NULL; + + int x = static_cast ((p[0] - bounds_[0])/spacing_[0]); + int y = static_cast ((p[1] - bounds_[2])/spacing_[1]); + int z = static_cast ((p[2] - bounds_[4])/spacing_[2]); + + return &voxels_[z*num_of_voxels_xy_plane_ + y*num_of_voxels_[0] + x]; +} + +//================================================================================================================================ + +template inline T* +pcl::recognition::VoxelStructure::getVoxel (int x, int y, int z) const +{ + if ( x < 0 || x >= num_of_voxels_[0] ) return NULL; + if ( y < 0 || y >= num_of_voxels_[1] ) return NULL; + if ( z < 0 || z >= num_of_voxels_[2] ) return NULL; + + return &voxels_[z*num_of_voxels_xy_plane_ + y*num_of_voxels_[0] + x]; +} + +//================================================================================================================================ + +template inline int +pcl::recognition::VoxelStructure::getNeighbors (const REAL* p, T **neighs) const +{ + if ( p[0] < bounds_[0] || p[0] >= bounds_[1] || p[1] < bounds_[2] || p[1] >= bounds_[3] || p[2] < bounds_[4] || p[2] >= bounds_[5] ) + return 0; + + const int x = static_cast ((p[0] - bounds_[0])/spacing_[0]); + const int y = static_cast ((p[1] - bounds_[2])/spacing_[1]); + const int z = static_cast ((p[2] - bounds_[4])/spacing_[2]); + + const int x_m1 = x-1, x_p1 = x+1; + const int y_m1 = y-1, y_p1 = y+1; + const int z_m1 = z-1, z_p1 = z+1; + + T* voxel; + int num_neighs = 0; + + voxel = this->getVoxel (x_p1, y_p1, z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y_p1, z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y_p1, z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y , z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y , z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y , z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y_m1, z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y_m1, z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_p1, y_m1, z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + + voxel = this->getVoxel (x , y_p1, z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y_p1, z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y_p1, z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y , z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y , z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y , z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y_m1, z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y_m1, z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x , y_m1, z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + + voxel = this->getVoxel (x_m1, y_p1, z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y_p1, z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y_p1, z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y , z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y , z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y , z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y_m1, z_p1); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y_m1, z ); if ( voxel ) neighs[num_neighs++] = voxel; + voxel = this->getVoxel (x_m1, y_m1, z_m1); if ( voxel ) neighs[num_neighs++] = voxel; + + return num_neighs; +} + +//================================================================================================================================ + +#endif // PCL_RECOGNITION_VOXEL_STRUCTURE_HPP_ diff --git a/pcl-1.7/pcl/recognition/implicit_shape_model.h b/pcl-1.7/pcl/recognition/implicit_shape_model.h new file mode 100644 index 0000000..7acd17d --- /dev/null +++ b/pcl-1.7/pcl/recognition/implicit_shape_model.h @@ -0,0 +1,629 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_IMPLICIT_SHAPE_MODEL_H_ +#define PCL_IMPLICIT_SHAPE_MODEL_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief This struct is used for storing peak. */ + struct ISMPeak + { + /** \brief Point were this peak is located. */ + PCL_ADD_POINT4D; + + /** \brief Density of this peak. */ + double density; + + /** \brief Determines which class this peak belongs. */ + int class_id; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + } EIGEN_ALIGN16; + + namespace features + { + /** \brief This class is used for storing, analyzing and manipulating votes + * obtained from ISM algorithm. */ + template + class PCL_EXPORTS ISMVoteList + { + public: + + /** \brief Empty constructor with member variables initialization. */ + ISMVoteList (); + + /** \brief virtual descriptor. */ + virtual + ~ISMVoteList (); + + /** \brief This method simply adds another vote to the list. + * \param[in] in_vote vote to add + * \param[in] vote_origin origin of the added vote + * \param[in] in_class class for which this vote is cast + */ + void + addVote (pcl::InterestPoint& in_vote, const PointT &vote_origin, int in_class); + + /** \brief Returns the colored cloud that consists of votes for center (blue points) and + * initial point cloud (if it was passed). + * \param[in] cloud cloud that needs to be merged with votes for visualizing. */ + typename pcl::PointCloud::Ptr + getColoredCloud (typename pcl::PointCloud::Ptr cloud = 0); + + /** \brief This method finds the strongest peaks (points were density has most higher values). + * It is based on the non maxima supression principles. + * \param[out] out_peaks it will contain the strongest peaks + * \param[in] in_class_id class of interest for which peaks are evaluated + * \param[in] in_non_maxima_radius non maxima supression radius. The shapes radius is recommended for this value. + * \param in_sigma + */ + void + findStrongestPeaks (std::vector > &out_peaks, int in_class_id, double in_non_maxima_radius, double in_sigma); + + /** \brief Returns the density at the specified point. + * \param[in] point point of interest + * \param[in] sigma_dist + */ + double + getDensityAtPoint (const PointT &point, double sigma_dist); + + /** \brief This method simply returns the number of votes. */ + unsigned int + getNumberOfVotes (); + + protected: + + /** \brief this method is simply setting up the search tree. */ + void + validateTree (); + + Eigen::Vector3f + shiftMean (const Eigen::Vector3f& snapPt, const double in_dSigmaDist); + + protected: + + /** \brief Stores all votes. */ + pcl::PointCloud::Ptr votes_; + + /** \brief Signalizes if the tree is valid. */ + bool tree_is_valid_; + + /** \brief Stores the origins of the votes. */ + typename pcl::PointCloud::Ptr votes_origins_; + + /** \brief Stores classes for which every single vote was cast. */ + std::vector votes_class_; + + /** \brief Stores the search tree. */ + pcl::KdTreeFLANN::Ptr tree_; + + /** \brief Stores neighbours indices. */ + std::vector k_ind_; + + /** \brief Stores square distances to the corresponding neighbours. */ + std::vector k_sqr_dist_; + }; + + /** \brief The assignment of this structure is to store the statistical/learned weights and other information + * of the trained Implict Shape Model algorithm. + */ + struct PCL_EXPORTS ISMModel + { + /** \brief Simple constructor that initializes the structure. */ + ISMModel (); + + /** \brief Copy constructor for deep copy. */ + ISMModel (ISMModel const & copy); + + /** Destructor that frees memory. */ + virtual + ~ISMModel (); + + /** \brief This method simply saves the trained model for later usage. + * \param[in] file_name path to file for saving model + */ + bool + saveModelToFile (std::string& file_name); + + /** \brief This method loads the trained model from file. + * \param[in] file_name path to file which stores trained model + */ + bool + loadModelFromfile (std::string& file_name); + + /** \brief this method resets all variables and frees memory. */ + void + reset (); + + /** Operator overloading for deep copy. */ + ISMModel & operator = (const ISMModel& other); + + /** \brief Stores statistical weights. */ + std::vector > statistical_weights_; + + /** \brief Stores learned weights. */ + std::vector learned_weights_; + + /** \brief Stores the class label for every direction. */ + std::vector classes_; + + /** \brief Stores the sigma value for each class. This values were used to compute the learned weights. */ + std::vector sigmas_; + + /** \brief Stores the directions to objects center for each visual word. */ + Eigen::MatrixXf directions_to_center_; + + /** \brief Stores the centers of the clusters that were obtained during the visual words clusterization. */ + Eigen::MatrixXf clusters_centers_; + + /** \brief This is an array of clusters. Each cluster stores the indices of the visual words that it contains. */ + std::vector > clusters_; + + /** \brief Stores the number of classes. */ + unsigned int number_of_classes_; + + /** \brief Stores the number of visual words. */ + unsigned int number_of_visual_words_; + + /** \brief Stores the number of clusters. */ + unsigned int number_of_clusters_; + + /** \brief Stores descriptors dimension. */ + unsigned int descriptors_dimension_; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } + + namespace ism + { + /** \brief This class implements Implicit Shape Model algorithm described in + * "Hough Transforms and 3D SURF for robust three dimensional classication" + * by Jan Knopp1, Mukta Prasad, Geert Willems1, Radu Timofte, and Luc Van Gool. + * It has two main member functions. One for training, using the data for which we know + * which class it belongs to. And second for investigating a cloud for the presence + * of the class of interest. + * Implementation of the ISM algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classication" + * by Jan Knopp, Mukta Prasad, Geert Willems, Radu Timofte, and Luc Van Gool + * + * Authors: Roman Shapovalov, Alexander Velizhev, Sergey Ushakov + */ + template + class PCL_EXPORTS ImplicitShapeModelEstimation + { + public: + + typedef boost::shared_ptr ISMModelPtr; + + protected: + + /** \brief This structure stores the information about the keypoint. */ + struct PCL_EXPORTS LocationInfo + { + /** \brief Location info constructor. + * \param[in] model_num number of training model. + * \param[in] dir_to_center expected direction to center + * \param[in] origin initial point + * \param[in] normal normal of the initial point + */ + LocationInfo (unsigned int model_num, const PointT& dir_to_center, const PointT& origin, const NormalT& normal) : + model_num_ (model_num), + dir_to_center_ (dir_to_center), + point_ (origin), + normal_ (normal) {}; + + /** \brief Tells from which training model this keypoint was extracted. */ + unsigned int model_num_; + + /** \brief Expected direction to center for this keypoint. */ + PointT dir_to_center_; + + /** \brief Stores the initial point. */ + PointT point_; + + /** \brief Stores the normal of the initial point. */ + NormalT normal_; + }; + + /** \brief This structure is used for determining the end of the + * k-means clustering process. */ + typedef struct PCL_EXPORTS TC + { + enum + { + COUNT = 1, + EPS = 2 + }; + + /** \brief Termination criteria constructor. + * \param[in] type defines the condition of termination(max iter., desired accuracy) + * \param[in] max_count defines the max number of iterations + * \param[in] epsilon defines the desired accuracy + */ + TC(int type, int max_count, float epsilon) : + type_ (type), + max_count_ (max_count), + epsilon_ (epsilon) {}; + + /** \brief Flag that determines when the k-means clustering must be stopped. + * If type_ equals COUNT then it must be stopped when the max number of iterations will be + * reached. If type_ eaquals EPS then it must be stopped when the desired accuracy will be reached. + * These flags can be used together, in that case the clustering will be finished when one of these + * conditions will be reached. + */ + int type_; + + /** \brief Defines maximum number of iterations for k-means clustering. */ + int max_count_; + + /** \brief Defines the accuracy for k-means clustering. */ + float epsilon_; + } TermCriteria; + + /** \brief Structure for storing the visual word. */ + struct PCL_EXPORTS VisualWordStat + { + /** \brief Empty constructor with member variables initialization. */ + VisualWordStat () : + class_ (-1), + learned_weight_ (0.0f), + dir_to_center_ (0.0f, 0.0f, 0.0f) {}; + + /** \brief Which class this vote belongs. */ + int class_; + + /** \brief Weight of the vote. */ + float learned_weight_; + + /** \brief Expected direction to center. */ + pcl::PointXYZ dir_to_center_; + }; + + public: + + /** \brief Simple constructor that initializes everything. */ + ImplicitShapeModelEstimation (); + + /** \brief Simple destructor. */ + virtual + ~ImplicitShapeModelEstimation (); + + /** \brief This method simply returns the clouds that were set as the training clouds. */ + std::vector::Ptr> + getTrainingClouds (); + + /** \brief Allows to set clouds for training the ISM model. + * \param[in] training_clouds array of point clouds for training + */ + void + setTrainingClouds (const std::vector< typename pcl::PointCloud::Ptr >& training_clouds); + + /** \brief Returns the array of classes that indicates which class the corresponding training cloud belongs. */ + std::vector + getTrainingClasses (); + + /** \brief Allows to set the class labels for the corresponding training clouds. + * \param[in] training_classes array of class labels + */ + void + setTrainingClasses (const std::vector& training_classes); + + /** \brief This method returns the coresponding cloud of normals for every training point cloud. */ + std::vector::Ptr> + getTrainingNormals (); + + /** \brief Allows to set normals for the training clouds that were passed through setTrainingClouds method. + * \param[in] training_normals array of clouds, each cloud is the cloud of normals + */ + void + setTrainingNormals (const std::vector< typename pcl::PointCloud::Ptr >& training_normals); + + /** \brief Returns the sampling size used for cloud simplification. */ + float + getSamplingSize (); + + /** \brief Changes the sampling size used for cloud simplification. + * \param[in] sampling_size desired size of grid bin + */ + void + setSamplingSize (float sampling_size); + + /** \brief Returns the current feature estimator used for extraction of the descriptors. */ + boost::shared_ptr > > + getFeatureEstimator (); + + /** \brief Changes the feature estimator. + * \param[in] feature feature estimator that will be used to extract the descriptors. + * Note that it must be fully initialized and configured. + */ + void + setFeatureEstimator (boost::shared_ptr > > feature); + + /** \brief Returns the number of clusters used for descriptor clustering. */ + unsigned int + getNumberOfClusters (); + + /** \brief Changes the number of clusters. + * \param num_of_clusters desired number of clusters + */ + void + setNumberOfClusters (unsigned int num_of_clusters); + + /** \brief Returns the array of sigma values. */ + std::vector + getSigmaDists (); + + /** \brief This method allows to set the value of sigma used for calculating the learned weights for every single class. + * \param[in] training_sigmas new sigmas for every class. If you want these values to be computed automatically, + * just pass the empty array. The automatic regime calculates the maximum distance between the objects points and takes 10% of + * this value as recomended in the article. If there are several objects of the same class, + * then it computes the average maximum distance and takes 10%. Note that each class has its own sigma value. + */ + void + setSigmaDists (const std::vector& training_sigmas); + + /** \brief Returns the state of Nvot coeff from [Knopp et al., 2010, (4)], + * if set to false then coeff is taken as 1.0. It is just a kind of heuristic. + * The default behavior is as in the article. So you can ignore this if you want. + */ + bool + getNVotState (); + + /** \brief Changes the state of the Nvot coeff from [Knopp et al., 2010, (4)]. + * \param[in] state desired state, if false then Nvot is taken as 1.0 + */ + void + setNVotState (bool state); + + /** \brief This method performs training and forms a visual vocabulary. It returns a trained model that + * can be saved to file for later usage. + * \param[out] trained_model trained model + */ + bool + trainISM (ISMModelPtr& trained_model); + + /** \brief This function is searching for the class of interest in a given cloud + * and returns the list of votes. + * \param[in] model trained model which will be used for searching the objects + * \param[in] in_cloud input cloud that need to be investigated + * \param[in] in_normals cloud of normals coresponding to the input cloud + * \param[in] in_class_of_interest class which we are looking for + */ + boost::shared_ptr > + findObjects (ISMModelPtr model, typename pcl::PointCloud::Ptr in_cloud, typename pcl::PointCloud::Ptr in_normals, int in_class_of_interest); + + protected: + + /** \brief Extracts the descriptors from the input clouds. + * \param[out] histograms it will store the descriptors for each key point + * \param[out] locations it will contain the comprehensive information (such as direction, initial keypoint) + * for the corresponding descriptors + */ + bool + extractDescriptors (std::vector >& histograms, + std::vector >& locations); + + /** \brief This method performs descriptor clustering. + * \param[in] histograms descriptors to cluster + * \param[out] labels it contains labels for each descriptor + * \param[out] clusters_centers stores the centers of clusters + */ + bool + clusterDescriptors (std::vector< pcl::Histogram >& histograms, Eigen::MatrixXi& labels, Eigen::MatrixXf& clusters_centers); + + /** \brief This method calculates the value of sigma used for calculating the learned weights for every single class. + * \param[out] sigmas computed sigmas. + */ + void + calculateSigmas (std::vector& sigmas); + + /** \brief This function forms a visual vocabulary and evaluates weights + * described in [Knopp et al., 2010, (5)]. + * \param[in] locations array containing description of each keypoint: its position, which cloud belongs + * and expected direction to center + * \param[in] labels labels that were obtained during k-means clustering + * \param[in] sigmas array of sigmas for each class + * \param[in] clusters clusters that were obtained during k-means clustering + * \param[out] statistical_weights stores the computed statistical weights + * \param[out] learned_weights stores the computed learned weights + */ + void + calculateWeights (const std::vector< LocationInfo, Eigen::aligned_allocator >& locations, + const Eigen::MatrixXi &labels, + std::vector& sigmas, + std::vector >& clusters, + std::vector >& statistical_weights, + std::vector& learned_weights); + + /** \brief Simplifies the cloud using voxel grid principles. + * \param[in] in_point_cloud cloud that need to be simplified + * \param[in] in_normal_cloud normals of the cloud that need to be simplified + * \param[out] out_sampled_point_cloud simplified cloud + * \param[out] out_sampled_normal_cloud and the corresponding normals + */ + void + simplifyCloud (typename pcl::PointCloud::ConstPtr in_point_cloud, + typename pcl::PointCloud::ConstPtr in_normal_cloud, + typename pcl::PointCloud::Ptr out_sampled_point_cloud, + typename pcl::PointCloud::Ptr out_sampled_normal_cloud); + + /** \brief This method simply shifts the clouds points relative to the passed point. + * \param[in] in_cloud cloud to shift + * \param[in] shift_point point relative to which the cloud will be shifted + */ + void + shiftCloud (typename pcl::PointCloud::Ptr in_cloud, Eigen::Vector3f shift_point); + + /** \brief This method simply computes the rotation matrix, so that the given normal + * would match the Y axis after the transformation. This is done because the algorithm needs to be invariant + * to the affine transformations. + * \param[in] in_normal normal for which the rotation matrix need to be computed + */ + Eigen::Matrix3f + alignYCoordWithNormal (const NormalT& in_normal); + + /** \brief This method applies transform set in in_transform to vector io_vector. + * \param[in] io_vec vector that need to be transformed + * \param[in] in_transform matrix that contains the transformation + */ + void + applyTransform (Eigen::Vector3f& io_vec, const Eigen::Matrix3f& in_transform); + + /** \brief This method estimates features for the given point cloud. + * \param[in] sampled_point_cloud sampled point cloud for which the features must be computed + * \param[in] normal_cloud normals for the original point cloud + * \param[out] feature_cloud it will store the computed histograms (features) for the given cloud + */ + void + estimateFeatures (typename pcl::PointCloud::Ptr sampled_point_cloud, + typename pcl::PointCloud::Ptr normal_cloud, + typename pcl::PointCloud >::Ptr feature_cloud); + + /** \brief Performs K-means clustering. + * \param[in] points_to_cluster points to cluster + * \param[in] number_of_clusters desired number of clusters + * \param[out] io_labels output parameter, which stores the label for each point + * \param[in] criteria defines when the computational process need to be finished. For example if the + * desired accuracy is achieved or the iteration number exceeds given value + * \param[in] attempts number of attempts to compute clustering + * \param[in] flags if set to USE_INITIAL_LABELS then initial approximation of labels is taken from io_labels + * \param[out] cluster_centers it will store the cluster centers + */ + double + computeKMeansClustering (const Eigen::MatrixXf& points_to_cluster, + int number_of_clusters, + Eigen::MatrixXi& io_labels, + TermCriteria criteria, + int attempts, + int flags, + Eigen::MatrixXf& cluster_centers); + + /** \brief Generates centers for clusters as described in + * Arthur, David and Sergei Vassilvitski (2007) k-means++: The Advantages of Careful Seeding. + * \param[in] data points to cluster + * \param[out] out_centers it will contain generated centers + * \param[in] number_of_clusters defines the number of desired cluster centers + * \param[in] trials number of trials to generate a center + */ + void + generateCentersPP (const Eigen::MatrixXf& data, + Eigen::MatrixXf& out_centers, + int number_of_clusters, + int trials); + + /** \brief Generates random center for cluster. + * \param[in] boxes contains min and max values for each dimension + * \param[out] center it will the contain generated center + */ + void + generateRandomCenter (const std::vector& boxes, Eigen::VectorXf& center); + + /** \brief Computes the square distance beetween two vectors. + * \param[in] vec_1 first vector + * \param[in] vec_2 second vector + */ + float + computeDistance (Eigen::VectorXf& vec_1, Eigen::VectorXf& vec_2); + + /** \brief Forbids the assignment operator. */ + ImplicitShapeModelEstimation& + operator= (const ImplicitShapeModelEstimation&); + + protected: + + /** \brief Stores the clouds used for training. */ + std::vector::Ptr> training_clouds_; + + /** \brief Stores the class number for each cloud from training_clouds_. */ + std::vector training_classes_; + + /** \brief Stores the normals for each training cloud. */ + std::vector::Ptr> training_normals_; + + /** \brief This array stores the sigma values for each training class. If this array has a size equals 0, then + * sigma values will be calculated automatically. + */ + std::vector training_sigmas_; + + /** \brief This value is used for the simplification. It sets the size of grid bin. */ + float sampling_size_; + + /** \brief Stores the feature estimator. */ + boost::shared_ptr > > feature_estimator_; + + /** \brief Number of clusters, is used for clustering descriptors during the training. */ + unsigned int number_of_clusters_; + + /** \brief If set to false then Nvot coeff from [Knopp et al., 2010, (4)] is equal 1.0. */ + bool n_vot_ON_; + + /** \brief This const value is used for indicating that for k-means clustering centers must + * be generated as described in + * Arthur, David and Sergei Vassilvitski (2007) k-means++: The Advantages of Careful Seeding. */ + static const int PP_CENTERS = 2; + + /** \brief This const value is used for indicating that input labels must be taken as the + * initial approximation for k-means clustering. */ + static const int USE_INITIAL_LABELS = 1; + }; + } +} + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::ISMPeak, + (float, x, x) + (float, y, y) + (float, z, z) + (float, density, ism_density) + (float, class_id, ism_class_id) +) + +#endif //#ifndef PCL_IMPLICIT_SHAPE_MODEL_H_ diff --git a/pcl-1.7/pcl/recognition/line_rgbd.h b/pcl-1.7/pcl/recognition/line_rgbd.h new file mode 100644 index 0000000..8b1b3f3 --- /dev/null +++ b/pcl-1.7/pcl/recognition/line_rgbd.h @@ -0,0 +1,320 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RECOGNITION_LINEMOD_LINE_RGBD +#define PCL_RECOGNITION_LINEMOD_LINE_RGBD + +#include +#include +#include +#include + +namespace pcl +{ + + struct BoundingBoxXYZ + { + /** \brief Constructor. */ + BoundingBoxXYZ () : x (0.0f), y (0.0f), z (0.0f), width (0.0f), height (0.0f), depth (0.0f) {} + + /** \brief X-coordinate of the upper left front point */ + float x; + /** \brief Y-coordinate of the upper left front point */ + float y; + /** \brief Z-coordinate of the upper left front point */ + float z; + + /** \brief Width of the bounding box */ + float width; + /** \brief Height of the bounding box */ + float height; + /** \brief Depth of the bounding box */ + float depth; + }; + + /** \brief High-level class for template matching using the LINEMOD approach based on RGB and Depth data. + * \author Stefan Holzer + */ + template + class PCL_EXPORTS LineRGBD + { + public: + + /** \brief A LineRGBD detection. */ + struct Detection + { + /** \brief Constructor. */ + Detection () : template_id (0), object_id (0), detection_id (0), response (0.0f), bounding_box () {} + + /** \brief The ID of the template. */ + size_t template_id; + /** \brief The ID of the object corresponding to the template. */ + size_t object_id; + /** \brief The ID of this detection. This is only valid for the last call of the method detect (...). */ + size_t detection_id; + /** \brief The response of this detection. Responses are between 0 and 1, where 1 is best. */ + float response; + /** \brief The 3D bounding box of the detection. */ + BoundingBoxXYZ bounding_box; + /** \brief The 2D template region of the detection. */ + RegionXY region; + }; + + /** \brief Constructor */ + LineRGBD () + : intersection_volume_threshold_ (1.0f) + , linemod_ () + , color_gradient_mod_ () + , surface_normal_mod_ () + , cloud_xyz_ () + , cloud_rgb_ () + , template_point_clouds_ () + , bounding_boxes_ () + , object_ids_ () + , detections_ () + { + } + + /** \brief Destructor */ + virtual ~LineRGBD () + { + } + + /** \brief Loads templates from a LMT (LineMod Template) file. Overrides old templates. + * + * LineMod Template files are TAR files that store pairs of PCD datasets + * together with their LINEMOD signatures in \ref + * SparseQuantizedMultiModTemplate format. + * + * \param[in] file_name The name of the file that stores the templates. + * \param object_id + * + * \return true, if the operation was successful, false otherwise. + */ + bool + loadTemplates (const std::string &file_name, size_t object_id = 0); + + bool + addTemplate (const SparseQuantizedMultiModTemplate & sqmmt, pcl::PointCloud & cloud, size_t object_id = 0); + + /** \brief Sets the threshold for the detection responses. Responses are between 0 and 1, where 1 is a best. + * \param[in] threshold The threshold used to decide where a template is detected. + */ + inline void + setDetectionThreshold (float threshold) + { + linemod_.setDetectionThreshold (threshold); + } + + /** \brief Sets the threshold on the magnitude of color gradients. Color gradients with a magnitude below + * this threshold are not considered in the detection process. + * \param[in] threshold The threshold on the magnitude of color gradients. + */ + inline void + setGradientMagnitudeThreshold (const float threshold) + { + color_gradient_mod_.setGradientMagnitudeThreshold (threshold); + } + + /** \brief Sets the threshold for the decision whether two detections of the same template are merged or not. + * If ratio between the intersection of the bounding boxes of two detections and the original bounding + * boxes is larger than the specified threshold then they are merged. If detection A overlaps with + * detection B and B with C than A, B, and C are merged. Threshold has to be between 0 and 1. + * \param[in] threshold The threshold on the ratio between the intersection bounding box and the original + * bounding box. + */ + inline void + setIntersectionVolumeThreshold (const float threshold = 1.0f) + { + intersection_volume_threshold_ = threshold; + } + + /** \brief Sets the input cloud with xyz point coordinates. The cloud has to be organized. + * \param[in] cloud The input cloud with xyz point coordinates. + */ + inline void + setInputCloud (const typename pcl::PointCloud::ConstPtr & cloud) + { + cloud_xyz_ = cloud; + + surface_normal_mod_.setInputCloud (cloud); + surface_normal_mod_.processInputData (); + } + + /** \brief Sets the input cloud with rgb values. The cloud has to be organized. + * \param[in] cloud The input cloud with rgb values. + */ + inline void + setInputColors (const typename pcl::PointCloud::ConstPtr & cloud) + { + cloud_rgb_ = cloud; + + color_gradient_mod_.setInputCloud (cloud); + color_gradient_mod_.processInputData (); + } + + /** \brief Creates a template from the specified data and adds it to the matching queue. + * \param cloud + * \param object_id + * \param[in] mask_xyz the mask that determine which parts of the xyz-modality are used for creating the template. + * \param[in] mask_rgb the mask that determine which parts of the rgb-modality are used for creating the template. + * \param[in] region the region which will be associated with the template (can be larger than the actual modality-maps). + */ + int + createAndAddTemplate ( + pcl::PointCloud & cloud, + const size_t object_id, + const MaskMap & mask_xyz, + const MaskMap & mask_rgb, + const RegionXY & region); + + + /** \brief Applies the detection process and fills the supplied vector with the detection instances. + * \param[out] detections The storage for the detection instances. + */ + void + detect (std::vector::Detection> & detections); + + /** \brief Applies the detection process in a semi-scale-invariant manner. This is done by acutally + * scaling the template to different sizes. + */ + void + detectSemiScaleInvariant (std::vector::Detection> & detections, + float min_scale = 0.6944444f, + float max_scale = 1.44f, + float scale_multiplier = 1.2f); + + /** \brief Computes and returns the point cloud of the specified detection. This is the template point + * cloud transformed to the detection coordinates. The detection ID refers to the last call of + * the method detect (...). + * \param[in] detection_id The ID of the detection (according to the last call of the method detect (...)). + * \param[out] cloud The storage for the transformed points. + */ + void + computeTransformedTemplatePoints (const size_t detection_id, + pcl::PointCloud & cloud); + + /** \brief Finds the indices of the points in the input cloud which correspond to the specified detection. + * The detection ID refers to the last call of the method detect (...). + * \param[in] detection_id The ID of the detection (according to the last call of the method detect (...)). + */ + inline std::vector + findObjectPointIndices (const size_t detection_id) + { + if (detection_id >= detections_.size ()) + PCL_ERROR ("ERROR pcl::LineRGBD::computeTransformedTemplatePoints - detection_id is out of bounds\n"); + + // TODO: compute transform from detection + // TODO: transform template points + std::vector vec; + return (vec); + } + + + protected: + + /** \brief Aligns the template points with the points found at the detection position of the specified detection. + * The detection ID refers to the last call of the method detect (...). + * \param[in] detection_id The ID of the detection (according to the last call of the method detect (...)). + */ + inline std::vector + alignTemplatePoints (const size_t detection_id) + { + if (detection_id >= detections_.size ()) + PCL_ERROR ("ERROR pcl::LineRGBD::computeTransformedTemplatePoints - detection_id is out of bounds\n"); + + // TODO: compute transform from detection + // TODO: transform template points + std::vector vec; + return (vec); + } + + /** \brief Refines the found detections along the depth. */ + void + refineDetectionsAlongDepth (); + + /** \brief Applies projective ICP on detections to find their correct position in depth. */ + void + applyProjectiveDepthICPOnDetections (); + + /** \brief Checks for overlapping detections, removes them and keeps only the strongest one. */ + void + removeOverlappingDetections (); + + /** \brief Computes the volume of the intersection between two bounding boxes. + * \param[in] box1 First bounding box. + * \param[in] box2 Second bounding box. + */ + static float + computeBoundingBoxIntersectionVolume (const BoundingBoxXYZ &box1, const BoundingBoxXYZ &box2); + + private: + /** \brief Read another LTM header chunk. */ + bool + readLTMHeader (int fd, pcl::io::TARHeader &header); + + /** \brief Intersection volume threshold. */ + float intersection_volume_threshold_; + + /** \brief LINEMOD instance. */ + public: pcl::LINEMOD linemod_; + /** \brief Color gradient modality. */ + pcl::ColorGradientModality color_gradient_mod_; + /** \brief Surface normal modality. */ + pcl::SurfaceNormalModality surface_normal_mod_; + + /** \brief XYZ point cloud. */ + typename pcl::PointCloud::ConstPtr cloud_xyz_; + /** \brief RGB point cloud. */ + typename pcl::PointCloud::ConstPtr cloud_rgb_; + + /** \brief Point clouds corresponding to the templates. */ + pcl::PointCloud::CloudVectorType template_point_clouds_; + /** \brief Bounding boxes corresonding to the templates. */ + std::vector bounding_boxes_; + /** \brief Object IDs corresponding to the templates. */ + std::vector object_ids_; + + /** \brief Detections from last call of method detect (...). */ + std::vector::Detection> detections_; + }; + +} + +#include + +#endif diff --git a/pcl-1.7/pcl/recognition/linemod.h b/pcl-1.7/pcl/recognition/linemod.h new file mode 100644 index 0000000..54ffc28 --- /dev/null +++ b/pcl-1.7/pcl/recognition/linemod.h @@ -0,0 +1,479 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RECOGNITION_LINEMOD +#define PCL_RECOGNITION_LINEMOD + +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + + /** \brief Stores a set of energy maps. + * \author Stefan Holzer + */ + class PCL_EXPORTS EnergyMaps + { + public: + /** \brief Constructor. */ + EnergyMaps () : width_ (0), height_ (0), nr_bins_ (0), maps_ () + { + } + + /** \brief Destructor. */ + virtual ~EnergyMaps () + { + } + + /** \brief Returns the width of the energy maps. */ + inline size_t + getWidth () const + { + return (width_); + } + + /** \brief Returns the height of the energy maps. */ + inline size_t + getHeight () const + { + return (height_); + } + + /** \brief Returns the number of bins used for quantization (which is equal to the number of energy maps). */ + inline size_t + getNumOfBins () const + { + return (nr_bins_); + } + + /** \brief Initializes the set of energy maps. + * \param[in] width the width of the energy maps. + * \param[in] height the height of the energy maps. + * \param[in] nr_bins the number of bins used for quantization. + */ + void + initialize (const size_t width, const size_t height, const size_t nr_bins) + { + maps_.resize(nr_bins, NULL); + width_ = width; + height_ = height; + nr_bins_ = nr_bins; + + const size_t mapsSize = width*height; + + for (size_t map_index = 0; map_index < maps_.size (); ++map_index) + { + //maps_[map_index] = new unsigned char[mapsSize]; + maps_[map_index] = reinterpret_cast (aligned_malloc (mapsSize)); + memset (maps_[map_index], 0, mapsSize); + } + } + + /** \brief Releases the internal data. */ + void + releaseAll () + { + for (size_t map_index = 0; map_index < maps_.size (); ++map_index) + //if (maps_[map_index] != NULL) delete[] maps_[map_index]; + if (maps_[map_index] != NULL) aligned_free (maps_[map_index]); + + maps_.clear (); + width_ = 0; + height_ = 0; + nr_bins_ = 0; + } + + /** \brief Operator for accessing a specific element in the set of energy maps. + * \param[in] bin_index the quantization bin (states which of the energy maps to access). + * \param[in] col_index the column index within the specified energy map. + * \param[in] row_index the row index within the specified energy map. + */ + inline unsigned char & + operator() (const size_t bin_index, const size_t col_index, const size_t row_index) + { + return (maps_[bin_index][row_index*width_ + col_index]); + } + + /** \brief Operator for accessing a specific element in the set of energy maps. + * \param[in] bin_index the quantization bin (states which of the energy maps to access). + * \param[in] index the element index within the specified energy map. + */ + inline unsigned char & + operator() (const size_t bin_index, const size_t index) + { + return (maps_[bin_index][index]); + } + + /** \brief Returns a pointer to the data of the specified energy map. + * \param[in] bin_index the index of the energy map to return (== the quantization bin). + */ + inline unsigned char * + operator() (const size_t bin_index) + { + return (maps_[bin_index]); + } + + /** \brief Operator for accessing a specific element in the set of energy maps. + * \param[in] bin_index the quantization bin (states which of the energy maps to access). + * \param[in] col_index the column index within the specified energy map. + * \param[in] row_index the row index within the specified energy map. + */ + inline const unsigned char & + operator() (const size_t bin_index, const size_t col_index, const size_t row_index) const + { + return (maps_[bin_index][row_index*width_ + col_index]); + } + + /** \brief Operator for accessing a specific element in the set of energy maps. + * \param[in] bin_index the quantization bin (states which of the energy maps to access). + * \param[in] index the element index within the specified energy map. + */ + inline const unsigned char & + operator() (const size_t bin_index, const size_t index) const + { + return (maps_[bin_index][index]); + } + + /** \brief Returns a pointer to the data of the specified energy map. + * \param[in] bin_index the index of the energy map to return (== the quantization bin). + */ + inline const unsigned char * + operator() (const size_t bin_index) const + { + return (maps_[bin_index]); + } + + private: + /** \brief The width of the energy maps. */ + size_t width_; + /** \brief The height of the energy maps. */ + size_t height_; + /** \brief The number of quantization bins (== the number of internally stored energy maps). */ + size_t nr_bins_; + /** \brief Storage for the energy maps. */ + std::vector maps_; + }; + + /** \brief Stores a set of linearized maps. + * \author Stefan Holzer + */ + class PCL_EXPORTS LinearizedMaps + { + public: + /** \brief Constructor. */ + LinearizedMaps () : width_ (0), height_ (0), mem_width_ (0), mem_height_ (0), step_size_ (0), maps_ () + { + } + + /** \brief Destructor. */ + virtual ~LinearizedMaps () + { + } + + /** \brief Returns the width of the linearized map. */ + inline size_t + getWidth () const { return (width_); } + + /** \brief Returns the height of the linearized map. */ + inline size_t + getHeight () const { return (height_); } + + /** \brief Returns the step-size used to construct the linearized map. */ + inline size_t + getStepSize () const { return (step_size_); } + + /** \brief Returns the size of the memory map. */ + inline size_t + getMapMemorySize () const { return (mem_width_ * mem_height_); } + + /** \brief Initializes the linearized map. + * \param[in] width the width of the source map. + * \param[in] height the height of the source map. + * \param[in] step_size the step-size used to sample the source map. + */ + void + initialize (const size_t width, const size_t height, const size_t step_size) + { + maps_.resize(step_size*step_size, NULL); + width_ = width; + height_ = height; + mem_width_ = width / step_size; + mem_height_ = height / step_size; + step_size_ = step_size; + + const size_t mapsSize = mem_width_ * mem_height_; + + for (size_t map_index = 0; map_index < maps_.size (); ++map_index) + { + //maps_[map_index] = new unsigned char[2*mapsSize]; + maps_[map_index] = reinterpret_cast (aligned_malloc (2*mapsSize)); + memset (maps_[map_index], 0, 2*mapsSize); + } + } + + /** \brief Releases the internal memory. */ + void + releaseAll () + { + for (size_t map_index = 0; map_index < maps_.size (); ++map_index) + //if (maps_[map_index] != NULL) delete[] maps_[map_index]; + if (maps_[map_index] != NULL) aligned_free (maps_[map_index]); + + maps_.clear (); + width_ = 0; + height_ = 0; + mem_width_ = 0; + mem_height_ = 0; + step_size_ = 0; + } + + /** \brief Operator to access elements of the linearized map by column and row index. + * \param[in] col_index the column index. + * \param[in] row_index the row index. + */ + inline unsigned char * + operator() (const size_t col_index, const size_t row_index) + { + return (maps_[row_index*step_size_ + col_index]); + } + + /** \brief Returns a linearized map starting at the specified position. + * \param[in] col_index the column index at which the returned map starts. + * \param[in] row_index the row index at which the returned map starts. + */ + inline unsigned char * + getOffsetMap (const size_t col_index, const size_t row_index) + { + const size_t map_col = col_index % step_size_; + const size_t map_row = row_index % step_size_; + + const size_t map_mem_col_index = col_index / step_size_; + const size_t map_mem_row_index = row_index / step_size_; + + return (maps_[map_row*step_size_ + map_col] + map_mem_row_index*mem_width_ + map_mem_col_index); + } + + private: + /** \brief the original width of the data represented by the map. */ + size_t width_; + /** \brief the original height of the data represented by the map. */ + size_t height_; + /** \brief the actual width of the linearized map. */ + size_t mem_width_; + /** \brief the actual height of the linearized map. */ + size_t mem_height_; + /** \brief the step-size used for sampling the original data. */ + size_t step_size_; + /** \brief a vector containing all the linearized maps. */ + std::vector maps_; + }; + + /** \brief Represents a detection of a template using the LINEMOD approach. + * \author Stefan Holzer + */ + struct PCL_EXPORTS LINEMODDetection + { + /** \brief Constructor. */ + LINEMODDetection () : x (0), y (0), template_id (0), score (0.0f), scale (1.0f) {} + + /** \brief x-position of the detection. */ + int x; + /** \brief y-position of the detection. */ + int y; + /** \brief ID of the detected template. */ + int template_id; + /** \brief score of the detection. */ + float score; + /** \brief scale at which the template was detected. */ + float scale; + }; + + /** + * \brief Template matching using the LINEMOD approach. + * \author Stefan Holzer, Stefan Hinterstoisser + */ + class PCL_EXPORTS LINEMOD + { + public: + /** \brief Constructor */ + LINEMOD (); + + /** \brief Destructor */ + virtual ~LINEMOD (); + + /** \brief Creates a template from the specified data and adds it to the matching queue. + * \param[in] modalities the modalities used to create the template. + * \param[in] masks the masks that determine which parts of the modalities are used for creating the template. + * \param[in] region the region which will be associated with the template (can be larger than the actual modality-maps). + */ + int + createAndAddTemplate (const std::vector & modalities, + const std::vector & masks, + const RegionXY & region); + + /** \brief Adds the specified template to the matching queue. + * \param[in] linemod_template the template to add. + */ + int + addTemplate (const SparseQuantizedMultiModTemplate & linemod_template); + + /** \brief Detects the stored templates in the supplied modality data. + * \param[in] modalities the modalities that will be used for detection. + * \param[out] detections the destination for the detections. + */ + void + detectTemplates (const std::vector & modalities, + std::vector & detections) const; + + /** \brief Detects the stored templates in a semi scale invariant manner + * by applying the detection to multiple scaled versions of the input data. + * \param[in] modalities the modalities that will be used for detection. + * \param[out] detections the destination for the detections. + * \param[in] min_scale the minimum scale. + * \param[in] max_scale the maximum scale. + * \param[in] scale_multiplier the multiplier for getting from one scale to the next. + */ + void + detectTemplatesSemiScaleInvariant (const std::vector & modalities, + std::vector & detections, + float min_scale = 0.6944444f, + float max_scale = 1.44f, + float scale_multiplier = 1.2f) const; + + /** \brief Matches the stored templates to the supplied modality data. + * \param[in] modalities the modalities that will be used for matching. + * \param[out] matches the found matches. + */ + void + matchTemplates (const std::vector & modalities, + std::vector & matches) const; + + /** \brief Sets the detection threshold. + * \param[in] threshold the detection threshold. + */ + inline void + setDetectionThreshold (float threshold) + { + template_threshold_ = threshold; + } + + /** \brief Enables/disables non-maximum suppression. + * \param[in] use_non_max_suppression determines whether to use non-maximum suppression or not. + */ + inline void + setNonMaxSuppression (bool use_non_max_suppression) + { + use_non_max_suppression_ = use_non_max_suppression; + } + + /** \brief Enables/disables averaging of close detections. + * \param[in] average_detections determines whether to average close detections or not. + */ + inline void + setDetectionAveraging (bool average_detections) + { + average_detections_ = average_detections; + } + + /** \brief Returns the template with the specified ID. + * \param[in] template_id the ID of the template to return. + */ + inline const SparseQuantizedMultiModTemplate & + getTemplate (int template_id) const + { + return (templates_[template_id]); + } + + /** \brief Returns the number of stored/trained templates. */ + inline size_t + getNumOfTemplates () const + { + return (templates_.size ()); + } + + /** \brief Saves the stored templates to the specified file. + * \param[in] file_name the name of the file to save the templates to. + */ + void + saveTemplates (const char * file_name) const; + + /** \brief Loads templates from the specified file. + * \param[in] file_name the name of the file to load the template from. + */ + void + loadTemplates (const char * file_name); + + /** \brief Loads templates from the specified files. + * \param[in] file_names vector of files to load the templates from. + */ + + void + loadTemplates (std::vector & file_names); + + /** \brief Serializes the stored templates to the specified stream. + * \param[in] stream the stream the templates will be written to. + */ + void + serialize (std::ostream & stream) const; + + /** \brief Deserializes templates from the specified stream. + * \param[in] stream the stream the templates will be read from. + */ + void + deserialize (std::istream & stream); + + + private: + /** template response threshold */ + float template_threshold_; + /** states whether non-max-suppression on detections is enabled or not */ + bool use_non_max_suppression_; + /** states whether to return an averaged detection */ + bool average_detections_; + /** template storage */ + std::vector templates_; + }; + +} + +#endif diff --git a/pcl-1.7/pcl/recognition/linemod/line_rgbd.h b/pcl-1.7/pcl/recognition/linemod/line_rgbd.h new file mode 100644 index 0000000..8b1b3f3 --- /dev/null +++ b/pcl-1.7/pcl/recognition/linemod/line_rgbd.h @@ -0,0 +1,320 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RECOGNITION_LINEMOD_LINE_RGBD +#define PCL_RECOGNITION_LINEMOD_LINE_RGBD + +#include +#include +#include +#include + +namespace pcl +{ + + struct BoundingBoxXYZ + { + /** \brief Constructor. */ + BoundingBoxXYZ () : x (0.0f), y (0.0f), z (0.0f), width (0.0f), height (0.0f), depth (0.0f) {} + + /** \brief X-coordinate of the upper left front point */ + float x; + /** \brief Y-coordinate of the upper left front point */ + float y; + /** \brief Z-coordinate of the upper left front point */ + float z; + + /** \brief Width of the bounding box */ + float width; + /** \brief Height of the bounding box */ + float height; + /** \brief Depth of the bounding box */ + float depth; + }; + + /** \brief High-level class for template matching using the LINEMOD approach based on RGB and Depth data. + * \author Stefan Holzer + */ + template + class PCL_EXPORTS LineRGBD + { + public: + + /** \brief A LineRGBD detection. */ + struct Detection + { + /** \brief Constructor. */ + Detection () : template_id (0), object_id (0), detection_id (0), response (0.0f), bounding_box () {} + + /** \brief The ID of the template. */ + size_t template_id; + /** \brief The ID of the object corresponding to the template. */ + size_t object_id; + /** \brief The ID of this detection. This is only valid for the last call of the method detect (...). */ + size_t detection_id; + /** \brief The response of this detection. Responses are between 0 and 1, where 1 is best. */ + float response; + /** \brief The 3D bounding box of the detection. */ + BoundingBoxXYZ bounding_box; + /** \brief The 2D template region of the detection. */ + RegionXY region; + }; + + /** \brief Constructor */ + LineRGBD () + : intersection_volume_threshold_ (1.0f) + , linemod_ () + , color_gradient_mod_ () + , surface_normal_mod_ () + , cloud_xyz_ () + , cloud_rgb_ () + , template_point_clouds_ () + , bounding_boxes_ () + , object_ids_ () + , detections_ () + { + } + + /** \brief Destructor */ + virtual ~LineRGBD () + { + } + + /** \brief Loads templates from a LMT (LineMod Template) file. Overrides old templates. + * + * LineMod Template files are TAR files that store pairs of PCD datasets + * together with their LINEMOD signatures in \ref + * SparseQuantizedMultiModTemplate format. + * + * \param[in] file_name The name of the file that stores the templates. + * \param object_id + * + * \return true, if the operation was successful, false otherwise. + */ + bool + loadTemplates (const std::string &file_name, size_t object_id = 0); + + bool + addTemplate (const SparseQuantizedMultiModTemplate & sqmmt, pcl::PointCloud & cloud, size_t object_id = 0); + + /** \brief Sets the threshold for the detection responses. Responses are between 0 and 1, where 1 is a best. + * \param[in] threshold The threshold used to decide where a template is detected. + */ + inline void + setDetectionThreshold (float threshold) + { + linemod_.setDetectionThreshold (threshold); + } + + /** \brief Sets the threshold on the magnitude of color gradients. Color gradients with a magnitude below + * this threshold are not considered in the detection process. + * \param[in] threshold The threshold on the magnitude of color gradients. + */ + inline void + setGradientMagnitudeThreshold (const float threshold) + { + color_gradient_mod_.setGradientMagnitudeThreshold (threshold); + } + + /** \brief Sets the threshold for the decision whether two detections of the same template are merged or not. + * If ratio between the intersection of the bounding boxes of two detections and the original bounding + * boxes is larger than the specified threshold then they are merged. If detection A overlaps with + * detection B and B with C than A, B, and C are merged. Threshold has to be between 0 and 1. + * \param[in] threshold The threshold on the ratio between the intersection bounding box and the original + * bounding box. + */ + inline void + setIntersectionVolumeThreshold (const float threshold = 1.0f) + { + intersection_volume_threshold_ = threshold; + } + + /** \brief Sets the input cloud with xyz point coordinates. The cloud has to be organized. + * \param[in] cloud The input cloud with xyz point coordinates. + */ + inline void + setInputCloud (const typename pcl::PointCloud::ConstPtr & cloud) + { + cloud_xyz_ = cloud; + + surface_normal_mod_.setInputCloud (cloud); + surface_normal_mod_.processInputData (); + } + + /** \brief Sets the input cloud with rgb values. The cloud has to be organized. + * \param[in] cloud The input cloud with rgb values. + */ + inline void + setInputColors (const typename pcl::PointCloud::ConstPtr & cloud) + { + cloud_rgb_ = cloud; + + color_gradient_mod_.setInputCloud (cloud); + color_gradient_mod_.processInputData (); + } + + /** \brief Creates a template from the specified data and adds it to the matching queue. + * \param cloud + * \param object_id + * \param[in] mask_xyz the mask that determine which parts of the xyz-modality are used for creating the template. + * \param[in] mask_rgb the mask that determine which parts of the rgb-modality are used for creating the template. + * \param[in] region the region which will be associated with the template (can be larger than the actual modality-maps). + */ + int + createAndAddTemplate ( + pcl::PointCloud & cloud, + const size_t object_id, + const MaskMap & mask_xyz, + const MaskMap & mask_rgb, + const RegionXY & region); + + + /** \brief Applies the detection process and fills the supplied vector with the detection instances. + * \param[out] detections The storage for the detection instances. + */ + void + detect (std::vector::Detection> & detections); + + /** \brief Applies the detection process in a semi-scale-invariant manner. This is done by acutally + * scaling the template to different sizes. + */ + void + detectSemiScaleInvariant (std::vector::Detection> & detections, + float min_scale = 0.6944444f, + float max_scale = 1.44f, + float scale_multiplier = 1.2f); + + /** \brief Computes and returns the point cloud of the specified detection. This is the template point + * cloud transformed to the detection coordinates. The detection ID refers to the last call of + * the method detect (...). + * \param[in] detection_id The ID of the detection (according to the last call of the method detect (...)). + * \param[out] cloud The storage for the transformed points. + */ + void + computeTransformedTemplatePoints (const size_t detection_id, + pcl::PointCloud & cloud); + + /** \brief Finds the indices of the points in the input cloud which correspond to the specified detection. + * The detection ID refers to the last call of the method detect (...). + * \param[in] detection_id The ID of the detection (according to the last call of the method detect (...)). + */ + inline std::vector + findObjectPointIndices (const size_t detection_id) + { + if (detection_id >= detections_.size ()) + PCL_ERROR ("ERROR pcl::LineRGBD::computeTransformedTemplatePoints - detection_id is out of bounds\n"); + + // TODO: compute transform from detection + // TODO: transform template points + std::vector vec; + return (vec); + } + + + protected: + + /** \brief Aligns the template points with the points found at the detection position of the specified detection. + * The detection ID refers to the last call of the method detect (...). + * \param[in] detection_id The ID of the detection (according to the last call of the method detect (...)). + */ + inline std::vector + alignTemplatePoints (const size_t detection_id) + { + if (detection_id >= detections_.size ()) + PCL_ERROR ("ERROR pcl::LineRGBD::computeTransformedTemplatePoints - detection_id is out of bounds\n"); + + // TODO: compute transform from detection + // TODO: transform template points + std::vector vec; + return (vec); + } + + /** \brief Refines the found detections along the depth. */ + void + refineDetectionsAlongDepth (); + + /** \brief Applies projective ICP on detections to find their correct position in depth. */ + void + applyProjectiveDepthICPOnDetections (); + + /** \brief Checks for overlapping detections, removes them and keeps only the strongest one. */ + void + removeOverlappingDetections (); + + /** \brief Computes the volume of the intersection between two bounding boxes. + * \param[in] box1 First bounding box. + * \param[in] box2 Second bounding box. + */ + static float + computeBoundingBoxIntersectionVolume (const BoundingBoxXYZ &box1, const BoundingBoxXYZ &box2); + + private: + /** \brief Read another LTM header chunk. */ + bool + readLTMHeader (int fd, pcl::io::TARHeader &header); + + /** \brief Intersection volume threshold. */ + float intersection_volume_threshold_; + + /** \brief LINEMOD instance. */ + public: pcl::LINEMOD linemod_; + /** \brief Color gradient modality. */ + pcl::ColorGradientModality color_gradient_mod_; + /** \brief Surface normal modality. */ + pcl::SurfaceNormalModality surface_normal_mod_; + + /** \brief XYZ point cloud. */ + typename pcl::PointCloud::ConstPtr cloud_xyz_; + /** \brief RGB point cloud. */ + typename pcl::PointCloud::ConstPtr cloud_rgb_; + + /** \brief Point clouds corresponding to the templates. */ + pcl::PointCloud::CloudVectorType template_point_clouds_; + /** \brief Bounding boxes corresonding to the templates. */ + std::vector bounding_boxes_; + /** \brief Object IDs corresponding to the templates. */ + std::vector object_ids_; + + /** \brief Detections from last call of method detect (...). */ + std::vector::Detection> detections_; + }; + +} + +#include + +#endif diff --git a/pcl-1.7/pcl/recognition/mask_map.h b/pcl-1.7/pcl/recognition/mask_map.h new file mode 100644 index 0000000..9f75717 --- /dev/null +++ b/pcl-1.7/pcl/recognition/mask_map.h @@ -0,0 +1,122 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_MASK_MAP +#define PCL_FEATURES_MASK_MAP + +#include +#include +#include + +namespace pcl +{ + class PCL_EXPORTS MaskMap + { + public: + MaskMap (); + MaskMap (size_t width, size_t height); + virtual ~MaskMap (); + + void + resize (size_t width, size_t height); + + inline size_t + getWidth () const { return (width_); } + + inline size_t + getHeight () const { return (height_); } + + inline unsigned char* + getData () { return (&data_[0]); } + + inline const unsigned char* + getData () const { return (&data_[0]); } + + static void + getDifferenceMask (const MaskMap & mask0, + const MaskMap & mask1, + MaskMap & diff_mask); + + inline void + set (const size_t x, const size_t y) + { + data_[y*width_+x] = 255; + } + + inline void + unset (const size_t x, const size_t y) + { + data_[y*width_+x] = 0; + } + + inline bool + isSet (const size_t x, const size_t y) const + { + return (data_[y*width_+x] != 0); + } + + inline void + reset () + { + memset (&data_[0], 0, width_*height_); + } + + inline unsigned char & + operator() (const size_t x, const size_t y) + { + return (data_[y*width_+x]); + } + + inline const unsigned char & + operator() (const size_t x, const size_t y) const + { + return (data_[y*width_+x]); + } + + void + erode (MaskMap & eroded_mask) const; + + private: + //unsigned char * data_; + std::vector data_; + size_t width_; + size_t height_; + }; + +} + +#endif diff --git a/pcl-1.7/pcl/recognition/model_library.h b/pcl-1.7/pcl/recognition/model_library.h new file mode 100644 index 0000000..c1dc136 --- /dev/null +++ b/pcl-1.7/pcl/recognition/model_library.h @@ -0,0 +1,274 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_RECOGNITION_MODEL_LIBRARY_H_ +#define PCL_RECOGNITION_MODEL_LIBRARY_H_ + +#include "auxiliary.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace recognition + { + class PCL_EXPORTS ModelLibrary + { + public: + typedef pcl::PointCloud PointCloudIn; + typedef pcl::PointCloud PointCloudN; + + /** \brief Stores some information about the model. */ + class Model + { + public: + Model (const PointCloudIn& points, const PointCloudN& normals, float voxel_size, const std::string& object_name, + float frac_of_points_for_registration, void* user_data = NULL) + : obj_name_(object_name), + user_data_ (user_data) + { + octree_.build (points, voxel_size, &normals); + + const std::vector& full_leaves = octree_.getFullLeaves (); + if ( full_leaves.empty () ) + return; + + // Initialize + std::vector::const_iterator it = full_leaves.begin (); + const float *p = (*it)->getData ()->getPoint (); + aux::copy3 (p, octree_center_of_mass_); + bounds_of_octree_points_[0] = bounds_of_octree_points_[1] = p[0]; + bounds_of_octree_points_[2] = bounds_of_octree_points_[3] = p[1]; + bounds_of_octree_points_[4] = bounds_of_octree_points_[5] = p[2]; + + // Compute both the bounds and the center of mass of the octree points + for ( ++it ; it != full_leaves.end () ; ++it ) + { + aux::add3 (octree_center_of_mass_, (*it)->getData ()->getPoint ()); + aux::expandBoundingBoxToContainPoint (bounds_of_octree_points_, (*it)->getData ()->getPoint ()); + } + + int num_octree_points = static_cast (full_leaves.size ()); + // Finalize the center of mass computation + aux::mult3 (octree_center_of_mass_, 1.0f/static_cast (num_octree_points)); + + int num_points_for_registration = static_cast (static_cast (num_octree_points)*frac_of_points_for_registration); + points_for_registration_.resize (static_cast (num_points_for_registration)); + + // Prepare for random point sampling + std::vector ids (num_octree_points); + for ( int i = 0 ; i < num_octree_points ; ++i ) + ids[i] = i; + + // The random generator + pcl::common::UniformGenerator randgen (0, num_octree_points - 1, static_cast (time (NULL))); + + // Randomly sample some points from the octree + for ( int i = 0 ; i < num_points_for_registration ; ++i ) + { + // Choose a random position within the array of ids + randgen.setParameters (0, static_cast (ids.size ()) - 1); + int rand_pos = randgen.run (); + + // Copy the randomly selected octree point + aux::copy3 (octree_.getFullLeaves ()[ids[rand_pos]]->getData ()->getPoint (), points_for_registration_[i]); + + // Delete the selected id + ids.erase (ids.begin() + rand_pos); + } + } + + virtual ~Model () + { + } + + inline const std::string& + getObjectName () const + { + return (obj_name_); + } + + inline const ORROctree& + getOctree () const + { + return (octree_); + } + + inline void* + getUserData () const + { + return (user_data_); + } + + inline const float* + getOctreeCenterOfMass () const + { + return (octree_center_of_mass_); + } + + inline const float* + getBoundsOfOctreePoints () const + { + return (bounds_of_octree_points_); + } + + inline const PointCloudIn& + getPointsForRegistration () const + { + return (points_for_registration_); + } + + protected: + const std::string obj_name_; + ORROctree octree_; + float octree_center_of_mass_[3]; + float bounds_of_octree_points_[6]; + PointCloudIn points_for_registration_; + void* user_data_; + }; + + typedef std::list > node_data_pair_list; + typedef std::map HashTableCell; + typedef VoxelStructure HashTable; + + public: + /** \brief This class is used by 'ObjRecRANSAC' to maintain the object models to be recognized. Normally, you do not need to use + * this class directly. */ + ModelLibrary (float pair_width, float voxel_size, float max_coplanarity_angle = 3.0f*AUX_DEG_TO_RADIANS/*3 degrees*/); + virtual ~ModelLibrary () + { + this->clear(); + } + + /** \brief Removes all models from the library and clears the hash table. */ + void + removeAllModels (); + + /** \brief This is a threshold. The larger the value the more point pairs will be considered as co-planar and will + * be ignored in the off-line model pre-processing and in the online recognition phases. This makes sense only if + * "ignore co-planar points" is on. Call this method before calling addModel. */ + inline void + setMaxCoplanarityAngleDegrees (float max_coplanarity_angle_degrees) + { + max_coplanarity_angle_ = max_coplanarity_angle_degrees*AUX_DEG_TO_RADIANS; + } + + /** \brief Call this method in order NOT to add co-planar point pairs to the hash table. The default behavior + * is ignoring co-planar points on. */ + inline void + ignoreCoplanarPointPairsOn () + { + ignore_coplanar_opps_ = true; + } + + /** \brief Call this method in order to add all point pairs (co-planar as well) to the hash table. The default + * behavior is ignoring co-planar points on. */ + inline void + ignoreCoplanarPointPairsOff () + { + ignore_coplanar_opps_ = false; + } + + /** \brief Adds a model to the hash table. + * + * \param[in] points represents the model to be added. + * \param[in] normals are the normals at the model points. + * \param[in] object_name is the unique name of the object to be added. + * \param[in] frac_of_points_for_registration is the number of points used for fast ICP registration prior to hypothesis testing + * \param[in] user_data is a pointer to some data (can be NULL) + * + * Returns true if model successfully added and false otherwise (e.g., if object_name is not unique). */ + bool + addModel (const PointCloudIn& points, const PointCloudN& normals, const std::string& object_name, + float frac_of_points_for_registration, void* user_data = NULL); + + /** \brief Returns the hash table built by this instance. */ + inline const HashTable& + getHashTable () const + { + return (hash_table_); + } + + inline const Model* + getModel (const std::string& name) const + { + std::map::const_iterator it = models_.find (name); + if ( it != models_.end () ) + return (it->second); + + return (NULL); + } + + inline const std::map& + getModels () const + { + return (models_); + } + + protected: + /** \brief Removes all models from the library and destroys the hash table. This method should be called upon destroying this object. */ + void + clear (); + + /** \brief Returns true if the oriented point pair was added to the hash table and false otherwise. */ + bool + addToHashTable (Model* model, const ORROctree::Node::Data* data1, const ORROctree::Node::Data* data2); + + protected: + float pair_width_; + float voxel_size_; + float max_coplanarity_angle_; + bool ignore_coplanar_opps_; + + std::map models_; + HashTable hash_table_; + int num_of_cells_[3]; + }; + } // namespace recognition +} // namespace pcl + +#endif // PCL_RECOGNITION_MODEL_LIBRARY_H_ diff --git a/pcl-1.7/pcl/recognition/obj_rec_ransac.h b/pcl-1.7/pcl/recognition/obj_rec_ransac.h new file mode 100644 index 0000000..fe1ed38 --- /dev/null +++ b/pcl-1.7/pcl/recognition/obj_rec_ransac.h @@ -0,0 +1,484 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_RECOGNITION_OBJ_REC_RANSAC_H_ +#define PCL_RECOGNITION_OBJ_REC_RANSAC_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define OBJ_REC_RANSAC_VERBOSE + +namespace pcl +{ + namespace recognition + { + /** \brief This is a RANSAC-based 3D object recognition method. Do the following to use it: (i) call addModel() k times with k different models + * representing the objects to be recognized and (ii) call recognize() with the 3D scene in which the objects should be recognized. Recognition means both + * object identification and pose (position + orientation) estimation. Check the method descriptions for more details. + * + * \note If you use this code in any academic work, please cite: + * + * - Chavdar Papazov, Sami Haddadin, Sven Parusel, Kai Krieger and Darius Burschka. + * Rigid 3D geometry matching for grasping of known objects in cluttered scenes. + * The International Journal of Robotics Research 2012. DOI: 10.1177/0278364911436019 + * + * - Chavdar Papazov and Darius Burschka. + * An Efficient RANSAC for 3D Object Recognition in Noisy and Occluded Scenes. + * In Proceedings of the 10th Asian Conference on Computer Vision (ACCV'10), + * November 2010. + * + * + * \author Chavdar Papazov + * \ingroup recognition + */ + class PCL_EXPORTS ObjRecRANSAC + { + public: + typedef ModelLibrary::PointCloudIn PointCloudIn; + typedef ModelLibrary::PointCloudN PointCloudN; + + typedef BVH BVHH; + + /** \brief This is an output item of the ObjRecRANSAC::recognize() method. It contains the recognized model, its name (the ones passed to + * ObjRecRANSAC::addModel()), the rigid transform which aligns the model with the input scene and the match confidence which is a number + * in the interval (0, 1] which gives the fraction of the model surface area matched to the scene. E.g., a match confidence of 0.3 means + * that 30% of the object surface area was matched to the scene points. If the scene is represented by a single range image, the match + * confidence can not be greater than 0.5 since the range scanner sees only one side of each object. + */ + class Output + { + public: + Output (const std::string& object_name, const float rigid_transform[12], float match_confidence, void* user_data) : + object_name_ (object_name), + match_confidence_ (match_confidence), + user_data_ (user_data) + { + memcpy(this->rigid_transform_, rigid_transform, 12*sizeof (float)); + } + virtual ~Output (){} + + public: + std::string object_name_; + float rigid_transform_[12]; + float match_confidence_; + void* user_data_; + }; + + class OrientedPointPair + { + public: + OrientedPointPair (const float *p1, const float *n1, const float *p2, const float *n2) + : p1_ (p1), n1_ (n1), p2_ (p2), n2_ (n2) + { + } + + virtual ~OrientedPointPair (){} + + public: + const float *p1_, *n1_, *p2_, *n2_; + }; + + class HypothesisCreator + { + public: + HypothesisCreator (){} + virtual ~HypothesisCreator (){} + + Hypothesis* create (const SimpleOctree::Node* ) const { return new Hypothesis ();} + }; + + typedef SimpleOctree HypothesisOctree; + + public: + /** \brief Constructor with some important parameters which can not be changed once an instance of that class is created. + * + * \param[in] pair_width should be roughly half the extent of the visible object part. This means, for each object point p there should be (at least) + * one point q (from the same object) such that ||p - q|| <= pair_width. Tradeoff: smaller values allow for detection in more occluded scenes but lead + * to more imprecise alignment. Bigger values lead to better alignment but require large visible object parts (i.e., less occlusion). + * + * \param[in] voxel_size is the size of the leafs of the octree, i.e., the "size" of the discretization. Tradeoff: High values lead to less + * computation time but ignore object details. Small values allow to better distinguish between objects, but will introduce more holes in the resulting + * "voxel-surface" (especially for a sparsely sampled scene). */ + ObjRecRANSAC (float pair_width, float voxel_size); + virtual ~ObjRecRANSAC () + { + this->clear (); + this->clearTestData (); + } + + /** \brief Removes all models from the model library and releases some memory dynamically allocated by this instance. */ + void + inline clear() + { + model_library_.removeAllModels (); + scene_octree_.clear (); + scene_octree_proj_.clear (); + sampled_oriented_point_pairs_.clear (); + transform_space_.clear (); + scene_octree_points_.reset (); + } + + /** \brief This is a threshold. The larger the value the more point pairs will be considered as co-planar and will + * be ignored in the off-line model pre-processing and in the online recognition phases. This makes sense only if + * "ignore co-planar points" is on. Call this method before calling addModel. This method calls the corresponding + * method of the model library. */ + inline void + setMaxCoplanarityAngleDegrees (float max_coplanarity_angle_degrees) + { + max_coplanarity_angle_ = max_coplanarity_angle_degrees*AUX_DEG_TO_RADIANS; + model_library_.setMaxCoplanarityAngleDegrees (max_coplanarity_angle_degrees); + } + + inline void + setSceneBoundsEnlargementFactor (float value) + { + scene_bounds_enlargement_factor_ = value; + } + + /** \brief Default is on. This method calls the corresponding method of the model library. */ + inline void + ignoreCoplanarPointPairsOn () + { + ignore_coplanar_opps_ = true; + model_library_.ignoreCoplanarPointPairsOn (); + } + + /** \brief Default is on. This method calls the corresponding method of the model library. */ + inline void + ignoreCoplanarPointPairsOff () + { + ignore_coplanar_opps_ = false; + model_library_.ignoreCoplanarPointPairsOff (); + } + + inline void + icpHypothesesRefinementOn () + { + do_icp_hypotheses_refinement_ = true; + } + + inline void + icpHypothesesRefinementOff () + { + do_icp_hypotheses_refinement_ = false; + } + + /** \brief Add an object model to be recognized. + * + * \param[in] points are the object points. + * \param[in] normals at each point. + * \param[in] object_name is an identifier for the object. If that object is detected in the scene 'object_name' + * is returned by the recognition method and you know which object has been detected. Note that 'object_name' has + * to be unique! + * \param[in] user_data is a pointer to some data (can be NULL) + * + * The method returns true if the model was successfully added to the model library and false otherwise (e.g., if 'object_name' is already in use). + */ + inline bool + addModel (const PointCloudIn& points, const PointCloudN& normals, const std::string& object_name, void* user_data = NULL) + { + return (model_library_.addModel (points, normals, object_name, frac_of_points_for_icp_refinement_, user_data)); + } + + /** \brief This method performs the recognition of the models loaded to the model library with the method addModel(). + * + * \param[in] scene is the 3d scene in which the object should be recognized. + * \param[in] normals are the scene normals. + * \param[out] recognized_objects is the list of output items each one containing the recognized model instance, its name, the aligning rigid transform + * and the match confidence (see ObjRecRANSAC::Output for further explanations). + * \param[in] success_probability is the user-defined probability of detecting all objects in the scene. + */ + void + recognize (const PointCloudIn& scene, const PointCloudN& normals, std::list& recognized_objects, double success_probability = 0.99); + + inline void + enterTestModeSampleOPP () + { + rec_mode_ = ObjRecRANSAC::SAMPLE_OPP; + } + + inline void + enterTestModeTestHypotheses () + { + rec_mode_ = ObjRecRANSAC::TEST_HYPOTHESES; + } + + inline void + leaveTestMode () + { + rec_mode_ = ObjRecRANSAC::FULL_RECOGNITION; + } + + /** \brief This function is useful for testing purposes. It returns the oriented point pairs which were sampled from the + * scene during the recognition process. Makes sense only if some of the testing modes are active. */ + inline const std::list& + getSampledOrientedPointPairs () const + { + return (sampled_oriented_point_pairs_); + } + + /** \brief This function is useful for testing purposes. It returns the accepted hypotheses generated during the + * recognition process. Makes sense only if some of the testing modes are active. */ + inline const std::vector& + getAcceptedHypotheses () const + { + return (accepted_hypotheses_); + } + + /** \brief This function is useful for testing purposes. It returns the accepted hypotheses generated during the + * recognition process. Makes sense only if some of the testing modes are active. */ + inline void + getAcceptedHypotheses (std::vector& out) const + { + out = accepted_hypotheses_; + } + + /** \brief Returns the hash table in the model library. */ + inline const pcl::recognition::ModelLibrary::HashTable& + getHashTable () const + { + return (model_library_.getHashTable ()); + } + + inline const ModelLibrary& + getModelLibrary () const + { + return (model_library_); + } + + inline const ModelLibrary::Model* + getModel (const std::string& name) const + { + return (model_library_.getModel (name)); + } + + inline const ORROctree& + getSceneOctree () const + { + return (scene_octree_); + } + + inline RigidTransformSpace& + getRigidTransformSpace () + { + return (transform_space_); + } + + inline float + getPairWidth () const + { + return pair_width_; + } + + protected: + enum Recognition_Mode {SAMPLE_OPP, TEST_HYPOTHESES, /*BUILD_CONFLICT_GRAPH,*/ FULL_RECOGNITION}; + + friend class ModelLibrary; + + inline int + computeNumberOfIterations (double success_probability) const + { + // 'p_obj' is the probability that given that the first sample point belongs to an object, + // the second sample point will belong to the same object + const double p_obj = 0.25f; + // old version: p = p_obj*relative_obj_size_*fraction_of_pairs_in_hash_table_; + const double p = p_obj*relative_obj_size_; + + if ( 1.0 - p <= 0.0 ) + return 1; + + return static_cast (log (1.0-success_probability)/log (1.0-p) + 1.0); + } + + inline void + clearTestData () + { + sampled_oriented_point_pairs_.clear (); + accepted_hypotheses_.clear (); + transform_space_.clear (); + } + + void + sampleOrientedPointPairs (int num_iterations, const std::vector& full_scene_leaves, std::list& output) const; + + int + generateHypotheses (const std::list& pairs, std::list& out) const; + + /** \brief Groups close hypotheses in 'hypotheses'. Saves a representative for each group in 'out'. Returns the + * number of hypotheses after grouping. */ + int + groupHypotheses(std::list& hypotheses, int num_hypotheses, RigidTransformSpace& transform_space, + HypothesisOctree& grouped_hypotheses) const; + + inline void + testHypothesis (Hypothesis* hypothesis, int& match, int& penalty) const; + + inline void + testHypothesisNormalBased (Hypothesis* hypothesis, float& match) const; + + void + buildGraphOfCloseHypotheses (HypothesisOctree& hypotheses, ORRGraph& graph) const; + + void + filterGraphOfCloseHypotheses (ORRGraph& graph, std::vector& out) const; + + void + buildGraphOfConflictingHypotheses (const BVHH& bvh, ORRGraph& graph) const; + + void + filterGraphOfConflictingHypotheses (ORRGraph& graph, std::list& recognized_objects) const; + + /** \brief Computes the rigid transform that maps the line (a1, b1) to (a2, b2). + * The computation is based on the corresponding points 'a1' <-> 'a2' and 'b1' <-> 'b2' + * and the normals 'a1_n', 'b1_n', 'a2_n', and 'b2_n'. The result is saved in + * 'rigid_transform' which is an array of length 12. The first 9 elements are the + * rotational part (row major order) and the last 3 are the translation. */ + inline void + computeRigidTransform( + const float *a1, const float *a1_n, const float *b1, const float* b1_n, + const float *a2, const float *a2_n, const float *b2, const float* b2_n, + float* rigid_transform) const + { + // Some local variables + float o1[3], o2[3], x1[3], x2[3], y1[3], y2[3], z1[3], z2[3], tmp1[3], tmp2[3], Ro1[3], invFrame1[3][3]; + + // Compute the origins + o1[0] = 0.5f*(a1[0] + b1[0]); + o1[1] = 0.5f*(a1[1] + b1[1]); + o1[2] = 0.5f*(a1[2] + b1[2]); + + o2[0] = 0.5f*(a2[0] + b2[0]); + o2[1] = 0.5f*(a2[1] + b2[1]); + o2[2] = 0.5f*(a2[2] + b2[2]); + + // Compute the x-axes + aux::diff3 (b1, a1, x1); aux::normalize3 (x1); + aux::diff3 (b2, a2, x2); aux::normalize3 (x2); + // Compute the y-axes. First y-axis + aux::projectOnPlane3 (a1_n, x1, tmp1); aux::normalize3 (tmp1); + aux::projectOnPlane3 (b1_n, x1, tmp2); aux::normalize3 (tmp2); + aux::sum3 (tmp1, tmp2, y1); aux::normalize3 (y1); + // Second y-axis + aux::projectOnPlane3 (a2_n, x2, tmp1); aux::normalize3 (tmp1); + aux::projectOnPlane3 (b2_n, x2, tmp2); aux::normalize3 (tmp2); + aux::sum3 (tmp1, tmp2, y2); aux::normalize3 (y2); + // Compute the z-axes + aux::cross3 (x1, y1, z1); + aux::cross3 (x2, y2, z2); + + // 1. Invert the matrix [x1|y1|z1] (note that x1, y1, and z1 are treated as columns!) + invFrame1[0][0] = x1[0]; invFrame1[0][1] = x1[1]; invFrame1[0][2] = x1[2]; + invFrame1[1][0] = y1[0]; invFrame1[1][1] = y1[1]; invFrame1[1][2] = y1[2]; + invFrame1[2][0] = z1[0]; invFrame1[2][1] = z1[1]; invFrame1[2][2] = z1[2]; + // 2. Compute the desired rotation as rigid_transform = [x2|y2|z2]*invFrame1 + aux::mult3x3 (x2, y2, z2, invFrame1, rigid_transform); + + // Construct the translation which is the difference between the rotated o1 and o2 + aux::mult3x3 (rigid_transform, o1, Ro1); + rigid_transform[9] = o2[0] - Ro1[0]; + rigid_transform[10] = o2[1] - Ro1[1]; + rigid_transform[11] = o2[2] - Ro1[2]; + } + + /** \brief Computes the signature of the oriented point pair ((p1, n1), (p2, n2)) consisting of the angles between + * \param p1 + * \param n1 + * \param p2 + * \param n2 + * \param[out] signature is an array of three doubles saving the three angles in the order shown above. */ + static inline void + compute_oriented_point_pair_signature (const float *p1, const float *n1, const float *p2, const float *n2, float signature[3]) + { + // Get the line from p1 to p2 + float cl[3] = {p2[0] - p1[0], p2[1] - p1[1], p2[2] - p1[2]}; + aux::normalize3 (cl); + + signature[0] = std::acos (aux::clamp (aux::dot3 (n1,cl), -1.0f, 1.0f)); cl[0] = -cl[0]; cl[1] = -cl[1]; cl[2] = -cl[2]; + signature[1] = std::acos (aux::clamp (aux::dot3 (n2,cl), -1.0f, 1.0f)); + signature[2] = std::acos (aux::clamp (aux::dot3 (n1,n2), -1.0f, 1.0f)); + } + + protected: + // Parameters + float pair_width_; + float voxel_size_; + float position_discretization_; + float rotation_discretization_; + float abs_zdist_thresh_; + float relative_obj_size_; + float visibility_; + float relative_num_of_illegal_pts_; + float intersection_fraction_; + float max_coplanarity_angle_; + float scene_bounds_enlargement_factor_; + bool ignore_coplanar_opps_; + float frac_of_points_for_icp_refinement_; + bool do_icp_hypotheses_refinement_; + + ModelLibrary model_library_; + ORROctree scene_octree_; + ORROctreeZProjection scene_octree_proj_; + RigidTransformSpace transform_space_; + TrimmedICP trimmed_icp_; + PointCloudIn::Ptr scene_octree_points_; + + std::list sampled_oriented_point_pairs_; + std::vector accepted_hypotheses_; + Recognition_Mode rec_mode_; + }; + } // namespace recognition +} // namespace pcl + +#endif // PCL_RECOGNITION_OBJ_REC_RANSAC_H_ diff --git a/pcl-1.7/pcl/recognition/orr_graph.h b/pcl-1.7/pcl/recognition/orr_graph.h new file mode 100644 index 0000000..351d6ad --- /dev/null +++ b/pcl-1.7/pcl/recognition/orr_graph.h @@ -0,0 +1,225 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/* + * orr_graph.h + * + * Created on: Nov 23, 2012 + * Author: papazov + */ + +#ifndef PCL_RECOGNITION_ORR_GRAPH_H_ +#define PCL_RECOGNITION_ORR_GRAPH_H_ + +#include + +namespace pcl +{ + namespace recognition + { + template + class ORRGraph + { + public: + class Node + { + public: + enum State {ON, OFF, UNDEF}; + + Node (int id) + : id_ (id), + state_(UNDEF) + {} + + virtual ~Node (){} + + inline const std::set& + getNeighbors () const + { + return (neighbors_); + } + + inline const NodeData& + getData () const + { + return (data_); + } + + inline void + setData (const NodeData& data) + { + data_ = data; + } + + inline int + getId () const + { + return (id_); + } + + inline void + setId (int id) + { + id_ = id; + } + + inline void + setFitness (int fitness) + { + fitness_ = fitness; + } + + static inline bool + compare (const Node* a, const Node* b) + { + return (static_cast (a->fitness_ > b->fitness_)); + } + + friend class ORRGraph; + + protected: + std::set neighbors_; + NodeData data_; + int id_; + int fitness_; + State state_; + }; + + public: + ORRGraph (){} + virtual ~ORRGraph (){ this->clear ();} + + inline void + clear () + { + for ( typename std::vector::iterator nit = nodes_.begin () ; nit != nodes_.end () ; ++nit ) + delete *nit; + + nodes_.clear (); + } + + /** \brief Drops all existing graph nodes and creates 'n' new ones. */ + inline void + resize (int n) + { + if ( !n ) + return; + + for ( typename std::vector::iterator nit = nodes_.begin () ; nit != nodes_.end () ; ++nit ) + delete *nit; + + nodes_.resize (static_cast (n)); + + for ( int i = 0 ; i < n ; ++i ) + nodes_[i] = new Node (i); + } + + inline void + computeMaximalOnOffPartition (std::list& on_nodes, std::list& off_nodes) + { + std::vector sorted_nodes (nodes_.size ()); + int i = 0; + + // Set all nodes to undefined + for ( typename std::vector::iterator it = nodes_.begin () ; it != nodes_.end () ; ++it ) + { + sorted_nodes[i++] = *it; + (*it)->state_ = Node::UNDEF; + } + + // Now sort the nodes according to the fitness + std::sort (sorted_nodes.begin (), sorted_nodes.end (), Node::compare); + + // Now run through the array and start switching nodes on and off + for ( typename std::vector::iterator it = sorted_nodes.begin () ; it != sorted_nodes.end () ; ++it ) + { + // Ignore graph nodes which are already OFF + if ( (*it)->state_ == Node::OFF ) + continue; + + // Set the node to ON + (*it)->state_ = Node::ON; + + // Set all its neighbors to OFF + for ( typename std::set::iterator neigh = (*it)->neighbors_.begin () ; neigh != (*it)->neighbors_.end () ; ++neigh ) + { + (*neigh)->state_ = Node::OFF; + off_nodes.push_back (*neigh); + } + + // Output the node + on_nodes.push_back (*it); + } + } + + inline void + insertUndirectedEdge (int id1, int id2) + { + nodes_[id1]->neighbors_.insert (nodes_[id2]); + nodes_[id2]->neighbors_.insert (nodes_[id1]); + } + + inline void + insertDirectedEdge (int id1, int id2) + { + nodes_[id1]->neighbors_.insert (nodes_[id2]); + } + + inline void + deleteUndirectedEdge (int id1, int id2) + { + nodes_[id1]->neighbors_.erase (nodes_[id2]); + nodes_[id2]->neighbors_.erase (nodes_[id1]); + } + + inline void + deleteDirectedEdge (int id1, int id2) + { + nodes_[id1]->neighbors_.erase (nodes_[id2]); + } + + inline typename std::vector& + getNodes (){ return nodes_;} + + public: + typename std::vector nodes_; + }; + } // namespace recognition +} // namespace pcl + +#endif /* PCL_RECOGNITION_ORR_GRAPH_H_ */ diff --git a/pcl-1.7/pcl/recognition/orr_octree.h b/pcl-1.7/pcl/recognition/orr_octree.h new file mode 100644 index 0000000..8eaad54 --- /dev/null +++ b/pcl-1.7/pcl/recognition/orr_octree.h @@ -0,0 +1,492 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/* + * orr_octree.h + * + * Created on: Oct 23, 2012 + * Author: papazov + */ + +#ifndef PCL_RECOGNITION_ORR_OCTREE_H_ +#define PCL_RECOGNITION_ORR_OCTREE_H_ + +#include "auxiliary.h" +#include +#include +#include +#include +#include +#include +#include +#include + +//#define PCL_REC_ORR_OCTREE_VERBOSE + +namespace pcl +{ + namespace recognition + { + /** \brief That's a very specialized and simple octree class. That's the way it is intended to + * be, that's why no templates and stuff like this. + * + * \author Chavdar Papazov + * \ingroup recognition + */ + class PCL_EXPORTS ORROctree + { + public: + typedef pcl::PointCloud PointCloudIn; + typedef pcl::PointCloud PointCloudOut; + typedef pcl::PointCloud PointCloudN; + + class Node + { + public: + class Data + { + public: + Data (int id_x, int id_y, int id_z, int lin_id, void* user_data = NULL) + : id_x_ (id_x), + id_y_ (id_y), + id_z_ (id_z), + lin_id_ (lin_id), + num_points_ (0), + user_data_ (user_data) + { + n_[0] = n_[1] = n_[2] = p_[0] = p_[1] = p_[2] = 0.0f; + } + + virtual~ Data (){} + + inline void + addToPoint (float x, float y, float z) + { + p_[0] += x; p_[1] += y; p_[2] += z; + ++num_points_; + } + + inline void + computeAveragePoint () + { + if ( num_points_ < 2 ) + return; + + aux::mult3 (p_, 1.0f/static_cast (num_points_)); + num_points_ = 1; + } + + inline void + addToNormal (float x, float y, float z) { n_[0] += x; n_[1] += y; n_[2] += z;} + + inline const float* + getPoint () const { return p_;} + + inline float* + getPoint (){ return p_;} + + inline const float* + getNormal () const { return n_;} + + inline float* + getNormal (){ return n_;} + + inline void + get3dId (int id[3]) const + { + id[0] = id_x_; + id[1] = id_y_; + id[2] = id_z_; + } + + inline int + get3dIdX () const {return id_x_;} + + inline int + get3dIdY () const {return id_y_;} + + inline int + get3dIdZ () const {return id_z_;} + + inline int + getLinearId () const { return lin_id_;} + + inline void + setUserData (void* user_data){ user_data_ = user_data;} + + inline void* + getUserData () const { return user_data_;} + + inline void + insertNeighbor (Node* node){ neighbors_.insert (node);} + + inline const std::set& + getNeighbors () const { return (neighbors_);} + + protected: + float n_[3], p_[3]; + int id_x_, id_y_, id_z_, lin_id_, num_points_; + std::set neighbors_; + void *user_data_; + }; + + Node () + : data_ (NULL), + parent_ (NULL), + children_(NULL) + {} + + virtual~ Node () + { + this->deleteChildren (); + this->deleteData (); + } + + inline void + setCenter(const float *c) { center_[0] = c[0]; center_[1] = c[1]; center_[2] = c[2];} + + inline void + setBounds(const float *b) { bounds_[0] = b[0]; bounds_[1] = b[1]; bounds_[2] = b[2]; bounds_[3] = b[3]; bounds_[4] = b[4]; bounds_[5] = b[5];} + + inline void + setParent(Node* parent) { parent_ = parent;} + + inline void + setData(Node::Data* data) { data_ = data;} + + /** \brief Computes the "radius" of the node which is half the diagonal length. */ + inline void + computeRadius() + { + float v[3] = {0.5f*(bounds_[1]-bounds_[0]), 0.5f*(bounds_[3]-bounds_[2]), 0.5f*(bounds_[5]-bounds_[4])}; + radius_ = static_cast (aux::length3 (v)); + } + + inline const float* + getCenter() const { return center_;} + + inline const float* + getBounds() const { return bounds_;} + + inline void + getBounds(float b[6]) const + { + memcpy (b, bounds_, 6*sizeof (float)); + } + + inline Node* + getChild (int id) { return &children_[id];} + + inline Node* + getChildren () { return children_;} + + inline Node::Data* + getData (){ return data_;} + + inline const Node::Data* + getData () const { return data_;} + + inline void + setUserData (void* user_data){ data_->setUserData (user_data);} + + inline Node* + getParent (){ return parent_;} + + inline bool + hasData (){ return static_cast (data_);} + + inline bool + hasChildren (){ return static_cast (children_);} + + /** \brief Computes the "radius" of the node which is half the diagonal length. */ + inline float + getRadius (){ return radius_;} + + bool + createChildren (); + + inline void + deleteChildren () + { + if ( children_ ) + { + delete[] children_; + children_ = NULL; + } + } + + inline void + deleteData () + { + if ( data_ ) + { + delete data_; + data_ = NULL; + } + } + + /** \brief Make this and 'node' neighbors by inserting each node in the others node neighbor set. Nothing happens + * of either of the nodes has no data. */ + inline void + makeNeighbors (Node* node) + { + if ( !this->getData () || !node->getData () ) + return; + + this->getData ()->insertNeighbor (node); + node->getData ()->insertNeighbor (this); + } + + protected: + Node::Data *data_; + float center_[3], bounds_[6], radius_; + Node *parent_, *children_; + }; + + ORROctree (); + virtual ~ORROctree (){ this->clear ();} + + void + clear (); + + /** \brief Creates an octree which encloses 'points' and with leaf size equal to 'voxel_size'. + * 'enlarge_bounds' makes sure that no points from the input will lie on the octree boundary + * by enlarging the bounds by that factor. For example, enlarge_bounds = 1 means that the + * bounds will be enlarged by 100%. The default value is fine. */ + void + build (const PointCloudIn& points, float voxel_size, const PointCloudN* normals = NULL, float enlarge_bounds = 0.00001f); + + /** \brief Creates an empty octree with bounds at least as large as the ones provided as input and with leaf + * size equal to 'voxel_size'. */ + void + build (const float* bounds, float voxel_size); + + /** \brief Creates the leaf containing p = (x, y, z) and returns a pointer to it, however, only if p lies within + * the octree bounds! A more general version which allows p to be out of bounds is not implemented yet. The method + * returns NULL if p is not within the root bounds. If the leaf containing p already exists nothing happens and + * method just returns a pointer to the leaf. */ + inline ORROctree::Node* + createLeaf (float x, float y, float z) + { + // Make sure that the input point is within the octree bounds + if ( x < bounds_[0] || x > bounds_[1] || + y < bounds_[2] || y > bounds_[3] || + z < bounds_[4] || z > bounds_[5] ) + { + return (NULL); + } + + ORROctree::Node* node = root_; + const float *c; + int id; + + // Go down to the right leaf + for ( int l = 0 ; l < tree_levels_ ; ++l ) + { + node->createChildren (); + c = node->getCenter (); + id = 0; + + if ( x >= c[0] ) id |= 4; + if ( y >= c[1] ) id |= 2; + if ( z >= c[2] ) id |= 1; + + node = node->getChild (id); + } + + if ( !node->getData () ) + { + Node::Data* data = new Node::Data ( + static_cast ((node->getCenter ()[0] - bounds_[0])/voxel_size_), + static_cast ((node->getCenter ()[1] - bounds_[2])/voxel_size_), + static_cast ((node->getCenter ()[2] - bounds_[4])/voxel_size_), + static_cast (full_leaves_.size ())); + + node->setData (data); + this->insertNeighbors (node); + full_leaves_.push_back (node); + } + + return (node); + } + + /** \brief This method returns a super set of the full leavess which are intersected by the sphere + * with radius 'radius' and centered at 'p'. Pointers to the intersected full leaves are saved in + * 'out'. The method computes a super set in the sense that in general not all leaves saved in 'out' + * are really intersected by the sphere. The intersection test is based on the leaf radius (since + * its faster than checking all leaf corners and sides), so we report more leaves than we should, + * but still, this is a fair approximation. */ + void + getFullLeavesIntersectedBySphere (const float* p, float radius, std::list& out) const; + + /** \brief Randomly chooses and returns a full leaf that is intersected by the sphere with center 'p' + * and 'radius'. Returns NULL if no leaf is intersected by that sphere. */ + ORROctree::Node* + getRandomFullLeafOnSphere (const float* p, float radius) const; + + /** \brief Since the leaves are aligned in a rectilinear grid, each leaf has a unique id. The method returns the leaf + * with id [i, j, k] or NULL is no such leaf exists. */ + ORROctree::Node* + getLeaf (int i, int j, int k) + { + float offset = 0.5f*voxel_size_; + float p[3] = {bounds_[0] + offset + static_cast (i)*voxel_size_, + bounds_[2] + offset + static_cast (j)*voxel_size_, + bounds_[4] + offset + static_cast (k)*voxel_size_}; + + return (this->getLeaf (p[0], p[1], p[2])); + } + + /** \brief Returns a pointer to the leaf containing p = (x, y, z) or NULL if no such leaf exists. */ + inline ORROctree::Node* + getLeaf (float x, float y, float z) + { + // Make sure that the input point is within the octree bounds + if ( x < bounds_[0] || x > bounds_[1] || + y < bounds_[2] || y > bounds_[3] || + z < bounds_[4] || z > bounds_[5] ) + { + return (NULL); + } + + ORROctree::Node* node = root_; + const float *c; + int id; + + // Go down to the right leaf + for ( int l = 0 ; l < tree_levels_ ; ++l ) + { + if ( !node->hasChildren () ) + return (NULL); + + c = node->getCenter (); + id = 0; + + if ( x >= c[0] ) id |= 4; + if ( y >= c[1] ) id |= 2; + if ( z >= c[2] ) id |= 1; + + node = node->getChild (id); + } + + return (node); + } + + /** \brief Deletes the branch 'node' is part of. */ + void + deleteBranch (Node* node); + + /** \brief Returns a vector with all octree leaves which contain at least one point. */ + inline std::vector& + getFullLeaves () { return full_leaves_;} + + inline const std::vector& + getFullLeaves () const { return full_leaves_;} + + void + getFullLeavesPoints (PointCloudOut& out) const; + + void + getNormalsOfFullLeaves (PointCloudN& out) const; + + inline ORROctree::Node* + getRoot (){ return root_;} + + inline const float* + getBounds () const + { + return (bounds_); + } + + inline void + getBounds (float b[6]) const + { + memcpy (b, bounds_, 6*sizeof (float)); + } + + inline float + getVoxelSize () const { return voxel_size_;} + + inline void + insertNeighbors (Node* node) + { + const float* c = node->getCenter (); + float s = 0.5f*voxel_size_; + Node *neigh; + + neigh = this->getLeaf (c[0]+s, c[1]+s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1]+s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1]+s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1] , c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1] , c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1] , c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1]-s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1]-s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1]-s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + + neigh = this->getLeaf (c[0] , c[1]+s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0] , c[1]+s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0] , c[1]+s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0] , c[1] , c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + //neigh = this->getLeaf (c[0] , c[1] , c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0] , c[1] , c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0] , c[1]-s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0] , c[1]-s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0] , c[1]-s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + + neigh = this->getLeaf (c[0]-s, c[1]+s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1]+s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1]+s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1] , c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1] , c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1] , c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1]-s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1]-s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1]-s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + } + + protected: + float voxel_size_, bounds_[6]; + int tree_levels_; + Node* root_; + std::vector full_leaves_; + }; + } // namespace recognition +} // namespace pcl + +#endif /* PCL_RECOGNITION_ORR_OCTREE_H_ */ diff --git a/pcl-1.7/pcl/recognition/orr_octree_zprojection.h b/pcl-1.7/pcl/recognition/orr_octree_zprojection.h new file mode 100644 index 0000000..524a044 --- /dev/null +++ b/pcl-1.7/pcl/recognition/orr_octree_zprojection.h @@ -0,0 +1,216 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/* + * orr_octree_zprojection.h + * + * Created on: Nov 17, 2012 + * Author: papazov + */ + +#ifndef ORR_OCTREE_ZPROJECTION_H_ +#define ORR_OCTREE_ZPROJECTION_H_ + +#include "orr_octree.h" +#include +#include + + +namespace pcl +{ + namespace recognition + { + class ORROctree; + + class PCL_EXPORTS ORROctreeZProjection + { + public: + class Pixel + { + public: + Pixel (int id): id_ (id) {} + + inline void + set_z1 (float z1) { z1_ = z1;} + + inline void + set_z2 (float z2) { z2_ = z2;} + + float + z1 () const { return z1_;} + + float + z2 () const { return z2_;} + + int + getId () const { return id_;} + + protected: + float z1_, z2_; + int id_; + }; + + public: + class Set + { + public: + Set (int x, int y) + : nodes_ (compare_nodes_z), x_ (x), y_ (y) + {} + + static inline bool + compare_nodes_z (ORROctree::Node* node1, ORROctree::Node* node2) + { + return static_cast (node1->getData ()->get3dIdZ () < node2->getData ()->get3dIdZ ()); + } + + inline void + insert (ORROctree::Node* leaf) { nodes_.insert(leaf);} + + inline std::set& + get_nodes (){ return nodes_;} + + inline int + get_x () const { return x_;} + + inline int + get_y () const { return y_;} + + protected: + std::set nodes_; + int x_, y_; + }; + + public: + ORROctreeZProjection () + : pixels_(NULL), + sets_(NULL) + {} + virtual ~ORROctreeZProjection (){ this->clear();} + + void + build (const ORROctree& input, float eps_front, float eps_back); + + void + clear (); + + inline void + getPixelCoordinates (const float* p, int& x, int& y) const + { + x = static_cast ((p[0] - bounds_[0])*inv_pixel_size_); + y = static_cast ((p[1] - bounds_[2])*inv_pixel_size_); + } + + inline const Pixel* + getPixel (const float* p) const + { + int x, y; this->getPixelCoordinates (p, x, y); + + if ( x < 0 || x >= num_pixels_x_ ) return (NULL); + if ( y < 0 || y >= num_pixels_y_ ) return (NULL); + + return (pixels_[x][y]); + } + + inline Pixel* + getPixel (const float* p) + { + int x, y; this->getPixelCoordinates (p, x, y); + + if ( x < 0 || x >= num_pixels_x_ ) return (NULL); + if ( y < 0 || y >= num_pixels_y_ ) return (NULL); + + return (pixels_[x][y]); + } + + inline const std::set* + getOctreeNodes (const float* p) const + { + int x, y; this->getPixelCoordinates (p, x, y); + + if ( x < 0 || x >= num_pixels_x_ ) return (NULL); + if ( y < 0 || y >= num_pixels_y_ ) return (NULL); + + if ( !sets_[x][y] ) + return NULL; + + return (&sets_[x][y]->get_nodes ()); + } + + inline std::list& + getFullPixels (){ return full_pixels_;} + + inline const Pixel* + getPixel (int i, int j) const + { + return pixels_[i][j]; + } + + inline float + getPixelSize () const + { + return pixel_size_; + } + + inline const float* + getBounds () const + { + return bounds_; + } + + /** \brief Get the width ('num_x') and height ('num_y') of the image. */ + inline void + getNumberOfPixels (int& num_x, int& num_y) const + { + num_x = num_pixels_x_; + num_y = num_pixels_y_; + } + + protected: + float pixel_size_, inv_pixel_size_, bounds_[4], extent_x_, extent_y_; + int num_pixels_x_, num_pixels_y_, num_pixels_; + Pixel ***pixels_; + Set ***sets_; + std::list full_sets_; + std::list full_pixels_; + }; + } // namespace recognition +} // namespace pcl + + +#endif /* ORR_OCTREE_ZPROJECTION_H_ */ diff --git a/pcl-1.7/pcl/recognition/point_types.h b/pcl-1.7/pcl/recognition/point_types.h new file mode 100644 index 0000000..8176a38 --- /dev/null +++ b/pcl-1.7/pcl/recognition/point_types.h @@ -0,0 +1,112 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RECOGNITION_POINT_TYPES +#define PCL_RECOGNITION_POINT_TYPES + +#include +#include +#include + + +namespace pcl +{ + + /** \brief A point structure for representing RGB color + * \ingroup common + */ + //struct EIGEN_ALIGN16 PointRGB + //{ + // union + // { + // union + // { + // struct + // { + // uint8_t b; + // uint8_t g; + // uint8_t r; + // uint8_t _unused; + // }; + // float rgb; + // }; + // uint32_t rgba; + // }; + + // inline PointRGB () + // {} + + // inline PointRGB (const uint8_t b, const uint8_t g, const uint8_t r) + // : b (b), g (g), r (r), _unused (0) + // {} + + // EIGEN_MAKE_ALIGNED_OPERATOR_NEW + //}; + + + /** \brief A point structure representing Euclidean xyz coordinates, and the intensity value. + * \ingroup common + */ + struct EIGEN_ALIGN16 GradientXY + { + union + { + struct + { + float x; + float y; + float angle; + float magnitude; + }; + float data[4]; + }; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + inline bool operator< (const GradientXY & rhs) + { + return (magnitude > rhs.magnitude); + } + }; + inline std::ostream & operator << (std::ostream & os, const GradientXY & p) + { + os << "(" << p.x << "," << p.y << " - " << p.magnitude << ")"; + return (os); + } + +} + +#endif diff --git a/pcl-1.7/pcl/recognition/quantizable_modality.h b/pcl-1.7/pcl/recognition/quantizable_modality.h new file mode 100644 index 0000000..c64617b --- /dev/null +++ b/pcl-1.7/pcl/recognition/quantizable_modality.h @@ -0,0 +1,92 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_QUANTIZABLE_MODALITY +#define PCL_FEATURES_QUANTIZABLE_MODALITY + +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Interface for a quantizable modality. + * \author Stefan Holzer + */ + class PCL_EXPORTS QuantizableModality + { + public: + /** \brief Constructor. */ + QuantizableModality (); + /** \brief Destructor. */ + virtual ~QuantizableModality (); + + /** \brief Returns a reference to the internally computed quantized map. */ + virtual QuantizedMap & + getQuantizedMap () = 0; + + /** \brief Returns a reference to the internally computed spreaded quantized map. */ + virtual QuantizedMap & + getSpreadedQuantizedMap () = 0; + + /** \brief Extracts features from this modality within the specified mask. + * \param[in] mask defines the areas where features are searched in. + * \param[in] nr_features defines the number of features to be extracted + * (might be less if not sufficient information is present in the modality). + * \param[in] modality_index the index which is stored in the extracted features. + * \param[out] features the destination for the extracted features. + */ + virtual void + extractFeatures (const MaskMap & mask, size_t nr_features, size_t modality_index, + std::vector & features) const = 0; + + /** \brief Extracts all possible features from the modality within the specified mask. + * \param[in] mask defines the areas where features are searched in. + * \param[in] nr_features IGNORED (TODO: remove this parameter). + * \param[in] modality_index the index which is stored in the extracted features. + * \param[out] features the destination for the extracted features. + */ + virtual void + extractAllFeatures (const MaskMap & mask, size_t nr_features, size_t modality_index, + std::vector & features) const = 0; + }; +} + +#endif diff --git a/pcl-1.7/pcl/recognition/quantized_map.h b/pcl-1.7/pcl/recognition/quantized_map.h new file mode 100644 index 0000000..c61a449 --- /dev/null +++ b/pcl-1.7/pcl/recognition/quantized_map.h @@ -0,0 +1,155 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_QUANTIZED_MAP +#define PCL_FEATURES_QUANTIZED_MAP + +#include +#include + +namespace pcl +{ + class PCL_EXPORTS QuantizedMap + { + public: + + QuantizedMap (); + QuantizedMap (size_t width, size_t height); + QuantizedMap (const QuantizedMap & copy_me); + + virtual ~QuantizedMap (); + + inline size_t + getWidth () const { return (width_); } + + inline size_t + getHeight () const { return (height_); } + + inline unsigned char* + getData () { return (&data_[0]); } + + inline const unsigned char* + getData () const { return (&data_[0]); } + + inline QuantizedMap + getSubMap (size_t x, + size_t y, + size_t width, + size_t height) + { + QuantizedMap subMap(width, height); + + for (size_t row_index = 0; row_index < height; ++row_index) + { + for (size_t col_index = 0; col_index < width; ++col_index) + { + //const size_t index = (row_index+y)*width_ + (col_index+x); + //const unsigned char value = data_[index]; + //subMap.data_[row_index*width + col_index] = value;//data_[(row_index+y)*width_ + (col_index+x)]; + subMap (col_index, row_index) = (*this) (col_index + x, row_index + y); + } + } + + return subMap; + } + + void + resize (size_t width, size_t height); + + inline unsigned char & + operator() (const size_t x, const size_t y) + { + return (data_[y*width_+x]); + } + + inline const unsigned char & + operator() (const size_t x, const size_t y) const + { + return (data_[y*width_+x]); + } + + static void + spreadQuantizedMap (const QuantizedMap & input_map, QuantizedMap & output_map, size_t spreading_size); + + void + serialize (std::ostream & stream) const + { + const int width = static_cast (width_); + const int height = static_cast (height_); + + stream.write (reinterpret_cast (&width), sizeof (width)); + stream.write (reinterpret_cast (&height), sizeof (height)); + + const int num_of_elements = static_cast (data_.size ()); + stream.write (reinterpret_cast (&num_of_elements), sizeof (num_of_elements)); + for (int element_index = 0; element_index < num_of_elements; ++element_index) + { + stream.write (reinterpret_cast (&(data_[element_index])), sizeof (data_[element_index])); + } + } + + void + deserialize (std::istream & stream) + { + int width; + int height; + + stream.read (reinterpret_cast (&width), sizeof (width)); + stream.read (reinterpret_cast (&height), sizeof (height)); + + width_ = static_cast (width); + height_ = static_cast (height); + + int num_of_elements; + stream.read (reinterpret_cast (&num_of_elements), sizeof (num_of_elements)); + data_.resize (num_of_elements); + for (int element_index = 0; element_index < num_of_elements; ++element_index) + { + stream.read (reinterpret_cast (&(data_[element_index])), sizeof (data_[element_index])); + } + } + + + //private: + std::vector data_; + size_t width_; + size_t height_; + + }; +} + +#endif diff --git a/pcl-1.7/pcl/recognition/ransac_based/auxiliary.h b/pcl-1.7/pcl/recognition/ransac_based/auxiliary.h new file mode 100644 index 0000000..91e775c --- /dev/null +++ b/pcl-1.7/pcl/recognition/ransac_based/auxiliary.h @@ -0,0 +1,467 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RECOGNITION_RANSAC_BASED_AUX_H_ +#define PCL_RECOGNITION_RANSAC_BASED_AUX_H_ + +#include +#include +#include +#include + +#define AUX_PI_FLOAT 3.14159265358979323846f +#define AUX_HALF_PI 1.57079632679489661923f +#define AUX_DEG_TO_RADIANS (3.14159265358979323846f/180.0f) + +namespace pcl +{ + namespace recognition + { + namespace aux + { + template bool + compareOrderedPairs (const std::pair& a, const std::pair& b) + { + if ( a.first == b.first ) + return static_cast (a.second < b.second); + + return static_cast (a.first < b.first); + } + + template T + sqr (T a) + { + return (a*a); + } + + template T + clamp (T value, T min, T max) + { + if ( value < min ) + return min; + else if ( value > max ) + return max; + + return value; + } + + /** \brief Expands the destination bounding box 'dst' such that it contains 'src'. */ + template void + expandBoundingBox (T dst[6], const T src[6]) + { + if ( src[0] < dst[0] ) dst[0] = src[0]; + if ( src[2] < dst[2] ) dst[2] = src[2]; + if ( src[4] < dst[4] ) dst[4] = src[4]; + + if ( src[1] > dst[1] ) dst[1] = src[1]; + if ( src[3] > dst[3] ) dst[3] = src[3]; + if ( src[5] > dst[5] ) dst[5] = src[5]; + } + + /** \brief Expands the bounding box 'bbox' such that it contains the point 'p'. */ + template void + expandBoundingBoxToContainPoint (T bbox[6], const T p[3]) + { + if ( p[0] < bbox[0] ) bbox[0] = p[0]; + else if ( p[0] > bbox[1] ) bbox[1] = p[0]; + + if ( p[1] < bbox[2] ) bbox[2] = p[1]; + else if ( p[1] > bbox[3] ) bbox[3] = p[1]; + + if ( p[2] < bbox[4] ) bbox[4] = p[2]; + else if ( p[2] > bbox[5] ) bbox[5] = p[2]; + } + + /** \brief v[0] = v[1] = v[2] = value */ + template void + set3 (T v[3], T value) + { + v[0] = v[1] = v[2] = value; + } + + /** \brief dst = src */ + template void + copy3 (const T src[3], T dst[3]) + { + dst[0] = src[0]; + dst[1] = src[1]; + dst[2] = src[2]; + } + + /** \brief dst = src */ + template void + copy3 (const T src[3], pcl::PointXYZ& dst) + { + dst.x = src[0]; + dst.y = src[1]; + dst.z = src[2]; + } + + /** \brief a = -a */ + template void + flip3 (T a[3]) + { + a[0] = -a[0]; + a[1] = -a[1]; + a[2] = -a[2]; + } + + /** \brief a = b */ + template bool + equal3 (const T a[3], const T b[3]) + { + return (a[0] == b[0] && a[1] == b[1] && a[2] == b[2]); + } + + /** \brief a += b */ + template void + add3 (T a[3], const T b[3]) + { + a[0] += b[0]; + a[1] += b[1]; + a[2] += b[2]; + } + + /** \brief c = a + b */ + template void + sum3 (const T a[3], const T b[3], T c[3]) + { + c[0] = a[0] + b[0]; + c[1] = a[1] + b[1]; + c[2] = a[2] + b[2]; + } + + /** \brief c = a - b */ + template void + diff3 (const T a[3], const T b[3], T c[3]) + { + c[0] = a[0] - b[0]; + c[1] = a[1] - b[1]; + c[2] = a[2] - b[2]; + } + + template void + cross3 (const T v1[3], const T v2[3], T out[3]) + { + out[0] = v1[1]*v2[2] - v1[2]*v2[1]; + out[1] = v1[2]*v2[0] - v1[0]*v2[2]; + out[2] = v1[0]*v2[1] - v1[1]*v2[0]; + } + + /** \brief Returns the length of v. */ + template T + length3 (const T v[3]) + { + return (std::sqrt (v[0]*v[0] + v[1]*v[1] + v[2]*v[2])); + } + + /** \brief Returns the Euclidean distance between a and b. */ + template T + distance3 (const T a[3], const T b[3]) + { + T l[3] = {a[0]-b[0], a[1]-b[1], a[2]-b[2]}; + return (length3 (l)); + } + + /** \brief Returns the squared Euclidean distance between a and b. */ + template T + sqrDistance3 (const T a[3], const T b[3]) + { + return (aux::sqr (a[0]-b[0]) + aux::sqr (a[1]-b[1]) + aux::sqr (a[2]-b[2])); + } + + /** \brief Returns the dot product a*b */ + template T + dot3 (const T a[3], const T b[3]) + { + return (a[0]*b[0] + a[1]*b[1] + a[2]*b[2]); + } + + /** \brief Returns the dot product (x, y, z)*(u, v, w) = x*u + y*v + z*w */ + template T + dot3 (T x, T y, T z, T u, T v, T w) + { + return (x*u + y*v + z*w); + } + + /** \brief v = scalar*v. */ + template void + mult3 (T* v, T scalar) + { + v[0] *= scalar; + v[1] *= scalar; + v[2] *= scalar; + } + + /** \brief out = scalar*v. */ + template void + mult3 (const T* v, T scalar, T* out) + { + out[0] = v[0]*scalar; + out[1] = v[1]*scalar; + out[2] = v[2]*scalar; + } + + /** \brief Normalize v */ + template void + normalize3 (T v[3]) + { + T inv_len = (static_cast (1.0))/aux::length3 (v); + v[0] *= inv_len; + v[1] *= inv_len; + v[2] *= inv_len; + } + + /** \brief Returns the square length of v. */ + template T + sqrLength3 (const T v[3]) + { + return (v[0]*v[0] + v[1]*v[1] + v[2]*v[2]); + } + + /** Projects 'x' on the plane through 0 and with normal 'planeNormal' and saves the result in 'out'. */ + template void + projectOnPlane3 (const T x[3], const T planeNormal[3], T out[3]) + { + T dot = aux::dot3 (planeNormal, x); + // Project 'x' on the plane normal + T nproj[3] = {-dot*planeNormal[0], -dot*planeNormal[1], -dot*planeNormal[2]}; + aux::sum3 (x, nproj, out); + } + + /** \brief Sets 'm' to the 3x3 identity matrix. */ + template void + identity3x3 (T m[9]) + { + m[0] = m[4] = m[8] = 1.0; + m[1] = m[2] = m[3] = m[5] = m[6] = m[7] = 0.0; + } + + /** \brief out = mat*v. 'm' is an 1D array of 9 elements treated as a 3x3 matrix (row major order). */ + template void + mult3x3(const T m[9], const T v[3], T out[3]) + { + out[0] = v[0]*m[0] + v[1]*m[1] + v[2]*m[2]; + out[1] = v[0]*m[3] + v[1]*m[4] + v[2]*m[5]; + out[2] = v[0]*m[6] + v[1]*m[7] + v[2]*m[8]; + } + + /** Let x, y, z be the columns of the matrix a = [x|y|z]. The method computes out = a*m. + * Note that 'out' is a 1D array of 9 elements and the resulting matrix is stored in row + * major order, i.e., the first matrix row is (out[0] out[1] out[2]), the second + * (out[3] out[4] out[5]) and the third (out[6] out[7] out[8]). */ + template void + mult3x3 (const T x[3], const T y[3], const T z[3], const T m[3][3], T out[9]) + { + out[0] = x[0]*m[0][0] + y[0]*m[1][0] + z[0]*m[2][0]; + out[1] = x[0]*m[0][1] + y[0]*m[1][1] + z[0]*m[2][1]; + out[2] = x[0]*m[0][2] + y[0]*m[1][2] + z[0]*m[2][2]; + + out[3] = x[1]*m[0][0] + y[1]*m[1][0] + z[1]*m[2][0]; + out[4] = x[1]*m[0][1] + y[1]*m[1][1] + z[1]*m[2][1]; + out[5] = x[1]*m[0][2] + y[1]*m[1][2] + z[1]*m[2][2]; + + out[6] = x[2]*m[0][0] + y[2]*m[1][0] + z[2]*m[2][0]; + out[7] = x[2]*m[0][1] + y[2]*m[1][1] + z[2]*m[2][1]; + out[8] = x[2]*m[0][2] + y[2]*m[1][2] + z[2]*m[2][2]; + } + + /** \brief The first 9 elements of 't' are treated as a 3x3 matrix (row major order) and the last 3 as a translation. + * First, 'p' is multiplied by that matrix and then translated. The result is saved in 'out'. */ + template void + transform(const T t[12], const T p[3], T out[3]) + { + out[0] = t[0]*p[0] + t[1]*p[1] + t[2]*p[2] + t[9]; + out[1] = t[3]*p[0] + t[4]*p[1] + t[5]*p[2] + t[10]; + out[2] = t[6]*p[0] + t[7]*p[1] + t[8]*p[2] + t[11]; + } + + /** \brief The first 9 elements of 't' are treated as a 3x3 matrix (row major order) and the last 3 as a translation. + * First, (x, y, z) is multiplied by that matrix and then translated. The result is saved in 'out'. */ + template void + transform(const T t[12], T x, T y, T z, T out[3]) + { + out[0] = t[0]*x + t[1]*y + t[2]*z + t[9]; + out[1] = t[3]*x + t[4]*y + t[5]*z + t[10]; + out[2] = t[6]*x + t[7]*y + t[8]*z + t[11]; + } + + /** \brief Compute out = (upper left 3x3 of mat)*p + last column of mat. */ + template void + transform(const Eigen::Matrix& mat, const pcl::PointXYZ& p, pcl::PointXYZ& out) + { + out.x = mat(0,0)*p.x + mat(0,1)*p.y + mat(0,2)*p.z + mat(0,3); + out.y = mat(1,0)*p.x + mat(1,1)*p.y + mat(1,2)*p.z + mat(1,3); + out.z = mat(2,0)*p.x + mat(2,1)*p.y + mat(2,2)*p.z + mat(2,3); + } + + /** \brief The first 9 elements of 't' are treated as a 3x3 matrix (row major order) and the last 3 as a translation. + * First, 'p' is multiplied by that matrix and then translated. The result is saved in 'out'. */ + template void + transform(const T t[12], const pcl::PointXYZ& p, T out[3]) + { + out[0] = t[0]*p.x + t[1]*p.y + t[2]*p.z + t[9]; + out[1] = t[3]*p.x + t[4]*p.y + t[5]*p.z + t[10]; + out[2] = t[6]*p.x + t[7]*p.y + t[8]*p.z + t[11]; + } + + /** \brief Returns true if the points 'p1' and 'p2' are co-planar and false otherwise. The method assumes that 'n1' + * is a normal at 'p1' and 'n2' is a normal at 'p2'. 'max_angle' is the threshold used for the test. The bigger + * the value the larger the deviation between the normals can be which still leads to a positive test result. The + * angle has to be in radians. */ + template bool + pointsAreCoplanar (const T p1[3], const T n1[3], const T p2[3], const T n2[3], T max_angle) + { + // Compute the angle between 'n1' and 'n2' and compare it with 'max_angle' + if ( std::acos (aux::clamp (aux::dot3 (n1, n2), -1.0f, 1.0f)) > max_angle ) + return (false); + + T cl[3] = {p2[0] - p1[0], p2[1] - p1[1], p2[2] - p1[2]}; + aux::normalize3 (cl); + + // Compute the angle between 'cl' and 'n1' + T tmp_angle = std::acos (aux::clamp (aux::dot3 (n1, cl), -1.0f, 1.0f)); + + // 'tmp_angle' should not deviate too much from 90 degrees + if ( std::fabs (tmp_angle - AUX_HALF_PI) > max_angle ) + return (false); + + // All tests passed => the points are coplanar + return (true); + } + + template void + array12ToMatrix4x4 (const Scalar src[12], Eigen::Matrix& dst) + { + dst(0,0) = src[0]; dst(0,1) = src[1]; dst(0,2) = src[2]; dst(0,3) = src[9]; + dst(1,0) = src[3]; dst(1,1) = src[4]; dst(1,2) = src[5]; dst(1,3) = src[10]; + dst(2,0) = src[6]; dst(2,1) = src[7]; dst(2,2) = src[8]; dst(2,3) = src[11]; + dst(3,0) = dst(3,1) = dst(3,2) = 0.0; dst(3,3) = 1.0; + } + + template void + matrix4x4ToArray12 (const Eigen::Matrix& src, Scalar dst[12]) + { + dst[0] = src(0,0); dst[1] = src(0,1); dst[2] = src(0,2); dst[9] = src(0,3); + dst[3] = src(1,0); dst[4] = src(1,1); dst[5] = src(1,2); dst[10] = src(1,3); + dst[6] = src(2,0); dst[7] = src(2,1); dst[8] = src(2,2); dst[11] = src(2,3); + } + + /** \brief The method copies the input array 'src' to the eigen matrix 'dst' in row major order. + * dst[0] = src(0,0); dst[1] = src(0,1); dst[2] = src(0,2); + * dst[3] = src(1,0); dst[4] = src(1,1); dst[5] = src(1,2); + * dst[6] = src(2,0); dst[7] = src(2,1); dst[8] = src(2,2); + * */ + template void + eigenMatrix3x3ToArray9RowMajor (const Eigen::Matrix& src, T dst[9]) + { + dst[0] = src(0,0); dst[1] = src(0,1); dst[2] = src(0,2); + dst[3] = src(1,0); dst[4] = src(1,1); dst[5] = src(1,2); + dst[6] = src(2,0); dst[7] = src(2,1); dst[8] = src(2,2); + } + + /** \brief The method copies the input array 'src' to the eigen matrix 'dst' in row major order. + * dst(0,0) = src[0]; dst(0,1) = src[1]; dst(0,2) = src[2]; + * dst(1,0) = src[3]; dst(1,1) = src[4]; dst(1,2) = src[5]; + * dst(2,0) = src[6]; dst(2,1) = src[7]; dst(2,2) = src[8]; + * */ + template void + toEigenMatrix3x3RowMajor (const T src[9], Eigen::Matrix& dst) + { + dst(0,0) = src[0]; dst(0,1) = src[1]; dst(0,2) = src[2]; + dst(1,0) = src[3]; dst(1,1) = src[4]; dst(1,2) = src[5]; + dst(2,0) = src[6]; dst(2,1) = src[7]; dst(2,2) = src[8]; + } + + /** brief Computes a rotation matrix from the provided input vector 'axis_angle'. The direction of 'axis_angle' is the rotation axis + * and its magnitude is the angle of rotation about that axis. 'rotation_matrix' is the output rotation matrix saved in row major order. */ + template void + axisAngleToRotationMatrix (const T axis_angle[3], T rotation_matrix[9]) + { + // Get the angle of rotation + T angle = aux::length3 (axis_angle); + if ( angle == 0.0 ) + { + // Undefined rotation -> set to identity + aux::identity3x3 (rotation_matrix); + return; + } + + // Normalize the input + T normalized_axis_angle[3]; + aux::mult3 (axis_angle, static_cast (1.0)/angle, normalized_axis_angle); + + // The eigen objects + Eigen::Matrix mat_axis(normalized_axis_angle); + Eigen::AngleAxis eigen_angle_axis (angle, mat_axis); + + // Save the output + aux::eigenMatrix3x3ToArray9RowMajor (eigen_angle_axis.toRotationMatrix (), rotation_matrix); + } + + /** brief Extracts the angle-axis representation from 'rotation_matrix', i.e., computes a rotation 'axis' and an 'angle' + * of rotation about that axis from the provided input. The output 'angle' is in the range [0, pi] and 'axis' is normalized. */ + template void + rotationMatrixToAxisAngle (const T rotation_matrix[9], T axis[3], T& angle) + { + // The eigen objects + Eigen::AngleAxis angle_axis; + Eigen::Matrix rot_mat; + // Copy the input matrix to the eigen matrix in row major order + aux::toEigenMatrix3x3RowMajor (rotation_matrix, rot_mat); + + // Do the computation + angle_axis.fromRotationMatrix (rot_mat); + + // Save the result + axis[0] = angle_axis.axis () (0,0); + axis[1] = angle_axis.axis () (1,0); + axis[2] = angle_axis.axis () (2,0); + angle = angle_axis.angle (); + + // Make sure that 'angle' is in the range [0, pi] + if ( angle > AUX_PI_FLOAT ) + { + angle = 2.0f*AUX_PI_FLOAT - angle; + aux::flip3 (axis); + } + } + } // namespace aux + } // namespace recognition +} // namespace pcl + +#endif // AUX_H_ diff --git a/pcl-1.7/pcl/recognition/ransac_based/bvh.h b/pcl-1.7/pcl/recognition/ransac_based/bvh.h new file mode 100644 index 0000000..bf6e889 --- /dev/null +++ b/pcl-1.7/pcl/recognition/ransac_based/bvh.h @@ -0,0 +1,316 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/* + * bvh.h + * + * Created on: Mar 7, 2013 + * Author: papazov + */ + +#ifndef PCL_RECOGNITION_BVH_H_ +#define PCL_RECOGNITION_BVH_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace recognition + { + /** \brief This class is an implementation of bounding volume hierarchies. Use the build method to construct + * the data structure. To use the class, construct an std::vector of pointers to BVH::BoundedObject objects + * and pass it to the build method. BVH::BoundedObject is a template class, so you can save user-defined data + * in it. + * + * The tree is built such that each leaf contains exactly one object. */ + template + class PCL_EXPORTS BVH + { + public: + class BoundedObject + { + public: + BoundedObject (const UserData& data) + : data_ (data) + { + } + + virtual ~BoundedObject () + { + } + + /** \brief This method is for std::sort. */ + inline static bool + compareCentroidsXCoordinates (const BoundedObject* a, const BoundedObject* b) + { + return static_cast (a->getCentroid ()[0] < b->getCentroid ()[0]); + } + + float* + getBounds () + { + return (bounds_); + } + + float* + getCentroid () + { + return (centroid_); + } + + const float* + getCentroid () const + { + return (centroid_); + } + + UserData& + getData () + { + return (data_); + } + + protected: + /** These are the bounds of the object.*/ + float bounds_[6]; + /** This is the centroid. */ + float centroid_[3]; + /** This is the user-defined data object. */ + UserData data_; + }; + + protected: + class Node + { + public: + /** \brief 'sorted_objects' is a sorted vector of bounded objects. It has to be sorted in ascending order according + * to the objects' x-coordinates. The constructor recursively calls itself with the right 'first_id' and 'last_id' + * and with the same vector 'sorted_objects'. */ + Node (std::vector& sorted_objects, int first_id, int last_id) + { + // Initialize the bounds of the node + memcpy (bounds_, sorted_objects[first_id]->getBounds (), 6*sizeof (float)); + + // Expand the bounds of the node + for ( int i = first_id + 1 ; i <= last_id ; ++i ) + aux::expandBoundingBox(bounds_, sorted_objects[i]->getBounds()); + + // Shall we create children? + if ( first_id != last_id ) + { + // Division by 2 + int mid_id = (first_id + last_id) >> 1; + children_[0] = new Node(sorted_objects, first_id, mid_id); + children_[1] = new Node(sorted_objects, mid_id + 1, last_id); + } + else + { + // We reached a leaf + object_ = sorted_objects[first_id]; + children_[0] = children_[1] = 0; + } + } + + virtual ~Node () + { + if ( children_[0] ) + { + delete children_[0]; + delete children_[1]; + } + } + + bool + hasChildren () const + { + return static_cast(children_[0]); + } + + Node* + getLeftChild () + { + return children_[0]; + } + + Node* + getRightChild () + { + return children_[1]; + } + + BoundedObject* + getObject () + { + return object_; + } + + bool + isLeaf () const + { + return !static_cast(children_[0]); + } + + /** \brief Returns true if 'box' intersects or touches (with a side or a vertex) this node. */ + inline bool + intersect(const float box[6]) const + { + if ( box[1] < bounds_[0] || box[3] < bounds_[2] || box[5] < bounds_[4] || + box[0] > bounds_[1] || box[2] > bounds_[3] || box[4] > bounds_[5] ) + return false; + + return true; + } + + /** \brief Computes and returns the volume of the bounding box of this node. */ + double + computeBoundingBoxVolume() const + { + return (bounds_[1] - bounds_[0]) * (bounds_[3] - bounds_[2]) * (bounds_[5] - bounds_[4]); + } + + friend class BVH; + + protected: + float bounds_[6]; + Node* children_[2]; + BoundedObject* object_; + }; + + public: + BVH() + : root_ (0), + sorted_objects_ (0) + { + } + + virtual ~BVH() + { + this->clear (); + } + + /** \brief Creates the tree. No need to call clear, it's called within the method. 'objects' is a vector of + * pointers to bounded objects which have to have valid bounds and centroids. Use the getData method of + * BoundedObject to retrieve the user-defined data saved in the object. Note that vector will be sorted within + * the method! + * + * The tree is built such that each leaf contains exactly one object. */ + void + build(std::vector& objects) + { + this->clear(); + + if ( objects.size () == 0 ) + return; + + sorted_objects_ = &objects; + + // Now sort the objects according to the x-coordinates of their centroids + std::sort (objects.begin (), objects.end (), BoundedObject::compareCentroidsXCoordinates); + + // Create the root -> it recursively creates the children nodes until each leaf contains exactly one object + root_ = new Node (objects, 0, static_cast (objects.size () - 1)); + } + + /** \brief Frees the memory allocated by this object. After that, you have to call build to use the tree again. */ + void + clear() + { + if ( root_ ) + { + delete root_; + root_ = 0; + } + } + + inline const std::vector* + getInputObjects () const + { + return (sorted_objects_); + } + + /** \brief Pushes back in 'intersected_objects' the bounded objects intersected by the input 'box' and returns true. + * Returns false if no objects are intersected. */ + inline bool + intersect(const float box[6], std::list& intersected_objects) const + { + if ( !root_ ) + return false; + + bool got_intersection = false; + + // Start the intersection process at the root + std::list working_list; + working_list.push_back (root_); + + while ( !working_list.empty () ) + { + Node* node = working_list.front (); + working_list.pop_front (); + + // Is 'node' intersected by the box? + if ( node->intersect (box) ) + { + // We have to check the children of the intersected 'node' + if ( node->hasChildren () ) + { + working_list.push_back (node->getLeftChild ()); + working_list.push_back (node->getRightChild ()); + } + else // 'node' is a leaf -> save it's object in the output list + { + intersected_objects.push_back (node->getObject ()); + got_intersection = true; + } + } + } + + return (got_intersection); + } + + protected: + Node* root_; + std::vector* sorted_objects_; + }; + } // namespace recognition +} // namespace pcl + +#endif /* PCL_RECOGNITION_BVH_H_ */ diff --git a/pcl-1.7/pcl/recognition/ransac_based/hypothesis.h b/pcl-1.7/pcl/recognition/ransac_based/hypothesis.h new file mode 100644 index 0000000..4ac961a --- /dev/null +++ b/pcl-1.7/pcl/recognition/ransac_based/hypothesis.h @@ -0,0 +1,160 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/* + * hypothesis.h + * + * Created on: Mar 12, 2013 + * Author: papazov + */ + +#ifndef PCL_RECOGNITION_HYPOTHESIS_H_ +#define PCL_RECOGNITION_HYPOTHESIS_H_ + +#include +#include + +namespace pcl +{ + namespace recognition + { + class HypothesisBase + { + public: + HypothesisBase (const ModelLibrary::Model* obj_model) + : obj_model_ (obj_model) + {} + + HypothesisBase (const ModelLibrary::Model* obj_model, const float* rigid_transform) + : obj_model_ (obj_model) + { + memcpy (rigid_transform_, rigid_transform, 12*sizeof (float)); + } + + virtual ~HypothesisBase (){} + + void + setModel (const ModelLibrary::Model* model) + { + obj_model_ = model; + } + + public: + float rigid_transform_[12]; + const ModelLibrary::Model* obj_model_; + }; + + class Hypothesis: public HypothesisBase + { + public: + Hypothesis (const ModelLibrary::Model* obj_model = NULL) + : HypothesisBase (obj_model), + match_confidence_ (-1.0f), + linear_id_ (-1) + { + } + + Hypothesis (const Hypothesis& src) + : HypothesisBase (src.obj_model_, src.rigid_transform_), + match_confidence_ (src.match_confidence_), + explained_pixels_ (src.explained_pixels_) + { + } + + virtual ~Hypothesis (){} + + const Hypothesis& + operator =(const Hypothesis& src) + { + memcpy (this->rigid_transform_, src.rigid_transform_, 12*sizeof (float)); + this->obj_model_ = src.obj_model_; + this->match_confidence_ = src.match_confidence_; + this->explained_pixels_ = src.explained_pixels_; + + return *this; + } + + void + setLinearId (int id) + { + linear_id_ = id; + } + + int + getLinearId () const + { + return (linear_id_); + } + + void + computeBounds (float bounds[6]) const + { + const float *b = obj_model_->getBoundsOfOctreePoints (); + float p[3]; + + // Initialize 'bounds' + aux::transform (rigid_transform_, b[0], b[2], b[4], p); + bounds[0] = bounds[1] = p[0]; + bounds[2] = bounds[3] = p[1]; + bounds[4] = bounds[5] = p[2]; + + // Expand 'bounds' to contain the other 7 points of the octree bounding box + aux::transform (rigid_transform_, b[0], b[2], b[5], p); aux::expandBoundingBoxToContainPoint (bounds, p); + aux::transform (rigid_transform_, b[0], b[3], b[4], p); aux::expandBoundingBoxToContainPoint (bounds, p); + aux::transform (rigid_transform_, b[0], b[3], b[5], p); aux::expandBoundingBoxToContainPoint (bounds, p); + aux::transform (rigid_transform_, b[1], b[2], b[4], p); aux::expandBoundingBoxToContainPoint (bounds, p); + aux::transform (rigid_transform_, b[1], b[2], b[5], p); aux::expandBoundingBoxToContainPoint (bounds, p); + aux::transform (rigid_transform_, b[1], b[3], b[4], p); aux::expandBoundingBoxToContainPoint (bounds, p); + aux::transform (rigid_transform_, b[1], b[3], b[5], p); aux::expandBoundingBoxToContainPoint (bounds, p); + } + + void + computeCenterOfMass (float center_of_mass[3]) const + { + aux::transform (rigid_transform_, obj_model_->getOctreeCenterOfMass (), center_of_mass); + } + + public: + float match_confidence_; + std::set explained_pixels_; + int linear_id_; + }; + } // namespace recognition +} // namespace pcl + +#endif /* PCL_RECOGNITION_HYPOTHESIS_H_ */ diff --git a/pcl-1.7/pcl/recognition/ransac_based/model_library.h b/pcl-1.7/pcl/recognition/ransac_based/model_library.h new file mode 100644 index 0000000..c1dc136 --- /dev/null +++ b/pcl-1.7/pcl/recognition/ransac_based/model_library.h @@ -0,0 +1,274 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_RECOGNITION_MODEL_LIBRARY_H_ +#define PCL_RECOGNITION_MODEL_LIBRARY_H_ + +#include "auxiliary.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace recognition + { + class PCL_EXPORTS ModelLibrary + { + public: + typedef pcl::PointCloud PointCloudIn; + typedef pcl::PointCloud PointCloudN; + + /** \brief Stores some information about the model. */ + class Model + { + public: + Model (const PointCloudIn& points, const PointCloudN& normals, float voxel_size, const std::string& object_name, + float frac_of_points_for_registration, void* user_data = NULL) + : obj_name_(object_name), + user_data_ (user_data) + { + octree_.build (points, voxel_size, &normals); + + const std::vector& full_leaves = octree_.getFullLeaves (); + if ( full_leaves.empty () ) + return; + + // Initialize + std::vector::const_iterator it = full_leaves.begin (); + const float *p = (*it)->getData ()->getPoint (); + aux::copy3 (p, octree_center_of_mass_); + bounds_of_octree_points_[0] = bounds_of_octree_points_[1] = p[0]; + bounds_of_octree_points_[2] = bounds_of_octree_points_[3] = p[1]; + bounds_of_octree_points_[4] = bounds_of_octree_points_[5] = p[2]; + + // Compute both the bounds and the center of mass of the octree points + for ( ++it ; it != full_leaves.end () ; ++it ) + { + aux::add3 (octree_center_of_mass_, (*it)->getData ()->getPoint ()); + aux::expandBoundingBoxToContainPoint (bounds_of_octree_points_, (*it)->getData ()->getPoint ()); + } + + int num_octree_points = static_cast (full_leaves.size ()); + // Finalize the center of mass computation + aux::mult3 (octree_center_of_mass_, 1.0f/static_cast (num_octree_points)); + + int num_points_for_registration = static_cast (static_cast (num_octree_points)*frac_of_points_for_registration); + points_for_registration_.resize (static_cast (num_points_for_registration)); + + // Prepare for random point sampling + std::vector ids (num_octree_points); + for ( int i = 0 ; i < num_octree_points ; ++i ) + ids[i] = i; + + // The random generator + pcl::common::UniformGenerator randgen (0, num_octree_points - 1, static_cast (time (NULL))); + + // Randomly sample some points from the octree + for ( int i = 0 ; i < num_points_for_registration ; ++i ) + { + // Choose a random position within the array of ids + randgen.setParameters (0, static_cast (ids.size ()) - 1); + int rand_pos = randgen.run (); + + // Copy the randomly selected octree point + aux::copy3 (octree_.getFullLeaves ()[ids[rand_pos]]->getData ()->getPoint (), points_for_registration_[i]); + + // Delete the selected id + ids.erase (ids.begin() + rand_pos); + } + } + + virtual ~Model () + { + } + + inline const std::string& + getObjectName () const + { + return (obj_name_); + } + + inline const ORROctree& + getOctree () const + { + return (octree_); + } + + inline void* + getUserData () const + { + return (user_data_); + } + + inline const float* + getOctreeCenterOfMass () const + { + return (octree_center_of_mass_); + } + + inline const float* + getBoundsOfOctreePoints () const + { + return (bounds_of_octree_points_); + } + + inline const PointCloudIn& + getPointsForRegistration () const + { + return (points_for_registration_); + } + + protected: + const std::string obj_name_; + ORROctree octree_; + float octree_center_of_mass_[3]; + float bounds_of_octree_points_[6]; + PointCloudIn points_for_registration_; + void* user_data_; + }; + + typedef std::list > node_data_pair_list; + typedef std::map HashTableCell; + typedef VoxelStructure HashTable; + + public: + /** \brief This class is used by 'ObjRecRANSAC' to maintain the object models to be recognized. Normally, you do not need to use + * this class directly. */ + ModelLibrary (float pair_width, float voxel_size, float max_coplanarity_angle = 3.0f*AUX_DEG_TO_RADIANS/*3 degrees*/); + virtual ~ModelLibrary () + { + this->clear(); + } + + /** \brief Removes all models from the library and clears the hash table. */ + void + removeAllModels (); + + /** \brief This is a threshold. The larger the value the more point pairs will be considered as co-planar and will + * be ignored in the off-line model pre-processing and in the online recognition phases. This makes sense only if + * "ignore co-planar points" is on. Call this method before calling addModel. */ + inline void + setMaxCoplanarityAngleDegrees (float max_coplanarity_angle_degrees) + { + max_coplanarity_angle_ = max_coplanarity_angle_degrees*AUX_DEG_TO_RADIANS; + } + + /** \brief Call this method in order NOT to add co-planar point pairs to the hash table. The default behavior + * is ignoring co-planar points on. */ + inline void + ignoreCoplanarPointPairsOn () + { + ignore_coplanar_opps_ = true; + } + + /** \brief Call this method in order to add all point pairs (co-planar as well) to the hash table. The default + * behavior is ignoring co-planar points on. */ + inline void + ignoreCoplanarPointPairsOff () + { + ignore_coplanar_opps_ = false; + } + + /** \brief Adds a model to the hash table. + * + * \param[in] points represents the model to be added. + * \param[in] normals are the normals at the model points. + * \param[in] object_name is the unique name of the object to be added. + * \param[in] frac_of_points_for_registration is the number of points used for fast ICP registration prior to hypothesis testing + * \param[in] user_data is a pointer to some data (can be NULL) + * + * Returns true if model successfully added and false otherwise (e.g., if object_name is not unique). */ + bool + addModel (const PointCloudIn& points, const PointCloudN& normals, const std::string& object_name, + float frac_of_points_for_registration, void* user_data = NULL); + + /** \brief Returns the hash table built by this instance. */ + inline const HashTable& + getHashTable () const + { + return (hash_table_); + } + + inline const Model* + getModel (const std::string& name) const + { + std::map::const_iterator it = models_.find (name); + if ( it != models_.end () ) + return (it->second); + + return (NULL); + } + + inline const std::map& + getModels () const + { + return (models_); + } + + protected: + /** \brief Removes all models from the library and destroys the hash table. This method should be called upon destroying this object. */ + void + clear (); + + /** \brief Returns true if the oriented point pair was added to the hash table and false otherwise. */ + bool + addToHashTable (Model* model, const ORROctree::Node::Data* data1, const ORROctree::Node::Data* data2); + + protected: + float pair_width_; + float voxel_size_; + float max_coplanarity_angle_; + bool ignore_coplanar_opps_; + + std::map models_; + HashTable hash_table_; + int num_of_cells_[3]; + }; + } // namespace recognition +} // namespace pcl + +#endif // PCL_RECOGNITION_MODEL_LIBRARY_H_ diff --git a/pcl-1.7/pcl/recognition/ransac_based/obj_rec_ransac.h b/pcl-1.7/pcl/recognition/ransac_based/obj_rec_ransac.h new file mode 100644 index 0000000..fe1ed38 --- /dev/null +++ b/pcl-1.7/pcl/recognition/ransac_based/obj_rec_ransac.h @@ -0,0 +1,484 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_RECOGNITION_OBJ_REC_RANSAC_H_ +#define PCL_RECOGNITION_OBJ_REC_RANSAC_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define OBJ_REC_RANSAC_VERBOSE + +namespace pcl +{ + namespace recognition + { + /** \brief This is a RANSAC-based 3D object recognition method. Do the following to use it: (i) call addModel() k times with k different models + * representing the objects to be recognized and (ii) call recognize() with the 3D scene in which the objects should be recognized. Recognition means both + * object identification and pose (position + orientation) estimation. Check the method descriptions for more details. + * + * \note If you use this code in any academic work, please cite: + * + * - Chavdar Papazov, Sami Haddadin, Sven Parusel, Kai Krieger and Darius Burschka. + * Rigid 3D geometry matching for grasping of known objects in cluttered scenes. + * The International Journal of Robotics Research 2012. DOI: 10.1177/0278364911436019 + * + * - Chavdar Papazov and Darius Burschka. + * An Efficient RANSAC for 3D Object Recognition in Noisy and Occluded Scenes. + * In Proceedings of the 10th Asian Conference on Computer Vision (ACCV'10), + * November 2010. + * + * + * \author Chavdar Papazov + * \ingroup recognition + */ + class PCL_EXPORTS ObjRecRANSAC + { + public: + typedef ModelLibrary::PointCloudIn PointCloudIn; + typedef ModelLibrary::PointCloudN PointCloudN; + + typedef BVH BVHH; + + /** \brief This is an output item of the ObjRecRANSAC::recognize() method. It contains the recognized model, its name (the ones passed to + * ObjRecRANSAC::addModel()), the rigid transform which aligns the model with the input scene and the match confidence which is a number + * in the interval (0, 1] which gives the fraction of the model surface area matched to the scene. E.g., a match confidence of 0.3 means + * that 30% of the object surface area was matched to the scene points. If the scene is represented by a single range image, the match + * confidence can not be greater than 0.5 since the range scanner sees only one side of each object. + */ + class Output + { + public: + Output (const std::string& object_name, const float rigid_transform[12], float match_confidence, void* user_data) : + object_name_ (object_name), + match_confidence_ (match_confidence), + user_data_ (user_data) + { + memcpy(this->rigid_transform_, rigid_transform, 12*sizeof (float)); + } + virtual ~Output (){} + + public: + std::string object_name_; + float rigid_transform_[12]; + float match_confidence_; + void* user_data_; + }; + + class OrientedPointPair + { + public: + OrientedPointPair (const float *p1, const float *n1, const float *p2, const float *n2) + : p1_ (p1), n1_ (n1), p2_ (p2), n2_ (n2) + { + } + + virtual ~OrientedPointPair (){} + + public: + const float *p1_, *n1_, *p2_, *n2_; + }; + + class HypothesisCreator + { + public: + HypothesisCreator (){} + virtual ~HypothesisCreator (){} + + Hypothesis* create (const SimpleOctree::Node* ) const { return new Hypothesis ();} + }; + + typedef SimpleOctree HypothesisOctree; + + public: + /** \brief Constructor with some important parameters which can not be changed once an instance of that class is created. + * + * \param[in] pair_width should be roughly half the extent of the visible object part. This means, for each object point p there should be (at least) + * one point q (from the same object) such that ||p - q|| <= pair_width. Tradeoff: smaller values allow for detection in more occluded scenes but lead + * to more imprecise alignment. Bigger values lead to better alignment but require large visible object parts (i.e., less occlusion). + * + * \param[in] voxel_size is the size of the leafs of the octree, i.e., the "size" of the discretization. Tradeoff: High values lead to less + * computation time but ignore object details. Small values allow to better distinguish between objects, but will introduce more holes in the resulting + * "voxel-surface" (especially for a sparsely sampled scene). */ + ObjRecRANSAC (float pair_width, float voxel_size); + virtual ~ObjRecRANSAC () + { + this->clear (); + this->clearTestData (); + } + + /** \brief Removes all models from the model library and releases some memory dynamically allocated by this instance. */ + void + inline clear() + { + model_library_.removeAllModels (); + scene_octree_.clear (); + scene_octree_proj_.clear (); + sampled_oriented_point_pairs_.clear (); + transform_space_.clear (); + scene_octree_points_.reset (); + } + + /** \brief This is a threshold. The larger the value the more point pairs will be considered as co-planar and will + * be ignored in the off-line model pre-processing and in the online recognition phases. This makes sense only if + * "ignore co-planar points" is on. Call this method before calling addModel. This method calls the corresponding + * method of the model library. */ + inline void + setMaxCoplanarityAngleDegrees (float max_coplanarity_angle_degrees) + { + max_coplanarity_angle_ = max_coplanarity_angle_degrees*AUX_DEG_TO_RADIANS; + model_library_.setMaxCoplanarityAngleDegrees (max_coplanarity_angle_degrees); + } + + inline void + setSceneBoundsEnlargementFactor (float value) + { + scene_bounds_enlargement_factor_ = value; + } + + /** \brief Default is on. This method calls the corresponding method of the model library. */ + inline void + ignoreCoplanarPointPairsOn () + { + ignore_coplanar_opps_ = true; + model_library_.ignoreCoplanarPointPairsOn (); + } + + /** \brief Default is on. This method calls the corresponding method of the model library. */ + inline void + ignoreCoplanarPointPairsOff () + { + ignore_coplanar_opps_ = false; + model_library_.ignoreCoplanarPointPairsOff (); + } + + inline void + icpHypothesesRefinementOn () + { + do_icp_hypotheses_refinement_ = true; + } + + inline void + icpHypothesesRefinementOff () + { + do_icp_hypotheses_refinement_ = false; + } + + /** \brief Add an object model to be recognized. + * + * \param[in] points are the object points. + * \param[in] normals at each point. + * \param[in] object_name is an identifier for the object. If that object is detected in the scene 'object_name' + * is returned by the recognition method and you know which object has been detected. Note that 'object_name' has + * to be unique! + * \param[in] user_data is a pointer to some data (can be NULL) + * + * The method returns true if the model was successfully added to the model library and false otherwise (e.g., if 'object_name' is already in use). + */ + inline bool + addModel (const PointCloudIn& points, const PointCloudN& normals, const std::string& object_name, void* user_data = NULL) + { + return (model_library_.addModel (points, normals, object_name, frac_of_points_for_icp_refinement_, user_data)); + } + + /** \brief This method performs the recognition of the models loaded to the model library with the method addModel(). + * + * \param[in] scene is the 3d scene in which the object should be recognized. + * \param[in] normals are the scene normals. + * \param[out] recognized_objects is the list of output items each one containing the recognized model instance, its name, the aligning rigid transform + * and the match confidence (see ObjRecRANSAC::Output for further explanations). + * \param[in] success_probability is the user-defined probability of detecting all objects in the scene. + */ + void + recognize (const PointCloudIn& scene, const PointCloudN& normals, std::list& recognized_objects, double success_probability = 0.99); + + inline void + enterTestModeSampleOPP () + { + rec_mode_ = ObjRecRANSAC::SAMPLE_OPP; + } + + inline void + enterTestModeTestHypotheses () + { + rec_mode_ = ObjRecRANSAC::TEST_HYPOTHESES; + } + + inline void + leaveTestMode () + { + rec_mode_ = ObjRecRANSAC::FULL_RECOGNITION; + } + + /** \brief This function is useful for testing purposes. It returns the oriented point pairs which were sampled from the + * scene during the recognition process. Makes sense only if some of the testing modes are active. */ + inline const std::list& + getSampledOrientedPointPairs () const + { + return (sampled_oriented_point_pairs_); + } + + /** \brief This function is useful for testing purposes. It returns the accepted hypotheses generated during the + * recognition process. Makes sense only if some of the testing modes are active. */ + inline const std::vector& + getAcceptedHypotheses () const + { + return (accepted_hypotheses_); + } + + /** \brief This function is useful for testing purposes. It returns the accepted hypotheses generated during the + * recognition process. Makes sense only if some of the testing modes are active. */ + inline void + getAcceptedHypotheses (std::vector& out) const + { + out = accepted_hypotheses_; + } + + /** \brief Returns the hash table in the model library. */ + inline const pcl::recognition::ModelLibrary::HashTable& + getHashTable () const + { + return (model_library_.getHashTable ()); + } + + inline const ModelLibrary& + getModelLibrary () const + { + return (model_library_); + } + + inline const ModelLibrary::Model* + getModel (const std::string& name) const + { + return (model_library_.getModel (name)); + } + + inline const ORROctree& + getSceneOctree () const + { + return (scene_octree_); + } + + inline RigidTransformSpace& + getRigidTransformSpace () + { + return (transform_space_); + } + + inline float + getPairWidth () const + { + return pair_width_; + } + + protected: + enum Recognition_Mode {SAMPLE_OPP, TEST_HYPOTHESES, /*BUILD_CONFLICT_GRAPH,*/ FULL_RECOGNITION}; + + friend class ModelLibrary; + + inline int + computeNumberOfIterations (double success_probability) const + { + // 'p_obj' is the probability that given that the first sample point belongs to an object, + // the second sample point will belong to the same object + const double p_obj = 0.25f; + // old version: p = p_obj*relative_obj_size_*fraction_of_pairs_in_hash_table_; + const double p = p_obj*relative_obj_size_; + + if ( 1.0 - p <= 0.0 ) + return 1; + + return static_cast (log (1.0-success_probability)/log (1.0-p) + 1.0); + } + + inline void + clearTestData () + { + sampled_oriented_point_pairs_.clear (); + accepted_hypotheses_.clear (); + transform_space_.clear (); + } + + void + sampleOrientedPointPairs (int num_iterations, const std::vector& full_scene_leaves, std::list& output) const; + + int + generateHypotheses (const std::list& pairs, std::list& out) const; + + /** \brief Groups close hypotheses in 'hypotheses'. Saves a representative for each group in 'out'. Returns the + * number of hypotheses after grouping. */ + int + groupHypotheses(std::list& hypotheses, int num_hypotheses, RigidTransformSpace& transform_space, + HypothesisOctree& grouped_hypotheses) const; + + inline void + testHypothesis (Hypothesis* hypothesis, int& match, int& penalty) const; + + inline void + testHypothesisNormalBased (Hypothesis* hypothesis, float& match) const; + + void + buildGraphOfCloseHypotheses (HypothesisOctree& hypotheses, ORRGraph& graph) const; + + void + filterGraphOfCloseHypotheses (ORRGraph& graph, std::vector& out) const; + + void + buildGraphOfConflictingHypotheses (const BVHH& bvh, ORRGraph& graph) const; + + void + filterGraphOfConflictingHypotheses (ORRGraph& graph, std::list& recognized_objects) const; + + /** \brief Computes the rigid transform that maps the line (a1, b1) to (a2, b2). + * The computation is based on the corresponding points 'a1' <-> 'a2' and 'b1' <-> 'b2' + * and the normals 'a1_n', 'b1_n', 'a2_n', and 'b2_n'. The result is saved in + * 'rigid_transform' which is an array of length 12. The first 9 elements are the + * rotational part (row major order) and the last 3 are the translation. */ + inline void + computeRigidTransform( + const float *a1, const float *a1_n, const float *b1, const float* b1_n, + const float *a2, const float *a2_n, const float *b2, const float* b2_n, + float* rigid_transform) const + { + // Some local variables + float o1[3], o2[3], x1[3], x2[3], y1[3], y2[3], z1[3], z2[3], tmp1[3], tmp2[3], Ro1[3], invFrame1[3][3]; + + // Compute the origins + o1[0] = 0.5f*(a1[0] + b1[0]); + o1[1] = 0.5f*(a1[1] + b1[1]); + o1[2] = 0.5f*(a1[2] + b1[2]); + + o2[0] = 0.5f*(a2[0] + b2[0]); + o2[1] = 0.5f*(a2[1] + b2[1]); + o2[2] = 0.5f*(a2[2] + b2[2]); + + // Compute the x-axes + aux::diff3 (b1, a1, x1); aux::normalize3 (x1); + aux::diff3 (b2, a2, x2); aux::normalize3 (x2); + // Compute the y-axes. First y-axis + aux::projectOnPlane3 (a1_n, x1, tmp1); aux::normalize3 (tmp1); + aux::projectOnPlane3 (b1_n, x1, tmp2); aux::normalize3 (tmp2); + aux::sum3 (tmp1, tmp2, y1); aux::normalize3 (y1); + // Second y-axis + aux::projectOnPlane3 (a2_n, x2, tmp1); aux::normalize3 (tmp1); + aux::projectOnPlane3 (b2_n, x2, tmp2); aux::normalize3 (tmp2); + aux::sum3 (tmp1, tmp2, y2); aux::normalize3 (y2); + // Compute the z-axes + aux::cross3 (x1, y1, z1); + aux::cross3 (x2, y2, z2); + + // 1. Invert the matrix [x1|y1|z1] (note that x1, y1, and z1 are treated as columns!) + invFrame1[0][0] = x1[0]; invFrame1[0][1] = x1[1]; invFrame1[0][2] = x1[2]; + invFrame1[1][0] = y1[0]; invFrame1[1][1] = y1[1]; invFrame1[1][2] = y1[2]; + invFrame1[2][0] = z1[0]; invFrame1[2][1] = z1[1]; invFrame1[2][2] = z1[2]; + // 2. Compute the desired rotation as rigid_transform = [x2|y2|z2]*invFrame1 + aux::mult3x3 (x2, y2, z2, invFrame1, rigid_transform); + + // Construct the translation which is the difference between the rotated o1 and o2 + aux::mult3x3 (rigid_transform, o1, Ro1); + rigid_transform[9] = o2[0] - Ro1[0]; + rigid_transform[10] = o2[1] - Ro1[1]; + rigid_transform[11] = o2[2] - Ro1[2]; + } + + /** \brief Computes the signature of the oriented point pair ((p1, n1), (p2, n2)) consisting of the angles between + * \param p1 + * \param n1 + * \param p2 + * \param n2 + * \param[out] signature is an array of three doubles saving the three angles in the order shown above. */ + static inline void + compute_oriented_point_pair_signature (const float *p1, const float *n1, const float *p2, const float *n2, float signature[3]) + { + // Get the line from p1 to p2 + float cl[3] = {p2[0] - p1[0], p2[1] - p1[1], p2[2] - p1[2]}; + aux::normalize3 (cl); + + signature[0] = std::acos (aux::clamp (aux::dot3 (n1,cl), -1.0f, 1.0f)); cl[0] = -cl[0]; cl[1] = -cl[1]; cl[2] = -cl[2]; + signature[1] = std::acos (aux::clamp (aux::dot3 (n2,cl), -1.0f, 1.0f)); + signature[2] = std::acos (aux::clamp (aux::dot3 (n1,n2), -1.0f, 1.0f)); + } + + protected: + // Parameters + float pair_width_; + float voxel_size_; + float position_discretization_; + float rotation_discretization_; + float abs_zdist_thresh_; + float relative_obj_size_; + float visibility_; + float relative_num_of_illegal_pts_; + float intersection_fraction_; + float max_coplanarity_angle_; + float scene_bounds_enlargement_factor_; + bool ignore_coplanar_opps_; + float frac_of_points_for_icp_refinement_; + bool do_icp_hypotheses_refinement_; + + ModelLibrary model_library_; + ORROctree scene_octree_; + ORROctreeZProjection scene_octree_proj_; + RigidTransformSpace transform_space_; + TrimmedICP trimmed_icp_; + PointCloudIn::Ptr scene_octree_points_; + + std::list sampled_oriented_point_pairs_; + std::vector accepted_hypotheses_; + Recognition_Mode rec_mode_; + }; + } // namespace recognition +} // namespace pcl + +#endif // PCL_RECOGNITION_OBJ_REC_RANSAC_H_ diff --git a/pcl-1.7/pcl/recognition/ransac_based/orr_graph.h b/pcl-1.7/pcl/recognition/ransac_based/orr_graph.h new file mode 100644 index 0000000..351d6ad --- /dev/null +++ b/pcl-1.7/pcl/recognition/ransac_based/orr_graph.h @@ -0,0 +1,225 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/* + * orr_graph.h + * + * Created on: Nov 23, 2012 + * Author: papazov + */ + +#ifndef PCL_RECOGNITION_ORR_GRAPH_H_ +#define PCL_RECOGNITION_ORR_GRAPH_H_ + +#include + +namespace pcl +{ + namespace recognition + { + template + class ORRGraph + { + public: + class Node + { + public: + enum State {ON, OFF, UNDEF}; + + Node (int id) + : id_ (id), + state_(UNDEF) + {} + + virtual ~Node (){} + + inline const std::set& + getNeighbors () const + { + return (neighbors_); + } + + inline const NodeData& + getData () const + { + return (data_); + } + + inline void + setData (const NodeData& data) + { + data_ = data; + } + + inline int + getId () const + { + return (id_); + } + + inline void + setId (int id) + { + id_ = id; + } + + inline void + setFitness (int fitness) + { + fitness_ = fitness; + } + + static inline bool + compare (const Node* a, const Node* b) + { + return (static_cast (a->fitness_ > b->fitness_)); + } + + friend class ORRGraph; + + protected: + std::set neighbors_; + NodeData data_; + int id_; + int fitness_; + State state_; + }; + + public: + ORRGraph (){} + virtual ~ORRGraph (){ this->clear ();} + + inline void + clear () + { + for ( typename std::vector::iterator nit = nodes_.begin () ; nit != nodes_.end () ; ++nit ) + delete *nit; + + nodes_.clear (); + } + + /** \brief Drops all existing graph nodes and creates 'n' new ones. */ + inline void + resize (int n) + { + if ( !n ) + return; + + for ( typename std::vector::iterator nit = nodes_.begin () ; nit != nodes_.end () ; ++nit ) + delete *nit; + + nodes_.resize (static_cast (n)); + + for ( int i = 0 ; i < n ; ++i ) + nodes_[i] = new Node (i); + } + + inline void + computeMaximalOnOffPartition (std::list& on_nodes, std::list& off_nodes) + { + std::vector sorted_nodes (nodes_.size ()); + int i = 0; + + // Set all nodes to undefined + for ( typename std::vector::iterator it = nodes_.begin () ; it != nodes_.end () ; ++it ) + { + sorted_nodes[i++] = *it; + (*it)->state_ = Node::UNDEF; + } + + // Now sort the nodes according to the fitness + std::sort (sorted_nodes.begin (), sorted_nodes.end (), Node::compare); + + // Now run through the array and start switching nodes on and off + for ( typename std::vector::iterator it = sorted_nodes.begin () ; it != sorted_nodes.end () ; ++it ) + { + // Ignore graph nodes which are already OFF + if ( (*it)->state_ == Node::OFF ) + continue; + + // Set the node to ON + (*it)->state_ = Node::ON; + + // Set all its neighbors to OFF + for ( typename std::set::iterator neigh = (*it)->neighbors_.begin () ; neigh != (*it)->neighbors_.end () ; ++neigh ) + { + (*neigh)->state_ = Node::OFF; + off_nodes.push_back (*neigh); + } + + // Output the node + on_nodes.push_back (*it); + } + } + + inline void + insertUndirectedEdge (int id1, int id2) + { + nodes_[id1]->neighbors_.insert (nodes_[id2]); + nodes_[id2]->neighbors_.insert (nodes_[id1]); + } + + inline void + insertDirectedEdge (int id1, int id2) + { + nodes_[id1]->neighbors_.insert (nodes_[id2]); + } + + inline void + deleteUndirectedEdge (int id1, int id2) + { + nodes_[id1]->neighbors_.erase (nodes_[id2]); + nodes_[id2]->neighbors_.erase (nodes_[id1]); + } + + inline void + deleteDirectedEdge (int id1, int id2) + { + nodes_[id1]->neighbors_.erase (nodes_[id2]); + } + + inline typename std::vector& + getNodes (){ return nodes_;} + + public: + typename std::vector nodes_; + }; + } // namespace recognition +} // namespace pcl + +#endif /* PCL_RECOGNITION_ORR_GRAPH_H_ */ diff --git a/pcl-1.7/pcl/recognition/ransac_based/orr_octree.h b/pcl-1.7/pcl/recognition/ransac_based/orr_octree.h new file mode 100644 index 0000000..8eaad54 --- /dev/null +++ b/pcl-1.7/pcl/recognition/ransac_based/orr_octree.h @@ -0,0 +1,492 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/* + * orr_octree.h + * + * Created on: Oct 23, 2012 + * Author: papazov + */ + +#ifndef PCL_RECOGNITION_ORR_OCTREE_H_ +#define PCL_RECOGNITION_ORR_OCTREE_H_ + +#include "auxiliary.h" +#include +#include +#include +#include +#include +#include +#include +#include + +//#define PCL_REC_ORR_OCTREE_VERBOSE + +namespace pcl +{ + namespace recognition + { + /** \brief That's a very specialized and simple octree class. That's the way it is intended to + * be, that's why no templates and stuff like this. + * + * \author Chavdar Papazov + * \ingroup recognition + */ + class PCL_EXPORTS ORROctree + { + public: + typedef pcl::PointCloud PointCloudIn; + typedef pcl::PointCloud PointCloudOut; + typedef pcl::PointCloud PointCloudN; + + class Node + { + public: + class Data + { + public: + Data (int id_x, int id_y, int id_z, int lin_id, void* user_data = NULL) + : id_x_ (id_x), + id_y_ (id_y), + id_z_ (id_z), + lin_id_ (lin_id), + num_points_ (0), + user_data_ (user_data) + { + n_[0] = n_[1] = n_[2] = p_[0] = p_[1] = p_[2] = 0.0f; + } + + virtual~ Data (){} + + inline void + addToPoint (float x, float y, float z) + { + p_[0] += x; p_[1] += y; p_[2] += z; + ++num_points_; + } + + inline void + computeAveragePoint () + { + if ( num_points_ < 2 ) + return; + + aux::mult3 (p_, 1.0f/static_cast (num_points_)); + num_points_ = 1; + } + + inline void + addToNormal (float x, float y, float z) { n_[0] += x; n_[1] += y; n_[2] += z;} + + inline const float* + getPoint () const { return p_;} + + inline float* + getPoint (){ return p_;} + + inline const float* + getNormal () const { return n_;} + + inline float* + getNormal (){ return n_;} + + inline void + get3dId (int id[3]) const + { + id[0] = id_x_; + id[1] = id_y_; + id[2] = id_z_; + } + + inline int + get3dIdX () const {return id_x_;} + + inline int + get3dIdY () const {return id_y_;} + + inline int + get3dIdZ () const {return id_z_;} + + inline int + getLinearId () const { return lin_id_;} + + inline void + setUserData (void* user_data){ user_data_ = user_data;} + + inline void* + getUserData () const { return user_data_;} + + inline void + insertNeighbor (Node* node){ neighbors_.insert (node);} + + inline const std::set& + getNeighbors () const { return (neighbors_);} + + protected: + float n_[3], p_[3]; + int id_x_, id_y_, id_z_, lin_id_, num_points_; + std::set neighbors_; + void *user_data_; + }; + + Node () + : data_ (NULL), + parent_ (NULL), + children_(NULL) + {} + + virtual~ Node () + { + this->deleteChildren (); + this->deleteData (); + } + + inline void + setCenter(const float *c) { center_[0] = c[0]; center_[1] = c[1]; center_[2] = c[2];} + + inline void + setBounds(const float *b) { bounds_[0] = b[0]; bounds_[1] = b[1]; bounds_[2] = b[2]; bounds_[3] = b[3]; bounds_[4] = b[4]; bounds_[5] = b[5];} + + inline void + setParent(Node* parent) { parent_ = parent;} + + inline void + setData(Node::Data* data) { data_ = data;} + + /** \brief Computes the "radius" of the node which is half the diagonal length. */ + inline void + computeRadius() + { + float v[3] = {0.5f*(bounds_[1]-bounds_[0]), 0.5f*(bounds_[3]-bounds_[2]), 0.5f*(bounds_[5]-bounds_[4])}; + radius_ = static_cast (aux::length3 (v)); + } + + inline const float* + getCenter() const { return center_;} + + inline const float* + getBounds() const { return bounds_;} + + inline void + getBounds(float b[6]) const + { + memcpy (b, bounds_, 6*sizeof (float)); + } + + inline Node* + getChild (int id) { return &children_[id];} + + inline Node* + getChildren () { return children_;} + + inline Node::Data* + getData (){ return data_;} + + inline const Node::Data* + getData () const { return data_;} + + inline void + setUserData (void* user_data){ data_->setUserData (user_data);} + + inline Node* + getParent (){ return parent_;} + + inline bool + hasData (){ return static_cast (data_);} + + inline bool + hasChildren (){ return static_cast (children_);} + + /** \brief Computes the "radius" of the node which is half the diagonal length. */ + inline float + getRadius (){ return radius_;} + + bool + createChildren (); + + inline void + deleteChildren () + { + if ( children_ ) + { + delete[] children_; + children_ = NULL; + } + } + + inline void + deleteData () + { + if ( data_ ) + { + delete data_; + data_ = NULL; + } + } + + /** \brief Make this and 'node' neighbors by inserting each node in the others node neighbor set. Nothing happens + * of either of the nodes has no data. */ + inline void + makeNeighbors (Node* node) + { + if ( !this->getData () || !node->getData () ) + return; + + this->getData ()->insertNeighbor (node); + node->getData ()->insertNeighbor (this); + } + + protected: + Node::Data *data_; + float center_[3], bounds_[6], radius_; + Node *parent_, *children_; + }; + + ORROctree (); + virtual ~ORROctree (){ this->clear ();} + + void + clear (); + + /** \brief Creates an octree which encloses 'points' and with leaf size equal to 'voxel_size'. + * 'enlarge_bounds' makes sure that no points from the input will lie on the octree boundary + * by enlarging the bounds by that factor. For example, enlarge_bounds = 1 means that the + * bounds will be enlarged by 100%. The default value is fine. */ + void + build (const PointCloudIn& points, float voxel_size, const PointCloudN* normals = NULL, float enlarge_bounds = 0.00001f); + + /** \brief Creates an empty octree with bounds at least as large as the ones provided as input and with leaf + * size equal to 'voxel_size'. */ + void + build (const float* bounds, float voxel_size); + + /** \brief Creates the leaf containing p = (x, y, z) and returns a pointer to it, however, only if p lies within + * the octree bounds! A more general version which allows p to be out of bounds is not implemented yet. The method + * returns NULL if p is not within the root bounds. If the leaf containing p already exists nothing happens and + * method just returns a pointer to the leaf. */ + inline ORROctree::Node* + createLeaf (float x, float y, float z) + { + // Make sure that the input point is within the octree bounds + if ( x < bounds_[0] || x > bounds_[1] || + y < bounds_[2] || y > bounds_[3] || + z < bounds_[4] || z > bounds_[5] ) + { + return (NULL); + } + + ORROctree::Node* node = root_; + const float *c; + int id; + + // Go down to the right leaf + for ( int l = 0 ; l < tree_levels_ ; ++l ) + { + node->createChildren (); + c = node->getCenter (); + id = 0; + + if ( x >= c[0] ) id |= 4; + if ( y >= c[1] ) id |= 2; + if ( z >= c[2] ) id |= 1; + + node = node->getChild (id); + } + + if ( !node->getData () ) + { + Node::Data* data = new Node::Data ( + static_cast ((node->getCenter ()[0] - bounds_[0])/voxel_size_), + static_cast ((node->getCenter ()[1] - bounds_[2])/voxel_size_), + static_cast ((node->getCenter ()[2] - bounds_[4])/voxel_size_), + static_cast (full_leaves_.size ())); + + node->setData (data); + this->insertNeighbors (node); + full_leaves_.push_back (node); + } + + return (node); + } + + /** \brief This method returns a super set of the full leavess which are intersected by the sphere + * with radius 'radius' and centered at 'p'. Pointers to the intersected full leaves are saved in + * 'out'. The method computes a super set in the sense that in general not all leaves saved in 'out' + * are really intersected by the sphere. The intersection test is based on the leaf radius (since + * its faster than checking all leaf corners and sides), so we report more leaves than we should, + * but still, this is a fair approximation. */ + void + getFullLeavesIntersectedBySphere (const float* p, float radius, std::list& out) const; + + /** \brief Randomly chooses and returns a full leaf that is intersected by the sphere with center 'p' + * and 'radius'. Returns NULL if no leaf is intersected by that sphere. */ + ORROctree::Node* + getRandomFullLeafOnSphere (const float* p, float radius) const; + + /** \brief Since the leaves are aligned in a rectilinear grid, each leaf has a unique id. The method returns the leaf + * with id [i, j, k] or NULL is no such leaf exists. */ + ORROctree::Node* + getLeaf (int i, int j, int k) + { + float offset = 0.5f*voxel_size_; + float p[3] = {bounds_[0] + offset + static_cast (i)*voxel_size_, + bounds_[2] + offset + static_cast (j)*voxel_size_, + bounds_[4] + offset + static_cast (k)*voxel_size_}; + + return (this->getLeaf (p[0], p[1], p[2])); + } + + /** \brief Returns a pointer to the leaf containing p = (x, y, z) or NULL if no such leaf exists. */ + inline ORROctree::Node* + getLeaf (float x, float y, float z) + { + // Make sure that the input point is within the octree bounds + if ( x < bounds_[0] || x > bounds_[1] || + y < bounds_[2] || y > bounds_[3] || + z < bounds_[4] || z > bounds_[5] ) + { + return (NULL); + } + + ORROctree::Node* node = root_; + const float *c; + int id; + + // Go down to the right leaf + for ( int l = 0 ; l < tree_levels_ ; ++l ) + { + if ( !node->hasChildren () ) + return (NULL); + + c = node->getCenter (); + id = 0; + + if ( x >= c[0] ) id |= 4; + if ( y >= c[1] ) id |= 2; + if ( z >= c[2] ) id |= 1; + + node = node->getChild (id); + } + + return (node); + } + + /** \brief Deletes the branch 'node' is part of. */ + void + deleteBranch (Node* node); + + /** \brief Returns a vector with all octree leaves which contain at least one point. */ + inline std::vector& + getFullLeaves () { return full_leaves_;} + + inline const std::vector& + getFullLeaves () const { return full_leaves_;} + + void + getFullLeavesPoints (PointCloudOut& out) const; + + void + getNormalsOfFullLeaves (PointCloudN& out) const; + + inline ORROctree::Node* + getRoot (){ return root_;} + + inline const float* + getBounds () const + { + return (bounds_); + } + + inline void + getBounds (float b[6]) const + { + memcpy (b, bounds_, 6*sizeof (float)); + } + + inline float + getVoxelSize () const { return voxel_size_;} + + inline void + insertNeighbors (Node* node) + { + const float* c = node->getCenter (); + float s = 0.5f*voxel_size_; + Node *neigh; + + neigh = this->getLeaf (c[0]+s, c[1]+s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1]+s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1]+s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1] , c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1] , c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1] , c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1]-s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1]-s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]+s, c[1]-s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + + neigh = this->getLeaf (c[0] , c[1]+s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0] , c[1]+s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0] , c[1]+s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0] , c[1] , c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + //neigh = this->getLeaf (c[0] , c[1] , c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0] , c[1] , c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0] , c[1]-s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0] , c[1]-s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0] , c[1]-s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + + neigh = this->getLeaf (c[0]-s, c[1]+s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1]+s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1]+s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1] , c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1] , c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1] , c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1]-s, c[2]+s); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1]-s, c[2] ); if ( neigh ) node->makeNeighbors (neigh); + neigh = this->getLeaf (c[0]-s, c[1]-s, c[2]-s); if ( neigh ) node->makeNeighbors (neigh); + } + + protected: + float voxel_size_, bounds_[6]; + int tree_levels_; + Node* root_; + std::vector full_leaves_; + }; + } // namespace recognition +} // namespace pcl + +#endif /* PCL_RECOGNITION_ORR_OCTREE_H_ */ diff --git a/pcl-1.7/pcl/recognition/ransac_based/orr_octree_zprojection.h b/pcl-1.7/pcl/recognition/ransac_based/orr_octree_zprojection.h new file mode 100644 index 0000000..524a044 --- /dev/null +++ b/pcl-1.7/pcl/recognition/ransac_based/orr_octree_zprojection.h @@ -0,0 +1,216 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/* + * orr_octree_zprojection.h + * + * Created on: Nov 17, 2012 + * Author: papazov + */ + +#ifndef ORR_OCTREE_ZPROJECTION_H_ +#define ORR_OCTREE_ZPROJECTION_H_ + +#include "orr_octree.h" +#include +#include + + +namespace pcl +{ + namespace recognition + { + class ORROctree; + + class PCL_EXPORTS ORROctreeZProjection + { + public: + class Pixel + { + public: + Pixel (int id): id_ (id) {} + + inline void + set_z1 (float z1) { z1_ = z1;} + + inline void + set_z2 (float z2) { z2_ = z2;} + + float + z1 () const { return z1_;} + + float + z2 () const { return z2_;} + + int + getId () const { return id_;} + + protected: + float z1_, z2_; + int id_; + }; + + public: + class Set + { + public: + Set (int x, int y) + : nodes_ (compare_nodes_z), x_ (x), y_ (y) + {} + + static inline bool + compare_nodes_z (ORROctree::Node* node1, ORROctree::Node* node2) + { + return static_cast (node1->getData ()->get3dIdZ () < node2->getData ()->get3dIdZ ()); + } + + inline void + insert (ORROctree::Node* leaf) { nodes_.insert(leaf);} + + inline std::set& + get_nodes (){ return nodes_;} + + inline int + get_x () const { return x_;} + + inline int + get_y () const { return y_;} + + protected: + std::set nodes_; + int x_, y_; + }; + + public: + ORROctreeZProjection () + : pixels_(NULL), + sets_(NULL) + {} + virtual ~ORROctreeZProjection (){ this->clear();} + + void + build (const ORROctree& input, float eps_front, float eps_back); + + void + clear (); + + inline void + getPixelCoordinates (const float* p, int& x, int& y) const + { + x = static_cast ((p[0] - bounds_[0])*inv_pixel_size_); + y = static_cast ((p[1] - bounds_[2])*inv_pixel_size_); + } + + inline const Pixel* + getPixel (const float* p) const + { + int x, y; this->getPixelCoordinates (p, x, y); + + if ( x < 0 || x >= num_pixels_x_ ) return (NULL); + if ( y < 0 || y >= num_pixels_y_ ) return (NULL); + + return (pixels_[x][y]); + } + + inline Pixel* + getPixel (const float* p) + { + int x, y; this->getPixelCoordinates (p, x, y); + + if ( x < 0 || x >= num_pixels_x_ ) return (NULL); + if ( y < 0 || y >= num_pixels_y_ ) return (NULL); + + return (pixels_[x][y]); + } + + inline const std::set* + getOctreeNodes (const float* p) const + { + int x, y; this->getPixelCoordinates (p, x, y); + + if ( x < 0 || x >= num_pixels_x_ ) return (NULL); + if ( y < 0 || y >= num_pixels_y_ ) return (NULL); + + if ( !sets_[x][y] ) + return NULL; + + return (&sets_[x][y]->get_nodes ()); + } + + inline std::list& + getFullPixels (){ return full_pixels_;} + + inline const Pixel* + getPixel (int i, int j) const + { + return pixels_[i][j]; + } + + inline float + getPixelSize () const + { + return pixel_size_; + } + + inline const float* + getBounds () const + { + return bounds_; + } + + /** \brief Get the width ('num_x') and height ('num_y') of the image. */ + inline void + getNumberOfPixels (int& num_x, int& num_y) const + { + num_x = num_pixels_x_; + num_y = num_pixels_y_; + } + + protected: + float pixel_size_, inv_pixel_size_, bounds_[4], extent_x_, extent_y_; + int num_pixels_x_, num_pixels_y_, num_pixels_; + Pixel ***pixels_; + Set ***sets_; + std::list full_sets_; + std::list full_pixels_; + }; + } // namespace recognition +} // namespace pcl + + +#endif /* ORR_OCTREE_ZPROJECTION_H_ */ diff --git a/pcl-1.7/pcl/recognition/ransac_based/rigid_transform_space.h b/pcl-1.7/pcl/recognition/ransac_based/rigid_transform_space.h new file mode 100644 index 0000000..86574b0 --- /dev/null +++ b/pcl-1.7/pcl/recognition/ransac_based/rigid_transform_space.h @@ -0,0 +1,414 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/* + * rigid_transform_space.h + * + * Created on: Feb 15, 2013 + * Author: papazov + */ + +#ifndef PCL_RECOGNITION_RIGID_TRANSFORM_SPACE_H_ +#define PCL_RECOGNITION_RIGID_TRANSFORM_SPACE_H_ + +#include "simple_octree.h" +#include "model_library.h" +#include +#include +#include + +namespace pcl +{ + namespace recognition + { + class RotationSpaceCell + { + public: + class Entry + { + public: + Entry () + : num_transforms_ (0) + { + aux::set3 (axis_angle_, 0.0f); + aux::set3 (translation_, 0.0f); + } + + Entry (const Entry& src) + : num_transforms_ (src.num_transforms_) + { + aux::copy3 (src.axis_angle_, this->axis_angle_); + aux::copy3 (src.translation_, this->translation_); + } + + const Entry& operator = (const Entry& src) + { + num_transforms_ = src.num_transforms_; + aux::copy3 (src.axis_angle_, this->axis_angle_); + aux::copy3 (src.translation_, this->translation_); + + return *this; + } + + inline const Entry& + addRigidTransform (const float axis_angle[3], const float translation[3]) + { + aux::add3 (this->axis_angle_, axis_angle); + aux::add3 (this->translation_, translation); + ++num_transforms_; + + return *this; + } + + inline void + computeAverageRigidTransform (float *rigid_transform = NULL) + { + if ( num_transforms_ >= 2 ) + { + float factor = 1.0f/static_cast (num_transforms_); + aux::mult3 (axis_angle_, factor); + aux::mult3 (translation_, factor); + num_transforms_ = 1; + } + + if ( rigid_transform ) + { + // Save the rotation (in matrix form) + aux::axisAngleToRotationMatrix (axis_angle_, rigid_transform); + // Save the translation + aux::copy3 (translation_, rigid_transform + 9); + } + } + + inline const float* + getAxisAngle () const + { + return (axis_angle_); + } + + inline const float* + getTranslation () const + { + return (translation_); + } + + inline int + getNumberOfTransforms () const + { + return (num_transforms_); + } + + protected: + float axis_angle_[3], translation_[3]; + int num_transforms_; + };// class Entry + + public: + RotationSpaceCell (){} + virtual ~RotationSpaceCell () + { + model_to_entry_.clear (); + } + + inline std::map& + getEntries () + { + return (model_to_entry_); + } + + inline const RotationSpaceCell::Entry* + getEntry (const ModelLibrary::Model* model) const + { + std::map::const_iterator res = model_to_entry_.find (model); + + if ( res != model_to_entry_.end () ) + return (&res->second); + + return (NULL); + } + + inline const RotationSpaceCell::Entry& + addRigidTransform (const ModelLibrary::Model* model, const float axis_angle[3], const float translation[3]) + { + return model_to_entry_[model].addRigidTransform (axis_angle, translation); + } + + protected: + std::map model_to_entry_; + }; // class RotationSpaceCell + + class RotationSpaceCellCreator + { + public: + RotationSpaceCellCreator (){} + virtual ~RotationSpaceCellCreator (){} + + RotationSpaceCell* create (const SimpleOctree::Node* ) + { + return (new RotationSpaceCell ()); + } + }; + + typedef SimpleOctree CellOctree; + + /** \brief This is a class for a discrete representation of the rotation space based on the axis-angle representation. + * This class is not supposed to be very general. That's why it is dependent on the class ModelLibrary. + * + * \author Chavdar Papazov + * \ingroup recognition + */ + class PCL_EXPORTS RotationSpace + { + public: + /** \brief We use the axis-angle representation for rotations. The axis is encoded in the vector + * and the angle is its magnitude. This is represented in an octree with bounds [-pi, pi]^3. */ + RotationSpace (float discretization) + { + float min = -(AUX_PI_FLOAT + 0.000000001f), max = AUX_PI_FLOAT + 0.000000001f; + float bounds[6] = {min, max, min, max, min, max}; + + // Build the voxel structure + octree_.build (bounds, discretization, &cell_creator_); + } + + virtual ~RotationSpace () + { + octree_.clear (); + } + + inline void + setCenter (const float* c) + { + center_[0] = c[0]; + center_[1] = c[1]; + center_[2] = c[2]; + } + + inline const float* + getCenter () const { return center_;} + + inline bool + getTransformWithMostVotes (const ModelLibrary::Model* model, float rigid_transform[12]) const + { + RotationSpaceCell::Entry with_most_votes; + const std::vector& full_leaves = octree_.getFullLeaves (); + int max_num_transforms = 0; + + // For each full leaf + for ( std::vector::const_iterator leaf = full_leaves.begin () ; leaf != full_leaves.end () ; ++leaf ) + { + // Is there an entry for 'model' in the current cell + const RotationSpaceCell::Entry *entry = (*leaf)->getData ().getEntry (model); + if ( !entry ) + continue; + + int num_transforms = entry->getNumberOfTransforms (); + const std::set& neighs = (*leaf)->getNeighbors (); + + // For each neighbor + for ( std::set::const_iterator neigh = neighs.begin () ; neigh != neighs.end () ; ++neigh ) + { + const RotationSpaceCell::Entry *neigh_entry = (*neigh)->getData ().getEntry (model); + if ( !neigh_entry ) + continue; + + num_transforms += neigh_entry->getNumberOfTransforms (); + } + + if ( num_transforms > max_num_transforms ) + { + with_most_votes = *entry; + max_num_transforms = num_transforms; + } + } + + if ( !max_num_transforms ) + return false; + + with_most_votes.computeAverageRigidTransform (rigid_transform); + + return true; + } + + inline bool + addRigidTransform (const ModelLibrary::Model* model, const float axis_angle[3], const float translation[3]) + { + CellOctree::Node* cell = octree_.createLeaf (axis_angle[0], axis_angle[1], axis_angle[2]); + + if ( !cell ) + { + const float *b = octree_.getBounds (); + printf ("WARNING in 'RotationSpace::%s()': the provided axis-angle input (%f, %f, %f) is " + "out of the rotation space bounds ([%f, %f], [%f, %f], [%f, %f]).\n", + __func__, axis_angle[0], axis_angle[1], axis_angle[2], b[0], b[1], b[2], b[3], b[4], b[5]); + return (false); + } + + // Add the rigid transform to the cell + cell->getData ().addRigidTransform (model, axis_angle, translation); + + return (true); + } + + protected: + CellOctree octree_; + RotationSpaceCellCreator cell_creator_; + float center_[3]; + };// class RotationSpace + + class RotationSpaceCreator + { + public: + RotationSpaceCreator() + : counter_ (0) + {} + + virtual ~RotationSpaceCreator(){} + + RotationSpace* create(const SimpleOctree::Node* leaf) + { + RotationSpace *rot_space = new RotationSpace (discretization_); + rot_space->setCenter (leaf->getCenter ()); + rotation_spaces_.push_back (rot_space); + + ++counter_; + + return (rot_space); + } + + void + setDiscretization (float value){ discretization_ = value;} + + int + getNumberOfRotationSpaces () const { return (counter_);} + + const std::list& + getRotationSpaces () const { return (rotation_spaces_);} + + std::list& + getRotationSpaces (){ return (rotation_spaces_);} + + void + reset () + { + counter_ = 0; + rotation_spaces_.clear (); + } + + protected: + float discretization_; + int counter_; + std::list rotation_spaces_; + }; + + typedef SimpleOctree RotationSpaceOctree; + + class PCL_EXPORTS RigidTransformSpace + { + public: + RigidTransformSpace (){} + virtual ~RigidTransformSpace (){ this->clear ();} + + inline void + build (const float* pos_bounds, float translation_cell_size, float rotation_cell_size) + { + this->clear (); + + rotation_space_creator_.setDiscretization (rotation_cell_size); + + pos_octree_.build (pos_bounds, translation_cell_size, &rotation_space_creator_); + } + + inline void + clear () + { + pos_octree_.clear (); + rotation_space_creator_.reset (); + } + + inline std::list& + getRotationSpaces () + { + return (rotation_space_creator_.getRotationSpaces ()); + } + + inline const std::list& + getRotationSpaces () const + { + return (rotation_space_creator_.getRotationSpaces ()); + } + + inline int + getNumberOfOccupiedRotationSpaces () + { + return (rotation_space_creator_.getNumberOfRotationSpaces ()); + } + + inline bool + addRigidTransform (const ModelLibrary::Model* model, const float position[3], const float rigid_transform[12]) + { + // Get the leaf 'position' ends up in + RotationSpaceOctree::Node* leaf = pos_octree_.createLeaf (position[0], position[1], position[2]); + + if ( !leaf ) + { + printf ("WARNING in 'RigidTransformSpace::%s()': the input position (%f, %f, %f) is out of bounds.\n", + __func__, position[0], position[1], position[2]); + return (false); + } + + float rot_angle, axis_angle[3]; + // Extract the axis-angle representation from the rotation matrix + aux::rotationMatrixToAxisAngle (rigid_transform, axis_angle, rot_angle); + // Multiply the axis by the angle to get the final representation + aux::mult3 (axis_angle, rot_angle); + + // Now, add the rigid transform to the rotation space + leaf->getData ().addRigidTransform (model, axis_angle, rigid_transform + 9); + + return (true); + } + + protected: + RotationSpaceOctree pos_octree_; + RotationSpaceCreator rotation_space_creator_; + }; // class RigidTransformSpace + } // namespace recognition +} // namespace pcl + +#endif /* PCL_RECOGNITION_RIGID_TRANSFORM_SPACE_H_ */ diff --git a/pcl-1.7/pcl/recognition/ransac_based/simple_octree.h b/pcl-1.7/pcl/recognition/ransac_based/simple_octree.h new file mode 100644 index 0000000..db42ced --- /dev/null +++ b/pcl-1.7/pcl/recognition/ransac_based/simple_octree.h @@ -0,0 +1,211 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/* + * simple_octree.h + * + * Created on: Mar 11, 2013 + * Author: papazov + */ + +#ifndef SIMPLE_OCTREE_H_ +#define SIMPLE_OCTREE_H_ + +#include +#include + +namespace pcl +{ + namespace recognition + { + template + class PCL_EXPORTS SimpleOctree + { + public: + class Node + { + public: + Node (); + + virtual~ Node (); + + inline void + setCenter (const Scalar *c); + + inline void + setBounds (const Scalar *b); + + inline const Scalar* + getCenter () const { return center_;} + + inline const Scalar* + getBounds () const { return bounds_;} + + inline void + getBounds (Scalar b[6]) const { memcpy (b, bounds_, 6*sizeof (Scalar));} + + inline Node* + getChild (int id) { return &children_[id];} + + inline Node* + getChildren () { return children_;} + + inline void + setData (const NodeData& src){ *data_ = src;} + + inline NodeData& + getData (){ return *data_;} + + inline const NodeData& + getData () const { return *data_;} + + inline Node* + getParent (){ return parent_;} + + inline float + getRadius () const { return radius_;} + + inline bool + hasData (){ return static_cast (data_);} + + inline bool + hasChildren (){ return static_cast (children_);} + + inline const std::set& + getNeighbors () const { return (full_leaf_neighbors_);} + + inline void + deleteChildren (); + + inline void + deleteData (); + + friend class SimpleOctree; + + protected: + void + setData (NodeData* data){ if ( data_ ) delete data_; data_ = data;} + + inline bool + createChildren (); + + /** \brief Make this and 'node' neighbors by inserting each node in the others node neighbor set. Nothing happens + * of either of the nodes has no data. */ + inline void + makeNeighbors (Node* node); + + inline void + setParent (Node* parent){ parent_ = parent;} + + /** \brief Computes the "radius" of the node which is half the diagonal length. */ + inline void + computeRadius (); + + protected: + NodeData *data_; + Scalar center_[3], bounds_[6]; + Node *parent_, *children_; + Scalar radius_; + std::set full_leaf_neighbors_; + }; + + public: + SimpleOctree (); + + virtual ~SimpleOctree (); + + void + clear (); + + /** \brief Creates an empty octree with bounds at least as large as the ones provided as input and with leaf + * size equal to 'voxel_size'. */ + void + build (const Scalar* bounds, Scalar voxel_size, NodeDataCreator* node_data_creator); + + /** \brief Creates the leaf containing p = (x, y, z) and returns a pointer to it, however, only if p lies within + * the octree bounds! A more general version which allows p to be out of bounds is not implemented yet. The method + * returns NULL if p is not within the root bounds. If the leaf containing p already exists nothing happens and + * method just returns a pointer to the leaf. Note that for a new created leaf, the method also creates its data + * object. */ + inline Node* + createLeaf (Scalar x, Scalar y, Scalar z); + + /** \brief Since the leaves are aligned in a rectilinear grid, each leaf has a unique id. The method returns the full + * leaf, i.e., the one having a data object, with id [i, j, k] or NULL is no such leaf exists. */ + inline Node* + getFullLeaf (int i, int j, int k); + + /** \brief Returns a pointer to the full leaf, i.e., one having a data pbject, containing p = (x, y, z) or NULL if no such leaf exists. */ + inline Node* + getFullLeaf (Scalar x, Scalar y, Scalar z); + + inline std::vector& + getFullLeaves () { return full_leaves_;} + + inline const std::vector& + getFullLeaves () const { return full_leaves_;} + + inline Node* + getRoot (){ return root_;} + + inline const Scalar* + getBounds () const { return (bounds_);} + + inline void + getBounds (Scalar b[6]) const { memcpy (b, bounds_, 6*sizeof (Scalar));} + + inline Scalar + getVoxelSize () const { return voxel_size_;} + + protected: + inline void + insertNeighbors (Node* node); + + protected: + Scalar voxel_size_, bounds_[6]; + int tree_levels_; + Node* root_; + std::vector full_leaves_; + NodeDataCreator* node_data_creator_; + }; + } // namespace recognition +} // namespace pcl + +#include + +#endif /* SIMPLE_OCTREE_H_ */ diff --git a/pcl-1.7/pcl/recognition/ransac_based/trimmed_icp.h b/pcl-1.7/pcl/recognition/ransac_based/trimmed_icp.h new file mode 100644 index 0000000..e07bab0 --- /dev/null +++ b/pcl-1.7/pcl/recognition/ransac_based/trimmed_icp.h @@ -0,0 +1,187 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +/* + * trimmed_icp.h + * + * Created on: Mar 10, 2013 + * Author: papazov + */ + +#ifndef TRIMMED_ICP_H_ +#define TRIMMED_ICP_H_ + +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace recognition + { + template + class PCL_EXPORTS TrimmedICP: public pcl::registration::TransformationEstimationSVD + { + public: + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename Eigen::Matrix Matrix4; + + public: + TrimmedICP () + : new_to_old_energy_ratio_ (0.99f) + {} + + virtual ~TrimmedICP () + {} + + /** \brief Call this method before calling align(). + * + * \param[in] target is target point cloud. The method builds a kd-tree based on 'target' for performing fast closest point search. + * The source point cloud will be registered to 'target' (see align() method). + * */ + inline void + init (const PointCloudConstPtr& target) + { + target_points_ = target; + kdtree_.setInputCloud (target); + } + + /** \brief The method performs trimmed ICP, i.e., it rigidly registers the source to the target (passed to the init() method). + * + * \param[in] source_points is the point cloud to be registered to the target. + * \param[in] num_source_points_to_use gives the number of closest source points taken into account for registration. By closest + * source points we mean the source points closest to the target. These points are computed anew at each iteration. + * \param[in,out] guess_and_result is the estimated rigid transform. IMPORTANT: this matrix is also taken as the initial guess + * for the alignment. If there is no guess, set the matrix to identity! + * */ + inline void + align (const PointCloud& source_points, int num_source_points_to_use, Matrix4& guess_and_result) const + { + int num_trimmed_source_points = num_source_points_to_use, num_source_points = static_cast (source_points.size ()); + + if ( num_trimmed_source_points >= num_source_points ) + { + printf ("WARNING in 'TrimmedICP::%s()': the user-defined number of source points of interest is greater or equal to " + "the total number of source points. Trimmed ICP will work correctly but won't be very efficient. Either set " + "the number of source points to use to a lower value or use standard ICP.\n", __func__); + num_trimmed_source_points = num_source_points; + } + + // These are vectors containing source to target correspondences + pcl::Correspondences full_src_to_tgt (num_source_points), trimmed_src_to_tgt (num_trimmed_source_points); + + // Some variables for the closest point search + pcl::PointXYZ transformed_source_point; + std::vector target_index (1); + std::vector sqr_dist_to_target (1); + float old_energy, energy = std::numeric_limits::max (); + +// printf ("\nalign\n"); + + do + { + // Update the correspondences + for ( int i = 0 ; i < num_source_points ; ++i ) + { + // Transform the i-th source point based on the current transform matrix + aux::transform (guess_and_result, source_points.points[i], transformed_source_point); + + // Perform the closest point search + kdtree_.nearestKSearch (transformed_source_point, 1, target_index, sqr_dist_to_target); + + // Update the i-th correspondence + full_src_to_tgt[i].index_query = i; + full_src_to_tgt[i].index_match = target_index[0]; + full_src_to_tgt[i].distance = sqr_dist_to_target[0]; + } + + // Sort in ascending order according to the squared distance + std::sort (full_src_to_tgt.begin (), full_src_to_tgt.end (), TrimmedICP::compareCorrespondences); + + old_energy = energy; + energy = 0.0f; + + // Now, setup the trimmed correspondences used for the transform estimation + for ( int i = 0 ; i < num_trimmed_source_points ; ++i ) + { + trimmed_src_to_tgt[i].index_query = full_src_to_tgt[i].index_query; + trimmed_src_to_tgt[i].index_match = full_src_to_tgt[i].index_match; + energy += full_src_to_tgt[i].distance; + } + + this->estimateRigidTransformation (source_points, *target_points_, trimmed_src_to_tgt, guess_and_result); + +// printf ("energy = %f, energy diff. = %f, ratio = %f\n", energy, old_energy - energy, energy/old_energy); + } + while ( energy/old_energy < new_to_old_energy_ratio_ ); // iterate if enough progress + +// printf ("\n"); + } + + inline void + setNewToOldEnergyRatio (float ratio) + { + if ( ratio >= 1 ) + new_to_old_energy_ratio_ = 0.99f; + else + new_to_old_energy_ratio_ = ratio; + } + + protected: + static inline bool + compareCorrespondences (const pcl::Correspondence& a, const pcl::Correspondence& b) + { + return static_cast (a.distance < b.distance); + } + + protected: + PointCloudConstPtr target_points_; + pcl::KdTreeFLANN kdtree_; + float new_to_old_energy_ratio_; + }; + } // namespace recognition +} // namespace pcl + + +#endif /* TRIMMED_ICP_H_ */ diff --git a/pcl-1.7/pcl/recognition/ransac_based/voxel_structure.h b/pcl-1.7/pcl/recognition/ransac_based/voxel_structure.h new file mode 100644 index 0000000..ed90c4d --- /dev/null +++ b/pcl-1.7/pcl/recognition/ransac_based/voxel_structure.h @@ -0,0 +1,171 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_RECOGNITION_VOXEL_STRUCTURE_H_ +#define PCL_RECOGNITION_VOXEL_STRUCTURE_H_ + +#include + +namespace pcl +{ + namespace recognition + { + /** \brief This class is a box in R3 built of voxels ordered in a regular rectangular grid. Each voxel is of type T. */ + template + class VoxelStructure + { + public: + inline VoxelStructure (): voxels_(NULL){} + inline virtual ~VoxelStructure (){ this->clear();} + + /** \brief Call this method before using an instance of this class. Parameter meaning is obvious. */ + inline void + build (const REAL bounds[6], int num_of_voxels[3]); + + /** \brief Release the memory allocated for the voxels. */ + inline void + clear (){ if ( voxels_ ){ delete[] voxels_; voxels_ = NULL;}} + + /** \brief Returns a pointer to the voxel which contains p or NULL if p is not inside the structure. */ + inline T* + getVoxel (const REAL p[3]); + + /** \brief Returns a pointer to the voxel with integer id (x,y,z) or NULL if (x,y,z) is out of bounds. */ + inline T* + getVoxel (int x, int y, int z) const; + + /** \brief Returns the linear voxel array. */ + const inline T* + getVoxels () const + { + return voxels_; + } + + /** \brief Returns the linear voxel array. */ + inline T* + getVoxels () + { + return voxels_; + } + + /** \brief Converts a linear id to a 3D id, i.e., computes the integer 3D coordinates of a voxel from its position in the voxel array. + * + * \param[in] linear_id the position of the voxel in the internal voxel array. + * \param[out] id3d an array of 3 integers for the integer coordinates of the voxel. */ + inline void + compute3dId (int linear_id, int id3d[3]) const + { + // Compute the z axis id + id3d[2] = linear_id / num_of_voxels_xy_plane_; + int proj_xy = linear_id % num_of_voxels_xy_plane_; + // Compute the y axis id + id3d[1] = proj_xy / num_of_voxels_[0]; + // Compute the x axis id + id3d[0] = proj_xy % num_of_voxels_[0]; + } + + /** \brief Returns the number of voxels in x, y and z direction. */ + inline const int* + getNumberOfVoxelsXYZ() const + { + return (num_of_voxels_); + } + + /** \brief Computes the center of the voxel with given integer coordinates. + * + * \param[in] id3 the integer coordinates along the x, y and z axis. + * \param[out] center */ + inline void + computeVoxelCenter (const int id3[3], REAL center[3]) const + { + center[0] = min_center_[0] + static_cast (id3[0])*spacing_[0]; + center[1] = min_center_[1] + static_cast (id3[1])*spacing_[1]; + center[2] = min_center_[2] + static_cast (id3[2])*spacing_[2]; + } + + /** \brief Returns the total number of voxels. */ + inline int + getNumberOfVoxels() const + { + return (total_num_of_voxels_); + } + + /** \brief Returns the bounds of the voxel structure, which is pointer to the internal array of 6 doubles: (min_x, max_x, min_y, max_y, min_z, max_z). */ + inline const float* + getBounds() const + { + return (bounds_); + } + + /** \brief Copies the bounds of the voxel structure to 'b'. */ + inline void + getBounds(REAL b[6]) const + { + b[0] = bounds_[0]; + b[1] = bounds_[1]; + b[2] = bounds_[2]; + b[3] = bounds_[3]; + b[4] = bounds_[4]; + b[5] = bounds_[5]; + } + + /** \brief Returns the voxel spacing in x, y and z direction. That's the same as the voxel size along each axis. */ + const REAL* + getVoxelSpacing() const + { + return (spacing_); + } + + /** \brief Saves pointers to the voxels which are neighbors of the voxels which contains 'p'. The containing voxel is returned too. + * 'neighs' has to be an array of pointers with space for at least 27 pointers (27 = 3^3 which is the max number of neighbors). The */ + inline int + getNeighbors (const REAL* p, T **neighs) const; + + protected: + T *voxels_; + int num_of_voxels_[3], num_of_voxels_xy_plane_, total_num_of_voxels_; + REAL bounds_[6]; + REAL spacing_[3]; // spacing betwen the voxel in x, y and z direction = voxel size in x, y and z direction + REAL min_center_[3]; // the center of the voxel with integer coordinates (0, 0, 0) + }; + } // namespace recognition +} // namespace pcl + +#include + +#endif // PCL_RECOGNITION_VOXEL_STRUCTURE_H_ diff --git a/pcl-1.7/pcl/recognition/region_xy.h b/pcl-1.7/pcl/recognition/region_xy.h new file mode 100644 index 0000000..8576d1c --- /dev/null +++ b/pcl-1.7/pcl/recognition/region_xy.h @@ -0,0 +1,121 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_REGION_XY_ +#define PCL_FEATURES_REGION_XY_ + +#include + +namespace pcl +{ + /** \brief Function for reading data from a stream. */ + template + void read (std::istream & stream, Type & value) + { + stream.read (reinterpret_cast (&value), sizeof(value)); + } + + /** \brief Function for reading data arrays from a stream. */ + template + void read (std::istream & stream, Type * value, int nr_values) + { + for (int value_index = 0; value_index < nr_values; ++value_index) + { + read (stream, value[value_index]); + } + } + + /** \brief Function for writing data to a stream. */ + template + void write (std::ostream & stream, Type value) + { + stream.write (reinterpret_cast (&value), sizeof (value)); + } + + /** \brief Function for writing data arrays to a stream. */ + template + void write (std::ostream & stream, Type * value, int nr_values) + { + for (int value_index = 0; value_index < nr_values; ++value_index) + { + write (stream, value[value_index]); + } + } + + /** \brief Defines a region in XY-space. + * \author Stefan Holzer + */ + struct PCL_EXPORTS RegionXY + { + /** \brief Constructor. */ + RegionXY () : x (0), y (0), width (0), height (0) {} + + /** \brief x-position of the region. */ + int x; + /** \brief y-position of the region. */ + int y; + /** \brief width of the region. */ + int width; + /** \brief height of the region. */ + int height; + + /** \brief Serializes the object to the specified stream. + * \param[out] stream the stream the object will be serialized to. */ + void + serialize (std::ostream & stream) const + { + write (stream, x); + write (stream, y); + write (stream, width); + write (stream, height); + } + + /** \brief Deserializes the object from the specified stream. + * \param[in] stream the stream the object will be deserialized from. */ + void + deserialize (::std::istream & stream) + { + read (stream, x); + read (stream, y); + read (stream, width); + read (stream, height); + } + + }; +} + +#endif // PCL_FEATURES_REGION_XY_ diff --git a/pcl-1.7/pcl/recognition/rigid_transform_space.h b/pcl-1.7/pcl/recognition/rigid_transform_space.h new file mode 100644 index 0000000..86574b0 --- /dev/null +++ b/pcl-1.7/pcl/recognition/rigid_transform_space.h @@ -0,0 +1,414 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/* + * rigid_transform_space.h + * + * Created on: Feb 15, 2013 + * Author: papazov + */ + +#ifndef PCL_RECOGNITION_RIGID_TRANSFORM_SPACE_H_ +#define PCL_RECOGNITION_RIGID_TRANSFORM_SPACE_H_ + +#include "simple_octree.h" +#include "model_library.h" +#include +#include +#include + +namespace pcl +{ + namespace recognition + { + class RotationSpaceCell + { + public: + class Entry + { + public: + Entry () + : num_transforms_ (0) + { + aux::set3 (axis_angle_, 0.0f); + aux::set3 (translation_, 0.0f); + } + + Entry (const Entry& src) + : num_transforms_ (src.num_transforms_) + { + aux::copy3 (src.axis_angle_, this->axis_angle_); + aux::copy3 (src.translation_, this->translation_); + } + + const Entry& operator = (const Entry& src) + { + num_transforms_ = src.num_transforms_; + aux::copy3 (src.axis_angle_, this->axis_angle_); + aux::copy3 (src.translation_, this->translation_); + + return *this; + } + + inline const Entry& + addRigidTransform (const float axis_angle[3], const float translation[3]) + { + aux::add3 (this->axis_angle_, axis_angle); + aux::add3 (this->translation_, translation); + ++num_transforms_; + + return *this; + } + + inline void + computeAverageRigidTransform (float *rigid_transform = NULL) + { + if ( num_transforms_ >= 2 ) + { + float factor = 1.0f/static_cast (num_transforms_); + aux::mult3 (axis_angle_, factor); + aux::mult3 (translation_, factor); + num_transforms_ = 1; + } + + if ( rigid_transform ) + { + // Save the rotation (in matrix form) + aux::axisAngleToRotationMatrix (axis_angle_, rigid_transform); + // Save the translation + aux::copy3 (translation_, rigid_transform + 9); + } + } + + inline const float* + getAxisAngle () const + { + return (axis_angle_); + } + + inline const float* + getTranslation () const + { + return (translation_); + } + + inline int + getNumberOfTransforms () const + { + return (num_transforms_); + } + + protected: + float axis_angle_[3], translation_[3]; + int num_transforms_; + };// class Entry + + public: + RotationSpaceCell (){} + virtual ~RotationSpaceCell () + { + model_to_entry_.clear (); + } + + inline std::map& + getEntries () + { + return (model_to_entry_); + } + + inline const RotationSpaceCell::Entry* + getEntry (const ModelLibrary::Model* model) const + { + std::map::const_iterator res = model_to_entry_.find (model); + + if ( res != model_to_entry_.end () ) + return (&res->second); + + return (NULL); + } + + inline const RotationSpaceCell::Entry& + addRigidTransform (const ModelLibrary::Model* model, const float axis_angle[3], const float translation[3]) + { + return model_to_entry_[model].addRigidTransform (axis_angle, translation); + } + + protected: + std::map model_to_entry_; + }; // class RotationSpaceCell + + class RotationSpaceCellCreator + { + public: + RotationSpaceCellCreator (){} + virtual ~RotationSpaceCellCreator (){} + + RotationSpaceCell* create (const SimpleOctree::Node* ) + { + return (new RotationSpaceCell ()); + } + }; + + typedef SimpleOctree CellOctree; + + /** \brief This is a class for a discrete representation of the rotation space based on the axis-angle representation. + * This class is not supposed to be very general. That's why it is dependent on the class ModelLibrary. + * + * \author Chavdar Papazov + * \ingroup recognition + */ + class PCL_EXPORTS RotationSpace + { + public: + /** \brief We use the axis-angle representation for rotations. The axis is encoded in the vector + * and the angle is its magnitude. This is represented in an octree with bounds [-pi, pi]^3. */ + RotationSpace (float discretization) + { + float min = -(AUX_PI_FLOAT + 0.000000001f), max = AUX_PI_FLOAT + 0.000000001f; + float bounds[6] = {min, max, min, max, min, max}; + + // Build the voxel structure + octree_.build (bounds, discretization, &cell_creator_); + } + + virtual ~RotationSpace () + { + octree_.clear (); + } + + inline void + setCenter (const float* c) + { + center_[0] = c[0]; + center_[1] = c[1]; + center_[2] = c[2]; + } + + inline const float* + getCenter () const { return center_;} + + inline bool + getTransformWithMostVotes (const ModelLibrary::Model* model, float rigid_transform[12]) const + { + RotationSpaceCell::Entry with_most_votes; + const std::vector& full_leaves = octree_.getFullLeaves (); + int max_num_transforms = 0; + + // For each full leaf + for ( std::vector::const_iterator leaf = full_leaves.begin () ; leaf != full_leaves.end () ; ++leaf ) + { + // Is there an entry for 'model' in the current cell + const RotationSpaceCell::Entry *entry = (*leaf)->getData ().getEntry (model); + if ( !entry ) + continue; + + int num_transforms = entry->getNumberOfTransforms (); + const std::set& neighs = (*leaf)->getNeighbors (); + + // For each neighbor + for ( std::set::const_iterator neigh = neighs.begin () ; neigh != neighs.end () ; ++neigh ) + { + const RotationSpaceCell::Entry *neigh_entry = (*neigh)->getData ().getEntry (model); + if ( !neigh_entry ) + continue; + + num_transforms += neigh_entry->getNumberOfTransforms (); + } + + if ( num_transforms > max_num_transforms ) + { + with_most_votes = *entry; + max_num_transforms = num_transforms; + } + } + + if ( !max_num_transforms ) + return false; + + with_most_votes.computeAverageRigidTransform (rigid_transform); + + return true; + } + + inline bool + addRigidTransform (const ModelLibrary::Model* model, const float axis_angle[3], const float translation[3]) + { + CellOctree::Node* cell = octree_.createLeaf (axis_angle[0], axis_angle[1], axis_angle[2]); + + if ( !cell ) + { + const float *b = octree_.getBounds (); + printf ("WARNING in 'RotationSpace::%s()': the provided axis-angle input (%f, %f, %f) is " + "out of the rotation space bounds ([%f, %f], [%f, %f], [%f, %f]).\n", + __func__, axis_angle[0], axis_angle[1], axis_angle[2], b[0], b[1], b[2], b[3], b[4], b[5]); + return (false); + } + + // Add the rigid transform to the cell + cell->getData ().addRigidTransform (model, axis_angle, translation); + + return (true); + } + + protected: + CellOctree octree_; + RotationSpaceCellCreator cell_creator_; + float center_[3]; + };// class RotationSpace + + class RotationSpaceCreator + { + public: + RotationSpaceCreator() + : counter_ (0) + {} + + virtual ~RotationSpaceCreator(){} + + RotationSpace* create(const SimpleOctree::Node* leaf) + { + RotationSpace *rot_space = new RotationSpace (discretization_); + rot_space->setCenter (leaf->getCenter ()); + rotation_spaces_.push_back (rot_space); + + ++counter_; + + return (rot_space); + } + + void + setDiscretization (float value){ discretization_ = value;} + + int + getNumberOfRotationSpaces () const { return (counter_);} + + const std::list& + getRotationSpaces () const { return (rotation_spaces_);} + + std::list& + getRotationSpaces (){ return (rotation_spaces_);} + + void + reset () + { + counter_ = 0; + rotation_spaces_.clear (); + } + + protected: + float discretization_; + int counter_; + std::list rotation_spaces_; + }; + + typedef SimpleOctree RotationSpaceOctree; + + class PCL_EXPORTS RigidTransformSpace + { + public: + RigidTransformSpace (){} + virtual ~RigidTransformSpace (){ this->clear ();} + + inline void + build (const float* pos_bounds, float translation_cell_size, float rotation_cell_size) + { + this->clear (); + + rotation_space_creator_.setDiscretization (rotation_cell_size); + + pos_octree_.build (pos_bounds, translation_cell_size, &rotation_space_creator_); + } + + inline void + clear () + { + pos_octree_.clear (); + rotation_space_creator_.reset (); + } + + inline std::list& + getRotationSpaces () + { + return (rotation_space_creator_.getRotationSpaces ()); + } + + inline const std::list& + getRotationSpaces () const + { + return (rotation_space_creator_.getRotationSpaces ()); + } + + inline int + getNumberOfOccupiedRotationSpaces () + { + return (rotation_space_creator_.getNumberOfRotationSpaces ()); + } + + inline bool + addRigidTransform (const ModelLibrary::Model* model, const float position[3], const float rigid_transform[12]) + { + // Get the leaf 'position' ends up in + RotationSpaceOctree::Node* leaf = pos_octree_.createLeaf (position[0], position[1], position[2]); + + if ( !leaf ) + { + printf ("WARNING in 'RigidTransformSpace::%s()': the input position (%f, %f, %f) is out of bounds.\n", + __func__, position[0], position[1], position[2]); + return (false); + } + + float rot_angle, axis_angle[3]; + // Extract the axis-angle representation from the rotation matrix + aux::rotationMatrixToAxisAngle (rigid_transform, axis_angle, rot_angle); + // Multiply the axis by the angle to get the final representation + aux::mult3 (axis_angle, rot_angle); + + // Now, add the rigid transform to the rotation space + leaf->getData ().addRigidTransform (model, axis_angle, rigid_transform + 9); + + return (true); + } + + protected: + RotationSpaceOctree pos_octree_; + RotationSpaceCreator rotation_space_creator_; + }; // class RigidTransformSpace + } // namespace recognition +} // namespace pcl + +#endif /* PCL_RECOGNITION_RIGID_TRANSFORM_SPACE_H_ */ diff --git a/pcl-1.7/pcl/recognition/simple_octree.h b/pcl-1.7/pcl/recognition/simple_octree.h new file mode 100644 index 0000000..db42ced --- /dev/null +++ b/pcl-1.7/pcl/recognition/simple_octree.h @@ -0,0 +1,211 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +/* + * simple_octree.h + * + * Created on: Mar 11, 2013 + * Author: papazov + */ + +#ifndef SIMPLE_OCTREE_H_ +#define SIMPLE_OCTREE_H_ + +#include +#include + +namespace pcl +{ + namespace recognition + { + template + class PCL_EXPORTS SimpleOctree + { + public: + class Node + { + public: + Node (); + + virtual~ Node (); + + inline void + setCenter (const Scalar *c); + + inline void + setBounds (const Scalar *b); + + inline const Scalar* + getCenter () const { return center_;} + + inline const Scalar* + getBounds () const { return bounds_;} + + inline void + getBounds (Scalar b[6]) const { memcpy (b, bounds_, 6*sizeof (Scalar));} + + inline Node* + getChild (int id) { return &children_[id];} + + inline Node* + getChildren () { return children_;} + + inline void + setData (const NodeData& src){ *data_ = src;} + + inline NodeData& + getData (){ return *data_;} + + inline const NodeData& + getData () const { return *data_;} + + inline Node* + getParent (){ return parent_;} + + inline float + getRadius () const { return radius_;} + + inline bool + hasData (){ return static_cast (data_);} + + inline bool + hasChildren (){ return static_cast (children_);} + + inline const std::set& + getNeighbors () const { return (full_leaf_neighbors_);} + + inline void + deleteChildren (); + + inline void + deleteData (); + + friend class SimpleOctree; + + protected: + void + setData (NodeData* data){ if ( data_ ) delete data_; data_ = data;} + + inline bool + createChildren (); + + /** \brief Make this and 'node' neighbors by inserting each node in the others node neighbor set. Nothing happens + * of either of the nodes has no data. */ + inline void + makeNeighbors (Node* node); + + inline void + setParent (Node* parent){ parent_ = parent;} + + /** \brief Computes the "radius" of the node which is half the diagonal length. */ + inline void + computeRadius (); + + protected: + NodeData *data_; + Scalar center_[3], bounds_[6]; + Node *parent_, *children_; + Scalar radius_; + std::set full_leaf_neighbors_; + }; + + public: + SimpleOctree (); + + virtual ~SimpleOctree (); + + void + clear (); + + /** \brief Creates an empty octree with bounds at least as large as the ones provided as input and with leaf + * size equal to 'voxel_size'. */ + void + build (const Scalar* bounds, Scalar voxel_size, NodeDataCreator* node_data_creator); + + /** \brief Creates the leaf containing p = (x, y, z) and returns a pointer to it, however, only if p lies within + * the octree bounds! A more general version which allows p to be out of bounds is not implemented yet. The method + * returns NULL if p is not within the root bounds. If the leaf containing p already exists nothing happens and + * method just returns a pointer to the leaf. Note that for a new created leaf, the method also creates its data + * object. */ + inline Node* + createLeaf (Scalar x, Scalar y, Scalar z); + + /** \brief Since the leaves are aligned in a rectilinear grid, each leaf has a unique id. The method returns the full + * leaf, i.e., the one having a data object, with id [i, j, k] or NULL is no such leaf exists. */ + inline Node* + getFullLeaf (int i, int j, int k); + + /** \brief Returns a pointer to the full leaf, i.e., one having a data pbject, containing p = (x, y, z) or NULL if no such leaf exists. */ + inline Node* + getFullLeaf (Scalar x, Scalar y, Scalar z); + + inline std::vector& + getFullLeaves () { return full_leaves_;} + + inline const std::vector& + getFullLeaves () const { return full_leaves_;} + + inline Node* + getRoot (){ return root_;} + + inline const Scalar* + getBounds () const { return (bounds_);} + + inline void + getBounds (Scalar b[6]) const { memcpy (b, bounds_, 6*sizeof (Scalar));} + + inline Scalar + getVoxelSize () const { return voxel_size_;} + + protected: + inline void + insertNeighbors (Node* node); + + protected: + Scalar voxel_size_, bounds_[6]; + int tree_levels_; + Node* root_; + std::vector full_leaves_; + NodeDataCreator* node_data_creator_; + }; + } // namespace recognition +} // namespace pcl + +#include + +#endif /* SIMPLE_OCTREE_H_ */ diff --git a/pcl-1.7/pcl/recognition/sparse_quantized_multi_mod_template.h b/pcl-1.7/pcl/recognition/sparse_quantized_multi_mod_template.h new file mode 100644 index 0000000..3f68d87 --- /dev/null +++ b/pcl-1.7/pcl/recognition/sparse_quantized_multi_mod_template.h @@ -0,0 +1,156 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_FEATURES_SPARSE_QUANTIZED_MULTI_MOD_TEMPLATE +#define PCL_FEATURES_SPARSE_QUANTIZED_MULTI_MOD_TEMPLATE + +#include + +#include + +namespace pcl +{ + + /** \brief Feature that defines a position and quantized value in a specific modality. + * \author Stefan Holzer + */ + struct QuantizedMultiModFeature + { + /** \brief Constructor. */ + QuantizedMultiModFeature () : x (0), y (0), modality_index (0), quantized_value (0) {} + + /** \brief x-position. */ + int x; + /** \brief y-position. */ + int y; + /** \brief the index of the corresponding modality. */ + size_t modality_index; + /** \brief the quantized value attached to the feature. */ + unsigned char quantized_value; + + /** \brief Compares whether two features are the same. + * \param[in] base the feature to compare to. + */ + bool + compareForEquality (const QuantizedMultiModFeature & base) + { + if (base.x != x) + return false; + if (base.y != y) + return false; + if (base.modality_index != modality_index) + return false; + if (base.quantized_value != quantized_value) + return false; + + return true; + } + + /** \brief Serializes the object to the specified stream. + * \param[out] stream the stream the object will be serialized to. */ + void + serialize (std::ostream & stream) const + { + write (stream, x); + write (stream, y); + write (stream, modality_index); + write (stream, quantized_value); + } + + /** \brief Deserializes the object from the specified stream. + * \param[in] stream the stream the object will be deserialized from. */ + void + deserialize (std::istream & stream) + { + read (stream, x); + read (stream, y); + read (stream, modality_index); + read (stream, quantized_value); + } + }; + + /** \brief A multi-modality template constructed from a set of quantized multi-modality features. + * \author Stefan Holzer + */ + struct SparseQuantizedMultiModTemplate + { + /** \brief Constructor. */ + SparseQuantizedMultiModTemplate () : features (), region () {} + + /** \brief The storage for the multi-modality features. */ + std::vector features; + + /** \brief The region assigned to the template. */ + RegionXY region; + + /** \brief Serializes the object to the specified stream. + * \param[out] stream the stream the object will be serialized to. */ + void + serialize (std::ostream & stream) const + { + const int num_of_features = static_cast (features.size ()); + write (stream, num_of_features); + for (int feature_index = 0; feature_index < num_of_features; ++feature_index) + { + features[feature_index].serialize (stream); + } + + region.serialize (stream); + } + + /** \brief Deserializes the object from the specified stream. + * \param[in] stream the stream the object will be deserialized from. */ + void + deserialize (std::istream & stream) + { + features.clear (); + + int num_of_features; + read (stream, num_of_features); + features.resize (num_of_features); + for (int feature_index = 0; feature_index < num_of_features; ++feature_index) + { + features[feature_index].deserialize (stream); + } + + region.deserialize (stream); + } + }; + +} + +#endif diff --git a/pcl-1.7/pcl/recognition/surface_normal_modality.h b/pcl-1.7/pcl/recognition/surface_normal_modality.h new file mode 100644 index 0000000..05c3b40 --- /dev/null +++ b/pcl-1.7/pcl/recognition/surface_normal_modality.h @@ -0,0 +1,1644 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_RECOGNITION_SURFACE_NORMAL_MODALITY +#define PCL_RECOGNITION_SURFACE_NORMAL_MODALITY + +#include +#include + +#include +#include +#include +#include + +namespace pcl +{ + + /** \brief Map that stores orientations. + * \author Stefan Holzer + */ + struct PCL_EXPORTS LINEMOD_OrientationMap + { + public: + /** \brief Constructor. */ + inline LINEMOD_OrientationMap () : width_ (0), height_ (0), map_ () {} + /** \brief Destructor. */ + inline ~LINEMOD_OrientationMap () {} + + /** \brief Returns the width of the modality data map. */ + inline size_t + getWidth () const + { + return width_; + } + + /** \brief Returns the height of the modality data map. */ + inline size_t + getHeight () const + { + return height_; + } + + /** \brief Resizes the map to the specific width and height and initializes + * all new elements with the specified value. + * \param[in] width the width of the resized map. + * \param[in] height the height of the resized map. + * \param[in] value the value all new elements will be initialized with. + */ + inline void + resize (const size_t width, const size_t height, const float value) + { + width_ = width; + height_ = height; + map_.clear (); + map_.resize (width*height, value); + } + + /** \brief Operator to access elements of the map. + * \param[in] col_index the column index of the element to access. + * \param[in] row_index the row index of the element to access. + */ + inline float & + operator() (const size_t col_index, const size_t row_index) + { + return map_[row_index * width_ + col_index]; + } + + /** \brief Operator to access elements of the map. + * \param[in] col_index the column index of the element to access. + * \param[in] row_index the row index of the element to access. + */ + inline const float & + operator() (const size_t col_index, const size_t row_index) const + { + return map_[row_index * width_ + col_index]; + } + + private: + /** \brief The width of the map. */ + size_t width_; + /** \brief The height of the map. */ + size_t height_; + /** \brief Storage for the data of the map. */ + std::vector map_; + + }; + + /** \brief Look-up-table for fast surface normal quantization. + * \author Stefan Holzer + */ + struct QuantizedNormalLookUpTable + { + /** \brief The range of the LUT in x-direction. */ + int range_x; + /** \brief The range of the LUT in y-direction. */ + int range_y; + /** \brief The range of the LUT in z-direction. */ + int range_z; + + /** \brief The offset in x-direction. */ + int offset_x; + /** \brief The offset in y-direction. */ + int offset_y; + /** \brief The offset in z-direction. */ + int offset_z; + + /** \brief The size of the LUT in x-direction. */ + int size_x; + /** \brief The size of the LUT in y-direction. */ + int size_y; + /** \brief The size of the LUT in z-direction. */ + int size_z; + + /** \brief The LUT data. */ + unsigned char * lut; + + /** \brief Constructor. */ + QuantizedNormalLookUpTable () : + range_x (-1), range_y (-1), range_z (-1), + offset_x (-1), offset_y (-1), offset_z (-1), + size_x (-1), size_y (-1), size_z (-1), lut (NULL) + {} + + /** \brief Destructor. */ + ~QuantizedNormalLookUpTable () + { + if (lut != NULL) + delete[] lut; + } + + /** \brief Initializes the LUT. + * \param[in] range_x_arg the range of the LUT in x-direction. + * \param[in] range_y_arg the range of the LUT in y-direction. + * \param[in] range_z_arg the range of the LUT in z-direction. + */ + void + initializeLUT (const int range_x_arg, const int range_y_arg, const int range_z_arg) + { + range_x = range_x_arg; + range_y = range_y_arg; + range_z = range_z_arg; + size_x = range_x_arg+1; + size_y = range_y_arg+1; + size_z = range_z_arg+1; + offset_x = range_x_arg/2; + offset_y = range_y_arg/2; + offset_z = range_z_arg; + + //if (lut != NULL) free16(lut); + //lut = malloc16(size_x*size_y*size_z); + + if (lut != NULL) + delete[] lut; + lut = new unsigned char[size_x*size_y*size_z]; + + const int nr_normals = 8; + pcl::PointCloud::VectorType ref_normals (nr_normals); + + const float normal0_angle = 40.0f * 3.14f / 180.0f; + ref_normals[0].x = cosf (normal0_angle); + ref_normals[0].y = 0.0f; + ref_normals[0].z = -sinf (normal0_angle); + + const float inv_nr_normals = 1.0f / static_cast (nr_normals); + for (int normal_index = 1; normal_index < nr_normals; ++normal_index) + { + const float angle = 2.0f * static_cast (M_PI * normal_index * inv_nr_normals); + + ref_normals[normal_index].x = cosf (angle) * ref_normals[0].x - sinf (angle) * ref_normals[0].y; + ref_normals[normal_index].y = sinf (angle) * ref_normals[0].x + cosf (angle) * ref_normals[0].y; + ref_normals[normal_index].z = ref_normals[0].z; + } + + // normalize normals + for (int normal_index = 0; normal_index < nr_normals; ++normal_index) + { + const float length = sqrtf (ref_normals[normal_index].x * ref_normals[normal_index].x + + ref_normals[normal_index].y * ref_normals[normal_index].y + + ref_normals[normal_index].z * ref_normals[normal_index].z); + + const float inv_length = 1.0f / length; + + ref_normals[normal_index].x *= inv_length; + ref_normals[normal_index].y *= inv_length; + ref_normals[normal_index].z *= inv_length; + } + + // set LUT + for (int z_index = 0; z_index < size_z; ++z_index) + { + for (int y_index = 0; y_index < size_y; ++y_index) + { + for (int x_index = 0; x_index < size_x; ++x_index) + { + PointXYZ normal (static_cast (x_index - range_x/2), + static_cast (y_index - range_y/2), + static_cast (z_index - range_z)); + const float length = sqrtf (normal.x*normal.x + normal.y*normal.y + normal.z*normal.z); + const float inv_length = 1.0f / (length + 0.00001f); + + normal.x *= inv_length; + normal.y *= inv_length; + normal.z *= inv_length; + + float max_response = -1.0f; + int max_index = -1; + + for (int normal_index = 0; normal_index < nr_normals; ++normal_index) + { + const float response = normal.x * ref_normals[normal_index].x + + normal.y * ref_normals[normal_index].y + + normal.z * ref_normals[normal_index].z; + + const float abs_response = fabsf (response); + if (max_response < abs_response) + { + max_response = abs_response; + max_index = normal_index; + } + + lut[z_index*size_y*size_x + y_index*size_x + x_index] = static_cast (0x1 << max_index); + } + } + } + } + } + + /** \brief Operator to access an element in the LUT. + * \param[in] x the x-component of the normal. + * \param[in] y the y-component of the normal. + * \param[in] z the z-component of the normal. + */ + inline unsigned char + operator() (const float x, const float y, const float z) const + { + const size_t x_index = static_cast (x * static_cast (offset_x) + static_cast (offset_x)); + const size_t y_index = static_cast (y * static_cast (offset_y) + static_cast (offset_y)); + const size_t z_index = static_cast (z * static_cast (range_z) + static_cast (range_z)); + + const size_t index = z_index*size_y*size_x + y_index*size_x + x_index; + + return (lut[index]); + } + + /** \brief Operator to access an element in the LUT. + * \param[in] index the index of the element. + */ + inline unsigned char + operator() (const int index) const + { + return (lut[index]); + } + }; + + + /** \brief Modality based on surface normals. + * \author Stefan Holzer + */ + template + class SurfaceNormalModality : public QuantizableModality, public PCLBase + { + protected: + using PCLBase::input_; + + /** \brief Candidate for a feature (used in feature extraction methods). */ + struct Candidate + { + /** \brief Constructor. */ + Candidate () : normal (), distance (0.0f), bin_index (0), x (0), y (0) {} + + /** \brief Normal. */ + Normal normal; + /** \brief Distance to the next different quantized value. */ + float distance; + + /** \brief Quantized value. */ + unsigned char bin_index; + + /** \brief x-position of the feature. */ + size_t x; + /** \brief y-position of the feature. */ + size_t y; + + /** \brief Compares two candidates based on their distance to the next different quantized value. + * \param[in] rhs the candidate to compare with. + */ + bool + operator< (const Candidate & rhs) const + { + return (distance > rhs.distance); + } + }; + + public: + typedef typename pcl::PointCloud PointCloudIn; + + /** \brief Constructor. */ + SurfaceNormalModality (); + /** \brief Destructor. */ + virtual ~SurfaceNormalModality (); + + /** \brief Sets the spreading size. + * \param[in] spreading_size the spreading size. + */ + inline void + setSpreadingSize (const size_t spreading_size) + { + spreading_size_ = spreading_size; + } + + /** \brief Enables/disables the use of extracting a variable number of features. + * \param[in] enabled specifies whether extraction of a variable number of features will be enabled/disabled. + */ + inline void + setVariableFeatureNr (const bool enabled) + { + variable_feature_nr_ = enabled; + } + + /** \brief Returns the surface normals. */ + inline pcl::PointCloud & + getSurfaceNormals () + { + return surface_normals_; + } + + /** \brief Returns the surface normals. */ + inline const pcl::PointCloud & + getSurfaceNormals () const + { + return surface_normals_; + } + + /** \brief Returns a reference to the internal quantized map. */ + inline QuantizedMap & + getQuantizedMap () + { + return (filtered_quantized_surface_normals_); + } + + /** \brief Returns a reference to the internal spreaded quantized map. */ + inline QuantizedMap & + getSpreadedQuantizedMap () + { + return (spreaded_quantized_surface_normals_); + } + + /** \brief Returns a reference to the orientation map. */ + inline LINEMOD_OrientationMap & + getOrientationMap () + { + return (surface_normal_orientations_); + } + + /** \brief Extracts features from this modality within the specified mask. + * \param[in] mask defines the areas where features are searched in. + * \param[in] nr_features defines the number of features to be extracted + * (might be less if not sufficient information is present in the modality). + * \param[in] modality_index the index which is stored in the extracted features. + * \param[out] features the destination for the extracted features. + */ + void + extractFeatures (const MaskMap & mask, size_t nr_features, size_t modality_index, + std::vector & features) const; + + /** \brief Extracts all possible features from the modality within the specified mask. + * \param[in] mask defines the areas where features are searched in. + * \param[in] nr_features IGNORED (TODO: remove this parameter). + * \param[in] modality_index the index which is stored in the extracted features. + * \param[out] features the destination for the extracted features. + */ + void + extractAllFeatures (const MaskMap & mask, size_t nr_features, size_t modality_index, + std::vector & features) const; + + /** \brief Provide a pointer to the input dataset (overwrites the PCLBase::setInputCloud method) + * \param[in] cloud the const boost shared pointer to a PointCloud message + */ + virtual void + setInputCloud (const typename PointCloudIn::ConstPtr & cloud) + { + input_ = cloud; + } + + /** \brief Processes the input data (smoothing, computing gradients, quantizing, filtering, spreading). */ + virtual void + processInputData (); + + /** \brief Processes the input data assuming that everything up to filtering is already done/available + * (so only spreading is performed). */ + virtual void + processInputDataFromFiltered (); + + protected: + + /** \brief Computes the surface normals from the input cloud. */ + void + computeSurfaceNormals (); + + /** \brief Computes and quantizes the surface normals. */ + void + computeAndQuantizeSurfaceNormals (); + + /** \brief Computes and quantizes the surface normals. */ + void + computeAndQuantizeSurfaceNormals2 (); + + /** \brief Quantizes the surface normals. */ + void + quantizeSurfaceNormals (); + + /** \brief Filters the quantized surface normals. */ + void + filterQuantizedSurfaceNormals (); + + /** \brief Computes a distance map from the supplied input mask. + * \param[in] input the mask for which a distance map will be computed. + * \param[out] output the destination for the distance map. + */ + void + computeDistanceMap (const MaskMap & input, DistanceMap & output) const; + + private: + + /** \brief Determines whether variable numbers of features are extracted or not. */ + bool variable_feature_nr_; + + /** \brief The feature distance threshold. */ + float feature_distance_threshold_; + /** \brief Minimum distance of a feature to a border. */ + float min_distance_to_border_; + + /** \brief Look-up-table for quantizing surface normals. */ + QuantizedNormalLookUpTable normal_lookup_; + + /** \brief The spreading size. */ + size_t spreading_size_; + + /** \brief Point cloud holding the computed surface normals. */ + pcl::PointCloud surface_normals_; + /** \brief Quantized surface normals. */ + pcl::QuantizedMap quantized_surface_normals_; + /** \brief Filtered quantized surface normals. */ + pcl::QuantizedMap filtered_quantized_surface_normals_; + /** \brief Spreaded quantized surface normals. */ + pcl::QuantizedMap spreaded_quantized_surface_normals_; + + /** \brief Map containing surface normal orientations. */ + pcl::LINEMOD_OrientationMap surface_normal_orientations_; + + }; + +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::SurfaceNormalModality:: +SurfaceNormalModality () + : variable_feature_nr_ (false) + , feature_distance_threshold_ (2.0f) + , min_distance_to_border_ (2.0f) + , normal_lookup_ () + , spreading_size_ (8) + , surface_normals_ () + , quantized_surface_normals_ () + , filtered_quantized_surface_normals_ () + , spreaded_quantized_surface_normals_ () + , surface_normal_orientations_ () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::SurfaceNormalModality::~SurfaceNormalModality () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SurfaceNormalModality::processInputData () +{ + // compute surface normals + //computeSurfaceNormals (); + + // quantize surface normals + //quantizeSurfaceNormals (); + + computeAndQuantizeSurfaceNormals2 (); + + // filter quantized surface normals + filterQuantizedSurfaceNormals (); + + // spread quantized surface normals + pcl::QuantizedMap::spreadQuantizedMap (filtered_quantized_surface_normals_, + spreaded_quantized_surface_normals_, + spreading_size_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SurfaceNormalModality::processInputDataFromFiltered () +{ + // spread quantized surface normals + pcl::QuantizedMap::spreadQuantizedMap (filtered_quantized_surface_normals_, + spreaded_quantized_surface_normals_, + spreading_size_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SurfaceNormalModality::computeSurfaceNormals () +{ + // compute surface normals + pcl::LinearLeastSquaresNormalEstimation ne; + ne.setMaxDepthChangeFactor(0.05f); + ne.setNormalSmoothingSize(5.0f); + ne.setDepthDependentSmoothing(false); + ne.setInputCloud (input_); + ne.compute (surface_normals_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SurfaceNormalModality::computeAndQuantizeSurfaceNormals () +{ + // compute surface normals + //pcl::LinearLeastSquaresNormalEstimation ne; + //ne.setMaxDepthChangeFactor(0.05f); + //ne.setNormalSmoothingSize(5.0f); + //ne.setDepthDependentSmoothing(false); + //ne.setInputCloud (input_); + //ne.compute (surface_normals_); + + + const float bad_point = std::numeric_limits::quiet_NaN (); + + const int width = input_->width; + const int height = input_->height; + + surface_normals_.resize (width*height); + surface_normals_.width = width; + surface_normals_.height = height; + surface_normals_.is_dense = false; + + quantized_surface_normals_.resize (width, height); + + // we compute the normals as follows: + // ---------------------------------- + // + // for the depth-gradient you can make the following first-order Taylor approximation: + // D(x + dx) - D(x) = dx^T \Delta D + h.o.t. + // + // build linear system by stacking up equation for 8 neighbor points: + // Y = X \Delta D + // + // => \Delta D = (X^T X)^{-1} X^T Y + // => \Delta D = (A)^{-1} b + + for (int y = 0; y < height; ++y) + { + for (int x = 0; x < width; ++x) + { + const int index = y * width + x; + + const float px = input_->points[index].x; + const float py = input_->points[index].y; + const float pz = input_->points[index].z; + + if (pcl_isnan(px) || pz > 2.0f) + { + surface_normals_.points[index].normal_x = bad_point; + surface_normals_.points[index].normal_y = bad_point; + surface_normals_.points[index].normal_z = bad_point; + surface_normals_.points[index].curvature = bad_point; + + quantized_surface_normals_ (x, y) = 0; + + continue; + } + + const int smoothingSizeInt = 5; + + float matA0 = 0.0f; + float matA1 = 0.0f; + float matA3 = 0.0f; + + float vecb0 = 0.0f; + float vecb1 = 0.0f; + + for (int v = y - smoothingSizeInt; v <= y + smoothingSizeInt; v += smoothingSizeInt) + { + for (int u = x - smoothingSizeInt; u <= x + smoothingSizeInt; u += smoothingSizeInt) + { + if (u < 0 || u >= width || v < 0 || v >= height) continue; + + const size_t index2 = v * width + u; + + const float qx = input_->points[index2].x; + const float qy = input_->points[index2].y; + const float qz = input_->points[index2].z; + + if (pcl_isnan(qx)) continue; + + const float delta = qz - pz; + const float i = qx - px; + const float j = qy - py; + + const float f = fabs(delta) < 0.05f ? 1.0f : 0.0f; + + matA0 += f * i * i; + matA1 += f * i * j; + matA3 += f * j * j; + vecb0 += f * i * delta; + vecb1 += f * j * delta; + } + } + + const float det = matA0 * matA3 - matA1 * matA1; + const float ddx = matA3 * vecb0 - matA1 * vecb1; + const float ddy = -matA1 * vecb0 + matA0 * vecb1; + + const float nx = ddx; + const float ny = ddy; + const float nz = -det * pz; + + const float length = nx * nx + ny * ny + nz * nz; + + if (length <= 0.0f) + { + surface_normals_.points[index].normal_x = bad_point; + surface_normals_.points[index].normal_y = bad_point; + surface_normals_.points[index].normal_z = bad_point; + surface_normals_.points[index].curvature = bad_point; + + quantized_surface_normals_ (x, y) = 0; + } + else + { + const float normInv = 1.0f / sqrtf (length); + + const float normal_x = nx * normInv; + const float normal_y = ny * normInv; + const float normal_z = nz * normInv; + + surface_normals_.points[index].normal_x = normal_x; + surface_normals_.points[index].normal_y = normal_y; + surface_normals_.points[index].normal_z = normal_z; + surface_normals_.points[index].curvature = bad_point; + + float angle = 11.25f + atan2 (normal_y, normal_x)*180.0f/3.14f; + + if (angle < 0.0f) angle += 360.0f; + if (angle >= 360.0f) angle -= 360.0f; + + int bin_index = static_cast (angle*8.0f/360.0f) & 7; + + quantized_surface_normals_ (x, y) = static_cast (bin_index); + } + } + } +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +// Contains GRANULARITY and NORMAL_LUT +//#include "normal_lut.i" + +static void accumBilateral(long delta, long i, long j, long * A, long * b, int threshold) +{ + long f = std::abs(delta) < threshold ? 1 : 0; + + const long fi = f * i; + const long fj = f * j; + + A[0] += fi * i; + A[1] += fi * j; + A[3] += fj * j; + b[0] += fi * delta; + b[1] += fj * delta; +} + +/** + * \brief Compute quantized normal image from depth image. + * + * Implements section 2.6 "Extension to Dense Depth Sensors." + * + * \todo Should also need camera model, or at least focal lengths? Replace distance_threshold with mask? + */ +template void +pcl::SurfaceNormalModality::computeAndQuantizeSurfaceNormals2 () +{ + const int width = input_->width; + const int height = input_->height; + + unsigned short * lp_depth = new unsigned short[width*height]; + unsigned char * lp_normals = new unsigned char[width*height]; + memset (lp_normals, 0, width*height); + + surface_normal_orientations_.resize (width, height, 0.0f); + + for (int row_index = 0; row_index < height; ++row_index) + { + for (int col_index = 0; col_index < width; ++col_index) + { + const float value = input_->points[row_index*width + col_index].z; + if (pcl_isfinite (value)) + { + lp_depth[row_index*width + col_index] = static_cast (value * 1000.0f); + } + else + { + lp_depth[row_index*width + col_index] = 0; + } + } + } + + const int l_W = width; + const int l_H = height; + + const int l_r = 5; // used to be 7 + //const int l_offset0 = -l_r - l_r * l_W; + //const int l_offset1 = 0 - l_r * l_W; + //const int l_offset2 = +l_r - l_r * l_W; + //const int l_offset3 = -l_r; + //const int l_offset4 = +l_r; + //const int l_offset5 = -l_r + l_r * l_W; + //const int l_offset6 = 0 + l_r * l_W; + //const int l_offset7 = +l_r + l_r * l_W; + + const int offsets_i[] = {-l_r, 0, l_r, -l_r, l_r, -l_r, 0, l_r}; + const int offsets_j[] = {-l_r, -l_r, -l_r, 0, 0, l_r, l_r, l_r}; + const int offsets[] = { offsets_i[0] + offsets_j[0] * l_W + , offsets_i[1] + offsets_j[1] * l_W + , offsets_i[2] + offsets_j[2] * l_W + , offsets_i[3] + offsets_j[3] * l_W + , offsets_i[4] + offsets_j[4] * l_W + , offsets_i[5] + offsets_j[5] * l_W + , offsets_i[6] + offsets_j[6] * l_W + , offsets_i[7] + offsets_j[7] * l_W }; + + + //const int l_offsetx = GRANULARITY / 2; + //const int l_offsety = GRANULARITY / 2; + + const int difference_threshold = 50; + const int distance_threshold = 2000; + + //const double scale = 1000.0; + //const double difference_threshold = 0.05 * scale; + //const double distance_threshold = 2.0 * scale; + + for (int l_y = l_r; l_y < l_H - l_r - 1; ++l_y) + { + unsigned short * lp_line = lp_depth + (l_y * l_W + l_r); + unsigned char * lp_norm = lp_normals + (l_y * l_W + l_r); + + for (int l_x = l_r; l_x < l_W - l_r - 1; ++l_x) + { + long l_d = lp_line[0]; + //float l_d = input_->points[(l_y * l_W + l_r) + l_x].z; + //float px = input_->points[(l_y * l_W + l_r) + l_x].x; + //float py = input_->points[(l_y * l_W + l_r) + l_x].y; + + if (l_d < distance_threshold) + { + // accum + long l_A[4]; l_A[0] = l_A[1] = l_A[2] = l_A[3] = 0; + long l_b[2]; l_b[0] = l_b[1] = 0; + //double l_A[4]; l_A[0] = l_A[1] = l_A[2] = l_A[3] = 0; + //double l_b[2]; l_b[0] = l_b[1] = 0; + + accumBilateral(lp_line[offsets[0]] - l_d, offsets_i[0], offsets_j[0], l_A, l_b, difference_threshold); + accumBilateral(lp_line[offsets[1]] - l_d, offsets_i[1], offsets_j[1], l_A, l_b, difference_threshold); + accumBilateral(lp_line[offsets[2]] - l_d, offsets_i[2], offsets_j[2], l_A, l_b, difference_threshold); + accumBilateral(lp_line[offsets[3]] - l_d, offsets_i[3], offsets_j[3], l_A, l_b, difference_threshold); + accumBilateral(lp_line[offsets[4]] - l_d, offsets_i[4], offsets_j[4], l_A, l_b, difference_threshold); + accumBilateral(lp_line[offsets[5]] - l_d, offsets_i[5], offsets_j[5], l_A, l_b, difference_threshold); + accumBilateral(lp_line[offsets[6]] - l_d, offsets_i[6], offsets_j[6], l_A, l_b, difference_threshold); + accumBilateral(lp_line[offsets[7]] - l_d, offsets_i[7], offsets_j[7], l_A, l_b, difference_threshold); + + //for (size_t index = 0; index < 8; ++index) + //{ + // //accumBilateral(lp_line[offsets[index]] - l_d, offsets_i[index], offsets_j[index], l_A, l_b, difference_threshold); + + // //const long delta = lp_line[offsets[index]] - l_d; + // //const long i = offsets_i[index]; + // //const long j = offsets_j[index]; + // //long * A = l_A; + // //long * b = l_b; + // //const int threshold = difference_threshold; + + // //const long f = std::abs(delta) < threshold ? 1 : 0; + + // //const long fi = f * i; + // //const long fj = f * j; + + // //A[0] += fi * i; + // //A[1] += fi * j; + // //A[3] += fj * j; + // //b[0] += fi * delta; + // //b[1] += fj * delta; + + + // const double delta = 1000.0f * (input_->points[(l_y * l_W + l_r) + l_x + offsets[index]].z - l_d); + // const double i = offsets_i[index]; + // const double j = offsets_j[index]; + // //const float i = input_->points[(l_y * l_W + l_r) + l_x + offsets[index]].x - px;//offsets_i[index]; + // //const float j = input_->points[(l_y * l_W + l_r) + l_x + offsets[index]].y - py;//offsets_j[index]; + // double * A = l_A; + // double * b = l_b; + // const double threshold = difference_threshold; + + // const double f = std::fabs(delta) < threshold ? 1.0f : 0.0f; + + // const double fi = f * i; + // const double fj = f * j; + + // A[0] += fi * i; + // A[1] += fi * j; + // A[3] += fj * j; + // b[0] += fi * delta; + // b[1] += fj * delta; + //} + + //long f = std::abs(delta) < threshold ? 1 : 0; + + //const long fi = f * i; + //const long fj = f * j; + + //A[0] += fi * i; + //A[1] += fi * j; + //A[3] += fj * j; + //b[0] += fi * delta; + //b[1] += fj * delta; + + + // solve + long l_det = l_A[0] * l_A[3] - l_A[1] * l_A[1]; + long l_ddx = l_A[3] * l_b[0] - l_A[1] * l_b[1]; + long l_ddy = -l_A[1] * l_b[0] + l_A[0] * l_b[1]; + + /// @todo Magic number 1150 is focal length? This is something like + /// f in SXGA mode, but in VGA is more like 530. + float l_nx = static_cast(1150 * l_ddx); + float l_ny = static_cast(1150 * l_ddy); + float l_nz = static_cast(-l_det * l_d); + + //// solve + //double l_det = l_A[0] * l_A[3] - l_A[1] * l_A[1]; + //double l_ddx = l_A[3] * l_b[0] - l_A[1] * l_b[1]; + //double l_ddy = -l_A[1] * l_b[0] + l_A[0] * l_b[1]; + + ///// @todo Magic number 1150 is focal length? This is something like + ///// f in SXGA mode, but in VGA is more like 530. + //const double dummy_focal_length = 1150.0f; + //double l_nx = l_ddx * dummy_focal_length; + //double l_ny = l_ddy * dummy_focal_length; + //double l_nz = -l_det * l_d; + + float l_sqrt = sqrtf (l_nx * l_nx + l_ny * l_ny + l_nz * l_nz); + + if (l_sqrt > 0) + { + float l_norminv = 1.0f / (l_sqrt); + + l_nx *= l_norminv; + l_ny *= l_norminv; + l_nz *= l_norminv; + + float angle = 22.5f + atan2f (l_ny, l_nx) * 180.0f / 3.14f; + + if (angle < 0.0f) angle += 360.0f; + if (angle >= 360.0f) angle -= 360.0f; + + int bin_index = static_cast (angle*8.0f/360.0f) & 7; + + surface_normal_orientations_ (l_x, l_y) = angle; + + //*lp_norm = fabs(l_nz)*255; + + //int l_val1 = static_cast(l_nx * l_offsetx + l_offsetx); + //int l_val2 = static_cast(l_ny * l_offsety + l_offsety); + //int l_val3 = static_cast(l_nz * GRANULARITY + GRANULARITY); + + //*lp_norm = NORMAL_LUT[l_val3][l_val2][l_val1]; + *lp_norm = static_cast (0x1 << bin_index); + } + else + { + *lp_norm = 0; // Discard shadows from depth sensor + } + } + else + { + *lp_norm = 0; //out of depth + } + ++lp_line; + ++lp_norm; + } + } + /*cvSmooth(m_dep[0], m_dep[0], CV_MEDIAN, 5, 5);*/ + + unsigned char map[255]; + memset(map, 0, 255); + + map[0x1<<0] = 0; + map[0x1<<1] = 1; + map[0x1<<2] = 2; + map[0x1<<3] = 3; + map[0x1<<4] = 4; + map[0x1<<5] = 5; + map[0x1<<6] = 6; + map[0x1<<7] = 7; + + quantized_surface_normals_.resize (width, height); + for (int row_index = 0; row_index < height; ++row_index) + { + for (int col_index = 0; col_index < width; ++col_index) + { + quantized_surface_normals_ (col_index, row_index) = map[lp_normals[row_index*width + col_index]]; + } + } + + delete[] lp_depth; + delete[] lp_normals; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SurfaceNormalModality::extractFeatures (const MaskMap & mask, + const size_t nr_features, + const size_t modality_index, + std::vector & features) const +{ + const size_t width = mask.getWidth (); + const size_t height = mask.getHeight (); + + //cv::Mat maskImage(height, width, CV_8U, mask.mask); + //cv::erode(maskImage, maskImage + + // create distance maps for every quantization value + //cv::Mat distance_maps[8]; + //for (int map_index = 0; map_index < 8; ++map_index) + //{ + // distance_maps[map_index] = ::cv::Mat::zeros(height, width, CV_8U); + //} + + MaskMap mask_maps[8]; + for (size_t map_index = 0; map_index < 8; ++map_index) + mask_maps[map_index].resize (width, height); + + unsigned char map[255]; + memset(map, 0, 255); + + map[0x1<<0] = 0; + map[0x1<<1] = 1; + map[0x1<<2] = 2; + map[0x1<<3] = 3; + map[0x1<<4] = 4; + map[0x1<<5] = 5; + map[0x1<<6] = 6; + map[0x1<<7] = 7; + + QuantizedMap distance_map_indices (width, height); + //memset (distance_map_indices.data, 0, sizeof (distance_map_indices.data[0])*width*height); + + for (size_t row_index = 0; row_index < height; ++row_index) + { + for (size_t col_index = 0; col_index < width; ++col_index) + { + if (mask (col_index, row_index) != 0) + { + //const unsigned char quantized_value = quantized_surface_normals_ (row_index, col_index); + const unsigned char quantized_value = filtered_quantized_surface_normals_ (col_index, row_index); + + if (quantized_value == 0) + continue; + const int dist_map_index = map[quantized_value]; + + distance_map_indices (col_index, row_index) = static_cast (dist_map_index); + //distance_maps[dist_map_index].at(row_index, col_index) = 255; + mask_maps[dist_map_index] (col_index, row_index) = 255; + } + } + } + + DistanceMap distance_maps[8]; + for (int map_index = 0; map_index < 8; ++map_index) + computeDistanceMap (mask_maps[map_index], distance_maps[map_index]); + + DistanceMap mask_distance_maps; + computeDistanceMap (mask, mask_distance_maps); + + std::list list1; + std::list list2; + + float weights[8] = {0,0,0,0,0,0,0,0}; + + const size_t off = 4; + for (size_t row_index = off; row_index < height-off; ++row_index) + { + for (size_t col_index = off; col_index < width-off; ++col_index) + { + if (mask (col_index, row_index) != 0) + { + //const unsigned char quantized_value = quantized_surface_normals_ (row_index, col_index); + const unsigned char quantized_value = filtered_quantized_surface_normals_ (col_index, row_index); + + //const float nx = surface_normals_ (col_index, row_index).normal_x; + //const float ny = surface_normals_ (col_index, row_index).normal_y; + //const float nz = surface_normals_ (col_index, row_index).normal_z; + + if (quantized_value != 0)// && !(pcl_isnan (nx) || pcl_isnan (ny) || pcl_isnan (nz))) + { + const int distance_map_index = map[quantized_value]; + + //const float distance = distance_maps[distance_map_index].at (row_index, col_index); + const float distance = distance_maps[distance_map_index] (col_index, row_index); + const float distance_to_border = mask_distance_maps (col_index, row_index); + + if (distance >= feature_distance_threshold_ && distance_to_border >= min_distance_to_border_) + { + Candidate candidate; + + candidate.distance = distance; + candidate.x = col_index; + candidate.y = row_index; + candidate.bin_index = static_cast (distance_map_index); + + list1.push_back (candidate); + + ++weights[distance_map_index]; + } + } + } + } + } + + for (typename std::list::iterator iter = list1.begin (); iter != list1.end (); ++iter) + iter->distance *= 1.0f / weights[iter->bin_index]; + + list1.sort (); + + if (variable_feature_nr_) + { + int distance = static_cast (list1.size ()); + bool feature_selection_finished = false; + while (!feature_selection_finished) + { + const int sqr_distance = distance*distance; + for (typename std::list::iterator iter1 = list1.begin (); iter1 != list1.end (); ++iter1) + { + bool candidate_accepted = true; + for (typename std::list::iterator iter2 = list2.begin (); iter2 != list2.end (); ++iter2) + { + const int dx = static_cast (iter1->x) - static_cast (iter2->x); + const int dy = static_cast (iter1->y) - static_cast (iter2->y); + const int tmp_distance = dx*dx + dy*dy; + + if (tmp_distance < sqr_distance) + { + candidate_accepted = false; + break; + } + } + + + float min_min_sqr_distance = std::numeric_limits::max (); + float max_min_sqr_distance = 0; + for (typename std::list::iterator iter2 = list2.begin (); iter2 != list2.end (); ++iter2) + { + float min_sqr_distance = std::numeric_limits::max (); + for (typename std::list::iterator iter3 = list2.begin (); iter3 != list2.end (); ++iter3) + { + if (iter2 == iter3) + continue; + + const float dx = static_cast (iter2->x) - static_cast (iter3->x); + const float dy = static_cast (iter2->y) - static_cast (iter3->y); + + const float sqr_distance = dx*dx + dy*dy; + + if (sqr_distance < min_sqr_distance) + { + min_sqr_distance = sqr_distance; + } + + //std::cerr << min_sqr_distance; + } + //std::cerr << std::endl; + + // check current feature + { + const float dx = static_cast (iter2->x) - static_cast (iter1->x); + const float dy = static_cast (iter2->y) - static_cast (iter1->y); + + const float sqr_distance = dx*dx + dy*dy; + + if (sqr_distance < min_sqr_distance) + { + min_sqr_distance = sqr_distance; + } + } + + if (min_sqr_distance < min_min_sqr_distance) + min_min_sqr_distance = min_sqr_distance; + if (min_sqr_distance > max_min_sqr_distance) + max_min_sqr_distance = min_sqr_distance; + + //std::cerr << min_sqr_distance << ", " << min_min_sqr_distance << ", " << max_min_sqr_distance << std::endl; + } + + if (candidate_accepted) + { + //std::cerr << "feature_index: " << list2.size () << std::endl; + //std::cerr << "min_min_sqr_distance: " << min_min_sqr_distance << std::endl; + //std::cerr << "max_min_sqr_distance: " << max_min_sqr_distance << std::endl; + + if (min_min_sqr_distance < 50) + { + feature_selection_finished = true; + break; + } + + list2.push_back (*iter1); + } + + //if (list2.size () == nr_features) + //{ + // feature_selection_finished = true; + // break; + //} + } + --distance; + } + } + else + { + if (list1.size () <= nr_features) + { + features.reserve (list1.size ()); + for (typename std::list::iterator iter = list1.begin (); iter != list1.end (); ++iter) + { + QuantizedMultiModFeature feature; + + feature.x = static_cast (iter->x); + feature.y = static_cast (iter->y); + feature.modality_index = modality_index; + feature.quantized_value = filtered_quantized_surface_normals_ (iter->x, iter->y); + + features.push_back (feature); + } + + return; + } + + int distance = static_cast (list1.size () / nr_features + 1); // ??? @todo:!:!:!:!:!:! + while (list2.size () != nr_features) + { + const int sqr_distance = distance*distance; + for (typename std::list::iterator iter1 = list1.begin (); iter1 != list1.end (); ++iter1) + { + bool candidate_accepted = true; + + for (typename std::list::iterator iter2 = list2.begin (); iter2 != list2.end (); ++iter2) + { + const int dx = static_cast (iter1->x) - static_cast (iter2->x); + const int dy = static_cast (iter1->y) - static_cast (iter2->y); + const int tmp_distance = dx*dx + dy*dy; + + if (tmp_distance < sqr_distance) + { + candidate_accepted = false; + break; + } + } + + if (candidate_accepted) + list2.push_back (*iter1); + + if (list2.size () == nr_features) break; + } + --distance; + } + } + + for (typename std::list::iterator iter2 = list2.begin (); iter2 != list2.end (); ++iter2) + { + QuantizedMultiModFeature feature; + + feature.x = static_cast (iter2->x); + feature.y = static_cast (iter2->y); + feature.modality_index = modality_index; + feature.quantized_value = filtered_quantized_surface_normals_ (iter2->x, iter2->y); + + features.push_back (feature); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SurfaceNormalModality::extractAllFeatures ( + const MaskMap & mask, const size_t, const size_t modality_index, + std::vector & features) const +{ + const size_t width = mask.getWidth (); + const size_t height = mask.getHeight (); + + //cv::Mat maskImage(height, width, CV_8U, mask.mask); + //cv::erode(maskImage, maskImage + + // create distance maps for every quantization value + //cv::Mat distance_maps[8]; + //for (int map_index = 0; map_index < 8; ++map_index) + //{ + // distance_maps[map_index] = ::cv::Mat::zeros(height, width, CV_8U); + //} + + MaskMap mask_maps[8]; + for (size_t map_index = 0; map_index < 8; ++map_index) + mask_maps[map_index].resize (width, height); + + unsigned char map[255]; + memset(map, 0, 255); + + map[0x1<<0] = 0; + map[0x1<<1] = 1; + map[0x1<<2] = 2; + map[0x1<<3] = 3; + map[0x1<<4] = 4; + map[0x1<<5] = 5; + map[0x1<<6] = 6; + map[0x1<<7] = 7; + + QuantizedMap distance_map_indices (width, height); + //memset (distance_map_indices.data, 0, sizeof (distance_map_indices.data[0])*width*height); + + for (size_t row_index = 0; row_index < height; ++row_index) + { + for (size_t col_index = 0; col_index < width; ++col_index) + { + if (mask (col_index, row_index) != 0) + { + //const unsigned char quantized_value = quantized_surface_normals_ (row_index, col_index); + const unsigned char quantized_value = filtered_quantized_surface_normals_ (col_index, row_index); + + if (quantized_value == 0) + continue; + const int dist_map_index = map[quantized_value]; + + distance_map_indices (col_index, row_index) = static_cast (dist_map_index); + //distance_maps[dist_map_index].at(row_index, col_index) = 255; + mask_maps[dist_map_index] (col_index, row_index) = 255; + } + } + } + + DistanceMap distance_maps[8]; + for (int map_index = 0; map_index < 8; ++map_index) + computeDistanceMap (mask_maps[map_index], distance_maps[map_index]); + + DistanceMap mask_distance_maps; + computeDistanceMap (mask, mask_distance_maps); + + std::list list1; + std::list list2; + + float weights[8] = {0,0,0,0,0,0,0,0}; + + const size_t off = 4; + for (size_t row_index = off; row_index < height-off; ++row_index) + { + for (size_t col_index = off; col_index < width-off; ++col_index) + { + if (mask (col_index, row_index) != 0) + { + //const unsigned char quantized_value = quantized_surface_normals_ (row_index, col_index); + const unsigned char quantized_value = filtered_quantized_surface_normals_ (col_index, row_index); + + //const float nx = surface_normals_ (col_index, row_index).normal_x; + //const float ny = surface_normals_ (col_index, row_index).normal_y; + //const float nz = surface_normals_ (col_index, row_index).normal_z; + + if (quantized_value != 0)// && !(pcl_isnan (nx) || pcl_isnan (ny) || pcl_isnan (nz))) + { + const int distance_map_index = map[quantized_value]; + + //const float distance = distance_maps[distance_map_index].at (row_index, col_index); + const float distance = distance_maps[distance_map_index] (col_index, row_index); + const float distance_to_border = mask_distance_maps (col_index, row_index); + + if (distance >= feature_distance_threshold_ && distance_to_border >= min_distance_to_border_) + { + Candidate candidate; + + candidate.distance = distance; + candidate.x = col_index; + candidate.y = row_index; + candidate.bin_index = static_cast (distance_map_index); + + list1.push_back (candidate); + + ++weights[distance_map_index]; + } + } + } + } + } + + for (typename std::list::iterator iter = list1.begin (); iter != list1.end (); ++iter) + iter->distance *= 1.0f / weights[iter->bin_index]; + + list1.sort (); + + features.reserve (list1.size ()); + for (typename std::list::iterator iter = list1.begin (); iter != list1.end (); ++iter) + { + QuantizedMultiModFeature feature; + + feature.x = static_cast (iter->x); + feature.y = static_cast (iter->y); + feature.modality_index = modality_index; + feature.quantized_value = filtered_quantized_surface_normals_ (iter->x, iter->y); + + features.push_back (feature); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SurfaceNormalModality::quantizeSurfaceNormals () +{ + const size_t width = input_->width; + const size_t height = input_->height; + + quantized_surface_normals_.resize (width, height); + + for (size_t row_index = 0; row_index < height; ++row_index) + { + for (size_t col_index = 0; col_index < width; ++col_index) + { + const float normal_x = surface_normals_ (col_index, row_index).normal_x; + const float normal_y = surface_normals_ (col_index, row_index).normal_y; + const float normal_z = surface_normals_ (col_index, row_index).normal_z; + + if (pcl_isnan(normal_x) || pcl_isnan(normal_y) || pcl_isnan(normal_z) || normal_z > 0) + { + quantized_surface_normals_ (col_index, row_index) = 0; + continue; + } + + //quantized_surface_normals_.data[row_index*width+col_index] = + // normal_lookup_(normal_x, normal_y, normal_z); + + float angle = 11.25f + atan2f (normal_y, normal_x)*180.0f/3.14f; + + if (angle < 0.0f) angle += 360.0f; + if (angle >= 360.0f) angle -= 360.0f; + + int bin_index = static_cast (angle*8.0f/360.0f); + + //quantized_surface_normals_.data[row_index*width+col_index] = 0x1 << bin_index; + quantized_surface_normals_ (col_index, row_index) = static_cast (bin_index); + } + } + + return; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SurfaceNormalModality::filterQuantizedSurfaceNormals () +{ + const int width = input_->width; + const int height = input_->height; + + filtered_quantized_surface_normals_.resize (width, height); + + //for (int row_index = 2; row_index < height-2; ++row_index) + //{ + // for (int col_index = 2; col_index < width-2; ++col_index) + // { + // std::list values; + // values.reserve (25); + + // unsigned char * dataPtr = quantized_surface_normals_.getData () + (row_index-2)*width+col_index-2; + // values.push_back (dataPtr[0]); + // values.push_back (dataPtr[1]); + // values.push_back (dataPtr[2]); + // values.push_back (dataPtr[3]); + // values.push_back (dataPtr[4]); + // dataPtr += width; + // values.push_back (dataPtr[0]); + // values.push_back (dataPtr[1]); + // values.push_back (dataPtr[2]); + // values.push_back (dataPtr[3]); + // values.push_back (dataPtr[4]); + // dataPtr += width; + // values.push_back (dataPtr[0]); + // values.push_back (dataPtr[1]); + // values.push_back (dataPtr[2]); + // values.push_back (dataPtr[3]); + // values.push_back (dataPtr[4]); + // dataPtr += width; + // values.push_back (dataPtr[0]); + // values.push_back (dataPtr[1]); + // values.push_back (dataPtr[2]); + // values.push_back (dataPtr[3]); + // values.push_back (dataPtr[4]); + // dataPtr += width; + // values.push_back (dataPtr[0]); + // values.push_back (dataPtr[1]); + // values.push_back (dataPtr[2]); + // values.push_back (dataPtr[3]); + // values.push_back (dataPtr[4]); + + // values.sort (); + + // filtered_quantized_surface_normals_ (col_index, row_index) = values[12]; + // } + //} + + + //for (int row_index = 2; row_index < height-2; ++row_index) + //{ + // for (int col_index = 2; col_index < width-2; ++col_index) + // { + // filtered_quantized_surface_normals_ (col_index, row_index) = static_cast (0x1 << (quantized_surface_normals_ (col_index, row_index) - 1)); + // } + //} + + + // filter data + for (int row_index = 2; row_index < height-2; ++row_index) + { + for (int col_index = 2; col_index < width-2; ++col_index) + { + unsigned char histogram[9] = {0,0,0,0,0,0,0,0,0}; + + //{ + // unsigned char * dataPtr = quantized_surface_normals_.getData () + (row_index-1)*width+col_index-1; + // ++histogram[dataPtr[0]]; + // ++histogram[dataPtr[1]]; + // ++histogram[dataPtr[2]]; + //} + //{ + // unsigned char * dataPtr = quantized_surface_normals_.getData () + row_index*width+col_index-1; + // ++histogram[dataPtr[0]]; + // ++histogram[dataPtr[1]]; + // ++histogram[dataPtr[2]]; + //} + //{ + // unsigned char * dataPtr = quantized_surface_normals_.getData () + (row_index+1)*width+col_index-1; + // ++histogram[dataPtr[0]]; + // ++histogram[dataPtr[1]]; + // ++histogram[dataPtr[2]]; + //} + + { + unsigned char * dataPtr = quantized_surface_normals_.getData () + (row_index-2)*width+col_index-2; + ++histogram[dataPtr[0]]; + ++histogram[dataPtr[1]]; + ++histogram[dataPtr[2]]; + ++histogram[dataPtr[3]]; + ++histogram[dataPtr[4]]; + } + { + unsigned char * dataPtr = quantized_surface_normals_.getData () + (row_index-1)*width+col_index-2; + ++histogram[dataPtr[0]]; + ++histogram[dataPtr[1]]; + ++histogram[dataPtr[2]]; + ++histogram[dataPtr[3]]; + ++histogram[dataPtr[4]]; + } + { + unsigned char * dataPtr = quantized_surface_normals_.getData () + (row_index)*width+col_index-2; + ++histogram[dataPtr[0]]; + ++histogram[dataPtr[1]]; + ++histogram[dataPtr[2]]; + ++histogram[dataPtr[3]]; + ++histogram[dataPtr[4]]; + } + { + unsigned char * dataPtr = quantized_surface_normals_.getData () + (row_index+1)*width+col_index-2; + ++histogram[dataPtr[0]]; + ++histogram[dataPtr[1]]; + ++histogram[dataPtr[2]]; + ++histogram[dataPtr[3]]; + ++histogram[dataPtr[4]]; + } + { + unsigned char * dataPtr = quantized_surface_normals_.getData () + (row_index+2)*width+col_index-2; + ++histogram[dataPtr[0]]; + ++histogram[dataPtr[1]]; + ++histogram[dataPtr[2]]; + ++histogram[dataPtr[3]]; + ++histogram[dataPtr[4]]; + } + + + unsigned char max_hist_value = 0; + int max_hist_index = -1; + + if (max_hist_value < histogram[1]) {max_hist_index = 0; max_hist_value = histogram[1];} + if (max_hist_value < histogram[2]) {max_hist_index = 1; max_hist_value = histogram[2];} + if (max_hist_value < histogram[3]) {max_hist_index = 2; max_hist_value = histogram[3];} + if (max_hist_value < histogram[4]) {max_hist_index = 3; max_hist_value = histogram[4];} + if (max_hist_value < histogram[5]) {max_hist_index = 4; max_hist_value = histogram[5];} + if (max_hist_value < histogram[6]) {max_hist_index = 5; max_hist_value = histogram[6];} + if (max_hist_value < histogram[7]) {max_hist_index = 6; max_hist_value = histogram[7];} + if (max_hist_value < histogram[8]) {max_hist_index = 7; max_hist_value = histogram[8];} + + if (max_hist_index != -1 && max_hist_value >= 1) + { + filtered_quantized_surface_normals_ (col_index, row_index) = static_cast (0x1 << max_hist_index); + } + else + { + filtered_quantized_surface_normals_ (col_index, row_index) = 0; + } + + //filtered_quantized_color_gradients_.data[row_index*width+col_index] = quantized_color_gradients_.data[row_index*width+col_index]; + } + } + + + + //cv::Mat data1(quantized_surface_normals_.height, quantized_surface_normals_.width, CV_8U, quantized_surface_normals_.data); + //cv::Mat data2(filtered_quantized_surface_normals_.height, filtered_quantized_surface_normals_.width, CV_8U, filtered_quantized_surface_normals_.data); + + //cv::medianBlur(data1, data2, 3); + + //for (int row_index = 0; row_index < height; ++row_index) + //{ + // for (int col_index = 0; col_index < width; ++col_index) + // { + // filtered_quantized_surface_normals_.data[row_index*width+col_index] = 0x1 << filtered_quantized_surface_normals_.data[row_index*width+col_index]; + // } + //} +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SurfaceNormalModality::computeDistanceMap (const MaskMap & input, DistanceMap & output) const +{ + const size_t width = input.getWidth (); + const size_t height = input.getHeight (); + + output.resize (width, height); + + // compute distance map + //float *distance_map = new float[input_->points.size ()]; + const unsigned char * mask_map = input.getData (); + float * distance_map = output.getData (); + for (size_t index = 0; index < width*height; ++index) + { + if (mask_map[index] == 0) + distance_map[index] = 0.0f; + else + distance_map[index] = static_cast (width + height); + } + + // first pass + float * previous_row = distance_map; + float * current_row = previous_row + width; + for (size_t ri = 1; ri < height; ++ri) + { + for (size_t ci = 1; ci < width; ++ci) + { + const float up_left = previous_row [ci - 1] + 1.4f; //distance_map[(ri-1)*input_->width + ci-1] + 1.4f; + const float up = previous_row [ci] + 1.0f; //distance_map[(ri-1)*input_->width + ci] + 1.0f; + const float up_right = previous_row [ci + 1] + 1.4f; //distance_map[(ri-1)*input_->width + ci+1] + 1.4f; + const float left = current_row [ci - 1] + 1.0f; //distance_map[ri*input_->width + ci-1] + 1.0f; + const float center = current_row [ci]; //distance_map[ri*input_->width + ci]; + + const float min_value = std::min (std::min (up_left, up), std::min (left, up_right)); + + if (min_value < center) + current_row[ci] = min_value; //distance_map[ri * input_->width + ci] = min_value; + } + previous_row = current_row; + current_row += width; + } + + // second pass + float * next_row = distance_map + width * (height - 1); + current_row = next_row - width; + for (int ri = static_cast (height)-2; ri >= 0; --ri) + { + for (int ci = static_cast (width)-2; ci >= 0; --ci) + { + const float lower_left = next_row [ci - 1] + 1.4f; //distance_map[(ri+1)*input_->width + ci-1] + 1.4f; + const float lower = next_row [ci] + 1.0f; //distance_map[(ri+1)*input_->width + ci] + 1.0f; + const float lower_right = next_row [ci + 1] + 1.4f; //distance_map[(ri+1)*input_->width + ci+1] + 1.4f; + const float right = current_row [ci + 1] + 1.0f; //distance_map[ri*input_->width + ci+1] + 1.0f; + const float center = current_row [ci]; //distance_map[ri*input_->width + ci]; + + const float min_value = std::min (std::min (lower_left, lower), std::min (right, lower_right)); + + if (min_value < center) + current_row[ci] = min_value; //distance_map[ri*input_->width + ci] = min_value; + } + next_row = current_row; + current_row -= width; + } +} + + +#endif diff --git a/pcl-1.7/pcl/recognition/trimmed_icp.h b/pcl-1.7/pcl/recognition/trimmed_icp.h new file mode 100644 index 0000000..e07bab0 --- /dev/null +++ b/pcl-1.7/pcl/recognition/trimmed_icp.h @@ -0,0 +1,187 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +/* + * trimmed_icp.h + * + * Created on: Mar 10, 2013 + * Author: papazov + */ + +#ifndef TRIMMED_ICP_H_ +#define TRIMMED_ICP_H_ + +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace recognition + { + template + class PCL_EXPORTS TrimmedICP: public pcl::registration::TransformationEstimationSVD + { + public: + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename Eigen::Matrix Matrix4; + + public: + TrimmedICP () + : new_to_old_energy_ratio_ (0.99f) + {} + + virtual ~TrimmedICP () + {} + + /** \brief Call this method before calling align(). + * + * \param[in] target is target point cloud. The method builds a kd-tree based on 'target' for performing fast closest point search. + * The source point cloud will be registered to 'target' (see align() method). + * */ + inline void + init (const PointCloudConstPtr& target) + { + target_points_ = target; + kdtree_.setInputCloud (target); + } + + /** \brief The method performs trimmed ICP, i.e., it rigidly registers the source to the target (passed to the init() method). + * + * \param[in] source_points is the point cloud to be registered to the target. + * \param[in] num_source_points_to_use gives the number of closest source points taken into account for registration. By closest + * source points we mean the source points closest to the target. These points are computed anew at each iteration. + * \param[in,out] guess_and_result is the estimated rigid transform. IMPORTANT: this matrix is also taken as the initial guess + * for the alignment. If there is no guess, set the matrix to identity! + * */ + inline void + align (const PointCloud& source_points, int num_source_points_to_use, Matrix4& guess_and_result) const + { + int num_trimmed_source_points = num_source_points_to_use, num_source_points = static_cast (source_points.size ()); + + if ( num_trimmed_source_points >= num_source_points ) + { + printf ("WARNING in 'TrimmedICP::%s()': the user-defined number of source points of interest is greater or equal to " + "the total number of source points. Trimmed ICP will work correctly but won't be very efficient. Either set " + "the number of source points to use to a lower value or use standard ICP.\n", __func__); + num_trimmed_source_points = num_source_points; + } + + // These are vectors containing source to target correspondences + pcl::Correspondences full_src_to_tgt (num_source_points), trimmed_src_to_tgt (num_trimmed_source_points); + + // Some variables for the closest point search + pcl::PointXYZ transformed_source_point; + std::vector target_index (1); + std::vector sqr_dist_to_target (1); + float old_energy, energy = std::numeric_limits::max (); + +// printf ("\nalign\n"); + + do + { + // Update the correspondences + for ( int i = 0 ; i < num_source_points ; ++i ) + { + // Transform the i-th source point based on the current transform matrix + aux::transform (guess_and_result, source_points.points[i], transformed_source_point); + + // Perform the closest point search + kdtree_.nearestKSearch (transformed_source_point, 1, target_index, sqr_dist_to_target); + + // Update the i-th correspondence + full_src_to_tgt[i].index_query = i; + full_src_to_tgt[i].index_match = target_index[0]; + full_src_to_tgt[i].distance = sqr_dist_to_target[0]; + } + + // Sort in ascending order according to the squared distance + std::sort (full_src_to_tgt.begin (), full_src_to_tgt.end (), TrimmedICP::compareCorrespondences); + + old_energy = energy; + energy = 0.0f; + + // Now, setup the trimmed correspondences used for the transform estimation + for ( int i = 0 ; i < num_trimmed_source_points ; ++i ) + { + trimmed_src_to_tgt[i].index_query = full_src_to_tgt[i].index_query; + trimmed_src_to_tgt[i].index_match = full_src_to_tgt[i].index_match; + energy += full_src_to_tgt[i].distance; + } + + this->estimateRigidTransformation (source_points, *target_points_, trimmed_src_to_tgt, guess_and_result); + +// printf ("energy = %f, energy diff. = %f, ratio = %f\n", energy, old_energy - energy, energy/old_energy); + } + while ( energy/old_energy < new_to_old_energy_ratio_ ); // iterate if enough progress + +// printf ("\n"); + } + + inline void + setNewToOldEnergyRatio (float ratio) + { + if ( ratio >= 1 ) + new_to_old_energy_ratio_ = 0.99f; + else + new_to_old_energy_ratio_ = ratio; + } + + protected: + static inline bool + compareCorrespondences (const pcl::Correspondence& a, const pcl::Correspondence& b) + { + return static_cast (a.distance < b.distance); + } + + protected: + PointCloudConstPtr target_points_; + pcl::KdTreeFLANN kdtree_; + float new_to_old_energy_ratio_; + }; + } // namespace recognition +} // namespace pcl + + +#endif /* TRIMMED_ICP_H_ */ diff --git a/pcl-1.7/pcl/recognition/voxel_structure.h b/pcl-1.7/pcl/recognition/voxel_structure.h new file mode 100644 index 0000000..ed90c4d --- /dev/null +++ b/pcl-1.7/pcl/recognition/voxel_structure.h @@ -0,0 +1,171 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_RECOGNITION_VOXEL_STRUCTURE_H_ +#define PCL_RECOGNITION_VOXEL_STRUCTURE_H_ + +#include + +namespace pcl +{ + namespace recognition + { + /** \brief This class is a box in R3 built of voxels ordered in a regular rectangular grid. Each voxel is of type T. */ + template + class VoxelStructure + { + public: + inline VoxelStructure (): voxels_(NULL){} + inline virtual ~VoxelStructure (){ this->clear();} + + /** \brief Call this method before using an instance of this class. Parameter meaning is obvious. */ + inline void + build (const REAL bounds[6], int num_of_voxels[3]); + + /** \brief Release the memory allocated for the voxels. */ + inline void + clear (){ if ( voxels_ ){ delete[] voxels_; voxels_ = NULL;}} + + /** \brief Returns a pointer to the voxel which contains p or NULL if p is not inside the structure. */ + inline T* + getVoxel (const REAL p[3]); + + /** \brief Returns a pointer to the voxel with integer id (x,y,z) or NULL if (x,y,z) is out of bounds. */ + inline T* + getVoxel (int x, int y, int z) const; + + /** \brief Returns the linear voxel array. */ + const inline T* + getVoxels () const + { + return voxels_; + } + + /** \brief Returns the linear voxel array. */ + inline T* + getVoxels () + { + return voxels_; + } + + /** \brief Converts a linear id to a 3D id, i.e., computes the integer 3D coordinates of a voxel from its position in the voxel array. + * + * \param[in] linear_id the position of the voxel in the internal voxel array. + * \param[out] id3d an array of 3 integers for the integer coordinates of the voxel. */ + inline void + compute3dId (int linear_id, int id3d[3]) const + { + // Compute the z axis id + id3d[2] = linear_id / num_of_voxels_xy_plane_; + int proj_xy = linear_id % num_of_voxels_xy_plane_; + // Compute the y axis id + id3d[1] = proj_xy / num_of_voxels_[0]; + // Compute the x axis id + id3d[0] = proj_xy % num_of_voxels_[0]; + } + + /** \brief Returns the number of voxels in x, y and z direction. */ + inline const int* + getNumberOfVoxelsXYZ() const + { + return (num_of_voxels_); + } + + /** \brief Computes the center of the voxel with given integer coordinates. + * + * \param[in] id3 the integer coordinates along the x, y and z axis. + * \param[out] center */ + inline void + computeVoxelCenter (const int id3[3], REAL center[3]) const + { + center[0] = min_center_[0] + static_cast (id3[0])*spacing_[0]; + center[1] = min_center_[1] + static_cast (id3[1])*spacing_[1]; + center[2] = min_center_[2] + static_cast (id3[2])*spacing_[2]; + } + + /** \brief Returns the total number of voxels. */ + inline int + getNumberOfVoxels() const + { + return (total_num_of_voxels_); + } + + /** \brief Returns the bounds of the voxel structure, which is pointer to the internal array of 6 doubles: (min_x, max_x, min_y, max_y, min_z, max_z). */ + inline const float* + getBounds() const + { + return (bounds_); + } + + /** \brief Copies the bounds of the voxel structure to 'b'. */ + inline void + getBounds(REAL b[6]) const + { + b[0] = bounds_[0]; + b[1] = bounds_[1]; + b[2] = bounds_[2]; + b[3] = bounds_[3]; + b[4] = bounds_[4]; + b[5] = bounds_[5]; + } + + /** \brief Returns the voxel spacing in x, y and z direction. That's the same as the voxel size along each axis. */ + const REAL* + getVoxelSpacing() const + { + return (spacing_); + } + + /** \brief Saves pointers to the voxels which are neighbors of the voxels which contains 'p'. The containing voxel is returned too. + * 'neighs' has to be an array of pointers with space for at least 27 pointers (27 = 3^3 which is the max number of neighbors). The */ + inline int + getNeighbors (const REAL* p, T **neighs) const; + + protected: + T *voxels_; + int num_of_voxels_[3], num_of_voxels_xy_plane_, total_num_of_voxels_; + REAL bounds_[6]; + REAL spacing_[3]; // spacing betwen the voxel in x, y and z direction = voxel size in x, y and z direction + REAL min_center_[3]; // the center of the voxel with integer coordinates (0, 0, 0) + }; + } // namespace recognition +} // namespace pcl + +#include + +#endif // PCL_RECOGNITION_VOXEL_STRUCTURE_H_ diff --git a/pcl-1.7/pcl/register_point_struct.h b/pcl-1.7/pcl/register_point_struct.h new file mode 100644 index 0000000..57a0e42 --- /dev/null +++ b/pcl-1.7/pcl/register_point_struct.h @@ -0,0 +1,367 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTER_POINT_STRUCT_H_ +#define PCL_REGISTER_POINT_STRUCT_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#if defined _MSC_VER + #pragma warning (push, 2) + // 4244 : conversion from 'type1' to 'type2', possible loss of data + #pragma warning (disable: 4244) +#endif + +//https://bugreports.qt-project.org/browse/QTBUG-22829 +#ifndef Q_MOC_RUN +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#endif +#include //offsetof + +// Must be used in global namespace with name fully qualified +#define POINT_CLOUD_REGISTER_POINT_STRUCT(name, fseq) \ + POINT_CLOUD_REGISTER_POINT_STRUCT_I(name, \ + BOOST_PP_CAT(POINT_CLOUD_REGISTER_POINT_STRUCT_X fseq, 0)) \ + /***/ + +#define POINT_CLOUD_REGISTER_POINT_WRAPPER(wrapper, pod) \ + BOOST_MPL_ASSERT_MSG(sizeof(wrapper) == sizeof(pod), POINT_WRAPPER_AND_POD_TYPES_HAVE_DIFFERENT_SIZES, (wrapper&, pod&)); \ + namespace pcl { \ + namespace traits { \ + template<> struct POD { typedef pod type; }; \ + } \ + } \ + /***/ + +// These macros help transform the unusual data structure (type, name, tag)(type, name, tag)... +// into a proper preprocessor sequence of 3-tuples ((type, name, tag))((type, name, tag))... +#define POINT_CLOUD_REGISTER_POINT_STRUCT_X(type, name, tag) \ + ((type, name, tag)) POINT_CLOUD_REGISTER_POINT_STRUCT_Y +#define POINT_CLOUD_REGISTER_POINT_STRUCT_Y(type, name, tag) \ + ((type, name, tag)) POINT_CLOUD_REGISTER_POINT_STRUCT_X +#define POINT_CLOUD_REGISTER_POINT_STRUCT_X0 +#define POINT_CLOUD_REGISTER_POINT_STRUCT_Y0 + +namespace pcl +{ + namespace traits + { + template inline + typename boost::disable_if_c::value>::type + plus (T &l, const T &r) + { + l += r; + } + + template inline + typename boost::enable_if_c::value>::type + plus (typename boost::remove_const::type &l, const T &r) + { + typedef typename boost::remove_all_extents::type type; + static const uint32_t count = sizeof (T) / sizeof (type); + for (int i = 0; i < count; ++i) + l[i] += r[i]; + } + + template inline + typename boost::disable_if_c::value>::type + plusscalar (T1 &p, const T2 &scalar) + { + p += scalar; + } + + template inline + typename boost::enable_if_c::value>::type + plusscalar (T1 &p, const T2 &scalar) + { + typedef typename boost::remove_all_extents::type type; + static const uint32_t count = sizeof (T1) / sizeof (type); + for (int i = 0; i < count; ++i) + p[i] += scalar; + } + + template inline + typename boost::disable_if_c::value>::type + minus (T &l, const T &r) + { + l -= r; + } + + template inline + typename boost::enable_if_c::value>::type + minus (typename boost::remove_const::type &l, const T &r) + { + typedef typename boost::remove_all_extents::type type; + static const uint32_t count = sizeof (T) / sizeof (type); + for (int i = 0; i < count; ++i) + l[i] -= r[i]; + } + + template inline + typename boost::disable_if_c::value>::type + minusscalar (T1 &p, const T2 &scalar) + { + p -= scalar; + } + + template inline + typename boost::enable_if_c::value>::type + minusscalar (T1 &p, const T2 &scalar) + { + typedef typename boost::remove_all_extents::type type; + static const uint32_t count = sizeof (T1) / sizeof (type); + for (int i = 0; i < count; ++i) + p[i] -= scalar; + } + + template inline + typename boost::disable_if_c::value>::type + mulscalar (T1 &p, const T2 &scalar) + { + p *= scalar; + } + + template inline + typename boost::enable_if_c::value>::type + mulscalar (T1 &p, const T2 &scalar) + { + typedef typename boost::remove_all_extents::type type; + static const uint32_t count = sizeof (T1) / sizeof (type); + for (int i = 0; i < count; ++i) + p[i] *= scalar; + } + + template inline + typename boost::disable_if_c::value>::type + divscalar (T1 &p, const T2 &scalar) + { + p /= scalar; + } + + template inline + typename boost::enable_if_c::value>::type + divscalar (T1 &p, const T2 &scalar) + { + typedef typename boost::remove_all_extents::type type; + static const uint32_t count = sizeof (T1) / sizeof (type); + for (int i = 0; i < count; ++i) + p[i] /= scalar; + } + } +} + +// Point operators +#define PCL_PLUSEQ_POINT_TAG(r, data, elem) \ + pcl::traits::plus (lhs.BOOST_PP_TUPLE_ELEM(3, 1, elem), \ + rhs.BOOST_PP_TUPLE_ELEM(3, 1, elem)); \ + /***/ + +#define PCL_PLUSEQSC_POINT_TAG(r, data, elem) \ + pcl::traits::plusscalar (p.BOOST_PP_TUPLE_ELEM(3, 1, elem), \ + scalar); \ + /***/ + //p.BOOST_PP_TUPLE_ELEM(3, 1, elem) += scalar; \ + +#define PCL_MINUSEQ_POINT_TAG(r, data, elem) \ + pcl::traits::minus (lhs.BOOST_PP_TUPLE_ELEM(3, 1, elem), \ + rhs.BOOST_PP_TUPLE_ELEM(3, 1, elem)); \ + /***/ + +#define PCL_MINUSEQSC_POINT_TAG(r, data, elem) \ + pcl::traits::minusscalar (p.BOOST_PP_TUPLE_ELEM(3, 1, elem), \ + scalar); \ + /***/ + //p.BOOST_PP_TUPLE_ELEM(3, 1, elem) -= scalar; \ + +#define PCL_MULEQSC_POINT_TAG(r, data, elem) \ + pcl::traits::mulscalar (p.BOOST_PP_TUPLE_ELEM(3, 1, elem), \ + scalar); \ + /***/ + +#define PCL_DIVEQSC_POINT_TAG(r, data, elem) \ + pcl::traits::divscalar (p.BOOST_PP_TUPLE_ELEM(3, 1, elem), \ + scalar); \ + /***/ + +// Construct type traits given full sequence of (type, name, tag) triples +// BOOST_MPL_ASSERT_MSG(boost::is_pod::value, +// REGISTERED_POINT_TYPE_MUST_BE_PLAIN_OLD_DATA, (name)); +#define POINT_CLOUD_REGISTER_POINT_STRUCT_I(name, seq) \ + namespace pcl \ + { \ + namespace fields \ + { \ + BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_TAG, name, seq) \ + } \ + namespace traits \ + { \ + BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_NAME, name, seq) \ + BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_OFFSET, name, seq) \ + BOOST_PP_SEQ_FOR_EACH(POINT_CLOUD_REGISTER_FIELD_DATATYPE, name, seq) \ + POINT_CLOUD_REGISTER_POINT_FIELD_LIST(name, POINT_CLOUD_EXTRACT_TAGS(seq)) \ + } \ + namespace common \ + { \ + inline const name& \ + operator+= (name& lhs, const name& rhs) \ + { \ + BOOST_PP_SEQ_FOR_EACH(PCL_PLUSEQ_POINT_TAG, _, seq) \ + return (lhs); \ + } \ + inline const name& \ + operator+= (name& p, const float& scalar) \ + { \ + BOOST_PP_SEQ_FOR_EACH(PCL_PLUSEQSC_POINT_TAG, _, seq) \ + return (p); \ + } \ + inline const name operator+ (const name& lhs, const name& rhs) \ + { name result = lhs; result += rhs; return (result); } \ + inline const name operator+ (const float& scalar, const name& p) \ + { name result = p; result += scalar; return (result); } \ + inline const name operator+ (const name& p, const float& scalar) \ + { name result = p; result += scalar; return (result); } \ + inline const name& \ + operator-= (name& lhs, const name& rhs) \ + { \ + BOOST_PP_SEQ_FOR_EACH(PCL_MINUSEQ_POINT_TAG, _, seq) \ + return (lhs); \ + } \ + inline const name& \ + operator-= (name& p, const float& scalar) \ + { \ + BOOST_PP_SEQ_FOR_EACH(PCL_MINUSEQSC_POINT_TAG, _, seq) \ + return (p); \ + } \ + inline const name operator- (const name& lhs, const name& rhs) \ + { name result = lhs; result -= rhs; return (result); } \ + inline const name operator- (const float& scalar, const name& p) \ + { name result = p; result -= scalar; return (result); } \ + inline const name operator- (const name& p, const float& scalar) \ + { name result = p; result -= scalar; return (result); } \ + inline const name& \ + operator*= (name& p, const float& scalar) \ + { \ + BOOST_PP_SEQ_FOR_EACH(PCL_MULEQSC_POINT_TAG, _, seq) \ + return (p); \ + } \ + inline const name operator* (const float& scalar, const name& p) \ + { name result = p; result *= scalar; return (result); } \ + inline const name operator* (const name& p, const float& scalar) \ + { name result = p; result *= scalar; return (result); } \ + inline const name& \ + operator/= (name& p, const float& scalar) \ + { \ + BOOST_PP_SEQ_FOR_EACH(PCL_DIVEQSC_POINT_TAG, _, seq) \ + return (p); \ + } \ + inline const name operator/ (const float& scalar, const name& p) \ + { name result = p; result /= scalar; return (result); } \ + inline const name operator/ (const name& p, const float& scalar) \ + { name result = p; result /= scalar; return (result); } \ + } \ + } \ + /***/ + +#define POINT_CLOUD_REGISTER_FIELD_TAG(r, name, elem) \ + struct BOOST_PP_TUPLE_ELEM(3, 2, elem); \ + /***/ + +#define POINT_CLOUD_REGISTER_FIELD_NAME(r, point, elem) \ + template \ + struct name \ + { \ + static const char value[]; \ + }; \ + \ + template \ + const char name::value[] = \ + BOOST_PP_STRINGIZE(BOOST_PP_TUPLE_ELEM(3, 2, elem)); \ + /***/ + +#define POINT_CLOUD_REGISTER_FIELD_OFFSET(r, name, elem) \ + template<> struct offset \ + { \ + static const size_t value = offsetof(name, BOOST_PP_TUPLE_ELEM(3, 1, elem)); \ + }; \ + /***/ + +// \note: the mpl::identity weirdness is to support array types without requiring the +// user to wrap them. The basic problem is: +// typedef float[81] type; // SYNTAX ERROR! +// typedef float type[81]; // OK, can now use "type" as a synonym for float[81] +#define POINT_CLOUD_REGISTER_FIELD_DATATYPE(r, name, elem) \ + template<> struct datatype \ + { \ + typedef boost::mpl::identity::type type; \ + typedef decomposeArray decomposed; \ + static const uint8_t value = asEnum::value; \ + static const uint32_t size = decomposed::value; \ + }; \ + /***/ + +#define POINT_CLOUD_TAG_OP(s, data, elem) pcl::fields::BOOST_PP_TUPLE_ELEM(3, 2, elem) + +#define POINT_CLOUD_EXTRACT_TAGS(seq) BOOST_PP_SEQ_TRANSFORM(POINT_CLOUD_TAG_OP, _, seq) + +#define POINT_CLOUD_REGISTER_POINT_FIELD_LIST(name, seq) \ + template<> struct fieldList \ + { \ + typedef boost::mpl::vector type; \ + }; \ + /***/ + +#if defined _MSC_VER + #pragma warning (pop) +#endif + +#endif //#ifndef PCL_REGISTER_POINT_STRUCT_H_ diff --git a/pcl-1.7/pcl/registration/bfgs.h b/pcl-1.7/pcl/registration/bfgs.h new file mode 100644 index 0000000..99f8482 --- /dev/null +++ b/pcl-1.7/pcl/registration/bfgs.h @@ -0,0 +1,618 @@ +#ifndef PCL_FOR_EIGEN_BFGS_H +#define PCL_FOR_EIGEN_BFGS_H + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include + +namespace Eigen +{ + template< typename _Scalar > + class PolynomialSolver<_Scalar,2> : public PolynomialSolverBase<_Scalar,2> + { + public: + typedef PolynomialSolverBase<_Scalar,2> PS_Base; + EIGEN_POLYNOMIAL_SOLVER_BASE_INHERITED_TYPES( PS_Base ) + + public: + + virtual ~PolynomialSolver () {} + + template< typename OtherPolynomial > + inline PolynomialSolver( const OtherPolynomial& poly, bool& hasRealRoot ) + { + compute( poly, hasRealRoot ); + } + + /** Computes the complex roots of a new polynomial. */ + template< typename OtherPolynomial > + void compute( const OtherPolynomial& poly, bool& hasRealRoot) + { + const Scalar ZERO(0); + Scalar a2(2 * poly[2]); + assert( ZERO != poly[poly.size()-1] ); + Scalar discriminant ((poly[1] * poly[1]) - (4 * poly[0] * poly[2])); + if (ZERO < discriminant) + { + Scalar discriminant_root (std::sqrt (discriminant)); + m_roots[0] = (-poly[1] - discriminant_root) / (a2) ; + m_roots[1] = (-poly[1] + discriminant_root) / (a2) ; + hasRealRoot = true; + } + else { + if (ZERO == discriminant) + { + m_roots.resize (1); + m_roots[0] = -poly[1] / a2; + hasRealRoot = true; + } + else + { + Scalar discriminant_root (std::sqrt (-discriminant)); + m_roots[0] = RootType (-poly[1] / a2, -discriminant_root / a2); + m_roots[1] = RootType (-poly[1] / a2, discriminant_root / a2); + hasRealRoot = false; + } + } + } + + template< typename OtherPolynomial > + void compute( const OtherPolynomial& poly) + { + bool hasRealRoot; + compute(poly, hasRealRoot); + } + + protected: + using PS_Base::m_roots; + }; +} + +template +struct BFGSDummyFunctor +{ + typedef _Scalar Scalar; + enum { InputsAtCompileTime = NX }; + typedef Eigen::Matrix VectorType; + + const int m_inputs; + + BFGSDummyFunctor() : m_inputs(InputsAtCompileTime) {} + BFGSDummyFunctor(int inputs) : m_inputs(inputs) {} + + virtual ~BFGSDummyFunctor() {} + int inputs() const { return m_inputs; } + + virtual double operator() (const VectorType &x) = 0; + virtual void df(const VectorType &x, VectorType &df) = 0; + virtual void fdf(const VectorType &x, Scalar &f, VectorType &df) = 0; +}; + +namespace BFGSSpace { + enum Status { + NegativeGradientEpsilon = -3, + NotStarted = -2, + Running = -1, + Success = 0, + NoProgress = 1 + }; +} + +/** + * BFGS stands for Broyden–Fletcher–Goldfarb–Shanno (BFGS) method for solving + * unconstrained nonlinear optimization problems. + * For further details please visit: http://en.wikipedia.org/wiki/BFGS_method + * The method provided here is almost similar to the one provided by GSL. + * It reproduces Fletcher's original algorithm in Practical Methods of Optimization + * algorithms : 2.6.2 and 2.6.4 and uses the same politics in GSL with cubic + * interpolation whenever it is possible else falls to quadratic interpolation for + * alpha parameter. + */ +template +class BFGS +{ +public: + typedef typename FunctorType::Scalar Scalar; + typedef typename FunctorType::VectorType FVectorType; + + BFGS(FunctorType &_functor) + : pnorm(0), g0norm(0), iter(-1), functor(_functor) { } + + typedef Eigen::DenseIndex Index; + + struct Parameters { + Parameters() + : max_iters(400) + , bracket_iters(100) + , section_iters(100) + , rho(0.01) + , sigma(0.01) + , tau1(9) + , tau2(0.05) + , tau3(0.5) + , step_size(1) + , order(3) {} + Index max_iters; // maximum number of function evaluation + Index bracket_iters; + Index section_iters; + Scalar rho; + Scalar sigma; + Scalar tau1; + Scalar tau2; + Scalar tau3; + Scalar step_size; + Index order; + }; + + BFGSSpace::Status minimize(FVectorType &x); + BFGSSpace::Status minimizeInit(FVectorType &x); + BFGSSpace::Status minimizeOneStep(FVectorType &x); + BFGSSpace::Status testGradient(Scalar epsilon); + void resetParameters(void) { parameters = Parameters(); } + + Parameters parameters; + Scalar f; + FVectorType gradient; +private: + + BFGS& operator=(const BFGS&); + BFGSSpace::Status lineSearch (Scalar rho, Scalar sigma, + Scalar tau1, Scalar tau2, Scalar tau3, + int order, Scalar alpha1, Scalar &alpha_new); + Scalar interpolate (Scalar a, Scalar fa, Scalar fpa, + Scalar b, Scalar fb, Scalar fpb, Scalar xmin, Scalar xmax, + int order); + void checkExtremum (const Eigen::Matrix& coefficients, Scalar x, Scalar& xmin, Scalar& fmin); + void moveTo (Scalar alpha); + Scalar slope (); + Scalar applyF (Scalar alpha); + Scalar applyDF (Scalar alpha); + void applyFDF (Scalar alpha, Scalar &f, Scalar &df); + void updatePosition (Scalar alpha, FVectorType& x, Scalar& f, FVectorType& g); + void changeDirection (); + + Scalar delta_f, fp0; + FVectorType x0, dx0, dg0, g0, dx, p; + Scalar pnorm, g0norm; + + Scalar f_alpha; + Scalar df_alpha; + FVectorType x_alpha; + FVectorType g_alpha; + + // cache "keys" + Scalar f_cache_key; + Scalar df_cache_key; + Scalar x_cache_key; + Scalar g_cache_key; + + Index iter; + FunctorType &functor; +}; + + +template void +BFGS::checkExtremum(const Eigen::Matrix& coefficients, Scalar x, Scalar& xmin, Scalar& fmin) +{ + Scalar y = Eigen::poly_eval(coefficients, x); + if(y < fmin) { xmin = x; fmin = y; } +} + +template void +BFGS::moveTo(Scalar alpha) +{ + x_alpha = x0 + alpha * p; + x_cache_key = alpha; +} + +template typename BFGS::Scalar +BFGS::slope() +{ + return (g_alpha.dot (p)); +} + +template typename BFGS::Scalar +BFGS::applyF(Scalar alpha) +{ + if (alpha == f_cache_key) return f_alpha; + moveTo (alpha); + f_alpha = functor (x_alpha); + f_cache_key = alpha; + return (f_alpha); +} + +template typename BFGS::Scalar +BFGS::applyDF(Scalar alpha) +{ + if (alpha == df_cache_key) return df_alpha; + moveTo (alpha); + if(alpha != g_cache_key) + { + functor.df (x_alpha, g_alpha); + g_cache_key = alpha; + } + df_alpha = slope (); + df_cache_key = alpha; + return (df_alpha); +} + +template void +BFGS::applyFDF(Scalar alpha, Scalar& f, Scalar& df) +{ + if(alpha == f_cache_key && alpha == df_cache_key) + { + f = f_alpha; + df = df_alpha; + return; + } + + if(alpha == f_cache_key || alpha == df_cache_key) + { + f = applyF (alpha); + df = applyDF (alpha); + return; + } + + moveTo (alpha); + functor.fdf (x_alpha, f_alpha, g_alpha); + f_cache_key = alpha; + g_cache_key = alpha; + df_alpha = slope (); + df_cache_key = alpha; + f = f_alpha; + df = df_alpha; +} + +template void +BFGS::updatePosition (Scalar alpha, FVectorType &x, Scalar &f, FVectorType &g) +{ + { + Scalar f_alpha, df_alpha; + applyFDF (alpha, f_alpha, df_alpha); + } ; + + f = f_alpha; + x = x_alpha; + g = g_alpha; +} + +template void +BFGS::changeDirection () +{ + x_alpha = x0; + x_cache_key = 0.0; + f_cache_key = 0.0; + g_alpha = g0; + g_cache_key = 0.0; + df_alpha = slope (); + df_cache_key = 0.0; +} + +template BFGSSpace::Status +BFGS::minimize(FVectorType &x) +{ + BFGSSpace::Status status = minimizeInit(x); + do { + status = minimizeOneStep(x); + iter++; + } while (status==BFGSSpace::Success && iter < parameters.max_iters); + return status; +} + +template BFGSSpace::Status +BFGS::minimizeInit(FVectorType &x) +{ + iter = 0; + delta_f = 0; + dx.setZero (); + functor.fdf(x, f, gradient); + x0 = x; + g0 = gradient; + g0norm = g0.norm (); + p = gradient * -1/g0norm; + pnorm = p.norm (); + fp0 = -g0norm; + + { + x_alpha = x0; x_cache_key = 0; + + f_alpha = f; f_cache_key = 0; + + g_alpha = g0; g_cache_key = 0; + + df_alpha = slope (); df_cache_key = 0; + } + + return BFGSSpace::NotStarted; +} + +template BFGSSpace::Status +BFGS::minimizeOneStep(FVectorType &x) +{ + Scalar alpha = 0.0, alpha1; + Scalar f0 = f; + if (pnorm == 0.0 || g0norm == 0.0 || fp0 == 0) + { + dx.setZero (); + return BFGSSpace::NoProgress; + } + + if (delta_f < 0) + { + Scalar del = std::max (-delta_f, 10 * std::numeric_limits::epsilon() * fabs(f0)); + alpha1 = std::min (1.0, 2.0 * del / (-fp0)); + } + else + alpha1 = fabs(parameters.step_size); + + BFGSSpace::Status status = lineSearch(parameters.rho, parameters.sigma, + parameters.tau1, parameters.tau2, parameters.tau3, + parameters.order, alpha1, alpha); + + if(status != BFGSSpace::Success) + return status; + + updatePosition(alpha, x, f, gradient); + + delta_f = f - f0; + + /* Choose a new direction for the next step */ + { + /* This is the BFGS update: */ + /* p' = g1 - A dx - B dg */ + /* A = - (1+ dg.dg/dx.dg) B + dg.g/dx.dg */ + /* B = dx.g/dx.dg */ + + Scalar dxg, dgg, dxdg, dgnorm, A, B; + + /* dx0 = x - x0 */ + dx0 = x - x0; + dx = dx0; /* keep a copy */ + + /* dg0 = g - g0 */ + dg0 = gradient - g0; + dxg = dx0.dot (gradient); + dgg = dg0.dot (gradient); + dxdg = dx0.dot (dg0); + dgnorm = dg0.norm (); + + if (dxdg != 0) + { + B = dxg / dxdg; + A = -(1.0 + dgnorm * dgnorm / dxdg) * B + dgg / dxdg; + } + else + { + B = 0; + A = 0; + } + + p = -A * dx0; + p+= gradient; + p+= -B * dg0 ; + } + + g0 = gradient; + x0 = x; + g0norm = g0.norm (); + pnorm = p.norm (); + + Scalar dir = ((p.dot (gradient)) > 0) ? -1.0 : 1.0; + p*= dir / pnorm; + pnorm = p.norm (); + fp0 = p.dot (g0); + + changeDirection(); + return BFGSSpace::Success; +} + +template typename BFGSSpace::Status +BFGS::testGradient(Scalar epsilon) +{ + if(epsilon < 0) + return BFGSSpace::NegativeGradientEpsilon; + else + { + if(gradient.norm () < epsilon) + return BFGSSpace::Success; + else + return BFGSSpace::Running; + } +} + +template typename BFGS::Scalar +BFGS::interpolate (Scalar a, Scalar fa, Scalar fpa, + Scalar b, Scalar fb, Scalar fpb, + Scalar xmin, Scalar xmax, + int order) +{ + /* Map [a,b] to [0,1] */ + Scalar y, alpha, ymin, ymax, fmin; + + ymin = (xmin - a) / (b - a); + ymax = (xmax - a) / (b - a); + + // Ensure ymin <= ymax + if (ymin > ymax) { Scalar tmp = ymin; ymin = ymax; ymax = tmp; }; + + if (order > 2 && !(fpb != fpb) && fpb != std::numeric_limits::infinity ()) + { + fpa = fpa * (b - a); + fpb = fpb * (b - a); + + Scalar eta = 3 * (fb - fa) - 2 * fpa - fpb; + Scalar xi = fpa + fpb - 2 * (fb - fa); + Scalar c0 = fa, c1 = fpa, c2 = eta, c3 = xi; + Scalar y0, y1; + Eigen::Matrix coefficients; + coefficients << c0, c1, c2, c3; + + y = ymin; + // Evaluate the cubic polyinomial at ymin; + fmin = Eigen::poly_eval (coefficients, ymin); + checkExtremum (coefficients, ymax, y, fmin); + { + // Solve quadratic polynomial for the derivate + Eigen::Matrix coefficients2; + coefficients2 << c1, 2 * c2, 3 * c3; + bool real_roots; + Eigen::PolynomialSolver solver (coefficients2, real_roots); + if(real_roots) + { + if ((solver.roots ()).size () == 2) /* found 2 roots */ + { + y0 = std::real (solver.roots () [0]); + y1 = std::real (solver.roots () [1]); + if(y0 > y1) { Scalar tmp (y0); y0 = y1; y1 = tmp; } + if (y0 > ymin && y0 < ymax) + checkExtremum (coefficients, y0, y, fmin); + if (y1 > ymin && y1 < ymax) + checkExtremum (coefficients, y1, y, fmin); + } + else if ((solver.roots ()).size () == 1) /* found 1 root */ + { + y0 = std::real (solver.roots () [0]); + if (y0 > ymin && y0 < ymax) + checkExtremum (coefficients, y0, y, fmin); + } + } + } + } + else + { + fpa = fpa * (b - a); + Scalar fl = fa + ymin*(fpa + ymin*(fb - fa -fpa)); + Scalar fh = fa + ymax*(fpa + ymax*(fb - fa -fpa)); + Scalar c = 2 * (fb - fa - fpa); /* curvature */ + y = ymin; fmin = fl; + + if (fh < fmin) { y = ymax; fmin = fh; } + + if (c > a) /* positive curvature required for a minimum */ + { + Scalar z = -fpa / c; /* location of minimum */ + if (z > ymin && z < ymax) { + Scalar f = fa + z*(fpa + z*(fb - fa -fpa)); + if (f < fmin) { y = z; fmin = f; }; + } + } + } + + alpha = a + y * (b - a); + return alpha; +} + +template BFGSSpace::Status +BFGS::lineSearch(Scalar rho, Scalar sigma, + Scalar tau1, Scalar tau2, Scalar tau3, + int order, Scalar alpha1, Scalar &alpha_new) +{ + Scalar f0, fp0, falpha, falpha_prev, fpalpha, fpalpha_prev, delta, alpha_next; + Scalar alpha = alpha1, alpha_prev = 0.0; + Scalar a, b, fa, fb, fpa, fpb; + Index i = 0; + + applyFDF (0.0, f0, fp0); + + falpha_prev = f0; + fpalpha_prev = fp0; + + /* Avoid uninitialized variables morning */ + a = 0.0; b = alpha; + fa = f0; fb = 0.0; + fpa = fp0; fpb = 0.0; + + /* Begin bracketing */ + + while (i++ < parameters.bracket_iters) + { + falpha = applyF (alpha); + + if (falpha > f0 + alpha * rho * fp0 || falpha >= falpha_prev) + { + a = alpha_prev; fa = falpha_prev; fpa = fpalpha_prev; + b = alpha; fb = falpha; fpb = std::numeric_limits::quiet_NaN (); + break; + } + + fpalpha = applyDF (alpha); + + /* Fletcher's sigma test */ + if (fabs (fpalpha) <= -sigma * fp0) + { + alpha_new = alpha; + return BFGSSpace::Success; + } + + if (fpalpha >= 0) + { + a = alpha; fa = falpha; fpa = fpalpha; + b = alpha_prev; fb = falpha_prev; fpb = fpalpha_prev; + break; /* goto sectioning */ + } + + delta = alpha - alpha_prev; + + { + Scalar lower = alpha + delta; + Scalar upper = alpha + tau1 * delta; + + alpha_next = interpolate (alpha_prev, falpha_prev, fpalpha_prev, + alpha, falpha, fpalpha, lower, upper, order); + + } + + alpha_prev = alpha; + falpha_prev = falpha; + fpalpha_prev = fpalpha; + alpha = alpha_next; + } + /* Sectioning of bracket [a,b] */ + while (i++ < parameters.section_iters) + { + delta = b - a; + + { + Scalar lower = a + tau2 * delta; + Scalar upper = b - tau3 * delta; + + alpha = interpolate (a, fa, fpa, b, fb, fpb, lower, upper, order); + } + falpha = applyF (alpha); + if ((a-alpha)*fpa <= std::numeric_limits::epsilon ()) { + /* roundoff prevents progress */ + return BFGSSpace::NoProgress; + }; + + if (falpha > f0 + rho * alpha * fp0 || falpha >= fa) + { + /* a_next = a; */ + b = alpha; fb = falpha; fpb = std::numeric_limits::quiet_NaN (); + } + else + { + fpalpha = applyDF (alpha); + + if (fabs(fpalpha) <= -sigma * fp0) + { + alpha_new = alpha; + return BFGSSpace::Success; /* terminate */ + } + + if ( ((b-a) >= 0 && fpalpha >= 0) || ((b-a) <=0 && fpalpha <= 0)) + { + b = a; fb = fa; fpb = fpa; + a = alpha; fa = falpha; fpa = fpalpha; + } + else + { + a = alpha; fa = falpha; fpa = fpalpha; + } + } + } + return BFGSSpace::Success; +} +#endif // PCL_FOR_EIGEN_BFGS_H + diff --git a/pcl-1.7/pcl/registration/boost.h b/pcl-1.7/pcl/registration/boost.h new file mode 100644 index 0000000..e5ae80f --- /dev/null +++ b/pcl-1.7/pcl/registration/boost.h @@ -0,0 +1,58 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_BOOST_H_ +#define PCL_REGISTRATION_BOOST_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +//#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#endif // PCL_REGISTRATION_BOOST_H_ diff --git a/pcl-1.7/pcl/registration/boost_graph.h b/pcl-1.7/pcl/registration/boost_graph.h new file mode 100644 index 0000000..0948d93 --- /dev/null +++ b/pcl-1.7/pcl/registration/boost_graph.h @@ -0,0 +1,103 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_BOOST_GRAPH_H_ +#define PCL_REGISTRATION_BOOST_GRAPH_H_ + +#include +#include +#include + +namespace boost +{ + + struct eigen_vecS + { + }; + + template + struct container_gen + { + typedef std::vector > type; + }; + + template <> + struct parallel_edge_traits + { + typedef allow_parallel_edge_tag type; + }; + + namespace detail + { + template <> + struct is_random_access + { + enum { value = true }; + typedef mpl::true_ type; + }; + } + + struct eigen_listS + { + }; + + template + struct container_gen + { + typedef std::list > type; + }; + + template <> + struct parallel_edge_traits + { + typedef allow_parallel_edge_tag type; + }; + + namespace detail + { + template <> + struct is_random_access + { + enum { value = false }; + typedef mpl::false_ type; + }; + } +} + +#endif // PCL_REGISTRATION_BOOST_GRAPH_H_ diff --git a/pcl-1.7/pcl/registration/convergence_criteria.h b/pcl-1.7/pcl/registration/convergence_criteria.h new file mode 100644 index 0000000..0e51b9f --- /dev/null +++ b/pcl-1.7/pcl/registration/convergence_criteria.h @@ -0,0 +1,90 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_CONVERGENCE_CRIERIA_H_ +#define PCL_REGISTRATION_CONVERGENCE_CRIERIA_H_ + +#include + +namespace pcl +{ + namespace registration + { + /** \brief @b ConvergenceCriteria represents an abstract base class for + * different convergence criteria used in registration loops. + * + * This should be used as part of an Iterative Closest Point (ICP)-like + * method, to verify if the algorithm has reached convergence. + * + * Typical convergence criteria that could inherit from this include: + * + * * a maximum number of iterations has been reached + * * the transformation (R, t) cannot be further updated (the difference between current and previous is smaller than a threshold) + * * the Mean Squared Error (MSE) between the current set of correspondences and the previous one is smaller than some threshold + * + * \author Radu B. Rusu + * \ingroup registration + */ + class PCL_EXPORTS ConvergenceCriteria + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Empty constructor. */ + ConvergenceCriteria () {} + + /** \brief Empty destructor. */ + virtual ~ConvergenceCriteria () {} + + /** \brief Check if convergence has been reached. Pure virtual. */ + virtual bool + hasConverged () = 0; + + /** \brief Bool operator. */ + operator bool () + { + return (hasConverged ()); + } + }; + } +} + +#endif // PCL_REGISTRATION_CONVERGENCE_CRIERIA_H_ + diff --git a/pcl-1.7/pcl/registration/correspondence_estimation.h b/pcl-1.7/pcl/registration/correspondence_estimation.h new file mode 100644 index 0000000..174a16a --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_estimation.h @@ -0,0 +1,563 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_H_ + +#include + +#include +#include +#include +#include +#include + +// added from outside +#include +#include +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief Abstract @b CorrespondenceEstimationBase class. + * All correspondence estimation methods should inherit from this. + * \author Radu B. Rusu + * \ingroup registration + */ + template + class CorrespondenceEstimationBase: public PCLBase + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + // using PCLBase::initCompute; + using PCLBase::deinitCompute; + using PCLBase::input_; + using PCLBase::indices_; + using PCLBase::setIndices; + + typedef pcl::search::KdTree KdTree; + typedef typename KdTree::Ptr KdTreePtr; + + typedef pcl::search::KdTree KdTreeReciprocal; + typedef typename KdTree::Ptr KdTreeReciprocalPtr; + + typedef pcl::PointCloud PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef pcl::PointCloud PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + typedef typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr; + + std::vector points_target_; // target + std::vector * points_target_ptr_; // target + std::vector index_target_; + std::vector * index_target_ptr_; + + std::vector points_src_; // source + std::vector * points_src_ptr_; // source + + std::vector index_src_; + std::vector * index_src_ptr_; + + KdTreeH * treeH_source_; + KdTreeH * treeH_target_; + + /** \brief Empty constructor. */ + CorrespondenceEstimationBase () + : corr_name_ ("CorrespondenceEstimationBase") + , tree_ (new pcl::search::KdTree) + , tree_reciprocal_ (new pcl::search::KdTree) + , target_ () + , target_indices_ () + , point_representation_ () + , input_transformed_ () + , input_fields_ () + , target_cloud_updated_ (true) + , source_cloud_updated_ (true) + , force_no_recompute_ (false) + , force_no_recompute_reciprocal_ (false) + , treeH_source_ (NULL) + , treeH_target_ (NULL) + , use_customized_tree_ (false) + , max_leaf_size_ (64) + , approx_radius_para_(0.0) + , approx_nn_para_(0.0) + , approx_nn_ops_num_(0.0) + , approx_leaders_num_(0) + , approx_followers_num_(0) + , save_approx_data_(false) + { + // PCL_ERROR ("CorrespondenceEstimationBase Init\n"); + } + + /** \brief Empty destructor */ + virtual ~CorrespondenceEstimationBase () + { + } + + /** Build the customized KDTree (for source point cloud). **/ + void buildHKdTree_source() + { + treeH_source_ = new KdTreeH(points_src_ptr_, \ + index_src_ptr_, max_leaf_size_, approx_radius_para_, approx_nn_para_); + treeH_source_->buildKDTree(); + } + + /** Build the customized KDTree (for target point cloud). **/ + void buildHKdTree_target() + { + treeH_target_ = new KdTreeH(points_target_ptr_, \ + index_target_ptr_, max_leaf_size_, approx_radius_para_, approx_nn_para_); + treeH_target_->buildKDTree(); + } + + /** \brief Provide a pointer to the input source + * (e.g., the point cloud that we want to align to the target) + * + * \param[in] cloud the input point cloud source + */ + PCL_DEPRECATED ("[pcl::registration::CorrespondenceEstimationBase::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.") + void + setInputCloud (const PointCloudSourceConstPtr &cloud); + + /** \brief Get a pointer to the input point cloud dataset target. */ + PCL_DEPRECATED ("[pcl::registration::CorrespondenceEstimationBase::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.") + PointCloudSourceConstPtr const + getInputCloud (); + + /** \brief Provide a pointer to the input source + * (e.g., the point cloud that we want to align to the target) + * + * \param[in] cloud the input point cloud source + */ + inline void + setInputSource (const PointCloudSourceConstPtr &cloud) + { + source_cloud_updated_ = true; + PCLBase::setInputCloud (cloud); + pcl::getFields (*cloud, input_fields_); + } + + /** \brief Get a pointer to the input point cloud dataset target. */ + inline PointCloudSourceConstPtr const + getInputSource () + { + return (input_ ); + } + + /** \brief Provide a pointer to the input target + * (e.g., the point cloud that we want to align the input source to) + * \param[in] cloud the input point cloud target + */ + inline void + setInputTarget (const PointCloudTargetConstPtr &cloud); + + /** \brief Get a pointer to the input point cloud dataset target. */ + inline PointCloudTargetConstPtr const + getInputTarget () { return (target_ ); } + + /** \brief See if this rejector requires source normals */ + virtual bool + requiresSourceNormals () const + { return (false); } + + /** \brief Abstract method for setting the source normals */ + virtual void + setSourceNormals (pcl::PCLPointCloud2::ConstPtr /*cloud2*/) + { + PCL_WARN ("[pcl::registration::%s::setSourceNormals] This class does not require input source normals", getClassName ().c_str ()); + } + + /** \brief See if this rejector requires target normals */ + virtual bool + requiresTargetNormals () const + { return (false); } + + /** \brief Abstract method for setting the target normals */ + virtual void + setTargetNormals (pcl::PCLPointCloud2::ConstPtr /*cloud2*/) + { + PCL_WARN ("[pcl::registration::%s::setTargetNormals] This class does not require input target normals", getClassName ().c_str ()); + } + + /** \brief Provide a pointer to the vector of indices that represent the + * input source point cloud. + * \param[in] indices a pointer to the vector of indices + */ + inline void + setIndicesSource (const IndicesPtr &indices) + { + setIndices (indices); + } + + /** \brief Get a pointer to the vector of indices used for the source dataset. */ + inline IndicesPtr const + getIndicesSource () { return (indices_); } + + /** \brief Provide a pointer to the vector of indices that represent the input target point cloud. + * \param[in] indices a pointer to the vector of indices + */ + inline void + setIndicesTarget (const IndicesPtr &indices) + { + target_cloud_updated_ = true; + target_indices_ = indices; + } + + /** \brief Get a pointer to the vector of indices used for the target dataset. */ + inline IndicesPtr const + getIndicesTarget () { return (target_indices_); } + + /** \brief Provide a pointer to the search object used to find correspondences in + * the target cloud. + * \param[in] tree a pointer to the spatial search object. + * \param[in] force_no_recompute If set to true, this tree will NEVER be + * recomputed, regardless of calls to setInputTarget. Only use if you are + * confident that the tree will be set correctly. + */ + inline void + setSearchMethodTarget (const KdTreePtr &tree, + bool force_no_recompute = false) + { + tree_ = tree; + if (force_no_recompute) + { + force_no_recompute_ = true; + } + // Since we just set a new tree, we need to check for updates + target_cloud_updated_ = true; + } + + /** \brief Get a pointer to the search method used to find correspondences in the + * target cloud. */ + inline KdTreePtr + getSearchMethodTarget () const + { + return (tree_); + } + + /** \brief Provide a pointer to the search object used to find correspondences in + * the source cloud (usually used by reciprocal correspondence finding). + * \param[in] tree a pointer to the spatial search object. + * \param[in] force_no_recompute If set to true, this tree will NEVER be + * recomputed, regardless of calls to setInputSource. Only use if you are + * extremely confident that the tree will be set correctly. + */ + inline void + setSearchMethodSource (const KdTreeReciprocalPtr &tree, + bool force_no_recompute = false) + { + tree_reciprocal_ = tree; + if ( force_no_recompute ) + { + force_no_recompute_reciprocal_ = true; + } + // Since we just set a new tree, we need to check for updates + source_cloud_updated_ = true; + } + + /** \brief Get a pointer to the search method used to find correspondences in the + * source cloud. */ + inline KdTreeReciprocalPtr + getSearchMethodSource () const + { + return (tree_reciprocal_); + } + + /** \brief Determine the correspondences between input and target cloud. + * \param[out] correspondences the found correspondences (index of query point, index of target point, distance) + * \param[in] max_distance maximum allowed distance between correspondences + */ + virtual void + determineCorrespondences (pcl::Correspondences &correspondences, + double max_distance = std::numeric_limits::max ()) = 0; + + /** \brief Determine the reciprocal correspondences between input and target cloud. + * A correspondence is considered reciprocal if both Src_i has Tgt_i as a + * correspondence, and Tgt_i has Src_i as one. + * + * \param[out] correspondences the found correspondences (index of query and target point, distance) + * \param[in] max_distance maximum allowed distance between correspondences + */ + virtual void + determineReciprocalCorrespondences (pcl::Correspondences &correspondences, + double max_distance = std::numeric_limits::max ()) = 0; + + /** \brief Provide a boost shared pointer to the PointRepresentation to be used + * when searching for nearest neighbors. + * + * \param[in] point_representation the PointRepresentation to be used by the + * k-D tree for nearest neighbor search + */ + inline void + setPointRepresentation (const PointRepresentationConstPtr &point_representation) + { + point_representation_ = point_representation; + } + + /** \brief Clone and cast to CorrespondenceEstimationBase */ + virtual boost::shared_ptr< CorrespondenceEstimationBase > clone () const = 0; + + inline void setUseCustomizedKDTree(bool use_customized_tree) { use_customized_tree_ = use_customized_tree;} + inline void setMaxLeafSize(int size) {max_leaf_size_ = size;} + inline void setSaveApproxData(bool save) {save_approx_data_ = save;} + + inline void setApproxNNPara(float approx_nn_para) { approx_nn_para_ = approx_nn_para; } + inline void getApproxNNOpsNum(int &approx_nn_ops_num) { approx_nn_ops_num = approx_nn_ops_num_; } + inline void getApproxLeadersNum(int &approx_leaders_num){ approx_leaders_num = approx_leaders_num_;} + inline void getApproxFollowersNum(int &approx_followers_num){ approx_followers_num = approx_followers_num_;} + + protected: + /** \brief The correspondence estimation method name. */ + std::string corr_name_; + + /** \brief A pointer to the spatial search object used for the target dataset. */ + KdTreePtr tree_; + + /** \brief A pointer to the spatial search object used for the source dataset. */ + KdTreeReciprocalPtr tree_reciprocal_; + + /** \brief The input point cloud dataset target. */ + PointCloudTargetConstPtr target_; + + /** \brief The target point cloud dataset indices. */ + IndicesPtr target_indices_; + + /** \brief The point representation used (internal). */ + PointRepresentationConstPtr point_representation_; + + /** \brief The transformed input source point cloud dataset. */ + PointCloudTargetPtr input_transformed_; + + /** \brief The types of input point fields available. */ + std::vector input_fields_; + + /** \brief Abstract class get name method. */ + inline const std::string& + getClassName () const { return (corr_name_); } + + /** \brief Internal computation initalization. */ + bool + initCompute (); + + /** \brief Internal computation initalization for reciprocal correspondences. */ + bool + initComputeReciprocal (); + + /** \brief Variable that stores whether we have a new target cloud, meaning we need to pre-process it again. + * This way, we avoid rebuilding the kd-tree for the target cloud every time the determineCorrespondences () method + * is called. */ + bool target_cloud_updated_; + /** \brief Variable that stores whether we have a new source cloud, meaning we need to pre-process it again. + * This way, we avoid rebuilding the reciprocal kd-tree for the source cloud every time the determineCorrespondences () method + * is called. */ + bool source_cloud_updated_; + /** \brief A flag which, if set, means the tree operating on the target cloud + * will never be recomputed*/ + bool force_no_recompute_; + + /** \brief A flag which, if set, means the tree operating on the source cloud + * will never be recomputed*/ + bool force_no_recompute_reciprocal_; + + /** Whether to use the customized KD-Tree data structure. **/ + bool use_customized_tree_; + + // Approximate parameter in radius search. + float approx_radius_para_; + + // Approximate parameter in NN search. + float approx_nn_para_; + + /** Number of operations in the approximation search **/ + int approx_nn_ops_num_; + + /** Number of leaders in the approximation search **/ + int approx_leaders_num_; + + /** Number of leaders in the approximation search **/ + int approx_followers_num_; + + /** Maximum number of points in each leaf node (of the searching KDTree). **/ + int max_leaf_size_; + + /** Whether to save operations number, leader and follower info in approx search. **/ + bool save_approx_data_; + + }; + + /** \brief @b CorrespondenceEstimation represents the base class for + * determining correspondences between target and query point + * sets/features. + * + * Code example: + * + * \code + * pcl::PointCloud::Ptr source, target; + * // ... read or fill in source and target + * pcl::CorrespondenceEstimation est; + * est.setInputSource (source); + * est.setInputTarget (target); + * + * pcl::Correspondences all_correspondences; + * // Determine all reciprocal correspondences + * est.determineReciprocalCorrespondences (all_correspondences); + * \endcode + * + * \author Radu B. Rusu, Michael Dixon, Dirk Holz + * \ingroup registration + */ + template + class CorrespondenceEstimation : public CorrespondenceEstimationBase + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using CorrespondenceEstimationBase::point_representation_; + using CorrespondenceEstimationBase::input_transformed_; + using CorrespondenceEstimationBase::tree_; + using CorrespondenceEstimationBase::tree_reciprocal_; + using CorrespondenceEstimationBase::target_; + using CorrespondenceEstimationBase::corr_name_; + using CorrespondenceEstimationBase::target_indices_; + using CorrespondenceEstimationBase::getClassName; + using CorrespondenceEstimationBase::initCompute; + using CorrespondenceEstimationBase::initComputeReciprocal; + using CorrespondenceEstimationBase::input_; + using CorrespondenceEstimationBase::indices_; + using CorrespondenceEstimationBase::input_fields_; + + using CorrespondenceEstimationBase::treeH_source_ ; + using CorrespondenceEstimationBase::treeH_target_ ; + + using CorrespondenceEstimationBase::points_target_; + using CorrespondenceEstimationBase::points_target_ptr_; // target + using CorrespondenceEstimationBase::index_target_; + using CorrespondenceEstimationBase::index_target_ptr_; + using CorrespondenceEstimationBase::points_src_; // source + using CorrespondenceEstimationBase::points_src_ptr_; // source + using CorrespondenceEstimationBase::index_src_; + using CorrespondenceEstimationBase::index_src_ptr_; + + using CorrespondenceEstimationBase::buildHKdTree_target; + using CorrespondenceEstimationBase::buildHKdTree_source; + + using CorrespondenceEstimationBase::setMaxLeafSize; + using CorrespondenceEstimationBase::max_leaf_size_; + + using CorrespondenceEstimationBase::use_customized_tree_; + using CorrespondenceEstimationBase::approx_nn_ops_num_; + using CorrespondenceEstimationBase::approx_leaders_num_; + using CorrespondenceEstimationBase::approx_followers_num_; + using CorrespondenceEstimationBase::save_approx_data_; + + + using PCLBase::deinitCompute; + + typedef pcl::search::KdTree KdTree; + typedef typename pcl::search::KdTree::Ptr KdTreePtr; + + typedef pcl::PointCloud PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef pcl::PointCloud PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + typedef typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr; + + /** \brief Empty constructor. */ + CorrespondenceEstimation () + { + corr_name_ = "CorrespondenceEstimation"; + } + + /** \brief Empty destructor */ + virtual ~CorrespondenceEstimation () + { + delete treeH_target_; + delete treeH_source_; + } + + /** \brief Determine the correspondences between input and target cloud. + * \param[out] correspondences the found correspondences (index of query point, index of target point, distance) + * \param[in] max_distance maximum allowed distance between correspondences + */ + virtual void + determineCorrespondences (pcl::Correspondences &correspondences, + double max_distance = std::numeric_limits::max ()); + + /** \brief Determine the reciprocal correspondences between input and target cloud. + * A correspondence is considered reciprocal if both Src_i has Tgt_i as a + * correspondence, and Tgt_i has Src_i as one. + * + * \param[out] correspondences the found correspondences (index of query and target point, distance) + * \param[in] max_distance maximum allowed distance between correspondences + */ + virtual void + determineReciprocalCorrespondences (pcl::Correspondences &correspondences, + double max_distance = std::numeric_limits::max ()); + + + /** \brief Clone and cast to CorrespondenceEstimationBase */ + virtual boost::shared_ptr< CorrespondenceEstimationBase > + clone () const + { + Ptr copy (new CorrespondenceEstimation (*this)); + return (copy); + } + + }; + } +} + +#include + +#endif /* PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_H_ */ diff --git a/pcl-1.7/pcl/registration/correspondence_estimation_backprojection.h b/pcl-1.7/pcl/registration/correspondence_estimation_backprojection.h new file mode 100644 index 0000000..0a96c58 --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_estimation_backprojection.h @@ -0,0 +1,228 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_BACK_PROJECTION_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_BACK_PROJECTION_H_ + +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief @b CorrespondenceEstimationBackprojection computes + * correspondences as points in the target cloud which have minimum + * \author Suat Gedikli + * \ingroup registration + */ + template + class CorrespondenceEstimationBackProjection : public CorrespondenceEstimationBase + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using CorrespondenceEstimationBase::initCompute; + using CorrespondenceEstimationBase::initComputeReciprocal; + using CorrespondenceEstimationBase::input_transformed_; + using PCLBase::deinitCompute; + using PCLBase::input_; + using PCLBase::indices_; + using CorrespondenceEstimationBase::getClassName; + using CorrespondenceEstimationBase::point_representation_; + using CorrespondenceEstimationBase::target_indices_; + + typedef typename pcl::search::KdTree KdTree; + typedef typename pcl::search::KdTree::Ptr KdTreePtr; + + typedef pcl::PointCloud PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef pcl::PointCloud PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + typedef pcl::PointCloud PointCloudNormals; + typedef typename PointCloudNormals::Ptr NormalsPtr; + typedef typename PointCloudNormals::ConstPtr NormalsConstPtr; + + /** \brief Empty constructor. + * + * \note + * Sets the number of neighbors to be considered in the target point cloud (k_) to 10. + */ + CorrespondenceEstimationBackProjection () + : source_normals_ () + , source_normals_transformed_ () + , target_normals_ () + , k_ (10) + { + corr_name_ = "CorrespondenceEstimationBackProjection"; + } + + /** \brief Empty destructor */ + virtual ~CorrespondenceEstimationBackProjection () {} + + /** \brief Set the normals computed on the source point cloud + * \param[in] normals the normals computed for the source cloud + */ + inline void + setSourceNormals (const NormalsConstPtr &normals) { source_normals_ = normals; } + + /** \brief Get the normals of the source point cloud + */ + inline NormalsConstPtr + getSourceNormals () const { return (source_normals_); } + + /** \brief Set the normals computed on the target point cloud + * \param[in] normals the normals computed for the target cloud + */ + inline void + setTargetNormals (const NormalsConstPtr &normals) { target_normals_ = normals; } + + /** \brief Get the normals of the target point cloud + */ + inline NormalsConstPtr + getTargetNormals () const { return (target_normals_); } + + + /** \brief See if this rejector requires source normals */ + bool + requiresSourceNormals () const + { return (true); } + + /** \brief Blob method for setting the source normals */ + void + setSourceNormals (pcl::PCLPointCloud2::ConstPtr cloud2) + { + NormalsPtr cloud (new PointCloudNormals); + fromPCLPointCloud2 (*cloud2, *cloud); + setSourceNormals (cloud); + } + + /** \brief See if this rejector requires target normals*/ + bool + requiresTargetNormals () const + { return (true); } + + /** \brief Method for setting the target normals */ + void + setTargetNormals (pcl::PCLPointCloud2::ConstPtr cloud2) + { + NormalsPtr cloud (new PointCloudNormals); + fromPCLPointCloud2 (*cloud2, *cloud); + setTargetNormals (cloud); + } + + /** \brief Determine the correspondences between input and target cloud. + * \param[out] correspondences the found correspondences (index of query point, index of target point, distance) + * \param[in] max_distance maximum distance between the normal on the source point cloud and the corresponding point in the target + * point cloud + */ + void + determineCorrespondences (pcl::Correspondences &correspondences, + double max_distance = std::numeric_limits::max ()); + + /** \brief Determine the reciprocal correspondences between input and target cloud. + * A correspondence is considered reciprocal if both Src_i has Tgt_i as a + * correspondence, and Tgt_i has Src_i as one. + * + * \param[out] correspondences the found correspondences (index of query and target point, distance) + * \param[in] max_distance maximum allowed distance between correspondences + */ + virtual void + determineReciprocalCorrespondences (pcl::Correspondences &correspondences, + double max_distance = std::numeric_limits::max ()); + + /** \brief Set the number of nearest neighbours to be considered in the target + * point cloud. By default, we use k = 10 nearest neighbors. + * + * \param[in] k the number of nearest neighbours to be considered + */ + inline void + setKSearch (unsigned int k) { k_ = k; } + + /** \brief Get the number of nearest neighbours considered in the target point + * cloud for computing correspondences. By default we use k = 10 nearest + * neighbors. + */ + inline unsigned int + getKSearch () const { return (k_); } + + /** \brief Clone and cast to CorrespondenceEstimationBase */ + virtual boost::shared_ptr< CorrespondenceEstimationBase > + clone () const + { + Ptr copy (new CorrespondenceEstimationBackProjection (*this)); + return (copy); + } + + protected: + + using CorrespondenceEstimationBase::corr_name_; + using CorrespondenceEstimationBase::tree_; + using CorrespondenceEstimationBase::tree_reciprocal_; + using CorrespondenceEstimationBase::target_; + + /** \brief Internal computation initalization. */ + bool + initCompute (); + + private: + + /** \brief The normals computed at each point in the source cloud */ + NormalsConstPtr source_normals_; + + /** \brief The normals computed at each point in the source cloud */ + NormalsPtr source_normals_transformed_; + + /** \brief The normals computed at each point in the target cloud */ + NormalsConstPtr target_normals_; + + /** \brief The number of neighbours to be considered in the target point cloud */ + unsigned int k_; + }; + } +} + +#include + +#endif /* PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_BACK_PROJECTION_H_ */ diff --git a/pcl-1.7/pcl/registration/correspondence_estimation_normal_shooting.h b/pcl-1.7/pcl/registration/correspondence_estimation_normal_shooting.h new file mode 100644 index 0000000..4c5e0ab --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_estimation_normal_shooting.h @@ -0,0 +1,221 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_NORMAL_SHOOTING_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_NORMAL_SHOOTING_H_ + +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief @b CorrespondenceEstimationNormalShooting computes + * correspondences as points in the target cloud which have minimum + * distance to normals computed on the input cloud + * + * Code example: + * + * \code + * pcl::PointCloud::Ptr source, target; + * // ... read or fill in source and target + * pcl::CorrespondenceEstimationNormalShooting est; + * est.setInputSource (source); + * est.setSourceNormals (source); + * + * est.setInputTarget (target); + * + * // Test the first 10 correspondences for each point in source, and return the best + * est.setKSearch (10); + * + * pcl::Correspondences all_correspondences; + * // Determine all correspondences + * est.determineCorrespondences (all_correspondences); + * \endcode + * + * \author Aravindhan K. Krishnan, Radu B. Rusu + * \ingroup registration + */ + template + class CorrespondenceEstimationNormalShooting : public CorrespondenceEstimationBase + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using CorrespondenceEstimationBase::initCompute; + using CorrespondenceEstimationBase::initComputeReciprocal; + using CorrespondenceEstimationBase::input_transformed_; + using PCLBase::deinitCompute; + using PCLBase::input_; + using PCLBase::indices_; + using CorrespondenceEstimationBase::getClassName; + using CorrespondenceEstimationBase::point_representation_; + using CorrespondenceEstimationBase::target_indices_; + + typedef typename pcl::search::KdTree KdTree; + typedef typename pcl::search::KdTree::Ptr KdTreePtr; + + typedef pcl::PointCloud PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef pcl::PointCloud PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + typedef pcl::PointCloud PointCloudNormals; + typedef typename PointCloudNormals::Ptr NormalsPtr; + typedef typename PointCloudNormals::ConstPtr NormalsConstPtr; + + /** \brief Empty constructor. + * + * \note + * Sets the number of neighbors to be considered in the target point cloud (k_) to 10. + */ + CorrespondenceEstimationNormalShooting () + : source_normals_ () + , source_normals_transformed_ () + , k_ (10) + { + corr_name_ = "CorrespondenceEstimationNormalShooting"; + } + + /** \brief Empty destructor */ + virtual ~CorrespondenceEstimationNormalShooting () {} + + /** \brief Set the normals computed on the source point cloud + * \param[in] normals the normals computed for the source cloud + */ + inline void + setSourceNormals (const NormalsConstPtr &normals) { source_normals_ = normals; } + + /** \brief Get the normals of the source point cloud + */ + inline NormalsConstPtr + getSourceNormals () const { return (source_normals_); } + + + /** \brief See if this rejector requires source normals */ + bool + requiresSourceNormals () const + { return (true); } + + /** \brief Blob method for setting the source normals */ + void + setSourceNormals (pcl::PCLPointCloud2::ConstPtr cloud2) + { + NormalsPtr cloud (new PointCloudNormals); + fromPCLPointCloud2 (*cloud2, *cloud); + setSourceNormals (cloud); + } + + /** \brief Determine the correspondences between input and target cloud. + * \param[out] correspondences the found correspondences (index of query point, index of target point, distance) + * \param[in] max_distance maximum distance between the normal on the source point cloud and the corresponding point in the target + * point cloud + */ + void + determineCorrespondences (pcl::Correspondences &correspondences, + double max_distance = std::numeric_limits::max ()); + + /** \brief Determine the reciprocal correspondences between input and target cloud. + * A correspondence is considered reciprocal if both Src_i has Tgt_i as a + * correspondence, and Tgt_i has Src_i as one. + * + * \param[out] correspondences the found correspondences (index of query and target point, distance) + * \param[in] max_distance maximum allowed distance between correspondences + */ + virtual void + determineReciprocalCorrespondences (pcl::Correspondences &correspondences, + double max_distance = std::numeric_limits::max ()); + + /** \brief Set the number of nearest neighbours to be considered in the target + * point cloud. By default, we use k = 10 nearest neighbors. + * + * \param[in] k the number of nearest neighbours to be considered + */ + inline void + setKSearch (unsigned int k) { k_ = k; } + + /** \brief Get the number of nearest neighbours considered in the target point + * cloud for computing correspondences. By default we use k = 10 nearest + * neighbors. + */ + inline unsigned int + getKSearch () const { return (k_); } + + /** \brief Clone and cast to CorrespondenceEstimationBase */ + virtual boost::shared_ptr< CorrespondenceEstimationBase > + clone () const + { + Ptr copy (new CorrespondenceEstimationNormalShooting (*this)); + return (copy); + } + + protected: + + using CorrespondenceEstimationBase::corr_name_; + using CorrespondenceEstimationBase::tree_; + using CorrespondenceEstimationBase::tree_reciprocal_; + using CorrespondenceEstimationBase::target_; + + /** \brief Internal computation initalization. */ + bool + initCompute (); + + private: + + /** \brief The normals computed at each point in the source cloud */ + NormalsConstPtr source_normals_; + + /** \brief The normals computed at each point in the source cloud */ + NormalsPtr source_normals_transformed_; + + /** \brief The number of neighbours to be considered in the target point cloud */ + unsigned int k_; + }; + } +} + +#include + +#endif /* PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_NORMAL_SHOOTING_H_ */ diff --git a/pcl-1.7/pcl/registration/correspondence_estimation_organized_projection.h b/pcl-1.7/pcl/registration/correspondence_estimation_organized_projection.h new file mode 100644 index 0000000..a6ba9fd --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_estimation_organized_projection.h @@ -0,0 +1,210 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + + +#ifndef PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_ORGANIZED_PROJECTION_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_ORGANIZED_PROJECTION_H_ + +#include + +namespace pcl +{ + namespace registration + { + /** \brief CorrespondenceEstimationOrganizedProjection computes correspondences by projecting the source point cloud + * onto the target point cloud using the camera intrinsic and extrinsic parameters. The correspondences can be trimmed + * by a depth threshold and by a distance threshold. + * It is not as precise as a nearest neighbor search, but it is much faster, as it avoids the usage of any additional + * structures (i.e., kd-trees). + * \note The target point cloud must be organized (no restrictions on the source) and the target point cloud must be + * given in the camera coordinate frame. Any other transformation is specified by the src_to_tgt_transformation_ + * variable. + * \author Alex Ichim + */ + template + class CorrespondenceEstimationOrganizedProjection : public CorrespondenceEstimationBase + { + public: + using CorrespondenceEstimationBase::initCompute; + using CorrespondenceEstimationBase::input_transformed_; + using PCLBase::deinitCompute; + using PCLBase::input_; + using PCLBase::indices_; + using CorrespondenceEstimationBase::getClassName; + using CorrespondenceEstimationBase::point_representation_; + using CorrespondenceEstimationBase::target_cloud_updated_; + + typedef pcl::PointCloud PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef pcl::PointCloud PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + typedef boost::shared_ptr< CorrespondenceEstimationOrganizedProjection > Ptr; + typedef boost::shared_ptr< const CorrespondenceEstimationOrganizedProjection > ConstPtr; + + + + /** \brief Empty constructor that sets all the intrinsic calibration to the default Kinect values. */ + CorrespondenceEstimationOrganizedProjection () + : fx_ (525.f) + , fy_ (525.f) + , cx_ (319.5f) + , cy_ (239.5f) + , src_to_tgt_transformation_ (Eigen::Matrix4f::Identity ()) + , depth_threshold_ (std::numeric_limits::max ()) + , projection_matrix_ (Eigen::Matrix3f::Identity ()) + { } + + + /** \brief Sets the focal length parameters of the target camera. + * \param[in] fx the focal length in pixels along the x-axis of the image + * \param[in] fy the focal length in pixels along the y-axis of the image + */ + inline void + setFocalLengths (const float fx, const float fy) + { fx_ = fx; fy_ = fy; } + + /** \brief Reads back the focal length parameters of the target camera. + * \param[out] fx the focal length in pixels along the x-axis of the image + * \param[out] fy the focal length in pixels along the y-axis of the image + */ + inline void + getFocalLengths (float &fx, float &fy) const + { fx = fx_; fy = fy_; } + + + /** \brief Sets the camera center parameters of the target camera. + * \param[in] cx the x-coordinate of the camera center + * \param[in] cy the y-coordinate of the camera center + */ + inline void + setCameraCenters (const float cx, const float cy) + { cx_ = cx; cy_ = cy; } + + /** \brief Reads back the camera center parameters of the target camera. + * \param[out] cx the x-coordinate of the camera center + * \param[out] cy the y-coordinate of the camera center + */ + inline void + getCameraCenters (float &cx, float &cy) const + { cx = cx_; cy = cy_; } + + /** \brief Sets the transformation from the source point cloud to the target point cloud. + * \note The target point cloud must be in its local camera coordinates, so use this transformation to correct + * for that. + * \param[in] src_to_tgt_transformation the transformation + */ + inline void + setSourceTransformation (const Eigen::Matrix4f &src_to_tgt_transformation) + { src_to_tgt_transformation_ = src_to_tgt_transformation; } + + /** \brief Reads back the transformation from the source point cloud to the target point cloud. + * \note The target point cloud must be in its local camera coordinates, so use this transformation to correct + * for that. + * \return the transformation + */ + inline Eigen::Matrix4f + getSourceTransformation () const + { return (src_to_tgt_transformation_); } + + /** \brief Sets the depth threshold; after projecting the source points in the image space of the target camera, + * this threshold is applied on the depths of corresponding dexels to eliminate the ones that are too far from + * each other. + * \param[in] depth_threshold the depth threshold + */ + inline void + setDepthThreshold (const float depth_threshold) + { depth_threshold_ = depth_threshold; } + + /** \brief Reads back the depth threshold; after projecting the source points in the image space of the target + * camera, this threshold is applied on the depths of corresponding dexels to eliminate the ones that are too + * far from each other. + * \return the depth threshold + */ + inline float + getDepthThreshold () const + { return (depth_threshold_); } + + /** \brief Computes the correspondences, applying a maximum Euclidean distance threshold. + * \param correspondences + * \param[in] max_distance Euclidean distance threshold above which correspondences will be rejected + */ + void + determineCorrespondences (Correspondences &correspondences, double max_distance); + + /** \brief Computes the correspondences, applying a maximum Euclidean distance threshold. + * \param correspondences + * \param[in] max_distance Euclidean distance threshold above which correspondences will be rejected + */ + void + determineReciprocalCorrespondences (Correspondences &correspondences, double max_distance); + + /** \brief Clone and cast to CorrespondenceEstimationBase */ + virtual boost::shared_ptr< CorrespondenceEstimationBase > + clone () const + { + Ptr copy (new CorrespondenceEstimationOrganizedProjection (*this)); + return (copy); + } + + protected: + using CorrespondenceEstimationBase::target_; + + bool + initCompute (); + + float fx_, fy_; + float cx_, cy_; + Eigen::Matrix4f src_to_tgt_transformation_; + float depth_threshold_; + + Eigen::Matrix3f projection_matrix_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } +} + +#include + +#endif /* PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_ORGANIZED_PROJECTION_H_ */ diff --git a/pcl-1.7/pcl/registration/correspondence_rejection.h b/pcl-1.7/pcl/registration/correspondence_rejection.h new file mode 100644 index 0000000..36254e2 --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_rejection.h @@ -0,0 +1,423 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_H_ + +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace registration + { + /** @b CorrespondenceRejector represents the base class for correspondence rejection methods + * \author Dirk Holz + * \ingroup registration + */ + class CorrespondenceRejector + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Empty constructor. */ + CorrespondenceRejector () + : rejection_name_ () + , input_correspondences_ () + {} + + /** \brief Empty destructor. */ + virtual ~CorrespondenceRejector () {} + + /** \brief Provide a pointer to the vector of the input correspondences. + * \param[in] correspondences the const boost shared pointer to a correspondence vector + */ + virtual inline void + setInputCorrespondences (const CorrespondencesConstPtr &correspondences) + { + input_correspondences_ = correspondences; + }; + + /** \brief Get a pointer to the vector of the input correspondences. + * \return correspondences the const boost shared pointer to a correspondence vector + */ + inline CorrespondencesConstPtr + getInputCorrespondences () { return input_correspondences_; }; + + /** \brief Run correspondence rejection + * \param[out] correspondences Vector of correspondences that have not been rejected. + */ + inline void + getCorrespondences (pcl::Correspondences &correspondences) + { + if (!input_correspondences_ || (input_correspondences_->empty ())) + return; + + applyRejection (correspondences); + } + + /** \brief Get a list of valid correspondences after rejection from the original set of correspondences. + * Pure virtual. Compared to \a getCorrespondences this function is + * stateless, i.e., input correspondences do not need to be provided beforehand, + * but are directly provided in the function call. + * \param[in] original_correspondences the set of initial correspondences given + * \param[out] remaining_correspondences the resultant filtered set of remaining correspondences + */ + virtual inline void + getRemainingCorrespondences (const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences) = 0; + + /** \brief Determine the indices of query points of + * correspondences that have been rejected, i.e., the difference + * between the input correspondences (set via \a setInputCorrespondences) + * and the given correspondence vector. + * \param[in] correspondences Vector of correspondences after rejection + * \param[out] indices Vector of query point indices of those correspondences + * that have been rejected. + */ + inline void + getRejectedQueryIndices (const pcl::Correspondences &correspondences, + std::vector& indices) + { + if (!input_correspondences_ || input_correspondences_->empty ()) + { + PCL_WARN ("[pcl::registration::%s::getRejectedQueryIndices] Input correspondences not set (lookup of rejected correspondences _not_ possible).\n", getClassName ().c_str ()); + return; + } + + pcl::getRejectedQueryIndices(*input_correspondences_, correspondences, indices); + } + + /** \brief Get a string representation of the name of this class. */ + inline const std::string& + getClassName () const { return (rejection_name_); } + + + /** \brief See if this rejector requires source points */ + virtual bool + requiresSourcePoints () const + { return (false); } + + /** \brief Abstract method for setting the source cloud */ + virtual void + setSourcePoints (pcl::PCLPointCloud2::ConstPtr /*cloud2*/) + { + PCL_WARN ("[pcl::registration::%s::setSourcePoints] This class does not require an input source cloud", getClassName ().c_str ()); + } + + /** \brief See if this rejector requires source normals */ + virtual bool + requiresSourceNormals () const + { return (false); } + + /** \brief Abstract method for setting the source normals */ + virtual void + setSourceNormals (pcl::PCLPointCloud2::ConstPtr /*cloud2*/) + { + PCL_WARN ("[pcl::registration::%s::setSourceNormals] This class does not require input source normals", getClassName ().c_str ()); + } + /** \brief See if this rejector requires a target cloud */ + virtual bool + requiresTargetPoints () const + { return (false); } + + /** \brief Abstract method for setting the target cloud */ + virtual void + setTargetPoints (pcl::PCLPointCloud2::ConstPtr /*cloud2*/) + { + PCL_WARN ("[pcl::registration::%s::setTargetPoints] This class does not require an input target cloud", getClassName ().c_str ()); + } + + /** \brief See if this rejector requires target normals */ + virtual bool + requiresTargetNormals () const + { return (false); } + + /** \brief Abstract method for setting the target normals */ + virtual void + setTargetNormals (pcl::PCLPointCloud2::ConstPtr /*cloud2*/) + { + PCL_WARN ("[pcl::registration::%s::setTargetNormals] This class does not require input target normals", getClassName ().c_str ()); + } + + protected: + + /** \brief The name of the rejection method. */ + std::string rejection_name_; + + /** \brief The input correspondences. */ + CorrespondencesConstPtr input_correspondences_; + + /** \brief Abstract rejection method. */ + virtual void + applyRejection (Correspondences &correspondences) = 0; + }; + + /** @b DataContainerInterface provides a generic interface for computing correspondence scores between correspondent + * points in the input and target clouds + * \ingroup registration + */ + class DataContainerInterface + { + public: + virtual ~DataContainerInterface () {} + virtual double getCorrespondenceScore (int index) = 0; + virtual double getCorrespondenceScore (const pcl::Correspondence &) = 0; + }; + + /** @b DataContainer is a container for the input and target point clouds and implements the interface + * to compute correspondence scores between correspondent points in the input and target clouds + * \ingroup registration + */ + template + class DataContainer : public DataContainerInterface + { + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename pcl::search::KdTree::Ptr KdTreePtr; + + typedef pcl::PointCloud Normals; + typedef typename Normals::Ptr NormalsPtr; + typedef typename Normals::ConstPtr NormalsConstPtr; + + public: + + /** \brief Empty constructor. */ + DataContainer (bool needs_normals = false) + : input_ () + , input_transformed_ () + , target_ () + , input_normals_ () + , input_normals_transformed_ () + , target_normals_ () + , tree_ (new pcl::search::KdTree) + , class_name_ ("DataContainer") + , needs_normals_ (needs_normals) + , target_cloud_updated_ (true) + , force_no_recompute_ (false) + { + } + + /** \brief Empty destructor */ + virtual ~DataContainer () {} + + /** \brief Provide a source point cloud dataset (must contain XYZ + * data!), used to compute the correspondence distance. + * \param[in] cloud a cloud containing XYZ data + */ + PCL_DEPRECATED ("[pcl::registration::DataContainer::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.") + void + setInputCloud (const PointCloudConstPtr &cloud); + + /** \brief Get a pointer to the input point cloud dataset target. */ + PCL_DEPRECATED ("[pcl::registration::DataContainer::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.") + PointCloudConstPtr const + getInputCloud (); + + /** \brief Provide a source point cloud dataset (must contain XYZ + * data!), used to compute the correspondence distance. + * \param[in] cloud a cloud containing XYZ data + */ + inline void + setInputSource (const PointCloudConstPtr &cloud) + { + input_ = cloud; + } + + /** \brief Get a pointer to the input point cloud dataset target. */ + inline PointCloudConstPtr const + getInputSource () { return (input_); } + + /** \brief Provide a target point cloud dataset (must contain XYZ + * data!), used to compute the correspondence distance. + * \param[in] target a cloud containing XYZ data + */ + inline void + setInputTarget (const PointCloudConstPtr &target) + { + target_ = target; + target_cloud_updated_ = true; + } + + /** \brief Get a pointer to the input point cloud dataset target. */ + inline PointCloudConstPtr const + getInputTarget () { return (target_); } + + /** \brief Provide a pointer to the search object used to find correspondences in + * the target cloud. + * \param[in] tree a pointer to the spatial search object. + * \param[in] force_no_recompute If set to true, this tree will NEVER be + * recomputed, regardless of calls to setInputTarget. Only use if you are + * confident that the tree will be set correctly. + */ + inline void + setSearchMethodTarget (const KdTreePtr &tree, + bool force_no_recompute = false) + { + tree_ = tree; + if (force_no_recompute) + { + force_no_recompute_ = true; + } + target_cloud_updated_ = true; + } + + /** \brief Set the normals computed on the input point cloud + * \param[in] normals the normals computed for the input cloud + */ + inline void + setInputNormals (const NormalsConstPtr &normals) { input_normals_ = normals; } + + /** \brief Get the normals computed on the input point cloud */ + inline NormalsConstPtr + getInputNormals () { return (input_normals_); } + + /** \brief Set the normals computed on the target point cloud + * \param[in] normals the normals computed for the input cloud + */ + inline void + setTargetNormals (const NormalsConstPtr &normals) { target_normals_ = normals; } + + /** \brief Get the normals computed on the target point cloud */ + inline NormalsConstPtr + getTargetNormals () { return (target_normals_); } + + /** \brief Get the correspondence score for a point in the input cloud + * \param[in] index index of the point in the input cloud + */ + inline double + getCorrespondenceScore (int index) + { + if ( target_cloud_updated_ && !force_no_recompute_ ) + { + tree_->setInputCloud (target_); + } + std::vector indices (1); + std::vector distances (1); + if (tree_->nearestKSearch (input_->points[index], 1, indices, distances)) + return (distances[0]); + else + return (std::numeric_limits::max ()); + } + + /** \brief Get the correspondence score for a given pair of correspondent points + * \param[in] corr Correspondent points + */ + inline double + getCorrespondenceScore (const pcl::Correspondence &corr) + { + // Get the source and the target feature from the list + const PointT &src = input_->points[corr.index_query]; + const PointT &tgt = target_->points[corr.index_match]; + + return ((src.getVector4fMap () - tgt.getVector4fMap ()).squaredNorm ()); + } + + /** \brief Get the correspondence score for a given pair of correspondent points based on + * the angle betweeen the normals. The normmals for the in put and target clouds must be + * set before using this function + * \param[in] corr Correspondent points + */ + inline double + getCorrespondenceScoreFromNormals (const pcl::Correspondence &corr) + { + //assert ( (input_normals_->points.size () != 0) && (target_normals_->points.size () != 0) && "Normals are not set for the input and target point clouds"); + assert (input_normals_ && target_normals_ && "Normals are not set for the input and target point clouds"); + const NormalT &src = input_normals_->points[corr.index_query]; + const NormalT &tgt = target_normals_->points[corr.index_match]; + return (double ((src.normal[0] * tgt.normal[0]) + (src.normal[1] * tgt.normal[1]) + (src.normal[2] * tgt.normal[2]))); + } + + private: + /** \brief The input point cloud dataset */ + PointCloudConstPtr input_; + + /** \brief The input transformed point cloud dataset */ + PointCloudPtr input_transformed_; + + /** \brief The target point cloud datase. */ + PointCloudConstPtr target_; + + /** \brief Normals to the input point cloud */ + NormalsConstPtr input_normals_; + + /** \brief Normals to the input point cloud */ + NormalsPtr input_normals_transformed_; + + /** \brief Normals to the target point cloud */ + NormalsConstPtr target_normals_; + + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + + /** \brief The name of the rejection method. */ + std::string class_name_; + + /** \brief Should the current data container use normals? */ + bool needs_normals_; + + /** \brief Variable that stores whether we have a new target cloud, meaning we need to pre-process it again. + * This way, we avoid rebuilding the kd-tree */ + bool target_cloud_updated_; + + /** \brief A flag which, if set, means the tree operating on the target cloud + * will never be recomputed*/ + bool force_no_recompute_; + + + + /** \brief Get a string representation of the name of this class. */ + inline const std::string& + getClassName () const { return (class_name_); } + }; + } +} + +#include + +#endif /* PCL_REGISTRATION_CORRESPONDENCE_REJECTION_H_ */ + diff --git a/pcl-1.7/pcl/registration/correspondence_rejection_distance.h b/pcl-1.7/pcl/registration/correspondence_rejection_distance.h new file mode 100644 index 0000000..cbbe5f4 --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_rejection_distance.h @@ -0,0 +1,210 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_DISTANCE_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_DISTANCE_H_ + +#include + +namespace pcl +{ + namespace registration + { + /** + * @b CorrespondenceRejectorDistance implements a simple correspondence + * rejection method based on thresholding the distances between the + * correspondences. + * + * \note If \ref setInputCloud and \ref setInputTarget are given, then the + * distances between correspondences will be estimated using the given XYZ + * data, and not read from the set of input correspondences. + * + * \author Dirk Holz, Radu B. Rusu + * \ingroup registration + */ + class PCL_EXPORTS CorrespondenceRejectorDistance: public CorrespondenceRejector + { + using CorrespondenceRejector::input_correspondences_; + using CorrespondenceRejector::rejection_name_; + using CorrespondenceRejector::getClassName; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Empty constructor. */ + CorrespondenceRejectorDistance () : max_distance_(std::numeric_limits::max ()), + data_container_ () + { + rejection_name_ = "CorrespondenceRejectorDistance"; + } + + /** \brief Empty destructor */ + virtual ~CorrespondenceRejectorDistance () {} + + /** \brief Get a list of valid correspondences after rejection from the original set of correspondences. + * \param[in] original_correspondences the set of initial correspondences given + * \param[out] remaining_correspondences the resultant filtered set of remaining correspondences + */ + void + getRemainingCorrespondences (const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences); + + /** \brief Set the maximum distance used for thresholding in correspondence rejection. + * \param[in] distance Distance to be used as maximum distance between correspondences. + * Correspondences with larger distances are rejected. + * \note Internally, the distance will be stored squared. + */ + virtual inline void + setMaximumDistance (float distance) { max_distance_ = distance * distance; }; + + /** \brief Get the maximum distance used for thresholding in correspondence rejection. */ + inline float + getMaximumDistance () { return std::sqrt (max_distance_); }; + + /** \brief Provide a source point cloud dataset (must contain XYZ + * data!), used to compute the correspondence distance. + * \param[in] cloud a cloud containing XYZ data + */ + template inline void + setInputCloud (const typename pcl::PointCloud::ConstPtr &cloud) + { + PCL_WARN ("[pcl::registration::%s::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.\n", getClassName ().c_str ()); + if (!data_container_) + data_container_.reset (new DataContainer); + boost::static_pointer_cast > (data_container_)->setInputSource (cloud); + } + + /** \brief Provide a source point cloud dataset (must contain XYZ + * data!), used to compute the correspondence distance. + * \param[in] cloud a cloud containing XYZ data + */ + template inline void + setInputSource (const typename pcl::PointCloud::ConstPtr &cloud) + { + if (!data_container_) + data_container_.reset (new DataContainer); + boost::static_pointer_cast > (data_container_)->setInputSource (cloud); + } + + /** \brief Provide a target point cloud dataset (must contain XYZ + * data!), used to compute the correspondence distance. + * \param[in] target a cloud containing XYZ data + */ + template inline void + setInputTarget (const typename pcl::PointCloud::ConstPtr &target) + { + if (!data_container_) + data_container_.reset (new DataContainer); + boost::static_pointer_cast > (data_container_)->setInputTarget (target); + } + + + /** \brief See if this rejector requires source points */ + bool + requiresSourcePoints () const + { return (true); } + + /** \brief Blob method for setting the source cloud */ + void + setSourcePoints (pcl::PCLPointCloud2::ConstPtr cloud2) + { + PointCloud::Ptr cloud (new PointCloud); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputSource (cloud); + } + + /** \brief See if this rejector requires a target cloud */ + bool + requiresTargetPoints () const + { return (true); } + + /** \brief Method for setting the target cloud */ + void + setTargetPoints (pcl::PCLPointCloud2::ConstPtr cloud2) + { + PointCloud::Ptr cloud (new PointCloud); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputTarget (cloud); + } + + /** \brief Provide a pointer to the search object used to find correspondences in + * the target cloud. + * \param[in] tree a pointer to the spatial search object. + * \param[in] force_no_recompute If set to true, this tree will NEVER be + * recomputed, regardless of calls to setInputTarget. Only use if you are + * confident that the tree will be set correctly. + */ + template inline void + setSearchMethodTarget (const boost::shared_ptr > &tree, + bool force_no_recompute = false) + { + boost::static_pointer_cast< DataContainer > + (data_container_)->setSearchMethodTarget (tree, force_no_recompute ); + } + + + protected: + + /** \brief Apply the rejection algorithm. + * \param[out] correspondences the set of resultant correspondences. + */ + inline void + applyRejection (pcl::Correspondences &correspondences) + { + getRemainingCorrespondences (*input_correspondences_, correspondences); + } + + /** \brief The maximum distance threshold between two correspondent points in source <-> target. If the + * distance is larger than this threshold, the points will not be ignored in the alignment process. + */ + float max_distance_; + + typedef boost::shared_ptr DataContainerPtr; + + /** \brief A pointer to the DataContainer object containing the input and target point clouds */ + DataContainerPtr data_container_; + }; + + } +} + +#include + +#endif /* PCL_REGISTRATION_CORRESPONDENCE_REJECTION_DISTANCE_H_ */ diff --git a/pcl-1.7/pcl/registration/correspondence_rejection_features.h b/pcl-1.7/pcl/registration/correspondence_rejection_features.h new file mode 100644 index 0000000..e69a6db --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_rejection_features.h @@ -0,0 +1,303 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_FEATURES_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_FEATURES_H_ + +#include +#include +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief CorrespondenceRejectorFeatures implements a correspondence rejection method based on a set of feature + * descriptors. Given an input feature space, the method checks if each feature in the source cloud has a + * correspondence in the target cloud, either by checking the first K (given) point correspondences, or + * by defining a tolerance threshold via a radius in feature space. + * \todo explain this better. + * \author Radu B. Rusu + * \ingroup registration + */ + class PCL_EXPORTS CorrespondenceRejectorFeatures: public CorrespondenceRejector + { + using CorrespondenceRejector::input_correspondences_; + using CorrespondenceRejector::rejection_name_; + using CorrespondenceRejector::getClassName; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Empty constructor. */ + CorrespondenceRejectorFeatures () : max_distance_ (std::numeric_limits::max ()), features_map_ () + { + rejection_name_ = "CorrespondenceRejectorFeatures"; + } + + /** \brief Empty destructor. */ + virtual ~CorrespondenceRejectorFeatures () {} + + /** \brief Get a list of valid correspondences after rejection from the original set of correspondences + * \param[in] original_correspondences the set of initial correspondences given + * \param[out] remaining_correspondences the resultant filtered set of remaining correspondences + */ + void + getRemainingCorrespondences (const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences); + + /** \brief Provide a pointer to a cloud of feature descriptors associated with the source point cloud + * \param[in] source_feature a cloud of feature descriptors associated with the source point cloud + * \param[in] key a string that uniquely identifies the feature + */ + template inline void + setSourceFeature (const typename pcl::PointCloud::ConstPtr &source_feature, + const std::string &key); + + /** \brief Get a pointer to the source cloud's feature descriptors, specified by the given \a key + * \param[in] key a string that uniquely identifies the feature (must match the key provided by setSourceFeature) + */ + template inline typename pcl::PointCloud::ConstPtr + getSourceFeature (const std::string &key); + + /** \brief Provide a pointer to a cloud of feature descriptors associated with the target point cloud + * \param[in] target_feature a cloud of feature descriptors associated with the target point cloud + * \param[in] key a string that uniquely identifies the feature + */ + template inline void + setTargetFeature (const typename pcl::PointCloud::ConstPtr &target_feature, + const std::string &key); + + /** \brief Get a pointer to the source cloud's feature descriptors, specified by the given \a key + * \param[in] key a string that uniquely identifies the feature (must match the key provided by setTargetFeature) + */ + template inline typename pcl::PointCloud::ConstPtr + getTargetFeature (const std::string &key); + + /** \brief Set a hard distance threshold in the feature \a FeatureT space, between source and target + * features. Any feature correspondence that is above this threshold will be considered bad and will be + * filtered out. + * \param[in] thresh the distance threshold + * \param[in] key a string that uniquely identifies the feature + */ + template inline void + setDistanceThreshold (double thresh, const std::string &key); + + /** \brief Test that all features are valid (i.e., does each key have a valid source cloud, target cloud, + * and search method) + */ + inline bool + hasValidFeatures (); + + /** \brief Provide a boost shared pointer to a PointRepresentation to be used when comparing features + * \param[in] key a string that uniquely identifies the feature + * \param[in] fr the point feature representation to be used + */ + template inline void + setFeatureRepresentation (const typename pcl::PointRepresentation::ConstPtr &fr, + const std::string &key); + + protected: + + /** \brief Apply the rejection algorithm. + * \param[out] correspondences the set of resultant correspondences. + */ + inline void + applyRejection (pcl::Correspondences &correspondences) + { + getRemainingCorrespondences (*input_correspondences_, correspondences); + } + + /** \brief The maximum distance threshold between two correspondent points in source <-> target. If the + * distance is larger than this threshold, the points will not be ignored in the alignment process. + */ + float max_distance_; + + class FeatureContainerInterface + { + public: + /** \brief Empty destructor */ + virtual ~FeatureContainerInterface () {} + virtual bool isValid () = 0; + virtual double getCorrespondenceScore (int index) = 0; + virtual bool isCorrespondenceValid (int index) = 0; + }; + + typedef boost::unordered_map > FeaturesMap; + + /** \brief An STL map containing features to use when performing the correspondence search.*/ + FeaturesMap features_map_; + + /** \brief An inner class containing pointers to the source and target feature clouds + * and the parameters needed to perform the correspondence search. This class extends + * FeatureContainerInterface, which contains abstract methods for any methods that do not depend on the + * FeatureT --- these methods can thus be called from a pointer to FeatureContainerInterface without + * casting to the derived class. + */ + template + class FeatureContainer : public pcl::registration::CorrespondenceRejectorFeatures::FeatureContainerInterface + { + public: + typedef typename pcl::PointCloud::ConstPtr FeatureCloudConstPtr; + typedef boost::function &, int, std::vector &, + std::vector &)> SearchMethod; + + typedef typename pcl::PointRepresentation::ConstPtr PointRepresentationConstPtr; + + FeatureContainer () : thresh_(std::numeric_limits::max ()), feature_representation_() + { + } + + /** \brief Empty destructor */ + virtual ~FeatureContainer () {} + + inline void + setSourceFeature (const FeatureCloudConstPtr &source_features) + { + source_features_ = source_features; + } + + inline FeatureCloudConstPtr + getSourceFeature () + { + return (source_features_); + } + + inline void + setTargetFeature (const FeatureCloudConstPtr &target_features) + { + target_features_ = target_features; + } + + inline FeatureCloudConstPtr + getTargetFeature () + { + return (target_features_); + } + + inline void + setDistanceThreshold (double thresh) + { + thresh_ = thresh; + } + + virtual inline bool + isValid () + { + if (!source_features_ || !target_features_) + return (false); + else + return (source_features_->points.size () > 0 && + target_features_->points.size () > 0); + } + + /** \brief Provide a boost shared pointer to a PointRepresentation to be used when comparing features + * \param[in] fr the point feature representation to be used + */ + inline void + setFeatureRepresentation (const PointRepresentationConstPtr &fr) + { + feature_representation_ = fr; + } + + /** \brief Obtain a score between a pair of correspondences. + * \param[in] index the index to check in the list of correspondences + * \return score the resultant computed score + */ + virtual inline double + getCorrespondenceScore (int index) + { + // If no feature representation was given, reset to the default implementation for FeatureT + if (!feature_representation_) + feature_representation_.reset (new DefaultFeatureRepresentation); + + // Get the source and the target feature from the list + const FeatureT &feat_src = source_features_->points[index]; + const FeatureT &feat_tgt = target_features_->points[index]; + + // Check if the representations are valid + if (!feature_representation_->isValid (feat_src) || !feature_representation_->isValid (feat_tgt)) + { + PCL_ERROR ("[pcl::registration::%s::getCorrespondenceScore] Invalid feature representation given!\n", this->getClassName ().c_str ()); + return (std::numeric_limits::max ()); + } + + // Set the internal feature point representation of choice + Eigen::VectorXf feat_src_ptr = Eigen::VectorXf::Zero (feature_representation_->getNumberOfDimensions ()); + feature_representation_->vectorize (FeatureT (feat_src), feat_src_ptr); + Eigen::VectorXf feat_tgt_ptr = Eigen::VectorXf::Zero (feature_representation_->getNumberOfDimensions ()); + feature_representation_->vectorize (FeatureT (feat_tgt), feat_tgt_ptr); + + // Compute the L2 norm + return ((feat_src_ptr - feat_tgt_ptr).squaredNorm ()); + } + + /** \brief Check whether the correspondence pair at the given index is valid + * by computing the score and testing it against the user given threshold + * \param[in] index the index to check in the list of correspondences + * \return true if the correspondence is good, false otherwise + */ + virtual inline bool + isCorrespondenceValid (int index) + { + if (getCorrespondenceScore (index) < thresh_ * thresh_) + return (true); + else + return (false); + } + + private: + FeatureCloudConstPtr source_features_, target_features_; + SearchMethod search_method_; + + /** \brief The L2 squared Euclidean threshold. */ + double thresh_; + + /** \brief The internal point feature representation used. */ + PointRepresentationConstPtr feature_representation_; + }; + }; + } +} + +#include + +#endif /* PCL_REGISTRATION_CORRESPONDENCE_REJECTION_FEATURES_H_ */ diff --git a/pcl-1.7/pcl/registration/correspondence_rejection_median_distance.h b/pcl-1.7/pcl/registration/correspondence_rejection_median_distance.h new file mode 100644 index 0000000..71655f9 --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_rejection_median_distance.h @@ -0,0 +1,213 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_H_ + +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief CorrespondenceRejectorMedianDistance implements a simple correspondence + * rejection method based on thresholding based on the median distance between the + * correspondences. + * + * \note If \ref setInputCloud and \ref setInputTarget are given, then the + * distances between correspondences will be estimated using the given XYZ + * data, and not read from the set of input correspondences. + * + * \author Aravindhan K Krishnan. This code is ported from libpointmatcher (https://github.com/ethz-asl/libpointmatcher) + * \ingroup registration + */ + class PCL_EXPORTS CorrespondenceRejectorMedianDistance: public CorrespondenceRejector + { + using CorrespondenceRejector::input_correspondences_; + using CorrespondenceRejector::rejection_name_; + using CorrespondenceRejector::getClassName; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Empty constructor. */ + CorrespondenceRejectorMedianDistance () + : median_distance_ (0) + , factor_ (1.0) + , data_container_ () + { + rejection_name_ = "CorrespondenceRejectorMedianDistance"; + } + + /** \brief Get a list of valid correspondences after rejection from the original set of correspondences. + * \param[in] original_correspondences the set of initial correspondences given + * \param[out] remaining_correspondences the resultant filtered set of remaining correspondences + */ + void + getRemainingCorrespondences (const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences); + + /** \brief Get the median distance used for thresholding in correspondence rejection. */ + inline double + getMedianDistance () const { return (median_distance_); }; + + /** \brief Provide a source point cloud dataset (must contain XYZ + * data!), used to compute the correspondence distance. + * \param[in] cloud a cloud containing XYZ data + */ + template inline void + setInputSource (const typename pcl::PointCloud::ConstPtr &cloud) + { + if (!data_container_) + data_container_.reset (new DataContainer); + boost::static_pointer_cast > (data_container_)->setInputSource (cloud); + } + + /** \brief Provide a source point cloud dataset (must contain XYZ + * data!), used to compute the correspondence distance. + * \param[in] cloud a cloud containing XYZ data + */ + template inline void + setInputCloud (const typename pcl::PointCloud::ConstPtr &cloud) + { + PCL_WARN ("[pcl::registration::%s::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.\n", getClassName ().c_str ()); + if (!data_container_) + data_container_.reset (new DataContainer); + boost::static_pointer_cast > (data_container_)->setInputSource (cloud); + } + + /** \brief Provide a target point cloud dataset (must contain XYZ + * data!), used to compute the correspondence distance. + * \param[in] target a cloud containing XYZ data + */ + template inline void + setInputTarget (const typename pcl::PointCloud::ConstPtr &target) + { + if (!data_container_) + data_container_.reset (new DataContainer); + boost::static_pointer_cast > (data_container_)->setInputTarget (target); + } + + /** \brief See if this rejector requires source points */ + bool + requiresSourcePoints () const + { return (true); } + + /** \brief Blob method for setting the source cloud */ + void + setSourcePoints (pcl::PCLPointCloud2::ConstPtr cloud2) + { + PointCloud::Ptr cloud (new PointCloud); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputSource (cloud); + } + + /** \brief See if this rejector requires a target cloud */ + bool + requiresTargetPoints () const + { return (true); } + + /** \brief Method for setting the target cloud */ + void + setTargetPoints (pcl::PCLPointCloud2::ConstPtr cloud2) + { + PointCloud::Ptr cloud (new PointCloud); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputTarget (cloud); + } + + /** \brief Provide a pointer to the search object used to find correspondences in + * the target cloud. + * \param[in] tree a pointer to the spatial search object. + * \param[in] force_no_recompute If set to true, this tree will NEVER be + * recomputed, regardless of calls to setInputTarget. Only use if you are + * confident that the tree will be set correctly. + */ + template inline void + setSearchMethodTarget (const boost::shared_ptr > &tree, + bool force_no_recompute = false) + { + boost::static_pointer_cast< DataContainer > + (data_container_)->setSearchMethodTarget (tree, force_no_recompute ); + } + + /** \brief Set the factor for correspondence rejection. Points with distance greater than median times factor + * will be rejected + * \param[in] factor value + */ + inline void + setMedianFactor (double factor) { factor_ = factor; }; + + /** \brief Get the factor used for thresholding in correspondence rejection. */ + inline double + getMedianFactor () const { return factor_; }; + + protected: + + /** \brief Apply the rejection algorithm. + * \param[out] correspondences the set of resultant correspondences. + */ + inline void + applyRejection (pcl::Correspondences &correspondences) + { + getRemainingCorrespondences (*input_correspondences_, correspondences); + } + + /** \brief The median distance threshold between two correspondent points in source <-> target. + */ + double median_distance_; + + /** \brief The factor for correspondence rejection. Points with distance greater than median times factor + * will be rejected + */ + double factor_; + + typedef boost::shared_ptr DataContainerPtr; + + /** \brief A pointer to the DataContainer object containing the input and target point clouds */ + DataContainerPtr data_container_; + }; + } +} + +#include + +#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_H_ diff --git a/pcl-1.7/pcl/registration/correspondence_rejection_one_to_one.h b/pcl-1.7/pcl/registration/correspondence_rejection_one_to_one.h new file mode 100644 index 0000000..5e08e15 --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_rejection_one_to_one.h @@ -0,0 +1,98 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_ONE_TO_ONE_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_ONE_TO_ONE_H_ + +#include + +namespace pcl +{ + namespace registration + { + /** \brief CorrespondenceRejectorOneToOne implements a correspondence + * rejection method based on eliminating duplicate match indices in + * the correspondences. Correspondences with the same match index are + * removed and only the one with smallest distance between query and + * match are kept. That is, considering match->query 1-m correspondences + * are removed leaving only 1-1 correspondences. + * \author Dirk Holz + * \ingroup registration + */ + class PCL_EXPORTS CorrespondenceRejectorOneToOne: public CorrespondenceRejector + { + using CorrespondenceRejector::input_correspondences_; + using CorrespondenceRejector::rejection_name_; + using CorrespondenceRejector::getClassName; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Empty constructor. */ + CorrespondenceRejectorOneToOne () + { + rejection_name_ = "CorrespondenceRejectorOneToOne"; + } + + /** \brief Get a list of valid correspondences after rejection from the original set of correspondences. + * \param[in] original_correspondences the set of initial correspondences given + * \param[out] remaining_correspondences the resultant filtered set of remaining correspondences + */ + void + getRemainingCorrespondences (const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences); + + protected: + /** \brief Apply the rejection algorithm. + * \param[out] correspondences the set of resultant correspondences. + */ + inline void + applyRejection (pcl::Correspondences &correspondences) + { + getRemainingCorrespondences (*input_correspondences_, correspondences); + } + }; + + } +} + +#include + +#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_ONE_TO_ONE_H_ diff --git a/pcl-1.7/pcl/registration/correspondence_rejection_organized_boundary.h b/pcl-1.7/pcl/registration/correspondence_rejection_organized_boundary.h new file mode 100644 index 0000000..4ceec18 --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_rejection_organized_boundary.h @@ -0,0 +1,149 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) Alexandru-Eugen Ichim + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_H_ + +#include + + +namespace pcl +{ + namespace registration + { + /** + * @brief The CorrespondenceRejectionOrganizedBoundary class implements a simple correspondence rejection measure. + * For each pair of points in correspondence, it checks whether they are on the boundary of a silhouette. This is + * done by counting the number of NaN dexels in a window around the points (the threshold and window size can be set + * by the user). + * \note Both the source and the target clouds need to be organized, otherwise all the correspondences will be rejected. + * + * \author Alexandru E. Ichim + * \ingroup registration + */ + class PCL_EXPORTS CorrespondenceRejectionOrganizedBoundary : public CorrespondenceRejector + { + public: + /** @brief Empty constructor. */ + CorrespondenceRejectionOrganizedBoundary () + : boundary_nans_threshold_ (8) + , window_size_ (5) + , depth_step_threshold_ (0.025f) + , data_container_ () + { } + + void + getRemainingCorrespondences (const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences); + + inline void + setNumberOfBoundaryNaNs (int val) + { boundary_nans_threshold_ = val; } + + + template inline void + setInputSource (const typename pcl::PointCloud::ConstPtr &cloud) + { + if (!data_container_) + data_container_.reset (new pcl::registration::DataContainer); + boost::static_pointer_cast > (data_container_)->setInputSource (cloud); + } + + template inline void + setInputTarget (const typename pcl::PointCloud::ConstPtr &cloud) + { + if (!data_container_) + data_container_.reset (new pcl::registration::DataContainer); + boost::static_pointer_cast > (data_container_)->setInputTarget (cloud); + } + + /** \brief See if this rejector requires source points */ + bool + requiresSourcePoints () const + { return (true); } + + /** \brief Blob method for setting the source cloud */ + void + setSourcePoints (pcl::PCLPointCloud2::ConstPtr cloud2) + { + PointCloud::Ptr cloud (new PointCloud); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputSource (cloud); + } + + /** \brief See if this rejector requires a target cloud */ + bool + requiresTargetPoints () const + { return (true); } + + /** \brief Method for setting the target cloud */ + void + setTargetPoints (pcl::PCLPointCloud2::ConstPtr cloud2) + { + PointCloud::Ptr cloud (new PointCloud); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputTarget (cloud); + } + + virtual bool + updateSource (const Eigen::Matrix4d &) + { return (true); } + + protected: + + /** \brief Apply the rejection algorithm. + * \param[out] correspondences the set of resultant correspondences. + */ + inline void + applyRejection (pcl::Correspondences &correspondences) + { getRemainingCorrespondences (*input_correspondences_, correspondences); } + + int boundary_nans_threshold_; + int window_size_; + float depth_step_threshold_; + + typedef boost::shared_ptr DataContainerPtr; + DataContainerPtr data_container_; + }; + } +} + +#include + + +#endif /* PCL_REGISTRATION_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_H_ */ diff --git a/pcl-1.7/pcl/registration/correspondence_rejection_poly.h b/pcl-1.7/pcl/registration/correspondence_rejection_poly.h new file mode 100644 index 0000000..4be1837 --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_rejection_poly.h @@ -0,0 +1,385 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_POLY_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_POLY_H_ + +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief CorrespondenceRejectorPoly implements a correspondence rejection method that exploits low-level and + * pose-invariant geometric constraints between two point sets by forming virtual polygons of a user-specifiable + * cardinality on each model using the input correspondences. + * These polygons are then checked in a pose-invariant manner (i.e. the side lengths must be approximately equal), + * and rejection is performed by thresholding these edge lengths. + * + * If you use this in academic work, please cite: + * + * A. G. Buch, D. Kraft, J.-K. Kämäräinen, H. G. Petersen and N. Krüger. + * Pose Estimation using Local Structure-Specific Shape and Appearance Context. + * International Conference on Robotics and Automation (ICRA), 2013. + * + * \author Anders Glent Buch + * \ingroup registration + */ + template + class PCL_EXPORTS CorrespondenceRejectorPoly: public CorrespondenceRejector + { + using CorrespondenceRejector::input_correspondences_; + using CorrespondenceRejector::rejection_name_; + using CorrespondenceRejector::getClassName; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef pcl::PointCloud PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef pcl::PointCloud PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + /** \brief Empty constructor */ + CorrespondenceRejectorPoly () + : iterations_ (10000) + , cardinality_ (3) + , similarity_threshold_ (0.75f) + , similarity_threshold_squared_ (0.75f * 0.75f) + { + rejection_name_ = "CorrespondenceRejectorPoly"; + } + + /** \brief Get a list of valid correspondences after rejection from the original set of correspondences. + * \param[in] original_correspondences the set of initial correspondences given + * \param[out] remaining_correspondences the resultant filtered set of remaining correspondences + */ + void + getRemainingCorrespondences (const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences); + + /** \brief Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance. + * \param[in] cloud a cloud containing XYZ data + */ + inline void + setInputSource (const PointCloudSourceConstPtr &cloud) + { + input_ = cloud; + } + + /** \brief Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance. + * \param[in] cloud a cloud containing XYZ data + */ + inline void + setInputCloud (const PointCloudSourceConstPtr &cloud) + { + PCL_WARN ("[pcl::registration::%s::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.\n", + getClassName ().c_str ()); + input_ = cloud; + } + + /** \brief Provide a target point cloud dataset (must contain XYZ data!), used to compute the correspondence distance. + * \param[in] target a cloud containing XYZ data + */ + inline void + setInputTarget (const PointCloudTargetConstPtr &target) + { + target_ = target; + } + + /** \brief See if this rejector requires source points */ + bool + requiresSourcePoints () const + { return (true); } + + /** \brief Blob method for setting the source cloud */ + void + setSourcePoints (pcl::PCLPointCloud2::ConstPtr cloud2) + { + PointCloudSourcePtr cloud (new PointCloudSource); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputSource (cloud); + } + + /** \brief See if this rejector requires a target cloud */ + bool + requiresTargetPoints () const + { return (true); } + + /** \brief Method for setting the target cloud */ + void + setTargetPoints (pcl::PCLPointCloud2::ConstPtr cloud2) + { + PointCloudTargetPtr cloud (new PointCloudTarget); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputTarget (cloud); + } + + /** \brief Set the polygon cardinality + * \param cardinality polygon cardinality + */ + inline void + setCardinality (int cardinality) + { + cardinality_ = cardinality; + } + + /** \brief Get the polygon cardinality + * \return polygon cardinality + */ + inline int + getCardinality () + { + return (cardinality_); + } + + /** \brief Set the similarity threshold in [0,1[ between edge lengths, + * where 1 is a perfect match + * \param similarity_threshold similarity threshold + */ + inline void + setSimilarityThreshold (float similarity_threshold) + { + similarity_threshold_ = similarity_threshold; + similarity_threshold_squared_ = similarity_threshold * similarity_threshold; + } + + /** \brief Get the similarity threshold between edge lengths + * \return similarity threshold + */ + inline float + getSimilarityThreshold () + { + return (similarity_threshold_); + } + + /** \brief Set the number of iterations + * \param iterations number of iterations + */ + inline void + setIterations (int iterations) + { + iterations_ = iterations; + } + + /** \brief Get the number of iterations + * \return number of iterations + */ + inline int + getIterations () + { + return (iterations_); + } + + /** \brief Polygonal rejection of a single polygon, indexed by a subset of correspondences + * \param corr all correspondences into \ref input_ and \ref target_ + * \param idx sampled indices into \b correspondences, must have a size equal to \ref cardinality_ + * \return true if all edge length ratios are larger than or equal to \ref similarity_threshold_ + */ + inline bool + thresholdPolygon (const pcl::Correspondences& corr, const std::vector& idx) + { + if (cardinality_ == 2) // Special case: when two points are considered, we only have one edge + { + return (thresholdEdgeLength (corr[ idx[0] ].index_query, corr[ idx[1] ].index_query, + corr[ idx[0] ].index_match, corr[ idx[1] ].index_match, + cardinality_)); + } + else + { // Otherwise check all edges + for (int i = 0; i < cardinality_; ++i) + if (!thresholdEdgeLength (corr[ idx[i] ].index_query, corr[ idx[(i+1)%cardinality_] ].index_query, + corr[ idx[i] ].index_match, corr[ idx[(i+1)%cardinality_] ].index_match, + similarity_threshold_squared_)) + return (false); + + return (true); + } + } + + /** \brief Polygonal rejection of a single polygon, indexed by two point index vectors + * \param source_indices indices of polygon points in \ref input_, must have a size equal to \ref cardinality_ + * \param target_indices corresponding indices of polygon points in \ref target_, must have a size equal to \ref cardinality_ + * \return true if all edge length ratios are larger than or equal to \ref similarity_threshold_ + */ + inline bool + thresholdPolygon (const std::vector& source_indices, const std::vector& target_indices) + { + // Convert indices to correspondences and an index vector pointing to each element + pcl::Correspondences corr (cardinality_); + std::vector idx (cardinality_); + for (int i = 0; i < cardinality_; ++i) + { + corr[i].index_query = source_indices[i]; + corr[i].index_match = target_indices[i]; + idx[i] = i; + } + + return (thresholdPolygon (corr, idx)); + } + + protected: + /** \brief Apply the rejection algorithm. + * \param[out] correspondences the set of resultant correspondences. + */ + inline void + applyRejection (pcl::Correspondences &correspondences) + { + getRemainingCorrespondences (*input_correspondences_, correspondences); + } + + /** \brief Get k unique random indices in range {0,...,n-1} (sampling without replacement) + * \note No check is made to ensure that k <= n. + * \param n upper index range, exclusive + * \param k number of unique indices to sample + * \return k unique random indices in range {0,...,n-1} + */ + inline std::vector + getUniqueRandomIndices (int n, int k) + { + // Marked sampled indices and sample counter + std::vector sampled (n, false); + int samples = 0; + // Resulting unique indices + std::vector result; + result.reserve (k); + do + { + // Pick a random index in the range + const int idx = (std::rand () % n); + // If unique + if (!sampled[idx]) + { + // Mark as sampled and increment result counter + sampled[idx] = true; + ++samples; + // Store + result.push_back (idx); + } + } + while (samples < k); + + return (result); + } + + /** \brief Squared Euclidean distance between two points using the members x, y and z + * \param p1 first point + * \param p2 second point + * \return squared Euclidean distance + */ + inline float + computeSquaredDistance (const SourceT& p1, const TargetT& p2) + { + const float dx = p2.x - p1.x; + const float dy = p2.y - p1.y; + const float dz = p2.z - p1.z; + + return (dx*dx + dy*dy + dz*dz); + } + + /** \brief Edge length similarity thresholding + * \param index_query_1 index of first source vertex + * \param index_query_2 index of second source vertex + * \param index_match_1 index of first target vertex + * \param index_match_2 index of second target vertex + * \param simsq squared similarity threshold in [0,1] + * \return true if edge length ratio is larger than or equal to threshold + */ + inline bool + thresholdEdgeLength (int index_query_1, + int index_query_2, + int index_match_1, + int index_match_2, + float simsq) + { + // Distance between source points + const float dist_src = computeSquaredDistance ((*input_)[index_query_1], (*input_)[index_query_2]); + // Distance between target points + const float dist_tgt = computeSquaredDistance ((*target_)[index_match_1], (*target_)[index_match_2]); + // Edge length similarity [0,1] where 1 is a perfect match + const float edge_sim = (dist_src < dist_tgt ? dist_src / dist_tgt : dist_tgt / dist_src); + + return (edge_sim >= simsq); + } + + /** \brief Compute a linear histogram. This function is equivalent to the MATLAB function \b histc, with the + * edges set as follows: lower:(upper-lower)/bins:upper + * \param data input samples + * \param lower lower bound of input samples + * \param upper upper bound of input samples + * \param bins number of bins in output + * \return linear histogram + */ + std::vector + computeHistogram (const std::vector& data, float lower, float upper, int bins); + + /** \brief Find the optimal value for binary histogram thresholding using Otsu's method + * \param histogram input histogram + * \return threshold value according to Otsu's criterion + */ + int + findThresholdOtsu (const std::vector& histogram); + + /** \brief The input point cloud dataset */ + PointCloudSourceConstPtr input_; + + /** \brief The input point cloud dataset target */ + PointCloudTargetConstPtr target_; + + /** \brief Number of iterations to run */ + int iterations_; + + /** \brief The polygon cardinality used during rejection */ + int cardinality_; + + /** \brief Lower edge length threshold in [0,1] used for verifying polygon similarities, where 1 is a perfect match */ + float similarity_threshold_; + + /** \brief Squared value if \ref similarity_threshold_, only for internal use */ + float similarity_threshold_squared_; + }; + } +} + +#include + +#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_POLY_H_ diff --git a/pcl-1.7/pcl/registration/correspondence_rejection_sample_consensus.h b/pcl-1.7/pcl/registration/correspondence_rejection_sample_consensus.h new file mode 100644 index 0000000..f4c684d --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_rejection_sample_consensus.h @@ -0,0 +1,282 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_H_ + +#include + +#include +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief CorrespondenceRejectorSampleConsensus implements a correspondence rejection + * using Random Sample Consensus to identify inliers (and reject outliers) + * \author Dirk Holz + * \ingroup registration + */ + template + class CorrespondenceRejectorSampleConsensus: public CorrespondenceRejector + { + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + using CorrespondenceRejector::input_correspondences_; + using CorrespondenceRejector::rejection_name_; + using CorrespondenceRejector::getClassName; + + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Empty constructor. Sets the inlier threshold to 5cm (0.05m), + * and the maximum number of iterations to 1000. + */ + CorrespondenceRejectorSampleConsensus () + : inlier_threshold_ (1.20) //default: 0.05 + , max_iterations_ (100) // std::numeric_limits::max (), default: 1000 + , input_ () + , input_transformed_ () + , target_ () + , best_transformation_ () + , refine_ (false) + , save_inliers_ (false) + { + rejection_name_ = "CorrespondenceRejectorSampleConsensus"; + } + + /** \brief Empty destructor. */ + virtual ~CorrespondenceRejectorSampleConsensus () {} + + /** \brief Get a list of valid correspondences after rejection from the original set of correspondences. + * \param[in] original_correspondences the set of initial correspondences given + * \param[out] remaining_correspondences the resultant filtered set of remaining correspondences + */ + inline void + getRemainingCorrespondences (const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences); + + /** \brief Provide a source point cloud dataset (must contain XYZ data!) + * \param[in] cloud a cloud containing XYZ data + */ + PCL_DEPRECATED ("[pcl::registration::CorrespondenceRejectorSampleConsensus::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead:)))))") + virtual void + setInputCloud (const PointCloudConstPtr &cloud); + + /** \brief Get a pointer to the input point cloud dataset target. */ + PCL_DEPRECATED ("[pcl::registration::CorrespondenceRejectorSampleConsensus::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.") + PointCloudConstPtr const + getInputCloud (); + + /** \brief Provide a source point cloud dataset (must contain XYZ data!) + * \param[in] cloud a cloud containing XYZ data + */ + virtual inline void + setInputSource (const PointCloudConstPtr &cloud) + { + input_ = cloud; + } + + /** \brief Get a pointer to the input point cloud dataset target. */ + inline PointCloudConstPtr const + getInputSource () { return (input_); } + + /** \brief Provide a target point cloud dataset (must contain XYZ data!) + * \param[in] cloud a cloud containing XYZ data + */ + PCL_DEPRECATED ("[pcl::registration::CorrespondenceRejectorSampleConsensus::setTargetCloud] setTargetCloud is deprecated. Please use setInputTarget instead.") + virtual void + setTargetCloud (const PointCloudConstPtr &cloud); + + /** \brief Provide a target point cloud dataset (must contain XYZ data!) + * \param[in] cloud a cloud containing XYZ data + */ + virtual inline void + setInputTarget (const PointCloudConstPtr &cloud) { target_ = cloud; } + + /** \brief Get a pointer to the input point cloud dataset target. */ + inline PointCloudConstPtr const + getInputTarget () { return (target_ ); } + + + /** \brief See if this rejector requires source points */ + bool + requiresSourcePoints () const + { return (true); } + + /** \brief Blob method for setting the source cloud */ + void + setSourcePoints (pcl::PCLPointCloud2::ConstPtr cloud2) + { + PointCloudPtr cloud (new PointCloud); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputSource (cloud); + } + + /** \brief See if this rejector requires a target cloud */ + bool + requiresTargetPoints () const + { return (true); } + + /** \brief Method for setting the target cloud */ + void + setTargetPoints (pcl::PCLPointCloud2::ConstPtr cloud2) + { + PointCloudPtr cloud (new PointCloud); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputTarget (cloud); + } + + /** \brief Set the maximum distance between corresponding points. + * Correspondences with distances below the threshold are considered as inliers. + * \param[in] threshold Distance threshold in the same dimension as source and target data sets. + */ + inline void + setInlierThreshold (double threshold) { inlier_threshold_ = threshold; }; + + /** \brief Get the maximum distance between corresponding points. + * \return Distance threshold in the same dimension as source and target data sets. + */ + inline double + getInlierThreshold () { return inlier_threshold_; }; + + /** \brief Set the maximum number of iterations. + * \param[in] max_iterations Maximum number if iterations to run + */ + PCL_DEPRECATED ("[pcl::registration::CorrespondenceRejectorSampleConsensus::setMaxIterations] setMaxIterations is deprecated. Please use setMaximumIterations instead.") + void + setMaxIterations (int max_iterations); + + /** \brief Set the maximum number of iterations. + * \param[in] max_iterations Maximum number if iterations to run + */ + inline void + setMaximumIterations (int max_iterations) { max_iterations_ = std::max (max_iterations, 0); } + + /** \brief Get the maximum number of iterations. + * \return max_iterations Maximum number if iterations to run + */ + PCL_DEPRECATED ("[pcl::registration::CorrespondenceRejectorSampleConsensus::getMaxIterations] getMaxIterations is deprecated. Please use getMaximumIterations instead.") + int + getMaxIterations (); + + /** \brief Get the maximum number of iterations. + * \return max_iterations Maximum number if iterations to run + */ + inline int + getMaximumIterations () { return (max_iterations_); } + + /** \brief Get the best transformation after RANSAC rejection. + * \return The homogeneous 4x4 transformation yielding the largest number of inliers. + */ + inline Eigen::Matrix4f + getBestTransformation () { return best_transformation_; }; + + /** \brief Specify whether the model should be refined internally using the variance of the inliers + * \param[in] refine true if the model should be refined, false otherwise + */ + inline void + setRefineModel (const bool refine) + { + refine_ = refine; + } + + /** \brief Get the internal refine parameter value as set by the user using setRefineModel */ + inline bool + getRefineModel () const + { + return (refine_); + } + + /** \brief Get the inlier indices found by the correspondence rejector. This information is only saved if setSaveInliers(true) was called in advance. + * \param[out] inlier_indices Indices for the inliers + */ + inline void + getInliersIndices (std::vector &inlier_indices) { inlier_indices = inlier_indices_; } + + /** \brief Set whether to save inliers or not + * \param[in] s True to save inliers / False otherwise + */ + inline void + setSaveInliers (bool s) { save_inliers_ = s; } + + /** \brief Get whether the rejector is configured to save inliers */ + inline bool + getSaveInliers () { return save_inliers_; } + + + protected: + + /** \brief Apply the rejection algorithm. + * \param[out] correspondences the set of resultant correspondences. + */ + inline void + applyRejection (pcl::Correspondences &correspondences) + { + getRemainingCorrespondences (*input_correspondences_, correspondences); + } + + double inlier_threshold_; + + int max_iterations_; + + PointCloudConstPtr input_; + PointCloudPtr input_transformed_; + PointCloudConstPtr target_; + + Eigen::Matrix4f best_transformation_; + + bool refine_; + std::vector inlier_indices_; + bool save_inliers_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } +} + +#include + +#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_H_ diff --git a/pcl-1.7/pcl/registration/correspondence_rejection_sample_consensus_2d.h b/pcl-1.7/pcl/registration/correspondence_rejection_sample_consensus_2d.h new file mode 100644 index 0000000..cfbd9fa --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_rejection_sample_consensus_2d.h @@ -0,0 +1,165 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_2D_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_2D_H_ + +#include + +namespace pcl +{ + namespace registration + { + /** \brief CorrespondenceRejectorSampleConsensus2D implements a pixel-based + * correspondence rejection using Random Sample Consensus to identify inliers + * (and reject outliers) + * \author Radu B. Rusu + * \ingroup registration + */ + template + class CorrespondenceRejectorSampleConsensus2D: public CorrespondenceRejectorSampleConsensus + { + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + using CorrespondenceRejectorSampleConsensus::refine_; + using CorrespondenceRejectorSampleConsensus::input_; + using CorrespondenceRejectorSampleConsensus::target_; + using CorrespondenceRejectorSampleConsensus::input_correspondences_; + using CorrespondenceRejectorSampleConsensus::rejection_name_; + using CorrespondenceRejectorSampleConsensus::getClassName; + using CorrespondenceRejectorSampleConsensus::inlier_threshold_; + using CorrespondenceRejectorSampleConsensus::max_iterations_; + using CorrespondenceRejectorSampleConsensus::best_transformation_; + + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Empty constructor. Sets the inlier threshold to 5cm (0.05m), + * and the maximum number of iterations to 1000. + */ + CorrespondenceRejectorSampleConsensus2D () + : projection_matrix_ (Eigen::Matrix3f::Identity ()) + { + rejection_name_ = "CorrespondenceRejectorSampleConsensus2D"; + // Put the projection matrix together + //projection_matrix_ (0, 0) = 525.f; + //projection_matrix_ (1, 1) = 525.f; + //projection_matrix_ (0, 2) = 320.f; + //projection_matrix_ (1, 2) = 240.f; + } + + /** \brief Get a list of valid correspondences after rejection from the original set of correspondences. + * \param[in] original_correspondences the set of initial correspondences given + * \param[out] remaining_correspondences the resultant filtered set of remaining correspondences + */ + inline void + getRemainingCorrespondences (const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences); + + /** \brief Sets the focal length parameters of the target camera. + * \param[in] fx the focal length in pixels along the x-axis of the image + * \param[in] fy the focal length in pixels along the y-axis of the image + */ + inline void + setFocalLengths (const float fx, const float fy) + { + projection_matrix_ (0, 0) = fx; + projection_matrix_ (1, 1) = fy; + } + + /** \brief Reads back the focal length parameters of the target camera. + * \param[out] fx the focal length in pixels along the x-axis of the image + * \param[out] fy the focal length in pixels along the y-axis of the image + */ + inline void + getFocalLengths (float &fx, float &fy) const + { + fx = projection_matrix_ (0, 0); + fy = projection_matrix_ (1, 1); + } + + + /** \brief Sets the camera center parameters of the target camera. + * \param[in] cx the x-coordinate of the camera center + * \param[in] cy the y-coordinate of the camera center + */ + inline void + setCameraCenters (const float cx, const float cy) + { + projection_matrix_ (0, 2) = cx; + projection_matrix_ (1, 2) = cy; + } + + /** \brief Reads back the camera center parameters of the target camera. + * \param[out] cx the x-coordinate of the camera center + * \param[out] cy the y-coordinate of the camera center + */ + inline void + getCameraCenters (float &cx, float &cy) const + { + cx = projection_matrix_ (0, 2); + cy = projection_matrix_ (1, 2); + } + + protected: + + /** \brief Apply the rejection algorithm. + * \param[out] correspondences the set of resultant correspondences. + */ + inline void + applyRejection (pcl::Correspondences &correspondences) + { + getRemainingCorrespondences (*input_correspondences_, correspondences); + } + + /** \brief Camera projection matrix. */ + Eigen::Matrix3f projection_matrix_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } +} + +#include + +#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_2D_H_ + diff --git a/pcl-1.7/pcl/registration/correspondence_rejection_surface_normal.h b/pcl-1.7/pcl/registration/correspondence_rejection_surface_normal.h new file mode 100644 index 0000000..9eda90b --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_rejection_surface_normal.h @@ -0,0 +1,325 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SURFACE_NORMAL_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SURFACE_NORMAL_H_ + +#include +#include + +namespace pcl +{ + namespace registration + { + /** + * @b CorrespondenceRejectorSurfaceNormal implements a simple correspondence + * rejection method based on the angle between the normals at correspondent points. + * + * \note If \ref setInputCloud and \ref setInputTarget are given, then the + * distances between correspondences will be estimated using the given XYZ + * data, and not read from the set of input correspondences. + * + * \author Aravindhan K Krishnan (original code from libpointmatcher: https://github.com/ethz-asl/libpointmatcher) + * \ingroup registration + */ + class PCL_EXPORTS CorrespondenceRejectorSurfaceNormal: public CorrespondenceRejector + { + using CorrespondenceRejector::input_correspondences_; + using CorrespondenceRejector::rejection_name_; + using CorrespondenceRejector::getClassName; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Empty constructor. Sets the threshold to 1.0. */ + CorrespondenceRejectorSurfaceNormal () + : threshold_ (1.0) + , data_container_ () + { + rejection_name_ = "CorrespondenceRejectorSurfaceNormal"; + } + + /** \brief Get a list of valid correspondences after rejection from the original set of correspondences. + * \param[in] original_correspondences the set of initial correspondences given + * \param[out] remaining_correspondences the resultant filtered set of remaining correspondences + */ + void + getRemainingCorrespondences (const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences); + + /** \brief Set the thresholding angle between the normals for correspondence rejection. + * \param[in] threshold cosine of the thresholding angle between the normals for rejection + */ + inline void + setThreshold (double threshold) { threshold_ = threshold; }; + + /** \brief Get the thresholding angle between the normals for correspondence rejection. */ + inline double + getThreshold () const { return threshold_; }; + + /** \brief Initialize the data container object for the point type and the normal type. */ + template inline void + initializeDataContainer () + { + data_container_.reset (new DataContainer); + } + + /** \brief Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance. + * \param[in] input a cloud containing XYZ data + */ + template inline void + setInputCloud (const typename pcl::PointCloud::ConstPtr &input) + { + PCL_WARN ("[pcl::registration::%s::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.\n", getClassName ().c_str ()); + if (!data_container_) + { + PCL_ERROR ("[pcl::registration::%s::setInputCloud] Initialize the data container object by calling intializeDataContainer () before using this function.\n", getClassName ().c_str ()); + return; + } + boost::static_pointer_cast > (data_container_)->setInputSource (input); + } + + /** \brief Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance. + * \param[in] input a cloud containing XYZ data + */ + template inline void + setInputSource (const typename pcl::PointCloud::ConstPtr &input) + { + if (!data_container_) + { + PCL_ERROR ("[pcl::registration::%s::setInputCloud] Initialize the data container object by calling intializeDataContainer () before using this function.\n", getClassName ().c_str ()); + return; + } + boost::static_pointer_cast > (data_container_)->setInputSource (input); + } + + /** \brief Get the target input point cloud */ + template inline typename pcl::PointCloud::ConstPtr + getInputSource () const + { + if (!data_container_) + { + PCL_ERROR ("[pcl::registration::%s::getInputSource] Initialize the data container object by calling intializeDataContainer () before using this function.\n", getClassName ().c_str ()); + return; + } + return (boost::static_pointer_cast > (data_container_)->getInputSource ()); + } + + /** \brief Provide a target point cloud dataset (must contain XYZ data!), used to compute the correspondence distance. + * \param[in] target a cloud containing XYZ data + */ + template inline void + setInputTarget (const typename pcl::PointCloud::ConstPtr &target) + { + if (!data_container_) + { + PCL_ERROR ("[pcl::registration::%s::setInputTarget] Initialize the data container object by calling intializeDataContainer () before using this function.\n", getClassName ().c_str ()); + return; + } + boost::static_pointer_cast > (data_container_)->setInputTarget (target); + } + + /** \brief Provide a pointer to the search object used to find correspondences in + * the target cloud. + * \param[in] tree a pointer to the spatial search object. + * \param[in] force_no_recompute If set to true, this tree will NEVER be + * recomputed, regardless of calls to setInputTarget. Only use if you are + * confident that the tree will be set correctly. + */ + template inline void + setSearchMethodTarget (const boost::shared_ptr > &tree, + bool force_no_recompute = false) + { + boost::static_pointer_cast< DataContainer > + (data_container_)->setSearchMethodTarget (tree, force_no_recompute ); + } + + /** \brief Get the target input point cloud */ + template inline typename pcl::PointCloud::ConstPtr + getInputTarget () const + { + if (!data_container_) + { + PCL_ERROR ("[pcl::registration::%s::getInputTarget] Initialize the data container object by calling intializeDataContainer () before using this function.\n", getClassName ().c_str ()); + return; + } + return (boost::static_pointer_cast > (data_container_)->getInputTarget ()); + } + + /** \brief Set the normals computed on the input point cloud + * \param[in] normals the normals computed for the input cloud + */ + template inline void + setInputNormals (const typename pcl::PointCloud::ConstPtr &normals) + { + if (!data_container_) + { + PCL_ERROR ("[pcl::registration::%s::setInputNormals] Initialize the data container object by calling intializeDataContainer () before using this function.\n", getClassName ().c_str ()); + return; + } + boost::static_pointer_cast > (data_container_)->setInputNormals (normals); + } + + /** \brief Get the normals computed on the input point cloud */ + template inline typename pcl::PointCloud::Ptr + getInputNormals () const + { + if (!data_container_) + { + PCL_ERROR ("[pcl::registration::%s::getInputNormals] Initialize the data container object by calling intializeDataContainer () before using this function.\n", getClassName ().c_str ()); + return; + } + return (boost::static_pointer_cast > (data_container_)->getInputNormals ()); + } + + /** \brief Set the normals computed on the target point cloud + * \param[in] normals the normals computed for the input cloud + */ + template inline void + setTargetNormals (const typename pcl::PointCloud::ConstPtr &normals) + { + if (!data_container_) + { + PCL_ERROR ("[pcl::registration::%s::setTargetNormals] Initialize the data container object by calling intializeDataContainer () before using this function.\n", getClassName ().c_str ()); + return; + } + boost::static_pointer_cast > (data_container_)->setTargetNormals (normals); + } + + /** \brief Get the normals computed on the target point cloud */ + template inline typename pcl::PointCloud::Ptr + getTargetNormals () const + { + if (!data_container_) + { + PCL_ERROR ("[pcl::registration::%s::getTargetNormals] Initialize the data container object by calling intializeDataContainer () before using this function.\n", getClassName ().c_str ()); + return; + } + return (boost::static_pointer_cast > (data_container_)->getTargetNormals ()); + } + + + /** \brief See if this rejector requires source points */ + bool + requiresSourcePoints () const + { return (true); } + + /** \brief Blob method for setting the source cloud */ + void + setSourcePoints (pcl::PCLPointCloud2::ConstPtr cloud2) + { + if (!data_container_) + initializeDataContainer (); + PointCloud::Ptr cloud (new PointCloud); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputSource (cloud); + } + + /** \brief See if this rejector requires a target cloud */ + bool + requiresTargetPoints () const + { return (true); } + + /** \brief Method for setting the target cloud */ + void + setTargetPoints (pcl::PCLPointCloud2::ConstPtr cloud2) + { + if (!data_container_) + initializeDataContainer (); + PointCloud::Ptr cloud (new PointCloud); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputTarget (cloud); + } + + /** \brief See if this rejector requires source normals */ + bool + requiresSourceNormals () const + { return (true); } + + /** \brief Blob method for setting the source normals */ + void + setSourceNormals (pcl::PCLPointCloud2::ConstPtr cloud2) + { + if (!data_container_) + initializeDataContainer (); + PointCloud::Ptr cloud (new PointCloud); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputNormals (cloud); + } + + /** \brief See if this rejector requires target normals*/ + bool + requiresTargetNormals () const + { return (true); } + + /** \brief Method for setting the target normals */ + void + setTargetNormals (pcl::PCLPointCloud2::ConstPtr cloud2) + { + if (!data_container_) + initializeDataContainer (); + PointCloud::Ptr cloud (new PointCloud); + fromPCLPointCloud2 (*cloud2, *cloud); + setTargetNormals (cloud); + } + + protected: + + /** \brief Apply the rejection algorithm. + * \param[out] correspondences the set of resultant correspondences. + */ + inline void + applyRejection (pcl::Correspondences &correspondences) + { + getRemainingCorrespondences (*input_correspondences_, correspondences); + } + + /** \brief The median distance threshold between two correspondent points in source <-> target. */ + double threshold_; + + typedef boost::shared_ptr DataContainerPtr; + /** \brief A pointer to the DataContainer object containing the input and target point clouds */ + DataContainerPtr data_container_; + }; + } +} + +#include + +#endif diff --git a/pcl-1.7/pcl/registration/correspondence_rejection_trimmed.h b/pcl-1.7/pcl/registration/correspondence_rejection_trimmed.h new file mode 100644 index 0000000..d92c66f --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_rejection_trimmed.h @@ -0,0 +1,141 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_TRIMMED_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_TRIMMED_H_ + +#include + +namespace pcl +{ + namespace registration + { + /** \brief CorrespondenceRejectorTrimmed implements a correspondence + * rejection for ICP-like registration algorithms that uses only the best + * 'k' correspondences where 'k' is some estimate of the overlap between + * the two point clouds being registered. + * + * Reference: + * 'The Trimmed Iterative Closest Point Algorithm' by + * D. Chetverikov, D. Svirko, D. Stepanov, and Pavel Krsek. + * In Proceedings of the 16th International Conference on Pattern + * Recognition (ICPR 2002). + * + * \author Dirk Holz + * \ingroup registration + */ + class PCL_EXPORTS CorrespondenceRejectorTrimmed: public CorrespondenceRejector + { + using CorrespondenceRejector::input_correspondences_; + using CorrespondenceRejector::rejection_name_; + using CorrespondenceRejector::getClassName; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Empty constructor. */ + CorrespondenceRejectorTrimmed () : + overlap_ratio_ (0.5f), + nr_min_correspondences_ (0) + { + rejection_name_ = "CorrespondenceRejectorTrimmed"; + } + + /** \brief Destructor. */ + virtual ~CorrespondenceRejectorTrimmed () {} + + /** \brief Set the expected ratio of overlap between point clouds (in + * terms of correspondences). + * \param[in] ratio ratio of overlap between 0 (no overlap, no + * correspondences) and 1 (full overlap, all correspondences) + */ + virtual inline void + setOverlapRatio (float ratio) { overlap_ratio_ = std::min (1.0f, std::max (0.0f, ratio)); }; + + /** \brief Get the maximum distance used for thresholding in correspondence rejection. */ + inline float + getOverlapRatio () { return overlap_ratio_; }; + + /** \brief Set a minimum number of correspondences. If the specified overlap ratio causes to have + * less correspondences, \a CorrespondenceRejectorTrimmed will try to return at least + * \a nr_min_correspondences_ correspondences (or all correspondences in case \a nr_min_correspondences_ + * is less than the number of given correspondences). + * \param[in] min_correspondences the minimum number of correspondences + */ + inline void + setMinCorrespondences (unsigned int min_correspondences) { nr_min_correspondences_ = min_correspondences; }; + + /** \brief Get the minimum number of correspondences. */ + inline unsigned int + getMinCorrespondences () { return nr_min_correspondences_; }; + + + /** \brief Get a list of valid correspondences after rejection from the original set of correspondences. + * \param[in] original_correspondences the set of initial correspondences given + * \param[out] remaining_correspondences the resultant filtered set of remaining correspondences + */ + void + getRemainingCorrespondences (const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences); + + protected: + + /** \brief Apply the rejection algorithm. + * \param[out] correspondences the set of resultant correspondences. + */ + inline void + applyRejection (pcl::Correspondences &correspondences) + { + getRemainingCorrespondences (*input_correspondences_, correspondences); + } + + /** Overlap Ratio in [0..1] */ + float overlap_ratio_; + + /** Minimum number of correspondences. */ + unsigned int nr_min_correspondences_; + }; + + } +} + +#include + +#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_TRIMMED_H_ diff --git a/pcl-1.7/pcl/registration/correspondence_rejection_var_trimmed.h b/pcl-1.7/pcl/registration/correspondence_rejection_var_trimmed.h new file mode 100644 index 0000000..5a92a66 --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_rejection_var_trimmed.h @@ -0,0 +1,255 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Open Perception, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_VAR_TRIMMED_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_VAR_TRIMMED_H_ + +#include +#include + +#include + +namespace pcl +{ + namespace registration + { + /** + * @b CorrespondenceRejectoVarTrimmed implements a simple correspondence + * rejection method by considering as inliers a certain percentage of correspondences + * with the least distances. The percentage of inliers is computed internally as mentioned + * in the paper 'Outlier Robust ICP for minimizing Fractional RMSD, J. M. Philips et al' + * + * \note If \ref setInputCloud and \ref setInputTarget are given, then the + * distances between correspondences will be estimated using the given XYZ + * data, and not read from the set of input correspondences. + * + * \author Aravindhan K Krishnan. This code is ported from libpointmatcher (https://github.com/ethz-asl/libpointmatcher) + * \ingroup registration + */ + class PCL_EXPORTS CorrespondenceRejectorVarTrimmed: public CorrespondenceRejector + { + using CorrespondenceRejector::input_correspondences_; + using CorrespondenceRejector::rejection_name_; + using CorrespondenceRejector::getClassName; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Empty constructor. */ + CorrespondenceRejectorVarTrimmed () : + trimmed_distance_ (0), + factor_ (), + min_ratio_ (0.05), + max_ratio_ (0.95), + lambda_ (0.95), + data_container_ () + { + rejection_name_ = "CorrespondenceRejectorVarTrimmed"; + } + + /** \brief Get a list of valid correspondences after rejection from the original set of correspondences. + * \param[in] original_correspondences the set of initial correspondences given + * \param[out] remaining_correspondences the resultant filtered set of remaining correspondences + */ + void + getRemainingCorrespondences (const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences); + + /** \brief Get the trimmed distance used for thresholding in correspondence rejection. */ + inline double + getTrimmedDistance () const { return trimmed_distance_; }; + + /** \brief Provide a source point cloud dataset (must contain XYZ + * data!), used to compute the correspondence distance. + * \param[in] cloud a cloud containing XYZ data + */ + template inline void + setInputSource (const typename pcl::PointCloud::ConstPtr &cloud) + { + if (!data_container_) + data_container_.reset (new DataContainer); + boost::static_pointer_cast > (data_container_)->setInputSource (cloud); + } + + /** \brief Provide a source point cloud dataset (must contain XYZ + * data!), used to compute the correspondence distance. + * \param[in] cloud a cloud containing XYZ data + */ + template inline void + setInputCloud (const typename pcl::PointCloud::ConstPtr &cloud) + { + PCL_WARN ("[pcl::registration::%s::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.\n", getClassName ().c_str ()); + if (!data_container_) + data_container_.reset (new DataContainer); + boost::static_pointer_cast > (data_container_)->setInputSource (cloud); + } + + /** \brief Provide a target point cloud dataset (must contain XYZ + * data!), used to compute the correspondence distance. + * \param[in] target a cloud containing XYZ data + */ + template inline void + setInputTarget (const typename pcl::PointCloud::ConstPtr &target) + { + if (!data_container_) + data_container_.reset (new DataContainer); + boost::static_pointer_cast > (data_container_)->setInputTarget (target); + } + + + + /** \brief See if this rejector requires source points */ + bool + requiresSourcePoints () const + { return (true); } + + /** \brief Blob method for setting the source cloud */ + void + setSourcePoints (pcl::PCLPointCloud2::ConstPtr cloud2) + { + PointCloud::Ptr cloud (new PointCloud); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputSource (cloud); + } + + /** \brief See if this rejector requires a target cloud */ + bool + requiresTargetPoints () const + { return (true); } + + /** \brief Method for setting the target cloud */ + void + setTargetPoints (pcl::PCLPointCloud2::ConstPtr cloud2) + { + PointCloud::Ptr cloud (new PointCloud); + fromPCLPointCloud2 (*cloud2, *cloud); + setInputTarget (cloud); + } + + /** \brief Provide a pointer to the search object used to find correspondences in + * the target cloud. + * \param[in] tree a pointer to the spatial search object. + * \param[in] force_no_recompute If set to true, this tree will NEVER be + * recomputed, regardless of calls to setInputTarget. Only use if you are + * confident that the tree will be set correctly. + */ + template inline void + setSearchMethodTarget (const boost::shared_ptr > &tree, + bool force_no_recompute = false) + { + boost::static_pointer_cast< DataContainer > + (data_container_)->setSearchMethodTarget (tree, force_no_recompute ); + } + + /** \brief Get the computed inlier ratio used for thresholding in correspondence rejection. */ + inline double + getTrimFactor () const { return factor_; } + + /** brief set the minimum overlap ratio + * \param[in] ratio the overlap ratio [0..1] + */ + inline void + setMinRatio (double ratio) { min_ratio_ = ratio; } + + /** brief get the minimum overlap ratio + */ + inline double + getMinRatio () const { return min_ratio_; } + + /** brief set the maximum overlap ratio + * \param[in] ratio the overlap ratio [0..1] + */ + inline void + setMaxRatio (double ratio) { max_ratio_ = ratio; } + + /** brief get the maximum overlap ratio + */ + inline double + getMaxRatio () const { return max_ratio_; } + + protected: + + /** \brief Apply the rejection algorithm. + * \param[out] correspondences the set of resultant correspondences. + */ + inline void + applyRejection (pcl::Correspondences &correspondences) + { + getRemainingCorrespondences (*input_correspondences_, correspondences); + } + + /** \brief The inlier distance threshold (based on the computed trim factor) between two correspondent points in source <-> target. + */ + double trimmed_distance_; + + /** \brief The factor for correspondence rejection. Only factor times the total points sorted based on + * the correspondence distances will be considered as inliers. Remaining points are rejected. This factor is + * computed internally + */ + double factor_; + + /** \brief The minimum overlap ratio between the input and target clouds + */ + double min_ratio_; + + /** \brief The maximum overlap ratio between the input and target clouds + */ + double max_ratio_; + + /** \brief part of the term that balances the root mean square difference. This is an internal parameter + */ + double lambda_; + + typedef boost::shared_ptr DataContainerPtr; + + /** \brief A pointer to the DataContainer object containing the input and target point clouds */ + DataContainerPtr data_container_; + + private: + + /** \brief finds the optimal inlier ratio. This is based on the paper 'Outlier Robust ICP for minimizing Fractional RMSD, J. M. Philips et al' + */ + inline float optimizeInlierRatio (std::vector &dists); + }; + } +} + +#include + +#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_VAR_TRIMMED_H_ diff --git a/pcl-1.7/pcl/registration/correspondence_sorting.h b/pcl-1.7/pcl/registration/correspondence_sorting.h new file mode 100644 index 0000000..fd2b2fd --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_sorting.h @@ -0,0 +1,129 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_CORRESPONDENCE_SORTING_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_SORTING_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include + +namespace pcl +{ + namespace registration + { + /** @b sortCorrespondencesByQueryIndex : a functor for sorting correspondences by query index + * \author Dirk Holz + * \ingroup registration + */ + struct sortCorrespondencesByQueryIndex : public std::binary_function + { + bool + operator()( pcl::Correspondence a, pcl::Correspondence b) + { + return (a.index_query < b.index_query); + } + }; + + /** @b sortCorrespondencesByMatchIndex : a functor for sorting correspondences by match index + * \author Dirk Holz + * \ingroup registration + */ + struct sortCorrespondencesByMatchIndex : public std::binary_function + { + bool + operator()( pcl::Correspondence a, pcl::Correspondence b) + { + return (a.index_match < b.index_match); + } + }; + + /** @b sortCorrespondencesByDistance : a functor for sorting correspondences by distance + * \author Dirk Holz + * \ingroup registration + */ + struct sortCorrespondencesByDistance : public std::binary_function + { + bool + operator()( pcl::Correspondence a, pcl::Correspondence b) + { + return (a.distance < b.distance); + } + }; + + /** @b sortCorrespondencesByQueryIndexAndDistance : a functor for sorting correspondences by query index _and_ distance + * \author Dirk Holz + * \ingroup registration + */ + struct sortCorrespondencesByQueryIndexAndDistance : public std::binary_function + { + inline bool + operator()( pcl::Correspondence a, pcl::Correspondence b) + { + if (a.index_query < b.index_query) + return (true); + else if ( (a.index_query == b.index_query) && (a.distance < b.distance) ) + return (true); + return (false); + } + }; + + /** @b sortCorrespondencesByMatchIndexAndDistance : a functor for sorting correspondences by match index _and_ distance + * \author Dirk Holz + * \ingroup registration + */ + struct sortCorrespondencesByMatchIndexAndDistance : public std::binary_function + { + inline bool + operator()( pcl::Correspondence a, pcl::Correspondence b) + { + if (a.index_match < b.index_match) + return (true); + else if ( (a.index_match == b.index_match) && (a.distance < b.distance) ) + return (true); + return (false); + } + }; + + } +} + +#endif /* PCL_REGISTRATION_CORRESPONDENCE_SORTING_H_ */ diff --git a/pcl-1.7/pcl/registration/correspondence_types.h b/pcl-1.7/pcl/registration/correspondence_types.h new file mode 100644 index 0000000..ef7905b --- /dev/null +++ b/pcl-1.7/pcl/registration/correspondence_types.h @@ -0,0 +1,79 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_CORRESPONDENCE_TYPES_H_ +#define PCL_REGISTRATION_CORRESPONDENCE_TYPES_H_ + +#include + +namespace pcl +{ + namespace registration + { + /** \brief calculates the mean and standard deviation of descriptor distances from correspondences + * \param[in] correspondences list of correspondences + * \param[out] mean the mean descriptor distance of correspondences + * \param[out] stddev the standard deviation of descriptor distances. + * \note The sample varaiance is used to determine the standard deviation + */ + inline void + getCorDistMeanStd (const pcl::Correspondences& correspondences, double &mean, double &stddev); + + /** \brief extracts the query indices + * \param[in] correspondences list of correspondences + * \param[out] indices array of extracted indices. + * \note order of indices corresponds to input list of descriptor correspondences + */ + inline void + getQueryIndices (const pcl::Correspondences& correspondences, std::vector& indices); + + /** \brief extracts the match indices + * \param[in] correspondences list of correspondences + * \param[out] indices array of extracted indices. + * \note order of indices corresponds to input list of descriptor correspondences + */ + inline void + getMatchIndices (const pcl::Correspondences& correspondences, std::vector& indices); + + } +} + +#include + +#endif /* PCL_REGISTRATION_CORRESPONDENCE_TYPES_H_ */ diff --git a/pcl-1.7/pcl/registration/default_convergence_criteria.h b/pcl-1.7/pcl/registration/default_convergence_criteria.h new file mode 100644 index 0000000..32f623e --- /dev/null +++ b/pcl-1.7/pcl/registration/default_convergence_criteria.h @@ -0,0 +1,281 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_DEFAULT_CONVERGENCE_CRITERIA_H_ +#define PCL_REGISTRATION_DEFAULT_CONVERGENCE_CRITERIA_H_ + +#include +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief @b DefaultConvergenceCriteria represents an instantiation of + * ConvergenceCriteria, and implements the following criteria for registration loop + * evaluation: + * + * * a maximum number of iterations has been reached + * * the transformation (R, t) cannot be further updated (the difference between current and previous is smaller than a threshold) + * * the Mean Squared Error (MSE) between the current set of correspondences and the previous one is smaller than some threshold (both relative and absolute tests) + * + * \note Convergence is considered reached if ANY of the above criteria are met. + * + * \author Radu B. Rusu + * \ingroup registration + */ + template + class DefaultConvergenceCriteria : public ConvergenceCriteria + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef Eigen::Matrix Matrix4; + + enum ConvergenceState + { + CONVERGENCE_CRITERIA_NOT_CONVERGED, + CONVERGENCE_CRITERIA_ITERATIONS, + CONVERGENCE_CRITERIA_TRANSFORM, + CONVERGENCE_CRITERIA_ABS_MSE, + CONVERGENCE_CRITERIA_REL_MSE, + CONVERGENCE_CRITERIA_NO_CORRESPONDENCES + }; + + /** \brief Empty constructor. + * Sets: + * * the maximum number of iterations to 1000 + * * the rotation threshold to 0.256 degrees (0.99999) + * * the translation threshold to 0.0003 meters (3e-4^2) + * * the MSE relative / absolute thresholds to 0.001% and 1e-12 + * + * \param[in] iterations a reference to the number of iterations the loop has ran so far + * \param[in] transform a reference to the current transformation obtained by the transformation evaluation + * \param[in] correspondences a reference to the current set of point correspondences between source and target + */ + DefaultConvergenceCriteria (const int &iterations, const Matrix4 &transform, const pcl::Correspondences &correspondences) + : iterations_ (iterations) + , transformation_ (transform) + , correspondences_ (correspondences) + , correspondences_prev_mse_ (std::numeric_limits::max ()) + , correspondences_cur_mse_ (std::numeric_limits::max ()) + , max_iterations_ (100) // 100 iterations + , failure_after_max_iter_ (false) + , rotation_threshold_ (0.99999) // 0.256 degrees + , translation_threshold_ (3e-4 * 3e-4) // 0.0003 meters + , mse_threshold_relative_ (0.00001) // 0.001% of the previous MSE (relative error) + , mse_threshold_absolute_ (1e-12) // MSE (absolute error) + , iterations_similar_transforms_ (0) + , max_iterations_similar_transforms_ (0) + , convergence_state_ (CONVERGENCE_CRITERIA_NOT_CONVERGED) + { + } + + /** \brief Empty destructor */ + virtual ~DefaultConvergenceCriteria () {} + + /** \brief Set the maximum number of iterations that the internal rotation, + * translation, and MSE differences are allowed to be similar. + * \param[in] nr_iterations the maximum number of iterations + */ + inline void + setMaximumIterationsSimilarTransforms (const int nr_iterations) { max_iterations_similar_transforms_ = nr_iterations; } + + /** \brief Get the maximum number of iterations that the internal rotation, + * translation, and MSE differences are allowed to be similar, as set by the user. + */ + inline int + getMaximumIterationsSimilarTransforms () const { return (max_iterations_similar_transforms_); } + + /** \brief Set the maximum number of iterations the internal optimization should run for. + * \param[in] nr_iterations the maximum number of iterations the internal optimization should run for + */ + inline void + setMaximumIterations (const int nr_iterations) { max_iterations_ = nr_iterations; } + + /** \brief Get the maximum number of iterations the internal optimization should run for, as set by the user. */ + inline int + getMaximumIterations () const { return (max_iterations_); } + + /** \brief Specifies if the registration fails or converges when the maximum number of iterations is reached. + * \param[in] failure_after_max_iter If true, the registration fails. If false, the registration is assumed to have converged. + */ + inline void + setFailureAfterMaximumIterations (const bool failure_after_max_iter) { failure_after_max_iter_ = failure_after_max_iter; } + + /** \brief Get whether the registration will fail or converge when the maximum number of iterations is reached. */ + inline bool + getFailureAfterMaximumIterations () const { return (failure_after_max_iter_); } + + /** \brief Set the rotation threshold cosine angle (maximum allowable difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution. + * \param[in] threshold the rotation threshold in order for an optimization to be considered as having converged to the final solution. + */ + inline void + setRotationThreshold (const double threshold) { rotation_threshold_ = threshold; } + + /** \brief Get the rotation threshold cosine angle (maximum allowable difference between two consecutive transformations) as set by the user. + */ + inline double + getRotationThreshold () const { return (rotation_threshold_); } + + /** \brief Set the translation threshold (maximum allowable difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution. + * \param[in] threshold the translation threshold in order for an optimization to be considered as having converged to the final solution. + */ + inline void + setTranslationThreshold (const double threshold) { translation_threshold_ = threshold; } + + /** \brief Get the rotation threshold cosine angle (maximum allowable difference between two consecutive transformations) as set by the user. + */ + inline double + getTranslationThreshold () const { return (translation_threshold_); } + + /** \brief Set the relative MSE between two consecutive sets of correspondences. + * \param[in] mse_relative the relative MSE threshold + */ + inline void + setRelativeMSE (const double mse_relative) { mse_threshold_relative_ = mse_relative; } + + /** \brief Get the relative MSE between two consecutive sets of correspondences. */ + inline double + getRelativeMSE () const { return (mse_threshold_relative_); } + + /** \brief Set the absolute MSE between two consecutive sets of correspondences. + * \param[in] mse_absolute the relative MSE threshold + */ + inline void + setAbsoluteMSE (const double mse_absolute) { mse_threshold_absolute_ = mse_absolute; } + + /** \brief Get the absolute MSE between two consecutive sets of correspondences. */ + inline double + getAbsoluteMSE () const { return (mse_threshold_absolute_); } + + + /** \brief Check if convergence has been reached. */ + virtual bool + hasConverged (); + + /** \brief Return the convergence state after hasConverged () */ + ConvergenceState + getConvergenceState () + { + return (convergence_state_); + } + + /** \brief Sets the convergence state externally (for example, when ICP does not find + * enough correspondences to estimate a transformation, the function is called setting + * the convergence state to ConvergenceState::CONVERGENCE_CRITERIA_NO_CORRESPONDENCES) + * \param[in] c the convergence state + */ + inline void + setConvergenceState(ConvergenceState c) + { + convergence_state_ = c; + } + + protected: + + /** \brief Calculate the mean squared error (MSE) of the distance for a given set of correspondences. + * \param[in] correspondences the given set of correspondences + */ + inline double + calculateMSE (const pcl::Correspondences &correspondences) const + { + double mse = 0; + for (size_t i = 0; i < correspondences.size (); ++i) + mse += correspondences[i].distance; + mse /= double (correspondences.size ()); + return (mse); + } + + /** \brief The number of iterations done by the registration loop so far. */ + const int &iterations_; + + /** \brief The current transformation obtained by the transformation estimation method. */ + const Matrix4 &transformation_; + + /** \brief The current set of point correspondences between the source and the target. */ + const pcl::Correspondences &correspondences_; + + /** \brief The MSE for the previous set of correspondences. */ + double correspondences_prev_mse_; + + /** \brief The MSE for the current set of correspondences. */ + double correspondences_cur_mse_; + + /** \brief The maximum nuyyGmber of iterations that the registration loop is to be executed. */ + int max_iterations_; + + /** \brief Specifys if the registration fails or converges when the maximum number of iterations is reached. */ + bool failure_after_max_iter_; + + /** \brief The rotation threshold is the relative rotation between two iterations (as angle cosine). */ + double rotation_threshold_; + + /** \brief The translation threshold is the relative translation between two iterations (0 if no translation). */ + double translation_threshold_; + + /** \brief The relative change from the previous MSE for the current set of correspondences, e.g. .1 means 10% change. */ + double mse_threshold_relative_; + + /** \brief The absolute change from the previous MSE for the current set of correspondences. */ + double mse_threshold_absolute_; + + /** \brief Internal counter for the number of iterations that the internal + * rotation, translation, and MSE differences are allowed to be similar. */ + int iterations_similar_transforms_; + + /** \brief The maximum number of iterations that the internal rotation, + * translation, and MSE differences are allowed to be similar. */ + int max_iterations_similar_transforms_; + + /** \brief The state of the convergence (e.g., why did the registration converge). */ + ConvergenceState convergence_state_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } +} + +#include + +#endif // PCL_REGISTRATION_DEFAULT_CONVERGENCE_CRITERIA_H_ + diff --git a/pcl-1.7/pcl/registration/distances.h b/pcl-1.7/pcl/registration/distances.h new file mode 100644 index 0000000..a6886a8 --- /dev/null +++ b/pcl-1.7/pcl/registration/distances.h @@ -0,0 +1,145 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_DISTANCES_H +#define PCL_REGISTRATION_DISTANCES_H + +#include +#include + +namespace pcl +{ + namespace distances + { + + /** \brief Compute the median value from a set of doubles + * \param[in] fvec the set of doubles + * \param[in] m the number of doubles in the set + */ + inline double + computeMedian (double *fvec, int m) + { + // Copy the values to vectors for faster sorting + std::vector data (m); + memcpy (&data[0], fvec, sizeof (double) * m); + + std::nth_element(data.begin(), data.begin() + (data.size () >> 1), data.end()); + return (data[data.size () >> 1]); + } + + /** \brief Use a Huber kernel to estimate the distance between two vectors + * \param[in] p_src the first eigen vector + * \param[in] p_tgt the second eigen vector + * \param[in] sigma the sigma value + */ + inline double + huber (const Eigen::Vector4f &p_src, const Eigen::Vector4f &p_tgt, double sigma) + { + Eigen::Array4f diff = (p_tgt.array () - p_src.array ()).abs (); + double norm = 0.0; + for (int i = 0; i < 3; ++i) + { + if (diff[i] < sigma) + norm += diff[i] * diff[i]; + else + norm += 2.0 * sigma * diff[i] - sigma * sigma; + } + return (norm); + } + + /** \brief Use a Huber kernel to estimate the distance between two vectors + * \param[in] diff the norm difference between two vectors + * \param[in] sigma the sigma value + */ + inline double + huber (double diff, double sigma) + { + double norm = 0.0; + if (diff < sigma) + norm += diff * diff; + else + norm += 2.0 * sigma * diff - sigma * sigma; + return (norm); + } + + /** \brief Use a Gedikli kernel to estimate the distance between two vectors + * (for more information, see + * \param[in] val the norm difference between two vectors + * \param[in] clipping the clipping value + * \param[in] slope the slope. Default: 4 + */ + inline double + gedikli (double val, double clipping, double slope = 4) + { + return (1.0 / (1.0 + pow (fabs(val) / clipping, slope))); + } + + /** \brief Compute the Manhattan distance between two eigen vectors. + * \param[in] p_src the first eigen vector + * \param[in] p_tgt the second eigen vector + */ + inline double + l1 (const Eigen::Vector4f &p_src, const Eigen::Vector4f &p_tgt) + { + return ((p_src.array () - p_tgt.array ()).abs ().sum ()); + } + + /** \brief Compute the Euclidean distance between two eigen vectors. + * \param[in] p_src the first eigen vector + * \param[in] p_tgt the second eigen vector + */ + inline double + l2 (const Eigen::Vector4f &p_src, const Eigen::Vector4f &p_tgt) + { + return ((p_src - p_tgt).norm ()); + } + + /** \brief Compute the squared Euclidean distance between two eigen vectors. + * \param[in] p_src the first eigen vector + * \param[in] p_tgt the second eigen vector + */ + inline double + l2Sqr (const Eigen::Vector4f &p_src, const Eigen::Vector4f &p_tgt) + { + return ((p_src - p_tgt).squaredNorm ()); + } + } +} + +#endif diff --git a/pcl-1.7/pcl/registration/eigen.h b/pcl-1.7/pcl/registration/eigen.h new file mode 100644 index 0000000..fdfa07a --- /dev/null +++ b/pcl-1.7/pcl/registration/eigen.h @@ -0,0 +1,52 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $ + * + */ + +#ifndef PCL_REGISTRATION_EIGEN_H_ +#define PCL_REGISTRATION_EIGEN_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include +#include +#include + +#endif // PCL_REGISTRATION_EIGEN_H_ diff --git a/pcl-1.7/pcl/registration/elch.h b/pcl-1.7/pcl/registration/elch.h new file mode 100644 index 0000000..aa45b3e --- /dev/null +++ b/pcl-1.7/pcl/registration/elch.h @@ -0,0 +1,259 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_ELCH_H_ +#define PCL_ELCH_H_ + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief @b ELCH (Explicit Loop Closing Heuristic) class + * \author Jochen Sprickerhof + * \ingroup registration + */ + template + class ELCH : public PCLBase + { + public: + typedef boost::shared_ptr< ELCH > Ptr; + typedef boost::shared_ptr< const ELCH > ConstPtr; + + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + struct Vertex + { + Vertex () : cloud () {} + PointCloudPtr cloud; + Eigen::Affine3f transform; + }; + + /** \brief graph structure to hold the SLAM graph */ + typedef boost::adjacency_list< + boost::listS, boost::eigen_vecS, boost::undirectedS, + Vertex, + boost::no_property> + LoopGraph; + + typedef boost::shared_ptr< LoopGraph > LoopGraphPtr; + + typedef typename pcl::Registration Registration; + typedef typename Registration::Ptr RegistrationPtr; + typedef typename Registration::ConstPtr RegistrationConstPtr; + + /** \brief Empty constructor. */ + ELCH () : + loop_graph_ (new LoopGraph), + loop_start_ (0), + loop_end_ (0), + reg_ (new pcl::IterativeClosestPoint), + loop_transform_ (), + compute_loop_ (true), + vd_ () + {}; + + /** \brief Empty destructor */ + virtual ~ELCH () {} + + /** \brief Add a new point cloud to the internal graph. + * \param[in] cloud the new point cloud + */ + inline void + addPointCloud (PointCloudPtr cloud) + { + typename boost::graph_traits::vertex_descriptor vd = add_vertex (*loop_graph_); + (*loop_graph_)[vd].cloud = cloud; + if (num_vertices (*loop_graph_) > 1) + add_edge (vd_, vd, *loop_graph_); + vd_ = vd; + } + + /** \brief Getter for the internal graph. */ + inline LoopGraphPtr + getLoopGraph () + { + return (loop_graph_); + } + + /** \brief Setter for a new internal graph. + * \param[in] loop_graph the new graph + */ + inline void + setLoopGraph (LoopGraphPtr loop_graph) + { + loop_graph_ = loop_graph; + } + + /** \brief Getter for the first scan of a loop. */ + inline typename boost::graph_traits::vertex_descriptor + getLoopStart () + { + return (loop_start_); + } + + /** \brief Setter for the first scan of a loop. + * \param[in] loop_start the scan that starts the loop + */ + inline void + setLoopStart (const typename boost::graph_traits::vertex_descriptor &loop_start) + { + loop_start_ = loop_start; + } + + /** \brief Getter for the last scan of a loop. */ + inline typename boost::graph_traits::vertex_descriptor + getLoopEnd () + { + return (loop_end_); + } + + /** \brief Setter for the last scan of a loop. + * \param[in] loop_end the scan that ends the loop + */ + inline void + setLoopEnd (const typename boost::graph_traits::vertex_descriptor &loop_end) + { + loop_end_ = loop_end; + } + + /** \brief Getter for the registration algorithm. */ + inline RegistrationPtr + getReg () + { + return (reg_); + } + + /** \brief Setter for the registration algorithm. + * \param[in] reg the registration algorithm used to compute the transformation between the start and the end of the loop + */ + inline void + setReg (RegistrationPtr reg) + { + reg_ = reg; + } + + /** \brief Getter for the transformation between the first and the last scan. */ + inline Eigen::Matrix4f + getLoopTransform () + { + return (loop_transform_); + } + + /** \brief Setter for the transformation between the first and the last scan. + * \param[in] loop_transform the transformation between the first and the last scan + */ + inline void + setLoopTransform (const Eigen::Matrix4f &loop_transform) + { + loop_transform_ = loop_transform; + compute_loop_ = false; + } + + /** \brief Computes new poses for all point clouds by closing the loop + * between start and end point cloud. This will transform all given point + * clouds for now! + */ + void + compute (); + + protected: + using PCLBase::deinitCompute; + + /** \brief This method should get called before starting the actual computation. */ + virtual bool + initCompute (); + + private: + /** \brief graph structure for the internal optimization graph */ + typedef boost::adjacency_list< + boost::listS, boost::vecS, boost::undirectedS, + boost::no_property, + boost::property< boost::edge_weight_t, double > > + LOAGraph; + + /** + * graph balancer algorithm computes the weights + * @param[in] g the graph + * @param[in] f index of the first node + * @param[in] l index of the last node + * @param[out] weights array for the weights + */ + void + loopOptimizerAlgorithm (LOAGraph &g, double *weights); + + /** \brief The internal loop graph. */ + LoopGraphPtr loop_graph_; + + /** \brief The first scan of the loop. */ + typename boost::graph_traits::vertex_descriptor loop_start_; + + /** \brief The last scan of the loop. */ + typename boost::graph_traits::vertex_descriptor loop_end_; + + /** \brief The registration object used to close the loop. */ + RegistrationPtr reg_; + + /** \brief The transformation between that start and end of the loop. */ + Eigen::Matrix4f loop_transform_; + bool compute_loop_; + + /** \brief previously added node in the loop_graph_. */ + typename boost::graph_traits::vertex_descriptor vd_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } +} + +#include + +#endif // PCL_ELCH_H_ diff --git a/pcl-1.7/pcl/registration/exceptions.h b/pcl-1.7/pcl/registration/exceptions.h new file mode 100644 index 0000000..aacfdf5 --- /dev/null +++ b/pcl-1.7/pcl/registration/exceptions.h @@ -0,0 +1,76 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_EXCEPTIONS_H_ +#define PCL_REGISTRATION_EXCEPTIONS_H_ + +#include + +namespace pcl +{ + /** \class SolverDidntConvergeException + * \brief An exception that is thrown when the non linear solver didn't converge + */ + class PCL_EXPORTS SolverDidntConvergeException : public PCLException + { + public: + + SolverDidntConvergeException (const std::string& error_description, + const std::string& file_name = "", + const std::string& function_name = "" , + unsigned line_number = 0) throw () + : pcl::PCLException (error_description, file_name, function_name, line_number) { } + } ; + + /** \class NotEnoughPointsException + * \brief An exception that is thrown when the number of correspondants is not equal + * to the minimum required + */ + class PCL_EXPORTS NotEnoughPointsException : public PCLException + { + public: + + NotEnoughPointsException (const std::string& error_description, + const std::string& file_name = "", + const std::string& function_name = "" , + unsigned line_number = 0) throw () + : pcl::PCLException (error_description, file_name, function_name, line_number) { } + } ; +} +#endif//PCL_REGISTRATION_EXCEPTIONS_H_ diff --git a/pcl-1.7/pcl/registration/gicp.h b/pcl-1.7/pcl/registration/gicp.h new file mode 100644 index 0000000..a7afb89 --- /dev/null +++ b/pcl-1.7/pcl/registration/gicp.h @@ -0,0 +1,353 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_GICP_H_ +#define PCL_GICP_H_ + +#include +#include + +namespace pcl +{ + /** \brief GeneralizedIterativeClosestPoint is an ICP variant that implements the + * generalized iterative closest point algorithm as described by Alex Segal et al. in + * http://www.stanford.edu/~avsegal/resources/papers/Generalized_ICP.pdf + * The approach is based on using anistropic cost functions to optimize the alignment + * after closest point assignments have been made. + * The original code uses GSL and ANN while in ours we use an eigen mapped BFGS and + * FLANN. + * \author Nizar Sallem + * \ingroup registration + */ + template + class GeneralizedIterativeClosestPoint : public IterativeClosestPoint + { + public: + using IterativeClosestPoint::reg_name_; + using IterativeClosestPoint::getClassName; + using IterativeClosestPoint::indices_; + using IterativeClosestPoint::target_; + using IterativeClosestPoint::input_; + using IterativeClosestPoint::tree_; + using IterativeClosestPoint::tree_reciprocal_; + using IterativeClosestPoint::nr_iterations_; + using IterativeClosestPoint::max_iterations_; + using IterativeClosestPoint::previous_transformation_; + using IterativeClosestPoint::final_transformation_; + using IterativeClosestPoint::transformation_; + using IterativeClosestPoint::transformation_epsilon_; + using IterativeClosestPoint::converged_; + using IterativeClosestPoint::corr_dist_threshold_; + using IterativeClosestPoint::inlier_threshold_; + using IterativeClosestPoint::min_number_correspondences_; + using IterativeClosestPoint::update_visualizer_; + + typedef pcl::PointCloud PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef pcl::PointCloud PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + typedef typename Registration::KdTree InputKdTree; + typedef typename Registration::KdTreePtr InputKdTreePtr; + + typedef boost::shared_ptr< GeneralizedIterativeClosestPoint > Ptr; + typedef boost::shared_ptr< const GeneralizedIterativeClosestPoint > ConstPtr; + + + typedef Eigen::Matrix Vector6d; + + /** \brief Empty constructor. */ + GeneralizedIterativeClosestPoint () + : k_correspondences_(20) + , gicp_epsilon_(0.001) + , rotation_epsilon_(2e-3) + , input_covariances_(0) + , target_covariances_(0) + , mahalanobis_(0) + , max_inner_iterations_(20) + { + min_number_correspondences_ = 4; + reg_name_ = "GeneralizedIterativeClosestPoint"; + max_iterations_ = 200; + transformation_epsilon_ = 5e-4; + corr_dist_threshold_ = 5.; + rigid_transformation_estimation_ = + boost::bind (&GeneralizedIterativeClosestPoint::estimateRigidTransformationBFGS, + this, _1, _2, _3, _4, _5); + } + + /** \brief Provide a pointer to the input dataset + * \param cloud the const boost shared pointer to a PointCloud message + */ + PCL_DEPRECATED ("[pcl::registration::GeneralizedIterativeClosestPoint::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.") + void + setInputCloud (const PointCloudSourceConstPtr &cloud); + + /** \brief Provide a pointer to the input dataset + * \param cloud the const boost shared pointer to a PointCloud message + */ + inline void + setInputSource (const PointCloudSourceConstPtr &cloud) + { + + if (cloud->points.empty ()) + { + PCL_ERROR ("[pcl::%s::setInputSource] Invalid or empty point cloud dataset given!\n", getClassName ().c_str ()); + return; + } + PointCloudSource input = *cloud; + // Set all the point.data[3] values to 1 to aid the rigid transformation + for (size_t i = 0; i < input.size (); ++i) + input[i].data[3] = 1.0; + + pcl::IterativeClosestPoint::setInputSource (cloud); + input_covariances_.clear (); + input_covariances_.reserve (input_->size ()); + } + + /** \brief Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to) + * \param[in] target the input point cloud target + */ + inline void + setInputTarget (const PointCloudTargetConstPtr &target) + { + pcl::IterativeClosestPoint::setInputTarget(target); + target_covariances_.clear (); + target_covariances_.reserve (target_->size ()); + } + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using an iterative + * non-linear Levenberg-Marquardt approach. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the interst points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix + */ + void + estimateRigidTransformationBFGS (const PointCloudSource &cloud_src, + const std::vector &indices_src, + const PointCloudTarget &cloud_tgt, + const std::vector &indices_tgt, + Eigen::Matrix4f &transformation_matrix); + + /** \brief \return Mahalanobis distance matrix for the given point index */ + inline const Eigen::Matrix3d& mahalanobis(size_t index) const + { + assert(index < mahalanobis_.size()); + return mahalanobis_[index]; + } + + /** \brief Computes rotation matrix derivative. + * rotation matrix is obtainded from rotation angles x[3], x[4] and x[5] + * \return d/d_rx, d/d_ry and d/d_rz respectively in g[3], g[4] and g[5] + * param x array representing 3D transformation + * param R rotation matrix + * param g gradient vector + */ + void + computeRDerivative(const Vector6d &x, const Eigen::Matrix3d &R, Vector6d &g) const; + + /** \brief Set the rotation epsilon (maximum allowable difference between two + * consecutive rotations) in order for an optimization to be considered as having + * converged to the final solution. + * \param epsilon the rotation epsilon + */ + inline void + setRotationEpsilon (double epsilon) { rotation_epsilon_ = epsilon; } + + /** \brief Get the rotation epsilon (maximum allowable difference between two + * consecutive rotations) as set by the user. + */ + inline double + getRotationEpsilon () { return (rotation_epsilon_); } + + /** \brief Set the number of neighbors used when selecting a point neighbourhood + * to compute covariances. + * A higher value will bring more accurate covariance matrix but will make + * covariances computation slower. + * \param k the number of neighbors to use when computing covariances + */ + void + setCorrespondenceRandomness (int k) { k_correspondences_ = k; } + + /** \brief Get the number of neighbors used when computing covariances as set by + * the user + */ + int + getCorrespondenceRandomness () { return (k_correspondences_); } + + /** set maximum number of iterations at the optimization step + * \param[in] max maximum number of iterations for the optimizer + */ + void + setMaximumOptimizerIterations (int max) { max_inner_iterations_ = max; } + + ///\return maximum number of iterations at the optimization step + int + getMaximumOptimizerIterations () { return (max_inner_iterations_); } + + protected: + + /** \brief The number of neighbors used for covariances computation. + * default: 20 + */ + int k_correspondences_; + + /** \brief The epsilon constant for gicp paper; this is NOT the convergence + * tolerence + * default: 0.001 + */ + double gicp_epsilon_; + + /** The epsilon constant for rotation error. (In GICP the transformation epsilon + * is split in rotation part and translation part). + * default: 2e-3 + */ + double rotation_epsilon_; + + /** \brief base transformation */ + Eigen::Matrix4f base_transformation_; + + /** \brief Temporary pointer to the source dataset. */ + const PointCloudSource *tmp_src_; + + /** \brief Temporary pointer to the target dataset. */ + const PointCloudTarget *tmp_tgt_; + + /** \brief Temporary pointer to the source dataset indices. */ + const std::vector *tmp_idx_src_; + + /** \brief Temporary pointer to the target dataset indices. */ + const std::vector *tmp_idx_tgt_; + + + /** \brief Input cloud points covariances. */ + std::vector input_covariances_; + + /** \brief Target cloud points covariances. */ + std::vector target_covariances_; + + /** \brief Mahalanobis matrices holder. */ + std::vector mahalanobis_; + + /** \brief maximum number of optimizations */ + int max_inner_iterations_; + + /** \brief compute points covariances matrices according to the K nearest + * neighbors. K is set via setCorrespondenceRandomness() methode. + * \param cloud pointer to point cloud + * \param tree KD tree performer for nearest neighbors search + * \param[out] cloud_covariances covariances matrices for each point in the cloud + */ + template + void computeCovariances(typename pcl::PointCloud::ConstPtr cloud, + const typename pcl::search::KdTree::Ptr tree, + std::vector& cloud_covariances); + + /** \return trace of mat1^t . mat2 + * \param mat1 matrix of dimension nxm + * \param mat2 matrix of dimension nxp + */ + inline double + matricesInnerProd(const Eigen::MatrixXd& mat1, const Eigen::MatrixXd& mat2) const + { + double r = 0.; + size_t n = mat1.rows(); + // tr(mat1^t.mat2) + for(size_t i = 0; i < n; i++) + for(size_t j = 0; j < n; j++) + r += mat1 (j, i) * mat2 (i,j); + return r; + } + + /** \brief Rigid transformation computation method with initial guess. + * \param output the transformed input point cloud dataset using the rigid transformation found + * \param guess the initial guess of the transformation to compute + */ + void + computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess); + + /** \brief Search for the closest nearest neighbor of a given point. + * \param query the point to search a nearest neighbour for + * \param index vector of size 1 to store the index of the nearest neighbour found + * \param distance vector of size 1 to store the distance to nearest neighbour found + */ + inline bool + searchForNeighbors (const PointSource &query, std::vector& index, std::vector& distance) + { + int k = tree_->nearestKSearch (query, 1, index, distance); + if (k == 0) + return (false); + return (true); + } + + /// \brief compute transformation matrix from transformation matrix + void applyState(Eigen::Matrix4f &t, const Vector6d& x) const; + + /// \brief optimization functor structure + struct OptimizationFunctorWithIndices : public BFGSDummyFunctor + { + OptimizationFunctorWithIndices (const GeneralizedIterativeClosestPoint* gicp) + : BFGSDummyFunctor (), gicp_(gicp) {} + double operator() (const Vector6d& x); + void df(const Vector6d &x, Vector6d &df); + void fdf(const Vector6d &x, double &f, Vector6d &df); + + const GeneralizedIterativeClosestPoint *gicp_; + }; + + boost::function &cloud_src, + const std::vector &src_indices, + const pcl::PointCloud &cloud_tgt, + const std::vector &tgt_indices, + Eigen::Matrix4f &transformation_matrix)> rigid_transformation_estimation_; + }; +} + +#include + +#endif //#ifndef PCL_GICP_H_ diff --git a/pcl-1.7/pcl/registration/gicp6d.h b/pcl-1.7/pcl/registration/gicp6d.h new file mode 100644 index 0000000..a722204 --- /dev/null +++ b/pcl-1.7/pcl/registration/gicp6d.h @@ -0,0 +1,210 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_GICP6D_H_ +#define PCL_GICP6D_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + struct EIGEN_ALIGN16 _PointXYZLAB + { + PCL_ADD_POINT4D; // this adds the members x,y,z + union + { + struct + { + float L; + float a; + float b; + }; + float data_lab[4]; + }; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + /** \brief A custom point type for position and CIELAB color value */ + struct PointXYZLAB : public _PointXYZLAB + { + inline PointXYZLAB () + { + x = y = z = 0.0f; data[3] = 1.0f; // important for homogeneous coordinates + L = a = b = 0.0f; data_lab[3] = 0.0f; + } + }; +} + +// register the custom point type in PCL +POINT_CLOUD_REGISTER_POINT_STRUCT(pcl::_PointXYZLAB, + (float, x, x) + (float, y, y) + (float, z, z) + (float, L, L) + (float, a, a) + (float, b, b) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZLAB, pcl::_PointXYZLAB) + +namespace pcl +{ + /** \brief GeneralizedIterativeClosestPoint6D integrates L*a*b* color space information into the + * Generalized Iterative Closest Point (GICP) algorithm. + * + * The suggested input is PointXYZRGBA. + * + * \note If you use this code in any academic work, please cite: + * + * - M. Korn, M. Holzkothen, J. Pauli + * Color Supported Generalized-ICP. + * In Proceedings of VISAPP 2014 - International Conference on Computer Vision Theory and Applications, + * Lisbon, Portugal, January 2014. + * + * \author Martin Holzkothen, Michael Korn + * \ingroup registration + */ + class GeneralizedIterativeClosestPoint6D : public GeneralizedIterativeClosestPoint + { + typedef PointXYZRGBA PointSource; + typedef PointXYZRGBA PointTarget; + + public: + + /** \brief constructor. + * + * \param[in] lab_weight the color weight + */ + GeneralizedIterativeClosestPoint6D (float lab_weight = 0.032f); + + /** \brief Provide a pointer to the input source + * (e.g., the point cloud that we want to align to the target) + * + * \param[in] cloud the input point cloud source + */ + void + setInputSource (const PointCloudSourceConstPtr& cloud); + + /** \brief Provide a pointer to the input target + * (e.g., the point cloud that we want to align the input source to) + * + * \param[in] cloud the input point cloud target + */ + void + setInputTarget (const PointCloudTargetConstPtr& target); + + protected: + + /** \brief Rigid transformation computation method with initial guess. + * \param output the transformed input point cloud dataset using the rigid transformation found + * \param guess the initial guess of the transformation to compute + */ + void + computeTransformation (PointCloudSource& output, + const Eigen::Matrix4f& guess); + + /** \brief Search for the closest nearest neighbor of a given point. + * \param query the point to search a nearest neighbour for + * \param index vector of size 1 to store the index of the nearest neighbour found + * \param distance vector of size 1 to store the distance to nearest neighbour found + */ + inline bool + searchForNeighbors (const PointXYZLAB& query, std::vector& index, std::vector& distance); + + protected: + /** \brief Holds the converted (LAB) data cloud. */ + pcl::PointCloud::Ptr cloud_lab_; + + /** \brief Holds the converted (LAB) model cloud. */ + pcl::PointCloud::Ptr target_lab_; + + /** \brief 6d-tree to search in model cloud. */ + KdTreeFLANN target_tree_lab_; + + /** \brief The color weight. */ + float lab_weight_; + + /** \brief Custom point representation to perform kdtree searches in more than 3 (i.e. in all 6) dimensions. */ + class MyPointRepresentation : public PointRepresentation + { + using PointRepresentation::nr_dimensions_; + using PointRepresentation::trivial_; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + MyPointRepresentation () + { + nr_dimensions_ = 6; + trivial_ = false; + } + + virtual + ~MyPointRepresentation () + { + } + + inline Ptr + makeShared () const + { + return Ptr (new MyPointRepresentation (*this)); + } + + virtual void + copyToFloatArray (const PointXYZLAB &p, float * out) const + { + // copy all of the six values + out[0] = p.x; + out[1] = p.y; + out[2] = p.z; + out[3] = p.L; + out[4] = p.a; + out[5] = p.b; + } + }; + + /** \brief Enables 6d searches with kd-tree class using the color weight. */ + MyPointRepresentation point_rep_; + }; +} + +#endif //#ifndef PCL_GICP6D_H_ diff --git a/pcl-1.7/pcl/registration/ia_ransac.h b/pcl-1.7/pcl/registration/ia_ransac.h new file mode 100644 index 0000000..01888cf --- /dev/null +++ b/pcl-1.7/pcl/registration/ia_ransac.h @@ -0,0 +1,281 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef IA_RANSAC_H_ +#define IA_RANSAC_H_ + +#include +#include + +namespace pcl +{ + /** \brief @b SampleConsensusInitialAlignment is an implementation of the initial alignment algorithm described in + * section IV of "Fast Point Feature Histograms (FPFH) for 3D Registration," Rusu et al. + * \author Michael Dixon, Radu B. Rusu + * \ingroup registration + */ + template + class SampleConsensusInitialAlignment : public Registration + { + public: + using Registration::reg_name_; + using Registration::input_; + using Registration::indices_; + using Registration::target_; + using Registration::final_transformation_; + using Registration::transformation_; + using Registration::corr_dist_threshold_; + using Registration::min_number_correspondences_; + using Registration::max_iterations_; + using Registration::tree_; + using Registration::transformation_estimation_; + using Registration::converged_; + using Registration::getClassName; + + typedef typename Registration::PointCloudSource PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef typename Registration::PointCloudTarget PointCloudTarget; + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + typedef pcl::PointCloud FeatureCloud; + typedef typename FeatureCloud::Ptr FeatureCloudPtr; + typedef typename FeatureCloud::ConstPtr FeatureCloudConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + + class ErrorFunctor + { + public: + virtual ~ErrorFunctor () {} + virtual float operator () (float d) const = 0; + }; + + class HuberPenalty : public ErrorFunctor + { + private: + HuberPenalty () {} + public: + HuberPenalty (float threshold) : threshold_ (threshold) {} + virtual float operator () (float e) const + { + if (e <= threshold_) + return (0.5 * e*e); + else + return (0.5 * threshold_ * (2.0 * fabs (e) - threshold_)); + } + protected: + float threshold_; + }; + + class TruncatedError : public ErrorFunctor + { + private: + TruncatedError () {} + public: + virtual ~TruncatedError () {} + + TruncatedError (float threshold) : threshold_ (threshold) {} + virtual float operator () (float e) const + { + if (e <= threshold_) + return (e / threshold_); + else + return (1.0); + } + protected: + float threshold_; + }; + + typedef typename KdTreeFLANN::Ptr FeatureKdTreePtr; + /** \brief Constructor. */ + SampleConsensusInitialAlignment () : + input_features_ (), target_features_ (), + nr_samples_(3), min_sample_distance_ (0.0f), k_correspondences_ (10), + feature_tree_ (new pcl::KdTreeFLANN), + error_functor_ () + { + reg_name_ = "SampleConsensusInitialAlignment"; + max_iterations_ = 1000; + + // Setting a non-std::numeric_limits::max () value to corr_dist_threshold_ to make it play nicely with TruncatedError + corr_dist_threshold_ = 100.0f; + transformation_estimation_.reset (new pcl::registration::TransformationEstimationSVD); + }; + + /** \brief Provide a boost shared pointer to the source point cloud's feature descriptors + * \param features the source point cloud's features + */ + void + setSourceFeatures (const FeatureCloudConstPtr &features); + + /** \brief Get a pointer to the source point cloud's features */ + inline FeatureCloudConstPtr const + getSourceFeatures () { return (input_features_); } + + /** \brief Provide a boost shared pointer to the target point cloud's feature descriptors + * \param features the target point cloud's features + */ + void + setTargetFeatures (const FeatureCloudConstPtr &features); + + /** \brief Get a pointer to the target point cloud's features */ + inline FeatureCloudConstPtr const + getTargetFeatures () { return (target_features_); } + + /** \brief Set the minimum distances between samples + * \param min_sample_distance the minimum distances between samples + */ + void + setMinSampleDistance (float min_sample_distance) { min_sample_distance_ = min_sample_distance; } + + /** \brief Get the minimum distances between samples, as set by the user */ + float + getMinSampleDistance () { return (min_sample_distance_); } + + /** \brief Set the number of samples to use during each iteration + * \param nr_samples the number of samples to use during each iteration + */ + void + setNumberOfSamples (int nr_samples) { nr_samples_ = nr_samples; } + + /** \brief Get the number of samples to use during each iteration, as set by the user */ + int + getNumberOfSamples () { return (nr_samples_); } + + /** \brief Set the number of neighbors to use when selecting a random feature correspondence. A higher value will + * add more randomness to the feature matching. + * \param k the number of neighbors to use when selecting a random feature correspondence. + */ + void + setCorrespondenceRandomness (int k) { k_correspondences_ = k; } + + /** \brief Get the number of neighbors used when selecting a random feature correspondence, as set by the user */ + int + getCorrespondenceRandomness () { return (k_correspondences_); } + + /** \brief Specify the error function to minimize + * \note This call is optional. TruncatedError will be used by default + * \param[in] error_functor a shared pointer to a subclass of SampleConsensusInitialAlignment::ErrorFunctor + */ + void + setErrorFunction (const boost::shared_ptr & error_functor) { error_functor_ = error_functor; } + + /** \brief Get a shared pointer to the ErrorFunctor that is to be minimized + * \return A shared pointer to a subclass of SampleConsensusInitialAlignment::ErrorFunctor + */ + boost::shared_ptr + getErrorFunction () { return (error_functor_); } + + protected: + /** \brief Choose a random index between 0 and n-1 + * \param n the number of possible indices to choose from + */ + inline int + getRandomIndex (int n) { return (static_cast (n * (rand () / (RAND_MAX + 1.0)))); }; + + /** \brief Select \a nr_samples sample points from cloud while making sure that their pairwise distances are + * greater than a user-defined minimum distance, \a min_sample_distance. + * \param cloud the input point cloud + * \param nr_samples the number of samples to select + * \param min_sample_distance the minimum distance between any two samples + * \param sample_indices the resulting sample indices + */ + void + selectSamples (const PointCloudSource &cloud, int nr_samples, float min_sample_distance, + std::vector &sample_indices); + + /** \brief For each of the sample points, find a list of points in the target cloud whose features are similar to + * the sample points' features. From these, select one randomly which will be considered that sample point's + * correspondence. + * \param input_features a cloud of feature descriptors + * \param sample_indices the indices of each sample point + * \param corresponding_indices the resulting indices of each sample's corresponding point in the target cloud + */ + void + findSimilarFeatures (const FeatureCloud &input_features, const std::vector &sample_indices, + std::vector &corresponding_indices); + + /** \brief An error metric for that computes the quality of the alignment between the given cloud and the target. + * \param cloud the input cloud + * \param threshold distances greater than this value are capped + */ + float + computeErrorMetric (const PointCloudSource &cloud, float threshold); + + /** \brief Rigid transformation computation method. + * \param output the transformed input point cloud dataset using the rigid transformation found + * \param guess The computed transforamtion + */ + virtual void + computeTransformation (PointCloudSource &output, const Eigen::Matrix4f& guess); + + /** \brief The source point cloud's feature descriptors. */ + FeatureCloudConstPtr input_features_; + + /** \brief The target point cloud's feature descriptors. */ + FeatureCloudConstPtr target_features_; + + /** \brief The number of samples to use during each iteration. */ + int nr_samples_; + + /** \brief The minimum distances between samples. */ + float min_sample_distance_; + + /** \brief The number of neighbors to use when selecting a random feature correspondence. */ + int k_correspondences_; + + /** \brief The KdTree used to compare feature descriptors. */ + FeatureKdTreePtr feature_tree_; + + /** */ + boost::shared_ptr error_functor_; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#include + +#endif //#ifndef IA_RANSAC_H_ diff --git a/pcl-1.7/pcl/registration/icp.h b/pcl-1.7/pcl/registration/icp.h new file mode 100644 index 0000000..61e2f47 --- /dev/null +++ b/pcl-1.7/pcl/registration/icp.h @@ -0,0 +1,392 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_ICP_H_ +#define PCL_ICP_H_ + +// PCL includes +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +namespace pcl +{ + /** \brief @b IterativeClosestPoint provides a base implementation of the Iterative Closest Point algorithm. + * The transformation is estimated based on Singular Value Decomposition (SVD). + * + * The algorithm has several termination criteria: + * + *
    + *
  1. Number of iterations has reached the maximum user imposed number of iterations (via \ref setMaximumIterations)
  2. + *
  3. The epsilon (difference) between the previous transformation and the current estimated transformation is smaller than an user imposed value (via \ref setTransformationEpsilon)
  4. + *
  5. The sum of Euclidean squared errors is smaller than a user defined threshold (via \ref setEuclideanFitnessEpsilon)
  6. + *
+ * + * + * Usage example: + * \code + * IterativeClosestPoint icp; + * // Set the input source and target + * icp.setInputCloud (cloud_source); + * icp.setInputTarget (cloud_target); + * + * // Set the max correspondence distance to 5cm (e.g., correspondences with higher distances will be ignored) + * icp.setMaxCorrespondenceDistance (0.05); + * // Set the maximum number of iterations (criterion 1) + * icp.setMaximumIterations (50); + * // Set the transformation epsilon (criterion 2) + * icp.setTransformationEpsilon (1e-8); + * // Set the euclidean distance difference epsilon (criterion 3) + * icp.setEuclideanFitnessEpsilon (1); + * + * // Perform the alignment + * icp.align (cloud_source_registered); + * + * // Obtain the transformation that aligned cloud_source to cloud_source_registered + * Eigen::Matrix4f transformation = icp.getFinalTransformation (); + * \endcode + * + * \author Radu B. Rusu, Michael Dixon + * \ingroup registration + */ + template + class IterativeClosestPoint : public Registration + { + public: + typedef typename Registration::PointCloudSource PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef typename Registration::PointCloudTarget PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using Registration::reg_name_; + using Registration::getClassName; + using Registration::setInputSource; + using Registration::input_; + using Registration::indices_; + using Registration::target_; + using Registration::nr_iterations_; + using Registration::max_iterations_; + using Registration::previous_transformation_; + using Registration::final_transformation_; + using Registration::transformation_; + using Registration::transformation_epsilon_; + using Registration::converged_; + using Registration::corr_dist_threshold_; + using Registration::inlier_threshold_; + using Registration::min_number_correspondences_; + using Registration::update_visualizer_; + using Registration::euclidean_fitness_epsilon_; + using Registration::correspondences_; + using Registration::transformation_estimation_; + using Registration::correspondence_estimation_; + using Registration::correspondence_rejectors_; + + typename pcl::registration::DefaultConvergenceCriteria::Ptr convergence_criteria_; + typedef typename Registration::Matrix4 Matrix4; + + /** \brief Empty constructor. */ + IterativeClosestPoint () + : x_idx_offset_ (0) + , y_idx_offset_ (0) + , z_idx_offset_ (0) + , nx_idx_offset_ (0) + , ny_idx_offset_ (0) + , nz_idx_offset_ (0) + , use_reciprocal_correspondence_ (false) + , source_has_normals_ (false) + , target_has_normals_ (false) + , approx_nn_ops_num_(0.0) + , approx_leaders_num_(0) + , approx_followers_num_(0) + { + reg_name_ = "IterativeClosestPoint"; + /* different transformation estimation methods */ + transformation_estimation_.reset (new pcl::registration::TransformationEstimationPointToPlaneLLS ()); + // transformation_estimation_.reset (new pcl::registration::TransformationEstimationSVD ()); + + /* different correspondence estimation methods */ + correspondence_estimation_.reset (new pcl::registration::CorrespondenceEstimation); + // correspondence_estimation_.reset (new pcl::registration::CorrespondenceEstimationNormalShooting); + + convergence_criteria_.reset(new pcl::registration::DefaultConvergenceCriteria (nr_iterations_, transformation_, *correspondences_)); + + // To-do: add ransac here or out there + // pcl::registration::CorrespondenceRejector::Ptr ransac_rej \ + // (pcl::registration::CorrespondenceRejectorSampleConsensus ()); + + }; + + /** \brief Empty destructor */ + virtual ~IterativeClosestPoint () {} + + /** \brief Returns a pointer to the DefaultConvergenceCriteria used by the IterativeClosestPoint class. + * This allows to check the convergence state after the align() method as well as to configure + * DefaultConvergenceCriteria's parameters not available through the ICP API before the align() + * method is called. Please note that the align method sets max_iterations_, + * euclidean_fitness_epsilon_ and transformation_epsilon_ and therefore overrides the default / set + * values of the DefaultConvergenceCriteria instance. + * \return Pointer to the IterativeClosestPoint's DefaultConvergenceCriteria. + */ + inline typename pcl::registration::DefaultConvergenceCriteria::Ptr + getConvergeCriteria () + { + return convergence_criteria_; + } + + /** \brief Provide a pointer to the input source + * (e.g., the point cloud that we want to align to the target) + * + * \param[in] cloud the input point cloud source + */ + virtual void + setInputSource (const PointCloudSourceConstPtr &cloud) + { + Registration::setInputSource (cloud); + std::vector fields; + pcl::getFields (*cloud, fields); + source_has_normals_ = false; + for (size_t i = 0; i < fields.size (); ++i) + { + if (fields[i].name == "x") x_idx_offset_ = fields[i].offset; + else if (fields[i].name == "y") y_idx_offset_ = fields[i].offset; + else if (fields[i].name == "z") z_idx_offset_ = fields[i].offset; + else if (fields[i].name == "normal_x") + { + source_has_normals_ = true; + nx_idx_offset_ = fields[i].offset; + } + else if (fields[i].name == "normal_y") + { + source_has_normals_ = true; + ny_idx_offset_ = fields[i].offset; + } + else if (fields[i].name == "normal_z") + { + source_has_normals_ = true; + nz_idx_offset_ = fields[i].offset; + } + } + } + + /** \brief Provide a pointer to the input target + * (e.g., the point cloud that we want to align to the target) + * + * \param[in] cloud the input point cloud target + */ + virtual void + setInputTarget (const PointCloudTargetConstPtr &cloud) + { + Registration::setInputTarget (cloud); + std::vector fields; + pcl::getFields (*cloud, fields); + target_has_normals_ = false; + for (size_t i = 0; i < fields.size (); ++i) + { + if (fields[i].name == "normal_x" || fields[i].name == "normal_y" || fields[i].name == "normal_z") + { + target_has_normals_ = true; + break; + } + } + } + + /** \brief Set whether to use reciprocal correspondence or not + * + * \param[in] use_reciprocal_correspondence whether to use reciprocal correspondence or not + */ + inline void + setUseReciprocalCorrespondences (bool use_reciprocal_correspondence) + { + use_reciprocal_correspondence_ = use_reciprocal_correspondence; + } + + /** \brief Obtain whether reciprocal correspondence are used or not */ + inline bool + getUseReciprocalCorrespondences () const + { + return (use_reciprocal_correspondence_); + } + + inline void setSaveApproxData(bool save) + { + correspondence_estimation_->setSaveApproxData(save); + } + + inline void setUseCustomizedKDTree(bool use) + { + correspondence_estimation_->setUseCustomizedKDTree(use); + } + + inline void setMaxLeafSize(int size) + { + correspondence_estimation_->setMaxLeafSize(size); + } + + inline void setApproxNNPara(float approx_nn_para) + { + correspondence_estimation_->setApproxNNPara(approx_nn_para); + } + + inline int getIterNumber() { return nr_iterations_; } + inline int getApproxNNOpsNum() { return approx_nn_ops_num_; } + inline int getApproxLeadersNum() { return approx_leaders_num_; } + inline int getApproxFollowersNum() { return approx_followers_num_; } + + + protected: + + /** \brief Apply a rigid transform to a given dataset. Here we check whether whether + * the dataset has surface normals in addition to XYZ, and rotate normals as well. + * \param[in] input the input point cloud + * \param[out] output the resultant output point cloud + * \param[in] transform a 4x4 rigid transformation + * \note Can be used with cloud_in equal to cloud_out + */ + virtual void + transformCloud (const PointCloudSource &input, + PointCloudSource &output, + const Matrix4 &transform); + + /** \brief Rigid transformation computation method with initial guess. + * \param output the transformed input point cloud dataset using the rigid transformation found + * \param guess the initial guess of the transformation to compute + */ + virtual void + computeTransformation (PointCloudSource &output, const Matrix4 &guess); + + /** \brief Looks at the Estimators and Rejectors and determines whether their blob-setter methods need to be called */ + virtual void + determineRequiredBlobData (); + + /** \brief XYZ fields offset. */ + size_t x_idx_offset_, y_idx_offset_, z_idx_offset_; + + /** \brief Normal fields offset. */ + size_t nx_idx_offset_, ny_idx_offset_, nz_idx_offset_; + + /** \brief The correspondence type used for correspondence estimation. */ + bool use_reciprocal_correspondence_; + + /** \brief Internal check whether source dataset has normals or not. */ + bool source_has_normals_; + /** \brief Internal check whether target dataset has normals or not. */ + bool target_has_normals_; + + /** \brief Checks for whether estimators and rejectors need various data */ + bool need_source_blob_, need_target_blob_; + + /** Number of operations in the approximation search **/ + int approx_nn_ops_num_; + + /** Number of leaders in the approximation search **/ + int approx_leaders_num_; + + /** Number of followers in the approximation search **/ + int approx_followers_num_; + }; + + /** \brief @b IterativeClosestPointWithNormals is a special case of + * IterativeClosestPoint, that uses a transformation estimated based on + * Point to Plane distances by default. + * + * \author Radu B. Rusu + * \ingroup registration + */ + template + class IterativeClosestPointWithNormals : public IterativeClosestPoint + { + public: + typedef typename IterativeClosestPoint::PointCloudSource PointCloudSource; + typedef typename IterativeClosestPoint::PointCloudTarget PointCloudTarget; + typedef typename IterativeClosestPoint::Matrix4 Matrix4; + + using IterativeClosestPoint::reg_name_; + using IterativeClosestPoint::transformation_estimation_; + using IterativeClosestPoint::correspondence_rejectors_; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Empty constructor. */ + IterativeClosestPointWithNormals () + { + reg_name_ = "IterativeClosestPointWithNormals"; + transformation_estimation_.reset (new pcl::registration::TransformationEstimationPointToPlaneLLS ()); + //correspondence_rejectors_.add + }; + + /** \brief Empty destructor */ + virtual ~IterativeClosestPointWithNormals () {} + + protected: + + /** \brief Apply a rigid transform to a given dataset + * \param[in] input the input point cloud + * \param[out] output the resultant output point cloud + * \param[in] transform a 4x4 rigid transformation + * \note Can be used with cloud_in equal to cloud_out + */ + virtual void + transformCloud (const PointCloudSource &input, + PointCloudSource &output, + const Matrix4 &transform); + }; +} + +#include + +#endif //#ifndef PCL_ICP_H_ diff --git a/pcl-1.7/pcl/registration/icp_nl.h b/pcl-1.7/pcl/registration/icp_nl.h new file mode 100644 index 0000000..dce8a8e --- /dev/null +++ b/pcl-1.7/pcl/registration/icp_nl.h @@ -0,0 +1,108 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_ICP_NL_H_ +#define PCL_ICP_NL_H_ + +// PCL includes +#include +#include + +namespace pcl +{ + /** \brief @b IterativeClosestPointNonLinear is an ICP variant that uses Levenberg-Marquardt optimization + * backend. The resultant transformation is optimized as a quaternion. + * + * The algorithm has several termination criteria: + * + *
    + *
  1. Number of iterations has reached the maximum user imposed number of iterations + * (via \ref setMaximumIterations)
  2. + *
  3. The epsilon (difference) between the previous transformation and the current estimated transformation is + * smaller than an user imposed value (via \ref setTransformationEpsilon)
  4. + *
  5. The sum of Euclidean squared errors is smaller than a user defined threshold + * (via \ref setEuclideanFitnessEpsilon)
  6. + *
+ * + * \author Radu B. Rusu, Michael Dixon + * \ingroup registration + */ + template + class IterativeClosestPointNonLinear : public IterativeClosestPoint + { + using IterativeClosestPoint::min_number_correspondences_; + using IterativeClosestPoint::reg_name_; + using IterativeClosestPoint::transformation_estimation_; + using IterativeClosestPoint::computeTransformation; + + public: + + typedef boost::shared_ptr< IterativeClosestPointNonLinear > Ptr; + typedef boost::shared_ptr< const IterativeClosestPointNonLinear > ConstPtr; + + typedef typename Registration::Matrix4 Matrix4; + + /** \brief Empty constructor. */ + IterativeClosestPointNonLinear () + { + // build_tree_t_icp_ = 0.0; + // nn_time_icp_ = 0.0; + min_number_correspondences_ = 4; + reg_name_ = "IterativeClosestPointNonLinear"; + + transformation_estimation_.reset (new pcl::registration::TransformationEstimationLM); + } + + // // kdtree building time + // inline void getBuildTime_icp(float &build_time) + // { + // build_time = build_tree_t_icp_; + // } + + // // nn search time + // inline void getNnTime_icp(float &nn_time) + // { + // nn_time = nn_time_icp_; + // } + + }; +} + +#endif //#ifndef PCL_ICP_NL_H_ diff --git a/pcl-1.7/pcl/registration/impl/correspondence_estimation.hpp b/pcl-1.7/pcl/registration/impl/correspondence_estimation.hpp new file mode 100644 index 0000000..b3d3b20 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_estimation.hpp @@ -0,0 +1,417 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_ESTIMATION_H_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_ESTIMATION_H_ + +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceEstimationBase::setInputCloud (const typename pcl::registration::CorrespondenceEstimationBase::PointCloudSourceConstPtr &cloud) +{ + // PCL_ERROR("setInputCloud\n"); + setInputSource (cloud); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::registration::CorrespondenceEstimationBase::PointCloudSourceConstPtr const +pcl::registration::CorrespondenceEstimationBase::getInputCloud () +{ + return (getInputSource ()); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceEstimationBase::setInputTarget ( + const PointCloudTargetConstPtr &cloud) +{ + if (cloud->points.empty ()) + { + PCL_ERROR ("[pcl::registration::%s::setInputTarget] Invalid or empty point cloud dataset given!\n", getClassName ().c_str ()); + return; + } + target_ = cloud; + + // Set the internal point representation of choice + if (point_representation_) + tree_->setPointRepresentation (point_representation_); + + target_cloud_updated_ = true; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::registration::CorrespondenceEstimationBase::initCompute () +{ + if (!target_) + { + PCL_ERROR ("[pcl::registration::%s::compute] No input target dataset was given!\n", getClassName ().c_str ()); + return (false); + } + + // Only update target kd-tree if a new target cloud was set + if (target_cloud_updated_ && !force_no_recompute_) + { + if(!use_customized_tree_) + { /** Use FLANN **/ + if (target_indices_) tree_->setInputCloud (target_, target_indices_); + else tree_->setInputCloud (target_); + + target_cloud_updated_ = false; + } + else + { /** Use the customized tree only for 3-d points. **/ + if (std::is_same::value || + std::is_same::value) + { + /** Initialize the data structure used by the customized tree. **/ + points_target_.clear(); + for(size_t i = 0; i < target_->size(); i++) + { + Point point; + point.x = (*target_)[i].data[0]; + point.y = (*target_)[i].data[1]; + point.z = (*target_)[i].data[2]; + + points_target_.push_back(point); + } + points_target_ptr_ = &points_target_; + + // Initialize indices + if(target_indices_) + { /** if the target indices are given **/ + index_target_.clear(); + for(size_t i = 0; i < target_indices_->size(); i++) + index_target_.push_back((*target_indices_)[i]); + } + else + { + index_target_.clear(); + for(size_t i = 0; i < target_->size(); i++) + index_target_.push_back(i); + } + index_target_ptr_ = &index_target_; + + if (treeH_target_) delete treeH_target_; + buildHKdTree_target(); + } + else + { + PCL_ERROR ("Customized KD-Tree Only Accept Data with Three Dimensions!\n"); + exit(-1); + } + } + } + + return (PCLBase::initCompute ()); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::registration::CorrespondenceEstimationBase::initComputeReciprocal () +{ + // Only update source kd-tree if a new target cloud was set + if (source_cloud_updated_ && !force_no_recompute_reciprocal_) + { + if (!use_customized_tree_) + { + if (point_representation_) + tree_reciprocal_->setPointRepresentation (point_representation_); + // If the target indices have been given via setIndicesTarget + if (indices_) + tree_reciprocal_->setInputCloud (getInputSource(), getIndicesSource()); + else + tree_reciprocal_->setInputCloud (getInputSource()); + + source_cloud_updated_ = false; + } + + else + { + // Only for 3-d points. + if (std::is_same::value || + std::is_same::value) + { + points_src_.clear(); + for(size_t i = 0; i < input_->size(); i++) + { + Point point; + point.x = ((*input_)[i]).data[0]; + point.y = ((*input_)[i]).data[1]; + point.z = ((*input_)[i]).data[2]; + + points_src_.push_back(point); + } + points_src_ptr_ = &points_src_; + + // Initialize indices + if(indices_) + { + index_src_.clear(); + for(size_t i = 0; i < indices_->size(); i++) + index_src_.push_back((*indices_)[i]); + } + else + { + index_src_.clear(); + for(size_t i = 0; i < input_->size(); i++) + index_src_.push_back(i); + } + index_src_ptr_ = &index_src_; + + if (treeH_source_) delete treeH_source_; + buildHKdTree_source(); + } + else + { + PCL_ERROR ("The customized KD-Tree Only Accept Data with Three Dimensions!\n"); + exit(-1); + } + } + } + + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceEstimation::determineCorrespondences ( + pcl::Correspondences &correspondences, double max_distance) +{ + if (!initCompute ()) + return; + + double max_dist_sqr = max_distance * max_distance; + + correspondences.resize (indices_->size ()); + + int Search_K = 1; + + std::vector index (Search_K); + std::vector distance (Search_K); + pcl::Correspondence corr; + unsigned int nr_valid_correspondences = 0; + + int back_track = 0; + + // Check if the template types are the same. If true, avoid a copy. + // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT macro! + if (isSamePointType ()) + { + // Iterate over the input set of source indices + for (std::vector::const_iterator idx = indices_->begin (); \ + idx != indices_->end (); ++idx) + { + if (use_customized_tree_) + { + if (std::is_same::value || + std::is_same::value) + { + // Only for 3-d points + // reason: currently the implementation does not support + // high dimensional tree building and searching + + Point query; + query.x = (input_->points[*idx]).data[0]; + query.y = (input_->points[*idx]).data[1]; + query.z = (input_->points[*idx]).data[2]; + + // !!! Be sure to add these two lines. + index.resize(0); + distance.resize(0); + + back_track += treeH_target_->nearestKSearchApprox(query, 1, index, distance); + // currently, our implementation only support the nearest neighbor search + // i.e., K == 1 + } + else + { + PCL_ERROR ("The customized KD-Tree Only Accept Data with Three Dimensions!\n"); + exit(-1); + } + } + else + { /** Use FLANN **/ + tree_->nearestKSearch (input_->points[*idx], Search_K, index, distance); + } + + if (distance[0] > max_dist_sqr) + continue; + + corr.index_query = *idx; + corr.index_match = index[0]; // the nearest neighbor + corr.distance = distance[0]; // the nearest neighbor + correspondences[nr_valid_correspondences++] = corr; + } + if ((std::is_same::value || + std::is_same::value) && save_approx_data_) + { + approx_nn_ops_num_ += treeH_target_->approx_nn_ops_num_; + approx_leaders_num_ += treeH_target_->approx_leaders_num_; + approx_followers_num_ += treeH_target_->approx_followers_num_; + } + } + else {} + + correspondences.resize (nr_valid_correspondences); + deinitCompute (); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceEstimation::determineReciprocalCorrespondences ( + pcl::Correspondences &correspondences, double max_distance) +{ + if (!initCompute ()) + return; + + if (!initComputeReciprocal()) + return; + + double max_dist_sqr = max_distance * max_distance; + correspondences.resize (indices_->size()); + + int search_K = 1; + + std::vector index (search_K); + std::vector distance (search_K); + std::vector index_reciprocal (search_K); + std::vector distance_reciprocal (search_K); + + pcl::Correspondence corr; + unsigned int nr_valid_correspondences = 0; + + int target_idx = 0; + int back_track = 0; + + // Check if the template types are the same. If true, avoid a copy. + // Both point types MUST be registered using the + // POINT_CLOUD_REGISTER_POINT_STRUCT macro! + if (isSamePointType ()) + { + for (std::vector::const_iterator idx = indices_->begin (); idx != indices_->end (); ++idx) + { + if (use_customized_tree_) + { + if (std::is_same::value || + std::is_same::value) + { + // Only the customized tree for 3-d points + Point query; + query.x = (input_->points[*idx]).data[0]; + query.y = (input_->points[*idx]).data[1]; + query.z = (input_->points[*idx]).data[2]; + + index.resize(0); + distance.resize(0); + + back_track += treeH_target_->nearestKSearchApprox(query, search_K, index, distance); + } + else + { + PCL_ERROR ("The customized KD-Tree Only Accept Data with Three Dimensions!\n"); + exit(-1); + } + } + else + tree_->nearestKSearch (input_->points[*idx], search_K, index, distance); + + if (distance[0] > max_dist_sqr) + continue; + target_idx = index[0]; + + //------------------Reciprocal Search ------------------------------- + if (use_customized_tree_) + { + // Only for 3-d points + if (std::is_same::value || + std::is_same::value) + { + Point query; + query.x = (target_->points[target_idx]).data[0]; + query.y = (target_->points[target_idx]).data[1]; + query.z = (target_->points[target_idx]).data[2]; + + index_reciprocal.resize(0); + distance_reciprocal.resize(0); + + back_track += treeH_source_->nearestKSearchApprox(query, search_K, index_reciprocal, distance_reciprocal); + } + else + { + PCL_ERROR ("The customized KD-Tree Only Accept Data with Three Dimensions!\n"); + exit(-1); + } + } + else + { + tree_reciprocal_->nearestKSearch (target_->points[target_idx], search_K, \ + index_reciprocal, distance_reciprocal); + } + + // If not reciprocal: throw away + if (distance_reciprocal[0] > max_dist_sqr || *idx != index_reciprocal[0]) + continue; + + corr.index_query = *idx; + corr.index_match = index[0]; + corr.distance = distance[0]; + correspondences[nr_valid_correspondences++] = corr; + } + + if ((std::is_same::value || + std::is_same::value) && save_approx_data_) + { + approx_nn_ops_num_ += treeH_target_->approx_nn_ops_num_; + approx_nn_ops_num_ += treeH_source_->approx_nn_ops_num_; + approx_leaders_num_ += treeH_target_->approx_leaders_num_; + approx_leaders_num_ += treeH_source_->approx_leaders_num_; + approx_followers_num_ += treeH_target_->approx_followers_num_; + approx_followers_num_ += treeH_source_->approx_followers_num_; + } + } + else { } + + correspondences.resize (nr_valid_correspondences); + deinitCompute (); +} + +#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_ESTIMATION_H_ */ \ No newline at end of file diff --git a/pcl-1.7/pcl/registration/impl/correspondence_estimation_backprojection.hpp b/pcl-1.7/pcl/registration/impl/correspondence_estimation_backprojection.hpp new file mode 100644 index 0000000..7284f3e --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_estimation_backprojection.hpp @@ -0,0 +1,274 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_ESTIMATION_BACK_PROJECTION_HPP_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_ESTIMATION_BACK_PROJECTION_HPP_ + +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::registration::CorrespondenceEstimationBackProjection::initCompute () +{ + if (!source_normals_ || !target_normals_) + { + PCL_WARN ("[pcl::registration::%s::initCompute] Datasets containing normals for source/target have not been given!\n", getClassName ().c_str ()); + return (false); + } + + return (CorrespondenceEstimationBase::initCompute ()); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceEstimationBackProjection::determineCorrespondences ( + pcl::Correspondences &correspondences, double max_distance) +{ + if (!initCompute ()) + return; + + correspondences.resize (indices_->size ()); + + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + float min_dist = std::numeric_limits::max (); + int min_index = 0; + + pcl::Correspondence corr; + unsigned int nr_valid_correspondences = 0; + + // Check if the template types are the same. If true, avoid a copy. + // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT macro! + if (isSamePointType ()) + { + PointTarget pt; + // Iterate over the input set of source indices + for (std::vector::const_iterator idx_i = indices_->begin (); idx_i != indices_->end (); ++idx_i) + { + tree_->nearestKSearch (input_->points[*idx_i], k_, nn_indices, nn_dists); + + // Among the K nearest neighbours find the one with minimum perpendicular distance to the normal + min_dist = std::numeric_limits::max (); + + // Find the best correspondence + for (size_t j = 0; j < nn_indices.size (); j++) + { + float cos_angle = source_normals_->points[*idx_i].normal_x * target_normals_->points[nn_indices[j]].normal_x + + source_normals_->points[*idx_i].normal_y * target_normals_->points[nn_indices[j]].normal_y + + source_normals_->points[*idx_i].normal_z * target_normals_->points[nn_indices[j]].normal_z ; + float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle); + + if (dist < min_dist) + { + min_dist = dist; + min_index = static_cast (j); + } + } + if (min_dist > max_distance) + continue; + + corr.index_query = *idx_i; + corr.index_match = nn_indices[min_index]; + corr.distance = nn_dists[min_index];//min_dist; + correspondences[nr_valid_correspondences++] = corr; + } + } + else + { + PointTarget pt; + + // Iterate over the input set of source indices + for (std::vector::const_iterator idx_i = indices_->begin (); idx_i != indices_->end (); ++idx_i) + { + tree_->nearestKSearch (input_->points[*idx_i], k_, nn_indices, nn_dists); + + // Among the K nearest neighbours find the one with minimum perpendicular distance to the normal + min_dist = std::numeric_limits::max (); + + // Find the best correspondence + for (size_t j = 0; j < nn_indices.size (); j++) + { + PointSource pt_src; + // Copy the source data to a target PointTarget format so we can search in the tree + copyPoint (input_->points[*idx_i], pt_src); + + float cos_angle = source_normals_->points[*idx_i].normal_x * target_normals_->points[nn_indices[j]].normal_x + + source_normals_->points[*idx_i].normal_y * target_normals_->points[nn_indices[j]].normal_y + + source_normals_->points[*idx_i].normal_z * target_normals_->points[nn_indices[j]].normal_z ; + float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle); + + if (dist < min_dist) + { + min_dist = dist; + min_index = static_cast (j); + } + } + if (min_dist > max_distance) + continue; + + corr.index_query = *idx_i; + corr.index_match = nn_indices[min_index]; + corr.distance = nn_dists[min_index];//min_dist; + correspondences[nr_valid_correspondences++] = corr; + } + } + correspondences.resize (nr_valid_correspondences); + deinitCompute (); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceEstimationBackProjection::determineReciprocalCorrespondences ( + pcl::Correspondences &correspondences, double max_distance) +{ + if (!initCompute ()) + return; + + // Set the internal point representation of choice + if(!initComputeReciprocal()) + return; + + correspondences.resize (indices_->size ()); + + std::vector nn_indices (k_); + std::vector nn_dists (k_); + std::vector index_reciprocal (1); + std::vector distance_reciprocal (1); + + float min_dist = std::numeric_limits::max (); + int min_index = 0; + + pcl::Correspondence corr; + unsigned int nr_valid_correspondences = 0; + int target_idx = 0; + + // Check if the template types are the same. If true, avoid a copy. + // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT macro! + if (isSamePointType ()) + { + PointTarget pt; + // Iterate over the input set of source indices + for (std::vector::const_iterator idx_i = indices_->begin (); idx_i != indices_->end (); ++idx_i) + { + tree_->nearestKSearch (input_->points[*idx_i], k_, nn_indices, nn_dists); + + // Among the K nearest neighbours find the one with minimum perpendicular distance to the normal + min_dist = std::numeric_limits::max (); + + // Find the best correspondence + for (size_t j = 0; j < nn_indices.size (); j++) + { + float cos_angle = source_normals_->points[*idx_i].normal_x * target_normals_->points[nn_indices[j]].normal_x + + source_normals_->points[*idx_i].normal_y * target_normals_->points[nn_indices[j]].normal_y + + source_normals_->points[*idx_i].normal_z * target_normals_->points[nn_indices[j]].normal_z ; + float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle); + + if (dist < min_dist) + { + min_dist = dist; + min_index = static_cast (j); + } + } + if (min_dist > max_distance) + continue; + + // Check if the correspondence is reciprocal + target_idx = nn_indices[min_index]; + tree_reciprocal_->nearestKSearch (target_->points[target_idx], 1, index_reciprocal, distance_reciprocal); + + if (*idx_i != index_reciprocal[0]) + continue; + + corr.index_query = *idx_i; + corr.index_match = nn_indices[min_index]; + corr.distance = nn_dists[min_index];//min_dist; + correspondences[nr_valid_correspondences++] = corr; + } + } + else + { + PointTarget pt; + + // Iterate over the input set of source indices + for (std::vector::const_iterator idx_i = indices_->begin (); idx_i != indices_->end (); ++idx_i) + { + tree_->nearestKSearch (input_->points[*idx_i], k_, nn_indices, nn_dists); + + // Among the K nearest neighbours find the one with minimum perpendicular distance to the normal + min_dist = std::numeric_limits::max (); + + // Find the best correspondence + for (size_t j = 0; j < nn_indices.size (); j++) + { + PointSource pt_src; + // Copy the source data to a target PointTarget format so we can search in the tree + copyPoint (input_->points[*idx_i], pt_src); + + float cos_angle = source_normals_->points[*idx_i].normal_x * target_normals_->points[nn_indices[j]].normal_x + + source_normals_->points[*idx_i].normal_y * target_normals_->points[nn_indices[j]].normal_y + + source_normals_->points[*idx_i].normal_z * target_normals_->points[nn_indices[j]].normal_z ; + float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle); + + if (dist < min_dist) + { + min_dist = dist; + min_index = static_cast (j); + } + } + if (min_dist > max_distance) + continue; + + // Check if the correspondence is reciprocal + target_idx = nn_indices[min_index]; + tree_reciprocal_->nearestKSearch (target_->points[target_idx], 1, index_reciprocal, distance_reciprocal); + + if (*idx_i != index_reciprocal[0]) + continue; + + corr.index_query = *idx_i; + corr.index_match = nn_indices[min_index]; + corr.distance = nn_dists[min_index];//min_dist; + correspondences[nr_valid_correspondences++] = corr; + } + } + correspondences.resize (nr_valid_correspondences); + deinitCompute (); +} + +#endif // PCL_REGISTRATION_IMPL_CORRESPONDENCE_ESTIMATION_BACK_PROJECTION_HPP_ diff --git a/pcl-1.7/pcl/registration/impl/correspondence_estimation_normal_shooting.hpp b/pcl-1.7/pcl/registration/impl/correspondence_estimation_normal_shooting.hpp new file mode 100644 index 0000000..4402c54 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_estimation_normal_shooting.hpp @@ -0,0 +1,310 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_ESTIMATION_NORMAL_SHOOTING_H_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_ESTIMATION_NORMAL_SHOOTING_H_ + +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::registration::CorrespondenceEstimationNormalShooting::initCompute () +{ + if (!source_normals_) + { + PCL_WARN ("[pcl::registration::%s::initCompute] Datasets containing normals for source have not been given!\n", getClassName ().c_str ()); + return (false); + } + + return (CorrespondenceEstimationBase::initCompute ()); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceEstimationNormalShooting::determineCorrespondences ( + pcl::Correspondences &correspondences, double max_distance) +{ + if (!initCompute ()) + return; + + correspondences.resize (indices_->size ()); + + std::vector nn_indices (k_); + std::vector nn_dists (k_); + + double min_dist = std::numeric_limits::max (); + int min_index = 0; + + pcl::Correspondence corr; + unsigned int nr_valid_correspondences = 0; + + // Check if the template types are the same. If true, avoid a copy. + // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT macro! + if (isSamePointType ()) + { + PointTarget pt; + // Iterate over the input set of source indices + for (std::vector::const_iterator idx_i = indices_->begin (); idx_i != indices_->end (); ++idx_i) + { + tree_->nearestKSearch (input_->points[*idx_i], k_, nn_indices, nn_dists); + + // Among the K nearest neighbours find the one with minimum perpendicular distance to the normal + min_dist = std::numeric_limits::max (); + + // Find the best correspondence + for (size_t j = 0; j < nn_indices.size (); j++) + { + // computing the distance between a point and a line in 3d. + // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html + pt.x = target_->points[nn_indices[j]].x - input_->points[*idx_i].x; + pt.y = target_->points[nn_indices[j]].y - input_->points[*idx_i].y; + pt.z = target_->points[nn_indices[j]].z - input_->points[*idx_i].z; + + const NormalT &normal = source_normals_->points[*idx_i]; + Eigen::Vector3d N (normal.normal_x, normal.normal_y, normal.normal_z); + Eigen::Vector3d V (pt.x, pt.y, pt.z); + Eigen::Vector3d C = N.cross (V); + + // Check if we have a better correspondence + double dist = C.dot (C); + if (dist < min_dist) + { + min_dist = dist; + min_index = static_cast (j); + } + } + if (min_dist > max_distance) + continue; + + corr.index_query = *idx_i; + corr.index_match = nn_indices[min_index]; + corr.distance = nn_dists[min_index];//min_dist; + correspondences[nr_valid_correspondences++] = corr; + } + } + else + { + PointTarget pt; + + // Iterate over the input set of source indices + for (std::vector::const_iterator idx_i = indices_->begin (); idx_i != indices_->end (); ++idx_i) + { + tree_->nearestKSearch (input_->points[*idx_i], k_, nn_indices, nn_dists); + + // Among the K nearest neighbours find the one with minimum perpendicular distance to the normal + min_dist = std::numeric_limits::max (); + + // Find the best correspondence + for (size_t j = 0; j < nn_indices.size (); j++) + { + PointSource pt_src; + // Copy the source data to a target PointTarget format so we can search in the tree + copyPoint (input_->points[*idx_i], pt_src); + + // computing the distance between a point and a line in 3d. + // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html + pt.x = target_->points[nn_indices[j]].x - pt_src.x; + pt.y = target_->points[nn_indices[j]].y - pt_src.y; + pt.z = target_->points[nn_indices[j]].z - pt_src.z; + + const NormalT &normal = source_normals_->points[*idx_i]; + Eigen::Vector3d N (normal.normal_x, normal.normal_y, normal.normal_z); + Eigen::Vector3d V (pt.x, pt.y, pt.z); + Eigen::Vector3d C = N.cross (V); + + // Check if we have a better correspondence + double dist = C.dot (C); + if (dist < min_dist) + { + min_dist = dist; + min_index = static_cast (j); + } + } + if (min_dist > max_distance) + continue; + + corr.index_query = *idx_i; + corr.index_match = nn_indices[min_index]; + corr.distance = nn_dists[min_index];//min_dist; + correspondences[nr_valid_correspondences++] = corr; + } + } + correspondences.resize (nr_valid_correspondences); + deinitCompute (); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceEstimationNormalShooting::determineReciprocalCorrespondences ( + pcl::Correspondences &correspondences, double max_distance) +{ + if (!initCompute ()) + return; + + // setup tree for reciprocal search + // Set the internal point representation of choice + if (!initComputeReciprocal ()) + return; + + correspondences.resize (indices_->size ()); + + std::vector nn_indices (k_); + std::vector nn_dists (k_); + std::vector index_reciprocal (1); + std::vector distance_reciprocal (1); + + double min_dist = std::numeric_limits::max (); + int min_index = 0; + + pcl::Correspondence corr; + unsigned int nr_valid_correspondences = 0; + int target_idx = 0; + + // Check if the template types are the same. If true, avoid a copy. + // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT macro! + if (isSamePointType ()) + { + PointTarget pt; + // Iterate over the input set of source indices + for (std::vector::const_iterator idx_i = indices_->begin (); idx_i != indices_->end (); ++idx_i) + { + tree_->nearestKSearch (input_->points[*idx_i], k_, nn_indices, nn_dists); + + // Among the K nearest neighbours find the one with minimum perpendicular distance to the normal + min_dist = std::numeric_limits::max (); + + // Find the best correspondence + for (size_t j = 0; j < nn_indices.size (); j++) + { + // computing the distance between a point and a line in 3d. + // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html + pt.x = target_->points[nn_indices[j]].x - input_->points[*idx_i].x; + pt.y = target_->points[nn_indices[j]].y - input_->points[*idx_i].y; + pt.z = target_->points[nn_indices[j]].z - input_->points[*idx_i].z; + + const NormalT &normal = source_normals_->points[*idx_i]; + Eigen::Vector3d N (normal.normal_x, normal.normal_y, normal.normal_z); + Eigen::Vector3d V (pt.x, pt.y, pt.z); + Eigen::Vector3d C = N.cross (V); + + // Check if we have a better correspondence + double dist = C.dot (C); + if (dist < min_dist) + { + min_dist = dist; + min_index = static_cast (j); + } + } + if (min_dist > max_distance) + continue; + + // Check if the correspondence is reciprocal + target_idx = nn_indices[min_index]; + tree_reciprocal_->nearestKSearch (target_->points[target_idx], 1, index_reciprocal, distance_reciprocal); + + if (*idx_i != index_reciprocal[0]) + continue; + + // Correspondence IS reciprocal, save it and continue + corr.index_query = *idx_i; + corr.index_match = nn_indices[min_index]; + corr.distance = nn_dists[min_index];//min_dist; + correspondences[nr_valid_correspondences++] = corr; + } + } + else + { + PointTarget pt; + + // Iterate over the input set of source indices + for (std::vector::const_iterator idx_i = indices_->begin (); idx_i != indices_->end (); ++idx_i) + { + tree_->nearestKSearch (input_->points[*idx_i], k_, nn_indices, nn_dists); + + // Among the K nearest neighbours find the one with minimum perpendicular distance to the normal + min_dist = std::numeric_limits::max (); + + // Find the best correspondence + for (size_t j = 0; j < nn_indices.size (); j++) + { + PointSource pt_src; + // Copy the source data to a target PointTarget format so we can search in the tree + copyPoint (input_->points[*idx_i], pt_src); + + // computing the distance between a point and a line in 3d. + // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html + pt.x = target_->points[nn_indices[j]].x - pt_src.x; + pt.y = target_->points[nn_indices[j]].y - pt_src.y; + pt.z = target_->points[nn_indices[j]].z - pt_src.z; + + const NormalT &normal = source_normals_->points[*idx_i]; + Eigen::Vector3d N (normal.normal_x, normal.normal_y, normal.normal_z); + Eigen::Vector3d V (pt.x, pt.y, pt.z); + Eigen::Vector3d C = N.cross (V); + + // Check if we have a better correspondence + double dist = C.dot (C); + if (dist < min_dist) + { + min_dist = dist; + min_index = static_cast (j); + } + } + if (min_dist > max_distance) + continue; + + // Check if the correspondence is reciprocal + target_idx = nn_indices[min_index]; + tree_reciprocal_->nearestKSearch (target_->points[target_idx], 1, index_reciprocal, distance_reciprocal); + + if (*idx_i != index_reciprocal[0]) + continue; + + // Correspondence IS reciprocal, save it and continue + corr.index_query = *idx_i; + corr.index_match = nn_indices[min_index]; + corr.distance = nn_dists[min_index];//min_dist; + correspondences[nr_valid_correspondences++] = corr; + } + } + correspondences.resize (nr_valid_correspondences); + deinitCompute (); +} + +#endif // PCL_REGISTRATION_IMPL_CORRESPONDENCE_ESTIMATION_NORMAL_SHOOTING_H_ diff --git a/pcl-1.7/pcl/registration/impl/correspondence_estimation_organized_projection.hpp b/pcl-1.7/pcl/registration/impl/correspondence_estimation_organized_projection.hpp new file mode 100644 index 0000000..78359a2 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_estimation_organized_projection.hpp @@ -0,0 +1,127 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_ORGANIZED_PROJECTION_IMPL_HPP_ +#define PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_ORGANIZED_PROJECTION_IMPL_HPP_ + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::registration::CorrespondenceEstimationOrganizedProjection::initCompute () +{ + // Set the target_cloud_updated_ variable to true, so that the kd-tree is not built - it is not needed for this class + target_cloud_updated_ = false; + if (!CorrespondenceEstimationBase::initCompute ()) + return (false); + + /// Check if the target cloud is organized + if (!target_->isOrganized ()) + { + PCL_WARN ("[pcl::registration::%s::initCompute] Target cloud is not organized.\n", getClassName ().c_str ()); + return (false); + } + + /// Put the projection matrix together + projection_matrix_ (0, 0) = fx_; + projection_matrix_ (1, 1) = fy_; + projection_matrix_ (0, 2) = cx_; + projection_matrix_ (1, 2) = cy_; + + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceEstimationOrganizedProjection::determineCorrespondences ( + pcl::Correspondences &correspondences, + double max_distance) +{ + if (!initCompute ()) + return; + + correspondences.resize (indices_->size ()); + size_t c_index = 0; + + for (std::vector::const_iterator src_it = indices_->begin (); src_it != indices_->end (); ++src_it) + { + if (isFinite (input_->points[*src_it])) + { + Eigen::Vector4f p_src (src_to_tgt_transformation_ * input_->points[*src_it].getVector4fMap ()); + Eigen::Vector3f p_src3 (p_src[0], p_src[1], p_src[2]); + Eigen::Vector3f uv (projection_matrix_ * p_src3); + + /// Check if the point was behind the camera + if (uv[2] <= 0) + continue; + + int u = static_cast (uv[0] / uv[2]); + int v = static_cast (uv[1] / uv[2]); + + if (u >= 0 && u < static_cast (target_->width) && + v >= 0 && v < static_cast (target_->height)) + { + const PointTarget &pt_tgt = target_->at (u, v); + if (!isFinite (pt_tgt)) + continue; + /// Check if the depth difference is larger than the threshold + if (fabs (uv[2] - pt_tgt.z) > depth_threshold_) + continue; + + double dist = (p_src3 - pt_tgt.getVector3fMap ()).norm (); + if (dist < max_distance) + correspondences[c_index++] = pcl::Correspondence (*src_it, v * target_->width + u, static_cast (dist)); + } + } + } + + correspondences.resize (c_index); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceEstimationOrganizedProjection::determineReciprocalCorrespondences ( + pcl::Correspondences &correspondences, + double max_distance) +{ + // Call the normal determineCorrespondences (...), as doing it both ways will not improve the results + determineCorrespondences (correspondences, max_distance); +} + +#endif // PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_ORGANIZED_PROJECTION_IMPL_HPP_ + diff --git a/pcl-1.7/pcl/registration/impl/correspondence_rejection.hpp b/pcl-1.7/pcl/registration/impl/correspondence_rejection.hpp new file mode 100644 index 0000000..7c89862 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_rejection.hpp @@ -0,0 +1,58 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_IMPL_HPP_ +#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_IMPL_HPP_ + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::DataContainer::setInputCloud (const typename pcl::registration::DataContainer::PointCloudConstPtr &cloud) +{ + //input_ = cloud; + setInputSource (cloud); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::registration::DataContainer::PointCloudConstPtr const +pcl::registration::DataContainer::getInputCloud () +{ + return (getInputSource ()); + //return (input_); +} + +#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_IMPL_HPP_ + diff --git a/pcl-1.7/pcl/registration/impl/correspondence_rejection_distance.hpp b/pcl-1.7/pcl/registration/impl/correspondence_rejection_distance.hpp new file mode 100644 index 0000000..e7a174f --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_rejection_distance.hpp @@ -0,0 +1,44 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_DISTANCE_HPP_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_DISTANCE_HPP_ + + +#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_DISTANCE_HPP_ */ diff --git a/pcl-1.7/pcl/registration/impl/correspondence_rejection_features.hpp b/pcl-1.7/pcl/registration/impl/correspondence_rejection_features.hpp new file mode 100644 index 0000000..578d179 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_rejection_features.hpp @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_FEATURES_HPP_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_FEATURES_HPP_ + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::CorrespondenceRejectorFeatures::setSourceFeature ( + const typename pcl::PointCloud::ConstPtr &source_feature, const std::string &key) +{ + if (features_map_.count (key) == 0) + features_map_[key].reset (new FeatureContainer); + boost::static_pointer_cast > (features_map_[key])->setSourceFeature (source_feature); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline typename pcl::PointCloud::ConstPtr +pcl::registration::CorrespondenceRejectorFeatures::getSourceFeature (const std::string &key) +{ + if (features_map_.count (key) == 0) + return (boost::shared_ptr > ()); + else + return (boost::static_pointer_cast > (features_map_[key])->getSourceFeature ()); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::CorrespondenceRejectorFeatures::setTargetFeature ( + const typename pcl::PointCloud::ConstPtr &target_feature, const std::string &key) +{ + if (features_map_.count (key) == 0) + features_map_[key].reset (new FeatureContainer); + boost::static_pointer_cast > (features_map_[key])->setTargetFeature (target_feature); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline typename pcl::PointCloud::ConstPtr +pcl::registration::CorrespondenceRejectorFeatures::getTargetFeature (const std::string &key) +{ + if (features_map_.count (key) == 0) + return (boost::shared_ptr > ()); + else + return (boost::static_pointer_cast > (features_map_[key])->getTargetFeature ()); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::CorrespondenceRejectorFeatures::setDistanceThreshold ( + double thresh, const std::string &key) +{ + if (features_map_.count (key) == 0) + features_map_[key].reset (new FeatureContainer); + boost::static_pointer_cast > (features_map_[key])->setDistanceThreshold (thresh); +} + + + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::CorrespondenceRejectorFeatures::setFeatureRepresentation ( + const typename pcl::PointRepresentation::ConstPtr &fr, + const std::string &key) +{ + if (features_map_.count (key) == 0) + features_map_[key].reset (new FeatureContainer); + boost::static_pointer_cast > (features_map_[key])->setFeatureRepresentation (fr); +} + + +#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_FEATURES_HPP_ */ diff --git a/pcl-1.7/pcl/registration/impl/correspondence_rejection_median_distance.hpp b/pcl-1.7/pcl/registration/impl/correspondence_rejection_median_distance.hpp new file mode 100644 index 0000000..2884d25 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_rejection_median_distance.hpp @@ -0,0 +1,44 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_HPP_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_HPP_ + + +#endif // PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_HPP_ diff --git a/pcl-1.7/pcl/registration/impl/correspondence_rejection_one_to_one.hpp b/pcl-1.7/pcl/registration/impl/correspondence_rejection_one_to_one.hpp new file mode 100644 index 0000000..656b6db --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_rejection_one_to_one.hpp @@ -0,0 +1,43 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ONE_TO_ONE_HPP_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ONE_TO_ONE_HPP_ + +#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ONE_TO_ONE_HPP_ */ diff --git a/pcl-1.7/pcl/registration/impl/correspondence_rejection_organized_boundary.hpp b/pcl-1.7/pcl/registration/impl/correspondence_rejection_organized_boundary.hpp new file mode 100644 index 0000000..a6821e4 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_rejection_organized_boundary.hpp @@ -0,0 +1,43 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) Alexandru-Eugen Ichim + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + + +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_HPP_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_HPP_ + +#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_HPP_ */ diff --git a/pcl-1.7/pcl/registration/impl/correspondence_rejection_poly.hpp b/pcl-1.7/pcl/registration/impl/correspondence_rejection_poly.hpp new file mode 100644 index 0000000..5d3ebf9 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_rejection_poly.hpp @@ -0,0 +1,241 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_POLY_HPP_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_POLY_HPP_ + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceRejectorPoly::getRemainingCorrespondences ( + const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences) +{ + // This is reset after all the checks below + remaining_correspondences = original_correspondences; + + // Check source/target + if (!input_) + { + PCL_ERROR ("[pcl::registration::%s::getRemainingCorrespondences] No source was input! Returning all input correspondences.\n", + getClassName ().c_str ()); + return; + } + + if (!target_) + { + PCL_ERROR ("[pcl::registration::%s::getRemainingCorrespondences] No target was input! Returning all input correspondences.\n", + getClassName ().c_str ()); + return; + } + + // Check cardinality + if (cardinality_ < 2) + { + PCL_ERROR ("[pcl::registration::%s::getRemainingCorrespondences] Polygon cardinality too low!. Returning all input correspondences.\n", + getClassName ().c_str() ); + return; + } + + // Number of input correspondences + const int nr_correspondences = static_cast (original_correspondences.size ()); + + // Not enough correspondences for polygonal rejections + if (cardinality_ >= nr_correspondences) + { + PCL_ERROR ("[pcl::registration::%s::getRemainingCorrespondences] Number of correspondences smaller than polygon cardinality! Returning all input correspondences.\n", + getClassName ().c_str() ); + return; + } + + // Check similarity + if (similarity_threshold_ < 0.0f || similarity_threshold_ > 1.0f) + { + PCL_ERROR ("[pcl::registration::%s::getRemainingCorrespondences] Invalid edge length similarity - must be in [0,1]!. Returning all input correspondences.\n", + getClassName ().c_str() ); + return; + } + + // Similarity, squared + similarity_threshold_squared_ = similarity_threshold_ * similarity_threshold_; + + // Initialization of result + remaining_correspondences.clear (); + remaining_correspondences.reserve (nr_correspondences); + + // Number of times a correspondence is sampled and number of times it was accepted + std::vector num_samples (nr_correspondences, 0); + std::vector num_accepted (nr_correspondences, 0); + + // Main loop + for (int i = 0; i < iterations_; ++i) + { + // Sample cardinality_ correspondences without replacement + const std::vector idx = getUniqueRandomIndices (nr_correspondences, cardinality_); + + // Verify the polygon similarity + if (thresholdPolygon (original_correspondences, idx)) + { + // Increment sample counter and accept counter + for (int j = 0; j < cardinality_; ++j) + { + ++num_samples[ idx[j] ]; + ++num_accepted[ idx[j] ]; + } + } + else + { + // Not accepted, only increment sample counter + for (int j = 0; j < cardinality_; ++j) + ++num_samples[ idx[j] ]; + } + } + + // Now calculate the acceptance rate of each correspondence + std::vector accept_rate (nr_correspondences, 0.0f); + for (int i = 0; i < nr_correspondences; ++i) + { + const int numsi = num_samples[i]; + if (numsi == 0) + accept_rate[i] = 0.0f; + else + accept_rate[i] = static_cast (num_accepted[i]) / static_cast (numsi); + } + + // Compute a histogram in range [0,1] for acceptance rates + const int hist_size = nr_correspondences / 2; // TODO: Optimize this + const std::vector histogram = computeHistogram (accept_rate, 0.0f, 1.0f, hist_size); + + // Find the cut point between outliers and inliers using Otsu's thresholding method + const int cut_idx = findThresholdOtsu (histogram); + const float cut = static_cast (cut_idx) / static_cast (hist_size); + + // Threshold + for (int i = 0; i < nr_correspondences; ++i) + if (accept_rate[i] > cut) + remaining_correspondences.push_back (original_correspondences[i]); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template std::vector +pcl::registration::CorrespondenceRejectorPoly::computeHistogram (const std::vector& data, + float lower, float upper, int bins) +{ + // Result + std::vector result (bins, 0); + + // Last index into result and increment factor from data value --> index + const int last_idx = bins - 1; + const float idx_per_val = static_cast (bins) / (upper - lower); + + // Accumulate + for (std::vector::const_iterator it = data.begin (); it != data.end (); ++it) + ++result[ std::min (last_idx, int ((*it)*idx_per_val)) ]; + + return (result); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::registration::CorrespondenceRejectorPoly::findThresholdOtsu (const std::vector& histogram) +{ + // Precision + const double eps = std::numeric_limits::epsilon(); + + // Histogram dimension + const int nbins = static_cast (histogram.size ()); + + // Mean and inverse of the number of data points + double mean = 0.0; + double sum_inv = 0.0; + for (int i = 0; i < nbins; ++i) + { + mean += static_cast (i * histogram[i]); + sum_inv += static_cast (histogram[i]); + } + sum_inv = 1.0/sum_inv; + mean *= sum_inv; + + // Probability and mean of class 1 (data to the left of threshold) + double class_mean1 = 0.0; + double class_prob1 = 0.0; + double class_prob2 = 1.0; + + // Maximized between class variance and associated bin value + double between_class_variance_max = 0.0; + int result = 0; + + // Loop over all bin values + for (int i = 0; i < nbins; ++i) + { + class_mean1 *= class_prob1; + + // Probability of bin i + const double prob_i = static_cast (histogram[i]) * sum_inv; + + // Class probability 1: sum of probabilities from 0 to i + class_prob1 += prob_i; + + // Class probability 2: sum of probabilities from i+1 to nbins-1 + class_prob2 -= prob_i; + + // Avoid division by zero below + if (std::min (class_prob1,class_prob2) < eps || std::max (class_prob1,class_prob2) > 1.0-eps) + continue; + + // Class mean 1: sum of probabilities from 0 to i, weighted by bin value + class_mean1 = (class_mean1 + static_cast (i) * prob_i) / class_prob1; + + // Class mean 2: sum of probabilities from i+1 to nbins-1, weighted by bin value + const double class_mean2 = (mean - class_prob1*class_mean1) / class_prob2; + + // Between class variance + const double between_class_variance = class_prob1 * class_prob2 + * (class_mean1 - class_mean2) + * (class_mean1 - class_mean2); + + // If between class variance is maximized, update result + if (between_class_variance > between_class_variance_max) + { + between_class_variance_max = between_class_variance; + result = i; + } + } + + return (result); +} + +#endif // PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_POLY_HPP_ diff --git a/pcl-1.7/pcl/registration/impl/correspondence_rejection_sample_consensus.hpp b/pcl-1.7/pcl/registration/impl/correspondence_rejection_sample_consensus.hpp new file mode 100644 index 0000000..7ab5a2d --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_rejection_sample_consensus.hpp @@ -0,0 +1,180 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_HPP_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_HPP_ + +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceRejectorSampleConsensus::setInputCloud ( + const typename pcl::registration::CorrespondenceRejectorSampleConsensus::PointCloudConstPtr &cloud) +{ + setInputSource (cloud); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::registration::CorrespondenceRejectorSampleConsensus::PointCloudConstPtr const +pcl::registration::CorrespondenceRejectorSampleConsensus::getInputCloud () +{ + return (getInputSource ()); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceRejectorSampleConsensus::setTargetCloud ( + const typename pcl::registration::CorrespondenceRejectorSampleConsensus::PointCloudConstPtr &cloud) +{ + setInputTarget (cloud); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceRejectorSampleConsensus::setMaxIterations ( + int max_iterations) +{ + setMaximumIterations (max_iterations); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::registration::CorrespondenceRejectorSampleConsensus::getMaxIterations () +{ + return (getMaximumIterations ()); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceRejectorSampleConsensus::getRemainingCorrespondences ( + const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences) +{ + if (!input_) + { + PCL_ERROR ("[pcl::registration::%s::getRemainingCorrespondences] No input cloud dataset was given!\n", getClassName ().c_str ()); + return; + } + + if (!target_) + { + PCL_ERROR ("[pcl::registration::%s::getRemainingCorrespondences] No input target dataset was given!\n", getClassName ().c_str ()); + return; + } + + if (save_inliers_) + inlier_indices_.clear (); + + int nr_correspondences = static_cast (original_correspondences.size ()); + std::vector source_indices (nr_correspondences); + std::vector target_indices (nr_correspondences); + + // Copy the query-match indices + for (size_t i = 0; i < original_correspondences.size (); ++i) + { + source_indices[i] = original_correspondences[i].index_query; + target_indices[i] = original_correspondences[i].index_match; + } + + // from pcl/registration/icp.hpp: + std::vector source_indices_good; + std::vector target_indices_good; + { + // From the set of correspondences found, attempt to remove outliers + // Create the registration model + typedef typename pcl::SampleConsensusModelRegistration::Ptr SampleConsensusModelRegistrationPtr; + SampleConsensusModelRegistrationPtr model; + model.reset (new pcl::SampleConsensusModelRegistration (input_, source_indices)); + // Pass the target_indices + model->setInputTarget (target_, target_indices); + // Create a RANSAC model + pcl::RandomSampleConsensus sac (model, inlier_threshold_); + sac.setMaxIterations (max_iterations_); + + // Compute the set of inliers + if (!sac.computeModel ()) + { + remaining_correspondences = original_correspondences; + best_transformation_.setIdentity (); + return; + } + else + { + if (refine_ && !sac.refineModel ()) + { + PCL_ERROR ("[pcl::registration::CorrespondenceRejectorSampleConsensus::getRemainingCorrespondences] Could not refine the model! Returning an empty solution.\n"); + return; + } + + std::vector inliers; + sac.getInliers (inliers); + + if (inliers.size () < 3) + { + remaining_correspondences = original_correspondences; + best_transformation_.setIdentity (); + return; + } + boost::unordered_map index_to_correspondence; + for (int i = 0; i < nr_correspondences; ++i) + index_to_correspondence[original_correspondences[i].index_query] = i; + + remaining_correspondences.resize (inliers.size ()); + for (size_t i = 0; i < inliers.size (); ++i) + remaining_correspondences[i] = original_correspondences[index_to_correspondence[inliers[i]]]; + + if (save_inliers_) + { + inlier_indices_.reserve (inliers.size ()); + for (size_t i = 0; i < inliers.size (); ++i) + inlier_indices_.push_back (index_to_correspondence[inliers[i]]); + } + + // get best transformation + Eigen::VectorXf model_coefficients; + sac.getModelCoefficients (model_coefficients); + best_transformation_.row (0) = model_coefficients.segment<4>(0); + best_transformation_.row (1) = model_coefficients.segment<4>(4); + best_transformation_.row (2) = model_coefficients.segment<4>(8); + best_transformation_.row (3) = model_coefficients.segment<4>(12); + } + } +} + +#endif // PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_HPP_ diff --git a/pcl-1.7/pcl/registration/impl/correspondence_rejection_sample_consensus_2d.hpp b/pcl-1.7/pcl/registration/impl/correspondence_rejection_sample_consensus_2d.hpp new file mode 100644 index 0000000..97fb2c9 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_rejection_sample_consensus_2d.hpp @@ -0,0 +1,136 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_2D_HPP_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_2D_HPP_ + +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::CorrespondenceRejectorSampleConsensus2D::getRemainingCorrespondences ( + const pcl::Correspondences& original_correspondences, + pcl::Correspondences& remaining_correspondences) +{ + if (!input_) + { + PCL_ERROR ("[pcl::registration::%s::getRemainingCorrespondences] No input cloud dataset was given!\n", getClassName ().c_str ()); + return; + } + + if (!target_) + { + PCL_ERROR ("[pcl::registration::%s::getRemainingCorrespondences] No input target dataset was given!\n", getClassName ().c_str ()); + return; + } + + if (projection_matrix_ == Eigen::Matrix3f::Identity ()) + { + PCL_ERROR ("[pcl::registration::%s::getRemainingCorrespondences] Intrinsic camera parameters not given!\n", getClassName ().c_str ()); + return; + } + + int nr_correspondences = static_cast (original_correspondences.size ()); + std::vector source_indices (nr_correspondences); + std::vector target_indices (nr_correspondences); + + // Copy the query-match indices + for (size_t i = 0; i < original_correspondences.size (); ++i) + { + source_indices[i] = original_correspondences[i].index_query; + target_indices[i] = original_correspondences[i].index_match; + } + + // from pcl/registration/icp.hpp: + std::vector source_indices_good; + std::vector target_indices_good; + + // From the set of correspondences found, attempt to remove outliers + typename pcl::SampleConsensusModelRegistration2D::Ptr model (new pcl::SampleConsensusModelRegistration2D (input_, source_indices)); + // Pass the target_indices + model->setInputTarget (target_, target_indices); + model->setProjectionMatrix (projection_matrix_); + + // Create a RANSAC model + pcl::RandomSampleConsensus sac (model, inlier_threshold_); + sac.setMaxIterations (max_iterations_); + + // Compute the set of inliers + if (!sac.computeModel ()) + { + PCL_ERROR ("[pcl::registration::%s::getRemainingCorrespondences] Error computing model! Returning the original correspondences...\n", getClassName ().c_str ()); + remaining_correspondences = original_correspondences; + best_transformation_.setIdentity (); + return; + } + else + { + if (refine_ && !sac.refineModel (2.0)) + PCL_WARN ("[pcl::registration::%s::getRemainingCorrespondences] Error refining model!\n", getClassName ().c_str ()); + + std::vector inliers; + sac.getInliers (inliers); + + if (inliers.size () < 3) + { + PCL_ERROR ("[pcl::registration::%s::getRemainingCorrespondences] Less than 3 correspondences found!\n", getClassName ().c_str ()); + remaining_correspondences = original_correspondences; + best_transformation_.setIdentity (); + return; + } + + boost::unordered_map index_to_correspondence; + for (int i = 0; i < nr_correspondences; ++i) + index_to_correspondence[original_correspondences[i].index_query] = i; + + remaining_correspondences.resize (inliers.size ()); + for (size_t i = 0; i < inliers.size (); ++i) + remaining_correspondences[i] = original_correspondences[index_to_correspondence[inliers[i]]]; + + // get best transformation + Eigen::VectorXf model_coefficients; + sac.getModelCoefficients (model_coefficients); + best_transformation_.row (0) = model_coefficients.segment<4>(0); + best_transformation_.row (1) = model_coefficients.segment<4>(4); + best_transformation_.row (2) = model_coefficients.segment<4>(8); + best_transformation_.row (3) = model_coefficients.segment<4>(12); + } +} + +#endif // PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_2D_HPP_ + diff --git a/pcl-1.7/pcl/registration/impl/correspondence_rejection_surface_normal.hpp b/pcl-1.7/pcl/registration/impl/correspondence_rejection_surface_normal.hpp new file mode 100644 index 0000000..6509909 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_rejection_surface_normal.hpp @@ -0,0 +1,42 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SURFACE_NORMAL_HPP_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SURFACE_NORMAL_HPP_ + +#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SURFACE_NORMAL_HPP_ */ diff --git a/pcl-1.7/pcl/registration/impl/correspondence_rejection_trimmed.hpp b/pcl-1.7/pcl/registration/impl/correspondence_rejection_trimmed.hpp new file mode 100644 index 0000000..0690e1d --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_rejection_trimmed.hpp @@ -0,0 +1,43 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_TRIMMED_HPP_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_TRIMMED_HPP_ + +#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_TRIMMED_HPP_ */ diff --git a/pcl-1.7/pcl/registration/impl/correspondence_rejection_var_trimmed.hpp b/pcl-1.7/pcl/registration/impl/correspondence_rejection_var_trimmed.hpp new file mode 100644 index 0000000..53cd52f --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_rejection_var_trimmed.hpp @@ -0,0 +1,42 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_VAR_TRIMMED_HPP_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_VAR_TRIMMED_HPP_ + +#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_VAR_TRIMMED_HPP_ */ diff --git a/pcl-1.7/pcl/registration/impl/correspondence_types.hpp b/pcl-1.7/pcl/registration/impl/correspondence_types.hpp new file mode 100644 index 0000000..67938d6 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/correspondence_types.hpp @@ -0,0 +1,83 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_TYPES_H_ +#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_TYPES_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////// +inline void +pcl::registration::getCorDistMeanStd (const pcl::Correspondences &correspondences, double &mean, double &stddev) +{ + if (correspondences.empty ()) + return; + + double sum = 0, sq_sum = 0; + + for (size_t i = 0; i < correspondences.size (); ++i) + { + sum += correspondences[i].distance; + sq_sum += correspondences[i].distance * correspondences[i].distance; + } + mean = sum / static_cast (correspondences.size ()); + double variance = (sq_sum - sum * sum / static_cast (correspondences.size ())) / static_cast (correspondences.size () - 1); + stddev = sqrt (variance); +} + +////////////////////////////////////////////////////////////////////////////////////////// +inline void +pcl::registration::getQueryIndices (const pcl::Correspondences& correspondences, std::vector& indices) +{ + indices.resize (correspondences.size ()); + for (size_t i = 0; i < correspondences.size (); ++i) + indices[i] = correspondences[i].index_query; +} + +////////////////////////////////////////////////////////////////////////////////////////// +inline void +pcl::registration::getMatchIndices (const pcl::Correspondences& correspondences, std::vector& indices) +{ + indices.resize (correspondences.size ()); + for (size_t i = 0; i < correspondences.size (); ++i) + indices[i] = correspondences[i].index_match; +} + +#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_TYPES_H_ */ diff --git a/pcl-1.7/pcl/registration/impl/default_convergence_criteria.hpp b/pcl-1.7/pcl/registration/impl/default_convergence_criteria.hpp new file mode 100644 index 0000000..395709a --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/default_convergence_criteria.hpp @@ -0,0 +1,131 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_DEFAULT_CONVERGENCE_CRITERIA_HPP_ +#define PCL_REGISTRATION_DEFAULT_CONVERGENCE_CRITERIA_HPP_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::registration::DefaultConvergenceCriteria::hasConverged () +{ + convergence_state_ = CONVERGENCE_CRITERIA_NOT_CONVERGED; + + PCL_DEBUG ("[pcl::DefaultConvergenceCriteria::hasConverged] Iteration %d out of %d.\n", iterations_, max_iterations_); + // 1. Number of iterations has reached the maximum user imposed number of iterations + if (iterations_ >= max_iterations_) + { + if (failure_after_max_iter_) + return (false); + else + { + convergence_state_ = CONVERGENCE_CRITERIA_ITERATIONS; + return (true); + } + return (failure_after_max_iter_ ? false : true); + } + + // 2. The epsilon (difference) between the previous transformation and the current estimated transformation + double cos_angle = 0.5 * (transformation_.coeff (0, 0) + transformation_.coeff (1, 1) + transformation_.coeff (2, 2) - 1); + double translation_sqr = transformation_.coeff (0, 3) * transformation_.coeff (0, 3) + + transformation_.coeff (1, 3) * transformation_.coeff (1, 3) + + transformation_.coeff (2, 3) * transformation_.coeff (2, 3); + PCL_DEBUG ("[pcl::DefaultConvergenceCriteria::hasConverged] Current transformation gave %f rotation (cosine) and %f translation.\n", cos_angle, translation_sqr); + + if (cos_angle >= rotation_threshold_ && translation_sqr <= translation_threshold_) + { + if (iterations_similar_transforms_ < max_iterations_similar_transforms_) + { + // Increment the number of transforms that the thresholds are allowed to be similar + ++iterations_similar_transforms_; + return (false); + } + else + { + iterations_similar_transforms_ = 0; + convergence_state_ = CONVERGENCE_CRITERIA_TRANSFORM; + return (true); + } + } + + correspondences_cur_mse_ = calculateMSE (correspondences_); + PCL_DEBUG ("[pcl::DefaultConvergenceCriteria::hasConverged] Previous / Current MSE for correspondences distances is: %f / %f.\n", correspondences_prev_mse_, correspondences_cur_mse_); + + // 3. The relative sum of Euclidean squared errors is smaller than a user defined threshold + // Absolute + if (fabs (correspondences_cur_mse_ - correspondences_prev_mse_) < mse_threshold_absolute_) + { + if (iterations_similar_transforms_ < max_iterations_similar_transforms_) + { + // Increment the number of transforms that the thresholds are allowed to be similar + ++iterations_similar_transforms_; + return (false); + } + else + { + iterations_similar_transforms_ = 0; + convergence_state_ = CONVERGENCE_CRITERIA_ABS_MSE; + return (true); + } + } + + // Relative + if (fabs (correspondences_cur_mse_ - correspondences_prev_mse_) / correspondences_prev_mse_ < mse_threshold_relative_) + { + if (iterations_similar_transforms_ < max_iterations_similar_transforms_) + { + // Increment the number of transforms that the thresholds are allowed to be similar + ++iterations_similar_transforms_; + return (false); + } + else + { + iterations_similar_transforms_ = 0; + convergence_state_ = CONVERGENCE_CRITERIA_REL_MSE; + return (true); + } + } + + correspondences_prev_mse_ = correspondences_cur_mse_; + + return (false); +} + +#endif // PCL_REGISTRATION_DEFAULT_CONVERGENCE_CRITERIA_HPP_ diff --git a/pcl-1.7/pcl/registration/impl/elch.hpp b/pcl-1.7/pcl/registration/impl/elch.hpp new file mode 100644 index 0000000..21e1daa --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/elch.hpp @@ -0,0 +1,277 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_IMPL_ELCH_H_ +#define PCL_REGISTRATION_IMPL_ELCH_H_ + +#include +#include + +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::ELCH::loopOptimizerAlgorithm (LOAGraph &g, double *weights) +{ + std::list crossings, branches; + crossings.push_back (static_cast (loop_start_)); + crossings.push_back (static_cast (loop_end_)); + weights[loop_start_] = 0; + weights[loop_end_] = 1; + + int *p = new int[num_vertices (g)]; + int *p_min = new int[num_vertices (g)]; + double *d = new double[num_vertices (g)]; + double *d_min = new double[num_vertices (g)]; + double dist; + bool do_swap = false; + std::list::iterator crossings_it, end_it, start_min, end_min; + + // process all junctions + while (!crossings.empty ()) + { + dist = -1; + // find shortest crossing for all vertices on the loop + for (crossings_it = crossings.begin (); crossings_it != crossings.end (); ) + { + dijkstra_shortest_paths (g, *crossings_it, + predecessor_map(boost::make_iterator_property_map(p, get(boost::vertex_index, g))). + distance_map(boost::make_iterator_property_map(d, get(boost::vertex_index, g)))); + + end_it = crossings_it; + end_it++; + // find shortest crossing for one vertex + for (; end_it != crossings.end (); end_it++) + { + if (*end_it != p[*end_it] && (dist < 0 || d[*end_it] < dist)) + { + dist = d[*end_it]; + start_min = crossings_it; + end_min = end_it; + do_swap = true; + } + } + if (do_swap) + { + std::swap (p, p_min); + std::swap (d, d_min); + do_swap = false; + } + // vertex starts a branch + if (dist < 0) + { + branches.push_back (static_cast (*crossings_it)); + crossings_it = crossings.erase (crossings_it); + } + else + crossings_it++; + } + + if (dist > -1) + { + remove_edge (*end_min, p_min[*end_min], g); + for (int i = p_min[*end_min]; i != *start_min; i = p_min[i]) + { + //even right with weights[*start_min] > weights[*end_min]! (math works) + weights[i] = weights[*start_min] + (weights[*end_min] - weights[*start_min]) * d_min[i] / d_min[*end_min]; + remove_edge (i, p_min[i], g); + if (degree (i, g) > 0) + { + crossings.push_back (i); + } + } + + if (degree (*start_min, g) == 0) + crossings.erase (start_min); + + if (degree (*end_min, g) == 0) + crossings.erase (end_min); + } + } + + delete[] p; + delete[] p_min; + delete[] d; + delete[] d_min; + + boost::graph_traits::adjacency_iterator adjacent_it, adjacent_it_end; + int s; + + // error propagation + while (!branches.empty ()) + { + s = branches.front (); + branches.pop_front (); + + for (boost::tuples::tie (adjacent_it, adjacent_it_end) = adjacent_vertices (s, g); adjacent_it != adjacent_it_end; ++adjacent_it) + { + weights[*adjacent_it] = weights[s]; + if (degree (*adjacent_it, g) > 1) + branches.push_back (static_cast (*adjacent_it)); + } + clear_vertex (s, g); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::registration::ELCH::initCompute () +{ + /*if (!PCLBase::initCompute ()) + { + PCL_ERROR ("[pcl::registration:ELCH::initCompute] Init failed.\n"); + return (false); + }*/ //TODO + + if (loop_end_ == 0) + { + PCL_ERROR ("[pcl::registration::ELCH::initCompute] no end of loop defined!\n"); + deinitCompute (); + return (false); + } + + //compute transformation if it's not given + if (compute_loop_) + { + PointCloudPtr meta_start (new PointCloud); + PointCloudPtr meta_end (new PointCloud); + *meta_start = *(*loop_graph_)[loop_start_].cloud; + *meta_end = *(*loop_graph_)[loop_end_].cloud; + + typename boost::graph_traits::adjacency_iterator si, si_end; + for (boost::tuples::tie (si, si_end) = adjacent_vertices (loop_start_, *loop_graph_); si != si_end; si++) + *meta_start += *(*loop_graph_)[*si].cloud; + + for (boost::tuples::tie (si, si_end) = adjacent_vertices (loop_end_, *loop_graph_); si != si_end; si++) + *meta_end += *(*loop_graph_)[*si].cloud; + + //TODO use real pose instead of centroid + //Eigen::Vector4f pose_start; + //pcl::compute3DCentroid (*(*loop_graph_)[loop_start_].cloud, pose_start); + + //Eigen::Vector4f pose_end; + //pcl::compute3DCentroid (*(*loop_graph_)[loop_end_].cloud, pose_end); + + PointCloudPtr tmp (new PointCloud); + //Eigen::Vector4f diff = pose_start - pose_end; + //Eigen::Translation3f translation (diff.head (3)); + //Eigen::Affine3f trans = translation * Eigen::Quaternionf::Identity (); + //pcl::transformPointCloud (*(*loop_graph_)[loop_end_].cloud, *tmp, trans); + + reg_->setInputTarget (meta_start); + + reg_->setInputSource (meta_end); + + reg_->align (*tmp); + + loop_transform_ = reg_->getFinalTransformation (); + //TODO hack + //loop_transform_ *= trans.matrix (); + + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::ELCH::compute () +{ + if (!initCompute ()) + { + return; + } + + LOAGraph grb[4]; + + typename boost::graph_traits::edge_iterator edge_it, edge_it_end; + for (boost::tuples::tie (edge_it, edge_it_end) = edges (*loop_graph_); edge_it != edge_it_end; edge_it++) + { + for (int j = 0; j < 4; j++) + add_edge (source (*edge_it, *loop_graph_), target (*edge_it, *loop_graph_), 1, grb[j]); //TODO add variance + } + + double *weights[4]; + for (int i = 0; i < 4; i++) + { + weights[i] = new double[num_vertices (*loop_graph_)]; + loopOptimizerAlgorithm (grb[i], weights[i]); + } + + //TODO use pose + //Eigen::Vector4f cend; + //pcl::compute3DCentroid (*((*loop_graph_)[loop_end_].cloud), cend); + //Eigen::Translation3f tend (cend.head (3)); + //Eigen::Affine3f aend (tend); + //Eigen::Affine3f aendI = aend.inverse (); + + //TODO iterate ovr loop_graph_ + //typename boost::graph_traits::vertex_iterator vertex_it, vertex_it_end; + //for (boost::tuples::tie (vertex_it, vertex_it_end) = vertices (*loop_graph_); vertex_it != vertex_it_end; vertex_it++) + for (size_t i = 0; i < num_vertices (*loop_graph_); i++) + { + Eigen::Vector3f t2; + t2[0] = loop_transform_ (0, 3) * static_cast (weights[0][i]); + t2[1] = loop_transform_ (1, 3) * static_cast (weights[1][i]); + t2[2] = loop_transform_ (2, 3) * static_cast (weights[2][i]); + + Eigen::Affine3f bl (loop_transform_); + Eigen::Quaternionf q (bl.rotation ()); + Eigen::Quaternionf q2; + q2 = Eigen::Quaternionf::Identity ().slerp (static_cast (weights[3][i]), q); + + //TODO use rotation from branch start + Eigen::Translation3f t3 (t2); + Eigen::Affine3f a (t3 * q2); + //a = aend * a * aendI; + + pcl::transformPointCloud (*(*loop_graph_)[i].cloud, *(*loop_graph_)[i].cloud, a); + (*loop_graph_)[i].transform = a; + } + + add_edge (loop_start_, loop_end_, *loop_graph_); + + deinitCompute (); +} + +#endif // PCL_REGISTRATION_IMPL_ELCH_H_ diff --git a/pcl-1.7/pcl/registration/impl/gicp.hpp b/pcl-1.7/pcl/registration/impl/gicp.hpp new file mode 100644 index 0000000..ab9ba8d --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/gicp.hpp @@ -0,0 +1,484 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_IMPL_GICP_HPP_ +#define PCL_REGISTRATION_IMPL_GICP_HPP_ + +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GeneralizedIterativeClosestPoint::setInputCloud ( + const typename pcl::GeneralizedIterativeClosestPoint::PointCloudSourceConstPtr &cloud) +{ + setInputSource (cloud); +} + +//////////////////////////////////////////////////////////////////////////////////////// +template +template void +pcl::GeneralizedIterativeClosestPoint::computeCovariances(typename pcl::PointCloud::ConstPtr cloud, + const typename pcl::search::KdTree::Ptr kdtree, + std::vector& cloud_covariances) +{ + if (k_correspondences_ > int (cloud->size ())) + { + PCL_ERROR ("[pcl::GeneralizedIterativeClosestPoint::computeCovariances] Number or points in cloud (%lu) is less than k_correspondences_ (%lu)!\n", cloud->size (), k_correspondences_); + return; + } + + Eigen::Vector3d mean; + std::vector nn_indecies; nn_indecies.reserve (k_correspondences_); + std::vector nn_dist_sq; nn_dist_sq.reserve (k_correspondences_); + + // We should never get there but who knows + if(cloud_covariances.size () < cloud->size ()) + cloud_covariances.resize (cloud->size ()); + + typename pcl::PointCloud::const_iterator points_iterator = cloud->begin (); + std::vector::iterator matrices_iterator = cloud_covariances.begin (); + for(; + points_iterator != cloud->end (); + ++points_iterator, ++matrices_iterator) + { + const PointT &query_point = *points_iterator; + Eigen::Matrix3d &cov = *matrices_iterator; + // Zero out the cov and mean + cov.setZero (); + mean.setZero (); + + // Search for the K nearest neighbours + kdtree->nearestKSearch(query_point, k_correspondences_, nn_indecies, nn_dist_sq); + + // Find the covariance matrix + for(int j = 0; j < k_correspondences_; j++) { + const PointT &pt = (*cloud)[nn_indecies[j]]; + + mean[0] += pt.x; + mean[1] += pt.y; + mean[2] += pt.z; + + cov(0,0) += pt.x*pt.x; + + cov(1,0) += pt.y*pt.x; + cov(1,1) += pt.y*pt.y; + + cov(2,0) += pt.z*pt.x; + cov(2,1) += pt.z*pt.y; + cov(2,2) += pt.z*pt.z; + } + + mean /= static_cast (k_correspondences_); + // Get the actual covariance + for (int k = 0; k < 3; k++) + for (int l = 0; l <= k; l++) + { + cov(k,l) /= static_cast (k_correspondences_); + cov(k,l) -= mean[k]*mean[l]; + cov(l,k) = cov(k,l); + } + + // Compute the SVD (covariance matrix is symmetric so U = V') + Eigen::JacobiSVD svd(cov, Eigen::ComputeFullU); + cov.setZero (); + Eigen::Matrix3d U = svd.matrixU (); + // Reconstitute the covariance matrix with modified singular values using the column // vectors in V. + for(int k = 0; k < 3; k++) { + Eigen::Vector3d col = U.col(k); + double v = 1.; // biggest 2 singular values replaced by 1 + if(k == 2) // smallest singular value replaced by gicp_epsilon + v = gicp_epsilon_; + cov+= v * col * col.transpose(); + } + } +} + +//////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GeneralizedIterativeClosestPoint::computeRDerivative(const Vector6d &x, const Eigen::Matrix3d &R, Vector6d& g) const +{ + Eigen::Matrix3d dR_dPhi; + Eigen::Matrix3d dR_dTheta; + Eigen::Matrix3d dR_dPsi; + + double phi = x[3], theta = x[4], psi = x[5]; + + double cphi = cos(phi), sphi = sin(phi); + double ctheta = cos(theta), stheta = sin(theta); + double cpsi = cos(psi), spsi = sin(psi); + + dR_dPhi(0,0) = 0.; + dR_dPhi(1,0) = 0.; + dR_dPhi(2,0) = 0.; + + dR_dPhi(0,1) = sphi*spsi + cphi*cpsi*stheta; + dR_dPhi(1,1) = -cpsi*sphi + cphi*spsi*stheta; + dR_dPhi(2,1) = cphi*ctheta; + + dR_dPhi(0,2) = cphi*spsi - cpsi*sphi*stheta; + dR_dPhi(1,2) = -cphi*cpsi - sphi*spsi*stheta; + dR_dPhi(2,2) = -ctheta*sphi; + + dR_dTheta(0,0) = -cpsi*stheta; + dR_dTheta(1,0) = -spsi*stheta; + dR_dTheta(2,0) = -ctheta; + + dR_dTheta(0,1) = cpsi*ctheta*sphi; + dR_dTheta(1,1) = ctheta*sphi*spsi; + dR_dTheta(2,1) = -sphi*stheta; + + dR_dTheta(0,2) = cphi*cpsi*ctheta; + dR_dTheta(1,2) = cphi*ctheta*spsi; + dR_dTheta(2,2) = -cphi*stheta; + + dR_dPsi(0,0) = -ctheta*spsi; + dR_dPsi(1,0) = cpsi*ctheta; + dR_dPsi(2,0) = 0.; + + dR_dPsi(0,1) = -cphi*cpsi - sphi*spsi*stheta; + dR_dPsi(1,1) = -cphi*spsi + cpsi*sphi*stheta; + dR_dPsi(2,1) = 0.; + + dR_dPsi(0,2) = cpsi*sphi - cphi*spsi*stheta; + dR_dPsi(1,2) = sphi*spsi + cphi*cpsi*stheta; + dR_dPsi(2,2) = 0.; + + g[3] = matricesInnerProd(dR_dPhi, R); + g[4] = matricesInnerProd(dR_dTheta, R); + g[5] = matricesInnerProd(dR_dPsi, R); +} + +//////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GeneralizedIterativeClosestPoint::estimateRigidTransformationBFGS (const PointCloudSource &cloud_src, + const std::vector &indices_src, + const PointCloudTarget &cloud_tgt, + const std::vector &indices_tgt, + Eigen::Matrix4f &transformation_matrix) +{ + if (indices_src.size () < 4) // need at least 4 samples + { + PCL_THROW_EXCEPTION (NotEnoughPointsException, + "[pcl::GeneralizedIterativeClosestPoint::estimateRigidTransformationBFGS] Need at least 4 points to estimate a transform! Source and target have " << indices_src.size () << " points!"); + return; + } + // Set the initial solution + Vector6d x = Vector6d::Zero (); + x[0] = transformation_matrix (0,3); + x[1] = transformation_matrix (1,3); + x[2] = transformation_matrix (2,3); + x[3] = atan2 (transformation_matrix (2,1), transformation_matrix (2,2)); + x[4] = asin (-transformation_matrix (2,0)); + x[5] = atan2 (transformation_matrix (1,0), transformation_matrix (0,0)); + + // Set temporary pointers + tmp_src_ = &cloud_src; + tmp_tgt_ = &cloud_tgt; + tmp_idx_src_ = &indices_src; + tmp_idx_tgt_ = &indices_tgt; + + // Optimize using forward-difference approximation LM + const double gradient_tol = 1e-2; + OptimizationFunctorWithIndices functor(this); + BFGS bfgs (functor); + bfgs.parameters.sigma = 0.01; + bfgs.parameters.rho = 0.01; + bfgs.parameters.tau1 = 9; + bfgs.parameters.tau2 = 0.05; + bfgs.parameters.tau3 = 0.5; + bfgs.parameters.order = 3; + + int inner_iterations_ = 0; + int result = bfgs.minimizeInit (x); + result = BFGSSpace::Running; + do + { + inner_iterations_++; + result = bfgs.minimizeOneStep (x); + if(result) + { + break; + } + result = bfgs.testGradient(gradient_tol); + } while(result == BFGSSpace::Running && inner_iterations_ < max_inner_iterations_); + if(result == BFGSSpace::NoProgress || result == BFGSSpace::Success || inner_iterations_ == max_inner_iterations_) + { + PCL_DEBUG ("[pcl::registration::TransformationEstimationBFGS::estimateRigidTransformation]"); + PCL_DEBUG ("BFGS solver finished with exit code %i \n", result); + transformation_matrix.setIdentity(); + applyState(transformation_matrix, x); + } + else + PCL_THROW_EXCEPTION(SolverDidntConvergeException, + "[pcl::" << getClassName () << "::TransformationEstimationBFGS::estimateRigidTransformation] BFGS solver didn't converge!"); +} + +//////////////////////////////////////////////////////////////////////////////////////// +template inline double +pcl::GeneralizedIterativeClosestPoint::OptimizationFunctorWithIndices::operator() (const Vector6d& x) +{ + Eigen::Matrix4f transformation_matrix = gicp_->base_transformation_; + gicp_->applyState(transformation_matrix, x); + double f = 0; + int m = static_cast (gicp_->tmp_idx_src_->size ()); + for (int i = 0; i < m; ++i) + { + // The last coordinate, p_src[3] is guaranteed to be set to 1.0 in registration.hpp + Vector4fMapConst p_src = gicp_->tmp_src_->points[(*gicp_->tmp_idx_src_)[i]].getVector4fMap (); + // The last coordinate, p_tgt[3] is guaranteed to be set to 1.0 in registration.hpp + Vector4fMapConst p_tgt = gicp_->tmp_tgt_->points[(*gicp_->tmp_idx_tgt_)[i]].getVector4fMap (); + Eigen::Vector4f pp (transformation_matrix * p_src); + // Estimate the distance (cost function) + // The last coordiante is still guaranteed to be set to 1.0 + Eigen::Vector3d res(pp[0] - p_tgt[0], pp[1] - p_tgt[1], pp[2] - p_tgt[2]); + Eigen::Vector3d temp (gicp_->mahalanobis((*gicp_->tmp_idx_src_)[i]) * res); + //increment= res'*temp/num_matches = temp'*M*temp/num_matches (we postpone 1/num_matches after the loop closes) + f+= double(res.transpose() * temp); + } + return f/m; +} + +//////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::GeneralizedIterativeClosestPoint::OptimizationFunctorWithIndices::df (const Vector6d& x, Vector6d& g) +{ + Eigen::Matrix4f transformation_matrix = gicp_->base_transformation_; + gicp_->applyState(transformation_matrix, x); + //Zero out g + g.setZero (); + //Eigen::Vector3d g_t = g.head<3> (); + Eigen::Matrix3d R = Eigen::Matrix3d::Zero (); + int m = static_cast (gicp_->tmp_idx_src_->size ()); + for (int i = 0; i < m; ++i) + { + // The last coordinate, p_src[3] is guaranteed to be set to 1.0 in registration.hpp + Vector4fMapConst p_src = gicp_->tmp_src_->points[(*gicp_->tmp_idx_src_)[i]].getVector4fMap (); + // The last coordinate, p_tgt[3] is guaranteed to be set to 1.0 in registration.hpp + Vector4fMapConst p_tgt = gicp_->tmp_tgt_->points[(*gicp_->tmp_idx_tgt_)[i]].getVector4fMap (); + + Eigen::Vector4f pp (transformation_matrix * p_src); + // The last coordiante is still guaranteed to be set to 1.0 + Eigen::Vector3d res (pp[0] - p_tgt[0], pp[1] - p_tgt[1], pp[2] - p_tgt[2]); + // temp = M*res + Eigen::Vector3d temp (gicp_->mahalanobis ((*gicp_->tmp_idx_src_)[i]) * res); + // Increment translation gradient + // g.head<3> ()+= 2*M*res/num_matches (we postpone 2/num_matches after the loop closes) + g.head<3> ()+= temp; + // Increment rotation gradient + pp = gicp_->base_transformation_ * p_src; + Eigen::Vector3d p_src3 (pp[0], pp[1], pp[2]); + R+= p_src3 * temp.transpose(); + } + g.head<3> ()*= 2.0/m; + R*= 2.0/m; + gicp_->computeRDerivative(x, R, g); +} + +//////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::GeneralizedIterativeClosestPoint::OptimizationFunctorWithIndices::fdf (const Vector6d& x, double& f, Vector6d& g) +{ + Eigen::Matrix4f transformation_matrix = gicp_->base_transformation_; + gicp_->applyState(transformation_matrix, x); + f = 0; + g.setZero (); + Eigen::Matrix3d R = Eigen::Matrix3d::Zero (); + const int m = static_cast (gicp_->tmp_idx_src_->size ()); + for (int i = 0; i < m; ++i) + { + // The last coordinate, p_src[3] is guaranteed to be set to 1.0 in registration.hpp + Vector4fMapConst p_src = gicp_->tmp_src_->points[(*gicp_->tmp_idx_src_)[i]].getVector4fMap (); + // The last coordinate, p_tgt[3] is guaranteed to be set to 1.0 in registration.hpp + Vector4fMapConst p_tgt = gicp_->tmp_tgt_->points[(*gicp_->tmp_idx_tgt_)[i]].getVector4fMap (); + Eigen::Vector4f pp (transformation_matrix * p_src); + // The last coordiante is still guaranteed to be set to 1.0 + Eigen::Vector3d res (pp[0] - p_tgt[0], pp[1] - p_tgt[1], pp[2] - p_tgt[2]); + // temp = M*res + Eigen::Vector3d temp (gicp_->mahalanobis((*gicp_->tmp_idx_src_)[i]) * res); + // Increment total error + f+= double(res.transpose() * temp); + // Increment translation gradient + // g.head<3> ()+= 2*M*res/num_matches (we postpone 2/num_matches after the loop closes) + g.head<3> ()+= temp; + pp = gicp_->base_transformation_ * p_src; + Eigen::Vector3d p_src3 (pp[0], pp[1], pp[2]); + // Increment rotation gradient + R+= p_src3 * temp.transpose(); + } + f/= double(m); + g.head<3> ()*= double(2.0/m); + R*= 2.0/m; + gicp_->computeRDerivative(x, R, g); +} + +//////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::GeneralizedIterativeClosestPoint::computeTransformation (PointCloudSource &output, const Eigen::Matrix4f& guess) +{ + pcl::IterativeClosestPoint::initComputeReciprocal (); + using namespace std; + // Difference between consecutive transforms + double delta = 0; + // Get the size of the target + const size_t N = indices_->size (); + // Set the mahalanobis matrices to identity + mahalanobis_.resize (N, Eigen::Matrix3d::Identity ()); + // Compute target cloud covariance matrices + if (target_covariances_.empty ()) + computeCovariances (target_, tree_, target_covariances_); + // Compute input cloud covariance matrices + if (input_covariances_.empty ()) + computeCovariances (input_, tree_reciprocal_, input_covariances_); + + base_transformation_ = guess; + nr_iterations_ = 0; + converged_ = false; + double dist_threshold = corr_dist_threshold_ * corr_dist_threshold_; + std::vector nn_indices (1); + std::vector nn_dists (1); + + while(!converged_) + { + size_t cnt = 0; + std::vector source_indices (indices_->size ()); + std::vector target_indices (indices_->size ()); + + // guess corresponds to base_t and transformation_ to t + Eigen::Matrix4d transform_R = Eigen::Matrix4d::Zero (); + for(size_t i = 0; i < 4; i++) + for(size_t j = 0; j < 4; j++) + for(size_t k = 0; k < 4; k++) + transform_R(i,j)+= double(transformation_(i,k)) * double(guess(k,j)); + + Eigen::Matrix3d R = transform_R.topLeftCorner<3,3> (); + + for (size_t i = 0; i < N; i++) + { + PointSource query = output[i]; + query.getVector4fMap () = guess * query.getVector4fMap (); + query.getVector4fMap () = transformation_ * query.getVector4fMap (); + + if (!searchForNeighbors (query, nn_indices, nn_dists)) + { + PCL_ERROR ("[pcl::%s::computeTransformation] Unable to find a nearest neighbor in the target dataset for point %d in the source!\n", getClassName ().c_str (), (*indices_)[i]); + return; + } + + // Check if the distance to the nearest neighbor is smaller than the user imposed threshold + if (nn_dists[0] < dist_threshold) + { + Eigen::Matrix3d &C1 = input_covariances_[i]; + Eigen::Matrix3d &C2 = target_covariances_[nn_indices[0]]; + Eigen::Matrix3d &M = mahalanobis_[i]; + // M = R*C1 + M = R * C1; + // temp = M*R' + C2 = R*C1*R' + C2 + Eigen::Matrix3d temp = M * R.transpose(); + temp+= C2; + // M = temp^-1 + M = temp.inverse (); + source_indices[cnt] = static_cast (i); + target_indices[cnt] = nn_indices[0]; + cnt++; + } + } + // Resize to the actual number of valid correspondences + source_indices.resize(cnt); target_indices.resize(cnt); + /* optimize transformation using the current assignment and Mahalanobis metrics*/ + previous_transformation_ = transformation_; + //optimization right here + try + { + rigid_transformation_estimation_(output, source_indices, *target_, target_indices, transformation_); + /* compute the delta from this iteration */ + delta = 0.; + for(int k = 0; k < 4; k++) { + for(int l = 0; l < 4; l++) { + double ratio = 1; + if(k < 3 && l < 3) // rotation part of the transform + ratio = 1./rotation_epsilon_; + else + ratio = 1./transformation_epsilon_; + double c_delta = ratio*fabs(previous_transformation_(k,l) - transformation_(k,l)); + if(c_delta > delta) + delta = c_delta; + } + } + } + catch (PCLException &e) + { + PCL_DEBUG ("[pcl::%s::computeTransformation] Optimization issue %s\n", getClassName ().c_str (), e.what ()); + break; + } + nr_iterations_++; + // Check for convergence + if (nr_iterations_ >= max_iterations_ || delta < 1) + { + converged_ = true; + previous_transformation_ = transformation_; + PCL_DEBUG ("[pcl::%s::computeTransformation] Convergence reached. Number of iterations: %d out of %d. Transformation difference: %f\n", + getClassName ().c_str (), nr_iterations_, max_iterations_, (transformation_ - previous_transformation_).array ().abs ().sum ()); + } + else + PCL_DEBUG ("[pcl::%s::computeTransformation] Convergence failed\n", getClassName ().c_str ()); + } + //for some reason the static equivalent methode raises an error + // final_transformation_.block<3,3> (0,0) = (transformation_.block<3,3> (0,0)) * (guess.block<3,3> (0,0)); + // final_transformation_.block <3, 1> (0, 3) = transformation_.block <3, 1> (0, 3) + guess.rightCols<1>.block <3, 1> (0, 3); + final_transformation_.topLeftCorner (3,3) = previous_transformation_.topLeftCorner (3,3) * guess.topLeftCorner (3,3); + final_transformation_(0,3) = previous_transformation_(0,3) + guess(0,3); + final_transformation_(1,3) = previous_transformation_(1,3) + guess(1,3); + final_transformation_(2,3) = previous_transformation_(2,3) + guess(2,3); +} + +template void +pcl::GeneralizedIterativeClosestPoint::applyState(Eigen::Matrix4f &t, const Vector6d& x) const +{ + // !!! CAUTION Stanford GICP uses the Z Y X euler angles convention + Eigen::Matrix3f R; + R = Eigen::AngleAxisf (static_cast (x[5]), Eigen::Vector3f::UnitZ ()) + * Eigen::AngleAxisf (static_cast (x[4]), Eigen::Vector3f::UnitY ()) + * Eigen::AngleAxisf (static_cast (x[3]), Eigen::Vector3f::UnitX ()); + t.topLeftCorner<3,3> ().matrix () = R * t.topLeftCorner<3,3> ().matrix (); + Eigen::Vector4f T (static_cast (x[0]), static_cast (x[1]), static_cast (x[2]), 0.0f); + t.col (3) += T; +} + +#endif //PCL_REGISTRATION_IMPL_GICP_HPP_ diff --git a/pcl-1.7/pcl/registration/impl/ia_ransac.hpp b/pcl-1.7/pcl/registration/impl/ia_ransac.hpp new file mode 100644 index 0000000..180572c --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/ia_ransac.hpp @@ -0,0 +1,256 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef IA_RANSAC_HPP_ +#define IA_RANSAC_HPP_ + +#include + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusInitialAlignment::setSourceFeatures (const FeatureCloudConstPtr &features) +{ + if (features == NULL || features->empty ()) + { + PCL_ERROR ("[pcl::%s::setSourceFeatures] Invalid or empty point cloud dataset given!\n", getClassName ().c_str ()); + return; + } + input_features_ = features; +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusInitialAlignment::setTargetFeatures (const FeatureCloudConstPtr &features) +{ + if (features == NULL || features->empty ()) + { + PCL_ERROR ("[pcl::%s::setTargetFeatures] Invalid or empty point cloud dataset given!\n", getClassName ().c_str ()); + return; + } + target_features_ = features; + feature_tree_->setInputCloud (target_features_); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusInitialAlignment::selectSamples ( + const PointCloudSource &cloud, int nr_samples, float min_sample_distance, + std::vector &sample_indices) +{ + if (nr_samples > static_cast (cloud.points.size ())) + { + PCL_ERROR ("[pcl::%s::selectSamples] ", getClassName ().c_str ()); + PCL_ERROR ("The number of samples (%d) must not be greater than the number of points (%lu)!\n", + nr_samples, cloud.points.size ()); + return; + } + + // Iteratively draw random samples until nr_samples is reached + int iterations_without_a_sample = 0; + int max_iterations_without_a_sample = static_cast (3 * cloud.points.size ()); + sample_indices.clear (); + while (static_cast (sample_indices.size ()) < nr_samples) + { + // Choose a sample at random + int sample_index = getRandomIndex (static_cast (cloud.points.size ())); + + // Check to see if the sample is 1) unique and 2) far away from the other samples + bool valid_sample = true; + for (size_t i = 0; i < sample_indices.size (); ++i) + { + float distance_between_samples = euclideanDistance (cloud.points[sample_index], cloud.points[sample_indices[i]]); + + if (sample_index == sample_indices[i] || distance_between_samples < min_sample_distance) + { + valid_sample = false; + break; + } + } + + // If the sample is valid, add it to the output + if (valid_sample) + { + sample_indices.push_back (sample_index); + iterations_without_a_sample = 0; + } + else + ++iterations_without_a_sample; + + // If no valid samples can be found, relax the inter-sample distance requirements + if (iterations_without_a_sample >= max_iterations_without_a_sample) + { + PCL_WARN ("[pcl::%s::selectSamples] ", getClassName ().c_str ()); + PCL_WARN ("No valid sample found after %d iterations. Relaxing min_sample_distance_ to %f\n", + iterations_without_a_sample, 0.5*min_sample_distance); + + min_sample_distance_ *= 0.5f; + min_sample_distance = min_sample_distance_; + iterations_without_a_sample = 0; + } + } +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusInitialAlignment::findSimilarFeatures ( + const FeatureCloud &input_features, const std::vector &sample_indices, + std::vector &corresponding_indices) +{ + std::vector nn_indices (k_correspondences_); + std::vector nn_distances (k_correspondences_); + + corresponding_indices.resize (sample_indices.size ()); + for (size_t i = 0; i < sample_indices.size (); ++i) + { + // Find the k features nearest to input_features.points[sample_indices[i]] + feature_tree_->nearestKSearch (input_features, sample_indices[i], k_correspondences_, nn_indices, nn_distances); + + // Select one at random and add it to corresponding_indices + int random_correspondence = getRandomIndex (k_correspondences_); + corresponding_indices[i] = nn_indices[random_correspondence]; + } +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::SampleConsensusInitialAlignment::computeErrorMetric ( + const PointCloudSource &cloud, float) +{ + std::vector nn_index (1); + std::vector nn_distance (1); + + const ErrorFunctor & compute_error = *error_functor_; + float error = 0; + + for (int i = 0; i < static_cast (cloud.points.size ()); ++i) + { + // Find the distance between cloud.points[i] and its nearest neighbor in the target point cloud + tree_->nearestKSearch (cloud, i, 1, nn_index, nn_distance); + + // Compute the error + error += compute_error (nn_distance[0]); + } + return (error); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusInitialAlignment::computeTransformation (PointCloudSource &output, const Eigen::Matrix4f& guess) +{ + // Some sanity checks first + if (!input_features_) + { + PCL_ERROR ("[pcl::%s::computeTransformation] ", getClassName ().c_str ()); + PCL_ERROR ("No source features were given! Call setSourceFeatures before aligning.\n"); + return; + } + if (!target_features_) + { + PCL_ERROR ("[pcl::%s::computeTransformation] ", getClassName ().c_str ()); + PCL_ERROR ("No target features were given! Call setTargetFeatures before aligning.\n"); + return; + } + + if (input_->size () != input_features_->size ()) + { + PCL_ERROR ("[pcl::%s::computeTransformation] ", getClassName ().c_str ()); + PCL_ERROR ("The source points and source feature points need to be in a one-to-one relationship! Current input cloud sizes: %ld vs %ld.\n", + input_->size (), input_features_->size ()); + return; + } + + if (target_->size () != target_features_->size ()) + { + PCL_ERROR ("[pcl::%s::computeTransformation] ", getClassName ().c_str ()); + PCL_ERROR ("The target points and target feature points need to be in a one-to-one relationship! Current input cloud sizes: %ld vs %ld.\n", + target_->size (), target_features_->size ()); + return; + } + + if (!error_functor_) + error_functor_.reset (new TruncatedError (static_cast (corr_dist_threshold_))); + + + std::vector sample_indices (nr_samples_); + std::vector corresponding_indices (nr_samples_); + PointCloudSource input_transformed; + float error, lowest_error (0); + + final_transformation_ = guess; + int i_iter = 0; + converged_ = false; + if (!guess.isApprox (Eigen::Matrix4f::Identity (), 0.01f)) + { + // If guess is not the Identity matrix we check it. + transformPointCloud (*input_, input_transformed, final_transformation_); + lowest_error = computeErrorMetric (input_transformed, static_cast (corr_dist_threshold_)); + i_iter = 1; + } + + for (; i_iter < max_iterations_; ++i_iter) + { + // Draw nr_samples_ random samples + selectSamples (*input_, nr_samples_, min_sample_distance_, sample_indices); + + // Find corresponding features in the target cloud + findSimilarFeatures (*input_features_, sample_indices, corresponding_indices); + + // Estimate the transform from the samples to their corresponding points + transformation_estimation_->estimateRigidTransformation (*input_, sample_indices, *target_, corresponding_indices, transformation_); + + // Tranform the data and compute the error + transformPointCloud (*input_, input_transformed, transformation_); + error = computeErrorMetric (input_transformed, static_cast (corr_dist_threshold_)); + + // If the new error is lower, update the final transformation + if (i_iter == 0 || error < lowest_error) + { + lowest_error = error; + final_transformation_ = transformation_; + converged_=true; + } + } + + // Apply the final transformation + transformPointCloud (*input_, output, final_transformation_); +} + +#endif //#ifndef IA_RANSAC_HPP_ + diff --git a/pcl-1.7/pcl/registration/impl/icp.hpp b/pcl-1.7/pcl/registration/impl/icp.hpp new file mode 100644 index 0000000..fe89811 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/icp.hpp @@ -0,0 +1,314 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_IMPL_ICP_HPP_ +#define PCL_REGISTRATION_IMPL_ICP_HPP_ + +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IterativeClosestPoint::transformCloud ( + const PointCloudSource &input, + PointCloudSource &output, + const Matrix4 &transform) +{ + Eigen::Vector4f pt (0.0f, 0.0f, 0.0f, 1.0f), pt_t; + Eigen::Matrix4f tr = transform.template cast (); + + // XYZ is ALWAYS present due to the templatization, so we only have to check for normals + if (source_has_normals_) + { + Eigen::Vector3f nt, nt_t; + Eigen::Matrix3f rot = tr.block<3, 3> (0, 0); + + for (size_t i = 0; i < input.size (); ++i) + { + const uint8_t* data_in = reinterpret_cast (&input[i]); + uint8_t* data_out = reinterpret_cast (&output[i]); + memcpy (&pt[0], data_in + x_idx_offset_, sizeof (float)); + memcpy (&pt[1], data_in + y_idx_offset_, sizeof (float)); + memcpy (&pt[2], data_in + z_idx_offset_, sizeof (float)); + + if (!pcl_isfinite (pt[0]) || !pcl_isfinite (pt[1]) || !pcl_isfinite (pt[2])) + continue; + + pt_t = tr * pt; + + memcpy (data_out + x_idx_offset_, &pt_t[0], sizeof (float)); + memcpy (data_out + y_idx_offset_, &pt_t[1], sizeof (float)); + memcpy (data_out + z_idx_offset_, &pt_t[2], sizeof (float)); + + memcpy (&nt[0], data_in + nx_idx_offset_, sizeof (float)); + memcpy (&nt[1], data_in + ny_idx_offset_, sizeof (float)); + memcpy (&nt[2], data_in + nz_idx_offset_, sizeof (float)); + + if (!pcl_isfinite (nt[0]) || !pcl_isfinite (nt[1]) || !pcl_isfinite (nt[2])) + continue; + + nt_t = rot * nt; + + memcpy (data_out + nx_idx_offset_, &nt_t[0], sizeof (float)); + memcpy (data_out + ny_idx_offset_, &nt_t[1], sizeof (float)); + memcpy (data_out + nz_idx_offset_, &nt_t[2], sizeof (float)); + } + } + else + { + for (size_t i = 0; i < input.size (); ++i) + { + const uint8_t* data_in = reinterpret_cast (&input[i]); + uint8_t* data_out = reinterpret_cast (&output[i]); + memcpy (&pt[0], data_in + x_idx_offset_, sizeof (float)); + memcpy (&pt[1], data_in + y_idx_offset_, sizeof (float)); + memcpy (&pt[2], data_in + z_idx_offset_, sizeof (float)); + + if (!pcl_isfinite (pt[0]) || !pcl_isfinite (pt[1]) || !pcl_isfinite (pt[2])) + continue; + + pt_t = tr * pt; + + memcpy (data_out + x_idx_offset_, &pt_t[0], sizeof (float)); + memcpy (data_out + y_idx_offset_, &pt_t[1], sizeof (float)); + memcpy (data_out + z_idx_offset_, &pt_t[2], sizeof (float)); + } + } + +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IterativeClosestPoint::computeTransformation ( + PointCloudSource &output, const Matrix4 &guess) +{ + // PCL_ERROR ("computeTransformation()\n"); + // Point cloud containing the correspondences of each point in + PointCloudSourcePtr input_transformed (new PointCloudSource); + + nr_iterations_ = 0; + converged_ = false; + + // Initialise final transformation to the guessed one + final_transformation_ = guess; + + // If the guessed transformation is non identity + if (guess != Matrix4::Identity ()) + { + input_transformed->resize (input_->size ()); + // Apply guessed transformation prior to search for neighbours + transformCloud (*input_, *input_transformed, guess); + } + else + *input_transformed = *input_; + + transformation_ = Matrix4::Identity (); + + // Make blobs if necessary + determineRequiredBlobData (); + PCLPointCloud2::Ptr target_blob (new PCLPointCloud2); + if (need_target_blob_) + pcl::toPCLPointCloud2 (*target_, *target_blob); + + + + correspondence_estimation_->setInputTarget (target_); + if (correspondence_estimation_->requiresTargetNormals ()) + correspondence_estimation_->setTargetNormals (target_blob); + // Correspondence Rejectors need a binary blob + for (size_t i = 0; i < correspondence_rejectors_.size (); ++i) + { + registration::CorrespondenceRejector::Ptr& rej = correspondence_rejectors_[i]; + if (rej->requiresTargetPoints ()) + rej->setTargetPoints (target_blob); + if (rej->requiresTargetNormals () && target_has_normals_) + rej->setTargetNormals (target_blob); + } + + convergence_criteria_->setMaximumIterations (max_iterations_); + convergence_criteria_->setRelativeMSE (euclidean_fitness_epsilon_); + convergence_criteria_->setTranslationThreshold (transformation_epsilon_); + convergence_criteria_->setRotationThreshold (1.0 - transformation_epsilon_); + + // Repeat until convergence + do + { + // Get blob data if needed + PCLPointCloud2::Ptr input_transformed_blob; + if (need_source_blob_) + { + input_transformed_blob.reset (new PCLPointCloud2); + toPCLPointCloud2 (*input_transformed, *input_transformed_blob); + } + // Save the previously estimated transformation + previous_transformation_ = transformation_; + + // Set the source each iteration, to ensure the dirty flag is updated + + correspondence_estimation_->setInputSource (input_transformed); + if (correspondence_estimation_->requiresSourceNormals ()) + { + // std::cout << "using normal" << std::endl; + correspondence_estimation_->setSourceNormals (input_transformed_blob); + } + // Estimate correspondences + + /* 2. Matching */ + if (use_reciprocal_correspondence_) + correspondence_estimation_->determineReciprocalCorrespondences (*correspondences_, corr_dist_threshold_); + else + correspondence_estimation_->determineCorrespondences (*correspondences_, corr_dist_threshold_); + + /* 4. Rejecting */ + //if (correspondence_rejectors_.empty ()) + // std::cout << "correspondence_rejectors_:" << correspondence_rejectors_.size () << std::endl; + + CorrespondencesPtr temp_correspondences (new Correspondences (*correspondences_)); + for (size_t i = 0; i < correspondence_rejectors_.size (); ++i) + { + registration::CorrespondenceRejector::Ptr& rej = correspondence_rejectors_[i]; + //PCL_DEBUG ("Applying a correspondence rejector method: %s.\n", rej->getClassName ().c_str ()); + // std::cout << "Applying a correspondence rejector method:" << rej->getClassName ().c_str () << std::endl; + if (rej->requiresSourcePoints ()) + rej->setSourcePoints (input_transformed_blob); + if (rej->requiresSourceNormals () && source_has_normals_) + rej->setSourceNormals (input_transformed_blob); + rej->setInputCorrespondences (temp_correspondences); + rej->getCorrespondences (*correspondences_); + + // Modify input for the next iteration + if (i < correspondence_rejectors_.size () - 1) + *temp_correspondences = *correspondences_; + } + + size_t cnt = correspondences_->size (); + // Check whether we have enough correspondences + if (static_cast (cnt) < min_number_correspondences_) + { + PCL_ERROR ("[pcl::%s::computeTransformation] Not enough correspondences found. Relaxxx your threshold parameters.\n", getClassName ().c_str ()); + convergence_criteria_->setConvergenceState(pcl::registration::DefaultConvergenceCriteria::CONVERGENCE_CRITERIA_NO_CORRESPONDENCES); + converged_ = false; + break; + } + + /* 5&6. Error Metric && Minimizing */ + // Estimate the transform + transformation_estimation_->estimateRigidTransformation (*input_transformed, *target_, *correspondences_, transformation_); + + // Tranform the data + transformCloud (*input_transformed, *input_transformed, transformation_); + + // Obtain the final transformation + final_transformation_ = transformation_ * final_transformation_; + + ++nr_iterations_; + + // Update the vizualization of icp convergence + // if (update_visualizer_ != 0) + // update_visualizer_(output, source_indices_good, *target_, target_indices_good ); + + converged_ = static_cast ((*convergence_criteria_)); + } + while (!converged_); + + correspondence_estimation_->getApproxNNOpsNum(approx_nn_ops_num_); + correspondence_estimation_->getApproxLeadersNum(approx_leaders_num_); + correspondence_estimation_->getApproxFollowersNum(approx_followers_num_); + + // Transform the input cloud using the final transformation + PCL_DEBUG ("Transformation is:\n\t%5f\t%5f\t%5f\t%5f\n\t%5f\t%5f\t%5f\t%5f\n\t%5f\t%5f\t%5f\t%5f\n\t%5f\t%5f\t%5f\t%5f\n", + final_transformation_ (0, 0), final_transformation_ (0, 1), final_transformation_ (0, 2), final_transformation_ (0, 3), + final_transformation_ (1, 0), final_transformation_ (1, 1), final_transformation_ (1, 2), final_transformation_ (1, 3), + final_transformation_ (2, 0), final_transformation_ (2, 1), final_transformation_ (2, 2), final_transformation_ (2, 3), + final_transformation_ (3, 0), final_transformation_ (3, 1), final_transformation_ (3, 2), final_transformation_ (3, 3)); + + // Copy all the values + output = *input_; + // Transform the XYZ + normals + transformCloud (*input_, output, final_transformation_); +} + +template void +pcl::IterativeClosestPoint::determineRequiredBlobData () +{ + need_source_blob_ = false; + need_target_blob_ = false; + // Check estimator + need_source_blob_ |= correspondence_estimation_->requiresSourceNormals (); + need_target_blob_ |= correspondence_estimation_->requiresTargetNormals (); + // Add warnings if necessary + if (correspondence_estimation_->requiresSourceNormals () && !source_has_normals_) + { + PCL_WARN("[pcl::%s::determineRequiredBlobData] Estimator expects source normals, but we can't provide them.\n", getClassName ().c_str ()); + } + if (correspondence_estimation_->requiresTargetNormals () && !target_has_normals_) + { + PCL_WARN("[pcl::%s::determineRequiredBlobData] Estimator expects target normals, but we can't provide them.\n", getClassName ().c_str ()); + } + // Check rejectors + for (size_t i = 0; i < correspondence_rejectors_.size (); i++) + { + registration::CorrespondenceRejector::Ptr& rej = correspondence_rejectors_[i]; + need_source_blob_ |= rej->requiresSourcePoints (); + need_source_blob_ |= rej->requiresSourceNormals (); + need_target_blob_ |= rej->requiresTargetPoints (); + need_target_blob_ |= rej->requiresTargetNormals (); + if (rej->requiresSourceNormals () && !source_has_normals_) + { + PCL_WARN("[pcl::%s::determineRequiredBlobData] Rejector %s expects source normals, but we can't provide them.\n", getClassName ().c_str (), rej->getClassName ().c_str ()); + } + if (rej->requiresTargetNormals () && !target_has_normals_) + { + PCL_WARN("[pcl::%s::determineRequiredBlobData] Rejector %s expects target normals, but we can't provide them.\n", getClassName ().c_str (), rej->getClassName ().c_str ()); + } + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::IterativeClosestPointWithNormals::transformCloud ( + const PointCloudSource &input, + PointCloudSource &output, + const Matrix4 &transform) +{ + pcl::transformPointCloudWithNormals (input, output, transform); +} + +#endif /* PCL_REGISTRATION_IMPL_ICP_HPP_ */ \ No newline at end of file diff --git a/pcl-1.7/pcl/registration/impl/icp_nl.hpp b/pcl-1.7/pcl/registration/impl/icp_nl.hpp new file mode 100644 index 0000000..0cbf0ba --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/icp_nl.hpp @@ -0,0 +1,44 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_ICP_NL_HPP_ +#define PCL_REGISTRATION_ICP_NL_HPP_ + +#endif /* PCL_REGISTRATION_ICP_NL_HPP_ */ + diff --git a/pcl-1.7/pcl/registration/impl/joint_icp.hpp b/pcl-1.7/pcl/registration/impl/joint_icp.hpp new file mode 100644 index 0000000..a3623c1 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/joint_icp.hpp @@ -0,0 +1,326 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_REGISTRATION_IMPL_JOINT_ICP_HPP_ +#define PCL_REGISTRATION_IMPL_JOINT_ICP_HPP_ + +#include +#include +#include + + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::JointIterativeClosestPoint::computeTransformation ( + PointCloudSource &output, const Matrix4 &guess) +{ + // Point clouds containing the correspondences of each point in + if (sources_.size () != targets_.size () || sources_.empty () || targets_.empty ()) + { + PCL_ERROR ("[pcl::%s::computeTransformation] Must set InputSources and InputTargets to the same, nonzero size!\n", + getClassName ().c_str ()); + return; + } + bool manual_correspondence_estimations_set = true; + if (correspondence_estimations_.empty ()) + { + manual_correspondence_estimations_set = false; + correspondence_estimations_.resize (sources_.size ()); + for (size_t i = 0; i < sources_.size (); i++) + { + correspondence_estimations_[i] = correspondence_estimation_->clone (); + KdTreeReciprocalPtr src_tree (new KdTreeReciprocal); + KdTreePtr tgt_tree (new KdTree); + correspondence_estimations_[i]->setSearchMethodTarget (tgt_tree); + correspondence_estimations_[i]->setSearchMethodSource (src_tree); + } + } + if (correspondence_estimations_.size () != sources_.size ()) + { + PCL_ERROR ("[pcl::%s::computeTransform] Must set CorrespondenceEstimations to be the same size as the joint\n", + getClassName ().c_str ()); + return; + } + std::vector inputs_transformed (sources_.size ()); + for (size_t i = 0; i < sources_.size (); i++) + { + inputs_transformed[i].reset (new PointCloudSource); + } + + nr_iterations_ = 0; + converged_ = false; + + // Initialise final transformation to the guessed one + final_transformation_ = guess; + + // Make a combined transformed input and output + std::vector input_offsets (sources_.size ()); + std::vector target_offsets (targets_.size ()); + PointCloudSourcePtr sources_combined (new PointCloudSource); + PointCloudSourcePtr inputs_transformed_combined (new PointCloudSource); + PointCloudTargetPtr targets_combined (new PointCloudTarget); + size_t input_offset = 0; + size_t target_offset = 0; + for (size_t i = 0; i < sources_.size (); i++) + { + // If the guessed transformation is non identity + if (guess != Matrix4::Identity ()) + { + // Apply guessed transformation prior to search for neighbours + this->transformCloud (*sources_[i], *inputs_transformed[i], guess); + } + else + { + *inputs_transformed[i] = *sources_[i]; + } + *sources_combined += *sources_[i]; + *inputs_transformed_combined += *inputs_transformed[i]; + *targets_combined += *targets_[i]; + input_offsets[i] = input_offset; + target_offsets[i] = target_offset; + input_offset += inputs_transformed[i]->size (); + target_offset += targets_[i]->size (); + } + + + + transformation_ = Matrix4::Identity (); + // Make blobs if necessary + determineRequiredBlobData (); + // Pass in the default target for the Correspondence Estimation/Rejection code + for (size_t i = 0; i < sources_.size (); i++) + { + correspondence_estimations_[i]->setInputTarget (targets_[i]); + if (correspondence_estimations_[i]->requiresTargetNormals ()) + { + PCLPointCloud2::Ptr target_blob (new PCLPointCloud2); + pcl::toPCLPointCloud2 (*targets_[i], *target_blob); + correspondence_estimations_[i]->setTargetNormals (target_blob); + } + } + + PCLPointCloud2::Ptr targets_combined_blob (new PCLPointCloud2); + if (!correspondence_rejectors_.empty () && need_target_blob_) + pcl::toPCLPointCloud2 (*targets_combined, *targets_combined_blob); + + for (size_t i = 0; i < correspondence_rejectors_.size (); ++i) + { + registration::CorrespondenceRejector::Ptr& rej = correspondence_rejectors_[i]; + if (rej->requiresTargetPoints ()) + rej->setTargetPoints (targets_combined_blob); + if (rej->requiresTargetNormals () && target_has_normals_) + rej->setTargetNormals (targets_combined_blob); + } + + convergence_criteria_->setMaximumIterations (max_iterations_); + convergence_criteria_->setRelativeMSE (euclidean_fitness_epsilon_); + convergence_criteria_->setTranslationThreshold (transformation_epsilon_); + convergence_criteria_->setRotationThreshold (1.0 - transformation_epsilon_); + + // Repeat until convergence + std::vector partial_correspondences_ (sources_.size ()); + for (size_t i = 0; i < sources_.size (); i++) + { + partial_correspondences_[i].reset (new pcl::Correspondences); + } + + do + { + // Save the previously estimated transformation + previous_transformation_ = transformation_; + + // Set the source each iteration, to ensure the dirty flag is updated + correspondences_->clear (); + for (size_t i = 0; i < correspondence_estimations_.size (); i++) + { + correspondence_estimations_[i]->setInputSource (inputs_transformed[i]); + // Get blob data if needed + if (correspondence_estimations_[i]->requiresSourceNormals ()) + { + PCLPointCloud2::Ptr input_transformed_blob (new PCLPointCloud2); + toPCLPointCloud2 (*inputs_transformed[i], *input_transformed_blob); + correspondence_estimations_[i]->setSourceNormals (input_transformed_blob); + } + + // Estimate correspondences on each cloud pair separately + if (use_reciprocal_correspondence_) + { + correspondence_estimations_[i]->determineReciprocalCorrespondences (*partial_correspondences_[i], corr_dist_threshold_); + } + else + { + correspondence_estimations_[i]->determineCorrespondences (*partial_correspondences_[i], corr_dist_threshold_); + } + PCL_DEBUG ("[pcl::%s::computeTransformation] Found %d partial correspondences for cloud [%d]\n", + getClassName ().c_str (), + partial_correspondences_[i]->size (), i); + for (size_t j = 0; j < partial_correspondences_[i]->size (); j++) + { + pcl::Correspondence corr = partial_correspondences_[i]->at (j); + // Update the offsets to be for the combined clouds + corr.index_query += input_offsets[i]; + corr.index_match += target_offsets[i]; + correspondences_->push_back (corr); + } + } + PCL_DEBUG ("[pcl::%s::computeTransformation] Total correspondences: %d\n", getClassName ().c_str (), correspondences_->size ()); + + PCLPointCloud2::Ptr inputs_transformed_combined_blob; + if (need_source_blob_) + { + inputs_transformed_combined_blob.reset (new PCLPointCloud2); + toPCLPointCloud2 (*inputs_transformed_combined, *inputs_transformed_combined_blob); + } + CorrespondencesPtr temp_correspondences (new Correspondences (*correspondences_)); + for (size_t i = 0; i < correspondence_rejectors_.size (); ++i) + { + PCL_DEBUG ("Applying a correspondence rejector method: %s.\n", correspondence_rejectors_[i]->getClassName ().c_str ()); + registration::CorrespondenceRejector::Ptr& rej = correspondence_rejectors_[i]; + PCL_DEBUG ("Applying a correspondence rejector method: %s.\n", rej->getClassName ().c_str ()); + if (rej->requiresSourcePoints ()) + rej->setSourcePoints (inputs_transformed_combined_blob); + if (rej->requiresSourceNormals () && source_has_normals_) + rej->setSourceNormals (inputs_transformed_combined_blob); + rej->setInputCorrespondences (temp_correspondences); + rej->getCorrespondences (*correspondences_); + // Modify input for the next iteration + if (i < correspondence_rejectors_.size () - 1) + *temp_correspondences = *correspondences_; + } + + int cnt = correspondences_->size (); + // Check whether we have enough correspondences + if (cnt < min_number_correspondences_) + { + PCL_ERROR ("[pcl::%s::computeTransformation] Not enough correspondences found. Relax your threshold parameters.\n", getClassName ().c_str ()); + convergence_criteria_->setConvergenceState(pcl::registration::DefaultConvergenceCriteria::CONVERGENCE_CRITERIA_NO_CORRESPONDENCES); + converged_ = false; + break; + } + + // Estimate the transform jointly, on a combined correspondence set + transformation_estimation_->estimateRigidTransformation (*inputs_transformed_combined, *targets_combined, *correspondences_, transformation_); + + // Tranform the combined data + this->transformCloud (*inputs_transformed_combined, *inputs_transformed_combined, transformation_); + // And all its components + for (size_t i = 0; i < sources_.size (); i++) + { + this->transformCloud (*inputs_transformed[i], *inputs_transformed[i], transformation_); + } + + // Obtain the final transformation + final_transformation_ = transformation_ * final_transformation_; + + ++nr_iterations_; + + // Update the vizualization of icp convergence + //if (update_visualizer_ != 0) + // update_visualizer_(output, source_indices_good, *target_, target_indices_good ); + + converged_ = static_cast ((*convergence_criteria_)); + } + while (!converged_); + + PCL_DEBUG ("Transformation is:\n\t%5f\t%5f\t%5f\t%5f\n\t%5f\t%5f\t%5f\t%5f\n\t%5f\t%5f\t%5f\t%5f\n\t%5f\t%5f\t%5f\t%5f\n", + final_transformation_ (0, 0), final_transformation_ (0, 1), final_transformation_ (0, 2), final_transformation_ (0, 3), + final_transformation_ (1, 0), final_transformation_ (1, 1), final_transformation_ (1, 2), final_transformation_ (1, 3), + final_transformation_ (2, 0), final_transformation_ (2, 1), final_transformation_ (2, 2), final_transformation_ (2, 3), + final_transformation_ (3, 0), final_transformation_ (3, 1), final_transformation_ (3, 2), final_transformation_ (3, 3)); + + // For fitness checks, etc, we'll use an aggregated cloud for now (should be evaluating independently for correctness, but this requires propagating a few virtual methods from Registration) + IterativeClosestPoint::setInputSource (sources_combined); + IterativeClosestPoint::setInputTarget (targets_combined); + + // If we automatically set the correspondence estimators, we should clear them now + if (!manual_correspondence_estimations_set) + { + correspondence_estimations_.clear (); + } + + + // By definition, this method will return an empty cloud (for compliance with the ICP API). + // We can figure out a better solution, if necessary. + output = PointCloudSource (); +} + + template void +pcl::JointIterativeClosestPoint::determineRequiredBlobData () +{ + need_source_blob_ = false; + need_target_blob_ = false; + // Check estimators + for (size_t i = 0; i < correspondence_estimations_.size (); i++) + { + CorrespondenceEstimationPtr& ce = correspondence_estimations_[i]; + + need_source_blob_ |= ce->requiresSourceNormals (); + need_target_blob_ |= ce->requiresTargetNormals (); + // Add warnings if necessary + if (ce->requiresSourceNormals () && !source_has_normals_) + { + PCL_WARN("[pcl::%s::determineRequiredBlobData] Estimator expects source normals, but we can't provide them.\n", getClassName ().c_str ()); + } + if (ce->requiresTargetNormals () && !target_has_normals_) + { + PCL_WARN("[pcl::%s::determineRequiredBlobData] Estimator expects target normals, but we can't provide them.\n", getClassName ().c_str ()); + } + } + // Check rejectors + for (size_t i = 0; i < correspondence_rejectors_.size (); i++) + { + registration::CorrespondenceRejector::Ptr& rej = correspondence_rejectors_[i]; + need_source_blob_ |= rej->requiresSourcePoints (); + need_source_blob_ |= rej->requiresSourceNormals (); + need_target_blob_ |= rej->requiresTargetPoints (); + need_target_blob_ |= rej->requiresTargetNormals (); + if (rej->requiresSourceNormals () && !source_has_normals_) + { + PCL_WARN("[pcl::%s::determineRequiredBlobData] Rejector %s expects source normals, but we can't provide them.\n", getClassName ().c_str (), rej->getClassName ().c_str ()); + } + if (rej->requiresTargetNormals () && !target_has_normals_) + { + PCL_WARN("[pcl::%s::determineRequiredBlobData] Rejector %s expects target normals, but we can't provide them.\n", getClassName ().c_str (), rej->getClassName ().c_str ()); + } + } +} + + +#endif /* PCL_REGISTRATION_IMPL_JOINT_ICP_HPP_ */ + + diff --git a/pcl-1.7/pcl/registration/impl/lum.hpp b/pcl-1.7/pcl/registration/impl/lum.hpp new file mode 100644 index 0000000..7f854a9 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/lum.hpp @@ -0,0 +1,424 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: lum.hpp 5663 2012-05-02 13:49:39Z florentinus $ + * + */ + +#ifndef PCL_REGISTRATION_IMPL_LUM_HPP_ +#define PCL_REGISTRATION_IMPL_LUM_HPP_ + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::LUM::setLoopGraph (const SLAMGraphPtr &slam_graph) +{ + slam_graph_ = slam_graph; +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template inline typename pcl::registration::LUM::SLAMGraphPtr +pcl::registration::LUM::getLoopGraph () const +{ + return (slam_graph_); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::registration::LUM::SLAMGraph::vertices_size_type +pcl::registration::LUM::getNumVertices () const +{ + return (num_vertices (*slam_graph_)); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::LUM::setMaxIterations (int max_iterations) +{ + max_iterations_ = max_iterations; +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template inline int +pcl::registration::LUM::getMaxIterations () const +{ + return (max_iterations_); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::LUM::setConvergenceThreshold (float convergence_threshold) +{ + convergence_threshold_ = convergence_threshold; +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template inline float +pcl::registration::LUM::getConvergenceThreshold () const +{ + return (convergence_threshold_); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::registration::LUM::Vertex +pcl::registration::LUM::addPointCloud (const PointCloudPtr &cloud, const Eigen::Vector6f &pose) +{ + Vertex v = add_vertex (*slam_graph_); + (*slam_graph_)[v].cloud_ = cloud; + if (v == 0 && pose != Eigen::Vector6f::Zero ()) + { + PCL_WARN("[pcl::registration::LUM::addPointCloud] The pose estimate is ignored for the first cloud in the graph since that will become the reference pose.\n"); + (*slam_graph_)[v].pose_ = Eigen::Vector6f::Zero (); + return (v); + } + (*slam_graph_)[v].pose_ = pose; + return (v); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::LUM::setPointCloud (const Vertex &vertex, const PointCloudPtr &cloud) +{ + if (vertex >= getNumVertices ()) + { + PCL_ERROR("[pcl::registration::LUM::setPointCloud] You are attempting to set a point cloud to a non-existing graph vertex.\n"); + return; + } + (*slam_graph_)[vertex].cloud_ = cloud; +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template inline typename pcl::registration::LUM::PointCloudPtr +pcl::registration::LUM::getPointCloud (const Vertex &vertex) const +{ + if (vertex >= getNumVertices ()) + { + PCL_ERROR("[pcl::registration::LUM::getPointCloud] You are attempting to get a point cloud from a non-existing graph vertex.\n"); + return (PointCloudPtr ()); + } + return ((*slam_graph_)[vertex].cloud_); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::LUM::setPose (const Vertex &vertex, const Eigen::Vector6f &pose) +{ + if (vertex >= getNumVertices ()) + { + PCL_ERROR("[pcl::registration::LUM::setPose] You are attempting to set a pose estimate to a non-existing graph vertex.\n"); + return; + } + if (vertex == 0) + { + PCL_ERROR("[pcl::registration::LUM::setPose] The pose estimate is ignored for the first cloud in the graph since that will become the reference pose.\n"); + return; + } + (*slam_graph_)[vertex].pose_ = pose; +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template inline Eigen::Vector6f +pcl::registration::LUM::getPose (const Vertex &vertex) const +{ + if (vertex >= getNumVertices ()) + { + PCL_ERROR("[pcl::registration::LUM::getPose] You are attempting to get a pose estimate from a non-existing graph vertex.\n"); + return (Eigen::Vector6f::Zero ()); + } + return ((*slam_graph_)[vertex].pose_); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template inline Eigen::Affine3f +pcl::registration::LUM::getTransformation (const Vertex &vertex) const +{ + Eigen::Vector6f pose = getPose (vertex); + return (pcl::getTransformation (pose (0), pose (1), pose (2), pose (3), pose (4), pose (5))); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::LUM::setCorrespondences (const Vertex &source_vertex, const Vertex &target_vertex, const pcl::CorrespondencesPtr &corrs) +{ + if (source_vertex >= getNumVertices () || target_vertex >= getNumVertices () || source_vertex == target_vertex) + { + PCL_ERROR("[pcl::registration::LUM::setCorrespondences] You are attempting to set a set of correspondences between non-existing or identical graph vertices.\n"); + return; + } + Edge e; + bool present; + boost::tuples::tie (e, present) = edge (source_vertex, target_vertex, *slam_graph_); + if (!present) + boost::tuples::tie (e, present) = add_edge (source_vertex, target_vertex, *slam_graph_); + (*slam_graph_)[e].corrs_ = corrs; +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template inline pcl::CorrespondencesPtr +pcl::registration::LUM::getCorrespondences (const Vertex &source_vertex, const Vertex &target_vertex) const +{ + if (source_vertex >= getNumVertices () || target_vertex >= getNumVertices ()) + { + PCL_ERROR("[pcl::registration::LUM::getCorrespondences] You are attempting to get a set of correspondences between non-existing graph vertices.\n"); + return (pcl::CorrespondencesPtr ()); + } + Edge e; + bool present; + boost::tuples::tie (e, present) = edge (source_vertex, target_vertex, *slam_graph_); + if (!present) + { + PCL_ERROR("[pcl::registration::LUM::getCorrespondences] You are attempting to get a set of correspondences from a non-existing graph edge.\n"); + return (pcl::CorrespondencesPtr ()); + } + return ((*slam_graph_)[e].corrs_); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::LUM::compute () +{ + int n = static_cast (getNumVertices ()); + if (n < 2) + { + PCL_ERROR("[pcl::registration::LUM::compute] The slam graph needs at least 2 vertices.\n"); + return; + } + for (int i = 0; i < max_iterations_; ++i) + { + // Linearized computation of C^-1 and C^-1*D and convergence checking for all edges in the graph (results stored in slam_graph_) + typename SLAMGraph::edge_iterator e, e_end; + for (boost::tuples::tie (e, e_end) = edges (*slam_graph_); e != e_end; ++e) + computeEdge (*e); + + // Declare matrices G and B + Eigen::MatrixXf G = Eigen::MatrixXf::Zero (6 * (n - 1), 6 * (n - 1)); + Eigen::VectorXf B = Eigen::VectorXf::Zero (6 * (n - 1)); + + // Start at 1 because 0 is the reference pose + for (int vi = 1; vi != n; ++vi) + { + for (int vj = 0; vj != n; ++vj) + { + // Attempt to use the forward edge, otherwise use backward edge, otherwise there was no edge + Edge e; + bool present1, present2; + boost::tuples::tie (e, present1) = edge (vi, vj, *slam_graph_); + if (!present1) + { + boost::tuples::tie (e, present2) = edge (vj, vi, *slam_graph_); + if (!present2) + continue; + } + + // Fill in elements of G and B + if (vj > 0) + G.block (6 * (vi - 1), 6 * (vj - 1), 6, 6) = -(*slam_graph_)[e].cinv_; + G.block (6 * (vi - 1), 6 * (vi - 1), 6, 6) += (*slam_graph_)[e].cinv_; + B.segment (6 * (vi - 1), 6) += (present1 ? 1 : -1) * (*slam_graph_)[e].cinvd_; + } + } + + // Computation of the linear equation system: GX = B + // TODO investigate accuracy vs. speed tradeoff and find the best solving method for our type of linear equation (sparse) + Eigen::VectorXf X = G.colPivHouseholderQr ().solve (B); + + // Update the poses + float sum = 0.0; + for (int vi = 1; vi != n; ++vi) + { + Eigen::Vector6f difference_pose = static_cast (-incidenceCorrection (getPose (vi)).inverse () * X.segment (6 * (vi - 1), 6)); + sum += difference_pose.norm (); + setPose (vi, getPose (vi) + difference_pose); + } + + // Convergence check + if (sum <= convergence_threshold_ * static_cast (n - 1)) + return; + } +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::registration::LUM::PointCloudPtr +pcl::registration::LUM::getTransformedCloud (const Vertex &vertex) const +{ + PointCloudPtr out (new PointCloud); + pcl::transformPointCloud (*getPointCloud (vertex), *out, getTransformation (vertex)); + return (out); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::registration::LUM::PointCloudPtr +pcl::registration::LUM::getConcatenatedCloud () const +{ + PointCloudPtr out (new PointCloud); + typename SLAMGraph::vertex_iterator v, v_end; + for (boost::tuples::tie (v, v_end) = vertices (*slam_graph_); v != v_end; ++v) + { + PointCloud temp; + pcl::transformPointCloud (*getPointCloud (*v), temp, getTransformation (*v)); + *out += temp; + } + return (out); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::LUM::computeEdge (const Edge &e) +{ + // Get necessary local data from graph + PointCloudPtr source_cloud = (*slam_graph_)[source (e, *slam_graph_)].cloud_; + PointCloudPtr target_cloud = (*slam_graph_)[target (e, *slam_graph_)].cloud_; + Eigen::Vector6f source_pose = (*slam_graph_)[source (e, *slam_graph_)].pose_; + Eigen::Vector6f target_pose = (*slam_graph_)[target (e, *slam_graph_)].pose_; + pcl::CorrespondencesPtr corrs = (*slam_graph_)[e].corrs_; + + // Build the average and difference vectors for all correspondences + std::vector corrs_aver (corrs->size ()); + std::vector corrs_diff (corrs->size ()); + int oci = 0; // oci = output correspondence iterator + for (int ici = 0; ici != static_cast (corrs->size ()); ++ici) // ici = input correspondence iterator + { + // Compound the point pair onto the current pose + Eigen::Vector3f source_compounded = pcl::getTransformation (source_pose (0), source_pose (1), source_pose (2), source_pose (3), source_pose (4), source_pose (5)) * source_cloud->points[(*corrs)[ici].index_query].getVector3fMap (); + Eigen::Vector3f target_compounded = pcl::getTransformation (target_pose (0), target_pose (1), target_pose (2), target_pose (3), target_pose (4), target_pose (5)) * target_cloud->points[(*corrs)[ici].index_match].getVector3fMap (); + + // NaN points can not be passed to the remaining computational pipeline + if (!pcl_isfinite (source_compounded (0)) || !pcl_isfinite (source_compounded (1)) || !pcl_isfinite (source_compounded (2)) || !pcl_isfinite (target_compounded (0)) || !pcl_isfinite (target_compounded (1)) || !pcl_isfinite (target_compounded (2))) + continue; + + // Compute the point pair average and difference and store for later use + corrs_aver[oci] = 0.5 * (source_compounded + target_compounded); + corrs_diff[oci] = source_compounded - target_compounded; + oci++; + } + corrs_aver.resize (oci); + corrs_diff.resize (oci); + + // Need enough valid correspondences to get a good triangulation + if (oci < 3) + { + PCL_WARN("[pcl::registration::LUM::compute] The correspondences between vertex %d and %d do not contain enough valid correspondences to be considered for computation.\n", source (e, *slam_graph_), target (e, *slam_graph_)); + (*slam_graph_)[e].cinv_ = Eigen::Matrix6f::Zero (); + (*slam_graph_)[e].cinvd_ = Eigen::Vector6f::Zero (); + return; + } + + // Build the matrices M'M and M'Z + Eigen::Matrix6f MM = Eigen::Matrix6f::Zero (); + Eigen::Vector6f MZ = Eigen::Vector6f::Zero (); + for (int ci = 0; ci != oci; ++ci) // ci = correspondence iterator + { + // Fast computation of summation elements of M'M + MM (0, 4) -= corrs_aver[ci] (1); + MM (0, 5) += corrs_aver[ci] (2); + MM (1, 3) -= corrs_aver[ci] (2); + MM (1, 4) += corrs_aver[ci] (0); + MM (2, 3) += corrs_aver[ci] (1); + MM (2, 5) -= corrs_aver[ci] (0); + MM (3, 4) -= corrs_aver[ci] (0) * corrs_aver[ci] (2); + MM (3, 5) -= corrs_aver[ci] (0) * corrs_aver[ci] (1); + MM (4, 5) -= corrs_aver[ci] (1) * corrs_aver[ci] (2); + MM (3, 3) += corrs_aver[ci] (1) * corrs_aver[ci] (1) + corrs_aver[ci] (2) * corrs_aver[ci] (2); + MM (4, 4) += corrs_aver[ci] (0) * corrs_aver[ci] (0) + corrs_aver[ci] (1) * corrs_aver[ci] (1); + MM (5, 5) += corrs_aver[ci] (0) * corrs_aver[ci] (0) + corrs_aver[ci] (2) * corrs_aver[ci] (2); + + // Fast computation of M'Z + MZ (0) += corrs_diff[ci] (0); + MZ (1) += corrs_diff[ci] (1); + MZ (2) += corrs_diff[ci] (2); + MZ (3) += corrs_aver[ci] (1) * corrs_diff[ci] (2) - corrs_aver[ci] (2) * corrs_diff[ci] (1); + MZ (4) += corrs_aver[ci] (0) * corrs_diff[ci] (1) - corrs_aver[ci] (1) * corrs_diff[ci] (0); + MZ (5) += corrs_aver[ci] (2) * corrs_diff[ci] (0) - corrs_aver[ci] (0) * corrs_diff[ci] (2); + } + // Remaining elements of M'M + MM (0, 0) = MM (1, 1) = MM (2, 2) = static_cast (oci); + MM (4, 0) = MM (0, 4); + MM (5, 0) = MM (0, 5); + MM (3, 1) = MM (1, 3); + MM (4, 1) = MM (1, 4); + MM (3, 2) = MM (2, 3); + MM (5, 2) = MM (2, 5); + MM (4, 3) = MM (3, 4); + MM (5, 3) = MM (3, 5); + MM (5, 4) = MM (4, 5); + + // Compute pose difference estimation + Eigen::Vector6f D = static_cast (MM.inverse () * MZ); + + // Compute s^2 + float ss = 0.0f; + for (int ci = 0; ci != oci; ++ci) // ci = correspondence iterator + ss += static_cast (pow (corrs_diff[ci] (0) - (D (0) + corrs_aver[ci] (2) * D (5) - corrs_aver[ci] (1) * D (4)), 2.0f) + + pow (corrs_diff[ci] (1) - (D (1) + corrs_aver[ci] (0) * D (4) - corrs_aver[ci] (2) * D (3)), 2.0f) + + pow (corrs_diff[ci] (2) - (D (2) + corrs_aver[ci] (1) * D (3) - corrs_aver[ci] (0) * D (5)), 2.0f)); + + // When reaching the limitations of computation due to linearization + if (ss < 0.0000000000001 || !pcl_isfinite (ss)) + { + (*slam_graph_)[e].cinv_ = Eigen::Matrix6f::Zero (); + (*slam_graph_)[e].cinvd_ = Eigen::Vector6f::Zero (); + return; + } + + // Store the results in the slam graph + (*slam_graph_)[e].cinv_ = MM * (1.0f / ss); + (*slam_graph_)[e].cinvd_ = MZ * (1.0f / ss); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template inline Eigen::Matrix6f +pcl::registration::LUM::incidenceCorrection (const Eigen::Vector6f &pose) +{ + Eigen::Matrix6f out = Eigen::Matrix6f::Identity (); + float cx = cosf (pose (3)), sx = sinf (pose (3)), cy = cosf (pose (4)), sy = sinf (pose (4)); + out (0, 4) = pose (1) * sx - pose (2) * cx; + out (0, 5) = pose (1) * cx * cy + pose (2) * sx * cy; + out (1, 3) = pose (2); + out (1, 4) = -pose (0) * sx; + out (1, 5) = -pose (0) * cx * cy + pose (2) * sy; + out (2, 3) = -pose (1); + out (2, 4) = pose (0) * cx; + out (2, 5) = -pose (0) * sx * cy - pose (1) * sy; + out (3, 5) = sy; + out (4, 4) = sx; + out (4, 5) = cx * cy; + out (5, 4) = cx; + out (5, 5) = -sx * cy; + return (out); +} + +#define PCL_INSTANTIATE_LUM(T) template class PCL_EXPORTS pcl::registration::LUM; + +#endif // PCL_REGISTRATION_IMPL_LUM_HPP_ + diff --git a/pcl-1.7/pcl/registration/impl/ndt.hpp b/pcl-1.7/pcl/registration/impl/ndt.hpp new file mode 100644 index 0000000..b464fce --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/ndt.hpp @@ -0,0 +1,765 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_NDT_IMPL_H_ +#define PCL_REGISTRATION_NDT_IMPL_H_ + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::NormalDistributionsTransform::NormalDistributionsTransform () + : target_cells_ () + , resolution_ (1.0f) + , step_size_ (0.1) + , outlier_ratio_ (0.55) + , gauss_d1_ () + , gauss_d2_ () + , trans_probability_ () + , j_ang_a_ (), j_ang_b_ (), j_ang_c_ (), j_ang_d_ (), j_ang_e_ (), j_ang_f_ (), j_ang_g_ (), j_ang_h_ () + , h_ang_a2_ (), h_ang_a3_ (), h_ang_b2_ (), h_ang_b3_ (), h_ang_c2_ (), h_ang_c3_ (), h_ang_d1_ (), h_ang_d2_ () + , h_ang_d3_ (), h_ang_e1_ (), h_ang_e2_ (), h_ang_e3_ (), h_ang_f1_ (), h_ang_f2_ (), h_ang_f3_ () + , point_gradient_ () + , point_hessian_ () +{ + reg_name_ = "NormalDistributionsTransform"; + + double gauss_c1, gauss_c2, gauss_d3; + + // Initializes the guassian fitting parameters (eq. 6.8) [Magnusson 2009] + gauss_c1 = 10.0 * (1 - outlier_ratio_); + gauss_c2 = outlier_ratio_ / pow (resolution_, 3); + gauss_d3 = -log (gauss_c2); + gauss_d1_ = -log ( gauss_c1 + gauss_c2 ) - gauss_d3; + gauss_d2_ = -2 * log ((-log ( gauss_c1 * exp ( -0.5 ) + gauss_c2 ) - gauss_d3) / gauss_d1_); + + transformation_epsilon_ = 0.1; + max_iterations_ = 35; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::NormalDistributionsTransform::computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess) +{ + nr_iterations_ = 0; + converged_ = false; + + double gauss_c1, gauss_c2, gauss_d3; + + // Initializes the guassian fitting parameters (eq. 6.8) [Magnusson 2009] + gauss_c1 = 10 * (1 - outlier_ratio_); + gauss_c2 = outlier_ratio_ / pow (resolution_, 3); + gauss_d3 = -log (gauss_c2); + gauss_d1_ = -log ( gauss_c1 + gauss_c2 ) - gauss_d3; + gauss_d2_ = -2 * log ((-log ( gauss_c1 * exp ( -0.5 ) + gauss_c2 ) - gauss_d3) / gauss_d1_); + + if (guess != Eigen::Matrix4f::Identity ()) + { + // Initialise final transformation to the guessed one + final_transformation_ = guess; + // Apply guessed transformation prior to search for neighbours + transformPointCloud (output, output, guess); + } + + // Initialize Point Gradient and Hessian + point_gradient_.setZero (); + point_gradient_.block<3, 3>(0, 0).setIdentity (); + point_hessian_.setZero (); + + Eigen::Transform eig_transformation; + eig_transformation.matrix () = final_transformation_; + + // Convert initial guess matrix to 6 element transformation vector + Eigen::Matrix p, delta_p, score_gradient; + Eigen::Vector3f init_translation = eig_transformation.translation (); + Eigen::Vector3f init_rotation = eig_transformation.rotation ().eulerAngles (0, 1, 2); + p << init_translation (0), init_translation (1), init_translation (2), + init_rotation (0), init_rotation (1), init_rotation (2); + + Eigen::Matrix hessian; + + double score = 0; + double delta_p_norm; + + // Calculate derivates of initial transform vector, subsequent derivative calculations are done in the step length determination. + score = computeDerivatives (score_gradient, hessian, output, p); + + while (!converged_) + { + // Store previous transformation + previous_transformation_ = transformation_; + + // Solve for decent direction using newton method, line 23 in Algorithm 2 [Magnusson 2009] + Eigen::JacobiSVD > sv (hessian, Eigen::ComputeFullU | Eigen::ComputeFullV); + // Negative for maximization as opposed to minimization + delta_p = sv.solve (-score_gradient); + + //Calculate step length with guarnteed sufficient decrease [More, Thuente 1994] + delta_p_norm = delta_p.norm (); + + if (delta_p_norm == 0 || delta_p_norm != delta_p_norm) + { + trans_probability_ = score / static_cast (input_->points.size ()); + converged_ = delta_p_norm == delta_p_norm; + return; + } + + delta_p.normalize (); + delta_p_norm = computeStepLengthMT (p, delta_p, delta_p_norm, step_size_, transformation_epsilon_ / 2, score, score_gradient, hessian, output); + delta_p *= delta_p_norm; + + + transformation_ = (Eigen::Translation (static_cast (delta_p (0)), static_cast (delta_p (1)), static_cast (delta_p (2))) * + Eigen::AngleAxis (static_cast (delta_p (3)), Eigen::Vector3f::UnitX ()) * + Eigen::AngleAxis (static_cast (delta_p (4)), Eigen::Vector3f::UnitY ()) * + Eigen::AngleAxis (static_cast (delta_p (5)), Eigen::Vector3f::UnitZ ())).matrix (); + + + p = p + delta_p; + + // Update Visualizer (untested) + if (update_visualizer_ != 0) + update_visualizer_ (output, std::vector(), *target_, std::vector() ); + + if (nr_iterations_ > max_iterations_ || + (nr_iterations_ && (std::fabs (delta_p_norm) < transformation_epsilon_))) + { + converged_ = true; + } + + nr_iterations_++; + + } + + // Store transformation probability. The realtive differences within each scan registration are accurate + // but the normalization constants need to be modified for it to be globally accurate + trans_probability_ = score / static_cast (input_->points.size ()); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::NormalDistributionsTransform::computeDerivatives (Eigen::Matrix &score_gradient, + Eigen::Matrix &hessian, + PointCloudSource &trans_cloud, + Eigen::Matrix &p, + bool compute_hessian) +{ + // Original Point and Transformed Point + PointSource x_pt, x_trans_pt; + // Original Point and Transformed Point (for math) + Eigen::Vector3d x, x_trans; + // Occupied Voxel + TargetGridLeafConstPtr cell; + // Inverse Covariance of Occupied Voxel + Eigen::Matrix3d c_inv; + + score_gradient.setZero (); + hessian.setZero (); + double score = 0; + + // Precompute Angular Derivatives (eq. 6.19 and 6.21)[Magnusson 2009] + computeAngleDerivatives (p); + + // Update gradient and hessian for each point, line 17 in Algorithm 2 [Magnusson 2009] + for (size_t idx = 0; idx < input_->points.size (); idx++) + { + x_trans_pt = trans_cloud.points[idx]; + + // Find nieghbors (Radius search has been experimentally faster than direct neighbor checking. + std::vector neighborhood; + std::vector distances; + target_cells_.radiusSearch (x_trans_pt, resolution_, neighborhood, distances); + + for (typename std::vector::iterator neighborhood_it = neighborhood.begin (); neighborhood_it != neighborhood.end (); neighborhood_it++) + { + cell = *neighborhood_it; + x_pt = input_->points[idx]; + x = Eigen::Vector3d (x_pt.x, x_pt.y, x_pt.z); + + x_trans = Eigen::Vector3d (x_trans_pt.x, x_trans_pt.y, x_trans_pt.z); + + // Denorm point, x_k' in Equations 6.12 and 6.13 [Magnusson 2009] + x_trans -= cell->getMean (); + // Uses precomputed covariance for speed. + c_inv = cell->getInverseCov (); + + // Compute derivative of transform function w.r.t. transform vector, J_E and H_E in Equations 6.18 and 6.20 [Magnusson 2009] + computePointDerivatives (x); + // Update score, gradient and hessian, lines 19-21 in Algorithm 2, according to Equations 6.10, 6.12 and 6.13, respectively [Magnusson 2009] + score += updateDerivatives (score_gradient, hessian, x_trans, c_inv, compute_hessian); + + } + } + return (score); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::NormalDistributionsTransform::computeAngleDerivatives (Eigen::Matrix &p, bool compute_hessian) +{ + // Simplified math for near 0 angles + double cx, cy, cz, sx, sy, sz; + if (fabs (p (3)) < 10e-5) + { + //p(3) = 0; + cx = 1.0; + sx = 0.0; + } + else + { + cx = cos (p (3)); + sx = sin (p (3)); + } + if (fabs (p (4)) < 10e-5) + { + //p(4) = 0; + cy = 1.0; + sy = 0.0; + } + else + { + cy = cos (p (4)); + sy = sin (p (4)); + } + + if (fabs (p (5)) < 10e-5) + { + //p(5) = 0; + cz = 1.0; + sz = 0.0; + } + else + { + cz = cos (p (5)); + sz = sin (p (5)); + } + + // Precomputed angular gradiant components. Letters correspond to Equation 6.19 [Magnusson 2009] + j_ang_a_ << (-sx * sz + cx * sy * cz), (-sx * cz - cx * sy * sz), (-cx * cy); + j_ang_b_ << (cx * sz + sx * sy * cz), (cx * cz - sx * sy * sz), (-sx * cy); + j_ang_c_ << (-sy * cz), sy * sz, cy; + j_ang_d_ << sx * cy * cz, (-sx * cy * sz), sx * sy; + j_ang_e_ << (-cx * cy * cz), cx * cy * sz, (-cx * sy); + j_ang_f_ << (-cy * sz), (-cy * cz), 0; + j_ang_g_ << (cx * cz - sx * sy * sz), (-cx * sz - sx * sy * cz), 0; + j_ang_h_ << (sx * cz + cx * sy * sz), (cx * sy * cz - sx * sz), 0; + + if (compute_hessian) + { + // Precomputed angular hessian components. Letters correspond to Equation 6.21 and numbers correspond to row index [Magnusson 2009] + h_ang_a2_ << (-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), sx * cy; + h_ang_a3_ << (-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), (-cx * cy); + + h_ang_b2_ << (cx * cy * cz), (-cx * cy * sz), (cx * sy); + h_ang_b3_ << (sx * cy * cz), (-sx * cy * sz), (sx * sy); + + h_ang_c2_ << (-sx * cz - cx * sy * sz), (sx * sz - cx * sy * cz), 0; + h_ang_c3_ << (cx * cz - sx * sy * sz), (-sx * sy * cz - cx * sz), 0; + + h_ang_d1_ << (-cy * cz), (cy * sz), (sy); + h_ang_d2_ << (-sx * sy * cz), (sx * sy * sz), (sx * cy); + h_ang_d3_ << (cx * sy * cz), (-cx * sy * sz), (-cx * cy); + + h_ang_e1_ << (sy * sz), (sy * cz), 0; + h_ang_e2_ << (-sx * cy * sz), (-sx * cy * cz), 0; + h_ang_e3_ << (cx * cy * sz), (cx * cy * cz), 0; + + h_ang_f1_ << (-cy * cz), (cy * sz), 0; + h_ang_f2_ << (-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), 0; + h_ang_f3_ << (-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), 0; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::NormalDistributionsTransform::computePointDerivatives (Eigen::Vector3d &x, bool compute_hessian) +{ + // Calculate first derivative of Transformation Equation 6.17 w.r.t. transform vector p. + // Derivative w.r.t. ith element of transform vector corresponds to column i, Equation 6.18 and 6.19 [Magnusson 2009] + point_gradient_ (1, 3) = x.dot (j_ang_a_); + point_gradient_ (2, 3) = x.dot (j_ang_b_); + point_gradient_ (0, 4) = x.dot (j_ang_c_); + point_gradient_ (1, 4) = x.dot (j_ang_d_); + point_gradient_ (2, 4) = x.dot (j_ang_e_); + point_gradient_ (0, 5) = x.dot (j_ang_f_); + point_gradient_ (1, 5) = x.dot (j_ang_g_); + point_gradient_ (2, 5) = x.dot (j_ang_h_); + + if (compute_hessian) + { + // Vectors from Equation 6.21 [Magnusson 2009] + Eigen::Vector3d a, b, c, d, e, f; + + a << 0, x.dot (h_ang_a2_), x.dot (h_ang_a3_); + b << 0, x.dot (h_ang_b2_), x.dot (h_ang_b3_); + c << 0, x.dot (h_ang_c2_), x.dot (h_ang_c3_); + d << x.dot (h_ang_d1_), x.dot (h_ang_d2_), x.dot (h_ang_d3_); + e << x.dot (h_ang_e1_), x.dot (h_ang_e2_), x.dot (h_ang_e3_); + f << x.dot (h_ang_f1_), x.dot (h_ang_f2_), x.dot (h_ang_f3_); + + // Calculate second derivative of Transformation Equation 6.17 w.r.t. transform vector p. + // Derivative w.r.t. ith and jth elements of transform vector corresponds to the 3x1 block matrix starting at (3i,j), Equation 6.20 and 6.21 [Magnusson 2009] + point_hessian_.block<3, 1>(9, 3) = a; + point_hessian_.block<3, 1>(12, 3) = b; + point_hessian_.block<3, 1>(15, 3) = c; + point_hessian_.block<3, 1>(9, 4) = b; + point_hessian_.block<3, 1>(12, 4) = d; + point_hessian_.block<3, 1>(15, 4) = e; + point_hessian_.block<3, 1>(9, 5) = c; + point_hessian_.block<3, 1>(12, 5) = e; + point_hessian_.block<3, 1>(15, 5) = f; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::NormalDistributionsTransform::updateDerivatives (Eigen::Matrix &score_gradient, + Eigen::Matrix &hessian, + Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv, + bool compute_hessian) +{ + Eigen::Vector3d cov_dxd_pi; + // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 [Magnusson 2009] + double e_x_cov_x = exp (-gauss_d2_ * x_trans.dot (c_inv * x_trans) / 2); + // Calculate probability of transtormed points existance, Equation 6.9 [Magnusson 2009] + double score_inc = -gauss_d1_ * e_x_cov_x; + + e_x_cov_x = gauss_d2_ * e_x_cov_x; + + // Error checking for invalid values. + if (e_x_cov_x > 1 || e_x_cov_x < 0 || e_x_cov_x != e_x_cov_x) + return (0); + + // Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009] + e_x_cov_x *= gauss_d1_; + + + for (int i = 0; i < 6; i++) + { + // Sigma_k^-1 d(T(x,p))/dpi, Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009] + cov_dxd_pi = c_inv * point_gradient_.col (i); + + // Update gradient, Equation 6.12 [Magnusson 2009] + score_gradient (i) += x_trans.dot (cov_dxd_pi) * e_x_cov_x; + + if (compute_hessian) + { + for (int j = 0; j < hessian.cols (); j++) + { + // Update hessian, Equation 6.13 [Magnusson 2009] + hessian (i, j) += e_x_cov_x * (-gauss_d2_ * x_trans.dot (cov_dxd_pi) * x_trans.dot (c_inv * point_gradient_.col (j)) + + x_trans.dot (c_inv * point_hessian_.block<3, 1>(3 * i, j)) + + point_gradient_.col (j).dot (cov_dxd_pi) ); + } + } + } + + return (score_inc); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::NormalDistributionsTransform::computeHessian (Eigen::Matrix &hessian, + PointCloudSource &trans_cloud, Eigen::Matrix &) +{ + // Original Point and Transformed Point + PointSource x_pt, x_trans_pt; + // Original Point and Transformed Point (for math) + Eigen::Vector3d x, x_trans; + // Occupied Voxel + TargetGridLeafConstPtr cell; + // Inverse Covariance of Occupied Voxel + Eigen::Matrix3d c_inv; + + hessian.setZero (); + + // Precompute Angular Derivatives unessisary because only used after regular derivative calculation + + // Update hessian for each point, line 17 in Algorithm 2 [Magnusson 2009] + for (size_t idx = 0; idx < input_->points.size (); idx++) + { + x_trans_pt = trans_cloud.points[idx]; + + // Find nieghbors (Radius search has been experimentally faster than direct neighbor checking. + std::vector neighborhood; + std::vector distances; + target_cells_.radiusSearch (x_trans_pt, resolution_, neighborhood, distances); + + for (typename std::vector::iterator neighborhood_it = neighborhood.begin (); neighborhood_it != neighborhood.end (); neighborhood_it++) + { + cell = *neighborhood_it; + + { + x_pt = input_->points[idx]; + x = Eigen::Vector3d (x_pt.x, x_pt.y, x_pt.z); + + x_trans = Eigen::Vector3d (x_trans_pt.x, x_trans_pt.y, x_trans_pt.z); + + // Denorm point, x_k' in Equations 6.12 and 6.13 [Magnusson 2009] + x_trans -= cell->getMean (); + // Uses precomputed covariance for speed. + c_inv = cell->getInverseCov (); + + // Compute derivative of transform function w.r.t. transform vector, J_E and H_E in Equations 6.18 and 6.20 [Magnusson 2009] + computePointDerivatives (x); + // Update hessian, lines 21 in Algorithm 2, according to Equations 6.10, 6.12 and 6.13, respectively [Magnusson 2009] + updateHessian (hessian, x_trans, c_inv); + } + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::NormalDistributionsTransform::updateHessian (Eigen::Matrix &hessian, Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv) +{ + Eigen::Vector3d cov_dxd_pi; + // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 [Magnusson 2009] + double e_x_cov_x = gauss_d2_ * exp (-gauss_d2_ * x_trans.dot (c_inv * x_trans) / 2); + + // Error checking for invalid values. + if (e_x_cov_x > 1 || e_x_cov_x < 0 || e_x_cov_x != e_x_cov_x) + return; + + // Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009] + e_x_cov_x *= gauss_d1_; + + for (int i = 0; i < 6; i++) + { + // Sigma_k^-1 d(T(x,p))/dpi, Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009] + cov_dxd_pi = c_inv * point_gradient_.col (i); + + for (int j = 0; j < hessian.cols (); j++) + { + // Update hessian, Equation 6.13 [Magnusson 2009] + hessian (i, j) += e_x_cov_x * (-gauss_d2_ * x_trans.dot (cov_dxd_pi) * x_trans.dot (c_inv * point_gradient_.col (j)) + + x_trans.dot (c_inv * point_hessian_.block<3, 1>(3 * i, j)) + + point_gradient_.col (j).dot (cov_dxd_pi) ); + } + } + +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::NormalDistributionsTransform::updateIntervalMT (double &a_l, double &f_l, double &g_l, + double &a_u, double &f_u, double &g_u, + double a_t, double f_t, double g_t) +{ + // Case U1 in Update Algorithm and Case a in Modified Update Algorithm [More, Thuente 1994] + if (f_t > f_l) + { + a_u = a_t; + f_u = f_t; + g_u = g_t; + return (false); + } + // Case U2 in Update Algorithm and Case b in Modified Update Algorithm [More, Thuente 1994] + else + if (g_t * (a_l - a_t) > 0) + { + a_l = a_t; + f_l = f_t; + g_l = g_t; + return (false); + } + // Case U3 in Update Algorithm and Case c in Modified Update Algorithm [More, Thuente 1994] + else + if (g_t * (a_l - a_t) < 0) + { + a_u = a_l; + f_u = f_l; + g_u = g_l; + + a_l = a_t; + f_l = f_t; + g_l = g_t; + return (false); + } + // Interval Converged + else + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::NormalDistributionsTransform::trialValueSelectionMT (double a_l, double f_l, double g_l, + double a_u, double f_u, double g_u, + double a_t, double f_t, double g_t) +{ + // Case 1 in Trial Value Selection [More, Thuente 1994] + if (f_t > f_l) + { + // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t + // Equation 2.4.52 [Sun, Yuan 2006] + double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l; + double w = std::sqrt (z * z - g_t * g_l); + // Equation 2.4.56 [Sun, Yuan 2006] + double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w); + + // Calculate the minimizer of the quadratic that interpolates f_l, f_t and g_l + // Equation 2.4.2 [Sun, Yuan 2006] + double a_q = a_l - 0.5 * (a_l - a_t) * g_l / (g_l - (f_l - f_t) / (a_l - a_t)); + + if (std::fabs (a_c - a_l) < std::fabs (a_q - a_l)) + return (a_c); + else + return (0.5 * (a_q + a_c)); + } + // Case 2 in Trial Value Selection [More, Thuente 1994] + else + if (g_t * g_l < 0) + { + // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t + // Equation 2.4.52 [Sun, Yuan 2006] + double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l; + double w = std::sqrt (z * z - g_t * g_l); + // Equation 2.4.56 [Sun, Yuan 2006] + double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w); + + // Calculate the minimizer of the quadratic that interpolates f_l, g_l and g_t + // Equation 2.4.5 [Sun, Yuan 2006] + double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l; + + if (std::fabs (a_c - a_t) >= std::fabs (a_s - a_t)) + return (a_c); + else + return (a_s); + } + // Case 3 in Trial Value Selection [More, Thuente 1994] + else + if (std::fabs (g_t) <= std::fabs (g_l)) + { + // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t + // Equation 2.4.52 [Sun, Yuan 2006] + double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l; + double w = std::sqrt (z * z - g_t * g_l); + double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w); + + // Calculate the minimizer of the quadratic that interpolates g_l and g_t + // Equation 2.4.5 [Sun, Yuan 2006] + double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l; + + double a_t_next; + + if (std::fabs (a_c - a_t) < std::fabs (a_s - a_t)) + a_t_next = a_c; + else + a_t_next = a_s; + + if (a_t > a_l) + return (std::min (a_t + 0.66 * (a_u - a_t), a_t_next)); + else + return (std::max (a_t + 0.66 * (a_u - a_t), a_t_next)); + } + // Case 4 in Trial Value Selection [More, Thuente 1994] + else + { + // Calculate the minimizer of the cubic that interpolates f_u, f_t, g_u and g_t + // Equation 2.4.52 [Sun, Yuan 2006] + double z = 3 * (f_t - f_u) / (a_t - a_u) - g_t - g_u; + double w = std::sqrt (z * z - g_t * g_u); + // Equation 2.4.56 [Sun, Yuan 2006] + return (a_u + (a_t - a_u) * (w - g_u - z) / (g_t - g_u + 2 * w)); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::NormalDistributionsTransform::computeStepLengthMT (const Eigen::Matrix &x, Eigen::Matrix &step_dir, double step_init, double step_max, + double step_min, double &score, Eigen::Matrix &score_gradient, Eigen::Matrix &hessian, + PointCloudSource &trans_cloud) +{ + // Set the value of phi(0), Equation 1.3 [More, Thuente 1994] + double phi_0 = -score; + // Set the value of phi'(0), Equation 1.3 [More, Thuente 1994] + double d_phi_0 = -(score_gradient.dot (step_dir)); + + Eigen::Matrix x_t; + + if (d_phi_0 >= 0) + { + // Not a decent direction + if (d_phi_0 == 0) + return 0; + else + { + // Reverse step direction and calculate optimal step. + d_phi_0 *= -1; + step_dir *= -1; + + } + } + + // The Search Algorithm for T(mu) [More, Thuente 1994] + + int max_step_iterations = 10; + int step_iterations = 0; + + // Sufficient decreace constant, Equation 1.1 [More, Thuete 1994] + double mu = 1.e-4; + // Curvature condition constant, Equation 1.2 [More, Thuete 1994] + double nu = 0.9; + + // Initial endpoints of Interval I, + double a_l = 0, a_u = 0; + + // Auxiliary function psi is used until I is determined ot be a closed interval, Equation 2.1 [More, Thuente 1994] + double f_l = auxilaryFunction_PsiMT (a_l, phi_0, phi_0, d_phi_0, mu); + double g_l = auxilaryFunction_dPsiMT (d_phi_0, d_phi_0, mu); + + double f_u = auxilaryFunction_PsiMT (a_u, phi_0, phi_0, d_phi_0, mu); + double g_u = auxilaryFunction_dPsiMT (d_phi_0, d_phi_0, mu); + + // Check used to allow More-Thuente step length calculation to be skipped by making step_min == step_max + bool interval_converged = (step_max - step_min) > 0, open_interval = true; + + double a_t = step_init; + a_t = std::min (a_t, step_max); + a_t = std::max (a_t, step_min); + + x_t = x + step_dir * a_t; + + final_transformation_ = (Eigen::Translation(static_cast (x_t (0)), static_cast (x_t (1)), static_cast (x_t (2))) * + Eigen::AngleAxis (static_cast (x_t (3)), Eigen::Vector3f::UnitX ()) * + Eigen::AngleAxis (static_cast (x_t (4)), Eigen::Vector3f::UnitY ()) * + Eigen::AngleAxis (static_cast (x_t (5)), Eigen::Vector3f::UnitZ ())).matrix (); + + // New transformed point cloud + transformPointCloud (*input_, trans_cloud, final_transformation_); + + // Updates score, gradient and hessian. Hessian calculation is unessisary but testing showed that most step calculations use the + // initial step suggestion and recalculation the reusable portions of the hessian would intail more computation time. + score = computeDerivatives (score_gradient, hessian, trans_cloud, x_t, true); + + // Calculate phi(alpha_t) + double phi_t = -score; + // Calculate phi'(alpha_t) + double d_phi_t = -(score_gradient.dot (step_dir)); + + // Calculate psi(alpha_t) + double psi_t = auxilaryFunction_PsiMT (a_t, phi_t, phi_0, d_phi_0, mu); + // Calculate psi'(alpha_t) + double d_psi_t = auxilaryFunction_dPsiMT (d_phi_t, d_phi_0, mu); + + // Iterate until max number of iterations, interval convergance or a value satisfies the sufficient decrease, Equation 1.1, and curvature condition, Equation 1.2 [More, Thuente 1994] + while (!interval_converged && step_iterations < max_step_iterations && !(psi_t <= 0 /*Sufficient Decrease*/ && d_phi_t <= -nu * d_phi_0 /*Curvature Condition*/)) + { + // Use auxilary function if interval I is not closed + if (open_interval) + { + a_t = trialValueSelectionMT (a_l, f_l, g_l, + a_u, f_u, g_u, + a_t, psi_t, d_psi_t); + } + else + { + a_t = trialValueSelectionMT (a_l, f_l, g_l, + a_u, f_u, g_u, + a_t, phi_t, d_phi_t); + } + + a_t = std::min (a_t, step_max); + a_t = std::max (a_t, step_min); + + x_t = x + step_dir * a_t; + + final_transformation_ = (Eigen::Translation (static_cast (x_t (0)), static_cast (x_t (1)), static_cast (x_t (2))) * + Eigen::AngleAxis (static_cast (x_t (3)), Eigen::Vector3f::UnitX ()) * + Eigen::AngleAxis (static_cast (x_t (4)), Eigen::Vector3f::UnitY ()) * + Eigen::AngleAxis (static_cast (x_t (5)), Eigen::Vector3f::UnitZ ())).matrix (); + + // New transformed point cloud + // Done on final cloud to prevent wasted computation + transformPointCloud (*input_, trans_cloud, final_transformation_); + + // Updates score, gradient. Values stored to prevent wasted computation. + score = computeDerivatives (score_gradient, hessian, trans_cloud, x_t, false); + + // Calculate phi(alpha_t+) + phi_t = -score; + // Calculate phi'(alpha_t+) + d_phi_t = -(score_gradient.dot (step_dir)); + + // Calculate psi(alpha_t+) + psi_t = auxilaryFunction_PsiMT (a_t, phi_t, phi_0, d_phi_0, mu); + // Calculate psi'(alpha_t+) + d_psi_t = auxilaryFunction_dPsiMT (d_phi_t, d_phi_0, mu); + + // Check if I is now a closed interval + if (open_interval && (psi_t <= 0 && d_psi_t >= 0)) + { + open_interval = false; + + // Converts f_l and g_l from psi to phi + f_l = f_l + phi_0 - mu * d_phi_0 * a_l; + g_l = g_l + mu * d_phi_0; + + // Converts f_u and g_u from psi to phi + f_u = f_u + phi_0 - mu * d_phi_0 * a_u; + g_u = g_u + mu * d_phi_0; + } + + if (open_interval) + { + // Update interval end points using Updating Algorithm [More, Thuente 1994] + interval_converged = updateIntervalMT (a_l, f_l, g_l, + a_u, f_u, g_u, + a_t, psi_t, d_psi_t); + } + else + { + // Update interval end points using Modified Updating Algorithm [More, Thuente 1994] + interval_converged = updateIntervalMT (a_l, f_l, g_l, + a_u, f_u, g_u, + a_t, phi_t, d_phi_t); + } + + step_iterations++; + } + + // If inner loop was run then hessian needs to be calculated. + // Hessian is unnessisary for step length determination but gradients are required + // so derivative and transform data is stored for the next iteration. + if (step_iterations) + computeHessian (hessian, trans_cloud, x_t); + + return (a_t); +} + +#endif // PCL_REGISTRATION_NDT_IMPL_H_ diff --git a/pcl-1.7/pcl/registration/impl/ndt_2d.hpp b/pcl-1.7/pcl/registration/impl/ndt_2d.hpp new file mode 100644 index 0000000..8805209 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/ndt_2d.hpp @@ -0,0 +1,483 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_NDT_2D_IMPL_H_ +#define PCL_NDT_2D_IMPL_H_ +#include + +#include +#include + +namespace pcl +{ + namespace ndt2d + { + /** \brief Class to store vector value and first and second derivatives + * (grad vector and hessian matrix), so they can be returned easily from + * functions + */ + template + struct ValueAndDerivatives + { + ValueAndDerivatives () : hessian (), grad (), value () {} + + Eigen::Matrix hessian; + Eigen::Matrix grad; + T value; + + static ValueAndDerivatives + Zero () + { + ValueAndDerivatives r; + r.hessian = Eigen::Matrix::Zero (); + r.grad = Eigen::Matrix::Zero (); + r.value = 0; + return r; + } + + ValueAndDerivatives& + operator+= (ValueAndDerivatives const& r) + { + hessian += r.hessian; + grad += r.grad; + value += r.value; + return *this; + } + }; + + /** \brief A normal distribution estimation class. + * + * First the indices of of the points from a point cloud that should be + * modelled by the distribution are added with addIdx (...). + * + * Then estimateParams (...) uses the stored point indices to estimate the + * parameters of a normal distribution, and discards the stored indices. + * + * Finally the distriubution, and its derivatives, may be evaluated at any + * point using test (...). + */ + template + class NormalDist + { + typedef pcl::PointCloud PointCloud; + + public: + NormalDist () + : min_n_ (3), n_ (0), pt_indices_ (), mean_ (), covar_inv_ () + { + } + + /** \brief Store a point index to use later for estimating distribution parameters. + * \param[in] i Point index to store + */ + void + addIdx (size_t i) + { + pt_indices_.push_back (i); + } + + /** \brief Estimate the normal distribution parameters given the point indices provided. Memory of point indices is cleared. + * \param[in] cloud Point cloud corresponding to indices passed to addIdx. + * \param[in] min_covar_eigvalue_mult Set the smallest eigenvalue to this times the largest. + */ + void + estimateParams (const PointCloud& cloud, double min_covar_eigvalue_mult = 0.001) + { + Eigen::Vector2d sx = Eigen::Vector2d::Zero (); + Eigen::Matrix2d sxx = Eigen::Matrix2d::Zero (); + + std::vector::const_iterator i; + for (i = pt_indices_.begin (); i != pt_indices_.end (); i++) + { + Eigen::Vector2d p (cloud[*i]. x, cloud[*i]. y); + sx += p; + sxx += p * p.transpose (); + } + + n_ = pt_indices_.size (); + + if (n_ >= min_n_) + { + mean_ = sx / static_cast (n_); + // Using maximum likelihood estimation as in the original paper + Eigen::Matrix2d covar = (sxx - 2 * (sx * mean_.transpose ())) / static_cast (n_) + mean_ * mean_.transpose (); + + Eigen::SelfAdjointEigenSolver solver (covar); + if (solver.eigenvalues ()[0] < min_covar_eigvalue_mult * solver.eigenvalues ()[1]) + { + PCL_DEBUG ("[pcl::NormalDist::estimateParams] NDT normal fit: adjusting eigenvalue %f\n", solver.eigenvalues ()[0]); + Eigen::Matrix2d l = solver.eigenvalues ().asDiagonal (); + Eigen::Matrix2d q = solver.eigenvectors (); + // set minimum smallest eigenvalue: + l (0,0) = l (1,1) * min_covar_eigvalue_mult; + covar = q * l * q.transpose (); + } + covar_inv_ = covar.inverse (); + } + + pt_indices_.clear (); + } + + /** \brief Return the 'score' (denormalised likelihood) and derivatives of score of the point p given this distribution. + * \param[in] transformed_pt Location to evaluate at. + * \param[in] cos_theta sin(theta) of the current rotation angle of rigid transformation: to avoid repeated evaluation + * \param[in] sin_theta cos(theta) of the current rotation angle of rigid transformation: to avoid repeated evaluation + * estimateParams must have been called after at least three points were provided, or this will return zero. + * + */ + ValueAndDerivatives<3,double> + test (const PointT& transformed_pt, const double& cos_theta, const double& sin_theta) const + { + if (n_ < min_n_) + return ValueAndDerivatives<3,double>::Zero (); + + ValueAndDerivatives<3,double> r; + const double x = transformed_pt.x; + const double y = transformed_pt.y; + const Eigen::Vector2d p_xy (transformed_pt.x, transformed_pt.y); + const Eigen::Vector2d q = p_xy - mean_; + const Eigen::RowVector2d qt_cvi (q.transpose () * covar_inv_); + const double exp_qt_cvi_q = std::exp (-0.5 * double (qt_cvi * q)); + r.value = -exp_qt_cvi_q; + + Eigen::Matrix jacobian; + jacobian << + 1, 0, -(x * sin_theta + y*cos_theta), + 0, 1, x * cos_theta - y*sin_theta; + + for (size_t i = 0; i < 3; i++) + r.grad[i] = double (qt_cvi * jacobian.col (i)) * exp_qt_cvi_q; + + // second derivative only for i == j == 2: + const Eigen::Vector2d d2q_didj ( + y * sin_theta - x*cos_theta, + -(x * sin_theta + y*cos_theta) + ); + + for (size_t i = 0; i < 3; i++) + for (size_t j = 0; j < 3; j++) + r.hessian (i,j) = -exp_qt_cvi_q * ( + double (-qt_cvi*jacobian.col (i)) * double (-qt_cvi*jacobian.col (j)) + + (-qt_cvi * ((i==2 && j==2)? d2q_didj : Eigen::Vector2d::Zero ())) + + (-jacobian.col (j).transpose () * covar_inv_ * jacobian.col (i)) + ); + + return r; + } + + protected: + const size_t min_n_; + + size_t n_; + std::vector pt_indices_; + Eigen::Vector2d mean_; + Eigen::Matrix2d covar_inv_; + }; + + /** \brief Build a set of normal distributions modelling a 2D point cloud, + * and provide the value and derivatives of the model at any point via the + * test (...) function. + */ + template + class NDTSingleGrid: public boost::noncopyable + { + typedef typename pcl::PointCloud PointCloud; + typedef typename pcl::PointCloud::ConstPtr PointCloudConstPtr; + typedef typename pcl::ndt2d::NormalDist NormalDist; + + public: + NDTSingleGrid (PointCloudConstPtr cloud, + const Eigen::Vector2f& about, + const Eigen::Vector2f& extent, + const Eigen::Vector2f& step) + : min_ (about - extent), max_ (min_ + 2*extent), step_ (step), + cells_ ((max_[0]-min_[0]) / step_[0], + (max_[1]-min_[1]) / step_[1]), + normal_distributions_ (cells_[0], cells_[1]) + { + // sort through all points, assigning them to distributions: + NormalDist* n; + size_t used_points = 0; + for (size_t i = 0; i < cloud->size (); i++) + if ((n = normalDistForPoint (cloud->at (i)))) + { + n->addIdx (i); + used_points++; + } + + PCL_DEBUG ("[pcl::NDTSingleGrid] NDT single grid %dx%d using %d/%d points\n", cells_[0], cells_[1], used_points, cloud->size ()); + + // then bake the distributions such that they approximate the + // points (and throw away memory of the points) + for (int x = 0; x < cells_[0]; x++) + for (int y = 0; y < cells_[1]; y++) + normal_distributions_.coeffRef (x,y).estimateParams (*cloud); + } + + /** \brief Return the 'score' (denormalised likelihood) and derivatives of score of the point p given this distribution. + * \param[in] transformed_pt Location to evaluate at. + * \param[in] cos_theta sin(theta) of the current rotation angle of rigid transformation: to avoid repeated evaluation + * \param[in] sin_theta cos(theta) of the current rotation angle of rigid transformation: to avoid repeated evaluation + */ + ValueAndDerivatives<3,double> + test (const PointT& transformed_pt, const double& cos_theta, const double& sin_theta) const + { + const NormalDist* n = normalDistForPoint (transformed_pt); + // index is in grid, return score from the normal distribution from + // the correct part of the grid: + if (n) + return n->test (transformed_pt, cos_theta, sin_theta); + else + return ValueAndDerivatives<3,double>::Zero (); + } + + protected: + /** \brief Return the normal distribution covering the location of point p + * \param[in] p a point + */ + NormalDist* + normalDistForPoint (PointT const& p) const + { + // this would be neater in 3d... + Eigen::Vector2f idxf; + for (size_t i = 0; i < 2; i++) + idxf[i] = (p.getVector3fMap ()[i] - min_[i]) / step_[i]; + Eigen::Vector2i idxi = idxf.cast (); + for (size_t i = 0; i < 2; i++) + if (idxi[i] >= cells_[i] || idxi[i] < 0) + return NULL; + // const cast to avoid duplicating this function in const and + // non-const variants... + return const_cast (&normal_distributions_.coeffRef (idxi[0], idxi[1])); + } + + Eigen::Vector2f min_; + Eigen::Vector2f max_; + Eigen::Vector2f step_; + Eigen::Vector2i cells_; + + Eigen::Matrix normal_distributions_; + }; + + /** \brief Build a Normal Distributions Transform of a 2D point cloud. This + * consists of the sum of four overlapping models of the original points + * with normal distributions. + * The value and derivatives of the model at any point can be evaluated + * with the test (...) function. + */ + template + class NDT2D: public boost::noncopyable + { + typedef typename pcl::PointCloud PointCloud; + typedef typename pcl::PointCloud::ConstPtr PointCloudConstPtr; + typedef NDTSingleGrid SingleGrid; + + public: + /** \brief + * \param[in] cloud the input point cloud + * \param[in] about Centre of the grid for normal distributions model + * \param[in] extent Extent of grid for normal distributions model + * \param[in] step Size of region that each normal distribution will model + */ + NDT2D (PointCloudConstPtr cloud, + const Eigen::Vector2f& about, + const Eigen::Vector2f& extent, + const Eigen::Vector2f& step) + { + Eigen::Vector2f dx (step[0]/2, 0); + Eigen::Vector2f dy (0, step[1]/2); + single_grids_[0] = boost::make_shared (cloud, about, extent, step); + single_grids_[1] = boost::make_shared (cloud, about +dx, extent, step); + single_grids_[2] = boost::make_shared (cloud, about +dy, extent, step); + single_grids_[3] = boost::make_shared (cloud, about +dx+dy, extent, step); + } + + /** \brief Return the 'score' (denormalised likelihood) and derivatives of score of the point p given this distribution. + * \param[in] transformed_pt Location to evaluate at. + * \param[in] cos_theta sin(theta) of the current rotation angle of rigid transformation: to avoid repeated evaluation + * \param[in] sin_theta cos(theta) of the current rotation angle of rigid transformation: to avoid repeated evaluation + */ + ValueAndDerivatives<3,double> + test (const PointT& transformed_pt, const double& cos_theta, const double& sin_theta) const + { + ValueAndDerivatives<3,double> r = ValueAndDerivatives<3,double>::Zero (); + for (size_t i = 0; i < 4; i++) + r += single_grids_[i]->test (transformed_pt, cos_theta, sin_theta); + return r; + } + + protected: + boost::shared_ptr single_grids_[4]; + }; + + } // namespace ndt2d +} // namespace pcl + + +namespace Eigen +{ + /* This NumTraits specialisation is necessary because NormalDist is used as + * the element type of an Eigen Matrix. + */ + template struct NumTraits > + { + typedef double Real; + static Real dummy_precision () { return 1.0; } + enum { + IsComplex = 0, + IsInteger = 0, + IsSigned = 0, + RequireInitialization = 1, + ReadCost = 1, + AddCost = 1, + MulCost = 1 + }; + }; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::NormalDistributionsTransform2D::computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess) +{ + PointCloudSource intm_cloud = output; + + if (guess != Eigen::Matrix4f::Identity ()) + { + transformation_ = guess; + transformPointCloud (output, intm_cloud, transformation_); + } + + // build Normal Distribution Transform of target cloud: + ndt2d::NDT2D target_ndt (target_, grid_centre_, grid_extent_, grid_step_); + + // can't seem to use .block<> () member function on transformation_ + // directly... gcc bug? + Eigen::Matrix4f& transformation = transformation_; + + + // work with x translation, y translation and z rotation: extending to 3D + // would be some tricky maths, but not impossible. + const Eigen::Matrix3f initial_rot (transformation.block<3,3> (0,0)); + const Eigen::Vector3f rot_x (initial_rot*Eigen::Vector3f::UnitX ()); + const double z_rotation = std::atan2 (rot_x[1], rot_x[0]); + + Eigen::Vector3d xytheta_transformation ( + transformation (0,3), + transformation (1,3), + z_rotation + ); + + while (!converged_) + { + const double cos_theta = std::cos (xytheta_transformation[2]); + const double sin_theta = std::sin (xytheta_transformation[2]); + previous_transformation_ = transformation; + + ndt2d::ValueAndDerivatives<3, double> score = ndt2d::ValueAndDerivatives<3, double>::Zero (); + for (size_t i = 0; i < intm_cloud.size (); i++) + score += target_ndt.test (intm_cloud[i], cos_theta, sin_theta); + + PCL_DEBUG ("[pcl::NormalDistributionsTransform2D::computeTransformation] NDT score %f (x=%f,y=%f,r=%f)\n", + float (score.value), xytheta_transformation[0], xytheta_transformation[1], xytheta_transformation[2] + ); + + if (score.value != 0) + { + // test for positive definiteness, and adjust to ensure it if necessary: + Eigen::EigenSolver solver; + solver.compute (score.hessian, false); + double min_eigenvalue = 0; + for (int i = 0; i <3; i++) + if (solver.eigenvalues ()[i].real () < min_eigenvalue) + min_eigenvalue = solver.eigenvalues ()[i].real (); + + // ensure "safe" positive definiteness: this is a detail missing + // from the original paper + if (min_eigenvalue < 0) + { + double lambda = 1.1 * min_eigenvalue - 1; + score.hessian += Eigen::Vector3d (-lambda, -lambda, -lambda).asDiagonal (); + solver.compute (score.hessian, false); + PCL_DEBUG ("[pcl::NormalDistributionsTransform2D::computeTransformation] adjust hessian: %f: new eigenvalues:%f %f %f\n", + float (lambda), + solver.eigenvalues ()[0].real (), + solver.eigenvalues ()[1].real (), + solver.eigenvalues ()[2].real () + ); + } + assert (solver.eigenvalues ()[0].real () >= 0 && + solver.eigenvalues ()[1].real () >= 0 && + solver.eigenvalues ()[2].real () >= 0); + + Eigen::Vector3d delta_transformation (-score.hessian.inverse () * score.grad); + Eigen::Vector3d new_transformation = xytheta_transformation + newton_lambda_.cwiseProduct (delta_transformation); + + xytheta_transformation = new_transformation; + + // update transformation matrix from x, y, theta: + transformation.block<3,3> (0,0).matrix () = Eigen::Matrix3f (Eigen::AngleAxisf (static_cast (xytheta_transformation[2]), Eigen::Vector3f::UnitZ ())); + transformation.block<3,1> (0,3).matrix () = Eigen::Vector3f (static_cast (xytheta_transformation[0]), static_cast (xytheta_transformation[1]), 0.0f); + + //std::cout << "new transformation:\n" << transformation << std::endl; + } + else + { + PCL_ERROR ("[pcl::NormalDistributionsTransform2D::computeTransformation] no overlap: try increasing the size or reducing the step of the grid\n"); + break; + } + + transformPointCloud (output, intm_cloud, transformation); + + nr_iterations_++; + + if (update_visualizer_ != 0) + update_visualizer_ (output, *indices_, *target_, *indices_); + + //std::cout << "eps=" << fabs ((transformation - previous_transformation_).sum ()) << std::endl; + + if (nr_iterations_ > max_iterations_ || + (transformation - previous_transformation_).array ().abs ().sum () < transformation_epsilon_) + converged_ = true; + } + final_transformation_ = transformation; + output = intm_cloud; +} + +#endif // PCL_NDT_2D_IMPL_H_ + diff --git a/pcl-1.7/pcl/registration/impl/ppf_registration.hpp b/pcl-1.7/pcl/registration/impl/ppf_registration.hpp new file mode 100644 index 0000000..2203862 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/ppf_registration.hpp @@ -0,0 +1,349 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Willow Garage, Inc + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + + +#ifndef PCL_REGISTRATION_IMPL_PPF_REGISTRATION_H_ +#define PCL_REGISTRATION_IMPL_PPF_REGISTRATION_H_ + +#include +#include +#include + +#include +////////////////////////////////////////////////////////////////////////////////////////////// +void +pcl::PPFHashMapSearch::setInputFeatureCloud (PointCloud::ConstPtr feature_cloud) +{ + // Discretize the feature cloud and insert it in the hash map + feature_hash_map_->clear (); + unsigned int n = static_cast (sqrt (static_cast (feature_cloud->points.size ()))); + int d1, d2, d3, d4; + max_dist_ = -1.0; + alpha_m_.resize (n); + for (size_t i = 0; i < n; ++i) + { + std::vector alpha_m_row (n); + for (size_t j = 0; j < n; ++j) + { + d1 = static_cast (floor (feature_cloud->points[i*n+j].f1 / angle_discretization_step_)); + d2 = static_cast (floor (feature_cloud->points[i*n+j].f2 / angle_discretization_step_)); + d3 = static_cast (floor (feature_cloud->points[i*n+j].f3 / angle_discretization_step_)); + d4 = static_cast (floor (feature_cloud->points[i*n+j].f4 / distance_discretization_step_)); + feature_hash_map_->insert (std::pair > (HashKeyStruct (d1, d2, d3, d4), std::pair (i, j))); + alpha_m_row [j] = feature_cloud->points[i*n + j].alpha_m; + + if (max_dist_ < feature_cloud->points[i*n + j].f4) + max_dist_ = feature_cloud->points[i*n + j].f4; + } + alpha_m_[i] = alpha_m_row; + } + + internals_initialized_ = true; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +void +pcl::PPFHashMapSearch::nearestNeighborSearch (float &f1, float &f2, float &f3, float &f4, + std::vector > &indices) +{ + if (!internals_initialized_) + { + PCL_ERROR("[pcl::PPFRegistration::nearestNeighborSearch]: input feature cloud has not been set - skipping search!\n"); + return; + } + + int d1 = static_cast (floor (f1 / angle_discretization_step_)), + d2 = static_cast (floor (f2 / angle_discretization_step_)), + d3 = static_cast (floor (f3 / angle_discretization_step_)), + d4 = static_cast (floor (f4 / distance_discretization_step_)); + + indices.clear (); + HashKeyStruct key = HashKeyStruct (d1, d2, d3, d4); + std::pair map_iterator_pair = feature_hash_map_->equal_range (key); + for (; map_iterator_pair.first != map_iterator_pair.second; ++ map_iterator_pair.first) + indices.push_back (std::pair (map_iterator_pair.first->second.first, + map_iterator_pair.first->second.second)); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PPFRegistration::setInputTarget (const PointCloudTargetConstPtr &cloud) +{ + Registration::setInputTarget (cloud); + + scene_search_tree_ = typename pcl::KdTreeFLANN::Ptr (new pcl::KdTreeFLANN); + scene_search_tree_->setInputCloud (target_); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PPFRegistration::computeTransformation (PointCloudSource &output, const Eigen::Matrix4f& guess) +{ + if (!search_method_) + { + PCL_ERROR("[pcl::PPFRegistration::computeTransformation] Search method not set - skipping computeTransformation!\n"); + return; + } + + if (guess != Eigen::Matrix4f::Identity ()) + { + PCL_ERROR("[pcl::PPFRegistration::computeTransformation] setting initial transform (guess) not implemented!\n"); + } + + PoseWithVotesList voted_poses; + std::vector > accumulator_array; + accumulator_array.resize (input_->points.size ()); + + size_t aux_size = static_cast (floor (2 * M_PI / search_method_->getAngleDiscretizationStep ())); + for (size_t i = 0; i < input_->points.size (); ++i) + { + std::vector aux (aux_size); + accumulator_array[i] = aux; + } + PCL_INFO ("Accumulator array size: %u x %u.\n", accumulator_array.size (), accumulator_array.back ().size ()); + + // Consider every -th point as the reference point => fix s_r + float f1, f2, f3, f4; + for (size_t scene_reference_index = 0; scene_reference_index < target_->points.size (); scene_reference_index += scene_reference_point_sampling_rate_) + { + Eigen::Vector3f scene_reference_point = target_->points[scene_reference_index].getVector3fMap (), + scene_reference_normal = target_->points[scene_reference_index].getNormalVector3fMap (); + + float rotation_angle_sg = acosf (scene_reference_normal.dot (Eigen::Vector3f::UnitX ())); + bool parallel_to_x_sg = (scene_reference_normal.y() == 0.0f && scene_reference_normal.z() == 0.0f); + Eigen::Vector3f rotation_axis_sg = (parallel_to_x_sg)?(Eigen::Vector3f::UnitY ()):(scene_reference_normal.cross (Eigen::Vector3f::UnitX ()). normalized()); + Eigen::AngleAxisf rotation_sg (rotation_angle_sg, rotation_axis_sg); + Eigen::Affine3f transform_sg (Eigen::Translation3f ( rotation_sg * ((-1) * scene_reference_point)) * rotation_sg); + + // For every other point in the scene => now have pair (s_r, s_i) fixed + std::vector indices; + std::vector distances; + scene_search_tree_->radiusSearch (target_->points[scene_reference_index], + search_method_->getModelDiameter () /2, + indices, + distances); + for(size_t i = 0; i < indices.size (); ++i) +// for(size_t i = 0; i < target_->points.size (); ++i) + { + //size_t scene_point_index = i; + size_t scene_point_index = indices[i]; + if (scene_reference_index != scene_point_index) + { + if (/*pcl::computePPFPairFeature*/pcl::computePairFeatures (target_->points[scene_reference_index].getVector4fMap (), + target_->points[scene_reference_index].getNormalVector4fMap (), + target_->points[scene_point_index].getVector4fMap (), + target_->points[scene_point_index].getNormalVector4fMap (), + f1, f2, f3, f4)) + { + std::vector > nearest_indices; + search_method_->nearestNeighborSearch (f1, f2, f3, f4, nearest_indices); + + // Compute alpha_s angle + Eigen::Vector3f scene_point = target_->points[scene_point_index].getVector3fMap (); + + Eigen::Vector3f scene_point_transformed = transform_sg * scene_point; + float alpha_s = atan2f ( -scene_point_transformed(2), scene_point_transformed(1)); + if (sin (alpha_s) * scene_point_transformed(2) < 0.0f) + alpha_s *= (-1); + alpha_s *= (-1); + + // Go through point pairs in the model with the same discretized feature + for (std::vector >::iterator v_it = nearest_indices.begin (); v_it != nearest_indices.end (); ++ v_it) + { + size_t model_reference_index = v_it->first, + model_point_index = v_it->second; + // Calculate angle alpha = alpha_m - alpha_s + float alpha = search_method_->alpha_m_[model_reference_index][model_point_index] - alpha_s; + unsigned int alpha_discretized = static_cast (floor (alpha) + floor (M_PI / search_method_->getAngleDiscretizationStep ())); + accumulator_array[model_reference_index][alpha_discretized] ++; + } + } + else PCL_ERROR ("[pcl::PPFRegistration::computeTransformation] Computing pair feature vector between points %u and %u went wrong.\n", scene_reference_index, scene_point_index); + } + } + + size_t max_votes_i = 0, max_votes_j = 0; + unsigned int max_votes = 0; + + for (size_t i = 0; i < accumulator_array.size (); ++i) + for (size_t j = 0; j < accumulator_array.back ().size (); ++j) + { + if (accumulator_array[i][j] > max_votes) + { + max_votes = accumulator_array[i][j]; + max_votes_i = i; + max_votes_j = j; + } + // Reset accumulator_array for the next set of iterations with a new scene reference point + accumulator_array[i][j] = 0; + } + + Eigen::Vector3f model_reference_point = input_->points[max_votes_i].getVector3fMap (), + model_reference_normal = input_->points[max_votes_i].getNormalVector3fMap (); + float rotation_angle_mg = acosf (model_reference_normal.dot (Eigen::Vector3f::UnitX ())); + bool parallel_to_x_mg = (model_reference_normal.y() == 0.0f && model_reference_normal.z() == 0.0f); + Eigen::Vector3f rotation_axis_mg = (parallel_to_x_mg)?(Eigen::Vector3f::UnitY ()):(model_reference_normal.cross (Eigen::Vector3f::UnitX ()). normalized()); + Eigen::AngleAxisf rotation_mg (rotation_angle_mg, rotation_axis_mg); + Eigen::Affine3f transform_mg (Eigen::Translation3f ( rotation_mg * ((-1) * model_reference_point)) * rotation_mg); + Eigen::Affine3f max_transform = + transform_sg.inverse () * + Eigen::AngleAxisf ((static_cast (max_votes_j) - floorf (static_cast (M_PI) / search_method_->getAngleDiscretizationStep ())) * search_method_->getAngleDiscretizationStep (), Eigen::Vector3f::UnitX ()) * + transform_mg; + + voted_poses.push_back (PoseWithVotes (max_transform, max_votes)); + } + PCL_DEBUG ("Done with the Hough Transform ...\n"); + + // Cluster poses for filtering out outliers and obtaining more precise results + PoseWithVotesList results; + clusterPoses (voted_poses, results); + + pcl::transformPointCloud (*input_, output, results.front ().pose); + + transformation_ = final_transformation_ = results.front ().pose.matrix (); + converged_ = true; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PPFRegistration::clusterPoses (typename pcl::PPFRegistration::PoseWithVotesList &poses, + typename pcl::PPFRegistration::PoseWithVotesList &result) +{ + PCL_INFO ("Clustering poses ...\n"); + // Start off by sorting the poses by the number of votes + sort(poses.begin (), poses.end (), poseWithVotesCompareFunction); + + std::vector clusters; + std::vector > cluster_votes; + for (size_t poses_i = 0; poses_i < poses.size(); ++ poses_i) + { + bool found_cluster = false; + for (size_t clusters_i = 0; clusters_i < clusters.size(); ++ clusters_i) + { + if (posesWithinErrorBounds (poses[poses_i].pose, clusters[clusters_i].front ().pose)) + { + found_cluster = true; + clusters[clusters_i].push_back (poses[poses_i]); + cluster_votes[clusters_i].second += poses[poses_i].votes; + break; + } + } + + if (found_cluster == false) + { + // Create a new cluster with the current pose + PoseWithVotesList new_cluster; + new_cluster.push_back (poses[poses_i]); + clusters.push_back (new_cluster); + cluster_votes.push_back (std::pair (clusters.size () - 1, poses[poses_i].votes)); + } + } + + // Sort clusters by total number of votes + std::sort (cluster_votes.begin (), cluster_votes.end (), clusterVotesCompareFunction); + // Compute pose average and put them in result vector + /// @todo some kind of threshold for determining whether a cluster has enough votes or not... + /// now just taking the first three clusters + result.clear (); + size_t max_clusters = (clusters.size () < 3) ? clusters.size () : 3; + for (size_t cluster_i = 0; cluster_i < max_clusters; ++ cluster_i) + { + PCL_INFO ("Winning cluster has #votes: %d and #poses voted: %d.\n", cluster_votes[cluster_i].second, clusters[cluster_votes[cluster_i].first].size ()); + Eigen::Vector3f translation_average (0.0, 0.0, 0.0); + Eigen::Vector4f rotation_average (0.0, 0.0, 0.0, 0.0); + for (typename PoseWithVotesList::iterator v_it = clusters[cluster_votes[cluster_i].first].begin (); v_it != clusters[cluster_votes[cluster_i].first].end (); ++ v_it) + { + translation_average += v_it->pose.translation (); + /// averaging rotations by just averaging the quaternions in 4D space - reference "On Averaging Rotations" by CLAUS GRAMKOW + rotation_average += Eigen::Quaternionf (v_it->pose.rotation ()).coeffs (); + } + + translation_average /= static_cast (clusters[cluster_votes[cluster_i].first].size ()); + rotation_average /= static_cast (clusters[cluster_votes[cluster_i].first].size ()); + + Eigen::Affine3f transform_average; + transform_average.translation ().matrix () = translation_average; + transform_average.linear ().matrix () = Eigen::Quaternionf (rotation_average).normalized().toRotationMatrix (); + + result.push_back (PoseWithVotes (transform_average, cluster_votes[cluster_i].second)); + } +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::PPFRegistration::posesWithinErrorBounds (Eigen::Affine3f &pose1, + Eigen::Affine3f &pose2) +{ + float position_diff = (pose1.translation () - pose2.translation ()).norm (); + Eigen::AngleAxisf rotation_diff_mat (pose1.rotation ().inverse ().lazyProduct (pose2.rotation ())); + + float rotation_diff_angle = fabsf (rotation_diff_mat.angle ()); + + if (position_diff < clustering_position_diff_threshold_ && rotation_diff_angle < clustering_rotation_diff_threshold_) + return true; + else return false; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::PPFRegistration::poseWithVotesCompareFunction (const typename pcl::PPFRegistration::PoseWithVotes &a, + const typename pcl::PPFRegistration::PoseWithVotes &b ) +{ + return (a.votes > b.votes); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::PPFRegistration::clusterVotesCompareFunction (const std::pair &a, + const std::pair &b) +{ + return (a.second > b.second); +} + +//#define PCL_INSTANTIATE_PPFRegistration(PointSource,PointTarget) template class PCL_EXPORTS pcl::PPFRegistration; + +#endif // PCL_REGISTRATION_IMPL_PPF_REGISTRATION_H_ diff --git a/pcl-1.7/pcl/registration/impl/pyramid_feature_matching.hpp b/pcl-1.7/pcl/registration/impl/pyramid_feature_matching.hpp new file mode 100644 index 0000000..2753979 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/pyramid_feature_matching.hpp @@ -0,0 +1,315 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Willow Garage, Inc + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_IMPL_PYRAMID_FEATURE_MATCHING_H_ +#define PCL_REGISTRATION_IMPL_PYRAMID_FEATURE_MATCHING_H_ + +#include +#include + + +/** \brief Helper function to calculate the binary logarithm + * \param n_arg: some value + * \return binary logarithm (log2) of argument n_arg + */ +__inline float +Log2 (float n_arg) +{ + return std::log (n_arg) / float (M_LN2); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::PyramidFeatureHistogram::comparePyramidFeatureHistograms (const PyramidFeatureHistogramPtr &pyramid_a, + const PyramidFeatureHistogramPtr &pyramid_b) +{ + // do a few consistency checks before and during the computation + if (pyramid_a->nr_dimensions != pyramid_b->nr_dimensions) + { + PCL_ERROR ("[pcl::PyramidFeatureMatching::comparePyramidFeatureHistograms] The two given pyramids have different numbers of dimensions: %u vs %u\n", pyramid_a->nr_dimensions, pyramid_b->nr_dimensions); + return -1; + } + if (pyramid_a->nr_levels != pyramid_b->nr_levels) + { + PCL_ERROR ("[pcl::PyramidFeatureMatching::comparePyramidFeatureHistograms] The two given pyramids have different numbers of levels: %u vs %u\n", pyramid_a->nr_levels, pyramid_b->nr_levels); + return -1; + } + + + // calculate for level 0 first + if (pyramid_a->hist_levels[0].hist.size () != pyramid_b->hist_levels[0].hist.size ()) + { + PCL_ERROR ("[pcl::PyramidFeatureMatching::comparePyramidFeatureHistograms] The two given pyramids have different numbers of bins on level 0: %u vs %u\n", pyramid_a->hist_levels[0].hist.size (), pyramid_b->hist_levels[0].hist.size ()); + return -1; + } + float match_count_level = 0.0f, match_count_prev_level = 0.0f; + for (size_t bin_i = 0; bin_i < pyramid_a->hist_levels[0].hist.size (); ++bin_i) + { + if (pyramid_a->hist_levels[0].hist[bin_i] < pyramid_b->hist_levels[0].hist[bin_i]) + match_count_level += static_cast (pyramid_a->hist_levels[0].hist[bin_i]); + else + match_count_level += static_cast (pyramid_b->hist_levels[0].hist[bin_i]); + } + + + float match_count = match_count_level; + for (size_t level_i = 1; level_i < pyramid_a->nr_levels; ++level_i) + { + if (pyramid_a->hist_levels[level_i].hist.size () != pyramid_b->hist_levels[level_i].hist.size ()) + { + PCL_ERROR ("[pcl::PyramidFeatureMatching::comparePyramidFeatureHistograms] The two given pyramids have different numbers of bins on level %u: %u vs %u\n", level_i, pyramid_a->hist_levels[level_i].hist.size (), pyramid_b->hist_levels[level_i].hist.size ()); + return -1; + } + + match_count_prev_level = match_count_level; + match_count_level = 0.0f; + for (size_t bin_i = 0; bin_i < pyramid_a->hist_levels[level_i].hist.size (); ++bin_i) + { + if (pyramid_a->hist_levels[level_i].hist[bin_i] < pyramid_b->hist_levels[level_i].hist[bin_i]) + match_count_level += static_cast (pyramid_a->hist_levels[level_i].hist[bin_i]); + else + match_count_level += static_cast (pyramid_b->hist_levels[level_i].hist[bin_i]); + } + + float level_normalization_factor = powf (2.0f, static_cast (level_i)); + match_count += (match_count_level - match_count_prev_level) / level_normalization_factor; + } + + + // include self-similarity factors + float self_similarity_a = static_cast (pyramid_a->nr_features), + self_similarity_b = static_cast (pyramid_b->nr_features); + PCL_DEBUG ("[pcl::PyramidFeatureMatching::comparePyramidFeatureHistograms] Self similarity measures: %f, %f\n", self_similarity_a, self_similarity_b); + match_count /= sqrtf (self_similarity_a * self_similarity_b); + + return match_count; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::PyramidFeatureHistogram::PyramidFeatureHistogram () : + nr_dimensions (0), nr_levels (0), nr_features (0), + dimension_range_input_ (), dimension_range_target_ (), + feature_representation_ (new DefaultPointRepresentation), + is_computed_ (false), + hist_levels () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PyramidFeatureHistogram::PyramidFeatureHistogramLevel::initializeHistogramLevel () +{ + size_t total_vector_size = 1; + for (std::vector::iterator dim_it = bins_per_dimension.begin (); dim_it != bins_per_dimension.end (); ++dim_it) + total_vector_size *= *dim_it; + + hist.resize (total_vector_size, 0); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::PyramidFeatureHistogram::initializeHistogram () +{ + // a few consistency checks before starting the computations + if (!PCLBase::initCompute ()) + { + PCL_ERROR ("[pcl::PyramidFeatureHistogram::initializeHistogram] PCLBase initCompute failed\n"); + return false; + } + + if (dimension_range_input_.size () == 0) + { + PCL_ERROR ("[pcl::PyramidFeatureHistogram::initializeHistogram] Input dimension range was not set\n"); + return false; + } + + if (dimension_range_target_.size () == 0) + { + PCL_ERROR ("[pcl::PyramidFeatureHistogram::initializeHistogram] Target dimension range was not set\n"); + return false; + } + + if (dimension_range_input_.size () != dimension_range_target_.size ()) + { + PCL_ERROR ("[pcl::PyramidFeatureHistogram::initializeHistogram] Input and target dimension ranges do not agree in size: %u vs %u\n", + dimension_range_input_.size (), dimension_range_target_.size ()); + return false; + } + + + nr_dimensions = dimension_range_target_.size (); + nr_features = input_->points.size (); + float D = 0.0f; + for (std::vector >::iterator range_it = dimension_range_target_.begin (); range_it != dimension_range_target_.end (); ++range_it) + { + float aux = range_it->first - range_it->second; + D += aux * aux; + } + D = sqrtf (D); + nr_levels = static_cast (ceilf (Log2 (D))); + PCL_DEBUG ("[pcl::PyramidFeatureHistogram::initializeHistogram] Pyramid will have %u levels with a hyper-parallelepiped diagonal size of %f\n", nr_levels, D); + + + hist_levels.resize (nr_levels); + for (size_t level_i = 0; level_i < nr_levels; ++level_i) + { + std::vector bins_per_dimension (nr_dimensions); + std::vector bin_step (nr_dimensions); + for (size_t dim_i = 0; dim_i < nr_dimensions; ++dim_i) + { + bins_per_dimension[dim_i] = + static_cast (ceilf ((dimension_range_target_[dim_i].second - dimension_range_target_[dim_i].first) / (powf (2.0f, static_cast (level_i)) * sqrtf (static_cast (nr_dimensions))))); + bin_step[dim_i] = powf (2.0f, static_cast (level_i)) * sqrtf (static_cast (nr_dimensions)); + } + hist_levels[level_i] = PyramidFeatureHistogramLevel (bins_per_dimension, bin_step); + + PCL_DEBUG ("[pcl::PyramidFeatureHistogram::initializeHistogram] Created vector of size %u at level %u\nwith #bins per dimension:", hist_levels.back ().hist.size (), level_i); + for (size_t dim_i = 0; dim_i < nr_dimensions; ++dim_i) + PCL_DEBUG ("%u ", bins_per_dimension[dim_i]); + PCL_DEBUG ("\n"); + } + + return true; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template unsigned int& +pcl::PyramidFeatureHistogram::at (std::vector &access, + size_t &level) +{ + if (access.size () != nr_dimensions) + { + PCL_ERROR ("[pcl::PyramidFeatureHistogram::at] Cannot access histogram position because the access point does not have the right number of dimensions\n"); + return hist_levels.front ().hist.front (); + } + if (level >= hist_levels.size ()) + { + PCL_ERROR ("[pcl::PyramidFeatureHistogram::at] Trying to access a too large level\n"); + return hist_levels.front ().hist.front (); + } + + size_t vector_position = 0; + size_t dim_accumulator = 1; + + for (int i = static_cast (access.size ()) - 1; i >= 0; --i) + { + vector_position += access[i] * dim_accumulator; + dim_accumulator *= hist_levels[level].bins_per_dimension[i]; + } + + return hist_levels[level].hist[vector_position]; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template unsigned int& +pcl::PyramidFeatureHistogram::at (std::vector &feature, + size_t &level) +{ + if (feature.size () != nr_dimensions) + { + PCL_ERROR ("[pcl::PyramidFeatureHistogram::at] The given feature vector does not match the feature dimensions of the pyramid histogram: %u vs %u\n", feature.size (), nr_dimensions); + return hist_levels.front ().hist.front (); + } + if (level >= hist_levels.size ()) + { + PCL_ERROR ("[pcl::PyramidFeatureHistogram::at] Trying to access a too large level\n"); + return hist_levels.front ().hist.front (); + } + + std::vector access; + for (size_t dim_i = 0; dim_i < nr_dimensions; ++dim_i) + access.push_back (static_cast (floor ((feature[dim_i] - dimension_range_target_[dim_i].first) / hist_levels[level].bin_step[dim_i]))); + + return at (access, level); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PyramidFeatureHistogram::convertFeatureToVector (const PointFeature &feature, + std::vector &feature_vector) +{ + // convert feature to vector representation + feature_vector.resize (feature_representation_->getNumberOfDimensions ()); + feature_representation_->vectorize (feature, feature_vector); + + // adapt the values from the input range to the target range + for (size_t i = 0; i < feature_vector.size (); ++i) + feature_vector[i] = (feature_vector[i] - dimension_range_input_[i].first) / (dimension_range_input_[i].second - dimension_range_input_[i].first) * + (dimension_range_target_[i].second - dimension_range_target_[i].first) + dimension_range_target_[i].first; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PyramidFeatureHistogram::compute () +{ + if (!initializeHistogram ()) + return; + + for (size_t feature_i = 0; feature_i < input_->points.size (); ++feature_i) + { + std::vector feature_vector; + convertFeatureToVector (input_->points[feature_i], feature_vector); + addFeature (feature_vector); + } + + is_computed_ = true; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PyramidFeatureHistogram::addFeature (std::vector &feature) +{ + for (size_t level_i = 0; level_i < nr_levels; ++level_i) + at (feature, level_i) ++; +} + +#define PCL_INSTANTIATE_PyramidFeatureHistogram(PointFeature) template class PCL_EXPORTS pcl::PyramidFeatureHistogram; + +#endif /* PCL_REGISTRATION_IMPL_PYRAMID_FEATURE_MATCHING_H_ */ diff --git a/pcl-1.7/pcl/registration/impl/registration.hpp b/pcl-1.7/pcl/registration/impl/registration.hpp new file mode 100644 index 0000000..bbee173 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/registration.hpp @@ -0,0 +1,220 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::Registration::setInputCloud ( + const typename pcl::Registration::PointCloudSourceConstPtr &cloud) +{ + setInputSource (cloud); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::Registration::PointCloudSourceConstPtr const +pcl::Registration::getInputCloud () +{ + return (getInputSource ()); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::Registration::setInputTarget (const PointCloudTargetConstPtr &cloud) +{ + if (cloud->points.empty ()) + { + PCL_ERROR ("[pcl::%s::setInputTarget] Invalid or empty point cloud dataset given!\n", getClassName ().c_str ()); + return; + } + target_ = cloud; + target_cloud_updated_ = true; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::Registration::initCompute () +{ + if (!target_) + { + PCL_ERROR ("[pcl::registration::%s::compute] No input target dataset was given!\n", getClassName ().c_str ()); + return (false); + } + + // Only update target kd-tree if a new target cloud was set + if (target_cloud_updated_ && !force_no_recompute_) + { + tree_->setInputCloud (target_); + target_cloud_updated_ = false; + } + + + // Update the correspondence estimation + if (correspondence_estimation_) + { + correspondence_estimation_->setSearchMethodTarget (tree_, force_no_recompute_); + correspondence_estimation_->setSearchMethodSource (tree_reciprocal_, force_no_recompute_reciprocal_); + } + + // Note: we /cannot/ update the search method on all correspondence rejectors, because we know + // nothing about them. If they should be cached, they must be cached individually. + + return (PCLBase::initCompute ()); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::Registration::initComputeReciprocal () +{ + if (!input_) + { + PCL_ERROR ("[pcl::registration::%s::compute] No input source dataset was given!\n", getClassName ().c_str ()); + return (false); + } + + if (source_cloud_updated_ && !force_no_recompute_reciprocal_) + { + tree_reciprocal_->setInputCloud (input_); + source_cloud_updated_ = false; + } + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline double +pcl::Registration::getFitnessScore ( + const std::vector &distances_a, + const std::vector &distances_b) +{ + unsigned int nr_elem = static_cast (std::min (distances_a.size (), distances_b.size ())); + Eigen::VectorXf map_a = Eigen::VectorXf::Map (&distances_a[0], nr_elem); + Eigen::VectorXf map_b = Eigen::VectorXf::Map (&distances_b[0], nr_elem); + return (static_cast ((map_a - map_b).sum ()) / static_cast (nr_elem)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline double +pcl::Registration::getFitnessScore (double max_range) +{ + + double fitness_score = 0.0; + + // Transform the input dataset using the final transformation + PointCloudSource input_transformed; + transformPointCloud (*input_, input_transformed, final_transformation_); + + std::vector nn_indices (1); + std::vector nn_dists (1); + + // For each point in the source dataset + int nr = 0; + for (size_t i = 0; i < input_transformed.points.size (); ++i) + { + // Find its nearest neighbor in the target + tree_->nearestKSearch (input_transformed.points[i], 1, nn_indices, nn_dists); + + // Deal with occlusions (incomplete targets) + if (nn_dists[0] <= max_range) + { + // Add to the fitness score + fitness_score += nn_dists[0]; + nr++; + } + } + + if (nr > 0) + return (fitness_score / nr); + else + return (std::numeric_limits::max ()); + +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::Registration::align (PointCloudSource &output) +{ + align (output, Matrix4::Identity ()); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::Registration::align (PointCloudSource &output, const Matrix4& guess) +{ + if (!initCompute ()) + return; + + // Resize the output dataset + if (output.points.size () != indices_->size ()) + output.points.resize (indices_->size ()); + // Copy the header + output.header = input_->header; + // Check if the output will be computed for all points or only a subset + if (indices_->size () != input_->points.size ()) + { + output.width = static_cast (indices_->size ()); + output.height = 1; + } + else + { + output.width = static_cast (input_->width); + output.height = input_->height; + } + output.is_dense = input_->is_dense; + + // Copy the point data to output + for (size_t i = 0; i < indices_->size (); ++i) + output.points[i] = input_->points[(*indices_)[i]]; + + // Set the internal point representation of choice unless otherwise noted + if (point_representation_ && !force_no_recompute_) + tree_->setPointRepresentation (point_representation_); + + // Perform the actual transformation computation + converged_ = false; + final_transformation_ = transformation_ = previous_transformation_ = Matrix4::Identity (); + + // Right before we estimate the transformation, we set all the point.data[3] values to 1 to aid the rigid + // transformation + for (size_t i = 0; i < indices_->size (); ++i) + output.points[i].data[3] = 1.0; + + computeTransformation (output, guess); + + deinitCompute (); +} + diff --git a/pcl-1.7/pcl/registration/impl/sample_consensus_prerejective.hpp b/pcl-1.7/pcl/registration/impl/sample_consensus_prerejective.hpp new file mode 100644 index 0000000..a755e51 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/sample_consensus_prerejective.hpp @@ -0,0 +1,337 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_SAMPLE_CONSENSUS_PREREJECTIVE_HPP_ +#define PCL_REGISTRATION_SAMPLE_CONSENSUS_PREREJECTIVE_HPP_ + +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusPrerejective::setSourceFeatures (const FeatureCloudConstPtr &features) +{ + if (features == NULL || features->empty ()) + { + PCL_ERROR ("[pcl::%s::setSourceFeatures] Invalid or empty point cloud dataset given!\n", getClassName ().c_str ()); + return; + } + input_features_ = features; +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusPrerejective::setTargetFeatures (const FeatureCloudConstPtr &features) +{ + if (features == NULL || features->empty ()) + { + PCL_ERROR ("[pcl::%s::setTargetFeatures] Invalid or empty point cloud dataset given!\n", getClassName ().c_str ()); + return; + } + target_features_ = features; + feature_tree_->setInputCloud (target_features_); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusPrerejective::selectSamples ( + const PointCloudSource &cloud, int nr_samples, std::vector &sample_indices) +{ + if (nr_samples > static_cast (cloud.points.size ())) + { + PCL_ERROR ("[pcl::%s::selectSamples] ", getClassName ().c_str ()); + PCL_ERROR ("The number of samples (%d) must not be greater than the number of points (%lu)!\n", + nr_samples, cloud.points.size ()); + return; + } + + sample_indices.resize (nr_samples); + int temp_sample; + + // Draw random samples until n samples is reached + for (int i = 0; i < nr_samples; i++) + { + // Select a random number + sample_indices[i] = getRandomIndex (static_cast (cloud.points.size ()) - i); + + // Run trough list of numbers, starting at the lowest, to avoid duplicates + for (int j = 0; j < i; j++) + { + // Move value up if it is higher than previous selections to ensure true randomness + if (sample_indices[i] >= sample_indices[j]) + { + sample_indices[i]++; + } + else + { + // The new number is lower, place it at the correct point and break for a sorted list + temp_sample = sample_indices[i]; + for (int k = i; k > j; k--) + sample_indices[k] = sample_indices[k - 1]; + + sample_indices[j] = temp_sample; + break; + } + } + } +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusPrerejective::findSimilarFeatures ( + const std::vector &sample_indices, + std::vector >& similar_features, + std::vector &corresponding_indices) +{ + // Allocate results + corresponding_indices.resize (sample_indices.size ()); + std::vector nn_distances (k_correspondences_); + + // Loop over the sampled features + for (size_t i = 0; i < sample_indices.size (); ++i) + { + // Current feature index + const int idx = sample_indices[i]; + + // Find the k nearest feature neighbors to the sampled input feature if they are not in the cache already + if (similar_features[idx].empty ()) + feature_tree_->nearestKSearch (*input_features_, idx, k_correspondences_, similar_features[idx], nn_distances); + + // Select one at random and add it to corresponding_indices + if (k_correspondences_ == 1) + corresponding_indices[i] = similar_features[idx][0]; + else + corresponding_indices[i] = similar_features[idx][getRandomIndex (k_correspondences_)]; + } +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusPrerejective::computeTransformation (PointCloudSource &output, const Eigen::Matrix4f& guess) +{ + // Some sanity checks first + if (!input_features_) + { + PCL_ERROR ("[pcl::%s::computeTransformation] ", getClassName ().c_str ()); + PCL_ERROR ("No source features were given! Call setSourceFeatures before aligning.\n"); + return; + } + if (!target_features_) + { + PCL_ERROR ("[pcl::%s::computeTransformation] ", getClassName ().c_str ()); + PCL_ERROR ("No target features were given! Call setTargetFeatures before aligning.\n"); + return; + } + + if (input_->size () != input_features_->size ()) + { + PCL_ERROR ("[pcl::%s::computeTransformation] ", getClassName ().c_str ()); + PCL_ERROR ("The source points and source feature points need to be in a one-to-one relationship! Current input cloud sizes: %ld vs %ld.\n", + input_->size (), input_features_->size ()); + return; + } + + if (target_->size () != target_features_->size ()) + { + PCL_ERROR ("[pcl::%s::computeTransformation] ", getClassName ().c_str ()); + PCL_ERROR ("The target points and target feature points need to be in a one-to-one relationship! Current input cloud sizes: %ld vs %ld.\n", + target_->size (), target_features_->size ()); + return; + } + + if (inlier_fraction_ < 0.0f || inlier_fraction_ > 1.0f) + { + PCL_ERROR ("[pcl::%s::computeTransformation] ", getClassName ().c_str ()); + PCL_ERROR ("Illegal inlier fraction %f, must be in [0,1]!\n", + inlier_fraction_); + return; + } + + const float similarity_threshold = correspondence_rejector_poly_->getSimilarityThreshold (); + if (similarity_threshold < 0.0f || similarity_threshold >= 1.0f) + { + PCL_ERROR ("[pcl::%s::computeTransformation] ", getClassName ().c_str ()); + PCL_ERROR ("Illegal prerejection similarity threshold %f, must be in [0,1[!\n", + similarity_threshold); + return; + } + + if (k_correspondences_ <= 0) + { + PCL_ERROR ("[pcl::%s::computeTransformation] ", getClassName ().c_str ()); + PCL_ERROR ("Illegal correspondence randomness %d, must be > 0!\n", + k_correspondences_); + return; + } + + // Initialize prerejector (similarity threshold already set to default value in constructor) + correspondence_rejector_poly_->setInputSource (input_); + correspondence_rejector_poly_->setInputTarget (target_); + correspondence_rejector_poly_->setCardinality (nr_samples_); + int num_rejections = 0; // For debugging + + // Initialize results + final_transformation_ = guess; + inliers_.clear (); + float lowest_error = std::numeric_limits::max (); + converged_ = false; + + // Temporaries + std::vector inliers; + float inlier_fraction; + float error; + + // If guess is not the Identity matrix we check it + if (!guess.isApprox (Eigen::Matrix4f::Identity (), 0.01f)) + { + getFitness (inliers, error); + inlier_fraction = static_cast (inliers.size ()) / static_cast (input_->size ()); + error /= static_cast (inliers.size ()); + + if (inlier_fraction >= inlier_fraction_ && error < lowest_error) + { + inliers_ = inliers; + lowest_error = error; + converged_ = true; + } + } + + // Feature correspondence cache + std::vector > similar_features (input_->size ()); + + // Start + for (int i = 0; i < max_iterations_; ++i) + { + // Temporary containers + std::vector sample_indices; + std::vector corresponding_indices; + + // Draw nr_samples_ random samples + selectSamples (*input_, nr_samples_, sample_indices); + + // Find corresponding features in the target cloud + findSimilarFeatures (sample_indices, similar_features, corresponding_indices); + + // Apply prerejection + if (!correspondence_rejector_poly_->thresholdPolygon (sample_indices, corresponding_indices)) + { + ++num_rejections; + continue; + } + + // Estimate the transform from the correspondences, write to transformation_ + transformation_estimation_->estimateRigidTransformation (*input_, sample_indices, *target_, corresponding_indices, transformation_); + + // Take a backup of previous result + const Matrix4 final_transformation_prev = final_transformation_; + + // Set final result to current transformation + final_transformation_ = transformation_; + + // Transform the input and compute the error (uses input_ and final_transformation_) + getFitness (inliers, error); + + // Restore previous result + final_transformation_ = final_transformation_prev; + + // If the new fit is better, update results + inlier_fraction = static_cast (inliers.size ()) / static_cast (input_->size ()); + + // Update result if pose hypothesis is better + if (inlier_fraction >= inlier_fraction_ && error < lowest_error) + { + inliers_ = inliers; + lowest_error = error; + converged_ = true; + final_transformation_ = transformation_; + } + } + + // Apply the final transformation + if (converged_) + transformPointCloud (*input_, output, final_transformation_); + + // Debug output + PCL_DEBUG("[pcl::%s::computeTransformation] Rejected %i out of %i generated pose hypotheses.\n", + getClassName ().c_str (), num_rejections, max_iterations_); +} + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusPrerejective::getFitness (std::vector& inliers, float& fitness_score) +{ + // Initialize variables + inliers.clear (); + inliers.reserve (input_->size ()); + fitness_score = 0.0f; + + // Use squared distance for comparison with NN search results + const float max_range = corr_dist_threshold_ * corr_dist_threshold_; + + // Transform the input dataset using the final transformation + PointCloudSource input_transformed; + input_transformed.resize (input_->size ()); + transformPointCloud (*input_, input_transformed, final_transformation_); + + // For each point in the source dataset + for (size_t i = 0; i < input_transformed.points.size (); ++i) + { + // Find its nearest neighbor in the target + std::vector nn_indices (1); + std::vector nn_dists (1); + tree_->nearestKSearch (input_transformed.points[i], 1, nn_indices, nn_dists); + + // Check if point is an inlier + if (nn_dists[0] < max_range) + { + // Update inliers + inliers.push_back (static_cast (i)); + + // Update fitness score + fitness_score += nn_dists[0]; + } + } + + // Calculate MSE + if (inliers.size () > 0) + fitness_score /= static_cast (inliers.size ()); + else + fitness_score = std::numeric_limits::max (); +} + +#endif + diff --git a/pcl-1.7/pcl/registration/impl/transformation_estimation_2D.hpp b/pcl-1.7/pcl/registration/impl/transformation_estimation_2D.hpp new file mode 100644 index 0000000..759daa5 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/transformation_estimation_2D.hpp @@ -0,0 +1,165 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_2D_HPP_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_2D_HPP_ + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimation2D::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const +{ + size_t nr_points = cloud_src.points.size (); + if (cloud_tgt.points.size () != nr_points) + { + PCL_ERROR ("[pcl::TransformationEstimation2D::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", nr_points, cloud_tgt.points.size ()); + return; + } + + ConstCloudIterator source_it (cloud_src); + ConstCloudIterator target_it (cloud_tgt); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimation2D::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const +{ + if (indices_src.size () != cloud_tgt.points.size ()) + { + PCL_ERROR ("[pcl::Transformation2D::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", indices_src.size (), cloud_tgt.points.size ()); + return; + } + + ConstCloudIterator source_it (cloud_src, indices_src); + ConstCloudIterator target_it (cloud_tgt); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimation2D::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const +{ + if (indices_src.size () != indices_tgt.size ()) + { + PCL_ERROR ("[pcl::TransformationEstimation2D::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", indices_src.size (), indices_tgt.size ()); + return; + } + + ConstCloudIterator source_it (cloud_src, indices_src); + ConstCloudIterator target_it (cloud_tgt, indices_tgt); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimation2D::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const +{ + ConstCloudIterator source_it (cloud_src, correspondences, true); + ConstCloudIterator target_it (cloud_tgt, correspondences, false); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimation2D::estimateRigidTransformation ( + ConstCloudIterator& source_it, + ConstCloudIterator& target_it, + Matrix4 &transformation_matrix) const +{ + source_it.reset (); target_it.reset (); + + Eigen::Matrix centroid_src, centroid_tgt; + // Estimate the centroids of source, target + compute3DCentroid (source_it, centroid_src); + compute3DCentroid (target_it, centroid_tgt); + source_it.reset (); target_it.reset (); + + // ignore z component + centroid_src[2] = 0.0f; + centroid_tgt[2] = 0.0f; + // Subtract the centroids from source, target + Eigen::Matrix cloud_src_demean, cloud_tgt_demean; + demeanPointCloud (source_it, centroid_src, cloud_src_demean); + demeanPointCloud (target_it, centroid_tgt, cloud_tgt_demean); + + getTransformationFromCorrelation (cloud_src_demean, centroid_src, cloud_tgt_demean, centroid_tgt, transformation_matrix); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimation2D::getTransformationFromCorrelation ( + const Eigen::Matrix &cloud_src_demean, + const Eigen::Matrix ¢roid_src, + const Eigen::Matrix &cloud_tgt_demean, + const Eigen::Matrix ¢roid_tgt, + Matrix4 &transformation_matrix) const +{ + transformation_matrix.setIdentity (); + + // Assemble the correlation matrix H = source * target' + Eigen::Matrix H = (cloud_src_demean * cloud_tgt_demean.transpose ()).topLeftCorner (3, 3); + + float angle = atan2 ((H (0, 1) - H (1, 0)), (H(0, 0) + H (1, 1))); + + Eigen::Matrix R (Eigen::Matrix::Identity ()); + R (0, 0) = R (1, 1) = cos (angle); + R (0, 1) = -sin (angle); + R (1, 0) = sin (angle); + + // Return the correct transformation + transformation_matrix.topLeftCorner (3, 3).matrix () = R; + const Eigen::Matrix Rc (R * centroid_src.head (3).matrix ()); + transformation_matrix.block (0, 3, 3, 1).matrix () = centroid_tgt.head (3) - Rc; +} + +#endif // PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_2D_HPP_ diff --git a/pcl-1.7/pcl/registration/impl/transformation_estimation_dual_quaternion.hpp b/pcl-1.7/pcl/registration/impl/transformation_estimation_dual_quaternion.hpp new file mode 100644 index 0000000..f5f20cd --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/transformation_estimation_dual_quaternion.hpp @@ -0,0 +1,207 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_HPP_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_HPP_ + +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationDualQuaternion::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const +{ + size_t nr_points = cloud_src.points.size (); + if (cloud_tgt.points.size () != nr_points) + { + PCL_ERROR ("[pcl::TransformationEstimationDualQuaternion::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", nr_points, cloud_tgt.points.size ()); + return; + } + + ConstCloudIterator source_it (cloud_src); + ConstCloudIterator target_it (cloud_tgt); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimationDualQuaternion::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const +{ + if (indices_src.size () != cloud_tgt.points.size ()) + { + PCL_ERROR ("[pcl::TransformationDQ::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", indices_src.size (), cloud_tgt.points.size ()); + return; + } + + ConstCloudIterator source_it (cloud_src, indices_src); + ConstCloudIterator target_it (cloud_tgt); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationDualQuaternion::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const +{ + if (indices_src.size () != indices_tgt.size ()) + { + PCL_ERROR ("[pcl::TransformationEstimationDualQuaternion::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", indices_src.size (), indices_tgt.size ()); + return; + } + + ConstCloudIterator source_it (cloud_src, indices_src); + ConstCloudIterator target_it (cloud_tgt, indices_tgt); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimationDualQuaternion::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const +{ + ConstCloudIterator source_it (cloud_src, correspondences, true); + ConstCloudIterator target_it (cloud_tgt, correspondences, false); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationDualQuaternion::estimateRigidTransformation ( + ConstCloudIterator& source_it, + ConstCloudIterator& target_it, + Matrix4 &transformation_matrix) const +{ + const int npts = static_cast (source_it.size ()); + + transformation_matrix.setIdentity (); + + // dual quaternion optimization + Eigen::Matrix C1 = Eigen::Matrix::Zero (); + Eigen::Matrix C2 = Eigen::Matrix::Zero (); + double* c1 = C1.data (); + double* c2 = C2.data (); + + for (int i = 0; i < npts; ++i) + { + const PointSource& a = *source_it; + const PointTarget& b = *target_it; + const double axbx = a.x * b.x; + const double ayby = a.y * b.y; + const double azbz = a.z * b.z; + const double axby = a.x * b.y; + const double aybx = a.y * b.x; + const double axbz = a.x * b.z; + const double azbx = a.z * b.x; + const double aybz = a.y * b.z; + const double azby = a.z * b.y; + c1[0] += axbx - azbz - ayby; + c1[5] += ayby - azbz - axbx; + c1[10] += azbz - axbx - ayby; + c1[15] += axbx + ayby + azbz; + c1[1] += axby + aybx; + c1[2] += axbz + azbx; + c1[3] += aybz - azby; + c1[6] += azby + aybz; + c1[7] += azbx - axbz; + c1[11] += axby - aybx; + + c2[1] += a.z + b.z; + c2[2] -= a.y + b.y; + c2[3] += a.x - b.x; + c2[6] += a.x + b.x; + c2[7] += a.y - b.y; + c2[11] += a.z - b.z; + source_it++; + target_it++; + } + + c1[4] = c1[1]; + c1[8] = c1[2]; + c1[9] = c1[6]; + c1[12] = c1[3]; + c1[13] = c1[7]; + c1[14] = c1[11]; + c2[4] = -c2[1]; + c2[8] = -c2[2]; + c2[12] = -c2[3]; + c2[9] = -c2[6]; + c2[13] = -c2[7]; + c2[14] = -c2[11]; + + C1 *= -2.0; + C2 *= 2.0; + + const Eigen::Matrix A = (0.25 / double (npts)) * C2.transpose () * C2 - C1; + + const Eigen::EigenSolver > es (A); + + ptrdiff_t i; + es.eigenvalues ().real ().maxCoeff (&i); + const Eigen::Matrix qmat = es.eigenvectors ().col (i).real (); + const Eigen::Matrix smat = - (0.5 / double (npts)) * C2 * qmat; + + const Eigen::Quaternion q (qmat (3), qmat (0), qmat (1), qmat (2)); + const Eigen::Quaternion s (smat (3), smat (0), smat (1), smat (2)); + + const Eigen::Quaternion t = s * q.conjugate (); + + const Eigen::Matrix R (q.toRotationMatrix ()); + + for (int i = 0; i < 3; ++i) + for (int j = 0; j < 3; ++j) + transformation_matrix (i, j) = R (i, j); + + transformation_matrix (0, 3) = - t.x (); + transformation_matrix (1, 3) = - t.y (); + transformation_matrix (2, 3) = - t.z (); +} + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_HPP_ */ diff --git a/pcl-1.7/pcl/registration/impl/transformation_estimation_lm.hpp b/pcl-1.7/pcl/registration/impl/transformation_estimation_lm.hpp new file mode 100644 index 0000000..c857342 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/transformation_estimation_lm.hpp @@ -0,0 +1,273 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_LM_HPP_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_LM_HPP_ + +#include +#include +#include +#include + + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::registration::TransformationEstimationLM::TransformationEstimationLM () + : tmp_src_ () + , tmp_tgt_ () + , tmp_idx_src_ () + , tmp_idx_tgt_ () + , warp_point_ (new WarpPointRigid6D) +{ +}; + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimationLM::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const +{ + + // is the source dataset + if (cloud_src.points.size () != cloud_tgt.points.size ()) + { + PCL_ERROR ("[pcl::registration::TransformationEstimationLM::estimateRigidTransformation] "); + PCL_ERROR ("Number or points in source (%lu) differs than target (%lu)!\n", + cloud_src.points.size (), cloud_tgt.points.size ()); + return; + } + if (cloud_src.points.size () < 4) // need at least 4 samples + { + PCL_ERROR ("[pcl::registration::TransformationEstimationLM::estimateRigidTransformation] "); + PCL_ERROR ("Need at least 4 points to estimate a transform! Source and target have %lu points!\n", + cloud_src.points.size ()); + return; + } + + int n_unknowns = warp_point_->getDimension (); + VectorX x (n_unknowns); + x.setZero (); + + // Set temporary pointers + tmp_src_ = &cloud_src; + tmp_tgt_ = &cloud_tgt; + + OptimizationFunctor functor (static_cast (cloud_src.points.size ()), this); + Eigen::NumericalDiff num_diff (functor); + //Eigen::LevenbergMarquardt, double> lm (num_diff); + Eigen::LevenbergMarquardt, MatScalar> lm (num_diff); + int info = lm.minimize (x); + + // Compute the norm of the residuals + PCL_DEBUG ("[pcl::registration::TransformationEstimationLM::estimateRigidTransformation]"); + PCL_DEBUG ("LM solver finished with exit code %i, having a residual norm of %g. \n", info, lm.fvec.norm ()); + PCL_DEBUG ("Final solution: [%f", x[0]); + for (int i = 1; i < n_unknowns; ++i) + PCL_DEBUG (" %f", x[i]); + PCL_DEBUG ("]\n"); + + // Return the correct transformation + warp_point_->setParam (x); + transformation_matrix = warp_point_->getTransform (); + + tmp_src_ = NULL; + tmp_tgt_ = NULL; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimationLM::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const +{ + if (indices_src.size () != cloud_tgt.points.size ()) + { + PCL_ERROR ("[pcl::registration::TransformationEstimationLM::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", indices_src.size (), cloud_tgt.points.size ()); + return; + } + + // is the source dataset + transformation_matrix.setIdentity (); + + const int nr_correspondences = static_cast (cloud_tgt.points.size ()); + std::vector indices_tgt; + indices_tgt.resize(nr_correspondences); + for (int i = 0; i < nr_correspondences; ++i) + indices_tgt[i] = i; + + estimateRigidTransformation(cloud_src, indices_src, cloud_tgt, indices_tgt, transformation_matrix); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationLM::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const +{ + if (indices_src.size () != indices_tgt.size ()) + { + PCL_ERROR ("[pcl::registration::TransformationEstimationLM::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", indices_src.size (), indices_tgt.size ()); + return; + } + + if (indices_src.size () < 4) // need at least 4 samples + { + PCL_ERROR ("[pcl::IterativeClosestPointNonLinear::estimateRigidTransformationLM] "); + PCL_ERROR ("Need at least 4 points to estimate a transform! Source and target have %lu points!", + indices_src.size ()); + return; + } + + int n_unknowns = warp_point_->getDimension (); // get dimension of unknown space + VectorX x (n_unknowns); + x.setConstant (n_unknowns, 0); + + // Set temporary pointers + tmp_src_ = &cloud_src; + tmp_tgt_ = &cloud_tgt; + tmp_idx_src_ = &indices_src; + tmp_idx_tgt_ = &indices_tgt; + + OptimizationFunctorWithIndices functor (static_cast (indices_src.size ()), this); + Eigen::NumericalDiff num_diff (functor); + //Eigen::LevenbergMarquardt > lm (num_diff); + Eigen::LevenbergMarquardt, MatScalar> lm (num_diff); + int info = lm.minimize (x); + + // Compute the norm of the residuals + PCL_DEBUG ("[pcl::registration::TransformationEstimationLM::estimateRigidTransformation] LM solver finished with exit code %i, having a residual norm of %g. \n", info, lm.fvec.norm ()); + PCL_DEBUG ("Final solution: [%f", x[0]); + for (int i = 1; i < n_unknowns; ++i) + PCL_DEBUG (" %f", x[i]); + PCL_DEBUG ("]\n"); + + // Return the correct transformation + warp_point_->setParam (x); + transformation_matrix = warp_point_->getTransform (); + + tmp_src_ = NULL; + tmp_tgt_ = NULL; + tmp_idx_src_ = tmp_idx_tgt_ = NULL; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationLM::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const +{ + const int nr_correspondences = static_cast (correspondences.size ()); + std::vector indices_src (nr_correspondences); + std::vector indices_tgt (nr_correspondences); + for (int i = 0; i < nr_correspondences; ++i) + { + indices_src[i] = correspondences[i].index_query; + indices_tgt[i] = correspondences[i].index_match; + } + + estimateRigidTransformation (cloud_src, indices_src, cloud_tgt, indices_tgt, transformation_matrix); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::registration::TransformationEstimationLM::OptimizationFunctor::operator () ( + const VectorX &x, VectorX &fvec) const +{ + const PointCloud & src_points = *estimator_->tmp_src_; + const PointCloud & tgt_points = *estimator_->tmp_tgt_; + + // Initialize the warp function with the given parameters + estimator_->warp_point_->setParam (x); + + // Transform each source point and compute its distance to the corresponding target point + for (int i = 0; i < values (); ++i) + { + const PointSource & p_src = src_points.points[i]; + const PointTarget & p_tgt = tgt_points.points[i]; + + // Transform the source point based on the current warp parameters + Vector4 p_src_warped; + estimator_->warp_point_->warpPoint (p_src, p_src_warped); + + // Estimate the distance (cost function) + fvec[i] = estimator_->computeDistance (p_src_warped, p_tgt); + } + return (0); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::registration::TransformationEstimationLM::OptimizationFunctorWithIndices::operator() ( + const VectorX &x, VectorX &fvec) const +{ + const PointCloud & src_points = *estimator_->tmp_src_; + const PointCloud & tgt_points = *estimator_->tmp_tgt_; + const std::vector & src_indices = *estimator_->tmp_idx_src_; + const std::vector & tgt_indices = *estimator_->tmp_idx_tgt_; + + // Initialize the warp function with the given parameters + estimator_->warp_point_->setParam (x); + + // Transform each source point and compute its distance to the corresponding target point + for (int i = 0; i < values (); ++i) + { + const PointSource & p_src = src_points.points[src_indices[i]]; + const PointTarget & p_tgt = tgt_points.points[tgt_indices[i]]; + + // Transform the source point based on the current warp parameters + Vector4 p_src_warped; + estimator_->warp_point_->warpPoint (p_src, p_src_warped); + + // Estimate the distance (cost function) + fvec[i] = estimator_->computeDistance (p_src_warped, p_tgt); + } + return (0); +} + +//#define PCL_INSTANTIATE_TransformationEstimationLM(T,U) template class PCL_EXPORTS pcl::registration::TransformationEstimationLM; + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_LM_HPP_ */ diff --git a/pcl-1.7/pcl/registration/impl/transformation_estimation_point_to_plane_lls.hpp b/pcl-1.7/pcl/registration/impl/transformation_estimation_point_to_plane_lls.hpp new file mode 100644 index 0000000..6f318b4 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/transformation_estimation_point_to_plane_lls.hpp @@ -0,0 +1,250 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_HPP_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_HPP_ +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationPointToPlaneLLS:: +estimateRigidTransformation (const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const +{ + size_t nr_points = cloud_src.points.size (); + if (cloud_tgt.points.size () != nr_points) + { + PCL_ERROR ("[pcl::TransformationEstimationPointToPlaneLLS::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", nr_points, cloud_tgt.points.size ()); + return; + } + + ConstCloudIterator source_it (cloud_src); + ConstCloudIterator target_it (cloud_tgt); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimationPointToPlaneLLS:: +estimateRigidTransformation (const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const +{ + size_t nr_points = indices_src.size (); + if (cloud_tgt.points.size () != nr_points) + { + PCL_ERROR ("[pcl::TransformationEstimationPointToPlaneLLS::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", indices_src.size (), cloud_tgt.points.size ()); + return; + } + + ConstCloudIterator source_it (cloud_src, indices_src); + ConstCloudIterator target_it (cloud_tgt); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationPointToPlaneLLS:: +estimateRigidTransformation (const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const +{ + size_t nr_points = indices_src.size (); + if (indices_tgt.size () != nr_points) + { + PCL_ERROR ("[pcl::TransformationEstimationPointToPlaneLLS::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", indices_src.size (), indices_tgt.size ()); + return; + } + + ConstCloudIterator source_it (cloud_src, indices_src); + ConstCloudIterator target_it (cloud_tgt, indices_tgt); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationPointToPlaneLLS:: +estimateRigidTransformation (const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const +{ + ConstCloudIterator source_it (cloud_src, correspondences, true); + ConstCloudIterator target_it (cloud_tgt, correspondences, false); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationPointToPlaneLLS:: +constructTransformationMatrix (const double & alpha, const double & beta, const double & gamma, + const double & tx, const double & ty, const double & tz, + Matrix4 &transformation_matrix) const +{ + // Construct the transformation matrix from rotation and translation + transformation_matrix = Eigen::Matrix::Zero (); + transformation_matrix (0, 0) = static_cast ( cos (gamma) * cos (beta)); + transformation_matrix (0, 1) = static_cast (-sin (gamma) * cos (alpha) + cos (gamma) * sin (beta) * sin (alpha)); + transformation_matrix (0, 2) = static_cast ( sin (gamma) * sin (alpha) + cos (gamma) * sin (beta) * cos (alpha)); + transformation_matrix (1, 0) = static_cast ( sin (gamma) * cos (beta)); + transformation_matrix (1, 1) = static_cast ( cos (gamma) * cos (alpha) + sin (gamma) * sin (beta) * sin (alpha)); + transformation_matrix (1, 2) = static_cast (-cos (gamma) * sin (alpha) + sin (gamma) * sin (beta) * cos (alpha)); + transformation_matrix (2, 0) = static_cast (-sin (beta)); + transformation_matrix (2, 1) = static_cast ( cos (beta) * sin (alpha)); + transformation_matrix (2, 2) = static_cast ( cos (beta) * cos (alpha)); + + transformation_matrix (0, 3) = static_cast (tx); + transformation_matrix (1, 3) = static_cast (ty); + transformation_matrix (2, 3) = static_cast (tz); + transformation_matrix (3, 3) = static_cast (1); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationPointToPlaneLLS:: +estimateRigidTransformation (ConstCloudIterator& source_it, ConstCloudIterator& target_it, Matrix4 &transformation_matrix) const +{ + typedef Eigen::Matrix Vector6d; + typedef Eigen::Matrix Matrix6d; + + Matrix6d ATA; + Vector6d ATb; + ATA.setZero (); + ATb.setZero (); + + // Approximate as a linear least squares problem + while (source_it.isValid () && target_it.isValid ()) + { + if (!pcl_isfinite (source_it->x) || + !pcl_isfinite (source_it->y) || + !pcl_isfinite (source_it->z) || + !pcl_isfinite (target_it->x) || + !pcl_isfinite (target_it->y) || + !pcl_isfinite (target_it->z) || + !pcl_isfinite (target_it->normal_x) || + !pcl_isfinite (target_it->normal_y) || + !pcl_isfinite (target_it->normal_z)) + { + ++target_it; + ++source_it; + continue; + } + + const float & sx = source_it->x; + const float & sy = source_it->y; + const float & sz = source_it->z; + const float & dx = target_it->x; + const float & dy = target_it->y; + const float & dz = target_it->z; + const float & nx = target_it->normal[0]; + const float & ny = target_it->normal[1]; + const float & nz = target_it->normal[2]; + + double a = nz*sy - ny*sz; + double b = nx*sz - nz*sx; + double c = ny*sx - nx*sy; + + // 0 1 2 3 4 5 + // 6 7 8 9 10 11 + // 12 13 14 15 16 17 + // 18 19 20 21 22 23 + // 24 25 26 27 28 29 + // 30 31 32 33 34 35 + + ATA.coeffRef (0) += a * a; + ATA.coeffRef (1) += a * b; + ATA.coeffRef (2) += a * c; + ATA.coeffRef (3) += a * nx; + ATA.coeffRef (4) += a * ny; + ATA.coeffRef (5) += a * nz; + ATA.coeffRef (7) += b * b; + ATA.coeffRef (8) += b * c; + ATA.coeffRef (9) += b * nx; + ATA.coeffRef (10) += b * ny; + ATA.coeffRef (11) += b * nz; + ATA.coeffRef (14) += c * c; + ATA.coeffRef (15) += c * nx; + ATA.coeffRef (16) += c * ny; + ATA.coeffRef (17) += c * nz; + ATA.coeffRef (21) += nx * nx; + ATA.coeffRef (22) += nx * ny; + ATA.coeffRef (23) += nx * nz; + ATA.coeffRef (28) += ny * ny; + ATA.coeffRef (29) += ny * nz; + ATA.coeffRef (35) += nz * nz; + + double d = nx*dx + ny*dy + nz*dz - nx*sx - ny*sy - nz*sz; + ATb.coeffRef (0) += a * d; + ATb.coeffRef (1) += b * d; + ATb.coeffRef (2) += c * d; + ATb.coeffRef (3) += nx * d; + ATb.coeffRef (4) += ny * d; + ATb.coeffRef (5) += nz * d; + + ++target_it; + ++source_it; + } + ATA.coeffRef (6) = ATA.coeff (1); + ATA.coeffRef (12) = ATA.coeff (2); + ATA.coeffRef (13) = ATA.coeff (8); + ATA.coeffRef (18) = ATA.coeff (3); + ATA.coeffRef (19) = ATA.coeff (9); + ATA.coeffRef (20) = ATA.coeff (15); + ATA.coeffRef (24) = ATA.coeff (4); + ATA.coeffRef (25) = ATA.coeff (10); + ATA.coeffRef (26) = ATA.coeff (16); + ATA.coeffRef (27) = ATA.coeff (22); + ATA.coeffRef (30) = ATA.coeff (5); + ATA.coeffRef (31) = ATA.coeff (11); + ATA.coeffRef (32) = ATA.coeff (17); + ATA.coeffRef (33) = ATA.coeff (23); + ATA.coeffRef (34) = ATA.coeff (29); + + // Solve A*x = b + Vector6d x = static_cast (ATA.inverse () * ATb); + + // Construct the transformation matrix from x + constructTransformationMatrix (x (0), x (1), x (2), x (3), x (4), x (5), transformation_matrix); +} +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_HPP_ */ diff --git a/pcl-1.7/pcl/registration/impl/transformation_estimation_point_to_plane_lls_weighted.hpp b/pcl-1.7/pcl/registration/impl/transformation_estimation_point_to_plane_lls_weighted.hpp new file mode 100644 index 0000000..7f2ce74 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/transformation_estimation_point_to_plane_lls_weighted.hpp @@ -0,0 +1,280 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_WEIGHTED_HPP_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_WEIGHTED_HPP_ +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationPointToPlaneLLSWeighted:: +estimateRigidTransformation (const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const +{ + size_t nr_points = cloud_src.points.size (); + if (cloud_tgt.points.size () != nr_points) + { + PCL_ERROR ("[pcl::TransformationEstimationPointToPlaneLLSWeighted::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", nr_points, cloud_tgt.points.size ()); + return; + } + + if (weights_.size () != nr_points) + { + PCL_ERROR ("[pcl::TransformationEstimationPointToPlaneLLSWeighted::estimateRigidTransformation] Number or weights from the number of correspondences! Use setWeights () to set them.\n"); + return; + } + + ConstCloudIterator source_it (cloud_src); + ConstCloudIterator target_it (cloud_tgt); + typename std::vector::const_iterator weights_it = weights_.begin (); + estimateRigidTransformation (source_it, target_it, weights_it, transformation_matrix); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimationPointToPlaneLLSWeighted:: +estimateRigidTransformation (const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const +{ + size_t nr_points = indices_src.size (); + if (cloud_tgt.points.size () != nr_points) + { + PCL_ERROR ("[pcl::TransformationEstimationPointToPlaneLLSWeighted::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", indices_src.size (), cloud_tgt.points.size ()); + return; + } + + if (weights_.size () != nr_points) + { + PCL_ERROR ("[pcl::TransformationEstimationPointToPlaneLLSWeighted::estimateRigidTransformation] Number or weights from the number of correspondences! Use setWeights () to set them.\n"); + return; + } + + + ConstCloudIterator source_it (cloud_src, indices_src); + ConstCloudIterator target_it (cloud_tgt); + typename std::vector::const_iterator weights_it = weights_.begin (); + estimateRigidTransformation (source_it, target_it, weights_it, transformation_matrix); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationPointToPlaneLLSWeighted:: +estimateRigidTransformation (const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const +{ + size_t nr_points = indices_src.size (); + if (indices_tgt.size () != nr_points) + { + PCL_ERROR ("[pcl::TransformationEstimationPointToPlaneLLSWeighted::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", indices_src.size (), indices_tgt.size ()); + return; + } + + if (weights_.size () != nr_points) + { + PCL_ERROR ("[pcl::TransformationEstimationPointToPlaneLLSWeighted::estimateRigidTransformation] Number or weights from the number of correspondences! Use setWeights () to set them.\n"); + return; + } + + ConstCloudIterator source_it (cloud_src, indices_src); + ConstCloudIterator target_it (cloud_tgt, indices_tgt); + typename std::vector::const_iterator weights_it = weights_.begin (); + estimateRigidTransformation (source_it, target_it, weights_it, transformation_matrix); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationPointToPlaneLLSWeighted:: +estimateRigidTransformation (const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const +{ + ConstCloudIterator source_it (cloud_src, correspondences, true); + ConstCloudIterator target_it (cloud_tgt, correspondences, false); + std::vector weights (correspondences.size ()); + for (size_t i = 0; i < correspondences.size (); ++i) + weights[i] = correspondences[i].weight; + typename std::vector::const_iterator weights_it = weights.begin (); + estimateRigidTransformation (source_it, target_it, weights_it, transformation_matrix); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationPointToPlaneLLSWeighted:: +constructTransformationMatrix (const double & alpha, const double & beta, const double & gamma, + const double & tx, const double & ty, const double & tz, + Matrix4 &transformation_matrix) const +{ + // Construct the transformation matrix from rotation and translation + transformation_matrix = Eigen::Matrix::Zero (); + transformation_matrix (0, 0) = static_cast ( cos (gamma) * cos (beta)); + transformation_matrix (0, 1) = static_cast (-sin (gamma) * cos (alpha) + cos (gamma) * sin (beta) * sin (alpha)); + transformation_matrix (0, 2) = static_cast ( sin (gamma) * sin (alpha) + cos (gamma) * sin (beta) * cos (alpha)); + transformation_matrix (1, 0) = static_cast ( sin (gamma) * cos (beta)); + transformation_matrix (1, 1) = static_cast ( cos (gamma) * cos (alpha) + sin (gamma) * sin (beta) * sin (alpha)); + transformation_matrix (1, 2) = static_cast (-cos (gamma) * sin (alpha) + sin (gamma) * sin (beta) * cos (alpha)); + transformation_matrix (2, 0) = static_cast (-sin (beta)); + transformation_matrix (2, 1) = static_cast ( cos (beta) * sin (alpha)); + transformation_matrix (2, 2) = static_cast ( cos (beta) * cos (alpha)); + + transformation_matrix (0, 3) = static_cast (tx); + transformation_matrix (1, 3) = static_cast (ty); + transformation_matrix (2, 3) = static_cast (tz); + transformation_matrix (3, 3) = static_cast (1); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationPointToPlaneLLSWeighted:: +estimateRigidTransformation (ConstCloudIterator& source_it, + ConstCloudIterator& target_it, + typename std::vector::const_iterator& weights_it, + Matrix4 &transformation_matrix) const +{ + typedef Eigen::Matrix Vector6d; + typedef Eigen::Matrix Matrix6d; + + Matrix6d ATA; + Vector6d ATb; + ATA.setZero (); + ATb.setZero (); + + while (source_it.isValid () && target_it.isValid ()) + { + if (!pcl_isfinite (source_it->x) || + !pcl_isfinite (source_it->y) || + !pcl_isfinite (source_it->z) || + !pcl_isfinite (target_it->x) || + !pcl_isfinite (target_it->y) || + !pcl_isfinite (target_it->z) || + !pcl_isfinite (target_it->normal_x) || + !pcl_isfinite (target_it->normal_y) || + !pcl_isfinite (target_it->normal_z)) + { + ++ source_it; + ++ target_it; + ++ weights_it; + continue; + } + + const float & sx = source_it->x; + const float & sy = source_it->y; + const float & sz = source_it->z; + const float & dx = target_it->x; + const float & dy = target_it->y; + const float & dz = target_it->z; + const float & nx = target_it->normal[0] * (*weights_it); + const float & ny = target_it->normal[1] * (*weights_it); + const float & nz = target_it->normal[2] * (*weights_it); + + double a = nz*sy - ny*sz; + double b = nx*sz - nz*sx; + double c = ny*sx - nx*sy; + + // 0 1 2 3 4 5 + // 6 7 8 9 10 11 + // 12 13 14 15 16 17 + // 18 19 20 21 22 23 + // 24 25 26 27 28 29 + // 30 31 32 33 34 35 + + ATA.coeffRef (0) += a * a; + ATA.coeffRef (1) += a * b; + ATA.coeffRef (2) += a * c; + ATA.coeffRef (3) += a * nx; + ATA.coeffRef (4) += a * ny; + ATA.coeffRef (5) += a * nz; + ATA.coeffRef (7) += b * b; + ATA.coeffRef (8) += b * c; + ATA.coeffRef (9) += b * nx; + ATA.coeffRef (10) += b * ny; + ATA.coeffRef (11) += b * nz; + ATA.coeffRef (14) += c * c; + ATA.coeffRef (15) += c * nx; + ATA.coeffRef (16) += c * ny; + ATA.coeffRef (17) += c * nz; + ATA.coeffRef (21) += nx * nx; + ATA.coeffRef (22) += nx * ny; + ATA.coeffRef (23) += nx * nz; + ATA.coeffRef (28) += ny * ny; + ATA.coeffRef (29) += ny * nz; + ATA.coeffRef (35) += nz * nz; + + double d = nx*dx + ny*dy + nz*dz - nx*sx - ny*sy - nz*sz; + ATb.coeffRef (0) += a * d; + ATb.coeffRef (1) += b * d; + ATb.coeffRef (2) += c * d; + ATb.coeffRef (3) += nx * d; + ATb.coeffRef (4) += ny * d; + ATb.coeffRef (5) += nz * d; + + ++ source_it; + ++ target_it; + ++ weights_it; + } + + ATA.coeffRef (6) = ATA.coeff (1); + ATA.coeffRef (12) = ATA.coeff (2); + ATA.coeffRef (13) = ATA.coeff (8); + ATA.coeffRef (18) = ATA.coeff (3); + ATA.coeffRef (19) = ATA.coeff (9); + ATA.coeffRef (20) = ATA.coeff (15); + ATA.coeffRef (24) = ATA.coeff (4); + ATA.coeffRef (25) = ATA.coeff (10); + ATA.coeffRef (26) = ATA.coeff (16); + ATA.coeffRef (27) = ATA.coeff (22); + ATA.coeffRef (30) = ATA.coeff (5); + ATA.coeffRef (31) = ATA.coeff (11); + ATA.coeffRef (32) = ATA.coeff (17); + ATA.coeffRef (33) = ATA.coeff (23); + ATA.coeffRef (34) = ATA.coeff (29); + + // Solve A*x = b + Vector6d x = static_cast (ATA.inverse () * ATb); + + // Construct the transformation matrix from x + constructTransformationMatrix (x (0), x (1), x (2), x (3), x (4), x (5), transformation_matrix); +} +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_WEIGHTED_HPP_ */ diff --git a/pcl-1.7/pcl/registration/impl/transformation_estimation_point_to_plane_weighted.hpp b/pcl-1.7/pcl/registration/impl/transformation_estimation_point_to_plane_weighted.hpp new file mode 100644 index 0000000..d699437 --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/transformation_estimation_point_to_plane_weighted.hpp @@ -0,0 +1,303 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) Alexandru-Eugen Ichim + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_WEIGHTED_HPP_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_WEIGHTED_HPP_ + +#include +#include +#include +#include + + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::registration::TransformationEstimationPointToPlaneWeighted::TransformationEstimationPointToPlaneWeighted () + : tmp_src_ () + , tmp_tgt_ () + , tmp_idx_src_ () + , tmp_idx_tgt_ () + , warp_point_ (new WarpPointRigid6D) + , correspondence_weights_ () + , use_correspondence_weights_ (true) +{ +}; + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimationPointToPlaneWeighted::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const +{ + + // is the source dataset + if (cloud_src.points.size () != cloud_tgt.points.size ()) + { + PCL_ERROR ("[pcl::registration::TransformationEstimationPointToPlaneWeighted::estimateRigidTransformation] "); + PCL_ERROR ("Number or points in source (%lu) differs than target (%lu)!\n", + cloud_src.points.size (), cloud_tgt.points.size ()); + return; + } + if (cloud_src.points.size () < 4) // need at least 4 samples + { + PCL_ERROR ("[pcl::registration::TransformationEstimationPointToPlaneWeighted::estimateRigidTransformation] "); + PCL_ERROR ("Need at least 4 points to estimate a transform! Source and target have %lu points!\n", + cloud_src.points.size ()); + return; + } + + if (correspondence_weights_.size () != cloud_src.size ()) + { + PCL_ERROR ("[pcl::registration::TransformationEstimationPointToPlaneWeighted::estimateRigidTransformation] "); + PCL_ERROR ("Number of weights (%lu) differs than number of points (%lu)!\n", + correspondence_weights_.size (), cloud_src.points.size ()); + return; + } + + int n_unknowns = warp_point_->getDimension (); + VectorX x (n_unknowns); + x.setZero (); + + // Set temporary pointers + tmp_src_ = &cloud_src; + tmp_tgt_ = &cloud_tgt; + + OptimizationFunctor functor (static_cast (cloud_src.points.size ()), this); + Eigen::NumericalDiff num_diff (functor); + Eigen::LevenbergMarquardt, MatScalar> lm (num_diff); + int info = lm.minimize (x); + + // Compute the norm of the residuals + PCL_DEBUG ("[pcl::registration::TransformationEstimationPointToPlaneWeighted::estimateRigidTransformation]"); + PCL_DEBUG ("LM solver finished with exit code %i, having a residual norm of %g. \n", info, lm.fvec.norm ()); + PCL_DEBUG ("Final solution: [%f", x[0]); + for (int i = 1; i < n_unknowns; ++i) + PCL_DEBUG (" %f", x[i]); + PCL_DEBUG ("]\n"); + + // Return the correct transformation + warp_point_->setParam (x); + transformation_matrix = warp_point_->getTransform (); + + tmp_src_ = NULL; + tmp_tgt_ = NULL; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimationPointToPlaneWeighted::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const +{ + if (indices_src.size () != cloud_tgt.points.size ()) + { + PCL_ERROR ("[pcl::registration::TransformationEstimationPointToPlaneWeighted::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", indices_src.size (), cloud_tgt.points.size ()); + return; + } + + if (correspondence_weights_.size () != indices_src.size ()) + { + PCL_ERROR ("[pcl::registration::TransformationEstimationPointToPlaneWeighted::estimateRigidTransformation] "); + PCL_ERROR ("Number of weights (%lu) differs than number of points (%lu)!\n", + correspondence_weights_.size (), indices_src.size ()); + return; + } + + + // is the source dataset + transformation_matrix.setIdentity (); + + const int nr_correspondences = static_cast (cloud_tgt.points.size ()); + std::vector indices_tgt; + indices_tgt.resize(nr_correspondences); + for (int i = 0; i < nr_correspondences; ++i) + indices_tgt[i] = i; + + estimateRigidTransformation(cloud_src, indices_src, cloud_tgt, indices_tgt, transformation_matrix); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationPointToPlaneWeighted::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const +{ + if (indices_src.size () != indices_tgt.size ()) + { + PCL_ERROR ("[pcl::registration::TransformationEstimationPointToPlaneWeighted::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", indices_src.size (), indices_tgt.size ()); + return; + } + + if (indices_src.size () < 4) // need at least 4 samples + { + PCL_ERROR ("[pcl::IterativeClosestPointNonLinear::estimateRigidTransformationLM] "); + PCL_ERROR ("Need at least 4 points to estimate a transform! Source and target have %lu points!", + indices_src.size ()); + return; + } + + if (correspondence_weights_.size () != indices_src.size ()) + { + PCL_ERROR ("[pcl::registration::TransformationEstimationPointToPlaneWeighted::estimateRigidTransformation] "); + PCL_ERROR ("Number of weights (%lu) differs than number of points (%lu)!\n", + correspondence_weights_.size (), indices_src.size ()); + return; + } + + + int n_unknowns = warp_point_->getDimension (); // get dimension of unknown space + VectorX x (n_unknowns); + x.setConstant (n_unknowns, 0); + + // Set temporary pointers + tmp_src_ = &cloud_src; + tmp_tgt_ = &cloud_tgt; + tmp_idx_src_ = &indices_src; + tmp_idx_tgt_ = &indices_tgt; + + OptimizationFunctorWithIndices functor (static_cast (indices_src.size ()), this); + Eigen::NumericalDiff num_diff (functor); + Eigen::LevenbergMarquardt, MatScalar> lm (num_diff); + int info = lm.minimize (x); + + // Compute the norm of the residuals + PCL_DEBUG ("[pcl::registration::TransformationEstimationPointToPlaneWeighted::estimateRigidTransformation] LM solver finished with exit code %i, having a residual norm of %g. \n", info, lm.fvec.norm ()); + PCL_DEBUG ("Final solution: [%f", x[0]); + for (int i = 1; i < n_unknowns; ++i) + PCL_DEBUG (" %f", x[i]); + PCL_DEBUG ("]\n"); + + // Return the correct transformation + warp_point_->setParam (x); + transformation_matrix = warp_point_->getTransform (); + + tmp_src_ = NULL; + tmp_tgt_ = NULL; + tmp_idx_src_ = tmp_idx_tgt_ = NULL; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationPointToPlaneWeighted::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const +{ + const int nr_correspondences = static_cast (correspondences.size ()); + std::vector indices_src (nr_correspondences); + std::vector indices_tgt (nr_correspondences); + for (int i = 0; i < nr_correspondences; ++i) + { + indices_src[i] = correspondences[i].index_query; + indices_tgt[i] = correspondences[i].index_match; + } + + if (use_correspondence_weights_) + { + correspondence_weights_.resize (nr_correspondences); + for (size_t i = 0; i < nr_correspondences; ++i) + correspondence_weights_[i] = correspondences[i].weight; + } + + estimateRigidTransformation (cloud_src, indices_src, cloud_tgt, indices_tgt, transformation_matrix); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::registration::TransformationEstimationPointToPlaneWeighted::OptimizationFunctor::operator () ( + const VectorX &x, VectorX &fvec) const +{ + const PointCloud & src_points = *estimator_->tmp_src_; + const PointCloud & tgt_points = *estimator_->tmp_tgt_; + + // Initialize the warp function with the given parameters + estimator_->warp_point_->setParam (x); + + // Transform each source point and compute its distance to the corresponding target point + for (int i = 0; i < values (); ++i) + { + const PointSource & p_src = src_points.points[i]; + const PointTarget & p_tgt = tgt_points.points[i]; + + // Transform the source point based on the current warp parameters + Vector4 p_src_warped; + estimator_->warp_point_->warpPoint (p_src, p_src_warped); + + // Estimate the distance (cost function) + fvec[i] = estimator_->correspondence_weights_[i] * estimator_->computeDistance (p_src_warped, p_tgt); + } + return (0); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::registration::TransformationEstimationPointToPlaneWeighted::OptimizationFunctorWithIndices::operator() ( + const VectorX &x, VectorX &fvec) const +{ + const PointCloud & src_points = *estimator_->tmp_src_; + const PointCloud & tgt_points = *estimator_->tmp_tgt_; + const std::vector & src_indices = *estimator_->tmp_idx_src_; + const std::vector & tgt_indices = *estimator_->tmp_idx_tgt_; + + // Initialize the warp function with the given parameters + estimator_->warp_point_->setParam (x); + + // Transform each source point and compute its distance to the corresponding target point + for (int i = 0; i < values (); ++i) + { + const PointSource & p_src = src_points.points[src_indices[i]]; + const PointTarget & p_tgt = tgt_points.points[tgt_indices[i]]; + + // Transform the source point based on the current warp parameters + Vector4 p_src_warped; + estimator_->warp_point_->warpPoint (p_src, p_src_warped); + + // Estimate the distance (cost function) + fvec[i] = estimator_->correspondence_weights_[i] * estimator_->computeDistance (p_src_warped, p_tgt); + } + return (0); +} + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_WEIGHTED_HPP_ */ diff --git a/pcl-1.7/pcl/registration/impl/transformation_estimation_svd.hpp b/pcl-1.7/pcl/registration/impl/transformation_estimation_svd.hpp new file mode 100644 index 0000000..628de9e --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/transformation_estimation_svd.hpp @@ -0,0 +1,206 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_HPP_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_HPP_ + +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationSVD::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const +{ + size_t nr_points = cloud_src.points.size (); + if (cloud_tgt.points.size () != nr_points) + { + PCL_ERROR ("[pcl::TransformationEstimationSVD::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", nr_points, cloud_tgt.points.size ()); + return; + } + + ConstCloudIterator source_it (cloud_src); + ConstCloudIterator target_it (cloud_tgt); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimationSVD::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const +{ + if (indices_src.size () != cloud_tgt.points.size ()) + { + PCL_ERROR ("[pcl::TransformationSVD::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", indices_src.size (), cloud_tgt.points.size ()); + return; + } + + ConstCloudIterator source_it (cloud_src, indices_src); + ConstCloudIterator target_it (cloud_tgt); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationSVD::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const +{ + if (indices_src.size () != indices_tgt.size ()) + { + PCL_ERROR ("[pcl::TransformationEstimationSVD::estimateRigidTransformation] Number or points in source (%lu) differs than target (%lu)!\n", indices_src.size (), indices_tgt.size ()); + return; + } + + ConstCloudIterator source_it (cloud_src, indices_src); + ConstCloudIterator target_it (cloud_tgt, indices_tgt); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimationSVD::estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const +{ + ConstCloudIterator source_it (cloud_src, correspondences, true); + ConstCloudIterator target_it (cloud_tgt, correspondences, false); + estimateRigidTransformation (source_it, target_it, transformation_matrix); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::registration::TransformationEstimationSVD::estimateRigidTransformation ( + ConstCloudIterator& source_it, + ConstCloudIterator& target_it, + Matrix4 &transformation_matrix) const +{ + // Convert to Eigen format + const int npts = static_cast (source_it.size ()); + + + + if (use_umeyama_) + { // by default: use_umeyama_ == True + Eigen::Matrix cloud_src (3, npts); + Eigen::Matrix cloud_tgt (3, npts); + + for (int i = 0; i < npts; ++i) + { + cloud_src (0, i) = source_it->x; + cloud_src (1, i) = source_it->y; + cloud_src (2, i) = source_it->z; + ++source_it; + + cloud_tgt (0, i) = target_it->x; + cloud_tgt (1, i) = target_it->y; + cloud_tgt (2, i) = target_it->z; + ++target_it; + } + + // Call Umeyama directly from Eigen (PCL patched version until Eigen is released) + transformation_matrix = pcl::umeyama (cloud_src, cloud_tgt, false); + } + else + { + source_it.reset (); target_it.reset (); + // is the source dataset + transformation_matrix.setIdentity (); + + Eigen::Matrix centroid_src, centroid_tgt; + // Estimate the centroids of source, target + compute3DCentroid (source_it, centroid_src); + compute3DCentroid (target_it, centroid_tgt); + source_it.reset (); target_it.reset (); + + // Subtract the centroids from source, target + Eigen::Matrix cloud_src_demean, cloud_tgt_demean; + demeanPointCloud (source_it, centroid_src, cloud_src_demean); + demeanPointCloud (target_it, centroid_tgt, cloud_tgt_demean); + + getTransformationFromCorrelation (cloud_src_demean, centroid_src, cloud_tgt_demean, centroid_tgt, transformation_matrix); + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimationSVD::getTransformationFromCorrelation ( + const Eigen::Matrix &cloud_src_demean, + const Eigen::Matrix ¢roid_src, + const Eigen::Matrix &cloud_tgt_demean, + const Eigen::Matrix ¢roid_tgt, + Matrix4 &transformation_matrix) const +{ + transformation_matrix.setIdentity (); + + // Assemble the correlation matrix H = source * target' + Eigen::Matrix H = (cloud_src_demean * cloud_tgt_demean.transpose ()).topLeftCorner (3, 3); + + // Compute the Singular Value Decomposition + Eigen::JacobiSVD > svd (H, Eigen::ComputeFullU | Eigen::ComputeFullV); + Eigen::Matrix u = svd.matrixU (); + Eigen::Matrix v = svd.matrixV (); + + // Compute R = V * U' + if (u.determinant () * v.determinant () < 0) + { + for (int x = 0; x < 3; ++x) + v (x, 2) *= -1; + } + + Eigen::Matrix R = v * u.transpose (); + + // Return the correct transformation + transformation_matrix.topLeftCorner (3, 3) = R; + const Eigen::Matrix Rc (R * centroid_src.head (3)); + transformation_matrix.block (0, 3, 3, 1) = centroid_tgt.head (3) - Rc; +} + +//#define PCL_INSTANTIATE_TransformationEstimationSVD(T,U) template class PCL_EXPORTS pcl::registration::TransformationEstimationSVD; + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_HPP_ */ diff --git a/pcl-1.7/pcl/registration/impl/transformation_estimation_svd_scale.hpp b/pcl-1.7/pcl/registration/impl/transformation_estimation_svd_scale.hpp new file mode 100644 index 0000000..553342e --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/transformation_estimation_svd_scale.hpp @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_SCALE_HPP_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_SCALE_HPP_ + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::registration::TransformationEstimationSVDScale::getTransformationFromCorrelation ( + const Eigen::Matrix &cloud_src_demean, + const Eigen::Matrix ¢roid_src, + const Eigen::Matrix &cloud_tgt_demean, + const Eigen::Matrix ¢roid_tgt, + Matrix4 &transformation_matrix) const +{ + transformation_matrix.setIdentity (); + + // Assemble the correlation matrix H = source * target' + Eigen::Matrix H = (cloud_src_demean * cloud_tgt_demean.transpose ()).topLeftCorner (3, 3); + + // Compute the Singular Value Decomposition + Eigen::JacobiSVD > svd (H, Eigen::ComputeFullU | Eigen::ComputeFullV); + Eigen::Matrix u = svd.matrixU (); + Eigen::Matrix v = svd.matrixV (); + + // Compute R = V * U' + if (u.determinant () * v.determinant () < 0) + { + for (int x = 0; x < 3; ++x) + v (x, 2) *= -1; + } + + Eigen::Matrix R = v * u.transpose (); + + // rotated cloud + Eigen::Matrix R4; + R4.block (0, 0, 3, 3) = R; + R4 (0, 3) = 0; + R4 (1, 3) = 0; + R4 (2, 3) = 0; + R4 (3, 3) = 1; + + Eigen::Matrix src_ = R4 * cloud_src_demean; + + float scale1, scale2; + double sum_ss = 0.0f, sum_tt = 0.0f, sum_tt_ = 0.0f; + for (unsigned corrIdx = 0; corrIdx < cloud_src_demean.cols (); ++corrIdx) + { + sum_ss += cloud_src_demean (0, corrIdx) * cloud_src_demean (0, corrIdx); + sum_ss += cloud_src_demean (1, corrIdx) * cloud_src_demean (1, corrIdx); + sum_ss += cloud_src_demean (2, corrIdx) * cloud_src_demean (2, corrIdx); + + sum_tt += cloud_tgt_demean (0, corrIdx) * cloud_tgt_demean (0, corrIdx); + sum_tt += cloud_tgt_demean (1, corrIdx) * cloud_tgt_demean (1, corrIdx); + sum_tt += cloud_tgt_demean (2, corrIdx) * cloud_tgt_demean (2, corrIdx); + + sum_tt_ += cloud_tgt_demean (0, corrIdx) * src_ (0, corrIdx); + sum_tt_ += cloud_tgt_demean (1, corrIdx) * src_ (1, corrIdx); + sum_tt_ += cloud_tgt_demean (2, corrIdx) * src_ (2, corrIdx); + } + + scale1 = sqrt (sum_tt / sum_ss); + scale2 = sum_tt_ / sum_ss; + float scale = scale2; + transformation_matrix.topLeftCorner (3, 3) = scale * R; + const Eigen::Matrix Rc (scale * R * centroid_src.head (3)); + transformation_matrix.block (0, 3, 3, 1) = centroid_tgt. head (3) - Rc; +} + +//#define PCL_INSTANTIATE_TransformationEstimationSVD(T,U) template class PCL_EXPORTS pcl::registration::TransformationEstimationSVD; + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_SCALE_HPP_ */ diff --git a/pcl-1.7/pcl/registration/impl/transformation_validation_euclidean.hpp b/pcl-1.7/pcl/registration/impl/transformation_validation_euclidean.hpp new file mode 100644 index 0000000..63e014c --- /dev/null +++ b/pcl-1.7/pcl/registration/impl/transformation_validation_euclidean.hpp @@ -0,0 +1,98 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_VALIDATION_EUCLIDEAN_IMPL_H_ +#define PCL_REGISTRATION_TRANSFORMATION_VALIDATION_EUCLIDEAN_IMPL_H_ + +///////////////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::registration::TransformationValidationEuclidean::validateTransformation ( + const PointCloudSourceConstPtr &cloud_src, + const PointCloudTargetConstPtr &cloud_tgt, + const Matrix4 &transformation_matrix) const +{ + double fitness_score = 0.0; + + // Transform the input dataset using the final transformation + pcl::PointCloud input_transformed; + //transformPointCloud (*cloud_src, input_transformed, transformation_matrix); + input_transformed.resize (cloud_src->size ()); + for (size_t i = 0; i < cloud_src->size (); ++i) + { + const PointSource &src = cloud_src->points[i]; + PointTarget &tgt = input_transformed.points[i]; + tgt.x = static_cast (transformation_matrix (0, 0) * src.x + transformation_matrix (0, 1) * src.y + transformation_matrix (0, 2) * src.z + transformation_matrix (0, 3)); + tgt.y = static_cast (transformation_matrix (1, 0) * src.x + transformation_matrix (1, 1) * src.y + transformation_matrix (1, 2) * src.z + transformation_matrix (1, 3)); + tgt.z = static_cast (transformation_matrix (2, 0) * src.x + transformation_matrix (2, 1) * src.y + transformation_matrix (2, 2) * src.z + transformation_matrix (2, 3)); + } + + typename MyPointRepresentation::ConstPtr point_rep (new MyPointRepresentation); + if (!force_no_recompute_) + { + tree_->setPointRepresentation (point_rep); + tree_->setInputCloud (cloud_tgt); + } + + std::vector nn_indices (1); + std::vector nn_dists (1); + + // For each point in the source dataset + int nr = 0; + for (size_t i = 0; i < input_transformed.points.size (); ++i) + { + // Find its nearest neighbor in the target + tree_->nearestKSearch (input_transformed.points[i], 1, nn_indices, nn_dists); + + // Deal with occlusions (incomplete targets) + if (nn_dists[0] > max_range_) + continue; + + // Calculate the fitness score + fitness_score += nn_dists[0]; + ++nr; + } + + if (nr > 0) + return (fitness_score / nr); + else + return (std::numeric_limits::max ()); +} + +#endif // PCL_REGISTRATION_TRANSFORMATION_VALIDATION_EUCLIDEAN_IMPL_H_ + diff --git a/pcl-1.7/pcl/registration/joint_icp.h b/pcl-1.7/pcl/registration/joint_icp.h new file mode 100644 index 0000000..d51d76b --- /dev/null +++ b/pcl-1.7/pcl/registration/joint_icp.h @@ -0,0 +1,233 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_JOINT_ICP_H_ +#define PCL_JOINT_ICP_H_ + +// PCL includes +#include +namespace pcl +{ + /** \brief @b JointIterativeClosestPoint extends ICP to multiple frames which + * share the same transform. This is particularly useful when solving for + * camera extrinsics using multiple observations. When given a single pair of + * clouds, this reduces to vanilla ICP. + * + * \author Stephen Miller + * \ingroup registration + */ + template + class JointIterativeClosestPoint : public IterativeClosestPoint + { + public: + typedef typename IterativeClosestPoint::PointCloudSource PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef typename IterativeClosestPoint::PointCloudTarget PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + typedef pcl::search::KdTree KdTree; + typedef typename pcl::search::KdTree::Ptr KdTreePtr; + + typedef pcl::search::KdTree KdTreeReciprocal; + typedef typename KdTree::Ptr KdTreeReciprocalPtr; + + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename pcl::registration::CorrespondenceEstimationBase CorrespondenceEstimation; + typedef typename CorrespondenceEstimation::Ptr CorrespondenceEstimationPtr; + typedef typename CorrespondenceEstimation::ConstPtr CorrespondenceEstimationConstPtr; + + + using IterativeClosestPoint::reg_name_; + using IterativeClosestPoint::getClassName; + using IterativeClosestPoint::setInputSource; + using IterativeClosestPoint::input_; + using IterativeClosestPoint::indices_; + using IterativeClosestPoint::target_; + using IterativeClosestPoint::nr_iterations_; + using IterativeClosestPoint::max_iterations_; + using IterativeClosestPoint::previous_transformation_; + using IterativeClosestPoint::final_transformation_; + using IterativeClosestPoint::transformation_; + using IterativeClosestPoint::transformation_epsilon_; + using IterativeClosestPoint::converged_; + using IterativeClosestPoint::corr_dist_threshold_; + using IterativeClosestPoint::inlier_threshold_; + using IterativeClosestPoint::min_number_correspondences_; + using IterativeClosestPoint::update_visualizer_; + using IterativeClosestPoint::euclidean_fitness_epsilon_; + using IterativeClosestPoint::correspondences_; + using IterativeClosestPoint::transformation_estimation_; + using IterativeClosestPoint::correspondence_estimation_; + using IterativeClosestPoint::correspondence_rejectors_; + + using IterativeClosestPoint::use_reciprocal_correspondence_; + + using IterativeClosestPoint::convergence_criteria_; + using IterativeClosestPoint::source_has_normals_; + using IterativeClosestPoint::target_has_normals_; + using IterativeClosestPoint::need_source_blob_; + using IterativeClosestPoint::need_target_blob_; + + + typedef typename IterativeClosestPoint::Matrix4 Matrix4; + + /** \brief Empty constructor. */ + JointIterativeClosestPoint () + { + IterativeClosestPoint (); + reg_name_ = "JointIterativeClosestPoint"; + }; + + /** \brief Empty destructor */ + virtual ~JointIterativeClosestPoint () {} + + + /** \brief Provide a pointer to the input source + * (e.g., the point cloud that we want to align to the target) + */ + virtual void + setInputSource (const PointCloudSourceConstPtr& /*cloud*/) + { + PCL_WARN ("[pcl::%s::setInputSource] Warning; JointIterativeClosestPoint expects multiple clouds. Please use addInputSource.", + getClassName ().c_str ()); + return; + } + + /** \brief Add a source cloud to the joint solver + * + * \param[in] cloud source cloud + */ + inline void + addInputSource (const PointCloudSourceConstPtr &cloud) + { + // Set the parent InputSource, just to get all cached values (e.g. the existence of normals). + if (sources_.empty ()) + IterativeClosestPoint::setInputSource (cloud); + sources_.push_back (cloud); + } + + /** \brief Provide a pointer to the input target + * (e.g., the point cloud that we want to align to the target) + */ + virtual void + setInputTarget (const PointCloudTargetConstPtr& /*cloud*/) + { + PCL_WARN ("[pcl::%s::setInputTarget] Warning; JointIterativeClosestPoint expects multiple clouds. Please use addInputTarget.", + getClassName ().c_str ()); + return; + } + + /** \brief Add a target cloud to the joint solver + * + * \param[in] cloud target cloud + */ + inline void + addInputTarget (const PointCloudTargetConstPtr &cloud) + { + // Set the parent InputTarget, just to get all cached values (e.g. the existence of normals). + if (targets_.empty ()) + IterativeClosestPoint::setInputTarget (cloud); + targets_.push_back (cloud); + } + + /** \brief Add a manual correspondence estimator + * If you choose to do this, you must add one for each + * input source / target pair. They do not need to have trees + * or input clouds set ahead of time. + * + * \param[in] ce Correspondence estimation + */ + inline void + addCorrespondenceEstimation (CorrespondenceEstimationPtr ce) + { + correspondence_estimations_.push_back (ce); + } + + /** \brief Reset my list of input sources + */ + inline void + clearInputSources () + { sources_.clear (); } + + /** \brief Reset my list of input targets + */ + inline void + clearInputTargets () + { targets_.clear (); } + + /** \brief Reset my list of correspondence estimation methods. + */ + inline void + clearCorrespondenceEstimations () + { correspondence_estimations_.clear (); } + + + protected: + + /** \brief Rigid transformation computation method with initial guess. + * \param output the transformed input point cloud dataset using the rigid transformation found + * \param guess the initial guess of the transformation to compute + */ + virtual void + computeTransformation (PointCloudSource &output, const Matrix4 &guess); + + /** \brief Looks at the Estimators and Rejectors and determines whether their blob-setter methods need to be called */ + void + determineRequiredBlobData (); + + std::vector sources_; + std::vector targets_; + std::vector correspondence_estimations_; + }; + +} + +#include + +#endif //#ifndef PCL_JOINT_ICP_H_ + + diff --git a/pcl-1.7/pcl/registration/lum.h b/pcl-1.7/pcl/registration/lum.h new file mode 100644 index 0000000..6b48807 --- /dev/null +++ b/pcl-1.7/pcl/registration/lum.h @@ -0,0 +1,347 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: lum.h 5663 2012-05-02 13:49:39Z florentinus $ + * + */ + +#ifndef PCL_REGISTRATION_LUM_H_ +#define PCL_REGISTRATION_LUM_H_ + +#include +#include +#include +#include +#include +#include + +namespace Eigen +{ + typedef Eigen::Matrix Vector6f; + typedef Eigen::Matrix Matrix6f; +} + +namespace pcl +{ + namespace registration + { + /** \brief Globally Consistent Scan Matching based on an algorithm by Lu and Milios. + * \details A GraphSLAM algorithm where registration data is managed in a graph: + *
    + *
  • Vertices represent poses and hold the point cloud data and relative transformations.
  • + *
  • Edges represent pose constraints and hold the correspondence data between two point clouds.
  • + *
+ * Computation uses the first point cloud in the SLAM graph as a reference pose and attempts to align all other point clouds to it simultaneously. + * For more information: + *
  • + * F. Lu, E. Milios, + * Globally Consistent Range Scan Alignment for Environment Mapping, + * Autonomous Robots 4, April 1997 + *
  • + * Dorit Borrmann, Jan Elseberg, Kai Lingemann, Andreas Nüchter, and Joachim Hertzberg, + * The Efficient Extension of Globally Consistent Scan Matching to 6 DoF, + * In Proceedings of the 4th International Symposium on 3D Data Processing, Visualization and Transmission (3DPVT '08), June 2008 + *
+ * Usage example: + * \code + * pcl::registration::LUM lum; + * // Add point clouds as vertices to the SLAM graph + * lum.addPointCloud (cloud_0); + * lum.addPointCloud (cloud_1); + * lum.addPointCloud (cloud_2); + * // Use your favorite pairwise correspondence estimation algorithm(s) + * corrs_0_to_1 = someAlgo (cloud_0, cloud_1); + * corrs_1_to_2 = someAlgo (cloud_1, cloud_2); + * corrs_2_to_0 = someAlgo (lum.getPointCloud (2), lum.getPointCloud (0)); + * // Add the correspondence results as edges to the SLAM graph + * lum.setCorrespondences (0, 1, corrs_0_to_1); + * lum.setCorrespondences (1, 2, corrs_1_to_2); + * lum.setCorrespondences (2, 0, corrs_2_to_0); + * // Change the computation parameters + * lum.setMaxIterations (5); + * lum.setConvergenceThreshold (0.0); + * // Perform the actual LUM computation + * lum.compute (); + * // Return the concatenated point cloud result + * cloud_out = lum.getConcatenatedCloud (); + * // Return the separate point cloud transformations + * for(int i = 0; i < lum.getNumVertices (); i++) + * { + * transforms_out[i] = lum.getTransformation (i); + * } + * \endcode + * \author Frits Florentinus, Jochen Sprickerhof + * \ingroup registration + */ + template + class LUM + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + struct VertexProperties + { + PointCloudPtr cloud_; + Eigen::Vector6f pose_; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + struct EdgeProperties + { + pcl::CorrespondencesPtr corrs_; + Eigen::Matrix6f cinv_; + Eigen::Vector6f cinvd_; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + typedef boost::adjacency_list SLAMGraph; + typedef boost::shared_ptr SLAMGraphPtr; + typedef typename SLAMGraph::vertex_descriptor Vertex; + typedef typename SLAMGraph::edge_descriptor Edge; + + /** \brief Empty constructor. + */ + LUM () + : slam_graph_ (new SLAMGraph) + , max_iterations_ (5) + , convergence_threshold_ (0.0) + { + } + + /** \brief Set the internal SLAM graph structure. + * \details All data used and produced by LUM is stored in this boost::adjacency_list. + * It is recommended to use the LUM class itself to build the graph. + * This method could otherwise be useful for managing several SLAM graphs in one instance of LUM. + * \param[in] slam_graph The new SLAM graph. + */ + inline void + setLoopGraph (const SLAMGraphPtr &slam_graph); + + /** \brief Get the internal SLAM graph structure. + * \details All data used and produced by LUM is stored in this boost::adjacency_list. + * It is recommended to use the LUM class itself to build the graph. + * This method could otherwise be useful for managing several SLAM graphs in one instance of LUM. + * \return The current SLAM graph. + */ + inline SLAMGraphPtr + getLoopGraph () const; + + /** \brief Get the number of vertices in the SLAM graph. + * \return The current number of vertices in the SLAM graph. + */ + typename SLAMGraph::vertices_size_type + getNumVertices () const; + + /** \brief Set the maximum number of iterations for the compute() method. + * \details The compute() method finishes when max_iterations are met or when the convergence criteria is met. + * \param[in] max_iterations The new maximum number of iterations (default = 5). + */ + void + setMaxIterations (int max_iterations); + + /** \brief Get the maximum number of iterations for the compute() method. + * \details The compute() method finishes when max_iterations are met or when the convergence criteria is met. + * \return The current maximum number of iterations (default = 5). + */ + inline int + getMaxIterations () const; + + /** \brief Set the convergence threshold for the compute() method. + * \details When the compute() method computes the new poses relative to the old poses, it will determine the length of the difference vector. + * When the average length of all difference vectors becomes less than the convergence_threshold the convergence is assumed to be met. + * \param[in] convergence_threshold The new convergence threshold (default = 0.0). + */ + void + setConvergenceThreshold (float convergence_threshold); + + /** \brief Get the convergence threshold for the compute() method. + * \details When the compute() method computes the new poses relative to the old poses, it will determine the length of the difference vector. + * When the average length of all difference vectors becomes less than the convergence_threshold the convergence is assumed to be met. + * \return The current convergence threshold (default = 0.0). + */ + inline float + getConvergenceThreshold () const; + + /** \brief Add a new point cloud to the SLAM graph. + * \details This method will add a new vertex to the SLAM graph and attach a point cloud to that vertex. + * Optionally you can specify a pose estimate for this point cloud. + * A vertex' pose is always relative to the first vertex in the SLAM graph, i.e. the first point cloud that was added. + * Because this first vertex is the reference, you can not set a pose estimate for this vertex. + * Providing pose estimates to the vertices in the SLAM graph will reduce overall computation time of LUM. + * \note Vertex descriptors are typecastable to int. + * \param[in] cloud The new point cloud. + * \param[in] pose (optional) The pose estimate relative to the reference pose (first point cloud that was added). + * \return The vertex descriptor of the newly created vertex. + */ + Vertex + addPointCloud (const PointCloudPtr &cloud, const Eigen::Vector6f &pose = Eigen::Vector6f::Zero ()); + + /** \brief Change a point cloud on one of the SLAM graph's vertices. + * \details This method will change the point cloud attached to an existing vertex and will not alter the SLAM graph structure. + * Note that the correspondences attached to this vertex will not change and may need to be updated manually. + * \note Vertex descriptors are typecastable to int. + * \param[in] vertex The vertex descriptor of which to change the point cloud. + * \param[in] cloud The new point cloud for that vertex. + */ + inline void + setPointCloud (const Vertex &vertex, const PointCloudPtr &cloud); + + /** \brief Return a point cloud from one of the SLAM graph's vertices. + * \note Vertex descriptors are typecastable to int. + * \param[in] vertex The vertex descriptor of which to return the point cloud. + * \return The current point cloud for that vertex. + */ + inline PointCloudPtr + getPointCloud (const Vertex &vertex) const; + + /** \brief Change a pose estimate on one of the SLAM graph's vertices. + * \details A vertex' pose is always relative to the first vertex in the SLAM graph, i.e. the first point cloud that was added. + * Because this first vertex is the reference, you can not set a pose estimate for this vertex. + * Providing pose estimates to the vertices in the SLAM graph will reduce overall computation time of LUM. + * \note Vertex descriptors are typecastable to int. + * \param[in] vertex The vertex descriptor of which to set the pose estimate. + * \param[in] pose The new pose estimate for that vertex. + */ + inline void + setPose (const Vertex &vertex, const Eigen::Vector6f &pose); + + /** \brief Return a pose estimate from one of the SLAM graph's vertices. + * \note Vertex descriptors are typecastable to int. + * \param[in] vertex The vertex descriptor of which to return the pose estimate. + * \return The current pose estimate of that vertex. + */ + inline Eigen::Vector6f + getPose (const Vertex &vertex) const; + + /** \brief Return a pose estimate from one of the SLAM graph's vertices as an affine transformation matrix. + * \note Vertex descriptors are typecastable to int. + * \param[in] vertex The vertex descriptor of which to return the transformation matrix. + * \return The current transformation matrix of that vertex. + */ + inline Eigen::Affine3f + getTransformation (const Vertex &vertex) const; + + /** \brief Add/change a set of correspondences for one of the SLAM graph's edges. + * \details The edges in the SLAM graph are directional and point from source vertex to target vertex. + * The query indices of the correspondences, index the points at the source vertex' point cloud. + * The matching indices of the correspondences, index the points at the target vertex' point cloud. + * If no edge was present at the specified location, this method will add a new edge to the SLAM graph and attach the correspondences to that edge. + * If the edge was already present, this method will overwrite the correspondence information of that edge and will not alter the SLAM graph structure. + * \note Vertex descriptors are typecastable to int. + * \param[in] source_vertex The vertex descriptor of the correspondences' source point cloud. + * \param[in] target_vertex The vertex descriptor of the correspondences' target point cloud. + * \param[in] corrs The new set of correspondences for that edge. + */ + void + setCorrespondences (const Vertex &source_vertex, + const Vertex &target_vertex, + const pcl::CorrespondencesPtr &corrs); + + /** \brief Return a set of correspondences from one of the SLAM graph's edges. + * \note Vertex descriptors are typecastable to int. + * \param[in] source_vertex The vertex descriptor of the correspondences' source point cloud. + * \param[in] target_vertex The vertex descriptor of the correspondences' target point cloud. + * \return The current set of correspondences of that edge. + */ + inline pcl::CorrespondencesPtr + getCorrespondences (const Vertex &source_vertex, const Vertex &target_vertex) const; + + /** \brief Perform LUM's globally consistent scan matching. + * \details Computation uses the first point cloud in the SLAM graph as a reference pose and attempts to align all other point clouds to it simultaneously. + *
+ * Things to keep in mind: + *
    + *
  • Only those parts of the graph connected to the reference pose will properly align to it.
  • + *
  • All sets of correspondences should span the same space and need to be sufficient to determine a rigid transformation.
  • + *
  • The algorithm draws it strength from loops in the graph because it will distribute errors evenly amongst those loops.
  • + *
+ * Computation ends when either of the following conditions hold: + *
    + *
  • The number of iterations reaches max_iterations. Use setMaxIterations() to change.
  • + *
  • The convergence criteria is met. Use setConvergenceThreshold() to change.
  • + *
+ * Computation will change the pose estimates for the vertices of the SLAM graph, not the point clouds attached to them. + * The results can be retrieved with getPose(), getTransformation(), getTransformedCloud() or getConcatenatedCloud(). + */ + void + compute (); + + /** \brief Return a point cloud from one of the SLAM graph's vertices compounded onto its current pose estimate. + * \note Vertex descriptors are typecastable to int. + * \param[in] vertex The vertex descriptor of which to return the transformed point cloud. + * \return The transformed point cloud of that vertex. + */ + PointCloudPtr + getTransformedCloud (const Vertex &vertex) const; + + /** \brief Return a concatenated point cloud of all the SLAM graph's point clouds compounded onto their current pose estimates. + * \return The concatenated transformed point clouds of the entire SLAM graph. + */ + PointCloudPtr + getConcatenatedCloud () const; + + protected: + /** \brief Linearized computation of C^-1 and C^-1*D (results stored in slam_graph_). */ + void + computeEdge (const Edge &e); + + /** \brief Returns a pose corrected 6DoF incidence matrix. */ + inline Eigen::Matrix6f + incidenceCorrection (const Eigen::Vector6f &pose); + + private: + /** \brief The internal SLAM graph structure. */ + SLAMGraphPtr slam_graph_; + + /** \brief The maximum number of iterations for the compute() method. */ + int max_iterations_; + + /** \brief The convergence threshold for the summed vector lengths of all poses. */ + float convergence_threshold_; + }; + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_REGISTRATION_LUM_H_ + diff --git a/pcl-1.7/pcl/registration/ndt.h b/pcl-1.7/pcl/registration/ndt.h new file mode 100644 index 0000000..fe7d20c --- /dev/null +++ b/pcl-1.7/pcl/registration/ndt.h @@ -0,0 +1,469 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_NDT_H_ +#define PCL_REGISTRATION_NDT_H_ + +#include +#include + +#include + +namespace pcl +{ + /** \brief A 3D Normal Distribution Transform registration implementation for point cloud data. + * \note For more information please see + * Magnusson, M. (2009). The Three-Dimensional Normal-Distributions Transform — + * an Efï¬cient Representation for Registration, Surface Analysis, and Loop Detection. + * PhD thesis, Orebro University. Orebro Studies in Technology 36., + * More, J., and Thuente, D. (1994). Line Search Algorithm with Guaranteed Sufficient Decrease + * In ACM Transactions on Mathematical Software. and + * Sun, W. and Yuan, Y, (2006) Optimization Theory and Methods: Nonlinear Programming. 89-100 + * \note Math refactored by Todor Stoyanov. + * \author Brian Okorn (Space and Naval Warfare Systems Center Pacific) + */ + template + class NormalDistributionsTransform : public Registration + { + protected: + + typedef typename Registration::PointCloudSource PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef typename Registration::PointCloudTarget PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + /** \brief Typename of searchable voxel grid containing mean and covariance. */ + typedef VoxelGridCovariance TargetGrid; + /** \brief Typename of pointer to searchable voxel grid. */ + typedef TargetGrid* TargetGridPtr; + /** \brief Typename of const pointer to searchable voxel grid. */ + typedef const TargetGrid* TargetGridConstPtr; + /** \brief Typename of const pointer to searchable voxel grid leaf. */ + typedef typename TargetGrid::LeafConstPtr TargetGridLeafConstPtr; + + + public: + + typedef boost::shared_ptr< NormalDistributionsTransform > Ptr; + typedef boost::shared_ptr< const NormalDistributionsTransform > ConstPtr; + + + /** \brief Constructor. + * Sets \ref outlier_ratio_ to 0.35, \ref step_size_ to 0.05 and \ref resolution_ to 1.0 + */ + NormalDistributionsTransform (); + + /** \brief Empty destructor */ + virtual ~NormalDistributionsTransform () {} + + /** \brief Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to). + * \param[in] cloud the input point cloud target + */ + inline void + setInputTarget (const PointCloudTargetConstPtr &cloud) + { + Registration::setInputTarget (cloud); + init (); + } + + /** \brief Set/change the voxel grid resolution. + * \param[in] resolution side length of voxels + */ + inline void + setResolution (float resolution) + { + // Prevents unnessary voxel initiations + if (resolution_ != resolution) + { + resolution_ = resolution; + if (input_) + init (); + } + } + + /** \brief Get voxel grid resolution. + * \return side length of voxels + */ + inline float + getResolution () const + { + return (resolution_); + } + + /** \brief Get the newton line search maximum step length. + * \return maximum step length + */ + inline double + getStepSize () const + { + return (step_size_); + } + + /** \brief Set/change the newton line search maximum step length. + * \param[in] step_size maximum step length + */ + inline void + setStepSize (double step_size) + { + step_size_ = step_size; + } + + /** \brief Get the point cloud outlier ratio. + * \return outlier ratio + */ + inline double + getOulierRatio () const + { + return (outlier_ratio_); + } + + /** \brief Set/change the point cloud outlier ratio. + * \param[in] outlier_ratio outlier ratio + */ + inline void + setOulierRatio (double outlier_ratio) + { + outlier_ratio_ = outlier_ratio; + } + + /** \brief Get the registration alignment probability. + * \return transformation probability + */ + inline double + getTransformationProbability () const + { + return (trans_probability_); + } + + /** \brief Get the number of iterations required to calculate alignment. + * \return final number of iterations + */ + inline int + getFinalNumIteration () const + { + return (nr_iterations_); + } + + /** \brief Convert 6 element transformation vector to affine transformation. + * \param[in] x transformation vector of the form [x, y, z, roll, pitch, yaw] + * \param[out] trans affine transform corresponding to given transfomation vector + */ + static void + convertTransform (const Eigen::Matrix &x, Eigen::Affine3f &trans) + { + trans = Eigen::Translation(float (x (0)), float (x (1)), float (x (2))) * + Eigen::AngleAxis(float (x (3)), Eigen::Vector3f::UnitX ()) * + Eigen::AngleAxis(float (x (4)), Eigen::Vector3f::UnitY ()) * + Eigen::AngleAxis(float (x (5)), Eigen::Vector3f::UnitZ ()); + } + + /** \brief Convert 6 element transformation vector to transformation matrix. + * \param[in] x transformation vector of the form [x, y, z, roll, pitch, yaw] + * \param[out] trans 4x4 transformation matrix corresponding to given transfomation vector + */ + static void + convertTransform (const Eigen::Matrix &x, Eigen::Matrix4f &trans) + { + Eigen::Affine3f _affine; + convertTransform (x, _affine); + trans = _affine.matrix (); + } + + protected: + + using Registration::reg_name_; + using Registration::getClassName; + using Registration::input_; + using Registration::indices_; + using Registration::target_; + using Registration::nr_iterations_; + using Registration::max_iterations_; + using Registration::previous_transformation_; + using Registration::final_transformation_; + using Registration::transformation_; + using Registration::transformation_epsilon_; + using Registration::converged_; + using Registration::corr_dist_threshold_; + using Registration::inlier_threshold_; + + using Registration::update_visualizer_; + + /** \brief Estimate the transformation and returns the transformed source (input) as output. + * \param[out] output the resultant input transfomed point cloud dataset + */ + virtual void + computeTransformation (PointCloudSource &output) + { + computeTransformation (output, Eigen::Matrix4f::Identity ()); + } + + /** \brief Estimate the transformation and returns the transformed source (input) as output. + * \param[out] output the resultant input transfomed point cloud dataset + * \param[in] guess the initial gross estimation of the transformation + */ + virtual void + computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess); + + /** \brief Initiate covariance voxel structure. */ + void inline + init () + { + target_cells_.setLeafSize (resolution_, resolution_, resolution_); + target_cells_.setInputCloud ( target_ ); + // Initiate voxel structure. + target_cells_.filter (true); + } + + /** \brief Compute derivatives of probability function w.r.t. the transformation vector. + * \note Equation 6.10, 6.12 and 6.13 [Magnusson 2009]. + * \param[out] score_gradient the gradient vector of the probability function w.r.t. the transformation vector + * \param[out] hessian the hessian matrix of the probability function w.r.t. the transformation vector + * \param[in] trans_cloud transformed point cloud + * \param[in] p the current transform vector + * \param[in] compute_hessian flag to calculate hessian, unnessissary for step calculation. + */ + double + computeDerivatives (Eigen::Matrix &score_gradient, + Eigen::Matrix &hessian, + PointCloudSource &trans_cloud, + Eigen::Matrix &p, + bool compute_hessian = true); + + /** \brief Compute individual point contirbutions to derivatives of probability function w.r.t. the transformation vector. + * \note Equation 6.10, 6.12 and 6.13 [Magnusson 2009]. + * \param[in,out] score_gradient the gradient vector of the probability function w.r.t. the transformation vector + * \param[in,out] hessian the hessian matrix of the probability function w.r.t. the transformation vector + * \param[in] x_trans transformed point minus mean of occupied covariance voxel + * \param[in] c_inv covariance of occupied covariance voxel + * \param[in] compute_hessian flag to calculate hessian, unnessissary for step calculation. + */ + double + updateDerivatives (Eigen::Matrix &score_gradient, + Eigen::Matrix &hessian, + Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv, + bool compute_hessian = true); + + /** \brief Precompute anglular components of derivatives. + * \note Equation 6.19 and 6.21 [Magnusson 2009]. + * \param[in] p the current transform vector + * \param[in] compute_hessian flag to calculate hessian, unnessissary for step calculation. + */ + void + computeAngleDerivatives (Eigen::Matrix &p, bool compute_hessian = true); + + /** \brief Compute point derivatives. + * \note Equation 6.18-21 [Magnusson 2009]. + * \param[in] x point from the input cloud + * \param[in] compute_hessian flag to calculate hessian, unnessissary for step calculation. + */ + void + computePointDerivatives (Eigen::Vector3d &x, bool compute_hessian = true); + + /** \brief Compute hessian of probability function w.r.t. the transformation vector. + * \note Equation 6.13 [Magnusson 2009]. + * \param[out] hessian the hessian matrix of the probability function w.r.t. the transformation vector + * \param[in] trans_cloud transformed point cloud + * \param[in] p the current transform vector + */ + void + computeHessian (Eigen::Matrix &hessian, + PointCloudSource &trans_cloud, + Eigen::Matrix &p); + + /** \brief Compute individual point contirbutions to hessian of probability function w.r.t. the transformation vector. + * \note Equation 6.13 [Magnusson 2009]. + * \param[in,out] hessian the hessian matrix of the probability function w.r.t. the transformation vector + * \param[in] x_trans transformed point minus mean of occupied covariance voxel + * \param[in] c_inv covariance of occupied covariance voxel + */ + void + updateHessian (Eigen::Matrix &hessian, + Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv); + + /** \brief Compute line search step length and update transform and probability derivatives using More-Thuente method. + * \note Search Algorithm [More, Thuente 1994] + * \param[in] x initial transformation vector, \f$ x \f$ in Equation 1.3 (Moore, Thuente 1994) and \f$ \vec{p} \f$ in Algorithm 2 [Magnusson 2009] + * \param[in] step_dir descent direction, \f$ p \f$ in Equation 1.3 (Moore, Thuente 1994) and \f$ \delta \vec{p} \f$ normalized in Algorithm 2 [Magnusson 2009] + * \param[in] step_init initial step length estimate, \f$ \alpha_0 \f$ in Moore-Thuente (1994) and the noramal of \f$ \delta \vec{p} \f$ in Algorithm 2 [Magnusson 2009] + * \param[in] step_max maximum step length, \f$ \alpha_max \f$ in Moore-Thuente (1994) + * \param[in] step_min minimum step length, \f$ \alpha_min \f$ in Moore-Thuente (1994) + * \param[out] score final score function value, \f$ f(x + \alpha p) \f$ in Equation 1.3 (Moore, Thuente 1994) and \f$ score \f$ in Algorithm 2 [Magnusson 2009] + * \param[in,out] score_gradient gradient of score function w.r.t. transformation vector, \f$ f'(x + \alpha p) \f$ in Moore-Thuente (1994) and \f$ \vec{g} \f$ in Algorithm 2 [Magnusson 2009] + * \param[out] hessian hessian of score function w.r.t. transformation vector, \f$ f''(x + \alpha p) \f$ in Moore-Thuente (1994) and \f$ H \f$ in Algorithm 2 [Magnusson 2009] + * \param[in,out] trans_cloud transformed point cloud, \f$ X \f$ transformed by \f$ T(\vec{p},\vec{x}) \f$ in Algorithm 2 [Magnusson 2009] + * \return final step length + */ + double + computeStepLengthMT (const Eigen::Matrix &x, + Eigen::Matrix &step_dir, + double step_init, + double step_max, double step_min, + double &score, + Eigen::Matrix &score_gradient, + Eigen::Matrix &hessian, + PointCloudSource &trans_cloud); + + /** \brief Update interval of possible step lengths for More-Thuente method, \f$ I \f$ in More-Thuente (1994) + * \note Updating Algorithm until some value satifies \f$ \psi(\alpha_k) \leq 0 \f$ and \f$ \phi'(\alpha_k) \geq 0 \f$ + * and Modified Updating Algorithm from then on [More, Thuente 1994]. + * \param[in,out] a_l first endpoint of interval \f$ I \f$, \f$ \alpha_l \f$ in Moore-Thuente (1994) + * \param[in,out] f_l value at first endpoint, \f$ f_l \f$ in Moore-Thuente (1994), \f$ \psi(\alpha_l) \f$ for Update Algorithm and \f$ \phi(\alpha_l) \f$ for Modified Update Algorithm + * \param[in,out] g_l derivative at first endpoint, \f$ g_l \f$ in Moore-Thuente (1994), \f$ \psi'(\alpha_l) \f$ for Update Algorithm and \f$ \phi'(\alpha_l) \f$ for Modified Update Algorithm + * \param[in,out] a_u second endpoint of interval \f$ I \f$, \f$ \alpha_u \f$ in Moore-Thuente (1994) + * \param[in,out] f_u value at second endpoint, \f$ f_u \f$ in Moore-Thuente (1994), \f$ \psi(\alpha_u) \f$ for Update Algorithm and \f$ \phi(\alpha_u) \f$ for Modified Update Algorithm + * \param[in,out] g_u derivative at second endpoint, \f$ g_u \f$ in Moore-Thuente (1994), \f$ \psi'(\alpha_u) \f$ for Update Algorithm and \f$ \phi'(\alpha_u) \f$ for Modified Update Algorithm + * \param[in] a_t trial value, \f$ \alpha_t \f$ in Moore-Thuente (1994) + * \param[in] f_t value at trial value, \f$ f_t \f$ in Moore-Thuente (1994), \f$ \psi(\alpha_t) \f$ for Update Algorithm and \f$ \phi(\alpha_t) \f$ for Modified Update Algorithm + * \param[in] g_t derivative at trial value, \f$ g_t \f$ in Moore-Thuente (1994), \f$ \psi'(\alpha_t) \f$ for Update Algorithm and \f$ \phi'(\alpha_t) \f$ for Modified Update Algorithm + * \return if interval converges + */ + bool + updateIntervalMT (double &a_l, double &f_l, double &g_l, + double &a_u, double &f_u, double &g_u, + double a_t, double f_t, double g_t); + + /** \brief Select new trial value for More-Thuente method. + * \note Trial Value Selection [More, Thuente 1994], \f$ \psi(\alpha_k) \f$ is used for \f$ f_k \f$ and \f$ g_k \f$ + * until some value satifies the test \f$ \psi(\alpha_k) \leq 0 \f$ and \f$ \phi'(\alpha_k) \geq 0 \f$ + * then \f$ \phi(\alpha_k) \f$ is used from then on. + * \note Interpolation Minimizer equations from Optimization Theory and Methods: Nonlinear Programming By Wenyu Sun, Ya-xiang Yuan (89-100). + * \param[in] a_l first endpoint of interval \f$ I \f$, \f$ \alpha_l \f$ in Moore-Thuente (1994) + * \param[in] f_l value at first endpoint, \f$ f_l \f$ in Moore-Thuente (1994) + * \param[in] g_l derivative at first endpoint, \f$ g_l \f$ in Moore-Thuente (1994) + * \param[in] a_u second endpoint of interval \f$ I \f$, \f$ \alpha_u \f$ in Moore-Thuente (1994) + * \param[in] f_u value at second endpoint, \f$ f_u \f$ in Moore-Thuente (1994) + * \param[in] g_u derivative at second endpoint, \f$ g_u \f$ in Moore-Thuente (1994) + * \param[in] a_t previous trial value, \f$ \alpha_t \f$ in Moore-Thuente (1994) + * \param[in] f_t value at previous trial value, \f$ f_t \f$ in Moore-Thuente (1994) + * \param[in] g_t derivative at previous trial value, \f$ g_t \f$ in Moore-Thuente (1994) + * \return new trial value + */ + double + trialValueSelectionMT (double a_l, double f_l, double g_l, + double a_u, double f_u, double g_u, + double a_t, double f_t, double g_t); + + /** \brief Auxilary function used to determin endpoints of More-Thuente interval. + * \note \f$ \psi(\alpha) \f$ in Equation 1.6 (Moore, Thuente 1994) + * \param[in] a the step length, \f$ \alpha \f$ in More-Thuente (1994) + * \param[in] f_a function value at step length a, \f$ \phi(\alpha) \f$ in More-Thuente (1994) + * \param[in] f_0 initial function value, \f$ \phi(0) \f$ in Moore-Thuente (1994) + * \param[in] g_0 initial function gradiant, \f$ \phi'(0) \f$ in More-Thuente (1994) + * \param[in] mu the step length, constant \f$ \mu \f$ in Equation 1.1 [More, Thuente 1994] + * \return sufficent decrease value + */ + inline double + auxilaryFunction_PsiMT (double a, double f_a, double f_0, double g_0, double mu = 1.e-4) + { + return (f_a - f_0 - mu * g_0 * a); + } + + /** \brief Auxilary function derivative used to determin endpoints of More-Thuente interval. + * \note \f$ \psi'(\alpha) \f$, derivative of Equation 1.6 (Moore, Thuente 1994) + * \param[in] g_a function gradient at step length a, \f$ \phi'(\alpha) \f$ in More-Thuente (1994) + * \param[in] g_0 initial function gradiant, \f$ \phi'(0) \f$ in More-Thuente (1994) + * \param[in] mu the step length, constant \f$ \mu \f$ in Equation 1.1 [More, Thuente 1994] + * \return sufficent decrease derivative + */ + inline double + auxilaryFunction_dPsiMT (double g_a, double g_0, double mu = 1.e-4) + { + return (g_a - mu * g_0); + } + + /** \brief The voxel grid generated from target cloud containing point means and covariances. */ + TargetGrid target_cells_; + + //double fitness_epsilon_; + + /** \brief The side length of voxels. */ + float resolution_; + + /** \brief The maximum step length. */ + double step_size_; + + /** \brief The ratio of outliers of points w.r.t. a normal distribution, Equation 6.7 [Magnusson 2009]. */ + double outlier_ratio_; + + /** \brief The normalization constants used fit the point distribution to a normal distribution, Equation 6.8 [Magnusson 2009]. */ + double gauss_d1_, gauss_d2_; + + /** \brief The probability score of the transform applied to the input cloud, Equation 6.9 and 6.10 [Magnusson 2009]. */ + double trans_probability_; + + /** \brief Precomputed Angular Gradient + * + * The precomputed angular derivatives for the jacobian of a transformation vector, Equation 6.19 [Magnusson 2009]. + */ + Eigen::Vector3d j_ang_a_, j_ang_b_, j_ang_c_, j_ang_d_, j_ang_e_, j_ang_f_, j_ang_g_, j_ang_h_; + + /** \brief Precomputed Angular Hessian + * + * The precomputed angular derivatives for the hessian of a transformation vector, Equation 6.19 [Magnusson 2009]. + */ + Eigen::Vector3d h_ang_a2_, h_ang_a3_, + h_ang_b2_, h_ang_b3_, + h_ang_c2_, h_ang_c3_, + h_ang_d1_, h_ang_d2_, h_ang_d3_, + h_ang_e1_, h_ang_e2_, h_ang_e3_, + h_ang_f1_, h_ang_f2_, h_ang_f3_; + + /** \brief The first order derivative of the transformation of a point w.r.t. the transform vector, \f$ J_E \f$ in Equation 6.18 [Magnusson 2009]. */ + Eigen::Matrix point_gradient_; + + /** \brief The second order derivative of the transformation of a point w.r.t. the transform vector, \f$ H_E \f$ in Equation 6.20 [Magnusson 2009]. */ + Eigen::Matrix point_hessian_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + }; + +} + +#include + +#endif // PCL_REGISTRATION_NDT_H_ diff --git a/pcl-1.7/pcl/registration/ndt_2d.h b/pcl-1.7/pcl/registration/ndt_2d.h new file mode 100644 index 0000000..ce29a2a --- /dev/null +++ b/pcl-1.7/pcl/registration/ndt_2d.h @@ -0,0 +1,157 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_NDT_2D_H_ +#define PCL_NDT_2D_H_ + +#include + +namespace pcl +{ + /** \brief @b NormalDistributionsTransform2D provides an implementation of the + * Normal Distributions Transform algorithm for scan matching. + * + * This implementation is intended to match the definition: + * Peter Biber and Wolfgang Straßer. The normal distributions transform: A + * new approach to laser scan matching. In Proceedings of the IEEE In- + * ternational Conference on Intelligent Robots and Systems (IROS), pages + * 2743–2748, Las Vegas, USA, October 2003. + * + * \author James Crosby + */ + template + class NormalDistributionsTransform2D : public Registration + { + typedef typename Registration::PointCloudSource PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef typename Registration::PointCloudTarget PointCloudTarget; + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + public: + + typedef boost::shared_ptr< NormalDistributionsTransform2D > Ptr; + typedef boost::shared_ptr< const NormalDistributionsTransform2D > ConstPtr; + + /** \brief Empty constructor. */ + NormalDistributionsTransform2D () + : Registration (), + grid_centre_ (0,0), grid_step_ (1,1), grid_extent_ (20,20), newton_lambda_ (1,1,1) + { + reg_name_ = "NormalDistributionsTransform2D"; + } + + /** \brief Empty destructor */ + virtual ~NormalDistributionsTransform2D () {} + + /** \brief centre of the ndt grid (target coordinate system) + * \param centre value to set + */ + virtual void + setGridCentre (const Eigen::Vector2f& centre) { grid_centre_ = centre; } + + /** \brief Grid spacing (step) of the NDT grid + * \param[in] step value to set + */ + virtual void + setGridStep (const Eigen::Vector2f& step) { grid_step_ = step; } + + /** \brief NDT Grid extent (in either direction from the grid centre) + * \param[in] extent value to set + */ + virtual void + setGridExtent (const Eigen::Vector2f& extent) { grid_extent_ = extent; } + + /** \brief NDT Newton optimisation step size parameter + * \param[in] lambda step size: 1 is simple newton optimisation, smaller values may improve convergence + */ + virtual void + setOptimizationStepSize (const double& lambda) { newton_lambda_ = Eigen::Vector3d (lambda, lambda, lambda); } + + /** \brief NDT Newton optimisation step size parameter + * \param[in] lambda step size: (1,1,1) is simple newton optimisation, + * smaller values may improve convergence, or elements may be set to + * zero to prevent optimisation over some parameters + * + * This overload allows control of updates to the individual (x, y, + * theta) free parameters in the optimisation. If, for example, theta is + * believed to be close to the correct value a small value of lambda[2] + * should be used. + */ + virtual void + setOptimizationStepSize (const Eigen::Vector3d& lambda) { newton_lambda_ = lambda; } + + protected: + /** \brief Rigid transformation computation method with initial guess. + * \param[out] output the transformed input point cloud dataset using the rigid transformation found + * \param[in] guess the initial guess of the transformation to compute + */ + virtual void + computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess); + + using Registration::reg_name_; + using Registration::target_; + using Registration::converged_; + using Registration::nr_iterations_; + using Registration::max_iterations_; + using Registration::transformation_epsilon_; + using Registration::transformation_; + using Registration::previous_transformation_; + using Registration::final_transformation_; + using Registration::update_visualizer_; + using Registration::indices_; + + Eigen::Vector2f grid_centre_; + Eigen::Vector2f grid_step_; + Eigen::Vector2f grid_extent_; + Eigen::Vector3d newton_lambda_; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + +} // namespace pcl + +#include + +#endif // ndef PCL_NDT_2D_H_ + diff --git a/pcl-1.7/pcl/registration/pairwise_graph_registration.hpp b/pcl-1.7/pcl/registration/pairwise_graph_registration.hpp new file mode 100644 index 0000000..2a57773 --- /dev/null +++ b/pcl-1.7/pcl/registration/pairwise_graph_registration.hpp @@ -0,0 +1,79 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_IMPL_PAIRWISE_GRAPH_REGISTRATION_HPP_ +#define PCL_REGISTRATION_IMPL_PAIRWISE_GRAPH_REGISTRATION_HPP_ +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PairwiseGraphRegistration::computeRegistration () +{ + if (!registration_method_) + { + PCL_ERROR ("[pcl::PairwiseGraphRegistration::computeRegistration] No registration method set!\n"); + return; + } + + typename std::vector::iterator last_vx_it = last_vertices_.begin (); + if (last_aligned_vertex_ == boost::graph_traits::null_vertex ()) + { + last_aligned_vertex_ = *last_vx_it; + ++last_vx_it; + } + + pcl::PointCloud fake_cloud; + registration_method_->setInputTarget (boost::get_cloud (last_aligned_vertex_, *(graph_handler_->getGraph ()))); + for(; last_vx_it < last_vertices_.end (); ++last_vx_it) + { + registration_method_->setInputCloud (boost::get_cloud (*last_vx_it, *(graph_handler_->getGraph ()))); + + const Eigen::Matrix4f last_aligned_vertex_pose = boost::get_pose (last_aligned_vertex_, *(graph_handler_->getGraph ())); + if (!incremental_) + { + const Eigen::Matrix4f guess = last_aligned_vertex_pose.transpose () * boost::get_pose (*last_vx_it, *(graph_handler_->getGraph ())); + registration_method_->align (fake_cloud, guess); + } else + registration_method_->align (fake_cloud); + + const Eigen::Matrix4f global_ref_final_tr = last_aligned_vertex_pose * registration_method_->getFinalTransformation (); + boost::set_estimate (*last_vx_it, global_ref_final_tr, *(graph_handler_->getGraph ())); + last_aligned_vertex_ = *last_vx_it; + registration_method_->setInputTarget (boost::get_cloud (last_aligned_vertex_, *(graph_handler_->getGraph ()))); + } +} +#endif //PCL_REGISTRATION_IMPL_PAIRWISE_GRAPH_REGISTRATION_HPP_ diff --git a/pcl-1.7/pcl/registration/ppf_registration.h b/pcl-1.7/pcl/registration/ppf_registration.h new file mode 100644 index 0000000..2560ec6 --- /dev/null +++ b/pcl-1.7/pcl/registration/ppf_registration.h @@ -0,0 +1,291 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Willow Garage, Inc + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + + +#ifndef PCL_PPF_REGISTRATION_H_ +#define PCL_PPF_REGISTRATION_H_ + +#include +#include +#include + +namespace pcl +{ + class PCL_EXPORTS PPFHashMapSearch + { + public: + /** \brief Data structure to hold the information for the key in the feature hash map of the + * PPFHashMapSearch class + * \note It uses multiple pair levels in order to enable the usage of the boost::hash function + * which has the std::pair implementation (i.e., does not require a custom hash function) + */ + struct HashKeyStruct : public std::pair > > + { + HashKeyStruct(int a, int b, int c, int d) + { + this->first = a; + this->second.first = b; + this->second.second.first = c; + this->second.second.second = d; + } + }; + typedef boost::unordered_multimap > FeatureHashMapType; + typedef boost::shared_ptr FeatureHashMapTypePtr; + typedef boost::shared_ptr Ptr; + + + /** \brief Constructor for the PPFHashMapSearch class which sets the two step parameters for the enclosed data structure + * \param angle_discretization_step the step value between each bin of the hash map for the angular values + * \param distance_discretization_step the step value between each bin of the hash map for the distance values + */ + PPFHashMapSearch (float angle_discretization_step = 12.0f / 180.0f * static_cast (M_PI), + float distance_discretization_step = 0.01f) + : alpha_m_ () + , feature_hash_map_ (new FeatureHashMapType) + , internals_initialized_ (false) + , angle_discretization_step_ (angle_discretization_step) + , distance_discretization_step_ (distance_discretization_step) + , max_dist_ (-1.0f) + { + } + + /** \brief Method that sets the feature cloud to be inserted in the hash map + * \param feature_cloud a const smart pointer to the PPFSignature feature cloud + */ + void + setInputFeatureCloud (PointCloud::ConstPtr feature_cloud); + + /** \brief Function for finding the nearest neighbors for the given feature inside the discretized hash map + * \param f1 The 1st value describing the query PPFSignature feature + * \param f2 The 2nd value describing the query PPFSignature feature + * \param f3 The 3rd value describing the query PPFSignature feature + * \param f4 The 4th value describing the query PPFSignature feature + * \param indices a vector of pair indices representing the feature pairs that have been found in the bin + * corresponding to the query feature + */ + void + nearestNeighborSearch (float &f1, float &f2, float &f3, float &f4, + std::vector > &indices); + + /** \brief Convenience method for returning a copy of the class instance as a boost::shared_ptr */ + Ptr + makeShared() { return Ptr (new PPFHashMapSearch (*this)); } + + /** \brief Returns the angle discretization step parameter (the step value between each bin of the hash map for the angular values) */ + inline float + getAngleDiscretizationStep () { return angle_discretization_step_; } + + /** \brief Returns the distance discretization step parameter (the step value between each bin of the hash map for the distance values) */ + inline float + getDistanceDiscretizationStep () { return distance_discretization_step_; } + + /** \brief Returns the maximum distance found between any feature pair in the given input feature cloud */ + inline float + getModelDiameter () { return max_dist_; } + + std::vector > alpha_m_; + private: + FeatureHashMapTypePtr feature_hash_map_; + bool internals_initialized_; + + float angle_discretization_step_, distance_discretization_step_; + float max_dist_; + }; + + /** \brief Class that registers two point clouds based on their sets of PPFSignatures. + * Please refer to the following publication for more details: + * B. Drost, M. Ulrich, N. Navab, S. Ilic + * Model Globally, Match Locally: Efficient and Robust 3D Object Recognition + * 2010 IEEE Conference on Computer Vision and Pattern Recognition (CVPR) + * 13-18 June 2010, San Francisco, CA + * + * \note This class works in tandem with the PPFEstimation class + * + * \author Alexandru-Eugen Ichim + */ + template + class PPFRegistration : public Registration + { + public: + /** \brief Structure for storing a pose (represented as an Eigen::Affine3f) and an integer for counting votes + * \note initially used std::pair, but it proved problematic + * because of the Eigen structures alignment problems - std::pair does not have a custom allocator + */ + struct PoseWithVotes + { + PoseWithVotes(Eigen::Affine3f &a_pose, unsigned int &a_votes) + : pose (a_pose), + votes (a_votes) + {} + + Eigen::Affine3f pose; + unsigned int votes; + }; + typedef std::vector > PoseWithVotesList; + + /// input_ is the model cloud + using Registration::input_; + /// target_ is the scene cloud + using Registration::target_; + using Registration::converged_; + using Registration::final_transformation_; + using Registration::transformation_; + + typedef pcl::PointCloud PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef pcl::PointCloud PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + + /** \brief Empty constructor that initializes all the parameters of the algorithm with default values */ + PPFRegistration () + : Registration (), + search_method_ (), + scene_reference_point_sampling_rate_ (5), + clustering_position_diff_threshold_ (0.01f), + clustering_rotation_diff_threshold_ (20.0f / 180.0f * static_cast (M_PI)) + {} + + /** \brief Method for setting the position difference clustering parameter + * \param clustering_position_diff_threshold distance threshold below which two poses are + * considered close enough to be in the same cluster (for the clustering phase of the algorithm) + */ + inline void + setPositionClusteringThreshold (float clustering_position_diff_threshold) { clustering_position_diff_threshold_ = clustering_position_diff_threshold; } + + /** \brief Returns the parameter defining the position difference clustering parameter - + * distance threshold below which two poses are considered close enough to be in the same cluster + * (for the clustering phase of the algorithm) + */ + inline float + getPositionClusteringThreshold () { return clustering_position_diff_threshold_; } + + /** \brief Method for setting the rotation clustering parameter + * \param clustering_rotation_diff_threshold rotation difference threshold below which two + * poses are considered to be in the same cluster (for the clustering phase of the algorithm) + */ + inline void + setRotationClusteringThreshold (float clustering_rotation_diff_threshold) { clustering_rotation_diff_threshold_ = clustering_rotation_diff_threshold; } + + /** \brief Returns the parameter defining the rotation clustering threshold + */ + inline float + getRotationClusteringThreshold () { return clustering_rotation_diff_threshold_; } + + /** \brief Method for setting the scene reference point sampling rate + * \param scene_reference_point_sampling_rate sampling rate for the scene reference point + */ + inline void + setSceneReferencePointSamplingRate (unsigned int scene_reference_point_sampling_rate) { scene_reference_point_sampling_rate_ = scene_reference_point_sampling_rate; } + + /** \brief Returns the parameter for the scene reference point sampling rate of the algorithm */ + inline unsigned int + getSceneReferencePointSamplingRate () { return scene_reference_point_sampling_rate_; } + + /** \brief Function that sets the search method for the algorithm + * \note Right now, the only available method is the one initially proposed by + * the authors - by using a hash map with discretized feature vectors + * \param search_method smart pointer to the search method to be set + */ + inline void + setSearchMethod (PPFHashMapSearch::Ptr search_method) { search_method_ = search_method; } + + /** \brief Getter function for the search method of the class */ + inline PPFHashMapSearch::Ptr + getSearchMethod () { return search_method_; } + + /** \brief Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to) + * \param cloud the input point cloud target + */ + void + setInputTarget (const PointCloudTargetConstPtr &cloud); + + + private: + /** \brief Method that calculates the transformation between the input_ and target_ point clouds, based on the PPF features */ + void + computeTransformation (PointCloudSource &output, const Eigen::Matrix4f& guess); + + + /** \brief the search method that is going to be used to find matching feature pairs */ + PPFHashMapSearch::Ptr search_method_; + + /** \brief parameter for the sampling rate of the scene reference points */ + unsigned int scene_reference_point_sampling_rate_; + + /** \brief position and rotation difference thresholds below which two + * poses are considered to be in the same cluster (for the clustering phase of the algorithm) */ + float clustering_position_diff_threshold_, clustering_rotation_diff_threshold_; + + /** \brief use a kd-tree with range searches of range max_dist to skip an O(N) pass through the point cloud */ + typename pcl::KdTreeFLANN::Ptr scene_search_tree_; + + /** \brief static method used for the std::sort function to order two PoseWithVotes + * instances by their number of votes*/ + static bool + poseWithVotesCompareFunction (const PoseWithVotes &a, + const PoseWithVotes &b); + + /** \brief static method used for the std::sort function to order two pairs + * by the number of votes (unsigned integer value) */ + static bool + clusterVotesCompareFunction (const std::pair &a, + const std::pair &b); + + /** \brief Method that clusters a set of given poses by using the clustering thresholds + * and their corresponding number of votes (see publication for more details) */ + void + clusterPoses (PoseWithVotesList &poses, + PoseWithVotesList &result); + + /** \brief Method that checks whether two poses are close together - based on the clustering threshold parameters + * of the class */ + bool + posesWithinErrorBounds (Eigen::Affine3f &pose1, + Eigen::Affine3f &pose2); + }; +} + +#include + +#endif // PCL_PPF_REGISTRATION_H_ diff --git a/pcl-1.7/pcl/registration/pyramid_feature_matching.h b/pcl-1.7/pcl/registration/pyramid_feature_matching.h new file mode 100644 index 0000000..1796157 --- /dev/null +++ b/pcl-1.7/pcl/registration/pyramid_feature_matching.h @@ -0,0 +1,202 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Willow Garage, Inc + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_PYRAMID_FEATURE_MATCHING_H_ +#define PCL_PYRAMID_FEATURE_MATCHING_H_ + +#include +#include + +namespace pcl +{ + /** + * \brief Class that compares two sets of features by using a multiscale representation of the features inside a + * pyramid. Each level of the pyramid offers information about the similarity of the two feature sets. + * \note Works with any Point/Feature type which has a PointRepresentation implementation + * \note The only parameters it needs are the input dimension ranges and the output dimension ranges. The input + * dimension ranges represent the ranges in which each dimension of the feature vector lies. As described in the + * paper, a minimum inter-vector distance of sqrt(nr_dims)/2 is needed. As such, the target dimension range parameter + * is used in order to augment/reduce the range for each dimension in order to obtain the necessary minimal + * inter-vector distance and to add/subtract weight to/from certain dimensions of the feature vector. + * + * Follows the algorithm presented in the publication: + * Grauman, K. & Darrell, T. + * The Pyramid Match Kernel: Discriminative Classification with Sets of Image Features + * Tenth IEEE International Conference on Computer Vision ICCV05 Volume 1 + * October 2005 + * + * \author Alexandru-Eugen Ichim + */ + template + class PyramidFeatureHistogram : public PCLBase + { + public: + using PCLBase::input_; + + typedef boost::shared_ptr > Ptr; + typedef Ptr PyramidFeatureHistogramPtr; + typedef boost::shared_ptr > FeatureRepresentationConstPtr; + + + /** \brief Empty constructor that instantiates the feature representation variable */ + PyramidFeatureHistogram (); + + /** \brief Method for setting the input dimension range parameter. + * \note Please check the PyramidHistogram class description for more details about this parameter. + */ + inline void + setInputDimensionRange (std::vector > &dimension_range_input) + { dimension_range_input_ = dimension_range_input; } + + /** \brief Method for retrieving the input dimension range vector */ + inline std::vector > + getInputDimensionRange () { return dimension_range_input_; } + + /** \brief Method to set the target dimension range parameter. + * \note Please check the PyramidHistogram class description for more details about this parameter. + */ + inline void + setTargetDimensionRange (std::vector > &dimension_range_target) + { dimension_range_target_ = dimension_range_target; } + + /** \brief Method for retrieving the target dimension range vector */ + inline std::vector > + getTargetDimensionRange () { return dimension_range_target_; } + + /** \brief Provide a pointer to the feature representation to use to convert features to k-D vectors. + * \param feature_representation the const boost shared pointer to a PointRepresentation + */ + inline void + setPointRepresentation (const FeatureRepresentationConstPtr& feature_representation) { feature_representation_ = feature_representation; } + + /** \brief Get a pointer to the feature representation used when converting features into k-D vectors. */ + inline FeatureRepresentationConstPtr const + getPointRepresentation () { return feature_representation_; } + + /** \brief The central method for inserting the feature set inside the pyramid and obtaining the complete pyramid */ + void + compute (); + + /** \brief Checks whether the pyramid histogram has been computed */ + inline bool + isComputed () { return is_computed_; } + + /** \brief Static method for comparing two pyramid histograms that returns a floating point value between 0 and 1, + * representing the similiarity between the feature sets on which the two pyramid histograms are based. + * \param pyramid_a Pointer to the first pyramid to be compared (needs to be computed already). + * \param pyramid_b Pointer to the second pyramid to be compared (needs to be computed already). + */ + static float + comparePyramidFeatureHistograms (const PyramidFeatureHistogramPtr &pyramid_a, + const PyramidFeatureHistogramPtr &pyramid_b); + + + private: + size_t nr_dimensions, nr_levels, nr_features; + std::vector > dimension_range_input_, dimension_range_target_; + FeatureRepresentationConstPtr feature_representation_; + bool is_computed_; + + /** \brief Checks for input inconsistencies and initializes the underlying data structures */ + bool + initializeHistogram (); + + /** \brief Converts a feature in templated form to an STL vector. This is the point where the conversion from the + * input dimension range to the target dimension range is done. + */ + void + convertFeatureToVector (const PointFeature &feature, + std::vector &feature_vector); + + /** \brief Adds a feature vector to its corresponding bin at each level in the pyramid */ + void + addFeature (std::vector &feature); + + /** \brief Access the pyramid bin given the position of the bin at the given pyramid level + * and the pyramid level + * \param access index of the bin at the respective level + * \param level the level in the pyramid + */ + inline unsigned int& + at (std::vector &access, + size_t &level); + + /** \brief Access the pyramid bin given a feature vector and the pyramid level + * \param feature the feature in vectorized form + * \param level the level in the pyramid + */ + inline unsigned int& + at (std::vector &feature, + size_t &level); + + /** \brief Structure for representing a single pyramid histogram level */ + struct PyramidFeatureHistogramLevel + { + PyramidFeatureHistogramLevel () : + hist (), + bins_per_dimension (), + bin_step () + { + } + + PyramidFeatureHistogramLevel (std::vector &a_bins_per_dimension, std::vector &a_bin_step) : + hist (), + bins_per_dimension (a_bins_per_dimension), + bin_step (a_bin_step) + { + initializeHistogramLevel (); + } + + void + initializeHistogramLevel (); + + std::vector hist; + std::vector bins_per_dimension; + std::vector bin_step; + }; + std::vector hist_levels; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_PYRAMID_FEATURE_MATCHING_H_ diff --git a/pcl-1.7/pcl/registration/registration.h b/pcl-1.7/pcl/registration/registration.h new file mode 100644 index 0000000..b30ae68 --- /dev/null +++ b/pcl-1.7/pcl/registration/registration.h @@ -0,0 +1,609 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_H_ +#define PCL_REGISTRATION_H_ + +// PCL includes +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief @b Registration represents the base registration class for general purpose, ICP-like methods. + * \author Radu B. Rusu, Michael Dixon + * \ingroup registration + */ + template + class Registration : public PCLBase + { + public: + typedef Eigen::Matrix Matrix4; + + // using PCLBase::initCompute; + using PCLBase::deinitCompute; + using PCLBase::input_; + using PCLBase::indices_; + + typedef boost::shared_ptr< Registration > Ptr; + typedef boost::shared_ptr< const Registration > ConstPtr; + + typedef typename pcl::registration::CorrespondenceRejector::Ptr CorrespondenceRejectorPtr; + typedef pcl::search::KdTree KdTree; + typedef typename pcl::search::KdTree::Ptr KdTreePtr; + + typedef pcl::search::KdTree KdTreeReciprocal; + typedef typename KdTree::Ptr KdTreeReciprocalPtr; + + typedef pcl::PointCloud PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef pcl::PointCloud PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + typedef typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr; + + typedef typename pcl::registration::TransformationEstimation TransformationEstimation; + typedef typename TransformationEstimation::Ptr TransformationEstimationPtr; + typedef typename TransformationEstimation::ConstPtr TransformationEstimationConstPtr; + + typedef typename pcl::registration::CorrespondenceEstimationBase CorrespondenceEstimation; + typedef typename CorrespondenceEstimation::Ptr CorrespondenceEstimationPtr; + typedef typename CorrespondenceEstimation::ConstPtr CorrespondenceEstimationConstPtr; + + /** \brief Empty constructor. */ + Registration () + : reg_name_ () + , tree_ (new KdTree) + , tree_reciprocal_ (new KdTreeReciprocal) + , nr_iterations_ (0) + , max_iterations_ (10) + , ransac_iterations_ (0) + , target_ () + , final_transformation_ (Matrix4::Identity ()) + , transformation_ (Matrix4::Identity ()) + , previous_transformation_ (Matrix4::Identity ()) + , transformation_epsilon_ (0.0) + , euclidean_fitness_epsilon_ (-std::numeric_limits::max ()) + , corr_dist_threshold_ (std::sqrt (std::numeric_limits::max ())) + , inlier_threshold_ (0.05) + , converged_ (false) + , min_number_correspondences_ (3) + , correspondences_ (new Correspondences) + , transformation_estimation_ () + , correspondence_estimation_ () + , correspondence_rejectors_ () + , target_cloud_updated_ (true) + , source_cloud_updated_ (true) + , force_no_recompute_ (false) + , force_no_recompute_reciprocal_ (false) + , update_visualizer_ (NULL) + , point_representation_ () + { + } + + /** \brief destructor. */ + virtual ~Registration () {} + + /** \brief Provide a pointer to the transformation estimation object. + * (e.g., SVD, point to plane etc.) + * + * \param[in] te is the pointer to the corresponding transformation estimation object + * + * Code example: + * + * \code + * TransformationEstimationPointToPlaneLLS::Ptr trans_lls (new TransformationEstimationPointToPlaneLLS); + * icp.setTransformationEstimation (trans_lls); + * // or... + * TransformationEstimationSVD::Ptr trans_svd (new TransformationEstimationSVD); + * icp.setTransformationEstimation (trans_svd); + * \endcode + */ + void + setTransformationEstimation (const TransformationEstimationPtr &te) { transformation_estimation_ = te; } + + /** \brief Provide a pointer to the correspondence estimation object. + * (e.g., regular, reciprocal, normal shooting etc.) + * + * \param[in] ce is the pointer to the corresponding correspondence estimation object + * + * Code example: + * + * \code + * CorrespondenceEstimation::Ptr ce (new CorrespondenceEstimation); + * ce->setInputSource (source); + * ce->setInputTarget (target); + * icp.setCorrespondenceEstimation (ce); + * // or... + * CorrespondenceEstimationNormalShooting::Ptr cens (new CorrespondenceEstimationNormalShooting); + * ce->setInputSource (source); + * ce->setInputTarget (target); + * ce->setSourceNormals (source); + * ce->setTargetNormals (target); + * icp.setCorrespondenceEstimation (cens); + * \endcode + */ + void + setCorrespondenceEstimation (const CorrespondenceEstimationPtr &ce) { correspondence_estimation_ = ce; } + + /** \brief Provide a pointer to the input source + * (e.g., the point cloud that we want to align to the target) + * + * \param[in] cloud the input point cloud source + */ + PCL_DEPRECATED ("[pcl::registration::Registration::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.") + void + setInputCloud (const PointCloudSourceConstPtr &cloud); + + /** \brief Get a pointer to the input point cloud dataset target. */ + PCL_DEPRECATED ("[pcl::registration::Registration::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.") + PointCloudSourceConstPtr const + getInputCloud (); + + /** \brief Provide a pointer to the input source + * (e.g., the point cloud that we want to align to the target) + * + * \param[in] cloud the input point cloud source + */ + virtual void + setInputSource (const PointCloudSourceConstPtr &cloud) + { + source_cloud_updated_ = true; + PCLBase::setInputCloud (cloud); + } + + /** \brief Get a pointer to the input point cloud dataset target. */ + inline PointCloudSourceConstPtr const + getInputSource () { return (input_ ); } + + /** \brief Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to) + * \param[in] cloud the input point cloud target + */ + virtual inline void + setInputTarget (const PointCloudTargetConstPtr &cloud); + + /** \brief Get a pointer to the input point cloud dataset target. */ + inline PointCloudTargetConstPtr const + getInputTarget () { return (target_ ); } + + + /** \brief Provide a pointer to the search object used to find correspondences in + * the target cloud. + * \param[in] tree a pointer to the spatial search object. + * \param[in] force_no_recompute If set to true, this tree will NEVER be + * recomputed, regardless of calls to setInputTarget. Only use if you are + * confident that the tree will be set correctly. + */ + inline void + setSearchMethodTarget (const KdTreePtr &tree, + bool force_no_recompute = false) + { + tree_ = tree; + if (force_no_recompute) + { + force_no_recompute_ = true; + } + // Since we just set a new tree, we need to check for updates + target_cloud_updated_ = true; + } + + /** \brief Get a pointer to the search method used to find correspondences in the + * target cloud. */ + inline KdTreePtr + getSearchMethodTarget () const + { + return (tree_); + } + + /** \brief Provide a pointer to the search object used to find correspondences in + * the source cloud (usually used by reciprocal correspondence finding). + * \param[in] tree a pointer to the spatial search object. + * \param[in] force_no_recompute If set to true, this tree will NEVER be + * recomputed, regardless of calls to setInputSource. Only use if you are + * extremely confident that the tree will be set correctly. + */ + inline void + setSearchMethodSource (const KdTreeReciprocalPtr &tree, + bool force_no_recompute = false) + { + tree_reciprocal_ = tree; + if ( force_no_recompute ) + { + force_no_recompute_reciprocal_ = true; + } + // Since we just set a new tree, we need to check for updates + source_cloud_updated_ = true; + } + + /** \brief Get a pointer to the search method used to find correspondences in the + * source cloud. */ + inline KdTreeReciprocalPtr + getSearchMethodSource () const + { + return (tree_reciprocal_); + } + + /** \brief Get the final transformation matrix estimated by the registration method. */ + inline Matrix4 + getFinalTransformation () { return (final_transformation_); } + + /** \brief Get the last incremental transformation matrix estimated by the registration method. */ + inline Matrix4 + getLastIncrementalTransformation () { return (transformation_); } + + /** \brief Set the maximum number of iterations the internal optimization should run for. + * \param[in] nr_iterations the maximum number of iterations the internal optimization should run for + */ + inline void + setMaximumIterations (int nr_iterations) { max_iterations_ = nr_iterations; } + + /** \brief Get the maximum number of iterations the internal optimization should run for, as set by the user. */ + inline int + getMaximumIterations () { return (max_iterations_); } + + /** \brief Set the number of iterations RANSAC should run for. + * \param[in] ransac_iterations is the number of iterations RANSAC should run for + */ + inline void + setRANSACIterations (int ransac_iterations) { ransac_iterations_ = ransac_iterations; } + + /** \brief Get the number of iterations RANSAC should run for, as set by the user. */ + inline double + getRANSACIterations () { return (ransac_iterations_); } + + /** \brief Set the inlier distance threshold for the internal RANSAC outlier rejection loop. + * + * The method considers a point to be an inlier, if the distance between the target data index and the transformed + * source index is smaller than the given inlier distance threshold. + * The value is set by default to 0.05m. + * \param[in] inlier_threshold the inlier distance threshold for the internal RANSAC outlier rejection loop + */ + inline void + setRANSACOutlierRejectionThreshold (double inlier_threshold) { inlier_threshold_ = inlier_threshold; } + + /** \brief Get the inlier distance threshold for the internal outlier rejection loop as set by the user. */ + inline double + getRANSACOutlierRejectionThreshold () { return (inlier_threshold_); } + + /** \brief Set the maximum distance threshold between two correspondent points in source <-> target. If the + * distance is larger than this threshold, the points will be ignored in the alignment process. + * \param[in] distance_threshold the maximum distance threshold between a point and its nearest neighbor + * correspondent in order to be considered in the alignment process + */ + inline void + setMaxCorrespondenceDistance (double distance_threshold) { corr_dist_threshold_ = distance_threshold; } + + /** \brief Get the maximum distance threshold between two correspondent points in source <-> target. If the + * distance is larger than this threshold, the points will be ignored in the alignment process. + */ + inline double + getMaxCorrespondenceDistance () { return (corr_dist_threshold_); } + + /** \brief Set the transformation epsilon (maximum allowable difference between two consecutive + * transformations) in order for an optimization to be considered as having converged to the final + * solution. + * \param[in] epsilon the transformation epsilon in order for an optimization to be considered as having + * converged to the final solution. + */ + inline void + setTransformationEpsilon (double epsilon) { transformation_epsilon_ = epsilon; } + + /** \brief Get the transformation epsilon (maximum allowable difference between two consecutive + * transformations) as set by the user. + */ + inline double + getTransformationEpsilon () { return (transformation_epsilon_); } + + /** \brief Set the maximum allowed Euclidean error between two consecutive steps in the ICP loop, before + * the algorithm is considered to have converged. + * The error is estimated as the sum of the differences between correspondences in an Euclidean sense, + * divided by the number of correspondences. + * \param[in] epsilon the maximum allowed distance error before the algorithm will be considered to have + * converged + */ + + inline void + setEuclideanFitnessEpsilon (double epsilon) { euclidean_fitness_epsilon_ = epsilon; } + + /** \brief Get the maximum allowed distance error before the algorithm will be considered to have converged, + * as set by the user. See \ref setEuclideanFitnessEpsilon + */ + inline double + getEuclideanFitnessEpsilon () { return (euclidean_fitness_epsilon_); } + + /** \brief Provide a boost shared pointer to the PointRepresentation to be used when comparing points + * \param[in] point_representation the PointRepresentation to be used by the k-D tree + */ + inline void + setPointRepresentation (const PointRepresentationConstPtr &point_representation) + { + point_representation_ = point_representation; + } + + /** \brief Register the user callback function which will be called from registration thread + * in order to update point cloud obtained after each iteration + * \param[in] visualizerCallback reference of the user callback function + */ + template inline bool + registerVisualizationCallback (boost::function &visualizerCallback) + { + if (visualizerCallback != NULL) + { + update_visualizer_ = visualizerCallback; + return (true); + } + else + return (false); + } + + /** \brief Obtain the Euclidean fitness score (e.g., sum of squared distances from the source to the target) + * \param[in] max_range maximum allowable distance between a point and its correspondence in the target + * (default: double::max) + */ + inline double + getFitnessScore (double max_range = std::numeric_limits::max ()); + + /** \brief Obtain the Euclidean fitness score (e.g., sum of squared distances from the source to the target) + * from two sets of correspondence distances (distances between source and target points) + * \param[in] distances_a the first set of distances between correspondences + * \param[in] distances_b the second set of distances between correspondences + */ + inline double + getFitnessScore (const std::vector &distances_a, const std::vector &distances_b); + + /** \brief Return the state of convergence after the last align run */ + inline bool + hasConverged () { return (converged_); } + + /** \brief Call the registration algorithm which estimates the transformation and returns the transformed source + * (input) as \a output. + * \param[out] output the resultant input transfomed point cloud dataset + */ + inline void + align (PointCloudSource &output); + + /** \brief Call the registration algorithm which estimates the transformation and returns the transformed source + * (input) as \a output. + * \param[out] output the resultant input transfomed point cloud dataset + * \param[in] guess the initial gross estimation of the transformation + */ + inline void + align (PointCloudSource &output, const Matrix4& guess); + + /** \brief Abstract class get name method. */ + inline const std::string& + getClassName () const { return (reg_name_); } + + /** \brief Internal computation initalization. */ + bool + initCompute (); + + /** \brief Internal computation when reciprocal lookup is needed */ + bool + initComputeReciprocal (); + + /** \brief Add a new correspondence rejector to the list + * \param[in] rejector the new correspondence rejector to concatenate + * + * Code example: + * + * \code + * CorrespondenceRejectorDistance rej; + * rej.setInputCloud (keypoints_src); + * rej.setInputTarget (keypoints_tgt); + * rej.setMaximumDistance (1); + * rej.setInputCorrespondences (all_correspondences); + * + * // or... + * + * \endcode + */ + inline void + addCorrespondenceRejector (const CorrespondenceRejectorPtr &rejector) + { + correspondence_rejectors_.push_back (rejector); + } + + /** \brief Get the list of correspondence rejectors. */ + inline std::vector + getCorrespondenceRejectors () + { + return (correspondence_rejectors_); + } + + /** \brief Remove the i-th correspondence rejector in the list + * \param[in] i the position of the correspondence rejector in the list to remove + */ + inline bool + removeCorrespondenceRejector (unsigned int i) + { + if (i >= correspondence_rejectors_.size ()) + return (false); + correspondence_rejectors_.erase (correspondence_rejectors_.begin () + i); + return (true); + } + + /** \brief Clear the list of correspondence rejectors. */ + inline void + clearCorrespondenceRejectors () + { + correspondence_rejectors_.clear (); + } + + protected: + /** \brief The registration method name. */ + std::string reg_name_; + + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + + /** \brief A pointer to the spatial search object of the source. */ + KdTreeReciprocalPtr tree_reciprocal_; + + /** \brief The number of iterations the internal optimization ran for (used internally). */ + int nr_iterations_; + + /** \brief The maximum number of iterations the internal optimization should run for. + * The default value is 10. + */ + int max_iterations_; + + /** \brief The number of iterations RANSAC should run for. */ + int ransac_iterations_; + + /** \brief The input point cloud dataset target. */ + PointCloudTargetConstPtr target_; + + /** \brief The final transformation matrix estimated by the registration method after N iterations. */ + Matrix4 final_transformation_; + + /** \brief The transformation matrix estimated by the registration method. */ + Matrix4 transformation_; + + /** \brief The previous transformation matrix estimated by the registration method (used internally). */ + Matrix4 previous_transformation_; + + /** \brief The maximum difference between two consecutive transformations in order to consider convergence + * (user defined). + */ + double transformation_epsilon_; + + /** \brief The maximum allowed Euclidean error between two consecutive steps in the ICP loop, before the + * algorithm is considered to have converged. The error is estimated as the sum of the differences between + * correspondences in an Euclidean sense, divided by the number of correspondences. + */ + double euclidean_fitness_epsilon_; + + /** \brief The maximum distance threshold between two correspondent points in source <-> target. If the + * distance is larger than this threshold, the points will be ignored in the alignement process. + */ + double corr_dist_threshold_; + + /** \brief The inlier distance threshold for the internal RANSAC outlier rejection loop. + * The method considers a point to be an inlier, if the distance between the target data index and the transformed + * source index is smaller than the given inlier distance threshold. The default value is 0.05. + */ + double inlier_threshold_; + + /** \brief Holds internal convergence state, given user parameters. */ + bool converged_; + + /** \brief The minimum number of correspondences that the algorithm needs before attempting to estimate the + * transformation. The default value is 3. + */ + int min_number_correspondences_; + + /** \brief The set of correspondences determined at this ICP step. */ + CorrespondencesPtr correspondences_; + + /** \brief A TransformationEstimation object, used to calculate the 4x4 rigid transformation. */ + TransformationEstimationPtr transformation_estimation_; + + /** \brief A CorrespondenceEstimation object, used to estimate correspondences between the source and the target cloud. */ + CorrespondenceEstimationPtr correspondence_estimation_; + + /** \brief The list of correspondence rejectors to use. */ + std::vector correspondence_rejectors_; + + /** \brief Variable that stores whether we have a new target cloud, meaning we need to pre-process it again. + * This way, we avoid rebuilding the kd-tree for the target cloud every time the determineCorrespondences () method + * is called. */ + bool target_cloud_updated_; + /** \brief Variable that stores whether we have a new source cloud, meaning we need to pre-process it again. + * This way, we avoid rebuilding the reciprocal kd-tree for the source cloud every time the determineCorrespondences () method + * is called. */ + bool source_cloud_updated_; + /** \brief A flag which, if set, means the tree operating on the target cloud + * will never be recomputed*/ + bool force_no_recompute_; + + /** \brief A flag which, if set, means the tree operating on the source cloud + * will never be recomputed*/ + bool force_no_recompute_reciprocal_; + + /** \brief Callback function to update intermediate source point cloud position during it's registration + * to the target point cloud. + */ + boost::function &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt)> update_visualizer_; + + /** \brief Search for the closest nearest neighbor of a given point. + * \param cloud the point cloud dataset to use for nearest neighbor search + * \param index the index of the query point + * \param indices the resultant vector of indices representing the k-nearest neighbors + * \param distances the resultant distances from the query point to the k-nearest neighbors + */ + inline bool + searchForNeighbors (const PointCloudSource &cloud, int index, + std::vector &indices, std::vector &distances) + { + int k = tree_->nearestKSearch (cloud, index, 1, indices, distances); + if (k == 0) + return (false); + return (true); + } + + /** \brief Abstract transformation computation method with initial guess */ + virtual void + computeTransformation (PointCloudSource &output, const Matrix4& guess) = 0; + + private: + /** \brief The point representation used (internal). */ + PointRepresentationConstPtr point_representation_; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#include + +#endif //#ifndef PCL_REGISTRATION_H_ diff --git a/pcl-1.7/pcl/registration/sample_consensus_prerejective.h b/pcl-1.7/pcl/registration/sample_consensus_prerejective.h new file mode 100644 index 0000000..8ef2ada --- /dev/null +++ b/pcl-1.7/pcl/registration/sample_consensus_prerejective.h @@ -0,0 +1,320 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_SAMPLE_CONSENSUS_PREREJECTIVE_H_ +#define PCL_REGISTRATION_SAMPLE_CONSENSUS_PREREJECTIVE_H_ + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Pose estimation and alignment class using a prerejective RANSAC routine. + * + * This class inserts a simple, yet effective "prerejection" step into the standard + * RANSAC pose estimation loop in order to avoid verification of pose hypotheses + * that are likely to be wrong. This is achieved by local pose-invariant geometric + * constraints, as also implemented in the class + * \ref registration::CorrespondenceRejectorPoly "CorrespondenceRejectorPoly". + * + * In order to robustly align partial/occluded models, this routine performs + * fit error evaluation using only inliers, i.e. points closer than a + * Euclidean threshold, which is specifiable using \ref setInlierFraction(). + * + * The amount of prerejection or "greedyness" of the algorithm can be specified + * using \ref setSimilarityThreshold() in [0,1[, where a value of 0 means disabled, + * and 1 is maximally rejective. + * + * If you use this in academic work, please cite: + * + * A. G. Buch, D. Kraft, J.-K. Kämäräinen, H. G. Petersen and N. Krüger. + * Pose Estimation using Local Structure-Specific Shape and Appearance Context. + * International Conference on Robotics and Automation (ICRA), 2013. + * + * \author Anders Glent Buch (andersgb1@gmail.com) + * \ingroup registration + */ + template + class SampleConsensusPrerejective : public Registration + { + public: + typedef typename Registration::Matrix4 Matrix4; + + using Registration::reg_name_; + using Registration::getClassName; + using Registration::input_; + using Registration::target_; + using Registration::tree_; + using Registration::max_iterations_; + using Registration::corr_dist_threshold_; + using Registration::transformation_; + using Registration::final_transformation_; + using Registration::transformation_estimation_; + using Registration::getFitnessScore; + using Registration::converged_; + + typedef typename Registration::PointCloudSource PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef typename Registration::PointCloudTarget PointCloudTarget; + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + typedef pcl::PointCloud FeatureCloud; + typedef typename FeatureCloud::Ptr FeatureCloudPtr; + typedef typename FeatureCloud::ConstPtr FeatureCloudConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename KdTreeFLANN::Ptr FeatureKdTreePtr; + + typedef pcl::registration::CorrespondenceRejectorPoly CorrespondenceRejectorPoly; + typedef typename CorrespondenceRejectorPoly::Ptr CorrespondenceRejectorPolyPtr; + typedef typename CorrespondenceRejectorPoly::ConstPtr CorrespondenceRejectorPolyConstPtr; + + /** \brief Constructor */ + SampleConsensusPrerejective () + : input_features_ () + , target_features_ () + , nr_samples_(3) + , k_correspondences_ (2) + , feature_tree_ (new pcl::KdTreeFLANN) + , correspondence_rejector_poly_ (new CorrespondenceRejectorPoly) + , inlier_fraction_ (0.0f) + { + reg_name_ = "SampleConsensusPrerejective"; + correspondence_rejector_poly_->setSimilarityThreshold (0.6f); + max_iterations_ = 5000; + transformation_estimation_.reset (new pcl::registration::TransformationEstimationSVD); + }; + + /** \brief Destructor */ + virtual ~SampleConsensusPrerejective () + { + } + + /** \brief Provide a boost shared pointer to the source point cloud's feature descriptors + * \param features the source point cloud's features + */ + void + setSourceFeatures (const FeatureCloudConstPtr &features); + + /** \brief Get a pointer to the source point cloud's features */ + inline const FeatureCloudConstPtr + getSourceFeatures () const + { + return (input_features_); + } + + /** \brief Provide a boost shared pointer to the target point cloud's feature descriptors + * \param features the target point cloud's features + */ + void + setTargetFeatures (const FeatureCloudConstPtr &features); + + /** \brief Get a pointer to the target point cloud's features */ + inline const FeatureCloudConstPtr + getTargetFeatures () const + { + return (target_features_); + } + + /** \brief Set the number of samples to use during each iteration + * \param nr_samples the number of samples to use during each iteration + */ + inline void + setNumberOfSamples (int nr_samples) + { + nr_samples_ = nr_samples; + } + + /** \brief Get the number of samples to use during each iteration, as set by the user */ + inline int + getNumberOfSamples () const + { + return (nr_samples_); + } + + /** \brief Set the number of neighbors to use when selecting a random feature correspondence. A higher value will + * add more randomness to the feature matching. + * \param k the number of neighbors to use when selecting a random feature correspondence. + */ + inline void + setCorrespondenceRandomness (int k) + { + k_correspondences_ = k; + } + + /** \brief Get the number of neighbors used when selecting a random feature correspondence, as set by the user */ + inline int + getCorrespondenceRandomness () const + { + return (k_correspondences_); + } + + /** \brief Set the similarity threshold in [0,1[ between edge lengths of the underlying polygonal correspondence rejector object, + * where 1 is a perfect match + * \param similarity_threshold edge length similarity threshold + */ + inline void + setSimilarityThreshold (float similarity_threshold) + { + correspondence_rejector_poly_->setSimilarityThreshold (similarity_threshold); + } + + /** \brief Get the similarity threshold between edge lengths of the underlying polygonal correspondence rejector object, + * \return edge length similarity threshold + */ + inline float + getSimilarityThreshold () const + { + return correspondence_rejector_poly_->getSimilarityThreshold (); + } + + /** \brief Set the required inlier fraction (of the input) + * \param inlier_fraction required inlier fraction, must be in [0,1] + */ + inline void + setInlierFraction (float inlier_fraction) + { + inlier_fraction_ = inlier_fraction; + } + + /** \brief Get the required inlier fraction + * \return required inlier fraction in [0,1] + */ + inline float + getInlierFraction () const + { + return inlier_fraction_; + } + + /** \brief Get the inlier indices of the source point cloud under the final transformation + * @return inlier indices + */ + inline const std::vector& + getInliers () const + { + return inliers_; + } + + protected: + /** \brief Choose a random index between 0 and n-1 + * \param n the number of possible indices to choose from + */ + inline int + getRandomIndex (int n) const + { + return (static_cast (n * (rand () / (RAND_MAX + 1.0)))); + }; + + /** \brief Select \a nr_samples sample points from cloud while making sure that their pairwise distances are + * greater than a user-defined minimum distance, \a min_sample_distance. + * \param cloud the input point cloud + * \param nr_samples the number of samples to select + * \param sample_indices the resulting sample indices + */ + void + selectSamples (const PointCloudSource &cloud, int nr_samples, std::vector &sample_indices); + + /** \brief For each of the sample points, find a list of points in the target cloud whose features are similar to + * the sample points' features. From these, select one randomly which will be considered that sample point's + * correspondence. + * \param sample_indices the indices of each sample point + * \param similar_features correspondence cache, which is used to read/write already computed correspondences + * \param corresponding_indices the resulting indices of each sample's corresponding point in the target cloud + */ + void + findSimilarFeatures (const std::vector &sample_indices, + std::vector >& similar_features, + std::vector &corresponding_indices); + + /** \brief Rigid transformation computation method. + * \param output the transformed input point cloud dataset using the rigid transformation found + * \param guess The computed transformation + */ + void + computeTransformation (PointCloudSource &output, const Eigen::Matrix4f& guess); + + /** \brief Obtain the fitness of a transformation + * The following metrics are calculated, based on + * \b final_transformation_ and \b corr_dist_threshold_: + * - Inliers: the number of transformed points which are closer than threshold to NN + * - Error score: the MSE of the inliers + * \param inliers indices of source point cloud inliers + * \param fitness_score output fitness score as RMSE + */ + void + getFitness (std::vector& inliers, float& fitness_score); + + /** \brief The source point cloud's feature descriptors. */ + FeatureCloudConstPtr input_features_; + + /** \brief The target point cloud's feature descriptors. */ + FeatureCloudConstPtr target_features_; + + /** \brief The number of samples to use during each iteration. */ + int nr_samples_; + + /** \brief The number of neighbors to use when selecting a random feature correspondence. */ + int k_correspondences_; + + /** \brief The KdTree used to compare feature descriptors. */ + FeatureKdTreePtr feature_tree_; + + /** \brief The polygonal correspondence rejector used for prerejection */ + CorrespondenceRejectorPolyPtr correspondence_rejector_poly_; + + /** \brief The fraction [0,1] of inlier points required for accepting a transformation */ + float inlier_fraction_; + + /** \brief Inlier points of final transformation as indices into source */ + std::vector inliers_; + }; +} + +#include + +#endif diff --git a/pcl-1.7/pcl/registration/transformation_estimation.h b/pcl-1.7/pcl/registration/transformation_estimation.h new file mode 100644 index 0000000..1ad3b43 --- /dev/null +++ b/pcl-1.7/pcl/registration/transformation_estimation.h @@ -0,0 +1,129 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_H_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_H_ + +#include +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief TransformationEstimation represents the base class for methods for transformation estimation based on: + * - correspondence vectors + * - two point clouds (source and target) of the same size + * - a point cloud with a set of indices (source), and another point cloud (target) + * - two point clouds with two sets of indices (source and target) of the same size + * + * \note The class is templated on the source and target point types as well as on the output scalar of the transformation matrix (i.e., float or double). Default: float. + * \author Dirk Holz, Radu B. Rusu + * \ingroup registration + */ + template + class TransformationEstimation + { + public: + typedef Eigen::Matrix Matrix4; + + TransformationEstimation () {}; + virtual ~TransformationEstimation () {}; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud. + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + virtual void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const = 0; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + virtual void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const = 0; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the interst points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix + */ + virtual void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const = 0; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud. + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] correspondences the vector of correspondences between source and target point cloud + * \param[out] transformation_matrix the resultant transformation matrix + */ + virtual void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const = 0; + + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + }; + } +} + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_H_ */ diff --git a/pcl-1.7/pcl/registration/transformation_estimation_2D.h b/pcl-1.7/pcl/registration/transformation_estimation_2D.h new file mode 100644 index 0000000..9ed9c01 --- /dev/null +++ b/pcl-1.7/pcl/registration/transformation_estimation_2D.h @@ -0,0 +1,155 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_2D_H_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_2D_H_ + +#include + +namespace pcl +{ + namespace registration + { + /** @b TransformationEstimation2D implements a simple 2D rigid transformation + * estimation (x, y, theta) for a given pair of datasets. + * + * The two datasets should already be transformed so that the reference plane + * equals z = 0. + * + * \note The class is templated on the source and target point types as well as on the output scalar of the transformation matrix (i.e., float or double). Default: float. + * + * \author Suat Gedikli + * \ingroup registration + */ + template + class TransformationEstimation2D : public TransformationEstimation + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename TransformationEstimation::Matrix4 Matrix4; + + TransformationEstimation2D () {}; + virtual ~TransformationEstimation2D () {}; + + /** \brief Estimate a rigid transformation between a source and a target point cloud in 2D. + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid transformation between a source and a target point cloud in 2D. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid transformation between a source and a target point cloud in 2D. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the interst points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix + */ + virtual void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid transformation between a source and a target point cloud in 2D. + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] correspondences the vector of correspondences between source and target point cloud + * \param[out] transformation_matrix the resultant transformation matrix + */ + virtual void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const; + + protected: + + /** \brief Estimate a rigid rotation transformation between a source and a target + * \param[in] source_it an iterator over the source point cloud dataset + * \param[in] target_it an iterator over the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + void + estimateRigidTransformation (ConstCloudIterator& source_it, + ConstCloudIterator& target_it, + Matrix4 &transformation_matrix) const; + + /** \brief Obtain a 4x4 rigid transformation matrix from a correlation matrix H = src * tgt' + * \param[in] cloud_src_demean the input source cloud, demeaned, in Eigen format + * \param[in] centroid_src the input source centroid, in Eigen format + * \param[in] cloud_tgt_demean the input target cloud, demeaned, in Eigen format + * \param[in] centroid_tgt the input target cloud, in Eigen format + * \param[out] transformation_matrix the resultant 4x4 rigid transformation matrix + */ + void + getTransformationFromCorrelation ( + const Eigen::Matrix &cloud_src_demean, + const Eigen::Matrix ¢roid_src, + const Eigen::Matrix &cloud_tgt_demean, + const Eigen::Matrix ¢roid_tgt, + Matrix4 &transformation_matrix) const; + }; + + } +} + +#include + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_2D_H_ */ diff --git a/pcl-1.7/pcl/registration/transformation_estimation_dual_quaternion.h b/pcl-1.7/pcl/registration/transformation_estimation_dual_quaternion.h new file mode 100644 index 0000000..6ca1efd --- /dev/null +++ b/pcl-1.7/pcl/registration/transformation_estimation_dual_quaternion.h @@ -0,0 +1,142 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_H_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_H_ + +#include +#include + +namespace pcl +{ + namespace registration + { + /** @b TransformationEstimationDualQuaternion implements dual quaternion based estimation of + * the transformation aligning the given correspondences. + * + * \note The class is templated on the source and target point types as well as on the output scalar of the transformation matrix (i.e., float or double). Default: float. + * \author Sergey Zagoruyko + * \ingroup registration + */ + template + class TransformationEstimationDualQuaternion : public TransformationEstimation + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename TransformationEstimation::Matrix4 Matrix4; + + TransformationEstimationDualQuaternion () {}; + virtual ~TransformationEstimationDualQuaternion () {}; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using + * dual quaternion optimization + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using + * dual quaternion optimization + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using + * dual quaternion optimization + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the interst points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using + * dual quaternion optimization + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] correspondences the vector of correspondences between source and target point cloud + * \param[out] transformation_matrix the resultant transformation matrix + */ + void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const; + + protected: + + /** \brief Estimate a rigid rotation transformation between a source and a target + * \param[in] source_it an iterator over the source point cloud dataset + * \param[in] target_it an iterator over the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + void + estimateRigidTransformation (ConstCloudIterator& source_it, + ConstCloudIterator& target_it, + Matrix4 &transformation_matrix) const; + }; + + } +} + +#include + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_H_ */ diff --git a/pcl-1.7/pcl/registration/transformation_estimation_lm.h b/pcl-1.7/pcl/registration/transformation_estimation_lm.h new file mode 100644 index 0000000..7f3e43b --- /dev/null +++ b/pcl-1.7/pcl/registration/transformation_estimation_lm.h @@ -0,0 +1,356 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_LM_H_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_LM_H_ + +#include +#include +#include + +namespace pcl +{ + namespace registration + { + /** @b TransformationEstimationLM implements Levenberg Marquardt-based + * estimation of the transformation aligning the given correspondences. + * + * \note The class is templated on the source and target point types as well as on the output scalar of the transformation matrix (i.e., float or double). Default: float. + * \author Radu B. Rusu + * \ingroup registration + */ + template + class TransformationEstimationLM : public TransformationEstimation + { + typedef pcl::PointCloud PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef pcl::PointCloud PointCloudTarget; + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef Eigen::Matrix VectorX; + typedef Eigen::Matrix Vector4; + typedef typename TransformationEstimation::Matrix4 Matrix4; + + /** \brief Constructor. */ + TransformationEstimationLM (); + + /** \brief Copy constructor. + * \param[in] src the TransformationEstimationLM object to copy into this + */ + TransformationEstimationLM (const TransformationEstimationLM &src) : + tmp_src_ (src.tmp_src_), + tmp_tgt_ (src.tmp_tgt_), + tmp_idx_src_ (src.tmp_idx_src_), + tmp_idx_tgt_ (src.tmp_idx_tgt_), + warp_point_ (src.warp_point_) + {}; + + /** \brief Copy operator. + * \param[in] src the TransformationEstimationLM object to copy into this + */ + TransformationEstimationLM& + operator = (const TransformationEstimationLM &src) + { + tmp_src_ = src.tmp_src_; + tmp_tgt_ = src.tmp_tgt_; + tmp_idx_src_ = src.tmp_idx_src_; + tmp_idx_tgt_ = src.tmp_idx_tgt_; + warp_point_ = src.warp_point_; + } + + /** \brief Destructor. */ + virtual ~TransformationEstimationLM () {}; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using LM. + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using LM. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using LM. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the interst points from + * \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using LM. + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] correspondences the vector of correspondences between source and target point cloud + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const; + + /** \brief Set the function we use to warp points. Defaults to rigid 6D warp. + * \param[in] warp_fcn a shared pointer to an object that warps points + */ + void + setWarpFunction (const boost::shared_ptr > &warp_fcn) + { + warp_point_ = warp_fcn; + } + + protected: + /** \brief Compute the distance between a source point and its corresponding target point + * \param[in] p_src The source point + * \param[in] p_tgt The target point + * \return The distance between \a p_src and \a p_tgt + * + * \note Older versions of PCL used this method internally for calculating the + * optimization gradient. Since PCL 1.7, a switch has been made to the + * computeDistance method using Vector4 types instead. This method is only + * kept for API compatibility reasons. + */ + virtual MatScalar + computeDistance (const PointSource &p_src, const PointTarget &p_tgt) const + { + Vector4 s (p_src.x, p_src.y, p_src.z, 0); + Vector4 t (p_tgt.x, p_tgt.y, p_tgt.z, 0); + return ((s - t).norm ()); + } + + /** \brief Compute the distance between a source point and its corresponding target point + * \param[in] p_src The source point + * \param[in] p_tgt The target point + * \return The distance between \a p_src and \a p_tgt + * + * \note A different distance function can be defined by creating a subclass of + * TransformationEstimationLM and overriding this method. + * (See \a TransformationEstimationPointToPlane) + */ + virtual MatScalar + computeDistance (const Vector4 &p_src, const PointTarget &p_tgt) const + { + Vector4 t (p_tgt.x, p_tgt.y, p_tgt.z, 0); + return ((p_src - t).norm ()); + } + + /** \brief Temporary pointer to the source dataset. */ + mutable const PointCloudSource *tmp_src_; + + /** \brief Temporary pointer to the target dataset. */ + mutable const PointCloudTarget *tmp_tgt_; + + /** \brief Temporary pointer to the source dataset indices. */ + mutable const std::vector *tmp_idx_src_; + + /** \brief Temporary pointer to the target dataset indices. */ + mutable const std::vector *tmp_idx_tgt_; + + /** \brief The parameterized function used to warp the source to the target. */ + boost::shared_ptr > warp_point_; + + /** Base functor all the models that need non linear optimization must + * define their own one and implement operator() (const Eigen::VectorXd& x, Eigen::VectorXd& fvec) + * or operator() (const Eigen::VectorXf& x, Eigen::VectorXf& fvec) dependening on the choosen _Scalar + */ + template + struct Functor + { + typedef _Scalar Scalar; + enum + { + InputsAtCompileTime = NX, + ValuesAtCompileTime = NY + }; + typedef Eigen::Matrix<_Scalar,InputsAtCompileTime,1> InputType; + typedef Eigen::Matrix<_Scalar,ValuesAtCompileTime,1> ValueType; + typedef Eigen::Matrix<_Scalar,ValuesAtCompileTime,InputsAtCompileTime> JacobianType; + + /** \brief Empty Construtor. */ + Functor () : m_data_points_ (ValuesAtCompileTime) {} + + /** \brief Constructor + * \param[in] m_data_points number of data points to evaluate. + */ + Functor (int m_data_points) : m_data_points_ (m_data_points) {} + + /** \brief Destructor. */ + virtual ~Functor () {} + + /** \brief Get the number of values. */ + int + values () const { return (m_data_points_); } + + protected: + int m_data_points_; + }; + + struct OptimizationFunctor : public Functor + { + using Functor::values; + + /** Functor constructor + * \param[in] m_data_points the number of data points to evaluate + * \param[in,out] estimator pointer to the estimator object + */ + OptimizationFunctor (int m_data_points, + const TransformationEstimationLM *estimator) + : Functor (m_data_points), estimator_ (estimator) + {} + + /** Copy constructor + * \param[in] src the optimization functor to copy into this + */ + inline OptimizationFunctor (const OptimizationFunctor &src) : + Functor (src.m_data_points_), estimator_ () + { + *this = src; + } + + /** Copy operator + * \param[in] src the optimization functor to copy into this + */ + inline OptimizationFunctor& + operator = (const OptimizationFunctor &src) + { + Functor::operator=(src); + estimator_ = src.estimator_; + return (*this); + } + + /** \brief Destructor. */ + virtual ~OptimizationFunctor () {} + + /** Fill fvec from x. For the current state vector x fill the f values + * \param[in] x state vector + * \param[out] fvec f values vector + */ + int + operator () (const VectorX &x, VectorX &fvec) const; + + const TransformationEstimationLM *estimator_; + }; + + struct OptimizationFunctorWithIndices : public Functor + { + using Functor::values; + + /** Functor constructor + * \param[in] m_data_points the number of data points to evaluate + * \param[in,out] estimator pointer to the estimator object + */ + OptimizationFunctorWithIndices (int m_data_points, + const TransformationEstimationLM *estimator) + : Functor (m_data_points), estimator_ (estimator) + {} + + /** Copy constructor + * \param[in] src the optimization functor to copy into this + */ + inline OptimizationFunctorWithIndices (const OptimizationFunctorWithIndices &src) + : Functor (src.m_data_points_), estimator_ () + { + *this = src; + } + + /** Copy operator + * \param[in] src the optimization functor to copy into this + */ + inline OptimizationFunctorWithIndices& + operator = (const OptimizationFunctorWithIndices &src) + { + Functor::operator=(src); + estimator_ = src.estimator_; + return (*this); + } + + /** \brief Destructor. */ + virtual ~OptimizationFunctorWithIndices () {} + + /** Fill fvec from x. For the current state vector x fill the f values + * \param[in] x state vector + * \param[out] fvec f values vector + */ + int + operator () (const VectorX &x, VectorX &fvec) const; + + const TransformationEstimationLM *estimator_; + }; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } +} + +#include + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_LM_H_ */ + diff --git a/pcl-1.7/pcl/registration/transformation_estimation_point_to_plane.h b/pcl-1.7/pcl/registration/transformation_estimation_point_to_plane.h new file mode 100644 index 0000000..9b6c00d --- /dev/null +++ b/pcl-1.7/pcl/registration/transformation_estimation_point_to_plane.h @@ -0,0 +1,101 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_H_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_H_ + +#include +#include +#include + +namespace pcl +{ + namespace registration + { + /** @b TransformationEstimationPointToPlane uses Levenberg Marquardt optimization to find the + * transformation that minimizes the point-to-plane distance between the given correspondences. + * + * \author Michael Dixon + * \ingroup registration + */ + template + class TransformationEstimationPointToPlane : public TransformationEstimationLM + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef pcl::PointCloud PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + typedef pcl::PointCloud PointCloudTarget; + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + typedef Eigen::Matrix Vector4; + + TransformationEstimationPointToPlane () {}; + virtual ~TransformationEstimationPointToPlane () {}; + + protected: + virtual Scalar + computeDistance (const PointSource &p_src, const PointTarget &p_tgt) const + { + // Compute the point-to-plane distance + Vector4 s (p_src.x, p_src.y, p_src.z, 0); + Vector4 t (p_tgt.x, p_tgt.y, p_tgt.z, 0); + Vector4 n (p_tgt.normal_x, p_tgt.normal_y, p_tgt.normal_z, 0); + return ((s - t).dot (n)); + } + + virtual Scalar + computeDistance (const Vector4 &p_src, const PointTarget &p_tgt) const + { + // Compute the point-to-plane distance + Vector4 t (p_tgt.x, p_tgt.y, p_tgt.z, 0); + Vector4 n (p_tgt.normal_x, p_tgt.normal_y, p_tgt.normal_z, 0); + return ((p_src - t).dot (n)); + } + + }; + } +} + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_H_ */ + diff --git a/pcl-1.7/pcl/registration/transformation_estimation_point_to_plane_lls.h b/pcl-1.7/pcl/registration/transformation_estimation_point_to_plane_lls.h new file mode 100644 index 0000000..04d3583 --- /dev/null +++ b/pcl-1.7/pcl/registration/transformation_estimation_point_to_plane_lls.h @@ -0,0 +1,158 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_H_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_H_ + +#include +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief @b TransformationEstimationPointToPlaneLLS implements a Linear Least Squares (LLS) approximation + * for minimizing the point-to-plane distance between two clouds of corresponding points with normals. + * + * For additional details, see + * "Linear Least-Squares Optimization for Point-to-Plane ICP Surface Registration", Kok-Lim Low, 2004 + * + * \note The class is templated on the source and target point types as well as on the output scalar of the + * transformation matrix (i.e., float or double). Default: float. + * \author Michael Dixon + * \ingroup registration + */ + template + class TransformationEstimationPointToPlaneLLS : public TransformationEstimation + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename TransformationEstimation::Matrix4 Matrix4; + + TransformationEstimationPointToPlaneLLS () {}; + virtual ~TransformationEstimationPointToPlaneLLS () {}; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using SVD. + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using SVD. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using SVD. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the interst points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using SVD. + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] correspondences the vector of correspondences between source and target point cloud + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const; + + protected: + + /** \brief Estimate a rigid rotation transformation between a source and a target + * \param[in] source_it an iterator over the source point cloud dataset + * \param[in] target_it an iterator over the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + void + estimateRigidTransformation (ConstCloudIterator& source_it, + ConstCloudIterator& target_it, + Matrix4 &transformation_matrix) const; + + /** \brief Construct a 4 by 4 tranformation matrix from the provided rotation and translation. + * \param[in] alpha the rotation about the x-axis + * \param[in] beta the rotation about the y-axis + * \param[in] gamma the rotation about the z-axis + * \param[in] tx the x translation + * \param[in] ty the y translation + * \param[in] tz the z translation + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + constructTransformationMatrix (const double & alpha, const double & beta, const double & gamma, + const double & tx, const double & ty, const double & tz, + Matrix4 &transformation_matrix) const; + + }; + } +} + +#include + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_H_LLS_ */ diff --git a/pcl-1.7/pcl/registration/transformation_estimation_point_to_plane_lls_weighted.h b/pcl-1.7/pcl/registration/transformation_estimation_point_to_plane_lls_weighted.h new file mode 100644 index 0000000..33d8866 --- /dev/null +++ b/pcl-1.7/pcl/registration/transformation_estimation_point_to_plane_lls_weighted.h @@ -0,0 +1,169 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_WEIGHTED_H_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_WEIGHTED_H_ + +#include +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief @b TransformationEstimationPointToPlaneLLSWeighted implements a Linear Least Squares (LLS) approximation + * for minimizing the point-to-plane distance between two clouds of corresponding points with normals, with the + * possibility of assigning weights to the correspondences. + * + * For additional details, see + * "Linear Least-Squares Optimization for Point-to-Plane ICP Surface Registration", Kok-Lim Low, 2004 + * + * \note The class is templated on the source and target point types as well as on the output scalar of the + * transformation matrix (i.e., float or double). Default: float. + * \author Alex Ichim + * \ingroup registration + */ + template + class TransformationEstimationPointToPlaneLLSWeighted : public TransformationEstimation + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename TransformationEstimation::Matrix4 Matrix4; + + TransformationEstimationPointToPlaneLLSWeighted () { }; + virtual ~TransformationEstimationPointToPlaneLLSWeighted () { }; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using SVD. + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using SVD. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using SVD. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the interst points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using SVD. + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] correspondences the vector of correspondences between source and target point cloud + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const; + + + /** \brief Set the weights for the correspondences. + * \param[in] weights the weights for each correspondence + */ + inline void + setCorrespondenceWeights (const std::vector &weights) + { weights_ = weights; } + + protected: + + /** \brief Estimate a rigid rotation transformation between a source and a target + * \param[in] source_it an iterator over the source point cloud dataset + * \param[in] target_it an iterator over the target point cloud dataset + * \param weights_it + * \param[out] transformation_matrix the resultant transformation matrix + */ + void + estimateRigidTransformation (ConstCloudIterator& source_it, + ConstCloudIterator& target_it, + typename std::vector::const_iterator& weights_it, + Matrix4 &transformation_matrix) const; + + /** \brief Construct a 4 by 4 tranformation matrix from the provided rotation and translation. + * \param[in] alpha the rotation about the x-axis + * \param[in] beta the rotation about the y-axis + * \param[in] gamma the rotation about the z-axis + * \param[in] tx the x translation + * \param[in] ty the y translation + * \param[in] tz the z translation + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + constructTransformationMatrix (const double & alpha, const double & beta, const double & gamma, + const double & tx, const double & ty, const double & tz, + Matrix4 &transformation_matrix) const; + + std::vector weights_; + }; + } +} + +#include + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_WEIGHTED_H_ */ diff --git a/pcl-1.7/pcl/registration/transformation_estimation_point_to_plane_weighted.h b/pcl-1.7/pcl/registration/transformation_estimation_point_to_plane_weighted.h new file mode 100644 index 0000000..3013d67 --- /dev/null +++ b/pcl-1.7/pcl/registration/transformation_estimation_point_to_plane_weighted.h @@ -0,0 +1,341 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) Alexandru-Eugen Ichim + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + + +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_WEIGHTED_H_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_WEIGHTED_H_ + +#include +#include +#include + +namespace pcl +{ + namespace registration + { + /** @b TransformationEstimationPointToPlaneWeighted uses Levenberg Marquardt optimization to find the transformation + * that minimizes the point-to-plane distance between the given correspondences. In addition to the + * TransformationEstimationPointToPlane class, this version takes per-correspondence weights and optimizes accordingly. + * + * \author Alexandru-Eugen Ichim + * \ingroup registration + */ + template + class TransformationEstimationPointToPlaneWeighted : public TransformationEstimationPointToPlane + { + typedef pcl::PointCloud PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef pcl::PointCloud PointCloudTarget; + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef Eigen::Matrix VectorX; + typedef Eigen::Matrix Vector4; + typedef typename TransformationEstimation::Matrix4 Matrix4; + + /** \brief Constructor. */ + TransformationEstimationPointToPlaneWeighted (); + + /** \brief Copy constructor. + * \param[in] src the TransformationEstimationPointToPlaneWeighted object to copy into this + */ + TransformationEstimationPointToPlaneWeighted (const TransformationEstimationPointToPlaneWeighted &src) : + tmp_src_ (src.tmp_src_), + tmp_tgt_ (src.tmp_tgt_), + tmp_idx_src_ (src.tmp_idx_src_), + tmp_idx_tgt_ (src.tmp_idx_tgt_), + warp_point_ (src.warp_point_), + correspondence_weights_ (src.correspondence_weights_), + use_correspondence_weights_ (src.use_correspondence_weights_) + {}; + + /** \brief Copy operator. + * \param[in] src the TransformationEstimationPointToPlaneWeighted object to copy into this + */ + TransformationEstimationPointToPlaneWeighted& + operator = (const TransformationEstimationPointToPlaneWeighted &src) + { + tmp_src_ = src.tmp_src_; + tmp_tgt_ = src.tmp_tgt_; + tmp_idx_src_ = src.tmp_idx_src_; + tmp_idx_tgt_ = src.tmp_idx_tgt_; + warp_point_ = src.warp_point_; + correspondence_weights_ = src.correspondence_weights_; + use_correspondence_weights_ = src.use_correspondence_weights_; + } + + /** \brief Destructor. */ + virtual ~TransformationEstimationPointToPlaneWeighted () {}; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using LM. + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + * \note Uses the weights given by setWeights. + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using LM. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + * \note Uses the weights given by setWeights. + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using LM. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the interst points from + * \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix + * \note Uses the weights given by setWeights. + */ + void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using LM. + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] correspondences the vector of correspondences between source and target point cloud + * \param[out] transformation_matrix the resultant transformation matrix + * \note Uses the weights given by setWeights. + */ + void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const; + + + inline void + setWeights (const std::vector &weights) + { correspondence_weights_ = weights; } + + /// use the weights given in the pcl::CorrespondencesPtr for one of the estimateTransformation (...) methods + inline void + setUseCorrespondenceWeights (bool use_correspondence_weights) + { use_correspondence_weights_ = use_correspondence_weights; } + + /** \brief Set the function we use to warp points. Defaults to rigid 6D warp. + * \param[in] warp_fcn a shared pointer to an object that warps points + */ + void + setWarpFunction (const boost::shared_ptr > &warp_fcn) + { warp_point_ = warp_fcn; } + + protected: + bool use_correspondence_weights_; + mutable std::vector correspondence_weights_; + + /** \brief Temporary pointer to the source dataset. */ + mutable const PointCloudSource *tmp_src_; + + /** \brief Temporary pointer to the target dataset. */ + mutable const PointCloudTarget *tmp_tgt_; + + /** \brief Temporary pointer to the source dataset indices. */ + mutable const std::vector *tmp_idx_src_; + + /** \brief Temporary pointer to the target dataset indices. */ + mutable const std::vector *tmp_idx_tgt_; + + /** \brief The parameterized function used to warp the source to the target. */ + boost::shared_ptr > warp_point_; + + /** Base functor all the models that need non linear optimization must + * define their own one and implement operator() (const Eigen::VectorXd& x, Eigen::VectorXd& fvec) + * or operator() (const Eigen::VectorXf& x, Eigen::VectorXf& fvec) dependening on the choosen _Scalar + */ + template + struct Functor + { + typedef _Scalar Scalar; + enum + { + InputsAtCompileTime = NX, + ValuesAtCompileTime = NY + }; + typedef Eigen::Matrix<_Scalar,InputsAtCompileTime,1> InputType; + typedef Eigen::Matrix<_Scalar,ValuesAtCompileTime,1> ValueType; + typedef Eigen::Matrix<_Scalar,ValuesAtCompileTime,InputsAtCompileTime> JacobianType; + + /** \brief Empty Construtor. */ + Functor () : m_data_points_ (ValuesAtCompileTime) {} + + /** \brief Constructor + * \param[in] m_data_points number of data points to evaluate. + */ + Functor (int m_data_points) : m_data_points_ (m_data_points) {} + + /** \brief Destructor. */ + virtual ~Functor () {} + + /** \brief Get the number of values. */ + int + values () const { return (m_data_points_); } + + protected: + int m_data_points_; + }; + + struct OptimizationFunctor : public Functor + { + using Functor::values; + + /** Functor constructor + * \param[in] m_data_points the number of data points to evaluate + * \param[in,out] estimator pointer to the estimator object + */ + OptimizationFunctor (int m_data_points, + const TransformationEstimationPointToPlaneWeighted *estimator) + : Functor (m_data_points), estimator_ (estimator) + {} + + /** Copy constructor + * \param[in] src the optimization functor to copy into this + */ + inline OptimizationFunctor (const OptimizationFunctor &src) : + Functor (src.m_data_points_), estimator_ () + { + *this = src; + } + + /** Copy operator + * \param[in] src the optimization functor to copy into this + */ + inline OptimizationFunctor& + operator = (const OptimizationFunctor &src) + { + Functor::operator=(src); + estimator_ = src.estimator_; + return (*this); + } + + /** \brief Destructor. */ + virtual ~OptimizationFunctor () {} + + /** Fill fvec from x. For the current state vector x fill the f values + * \param[in] x state vector + * \param[out] fvec f values vector + */ + int + operator () (const VectorX &x, VectorX &fvec) const; + + const TransformationEstimationPointToPlaneWeighted *estimator_; + }; + + struct OptimizationFunctorWithIndices : public Functor + { + using Functor::values; + + /** Functor constructor + * \param[in] m_data_points the number of data points to evaluate + * \param[in,out] estimator pointer to the estimator object + */ + OptimizationFunctorWithIndices (int m_data_points, + const TransformationEstimationPointToPlaneWeighted *estimator) + : Functor (m_data_points), estimator_ (estimator) + {} + + /** Copy constructor + * \param[in] src the optimization functor to copy into this + */ + inline OptimizationFunctorWithIndices (const OptimizationFunctorWithIndices &src) + : Functor (src.m_data_points_), estimator_ () + { + *this = src; + } + + /** Copy operator + * \param[in] src the optimization functor to copy into this + */ + inline OptimizationFunctorWithIndices& + operator = (const OptimizationFunctorWithIndices &src) + { + Functor::operator=(src); + estimator_ = src.estimator_; + return (*this); + } + + /** \brief Destructor. */ + virtual ~OptimizationFunctorWithIndices () {} + + /** Fill fvec from x. For the current state vector x fill the f values + * \param[in] x state vector + * \param[out] fvec f values vector + */ + int + operator () (const VectorX &x, VectorX &fvec) const; + + const TransformationEstimationPointToPlaneWeighted *estimator_; + }; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } +} + +#include + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_WEIGHTED_H_ */ + diff --git a/pcl-1.7/pcl/registration/transformation_estimation_svd.h b/pcl-1.7/pcl/registration/transformation_estimation_svd.h new file mode 100644 index 0000000..c503068 --- /dev/null +++ b/pcl-1.7/pcl/registration/transformation_estimation_svd.h @@ -0,0 +1,161 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_H_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_H_ + +#include +#include + +namespace pcl +{ + namespace registration + { + /** @b TransformationEstimationSVD implements SVD-based estimation of + * the transformation aligning the given correspondences. + * + * \note The class is templated on the source and target point types as well as on the output scalar of the transformation matrix (i.e., float or double). Default: float. + * \author Dirk Holz, Radu B. Rusu + * \ingroup registration + */ + template + class TransformationEstimationSVD : public TransformationEstimation + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename TransformationEstimation::Matrix4 Matrix4; + + /** \brief Constructor + * \param[in] use_umeyama Toggles whether or not to use 3rd party software*/ + TransformationEstimationSVD (bool use_umeyama=true): + use_umeyama_ (use_umeyama) + {} + + virtual ~TransformationEstimationSVD () {}; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using SVD. + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using SVD. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using SVD. + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the interst points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix + */ + inline void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Matrix4 &transformation_matrix) const; + + /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using SVD. + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] correspondences the vector of correspondences between source and target point cloud + * \param[out] transformation_matrix the resultant transformation matrix + */ + void + estimateRigidTransformation ( + const pcl::PointCloud &cloud_src, + const pcl::PointCloud &cloud_tgt, + const pcl::Correspondences &correspondences, + Matrix4 &transformation_matrix) const; + + protected: + + /** \brief Estimate a rigid rotation transformation between a source and a target + * \param[in] source_it an iterator over the source point cloud dataset + * \param[in] target_it an iterator over the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + */ + void + estimateRigidTransformation (ConstCloudIterator& source_it, + ConstCloudIterator& target_it, + Matrix4 &transformation_matrix) const; + + /** \brief Obtain a 4x4 rigid transformation matrix from a correlation matrix H = src * tgt' + * \param[in] cloud_src_demean the input source cloud, demeaned, in Eigen format + * \param[in] centroid_src the input source centroid, in Eigen format + * \param[in] cloud_tgt_demean the input target cloud, demeaned, in Eigen format + * \param[in] centroid_tgt the input target cloud, in Eigen format + * \param[out] transformation_matrix the resultant 4x4 rigid transformation matrix + */ + virtual void + getTransformationFromCorrelation ( + const Eigen::Matrix &cloud_src_demean, + const Eigen::Matrix ¢roid_src, + const Eigen::Matrix &cloud_tgt_demean, + const Eigen::Matrix ¢roid_tgt, + Matrix4 &transformation_matrix) const; + + bool use_umeyama_; + }; + + } +} + +#include + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_H_ */ diff --git a/pcl-1.7/pcl/registration/transformation_estimation_svd_scale.h b/pcl-1.7/pcl/registration/transformation_estimation_svd_scale.h new file mode 100644 index 0000000..045c830 --- /dev/null +++ b/pcl-1.7/pcl/registration/transformation_estimation_svd_scale.h @@ -0,0 +1,92 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_SCALE_H_ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_SCALE_H_ + +#include + +namespace pcl +{ + namespace registration + { + /** @b TransformationEstimationSVD implements SVD-based estimation of + * the transformation aligning the given correspondences. + * Optionally the scale is estimated. Note that the similarity transform might not be optimal for the underlying Frobenius Norm. + * + * \note The class is templated on the source and target point types as well as on the output scalar of the transformation matrix (i.e., float or double). Default: float. + * \author Suat Gedikli + * \ingroup registration + */ + template + class TransformationEstimationSVDScale : public TransformationEstimationSVD + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename TransformationEstimationSVD::Matrix4 Matrix4; + + /** \brief Inherits from TransformationEstimationSVD, but forces it to not use the Umeyama method */ + TransformationEstimationSVDScale (): + TransformationEstimationSVD (false) + {} + + protected: + /** \brief Obtain a 4x4 rigid transformation matrix from a correlation matrix H = src * tgt' + * \param[in] cloud_src_demean the input source cloud, demeaned, in Eigen format + * \param[in] centroid_src the input source centroid, in Eigen format + * \param[in] cloud_tgt_demean the input target cloud, demeaned, in Eigen format + * \param[in] centroid_tgt the input target cloud, in Eigen format + * \param[out] transformation_matrix the resultant 4x4 rigid transformation matrix + */ + void + getTransformationFromCorrelation (const Eigen::Matrix &cloud_src_demean, + const Eigen::Matrix ¢roid_src, + const Eigen::Matrix &cloud_tgt_demean, + const Eigen::Matrix ¢roid_tgt, + Matrix4 &transformation_matrix) const; + }; + + } +} + +#include + +#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_SCALE_H_ */ diff --git a/pcl-1.7/pcl/registration/transformation_validation.h b/pcl-1.7/pcl/registration/transformation_validation.h new file mode 100644 index 0000000..9db6d17 --- /dev/null +++ b/pcl-1.7/pcl/registration/transformation_validation.h @@ -0,0 +1,131 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_VALIDATION_H_ +#define PCL_REGISTRATION_TRANSFORMATION_VALIDATION_H_ + +#include +#include +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief TransformationValidation represents the base class for methods + * that validate the correctness of a transformation found through \ref TransformationEstimation. + * + * The inputs for a validation estimation can take any or all of the following: + * + * - source point cloud + * - target point cloud + * - estimated transformation between source and target + * + * The output is in the form of a score or a confidence measure. + * + * \note The class is templated on the source and target point types as well as on the output scalar of the transformation matrix (i.e., float or double). Default: float. + * \author Radu B. Rusu + * \ingroup registration + */ + template + class TransformationValidation + { + public: + typedef Eigen::Matrix Matrix4; + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef pcl::PointCloud PointCloudSource; + typedef typename PointCloudSource::Ptr PointCloudSourcePtr; + typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; + + typedef pcl::PointCloud PointCloudTarget; + typedef typename PointCloudTarget::Ptr PointCloudTargetPtr; + typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr; + + TransformationValidation () {}; + virtual ~TransformationValidation () {}; + + /** \brief Validate the given transformation with respect to the input cloud data, and return a score. Pure virtual. + * + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the transformation matrix + * + * \return the score or confidence measure for the given + * transformation_matrix with respect to the input data + */ + virtual double + validateTransformation ( + const PointCloudSourceConstPtr &cloud_src, + const PointCloudTargetConstPtr &cloud_tgt, + const Matrix4 &transformation_matrix) const = 0; + + /** \brief Comparator function for deciding which score is better after running the + * validation on multiple transforms. Pure virtual. + * + * \note For example, for Euclidean distances smaller is better, for inliers the oposite. + * + * \param[in] score1 the first value + * \param[in] score2 the second value + * + * \return true if score1 is better than score2 + */ + virtual bool + operator() (const double &score1, const double &score2) const = 0; + + /** \brief Check if the score is valid for a specific transformation. Pure virtual. + * + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the transformation matrix + * + * \return true if the transformation is valid, false otherwise. + */ + virtual bool + isValid ( + const PointCloudSourceConstPtr &cloud_src, + const PointCloudTargetConstPtr &cloud_tgt, + const Matrix4 &transformation_matrix) const = 0; + }; + } +} + +#endif // PCL_REGISTRATION_TRANSFORMATION_VALIDATION_H_ diff --git a/pcl-1.7/pcl/registration/transformation_validation_euclidean.h b/pcl-1.7/pcl/registration/transformation_validation_euclidean.h new file mode 100644 index 0000000..ce2d374 --- /dev/null +++ b/pcl-1.7/pcl/registration/transformation_validation_euclidean.h @@ -0,0 +1,270 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMATION_VALIDATION_EUCLIDEAN_H_ +#define PCL_REGISTRATION_TRANSFORMATION_VALIDATION_EUCLIDEAN_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief TransformationValidationEuclidean computes an L2SQR norm between a source and target + * dataset. + * + * To prevent points with bad correspondences to contribute to the overall score, the class also + * accepts a maximum_range parameter given via \ref setMaxRange that is used as a cutoff value for + * nearest neighbor distance comparisons. + * + * The output score is normalized with respect to the number of valid correspondences found. + * + * Usage example: + * \code + * pcl::TransformationValidationEuclidean tve; + * tve.setMaxRange (0.01); // 1cm + * double score = tve.validateTransformation (source, target, transformation); + * \endcode + * + * \note The class is templated on the source and target point types as well as on the output scalar of the transformation matrix (i.e., float or double). Default: float. + * \author Radu B. Rusu + * \ingroup registration + */ + template + class TransformationValidationEuclidean + { + public: + typedef typename TransformationValidation::Matrix4 Matrix4; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename pcl::search::KdTree KdTree; + typedef typename pcl::search::KdTree::Ptr KdTreePtr; + + typedef typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr; + + typedef typename TransformationValidation::PointCloudSourceConstPtr PointCloudSourceConstPtr; + typedef typename TransformationValidation::PointCloudTargetConstPtr PointCloudTargetConstPtr; + + /** \brief Constructor. + * Sets the \a max_range parameter to double::max, \a threshold_ to NaN + * and initializes the internal search \a tree to a FLANN kd-tree. + */ + TransformationValidationEuclidean () : + max_range_ (std::numeric_limits::max ()), + threshold_ (std::numeric_limits::quiet_NaN ()), + tree_ (new pcl::search::KdTree), + force_no_recompute_ (false) + { + } + + virtual ~TransformationValidationEuclidean () {}; + + /** \brief Set the maximum allowable distance between a point and its correspondence in the + * target in order for a correspondence to be considered \a valid. Default: double::max. + * \param[in] max_range the new maximum allowable distance + */ + inline void + setMaxRange (double max_range) + { + max_range_ = max_range; + } + + /** \brief Get the maximum allowable distance between a point and its + * correspondence, as set by the user. + */ + inline double + getMaxRange () + { + return (max_range_); + } + + + /** \brief Provide a pointer to the search object used to find correspondences in + * the target cloud. + * \param[in] tree a pointer to the spatial search object. + * \param[in] force_no_recompute If set to true, this tree will NEVER be + * recomputed, regardless of calls to setInputTarget. Only use if you are + * confident that the tree will be set correctly. + */ + inline void + setSearchMethodTarget (const KdTreePtr &tree, + bool force_no_recompute = false) + { + tree_ = tree; + if (force_no_recompute) + { + force_no_recompute_ = true; + } + } + + /** \brief Set a threshold for which a specific transformation is considered valid. + * + * \note Since we're using MSE (Mean Squared Error) as a metric, the threshold + * represents the mean Euclidean distance threshold over all nearest neighbors + * up to max_range. + * + * \param[in] threshold the threshold for which a transformation is vali + */ + inline void + setThreshold (double threshold) + { + threshold_ = threshold; + } + + /** \brief Get the threshold for which a specific transformation is valid. */ + inline double + getThreshold () + { + return (threshold_); + } + + /** \brief Validate the given transformation with respect to the input cloud data, and return a score. + * + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + * + * \return the score or confidence measure for the given + * transformation_matrix with respect to the input data + */ + double + validateTransformation ( + const PointCloudSourceConstPtr &cloud_src, + const PointCloudTargetConstPtr &cloud_tgt, + const Matrix4 &transformation_matrix) const; + + /** \brief Comparator function for deciding which score is better after running the + * validation on multiple transforms. + * + * \param[in] score1 the first value + * \param[in] score2 the second value + * + * \return true if score1 is better than score2 + */ + virtual bool + operator() (const double &score1, const double &score2) const + { + return (score1 < score2); + } + + /** \brief Check if the score is valid for a specific transformation. + * + * \param[in] cloud_src the source point cloud dataset + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the transformation matrix + * + * \return true if the transformation is valid, false otherwise. + */ + virtual bool + isValid ( + const PointCloudSourceConstPtr &cloud_src, + const PointCloudTargetConstPtr &cloud_tgt, + const Matrix4 &transformation_matrix) const + { + if (pcl_isnan (threshold_)) + { + PCL_ERROR ("[pcl::TransformationValidationEuclidean::isValid] Threshold not set! Please use setThreshold () before continuing."); + return (false); + } + + return (validateTransformation (cloud_src, cloud_tgt, transformation_matrix) < threshold_); + } + + protected: + /** \brief The maximum allowable distance between a point and its correspondence in the target + * in order for a correspondence to be considered \a valid. Default: double::max. + */ + double max_range_; + + /** \brief The threshold for which a specific transformation is valid. + * Set to NaN by default, as we must require the user to set it. + */ + double threshold_; + + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + + /** \brief A flag which, if set, means the tree operating on the target cloud + * will never be recomputed*/ + bool force_no_recompute_; + + + /** \brief Internal point representation uses only 3D coordinates for L2 */ + class MyPointRepresentation: public pcl::PointRepresentation + { + using pcl::PointRepresentation::nr_dimensions_; + using pcl::PointRepresentation::trivial_; + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + MyPointRepresentation () + { + nr_dimensions_ = 3; + trivial_ = true; + } + + /** \brief Empty destructor */ + virtual ~MyPointRepresentation () {} + + virtual void + copyToFloatArray (const PointTarget &p, float * out) const + { + out[0] = p.x; + out[1] = p.y; + out[2] = p.z; + } + }; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } +} + +#include + +#endif // PCL_REGISTRATION_TRANSFORMATION_VALIDATION_EUCLIDEAN_H_ + diff --git a/pcl-1.7/pcl/registration/transforms.h b/pcl-1.7/pcl/registration/transforms.h new file mode 100644 index 0000000..3937c83 --- /dev/null +++ b/pcl-1.7/pcl/registration/transforms.h @@ -0,0 +1,45 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_REGISTRATION_TRANSFORMS_H_ +#define PCL_REGISTRATION_TRANSFORMS_H_ + +#include + +#endif // PCL_REGISTRATION_TRANSFORMS_H_ diff --git a/pcl-1.7/pcl/registration/warp_point_rigid.h b/pcl-1.7/pcl/registration/warp_point_rigid.h new file mode 100644 index 0000000..efdcfa7 --- /dev/null +++ b/pcl-1.7/pcl/registration/warp_point_rigid.h @@ -0,0 +1,133 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_WARP_POINT_RIGID_H_ +#define PCL_WARP_POINT_RIGID_H_ + +#include + +namespace pcl +{ + namespace registration + { + /** \brief Base warp point class. + * + * \note The class is templated on the source and target point types as well as on the output scalar of the transformation matrix (i.e., float or double). Default: float. + * \author Radu B. Rusu + * \ingroup registration + */ + template + class WarpPointRigid + { + public: + typedef Eigen::Matrix Matrix4; + typedef Eigen::Matrix VectorX; + typedef Eigen::Matrix Vector4; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor + * \param[in] nr_dim the number of dimensions + */ + WarpPointRigid (int nr_dim) + : nr_dim_ (nr_dim) + , transform_matrix_ (Matrix4::Zero ()) + { + transform_matrix_ (3, 3) = 1.0; + }; + + /** \brief Destructor. */ + virtual ~WarpPointRigid () {}; + + /** \brief Set warp parameters. Pure virtual. + * \param[in] p warp parameters + */ + virtual void + setParam (const VectorX& p) = 0; + + /** \brief Warp a point given a transformation matrix + * \param[in] pnt_in the point to warp (transform) + * \param[out] pnt_out the warped (transformed) point + */ + inline void + warpPoint (const PointSourceT& pnt_in, PointSourceT& pnt_out) const + { + pnt_out.x = static_cast (transform_matrix_ (0, 0) * pnt_in.x + transform_matrix_ (0, 1) * pnt_in.y + transform_matrix_ (0, 2) * pnt_in.z + transform_matrix_ (0, 3)); + pnt_out.y = static_cast (transform_matrix_ (1, 0) * pnt_in.x + transform_matrix_ (1, 1) * pnt_in.y + transform_matrix_ (1, 2) * pnt_in.z + transform_matrix_ (1, 3)); + pnt_out.z = static_cast (transform_matrix_ (2, 0) * pnt_in.x + transform_matrix_ (2, 1) * pnt_in.y + transform_matrix_ (2, 2) * pnt_in.z + transform_matrix_ (2, 3)); + //pnt_out.getVector3fMap () = transform_matrix_.topLeftCorner (3, 3) * + // pnt_in.getVector3fMap () + + // transform_matrix_.block (0, 3, 3, 1); + //pnt_out.data[3] = pnt_in.data[3]; + } + + /** \brief Warp a point given a transformation matrix + * \param[in] pnt_in the point to warp (transform) + * \param[out] pnt_out the warped (transformed) point + */ + inline void + warpPoint (const PointSourceT& pnt_in, Vector4& pnt_out) const + { + pnt_out[0] = static_cast (transform_matrix_ (0, 0) * pnt_in.x + transform_matrix_ (0, 1) * pnt_in.y + transform_matrix_ (0, 2) * pnt_in.z + transform_matrix_ (0, 3)); + pnt_out[1] = static_cast (transform_matrix_ (1, 0) * pnt_in.x + transform_matrix_ (1, 1) * pnt_in.y + transform_matrix_ (1, 2) * pnt_in.z + transform_matrix_ (1, 3)); + pnt_out[2] = static_cast (transform_matrix_ (2, 0) * pnt_in.x + transform_matrix_ (2, 1) * pnt_in.y + transform_matrix_ (2, 2) * pnt_in.z + transform_matrix_ (2, 3)); + pnt_out[3] = 0.0; + } + + /** \brief Get the number of dimensions. */ + inline int + getDimension () const { return (nr_dim_); } + + /** \brief Get the Transform used. */ + inline const Matrix4& + getTransform () const { return (transform_matrix_); } + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + protected: + int nr_dim_; + Matrix4 transform_matrix_; + }; + } // namespace registration +} // namespace pcl + +#endif diff --git a/pcl-1.7/pcl/registration/warp_point_rigid_3d.h b/pcl-1.7/pcl/registration/warp_point_rigid_3d.h new file mode 100644 index 0000000..0a0731f --- /dev/null +++ b/pcl-1.7/pcl/registration/warp_point_rigid_3d.h @@ -0,0 +1,100 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + + +#ifndef PCL_WARP_POINT_RIGID_3D_H_ +#define PCL_WARP_POINT_RIGID_3D_H_ + +#include +#include + +namespace pcl +{ + namespace registration + { + /** \brief @b WarpPointRigid3D enables 3D (1D rotation + 2D translation) + * transformations for points. + * + * \note The class is templated on the source and target point types as well as on the output scalar of the transformation matrix (i.e., float or double). Default: float. + * \author Radu B. Rusu + * \ingroup registration + */ + template + class WarpPointRigid3D : public WarpPointRigid + { + public: + typedef typename WarpPointRigid::Matrix4 Matrix4; + typedef typename WarpPointRigid::VectorX VectorX; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + WarpPointRigid3D () : WarpPointRigid (3) {} + + /** \brief Empty destructor */ + virtual ~WarpPointRigid3D () {} + + /** \brief Set warp parameters. + * \param[in] p warp parameters (tx ty rz) + */ + virtual void + setParam (const VectorX & p) + { + assert (p.rows () == this->getDimension ()); + Matrix4 &trans = this->transform_matrix_; + + trans = Matrix4::Zero (); + trans (3, 3) = 1; + trans (2, 2) = 1; // Rotation around the Z-axis + + // Copy the rotation and translation components + trans.block (0, 3, 4, 1) = Eigen::Matrix (p[0], p[1], 0, 1.0); + + // Compute w from the unit quaternion + Eigen::Rotation2D r (p[2]); + trans.topLeftCorner (2, 2) = r.toRotationMatrix (); + } + }; + } +} + +#endif + diff --git a/pcl-1.7/pcl/registration/warp_point_rigid_6d.h b/pcl-1.7/pcl/registration/warp_point_rigid_6d.h new file mode 100644 index 0000000..84b1c0d --- /dev/null +++ b/pcl-1.7/pcl/registration/warp_point_rigid_6d.h @@ -0,0 +1,102 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + + +#ifndef PCL_WARP_POINT_RIGID_6D_H_ +#define PCL_WARP_POINT_RIGID_6D_H_ + +#include + +namespace pcl +{ + namespace registration + { + /** \brief @b WarpPointRigid3D enables 6D (3D rotation + 3D translation) + * transformations for points. + * + * \note The class is templated on the source and target point types as well as on the output scalar of the transformation matrix (i.e., float or double). Default: float. + * \author Radu B. Rusu + * \ingroup registration + */ + template + class WarpPointRigid6D : public WarpPointRigid + { + public: + using WarpPointRigid::transform_matrix_; + + typedef typename WarpPointRigid::Matrix4 Matrix4; + typedef typename WarpPointRigid::VectorX VectorX; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + WarpPointRigid6D () : WarpPointRigid (6) {} + + /** \brief Empty destructor */ + virtual ~WarpPointRigid6D () {} + + /** \brief Set warp parameters. + * \note Assumes the quaternion parameters are normalized. + * \param[in] p warp parameters (tx ty tz qx qy qz) + */ + virtual void + setParam (const VectorX& p) + { + assert (p.rows () == this->getDimension ()); + + // Copy the rotation and translation components + transform_matrix_.setZero (); + transform_matrix_ (0, 3) = p[0]; + transform_matrix_ (1, 3) = p[1]; + transform_matrix_ (2, 3) = p[2]; + transform_matrix_ (3, 3) = 1; + + // Compute w from the unit quaternion + Eigen::Quaternion q (0, p[3], p[4], p[5]); + q.w () = static_cast (sqrt (1 - q.dot (q))); + q.normalize (); + transform_matrix_.topLeftCorner (3, 3) = q.toRotationMatrix (); + } + }; + } +} + +#endif + diff --git a/pcl-1.7/pcl/ros/conversions.h b/pcl-1.7/pcl/ros/conversions.h new file mode 100644 index 0000000..41d47f9 --- /dev/null +++ b/pcl-1.7/pcl/ros/conversions.h @@ -0,0 +1,125 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_ROS_CONVERSIONS_H_ +#define PCL_ROS_CONVERSIONS_H_ + +#ifdef __DEPRECATED +#warning The header is deprecated. please use \ + instead. +#endif + +#include + +namespace pcl +{ + /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud object using a field_map. + * \param[in] msg the PCLPointCloud2 binary blob + * \param[out] cloud the resultant pcl::PointCloud + * \param[in] field_map a MsgFieldMap object + * + * \note Use fromROSMsg (PCLPointCloud2, PointCloud) directly or create you + * own MsgFieldMap using: + * + * \code + * MsgFieldMap field_map; + * createMapping (msg.fields, field_map); + * \endcode + */ + template + PCL_DEPRECATED ("pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.") + void + fromROSMsg (const pcl::PCLPointCloud2& msg, pcl::PointCloud& cloud, + const MsgFieldMap& field_map) + { + fromPCLPointCloud2 (msg, cloud, field_map); + } + + /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud object. + * \param[in] msg the PCLPointCloud2 binary blob + * \param[out] cloud the resultant pcl::PointCloud + */ + template + PCL_DEPRECATED ("pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.") + void + fromROSMsg (const pcl::PCLPointCloud2& msg, pcl::PointCloud& cloud) + { + fromPCLPointCloud2 (msg, cloud); + } + + /** \brief Convert a pcl::PointCloud object to a PCLPointCloud2 binary data blob. + * \param[in] cloud the input pcl::PointCloud + * \param[out] msg the resultant PCLPointCloud2 binary blob + */ + template + PCL_DEPRECATED ("pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.") + void + toROSMsg (const pcl::PointCloud& cloud, pcl::PCLPointCloud2& msg) + { + toPCLPointCloud2 (cloud, msg); + } + + /** \brief Copy the RGB fields of a PointCloud into pcl::PCLImage format + * \param[in] cloud the point cloud message + * \param[out] msg the resultant pcl::PCLImage + * CloudT cloud type, CloudT should be akin to pcl::PointCloud + * \note will throw std::runtime_error if there is a problem + */ + template + PCL_DEPRECATED ("pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.") + void + toROSMsg (const CloudT& cloud, pcl::PCLImage& msg) + { + toPCLPointCloud2 (cloud, msg); + } + + /** \brief Copy the RGB fields of a PCLPointCloud2 msg into pcl::PCLImage format + * \param cloud the point cloud message + * \param msg the resultant pcl::PCLImage + * will throw std::runtime_error if there is a problem + */ + inline void + PCL_DEPRECATED ("pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.") + toROSMsg (const pcl::PCLPointCloud2& cloud, pcl::PCLImage& msg) + { + toPCLPointCloud2 (cloud, msg); + } +} + +#endif //#ifndef PCL_ROS_CONVERSIONS_H_ diff --git a/pcl-1.7/pcl/ros/register_point_struct.h b/pcl-1.7/pcl/ros/register_point_struct.h new file mode 100644 index 0000000..20e0231 --- /dev/null +++ b/pcl-1.7/pcl/ros/register_point_struct.h @@ -0,0 +1,52 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_ROS_REGISTER_POINT_STRUCT_H_ +#define PCL_ROS_REGISTER_POINT_STRUCT_H_ + +#ifdef __DEPRECATED +#warning The header is deprecated. please use \ + instead. +#endif + +#include + + +#endif //#ifndef PCL_ROS_REGISTER_POINT_STRUCT_H_ diff --git a/pcl-1.7/pcl/sample_consensus/boost.h b/pcl-1.7/pcl/sample_consensus/boost.h new file mode 100644 index 0000000..991ebb4 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/boost.h @@ -0,0 +1,49 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_BOOST_H_ +#define PCL_SAMPLE_CONSENSUS_BOOST_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include + +#endif // PCL_SAMPLE_CONSENSUS_BOOST_H_ diff --git a/pcl-1.7/pcl/sample_consensus/eigen.h b/pcl-1.7/pcl/sample_consensus/eigen.h new file mode 100644 index 0000000..674717c --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/eigen.h @@ -0,0 +1,50 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_EIGEN_H_ +#define PCL_SAMPLE_CONSENSUS_EIGEN_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include + +#endif // PCL_SAMPLE_CONSENSUS_EIGEN_H_ diff --git a/pcl-1.7/pcl/sample_consensus/impl/lmeds.hpp b/pcl-1.7/pcl/sample_consensus/impl/lmeds.hpp new file mode 100644 index 0000000..c24e988 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/lmeds.hpp @@ -0,0 +1,181 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_LMEDS_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_LMEDS_H_ + +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::LeastMedianSquares::computeModel (int debug_verbosity_level) +{ + // Warn and exit if no threshold was set + if (threshold_ == std::numeric_limits::max()) + { + PCL_ERROR ("[pcl::LeastMedianSquares::computeModel] No threshold set!\n"); + return (false); + } + + iterations_ = 0; + double d_best_penalty = std::numeric_limits::max(); + + std::vector best_model; + std::vector selection; + Eigen::VectorXf model_coefficients; + std::vector distances; + + int n_inliers_count = 0; + + unsigned skipped_count = 0; + // supress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! + const unsigned max_skip = max_iterations_ * 10; + + // Iterate + while (iterations_ < max_iterations_ && skipped_count < max_skip) + { + // Get X samples which satisfy the model criteria + sac_model_->getSamples (iterations_, selection); + + if (selection.empty ()) break; + + // Search for inliers in the point cloud for the current plane model M + if (!sac_model_->computeModelCoefficients (selection, model_coefficients)) + { + //iterations_++; + ++skipped_count; + continue; + } + + double d_cur_penalty = 0; + // d_cur_penalty = sum (min (dist, threshold)) + + // Iterate through the 3d points and calculate the distances from them to the model + sac_model_->getDistancesToModel (model_coefficients, distances); + + // No distances? The model must not respect the user given constraints + if (distances.empty ()) + { + //iterations_++; + ++skipped_count; + continue; + } + + std::sort (distances.begin (), distances.end ()); + // d_cur_penalty = median (distances) + size_t mid = sac_model_->getIndices ()->size () / 2; + if (mid >= distances.size ()) + { + //iterations_++; + ++skipped_count; + continue; + } + + // Do we have a "middle" point or should we "estimate" one ? + if (sac_model_->getIndices ()->size () % 2 == 0) + d_cur_penalty = (sqrt (distances[mid-1]) + sqrt (distances[mid])) / 2; + else + d_cur_penalty = sqrt (distances[mid]); + + // Better match ? + if (d_cur_penalty < d_best_penalty) + { + d_best_penalty = d_cur_penalty; + + // Save the current model/coefficients selection as being the best so far + model_ = selection; + model_coefficients_ = model_coefficients; + } + + ++iterations_; + if (debug_verbosity_level > 1) + PCL_DEBUG ("[pcl::LeastMedianSquares::computeModel] Trial %d out of %d. Best penalty is %f.\n", iterations_, max_iterations_, d_best_penalty); + } + + if (model_.empty ()) + { + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::LeastMedianSquares::computeModel] Unable to find a solution!\n"); + return (false); + } + + // Classify the data points into inliers and outliers + // Sigma = 1.4826 * (1 + 5 / (n-d)) * sqrt (M) + // @note: See "Robust Regression Methods for Computer Vision: A Review" + //double sigma = 1.4826 * (1 + 5 / (sac_model_->getIndices ()->size () - best_model.size ())) * sqrt (d_best_penalty); + //double threshold = 2.5 * sigma; + + // Iterate through the 3d points and calculate the distances from them to the model again + sac_model_->getDistancesToModel (model_coefficients_, distances); + // No distances? The model must not respect the user given constraints + if (distances.empty ()) + { + PCL_ERROR ("[pcl::LeastMedianSquares::computeModel] The model found failed to verify against the given constraints!\n"); + return (false); + } + + std::vector &indices = *sac_model_->getIndices (); + + if (distances.size () != indices.size ()) + { + PCL_ERROR ("[pcl::LeastMedianSquares::computeModel] Estimated distances (%lu) differs than the normal of indices (%lu).\n", distances.size (), indices.size ()); + return (false); + } + + inliers_.resize (distances.size ()); + // Get the inliers for the best model found + n_inliers_count = 0; + for (size_t i = 0; i < distances.size (); ++i) + if (distances[i] <= threshold_) + inliers_[n_inliers_count++] = indices[i]; + + // Resize the inliers vector + inliers_.resize (n_inliers_count); + + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::LeastMedianSquares::computeModel] Model: %lu size, %d inliers.\n", model_.size (), n_inliers_count); + + return (true); +} + +#define PCL_INSTANTIATE_LeastMedianSquares(T) template class PCL_EXPORTS pcl::LeastMedianSquares; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_LMEDS_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/mlesac.hpp b/pcl-1.7/pcl/sample_consensus/impl/mlesac.hpp new file mode 100644 index 0000000..7c6141e --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/mlesac.hpp @@ -0,0 +1,302 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_MLESAC_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_MLESAC_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::MaximumLikelihoodSampleConsensus::computeModel (int debug_verbosity_level) +{ + // Warn and exit if no threshold was set + if (threshold_ == std::numeric_limits::max()) + { + PCL_ERROR ("[pcl::MaximumLikelihoodSampleConsensus::computeModel] No threshold set!\n"); + return (false); + } + + iterations_ = 0; + double d_best_penalty = std::numeric_limits::max(); + double k = 1.0; + + std::vector best_model; + std::vector selection; + Eigen::VectorXf model_coefficients; + std::vector distances; + + // Compute sigma - remember to set threshold_ correctly ! + sigma_ = computeMedianAbsoluteDeviation (sac_model_->getInputCloud (), sac_model_->getIndices (), threshold_); + if (debug_verbosity_level > 1) + PCL_DEBUG ("[pcl::MaximumLikelihoodSampleConsensus::computeModel] Estimated sigma value: %f.\n", sigma_); + + // Compute the bounding box diagonal: V = sqrt (sum (max(pointCloud) - min(pointCloud)^2)) + Eigen::Vector4f min_pt, max_pt; + getMinMax (sac_model_->getInputCloud (), sac_model_->getIndices (), min_pt, max_pt); + max_pt -= min_pt; + double v = sqrt (max_pt.dot (max_pt)); + + int n_inliers_count = 0; + size_t indices_size; + unsigned skipped_count = 0; + // supress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! + const unsigned max_skip = max_iterations_ * 10; + + // Iterate + while (iterations_ < k && skipped_count < max_skip) + { + // Get X samples which satisfy the model criteria + sac_model_->getSamples (iterations_, selection); + + if (selection.empty ()) break; + + // Search for inliers in the point cloud for the current plane model M + if (!sac_model_->computeModelCoefficients (selection, model_coefficients)) + { + //iterations_++; + ++ skipped_count; + continue; + } + + // Iterate through the 3d points and calculate the distances from them to the model + sac_model_->getDistancesToModel (model_coefficients, distances); + + if (distances.empty ()) + { + //iterations_++; + ++skipped_count; + continue; + } + + // Use Expectiation-Maximization to find out the right value for d_cur_penalty + // ---[ Initial estimate for the gamma mixing parameter = 1/2 + double gamma = 0.5; + double p_outlier_prob = 0; + + indices_size = sac_model_->getIndices ()->size (); + std::vector p_inlier_prob (indices_size); + for (int j = 0; j < iterations_EM_; ++j) + { + // Likelihood of a datum given that it is an inlier + for (size_t i = 0; i < indices_size; ++i) + p_inlier_prob[i] = gamma * exp (- (distances[i] * distances[i] ) / 2 * (sigma_ * sigma_) ) / + (sqrt (2 * M_PI) * sigma_); + + // Likelihood of a datum given that it is an outlier + p_outlier_prob = (1 - gamma) / v; + + gamma = 0; + for (size_t i = 0; i < indices_size; ++i) + gamma += p_inlier_prob [i] / (p_inlier_prob[i] + p_outlier_prob); + gamma /= static_cast(sac_model_->getIndices ()->size ()); + } + + // Find the log likelihood of the model -L = -sum [log (pInlierProb + pOutlierProb)] + double d_cur_penalty = 0; + for (size_t i = 0; i < indices_size; ++i) + d_cur_penalty += log (p_inlier_prob[i] + p_outlier_prob); + d_cur_penalty = - d_cur_penalty; + + // Better match ? + if (d_cur_penalty < d_best_penalty) + { + d_best_penalty = d_cur_penalty; + + // Save the current model/coefficients selection as being the best so far + model_ = selection; + model_coefficients_ = model_coefficients; + + n_inliers_count = 0; + // Need to compute the number of inliers for this model to adapt k + for (size_t i = 0; i < distances.size (); ++i) + if (distances[i] <= 2 * sigma_) + n_inliers_count++; + + // Compute the k parameter (k=log(z)/log(1-w^n)) + double w = static_cast (n_inliers_count) / static_cast (sac_model_->getIndices ()->size ()); + double p_no_outliers = 1 - pow (w, static_cast (selection.size ())); + p_no_outliers = (std::max) (std::numeric_limits::epsilon (), p_no_outliers); // Avoid division by -Inf + p_no_outliers = (std::min) (1 - std::numeric_limits::epsilon (), p_no_outliers); // Avoid division by 0. + k = log (1 - probability_) / log (p_no_outliers); + } + + ++iterations_; + if (debug_verbosity_level > 1) + PCL_DEBUG ("[pcl::MaximumLikelihoodSampleConsensus::computeModel] Trial %d out of %d. Best penalty is %f.\n", iterations_, static_cast (ceil (k)), d_best_penalty); + if (iterations_ > max_iterations_) + { + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::MaximumLikelihoodSampleConsensus::computeModel] MLESAC reached the maximum number of trials.\n"); + break; + } + } + + if (model_.empty ()) + { + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::MaximumLikelihoodSampleConsensus::computeModel] Unable to find a solution!\n"); + return (false); + } + + // Iterate through the 3d points and calculate the distances from them to the model again + sac_model_->getDistancesToModel (model_coefficients_, distances); + std::vector &indices = *sac_model_->getIndices (); + if (distances.size () != indices.size ()) + { + PCL_ERROR ("[pcl::MaximumLikelihoodSampleConsensus::computeModel] Estimated distances (%lu) differs than the normal of indices (%lu).\n", distances.size (), indices.size ()); + return (false); + } + + inliers_.resize (distances.size ()); + // Get the inliers for the best model found + n_inliers_count = 0; + for (size_t i = 0; i < distances.size (); ++i) + if (distances[i] <= 2 * sigma_) + inliers_[n_inliers_count++] = indices[i]; + + // Resize the inliers vector + inliers_.resize (n_inliers_count); + + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::MaximumLikelihoodSampleConsensus::computeModel] Model: %lu size, %d inliers.\n", model_.size (), n_inliers_count); + + return (true); +} + +////////////////////////////////////////////////////////////////////////// +template double +pcl::MaximumLikelihoodSampleConsensus::computeMedianAbsoluteDeviation ( + const PointCloudConstPtr &cloud, + const boost::shared_ptr > &indices, + double sigma) +{ + std::vector distances (indices->size ()); + + Eigen::Vector4f median; + // median (dist (x - median (x))) + computeMedian (cloud, indices, median); + + for (size_t i = 0; i < indices->size (); ++i) + { + pcl::Vector4fMapConst pt = cloud->points[(*indices)[i]].getVector4fMap (); + Eigen::Vector4f ptdiff = pt - median; + ptdiff[3] = 0; + distances[i] = ptdiff.dot (ptdiff); + } + + std::sort (distances.begin (), distances.end ()); + + double result; + size_t mid = indices->size () / 2; + // Do we have a "middle" point or should we "estimate" one ? + if (indices->size () % 2 == 0) + result = (sqrt (distances[mid-1]) + sqrt (distances[mid])) / 2; + else + result = sqrt (distances[mid]); + return (sigma * result); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::MaximumLikelihoodSampleConsensus::getMinMax ( + const PointCloudConstPtr &cloud, + const boost::shared_ptr > &indices, + Eigen::Vector4f &min_p, + Eigen::Vector4f &max_p) +{ + min_p.setConstant (FLT_MAX); + max_p.setConstant (-FLT_MAX); + min_p[3] = max_p[3] = 0; + + for (size_t i = 0; i < indices->size (); ++i) + { + if (cloud->points[(*indices)[i]].x < min_p[0]) min_p[0] = cloud->points[(*indices)[i]].x; + if (cloud->points[(*indices)[i]].y < min_p[1]) min_p[1] = cloud->points[(*indices)[i]].y; + if (cloud->points[(*indices)[i]].z < min_p[2]) min_p[2] = cloud->points[(*indices)[i]].z; + + if (cloud->points[(*indices)[i]].x > max_p[0]) max_p[0] = cloud->points[(*indices)[i]].x; + if (cloud->points[(*indices)[i]].y > max_p[1]) max_p[1] = cloud->points[(*indices)[i]].y; + if (cloud->points[(*indices)[i]].z > max_p[2]) max_p[2] = cloud->points[(*indices)[i]].z; + } +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::MaximumLikelihoodSampleConsensus::computeMedian ( + const PointCloudConstPtr &cloud, + const boost::shared_ptr > &indices, + Eigen::Vector4f &median) +{ + // Copy the values to vectors for faster sorting + std::vector x (indices->size ()); + std::vector y (indices->size ()); + std::vector z (indices->size ()); + for (size_t i = 0; i < indices->size (); ++i) + { + x[i] = cloud->points[(*indices)[i]].x; + y[i] = cloud->points[(*indices)[i]].y; + z[i] = cloud->points[(*indices)[i]].z; + } + std::sort (x.begin (), x.end ()); + std::sort (y.begin (), y.end ()); + std::sort (z.begin (), z.end ()); + + size_t mid = indices->size () / 2; + if (indices->size () % 2 == 0) + { + median[0] = (x[mid-1] + x[mid]) / 2; + median[1] = (y[mid-1] + y[mid]) / 2; + median[2] = (z[mid-1] + z[mid]) / 2; + } + else + { + median[0] = x[mid]; + median[1] = y[mid]; + median[2] = z[mid]; + } + median[3] = 0; +} + +#define PCL_INSTANTIATE_MaximumLikelihoodSampleConsensus(T) template class PCL_EXPORTS pcl::MaximumLikelihoodSampleConsensus; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_MLESAC_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/msac.hpp b/pcl-1.7/pcl/sample_consensus/impl/msac.hpp new file mode 100644 index 0000000..659d338 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/msac.hpp @@ -0,0 +1,166 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_MSAC_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_MSAC_H_ + +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::MEstimatorSampleConsensus::computeModel (int debug_verbosity_level) +{ + // Warn and exit if no threshold was set + if (threshold_ == std::numeric_limits::max()) + { + PCL_ERROR ("[pcl::MEstimatorSampleConsensus::computeModel] No threshold set!\n"); + return (false); + } + + iterations_ = 0; + double d_best_penalty = std::numeric_limits::max(); + double k = 1.0; + + std::vector best_model; + std::vector selection; + Eigen::VectorXf model_coefficients; + std::vector distances; + + int n_inliers_count = 0; + unsigned skipped_count = 0; + // supress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! + const unsigned max_skip = max_iterations_ * 10; + + // Iterate + while (iterations_ < k && skipped_count < max_skip) + { + // Get X samples which satisfy the model criteria + sac_model_->getSamples (iterations_, selection); + + if (selection.empty ()) break; + + // Search for inliers in the point cloud for the current plane model M + if (!sac_model_->computeModelCoefficients (selection, model_coefficients)) + { + //iterations_++; + ++ skipped_count; + continue; + } + + double d_cur_penalty = 0; + // Iterate through the 3d points and calculate the distances from them to the model + sac_model_->getDistancesToModel (model_coefficients, distances); + + if (distances.empty () && k > 1.0) + continue; + + for (size_t i = 0; i < distances.size (); ++i) + d_cur_penalty += (std::min) (distances[i], threshold_); + + // Better match ? + if (d_cur_penalty < d_best_penalty) + { + d_best_penalty = d_cur_penalty; + + // Save the current model/coefficients selection as being the best so far + model_ = selection; + model_coefficients_ = model_coefficients; + + n_inliers_count = 0; + // Need to compute the number of inliers for this model to adapt k + for (size_t i = 0; i < distances.size (); ++i) + if (distances[i] <= threshold_) + ++n_inliers_count; + + // Compute the k parameter (k=log(z)/log(1-w^n)) + double w = static_cast (n_inliers_count) / static_cast (sac_model_->getIndices ()->size ()); + double p_no_outliers = 1.0 - pow (w, static_cast (selection.size ())); + p_no_outliers = (std::max) (std::numeric_limits::epsilon (), p_no_outliers); // Avoid division by -Inf + p_no_outliers = (std::min) (1.0 - std::numeric_limits::epsilon (), p_no_outliers); // Avoid division by 0. + k = log (1.0 - probability_) / log (p_no_outliers); + } + + ++iterations_; + if (debug_verbosity_level > 1) + PCL_DEBUG ("[pcl::MEstimatorSampleConsensus::computeModel] Trial %d out of %d. Best penalty is %f.\n", iterations_, static_cast (ceil (k)), d_best_penalty); + if (iterations_ > max_iterations_) + { + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::MEstimatorSampleConsensus::computeModel] MSAC reached the maximum number of trials.\n"); + break; + } + } + + if (model_.empty ()) + { + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::MEstimatorSampleConsensus::computeModel] Unable to find a solution!\n"); + return (false); + } + + // Iterate through the 3d points and calculate the distances from them to the model again + sac_model_->getDistancesToModel (model_coefficients_, distances); + std::vector &indices = *sac_model_->getIndices (); + + if (distances.size () != indices.size ()) + { + PCL_ERROR ("[pcl::MEstimatorSampleConsensus::computeModel] Estimated distances (%lu) differs than the normal of indices (%lu).\n", distances.size (), indices.size ()); + return (false); + } + + inliers_.resize (distances.size ()); + // Get the inliers for the best model found + n_inliers_count = 0; + for (size_t i = 0; i < distances.size (); ++i) + if (distances[i] <= threshold_) + inliers_[n_inliers_count++] = indices[i]; + + // Resize the inliers vector + inliers_.resize (n_inliers_count); + + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::MEstimatorSampleConsensus::computeModel] Model: %lu size, %d inliers.\n", model_.size (), n_inliers_count); + + return (true); +} + +#define PCL_INSTANTIATE_MEstimatorSampleConsensus(T) template class PCL_EXPORTS pcl::MEstimatorSampleConsensus; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_MSAC_H_ diff --git a/pcl-1.7/pcl/sample_consensus/impl/prosac.hpp b/pcl-1.7/pcl/sample_consensus/impl/prosac.hpp new file mode 100644 index 0000000..674eaa3 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/prosac.hpp @@ -0,0 +1,239 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_PROSAC_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_PROSAC_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include + +////////////////////////////////////////////////////////////////////////// +// Variable naming uses capital letters to make the comparison with the original paper easier +template bool +pcl::ProgressiveSampleConsensus::computeModel (int debug_verbosity_level) +{ + // Warn and exit if no threshold was set + if (threshold_ == DBL_MAX) + { + PCL_ERROR ("[pcl::ProgressiveSampleConsensus::computeModel] No threshold set!\n"); + return (false); + } + + // Initialize some PROSAC constants + const int T_N = 200000; + const size_t N = sac_model_->indices_->size (); + const size_t m = sac_model_->getSampleSize (); + float T_n = static_cast (T_N); + for (unsigned int i = 0; i < m; ++i) + T_n *= static_cast (m - i) / static_cast (N - i); + float T_prime_n = 1.0f; + size_t I_N_best = 0; + float n = static_cast (m); + + // Define the n_Start coefficients from Section 2.2 + float n_star = static_cast (N); + float epsilon_n_star = 0.0; + size_t k_n_star = T_N; + + // Compute the I_n_star_min of Equation 8 + std::vector I_n_star_min (N); + + // Initialize the usual RANSAC parameters + iterations_ = 0; + + std::vector inliers; + std::vector selection; + Eigen::VectorXf model_coefficients; + + // We will increase the pool so the indices_ vector can only contain m elements at first + std::vector index_pool; + index_pool.reserve (N); + for (unsigned int i = 0; i < n; ++i) + index_pool.push_back (sac_model_->indices_->operator[](i)); + + // Iterate + while (static_cast (iterations_) < k_n_star) + { + // Choose the samples + + // Step 1 + // According to Equation 5 in the text text, not the algorithm + if ((iterations_ == T_prime_n) && (n < n_star)) + { + // Increase the pool + ++n; + if (n >= N) + break; + index_pool.push_back (sac_model_->indices_->at(static_cast (n - 1))); + // Update other variables + float T_n_minus_1 = T_n; + T_n *= (static_cast(n) + 1.0f) / (static_cast(n) + 1.0f - static_cast(m)); + T_prime_n += ceilf (T_n - T_n_minus_1); + } + + // Step 2 + sac_model_->indices_->swap (index_pool); + selection.clear (); + sac_model_->getSamples (iterations_, selection); + if (T_prime_n < iterations_) + { + selection.pop_back (); + selection.push_back (sac_model_->indices_->at(static_cast (n - 1))); + } + + // Make sure we use the right indices for testing + sac_model_->indices_->swap (index_pool); + + if (selection.empty ()) + { + PCL_ERROR ("[pcl::ProgressiveSampleConsensus::computeModel] No samples could be selected!\n"); + break; + } + + // Search for inliers in the point cloud for the current model + if (!sac_model_->computeModelCoefficients (selection, model_coefficients)) + { + ++iterations_; + continue; + } + + // Select the inliers that are within threshold_ from the model + inliers.clear (); + sac_model_->selectWithinDistance (model_coefficients, threshold_, inliers); + + size_t I_N = inliers.size (); + + // If we find more inliers than before + if (I_N > I_N_best) + { + I_N_best = I_N; + + // Save the current model/inlier/coefficients selection as being the best so far + inliers_ = inliers; + model_ = selection; + model_coefficients_ = model_coefficients; + + // We estimate I_n_star for different possible values of n_star by using the inliers + std::sort (inliers.begin (), inliers.end ()); + + // Try to find a better n_star + // We minimize k_n_star and therefore maximize epsilon_n_star = I_n_star / n_star + size_t possible_n_star_best = N, I_possible_n_star_best = I_N; + float epsilon_possible_n_star_best = static_cast(I_possible_n_star_best) / static_cast(possible_n_star_best); + + // We only need to compute possible better epsilon_n_star for when _n is just about to be removed an inlier + size_t I_possible_n_star = I_N; + for (std::vector::const_reverse_iterator last_inlier = inliers.rbegin (), + inliers_end = inliers.rend (); + last_inlier != inliers_end; + ++last_inlier, --I_possible_n_star) + { + // The best possible_n_star for a given I_possible_n_star is the index of the last inlier + unsigned int possible_n_star = (*last_inlier) + 1; + if (possible_n_star <= m) + break; + + // If we find a better epsilon_n_star + float epsilon_possible_n_star = static_cast(I_possible_n_star) / static_cast(possible_n_star); + // Make sure we have a better epsilon_possible_n_star + if ((epsilon_possible_n_star > epsilon_n_star) && (epsilon_possible_n_star > epsilon_possible_n_star_best)) + { + // Typo in Equation 7, not (n-m choose i-m) but (n choose i-m) + size_t I_possible_n_star_min = m + + static_cast (ceil (boost::math::quantile (boost::math::complement (boost::math::binomial_distribution(static_cast (possible_n_star), 0.1f), 0.05)))); + // If Equation 9 is not verified, exit + if (I_possible_n_star < I_possible_n_star_min) + break; + + possible_n_star_best = possible_n_star; + I_possible_n_star_best = I_possible_n_star; + epsilon_possible_n_star_best = epsilon_possible_n_star; + } + } + + // Check if we get a better epsilon + if (epsilon_possible_n_star_best > epsilon_n_star) + { + // update the best value + epsilon_n_star = epsilon_possible_n_star_best; + + // Compute the new k_n_star + float bottom_log = 1 - std::pow (epsilon_n_star, static_cast(m)); + if (bottom_log == 0) + k_n_star = 1; + else if (bottom_log == 1) + k_n_star = T_N; + else + k_n_star = static_cast (ceil (log (0.05) / log (bottom_log))); + // It seems weird to have very few iterations, so do have a few (totally empirical) + k_n_star = (std::max)(k_n_star, 2 * m); + } + } + + ++iterations_; + if (debug_verbosity_level > 1) + PCL_DEBUG ("[pcl::ProgressiveSampleConsensus::computeModel] Trial %d out of %d: %d inliers (best is: %d so far).\n", iterations_, k_n_star, I_N, I_N_best); + if (iterations_ > max_iterations_) + { + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::ProgressiveSampleConsensus::computeModel] RANSAC reached the maximum number of trials.\n"); + break; + } + } + + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::ProgressiveSampleConsensus::computeModel] Model: %lu size, %d inliers.\n", model_.size (), I_N_best); + + if (model_.empty ()) + { + inliers_.clear (); + return (false); + } + + return (true); +} + +#define PCL_INSTANTIATE_ProgressiveSampleConsensus(T) template class PCL_EXPORTS pcl::ProgressiveSampleConsensus; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_PROSAC_H_ diff --git a/pcl-1.7/pcl/sample_consensus/impl/ransac.hpp b/pcl-1.7/pcl/sample_consensus/impl/ransac.hpp new file mode 100644 index 0000000..3c174fe --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/ransac.hpp @@ -0,0 +1,141 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_RANSAC_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_RANSAC_H_ + +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::RandomSampleConsensus::computeModel (int) +{ + // Warn and exit if no threshold was set + if (threshold_ == std::numeric_limits::max()) + { + PCL_ERROR ("[pcl::RandomSampleConsensus::computeModel] No threshold set!\n"); + return (false); + } + + iterations_ = 0; + int n_best_inliers_count = -INT_MAX; + double k = 1.0; + + std::vector selection; + Eigen::VectorXf model_coefficients; + + double log_probability = log (1.0 - probability_); + double one_over_indices = 1.0 / static_cast (sac_model_->getIndices ()->size ()); + + int n_inliers_count = 0; + unsigned skipped_count = 0; + // supress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! + const unsigned max_skip = max_iterations_ * 10; + + // Iterate + while (iterations_ < k && skipped_count < max_skip) + { + // Get X samples which satisfy the model criteria + sac_model_->getSamples (iterations_, selection); + + if (selection.empty ()) + { + PCL_ERROR ("[pcl::RandomSampleConsensus::computeModel] No samples could be selected!\n"); + break; + } + + // Search for inliers in the point cloud for the current plane model M + if (!sac_model_->computeModelCoefficients (selection, model_coefficients)) + { + //++iterations_; + ++skipped_count; + continue; + } + + // Select the inliers that are within threshold_ from the model + //sac_model_->selectWithinDistance (model_coefficients, threshold_, inliers); + //if (inliers.empty () && k > 1.0) + // continue; + + n_inliers_count = sac_model_->countWithinDistance (model_coefficients, threshold_); + + // Better match ? + if (n_inliers_count > n_best_inliers_count) + { + n_best_inliers_count = n_inliers_count; + + // Save the current model/inlier/coefficients selection as being the best so far + model_ = selection; + model_coefficients_ = model_coefficients; + + // Compute the k parameter (k=log(z)/log(1-w^n)) + double w = static_cast (n_best_inliers_count) * one_over_indices; + double p_no_outliers = 1.0 - pow (w, static_cast (selection.size ())); + p_no_outliers = (std::max) (std::numeric_limits::epsilon (), p_no_outliers); // Avoid division by -Inf + p_no_outliers = (std::min) (1.0 - std::numeric_limits::epsilon (), p_no_outliers); // Avoid division by 0. + k = log_probability / log (p_no_outliers); + } + + ++iterations_; + PCL_DEBUG ("[pcl::RandomSampleConsensus::computeModel] Trial %d out of %f: %d inliers (best is: %d so far).\n", iterations_, k, n_inliers_count, n_best_inliers_count); + if (iterations_ > max_iterations_) + { + PCL_DEBUG ("[pcl::RandomSampleConsensus::computeModel] RANSAC reached the maximum number of trials.\n"); + break; + } + } + + PCL_DEBUG ("[pcl::RandomSampleConsensus::computeModel] Model: %lu size, %d inliers.\n", model_.size (), n_best_inliers_count); + + if (model_.empty ()) + { + inliers_.clear (); + return (false); + } + + // Get the set of inliers that correspond to the best model found so far + sac_model_->selectWithinDistance (model_coefficients_, threshold_, inliers_); + return (true); +} + +#define PCL_INSTANTIATE_RandomSampleConsensus(T) template class PCL_EXPORTS pcl::RandomSampleConsensus; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_RANSAC_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/rmsac.hpp b/pcl-1.7/pcl/sample_consensus/impl/rmsac.hpp new file mode 100644 index 0000000..186f303 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/rmsac.hpp @@ -0,0 +1,184 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_RMSAC_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_RMSAC_H_ + +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::RandomizedMEstimatorSampleConsensus::computeModel (int debug_verbosity_level) +{ + // Warn and exit if no threshold was set + if (threshold_ == std::numeric_limits::max()) + { + PCL_ERROR ("[pcl::RandomizedMEstimatorSampleConsensus::computeModel] No threshold set!\n"); + return (false); + } + + iterations_ = 0; + double d_best_penalty = std::numeric_limits::max(); + double k = 1.0; + + std::vector best_model; + std::vector selection; + Eigen::VectorXf model_coefficients; + std::vector distances; + std::set indices_subset; + + int n_inliers_count = 0; + unsigned skipped_count = 0; + // supress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! + const unsigned max_skip = max_iterations_ * 10; + + // Number of samples to try randomly + size_t fraction_nr_points = pcl_lrint (static_cast(sac_model_->getIndices ()->size ()) * fraction_nr_pretest_ / 100.0); + + // Iterate + while (iterations_ < k && skipped_count < max_skip) + { + // Get X samples which satisfy the model criteria + sac_model_->getSamples (iterations_, selection); + + if (selection.empty ()) break; + + // Search for inliers in the point cloud for the current plane model M + if (!sac_model_->computeModelCoefficients (selection, model_coefficients)) + { + //iterations_++; + ++ skipped_count; + continue; + } + + // RMSAC addon: verify a random fraction of the data + // Get X random samples which satisfy the model criterion + this->getRandomSamples (sac_model_->getIndices (), fraction_nr_points, indices_subset); + + if (!sac_model_->doSamplesVerifyModel (indices_subset, model_coefficients, threshold_)) + { + // Unfortunately we cannot "continue" after the first iteration, because k might not be set, while iterations gets incremented + if (k != 1.0) + { + ++iterations_; + continue; + } + } + + double d_cur_penalty = 0; + // Iterate through the 3d points and calculate the distances from them to the model + sac_model_->getDistancesToModel (model_coefficients, distances); + + if (distances.empty () && k > 1.0) + continue; + + for (size_t i = 0; i < distances.size (); ++i) + d_cur_penalty += (std::min) (distances[i], threshold_); + + // Better match ? + if (d_cur_penalty < d_best_penalty) + { + d_best_penalty = d_cur_penalty; + + // Save the current model/coefficients selection as being the best so far + model_ = selection; + model_coefficients_ = model_coefficients; + + n_inliers_count = 0; + // Need to compute the number of inliers for this model to adapt k + for (size_t i = 0; i < distances.size (); ++i) + if (distances[i] <= threshold_) + n_inliers_count++; + + // Compute the k parameter (k=log(z)/log(1-w^n)) + double w = static_cast (n_inliers_count) / static_cast(sac_model_->getIndices ()->size ()); + double p_no_outliers = 1 - pow (w, static_cast (selection.size ())); + p_no_outliers = (std::max) (std::numeric_limits::epsilon (), p_no_outliers); // Avoid division by -Inf + p_no_outliers = (std::min) (1 - std::numeric_limits::epsilon (), p_no_outliers); // Avoid division by 0. + k = log (1 - probability_) / log (p_no_outliers); + } + + ++iterations_; + if (debug_verbosity_level > 1) + PCL_DEBUG ("[pcl::RandomizedMEstimatorSampleConsensus::computeModel] Trial %d out of %d. Best penalty is %f.\n", iterations_, static_cast (ceil (k)), d_best_penalty); + if (iterations_ > max_iterations_) + { + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::RandomizedMEstimatorSampleConsensus::computeModel] MSAC reached the maximum number of trials.\n"); + break; + } + } + + if (model_.empty ()) + { + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::RandomizedMEstimatorSampleConsensus::computeModel] Unable to find a solution!\n"); + return (false); + } + + // Iterate through the 3d points and calculate the distances from them to the model again + sac_model_->getDistancesToModel (model_coefficients_, distances); + std::vector &indices = *sac_model_->getIndices (); + if (distances.size () != indices.size ()) + { + PCL_ERROR ("[pcl::RandomizedMEstimatorSampleConsensus::computeModel] Estimated distances (%lu) differs than the normal of indices (%lu).\n", distances.size (), indices.size ()); + return (false); + } + + inliers_.resize (distances.size ()); + // Get the inliers for the best model found + n_inliers_count = 0; + for (size_t i = 0; i < distances.size (); ++i) + if (distances[i] <= threshold_) + inliers_[n_inliers_count++] = indices[i]; + + // Resize the inliers vector + inliers_.resize (n_inliers_count); + + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::RandomizedMEstimatorSampleConsensus::computeModel] Model: %lu size, %d inliers.\n", model_.size (), n_inliers_count); + + return (true); +} + +#define PCL_INSTANTIATE_RandomizedMEstimatorSampleConsensus(T) template class PCL_EXPORTS pcl::RandomizedMEstimatorSampleConsensus; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_RMSAC_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/rransac.hpp b/pcl-1.7/pcl/sample_consensus/impl/rransac.hpp new file mode 100644 index 0000000..338780d --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/rransac.hpp @@ -0,0 +1,151 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_RRANSAC_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_RRANSAC_H_ + +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::RandomizedRandomSampleConsensus::computeModel (int debug_verbosity_level) +{ + // Warn and exit if no threshold was set + if (threshold_ == std::numeric_limits::max()) + { + PCL_ERROR ("[pcl::RandomizedRandomSampleConsensus::computeModel] No threshold set!\n"); + return (false); + } + + iterations_ = 0; + int n_best_inliers_count = -INT_MAX; + double k = 1.0; + + std::vector selection; + Eigen::VectorXf model_coefficients; + std::set indices_subset; + + int n_inliers_count = 0; + unsigned skipped_count = 0; + // supress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! + const unsigned max_skip = max_iterations_ * 10; + + // Number of samples to try randomly + size_t fraction_nr_points = pcl_lrint (static_cast(sac_model_->getIndices ()->size ()) * fraction_nr_pretest_ / 100.0); + + // Iterate + while (iterations_ < k && skipped_count < max_skip) + { + // Get X samples which satisfy the model criteria + sac_model_->getSamples (iterations_, selection); + + if (selection.empty ()) break; + + // Search for inliers in the point cloud for the current plane model M + if (!sac_model_->computeModelCoefficients (selection, model_coefficients)) + { + //iterations_++; + ++ skipped_count; + continue; + } + + // RRANSAC addon: verify a random fraction of the data + // Get X random samples which satisfy the model criterion + this->getRandomSamples (sac_model_->getIndices (), fraction_nr_points, indices_subset); + if (!sac_model_->doSamplesVerifyModel (indices_subset, model_coefficients, threshold_)) + { + // Unfortunately we cannot "continue" after the first iteration, because k might not be set, while iterations gets incremented + if (k > 1.0) + { + ++iterations_; + continue; + } + } + + // Select the inliers that are within threshold_ from the model + n_inliers_count = sac_model_->countWithinDistance (model_coefficients, threshold_); + + // Better match ? + if (n_inliers_count > n_best_inliers_count) + { + n_best_inliers_count = n_inliers_count; + + // Save the current model/inlier/coefficients selection as being the best so far + model_ = selection; + model_coefficients_ = model_coefficients; + + // Compute the k parameter (k=log(z)/log(1-w^n)) + double w = static_cast (n_inliers_count) / static_cast (sac_model_->getIndices ()->size ()); + double p_no_outliers = 1 - pow (w, static_cast (selection.size ())); + p_no_outliers = (std::max) (std::numeric_limits::epsilon (), p_no_outliers); // Avoid division by -Inf + p_no_outliers = (std::min) (1 - std::numeric_limits::epsilon (), p_no_outliers); // Avoid division by 0. + k = log (1 - probability_) / log (p_no_outliers); + } + + ++iterations_; + + if (debug_verbosity_level > 1) + PCL_DEBUG ("[pcl::RandomizedRandomSampleConsensus::computeModel] Trial %d out of %d: %d inliers (best is: %d so far).\n", iterations_, static_cast (ceil (k)), n_inliers_count, n_best_inliers_count); + if (iterations_ > max_iterations_) + { + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::RandomizedRandomSampleConsensus::computeModel] RRANSAC reached the maximum number of trials.\n"); + break; + } + } + + if (debug_verbosity_level > 0) + PCL_DEBUG ("[pcl::RandomizedRandomSampleConsensus::computeModel] Model: %lu size, %d inliers.\n", model_.size (), n_best_inliers_count); + + if (model_.empty ()) + { + inliers_.clear (); + return (false); + } + + // Get the set of inliers that correspond to the best model found so far + sac_model_->selectWithinDistance (model_coefficients_, threshold_, inliers_); + return (true); +} + +#define PCL_INSTANTIATE_RandomizedRandomSampleConsensus(T) template class PCL_EXPORTS pcl::RandomizedRandomSampleConsensus; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_RRANSAC_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_circle.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_circle.hpp new file mode 100644 index 0000000..99a1009 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_circle.hpp @@ -0,0 +1,344 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CIRCLE_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CIRCLE_H_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCircle2D::isSampleGood(const std::vector &samples) const +{ + // Get the values at the two points + Eigen::Array2d p0 (input_->points[samples[0]].x, input_->points[samples[0]].y); + Eigen::Array2d p1 (input_->points[samples[1]].x, input_->points[samples[1]].y); + Eigen::Array2d p2 (input_->points[samples[2]].x, input_->points[samples[2]].y); + + // Compute the segment values (in 2d) between p1 and p0 + p1 -= p0; + // Compute the segment values (in 2d) between p2 and p0 + p2 -= p0; + + Eigen::Array2d dy1dy2 = p1 / p2; + + return (dy1dy2[0] != dy1dy2[1]); +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCircle2D::computeModelCoefficients (const std::vector &samples, Eigen::VectorXf &model_coefficients) +{ + // Need 3 samples + if (samples.size () != 3) + { + PCL_ERROR ("[pcl::SampleConsensusModelCircle2D::computeModelCoefficients] Invalid set of samples given (%lu)!\n", samples.size ()); + return (false); + } + + model_coefficients.resize (3); + + Eigen::Vector2d p0 (input_->points[samples[0]].x, input_->points[samples[0]].y); + Eigen::Vector2d p1 (input_->points[samples[1]].x, input_->points[samples[1]].y); + Eigen::Vector2d p2 (input_->points[samples[2]].x, input_->points[samples[2]].y); + + Eigen::Vector2d u = (p0 + p1) / 2.0; + Eigen::Vector2d v = (p1 + p2) / 2.0; + + Eigen::Vector2d p1p0dif = p1 - p0; + Eigen::Vector2d p2p1dif = p2 - p1; + Eigen::Vector2d uvdif = u - v; + + Eigen::Vector2d m (- p1p0dif[0] / p1p0dif[1], - p2p1dif[0] / p2p1dif[1]); + + // Center (x, y) + model_coefficients[0] = static_cast ((m[0] * u[0] - m[1] * v[0] - uvdif[1] ) / (m[0] - m[1])); + model_coefficients[1] = static_cast ((m[0] * m[1] * uvdif[0] + m[0] * v[1] - m[1] * u[1]) / (m[0] - m[1])); + + // Radius + model_coefficients[2] = static_cast (sqrt ((model_coefficients[0] - p0[0]) * (model_coefficients[0] - p0[0]) + + (model_coefficients[1] - p0[1]) * (model_coefficients[1] - p0[1]))); + return (true); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCircle2D::getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + distances.clear (); + return; + } + distances.resize (indices_->size ()); + + // Iterate through the 3d points and calculate the distances from them to the sphere + for (size_t i = 0; i < indices_->size (); ++i) + // Calculate the distance from the point to the circle as the difference between + // dist(point,circle_origin) and circle_radius + distances[i] = fabsf (sqrtf ( + ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) * + ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) + + + ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) * + ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) + ) - model_coefficients[2]); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCircle2D::selectWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold, + std::vector &inliers) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + inliers.clear (); + return; + } + int nr_p = 0; + inliers.resize (indices_->size ()); + error_sqr_dists_.resize (indices_->size ()); + + // Iterate through the 3d points and calculate the distances from them to the sphere + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the sphere as the difference between + // dist(point,sphere_origin) and sphere_radius + float distance = fabsf (sqrtf ( + ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) * + ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) + + + ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) * + ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) + ) - model_coefficients[2]); + if (distance < threshold) + { + // Returns the indices of the points whose distances are smaller than the threshold + inliers[nr_p] = (*indices_)[i]; + error_sqr_dists_[nr_p] = static_cast (distance); + ++nr_p; + } + } + inliers.resize (nr_p); + error_sqr_dists_.resize (nr_p); +} + +////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelCircle2D::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + return (0); + int nr_p = 0; + + // Iterate through the 3d points and calculate the distances from them to the sphere + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the sphere as the difference between + // dist(point,sphere_origin) and sphere_radius + float distance = fabsf (sqrtf ( + ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) * + ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) + + + ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) * + ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) + ) - model_coefficients[2]); + if (distance < threshold) + nr_p++; + } + return (nr_p); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCircle2D::optimizeModelCoefficients ( + const std::vector &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients) +{ + optimized_coefficients = model_coefficients; + + // Needs a set of valid model coefficients + if (model_coefficients.size () != 3) + { + PCL_ERROR ("[pcl::SampleConsensusModelCircle2D::optimizeModelCoefficients] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return; + } + + // Need at least 3 samples + if (inliers.size () <= 3) + { + PCL_ERROR ("[pcl::SampleConsensusModelCircle2D::optimizeModelCoefficients] Not enough inliers found to support a model (%lu)! Returning the same coefficients.\n", inliers.size ()); + return; + } + + tmp_inliers_ = &inliers; + + OptimizationFunctor functor (static_cast (inliers.size ()), this); + Eigen::NumericalDiff num_diff (functor); + Eigen::LevenbergMarquardt, float> lm (num_diff); + int info = lm.minimize (optimized_coefficients); + + // Compute the L2 norm of the residuals + PCL_DEBUG ("[pcl::SampleConsensusModelCircle2D::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g \nFinal solution: %g %g %g\n", + info, lm.fvec.norm (), model_coefficients[0], model_coefficients[1], model_coefficients[2], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2]); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCircle2D::projectPoints ( + const std::vector &inliers, const Eigen::VectorXf &model_coefficients, + PointCloud &projected_points, bool copy_data_fields) +{ + // Needs a valid set of model coefficients + if (model_coefficients.size () != 3) + { + PCL_ERROR ("[pcl::SampleConsensusModelCircle2D::projectPoints] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return; + } + + projected_points.header = input_->header; + projected_points.is_dense = input_->is_dense; + + // Copy all the data fields from the input cloud to the projected one? + if (copy_data_fields) + { + // Allocate enough space and copy the basics + projected_points.points.resize (input_->points.size ()); + projected_points.width = input_->width; + projected_points.height = input_->height; + + typedef typename pcl::traits::fieldList::type FieldList; + // Iterate over each point + for (size_t i = 0; i < projected_points.points.size (); ++i) + // Iterate over each dimension + pcl::for_each_type (NdConcatenateFunctor (input_->points[i], projected_points.points[i])); + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < inliers.size (); ++i) + { + float dx = input_->points[inliers[i]].x - model_coefficients[0]; + float dy = input_->points[inliers[i]].y - model_coefficients[1]; + float a = sqrtf ( (model_coefficients[2] * model_coefficients[2]) / (dx * dx + dy * dy) ); + + projected_points.points[inliers[i]].x = a * dx + model_coefficients[0]; + projected_points.points[inliers[i]].y = a * dy + model_coefficients[1]; + } + } + else + { + // Allocate enough space and copy the basics + projected_points.points.resize (inliers.size ()); + projected_points.width = static_cast (inliers.size ()); + projected_points.height = 1; + + typedef typename pcl::traits::fieldList::type FieldList; + // Iterate over each point + for (size_t i = 0; i < inliers.size (); ++i) + // Iterate over each dimension + pcl::for_each_type (NdConcatenateFunctor (input_->points[inliers[i]], projected_points.points[i])); + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < inliers.size (); ++i) + { + float dx = input_->points[inliers[i]].x - model_coefficients[0]; + float dy = input_->points[inliers[i]].y - model_coefficients[1]; + float a = sqrtf ( (model_coefficients[2] * model_coefficients[2]) / (dx * dx + dy * dy) ); + + projected_points.points[i].x = a * dx + model_coefficients[0]; + projected_points.points[i].y = a * dy + model_coefficients[1]; + } + } +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCircle2D::doSamplesVerifyModel ( + const std::set &indices, const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 3) + { + PCL_ERROR ("[pcl::SampleConsensusModelCircle2D::doSamplesVerifyModel] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + for (std::set::const_iterator it = indices.begin (); it != indices.end (); ++it) + // Calculate the distance from the point to the sphere as the difference between + //dist(point,sphere_origin) and sphere_radius + if (fabsf (sqrtf ( + ( input_->points[*it].x - model_coefficients[0] ) * + ( input_->points[*it].x - model_coefficients[0] ) + + ( input_->points[*it].y - model_coefficients[1] ) * + ( input_->points[*it].y - model_coefficients[1] ) + ) - model_coefficients[2]) > threshold) + return (false); + + return (true); +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCircle2D::isModelValid (const Eigen::VectorXf &model_coefficients) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 3) + { + PCL_ERROR ("[pcl::SampleConsensusModelCircle2D::isModelValid] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + if (radius_min_ != -std::numeric_limits::max() && model_coefficients[2] < radius_min_) + return (false); + if (radius_max_ != std::numeric_limits::max() && model_coefficients[2] > radius_max_) + return (false); + + return (true); +} + +#define PCL_INSTANTIATE_SampleConsensusModelCircle2D(T) template class PCL_EXPORTS pcl::SampleConsensusModelCircle2D; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CIRCLE_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_circle3d.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_circle3d.hpp new file mode 100644 index 0000000..d9ee61a --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_circle3d.hpp @@ -0,0 +1,460 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CIRCLE_3D_HPP_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CIRCLE_3D_HPP_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCircle3D::isSampleGood ( + const std::vector &samples) const +{ + // Get the values at the three points + Eigen::Vector3d p0 (input_->points[samples[0]].x, input_->points[samples[0]].y, input_->points[samples[0]].z); + Eigen::Vector3d p1 (input_->points[samples[1]].x, input_->points[samples[1]].y, input_->points[samples[1]].z); + Eigen::Vector3d p2 (input_->points[samples[2]].x, input_->points[samples[2]].y, input_->points[samples[2]].z); + + // calculate vectors between points + p1 -= p0; + p2 -= p0; + + if (p1.dot (p2) < 0.000001) + return (true); + else + return (false); +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCircle3D::computeModelCoefficients (const std::vector &samples, Eigen::VectorXf &model_coefficients) +{ + // Need 3 samples + if (samples.size () != 3) + { + PCL_ERROR ("[pcl::SampleConsensusModelCircle3D::computeModelCoefficients] Invalid set of samples given (%lu)!\n", samples.size ()); + return (false); + } + + model_coefficients.resize (7); //needing 7 coefficients: centerX, centerY, centerZ, radius, normalX, normalY, normalZ + + Eigen::Vector3d p0 (input_->points[samples[0]].x, input_->points[samples[0]].y, input_->points[samples[0]].z); + Eigen::Vector3d p1 (input_->points[samples[1]].x, input_->points[samples[1]].y, input_->points[samples[1]].z); + Eigen::Vector3d p2 (input_->points[samples[2]].x, input_->points[samples[2]].y, input_->points[samples[2]].z); + + + Eigen::Vector3d helper_vec01 = p0 - p1; + Eigen::Vector3d helper_vec02 = p0 - p2; + Eigen::Vector3d helper_vec10 = p1 - p0; + Eigen::Vector3d helper_vec12 = p1 - p2; + Eigen::Vector3d helper_vec20 = p2 - p0; + Eigen::Vector3d helper_vec21 = p2 - p1; + + Eigen::Vector3d common_helper_vec = helper_vec01.cross (helper_vec12); + + double commonDividend = 2.0 * common_helper_vec.squaredNorm (); + + double alpha = (helper_vec12.squaredNorm () * helper_vec01.dot (helper_vec02)) / commonDividend; + double beta = (helper_vec02.squaredNorm () * helper_vec10.dot (helper_vec12)) / commonDividend; + double gamma = (helper_vec01.squaredNorm () * helper_vec20.dot (helper_vec21)) / commonDividend; + + Eigen::Vector3d circle_center = alpha * p0 + beta * p1 + gamma * p2; + + Eigen::Vector3d circle_radiusVector = circle_center - p0; + double circle_radius = circle_radiusVector.norm (); + Eigen::Vector3d circle_normal = common_helper_vec.normalized (); + + model_coefficients[0] = static_cast (circle_center[0]); + model_coefficients[1] = static_cast (circle_center[1]); + model_coefficients[2] = static_cast (circle_center[2]); + model_coefficients[3] = static_cast (circle_radius); + model_coefficients[4] = static_cast (circle_normal[0]); + model_coefficients[5] = static_cast (circle_normal[1]); + model_coefficients[6] = static_cast (circle_normal[2]); + + return (true); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCircle3D::getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + distances.clear (); + return; + } + distances.resize (indices_->size ()); + + // Iterate through the 3d points and calculate the distances from them to the sphere + for (size_t i = 0; i < indices_->size (); ++i) + // Calculate the distance from the point to the circle: + // 1. calculate intersection point of the plane in which the circle lies and the + // line from the sample point with the direction of the plane normal (projected point) + // 2. calculate the intersection point of the line from the circle center to the projected point + // with the circle + // 3. calculate distance from corresponding point on the circle to the sample point + { + // what i have: + // P : Sample Point + Eigen::Vector3d P (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z); + // C : Circle Center + Eigen::Vector3d C (model_coefficients[0], model_coefficients[1], model_coefficients[2]); + // N : Circle (Plane) Normal + Eigen::Vector3d N (model_coefficients[4], model_coefficients[5], model_coefficients[6]); + // r : Radius + double r = model_coefficients[3]; + + Eigen::Vector3d helper_vectorPC = P - C; + // 1.1. get line parameter + double lambda = (helper_vectorPC.dot (N)) / N.squaredNorm (); + + // Projected Point on plane + Eigen::Vector3d P_proj = P + lambda * N; + Eigen::Vector3d helper_vectorP_projC = P_proj - C; + + // K : Point on Circle + Eigen::Vector3d K = C + r * helper_vectorP_projC.normalized (); + Eigen::Vector3d distanceVector = P - K; + + distances[i] = distanceVector.norm (); + } +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCircle3D::selectWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold, + std::vector &inliers) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + inliers.clear (); + return; + } + int nr_p = 0; + inliers.resize (indices_->size ()); + + // Iterate through the 3d points and calculate the distances from them to the sphere + for (size_t i = 0; i < indices_->size (); ++i) + { + // what i have: + // P : Sample Point + Eigen::Vector3d P (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z); + // C : Circle Center + Eigen::Vector3d C (model_coefficients[0], model_coefficients[1], model_coefficients[2]); + // N : Circle (Plane) Normal + Eigen::Vector3d N (model_coefficients[4], model_coefficients[5], model_coefficients[6]); + // r : Radius + double r = model_coefficients[3]; + + Eigen::Vector3d helper_vectorPC = P - C; + // 1.1. get line parameter + double lambda = (-(helper_vectorPC.dot (N))) / N.dot (N); + // Projected Point on plane + Eigen::Vector3d P_proj = P + lambda * N; + Eigen::Vector3d helper_vectorP_projC = P_proj - C; + + // K : Point on Circle + Eigen::Vector3d K = C + r * helper_vectorP_projC.normalized (); + Eigen::Vector3d distanceVector = P - K; + + if (distanceVector.norm () < threshold) + { + // Returns the indices of the points whose distances are smaller than the threshold + inliers[nr_p] = (*indices_)[i]; + nr_p++; + } + } + inliers.resize (nr_p); +} + +////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelCircle3D::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + return (0); + int nr_p = 0; + + // Iterate through the 3d points and calculate the distances from them to the sphere + for (size_t i = 0; i < indices_->size (); ++i) + { + // what i have: + // P : Sample Point + Eigen::Vector3d P (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z); + // C : Circle Center + Eigen::Vector3d C (model_coefficients[0], model_coefficients[1], model_coefficients[2]); + // N : Circle (Plane) Normal + Eigen::Vector3d N (model_coefficients[4], model_coefficients[5], model_coefficients[6]); + // r : Radius + double r = model_coefficients[3]; + + Eigen::Vector3d helper_vectorPC = P - C; + // 1.1. get line parameter + double lambda = (-(helper_vectorPC.dot (N))) / N.dot (N); + + // Projected Point on plane + Eigen::Vector3d P_proj = P + lambda * N; + Eigen::Vector3d helper_vectorP_projC = P_proj - C; + + // K : Point on Circle + Eigen::Vector3d K = C + r * helper_vectorP_projC.normalized (); + Eigen::Vector3d distanceVector = P - K; + + if (distanceVector.norm () < threshold) + nr_p++; + } + return (nr_p); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCircle3D::optimizeModelCoefficients ( + const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + Eigen::VectorXf &optimized_coefficients) +{ + optimized_coefficients = model_coefficients; + + // Needs a set of valid model coefficients + if (model_coefficients.size () != 7) + { + PCL_ERROR ("[pcl::SampleConsensusModelCircle3D::optimizeModelCoefficients] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return; + } + + // Need at least 3 samples + if (inliers.size () <= 3) + { + PCL_ERROR ("[pcl::SampleConsensusModelCircle3D::optimizeModelCoefficients] Not enough inliers found to support a model (%lu)! Returning the same coefficients.\n", inliers.size ()); + return; + } + + tmp_inliers_ = &inliers; + + OptimizationFunctor functor (static_cast (inliers.size ()), this); + Eigen::NumericalDiff num_diff (functor); + Eigen::LevenbergMarquardt, double> lm (num_diff); + Eigen::VectorXd coeff; + int info = lm.minimize (coeff); + for (int i = 0; i < coeff.size (); ++i) + optimized_coefficients[i] = static_cast (coeff[i]); + + // Compute the L2 norm of the residuals + PCL_DEBUG ("[pcl::SampleConsensusModelCircle3D::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g %g %g %g \nFinal solution: %g %g %g %g %g %g %g\n", + info, lm.fvec.norm (), model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], model_coefficients[4], model_coefficients[5], model_coefficients[6], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2], optimized_coefficients[3], optimized_coefficients[4], optimized_coefficients[5], optimized_coefficients[6]); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCircle3D::projectPoints ( + const std::vector &inliers, const Eigen::VectorXf &model_coefficients, + PointCloud &projected_points, bool copy_data_fields) +{ + // Needs a valid set of model coefficients + if (model_coefficients.size () != 7) + { + PCL_ERROR ("[pcl::SampleConsensusModelCircle3D::projectPoints] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return; + } + + projected_points.header = input_->header; + projected_points.is_dense = input_->is_dense; + + // Copy all the data fields from the input cloud to the projected one? + if (copy_data_fields) + { + // Allocate enough space and copy the basics + projected_points.points.resize (input_->points.size ()); + projected_points.width = input_->width; + projected_points.height = input_->height; + + typedef typename pcl::traits::fieldList::type FieldList; + // Iterate over each point + for (size_t i = 0; i < projected_points.points.size (); ++i) + // Iterate over each dimension + pcl::for_each_type (NdConcatenateFunctor (input_->points[i], projected_points.points[i])); + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < inliers.size (); ++i) + { + // what i have: + // P : Sample Point + Eigen::Vector3d P (input_->points[inliers[i]].x, input_->points[inliers[i]].y, input_->points[inliers[i]].z); + // C : Circle Center + Eigen::Vector3d C (model_coefficients[0], model_coefficients[1], model_coefficients[2]); + // N : Circle (Plane) Normal + Eigen::Vector3d N (model_coefficients[4], model_coefficients[5], model_coefficients[6]); + // r : Radius + double r = model_coefficients[3]; + + Eigen::Vector3d helper_vectorPC = P - C; + // 1.1. get line parameter + //float lambda = (helper_vectorPC.dot(N)) / N.squaredNorm() ; + double lambda = (-(helper_vectorPC.dot (N))) / N.dot (N); + // Projected Point on plane + Eigen::Vector3d P_proj = P + lambda * N; + Eigen::Vector3d helper_vectorP_projC = P_proj - C; + + // K : Point on Circle + Eigen::Vector3d K = C + r * helper_vectorP_projC.normalized (); + + projected_points.points[i].x = static_cast (K[0]); + projected_points.points[i].y = static_cast (K[1]); + projected_points.points[i].z = static_cast (K[2]); + } + } + else + { + // Allocate enough space and copy the basics + projected_points.points.resize (inliers.size ()); + projected_points.width = uint32_t (inliers.size ()); + projected_points.height = 1; + + typedef typename pcl::traits::fieldList::type FieldList; + // Iterate over each point + for (size_t i = 0; i < inliers.size (); ++i) + // Iterate over each dimension + pcl::for_each_type (NdConcatenateFunctor (input_->points[inliers[i]], projected_points.points[i])); + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < inliers.size (); ++i) + { + // what i have: + // P : Sample Point + Eigen::Vector3d P (input_->points[inliers[i]].x, input_->points[inliers[i]].y, input_->points[inliers[i]].z); + // C : Circle Center + Eigen::Vector3d C (model_coefficients[0], model_coefficients[1], model_coefficients[2]); + // N : Circle (Plane) Normal + Eigen::Vector3d N (model_coefficients[4], model_coefficients[5], model_coefficients[6]); + // r : Radius + double r = model_coefficients[3]; + + Eigen::Vector3d helper_vectorPC = P - C; + // 1.1. get line parameter + double lambda = (-(helper_vectorPC.dot (N))) / N.dot (N); + // Projected Point on plane + Eigen::Vector3d P_proj = P + lambda * N; + Eigen::Vector3d helper_vectorP_projC = P_proj - C; + + // K : Point on Circle + Eigen::Vector3d K = C + r * helper_vectorP_projC.normalized (); + + projected_points.points[i].x = static_cast (K[0]); + projected_points.points[i].y = static_cast (K[1]); + projected_points.points[i].z = static_cast (K[2]); + } + } +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCircle3D::doSamplesVerifyModel ( + const std::set &indices, + const Eigen::VectorXf &model_coefficients, + const double threshold) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 7) + { + PCL_ERROR ("[pcl::SampleConsensusModelCircle3D::doSamplesVerifyModel] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + for (std::set::const_iterator it = indices.begin (); it != indices.end (); ++it) + { + // Calculate the distance from the point to the sphere as the difference between + //dist(point,sphere_origin) and sphere_radius + + // what i have: + // P : Sample Point + Eigen::Vector3d P (input_->points[*it].x, input_->points[*it].y, input_->points[*it].z); + // C : Circle Center + Eigen::Vector3d C (model_coefficients[0], model_coefficients[1], model_coefficients[2]); + // N : Circle (Plane) Normal + Eigen::Vector3d N (model_coefficients[4], model_coefficients[5], model_coefficients[6]); + // r : Radius + double r = model_coefficients[3]; + Eigen::Vector3d helper_vectorPC = P - C; + // 1.1. get line parameter + double lambda = (-(helper_vectorPC.dot (N))) / N.dot (N); + // Projected Point on plane + Eigen::Vector3d P_proj = P + lambda * N; + Eigen::Vector3d helper_vectorP_projC = P_proj - C; + + // K : Point on Circle + Eigen::Vector3d K = C + r * helper_vectorP_projC.normalized (); + Eigen::Vector3d distanceVector = P - K; + + if (distanceVector.norm () > threshold) + return (false); + } + return (true); +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCircle3D::isModelValid (const Eigen::VectorXf &model_coefficients) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 7) + { + PCL_ERROR ("[pcl::SampleConsensusModelCircle3D::isModelValid] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + if (radius_min_ != -DBL_MAX && model_coefficients[3] < radius_min_) + return (false); + if (radius_max_ != DBL_MAX && model_coefficients[3] > radius_max_) + return (false); + + return (true); +} + +#define PCL_INSTANTIATE_SampleConsensusModelCircle3D(T) template class PCL_EXPORTS pcl::SampleConsensusModelCircle3D; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CIRCLE3D_HPP_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_cone.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_cone.hpp new file mode 100644 index 0000000..aca3df5 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_cone.hpp @@ -0,0 +1,529 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CONE_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CONE_H_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCone::isSampleGood(const std::vector &) const +{ + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCone::computeModelCoefficients ( + const std::vector &samples, Eigen::VectorXf &model_coefficients) +{ + // Need 3 samples + if (samples.size () != 3) + { + PCL_ERROR ("[pcl::SampleConsensusModelCone::computeModelCoefficients] Invalid set of samples given (%lu)!\n", samples.size ()); + return (false); + } + + if (!normals_) + { + PCL_ERROR ("[pcl::SampleConsensusModelCone::computeModelCoefficients] No input dataset containing normals was given!\n"); + return (false); + } + + Eigen::Vector4f p1 (input_->points[samples[0]].x, input_->points[samples[0]].y, input_->points[samples[0]].z, 0); + Eigen::Vector4f p2 (input_->points[samples[1]].x, input_->points[samples[1]].y, input_->points[samples[1]].z, 0); + Eigen::Vector4f p3 (input_->points[samples[2]].x, input_->points[samples[2]].y, input_->points[samples[2]].z, 0); + + Eigen::Vector4f n1 (normals_->points[samples[0]].normal[0], normals_->points[samples[0]].normal[1], normals_->points[samples[0]].normal[2], 0); + Eigen::Vector4f n2 (normals_->points[samples[1]].normal[0], normals_->points[samples[1]].normal[1], normals_->points[samples[1]].normal[2], 0); + Eigen::Vector4f n3 (normals_->points[samples[2]].normal[0], normals_->points[samples[2]].normal[1], normals_->points[samples[2]].normal[2], 0); + + //calculate apex (intersection of the three planes defined by points and belonging normals + Eigen::Vector4f ortho12 = n1.cross3(n2); + Eigen::Vector4f ortho23 = n2.cross3(n3); + Eigen::Vector4f ortho31 = n3.cross3(n1); + + float denominator = n1.dot(ortho23); + + float d1 = p1.dot (n1); + float d2 = p2.dot (n2); + float d3 = p3.dot (n3); + + Eigen::Vector4f apex = (d1 * ortho23 + d2 * ortho31 + d3 * ortho12) / denominator; + + //compute axis (normal of plane defined by: { apex+(p1-apex)/(||p1-apex||), apex+(p2-apex)/(||p2-apex||), apex+(p3-apex)/(||p3-apex||)} + Eigen::Vector4f ap1 = p1 - apex; + Eigen::Vector4f ap2 = p2 - apex; + Eigen::Vector4f ap3 = p3 - apex; + + Eigen::Vector4f np1 = apex + (ap1/ap1.norm ()); + Eigen::Vector4f np2 = apex + (ap2/ap2.norm ()); + Eigen::Vector4f np3 = apex + (ap3/ap3.norm ()); + + Eigen::Vector4f np1np2 = np2 - np1; + Eigen::Vector4f np1np3 = np3 - np1; + + Eigen::Vector4f axis_dir = np1np2.cross3 (np1np3); + axis_dir.normalize (); + + // normalize the vector (apex->p) for opening angle calculation + ap1.normalize (); + ap2.normalize (); + ap3.normalize (); + + //compute opening angle + float opening_angle = ( acosf (ap1.dot (axis_dir)) + acosf (ap2.dot (axis_dir)) + acosf (ap3.dot (axis_dir)) ) / 3.0f; + + model_coefficients.resize (7); + // model_coefficients.template head<3> () = line_pt.template head<3> (); + model_coefficients[0] = apex[0]; + model_coefficients[1] = apex[1]; + model_coefficients[2] = apex[2]; + // model_coefficients.template segment<3> (3) = line_dir.template head<3> (); + model_coefficients[3] = axis_dir[0]; + model_coefficients[4] = axis_dir[1]; + model_coefficients[5] = axis_dir[2]; + // cone radius + model_coefficients[6] = opening_angle; + + if (model_coefficients[6] != -std::numeric_limits::max() && model_coefficients[6] < min_angle_) + return (false); + if (model_coefficients[6] != std::numeric_limits::max() && model_coefficients[6] > max_angle_) + return (false); + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCone::getDistancesToModel ( + const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + distances.clear (); + return; + } + + distances.resize (indices_->size ()); + + Eigen::Vector4f apex (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f axis_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + float opening_angle = model_coefficients[6]; + + float apexdotdir = apex.dot (axis_dir); + float dirdotdir = 1.0f / axis_dir.dot (axis_dir); + // Iterate through the 3d points and calculate the distances from them to the cone + for (size_t i = 0; i < indices_->size (); ++i) + { + Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 0); + Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0); + + // Calculate the point's projection on the cone axis + float k = (pt.dot (axis_dir) - apexdotdir) * dirdotdir; + Eigen::Vector4f pt_proj = apex + k * axis_dir; + Eigen::Vector4f dir = pt - pt_proj; + dir.normalize (); + + // Calculate the actual radius of the cone at the level of the projected point + Eigen::Vector4f height = apex - pt_proj; + float actual_cone_radius = tanf (opening_angle) * height.norm (); + height.normalize (); + + // Calculate the cones perfect normals + Eigen::Vector4f cone_normal = sinf (opening_angle) * height + cosf (opening_angle) * dir; + + // Aproximate the distance from the point to the cone as the difference between + // dist(point,cone_axis) and actual cone radius + double d_euclid = fabs (pointToAxisDistance (pt, model_coefficients) - actual_cone_radius); + + // Calculate the angular distance between the point normal and the (dir=pt_proj->pt) vector + double d_normal = fabs (getAngle3D (n, cone_normal)); + d_normal = (std::min) (d_normal, M_PI - d_normal); + + distances[i] = fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCone::selectWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold, std::vector &inliers) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + inliers.clear (); + return; + } + + int nr_p = 0; + inliers.resize (indices_->size ()); + error_sqr_dists_.resize (indices_->size ()); + + Eigen::Vector4f apex (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f axis_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + float opening_angle = model_coefficients[6]; + + float apexdotdir = apex.dot (axis_dir); + float dirdotdir = 1.0f / axis_dir.dot (axis_dir); + // Iterate through the 3d points and calculate the distances from them to the cone + for (size_t i = 0; i < indices_->size (); ++i) + { + Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 0); + Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0); + + // Calculate the point's projection on the cone axis + float k = (pt.dot (axis_dir) - apexdotdir) * dirdotdir; + Eigen::Vector4f pt_proj = apex + k * axis_dir; + + // Calculate the direction of the point from center + Eigen::Vector4f pp_pt_dir = pt - pt_proj; + pp_pt_dir.normalize (); + + // Calculate the actual radius of the cone at the level of the projected point + Eigen::Vector4f height = apex - pt_proj; + double actual_cone_radius = tan(opening_angle) * height.norm (); + height.normalize (); + + // Calculate the cones perfect normals + Eigen::Vector4f cone_normal = sinf (opening_angle) * height + cosf (opening_angle) * pp_pt_dir; + + // Aproximate the distance from the point to the cone as the difference between + // dist(point,cone_axis) and actual cone radius + double d_euclid = fabs (pointToAxisDistance (pt, model_coefficients) - actual_cone_radius); + + // Calculate the angular distance between the point normal and the (dir=pt_proj->pt) vector + double d_normal = fabs (getAngle3D (n, cone_normal)); + d_normal = (std::min) (d_normal, M_PI - d_normal); + + double distance = fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid); + + if (distance < threshold) + { + // Returns the indices of the points whose distances are smaller than the threshold + inliers[nr_p] = (*indices_)[i]; + error_sqr_dists_[nr_p] = distance; + ++nr_p; + } + } + inliers.resize (nr_p); + error_sqr_dists_.resize (nr_p); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelCone::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + return (0); + + int nr_p = 0; + + Eigen::Vector4f apex (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f axis_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + float opening_angle = model_coefficients[6]; + + float apexdotdir = apex.dot (axis_dir); + float dirdotdir = 1.0f / axis_dir.dot (axis_dir); + // Iterate through the 3d points and calculate the distances from them to the cone + for (size_t i = 0; i < indices_->size (); ++i) + { + Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 0); + Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0); + + // Calculate the point's projection on the cone axis + float k = (pt.dot (axis_dir) - apexdotdir) * dirdotdir; + Eigen::Vector4f pt_proj = apex + k * axis_dir; + + // Calculate the direction of the point from center + Eigen::Vector4f pp_pt_dir = pt - pt_proj; + pp_pt_dir.normalize (); + + // Calculate the actual radius of the cone at the level of the projected point + Eigen::Vector4f height = apex - pt_proj; + double actual_cone_radius = tan(opening_angle) * height.norm (); + height.normalize (); + + // Calculate the cones perfect normals + Eigen::Vector4f cone_normal = sinf (opening_angle) * height + cosf (opening_angle) * pp_pt_dir; + + // Aproximate the distance from the point to the cone as the difference between + // dist(point,cone_axis) and actual cone radius + double d_euclid = fabs (pointToAxisDistance (pt, model_coefficients) - actual_cone_radius); + + // Calculate the angular distance between the point normal and the (dir=pt_proj->pt) vector + double d_normal = fabs (getAngle3D (n, cone_normal)); + d_normal = (std::min) (d_normal, M_PI - d_normal); + + if (fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid) < threshold) + nr_p++; + } + return (nr_p); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCone::optimizeModelCoefficients ( + const std::vector &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients) +{ + optimized_coefficients = model_coefficients; + + // Needs a set of valid model coefficients + if (model_coefficients.size () != 7) + { + PCL_ERROR ("[pcl::SampleConsensusModelCone::optimizeModelCoefficients] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return; + } + + if (inliers.empty ()) + { + PCL_DEBUG ("[pcl::SampleConsensusModelCone:optimizeModelCoefficients] Inliers vector empty! Returning the same coefficients.\n"); + return; + } + + tmp_inliers_ = &inliers; + + OptimizationFunctor functor (static_cast (inliers.size ()), this); + Eigen::NumericalDiff num_diff (functor); + Eigen::LevenbergMarquardt, float> lm (num_diff); + int info = lm.minimize (optimized_coefficients); + + // Compute the L2 norm of the residuals + PCL_DEBUG ("[pcl::SampleConsensusModelCone::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g %g %g %g \nFinal solution: %g %g %g %g %g %g %g\n", + info, lm.fvec.norm (), model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], + model_coefficients[4], model_coefficients[5], model_coefficients[6], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2], optimized_coefficients[3], optimized_coefficients[4], optimized_coefficients[5], optimized_coefficients[6]); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCone::projectPoints ( + const std::vector &inliers, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool copy_data_fields) +{ + // Needs a valid set of model coefficients + if (model_coefficients.size () != 7) + { + PCL_ERROR ("[pcl::SampleConsensusModelCone::projectPoints] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return; + } + + projected_points.header = input_->header; + projected_points.is_dense = input_->is_dense; + + Eigen::Vector4f apex (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f axis_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + float opening_angle = model_coefficients[6]; + + float apexdotdir = apex.dot (axis_dir); + float dirdotdir = 1.0f / axis_dir.dot (axis_dir); + + // Copy all the data fields from the input cloud to the projected one? + if (copy_data_fields) + { + // Allocate enough space and copy the basics + projected_points.points.resize (input_->points.size ()); + projected_points.width = input_->width; + projected_points.height = input_->height; + + typedef typename pcl::traits::fieldList::type FieldList; + // Iterate over each point + for (size_t i = 0; i < projected_points.points.size (); ++i) + // Iterate over each dimension + pcl::for_each_type (NdConcatenateFunctor (input_->points[i], projected_points.points[i])); + + // Iterate through the 3d points and calculate the distances from them to the cone + for (size_t i = 0; i < inliers.size (); ++i) + { + Eigen::Vector4f pt (input_->points[inliers[i]].x, + input_->points[inliers[i]].y, + input_->points[inliers[i]].z, + 1); + + float k = (pt.dot (axis_dir) - apexdotdir) * dirdotdir; + + pcl::Vector4fMap pp = projected_points.points[inliers[i]].getVector4fMap (); + pp.matrix () = apex + k * axis_dir; + + Eigen::Vector4f dir = pt - pp; + dir.normalize (); + + // Calculate the actual radius of the cone at the level of the projected point + Eigen::Vector4f height = apex - pp; + float actual_cone_radius = tanf (opening_angle) * height.norm (); + + // Calculate the projection of the point onto the cone + pp += dir * actual_cone_radius; + } + } + else + { + // Allocate enough space and copy the basics + projected_points.points.resize (inliers.size ()); + projected_points.width = static_cast (inliers.size ()); + projected_points.height = 1; + + typedef typename pcl::traits::fieldList::type FieldList; + // Iterate over each point + for (size_t i = 0; i < inliers.size (); ++i) + // Iterate over each dimension + pcl::for_each_type (NdConcatenateFunctor (input_->points[inliers[i]], projected_points.points[i])); + + // Iterate through the 3d points and calculate the distances from them to the cone + for (size_t i = 0; i < inliers.size (); ++i) + { + pcl::Vector4fMap pp = projected_points.points[i].getVector4fMap (); + pcl::Vector4fMapConst pt = input_->points[inliers[i]].getVector4fMap (); + + float k = (pt.dot (axis_dir) - apexdotdir) * dirdotdir; + // Calculate the projection of the point on the line + pp.matrix () = apex + k * axis_dir; + + Eigen::Vector4f dir = pt - pp; + dir.normalize (); + + // Calculate the actual radius of the cone at the level of the projected point + Eigen::Vector4f height = apex - pp; + float actual_cone_radius = tanf (opening_angle) * height.norm (); + + // Calculate the projection of the point onto the cone + pp += dir * actual_cone_radius; + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCone::doSamplesVerifyModel ( + const std::set &indices, const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 7) + { + PCL_ERROR ("[pcl::SampleConsensusModelCone::doSamplesVerifyModel] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + Eigen::Vector4f apex (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f axis_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + float openning_angle = model_coefficients[6]; + + float apexdotdir = apex.dot (axis_dir); + float dirdotdir = 1.0f / axis_dir.dot (axis_dir); + + // Iterate through the 3d points and calculate the distances from them to the cone + for (std::set::const_iterator it = indices.begin (); it != indices.end (); ++it) + { + Eigen::Vector4f pt (input_->points[*it].x, input_->points[*it].y, input_->points[*it].z, 0); + + // Calculate the point's projection on the cone axis + float k = (pt.dot (axis_dir) - apexdotdir) * dirdotdir; + Eigen::Vector4f pt_proj = apex + k * axis_dir; + Eigen::Vector4f dir = pt - pt_proj; + dir.normalize (); + + // Calculate the actual radius of the cone at the level of the projected point + Eigen::Vector4f height = apex - pt_proj; + double actual_cone_radius = tan (openning_angle) * height.norm (); + + // Aproximate the distance from the point to the cone as the difference between + // dist(point,cone_axis) and actual cone radius + if (fabs (static_cast(pointToAxisDistance (pt, model_coefficients) - actual_cone_radius)) > threshold) + return (false); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::SampleConsensusModelCone::pointToAxisDistance ( + const Eigen::Vector4f &pt, const Eigen::VectorXf &model_coefficients) +{ + Eigen::Vector4f apex (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f axis_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + return sqrt(pcl::sqrPointToLineDistance (pt, apex, axis_dir)); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCone::isModelValid (const Eigen::VectorXf &model_coefficients) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 7) + { + PCL_ERROR ("[pcl::SampleConsensusModelCone::isModelValid] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + // Check against template, if given + if (eps_angle_ > 0.0) + { + // Obtain the cone direction + Eigen::Vector4f coeff; + coeff[0] = model_coefficients[3]; + coeff[1] = model_coefficients[4]; + coeff[2] = model_coefficients[5]; + coeff[3] = 0; + + Eigen::Vector4f axis (axis_[0], axis_[1], axis_[2], 0); + double angle_diff = fabs (getAngle3D (axis, coeff)); + angle_diff = (std::min) (angle_diff, M_PI - angle_diff); + // Check whether the current cone model satisfies our angle threshold criterion with respect to the given axis + if (angle_diff > eps_angle_) + return (false); + } + + if (model_coefficients[6] != -std::numeric_limits::max() && model_coefficients[6] < min_angle_) + return (false); + if (model_coefficients[6] != std::numeric_limits::max() && model_coefficients[6] > max_angle_) + return (false); + + return (true); +} + +#define PCL_INSTANTIATE_SampleConsensusModelCone(PointT, PointNT) template class PCL_EXPORTS pcl::SampleConsensusModelCone; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CONE_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_cylinder.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_cylinder.hpp new file mode 100644 index 0000000..fb3a324 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_cylinder.hpp @@ -0,0 +1,482 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CYLINDER_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CYLINDER_H_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCylinder::isSampleGood (const std::vector &) const +{ + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCylinder::computeModelCoefficients ( + const std::vector &samples, Eigen::VectorXf &model_coefficients) +{ + // Need 2 samples + if (samples.size () != 2) + { + PCL_ERROR ("[pcl::SampleConsensusModelCylinder::computeModelCoefficients] Invalid set of samples given (%lu)!\n", samples.size ()); + return (false); + } + + if (!normals_) + { + PCL_ERROR ("[pcl::SampleConsensusModelCylinder::computeModelCoefficients] No input dataset containing normals was given!\n"); + return (false); + } + + if (fabs (input_->points[samples[0]].x - input_->points[samples[1]].x) <= std::numeric_limits::epsilon () && + fabs (input_->points[samples[0]].y - input_->points[samples[1]].y) <= std::numeric_limits::epsilon () && + fabs (input_->points[samples[0]].z - input_->points[samples[1]].z) <= std::numeric_limits::epsilon ()) + { + return (false); + } + + Eigen::Vector4f p1 (input_->points[samples[0]].x, input_->points[samples[0]].y, input_->points[samples[0]].z, 0); + Eigen::Vector4f p2 (input_->points[samples[1]].x, input_->points[samples[1]].y, input_->points[samples[1]].z, 0); + + Eigen::Vector4f n1 (normals_->points[samples[0]].normal[0], normals_->points[samples[0]].normal[1], normals_->points[samples[0]].normal[2], 0); + Eigen::Vector4f n2 (normals_->points[samples[1]].normal[0], normals_->points[samples[1]].normal[1], normals_->points[samples[1]].normal[2], 0); + Eigen::Vector4f w = n1 + p1 - p2; + + float a = n1.dot (n1); + float b = n1.dot (n2); + float c = n2.dot (n2); + float d = n1.dot (w); + float e = n2.dot (w); + float denominator = a*c - b*b; + float sc, tc; + // Compute the line parameters of the two closest points + if (denominator < 1e-8) // The lines are almost parallel + { + sc = 0.0f; + tc = (b > c ? d / b : e / c); // Use the largest denominator + } + else + { + sc = (b*e - c*d) / denominator; + tc = (a*e - b*d) / denominator; + } + + // point_on_axis, axis_direction + Eigen::Vector4f line_pt = p1 + n1 + sc * n1; + Eigen::Vector4f line_dir = p2 + tc * n2 - line_pt; + line_dir.normalize (); + + model_coefficients.resize (7); + // model_coefficients.template head<3> () = line_pt.template head<3> (); + model_coefficients[0] = line_pt[0]; + model_coefficients[1] = line_pt[1]; + model_coefficients[2] = line_pt[2]; + // model_coefficients.template segment<3> (3) = line_dir.template head<3> (); + model_coefficients[3] = line_dir[0]; + model_coefficients[4] = line_dir[1]; + model_coefficients[5] = line_dir[2]; + // cylinder radius + model_coefficients[6] = static_cast (sqrt (pcl::sqrPointToLineDistance (p1, line_pt, line_dir))); + + if (model_coefficients[6] > radius_max_ || model_coefficients[6] < radius_min_) + return (false); + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCylinder::getDistancesToModel ( + const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + distances.clear (); + return; + } + + distances.resize (indices_->size ()); + + Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + float ptdotdir = line_pt.dot (line_dir); + float dirdotdir = 1.0f / line_dir.dot (line_dir); + // Iterate through the 3d points and calculate the distances from them to the sphere + for (size_t i = 0; i < indices_->size (); ++i) + { + // Aproximate the distance from the point to the cylinder as the difference between + // dist(point,cylinder_axis) and cylinder radius + // @note need to revise this. + Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 0); + Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0); + + double d_euclid = fabs (pointToLineDistance (pt, model_coefficients) - model_coefficients[6]); + + // Calculate the point's projection on the cylinder axis + float k = (pt.dot (line_dir) - ptdotdir) * dirdotdir; + Eigen::Vector4f pt_proj = line_pt + k * line_dir; + Eigen::Vector4f dir = pt - pt_proj; + dir.normalize (); + + // Calculate the angular distance between the point normal and the (dir=pt_proj->pt) vector + double d_normal = fabs (getAngle3D (n, dir)); + d_normal = (std::min) (d_normal, M_PI - d_normal); + + distances[i] = fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCylinder::selectWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold, std::vector &inliers) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + inliers.clear (); + return; + } + + int nr_p = 0; + inliers.resize (indices_->size ()); + error_sqr_dists_.resize (indices_->size ()); + + Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + float ptdotdir = line_pt.dot (line_dir); + float dirdotdir = 1.0f / line_dir.dot (line_dir); + // Iterate through the 3d points and calculate the distances from them to the sphere + for (size_t i = 0; i < indices_->size (); ++i) + { + // Aproximate the distance from the point to the cylinder as the difference between + // dist(point,cylinder_axis) and cylinder radius + Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 0); + Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0); + double d_euclid = fabs (pointToLineDistance (pt, model_coefficients) - model_coefficients[6]); + + // Calculate the point's projection on the cylinder axis + float k = (pt.dot (line_dir) - ptdotdir) * dirdotdir; + Eigen::Vector4f pt_proj = line_pt + k * line_dir; + Eigen::Vector4f dir = pt - pt_proj; + dir.normalize (); + + // Calculate the angular distance between the point normal and the (dir=pt_proj->pt) vector + double d_normal = fabs (getAngle3D (n, dir)); + d_normal = (std::min) (d_normal, M_PI - d_normal); + + double distance = fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid); + if (distance < threshold) + { + // Returns the indices of the points whose distances are smaller than the threshold + inliers[nr_p] = (*indices_)[i]; + error_sqr_dists_[nr_p] = distance; + ++nr_p; + } + } + inliers.resize (nr_p); + error_sqr_dists_.resize (nr_p); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelCylinder::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + return (0); + + int nr_p = 0; + + Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + float ptdotdir = line_pt.dot (line_dir); + float dirdotdir = 1.0f / line_dir.dot (line_dir); + // Iterate through the 3d points and calculate the distances from them to the sphere + for (size_t i = 0; i < indices_->size (); ++i) + { + // Aproximate the distance from the point to the cylinder as the difference between + // dist(point,cylinder_axis) and cylinder radius + Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 0); + Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0); + double d_euclid = fabs (pointToLineDistance (pt, model_coefficients) - model_coefficients[6]); + + // Calculate the point's projection on the cylinder axis + float k = (pt.dot (line_dir) - ptdotdir) * dirdotdir; + Eigen::Vector4f pt_proj = line_pt + k * line_dir; + Eigen::Vector4f dir = pt - pt_proj; + dir.normalize (); + + // Calculate the angular distance between the point normal and the (dir=pt_proj->pt) vector + double d_normal = fabs (getAngle3D (n, dir)); + d_normal = (std::min) (d_normal, M_PI - d_normal); + + if (fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid) < threshold) + nr_p++; + } + return (nr_p); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCylinder::optimizeModelCoefficients ( + const std::vector &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients) +{ + optimized_coefficients = model_coefficients; + + // Needs a set of valid model coefficients + if (model_coefficients.size () != 7) + { + PCL_ERROR ("[pcl::SampleConsensusModelCylinder::optimizeModelCoefficients] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return; + } + + if (inliers.empty ()) + { + PCL_DEBUG ("[pcl::SampleConsensusModelCylinder:optimizeModelCoefficients] Inliers vector empty! Returning the same coefficients.\n"); + return; + } + + tmp_inliers_ = &inliers; + + OptimizationFunctor functor (static_cast (inliers.size ()), this); + Eigen::NumericalDiff num_diff (functor); + Eigen::LevenbergMarquardt, float> lm (num_diff); + int info = lm.minimize (optimized_coefficients); + + // Compute the L2 norm of the residuals + PCL_DEBUG ("[pcl::SampleConsensusModelCylinder::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g %g %g %g \nFinal solution: %g %g %g %g %g %g %g\n", + info, lm.fvec.norm (), model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], + model_coefficients[4], model_coefficients[5], model_coefficients[6], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2], optimized_coefficients[3], optimized_coefficients[4], optimized_coefficients[5], optimized_coefficients[6]); + + Eigen::Vector3f line_dir (optimized_coefficients[3], optimized_coefficients[4], optimized_coefficients[5]); + line_dir.normalize (); + optimized_coefficients[3] = line_dir[0]; + optimized_coefficients[4] = line_dir[1]; + optimized_coefficients[5] = line_dir[2]; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCylinder::projectPoints ( + const std::vector &inliers, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool copy_data_fields) +{ + // Needs a valid set of model coefficients + if (model_coefficients.size () != 7) + { + PCL_ERROR ("[pcl::SampleConsensusModelCylinder::projectPoints] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return; + } + + projected_points.header = input_->header; + projected_points.is_dense = input_->is_dense; + + Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + float ptdotdir = line_pt.dot (line_dir); + float dirdotdir = 1.0f / line_dir.dot (line_dir); + + // Copy all the data fields from the input cloud to the projected one? + if (copy_data_fields) + { + // Allocate enough space and copy the basics + projected_points.points.resize (input_->points.size ()); + projected_points.width = input_->width; + projected_points.height = input_->height; + + typedef typename pcl::traits::fieldList::type FieldList; + // Iterate over each point + for (size_t i = 0; i < projected_points.points.size (); ++i) + // Iterate over each dimension + pcl::for_each_type (NdConcatenateFunctor (input_->points[i], projected_points.points[i])); + + // Iterate through the 3d points and calculate the distances from them to the cylinder + for (size_t i = 0; i < inliers.size (); ++i) + { + Eigen::Vector4f p (input_->points[inliers[i]].x, + input_->points[inliers[i]].y, + input_->points[inliers[i]].z, + 1); + + float k = (p.dot (line_dir) - ptdotdir) * dirdotdir; + + pcl::Vector4fMap pp = projected_points.points[inliers[i]].getVector4fMap (); + pp.matrix () = line_pt + k * line_dir; + + Eigen::Vector4f dir = p - pp; + dir.normalize (); + + // Calculate the projection of the point onto the cylinder + pp += dir * model_coefficients[6]; + } + } + else + { + // Allocate enough space and copy the basics + projected_points.points.resize (inliers.size ()); + projected_points.width = static_cast (inliers.size ()); + projected_points.height = 1; + + typedef typename pcl::traits::fieldList::type FieldList; + // Iterate over each point + for (size_t i = 0; i < inliers.size (); ++i) + // Iterate over each dimension + pcl::for_each_type (NdConcatenateFunctor (input_->points[inliers[i]], projected_points.points[i])); + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < inliers.size (); ++i) + { + pcl::Vector4fMap pp = projected_points.points[i].getVector4fMap (); + pcl::Vector4fMapConst p = input_->points[inliers[i]].getVector4fMap (); + + float k = (p.dot (line_dir) - ptdotdir) * dirdotdir; + // Calculate the projection of the point on the line + pp.matrix () = line_pt + k * line_dir; + + Eigen::Vector4f dir = p - pp; + dir.normalize (); + + // Calculate the projection of the point onto the cylinder + pp += dir * model_coefficients[6]; + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCylinder::doSamplesVerifyModel ( + const std::set &indices, const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 7) + { + PCL_ERROR ("[pcl::SampleConsensusModelCylinder::doSamplesVerifyModel] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + for (std::set::const_iterator it = indices.begin (); it != indices.end (); ++it) + { + // Aproximate the distance from the point to the cylinder as the difference between + // dist(point,cylinder_axis) and cylinder radius + // @note need to revise this. + Eigen::Vector4f pt (input_->points[*it].x, input_->points[*it].y, input_->points[*it].z, 0); + if (fabs (pointToLineDistance (pt, model_coefficients) - model_coefficients[6]) > threshold) + return (false); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::SampleConsensusModelCylinder::pointToLineDistance ( + const Eigen::Vector4f &pt, const Eigen::VectorXf &model_coefficients) +{ + Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + return sqrt(pcl::sqrPointToLineDistance (pt, line_pt, line_dir)); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelCylinder::projectPointToCylinder ( + const Eigen::Vector4f &pt, const Eigen::VectorXf &model_coefficients, Eigen::Vector4f &pt_proj) +{ + Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + + float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) * line_dir.dot (line_dir); + pt_proj = line_pt + k * line_dir; + + Eigen::Vector4f dir = pt - pt_proj; + dir.normalize (); + + // Calculate the projection of the point onto the cylinder + pt_proj += dir * model_coefficients[6]; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelCylinder::isModelValid (const Eigen::VectorXf &model_coefficients) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 7) + { + PCL_ERROR ("[pcl::SampleConsensusModelCylinder::isModelValid] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + // Check against template, if given + if (eps_angle_ > 0.0) + { + // Obtain the cylinder direction + Eigen::Vector4f coeff; + coeff[0] = model_coefficients[3]; + coeff[1] = model_coefficients[4]; + coeff[2] = model_coefficients[5]; + coeff[3] = 0; + + Eigen::Vector4f axis (axis_[0], axis_[1], axis_[2], 0); + double angle_diff = fabs (getAngle3D (axis, coeff)); + angle_diff = (std::min) (angle_diff, M_PI - angle_diff); + // Check whether the current cylinder model satisfies our angle threshold criterion with respect to the given axis + if (angle_diff > eps_angle_) + return (false); + } + + if (radius_min_ != -std::numeric_limits::max() && model_coefficients[6] < radius_min_) + return (false); + if (radius_max_ != std::numeric_limits::max() && model_coefficients[6] > radius_max_) + return (false); + + return (true); +} + +#define PCL_INSTANTIATE_SampleConsensusModelCylinder(PointT, PointNT) template class PCL_EXPORTS pcl::SampleConsensusModelCylinder; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CYLINDER_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_line.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_line.hpp new file mode 100644 index 0000000..af019a1 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_line.hpp @@ -0,0 +1,335 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_LINE_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_LINE_H_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelLine::isSampleGood (const std::vector &samples) const +{ + if ( + (input_->points[samples[0]].x != input_->points[samples[1]].x) + && + (input_->points[samples[0]].y != input_->points[samples[1]].y) + && + (input_->points[samples[0]].z != input_->points[samples[1]].z)) + return (true); + + return (true); +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelLine::computeModelCoefficients ( + const std::vector &samples, Eigen::VectorXf &model_coefficients) +{ + // Need 2 samples + if (samples.size () != 2) + { + PCL_ERROR ("[pcl::SampleConsensusModelLine::computeModelCoefficients] Invalid set of samples given (%lu)!\n", samples.size ()); + return (false); + } + + if (fabs (input_->points[samples[0]].x - input_->points[samples[1]].x) <= std::numeric_limits::epsilon () && + fabs (input_->points[samples[0]].y - input_->points[samples[1]].y) <= std::numeric_limits::epsilon () && + fabs (input_->points[samples[0]].z - input_->points[samples[1]].z) <= std::numeric_limits::epsilon ()) + { + return (false); + } + + model_coefficients.resize (6); + model_coefficients[0] = input_->points[samples[0]].x; + model_coefficients[1] = input_->points[samples[0]].y; + model_coefficients[2] = input_->points[samples[0]].z; + + model_coefficients[3] = input_->points[samples[1]].x - model_coefficients[0]; + model_coefficients[4] = input_->points[samples[1]].y - model_coefficients[1]; + model_coefficients[5] = input_->points[samples[1]].z - model_coefficients[2]; + + model_coefficients.template tail<3> ().normalize (); + return (true); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelLine::getDistancesToModel ( + const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + // Needs a valid set of model coefficients + if (!isModelValid (model_coefficients)) + return; + + distances.resize (indices_->size ()); + + // Obtain the line point and direction + Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + line_dir.normalize (); + + // Iterate through the 3d points and calculate the distances from them to the line + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the line + // D = ||(P2-P1) x (P1-P0)|| / ||P2-P1|| = norm (cross (p2-p1, p2-p0)) / norm(p2-p1) + // Need to estimate sqrt here to keep MSAC and friends general + distances[i] = sqrt ((line_pt - input_->points[(*indices_)[i]].getVector4fMap ()).cross3 (line_dir).squaredNorm ()); + } +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelLine::selectWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold, std::vector &inliers) +{ + // Needs a valid set of model coefficients + if (!isModelValid (model_coefficients)) + return; + + double sqr_threshold = threshold * threshold; + + int nr_p = 0; + inliers.resize (indices_->size ()); + error_sqr_dists_.resize (indices_->size ()); + + // Obtain the line point and direction + Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + line_dir.normalize (); + + // Iterate through the 3d points and calculate the distances from them to the line + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the line + // D = ||(P2-P1) x (P1-P0)|| / ||P2-P1|| = norm (cross (p2-p1, p2-p0)) / norm(p2-p1) + double sqr_distance = (line_pt - input_->points[(*indices_)[i]].getVector4fMap ()).cross3 (line_dir).squaredNorm (); + + if (sqr_distance < sqr_threshold) + { + // Returns the indices of the points whose squared distances are smaller than the threshold + inliers[nr_p] = (*indices_)[i]; + error_sqr_dists_[nr_p] = sqr_distance; + ++nr_p; + } + } + inliers.resize (nr_p); + error_sqr_dists_.resize (nr_p); +} + +////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelLine::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Needs a valid set of model coefficients + if (!isModelValid (model_coefficients)) + return (0); + + double sqr_threshold = threshold * threshold; + + int nr_p = 0; + + // Obtain the line point and direction + Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + line_dir.normalize (); + + // Iterate through the 3d points and calculate the distances from them to the line + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the line + // D = ||(P2-P1) x (P1-P0)|| / ||P2-P1|| = norm (cross (p2-p1, p2-p0)) / norm(p2-p1) + double sqr_distance = (line_pt - input_->points[(*indices_)[i]].getVector4fMap ()).cross3 (line_dir).squaredNorm (); + + if (sqr_distance < sqr_threshold) + nr_p++; + } + return (nr_p); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelLine::optimizeModelCoefficients ( + const std::vector &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients) +{ + // Needs a valid set of model coefficients + if (!isModelValid (model_coefficients)) + { + optimized_coefficients = model_coefficients; + return; + } + + // Need at least 2 points to estimate a line + if (inliers.size () <= 2) + { + PCL_ERROR ("[pcl::SampleConsensusModelLine::optimizeModelCoefficients] Not enough inliers found to support a model (%lu)! Returning the same coefficients.\n", inliers.size ()); + optimized_coefficients = model_coefficients; + return; + } + + optimized_coefficients.resize (6); + + // Compute the 3x3 covariance matrix + Eigen::Vector4f centroid; + compute3DCentroid (*input_, inliers, centroid); + Eigen::Matrix3f covariance_matrix; + computeCovarianceMatrix (*input_, inliers, centroid, covariance_matrix); + optimized_coefficients[0] = centroid[0]; + optimized_coefficients[1] = centroid[1]; + optimized_coefficients[2] = centroid[2]; + + // Extract the eigenvalues and eigenvectors + EIGEN_ALIGN16 Eigen::Vector3f eigen_values; + EIGEN_ALIGN16 Eigen::Vector3f eigen_vector; + pcl::eigen33 (covariance_matrix, eigen_values); + pcl::computeCorrespondingEigenVector (covariance_matrix, eigen_values [2], eigen_vector); + //pcl::eigen33 (covariance_matrix, eigen_vectors, eigen_values); + + optimized_coefficients.template tail<3> ().matrix () = eigen_vector; +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelLine::projectPoints ( + const std::vector &inliers, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool copy_data_fields) +{ + // Needs a valid model coefficients + if (!isModelValid (model_coefficients)) + return; + + // Obtain the line point and direction + Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + + projected_points.header = input_->header; + projected_points.is_dense = input_->is_dense; + + // Copy all the data fields from the input cloud to the projected one? + if (copy_data_fields) + { + // Allocate enough space and copy the basics + projected_points.points.resize (input_->points.size ()); + projected_points.width = input_->width; + projected_points.height = input_->height; + + typedef typename pcl::traits::fieldList::type FieldList; + // Iterate over each point + for (size_t i = 0; i < projected_points.points.size (); ++i) + // Iterate over each dimension + pcl::for_each_type (NdConcatenateFunctor (input_->points[i], projected_points.points[i])); + + // Iterate through the 3d points and calculate the distances from them to the line + for (size_t i = 0; i < inliers.size (); ++i) + { + Eigen::Vector4f pt (input_->points[inliers[i]].x, input_->points[inliers[i]].y, input_->points[inliers[i]].z, 0); + // double k = (DOT_PROD_3D (points[i], p21) - dotA_B) / dotB_B; + float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) / line_dir.dot (line_dir); + + Eigen::Vector4f pp = line_pt + k * line_dir; + // Calculate the projection of the point on the line (pointProj = A + k * B) + projected_points.points[inliers[i]].x = pp[0]; + projected_points.points[inliers[i]].y = pp[1]; + projected_points.points[inliers[i]].z = pp[2]; + } + } + else + { + // Allocate enough space and copy the basics + projected_points.points.resize (inliers.size ()); + projected_points.width = static_cast (inliers.size ()); + projected_points.height = 1; + + typedef typename pcl::traits::fieldList::type FieldList; + // Iterate over each point + for (size_t i = 0; i < inliers.size (); ++i) + // Iterate over each dimension + pcl::for_each_type (NdConcatenateFunctor (input_->points[inliers[i]], projected_points.points[i])); + + // Iterate through the 3d points and calculate the distances from them to the line + for (size_t i = 0; i < inliers.size (); ++i) + { + Eigen::Vector4f pt (input_->points[inliers[i]].x, input_->points[inliers[i]].y, input_->points[inliers[i]].z, 0); + // double k = (DOT_PROD_3D (points[i], p21) - dotA_B) / dotB_B; + float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) / line_dir.dot (line_dir); + + Eigen::Vector4f pp = line_pt + k * line_dir; + // Calculate the projection of the point on the line (pointProj = A + k * B) + projected_points.points[i].x = pp[0]; + projected_points.points[i].y = pp[1]; + projected_points.points[i].z = pp[2]; + } + } +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelLine::doSamplesVerifyModel ( + const std::set &indices, const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Needs a valid set of model coefficients + if (!isModelValid (model_coefficients)) + return (false); + + // Obtain the line point and direction + Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + line_dir.normalize (); + + double sqr_threshold = threshold * threshold; + // Iterate through the 3d points and calculate the distances from them to the line + for (std::set::const_iterator it = indices.begin (); it != indices.end (); ++it) + { + // Calculate the distance from the point to the line + // D = ||(P2-P1) x (P1-P0)|| / ||P2-P1|| = norm (cross (p2-p1, p2-p0)) / norm(p2-p1) + if ((line_pt - input_->points[*it].getVector4fMap ()).cross3 (line_dir).squaredNorm () > sqr_threshold) + return (false); + } + + return (true); +} + +#define PCL_INSTANTIATE_SampleConsensusModelLine(T) template class PCL_EXPORTS pcl::SampleConsensusModelLine; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_LINE_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_normal_parallel_plane.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_normal_parallel_plane.hpp new file mode 100644 index 0000000..5177bf8 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_normal_parallel_plane.hpp @@ -0,0 +1,82 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PARALLEL_PLANE_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PARALLEL_PLANE_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelNormalParallelPlane::isModelValid (const Eigen::VectorXf &model_coefficients) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelNormalParallelPlane::isModelValid] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + // Check against template, if given + if (eps_angle_ > 0.0) + { + // Obtain the plane normal + Eigen::Vector4f coeff = model_coefficients; + coeff[3] = 0; + coeff.normalize (); + + if (fabs (axis_.dot (coeff)) < cos_angle_) + return (false); + } + + if (eps_dist_ > 0.0) + { + if (fabs (-model_coefficients[3] - distance_from_origin_) > eps_dist_) + return (false); + } + + return (true); +} + +#define PCL_INSTANTIATE_SampleConsensusModelNormalParallelPlane(PointT, PointNT) template class PCL_EXPORTS pcl::SampleConsensusModelNormalParallelPlane; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PARALLEL_PLANE_H_ + + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_normal_plane.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_normal_plane.hpp new file mode 100644 index 0000000..f56d1c0 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_normal_plane.hpp @@ -0,0 +1,198 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PLANE_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PLANE_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelNormalPlane::selectWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold, std::vector &inliers) +{ + if (!normals_) + { + PCL_ERROR ("[pcl::SampleConsensusModelNormalPlane::selectWithinDistance] No input dataset containing normals was given!\n"); + inliers.clear (); + return; + } + + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + inliers.clear (); + return; + } + + // Obtain the plane normal + Eigen::Vector4f coeff = model_coefficients; + coeff[3] = 0; + + int nr_p = 0; + inliers.resize (indices_->size ()); + error_sqr_dists_.resize (indices_->size ()); + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < indices_->size (); ++i) + { + const PointT &pt = input_->points[(*indices_)[i]]; + const PointNT &nt = normals_->points[(*indices_)[i]]; + // Calculate the distance from the point to the plane normal as the dot product + // D = (P-A).N/|N| + Eigen::Vector4f p (pt.x, pt.y, pt.z, 0); + Eigen::Vector4f n (nt.normal_x, nt.normal_y, nt.normal_z, 0); + double d_euclid = fabs (coeff.dot (p) + model_coefficients[3]); + + // Calculate the angular distance between the point normal and the plane normal + double d_normal = fabs (getAngle3D (n, coeff)); + d_normal = (std::min) (d_normal, M_PI - d_normal); + + // Weight with the point curvature. On flat surfaces, curvature -> 0, which means the normal will have a higher influence + double weight = normal_distance_weight_ * (1.0 - nt.curvature); + + double distance = fabs (weight * d_normal + (1.0 - weight) * d_euclid); + if (distance < threshold) + { + // Returns the indices of the points whose distances are smaller than the threshold + inliers[nr_p] = (*indices_)[i]; + error_sqr_dists_[nr_p] = distance; + ++nr_p; + } + } + inliers.resize (nr_p); + error_sqr_dists_.resize (nr_p); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelNormalPlane::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + if (!normals_) + { + PCL_ERROR ("[pcl::SampleConsensusModelNormalPlane::countWithinDistance] No input dataset containing normals was given!\n"); + return (0); + } + + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + return (0); + + // Obtain the plane normal + Eigen::Vector4f coeff = model_coefficients; + coeff[3] = 0; + + int nr_p = 0; + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < indices_->size (); ++i) + { + const PointT &pt = input_->points[(*indices_)[i]]; + const PointNT &nt = normals_->points[(*indices_)[i]]; + // Calculate the distance from the point to the plane normal as the dot product + // D = (P-A).N/|N| + Eigen::Vector4f p (pt.x, pt.y, pt.z, 0); + Eigen::Vector4f n (nt.normal_x, nt.normal_y, nt.normal_z, 0); + double d_euclid = fabs (coeff.dot (p) + model_coefficients[3]); + + // Calculate the angular distance between the point normal and the plane normal + double d_normal = fabs (getAngle3D (n, coeff)); + d_normal = (std::min) (d_normal, M_PI - d_normal); + + // Weight with the point curvature. On flat surfaces, curvature -> 0, which means the normal will have a higher influence + double weight = normal_distance_weight_ * (1.0 - nt.curvature); + + if (fabs (weight * d_normal + (1.0 - weight) * d_euclid) < threshold) + nr_p++; + } + return (nr_p); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelNormalPlane::getDistancesToModel ( + const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + if (!normals_) + { + PCL_ERROR ("[pcl::SampleConsensusModelNormalPlane::getDistancesToModel] No input dataset containing normals was given!\n"); + return; + } + + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + distances.clear (); + return; + } + + // Obtain the plane normal + Eigen::Vector4f coeff = model_coefficients; + coeff[3] = 0; + + distances.resize (indices_->size ()); + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < indices_->size (); ++i) + { + const PointT &pt = input_->points[(*indices_)[i]]; + const PointNT &nt = normals_->points[(*indices_)[i]]; + // Calculate the distance from the point to the plane normal as the dot product + // D = (P-A).N/|N| + Eigen::Vector4f p (pt.x, pt.y, pt.z, 0); + Eigen::Vector4f n (nt.normal_x, nt.normal_y, nt.normal_z, 0); + double d_euclid = fabs (coeff.dot (p) + model_coefficients[3]); + + // Calculate the angular distance between the point normal and the plane normal + double d_normal = fabs (getAngle3D (n, coeff)); + d_normal = (std::min) (d_normal, M_PI - d_normal); + + // Weight with the point curvature. On flat surfaces, curvature -> 0, which means the normal will have a higher influence + double weight = normal_distance_weight_ * (1.0 - nt.curvature); + + distances[i] = fabs (weight * d_normal + (1.0 - weight) * d_euclid); + } +} + +#define PCL_INSTANTIATE_SampleConsensusModelNormalPlane(PointT, PointNT) template class PCL_EXPORTS pcl::SampleConsensusModelNormalPlane; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PLANE_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_normal_sphere.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_normal_sphere.hpp new file mode 100644 index 0000000..4db84c1 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_normal_sphere.hpp @@ -0,0 +1,230 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: sac_model_normal_sphere.hpp schrandt $ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_SPHERE_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_SPHERE_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelNormalSphere::selectWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold, std::vector &inliers) +{ + if (!normals_) + { + PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::selectWithinDistance] No input dataset containing normals was given!\n"); + inliers.clear (); + return; + } + + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + inliers.clear (); + return; + } + + // Obtain the sphere center + Eigen::Vector4f center = model_coefficients; + center[3] = 0; + + int nr_p = 0; + inliers.resize (indices_->size ()); + error_sqr_dists_.resize (indices_->size ()); + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the sphere center as the difference between + // dist(point,sphere_origin) and sphere_radius + Eigen::Vector4f p (input_->points[(*indices_)[i]].x, + input_->points[(*indices_)[i]].y, + input_->points[(*indices_)[i]].z, + 0); + + Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], + normals_->points[(*indices_)[i]].normal[1], + normals_->points[(*indices_)[i]].normal[2], + 0); + + Eigen::Vector4f n_dir = p - center; + double d_euclid = fabs (n_dir.norm () - model_coefficients[3]); + + // Calculate the angular distance between the point normal and the plane normal + double d_normal = fabs (getAngle3D (n, n_dir)); + d_normal = (std::min) (d_normal, M_PI - d_normal); + + double distance = fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid); + if (distance < threshold) + { + // Returns the indices of the points whose distances are smaller than the threshold + inliers[nr_p] = (*indices_)[i]; + error_sqr_dists_[nr_p] = static_cast (distance); + ++nr_p; + } + } + inliers.resize (nr_p); + error_sqr_dists_.resize (nr_p); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelNormalSphere::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + if (!normals_) + { + PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given!\n"); + return (0); + } + + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + return(0); + + + // Obtain the shpere centroid + Eigen::Vector4f center = model_coefficients; + center[3] = 0; + + int nr_p = 0; + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the sphere centroid as the difference between + // dist(point,sphere_origin) and sphere_radius + Eigen::Vector4f p (input_->points[(*indices_)[i]].x, + input_->points[(*indices_)[i]].y, + input_->points[(*indices_)[i]].z, + 0); + + Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], + normals_->points[(*indices_)[i]].normal[1], + normals_->points[(*indices_)[i]].normal[2], + 0); + + Eigen::Vector4f n_dir = (p-center); + double d_euclid = fabs (n_dir.norm () - model_coefficients[3]); + // + // Calculate the angular distance between the point normal and the plane normal + double d_normal = fabs (getAngle3D (n, n_dir)); + d_normal = (std::min) (d_normal, M_PI - d_normal); + + if (fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid) < threshold) + nr_p++; + } + return (nr_p); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelNormalSphere::getDistancesToModel ( + const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + if (!normals_) + { + PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given!\n"); + return; + } + + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + distances.clear (); + return; + } + + // Obtain the sphere centroid + Eigen::Vector4f center = model_coefficients; + center[3] = 0; + + distances.resize (indices_->size ()); + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the sphere as the difference between + // dist(point,sphere_origin) and sphere_radius + Eigen::Vector4f p (input_->points[(*indices_)[i]].x, + input_->points[(*indices_)[i]].y, + input_->points[(*indices_)[i]].z, + 0); + + Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], + normals_->points[(*indices_)[i]].normal[1], + normals_->points[(*indices_)[i]].normal[2], + 0); + + Eigen::Vector4f n_dir = (p-center); + double d_euclid = fabs (n_dir.norm () - model_coefficients[3]); + // + // Calculate the angular distance between the point normal and the plane normal + double d_normal = fabs (getAngle3D (n, n_dir)); + d_normal = (std::min) (d_normal, M_PI - d_normal); + + distances[i] = fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelNormalSphere::isModelValid (const Eigen::VectorXf &model_coefficients) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::selectWithinDistance] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + if (radius_min_ != -std::numeric_limits::max() && model_coefficients[3] < radius_min_) + return (false); + if (radius_max_ != std::numeric_limits::max() && model_coefficients[3] > radius_max_) + return (false); + + return (true); +} + +#define PCL_INSTANTIATE_SampleConsensusModelNormalSphere(PointT, PointNT) template class PCL_EXPORTS pcl::SampleConsensusModelNormalSphere; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_SPHERE_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_parallel_line.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_parallel_line.hpp new file mode 100644 index 0000000..56627f3 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_parallel_line.hpp @@ -0,0 +1,120 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_PARALLEL_LINE_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_PARALLEL_LINE_H_ + +#include + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelParallelLine::selectWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold, std::vector &inliers) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + inliers.clear (); + return; + } + + SampleConsensusModelLine::selectWithinDistance (model_coefficients, threshold, inliers); +} + +////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelParallelLine::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + return (0); + + return (SampleConsensusModelLine::countWithinDistance (model_coefficients, threshold)); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelParallelLine::getDistancesToModel ( + const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + distances.clear (); + return; + } + + SampleConsensusModelLine::getDistancesToModel (model_coefficients, distances); +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelParallelLine::isModelValid (const Eigen::VectorXf &model_coefficients) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 6) + { + PCL_ERROR ("[pcl::SampleConsensusParallelLine::isModelValid] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + // Check against template, if given + if (eps_angle_ > 0.0) + { + // Obtain the line direction + Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + + Eigen::Vector4f axis (axis_[0], axis_[1], axis_[2], 0); + double angle_diff = fabs (getAngle3D (axis, line_dir)); + //angle_diff = (std::min) (angle_diff, M_PI - angle_diff); + angle_diff = fabs (angle_diff - (M_PI/2.0)); + // Check whether the current plane model satisfies our angle threshold criterion with respect to the given axis + if (angle_diff > eps_angle_) + return (false); + } + + return (true); +} + +#define PCL_INSTANTIATE_SampleConsensusModelParallelLine(T) template class PCL_EXPORTS pcl::SampleConsensusModelParallelLine; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_PARALLEL_LINE_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_parallel_plane.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_parallel_plane.hpp new file mode 100644 index 0000000..a87ec99 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_parallel_plane.hpp @@ -0,0 +1,118 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + a + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_PARALLEL_PLANE_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_PARALLEL_PLANE_H_ + +#include + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelParallelPlane::selectWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold, std::vector &inliers) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + inliers.clear (); + return; + } + + SampleConsensusModelPlane::selectWithinDistance (model_coefficients, threshold, inliers); +} + +////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelParallelPlane::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + return (0); + + return (SampleConsensusModelPlane::countWithinDistance (model_coefficients, threshold)); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelParallelPlane::getDistancesToModel ( + const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + distances.clear (); + return; + } + + SampleConsensusModelPlane::getDistancesToModel (model_coefficients, distances); +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelParallelPlane::isModelValid (const Eigen::VectorXf &model_coefficients) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelParallelPlane::isModelValid] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + // Check against template, if given + if (eps_angle_ > 0.0) + { + // Obtain the plane normal + Eigen::Vector4f coeff = model_coefficients; + coeff[3] = 0; + coeff.normalize (); + + Eigen::Vector4f axis (axis_[0], axis_[1], axis_[2], 0); + if (fabs (axis.dot (coeff)) > sin_angle_) + return (false); + } + + return (true); +} + +#define PCL_INSTANTIATE_SampleConsensusModelParallelPlane(T) template class PCL_EXPORTS pcl::SampleConsensusModelParallelPlane; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_PARALLEL_PLANE_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_perpendicular_plane.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_perpendicular_plane.hpp new file mode 100644 index 0000000..53317ae --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_perpendicular_plane.hpp @@ -0,0 +1,120 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_PERPENDICULAR_PLANE_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_PERPENDICULAR_PLANE_H_ + +#include + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelPerpendicularPlane::selectWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold, std::vector &inliers) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + inliers.clear (); + return; + } + + SampleConsensusModelPlane::selectWithinDistance (model_coefficients, threshold, inliers); +} + +////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelPerpendicularPlane::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + return (0); + + return (SampleConsensusModelPlane::countWithinDistance (model_coefficients, threshold)); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelPerpendicularPlane::getDistancesToModel ( + const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + distances.clear (); + return; + } + + SampleConsensusModelPlane::getDistancesToModel (model_coefficients, distances); +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelPerpendicularPlane::isModelValid (const Eigen::VectorXf &model_coefficients) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelPerpendicularPlane::isModelValid] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + // Check against template, if given + if (eps_angle_ > 0.0) + { + // Obtain the plane normal + Eigen::Vector4f coeff = model_coefficients; + coeff[3] = 0; + + Eigen::Vector4f axis (axis_[0], axis_[1], axis_[2], 0); + double angle_diff = fabs (getAngle3D (axis, coeff)); + angle_diff = (std::min) (angle_diff, M_PI - angle_diff); + // Check whether the current plane model satisfies our angle threshold criterion with respect to the given axis + if (angle_diff > eps_angle_) + return (false); + } + + return (true); +} + +#define PCL_INSTANTIATE_SampleConsensusModelPerpendicularPlane(T) template class PCL_EXPORTS pcl::SampleConsensusModelPerpendicularPlane; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_PERPENDICULAR_PLANE_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_plane.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_plane.hpp new file mode 100644 index 0000000..67749d4 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_plane.hpp @@ -0,0 +1,371 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_PLANE_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_PLANE_H_ + +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelPlane::isSampleGood (const std::vector &samples) const +{ + // Need an extra check in case the sample selection is empty + if (samples.empty ()) + return (false); + // Get the values at the two points + pcl::Array4fMapConst p0 = input_->points[samples[0]].getArray4fMap (); + pcl::Array4fMapConst p1 = input_->points[samples[1]].getArray4fMap (); + pcl::Array4fMapConst p2 = input_->points[samples[2]].getArray4fMap (); + + Eigen::Array4f dy1dy2 = (p1-p0) / (p2-p0); + + return ( (dy1dy2[0] != dy1dy2[1]) || (dy1dy2[2] != dy1dy2[1]) ); +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelPlane::computeModelCoefficients ( + const std::vector &samples, Eigen::VectorXf &model_coefficients) +{ + // Need 3 samples + if (samples.size () != 3) + { + PCL_ERROR ("[pcl::SampleConsensusModelPlane::computeModelCoefficients] Invalid set of samples given (%lu)!\n", samples.size ()); + return (false); + } + + pcl::Array4fMapConst p0 = input_->points[samples[0]].getArray4fMap (); + pcl::Array4fMapConst p1 = input_->points[samples[1]].getArray4fMap (); + pcl::Array4fMapConst p2 = input_->points[samples[2]].getArray4fMap (); + + // Compute the segment values (in 3d) between p1 and p0 + Eigen::Array4f p1p0 = p1 - p0; + // Compute the segment values (in 3d) between p2 and p0 + Eigen::Array4f p2p0 = p2 - p0; + + // Avoid some crashes by checking for collinearity here + Eigen::Array4f dy1dy2 = p1p0 / p2p0; + if ( (dy1dy2[0] == dy1dy2[1]) && (dy1dy2[2] == dy1dy2[1]) ) // Check for collinearity + return (false); + + // Compute the plane coefficients from the 3 given points in a straightforward manner + // calculate the plane normal n = (p2-p1) x (p3-p1) = cross (p2-p1, p3-p1) + model_coefficients.resize (4); + model_coefficients[0] = p1p0[1] * p2p0[2] - p1p0[2] * p2p0[1]; + model_coefficients[1] = p1p0[2] * p2p0[0] - p1p0[0] * p2p0[2]; + model_coefficients[2] = p1p0[0] * p2p0[1] - p1p0[1] * p2p0[0]; + model_coefficients[3] = 0; + + // Normalize + model_coefficients.normalize (); + + // ... + d = 0 + model_coefficients[3] = -1 * (model_coefficients.template head<4>().dot (p0.matrix ())); + + return (true); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelPlane::getDistancesToModel ( + const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + // Needs a valid set of model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelPlane::getDistancesToModel] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return; + } + + distances.resize (indices_->size ()); + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the plane normal as the dot product + // D = (P-A).N/|N| + /*distances[i] = fabs (model_coefficients[0] * input_->points[(*indices_)[i]].x + + model_coefficients[1] * input_->points[(*indices_)[i]].y + + model_coefficients[2] * input_->points[(*indices_)[i]].z + + model_coefficients[3]);*/ + Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, + input_->points[(*indices_)[i]].y, + input_->points[(*indices_)[i]].z, + 1); + distances[i] = fabs (model_coefficients.dot (pt)); + } +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelPlane::selectWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold, std::vector &inliers) +{ + // Needs a valid set of model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelPlane::selectWithinDistance] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return; + } + + int nr_p = 0; + inliers.resize (indices_->size ()); + error_sqr_dists_.resize (indices_->size ()); + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the plane normal as the dot product + // D = (P-A).N/|N| + Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, + input_->points[(*indices_)[i]].y, + input_->points[(*indices_)[i]].z, + 1); + + float distance = fabsf (model_coefficients.dot (pt)); + + if (distance < threshold) + { + // Returns the indices of the points whose distances are smaller than the threshold + inliers[nr_p] = (*indices_)[i]; + error_sqr_dists_[nr_p] = static_cast (distance); + ++nr_p; + } + } + inliers.resize (nr_p); + error_sqr_dists_.resize (nr_p); +} + +////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelPlane::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Needs a valid set of model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelPlane::countWithinDistance] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (0); + } + + int nr_p = 0; + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the plane normal as the dot product + // D = (P-A).N/|N| + Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, + input_->points[(*indices_)[i]].y, + input_->points[(*indices_)[i]].z, + 1); + if (fabs (model_coefficients.dot (pt)) < threshold) + nr_p++; + } + return (nr_p); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelPlane::optimizeModelCoefficients ( + const std::vector &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients) +{ + // Needs a valid set of model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelPlane::optimizeModelCoefficients] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + optimized_coefficients = model_coefficients; + return; + } + + // Need at least 3 points to estimate a plane + if (inliers.size () < 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelPlane::optimizeModelCoefficients] Not enough inliers found to support a model (%lu)! Returning the same coefficients.\n", inliers.size ()); + optimized_coefficients = model_coefficients; + return; + } + + Eigen::Vector4f plane_parameters; + + // Use Least-Squares to fit the plane through all the given sample points and find out its coefficients + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix; + Eigen::Vector4f xyz_centroid; + + computeMeanAndCovarianceMatrix (*input_, inliers, covariance_matrix, xyz_centroid); + + // Compute the model coefficients + EIGEN_ALIGN16 Eigen::Vector3f::Scalar eigen_value; + EIGEN_ALIGN16 Eigen::Vector3f eigen_vector; + pcl::eigen33 (covariance_matrix, eigen_value, eigen_vector); + + // Hessian form (D = nc . p_plane (centroid here) + p) + optimized_coefficients.resize (4); + optimized_coefficients[0] = eigen_vector [0]; + optimized_coefficients[1] = eigen_vector [1]; + optimized_coefficients[2] = eigen_vector [2]; + optimized_coefficients[3] = 0; + optimized_coefficients[3] = -1 * optimized_coefficients.dot (xyz_centroid); + + // Make sure it results in a valid model + if (!isModelValid (optimized_coefficients)) + { + optimized_coefficients = model_coefficients; + } +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelPlane::projectPoints ( + const std::vector &inliers, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool copy_data_fields) +{ + // Needs a valid set of model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelPlane::projectPoints] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return; + } + + projected_points.header = input_->header; + projected_points.is_dense = input_->is_dense; + + Eigen::Vector4f mc (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + + // normalize the vector perpendicular to the plane... + mc.normalize (); + // ... and store the resulting normal as a local copy of the model coefficients + Eigen::Vector4f tmp_mc = model_coefficients; + tmp_mc[0] = mc[0]; + tmp_mc[1] = mc[1]; + tmp_mc[2] = mc[2]; + + // Copy all the data fields from the input cloud to the projected one? + if (copy_data_fields) + { + // Allocate enough space and copy the basics + projected_points.points.resize (input_->points.size ()); + projected_points.width = input_->width; + projected_points.height = input_->height; + + typedef typename pcl::traits::fieldList::type FieldList; + // Iterate over each point + for (size_t i = 0; i < input_->points.size (); ++i) + // Iterate over each dimension + pcl::for_each_type (NdConcatenateFunctor (input_->points[i], projected_points.points[i])); + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < inliers.size (); ++i) + { + // Calculate the distance from the point to the plane + Eigen::Vector4f p (input_->points[inliers[i]].x, + input_->points[inliers[i]].y, + input_->points[inliers[i]].z, + 1); + // use normalized coefficients to calculate the scalar projection + float distance_to_plane = tmp_mc.dot (p); + + pcl::Vector4fMap pp = projected_points.points[inliers[i]].getVector4fMap (); + pp.matrix () = p - mc * distance_to_plane; // mc[3] = 0, therefore the 3rd coordinate is safe + } + } + else + { + // Allocate enough space and copy the basics + projected_points.points.resize (inliers.size ()); + projected_points.width = static_cast (inliers.size ()); + projected_points.height = 1; + + typedef typename pcl::traits::fieldList::type FieldList; + // Iterate over each point + for (size_t i = 0; i < inliers.size (); ++i) + // Iterate over each dimension + pcl::for_each_type (NdConcatenateFunctor (input_->points[inliers[i]], projected_points.points[i])); + + // Iterate through the 3d points and calculate the distances from them to the plane + for (size_t i = 0; i < inliers.size (); ++i) + { + // Calculate the distance from the point to the plane + Eigen::Vector4f p (input_->points[inliers[i]].x, + input_->points[inliers[i]].y, + input_->points[inliers[i]].z, + 1); + // use normalized coefficients to calculate the scalar projection + float distance_to_plane = tmp_mc.dot (p); + + pcl::Vector4fMap pp = projected_points.points[i].getVector4fMap (); + pp.matrix () = p - mc * distance_to_plane; // mc[3] = 0, therefore the 3rd coordinate is safe + } + } +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelPlane::doSamplesVerifyModel ( + const std::set &indices, const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Needs a valid set of model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelPlane::doSamplesVerifyModel] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + for (std::set::const_iterator it = indices.begin (); it != indices.end (); ++it) + { + Eigen::Vector4f pt (input_->points[*it].x, + input_->points[*it].y, + input_->points[*it].z, + 1); + if (fabs (model_coefficients.dot (pt)) > threshold) + return (false); + } + + return (true); +} + +#define PCL_INSTANTIATE_SampleConsensusModelPlane(T) template class PCL_EXPORTS pcl::SampleConsensusModelPlane; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_PLANE_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_registration.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_registration.hpp new file mode 100644 index 0000000..6f2de20 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_registration.hpp @@ -0,0 +1,304 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_REGISTRATION_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_REGISTRATION_H_ + +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelRegistration::isSampleGood (const std::vector &samples) const +{ + using namespace pcl::common; + using namespace pcl::traits; + + PointT p10 = input_->points[samples[1]] - input_->points[samples[0]]; + PointT p20 = input_->points[samples[2]] - input_->points[samples[0]]; + PointT p21 = input_->points[samples[2]] - input_->points[samples[1]]; + + return ((p10.x * p10.x + p10.y * p10.y + p10.z * p10.z) > sample_dist_thresh_ && + (p20.x * p20.x + p20.y * p20.y + p20.z * p20.z) > sample_dist_thresh_ && + (p21.x * p21.x + p21.y * p21.y + p21.z * p21.z) > sample_dist_thresh_); +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelRegistration::computeModelCoefficients (const std::vector &samples, Eigen::VectorXf &model_coefficients) +{ + if (!target_) + { + PCL_ERROR ("[pcl::SampleConsensusModelRegistration::computeModelCoefficients] No target dataset given!\n"); + return (false); + } + // Need 3 samples + if (samples.size () != 3) + return (false); + + std::vector indices_tgt (3); + for (int i = 0; i < 3; ++i) + indices_tgt[i] = correspondences_[samples[i]]; + + estimateRigidTransformationSVD (*input_, samples, *target_, indices_tgt, model_coefficients); + return (true); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelRegistration::getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + if (indices_->size () != indices_tgt_->size ()) + { + PCL_ERROR ("[pcl::SampleConsensusModelRegistration::getDistancesToModel] Number of source indices (%lu) differs than number of target indices (%lu)!\n", indices_->size (), indices_tgt_->size ()); + distances.clear (); + return; + } + if (!target_) + { + PCL_ERROR ("[pcl::SampleConsensusModelRegistration::getDistanceToModel] No target dataset given!\n"); + return; + } + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + distances.clear (); + return; + } + distances.resize (indices_->size ()); + + // Get the 4x4 transformation + Eigen::Matrix4f transform; + transform.row (0).matrix () = model_coefficients.segment<4>(0); + transform.row (1).matrix () = model_coefficients.segment<4>(4); + transform.row (2).matrix () = model_coefficients.segment<4>(8); + transform.row (3).matrix () = model_coefficients.segment<4>(12); + + for (size_t i = 0; i < indices_->size (); ++i) + { + Eigen::Vector4f pt_src (input_->points[(*indices_)[i]].x, + input_->points[(*indices_)[i]].y, + input_->points[(*indices_)[i]].z, 1); + Eigen::Vector4f pt_tgt (target_->points[(*indices_tgt_)[i]].x, + target_->points[(*indices_tgt_)[i]].y, + target_->points[(*indices_tgt_)[i]].z, 1); + + Eigen::Vector4f p_tr (transform * pt_src); + // Calculate the distance from the transformed point to its correspondence + // need to compute the real norm here to keep MSAC and friends general + distances[i] = (p_tr - pt_tgt).norm (); + } +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelRegistration::selectWithinDistance (const Eigen::VectorXf &model_coefficients, const double threshold, std::vector &inliers) +{ + if (indices_->size () != indices_tgt_->size ()) + { + PCL_ERROR ("[pcl::SampleConsensusModelRegistration::selectWithinDistance] Number of source indices (%lu) differs than number of target indices (%lu)!\n", indices_->size (), indices_tgt_->size ()); + inliers.clear (); + return; + } + if (!target_) + { + PCL_ERROR ("[pcl::SampleConsensusModelRegistration::selectWithinDistance] No target dataset given!\n"); + return; + } + + double thresh = threshold * threshold; + + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + inliers.clear (); + return; + } + + int nr_p = 0; + inliers.resize (indices_->size ()); + error_sqr_dists_.resize (indices_->size ()); + + Eigen::Matrix4f transform; + transform.row (0).matrix () = model_coefficients.segment<4>(0); + transform.row (1).matrix () = model_coefficients.segment<4>(4); + transform.row (2).matrix () = model_coefficients.segment<4>(8); + transform.row (3).matrix () = model_coefficients.segment<4>(12); + + for (size_t i = 0; i < indices_->size (); ++i) + { + Eigen::Vector4f pt_src (input_->points[(*indices_)[i]].x, + input_->points[(*indices_)[i]].y, + input_->points[(*indices_)[i]].z, 1); + Eigen::Vector4f pt_tgt (target_->points[(*indices_tgt_)[i]].x, + target_->points[(*indices_tgt_)[i]].y, + target_->points[(*indices_tgt_)[i]].z, 1); + + Eigen::Vector4f p_tr (transform * pt_src); + + float distance = (p_tr - pt_tgt).squaredNorm (); + // Calculate the distance from the transformed point to its correspondence + if (distance < thresh) + { + inliers[nr_p] = (*indices_)[i]; + error_sqr_dists_[nr_p] = static_cast (distance); + ++nr_p; + } + } + inliers.resize (nr_p); + error_sqr_dists_.resize (nr_p); +} + +////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelRegistration::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + if (indices_->size () != indices_tgt_->size ()) + { + PCL_ERROR ("[pcl::SampleConsensusModelRegistration::countWithinDistance] Number of source indices (%lu) differs than number of target indices (%lu)!\n", indices_->size (), indices_tgt_->size ()); + return (0); + } + if (!target_) + { + PCL_ERROR ("[pcl::SampleConsensusModelRegistration::countWithinDistance] No target dataset given!\n"); + return (0); + } + + double thresh = threshold * threshold; + + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + return (0); + + Eigen::Matrix4f transform; + transform.row (0).matrix () = model_coefficients.segment<4>(0); + transform.row (1).matrix () = model_coefficients.segment<4>(4); + transform.row (2).matrix () = model_coefficients.segment<4>(8); + transform.row (3).matrix () = model_coefficients.segment<4>(12); + + int nr_p = 0; + for (size_t i = 0; i < indices_->size (); ++i) + { + Eigen::Vector4f pt_src (input_->points[(*indices_)[i]].x, + input_->points[(*indices_)[i]].y, + input_->points[(*indices_)[i]].z, 1); + Eigen::Vector4f pt_tgt (target_->points[(*indices_tgt_)[i]].x, + target_->points[(*indices_tgt_)[i]].y, + target_->points[(*indices_tgt_)[i]].z, 1); + + Eigen::Vector4f p_tr (transform * pt_src); + // Calculate the distance from the transformed point to its correspondence + if ((p_tr - pt_tgt).squaredNorm () < thresh) + nr_p++; + } + return (nr_p); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelRegistration::optimizeModelCoefficients (const std::vector &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients) +{ + if (indices_->size () != indices_tgt_->size ()) + { + PCL_ERROR ("[pcl::SampleConsensusModelRegistration::optimizeModelCoefficients] Number of source indices (%lu) differs than number of target indices (%lu)!\n", indices_->size (), indices_tgt_->size ()); + optimized_coefficients = model_coefficients; + return; + } + + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients) || !target_) + { + optimized_coefficients = model_coefficients; + return; + } + + std::vector indices_src (inliers.size ()); + std::vector indices_tgt (inliers.size ()); + for (size_t i = 0; i < inliers.size (); ++i) + { + indices_src[i] = inliers[i]; + indices_tgt[i] = correspondences_[indices_src[i]]; + } + + estimateRigidTransformationSVD (*input_, indices_src, *target_, indices_tgt, optimized_coefficients); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelRegistration::estimateRigidTransformationSVD ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Eigen::VectorXf &transform) +{ + transform.resize (16); + + Eigen::Matrix src (3, indices_src.size ()); + Eigen::Matrix tgt (3, indices_tgt.size ()); + + for (size_t i = 0; i < indices_src.size (); ++i) + { + src (0, i) = cloud_src[indices_src[i]].x; + src (1, i) = cloud_src[indices_src[i]].y; + src (2, i) = cloud_src[indices_src[i]].z; + + tgt (0, i) = cloud_tgt[indices_tgt[i]].x; + tgt (1, i) = cloud_tgt[indices_tgt[i]].y; + tgt (2, i) = cloud_tgt[indices_tgt[i]].z; + } + + // Call Umeyama directly from Eigen + Eigen::Matrix4d transformation_matrix = pcl::umeyama (src, tgt, false); + + // Return the correct transformation + transform.segment<4> (0).matrix () = transformation_matrix.cast ().row (0); + transform.segment<4> (4).matrix () = transformation_matrix.cast ().row (1); + transform.segment<4> (8).matrix () = transformation_matrix.cast ().row (2); + transform.segment<4> (12).matrix () = transformation_matrix.cast ().row (3); +} + +#define PCL_INSTANTIATE_SampleConsensusModelRegistration(T) template class PCL_EXPORTS pcl::SampleConsensusModelRegistration; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_REGISTRATION_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_registration_2d.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_registration_2d.hpp new file mode 100644 index 0000000..54b8688 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_registration_2d.hpp @@ -0,0 +1,230 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_REGISTRATION_2D_HPP_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_REGISTRATION_2D_HPP_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelRegistration2D::isSampleGood (const std::vector&) const +{ + return (true); + //using namespace pcl::common; + //using namespace pcl::traits; + + //PointT p10 = input_->points[samples[1]] - input_->points[samples[0]]; + //PointT p20 = input_->points[samples[2]] - input_->points[samples[0]]; + //PointT p21 = input_->points[samples[2]] - input_->points[samples[1]]; + + //return ((p10.x * p10.x + p10.y * p10.y + p10.z * p10.z) > sample_dist_thresh_ && + // (p20.x * p20.x + p20.y * p20.y + p20.z * p20.z) > sample_dist_thresh_ && + // (p21.x * p21.x + p21.y * p21.y + p21.z * p21.z) > sample_dist_thresh_); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelRegistration2D::getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + PCL_INFO ("[pcl::SampleConsensusModelRegistration2D::getDistancesToModel]\n"); + if (indices_->size () != indices_tgt_->size ()) + { + PCL_ERROR ("[pcl::SampleConsensusModelRegistration2D::getDistancesToModel] Number of source indices (%lu) differs than number of target indices (%lu)!\n", indices_->size (), indices_tgt_->size ()); + distances.clear (); + return; + } + if (!target_) + { + PCL_ERROR ("[pcl::SampleConsensusModelRegistration2D::getDistanceToModel] No target dataset given!\n"); + return; + } + + distances.resize (indices_->size ()); + + // Get the 4x4 transformation + Eigen::Matrix4f transform; + transform.row (0).matrix () = model_coefficients.segment<4>(0); + transform.row (1).matrix () = model_coefficients.segment<4>(4); + transform.row (2).matrix () = model_coefficients.segment<4>(8); + transform.row (3).matrix () = model_coefficients.segment<4>(12); + + for (size_t i = 0; i < indices_->size (); ++i) + { + Eigen::Vector4f pt_src (input_->points[(*indices_)[i]].x, + input_->points[(*indices_)[i]].y, + input_->points[(*indices_)[i]].z, 1); + + Eigen::Vector4f p_tr (transform * pt_src); + + // Project the point on the image plane + Eigen::Vector3f p_tr3 (p_tr[0], p_tr[1], p_tr[2]); + Eigen::Vector3f uv (projection_matrix_ * p_tr3); + + if (uv[2] < 0) + continue; + + uv /= uv[2]; + + // Calculate the distance from the transformed point to its correspondence + // need to compute the real norm here to keep MSAC and friends general + distances[i] = std::sqrt ((uv[0] - target_->points[(*indices_tgt_)[i]].u) * + (uv[0] - target_->points[(*indices_tgt_)[i]].u) + + (uv[1] - target_->points[(*indices_tgt_)[i]].v) * + (uv[1] - target_->points[(*indices_tgt_)[i]].v)); + } +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelRegistration2D::selectWithinDistance (const Eigen::VectorXf &model_coefficients, const double threshold, std::vector &inliers) +{ + if (indices_->size () != indices_tgt_->size ()) + { + PCL_ERROR ("[pcl::SampleConsensusModelRegistration2D::selectWithinDistance] Number of source indices (%lu) differs than number of target indices (%lu)!\n", indices_->size (), indices_tgt_->size ()); + inliers.clear (); + return; + } + if (!target_) + { + PCL_ERROR ("[pcl::SampleConsensusModelRegistration2D::selectWithinDistance] No target dataset given!\n"); + return; + } + + double thresh = threshold * threshold; + + int nr_p = 0; + inliers.resize (indices_->size ()); + error_sqr_dists_.resize (indices_->size ()); + + Eigen::Matrix4f transform; + transform.row (0).matrix () = model_coefficients.segment<4>(0); + transform.row (1).matrix () = model_coefficients.segment<4>(4); + transform.row (2).matrix () = model_coefficients.segment<4>(8); + transform.row (3).matrix () = model_coefficients.segment<4>(12); + + for (size_t i = 0; i < indices_->size (); ++i) + { + Eigen::Vector4f pt_src (input_->points[(*indices_)[i]].x, + input_->points[(*indices_)[i]].y, + input_->points[(*indices_)[i]].z, 1); + + Eigen::Vector4f p_tr (transform * pt_src); + + // Project the point on the image plane + Eigen::Vector3f p_tr3 (p_tr[0], p_tr[1], p_tr[2]); + Eigen::Vector3f uv (projection_matrix_ * p_tr3); + + if (uv[2] < 0) + continue; + + uv /= uv[2]; + + double distance = ((uv[0] - target_->points[(*indices_tgt_)[i]].u) * + (uv[0] - target_->points[(*indices_tgt_)[i]].u) + + (uv[1] - target_->points[(*indices_tgt_)[i]].v) * + (uv[1] - target_->points[(*indices_tgt_)[i]].v)); + + // Calculate the distance from the transformed point to its correspondence + if (distance < thresh) + { + inliers[nr_p] = (*indices_)[i]; + error_sqr_dists_[nr_p] = distance; + ++nr_p; + } + } + inliers.resize (nr_p); + error_sqr_dists_.resize (nr_p); +} + +////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelRegistration2D::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + if (indices_->size () != indices_tgt_->size ()) + { + PCL_ERROR ("[pcl::SampleConsensusModelRegistration2D::countWithinDistance] Number of source indices (%lu) differs than number of target indices (%lu)!\n", indices_->size (), indices_tgt_->size ()); + return (0); + } + if (!target_) + { + PCL_ERROR ("[pcl::SampleConsensusModelRegistration2D::countWithinDistance] No target dataset given!\n"); + return (0); + } + + double thresh = threshold * threshold; + + Eigen::Matrix4f transform; + transform.row (0).matrix () = model_coefficients.segment<4>(0); + transform.row (1).matrix () = model_coefficients.segment<4>(4); + transform.row (2).matrix () = model_coefficients.segment<4>(8); + transform.row (3).matrix () = model_coefficients.segment<4>(12); + + int nr_p = 0; + + for (size_t i = 0; i < indices_->size (); ++i) + { + Eigen::Vector4f pt_src (input_->points[(*indices_)[i]].x, + input_->points[(*indices_)[i]].y, + input_->points[(*indices_)[i]].z, 1); + + Eigen::Vector4f p_tr (transform * pt_src); + + // Project the point on the image plane + Eigen::Vector3f p_tr3 (p_tr[0], p_tr[1], p_tr[2]); + Eigen::Vector3f uv (projection_matrix_ * p_tr3); + + if (uv[2] < 0) + continue; + + uv /= uv[2]; + + // Calculate the distance from the transformed point to its correspondence + if (((uv[0] - target_->points[(*indices_tgt_)[i]].u) * + (uv[0] - target_->points[(*indices_tgt_)[i]].u) + + (uv[1] - target_->points[(*indices_tgt_)[i]].v) * + (uv[1] - target_->points[(*indices_tgt_)[i]].v)) < thresh) + ++nr_p; + } + return (nr_p); +} + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_REGISTRATION_2D_HPP_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_sphere.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_sphere.hpp new file mode 100644 index 0000000..a86dac6 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_sphere.hpp @@ -0,0 +1,311 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_SPHERE_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_SPHERE_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelSphere::isSampleGood (const std::vector &) const +{ + return (true); +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelSphere::computeModelCoefficients ( + const std::vector &samples, Eigen::VectorXf &model_coefficients) +{ + // Need 4 samples + if (samples.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelSphere::computeModelCoefficients] Invalid set of samples given (%lu)!\n", samples.size ()); + return (false); + } + + Eigen::Matrix4f temp; + for (int i = 0; i < 4; i++) + { + temp (i, 0) = input_->points[samples[i]].x; + temp (i, 1) = input_->points[samples[i]].y; + temp (i, 2) = input_->points[samples[i]].z; + temp (i, 3) = 1; + } + float m11 = temp.determinant (); + if (m11 == 0) + return (false); // the points don't define a sphere! + + for (int i = 0; i < 4; ++i) + temp (i, 0) = (input_->points[samples[i]].x) * (input_->points[samples[i]].x) + + (input_->points[samples[i]].y) * (input_->points[samples[i]].y) + + (input_->points[samples[i]].z) * (input_->points[samples[i]].z); + float m12 = temp.determinant (); + + for (int i = 0; i < 4; ++i) + { + temp (i, 1) = temp (i, 0); + temp (i, 0) = input_->points[samples[i]].x; + } + float m13 = temp.determinant (); + + for (int i = 0; i < 4; ++i) + { + temp (i, 2) = temp (i, 1); + temp (i, 1) = input_->points[samples[i]].y; + } + float m14 = temp.determinant (); + + for (int i = 0; i < 4; ++i) + { + temp (i, 0) = temp (i, 2); + temp (i, 1) = input_->points[samples[i]].x; + temp (i, 2) = input_->points[samples[i]].y; + temp (i, 3) = input_->points[samples[i]].z; + } + float m15 = temp.determinant (); + + // Center (x , y, z) + model_coefficients.resize (4); + model_coefficients[0] = 0.5f * m12 / m11; + model_coefficients[1] = 0.5f * m13 / m11; + model_coefficients[2] = 0.5f * m14 / m11; + // Radius + model_coefficients[3] = sqrtf ( + model_coefficients[0] * model_coefficients[0] + + model_coefficients[1] * model_coefficients[1] + + model_coefficients[2] * model_coefficients[2] - m15 / m11); + + return (true); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelSphere::getDistancesToModel ( + const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + distances.clear (); + return; + } + distances.resize (indices_->size ()); + + // Iterate through the 3d points and calculate the distances from them to the sphere + for (size_t i = 0; i < indices_->size (); ++i) + // Calculate the distance from the point to the sphere as the difference between + //dist(point,sphere_origin) and sphere_radius + distances[i] = fabs (sqrtf ( + ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) * + ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) + + + ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) * + ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) + + + ( input_->points[(*indices_)[i]].z - model_coefficients[2] ) * + ( input_->points[(*indices_)[i]].z - model_coefficients[2] ) + ) - model_coefficients[3]); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelSphere::selectWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold, std::vector &inliers) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + { + inliers.clear (); + return; + } + + int nr_p = 0; + inliers.resize (indices_->size ()); + error_sqr_dists_.resize (indices_->size ()); + + // Iterate through the 3d points and calculate the distances from them to the sphere + for (size_t i = 0; i < indices_->size (); ++i) + { + double distance = fabs (sqrtf ( + ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) * + ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) + + + ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) * + ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) + + + ( input_->points[(*indices_)[i]].z - model_coefficients[2] ) * + ( input_->points[(*indices_)[i]].z - model_coefficients[2] ) + ) - model_coefficients[3]); + // Calculate the distance from the point to the sphere as the difference between + // dist(point,sphere_origin) and sphere_radius + if (distance < threshold) + { + // Returns the indices of the points whose distances are smaller than the threshold + inliers[nr_p] = (*indices_)[i]; + error_sqr_dists_[nr_p] = static_cast (distance); + ++nr_p; + } + } + inliers.resize (nr_p); + error_sqr_dists_.resize (nr_p); +} + +////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelSphere::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Check if the model is valid given the user constraints + if (!isModelValid (model_coefficients)) + return (0); + + int nr_p = 0; + + // Iterate through the 3d points and calculate the distances from them to the sphere + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the sphere as the difference between + // dist(point,sphere_origin) and sphere_radius + if (fabs (sqrtf ( + ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) * + ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) + + + ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) * + ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) + + + ( input_->points[(*indices_)[i]].z - model_coefficients[2] ) * + ( input_->points[(*indices_)[i]].z - model_coefficients[2] ) + ) - model_coefficients[3]) < threshold) + nr_p++; + } + return (nr_p); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelSphere::optimizeModelCoefficients ( + const std::vector &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients) +{ + optimized_coefficients = model_coefficients; + + // Needs a set of valid model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelSphere::optimizeModelCoefficients] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return; + } + + // Need at least 4 samples + if (inliers.size () <= 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelSphere::optimizeModelCoefficients] Not enough inliers found to support a model (%lu)! Returning the same coefficients.\n", inliers.size ()); + return; + } + + tmp_inliers_ = &inliers; + + OptimizationFunctor functor (static_cast (inliers.size ()), this); + Eigen::NumericalDiff num_diff (functor); + Eigen::LevenbergMarquardt, float> lm (num_diff); + int info = lm.minimize (optimized_coefficients); + + // Compute the L2 norm of the residuals + PCL_DEBUG ("[pcl::SampleConsensusModelSphere::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g \nFinal solution: %g %g %g %g\n", + info, lm.fvec.norm (), model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2], optimized_coefficients[3]); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelSphere::projectPoints ( + const std::vector &, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelSphere::projectPoints] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return; + } + + // Allocate enough space and copy the basics + projected_points.points.resize (input_->points.size ()); + projected_points.header = input_->header; + projected_points.width = input_->width; + projected_points.height = input_->height; + projected_points.is_dense = input_->is_dense; + + PCL_WARN ("[pcl::SampleConsensusModelSphere::projectPoints] Not implemented yet.\n"); + projected_points.points = input_->points; +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelSphere::doSamplesVerifyModel ( + const std::set &indices, const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Needs a valid model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelSphere::doSamplesVerifyModel] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + for (std::set::const_iterator it = indices.begin (); it != indices.end (); ++it) + // Calculate the distance from the point to the sphere as the difference between + //dist(point,sphere_origin) and sphere_radius + if (fabs (sqrt ( + ( input_->points[*it].x - model_coefficients[0] ) * + ( input_->points[*it].x - model_coefficients[0] ) + + ( input_->points[*it].y - model_coefficients[1] ) * + ( input_->points[*it].y - model_coefficients[1] ) + + ( input_->points[*it].z - model_coefficients[2] ) * + ( input_->points[*it].z - model_coefficients[2] ) + ) - model_coefficients[3]) > threshold) + return (false); + + return (true); +} + +#define PCL_INSTANTIATE_SampleConsensusModelSphere(T) template class PCL_EXPORTS pcl::SampleConsensusModelSphere; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_SPHERE_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/impl/sac_model_stick.hpp b/pcl-1.7/pcl/sample_consensus/impl/sac_model_stick.hpp new file mode 100644 index 0000000..3e43cde --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/impl/sac_model_stick.hpp @@ -0,0 +1,366 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: sac_model_line.hpp 2328 2011-08-31 08:11:00Z rusu $ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_STICK_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_STICK_H_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelStick::isSampleGood (const std::vector &samples) const +{ + if ( + (input_->points[samples[0]].x != input_->points[samples[1]].x) + && + (input_->points[samples[0]].y != input_->points[samples[1]].y) + && + (input_->points[samples[0]].z != input_->points[samples[1]].z)) + return (true); + + return (false); +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelStick::computeModelCoefficients ( + const std::vector &samples, Eigen::VectorXf &model_coefficients) +{ + // Need 2 samples + if (samples.size () != 2) + { + PCL_ERROR ("[pcl::SampleConsensusModelStick::computeModelCoefficients] Invalid set of samples given (%lu)!\n", samples.size ()); + return (false); + } + + model_coefficients.resize (7); + model_coefficients[0] = input_->points[samples[0]].x; + model_coefficients[1] = input_->points[samples[0]].y; + model_coefficients[2] = input_->points[samples[0]].z; + + model_coefficients[3] = input_->points[samples[1]].x; + model_coefficients[4] = input_->points[samples[1]].y; + model_coefficients[5] = input_->points[samples[1]].z; + +// model_coefficients[3] = input_->points[samples[1]].x - model_coefficients[0]; +// model_coefficients[4] = input_->points[samples[1]].y - model_coefficients[1]; +// model_coefficients[5] = input_->points[samples[1]].z - model_coefficients[2]; + +// model_coefficients.template segment<3> (3).normalize (); + // We don't care about model_coefficients[6] which is the width (radius) of the stick + + return (true); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelStick::getDistancesToModel ( + const Eigen::VectorXf &model_coefficients, std::vector &distances) +{ + // Needs a valid set of model coefficients + if (!isModelValid (model_coefficients)) + return; + + float sqr_threshold = static_cast (radius_max_ * radius_max_); + distances.resize (indices_->size ()); + + // Obtain the line point and direction + Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + line_dir.normalize (); + + // Iterate through the 3d points and calculate the distances from them to the line + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the line + // D = ||(P2-P1) x (P1-P0)|| / ||P2-P1|| = norm (cross (p2-p1, p2-p0)) / norm(p2-p1) + float sqr_distance = (line_pt - input_->points[(*indices_)[i]].getVector4fMap ()).cross3 (line_dir).squaredNorm (); + + if (sqr_distance < sqr_threshold) + // Need to estimate sqrt here to keep MSAC and friends general + distances[i] = sqrt (sqr_distance); + else + // Penalize outliers by doubling the distance + distances[i] = 2 * sqrt (sqr_distance); + } +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelStick::selectWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold, std::vector &inliers) +{ + // Needs a valid set of model coefficients + if (!isModelValid (model_coefficients)) + return; + + float sqr_threshold = static_cast (threshold * threshold); + + int nr_p = 0; + inliers.resize (indices_->size ()); + error_sqr_dists_.resize (indices_->size ()); + + // Obtain the line point and direction + Eigen::Vector4f line_pt1 (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_pt2 (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + Eigen::Vector4f line_dir = line_pt2 - line_pt1; + //Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + //Eigen::Vector4f line_dir (model_coefficients[3] - model_coefficients[0], model_coefficients[4] - model_coefficients[1], model_coefficients[5] - model_coefficients[2], 0); + line_dir.normalize (); + //float norm = line_dir.squaredNorm (); + + // Iterate through the 3d points and calculate the distances from them to the line + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the line + // D = ||(P2-P1) x (P1-P0)|| / ||P2-P1|| = norm (cross (p2-p1, p2-p0)) / norm(p2-p1) + Eigen::Vector4f dir = input_->points[(*indices_)[i]].getVector4fMap () - line_pt1; + //float u = dir.dot (line_dir); + + // If the point falls outside of the segment, ignore it + //if (u < 0.0f || u > 1.0f) + // continue; + + float sqr_distance = dir.cross3 (line_dir).squaredNorm (); + if (sqr_distance < sqr_threshold) + { + // Returns the indices of the points whose squared distances are smaller than the threshold + inliers[nr_p] = (*indices_)[i]; + error_sqr_dists_[nr_p] = static_cast (sqr_distance); + ++nr_p; + } + } + inliers.resize (nr_p); + error_sqr_dists_.resize (nr_p); +} + +/////////////////////////////////////////////////////////////////////////// +template int +pcl::SampleConsensusModelStick::countWithinDistance ( + const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Needs a valid set of model coefficients + if (!isModelValid (model_coefficients)) + return (0); + + float sqr_threshold = static_cast (threshold * threshold); + + int nr_i = 0, nr_o = 0; + + // Obtain the line point and direction + Eigen::Vector4f line_pt1 (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_pt2 (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + Eigen::Vector4f line_dir = line_pt2 - line_pt1; + line_dir.normalize (); + + //Eigen::Vector4f line_dir (model_coefficients[3] - model_coefficients[0], model_coefficients[4] - model_coefficients[1], model_coefficients[5] - model_coefficients[2], 0); + //Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + + // Iterate through the 3d points and calculate the distances from them to the line + for (size_t i = 0; i < indices_->size (); ++i) + { + // Calculate the distance from the point to the line + // D = ||(P2-P1) x (P1-P0)|| / ||P2-P1|| = norm (cross (p2-p1, p2-p0)) / norm(p2-p1) + Eigen::Vector4f dir = input_->points[(*indices_)[i]].getVector4fMap () - line_pt1; + //float u = dir.dot (line_dir); + + // If the point falls outside of the segment, ignore it + //if (u < 0.0f || u > 1.0f) + // continue; + + float sqr_distance = dir.cross3 (line_dir).squaredNorm (); + // Use a larger threshold (4 times the radius) to get more points in + if (sqr_distance < sqr_threshold) + nr_i++; + else if (sqr_distance < 4 * sqr_threshold) + nr_o++; + } + + return (nr_i - nr_o < 0 ? 0 : nr_i - nr_o); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelStick::optimizeModelCoefficients ( + const std::vector &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients) +{ + // Needs a valid set of model coefficients + if (!isModelValid (model_coefficients)) + { + optimized_coefficients = model_coefficients; + return; + } + + // Need at least 2 points to estimate a line + if (inliers.size () <= 2) + { + PCL_ERROR ("[pcl::SampleConsensusModelStick::optimizeModelCoefficients] Not enough inliers found to support a model (%lu)! Returning the same coefficients.\n", inliers.size ()); + optimized_coefficients = model_coefficients; + return; + } + + optimized_coefficients.resize (7); + + // Compute the 3x3 covariance matrix + Eigen::Vector4f centroid; + Eigen::Matrix3f covariance_matrix; + + computeMeanAndCovarianceMatrix (*input_, inliers, covariance_matrix, centroid); + + optimized_coefficients[0] = centroid[0]; + optimized_coefficients[1] = centroid[1]; + optimized_coefficients[2] = centroid[2]; + + // Extract the eigenvalues and eigenvectors + Eigen::Vector3f eigen_values; + Eigen::Vector3f eigen_vector; + pcl::eigen33 (covariance_matrix, eigen_values); + pcl::computeCorrespondingEigenVector (covariance_matrix, eigen_values [2], eigen_vector); + + optimized_coefficients.template segment<3> (3).matrix () = eigen_vector; +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::SampleConsensusModelStick::projectPoints ( + const std::vector &inliers, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool copy_data_fields) +{ + // Needs a valid model coefficients + if (!isModelValid (model_coefficients)) + return; + + // Obtain the line point and direction + Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + + projected_points.header = input_->header; + projected_points.is_dense = input_->is_dense; + + // Copy all the data fields from the input cloud to the projected one? + if (copy_data_fields) + { + // Allocate enough space and copy the basics + projected_points.points.resize (input_->points.size ()); + projected_points.width = input_->width; + projected_points.height = input_->height; + + typedef typename pcl::traits::fieldList::type FieldList; + // Iterate over each point + for (size_t i = 0; i < projected_points.points.size (); ++i) + // Iterate over each dimension + pcl::for_each_type (NdConcatenateFunctor (input_->points[i], projected_points.points[i])); + + // Iterate through the 3d points and calculate the distances from them to the line + for (size_t i = 0; i < inliers.size (); ++i) + { + Eigen::Vector4f pt (input_->points[inliers[i]].x, input_->points[inliers[i]].y, input_->points[inliers[i]].z, 0); + // double k = (DOT_PROD_3D (points[i], p21) - dotA_B) / dotB_B; + float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) / line_dir.dot (line_dir); + + Eigen::Vector4f pp = line_pt + k * line_dir; + // Calculate the projection of the point on the line (pointProj = A + k * B) + projected_points.points[inliers[i]].x = pp[0]; + projected_points.points[inliers[i]].y = pp[1]; + projected_points.points[inliers[i]].z = pp[2]; + } + } + else + { + // Allocate enough space and copy the basics + projected_points.points.resize (inliers.size ()); + projected_points.width = static_cast (inliers.size ()); + projected_points.height = 1; + + typedef typename pcl::traits::fieldList::type FieldList; + // Iterate over each point + for (size_t i = 0; i < inliers.size (); ++i) + // Iterate over each dimension + pcl::for_each_type (NdConcatenateFunctor (input_->points[inliers[i]], projected_points.points[i])); + + // Iterate through the 3d points and calculate the distances from them to the line + for (size_t i = 0; i < inliers.size (); ++i) + { + Eigen::Vector4f pt (input_->points[inliers[i]].x, input_->points[inliers[i]].y, input_->points[inliers[i]].z, 0); + // double k = (DOT_PROD_3D (points[i], p21) - dotA_B) / dotB_B; + float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) / line_dir.dot (line_dir); + + Eigen::Vector4f pp = line_pt + k * line_dir; + // Calculate the projection of the point on the line (pointProj = A + k * B) + projected_points.points[i].x = pp[0]; + projected_points.points[i].y = pp[1]; + projected_points.points[i].z = pp[2]; + } + } +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::SampleConsensusModelStick::doSamplesVerifyModel ( + const std::set &indices, const Eigen::VectorXf &model_coefficients, const double threshold) +{ + // Needs a valid set of model coefficients + if (!isModelValid (model_coefficients)) + return (false); + + // Obtain the line point and direction + Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0); + Eigen::Vector4f line_dir (model_coefficients[3] - model_coefficients[0], model_coefficients[4] - model_coefficients[1], model_coefficients[5] - model_coefficients[2], 0); + //Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0); + line_dir.normalize (); + + float sqr_threshold = static_cast (threshold * threshold); + // Iterate through the 3d points and calculate the distances from them to the line + for (std::set::const_iterator it = indices.begin (); it != indices.end (); ++it) + { + // Calculate the distance from the point to the line + // D = ||(P2-P1) x (P1-P0)|| / ||P2-P1|| = norm (cross (p2-p1, p2-p0)) / norm(p2-p1) + if ((line_pt - input_->points[*it].getVector4fMap ()).cross3 (line_dir).squaredNorm () > sqr_threshold) + return (false); + } + + return (true); +} + +#define PCL_INSTANTIATE_SampleConsensusModelStick(T) template class PCL_EXPORTS pcl::SampleConsensusModelStick; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_STICK_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/lmeds.h b/pcl-1.7/pcl/sample_consensus/lmeds.h new file mode 100644 index 0000000..81f224f --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/lmeds.h @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_LMEDS_H_ +#define PCL_SAMPLE_CONSENSUS_LMEDS_H_ + +#include +#include + +namespace pcl +{ + /** \brief @b LeastMedianSquares represents an implementation of the LMedS (Least Median of Squares) algorithm. LMedS + * is a RANSAC-like model-fitting algorithm that can tolerate up to 50% outliers without requiring thresholds to be + * set. See Andrea Fusiello's "Elements of Geometric Computer Vision" + * (http://homepages.inf.ed.ac.uk/rbf/CVonline/LOCAL_COPIES/FUSIELLO4/tutorial.html#x1-520007) for more details. + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class LeastMedianSquares : public SampleConsensus + { + typedef typename SampleConsensusModel::Ptr SampleConsensusModelPtr; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + using SampleConsensus::max_iterations_; + using SampleConsensus::threshold_; + using SampleConsensus::iterations_; + using SampleConsensus::sac_model_; + using SampleConsensus::model_; + using SampleConsensus::model_coefficients_; + using SampleConsensus::inliers_; + + /** \brief LMedS (Least Median of Squares) main constructor + * \param[in] model a Sample Consensus model + */ + LeastMedianSquares (const SampleConsensusModelPtr &model) + : SampleConsensus (model) + { + // Maximum number of trials before we give up. + max_iterations_ = 50; + } + + /** \brief LMedS (Least Median of Squares) main constructor + * \param[in] model a Sample Consensus model + * \param[in] threshold distance to model threshold + */ + LeastMedianSquares (const SampleConsensusModelPtr &model, double threshold) + : SampleConsensus (model, threshold) + { + // Maximum number of trials before we give up. + max_iterations_ = 50; + } + + /** \brief Compute the actual model and find the inliers + * \param[in] debug_verbosity_level enable/disable on-screen debug information and set the verbosity level + */ + bool + computeModel (int debug_verbosity_level = 0); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_LMEDS_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/method_types.h b/pcl-1.7/pcl/sample_consensus/method_types.h new file mode 100644 index 0000000..85786eb --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/method_types.h @@ -0,0 +1,55 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_METHOD_TYPES_H_ +#define PCL_SAMPLE_CONSENSUS_METHOD_TYPES_H_ + +namespace pcl +{ + const static int SAC_RANSAC = 0; + const static int SAC_LMEDS = 1; + const static int SAC_MSAC = 2; + const static int SAC_RRANSAC = 3; + const static int SAC_RMSAC = 4; + const static int SAC_MLESAC = 5; + const static int SAC_PROSAC = 6; +} + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_METHOD_TYPES_H_ diff --git a/pcl-1.7/pcl/sample_consensus/mlesac.h b/pcl-1.7/pcl/sample_consensus/mlesac.h new file mode 100644 index 0000000..3634175 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/mlesac.h @@ -0,0 +1,164 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MLESAC_H_ +#define PCL_SAMPLE_CONSENSUS_MLESAC_H_ + +#include +#include + +namespace pcl +{ + /** \brief @b MaximumLikelihoodSampleConsensus represents an implementation of the MLESAC (Maximum Likelihood + * Estimator SAmple Consensus) algorithm, as described in: "MLESAC: A new robust estimator with application to + * estimating image geometry", P.H.S. Torr and A. Zisserman, Computer Vision and Image Understanding, vol 78, 2000. + * \note MLESAC is useful in situations where most of the data samples belong to the model, and a fast outlier rejection algorithm is needed. + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class MaximumLikelihoodSampleConsensus : public SampleConsensus + { + typedef typename SampleConsensusModel::Ptr SampleConsensusModelPtr; + typedef typename SampleConsensusModel::PointCloudConstPtr PointCloudConstPtr; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + using SampleConsensus::max_iterations_; + using SampleConsensus::threshold_; + using SampleConsensus::iterations_; + using SampleConsensus::sac_model_; + using SampleConsensus::model_; + using SampleConsensus::model_coefficients_; + using SampleConsensus::inliers_; + using SampleConsensus::probability_; + + /** \brief MLESAC (Maximum Likelihood Estimator SAmple Consensus) main constructor + * \param[in] model a Sample Consensus model + */ + MaximumLikelihoodSampleConsensus (const SampleConsensusModelPtr &model) : + SampleConsensus (model), + iterations_EM_ (3), // Max number of EM (Expectation Maximization) iterations + sigma_ (0) + { + max_iterations_ = 10000; // Maximum number of trials before we give up. + } + + /** \brief MLESAC (Maximum Likelihood Estimator SAmple Consensus) main constructor + * \param[in] model a Sample Consensus model + * \param[in] threshold distance to model threshold + */ + MaximumLikelihoodSampleConsensus (const SampleConsensusModelPtr &model, double threshold) : + SampleConsensus (model, threshold), + iterations_EM_ (3), // Max number of EM (Expectation Maximization) iterations + sigma_ (0) + { + max_iterations_ = 10000; // Maximum number of trials before we give up. + } + + /** \brief Compute the actual model and find the inliers + * \param[in] debug_verbosity_level enable/disable on-screen debug information and set the verbosity level + */ + bool + computeModel (int debug_verbosity_level = 0); + + /** \brief Set the number of EM iterations. + * \param[in] iterations the number of EM iterations + */ + inline void + setEMIterations (int iterations) { iterations_EM_ = iterations; } + + /** \brief Get the number of EM iterations. */ + inline int + getEMIterations () const { return (iterations_EM_); } + + + protected: + /** \brief Compute the median absolute deviation: + * \f[ + * MAD = \sigma * median_i (| Xi - median_j(Xj) |) + * \f] + * \note Sigma needs to be chosen carefully (a good starting sigma value is 1.4826) + * \param[in] cloud the point cloud data message + * \param[in] indices the set of point indices to use + * \param[in] sigma the sigma value + */ + double + computeMedianAbsoluteDeviation (const PointCloudConstPtr &cloud, + const boost::shared_ptr > &indices, + double sigma); + + /** \brief Determine the minimum and maximum 3D bounding box coordinates for a given set of points + * \param[in] cloud the point cloud message + * \param[in] indices the set of point indices to use + * \param[out] min_p the resultant minimum bounding box coordinates + * \param[out] max_p the resultant maximum bounding box coordinates + */ + void + getMinMax (const PointCloudConstPtr &cloud, + const boost::shared_ptr > &indices, + Eigen::Vector4f &min_p, + Eigen::Vector4f &max_p); + + /** \brief Compute the median value of a 3D point cloud using a given set point indices and return it as a Point32. + * \param[in] cloud the point cloud data message + * \param[in] indices the point indices + * \param[out] median the resultant median value + */ + void + computeMedian (const PointCloudConstPtr &cloud, + const boost::shared_ptr > &indices, + Eigen::Vector4f &median); + + private: + /** \brief Maximum number of EM (Expectation Maximization) iterations. */ + int iterations_EM_; + /** \brief The MLESAC sigma parameter. */ + double sigma_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MLESAC_H_ diff --git a/pcl-1.7/pcl/sample_consensus/model_types.h b/pcl-1.7/pcl/sample_consensus/model_types.h new file mode 100644 index 0000000..cd5855e --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/model_types.h @@ -0,0 +1,98 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_TYPES_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_TYPES_H_ + +#include + +namespace pcl +{ + enum SacModel + { + SACMODEL_PLANE, + SACMODEL_LINE, + SACMODEL_CIRCLE2D, + SACMODEL_CIRCLE3D, + SACMODEL_SPHERE, + SACMODEL_CYLINDER, + SACMODEL_CONE, + SACMODEL_TORUS, + SACMODEL_PARALLEL_LINE, + SACMODEL_PERPENDICULAR_PLANE, + SACMODEL_PARALLEL_LINES, + SACMODEL_NORMAL_PLANE, + SACMODEL_NORMAL_SPHERE, + SACMODEL_REGISTRATION, + SACMODEL_REGISTRATION_2D, + SACMODEL_PARALLEL_PLANE, + SACMODEL_NORMAL_PARALLEL_PLANE, + SACMODEL_STICK + }; +} + +// Define the number of samples in SacModel needs +typedef std::map::value_type SampleSizeModel; +const static SampleSizeModel sample_size_pairs[] = {SampleSizeModel (pcl::SACMODEL_PLANE, 3), + SampleSizeModel (pcl::SACMODEL_LINE, 2), + SampleSizeModel (pcl::SACMODEL_CIRCLE2D, 3), + SampleSizeModel (pcl::SACMODEL_CIRCLE3D, 3), + SampleSizeModel (pcl::SACMODEL_SPHERE, 4), + SampleSizeModel (pcl::SACMODEL_CYLINDER, 2), + SampleSizeModel (pcl::SACMODEL_CONE, 3), + //SampleSizeModel (pcl::SACMODEL_TORUS, 2), + SampleSizeModel (pcl::SACMODEL_PARALLEL_LINE, 2), + SampleSizeModel (pcl::SACMODEL_PERPENDICULAR_PLANE, 3), + //SampleSizeModel (pcl::PARALLEL_LINES, 2), + SampleSizeModel (pcl::SACMODEL_NORMAL_PLANE, 3), + SampleSizeModel (pcl::SACMODEL_NORMAL_SPHERE, 4), + SampleSizeModel (pcl::SACMODEL_REGISTRATION, 3), + SampleSizeModel (pcl::SACMODEL_REGISTRATION_2D, 3), + SampleSizeModel (pcl::SACMODEL_PARALLEL_PLANE, 3), + SampleSizeModel (pcl::SACMODEL_NORMAL_PARALLEL_PLANE, 3), + SampleSizeModel (pcl::SACMODEL_STICK, 2)}; + +namespace pcl +{ + const static std::map SAC_SAMPLE_SIZE (sample_size_pairs, sample_size_pairs + + sizeof (sample_size_pairs) / sizeof (SampleSizeModel)); +} + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_TYPES_H_ diff --git a/pcl-1.7/pcl/sample_consensus/msac.h b/pcl-1.7/pcl/sample_consensus/msac.h new file mode 100644 index 0000000..3816617 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/msac.h @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MSAC_H_ +#define PCL_SAMPLE_CONSENSUS_MSAC_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief @b MEstimatorSampleConsensus represents an implementation of the MSAC (M-estimator SAmple Consensus) + * algorithm, as described in: "MLESAC: A new robust estimator with application to estimating image geometry", P.H.S. + * Torr and A. Zisserman, Computer Vision and Image Understanding, vol 78, 2000. + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class MEstimatorSampleConsensus : public SampleConsensus + { + typedef typename SampleConsensusModel::Ptr SampleConsensusModelPtr; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + using SampleConsensus::max_iterations_; + using SampleConsensus::threshold_; + using SampleConsensus::iterations_; + using SampleConsensus::sac_model_; + using SampleConsensus::model_; + using SampleConsensus::model_coefficients_; + using SampleConsensus::inliers_; + using SampleConsensus::probability_; + + /** \brief MSAC (M-estimator SAmple Consensus) main constructor + * \param[in] model a Sample Consensus model + */ + MEstimatorSampleConsensus (const SampleConsensusModelPtr &model) + : SampleConsensus (model) + { + // Maximum number of trials before we give up. + max_iterations_ = 10000; + } + + /** \brief MSAC (M-estimator SAmple Consensus) main constructor + * \param[in] model a Sample Consensus model + * \param[in] threshold distance to model threshold + */ + MEstimatorSampleConsensus (const SampleConsensusModelPtr &model, double threshold) + : SampleConsensus (model, threshold) + { + // Maximum number of trials before we give up. + max_iterations_ = 10000; + } + + /** \brief Compute the actual model and find the inliers + * \param[in] debug_verbosity_level enable/disable on-screen debug information and set the verbosity level + */ + bool + computeModel (int debug_verbosity_level = 0); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MSAC_H_ diff --git a/pcl-1.7/pcl/sample_consensus/prosac.h b/pcl-1.7/pcl/sample_consensus/prosac.h new file mode 100644 index 0000000..491daa5 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/prosac.h @@ -0,0 +1,106 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_PROSAC_H_ +#define PCL_SAMPLE_CONSENSUS_PROSAC_H_ + +#include +#include + +namespace pcl +{ + /** \brief @b RandomSampleConsensus represents an implementation of the RANSAC (RAndom SAmple Consensus) algorithm, as + * described in: "Matching with PROSAC – Progressive Sample Consensus", Chum, O. and Matas, J.G., CVPR, I: 220-226 + * 2005. + * \author Vincent Rabaud + * \ingroup sample_consensus + */ + template + class ProgressiveSampleConsensus : public SampleConsensus + { + typedef typename SampleConsensusModel::Ptr SampleConsensusModelPtr; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + using SampleConsensus::max_iterations_; + using SampleConsensus::threshold_; + using SampleConsensus::iterations_; + using SampleConsensus::sac_model_; + using SampleConsensus::model_; + using SampleConsensus::model_coefficients_; + using SampleConsensus::inliers_; + using SampleConsensus::probability_; + + /** \brief PROSAC (Progressive SAmple Consensus) main constructor + * \param[in] model a Sample Consensus model + */ + ProgressiveSampleConsensus (const SampleConsensusModelPtr &model) : + SampleConsensus (model) + { + // Maximum number of trials before we give up. + max_iterations_ = 10000; + } + + /** \brief PROSAC (Progressive SAmple Consensus) main constructor + * \param[in] model a Sample Consensus model + * \param[in] threshold distance to model threshold + */ + ProgressiveSampleConsensus (const SampleConsensusModelPtr &model, double threshold) : + SampleConsensus (model, threshold) + { + // Maximum number of trials before we give up. + max_iterations_ = 10000; + } + + /** \brief Compute the actual model and find the inliers + * \param[in] debug_verbosity_level enable/disable on-screen debug information and set the verbosity level + */ + bool + computeModel (int debug_verbosity_level = 0); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_PROSAC_H_ diff --git a/pcl-1.7/pcl/sample_consensus/ransac.h b/pcl-1.7/pcl/sample_consensus/ransac.h new file mode 100644 index 0000000..e010f1c --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/ransac.h @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_RANSAC_H_ +#define PCL_SAMPLE_CONSENSUS_RANSAC_H_ + +#include +#include + +namespace pcl +{ + /** \brief @b RandomSampleConsensus represents an implementation of the RANSAC (RAndom SAmple Consensus) algorithm, as + * described in: "Random Sample Consensus: A Paradigm for Model Fitting with Applications to Image Analysis and + * Automated Cartography", Martin A. Fischler and Robert C. Bolles, Comm. Of the ACM 24: 381–395, June 1981. + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class RandomSampleConsensus : public SampleConsensus + { + typedef typename SampleConsensusModel::Ptr SampleConsensusModelPtr; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + using SampleConsensus::max_iterations_; + using SampleConsensus::threshold_; + using SampleConsensus::iterations_; + using SampleConsensus::sac_model_; + using SampleConsensus::model_; + using SampleConsensus::model_coefficients_; + using SampleConsensus::inliers_; + using SampleConsensus::probability_; + + /** \brief RANSAC (RAndom SAmple Consensus) main constructor + * \param[in] model a Sample Consensus model + */ + RandomSampleConsensus (const SampleConsensusModelPtr &model) + : SampleConsensus (model) + { + // Maximum number of trials before we give up. + max_iterations_ = 10000; + } + + /** \brief RANSAC (RAndom SAmple Consensus) main constructor + * \param[in] model a Sample Consensus model + * \param[in] threshold distance to model threshold + */ + RandomSampleConsensus (const SampleConsensusModelPtr &model, double threshold) + : SampleConsensus (model, threshold) + { + // Maximum number of trials before we give up. + max_iterations_ = 10000; + } + + /** \brief Compute the actual model and find the inliers + * \param[in] debug_verbosity_level enable/disable on-screen debug information and set the verbosity level + */ + bool + computeModel (int debug_verbosity_level = 0); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_RANSAC_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/rmsac.h b/pcl-1.7/pcl/sample_consensus/rmsac.h new file mode 100644 index 0000000..69656f1 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/rmsac.h @@ -0,0 +1,124 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_RMSAC_H_ +#define PCL_SAMPLE_CONSENSUS_RMSAC_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief @b RandomizedMEstimatorSampleConsensus represents an implementation of the RMSAC (Randomized M-estimator + * SAmple Consensus) algorithm, which basically adds a Td,d test (see \a RandomizedRandomSampleConsensus) to an MSAC + * estimator (see \a MEstimatorSampleConsensus). + * \note RMSAC is useful in situations where most of the data samples belong to the model, and a fast outlier rejection algorithm is needed. + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class RandomizedMEstimatorSampleConsensus : public SampleConsensus + { + typedef typename SampleConsensusModel::Ptr SampleConsensusModelPtr; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + using SampleConsensus::max_iterations_; + using SampleConsensus::threshold_; + using SampleConsensus::iterations_; + using SampleConsensus::sac_model_; + using SampleConsensus::model_; + using SampleConsensus::model_coefficients_; + using SampleConsensus::inliers_; + using SampleConsensus::probability_; + + /** \brief RMSAC (Randomized M-estimator SAmple Consensus) main constructor + * \param[in] model a Sample Consensus model + */ + RandomizedMEstimatorSampleConsensus (const SampleConsensusModelPtr &model) + : SampleConsensus (model) + , fraction_nr_pretest_ (10.0) // Number of samples to try randomly in percents + { + // Maximum number of trials before we give up. + max_iterations_ = 10000; + } + + /** \brief RMSAC (Randomized M-estimator SAmple Consensus) main constructor + * \param[in] model a Sample Consensus model + * \param[in] threshold distance to model threshold + */ + RandomizedMEstimatorSampleConsensus (const SampleConsensusModelPtr &model, double threshold) + : SampleConsensus (model, threshold) + , fraction_nr_pretest_ (10.0) // Number of samples to try randomly in percents + { + // Maximum number of trials before we give up. + max_iterations_ = 10000; + } + + /** \brief Compute the actual model and find the inliers + * \param[in] debug_verbosity_level enable/disable on-screen debug information and set the verbosity level + */ + bool + computeModel (int debug_verbosity_level = 0); + + /** \brief Set the percentage of points to pre-test. + * \param[in] nr_pretest percentage of points to pre-test + */ + inline void + setFractionNrPretest (double nr_pretest) { fraction_nr_pretest_ = nr_pretest; } + + /** \brief Get the percentage of points to pre-test. */ + inline double + getFractionNrPretest () { return (fraction_nr_pretest_); } + + private: + /** \brief Number of samples to randomly pre-test, in percents. */ + double fraction_nr_pretest_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_RMSAC_H_ diff --git a/pcl-1.7/pcl/sample_consensus/rransac.h b/pcl-1.7/pcl/sample_consensus/rransac.h new file mode 100644 index 0000000..b9f0aa6 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/rransac.h @@ -0,0 +1,124 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_RRANSAC_H_ +#define PCL_SAMPLE_CONSENSUS_RRANSAC_H_ + +#include +#include + +namespace pcl +{ + /** \brief @b RandomizedRandomSampleConsensus represents an implementation of the RRANSAC (Randomized RAndom SAmple + * Consensus), as described in "Randomized RANSAC with Td,d test", O. Chum and J. Matas, Proc. British Machine Vision + * Conf. (BMVC '02), vol. 2, BMVA, pp. 448-457, 2002. + * \note RRANSAC is useful in situations where most of the data samples belong to the model, and a fast outlier rejection algorithm is needed. + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class RandomizedRandomSampleConsensus : public SampleConsensus + { + typedef typename SampleConsensusModel::Ptr SampleConsensusModelPtr; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + using SampleConsensus::max_iterations_; + using SampleConsensus::threshold_; + using SampleConsensus::iterations_; + using SampleConsensus::sac_model_; + using SampleConsensus::model_; + using SampleConsensus::model_coefficients_; + using SampleConsensus::inliers_; + using SampleConsensus::probability_; + + /** \brief RANSAC (Randomized RAndom SAmple Consensus) main constructor + * \param[in] model a Sample Consensus model + */ + RandomizedRandomSampleConsensus (const SampleConsensusModelPtr &model) + : SampleConsensus (model) + , fraction_nr_pretest_ (10.0) // Number of samples to try randomly in percents + { + // Maximum number of trials before we give up. + max_iterations_ = 10000; + } + + /** \brief RRANSAC (RAndom SAmple Consensus) main constructor + * \param[in] model a Sample Consensus model + * \param[in] threshold distance to model threshold + */ + RandomizedRandomSampleConsensus (const SampleConsensusModelPtr &model, double threshold) + : SampleConsensus (model, threshold) + , fraction_nr_pretest_ (10.0) // Number of samples to try randomly in percents + { + // Maximum number of trials before we give up. + max_iterations_ = 10000; + } + + /** \brief Compute the actual model and find the inliers + * \param[in] debug_verbosity_level enable/disable on-screen debug information and set the verbosity level + */ + bool + computeModel (int debug_verbosity_level = 0); + + /** \brief Set the percentage of points to pre-test. + * \param[in] nr_pretest percentage of points to pre-test + */ + inline void + setFractionNrPretest (double nr_pretest) { fraction_nr_pretest_ = nr_pretest; } + + /** \brief Get the percentage of points to pre-test. */ + inline double + getFractionNrPretest () { return (fraction_nr_pretest_); } + + private: + /** \brief Number of samples to randomly pre-test, in percents. */ + double fraction_nr_pretest_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_RRANSAC_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/sac.h b/pcl-1.7/pcl/sample_consensus/sac.h new file mode 100644 index 0000000..28cbbfd --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac.h @@ -0,0 +1,348 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_H_ +#define PCL_SAMPLE_CONSENSUS_H_ + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief SampleConsensus represents the base class. All sample consensus methods must inherit from this class. + * \author Radu Bogdan Rusu + * \ingroup sample_consensus + */ + template + class SampleConsensus + { + typedef typename SampleConsensusModel::Ptr SampleConsensusModelPtr; + + private: + /** \brief Constructor for base SAC. */ + SampleConsensus () {}; + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Constructor for base SAC. + * \param[in] model a Sample Consensus model + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensus (const SampleConsensusModelPtr &model, bool random = false) + : sac_model_ (model) + , model_ () + , inliers_ () + , model_coefficients_ () + , probability_ (0.99) + , iterations_ (0) + , threshold_ (std::numeric_limits::max ()) + , max_iterations_ (1000) + , rng_alg_ () + , rng_ (new boost::uniform_01 (rng_alg_)) + { + // Create a random number generator object + if (random) + rng_->base ().seed (static_cast (std::time (0))); + else + rng_->base ().seed (12345u); + }; + + /** \brief Constructor for base SAC. + * \param[in] model a Sample Consensus model + * \param[in] threshold distance to model threshol + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensus (const SampleConsensusModelPtr &model, + double threshold, + bool random = false) + : sac_model_ (model) + , model_ () + , inliers_ () + , model_coefficients_ () + , probability_ (0.99) + , iterations_ (0) + , threshold_ (threshold) + , max_iterations_ (1000) + , rng_alg_ () + , rng_ (new boost::uniform_01 (rng_alg_)) + { + // Create a random number generator object + if (random) + rng_->base ().seed (static_cast (std::time (0))); + else + rng_->base ().seed (12345u); + }; + + /** \brief Set the Sample Consensus model to use. + * \param[in] model a Sample Consensus model + */ + void + setSampleConsensusModel (const SampleConsensusModelPtr &model) + { + sac_model_ = model; + } + + /** \brief Get the Sample Consensus model used. */ + SampleConsensusModelPtr + getSampleConsensusModel () const + { + return (sac_model_); + } + + /** \brief Destructor for base SAC. */ + virtual ~SampleConsensus () {}; + + /** \brief Set the distance to model threshold. + * \param[in] threshold distance to model threshold + */ + inline void + setDistanceThreshold (double threshold) { threshold_ = threshold; } + + /** \brief Get the distance to model threshold, as set by the user. */ + inline double + getDistanceThreshold () { return (threshold_); } + + /** \brief Set the maximum number of iterations. + * \param[in] max_iterations maximum number of iterations + */ + inline void + setMaxIterations (int max_iterations) { max_iterations_ = max_iterations; } + + /** \brief Get the maximum number of iterations, as set by the user. */ + inline int + getMaxIterations () { return (max_iterations_); } + + /** \brief Set the desired probability of choosing at least one sample free from outliers. + * \param[in] probability the desired probability of choosing at least one sample free from outliers + * \note internally, the probability is set to 99% (0.99) by default. + */ + inline void + setProbability (double probability) { probability_ = probability; } + + /** \brief Obtain the probability of choosing at least one sample free from outliers, as set by the user. */ + inline double + getProbability () { return (probability_); } + + /** \brief Compute the actual model. Pure virtual. */ + virtual bool + computeModel (int debug_verbosity_level = 0) = 0; + + /** \brief Refine the model found. + * This loops over the model coefficients and optimizes them together + * with the set of inliers, until the change in the set of inliers is + * minimal. + * \param[in] sigma standard deviation multiplier for considering a sample as inlier (Mahalanobis distance) + * \param[in] max_iterations the maxim number of iterations to try to refine in case the inliers keep on changing + */ + virtual bool + refineModel (const double sigma = 3.0, const unsigned int max_iterations = 1000) + { + if (!sac_model_) + { + PCL_ERROR ("[pcl::SampleConsensus::refineModel] Critical error: NULL model!\n"); + return (false); + } + + double inlier_distance_threshold_sqr = threshold_ * threshold_, + error_threshold = threshold_; + double sigma_sqr = sigma * sigma; + unsigned int refine_iterations = 0; + bool inlier_changed = false, oscillating = false; + std::vector new_inliers, prev_inliers = inliers_; + std::vector inliers_sizes; + Eigen::VectorXf new_model_coefficients = model_coefficients_; + do + { + // Optimize the model coefficients + sac_model_->optimizeModelCoefficients (prev_inliers, new_model_coefficients, new_model_coefficients); + inliers_sizes.push_back (prev_inliers.size ()); + + // Select the new inliers based on the optimized coefficients and new threshold + sac_model_->selectWithinDistance (new_model_coefficients, error_threshold, new_inliers); + PCL_DEBUG ("[pcl::SampleConsensus::refineModel] Number of inliers found (before/after): %lu/%lu, with an error threshold of %g.\n", prev_inliers.size (), new_inliers.size (), error_threshold); + + if (new_inliers.empty ()) + { + refine_iterations++; + if (refine_iterations >= max_iterations) + break; + continue; + //return (false); + } + + // Estimate the variance and the new threshold + double variance = sac_model_->computeVariance (); + error_threshold = sqrt (std::min (inlier_distance_threshold_sqr, sigma_sqr * variance)); + + PCL_DEBUG ("[pcl::SampleConsensus::refineModel] New estimated error threshold: %g on iteration %d out of %d.\n", error_threshold, refine_iterations, max_iterations); + inlier_changed = false; + std::swap (prev_inliers, new_inliers); + // If the number of inliers changed, then we are still optimizing + if (new_inliers.size () != prev_inliers.size ()) + { + // Check if the number of inliers is oscillating in between two values + if (inliers_sizes.size () >= 4) + { + if (inliers_sizes[inliers_sizes.size () - 1] == inliers_sizes[inliers_sizes.size () - 3] && + inliers_sizes[inliers_sizes.size () - 2] == inliers_sizes[inliers_sizes.size () - 4]) + { + oscillating = true; + break; + } + } + inlier_changed = true; + continue; + } + + // Check the values of the inlier set + for (size_t i = 0; i < prev_inliers.size (); ++i) + { + // If the value of the inliers changed, then we are still optimizing + if (prev_inliers[i] != new_inliers[i]) + { + inlier_changed = true; + break; + } + } + } + while (inlier_changed && ++refine_iterations < max_iterations); + + // If the new set of inliers is empty, we didn't do a good job refining + if (new_inliers.empty ()) + { + PCL_ERROR ("[pcl::SampleConsensus::refineModel] Refinement failed: got an empty set of inliers!\n"); + return (false); + } + + if (oscillating) + { + PCL_DEBUG ("[pcl::SampleConsensus::refineModel] Detected oscillations in the model refinement.\n"); + return (true); + } + + // If no inliers have been changed anymore, then the refinement was successful + if (!inlier_changed) + { + std::swap (inliers_, new_inliers); + model_coefficients_ = new_model_coefficients; + return (true); + } + return (false); + } + + /** \brief Get a set of randomly selected indices. + * \param[in] indices the input indices vector + * \param[in] nr_samples the desired number of point indices to randomly select + * \param[out] indices_subset the resultant output set of randomly selected indices + */ + inline void + getRandomSamples (const boost::shared_ptr > &indices, + size_t nr_samples, + std::set &indices_subset) + { + indices_subset.clear (); + while (indices_subset.size () < nr_samples) + //indices_subset.insert ((*indices)[(int) (indices->size () * (rand () / (RAND_MAX + 1.0)))]); + indices_subset.insert ((*indices)[static_cast (static_cast(indices->size ()) * rnd ())]); + } + + /** \brief Return the best model found so far. + * \param[out] model the resultant model + */ + inline void + getModel (std::vector &model) { model = model_; } + + /** \brief Return the best set of inliers found so far for this model. + * \param[out] inliers the resultant set of inliers + */ + inline void + getInliers (std::vector &inliers) { inliers = inliers_; } + + /** \brief Return the model coefficients of the best model found so far. + * \param[out] model_coefficients the resultant model coefficients, as documented in \ref sample_consensus + */ + inline void + getModelCoefficients (Eigen::VectorXf &model_coefficients) { model_coefficients = model_coefficients_; } + + protected: + /** \brief The underlying data model used (i.e. what is it that we attempt to search for). */ + SampleConsensusModelPtr sac_model_; + + /** \brief The model found after the last computeModel () as point cloud indices. */ + std::vector model_; + + /** \brief The indices of the points that were chosen as inliers after the last computeModel () call. */ + std::vector inliers_; + + /** \brief The coefficients of our model computed directly from the model found. */ + Eigen::VectorXf model_coefficients_; + + /** \brief Desired probability of choosing at least one sample free from outliers. */ + double probability_; + + /** \brief Total number of internal loop iterations that we've done so far. */ + int iterations_; + + /** \brief Distance to model threshold. */ + double threshold_; + + /** \brief Maximum number of iterations before giving up. */ + int max_iterations_; + + /** \brief Boost-based random number generator algorithm. */ + boost::mt19937 rng_alg_; + + /** \brief Boost-based random number generator distribution. */ + boost::shared_ptr > rng_; + + /** \brief Boost-based random number generator. */ + inline double + rnd () + { + return ((*rng_) ()); + } + }; +} + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model.h b/pcl-1.7/pcl/sample_consensus/sac_model.h new file mode 100644 index 0000000..5659756 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model.h @@ -0,0 +1,651 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_H_ + +#include +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace pcl +{ + template class ProgressiveSampleConsensus; + + /** \brief @b SampleConsensusModel represents the base model class. All sample consensus models must inherit + * from this class. + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class SampleConsensusModel + { + public: + typedef typename pcl::PointCloud PointCloud; + typedef typename pcl::PointCloud::ConstPtr PointCloudConstPtr; + typedef typename pcl::PointCloud::Ptr PointCloudPtr; + typedef typename pcl::search::Search::Ptr SearchPtr; + + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + protected: + /** \brief Empty constructor for base SampleConsensusModel. + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModel (bool random = false) + : input_ () + , indices_ () + , radius_min_ (-std::numeric_limits::max ()) + , radius_max_ (std::numeric_limits::max ()) + , samples_radius_ (0.) + , samples_radius_search_ () + , shuffled_indices_ () + , rng_alg_ () + , rng_dist_ (new boost::uniform_int<> (0, std::numeric_limits::max ())) + , rng_gen_ () + , error_sqr_dists_ () + { + // Create a random number generator object + if (random) + rng_alg_.seed (static_cast (std::time(0))); + else + rng_alg_.seed (12345u); + + rng_gen_.reset (new boost::variate_generator > (rng_alg_, *rng_dist_)); + } + + public: + /** \brief Constructor for base SampleConsensusModel. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModel (const PointCloudConstPtr &cloud, bool random = false) + : input_ () + , indices_ () + , radius_min_ (-std::numeric_limits::max ()) + , radius_max_ (std::numeric_limits::max ()) + , samples_radius_ (0.) + , samples_radius_search_ () + , shuffled_indices_ () + , rng_alg_ () + , rng_dist_ (new boost::uniform_int<> (0, std::numeric_limits::max ())) + , rng_gen_ () + , error_sqr_dists_ () + { + if (random) + rng_alg_.seed (static_cast (std::time (0))); + else + rng_alg_.seed (12345u); + + // Sets the input cloud and creates a vector of "fake" indices + setInputCloud (cloud); + + // Create a random number generator object + rng_gen_.reset (new boost::variate_generator > (rng_alg_, *rng_dist_)); + } + + /** \brief Constructor for base SampleConsensusModel. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModel (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : input_ (cloud) + , indices_ (new std::vector (indices)) + , radius_min_ (-std::numeric_limits::max ()) + , radius_max_ (std::numeric_limits::max ()) + , samples_radius_ (0.) + , samples_radius_search_ () + , shuffled_indices_ () + , rng_alg_ () + , rng_dist_ (new boost::uniform_int<> (0, std::numeric_limits::max ())) + , rng_gen_ () + , error_sqr_dists_ () + { + if (random) + rng_alg_.seed (static_cast (std::time(0))); + else + rng_alg_.seed (12345u); + + if (indices_->size () > input_->points.size ()) + { + PCL_ERROR ("[pcl::SampleConsensusModel] Invalid index vector given with size %lu while the input PointCloud has size %lu!\n", indices_->size (), input_->points.size ()); + indices_->clear (); + } + shuffled_indices_ = *indices_; + + // Create a random number generator object + rng_gen_.reset (new boost::variate_generator > (rng_alg_, *rng_dist_)); + }; + + /** \brief Destructor for base SampleConsensusModel. */ + virtual ~SampleConsensusModel () {}; + + /** \brief Get a set of random data samples and return them as point + * indices. + * \param[out] iterations the internal number of iterations used by SAC methods + * \param[out] samples the resultant model samples + */ + virtual void + getSamples (int &iterations, std::vector &samples) + { + // We're assuming that indices_ have already been set in the constructor + if (indices_->size () < getSampleSize ()) + { + PCL_ERROR ("[pcl::SampleConsensusModel::getSamples] Can not select %lu unique points out of %lu!\n", + samples.size (), indices_->size ()); + // one of these will make it stop :) + samples.clear (); + iterations = INT_MAX - 1; + return; + } + + // Get a second point which is different than the first + samples.resize (getSampleSize ()); + for (unsigned int iter = 0; iter < max_sample_checks_; ++iter) + { + // Choose the random indices + if (samples_radius_ < std::numeric_limits::epsilon ()) + SampleConsensusModel::drawIndexSample (samples); + else + SampleConsensusModel::drawIndexSampleRadius (samples); + + // If it's a good sample, stop here + if (isSampleGood (samples)) + { + PCL_DEBUG ("[pcl::SampleConsensusModel::getSamples] Selected %lu samples.\n", samples.size ()); + return; + } + } + PCL_DEBUG ("[pcl::SampleConsensusModel::getSamples] WARNING: Could not select %d sample points in %d iterations!\n", getSampleSize (), max_sample_checks_); + samples.clear (); + } + + /** \brief Check whether the given index samples can form a valid model, + * compute the model coefficients from these samples and store them + * in model_coefficients. Pure virtual. + * \param[in] samples the point indices found as possible good candidates + * for creating a valid model + * \param[out] model_coefficients the computed model coefficients + */ + virtual bool + computeModelCoefficients (const std::vector &samples, + Eigen::VectorXf &model_coefficients) = 0; + + /** \brief Recompute the model coefficients using the given inlier set + * and return them to the user. Pure virtual. + * + * @note: these are the coefficients of the model after refinement + * (e.g., after a least-squares optimization) + * + * \param[in] inliers the data inliers supporting the model + * \param[in] model_coefficients the initial guess for the model coefficients + * \param[out] optimized_coefficients the resultant recomputed coefficients after non-linear optimization + */ + virtual void + optimizeModelCoefficients (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + Eigen::VectorXf &optimized_coefficients) = 0; + + /** \brief Compute all distances from the cloud data to a given model. Pure virtual. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[out] distances the resultant estimated distances + */ + virtual void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances) = 0; + + /** \brief Select all the points which respect the given model + * coefficients as inliers. Pure virtual. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from + * the outliers + * \param[out] inliers the resultant model inliers + */ + virtual void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers) = 0; + + /** \brief Count all the points which respect the given model + * coefficients as inliers. Pure virtual. + * + * \param[in] model_coefficients the coefficients of a model that we need to + * compute distances to + * \param[in] threshold a maximum admissible distance threshold for + * determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold) = 0; + + /** \brief Create a new point cloud with inliers projected onto the model. Pure virtual. + * \param[in] inliers the data inliers that we want to project on the model + * \param[in] model_coefficients the coefficients of a model + * \param[out] projected_points the resultant projected points + * \param[in] copy_data_fields set to true (default) if we want the \a + * projected_points cloud to be an exact copy of the input dataset minus + * the point projections on the plane model + */ + virtual void + projectPoints (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + PointCloud &projected_points, + bool copy_data_fields = true) = 0; + + /** \brief Verify whether a subset of indices verifies a given set of + * model coefficients. Pure virtual. + * + * \param[in] indices the data indices that need to be tested against the model + * \param[in] model_coefficients the set of model coefficients + * \param[in] threshold a maximum admissible distance threshold for + * determining the inliers from the outliers + */ + virtual bool + doSamplesVerifyModel (const std::set &indices, + const Eigen::VectorXf &model_coefficients, + const double threshold) = 0; + + /** \brief Provide a pointer to the input dataset + * \param[in] cloud the const boost shared pointer to a PointCloud message + */ + inline virtual void + setInputCloud (const PointCloudConstPtr &cloud) + { + input_ = cloud; + if (!indices_) + indices_.reset (new std::vector ()); + if (indices_->empty ()) + { + // Prepare a set of indices to be used (entire cloud) + indices_->resize (cloud->points.size ()); + for (size_t i = 0; i < cloud->points.size (); ++i) + (*indices_)[i] = static_cast (i); + } + shuffled_indices_ = *indices_; + } + + /** \brief Get a pointer to the input point cloud dataset. */ + inline PointCloudConstPtr + getInputCloud () const { return (input_); } + + /** \brief Provide a pointer to the vector of indices that represents the input data. + * \param[in] indices a pointer to the vector of indices that represents the input data. + */ + inline void + setIndices (const boost::shared_ptr > &indices) + { + indices_ = indices; + shuffled_indices_ = *indices_; + } + + /** \brief Provide the vector of indices that represents the input data. + * \param[out] indices the vector of indices that represents the input data. + */ + inline void + setIndices (const std::vector &indices) + { + indices_.reset (new std::vector (indices)); + shuffled_indices_ = indices; + } + + /** \brief Get a pointer to the vector of indices used. */ + inline boost::shared_ptr > + getIndices () const { return (indices_); } + + /** \brief Return an unique id for each type of model employed. */ + virtual SacModel + getModelType () const = 0; + + /** \brief Return the size of a sample from which a model is computed */ + inline unsigned int + getSampleSize () const + { + std::map::const_iterator it = SAC_SAMPLE_SIZE.find (getModelType ()); + if (it == SAC_SAMPLE_SIZE.end ()) + throw InvalidSACModelTypeException ("No sample size defined for given model type!\n"); + return (it->second); + } + + /** \brief Set the minimum and maximum allowable radius limits for the + * model (applicable to models that estimate a radius) + * \param[in] min_radius the minimum radius model + * \param[in] max_radius the maximum radius model + * \todo change this to set limits on the entire model + */ + inline void + setRadiusLimits (const double &min_radius, const double &max_radius) + { + radius_min_ = min_radius; + radius_max_ = max_radius; + } + + /** \brief Get the minimum and maximum allowable radius limits for the + * model as set by the user. + * + * \param[out] min_radius the resultant minimum radius model + * \param[out] max_radius the resultant maximum radius model + */ + inline void + getRadiusLimits (double &min_radius, double &max_radius) + { + min_radius = radius_min_; + max_radius = radius_max_; + } + + /** \brief Set the maximum distance allowed when drawing random samples + * \param[in] radius the maximum distance (L2 norm) + * \param search + */ + inline void + setSamplesMaxDist (const double &radius, SearchPtr search) + { + samples_radius_ = radius; + samples_radius_search_ = search; + } + + /** \brief Get maximum distance allowed when drawing random samples + * + * \param[out] radius the maximum distance (L2 norm) + */ + inline void + getSamplesMaxDist (double &radius) + { + radius = samples_radius_; + } + + friend class ProgressiveSampleConsensus; + + /** \brief Compute the variance of the errors to the model. + * \param[in] error_sqr_dists a vector holding the distances + */ + inline double + computeVariance (const std::vector &error_sqr_dists) + { + std::vector dists (error_sqr_dists); + std::sort (dists.begin (), dists.end ()); + double median_error_sqr = dists[dists.size () >> 1]; + return (2.1981 * median_error_sqr); + } + + /** \brief Compute the variance of the errors to the model from the internally + * estimated vector of distances. The model must be computed first (or at least + * selectWithinDistance must be called). + */ + inline double + computeVariance () + { + if (error_sqr_dists_.empty ()) + { + PCL_ERROR ("[pcl::SampleConsensusModel::computeVariance] The variance of the Sample Consensus model distances cannot be estimated, as the model has not been computed yet. Please compute the model first or at least run selectWithinDistance before continuing. Returning NAN!\n"); + return (std::numeric_limits::quiet_NaN ()); + } + return (computeVariance (error_sqr_dists_)); + } + + protected: + /** \brief Fills a sample array with random samples from the indices_ vector + * \param[out] sample the set of indices of target_ to analyze + */ + inline void + drawIndexSample (std::vector &sample) + { + size_t sample_size = sample.size (); + size_t index_size = shuffled_indices_.size (); + for (unsigned int i = 0; i < sample_size; ++i) + // The 1/(RAND_MAX+1.0) trick is when the random numbers are not uniformly distributed and for small modulo + // elements, that does not matter (and nowadays, random number generators are good) + //std::swap (shuffled_indices_[i], shuffled_indices_[i + (rand () % (index_size - i))]); + std::swap (shuffled_indices_[i], shuffled_indices_[i + (rnd () % (index_size - i))]); + std::copy (shuffled_indices_.begin (), shuffled_indices_.begin () + sample_size, sample.begin ()); + } + + /** \brief Fills a sample array with one random sample from the indices_ vector + * and other random samples that are closer than samples_radius_ + * \param[out] sample the set of indices of target_ to analyze + */ + inline void + drawIndexSampleRadius (std::vector &sample) + { + size_t sample_size = sample.size (); + size_t index_size = shuffled_indices_.size (); + + std::swap (shuffled_indices_[0], shuffled_indices_[0 + (rnd () % (index_size - 0))]); + //const PointT& pt0 = (*input_)[shuffled_indices_[0]]; + + std::vector indices; + std::vector sqr_dists; + + // If indices have been set when the search object was constructed, + // radiusSearch() expects an index into the indices vector as its + // first parameter. This can't be determined efficiently, so we use + // the point instead of the index. + // Returned indices are converted automatically. + samples_radius_search_->radiusSearch (input_->at(shuffled_indices_[0]), + samples_radius_, indices, sqr_dists ); + + if (indices.size () < sample_size - 1) + { + // radius search failed, make an invalid model + for(unsigned int i = 1; i < sample_size; ++i) + shuffled_indices_[i] = shuffled_indices_[0]; + } + else + { + for (unsigned int i = 0; i < sample_size-1; ++i) + std::swap (indices[i], indices[i + (rnd () % (indices.size () - i))]); + for (unsigned int i = 1; i < sample_size; ++i) + shuffled_indices_[i] = indices[i-1]; + } + + std::copy (shuffled_indices_.begin (), shuffled_indices_.begin () + sample_size, sample.begin ()); + } + + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + virtual inline bool + isModelValid (const Eigen::VectorXf &model_coefficients) = 0; + + /** \brief Check if a sample of indices results in a good sample of points + * indices. Pure virtual. + * \param[in] samples the resultant index samples + */ + virtual bool + isSampleGood (const std::vector &samples) const = 0; + + /** \brief A boost shared pointer to the point cloud data array. */ + PointCloudConstPtr input_; + + /** \brief A pointer to the vector of point indices to use. */ + boost::shared_ptr > indices_; + + /** The maximum number of samples to try until we get a good one */ + static const unsigned int max_sample_checks_ = 1000; + + /** \brief The minimum and maximum radius limits for the model. + * Applicable to all models that estimate a radius. + */ + double radius_min_, radius_max_; + + /** \brief The maximum distance of subsequent samples from the first (radius search) */ + double samples_radius_; + + /** \brief The search object for picking subsequent samples using radius search */ + SearchPtr samples_radius_search_; + + /** Data containing a shuffled version of the indices. This is used and modified when drawing samples. */ + std::vector shuffled_indices_; + + /** \brief Boost-based random number generator algorithm. */ + boost::mt19937 rng_alg_; + + /** \brief Boost-based random number generator distribution. */ + boost::shared_ptr > rng_dist_; + + /** \brief Boost-based random number generator. */ + boost::shared_ptr > > rng_gen_; + + /** \brief A vector holding the distances to the computed model. Used internally. */ + std::vector error_sqr_dists_; + + /** \brief Boost-based random number generator. */ + inline int + rnd () + { + return ((*rng_gen_) ()); + } + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + /** \brief @b SampleConsensusModelFromNormals represents the base model class + * for models that require the use of surface normals for estimation. + */ + template + class SampleConsensusModelFromNormals //: public SampleConsensusModel + { + public: + typedef typename pcl::PointCloud::ConstPtr PointCloudNConstPtr; + typedef typename pcl::PointCloud::Ptr PointCloudNPtr; + + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Empty constructor for base SampleConsensusModelFromNormals. */ + SampleConsensusModelFromNormals () : normal_distance_weight_ (0.0), normals_ () {}; + + /** \brief Destructor. */ + virtual ~SampleConsensusModelFromNormals () {} + + /** \brief Set the normal angular distance weight. + * \param[in] w the relative weight (between 0 and 1) to give to the angular + * distance (0 to pi/2) between point normals and the plane normal. + * (The Euclidean distance will have weight 1-w.) + */ + inline void + setNormalDistanceWeight (const double w) + { + normal_distance_weight_ = w; + } + + /** \brief Get the normal angular distance weight. */ + inline double + getNormalDistanceWeight () { return (normal_distance_weight_); } + + /** \brief Provide a pointer to the input dataset that contains the point + * normals of the XYZ dataset. + * + * \param[in] normals the const boost shared pointer to a PointCloud message + */ + inline void + setInputNormals (const PointCloudNConstPtr &normals) + { + normals_ = normals; + } + + /** \brief Get a pointer to the normals of the input XYZ point cloud dataset. */ + inline PointCloudNConstPtr + getInputNormals () { return (normals_); } + + protected: + /** \brief The relative weight (between 0 and 1) to give to the angular + * distance (0 to pi/2) between point normals and the plane normal. + */ + double normal_distance_weight_; + + /** \brief A pointer to the input dataset that contains the point normals + * of the XYZ dataset. + */ + PointCloudNConstPtr normals_; + }; + + /** Base functor all the models that need non linear optimization must + * define their own one and implement operator() (const Eigen::VectorXd& x, Eigen::VectorXd& fvec) + * or operator() (const Eigen::VectorXf& x, Eigen::VectorXf& fvec) dependening on the choosen _Scalar + */ + template + struct Functor + { + typedef _Scalar Scalar; + enum + { + InputsAtCompileTime = NX, + ValuesAtCompileTime = NY + }; + + typedef Eigen::Matrix ValueType; + typedef Eigen::Matrix InputType; + typedef Eigen::Matrix JacobianType; + + /** \brief Empty Construtor. */ + Functor () : m_data_points_ (ValuesAtCompileTime) {} + + /** \brief Constructor + * \param[in] m_data_points number of data points to evaluate. + */ + Functor (int m_data_points) : m_data_points_ (m_data_points) {} + + virtual ~Functor () {} + + /** \brief Get the number of values. */ + int + values () const { return (m_data_points_); } + + private: + const int m_data_points_; + }; +} + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_circle.h b/pcl-1.7/pcl/sample_consensus/sac_model_circle.h new file mode 100644 index 0000000..b27e7fb --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_circle.h @@ -0,0 +1,254 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CIRCLE2D_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_CIRCLE2D_H_ + +#include +#include + +namespace pcl +{ + /** \brief SampleConsensusModelCircle2D defines a model for 2D circle segmentation on the X-Y plane. + * + * The model coefficients are defined as: + * - \b center.x : the X coordinate of the circle's center + * - \b center.y : the Y coordinate of the circle's center + * - \b radius : the circle's radius + * + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class SampleConsensusModelCircle2D : public SampleConsensusModel + { + public: + using SampleConsensusModel::input_; + using SampleConsensusModel::indices_; + using SampleConsensusModel::radius_min_; + using SampleConsensusModel::radius_max_; + using SampleConsensusModel::error_sqr_dists_; + + typedef typename SampleConsensusModel::PointCloud PointCloud; + typedef typename SampleConsensusModel::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModel::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr Ptr; + + /** \brief Constructor for base SampleConsensusModelCircle2D. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelCircle2D (const PointCloudConstPtr &cloud, bool random = false) + : SampleConsensusModel (cloud, random), tmp_inliers_ () + {}; + + /** \brief Constructor for base SampleConsensusModelCircle2D. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelCircle2D (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModel (cloud, indices, random), tmp_inliers_ () + {}; + + /** \brief Copy constructor. + * \param[in] source the model to copy into this + */ + SampleConsensusModelCircle2D (const SampleConsensusModelCircle2D &source) : + SampleConsensusModel (), tmp_inliers_ () + { + *this = source; + } + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelCircle2D () {} + + /** \brief Copy constructor. + * \param[in] source the model to copy into this + */ + inline SampleConsensusModelCircle2D& + operator = (const SampleConsensusModelCircle2D &source) + { + SampleConsensusModel::operator=(source); + tmp_inliers_ = source.tmp_inliers_; + return (*this); + } + + /** \brief Check whether the given index samples can form a valid 2D circle model, compute the model coefficients + * from these samples and store them in model_coefficients. The circle coefficients are: x, y, R. + * \param[in] samples the point indices found as possible good candidates for creating a valid model + * \param[out] model_coefficients the resultant model coefficients + */ + bool + computeModelCoefficients (const std::vector &samples, + Eigen::VectorXf &model_coefficients); + + /** \brief Compute all distances from the cloud data to a given 2D circle model. + * \param[in] model_coefficients the coefficients of a 2D circle model that we need to compute distances to + * \param[out] distances the resultant estimated distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Compute all distances from the cloud data to a given 2D circle model. + * \param[in] model_coefficients the coefficients of a 2D circle model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Recompute the 2d circle coefficients using the given inlier set and return them to the user. + * @note: these are the coefficients of the 2d circle model after refinement (eg. after SVD) + * \param[in] inliers the data inliers found as supporting the model + * \param[in] model_coefficients the initial guess for the optimization + * \param[out] optimized_coefficients the resultant recomputed coefficients after non-linear optimization + */ + void + optimizeModelCoefficients (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + Eigen::VectorXf &optimized_coefficients); + + /** \brief Create a new point cloud with inliers projected onto the 2d circle model. + * \param[in] inliers the data inliers that we want to project on the 2d circle model + * \param[in] model_coefficients the coefficients of a 2d circle model + * \param[out] projected_points the resultant projected points + * \param[in] copy_data_fields set to true if we need to copy the other data fields + */ + void + projectPoints (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + PointCloud &projected_points, + bool copy_data_fields = true); + + /** \brief Verify whether a subset of indices verifies the given 2d circle model coefficients. + * \param[in] indices the data indices that need to be tested against the 2d circle model + * \param[in] model_coefficients the 2d circle model coefficients + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + */ + bool + doSamplesVerifyModel (const std::set &indices, + const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Return an unique id for this model (SACMODEL_CIRCLE2D). */ + inline pcl::SacModel + getModelType () const { return (SACMODEL_CIRCLE2D); } + + protected: + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + bool + isModelValid (const Eigen::VectorXf &model_coefficients); + + /** \brief Check if a sample of indices results in a good sample of points indices. + * \param[in] samples the resultant index samples + */ + bool + isSampleGood(const std::vector &samples) const; + + private: + /** \brief Temporary pointer to a list of given indices for optimizeModelCoefficients () */ + const std::vector *tmp_inliers_; + +#if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 +#pragma GCC diagnostic ignored "-Weffc++" +#endif + /** \brief Functor for the optimization function */ + struct OptimizationFunctor : pcl::Functor + { + /** \brief Functor constructor + * \param[in] m_data_points the number of data points to evaluate + * \param[in] estimator pointer to the estimator object + * \param[in] distance distance computation function pointer + */ + OptimizationFunctor (int m_data_points, pcl::SampleConsensusModelCircle2D *model) : + pcl::Functor(m_data_points), model_ (model) {} + + /** Cost function to be minimized + * \param[in] x the variables array + * \param[out] fvec the resultant functions evaluations + * \return 0 + */ + int + operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const + { + for (int i = 0; i < values (); ++i) + { + // Compute the difference between the center of the circle and the datapoint X_i + float xt = model_->input_->points[(*model_->tmp_inliers_)[i]].x - x[0]; + float yt = model_->input_->points[(*model_->tmp_inliers_)[i]].y - x[1]; + + // g = sqrt ((x-a)^2 + (y-b)^2) - R + fvec[i] = sqrtf (xt * xt + yt * yt) - x[2]; + } + return (0); + } + + pcl::SampleConsensusModelCircle2D *model_; + }; +#if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 +#pragma GCC diagnostic warning "-Weffc++" +#endif + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CIRCLE2D_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_circle3d.h b/pcl-1.7/pcl/sample_consensus/sac_model_circle3d.h new file mode 100644 index 0000000..5eed499 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_circle3d.h @@ -0,0 +1,264 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CIRCLE3D_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_CIRCLE3D_H_ + +#include +#include + +namespace pcl +{ + /** \brief SampleConsensusModelCircle3D defines a model for 3D circle segmentation. + * + * The model coefficients are defined as: + * - \b center.x : the X coordinate of the circle's center + * - \b center.y : the Y coordinate of the circle's center + * - \b center.z : the Z coordinate of the circle's center + * - \b radius : the circle's radius + * - \b normal.x : the X coordinate of the normal's direction + * - \b normal.y : the Y coordinate of the normal's direction + * - \b normal.z : the Z coordinate of the normal's direction + * + * \author Raoul Hoffmann, Karol Hausman, Radu B. Rusu + * \ingroup sample_consensus + */ + template + class SampleConsensusModelCircle3D : public SampleConsensusModel + { + public: + using SampleConsensusModel::input_; + using SampleConsensusModel::indices_; + using SampleConsensusModel::radius_min_; + using SampleConsensusModel::radius_max_; + + typedef typename SampleConsensusModel::PointCloud PointCloud; + typedef typename SampleConsensusModel::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModel::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor for base SampleConsensusModelCircle3D. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelCircle3D (const PointCloudConstPtr &cloud, + bool random = false) + : SampleConsensusModel (cloud, random) {}; + + /** \brief Constructor for base SampleConsensusModelCircle3D. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelCircle3D (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModel (cloud, indices, random) {}; + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelCircle3D () {} + + /** \brief Copy constructor. + * \param[in] source the model to copy into this + */ + SampleConsensusModelCircle3D (const SampleConsensusModelCircle3D &source) : + SampleConsensusModel (), tmp_inliers_ () + { + *this = source; + } + + /** \brief Copy constructor. + * \param[in] source the model to copy into this + */ + inline SampleConsensusModelCircle3D& + operator = (const SampleConsensusModelCircle3D &source) + { + SampleConsensusModel::operator=(source); + tmp_inliers_ = source.tmp_inliers_; + return (*this); + } + + /** \brief Check whether the given index samples can form a valid 2D circle model, compute the model coefficients + * from these samples and store them in model_coefficients. The circle coefficients are: x, y, R. + * \param[in] samples the point indices found as possible good candidates for creating a valid model + * \param[out] model_coefficients the resultant model coefficients + */ + bool + computeModelCoefficients (const std::vector &samples, + Eigen::VectorXf &model_coefficients); + + /** \brief Compute all distances from the cloud data to a given 3D circle model. + * \param[in] model_coefficients the coefficients of a 2D circle model that we need to compute distances to + * \param[out] distances the resultant estimated distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Compute all distances from the cloud data to a given 3D circle model. + * \param[in] model_coefficients the coefficients of a 3D circle model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Recompute the 3d circle coefficients using the given inlier set and return them to the user. + * @note: these are the coefficients of the 3d circle model after refinement (eg. after SVD) + * \param[in] inliers the data inliers found as supporting the model + * \param[in] model_coefficients the initial guess for the optimization + * \param[out] optimized_coefficients the resultant recomputed coefficients after non-linear optimization + */ + void + optimizeModelCoefficients (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + Eigen::VectorXf &optimized_coefficients); + + /** \brief Create a new point cloud with inliers projected onto the 3d circle model. + * \param[in] inliers the data inliers that we want to project on the 3d circle model + * \param[in] model_coefficients the coefficients of a 3d circle model + * \param[out] projected_points the resultant projected points + * \param[in] copy_data_fields set to true if we need to copy the other data fields + */ + void + projectPoints (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + PointCloud &projected_points, + bool copy_data_fields = true); + + /** \brief Verify whether a subset of indices verifies the given 3d circle model coefficients. + * \param[in] indices the data indices that need to be tested against the 3d circle model + * \param[in] model_coefficients the 3d circle model coefficients + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + */ + bool + doSamplesVerifyModel (const std::set &indices, + const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Return an unique id for this model (SACMODEL_CIRCLE3D). */ + inline pcl::SacModel + getModelType () const { return (SACMODEL_CIRCLE3D); } + + protected: + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + bool + isModelValid (const Eigen::VectorXf &model_coefficients); + + /** \brief Check if a sample of indices results in a good sample of points indices. + * \param[in] samples the resultant index samples + */ + bool + isSampleGood(const std::vector &samples) const; + + private: + /** \brief Temporary pointer to a list of given indices for optimizeModelCoefficients () */ + const std::vector *tmp_inliers_; + + /** \brief Functor for the optimization function */ + struct OptimizationFunctor : pcl::Functor + { + /** Functor constructor + * \param[in] m_data_points the number of functions + * \param[in] estimator pointer to the estimator object + * \param[in] distance distance computation function pointer + */ + OptimizationFunctor (int m_data_points, pcl::SampleConsensusModelCircle3D *model) : + pcl::Functor (m_data_points), model_ (model) {} + + /** Cost function to be minimized + * \param[in] x the variables array + * \param[out] fvec the resultant functions evaluations + * \return 0 + */ + int operator() (const Eigen::VectorXd &x, Eigen::VectorXd &fvec) const + { + for (int i = 0; i < values (); ++i) + { + // what i have: + // P : Sample Point + Eigen::Vector3d P (model_->input_->points[(*model_->tmp_inliers_)[i]].x, model_->input_->points[(*model_->tmp_inliers_)[i]].y, model_->input_->points[(*model_->tmp_inliers_)[i]].z); + // C : Circle Center + Eigen::Vector3d C (x[0], x[1], x[2]); + // N : Circle (Plane) Normal + Eigen::Vector3d N (x[4], x[5], x[6]); + // r : Radius + double r = x[3]; + + Eigen::Vector3d helperVectorPC = P - C; + // 1.1. get line parameter + //float lambda = (helperVectorPC.dot(N)) / N.squaredNorm() ; + double lambda = (-(helperVectorPC.dot (N))) / N.dot (N); + // Projected Point on plane + Eigen::Vector3d P_proj = P + lambda * N; + Eigen::Vector3d helperVectorP_projC = P_proj - C; + + // K : Point on Circle + Eigen::Vector3d K = C + r * helperVectorP_projC.normalized (); + Eigen::Vector3d distanceVector = P - K; + + fvec[i] = distanceVector.norm (); + } + return (0); + } + + pcl::SampleConsensusModelCircle3D *model_; + }; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CIRCLE3D_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_cone.h b/pcl-1.7/pcl/sample_consensus/sac_model_cone.h new file mode 100644 index 0000000..59501ac --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_cone.h @@ -0,0 +1,365 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CONE_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_CONE_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief @b SampleConsensusModelCone defines a model for 3D cone segmentation. + * The model coefficients are defined as: + *
    + *
  • apex.x : the X coordinate of cone's apex + *
  • apex.y : the Y coordinate of cone's apex + *
  • apex.z : the Z coordinate of cone's apex + *
  • axis_direction.x : the X coordinate of the cone's axis direction + *
  • axis_direction.y : the Y coordinate of the cone's axis direction + *
  • axis_direction.z : the Z coordinate of the cone's axis direction + *
  • opening_angle : the cone's opening angle + *
+ * \author Stefan Schrandt + * \ingroup sample_consensus + */ + template + class SampleConsensusModelCone : public SampleConsensusModel, public SampleConsensusModelFromNormals + { + public: + using SampleConsensusModel::input_; + using SampleConsensusModel::indices_; + using SampleConsensusModel::radius_min_; + using SampleConsensusModel::radius_max_; + using SampleConsensusModelFromNormals::normals_; + using SampleConsensusModelFromNormals::normal_distance_weight_; + using SampleConsensusModel::error_sqr_dists_; + + typedef typename SampleConsensusModel::PointCloud PointCloud; + typedef typename SampleConsensusModel::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModel::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr Ptr; + + /** \brief Constructor for base SampleConsensusModelCone. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelCone (const PointCloudConstPtr &cloud, bool random = false) + : SampleConsensusModel (cloud, random) + , SampleConsensusModelFromNormals () + , axis_ (Eigen::Vector3f::Zero ()) + , eps_angle_ (0) + , min_angle_ (-std::numeric_limits::max ()) + , max_angle_ (std::numeric_limits::max ()) + , tmp_inliers_ () + { + } + + /** \brief Constructor for base SampleConsensusModelCone. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelCone (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModel (cloud, indices, random) + , SampleConsensusModelFromNormals () + , axis_ (Eigen::Vector3f::Zero ()) + , eps_angle_ (0) + , min_angle_ (-std::numeric_limits::max ()) + , max_angle_ (std::numeric_limits::max ()) + , tmp_inliers_ () + { + } + + /** \brief Copy constructor. + * \param[in] source the model to copy into this + */ + SampleConsensusModelCone (const SampleConsensusModelCone &source) : + SampleConsensusModel (), + SampleConsensusModelFromNormals (), + axis_ (), eps_angle_ (), min_angle_ (), max_angle_ (), tmp_inliers_ () + { + *this = source; + } + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelCone () {} + + /** \brief Copy constructor. + * \param[in] source the model to copy into this + */ + inline SampleConsensusModelCone& + operator = (const SampleConsensusModelCone &source) + { + SampleConsensusModel::operator=(source); + axis_ = source.axis_; + eps_angle_ = source.eps_angle_; + min_angle_ = source.min_angle_; + max_angle_ = source.max_angle_; + tmp_inliers_ = source.tmp_inliers_; + return (*this); + } + + /** \brief Set the angle epsilon (delta) threshold. + * \param[in] ea the maximum allowed difference between the cone's axis and the given axis. + */ + inline void + setEpsAngle (double ea) { eps_angle_ = ea; } + + /** \brief Get the angle epsilon (delta) threshold. */ + inline double + getEpsAngle () const { return (eps_angle_); } + + /** \brief Set the axis along which we need to search for a cone direction. + * \param[in] ax the axis along which we need to search for a cone direction + */ + inline void + setAxis (const Eigen::Vector3f &ax) { axis_ = ax; } + + /** \brief Get the axis along which we need to search for a cone direction. */ + inline Eigen::Vector3f + getAxis () const { return (axis_); } + + /** \brief Set the minimum and maximum allowable opening angle for a cone model + * given from a user. + * \param[in] min_angle the minimum allwoable opening angle of a cone model + * \param[in] max_angle the maximum allwoable opening angle of a cone model + */ + inline void + setMinMaxOpeningAngle (const double &min_angle, const double &max_angle) + { + min_angle_ = min_angle; + max_angle_ = max_angle; + } + + /** \brief Get the opening angle which we need minumum to validate a cone model. + * \param[out] min_angle the minimum allwoable opening angle of a cone model + * \param[out] max_angle the maximum allwoable opening angle of a cone model + */ + inline void + getMinMaxOpeningAngle (double &min_angle, double &max_angle) const + { + min_angle = min_angle_; + max_angle = max_angle_; + } + + /** \brief Check whether the given index samples can form a valid cone model, compute the model coefficients + * from these samples and store them in model_coefficients. The cone coefficients are: apex, + * axis_direction, opening_angle. + * \param[in] samples the point indices found as possible good candidates for creating a valid model + * \param[out] model_coefficients the resultant model coefficients + */ + bool + computeModelCoefficients (const std::vector &samples, + Eigen::VectorXf &model_coefficients); + + /** \brief Compute all distances from the cloud data to a given cone model. + * \param[in] model_coefficients the coefficients of a cone model that we need to compute distances to + * \param[out] distances the resultant estimated distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Select all the points which respect the given model coefficients as inliers. + * \param[in] model_coefficients the coefficients of a cone model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + + /** \brief Recompute the cone coefficients using the given inlier set and return them to the user. + * @note: these are the coefficients of the cone model after refinement (eg. after SVD) + * \param[in] inliers the data inliers found as supporting the model + * \param[in] model_coefficients the initial guess for the optimization + * \param[out] optimized_coefficients the resultant recomputed coefficients after non-linear optimization + */ + void + optimizeModelCoefficients (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + Eigen::VectorXf &optimized_coefficients); + + + /** \brief Create a new point cloud with inliers projected onto the cone model. + * \param[in] inliers the data inliers that we want to project on the cone model + * \param[in] model_coefficients the coefficients of a cone model + * \param[out] projected_points the resultant projected points + * \param[in] copy_data_fields set to true if we need to copy the other data fields + */ + void + projectPoints (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + PointCloud &projected_points, + bool copy_data_fields = true); + + /** \brief Verify whether a subset of indices verifies the given cone model coefficients. + * \param[in] indices the data indices that need to be tested against the cone model + * \param[in] model_coefficients the cone model coefficients + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + */ + bool + doSamplesVerifyModel (const std::set &indices, + const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Return an unique id for this model (SACMODEL_CONE). */ + inline pcl::SacModel + getModelType () const { return (SACMODEL_CONE); } + + protected: + /** \brief Get the distance from a point to a line (represented by a point and a direction) + * \param[in] pt a point + * \param[in] model_coefficients the line coefficients (a point on the line, line direction) + */ + double + pointToAxisDistance (const Eigen::Vector4f &pt, const Eigen::VectorXf &model_coefficients); + + /** \brief Get a string representation of the name of this class. */ + std::string + getName () const { return ("SampleConsensusModelCone"); } + + protected: + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + bool + isModelValid (const Eigen::VectorXf &model_coefficients); + + /** \brief Check if a sample of indices results in a good sample of points + * indices. Pure virtual. + * \param[in] samples the resultant index samples + */ + bool + isSampleGood (const std::vector &samples) const; + + private: + /** \brief The axis along which we need to search for a plane perpendicular to. */ + Eigen::Vector3f axis_; + + /** \brief The maximum allowed difference between the plane normal and the given axis. */ + double eps_angle_; + + /** \brief The minimum and maximum allowed opening angles of valid cone model. */ + double min_angle_; + double max_angle_; + + /** \brief temporary pointer to a list of given indices for optimizeModelCoefficients () */ + const std::vector *tmp_inliers_; + +#if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 +#pragma GCC diagnostic ignored "-Weffc++" +#endif + /** \brief Functor for the optimization function */ + struct OptimizationFunctor : pcl::Functor + { + /** Functor constructor + * \param[in] m_data_points the number of data points to evaluate + * \param[in] estimator pointer to the estimator object + * \param[in] distance distance computation function pointer + */ + OptimizationFunctor (int m_data_points, pcl::SampleConsensusModelCone *model) : + pcl::Functor (m_data_points), model_ (model) {} + + /** Cost function to be minimized + * \param[in] x variables array + * \param[out] fvec resultant functions evaluations + * \return 0 + */ + int + operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const + { + Eigen::Vector4f apex (x[0], x[1], x[2], 0); + Eigen::Vector4f axis_dir (x[3], x[4], x[5], 0); + float opening_angle = x[6]; + + float apexdotdir = apex.dot (axis_dir); + float dirdotdir = 1.0f / axis_dir.dot (axis_dir); + + for (int i = 0; i < values (); ++i) + { + // dist = f - r + Eigen::Vector4f pt (model_->input_->points[(*model_->tmp_inliers_)[i]].x, + model_->input_->points[(*model_->tmp_inliers_)[i]].y, + model_->input_->points[(*model_->tmp_inliers_)[i]].z, 0); + + // Calculate the point's projection on the cone axis + float k = (pt.dot (axis_dir) - apexdotdir) * dirdotdir; + Eigen::Vector4f pt_proj = apex + k * axis_dir; + + // Calculate the actual radius of the cone at the level of the projected point + Eigen::Vector4f height = apex-pt_proj; + float actual_cone_radius = tanf (opening_angle) * height.norm (); + + fvec[i] = static_cast (pcl::sqrPointToLineDistance (pt, apex, axis_dir) - actual_cone_radius * actual_cone_radius); + } + return (0); + } + + pcl::SampleConsensusModelCone *model_; + }; +#if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 +#pragma GCC diagnostic warning "-Weffc++" +#endif + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CONE_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_cylinder.h b/pcl-1.7/pcl/sample_consensus/sac_model_cylinder.h new file mode 100644 index 0000000..663d449 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_cylinder.h @@ -0,0 +1,349 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CYLINDER_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_CYLINDER_H_ + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief @b SampleConsensusModelCylinder defines a model for 3D cylinder segmentation. + * The model coefficients are defined as: + * - \b point_on_axis.x : the X coordinate of a point located on the cylinder axis + * - \b point_on_axis.y : the Y coordinate of a point located on the cylinder axis + * - \b point_on_axis.z : the Z coordinate of a point located on the cylinder axis + * - \b axis_direction.x : the X coordinate of the cylinder's axis direction + * - \b axis_direction.y : the Y coordinate of the cylinder's axis direction + * - \b axis_direction.z : the Z coordinate of the cylinder's axis direction + * - \b radius : the cylinder's radius + * + * \author Radu Bogdan Rusu + * \ingroup sample_consensus + */ + template + class SampleConsensusModelCylinder : public SampleConsensusModel, public SampleConsensusModelFromNormals + { + public: + using SampleConsensusModel::input_; + using SampleConsensusModel::indices_; + using SampleConsensusModel::radius_min_; + using SampleConsensusModel::radius_max_; + using SampleConsensusModelFromNormals::normals_; + using SampleConsensusModelFromNormals::normal_distance_weight_; + using SampleConsensusModel::error_sqr_dists_; + + typedef typename SampleConsensusModel::PointCloud PointCloud; + typedef typename SampleConsensusModel::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModel::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr Ptr; + + /** \brief Constructor for base SampleConsensusModelCylinder. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelCylinder (const PointCloudConstPtr &cloud, bool random = false) + : SampleConsensusModel (cloud, random) + , SampleConsensusModelFromNormals () + , axis_ (Eigen::Vector3f::Zero ()) + , eps_angle_ (0) + , tmp_inliers_ () + { + } + + /** \brief Constructor for base SampleConsensusModelCylinder. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelCylinder (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModel (cloud, indices, random) + , SampleConsensusModelFromNormals () + , axis_ (Eigen::Vector3f::Zero ()) + , eps_angle_ (0) + , tmp_inliers_ () + { + } + + /** \brief Copy constructor. + * \param[in] source the model to copy into this + */ + SampleConsensusModelCylinder (const SampleConsensusModelCylinder &source) : + SampleConsensusModel (), + SampleConsensusModelFromNormals (), + axis_ (Eigen::Vector3f::Zero ()), + eps_angle_ (0), + tmp_inliers_ () + { + *this = source; + } + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelCylinder () {} + + /** \brief Copy constructor. + * \param[in] source the model to copy into this + */ + inline SampleConsensusModelCylinder& + operator = (const SampleConsensusModelCylinder &source) + { + SampleConsensusModel::operator=(source); + axis_ = source.axis_; + eps_angle_ = source.eps_angle_; + tmp_inliers_ = source.tmp_inliers_; + return (*this); + } + + /** \brief Set the angle epsilon (delta) threshold. + * \param[in] ea the maximum allowed difference between the cyilinder axis and the given axis. + */ + inline void + setEpsAngle (const double ea) { eps_angle_ = ea; } + + /** \brief Get the angle epsilon (delta) threshold. */ + inline double + getEpsAngle () { return (eps_angle_); } + + /** \brief Set the axis along which we need to search for a cylinder direction. + * \param[in] ax the axis along which we need to search for a cylinder direction + */ + inline void + setAxis (const Eigen::Vector3f &ax) { axis_ = ax; } + + /** \brief Get the axis along which we need to search for a cylinder direction. */ + inline Eigen::Vector3f + getAxis () { return (axis_); } + + /** \brief Check whether the given index samples can form a valid cylinder model, compute the model coefficients + * from these samples and store them in model_coefficients. The cylinder coefficients are: point_on_axis, + * axis_direction, cylinder_radius_R + * \param[in] samples the point indices found as possible good candidates for creating a valid model + * \param[out] model_coefficients the resultant model coefficients + */ + bool + computeModelCoefficients (const std::vector &samples, + Eigen::VectorXf &model_coefficients); + + /** \brief Compute all distances from the cloud data to a given cylinder model. + * \param[in] model_coefficients the coefficients of a cylinder model that we need to compute distances to + * \param[out] distances the resultant estimated distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Select all the points which respect the given model coefficients as inliers. + * \param[in] model_coefficients the coefficients of a cylinder model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Recompute the cylinder coefficients using the given inlier set and return them to the user. + * @note: these are the coefficients of the cylinder model after refinement (eg. after SVD) + * \param[in] inliers the data inliers found as supporting the model + * \param[in] model_coefficients the initial guess for the optimization + * \param[out] optimized_coefficients the resultant recomputed coefficients after non-linear optimization + */ + void + optimizeModelCoefficients (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + Eigen::VectorXf &optimized_coefficients); + + + /** \brief Create a new point cloud with inliers projected onto the cylinder model. + * \param[in] inliers the data inliers that we want to project on the cylinder model + * \param[in] model_coefficients the coefficients of a cylinder model + * \param[out] projected_points the resultant projected points + * \param[in] copy_data_fields set to true if we need to copy the other data fields + */ + void + projectPoints (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + PointCloud &projected_points, + bool copy_data_fields = true); + + /** \brief Verify whether a subset of indices verifies the given cylinder model coefficients. + * \param[in] indices the data indices that need to be tested against the cylinder model + * \param[in] model_coefficients the cylinder model coefficients + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + */ + bool + doSamplesVerifyModel (const std::set &indices, + const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Return an unique id for this model (SACMODEL_CYLINDER). */ + inline pcl::SacModel + getModelType () const { return (SACMODEL_CYLINDER); } + + protected: + /** \brief Get the distance from a point to a line (represented by a point and a direction) + * \param[in] pt a point + * \param[in] model_coefficients the line coefficients (a point on the line, line direction) + */ + double + pointToLineDistance (const Eigen::Vector4f &pt, const Eigen::VectorXf &model_coefficients); + + /** \brief Project a point onto a line given by a point and a direction vector + * \param[in] pt the input point to project + * \param[in] line_pt the point on the line (make sure that line_pt[3] = 0 as there are no internal checks!) + * \param[in] line_dir the direction of the line (make sure that line_dir[3] = 0 as there are no internal checks!) + * \param[out] pt_proj the resultant projected point + */ + inline void + projectPointToLine (const Eigen::Vector4f &pt, + const Eigen::Vector4f &line_pt, + const Eigen::Vector4f &line_dir, + Eigen::Vector4f &pt_proj) + { + float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) / line_dir.dot (line_dir); + // Calculate the projection of the point on the line + pt_proj = line_pt + k * line_dir; + } + + /** \brief Project a point onto a cylinder given by its model coefficients (point_on_axis, axis_direction, + * cylinder_radius_R) + * \param[in] pt the input point to project + * \param[in] model_coefficients the coefficients of the cylinder (point_on_axis, axis_direction, cylinder_radius_R) + * \param[out] pt_proj the resultant projected point + */ + void + projectPointToCylinder (const Eigen::Vector4f &pt, + const Eigen::VectorXf &model_coefficients, + Eigen::Vector4f &pt_proj); + + /** \brief Get a string representation of the name of this class. */ + std::string + getName () const { return ("SampleConsensusModelCylinder"); } + + protected: + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + bool + isModelValid (const Eigen::VectorXf &model_coefficients); + + /** \brief Check if a sample of indices results in a good sample of points + * indices. Pure virtual. + * \param[in] samples the resultant index samples + */ + bool + isSampleGood (const std::vector &samples) const; + + private: + /** \brief The axis along which we need to search for a plane perpendicular to. */ + Eigen::Vector3f axis_; + + /** \brief The maximum allowed difference between the plane normal and the given axis. */ + double eps_angle_; + + /** \brief temporary pointer to a list of given indices for optimizeModelCoefficients () */ + const std::vector *tmp_inliers_; + +#if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 +#pragma GCC diagnostic ignored "-Weffc++" +#endif + /** \brief Functor for the optimization function */ + struct OptimizationFunctor : pcl::Functor + { + /** Functor constructor + * \param[in] m_data_points the number of data points to evaluate + * \param[in] estimator pointer to the estimator object + * \param[in] distance distance computation function pointer + */ + OptimizationFunctor (int m_data_points, pcl::SampleConsensusModelCylinder *model) : + pcl::Functor (m_data_points), model_ (model) {} + + /** Cost function to be minimized + * \param[in] x variables array + * \param[out] fvec resultant functions evaluations + * \return 0 + */ + int + operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const + { + Eigen::Vector4f line_pt (x[0], x[1], x[2], 0); + Eigen::Vector4f line_dir (x[3], x[4], x[5], 0); + + for (int i = 0; i < values (); ++i) + { + // dist = f - r + Eigen::Vector4f pt (model_->input_->points[(*model_->tmp_inliers_)[i]].x, + model_->input_->points[(*model_->tmp_inliers_)[i]].y, + model_->input_->points[(*model_->tmp_inliers_)[i]].z, 0); + + fvec[i] = static_cast (pcl::sqrPointToLineDistance (pt, line_pt, line_dir) - x[6]*x[6]); + } + return (0); + } + + pcl::SampleConsensusModelCylinder *model_; + }; +#if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 +#pragma GCC diagnostic warning "-Weffc++" +#endif + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CYLINDER_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_line.h b/pcl-1.7/pcl/sample_consensus/sac_model_line.h new file mode 100644 index 0000000..6d49518 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_line.h @@ -0,0 +1,200 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_LINE_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_LINE_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief SampleConsensusModelLine defines a model for 3D line segmentation. + * The model coefficients are defined as: + * - \b point_on_line.x : the X coordinate of a point on the line + * - \b point_on_line.y : the Y coordinate of a point on the line + * - \b point_on_line.z : the Z coordinate of a point on the line + * - \b line_direction.x : the X coordinate of a line's direction + * - \b line_direction.y : the Y coordinate of a line's direction + * - \b line_direction.z : the Z coordinate of a line's direction + * + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class SampleConsensusModelLine : public SampleConsensusModel + { + public: + using SampleConsensusModel::input_; + using SampleConsensusModel::indices_; + using SampleConsensusModel::error_sqr_dists_; + + typedef typename SampleConsensusModel::PointCloud PointCloud; + typedef typename SampleConsensusModel::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModel::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr Ptr; + + /** \brief Constructor for base SampleConsensusModelLine. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelLine (const PointCloudConstPtr &cloud, bool random = false) + : SampleConsensusModel (cloud, random) {}; + + /** \brief Constructor for base SampleConsensusModelLine. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelLine (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModel (cloud, indices, random) {}; + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelLine () {} + + /** \brief Check whether the given index samples can form a valid line model, compute the model coefficients from + * these samples and store them internally in model_coefficients_. The line coefficients are represented by a + * point and a line direction + * \param[in] samples the point indices found as possible good candidates for creating a valid model + * \param[out] model_coefficients the resultant model coefficients + */ + bool + computeModelCoefficients (const std::vector &samples, + Eigen::VectorXf &model_coefficients); + + /** \brief Compute all squared distances from the cloud data to a given line model. + * \param[in] model_coefficients the coefficients of a line model that we need to compute distances to + * \param[out] distances the resultant estimated squared distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Select all the points which respect the given model coefficients as inliers. + * \param[in] model_coefficients the coefficients of a line model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Recompute the line coefficients using the given inlier set and return them to the user. + * @note: these are the coefficients of the line model after refinement (eg. after SVD) + * \param[in] inliers the data inliers found as supporting the model + * \param[in] model_coefficients the initial guess for the model coefficients + * \param[out] optimized_coefficients the resultant recomputed coefficients after optimization + */ + void + optimizeModelCoefficients (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + Eigen::VectorXf &optimized_coefficients); + + /** \brief Create a new point cloud with inliers projected onto the line model. + * \param[in] inliers the data inliers that we want to project on the line model + * \param[in] model_coefficients the *normalized* coefficients of a line model + * \param[out] projected_points the resultant projected points + * \param[in] copy_data_fields set to true if we need to copy the other data fields + */ + void + projectPoints (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + PointCloud &projected_points, + bool copy_data_fields = true); + + /** \brief Verify whether a subset of indices verifies the given line model coefficients. + * \param[in] indices the data indices that need to be tested against the line model + * \param[in] model_coefficients the line model coefficients + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + */ + bool + doSamplesVerifyModel (const std::set &indices, + const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Return an unique id for this model (SACMODEL_LINE). */ + inline pcl::SacModel + getModelType () const { return (SACMODEL_LINE); } + + protected: + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + inline bool + isModelValid (const Eigen::VectorXf &model_coefficients) + { + if (model_coefficients.size () != 6) + { + PCL_ERROR ("[pcl::SampleConsensusModelLine::selectWithinDistance] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + return (true); + } + + /** \brief Check if a sample of indices results in a good sample of points + * indices. + * \param[in] samples the resultant index samples + */ + bool + isSampleGood (const std::vector &samples) const; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_LINE_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_normal_parallel_plane.h b/pcl-1.7/pcl/sample_consensus/sac_model_normal_parallel_plane.h new file mode 100644 index 0000000..73a6e95 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_normal_parallel_plane.h @@ -0,0 +1,212 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_NORMALPARALLELPLANE_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_NORMALPARALLELPLANE_H_ + +#include +#include + +namespace pcl +{ + /** \brief SampleConsensusModelNormalParallelPlane defines a model for 3D + * plane segmentation using additional surface normal constraints. Basically + * this means that checking for inliers will not only involve a "distance to + * model" criterion, but also an additional "maximum angular deviation" + * between the plane's normal and the inlier points normals. In addition, + * the plane normal must lie parallel to an user-specified axis. + * + * The model coefficients are defined as: + * - \b a : the X coordinate of the plane's normal (normalized) + * - \b b : the Y coordinate of the plane's normal (normalized) + * - \b c : the Z coordinate of the plane's normal (normalized) + * - \b d : the fourth Hessian component of the plane's equation + * + * To set the influence of the surface normals in the inlier estimation + * process, set the normal weight (0.0-1.0), e.g.: + * \code + * SampleConsensusModelNormalPlane sac_model; + * ... + * sac_model.setNormalDistanceWeight (0.1); + * ... + * \endcode + * + * In addition, the user can specify more constraints, such as: + * + * - an axis along which we need to search for a plane perpendicular to (\ref setAxis); + * - an angle \a tolerance threshold between the plane's normal and the above given axis (\ref setEpsAngle); + * - a distance we expect the plane to be from the origin (\ref setDistanceFromOrigin); + * - a distance \a tolerance as the maximum allowed deviation from the above given distance from the origin (\ref setEpsDist). + * + * \note Please remember that you need to specify an angle > 0 in order to activate the axis-angle constraint! + * + * \author Radu B. Rusu and Jared Glover and Nico Blodow + * \ingroup sample_consensus + */ + template + class SampleConsensusModelNormalParallelPlane : public SampleConsensusModelNormalPlane + { + public: + using SampleConsensusModel::input_; + using SampleConsensusModel::indices_; + using SampleConsensusModelFromNormals::normals_; + using SampleConsensusModelFromNormals::normal_distance_weight_; + using SampleConsensusModel::error_sqr_dists_; + + typedef typename SampleConsensusModel::PointCloud PointCloud; + typedef typename SampleConsensusModel::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModel::PointCloudConstPtr PointCloudConstPtr; + + typedef typename SampleConsensusModelFromNormals::PointCloudNPtr PointCloudNPtr; + typedef typename SampleConsensusModelFromNormals::PointCloudNConstPtr PointCloudNConstPtr; + + typedef boost::shared_ptr Ptr; + + /** \brief Constructor for base SampleConsensusModelNormalParallelPlane. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelNormalParallelPlane (const PointCloudConstPtr &cloud, + bool random = false) + : SampleConsensusModelNormalPlane (cloud, random) + , axis_ (Eigen::Vector4f::Zero ()) + , distance_from_origin_ (0) + , eps_angle_ (-1.0) + , cos_angle_ (-1.0) + , eps_dist_ (0.0) + { + } + + /** \brief Constructor for base SampleConsensusModelNormalParallelPlane. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelNormalParallelPlane (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModelNormalPlane (cloud, indices, random) + , axis_ (Eigen::Vector4f::Zero ()) + , distance_from_origin_ (0) + , eps_angle_ (-1.0) + , cos_angle_ (-1.0) + , eps_dist_ (0.0) + { + } + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelNormalParallelPlane () {} + + /** \brief Set the axis along which we need to search for a plane perpendicular to. + * \param[in] ax the axis along which we need to search for a plane perpendicular to + */ + inline void + setAxis (const Eigen::Vector3f &ax) { axis_.head<3> () = ax; axis_.normalize ();} + + /** \brief Get the axis along which we need to search for a plane perpendicular to. */ + inline Eigen::Vector3f + getAxis () { return (axis_.head<3> ()); } + + /** \brief Set the angle epsilon (delta) threshold. + * \param[in] ea the maximum allowed deviation from 90 degrees between the plane normal and the given axis. + * \note You need to specify an angle > 0 in order to activate the axis-angle constraint! + */ + inline void + setEpsAngle (const double ea) { eps_angle_ = ea; cos_angle_ = fabs (cos (ea));} + + /** \brief Get the angle epsilon (delta) threshold. */ + inline double + getEpsAngle () { return (eps_angle_); } + + /** \brief Set the distance we expect the plane to be from the origin + * \param[in] d distance from the template plane to the origin + */ + inline void + setDistanceFromOrigin (const double d) { distance_from_origin_ = d; } + + /** \brief Get the distance of the plane from the origin. */ + inline double + getDistanceFromOrigin () { return (distance_from_origin_); } + + /** \brief Set the distance epsilon (delta) threshold. + * \param[in] delta the maximum allowed deviation from the template distance from the origin + */ + inline void + setEpsDist (const double delta) { eps_dist_ = delta; } + + /** \brief Get the distance epsilon (delta) threshold. */ + inline double + getEpsDist () { return (eps_dist_); } + + /** \brief Return an unique id for this model (SACMODEL_NORMAL_PARALLEL_PLANE). */ + inline pcl::SacModel + getModelType () const { return (SACMODEL_NORMAL_PARALLEL_PLANE); } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + protected: + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + bool + isModelValid (const Eigen::VectorXf &model_coefficients); + + private: + /** \brief The axis along which we need to search for a plane perpendicular to. */ + Eigen::Vector4f axis_; + + /** \brief The distance from the template plane to the origin. */ + double distance_from_origin_; + + /** \brief The maximum allowed difference between the plane normal and the given axis. */ + double eps_angle_; + + /** \brief The cosine of the angle*/ + double cos_angle_; + /** \brief The maximum allowed deviation from the template distance from the origin. */ + double eps_dist_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_NORMALPARALLELPLANE_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_normal_plane.h b/pcl-1.7/pcl/sample_consensus/sac_model_normal_plane.h new file mode 100644 index 0000000..62a21b4 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_normal_plane.h @@ -0,0 +1,162 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_NORMALPLANE_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_NORMALPLANE_H_ + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief SampleConsensusModelNormalPlane defines a model for 3D plane + * segmentation using additional surface normal constraints. Basically this + * means that checking for inliers will not only involve a "distance to + * model" criterion, but also an additional "maximum angular deviation" + * between the plane's normal and the inlier points normals. + * + * The model coefficients are defined as: + * - \b a : the X coordinate of the plane's normal (normalized) + * - \b b : the Y coordinate of the plane's normal (normalized) + * - \b c : the Z coordinate of the plane's normal (normalized) + * - \b d : the fourth Hessian component of the plane's equation + * + * To set the influence of the surface normals in the inlier estimation + * process, set the normal weight (0.0-1.0), e.g.: + * \code + * SampleConsensusModelNormalPlane sac_model; + * ... + * sac_model.setNormalDistanceWeight (0.1); + * ... + * \endcode + * + * \author Radu B. Rusu and Jared Glover + * \ingroup sample_consensus + */ + template + class SampleConsensusModelNormalPlane : public SampleConsensusModelPlane, public SampleConsensusModelFromNormals + { + public: + using SampleConsensusModel::input_; + using SampleConsensusModel::indices_; + using SampleConsensusModelFromNormals::normals_; + using SampleConsensusModelFromNormals::normal_distance_weight_; + using SampleConsensusModel::error_sqr_dists_; + using SampleConsensusModelPlane::isModelValid; + + typedef typename SampleConsensusModel::PointCloud PointCloud; + typedef typename SampleConsensusModel::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModel::PointCloudConstPtr PointCloudConstPtr; + + typedef typename SampleConsensusModelFromNormals::PointCloudNPtr PointCloudNPtr; + typedef typename SampleConsensusModelFromNormals::PointCloudNConstPtr PointCloudNConstPtr; + + typedef boost::shared_ptr Ptr; + + /** \brief Constructor for base SampleConsensusModelNormalPlane. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelNormalPlane (const PointCloudConstPtr &cloud, + bool random = false) + : SampleConsensusModelPlane (cloud, random) + , SampleConsensusModelFromNormals () + { + } + + /** \brief Constructor for base SampleConsensusModelNormalPlane. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelNormalPlane (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModelPlane (cloud, indices, random) + , SampleConsensusModelFromNormals () + { + } + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelNormalPlane () {} + + /** \brief Select all the points which respect the given model coefficients as inliers. + * \param[in] model_coefficients the coefficients of a plane model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Compute all distances from the cloud data to a given plane model. + * \param[in] model_coefficients the coefficients of a plane model that we need to compute distances to + * \param[out] distances the resultant estimated distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Return an unique id for this model (SACMODEL_NORMAL_PLANE). */ + inline pcl::SacModel + getModelType () const { return (SACMODEL_NORMAL_PLANE); } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_NORMALPLANE_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_normal_sphere.h b/pcl-1.7/pcl/sample_consensus/sac_model_normal_sphere.h new file mode 100644 index 0000000..fd48641 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_normal_sphere.h @@ -0,0 +1,163 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: sac_model_normal_sphere.h schrandt $ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_NORMALSPHERE_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_NORMALSPHERE_H_ + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief @b SampleConsensusModelNormalSphere defines a model for 3D sphere + * segmentation using additional surface normal constraints. Basically this + * means that checking for inliers will not only involve a "distance to + * model" criterion, but also an additional "maximum angular deviation" + * between the sphere's normal and the inlier points normals. + * + * The model coefficients are defined as: + *
    + *
  • a : the X coordinate of the plane's normal (normalized) + *
  • b : the Y coordinate of the plane's normal (normalized) + *
  • c : the Z coordinate of the plane's normal (normalized) + *
  • d : radius of the sphere + *
+ * + * \author Stefan Schrandt + * \ingroup sample_consensus + */ + template + class SampleConsensusModelNormalSphere : public SampleConsensusModelSphere, public SampleConsensusModelFromNormals + { + public: + using SampleConsensusModel::input_; + using SampleConsensusModel::indices_; + using SampleConsensusModel::radius_min_; + using SampleConsensusModel::radius_max_; + using SampleConsensusModelFromNormals::normals_; + using SampleConsensusModelFromNormals::normal_distance_weight_; + using SampleConsensusModel::error_sqr_dists_; + + typedef typename SampleConsensusModel::PointCloud PointCloud; + typedef typename SampleConsensusModel::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModel::PointCloudConstPtr PointCloudConstPtr; + + typedef typename SampleConsensusModelFromNormals::PointCloudNPtr PointCloudNPtr; + typedef typename SampleConsensusModelFromNormals::PointCloudNConstPtr PointCloudNConstPtr; + + typedef boost::shared_ptr Ptr; + + /** \brief Constructor for base SampleConsensusModelNormalSphere. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelNormalSphere (const PointCloudConstPtr &cloud, + bool random = false) + : SampleConsensusModelSphere (cloud, random) + , SampleConsensusModelFromNormals () + { + } + + /** \brief Constructor for base SampleConsensusModelNormalSphere. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelNormalSphere (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModelSphere (cloud, indices, random) + , SampleConsensusModelFromNormals () + { + } + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelNormalSphere () {} + + /** \brief Select all the points which respect the given model coefficients as inliers. + * \param[in] model_coefficients the coefficients of a sphere model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Compute all distances from the cloud data to a given sphere model. + * \param[in] model_coefficients the coefficients of a sphere model that we need to compute distances to + * \param[out] distances the resultant estimated distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Return an unique id for this model (SACMODEL_NORMAL_SPHERE). */ + inline pcl::SacModel + getModelType () const { return (SACMODEL_NORMAL_SPHERE); } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + protected: + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + bool + isModelValid (const Eigen::VectorXf &model_coefficients); + + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_NORMALSPHERE_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_parallel_line.h b/pcl-1.7/pcl/sample_consensus/sac_model_parallel_line.h new file mode 100644 index 0000000..e0167fd --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_parallel_line.h @@ -0,0 +1,172 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PARALLELLINE_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_PARALLELLINE_H_ + +#include +#include + +namespace pcl +{ + /** \brief SampleConsensusModelParallelLine defines a model for 3D line segmentation using additional angular + * constraints. + * The model coefficients are defined as: + * - \b point_on_line.x : the X coordinate of a point on the line + * - \b point_on_line.y : the Y coordinate of a point on the line + * - \b point_on_line.z : the Z coordinate of a point on the line + * - \b line_direction.x : the X coordinate of a line's direction + * - \b line_direction.y : the Y coordinate of a line's direction + * - \b line_direction.z : the Z coordinate of a line's direction + * + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class SampleConsensusModelParallelLine : public SampleConsensusModelLine + { + public: + typedef typename SampleConsensusModelLine::PointCloud PointCloud; + typedef typename SampleConsensusModelLine::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModelLine::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr Ptr; + + /** \brief Constructor for base SampleConsensusModelParallelLine. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelParallelLine (const PointCloudConstPtr &cloud, + bool random = false) + : SampleConsensusModelLine (cloud, random) + , axis_ (Eigen::Vector3f::Zero ()) + , eps_angle_ (0.0) + { + } + + /** \brief Constructor for base SampleConsensusModelParallelLine. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelParallelLine (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModelLine (cloud, indices, random) + , axis_ (Eigen::Vector3f::Zero ()) + , eps_angle_ (0.0) + { + } + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelParallelLine () {} + + /** \brief Set the axis along which we need to search for a plane perpendicular to. + * \param[in] ax the axis along which we need to search for a plane perpendicular to + */ + inline void + setAxis (const Eigen::Vector3f &ax) { axis_ = ax; axis_.normalize (); } + + /** \brief Get the axis along which we need to search for a plane perpendicular to. */ + inline Eigen::Vector3f + getAxis () { return (axis_); } + + /** \brief Set the angle epsilon (delta) threshold. + * \param[in] ea the maximum allowed difference between the plane normal and the given axis. + */ + inline void + setEpsAngle (const double ea) { eps_angle_ = ea; } + + /** \brief Get the angle epsilon (delta) threshold. */ + inline double getEpsAngle () { return (eps_angle_); } + + /** \brief Select all the points which respect the given model coefficients as inliers. + * \param[in] model_coefficients the coefficients of a line model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Compute all squared distances from the cloud data to a given line model. + * \param[in] model_coefficients the coefficients of a line model that we need to compute distances to + * \param[out] distances the resultant estimated squared distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Return an unique id for this model (SACMODEL_PARALLEL_LINE). */ + inline pcl::SacModel + getModelType () const { return (SACMODEL_PARALLEL_LINE); } + + protected: + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + bool + isModelValid (const Eigen::VectorXf &model_coefficients); + + protected: + /** \brief The axis along which we need to search for a plane perpendicular to. */ + Eigen::Vector3f axis_; + + /** \brief The maximum allowed difference between the plane normal and the given axis. */ + double eps_angle_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PARALLELLINE_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_parallel_plane.h b/pcl-1.7/pcl/sample_consensus/sac_model_parallel_plane.h new file mode 100644 index 0000000..3270f1d --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_parallel_plane.h @@ -0,0 +1,181 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PARALLELPLANE_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_PARALLELPLANE_H_ + +#include +#include + +namespace pcl +{ + /** \brief @b SampleConsensusModelParallelPlane defines a model for 3D plane segmentation using additional + * angular constraints. The plane must be parallel to a user-specified axis + * (\ref setAxis) within an user-specified angle threshold (\ref setEpsAngle). + * + * Code example for a plane model, parallel (within a 15 degrees tolerance) with the Z axis: + * \code + * SampleConsensusModelParallelPlane model (cloud); + * model.setAxis (Eigen::Vector3f (0.0, 0.0, 1.0)); + * model.setEpsAngle (pcl::deg2rad (15)); + * \endcode + * + * \note Please remember that you need to specify an angle > 0 in order to activate the axis-angle constraint! + * + * \author Radu B. Rusu, Nico Blodow + * \ingroup sample_consensus + */ + template + class SampleConsensusModelParallelPlane : public SampleConsensusModelPlane + { + public: + typedef typename SampleConsensusModelPlane::PointCloud PointCloud; + typedef typename SampleConsensusModelPlane::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModelPlane::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr Ptr; + + /** \brief Constructor for base SampleConsensusModelParallelPlane. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelParallelPlane (const PointCloudConstPtr &cloud, + bool random = false) + : SampleConsensusModelPlane (cloud, random) + , axis_ (Eigen::Vector3f::Zero ()) + , eps_angle_ (0.0) + , sin_angle_ (-1.0) + { + } + + /** \brief Constructor for base SampleConsensusModelParallelPlane. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelParallelPlane (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModelPlane (cloud, indices, random) + , axis_ (Eigen::Vector3f::Zero ()) + , eps_angle_ (0.0) + , sin_angle_ (-1.0) + { + } + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelParallelPlane () {} + + /** \brief Set the axis along which we need to search for a plane perpendicular to. + * \param[in] ax the axis along which we need to search for a plane perpendicular to + */ + inline void + setAxis (const Eigen::Vector3f &ax) { axis_ = ax; } + + /** \brief Get the axis along which we need to search for a plane perpendicular to. */ + inline Eigen::Vector3f + getAxis () { return (axis_); } + + /** \brief Set the angle epsilon (delta) threshold. + * \param[in] ea the maximum allowed difference between the plane normal and the given axis. + * \note You need to specify an angle > 0 in order to activate the axis-angle constraint! + */ + inline void + setEpsAngle (const double ea) { eps_angle_ = ea; sin_angle_ = fabs (sin (ea));} + + /** \brief Get the angle epsilon (delta) threshold. */ + inline double + getEpsAngle () { return (eps_angle_); } + + /** \brief Select all the points which respect the given model coefficients as inliers. + * \param[in] model_coefficients the coefficients of a plane model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Compute all distances from the cloud data to a given plane model. + * \param[in] model_coefficients the coefficients of a plane model that we need to compute distances to + * \param[out] distances the resultant estimated distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Return an unique id for this model (SACMODEL_PARALLEL_PLANE). */ + inline pcl::SacModel + getModelType () const { return (SACMODEL_PARALLEL_PLANE); } + + protected: + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + bool + isModelValid (const Eigen::VectorXf &model_coefficients); + + /** \brief The axis along which we need to search for a plane perpendicular to. */ + Eigen::Vector3f axis_; + + /** \brief The maximum allowed difference between the plane and the given axis. */ + double eps_angle_; + + /** \brief The sine of the angle*/ + double sin_angle_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PARALLELPLANE_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_perpendicular_plane.h b/pcl-1.7/pcl/sample_consensus/sac_model_perpendicular_plane.h new file mode 100644 index 0000000..e457a50 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_perpendicular_plane.h @@ -0,0 +1,181 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PERPENDICULARPLANE_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_PERPENDICULARPLANE_H_ + +#include +#include + +namespace pcl +{ + /** \brief SampleConsensusModelPerpendicularPlane defines a model for 3D plane segmentation using additional + * angular constraints. The plane must be perpendicular to an user-specified axis (\ref setAxis), up to an user-specified angle threshold (\ref setEpsAngle). + * The model coefficients are defined as: + * - \b a : the X coordinate of the plane's normal (normalized) + * - \b b : the Y coordinate of the plane's normal (normalized) + * - \b c : the Z coordinate of the plane's normal (normalized) + * - \b d : the fourth Hessian component of the plane's equation + * + * + * Code example for a plane model, perpendicular (within a 15 degrees tolerance) with the Z axis: + * \code + * SampleConsensusModelPerpendicularPlane model (cloud); + * model.setAxis (Eigen::Vector3f (0.0, 0.0, 1.0)); + * model.setEpsAngle (pcl::deg2rad (15)); + * \endcode + * + * \note Please remember that you need to specify an angle > 0 in order to activate the axis-angle constraint! + * + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class SampleConsensusModelPerpendicularPlane : public SampleConsensusModelPlane + { + public: + typedef typename SampleConsensusModelPlane::PointCloud PointCloud; + typedef typename SampleConsensusModelPlane::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModelPlane::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr Ptr; + + /** \brief Constructor for base SampleConsensusModelPerpendicularPlane. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelPerpendicularPlane (const PointCloudConstPtr &cloud, + bool random = false) + : SampleConsensusModelPlane (cloud, random) + , axis_ (Eigen::Vector3f::Zero ()) + , eps_angle_ (0.0) + { + } + + /** \brief Constructor for base SampleConsensusModelPerpendicularPlane. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelPerpendicularPlane (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModelPlane (cloud, indices, random) + , axis_ (Eigen::Vector3f::Zero ()) + , eps_angle_ (0.0) + { + } + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelPerpendicularPlane () {} + + /** \brief Set the axis along which we need to search for a plane perpendicular to. + * \param[in] ax the axis along which we need to search for a plane perpendicular to + */ + inline void + setAxis (const Eigen::Vector3f &ax) { axis_ = ax; } + + /** \brief Get the axis along which we need to search for a plane perpendicular to. */ + inline Eigen::Vector3f + getAxis () { return (axis_); } + + /** \brief Set the angle epsilon (delta) threshold. + * \param[in] ea the maximum allowed difference between the plane normal and the given axis. + * \note You need to specify an angle > 0 in order to activate the axis-angle constraint! + */ + inline void + setEpsAngle (const double ea) { eps_angle_ = ea; } + + /** \brief Get the angle epsilon (delta) threshold. */ + inline double + getEpsAngle () { return (eps_angle_); } + + /** \brief Select all the points which respect the given model coefficients as inliers. + * \param[in] model_coefficients the coefficients of a plane model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Compute all distances from the cloud data to a given plane model. + * \param[in] model_coefficients the coefficients of a plane model that we need to compute distances to + * \param[out] distances the resultant estimated distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Return an unique id for this model (SACMODEL_PERPENDICULAR_PLANE). */ + inline pcl::SacModel + getModelType () const { return (SACMODEL_PERPENDICULAR_PLANE); } + + protected: + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + bool + isModelValid (const Eigen::VectorXf &model_coefficients); + + /** \brief The axis along which we need to search for a plane perpendicular to. */ + Eigen::Vector3f axis_; + + /** \brief The maximum allowed difference between the plane normal and the given axis. */ + double eps_angle_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PERPENDICULARPLANE_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_plane.h b/pcl-1.7/pcl/sample_consensus/sac_model_plane.h new file mode 100644 index 0000000..831f32e --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_plane.h @@ -0,0 +1,274 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PLANE_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_PLANE_H_ + +#include +#include + +namespace pcl +{ + + /** \brief Project a point on a planar model given by a set of normalized coefficients + * \param[in] p the input point to project + * \param[in] model_coefficients the coefficients of the plane (a, b, c, d) that satisfy ax+by+cz+d=0 + * \param[out] q the resultant projected point + */ + template inline void + projectPoint (const Point &p, const Eigen::Vector4f &model_coefficients, Point &q) + { + // Calculate the distance from the point to the plane + Eigen::Vector4f pp (p.x, p.y, p.z, 1); + // use normalized coefficients to calculate the scalar projection + float distance_to_plane = pp.dot(model_coefficients); + + + //TODO: Why doesn't getVector4Map work here? + //Eigen::Vector4f q_e = q.getVector4fMap (); + //q_e = pp - model_coefficients * distance_to_plane; + + Eigen::Vector4f q_e = pp - distance_to_plane * model_coefficients; + q.x = q_e[0]; + q.y = q_e[1]; + q.z = q_e[2]; + } + + /** \brief Get the distance from a point to a plane (signed) defined by ax+by+cz+d=0 + * \param p a point + * \param a the normalized a coefficient of a plane + * \param b the normalized b coefficient of a plane + * \param c the normalized c coefficient of a plane + * \param d the normalized d coefficient of a plane + * \ingroup sample_consensus + */ + template inline double + pointToPlaneDistanceSigned (const Point &p, double a, double b, double c, double d) + { + return (a * p.x + b * p.y + c * p.z + d); + } + + /** \brief Get the distance from a point to a plane (signed) defined by ax+by+cz+d=0 + * \param p a point + * \param plane_coefficients the normalized coefficients (a, b, c, d) of a plane + * \ingroup sample_consensus + */ + template inline double + pointToPlaneDistanceSigned (const Point &p, const Eigen::Vector4f &plane_coefficients) + { + return ( plane_coefficients[0] * p.x + plane_coefficients[1] * p.y + plane_coefficients[2] * p.z + plane_coefficients[3] ); + } + + /** \brief Get the distance from a point to a plane (unsigned) defined by ax+by+cz+d=0 + * \param p a point + * \param a the normalized a coefficient of a plane + * \param b the normalized b coefficient of a plane + * \param c the normalized c coefficient of a plane + * \param d the normalized d coefficient of a plane + * \ingroup sample_consensus + */ + template inline double + pointToPlaneDistance (const Point &p, double a, double b, double c, double d) + { + return (fabs (pointToPlaneDistanceSigned (p, a, b, c, d)) ); + } + + /** \brief Get the distance from a point to a plane (unsigned) defined by ax+by+cz+d=0 + * \param p a point + * \param plane_coefficients the normalized coefficients (a, b, c, d) of a plane + * \ingroup sample_consensus + */ + template inline double + pointToPlaneDistance (const Point &p, const Eigen::Vector4f &plane_coefficients) + { + return ( fabs (pointToPlaneDistanceSigned (p, plane_coefficients)) ); + } + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief SampleConsensusModelPlane defines a model for 3D plane segmentation. + * The model coefficients are defined as: + * - \b a : the X coordinate of the plane's normal (normalized) + * - \b b : the Y coordinate of the plane's normal (normalized) + * - \b c : the Z coordinate of the plane's normal (normalized) + * - \b d : the fourth Hessian component of the plane's equation + * + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class SampleConsensusModelPlane : public SampleConsensusModel + { + public: + using SampleConsensusModel::input_; + using SampleConsensusModel::indices_; + using SampleConsensusModel::error_sqr_dists_; + + typedef typename SampleConsensusModel::PointCloud PointCloud; + typedef typename SampleConsensusModel::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModel::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr Ptr; + + /** \brief Constructor for base SampleConsensusModelPlane. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelPlane (const PointCloudConstPtr &cloud, bool random = false) + : SampleConsensusModel (cloud, random) {}; + + /** \brief Constructor for base SampleConsensusModelPlane. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelPlane (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModel (cloud, indices, random) {}; + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelPlane () {} + + /** \brief Check whether the given index samples can form a valid plane model, compute the model coefficients from + * these samples and store them internally in model_coefficients_. The plane coefficients are: + * a, b, c, d (ax+by+cz+d=0) + * \param[in] samples the point indices found as possible good candidates for creating a valid model + * \param[out] model_coefficients the resultant model coefficients + */ + bool + computeModelCoefficients (const std::vector &samples, + Eigen::VectorXf &model_coefficients); + + /** \brief Compute all distances from the cloud data to a given plane model. + * \param[in] model_coefficients the coefficients of a plane model that we need to compute distances to + * \param[out] distances the resultant estimated distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Select all the points which respect the given model coefficients as inliers. + * \param[in] model_coefficients the coefficients of a plane model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Recompute the plane coefficients using the given inlier set and return them to the user. + * @note: these are the coefficients of the plane model after refinement (eg. after SVD) + * \param[in] inliers the data inliers found as supporting the model + * \param[in] model_coefficients the initial guess for the model coefficients + * \param[out] optimized_coefficients the resultant recomputed coefficients after non-linear optimization + */ + void + optimizeModelCoefficients (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + Eigen::VectorXf &optimized_coefficients); + + /** \brief Create a new point cloud with inliers projected onto the plane model. + * \param[in] inliers the data inliers that we want to project on the plane model + * \param[in] model_coefficients the *normalized* coefficients of a plane model + * \param[out] projected_points the resultant projected points + * \param[in] copy_data_fields set to true if we need to copy the other data fields + */ + void + projectPoints (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + PointCloud &projected_points, + bool copy_data_fields = true); + + /** \brief Verify whether a subset of indices verifies the given plane model coefficients. + * \param[in] indices the data indices that need to be tested against the plane model + * \param[in] model_coefficients the plane model coefficients + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + */ + bool + doSamplesVerifyModel (const std::set &indices, + const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Return an unique id for this model (SACMODEL_PLANE). */ + inline pcl::SacModel + getModelType () const { return (SACMODEL_PLANE); } + + protected: + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + inline bool + isModelValid (const Eigen::VectorXf &model_coefficients) + { + // Needs a valid model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelPlane::isModelValid] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + return (true); + } + + private: + /** \brief Check if a sample of indices results in a good sample of points + * indices. + * \param[in] samples the resultant index samples + */ + virtual bool + isSampleGood (const std::vector &samples) const; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PLANE_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_registration.h b/pcl-1.7/pcl/sample_consensus/sac_model_registration.h new file mode 100644 index 0000000..09dd728 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_registration.h @@ -0,0 +1,337 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_H_ + +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief SampleConsensusModelRegistration defines a model for Point-To-Point registration outlier rejection. + * \author Radu Bogdan Rusu + * \ingroup sample_consensus + */ + template + class SampleConsensusModelRegistration : public SampleConsensusModel + { + public: + using SampleConsensusModel::input_; + using SampleConsensusModel::indices_; + using SampleConsensusModel::error_sqr_dists_; + + typedef typename SampleConsensusModel::PointCloud PointCloud; + typedef typename SampleConsensusModel::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModel::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr Ptr; + + /** \brief Constructor for base SampleConsensusModelRegistration. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelRegistration (const PointCloudConstPtr &cloud, + bool random = false) + : SampleConsensusModel (cloud, random) + , target_ () + , indices_tgt_ () + , correspondences_ () + , sample_dist_thresh_ (0) + { + // Call our own setInputCloud + setInputCloud (cloud); + } + + /** \brief Constructor for base SampleConsensusModelRegistration. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelRegistration (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModel (cloud, indices, random) + , target_ () + , indices_tgt_ () + , correspondences_ () + , sample_dist_thresh_ (0) + { + computeOriginalIndexMapping (); + computeSampleDistanceThreshold (cloud, indices); + } + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelRegistration () {} + + /** \brief Provide a pointer to the input dataset + * \param[in] cloud the const boost shared pointer to a PointCloud message + */ + inline virtual void + setInputCloud (const PointCloudConstPtr &cloud) + { + SampleConsensusModel::setInputCloud (cloud); + computeOriginalIndexMapping (); + computeSampleDistanceThreshold (cloud); + } + + /** \brief Set the input point cloud target. + * \param[in] target the input point cloud target + */ + inline void + setInputTarget (const PointCloudConstPtr &target) + { + target_ = target; + indices_tgt_.reset (new std::vector); + // Cache the size and fill the target indices + int target_size = static_cast (target->size ()); + indices_tgt_->resize (target_size); + + for (int i = 0; i < target_size; ++i) + (*indices_tgt_)[i] = i; + computeOriginalIndexMapping (); + } + + /** \brief Set the input point cloud target. + * \param[in] target the input point cloud target + * \param[in] indices_tgt a vector of point indices to be used from \a target + */ + inline void + setInputTarget (const PointCloudConstPtr &target, const std::vector &indices_tgt) + { + target_ = target; + indices_tgt_.reset (new std::vector (indices_tgt)); + computeOriginalIndexMapping (); + } + + /** \brief Compute a 4x4 rigid transformation matrix from the samples given + * \param[in] samples the indices found as good candidates for creating a valid model + * \param[out] model_coefficients the resultant model coefficients + */ + bool + computeModelCoefficients (const std::vector &samples, + Eigen::VectorXf &model_coefficients); + + /** \brief Compute all distances from the transformed points to their correspondences + * \param[in] model_coefficients the 4x4 transformation matrix + * \param[out] distances the resultant estimated distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Select all the points which respect the given model coefficients as inliers. + * \param[in] model_coefficients the 4x4 transformation matrix + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Recompute the 4x4 transformation using the given inlier set + * \param[in] inliers the data inliers found as supporting the model + * \param[in] model_coefficients the initial guess for the optimization + * \param[out] optimized_coefficients the resultant recomputed transformation + */ + void + optimizeModelCoefficients (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + Eigen::VectorXf &optimized_coefficients); + + void + projectPoints (const std::vector &, + const Eigen::VectorXf &, + PointCloud &, bool = true) + { + }; + + bool + doSamplesVerifyModel (const std::set &, + const Eigen::VectorXf &, + const double) + { + return (false); + } + + /** \brief Return an unique id for this model (SACMODEL_REGISTRATION). */ + inline pcl::SacModel + getModelType () const { return (SACMODEL_REGISTRATION); } + + protected: + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + inline bool + isModelValid (const Eigen::VectorXf &model_coefficients) + { + // Needs a valid model coefficients + if (model_coefficients.size () != 16) + return (false); + + return (true); + } + + /** \brief Check if a sample of indices results in a good sample of points + * indices. + * \param[in] samples the resultant index samples + */ + virtual bool + isSampleGood (const std::vector &samples) const; + + /** \brief Computes an "optimal" sample distance threshold based on the + * principal directions of the input cloud. + * \param[in] cloud the const boost shared pointer to a PointCloud message + */ + inline void + computeSampleDistanceThreshold (const PointCloudConstPtr &cloud) + { + // Compute the principal directions via PCA + Eigen::Vector4f xyz_centroid; + Eigen::Matrix3f covariance_matrix = Eigen::Matrix3f::Zero (); + + computeMeanAndCovarianceMatrix (*cloud, covariance_matrix, xyz_centroid); + + // Check if the covariance matrix is finite or not. + for (int i = 0; i < 3; ++i) + for (int j = 0; j < 3; ++j) + if (!pcl_isfinite (covariance_matrix.coeffRef (i, j))) + PCL_ERROR ("[pcl::SampleConsensusModelRegistration::computeSampleDistanceThreshold] Covariance matrix has NaN values! Is the input cloud finite?\n"); + + Eigen::Vector3f eigen_values; + pcl::eigen33 (covariance_matrix, eigen_values); + + // Compute the distance threshold for sample selection + sample_dist_thresh_ = eigen_values.array ().sqrt ().sum () / 3.0; + sample_dist_thresh_ *= sample_dist_thresh_; + PCL_DEBUG ("[pcl::SampleConsensusModelRegistration::setInputCloud] Estimated a sample selection distance threshold of: %f\n", sample_dist_thresh_); + } + + /** \brief Computes an "optimal" sample distance threshold based on the + * principal directions of the input cloud. + * \param[in] cloud the const boost shared pointer to a PointCloud message + * \param indices + */ + inline void + computeSampleDistanceThreshold (const PointCloudConstPtr &cloud, + const std::vector &indices) + { + // Compute the principal directions via PCA + Eigen::Vector4f xyz_centroid; + Eigen::Matrix3f covariance_matrix; + computeMeanAndCovarianceMatrix (*cloud, indices, covariance_matrix, xyz_centroid); + + // Check if the covariance matrix is finite or not. + for (int i = 0; i < 3; ++i) + for (int j = 0; j < 3; ++j) + if (!pcl_isfinite (covariance_matrix.coeffRef (i, j))) + PCL_ERROR ("[pcl::SampleConsensusModelRegistration::computeSampleDistanceThreshold] Covariance matrix has NaN values! Is the input cloud finite?\n"); + + Eigen::Vector3f eigen_values; + pcl::eigen33 (covariance_matrix, eigen_values); + + // Compute the distance threshold for sample selection + sample_dist_thresh_ = eigen_values.array ().sqrt ().sum () / 3.0; + sample_dist_thresh_ *= sample_dist_thresh_; + PCL_DEBUG ("[pcl::SampleConsensusModelRegistration::setInputCloud] Estimated a sample selection distance threshold of: %f\n", sample_dist_thresh_); + } + + /** \brief Estimate a rigid transformation between a source and a target point cloud using an SVD closed-form + * solution of absolute orientation using unit quaternions + * \param[in] cloud_src the source point cloud dataset + * \param[in] indices_src the vector of indices describing the points of interest in cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the interest points from + * indices_src + * \param[out] transform the resultant transformation matrix (as model coefficients) + * + * This method is an implementation of: Horn, B. “Closed-Form Solution of Absolute Orientation Using Unit Quaternions,†JOSA A, Vol. 4, No. 4, 1987 + */ + void + estimateRigidTransformationSVD (const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt, + Eigen::VectorXf &transform); + + /** \brief Compute mappings between original indices of the input_/target_ clouds. */ + void + computeOriginalIndexMapping () + { + if (!indices_tgt_ || !indices_ || indices_->empty () || indices_->size () != indices_tgt_->size ()) + return; + for (size_t i = 0; i < indices_->size (); ++i) + correspondences_[(*indices_)[i]] = (*indices_tgt_)[i]; + } + + /** \brief A boost shared pointer to the target point cloud data array. */ + PointCloudConstPtr target_; + + /** \brief A pointer to the vector of target point indices to use. */ + boost::shared_ptr > indices_tgt_; + + /** \brief Given the index in the original point cloud, give the matching original index in the target cloud */ + std::map correspondences_; + + /** \brief Internal distance threshold used for the sample selection step. */ + double sample_dist_thresh_; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#include + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_registration_2d.h b/pcl-1.7/pcl/sample_consensus/sac_model_registration_2d.h new file mode 100644 index 0000000..99785b1 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_registration_2d.h @@ -0,0 +1,215 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_2D_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_2D_H_ + +#include + +namespace pcl +{ + /** \brief SampleConsensusModelRegistration2D defines a model for Point-To-Point registration outlier rejection using distances between 2D pixels + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class SampleConsensusModelRegistration2D : public pcl::SampleConsensusModelRegistration + { + public: + using pcl::SampleConsensusModelRegistration::input_; + using pcl::SampleConsensusModelRegistration::target_; + using pcl::SampleConsensusModelRegistration::indices_; + using pcl::SampleConsensusModelRegistration::indices_tgt_; + using pcl::SampleConsensusModelRegistration::error_sqr_dists_; + using pcl::SampleConsensusModelRegistration::correspondences_; + using pcl::SampleConsensusModelRegistration::sample_dist_thresh_; + using pcl::SampleConsensusModelRegistration::computeOriginalIndexMapping; + + typedef typename pcl::SampleConsensusModel::PointCloud PointCloud; + typedef typename pcl::SampleConsensusModel::PointCloudPtr PointCloudPtr; + typedef typename pcl::SampleConsensusModel::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Constructor for base SampleConsensusModelRegistration2D. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelRegistration2D (const PointCloudConstPtr &cloud, + bool random = false) + : pcl::SampleConsensusModelRegistration (cloud, random) + , projection_matrix_ (Eigen::Matrix3f::Identity ()) + { + // Call our own setInputCloud + setInputCloud (cloud); + } + + /** \brief Constructor for base SampleConsensusModelRegistration2D. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelRegistration2D (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : pcl::SampleConsensusModelRegistration (cloud, indices, random) + , projection_matrix_ (Eigen::Matrix3f::Identity ()) + { + computeOriginalIndexMapping (); + computeSampleDistanceThreshold (cloud, indices); + } + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelRegistration2D () {} + + /** \brief Compute all distances from the transformed points to their correspondences + * \param[in] model_coefficients the 4x4 transformation matrix + * \param[out] distances the resultant estimated distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Select all the points which respect the given model coefficients as inliers. + * \param[in] model_coefficients the 4x4 transformation matrix + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Set the camera projection matrix. + * \param[in] projection_matrix the camera projection matrix + */ + inline void + setProjectionMatrix (const Eigen::Matrix3f &projection_matrix) + { projection_matrix_ = projection_matrix; } + + /** \brief Get the camera projection matrix. */ + inline Eigen::Matrix3f + getProjectionMatrix () const + { return (projection_matrix_); } + + protected: + /** \brief Check if a sample of indices results in a good sample of points + * indices. + * \param[in] samples the resultant index samples + */ + bool + isSampleGood (const std::vector &samples) const; + + /** \brief Computes an "optimal" sample distance threshold based on the + * principal directions of the input cloud. + */ + inline void + computeSampleDistanceThreshold (const PointCloudConstPtr&) + { + //// Compute the principal directions via PCA + //Eigen::Vector4f xyz_centroid; + //Eigen::Matrix3f covariance_matrix = Eigen::Matrix3f::Zero (); + + //computeMeanAndCovarianceMatrix (*cloud, covariance_matrix, xyz_centroid); + + //// Check if the covariance matrix is finite or not. + //for (int i = 0; i < 3; ++i) + // for (int j = 0; j < 3; ++j) + // if (!pcl_isfinite (covariance_matrix.coeffRef (i, j))) + // PCL_ERROR ("[pcl::SampleConsensusModelRegistration::computeSampleDistanceThreshold] Covariance matrix has NaN values! Is the input cloud finite?\n"); + + //Eigen::Vector3f eigen_values; + //pcl::eigen33 (covariance_matrix, eigen_values); + + //// Compute the distance threshold for sample selection + //sample_dist_thresh_ = eigen_values.array ().sqrt ().sum () / 3.0; + //sample_dist_thresh_ *= sample_dist_thresh_; + //PCL_DEBUG ("[pcl::SampleConsensusModelRegistration::setInputCloud] Estimated a sample selection distance threshold of: %f\n", sample_dist_thresh_); + } + + /** \brief Computes an "optimal" sample distance threshold based on the + * principal directions of the input cloud. + */ + inline void + computeSampleDistanceThreshold (const PointCloudConstPtr&, + const std::vector&) + { + //// Compute the principal directions via PCA + //Eigen::Vector4f xyz_centroid; + //Eigen::Matrix3f covariance_matrix; + //computeMeanAndCovarianceMatrix (*cloud, indices, covariance_matrix, xyz_centroid); + + //// Check if the covariance matrix is finite or not. + //for (int i = 0; i < 3; ++i) + // for (int j = 0; j < 3; ++j) + // if (!pcl_isfinite (covariance_matrix.coeffRef (i, j))) + // PCL_ERROR ("[pcl::SampleConsensusModelRegistration::computeSampleDistanceThreshold] Covariance matrix has NaN values! Is the input cloud finite?\n"); + + //Eigen::Vector3f eigen_values; + //pcl::eigen33 (covariance_matrix, eigen_values); + + //// Compute the distance threshold for sample selection + //sample_dist_thresh_ = eigen_values.array ().sqrt ().sum () / 3.0; + //sample_dist_thresh_ *= sample_dist_thresh_; + //PCL_DEBUG ("[pcl::SampleConsensusModelRegistration::setInputCloud] Estimated a sample selection distance threshold of: %f\n", sample_dist_thresh_); + } + + private: + /** \brief Camera projection matrix. */ + Eigen::Matrix3f projection_matrix_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#include + +#endif // PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_2D_H_ + diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_sphere.h b/pcl-1.7/pcl/sample_consensus/sac_model_sphere.h new file mode 100644 index 0000000..05a4038 --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_sphere.h @@ -0,0 +1,274 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_SPHERE_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_SPHERE_H_ + +#include +#include + +namespace pcl +{ + /** \brief SampleConsensusModelSphere defines a model for 3D sphere segmentation. + * The model coefficients are defined as: + * - \b center.x : the X coordinate of the sphere's center + * - \b center.y : the Y coordinate of the sphere's center + * - \b center.z : the Z coordinate of the sphere's center + * - \b radius : the sphere's radius + * + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class SampleConsensusModelSphere : public SampleConsensusModel + { + public: + using SampleConsensusModel::input_; + using SampleConsensusModel::indices_; + using SampleConsensusModel::radius_min_; + using SampleConsensusModel::radius_max_; + using SampleConsensusModel::error_sqr_dists_; + + typedef typename SampleConsensusModel::PointCloud PointCloud; + typedef typename SampleConsensusModel::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModel::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr Ptr; + + /** \brief Constructor for base SampleConsensusModelSphere. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelSphere (const PointCloudConstPtr &cloud, + bool random = false) + : SampleConsensusModel (cloud, random), tmp_inliers_ () + {} + + /** \brief Constructor for base SampleConsensusModelSphere. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelSphere (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModel (cloud, indices, random), tmp_inliers_ () + {} + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelSphere () {} + + /** \brief Copy constructor. + * \param[in] source the model to copy into this + */ + SampleConsensusModelSphere (const SampleConsensusModelSphere &source) : + SampleConsensusModel (), tmp_inliers_ () + { + *this = source; + } + + /** \brief Copy constructor. + * \param[in] source the model to copy into this + */ + inline SampleConsensusModelSphere& + operator = (const SampleConsensusModelSphere &source) + { + SampleConsensusModel::operator=(source); + tmp_inliers_ = source.tmp_inliers_; + return (*this); + } + + /** \brief Check whether the given index samples can form a valid sphere model, compute the model + * coefficients from these samples and store them internally in model_coefficients. + * The sphere coefficients are: x, y, z, R. + * \param[in] samples the point indices found as possible good candidates for creating a valid model + * \param[out] model_coefficients the resultant model coefficients + */ + bool + computeModelCoefficients (const std::vector &samples, + Eigen::VectorXf &model_coefficients); + + /** \brief Compute all distances from the cloud data to a given sphere model. + * \param[in] model_coefficients the coefficients of a sphere model that we need to compute distances to + * \param[out] distances the resultant estimated distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Select all the points which respect the given model coefficients as inliers. + * \param[in] model_coefficients the coefficients of a sphere model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Recompute the sphere coefficients using the given inlier set and return them to the user. + * @note: these are the coefficients of the sphere model after refinement (eg. after SVD) + * \param[in] inliers the data inliers found as supporting the model + * \param[in] model_coefficients the initial guess for the optimization + * \param[out] optimized_coefficients the resultant recomputed coefficients after non-linear optimization + */ + void + optimizeModelCoefficients (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + Eigen::VectorXf &optimized_coefficients); + + /** \brief Create a new point cloud with inliers projected onto the sphere model. + * \param[in] inliers the data inliers that we want to project on the sphere model + * \param[in] model_coefficients the coefficients of a sphere model + * \param[out] projected_points the resultant projected points + * \param[in] copy_data_fields set to true if we need to copy the other data fields + * \todo implement this. + */ + void + projectPoints (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + PointCloud &projected_points, + bool copy_data_fields = true); + + /** \brief Verify whether a subset of indices verifies the given sphere model coefficients. + * \param[in] indices the data indices that need to be tested against the sphere model + * \param[in] model_coefficients the sphere model coefficients + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + */ + bool + doSamplesVerifyModel (const std::set &indices, + const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Return an unique id for this model (SACMODEL_SPHERE). */ + inline pcl::SacModel getModelType () const { return (SACMODEL_SPHERE); } + + protected: + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + inline bool + isModelValid (const Eigen::VectorXf &model_coefficients) + { + // Needs a valid model coefficients + if (model_coefficients.size () != 4) + { + PCL_ERROR ("[pcl::SampleConsensusModelSphere::isModelValid] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + if (radius_min_ != -std::numeric_limits::max() && model_coefficients[3] < radius_min_) + return (false); + if (radius_max_ != std::numeric_limits::max() && model_coefficients[3] > radius_max_) + return (false); + + return (true); + } + + /** \brief Check if a sample of indices results in a good sample of points + * indices. + * \param[in] samples the resultant index samples + */ + bool + isSampleGood(const std::vector &samples) const; + + private: + /** \brief Temporary pointer to a list of given indices for optimizeModelCoefficients () */ + const std::vector *tmp_inliers_; + +#if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 +#pragma GCC diagnostic ignored "-Weffc++" +#endif + struct OptimizationFunctor : pcl::Functor + { + /** Functor constructor + * \param[in] m_data_points the number of data points to evaluate + * \param[in] estimator pointer to the estimator object + * \param[in] distance distance computation function pointer + */ + OptimizationFunctor (int m_data_points, pcl::SampleConsensusModelSphere *model) : + pcl::Functor(m_data_points), model_ (model) {} + + /** Cost function to be minimized + * \param[in] x the variables array + * \param[out] fvec the resultant functions evaluations + * \return 0 + */ + int + operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const + { + Eigen::Vector4f cen_t; + cen_t[3] = 0; + for (int i = 0; i < values (); ++i) + { + // Compute the difference between the center of the sphere and the datapoint X_i + cen_t[0] = model_->input_->points[(*model_->tmp_inliers_)[i]].x - x[0]; + cen_t[1] = model_->input_->points[(*model_->tmp_inliers_)[i]].y - x[1]; + cen_t[2] = model_->input_->points[(*model_->tmp_inliers_)[i]].z - x[2]; + + // g = sqrt ((x-a)^2 + (y-b)^2 + (z-c)^2) - R + fvec[i] = sqrtf (cen_t.dot (cen_t)) - x[3]; + } + return (0); + } + + pcl::SampleConsensusModelSphere *model_; + }; +#if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 +#pragma GCC diagnostic warning "-Weffc++" +#endif + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_SPHERE_H_ diff --git a/pcl-1.7/pcl/sample_consensus/sac_model_stick.h b/pcl-1.7/pcl/sample_consensus/sac_model_stick.h new file mode 100644 index 0000000..36ea13c --- /dev/null +++ b/pcl-1.7/pcl/sample_consensus/sac_model_stick.h @@ -0,0 +1,204 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: sac_model_line.h 2326 2011-08-31 07:48:25Z rusu $ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_MODEL_STICK_H_ +#define PCL_SAMPLE_CONSENSUS_MODEL_STICK_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief SampleConsensusModelStick defines a model for 3D stick segmentation. + * A stick is a line with an user given minimum/maximum width. + * The model coefficients are defined as: + * - \b point_on_line.x : the X coordinate of a point on the line + * - \b point_on_line.y : the Y coordinate of a point on the line + * - \b point_on_line.z : the Z coordinate of a point on the line + * - \b line_direction.x : the X coordinate of a line's direction + * - \b line_direction.y : the Y coordinate of a line's direction + * - \b line_direction.z : the Z coordinate of a line's direction + * - \b line_width : the width of the line + * \author Radu B. Rusu + * \ingroup sample_consensus + */ + template + class SampleConsensusModelStick : public SampleConsensusModel + { + public: + using SampleConsensusModel::input_; + using SampleConsensusModel::indices_; + using SampleConsensusModel::radius_min_; + using SampleConsensusModel::radius_max_; + using SampleConsensusModel::error_sqr_dists_; + + typedef typename SampleConsensusModel::PointCloud PointCloud; + typedef typename SampleConsensusModel::PointCloudPtr PointCloudPtr; + typedef typename SampleConsensusModel::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr Ptr; + + /** \brief Constructor for base SampleConsensusModelStick. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelStick (const PointCloudConstPtr &cloud, + bool random = false) + : SampleConsensusModel (cloud, random) {}; + + /** \brief Constructor for base SampleConsensusModelStick. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SampleConsensusModelStick (const PointCloudConstPtr &cloud, + const std::vector &indices, + bool random = false) + : SampleConsensusModel (cloud, indices, random) {}; + + /** \brief Empty destructor */ + virtual ~SampleConsensusModelStick () {} + + /** \brief Check whether the given index samples can form a valid stick model, compute the model coefficients from + * these samples and store them internally in model_coefficients_. The stick coefficients are represented by a + * point and a line direction + * \param[in] samples the point indices found as possible good candidates for creating a valid model + * \param[out] model_coefficients the resultant model coefficients + */ + bool + computeModelCoefficients (const std::vector &samples, + Eigen::VectorXf &model_coefficients); + + /** \brief Compute all squared distances from the cloud data to a given stick model. + * \param[in] model_coefficients the coefficients of a stick model that we need to compute distances to + * \param[out] distances the resultant estimated squared distances + */ + void + getDistancesToModel (const Eigen::VectorXf &model_coefficients, + std::vector &distances); + + /** \brief Select all the points which respect the given model coefficients as inliers. + * \param[in] model_coefficients the coefficients of a stick model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the resultant model inliers + */ + void + selectWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold, + std::vector &inliers); + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for determining the inliers from the outliers + * \return the resultant number of inliers + */ + virtual int + countWithinDistance (const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Recompute the stick coefficients using the given inlier set and return them to the user. + * @note: these are the coefficients of the stick model after refinement (eg. after SVD) + * \param[in] inliers the data inliers found as supporting the model + * \param[in] model_coefficients the initial guess for the model coefficients + * \param[out] optimized_coefficients the resultant recomputed coefficients after optimization + */ + void + optimizeModelCoefficients (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + Eigen::VectorXf &optimized_coefficients); + + /** \brief Create a new point cloud with inliers projected onto the stick model. + * \param[in] inliers the data inliers that we want to project on the stick model + * \param[in] model_coefficients the *normalized* coefficients of a stick model + * \param[out] projected_points the resultant projected points + * \param[in] copy_data_fields set to true if we need to copy the other data fields + */ + void + projectPoints (const std::vector &inliers, + const Eigen::VectorXf &model_coefficients, + PointCloud &projected_points, + bool copy_data_fields = true); + + /** \brief Verify whether a subset of indices verifies the given stick model coefficients. + * \param[in] indices the data indices that need to be tested against the plane model + * \param[in] model_coefficients the plane model coefficients + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + */ + bool + doSamplesVerifyModel (const std::set &indices, + const Eigen::VectorXf &model_coefficients, + const double threshold); + + /** \brief Return an unique id for this model (SACMODEL_STACK). */ + inline pcl::SacModel + getModelType () const { return (SACMODEL_STICK); } + + protected: + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + inline bool + isModelValid (const Eigen::VectorXf &model_coefficients) + { + if (model_coefficients.size () != 7) + { + PCL_ERROR ("[pcl::SampleConsensusModelStick::selectWithinDistance] Invalid number of model coefficients given (%lu)!\n", model_coefficients.size ()); + return (false); + } + + return (true); + } + + /** \brief Check if a sample of indices results in a good sample of points + * indices. + * \param[in] samples the resultant index samples + */ + bool + isSampleGood (const std::vector &samples) const; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_STICK_H_ diff --git a/pcl-1.7/pcl/search/brute_force.h b/pcl-1.7/pcl/search/brute_force.h new file mode 100644 index 0000000..4bed1ea --- /dev/null +++ b/pcl-1.7/pcl/search/brute_force.h @@ -0,0 +1,149 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SEARCH_BRUTE_FORCE_H_ +#define PCL_SEARCH_BRUTE_FORCE_H_ + +#include + +namespace pcl +{ + namespace search + { + /** \brief Implementation of a simple brute force search algorithm. + * \author Suat Gedikli + * \ingroup search + */ + template + class BruteForce: public Search + { + typedef typename Search::PointCloud PointCloud; + typedef typename Search::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr > IndicesPtr; + typedef boost::shared_ptr > IndicesConstPtr; + + using pcl::search::Search::input_; + using pcl::search::Search::indices_; + using pcl::search::Search::sorted_results_; + + struct Entry + { + Entry (int idx, float dist) : index (idx), distance (dist) {} + + Entry () : index (0), distance (0) {} + unsigned index; + float distance; + + inline bool + operator < (const Entry& other) const + { + return (distance < other.distance); + } + + inline bool + operator > (const Entry& other) const + { + return (distance > other.distance); + } + }; + + // replace by some metric functor + float getDistSqr (const PointT& point1, const PointT& point2) const; + public: + BruteForce (bool sorted_results = false) + : Search ("BruteForce", sorted_results) + { + } + + /** \brief Destructor for KdTree. */ + virtual + ~BruteForce () + { + } + + /** \brief Search for the k-nearest neighbors for the given query point. + * \param[in] point the given query point + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + */ + int + nearestKSearch (const PointT &point, int k, std::vector &k_indices, std::vector &k_distances) const; + + /** \brief Search for all the nearest neighbors of the query point in a given radius. + * \param[in] point the given query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + * \return number of neighbors found in radius + */ + int + radiusSearch (const PointT& point, double radius, + std::vector &k_indices, std::vector &k_sqr_distances, + unsigned int max_nn = 0) const; + + private: + int + denseKSearch (const PointT &point, int k, std::vector &k_indices, std::vector &k_distances) const; + + int + sparseKSearch (const PointT &point, int k, std::vector &k_indices, std::vector &k_distances) const; + + int + denseRadiusSearch (const PointT& point, double radius, + std::vector &k_indices, std::vector &k_sqr_distances, + unsigned int max_nn = 0) const; + + int + sparseRadiusSearch (const PointT& point, double radius, + std::vector &k_indices, std::vector &k_sqr_distances, + unsigned int max_nn = 0) const; + }; + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_SEARCH_BRUTE_FORCE_H_ diff --git a/pcl-1.7/pcl/search/flann_search.h b/pcl-1.7/pcl/search/flann_search.h new file mode 100644 index 0000000..33be27f --- /dev/null +++ b/pcl-1.7/pcl/search/flann_search.h @@ -0,0 +1,375 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_SEARCH_FLANN_SEARCH_H_ +#define PCL_SEARCH_FLANN_SEARCH_H_ + +#include +#include +#include + +namespace flann +{ + template class NNIndex; + template struct L2; + template struct L2_Simple; + template class Matrix; +} + +namespace pcl +{ + namespace search + { + + /** \brief @b search::FlannSearch is a generic FLANN wrapper class for the new search interface. + * It is able to wrap any FLANN index type, e.g. the kd tree as well as indices for high-dimensional + * searches and intended as a more powerful and cleaner successor to KdTreeFlann. + * + * By default, this class creates a single kd tree for indexing the input data. However, for high dimensions + * (> 10), it is often better to use the multiple randomized kd tree index provided by FLANN in combination with + * the \ref flann::L2 distance functor. During search in this type of index, the number of checks to perform before + * terminating the search can be controlled. Here is a code example if a high-dimensional 2-NN search: + * + * \code + * // Feature and distance type + * typedef SHOT352 FeatureT; + * typedef flann::L2 DistanceT; + * + * // Search and index types + * typedef search::FlannSearch SearchT; + * typedef typename SearchT::FlannIndexCreatorPtr CreatorPtrT; + * typedef typename SearchT::KdTreeMultiIndexCreator IndexT; + * typedef typename SearchT::PointRepresentationPtr RepresentationPtrT; + * + * // Features + * PointCloud::Ptr query, target; + * + * // Fill query and target with calculated features... + * + * // Instantiate search object with 4 randomized trees and 256 checks + * SearchT search (true, CreatorPtrT (new IndexT (4))); + * search.setPointRepresentation (RepresentationPtrT (new DefaultFeatureRepresentation)); + * search.setChecks (256); + * search.setInputCloud (target); + * + * // Do search + * std::vector > k_indices; + * std::vector > k_sqr_distances; + * search.nearestKSearch (*query, std::vector (), 2, k_indices, k_sqr_distances); + * \endcode + * + * \author Andreas Muetzel + * \author Anders Glent Buch (multiple randomized kd tree interface) + * \ingroup search + */ + template > + class FlannSearch: public Search + { + using Search::input_; + using Search::indices_; + using Search::sorted_results_; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename Search::PointCloud PointCloud; + typedef typename Search::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr > IndicesPtr; + typedef boost::shared_ptr > IndicesConstPtr; + + typedef boost::shared_ptr > MatrixPtr; + typedef boost::shared_ptr > MatrixConstPtr; + + typedef flann::NNIndex< FlannDistance > Index; + typedef boost::shared_ptr > IndexPtr; + + typedef pcl::PointRepresentation PointRepresentation; + typedef boost::shared_ptr PointRepresentationPtr; + typedef boost::shared_ptr PointRepresentationConstPtr; + + /** \brief Helper class that creates a FLANN index from a given FLANN matrix. To + * use a FLANN index type with FlannSearch, implement this interface and + * pass an object of the new type to the FlannSearch constructor. + * See the implementation of KdTreeIndexCreator for an example. + */ + class FlannIndexCreator + { + public: + /** \brief Create a FLANN Index from the input data. + * \param[in] data The FLANN matrix containing the input. + * \return The FLANN index. + */ + virtual IndexPtr createIndex (MatrixConstPtr data)=0; + + /** \brief destructor + */ + virtual ~FlannIndexCreator () {} + }; + typedef boost::shared_ptr FlannIndexCreatorPtr; + + /** \brief Creates a FLANN KdTreeSingleIndex from the given input data. + */ + class KdTreeIndexCreator: public FlannIndexCreator + { + public: + /** \param[in] max_leaf_size All FLANN kd trees created by this class will have + * a maximum of max_leaf_size points per leaf node. Higher values make index creation + * cheaper, but search more costly (and the other way around). + */ + KdTreeIndexCreator (unsigned int max_leaf_size=15) : max_leaf_size_ (max_leaf_size){} + + /** \brief Empty destructor */ + virtual ~KdTreeIndexCreator () {} + + /** \brief Create a FLANN Index from the input data. + * \param[in] data The FLANN matrix containing the input. + * \return The FLANN index. + */ + virtual IndexPtr createIndex (MatrixConstPtr data); + private: + unsigned int max_leaf_size_; + }; + + /** \brief Creates a FLANN KdTreeSingleIndex from the given input data. + */ + class KMeansIndexCreator: public FlannIndexCreator + { + public: + /** \brief All FLANN kd trees created by this class will have + * a maximum of max_leaf_size points per leaf node. Higher values make index creation + * cheaper, but search more costly (and the other way around). + */ + KMeansIndexCreator (){} + + /** \brief Empty destructor */ + virtual ~KMeansIndexCreator () {} + + /** \brief Create a FLANN Index from the input data. + * \param[in] data The FLANN matrix containing the input. + * \return The FLANN index. + */ + virtual IndexPtr createIndex (MatrixConstPtr data); + private: + }; + + /** \brief Creates a FLANN KdTreeIndex of multiple randomized trees from the given input data, + * suitable for feature matching. Note that in this case, it is often more efficient to use the + * \ref flann::L2 distance functor. + */ + class KdTreeMultiIndexCreator: public FlannIndexCreator + { + public: + /** \param[in] trees Number of randomized trees to create. + */ + KdTreeMultiIndexCreator (int trees = 4) : trees_ (trees) {} + + /** \brief Empty destructor */ + virtual ~KdTreeMultiIndexCreator () {} + + /** \brief Create a FLANN Index from the input data. + * \param[in] data The FLANN matrix containing the input. + * \return The FLANN index. + */ + virtual IndexPtr createIndex (MatrixConstPtr data); + private: + int trees_; + }; + + FlannSearch (bool sorted = true, FlannIndexCreatorPtr creator = FlannIndexCreatorPtr (new KdTreeIndexCreator ())); + + /** \brief Destructor for FlannSearch. */ + virtual + ~FlannSearch (); + + + //void + //setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices = IndicesConstPtr ()); + + /** \brief Set the search epsilon precision (error bound) for nearest neighbors searches. + * \param[in] eps precision (error bound) for nearest neighbors searches + */ + inline void + setEpsilon (double eps) + { + eps_ = eps; + } + + /** \brief Get the search epsilon precision (error bound) for nearest neighbors searches. */ + inline double + getEpsilon () + { + return (eps_); + } + + /** \brief Set the number of checks to perform during approximate searches in multiple randomized trees. + * \param[in] checks number of checks to perform during approximate searches in multiple randomized trees. + */ + inline void + setChecks (int checks) + { + checks_ = checks; + } + + /** \brief Get the number of checks to perform during approximate searches in multiple randomized trees. */ + inline int + getChecks () + { + return (checks_); + } + + /** \brief Provide a pointer to the input dataset. + * \param[in] cloud the const boost shared pointer to a PointCloud message + * \param[in] indices the point indices subset that is to be used from \a cloud + */ + virtual void + setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr& indices = IndicesConstPtr ()); + + /** \brief Search for the k-nearest neighbors for the given query point. + * \param[in] point the given query point + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + */ + int + nearestKSearch (const PointT &point, int k, std::vector &k_indices, std::vector &k_sqr_distances) const; + + + /** \brief Search for the k-nearest neighbors for the given query point. + * \param[in] cloud the point cloud data + * \param[in] indices a vector of point cloud indices to query for nearest neighbors + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points, k_indices[i] corresponds to the neighbors of the query point i + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points, k_sqr_distances[i] corresponds to the neighbors of the query point i + */ + virtual void + nearestKSearch (const PointCloud& cloud, const std::vector& indices, int k, + std::vector< std::vector >& k_indices, std::vector< std::vector >& k_sqr_distances) const; + + /** \brief Search for all the nearest neighbors of the query point in a given radius. + * \param[in] point the given query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + * \return number of neighbors found in radius + */ + int + radiusSearch (const PointT& point, double radius, + std::vector &k_indices, std::vector &k_sqr_distances, + unsigned int max_nn = 0) const; + + /** \brief Search for the k-nearest neighbors for the given query point. + * \param[in] cloud the point cloud data + * \param[in] indices a vector of point cloud indices to query for nearest neighbors + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points, k_indices[i] corresponds to the neighbors of the query point i + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points, k_sqr_distances[i] corresponds to the neighbors of the query point i + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value + */ + virtual void + radiusSearch (const PointCloud& cloud, const std::vector& indices, double radius, std::vector< std::vector >& k_indices, + std::vector< std::vector >& k_sqr_distances, unsigned int max_nn=0) const; + + /** \brief Provide a pointer to the point representation to use to convert points into k-D vectors. + * \param[in] point_representation the const boost shared pointer to a PointRepresentation + */ + inline void + setPointRepresentation (const PointRepresentationConstPtr &point_representation) + { + point_representation_ = point_representation; + dim_ = point_representation->getNumberOfDimensions (); + if (input_) // re-create the tree, since point_represenation might change things such as the scaling of the point clouds. + setInputCloud (input_, indices_); + } + + /** \brief Get a pointer to the point representation used when converting points into k-D vectors. */ + inline PointRepresentationConstPtr const + getPointRepresentation () + { + return (point_representation_); + } + + protected: + + /** \brief converts the input data to a format usable by FLANN + */ + void convertInputToFlannMatrix(); + + /** The FLANN index. + */ + IndexPtr index_; + + /** The index creator, used to (re-) create the index when the search data is passed. + */ + FlannIndexCreatorPtr creator_; + + /** Input data in FLANN format. + */ + MatrixPtr input_flann_; + + /** Epsilon for approximate NN search. + */ + float eps_; + + /** Number of checks to perform for approximate NN search using the multiple randomized tree index + */ + int checks_; + + bool input_copied_for_flann_; + + PointRepresentationConstPtr point_representation_; + + int dim_; + + std::vector index_mapping_; + bool identity_mapping_; + + }; + } +} + +#define PCL_INSTANTIATE_FlannSearch(T) template class PCL_EXPORTS pcl::search::FlannSearch; + +#endif // PCL_SEARCH_KDTREE_H_ + diff --git a/pcl-1.7/pcl/search/impl/brute_force.hpp b/pcl-1.7/pcl/search/impl/brute_force.hpp new file mode 100644 index 0000000..d4dc8a6 --- /dev/null +++ b/pcl-1.7/pcl/search/impl/brute_force.hpp @@ -0,0 +1,354 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SEARCH_IMPL_BRUTE_FORCE_SEARCH_H_ +#define PCL_SEARCH_IMPL_BRUTE_FORCE_SEARCH_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::search::BruteForce::getDistSqr ( + const PointT& point1, const PointT& point2) const +{ + return (point1.getVector3fMap () - point2.getVector3fMap ()).squaredNorm (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::BruteForce::nearestKSearch ( + const PointT& point, int k, std::vector& k_indices, std::vector& k_distances) const +{ + assert (isFinite (point) && "Invalid (NaN, Inf) point coordinates given to nearestKSearch!"); + + k_indices.clear (); + k_distances.clear (); + if (k < 1) + return 0; + + if (input_->is_dense) + return denseKSearch (point, k, k_indices, k_distances); + else + return sparseKSearch (point, k, k_indices, k_distances); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::BruteForce::denseKSearch ( + const PointT &point, int k, std::vector &k_indices, std::vector &k_distances) const +{ + // container for first k elements -> O(1) for insertion, since order not required here + std::vector result; + result.reserve (k); + std::priority_queue queue; + if (indices_ != NULL) + { + std::vector::const_iterator iIt =indices_->begin (); + std::vector::const_iterator iEnd = indices_->begin () + std::min (static_cast (k), static_cast (indices_->size ())); + for (; iIt != iEnd; ++iIt) + result.push_back (Entry (*iIt, getDistSqr (input_->points[*iIt], point))); + + queue = std::priority_queue (result.begin (), result.end ()); + + // add the rest + Entry entry; + for (; iIt != indices_->end (); ++iIt) + { + entry.distance = getDistSqr (input_->points[*iIt], point); + if (queue.top ().distance > entry.distance) + { + entry.index = *iIt; + queue.pop (); + queue.push (entry); + } + } + } + else + { + Entry entry; + for (entry.index = 0; entry.index < std::min (static_cast (k), static_cast (input_->size ())); ++entry.index) + { + entry.distance = getDistSqr (input_->points[entry.index], point); + result.push_back (entry); + } + + queue = std::priority_queue (result.begin (), result.end ()); + + // add the rest + for (; entry.index < input_->size (); ++entry.index) + { + entry.distance = getDistSqr (input_->points[entry.index], point); + if (queue.top ().distance > entry.distance) + { + queue.pop (); + queue.push (entry); + } + } + } + + k_indices.resize (queue.size ()); + k_distances.resize (queue.size ()); + size_t idx = queue.size () - 1; + while (!queue.empty ()) + { + k_indices [idx] = queue.top ().index; + k_distances [idx] = queue.top ().distance; + queue.pop (); + --idx; + } + + return (static_cast (k_indices.size ())); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::BruteForce::sparseKSearch ( + const PointT &point, int k, std::vector &k_indices, std::vector &k_distances) const +{ + // result used to collect the first k neighbors -> unordered + std::vector result; + result.reserve (k); + + std::priority_queue queue; + if (indices_ != NULL) + { + std::vector::const_iterator iIt =indices_->begin (); + for (; iIt != indices_->end () && result.size () < static_cast (k); ++iIt) + { + if (pcl_isfinite (input_->points[*iIt].x)) + result.push_back (Entry (*iIt, getDistSqr (input_->points[*iIt], point))); + } + + queue = std::priority_queue (result.begin (), result.end ()); + + // either we have k elements, or there are none left to iterate >in either case we're fine + // add the rest + Entry entry; + for (; iIt != indices_->end (); ++iIt) + { + if (!pcl_isfinite (input_->points[*iIt].x)) + continue; + + entry.distance = getDistSqr (input_->points[*iIt], point); + if (queue.top ().distance > entry.distance) + { + entry.index = *iIt; + queue.pop (); + queue.push (entry); + } + } + } + else + { + Entry entry; + for (entry.index = 0; entry.index < input_->size () && result.size () < static_cast (k); ++entry.index) + { + if (pcl_isfinite (input_->points[entry.index].x)) + { + entry.distance = getDistSqr (input_->points[entry.index], point); + result.push_back (entry); + } + } + queue = std::priority_queue (result.begin (), result.end ()); + + // add the rest + for (; entry.index < input_->size (); ++entry.index) + { + if (!pcl_isfinite (input_->points[entry.index].x)) + continue; + + entry.distance = getDistSqr (input_->points[entry.index], point); + if (queue.top ().distance > entry.distance) + { + queue.pop (); + queue.push (entry); + } + } + } + + k_indices.resize (queue.size ()); + k_distances.resize (queue.size ()); + size_t idx = queue.size () - 1; + while (!queue.empty ()) + { + k_indices [idx] = queue.top ().index; + k_distances [idx] = queue.top ().distance; + queue.pop (); + --idx; + } + return (static_cast (k_indices.size ())); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::BruteForce::denseRadiusSearch ( + const PointT& point, double radius, + std::vector &k_indices, std::vector &k_sqr_distances, + unsigned int max_nn) const +{ + radius *= radius; + + size_t reserve = max_nn; + if (reserve == 0) + { + if (indices_ != NULL) + reserve = std::min (indices_->size (), input_->size ()); + else + reserve = input_->size (); + } + k_indices.reserve (reserve); + k_sqr_distances.reserve (reserve); + float distance; + if (indices_ != NULL) + { + for (std::vector::const_iterator iIt =indices_->begin (); iIt != indices_->end (); ++iIt) + { + distance = getDistSqr (input_->points[*iIt], point); + if (distance <= radius) + { + k_indices.push_back (*iIt); + k_sqr_distances.push_back (distance); + if (k_indices.size () == max_nn) // max_nn = 0 -> never true + break; + } + } + } + else + { + for (unsigned index = 0; index < input_->size (); ++index) + { + distance = getDistSqr (input_->points[index], point); + if (distance <= radius) + { + k_indices.push_back (index); + k_sqr_distances.push_back (distance); + if (k_indices.size () == max_nn) // never true if max_nn = 0 + break; + } + } + } + + if (sorted_results_) + this->sortResults (k_indices, k_sqr_distances); + + return (static_cast (k_indices.size ())); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::BruteForce::sparseRadiusSearch ( + const PointT& point, double radius, + std::vector &k_indices, std::vector &k_sqr_distances, + unsigned int max_nn) const +{ + radius *= radius; + + size_t reserve = max_nn; + if (reserve == 0) + { + if (indices_ != NULL) + reserve = std::min (indices_->size (), input_->size ()); + else + reserve = input_->size (); + } + k_indices.reserve (reserve); + k_sqr_distances.reserve (reserve); + + float distance; + if (indices_ != NULL) + { + for (std::vector::const_iterator iIt =indices_->begin (); iIt != indices_->end (); ++iIt) + { + if (!pcl_isfinite (input_->points[*iIt].x)) + continue; + + distance = getDistSqr (input_->points[*iIt], point); + if (distance <= radius) + { + k_indices.push_back (*iIt); + k_sqr_distances.push_back (distance); + if (k_indices.size () == max_nn) // never true if max_nn = 0 + break; + } + } + } + else + { + for (unsigned index = 0; index < input_->size (); ++index) + { + if (!pcl_isfinite (input_->points[index].x)) + continue; + distance = getDistSqr (input_->points[index], point); + if (distance <= radius) + { + k_indices.push_back (index); + k_sqr_distances.push_back (distance); + if (k_indices.size () == max_nn) // never true if max_nn = 0 + break; + } + } + } + + if (sorted_results_) + this->sortResults (k_indices, k_sqr_distances); + + return (static_cast (k_indices.size ())); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::BruteForce::radiusSearch ( + const PointT& point, double radius, std::vector &k_indices, + std::vector &k_sqr_distances, unsigned int max_nn) const +{ + assert (isFinite (point) && "Invalid (NaN, Inf) point coordinates given to nearestKSearch!"); + + k_indices.clear (); + k_sqr_distances.clear (); + if (radius <= 0) + return 0; + + if (input_->is_dense) + return denseRadiusSearch (point, radius, k_indices, k_sqr_distances, max_nn); + else + return sparseRadiusSearch (point, radius, k_indices, k_sqr_distances, max_nn); +} + +#define PCL_INSTANTIATE_BruteForce(T) template class PCL_EXPORTS pcl::search::BruteForce; + +#endif //PCL_SEARCH_IMPL_BRUTE_FORCE_SEARCH_H_ diff --git a/pcl-1.7/pcl/search/impl/flann_search.hpp b/pcl-1.7/pcl/search/impl/flann_search.hpp new file mode 100644 index 0000000..1d310c3 --- /dev/null +++ b/pcl-1.7/pcl/search/impl/flann_search.hpp @@ -0,0 +1,434 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SEARCH_IMPL_FLANN_SEARCH_H_ +#define PCL_SEARCH_IMPL_FLANN_SEARCH_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template +typename pcl::search::FlannSearch::IndexPtr +pcl::search::FlannSearch::KdTreeIndexCreator::createIndex (MatrixConstPtr data) +{ + return (IndexPtr (new flann::KDTreeSingleIndex (*data,flann::KDTreeSingleIndexParams (max_leaf_size_)))); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +typename pcl::search::FlannSearch::IndexPtr +pcl::search::FlannSearch::KMeansIndexCreator::createIndex (MatrixConstPtr data) +{ + return (IndexPtr (new flann::KMeansIndex (*data,flann::KMeansIndexParams ()))); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +typename pcl::search::FlannSearch::IndexPtr +pcl::search::FlannSearch::KdTreeMultiIndexCreator::createIndex (MatrixConstPtr data) +{ + return (IndexPtr (new flann::KDTreeIndex (*data, flann::KDTreeIndexParams (trees_)))); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::search::FlannSearch::FlannSearch(bool sorted, FlannIndexCreatorPtr creator) : pcl::search::Search ("FlannSearch",sorted), + index_(), creator_ (creator), input_flann_(), eps_ (0), checks_ (32), input_copied_for_flann_ (false), point_representation_ (new DefaultPointRepresentation), + dim_ (0), index_mapping_(), identity_mapping_() +{ + dim_ = point_representation_->getNumberOfDimensions (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::search::FlannSearch::~FlannSearch() +{ + if (input_copied_for_flann_) + delete [] input_flann_->ptr(); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::FlannSearch::setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr& indices) +{ + input_ = cloud; + indices_ = indices; + convertInputToFlannMatrix (); + index_ = creator_->createIndex (input_flann_); + index_->buildIndex (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::FlannSearch::nearestKSearch (const PointT &point, int k, std::vector &indices, std::vector &dists) const +{ + assert (point_representation_->isValid (point) && "Invalid (NaN, Inf) point coordinates given to nearestKSearch!"); // remove this check as soon as FLANN does NaN checks internally + bool can_cast = point_representation_->isTrivial (); + + float* data = 0; + if (!can_cast) + { + data = new float [point_representation_->getNumberOfDimensions ()]; + point_representation_->vectorize (point,data); + } + + float* cdata = can_cast ? const_cast (reinterpret_cast (&point)): data; + const flann::Matrix m (cdata ,1, point_representation_->getNumberOfDimensions ()); + + flann::SearchParams p; + p.eps = eps_; + p.sorted = sorted_results_; + p.checks = checks_; + if (indices.size() != static_cast (k)) + indices.resize (k,-1); + if (dists.size() != static_cast (k)) + dists.resize (k); + flann::Matrix i (&indices[0],1,k); + flann::Matrix d (&dists[0],1,k); + int result = index_->knnSearch (m,i,d,k, p); + + delete [] data; + + if (!identity_mapping_) + { + for (size_t i = 0; i < static_cast (k); ++i) + { + int& neighbor_index = indices[i]; + neighbor_index = index_mapping_[neighbor_index]; + } + } + return result; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::FlannSearch::nearestKSearch ( + const PointCloud& cloud, const std::vector& indices, int k, std::vector< std::vector >& k_indices, + std::vector< std::vector >& k_sqr_distances) const +{ + if (indices.empty ()) + { + k_indices.resize (cloud.size ()); + k_sqr_distances.resize (cloud.size ()); + + if (! cloud.is_dense) // remove this check as soon as FLANN does NaN checks internally + { + for (size_t i = 0; i < cloud.size(); i++) + { + assert (point_representation_->isValid (cloud[i]) && "Invalid (NaN, Inf) point coordinates given to nearestKSearch!"); + } + } + + bool can_cast = point_representation_->isTrivial (); + + // full point cloud + trivial copy operation = no need to do any conversion/copying to the flann matrix! + float* data=0; + if (!can_cast) + { + data = new float[dim_*cloud.size ()]; + for (size_t i = 0; i < cloud.size (); ++i) + { + float* out = data+i*dim_; + point_representation_->vectorize (cloud[i],out); + } + } + + // const cast is evil, but the matrix constructor won't change the data, and the + // search won't change the matrix + float* cdata = can_cast ? const_cast (reinterpret_cast (&cloud[0])): data; + const flann::Matrix m (cdata ,cloud.size (), dim_, can_cast ? sizeof (PointT) : dim_ * sizeof (float) ); + + flann::SearchParams p; + p.sorted = sorted_results_; + p.eps = eps_; + p.checks = checks_; + index_->knnSearch (m,k_indices,k_sqr_distances,k, p); + + delete [] data; + } + else // if indices are present, the cloud has to be copied anyway. Only copy the relevant parts of the points here. + { + k_indices.resize (indices.size ()); + k_sqr_distances.resize (indices.size ()); + + if (! cloud.is_dense) // remove this check as soon as FLANN does NaN checks internally + { + for (size_t i = 0; i < indices.size(); i++) + { + assert (point_representation_->isValid (cloud [indices[i]]) && "Invalid (NaN, Inf) point coordinates given to nearestKSearch!"); + } + } + + float* data=new float [dim_*indices.size ()]; + for (size_t i = 0; i < indices.size (); ++i) + { + float* out = data+i*dim_; + point_representation_->vectorize (cloud[indices[i]],out); + } + const flann::Matrix m (data ,indices.size (), point_representation_->getNumberOfDimensions ()); + + flann::SearchParams p; + p.sorted = sorted_results_; + p.eps = eps_; + p.checks = checks_; + index_->knnSearch (m,k_indices,k_sqr_distances,k, p); + + delete[] data; + } + if (!identity_mapping_) + { + for (size_t j = 0; j < k_indices.size (); ++j) + { + for (size_t i = 0; i < static_cast (k); ++i) + { + int& neighbor_index = k_indices[j][i]; + neighbor_index = index_mapping_[neighbor_index]; + } + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::FlannSearch::radiusSearch (const PointT& point, double radius, + std::vector &indices, std::vector &distances, + unsigned int max_nn) const +{ + assert (point_representation_->isValid (point) && "Invalid (NaN, Inf) point coordinates given to radiusSearch!"); // remove this check as soon as FLANN does NaN checks internally + bool can_cast = point_representation_->isTrivial (); + + float* data = 0; + if (!can_cast) + { + data = new float [point_representation_->getNumberOfDimensions ()]; + point_representation_->vectorize (point,data); + } + + float* cdata = can_cast ? const_cast (reinterpret_cast (&point)) : data; + const flann::Matrix m (cdata ,1, point_representation_->getNumberOfDimensions ()); + + flann::SearchParams p; + p.sorted = sorted_results_; + p.eps = eps_; + p.max_neighbors = max_nn > 0 ? max_nn : -1; + p.checks = checks_; + std::vector > i (1); + std::vector > d (1); + int result = index_->radiusSearch (m,i,d,static_cast (radius * radius), p); + + delete [] data; + indices = i [0]; + distances = d [0]; + + if (!identity_mapping_) + { + for (size_t i = 0; i < indices.size (); ++i) + { + int& neighbor_index = indices [i]; + neighbor_index = index_mapping_ [neighbor_index]; + } + } + return result; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::FlannSearch::radiusSearch ( + const PointCloud& cloud, const std::vector& indices, double radius, std::vector< std::vector >& k_indices, + std::vector< std::vector >& k_sqr_distances, unsigned int max_nn) const +{ + if (indices.empty ()) // full point cloud + trivial copy operation = no need to do any conversion/copying to the flann matrix! + { + k_indices.resize (cloud.size ()); + k_sqr_distances.resize (cloud.size ()); + + if (! cloud.is_dense) // remove this check as soon as FLANN does NaN checks internally + { + for (size_t i = 0; i < cloud.size(); i++) + { + assert (point_representation_->isValid (cloud[i]) && "Invalid (NaN, Inf) point coordinates given to radiusSearch!"); + } + } + + bool can_cast = point_representation_->isTrivial (); + + float* data = 0; + if (!can_cast) + { + data = new float[dim_*cloud.size ()]; + for (size_t i = 0; i < cloud.size (); ++i) + { + float* out = data+i*dim_; + point_representation_->vectorize (cloud[i],out); + } + } + + float* cdata = can_cast ? const_cast (reinterpret_cast (&cloud[0])) : data; + const flann::Matrix m (cdata ,cloud.size (), dim_, can_cast ? sizeof (PointT) : dim_ * sizeof (float)); + + flann::SearchParams p; + p.sorted = sorted_results_; + p.eps = eps_; + p.checks = checks_; + // here: max_nn==0: take all neighbors. flann: max_nn==0: return no neighbors, only count them. max_nn==-1: return all neighbors + p.max_neighbors = max_nn != 0 ? max_nn : -1; + index_->radiusSearch (m,k_indices,k_sqr_distances,static_cast (radius * radius), p); + + delete [] data; + } + else // if indices are present, the cloud has to be copied anyway. Only copy the relevant parts of the points here. + { + k_indices.resize (indices.size ()); + k_sqr_distances.resize (indices.size ()); + + if (! cloud.is_dense) // remove this check as soon as FLANN does NaN checks internally + { + for (size_t i = 0; i < indices.size(); i++) + { + assert (point_representation_->isValid (cloud [indices[i]]) && "Invalid (NaN, Inf) point coordinates given to radiusSearch!"); + } + } + + float* data = new float [dim_ * indices.size ()]; + for (size_t i = 0; i < indices.size (); ++i) + { + float* out = data+i*dim_; + point_representation_->vectorize (cloud[indices[i]], out); + } + const flann::Matrix m (data, cloud.size (), point_representation_->getNumberOfDimensions ()); + + flann::SearchParams p; + p.sorted = sorted_results_; + p.eps = eps_; + p.checks = checks_; + // here: max_nn==0: take all neighbors. flann: max_nn==0: return no neighbors, only count them. max_nn==-1: return all neighbors + p.max_neighbors = max_nn != 0 ? max_nn : -1; + index_->radiusSearch (m, k_indices, k_sqr_distances, static_cast (radius * radius), p); + + delete[] data; + } + if (!identity_mapping_) + { + for (size_t j = 0; j < k_indices.size (); ++j ) + { + for (size_t i = 0; i < k_indices[j].size (); ++i) + { + int& neighbor_index = k_indices[j][i]; + neighbor_index = index_mapping_[neighbor_index]; + } + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::FlannSearch::convertInputToFlannMatrix () +{ + size_t original_no_of_points = indices_ && !indices_->empty () ? indices_->size () : input_->size (); + + if (input_copied_for_flann_) + delete input_flann_->ptr(); + input_copied_for_flann_ = true; + index_mapping_.clear(); + identity_mapping_ = true; + + //cloud_ = (float*)malloc (original_no_of_points * dim_ * sizeof (float)); + //index_mapping_.reserve(original_no_of_points); + //identity_mapping_ = true; + + if (!indices_ || indices_->empty ()) + { + // best case: all points can be passed to flann without any conversions + if (input_->is_dense && point_representation_->isTrivial ()) + { + // const cast is evil, but flann won't change the data + input_flann_ = MatrixPtr (new flann::Matrix (const_cast(reinterpret_cast(&(*input_) [0])), original_no_of_points, point_representation_->getNumberOfDimensions (),sizeof (PointT))); + input_copied_for_flann_ = false; + } + else + { + input_flann_ = MatrixPtr (new flann::Matrix (new float[original_no_of_points*point_representation_->getNumberOfDimensions ()], original_no_of_points, point_representation_->getNumberOfDimensions ())); + float* cloud_ptr = input_flann_->ptr(); + for (size_t i = 0; i < original_no_of_points; ++i) + { + const PointT& point = (*input_)[i]; + // Check if the point is invalid + if (!point_representation_->isValid (point)) + { + identity_mapping_ = false; + continue; + } + + index_mapping_.push_back (static_cast (i)); // If the returned index should be for the indices vector + + point_representation_->vectorize (point, cloud_ptr); + cloud_ptr += dim_; + } + } + + } + else + { + input_flann_ = MatrixPtr (new flann::Matrix (new float[original_no_of_points*point_representation_->getNumberOfDimensions ()], original_no_of_points, point_representation_->getNumberOfDimensions ())); + float* cloud_ptr = input_flann_->ptr(); + for (size_t indices_index = 0; indices_index < original_no_of_points; ++indices_index) + { + int cloud_index = (*indices_)[indices_index]; + const PointT& point = (*input_)[cloud_index]; + // Check if the point is invalid + if (!point_representation_->isValid (point)) + { + identity_mapping_ = false; + continue; + } + + index_mapping_.push_back (static_cast (indices_index)); // If the returned index should be for the indices vector + + point_representation_->vectorize (point, cloud_ptr); + cloud_ptr += dim_; + } + } + if (input_copied_for_flann_) + input_flann_->rows = index_mapping_.size (); +} + +#define PCL_INSTANTIATE_FlannSearch(T) template class PCL_EXPORTS pcl::search::FlannSearch; + +#endif diff --git a/pcl-1.7/pcl/search/impl/kdtree.hpp b/pcl-1.7/pcl/search/impl/kdtree.hpp new file mode 100644 index 0000000..5c8d502 --- /dev/null +++ b/pcl-1.7/pcl/search/impl/kdtree.hpp @@ -0,0 +1,120 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SEARCH_KDTREE_IMPL_HPP_ +#define PCL_SEARCH_KDTREE_IMPL_HPP_ + +#include +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::search::KdTree::KdTree (bool sorted) + : pcl::search::Search ("KdTree", sorted) + , tree_ (new Tree (sorted)) +{ + // PCL_ERROR("kdtree init (search/kdtree)\n"); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::KdTree::setPointRepresentation ( + const PointRepresentationConstPtr &point_representation) +{ + tree_->setPointRepresentation (point_representation); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::KdTree::setSortedResults (bool sorted_results) +{ + sorted_results_ = sorted_results; + tree_->setSortedResults (sorted_results); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::KdTree::setEpsilon (float eps) +{ + tree_->setEpsilon (eps); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::KdTree::setInputCloud ( + const PointCloudConstPtr& cloud, + const IndicesConstPtr& indices) +{ + // PCL_ERROR ("Building a kdtree (pcl)\n"); + tree_->setInputCloud (cloud, indices); + input_ = cloud; + indices_ = indices; +} + +// modification +// template void +// pcl::search::KdTree::setTreeType (int tree_type) +// { +// tree_->setTreeType (tree_type); +// } + +/////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::KdTree::nearestKSearch ( + const PointT &point, int k, std::vector &k_indices, + std::vector &k_sqr_distances) const +{ + return (tree_->nearestKSearch (point, k, k_indices, k_sqr_distances)); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::KdTree::radiusSearch ( + const PointT& point, double radius, + std::vector &k_indices, std::vector &k_sqr_distances, + unsigned int max_nn) const +{ + // PCL_ERROR ("radius search (pcl)\n"); + return (tree_->radiusSearch (point, radius, k_indices, k_sqr_distances, max_nn)); +} + +#define PCL_INSTANTIATE_KdTree(T) template class PCL_EXPORTS pcl::search::KdTree; + +#endif //#ifndef _PCL_SEARCH_KDTREE_IMPL_HPP_ + + diff --git a/pcl-1.7/pcl/search/impl/organized.hpp b/pcl-1.7/pcl/search/impl/organized.hpp new file mode 100644 index 0000000..1585ed2 --- /dev/null +++ b/pcl-1.7/pcl/search/impl/organized.hpp @@ -0,0 +1,391 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SEARCH_IMPL_ORGANIZED_NEIGHBOR_SEARCH_H_ +#define PCL_SEARCH_IMPL_ORGANIZED_NEIGHBOR_SEARCH_H_ + +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::OrganizedNeighbor::radiusSearch (const PointT &query, + const double radius, + std::vector &k_indices, + std::vector &k_sqr_distances, + unsigned int max_nn) const +{ + // NAN test + assert (isFinite (query) && "Invalid (NaN, Inf) point coordinates given to nearestKSearch!"); + + // search window + unsigned left, right, top, bottom; + //unsigned x, y, idx; + float squared_distance; + double squared_radius; + + k_indices.clear (); + k_sqr_distances.clear (); + + squared_radius = radius * radius; + + this->getProjectedRadiusSearchBox (query, static_cast (squared_radius), left, right, top, bottom); + + // iterate over search box + if (max_nn == 0 || max_nn >= static_cast (input_->points.size ())) + max_nn = static_cast (input_->points.size ()); + + k_indices.reserve (max_nn); + k_sqr_distances.reserve (max_nn); + + unsigned yEnd = (bottom + 1) * input_->width + right + 1; + register unsigned idx = top * input_->width + left; + unsigned skip = input_->width - right + left - 1; + unsigned xEnd = idx - left + right + 1; + + for (; xEnd != yEnd; idx += skip, xEnd += input_->width) + { + for (; idx < xEnd; ++idx) + { + if (!mask_[idx] || !isFinite (input_->points[idx])) + continue; + + float dist_x = input_->points[idx].x - query.x; + float dist_y = input_->points[idx].y - query.y; + float dist_z = input_->points[idx].z - query.z; + squared_distance = dist_x * dist_x + dist_y * dist_y + dist_z * dist_z; + //squared_distance = (input_->points[idx].getVector3fMap () - query.getVector3fMap ()).squaredNorm (); + if (squared_distance <= squared_radius) + { + k_indices.push_back (idx); + k_sqr_distances.push_back (squared_distance); + // already done ? + if (k_indices.size () == max_nn) + { + if (sorted_results_) + this->sortResults (k_indices, k_sqr_distances); + return (max_nn); + } + } + } + } + if (sorted_results_) + this->sortResults (k_indices, k_sqr_distances); + return (static_cast (k_indices.size ())); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::OrganizedNeighbor::nearestKSearch (const PointT &query, + int k, + std::vector &k_indices, + std::vector &k_sqr_distances) const +{ + assert (isFinite (query) && "Invalid (NaN, Inf) point coordinates given to nearestKSearch!"); + if (k < 1) + { + k_indices.clear (); + k_sqr_distances.clear (); + return (0); + } + + Eigen::Vector3f queryvec (query.x, query.y, query.z); + // project query point on the image plane + //Eigen::Vector3f q = KR_ * query.getVector3fMap () + projection_matrix_.block <3, 1> (0, 3); + Eigen::Vector3f q (KR_ * queryvec + projection_matrix_.block <3, 1> (0, 3)); + int xBegin = int(q [0] / q [2] + 0.5f); + int yBegin = int(q [1] / q [2] + 0.5f); + int xEnd = xBegin + 1; // end is the pixel that is not used anymore, like in iterators + int yEnd = yBegin + 1; + + // the search window. This is supposed to shrink within the iterations + unsigned left = 0; + unsigned right = input_->width - 1; + unsigned top = 0; + unsigned bottom = input_->height - 1; + + std::priority_queue results; + //std::vector k_results; + //k_results.reserve (k); + // add point laying on the projection of the query point. + if (xBegin >= 0 && + xBegin < static_cast (input_->width) && + yBegin >= 0 && + yBegin < static_cast (input_->height)) + testPoint (query, k, results, yBegin * input_->width + xBegin); + else // point lys + { + // find the box that touches the image border -> dont waste time evaluating boxes that are completely outside the image! + int dist = std::numeric_limits::max (); + + if (xBegin < 0) + dist = -xBegin; + else if (xBegin >= static_cast (input_->width)) + dist = xBegin - static_cast (input_->width); + + if (yBegin < 0) + dist = std::min (dist, -yBegin); + else if (yBegin >= static_cast (input_->height)) + dist = std::min (dist, yBegin - static_cast (input_->height)); + + xBegin -= dist; + xEnd += dist; + + yBegin -= dist; + yEnd += dist; + } + + + // stop used as isChanged as well as stop. + bool stop = false; + do + { + // increment box size + --xBegin; + ++xEnd; + --yBegin; + ++yEnd; + + // the range in x-direction which intersects with the image width + int xFrom = xBegin; + int xTo = xEnd; + clipRange (xFrom, xTo, 0, input_->width); + + // if x-extend is not 0 + if (xTo > xFrom) + { + // if upper line of the rectangle is visible and x-extend is not 0 + if (yBegin >= 0 && yBegin < static_cast (input_->height)) + { + int idx = yBegin * input_->width + xFrom; + int idxTo = idx + xTo - xFrom; + for (; idx < idxTo; ++idx) + stop = testPoint (query, k, results, idx) || stop; + } + + + // the row yEnd does NOT belong to the box -> last row = yEnd - 1 + // if lower line of the rectangle is visible + if (yEnd > 0 && yEnd <= static_cast (input_->height)) + { + int idx = (yEnd - 1) * input_->width + xFrom; + int idxTo = idx + xTo - xFrom; + + for (; idx < idxTo; ++idx) + stop = testPoint (query, k, results, idx) || stop; + } + + // skip first row and last row (already handled above) + int yFrom = yBegin + 1; + int yTo = yEnd - 1; + clipRange (yFrom, yTo, 0, input_->height); + + // if we have lines in between that are also visible + if (yFrom < yTo) + { + if (xBegin >= 0 && xBegin < static_cast (input_->width)) + { + int idx = yFrom * input_->width + xBegin; + int idxTo = yTo * input_->width + xBegin; + + for (; idx < idxTo; idx += input_->width) + stop = testPoint (query, k, results, idx) || stop; + } + + if (xEnd > 0 && xEnd <= static_cast (input_->width)) + { + int idx = yFrom * input_->width + xEnd - 1; + int idxTo = yTo * input_->width + xEnd - 1; + + for (; idx < idxTo; idx += input_->width) + stop = testPoint (query, k, results, idx) || stop; + } + + } + // stop here means that the k-nearest neighbor changed -> recalculate bounding box of ellipse. + if (stop) + getProjectedRadiusSearchBox (query, results.top ().distance, left, right, top, bottom); + + } + // now we use it as stop flag -> if bounding box is completely within the already examined search box were done! + stop = (static_cast (left) >= xBegin && static_cast (left) < xEnd && + static_cast (right) >= xBegin && static_cast (right) < xEnd && + static_cast (top) >= yBegin && static_cast (top) < yEnd && + static_cast (bottom) >= yBegin && static_cast (bottom) < yEnd); + + } while (!stop); + + + k_indices.resize (results.size ()); + k_sqr_distances.resize (results.size ()); + size_t idx = results.size () - 1; + while (!results.empty ()) + { + k_indices [idx] = results.top ().index; + k_sqr_distances [idx] = results.top ().distance; + results.pop (); + --idx; + } + + return (static_cast (k_indices.size ())); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::OrganizedNeighbor::getProjectedRadiusSearchBox (const PointT& point, + float squared_radius, + unsigned &minX, + unsigned &maxX, + unsigned &minY, + unsigned &maxY) const +{ + Eigen::Vector3f queryvec (point.x, point.y, point.z); + //Eigen::Vector3f q = KR_ * point.getVector3fMap () + projection_matrix_.block <3, 1> (0, 3); + Eigen::Vector3f q (KR_ * queryvec + projection_matrix_.block <3, 1> (0, 3)); + + float a = squared_radius * KR_KRT_.coeff (8) - q [2] * q [2]; + float b = squared_radius * KR_KRT_.coeff (7) - q [1] * q [2]; + float c = squared_radius * KR_KRT_.coeff (4) - q [1] * q [1]; + int min, max; + // a and c are multiplied by two already => - 4ac -> - ac + float det = b * b - a * c; + if (det < 0) + { + minY = 0; + maxY = input_->height - 1; + } + else + { + float y1 = static_cast ((b - sqrt (det)) / a); + float y2 = static_cast ((b + sqrt (det)) / a); + + min = std::min (static_cast (floor (y1)), static_cast (floor (y2))); + max = std::max (static_cast (ceil (y1)), static_cast (ceil (y2))); + minY = static_cast (std::min (static_cast (input_->height) - 1, std::max (0, min))); + maxY = static_cast (std::max (std::min (static_cast (input_->height) - 1, max), 0)); + } + + b = squared_radius * KR_KRT_.coeff (6) - q [0] * q [2]; + c = squared_radius * KR_KRT_.coeff (0) - q [0] * q [0]; + + det = b * b - a * c; + if (det < 0) + { + minX = 0; + maxX = input_->width - 1; + } + else + { + float x1 = static_cast ((b - sqrt (det)) / a); + float x2 = static_cast ((b + sqrt (det)) / a); + + min = std::min (static_cast (floor (x1)), static_cast (floor (x2))); + max = std::max (static_cast (ceil (x1)), static_cast (ceil (x2))); + minX = static_cast (std::min (static_cast (input_->width)- 1, std::max (0, min))); + maxX = static_cast (std::max (std::min (static_cast (input_->width) - 1, max), 0)); + } +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::OrganizedNeighbor::computeCameraMatrix (Eigen::Matrix3f& camera_matrix) const +{ + pcl::getCameraMatrixFromProjectionMatrix (projection_matrix_, camera_matrix); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::OrganizedNeighbor::estimateProjectionMatrix () +{ + // internally we calculate with double but store the result into float matrices. + projection_matrix_.setZero (); + if (input_->height == 1 || input_->width == 1) + { + PCL_ERROR ("[pcl::%s::estimateProjectionMatrix] Input dataset is not organized!\n", this->getName ().c_str ()); + return; + } + + const unsigned ySkip = (std::max) (input_->height >> pyramid_level_, unsigned (1)); + const unsigned xSkip = (std::max) (input_->width >> pyramid_level_, unsigned (1)); + + std::vector indices; + indices.reserve (input_->size () >> (pyramid_level_ << 1)); + + for (unsigned yIdx = 0, idx = 0; yIdx < input_->height; yIdx += ySkip, idx += input_->width * (ySkip - 1)) + { + for (unsigned xIdx = 0; xIdx < input_->width; xIdx += xSkip, idx += xSkip) + { + if (!mask_ [idx]) + continue; + + indices.push_back (idx); + } + } + + double residual_sqr = pcl::estimateProjectionMatrix (input_, projection_matrix_, indices); + + if (fabs (residual_sqr) > eps_ * float (indices.size ())) + { + PCL_ERROR ("[pcl::%s::radiusSearch] Input dataset is not from a projective device!\nResidual (MSE) %f, using %d valid points\n", this->getName ().c_str (), residual_sqr / double (indices.size()), indices.size ()); + return; + } + + // get left 3x3 sub matrix, which contains K * R, with K = camera matrix = [[fx s cx] [0 fy cy] [0 0 1]] + // and R being the rotation matrix + KR_ = projection_matrix_.topLeftCorner <3, 3> (); + + // precalculate KR * KR^T needed by calculations during nn-search + KR_KRT_ = KR_ * KR_.transpose (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::search::OrganizedNeighbor::projectPoint (const PointT& point, pcl::PointXY& q) const +{ + Eigen::Vector3f projected = KR_ * point.getVector3fMap () + projection_matrix_.block <3, 1> (0, 3); + q.x = projected [0] / projected [2]; + q.y = projected [1] / projected [2]; + return (projected[2] != 0); +} +#define PCL_INSTANTIATE_OrganizedNeighbor(T) template class PCL_EXPORTS pcl::search::OrganizedNeighbor; + +#endif diff --git a/pcl-1.7/pcl/search/impl/search.hpp b/pcl-1.7/pcl/search/impl/search.hpp new file mode 100644 index 0000000..72b6c26 --- /dev/null +++ b/pcl-1.7/pcl/search/impl/search.hpp @@ -0,0 +1,222 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SEARCH_SEARCH_IMPL_HPP_ +#define PCL_SEARCH_SEARCH_IMPL_HPP_ + +#include + +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::search::Search::Search (const std::string& name, bool sorted) + : input_ () + , indices_ () + , sorted_results_ (sorted) + , name_ (name) +{ + // PCL_ERROR("Constructor: Search\n"); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template const std::string& +pcl::search::Search::getName () const +{ + return (name_); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::Search::setSortedResults (bool sorted) +{ + sorted_results_ = sorted; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::search::Search::getSortedResults () +{ + return (sorted_results_); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::Search::setInputCloud ( + const PointCloudConstPtr& cloud, const IndicesConstPtr &indices) +{ + input_ = cloud; + indices_ = indices; +} + + +/////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::Search::nearestKSearch ( + const PointCloud &cloud, int index, int k, + std::vector &k_indices, std::vector &k_sqr_distances) const +{ + assert (index >= 0 && index < static_cast (cloud.points.size ()) && "Out-of-bounds error in nearestKSearch!"); + return (nearestKSearch (cloud.points[index], k, k_indices, k_sqr_distances)); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::Search::nearestKSearch ( + int index, int k, + std::vector &k_indices, + std::vector &k_sqr_distances) const +{ + if (indices_ == NULL) + { + assert (index >= 0 && index < static_cast (input_->points.size ()) && "Out-of-bounds error in nearestKSearch!"); + return (nearestKSearch (input_->points[index], k, k_indices, k_sqr_distances)); + } + else + { + assert (index >= 0 && index < static_cast (indices_->size ()) && "Out-of-bounds error in nearestKSearch!"); + if (index >= static_cast (indices_->size ()) || index < 0) + return (0); + return (nearestKSearch (input_->points[(*indices_)[index]], k, k_indices, k_sqr_distances)); + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::Search::nearestKSearch ( + const PointCloud& cloud, const std::vector& indices, + int k, std::vector< std::vector >& k_indices, + std::vector< std::vector >& k_sqr_distances) const +{ + if (indices.empty ()) + { + k_indices.resize (cloud.size ()); + k_sqr_distances.resize (cloud.size ()); + for (size_t i = 0; i < cloud.size (); i++) + nearestKSearch (cloud, static_cast (i), k, k_indices[i], k_sqr_distances[i]); + } + else + { + k_indices.resize (indices.size ()); + k_sqr_distances.resize (indices.size ()); + for (size_t i = 0; i < indices.size (); i++) + nearestKSearch (cloud, indices[i], k, k_indices[i], k_sqr_distances[i]); + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::Search::radiusSearch ( + const PointCloud &cloud, int index, double radius, + std::vector &k_indices, std::vector &k_sqr_distances, + unsigned int max_nn) const +{ + assert (index >= 0 && index < static_cast (cloud.points.size ()) && "Out-of-bounds error in radiusSearch!"); + return (radiusSearch(cloud.points[index], radius, k_indices, k_sqr_distances, max_nn)); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::search::Search::radiusSearch ( + int index, double radius, std::vector &k_indices, + std::vector &k_sqr_distances, unsigned int max_nn ) const +{ + if (indices_ == NULL) + { + assert (index >= 0 && index < static_cast (input_->points.size ()) && "Out-of-bounds error in radiusSearch!"); + return (radiusSearch (input_->points[index], radius, k_indices, k_sqr_distances, max_nn)); + } + else + { + assert (index >= 0 && index < static_cast (indices_->size ()) && "Out-of-bounds error in radiusSearch!"); + return (radiusSearch (input_->points[(*indices_)[index]], radius, k_indices, k_sqr_distances, max_nn)); + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::Search::radiusSearch ( + const PointCloud& cloud, + const std::vector& indices, + double radius, + std::vector< std::vector >& k_indices, + std::vector< std::vector > &k_sqr_distances, + unsigned int max_nn) const +{ + if (indices.empty ()) + { + k_indices.resize (cloud.size ()); + k_sqr_distances.resize (cloud.size ()); + for (size_t i = 0; i < cloud.size (); i++) + radiusSearch (cloud, static_cast (i), radius,k_indices[i], k_sqr_distances[i], max_nn); + } + else + { + k_indices.resize (indices.size ()); + k_sqr_distances.resize (indices.size ()); + for (size_t i = 0; i < indices.size (); i++) + radiusSearch (cloud,indices[i],radius,k_indices[i],k_sqr_distances[i], max_nn); + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::search::Search::sortResults ( + std::vector& indices, std::vector& distances) const +{ + std::vector order (indices.size ()); + for (size_t idx = 0; idx < order.size (); ++idx) + order [idx] = static_cast (idx); + + Compare compare (distances); + sort (order.begin (), order.end (), compare); + + std::vector sorted (indices.size ()); + for (size_t idx = 0; idx < order.size (); ++idx) + sorted [idx] = indices[order [idx]]; + + indices = sorted; + + // sort the according distances. + sort (distances.begin (), distances.end ()); +} + +#define PCL_INSTANTIATE_Search(T) template class PCL_EXPORTS pcl::search::Search; + +#endif //#ifndef _PCL_SEARCH_SEARCH_IMPL_HPP_ + + diff --git a/pcl-1.7/pcl/search/kdtree.h b/pcl-1.7/pcl/search/kdtree.h new file mode 100644 index 0000000..326ea77 --- /dev/null +++ b/pcl-1.7/pcl/search/kdtree.h @@ -0,0 +1,189 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_SEARCH_KDTREE_H_ +#define PCL_SEARCH_KDTREE_H_ + +#include +#include + +namespace pcl +{ + // Forward declarations + template class PointRepresentation; + + namespace search + { + /** \brief @b search::KdTree is a wrapper class which inherits the pcl::KdTree class for performing search + * functions using KdTree structure. KdTree is a generic type of 3D spatial locator using kD-tree structures. + * The class is making use of the FLANN (Fast Library for Approximate Nearest Neighbor) project + * by Marius Muja and David Lowe. + * + * \author Radu B. Rusu + * \ingroup search + */ + template > + class KdTree: public Search + { + public: + typedef typename Search::PointCloud PointCloud; + typedef typename Search::PointCloudConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr > IndicesPtr; + typedef boost::shared_ptr > IndicesConstPtr; + + using pcl::search::Search::indices_; + using pcl::search::Search::input_; + using pcl::search::Search::getIndices; + using pcl::search::Search::getInputCloud; + using pcl::search::Search::nearestKSearch; + using pcl::search::Search::radiusSearch; + using pcl::search::Search::sorted_results_; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef boost::shared_ptr KdTreePtr; + typedef boost::shared_ptr KdTreeConstPtr; + typedef boost::shared_ptr > PointRepresentationConstPtr; + + /** \brief Constructor for KdTree. + * + * \param[in] sorted set to true if the nearest neighbor search results + * need to be sorted in ascending order based on their distance to the + * query point + * + */ + KdTree (bool sorted = true); + + /** \brief Destructor for KdTree. */ + virtual + ~KdTree () + { + // PCL_ERROR("Destructor: kdtree\n"); + } + + /** \brief Provide a pointer to the point representation to use to convert points into k-D vectors. + * \param[in] point_representation the const boost shared pointer to a PointRepresentation + */ + void + setPointRepresentation (const PointRepresentationConstPtr &point_representation); + + /** \brief Get a pointer to the point representation used when converting points into k-D vectors. */ + inline PointRepresentationConstPtr + getPointRepresentation () const + { + return (tree_->getPointRepresentation ()); + } + + /** \brief Sets whether the results have to be sorted or not. + * \param[in] sorted_results set to true if the radius search results should be sorted + */ + void + setSortedResults (bool sorted_results); + + /** \brief Set the search epsilon precision (error bound) for nearest neighbors searches. + * \param[in] eps precision (error bound) for nearest neighbors searches + */ + void + setEpsilon (float eps); + + /** \brief Get the search epsilon precision (error bound) for nearest neighbors searches. */ + inline float + getEpsilon () const + { + return (tree_->getEpsilon ()); + } + + /** \brief Provide a pointer to the input dataset. + * \param[in] cloud the const boost shared pointer to a PointCloud message + * \param[in] indices the point indices subset that is to be used from \a cloud + */ + void + setInputCloud (const PointCloudConstPtr& cloud, + const IndicesConstPtr& indices = IndicesConstPtr ()); + + /** \brief Search for the k-nearest neighbors for the given query point. + * \param[in] point the given query point + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + */ + int + nearestKSearch (const PointT &point, int k, + std::vector &k_indices, + std::vector &k_sqr_distances) const; + + /** \brief Search for all the nearest neighbors of the query point in a given radius. + * \param[in] point the given query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + * \return number of neighbors found in radius + */ + int + radiusSearch (const PointT& point, double radius, + std::vector &k_indices, + std::vector &k_sqr_distances, + unsigned int max_nn = 0) const; + + // modification + // set kdtree type + // void setTreeType(int tree_type); + + protected: + /** \brief A pointer to the internal KdTree object. */ + KdTreePtr tree_; + }; + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#else +#define PCL_INSTANTIATE_KdTree(T) template class PCL_EXPORTS pcl::search::KdTree; +#endif + +#endif // PCL_SEARCH_KDTREE_H_ + diff --git a/pcl-1.7/pcl/search/octree.h b/pcl-1.7/pcl/search/octree.h new file mode 100644 index 0000000..dc5f701 --- /dev/null +++ b/pcl-1.7/pcl/search/octree.h @@ -0,0 +1,293 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_SEARCH_OCTREE_H +#define PCL_SEARCH_OCTREE_H + +#include +#include + +namespace pcl +{ + namespace search + { + /** \brief @b search::Octree is a wrapper class which implements nearest neighbor search operations based on the + * pcl::octree::Octree structure. + * + * The octree pointcloud class needs to be initialized with its voxel + * resolution. Its bounding box is automatically adjusted according to the + * pointcloud dimension or it can be predefined. Note: The tree depth + * equates to the resolution and the bounding box dimensions of the + * octree. + * + * \note typename: PointT: type of point used in pointcloud + * \note typename: LeafT: leaf node class (usuallt templated with integer indices values) + * \note typename: OctreeT: octree implementation () + * + * \author Julius Kammerl + * \ingroup search + */ + template > + class Octree: public Search + { + public: + // public typedefs + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef boost::shared_ptr > IndicesPtr; + typedef boost::shared_ptr > IndicesConstPtr; + + typedef pcl::PointCloud PointCloud; + typedef boost::shared_ptr PointCloudPtr; + typedef boost::shared_ptr PointCloudConstPtr; + + // Boost shared pointers + typedef boost::shared_ptr > OctreePointCloudSearchPtr; + typedef boost::shared_ptr > OctreePointCloudSearchConstPtr; + OctreePointCloudSearchPtr tree_; + + using pcl::search::Search::input_; + using pcl::search::Search::indices_; + using pcl::search::Search::sorted_results_; + + /** \brief Octree constructor. + * \param[in] resolution octree resolution at lowest octree level + */ + Octree (const double resolution) + : Search ("Octree") + , tree_ (new pcl::octree::OctreePointCloudSearch (resolution)) + { + } + + /** \brief Empty Destructor. */ + virtual + ~Octree () + { + } + + /** \brief Provide a pointer to the input dataset. + * \param[in] cloud the const boost shared pointer to a PointCloud message + */ + inline void + setInputCloud (const PointCloudConstPtr &cloud) + { + tree_->deleteTree (); + tree_->setInputCloud (cloud); + tree_->addPointsFromInputCloud (); + input_ = cloud; + } + + /** \brief Provide a pointer to the input dataset. + * \param[in] cloud the const boost shared pointer to a PointCloud message + * \param[in] indices the point indices subset that is to be used from \a cloud + */ + inline void + setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr& indices) + { + tree_->deleteTree (); + tree_->setInputCloud (cloud, indices); + tree_->addPointsFromInputCloud (); + input_ = cloud; + indices_ = indices; + } + + /** \brief Search for the k-nearest neighbors for the given query point. + * \param[in] cloud the point cloud data + * \param[in] index the index in \a cloud representing the query point + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + */ + inline int + nearestKSearch (const PointCloud &cloud, int index, int k, std::vector &k_indices, + std::vector &k_sqr_distances) const + { + return (tree_->nearestKSearch (cloud, index, k, k_indices, k_sqr_distances)); + } + + /** \brief Search for the k-nearest neighbors for the given query point. + * \param[in] point the given query point + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + */ + inline int + nearestKSearch (const PointT &point, int k, std::vector &k_indices, + std::vector &k_sqr_distances) const + { + return (tree_->nearestKSearch (point, k, k_indices, k_sqr_distances)); + } + + /** \brief Search for the k-nearest neighbors for the given query point (zero-copy). + * + * \param[in] index the index representing the query point in the + * dataset given by \a setInputCloud if indices were given in + * setInputCloud, index will be the position in the indices vector + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + */ + inline int + nearestKSearch (int index, int k, std::vector &k_indices, std::vector &k_sqr_distances) const + { + return (tree_->nearestKSearch (index, k, k_indices, k_sqr_distances)); + } + + /** \brief search for all neighbors of query point that are within a given radius. + * \param cloud the point cloud data + * \param index the index in \a cloud representing the query point + * \param radius the radius of the sphere bounding all of p_q's neighbors + * \param k_indices the resultant indices of the neighboring points + * \param k_sqr_distances the resultant squared distances to the neighboring points + * \param max_nn if given, bounds the maximum returned neighbors to this value + * \return number of neighbors found in radius + */ + inline int + radiusSearch (const PointCloud &cloud, + int index, + double radius, + std::vector &k_indices, + std::vector &k_sqr_distances, + unsigned int max_nn = 0) const + { + tree_->radiusSearch (cloud, index, radius, k_indices, k_sqr_distances, max_nn); + if (sorted_results_) + this->sortResults (k_indices, k_sqr_distances); + return (static_cast (k_indices.size ())); + } + + /** \brief search for all neighbors of query point that are within a given radius. + * \param p_q the given query point + * \param radius the radius of the sphere bounding all of p_q's neighbors + * \param k_indices the resultant indices of the neighboring points + * \param k_sqr_distances the resultant squared distances to the neighboring points + * \param max_nn if given, bounds the maximum returned neighbors to this value + * \return number of neighbors found in radius + */ + inline int + radiusSearch (const PointT &p_q, + double radius, + std::vector &k_indices, + std::vector &k_sqr_distances, + unsigned int max_nn = 0) const + { + tree_->radiusSearch (p_q, radius, k_indices, k_sqr_distances, max_nn); + if (sorted_results_) + this->sortResults (k_indices, k_sqr_distances); + return (static_cast (k_indices.size ())); + } + + /** \brief search for all neighbors of query point that are within a given radius. + * \param index index representing the query point in the dataset given by \a setInputCloud. + * If indices were given in setInputCloud, index will be the position in the indices vector + * \param radius radius of the sphere bounding all of p_q's neighbors + * \param k_indices the resultant indices of the neighboring points + * \param k_sqr_distances the resultant squared distances to the neighboring points + * \param max_nn if given, bounds the maximum returned neighbors to this value + * \return number of neighbors found in radius + */ + inline int + radiusSearch (int index, double radius, std::vector &k_indices, + std::vector &k_sqr_distances, unsigned int max_nn = 0) const + { + tree_->radiusSearch (index, radius, k_indices, k_sqr_distances, max_nn); + if (sorted_results_) + this->sortResults (k_indices, k_sqr_distances); + return (static_cast (k_indices.size ())); + } + + + /** \brief Search for approximate nearest neighbor at the query point. + * \param[in] cloud the point cloud data + * \param[in] query_index the index in \a cloud representing the query point + * \param[out] result_index the resultant index of the neighbor point + * \param[out] sqr_distance the resultant squared distance to the neighboring point + * \return number of neighbors found + */ + inline void + approxNearestSearch (const PointCloudConstPtr &cloud, int query_index, int &result_index, + float &sqr_distance) + { + return (tree_->approxNearestSearch (cloud->points[query_index], result_index, sqr_distance)); + } + + /** \brief Search for approximate nearest neighbor at the query point. + * \param[in] p_q the given query point + * \param[out] result_index the resultant index of the neighbor point + * \param[out] sqr_distance the resultant squared distance to the neighboring point + */ + inline void + approxNearestSearch (const PointT &p_q, int &result_index, float &sqr_distance) + { + return (tree_->approxNearestSearch (p_q, result_index, sqr_distance)); + } + + /** \brief Search for approximate nearest neighbor at the query point. + * \param query_index index representing the query point in the dataset given by \a setInputCloud. + * If indices were given in setInputCloud, index will be the position in the indices vector. + * \param result_index the resultant index of the neighbor point + * \param sqr_distance the resultant squared distance to the neighboring point + * \return number of neighbors found + */ + inline void + approxNearestSearch (int query_index, int &result_index, float &sqr_distance) + { + return (tree_->approxNearestSearch (query_index, result_index, sqr_distance)); + } + + }; + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#else +#define PCL_INSTANTIATE_Octree(T) template class PCL_EXPORTS pcl::search::Octree; +#endif + +#endif // PCL_SEARCH_OCTREE_H diff --git a/pcl-1.7/pcl/search/organized.h b/pcl-1.7/pcl/search/organized.h new file mode 100644 index 0000000..6c5678a --- /dev/null +++ b/pcl-1.7/pcl/search/organized.h @@ -0,0 +1,286 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SEARCH_ORGANIZED_NEIGHBOR_SEARCH_H_ +#define PCL_SEARCH_ORGANIZED_NEIGHBOR_SEARCH_H_ + +#include +#include +#include +#include + +#include +#include +#include +#include + +namespace pcl +{ + namespace search + { + /** \brief OrganizedNeighbor is a class for optimized nearest neigbhor search in organized point clouds. + * \author Radu B. Rusu, Julius Kammerl, Suat Gedikli, Koen Buys + * \ingroup search + */ + template + class OrganizedNeighbor : public pcl::search::Search + { + + public: + // public typedefs + typedef pcl::PointCloud PointCloud; + typedef boost::shared_ptr PointCloudPtr; + + typedef boost::shared_ptr PointCloudConstPtr; + typedef boost::shared_ptr > IndicesConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using pcl::search::Search::indices_; + using pcl::search::Search::sorted_results_; + using pcl::search::Search::input_; + + /** \brief Constructor + * \param[in] sorted_results whether the results should be return sorted in ascending order on the distances or not. + * This applies only for radius search, since knn always returns sorted resutls + * \param[in] eps the threshold for the mean-squared-error of the estimation of the projection matrix. + * if the MSE is above this value, the point cloud is considered as not from a projective device, + * thus organized neighbor search can not be applied on that cloud. + * \param[in] pyramid_level the level of the down sampled point cloud to be used for projection matrix estimation + */ + OrganizedNeighbor (bool sorted_results = false, float eps = 1e-4f, unsigned pyramid_level = 5) + : Search ("OrganizedNeighbor", sorted_results) + , projection_matrix_ (Eigen::Matrix::Zero ()) + , KR_ (Eigen::Matrix::Zero ()) + , KR_KRT_ (Eigen::Matrix::Zero ()) + , eps_ (eps) + , pyramid_level_ (pyramid_level) + , mask_ () + { + } + + /** \brief Empty deconstructor. */ + virtual ~OrganizedNeighbor () {} + + /** \brief Test whether this search-object is valid (input is organized AND from projective device) + * User should use this method after setting the input cloud, since setInput just prints an error + * if input is not organized or a projection matrix could not be determined. + * \return true if the input data is organized and from a projective device, false otherwise + */ + bool + isValid () const + { + // determinant (KR) = determinant (K) * determinant (R) = determinant (K) = f_x * f_y. + // If we expect at max an opening angle of 170degree in x-direction -> f_x = 2.0 * width / tan (85 degree); + // 2 * tan (85 degree) ~ 22.86 + float min_f = 0.043744332f * static_cast(input_->width); + //std::cout << "isValid: " << determinant3x3Matrix (KR_ / sqrt (KR_KRT_.coeff (8))) << " >= " << (min_f * min_f) << std::endl; + return (determinant3x3Matrix (KR_ / sqrtf (KR_KRT_.coeff (8))) >= (min_f * min_f)); + } + + /** \brief Compute the camera matrix + * \param[out] camera_matrix the resultant computed camera matrix + */ + void + computeCameraMatrix (Eigen::Matrix3f& camera_matrix) const; + + /** \brief Provide a pointer to the input data set, if user has focal length he must set it before calling this + * \param[in] cloud the const boost shared pointer to a PointCloud message + * \param[in] indices the const boost shared pointer to PointIndices + */ + virtual void + setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr &indices = IndicesConstPtr ()) + { + input_ = cloud; + + mask_.resize (input_->size ()); + input_ = cloud; + indices_ = indices; + + if (indices_.get () != NULL && indices_->size () != 0) + { + mask_.assign (input_->size (), 0); + for (std::vector::const_iterator iIt = indices_->begin (); iIt != indices_->end (); ++iIt) + mask_[*iIt] = 1; + } + else + mask_.assign (input_->size (), 1); + + estimateProjectionMatrix (); + } + + /** \brief Search for all neighbors of query point that are within a given radius. + * \param[in] p_q the given query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + * \return number of neighbors found in radius + */ + int + radiusSearch (const PointT &p_q, + double radius, + std::vector &k_indices, + std::vector &k_sqr_distances, + unsigned int max_nn = 0) const; + + /** \brief estimated the projection matrix from the input cloud. */ + void + estimateProjectionMatrix (); + + /** \brief Search for the k-nearest neighbors for a given query point. + * \note limiting the maximum search radius (with setMaxDistance) can lead to a significant improvement in search speed + * \param[in] p_q the given query point (\ref setInputCloud must be given a-priori!) + * \param[in] k the number of neighbors to search for (used only if horizontal and vertical window not given already!) + * \param[out] k_indices the resultant point indices (must be resized to \a k beforehand!) + * \param[out] k_sqr_distances \note this function does not return distances + * \return number of neighbors found + * @todo still need to implements this functionality + */ + int + nearestKSearch (const PointT &p_q, + int k, + std::vector &k_indices, + std::vector &k_sqr_distances) const; + + /** \brief projects a point into the image + * \param[in] p point in 3D World Coordinate Frame to be projected onto the image plane + * \param[out] q the 2D projected point in pixel coordinates (u,v) + * @return true if projection is valid, false otherwise + */ + bool projectPoint (const PointT& p, pcl::PointXY& q) const; + + protected: + + struct Entry + { + Entry (int idx, float dist) : index (idx), distance (dist) {} + Entry () : index (0), distance (0) {} + unsigned index; + float distance; + + inline bool + operator < (const Entry& other) const + { + return (distance < other.distance); + } + }; + + /** \brief test if point given by index is among the k NN in results to the query point. + * \param[in] query query point + * \param[in] k number of maximum nn interested in + * \param[in] queue priority queue with k NN + * \param[in] index index on point to be tested + * \return wheter the top element changed or not. + */ + inline bool + testPoint (const PointT& query, unsigned k, std::priority_queue& queue, unsigned index) const + { + const PointT& point = input_->points [index]; + if (mask_ [index] && pcl_isfinite (point.x)) + { + //float squared_distance = (point.getVector3fMap () - query.getVector3fMap ()).squaredNorm (); + float dist_x = point.x - query.x; + float dist_y = point.y - query.y; + float dist_z = point.z - query.z; + float squared_distance = dist_x * dist_x + dist_y * dist_y + dist_z * dist_z; + if (queue.size () < k) + queue.push (Entry (index, squared_distance)); + else if (queue.top ().distance > squared_distance) + { + queue.pop (); + queue.push (Entry (index, squared_distance)); + return true; // top element has changed! + } + } + return false; + } + + inline void + clipRange (int& begin, int &end, int min, int max) const + { + begin = std::max (std::min (begin, max), min); + end = std::min (std::max (end, min), max); + } + + /** \brief Obtain a search box in 2D from a sphere with a radius in 3D + * \param[in] point the query point (sphere center) + * \param[in] squared_radius the squared sphere radius + * \param[out] minX the min X box coordinate + * \param[out] minY the min Y box coordinate + * \param[out] maxX the max X box coordinate + * \param[out] maxY the max Y box coordinate + */ + void + getProjectedRadiusSearchBox (const PointT& point, float squared_radius, unsigned& minX, unsigned& minY, + unsigned& maxX, unsigned& maxY) const; + + + /** \brief the projection matrix. Either set by user or calculated by the first / each input cloud */ + Eigen::Matrix projection_matrix_; + + /** \brief inveser of the left 3x3 projection matrix which is K * R (with K being the camera matrix and R the rotation matrix)*/ + Eigen::Matrix KR_; + + /** \brief inveser of the left 3x3 projection matrix which is K * R (with K being the camera matrix and R the rotation matrix)*/ + Eigen::Matrix KR_KRT_; + + /** \brief epsilon value for the MSE of the projection matrix estimation*/ + const float eps_; + + /** \brief using only a subsample of points to calculate the projection matrix. pyramid_level_ = use down sampled cloud given by pyramid_level_*/ + const unsigned pyramid_level_; + + /** \brief mask, indicating whether the point was in the indices list or not.*/ + std::vector mask_; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif + diff --git a/pcl-1.7/pcl/search/pcl_search.h b/pcl-1.7/pcl/search/pcl_search.h new file mode 100644 index 0000000..4d8c537 --- /dev/null +++ b/pcl-1.7/pcl/search/pcl_search.h @@ -0,0 +1,49 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SEARCH_PCL_SEARCH_H_ +#define PCL_SEARCH_PCL_SEARCH_H_ + +#include +#include +#include +#include + +#endif // PCL_SEARCH_PCL_SEARCH_H_ + diff --git a/pcl-1.7/pcl/search/search.h b/pcl-1.7/pcl/search/search.h new file mode 100644 index 0000000..23aaff6 --- /dev/null +++ b/pcl-1.7/pcl/search/search.h @@ -0,0 +1,435 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SEARCH_SEARCH_H_ +#define PCL_SEARCH_SEARCH_H_ + +#include +#include +#include +#include + +#include + +namespace pcl +{ + namespace search + { + /** \brief Generic search class. All search wrappers must inherit from this. + * + * Each search method must implement 2 different types of search: + * - \b nearestKSearch - search for K-nearest neighbors. + * - \b radiusSearch - search for all nearest neighbors in a sphere of a given radius + * + * The input to each search method can be given in 3 different ways: + * - as a query point + * - as a (cloud, index) pair + * - as an index + * + * For the latter option, it is assumed that the user specified the input + * via a \ref setInputCloud () method first. + * + * \note In case of an error, all methods are supposed to return 0 as the number of neighbors found. + * + * \note libpcl_search deals with three-dimensional search problems. For higher + * level dimensional search, please refer to the libpcl_kdtree module. + * + * \author Radu B. Rusu + * \ingroup search + */ + template + class Search + { + public: + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef boost::shared_ptr > IndicesPtr; + typedef boost::shared_ptr > IndicesConstPtr; + + /** Constructor. */ + Search (const std::string& name = "", bool sorted = false); + + /** Destructor. */ + virtual + ~Search () + { + // PCL_ERROR("Destructor: search\n"); + } + + /** \brief Returns the search method name + */ + virtual const std::string& + getName () const; + + /** \brief sets whether the results should be sorted (ascending in the distance) or not + * \param[in] sorted should be true if the results should be sorted by the distance in ascending order. + * Otherwise the results may be returned in any order. + */ + virtual void + setSortedResults (bool sorted); + + /** \brief Gets whether the results should be sorted (ascending in the distance) or not + * Otherwise the results may be returned in any order. + */ + virtual bool + getSortedResults (); + + + /** \brief Pass the input dataset that the search will be performed on. + * \param[in] cloud a const pointer to the PointCloud data + * \param[in] indices the point indices subset that is to be used from the cloud + */ + virtual void + setInputCloud (const PointCloudConstPtr& cloud, + const IndicesConstPtr &indices = IndicesConstPtr ()); + + /** \brief Get a pointer to the input point cloud dataset. */ + virtual PointCloudConstPtr + getInputCloud () const + { + return (input_); + } + + /** \brief Get a pointer to the vector of indices used. */ + virtual IndicesConstPtr + getIndices () const + { + return (indices_); + } + + /** \brief Search for the k-nearest neighbors for the given query point. + * \param[in] point the given query point + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + */ + virtual int + nearestKSearch (const PointT &point, int k, std::vector &k_indices, + std::vector &k_sqr_distances) const = 0; + + /** \brief Search for k-nearest neighbors for the given query point. + * This method accepts a different template parameter for the point type. + * \param[in] point the given query point + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + */ + template inline int + nearestKSearchT (const PointTDiff &point, int k, + std::vector &k_indices, std::vector &k_sqr_distances) const + { + PointT p; + copyPoint (point, p); + return (nearestKSearch (p, k, k_indices, k_sqr_distances)); + } + + /** \brief Search for k-nearest neighbors for the given query point. + * + * \attention This method does not do any bounds checking for the input index + * (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data. + * + * \param[in] cloud the point cloud data + * \param[in] index a \a valid index in \a cloud representing a \a valid (i.e., finite) query point + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * + * \return number of neighbors found + * + * \exception asserts in debug mode if the index is not between 0 and the maximum number of points + */ + virtual int + nearestKSearch (const PointCloud &cloud, int index, int k, + std::vector &k_indices, + std::vector &k_sqr_distances) const; + + /** \brief Search for k-nearest neighbors for the given query point (zero-copy). + * + * \attention This method does not do any bounds checking for the input index + * (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data. + * + * \param[in] index a \a valid index representing a \a valid query point in the dataset given + * by \a setInputCloud. If indices were given in setInputCloud, index will be the position in + * the indices vector. + * + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points (must be resized to \a k a priori!) + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points (must be resized to \a k + * a priori!) + * \return number of neighbors found + * + * \exception asserts in debug mode if the index is not between 0 and the maximum number of points + */ + virtual int + nearestKSearch (int index, int k, + std::vector &k_indices, + std::vector &k_sqr_distances) const; + + /** \brief Search for the k-nearest neighbors for the given query point. + * \param[in] cloud the point cloud data + * \param[in] indices a vector of point cloud indices to query for nearest neighbors + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points, k_indices[i] corresponds to the neighbors of the query point i + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points, k_sqr_distances[i] corresponds to the neighbors of the query point i + */ + virtual void + nearestKSearch (const PointCloud& cloud, const std::vector& indices, + int k, std::vector< std::vector >& k_indices, + std::vector< std::vector >& k_sqr_distances) const; + + /** \brief Search for the k-nearest neighbors for the given query point. Use this method if the query points are of a different type than the points in the data set (e.g. PointXYZRGBA instead of PointXYZ). + * \param[in] cloud the point cloud data + * \param[in] indices a vector of point cloud indices to query for nearest neighbors + * \param[in] k the number of neighbors to search for + * \param[out] k_indices the resultant indices of the neighboring points, k_indices[i] corresponds to the neighbors of the query point i + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points, k_sqr_distances[i] corresponds to the neighbors of the query point i + * \note This method copies the input point cloud of type PointTDiff to a temporary cloud of type PointT and performs the batch search on the new cloud. You should prefer the single-point search if you don't use a search algorithm that accelerates batch NN search. + */ + template void + nearestKSearchT (const pcl::PointCloud &cloud, const std::vector& indices, int k, std::vector< std::vector > &k_indices, + std::vector< std::vector > &k_sqr_distances) const + { + // Copy all the data fields from the input cloud to the output one + typedef typename pcl::traits::fieldList::type FieldListInT; + typedef typename pcl::traits::fieldList::type FieldListOutT; + typedef typename pcl::intersect::type FieldList; + + pcl::PointCloud pc; + if (indices.empty ()) + { + pc.resize (cloud.size()); + for (size_t i = 0; i < cloud.size(); i++) + { + pcl::for_each_type (pcl::NdConcatenateFunctor ( + cloud[i], pc[i])); + } + nearestKSearch (pc,std::vector(),k,k_indices,k_sqr_distances); + } + else + { + pc.resize (indices.size()); + for (size_t i = 0; i < indices.size(); i++) + { + pcl::for_each_type (pcl::NdConcatenateFunctor ( + cloud[indices[i]], pc[i])); + } + nearestKSearch (pc,std::vector(),k,k_indices,k_sqr_distances); + } + } + + /** \brief Search for all the nearest neighbors of the query point in a given radius. + * \param[in] point the given query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + * \return number of neighbors found in radius + */ + virtual int + radiusSearch (const PointT& point, double radius, std::vector& k_indices, + std::vector& k_sqr_distances, unsigned int max_nn = 0) const = 0; + + /** \brief Search for all the nearest neighbors of the query point in a given radius. + * \param[in] point the given query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + * \return number of neighbors found in radius + */ + template inline int + radiusSearchT (const PointTDiff &point, double radius, std::vector &k_indices, + std::vector &k_sqr_distances, unsigned int max_nn = 0) const + { + PointT p; + copyPoint (point, p); + return (radiusSearch (p, radius, k_indices, k_sqr_distances, max_nn)); + } + + /** \brief Search for all the nearest neighbors of the query point in a given radius. + * + * \attention This method does not do any bounds checking for the input index + * (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data. + * + * \param[in] cloud the point cloud data + * \param[in] index a \a valid index in \a cloud representing a \a valid (i.e., finite) query point + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + * \return number of neighbors found in radius + * + * \exception asserts in debug mode if the index is not between 0 and the maximum number of points + */ + virtual int + radiusSearch (const PointCloud &cloud, int index, double radius, + std::vector &k_indices, std::vector &k_sqr_distances, + unsigned int max_nn = 0) const; + + /** \brief Search for all the nearest neighbors of the query point in a given radius (zero-copy). + * + * \attention This method does not do any bounds checking for the input index + * (i.e., index >= cloud.points.size () || index < 0), and assumes valid (i.e., finite) data. + * + * \param[in] index a \a valid index representing a \a valid query point in the dataset given + * by \a setInputCloud. If indices were given in setInputCloud, index will be the position in + * the indices vector. + * + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + * \return number of neighbors found in radius + * + * \exception asserts in debug mode if the index is not between 0 and the maximum number of points + */ + virtual int + radiusSearch (int index, double radius, std::vector &k_indices, + std::vector &k_sqr_distances, unsigned int max_nn = 0) const; + + /** \brief Search for all the nearest neighbors of the query point in a given radius. + * \param[in] cloud the point cloud data + * \param[in] indices the indices in \a cloud. If indices is empty, neighbors will be searched for all points. + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points, k_indices[i] corresponds to the neighbors of the query point i + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points, k_sqr_distances[i] corresponds to the neighbors of the query point i + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + */ + virtual void + radiusSearch (const PointCloud& cloud, + const std::vector& indices, + double radius, + std::vector< std::vector >& k_indices, + std::vector< std::vector > &k_sqr_distances, + unsigned int max_nn = 0) const; + + /** \brief Search for all the nearest neighbors of the query points in a given radius. + * \param[in] cloud the point cloud data + * \param[in] indices a vector of point cloud indices to query for nearest neighbors + * \param[in] radius the radius of the sphere bounding all of p_q's neighbors + * \param[out] k_indices the resultant indices of the neighboring points, k_indices[i] corresponds to the neighbors of the query point i + * \param[out] k_sqr_distances the resultant squared distances to the neighboring points, k_sqr_distances[i] corresponds to the neighbors of the query point i + * \param[in] max_nn if given, bounds the maximum returned neighbors to this value. If \a max_nn is set to + * 0 or to a number higher than the number of points in the input cloud, all neighbors in \a radius will be + * returned. + * \note This method copies the input point cloud of type PointTDiff to a temporary cloud of type PointT and performs the batch search on the new cloud. You should prefer the single-point search if you don't use a search algorithm that accelerates batch NN search. + */ + template void + radiusSearchT (const pcl::PointCloud &cloud, + const std::vector& indices, + double radius, + std::vector< std::vector > &k_indices, + std::vector< std::vector > &k_sqr_distances, + unsigned int max_nn = 0) const + { + // Copy all the data fields from the input cloud to the output one + typedef typename pcl::traits::fieldList::type FieldListInT; + typedef typename pcl::traits::fieldList::type FieldListOutT; + typedef typename pcl::intersect::type FieldList; + + pcl::PointCloud pc; + if (indices.empty ()) + { + pc.resize (cloud.size ()); + for (size_t i = 0; i < cloud.size (); ++i) + pcl::for_each_type (pcl::NdConcatenateFunctor (cloud[i], pc[i])); + radiusSearch (pc, std::vector (), radius, k_indices, k_sqr_distances, max_nn); + } + else + { + pc.resize (indices.size ()); + for (size_t i = 0; i < indices.size (); ++i) + pcl::for_each_type (pcl::NdConcatenateFunctor (cloud[indices[i]], pc[i])); + radiusSearch (pc, std::vector(), radius, k_indices, k_sqr_distances, max_nn); + } + } + + protected: + void + sortResults (std::vector& indices, std::vector& distances) const; + + PointCloudConstPtr input_; + IndicesConstPtr indices_; + bool sorted_results_; + std::string name_; + + private: + struct Compare + { + Compare (const std::vector& distances) + : distances_ (distances) + { + } + + bool + operator () (int first, int second) const + { + return (distances_ [first] < distances_[second]); + } + + const std::vector& distances_; + }; + }; // class Search + } // namespace search +} // namespace pcl + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef _PCL_SEARCH_SEARCH_H_ diff --git a/pcl-1.7/pcl/segmentation/approximate_progressive_morphological_filter.h b/pcl-1.7/pcl/segmentation/approximate_progressive_morphological_filter.h new file mode 100644 index 0000000..88101e4 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/approximate_progressive_morphological_filter.h @@ -0,0 +1,178 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2014, RadiantBlue Technologies, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_APPROXIMATE_PROGRESSIVE_MORPHOLOGICAL_FILTER_H_ +#define PCL_APPROXIMATE_PROGRESSIVE_MORPHOLOGICAL_FILTER_H_ + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief + * Implements the Progressive Morphological Filter for segmentation of ground points. + * Description can be found in the article + * "A Progressive Morphological Filter for Removing Nonground Measurements from + * Airborne LIDAR Data" + * by K. Zhang, S. Chen, D. Whitman, M. Shyu, J. Yan, and C. Zhang. + */ + template + class PCL_EXPORTS ApproximateProgressiveMorphologicalFilter : public pcl::PCLBase + { + public: + + typedef pcl::PointCloud PointCloud; + + using PCLBase ::input_; + using PCLBase ::indices_; + using PCLBase ::initCompute; + using PCLBase ::deinitCompute; + + public: + + /** \brief Constructor that sets default values for member variables. */ + ApproximateProgressiveMorphologicalFilter (); + + virtual + ~ApproximateProgressiveMorphologicalFilter (); + + /** \brief Get the maximum window size to be used in filtering ground returns. */ + inline int + getMaxWindowSize () const { return (max_window_size_); } + + /** \brief Set the maximum window size to be used in filtering ground returns. */ + inline void + setMaxWindowSize (int max_window_size) { max_window_size_ = max_window_size; } + + /** \brief Get the slope value to be used in computing the height threshold. */ + inline float + getSlope () const { return (slope_); } + + /** \brief Set the slope value to be used in computing the height threshold. */ + inline void + setSlope (float slope) { slope_ = slope; } + + /** \brief Get the maximum height above the parameterized ground surface to be considered a ground return. */ + inline float + getMaxDistance () const { return (max_distance_); } + + /** \brief Set the maximum height above the parameterized ground surface to be considered a ground return. */ + inline void + setMaxDistance (float max_distance) { max_distance_ = max_distance; } + + /** \brief Get the initial height above the parameterized ground surface to be considered a ground return. */ + inline float + getInitialDistance () const { return (initial_distance_); } + + /** \brief Set the initial height above the parameterized ground surface to be considered a ground return. */ + inline void + setInitialDistance (float initial_distance) { initial_distance_ = initial_distance; } + + /** \brief Get the cell size. */ + inline float + getCellSize () const { return (cell_size_); } + + /** \brief Set the cell size. */ + inline void + setCellSize (float cell_size) { cell_size_ = cell_size; } + + /** \brief Get the base to be used in computing progressive window sizes. */ + inline float + getBase () const { return (base_); } + + /** \brief Set the base to be used in computing progressive window sizes. */ + inline void + setBase (float base) { base_ = base; } + + /** \brief Get flag indicating whether or not to exponentially grow window sizes? */ + inline bool + getExponential () const { return (exponential_); } + + /** \brief Set flag indicating whether or not to exponentially grow window sizes? */ + inline void + setExponential (bool exponential) { exponential_ = exponential; } + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + + /** \brief This method launches the segmentation algorithm and returns indices of + * points determined to be ground returns. + * \param[out] ground indices of points determined to be ground returns. + */ + virtual void + extract (std::vector& ground); + + protected: + + /** \brief Maximum window size to be used in filtering ground returns. */ + int max_window_size_; + + /** \brief Slope value to be used in computing the height threshold. */ + float slope_; + + /** \brief Maximum height above the parameterized ground surface to be considered a ground return. */ + float max_distance_; + + /** \brief Initial height above the parameterized ground surface to be considered a ground return. */ + float initial_distance_; + + /** \brief Cell size. */ + float cell_size_; + + /** \brief Base to be used in computing progressive window sizes. */ + float base_; + + /** \brief Exponentially grow window sizes? */ + bool exponential_; + + /** \brief Number of threads to be used. */ + unsigned int threads_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif + diff --git a/pcl-1.7/pcl/segmentation/boost.h b/pcl-1.7/pcl/segmentation/boost.h new file mode 100644 index 0000000..f2baa9f --- /dev/null +++ b/pcl-1.7/pcl/segmentation/boost.h @@ -0,0 +1,61 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: io.h 5850 2012-06-06 14:04:59Z stfox88 $ + * + */ + +#ifndef PCL_SEGMENTATION_BOOST_H_ +#define PCL_SEGMENTATION_BOOST_H_ + +#ifdef __GNUC__ +#pragma GCC system_header +#endif + +#ifndef Q_MOC_RUN +// Marking all Boost headers as system headers to remove warnings +#include +#include +#include +#include +#include + +#if (BOOST_VERSION >= 104400) + #include +#endif +#endif + +#endif // PCL_SEGMENTATION_BOOST_H_ diff --git a/pcl-1.7/pcl/segmentation/comparator.h b/pcl-1.7/pcl/segmentation/comparator.h new file mode 100644 index 0000000..79b76f1 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/comparator.h @@ -0,0 +1,103 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + * + */ + +#ifndef PCL_SEGMENTATION_COMPARATOR_H_ +#define PCL_SEGMENTATION_COMPARATOR_H_ + +#include + +namespace pcl +{ + /** \brief Comparator is the base class for comparators that compare two points given some function. + * Currently intended for use with OrganizedConnectedComponentSegmentation + * + * \author Alex Trevor + */ + template + class Comparator + { + public: + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Empty constructor for comparator. */ + Comparator () : input_ () + { + } + + /** \brief Empty destructor for comparator. */ + virtual + ~Comparator () + { + } + + /** \brief Set the input cloud for the comparator. + * \param[in] cloud the point cloud this comparator will operate on + */ + virtual void + setInputCloud (const PointCloudConstPtr& cloud) + { + input_ = cloud; + } + + /** \brief Get the input cloud this comparator operates on. */ + virtual PointCloudConstPtr + getInputCloud () const + { + return (input_); + } + + /** \brief Compares the two points in the input cloud designated by these two indices. + * This is pure virtual and must be implemented by subclasses with some comparison function. + * \param[in] idx1 the index of the first point. + * \param[in] idx2 the index of the second point. + */ + virtual bool + compare (int idx1, int idx2) const = 0; + + protected: + PointCloudConstPtr input_; + }; +} + +#endif //#ifndef _PCL_SEGMENTATION_COMPARATOR_H_ diff --git a/pcl-1.7/pcl/segmentation/conditional_euclidean_clustering.h b/pcl-1.7/pcl/segmentation/conditional_euclidean_clustering.h new file mode 100644 index 0000000..a709df4 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/conditional_euclidean_clustering.h @@ -0,0 +1,244 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SEGMENTATION_CONDITIONAL_EUCLIDEAN_CLUSTERING_H_ +#define PCL_SEGMENTATION_CONDITIONAL_EUCLIDEAN_CLUSTERING_H_ + +#include +#include + +namespace pcl +{ + typedef std::vector IndicesClusters; + typedef boost::shared_ptr > IndicesClustersPtr; + + /** \brief @b ConditionalEuclideanClustering performs segmentation based on Euclidean distance and a user-defined clustering condition. + * \details The condition that need to hold is currently passed using a function pointer. + * For more information check the documentation of setConditionFunction() or the usage example below: + * \code + * bool + * enforceIntensitySimilarity (const pcl::PointXYZI& point_a, const pcl::PointXYZI& point_b, float squared_distance) + * { + * if (fabs (point_a.intensity - point_b.intensity) < 0.1f) + * return (true); + * else + * return (false); + * } + * // ... + * // Somewhere down to the main code + * // ... + * pcl::ConditionalEuclideanClustering cec (true); + * cec.setInputCloud (cloud_in); + * cec.setConditionFunction (&enforceIntensitySimilarity); + * // Points within this distance from one another are going to need to validate the enforceIntensitySimilarity function to be part of the same cluster: + * cec.setClusterTolerance (0.09f); + * // Size constraints for the clusters: + * cec.setMinClusterSize (5); + * cec.setMaxClusterSize (30); + * // The resulting clusters (an array of pointindices): + * cec.segment (*clusters); + * // The clusters that are too small or too large in size can also be extracted separately: + * cec.getRemovedClusters (small_clusters, large_clusters); + * \endcode + * \author Frits Florentinus + * \ingroup segmentation + */ + template + class ConditionalEuclideanClustering : public PCLBase + { + protected: + typedef typename pcl::search::Search::Ptr SearcherPtr; + + using PCLBase::input_; + using PCLBase::indices_; + using PCLBase::initCompute; + using PCLBase::deinitCompute; + + public: + /** \brief Constructor. + * \param[in] extract_removed_clusters Set to true if you want to be able to extract the clusters that are too large or too small (default = false) + */ + ConditionalEuclideanClustering (bool extract_removed_clusters = false) : + searcher_ (), + condition_function_ (), + cluster_tolerance_ (0.0f), + min_cluster_size_ (1), + max_cluster_size_ (std::numeric_limits::max ()), + extract_removed_clusters_ (extract_removed_clusters), + small_clusters_ (new pcl::IndicesClusters), + large_clusters_ (new pcl::IndicesClusters) + { + } + + /** \brief Set the condition that needs to hold for neighboring points to be considered part of the same cluster. + * \details Any two points within a certain distance from one another will need to evaluate this condition in order to be made part of the same cluster. + * The distance can be set using setClusterTolerance(). + *
+ * Note that for a point to be part of a cluster, the condition only needs to hold for at least 1 point pair. + * To clarify, the following statement is false: + * Any two points within a cluster always evaluate this condition function to true. + *

+ * The input arguments of the condition function are: + *
    + *
  • PointT The first point of the point pair
  • + *
  • PointT The second point of the point pair
  • + *
  • float The squared distance between the points
  • + *
+ * The output argument is a boolean, returning true will merge the second point into the cluster of the first point. + * \param[in] condition_function The condition function that needs to hold for clustering + */ + inline void + setConditionFunction (bool (*condition_function) (const PointT&, const PointT&, float)) + { + condition_function_ = condition_function; + } + + /** \brief Set the spatial tolerance for new cluster candidates. + * \details Any two points within this distance from one another will need to evaluate a certain condition in order to be made part of the same cluster. + * The condition can be set using setConditionFunction(). + * \param[in] cluster_tolerance The distance to scan for cluster candidates (default = 0.0) + */ + inline void + setClusterTolerance (float cluster_tolerance) + { + cluster_tolerance_ = cluster_tolerance; + } + + /** \brief Get the spatial tolerance for new cluster candidates.*/ + inline float + getClusterTolerance () + { + return (cluster_tolerance_); + } + + /** \brief Set the minimum number of points that a cluster needs to contain in order to be considered valid. + * \param[in] min_cluster_size The minimum cluster size (default = 1) + */ + inline void + setMinClusterSize (int min_cluster_size) + { + min_cluster_size_ = min_cluster_size; + } + + /** \brief Get the minimum number of points that a cluster needs to contain in order to be considered valid.*/ + inline int + getMinClusterSize () + { + return (min_cluster_size_); + } + + /** \brief Set the maximum number of points that a cluster needs to contain in order to be considered valid. + * \param[in] max_cluster_size The maximum cluster size (default = unlimited) + */ + inline void + setMaxClusterSize (int max_cluster_size) + { + max_cluster_size_ = max_cluster_size; + } + + /** \brief Get the maximum number of points that a cluster needs to contain in order to be considered valid.*/ + inline int + getMaxClusterSize () + { + return (max_cluster_size_); + } + + /** \brief Segment the input into separate clusters. + * \details The input can be set using setInputCloud() and setIndices(). + *
+ * The size constraints for the resulting clusters can be set using setMinClusterSize() and setMaxClusterSize(). + *
+ * The region growing parameters can be set using setConditionFunction() and setClusterTolerance(). + *
+ * \param[out] clusters The resultant set of indices, indexing the points of the input cloud that correspond to the clusters + */ + void + segment (IndicesClusters &clusters); + + /** \brief Get the clusters that are invalidated due to size constraints. + * \note The constructor of this class needs to be initialized with true, and the segment method needs to have been called prior to using this method. + * \param[out] small_clusters The resultant clusters that contain less than min_cluster_size points + * \param[out] large_clusters The resultant clusters that contain more than max_cluster_size points + */ + inline void + getRemovedClusters (IndicesClustersPtr &small_clusters, IndicesClustersPtr &large_clusters) + { + if (!extract_removed_clusters_) + { + PCL_WARN("[pcl::ConditionalEuclideanClustering::getRemovedClusters] You need to set extract_removed_clusters to true (in this class' constructor) if you want to use this functionality.\n"); + return; + } + small_clusters = small_clusters_; + large_clusters = large_clusters_; + } + + private: + /** \brief A pointer to the spatial search object */ + SearcherPtr searcher_; + + /** \brief The condition function that needs to hold for clustering */ + bool (*condition_function_) (const PointT&, const PointT&, float); + + /** \brief The distance to scan for cluster candidates (default = 0.0) */ + float cluster_tolerance_; + + /** \brief The minimum cluster size (default = 1) */ + int min_cluster_size_; + + /** \brief The maximum cluster size (default = unlimited) */ + int max_cluster_size_; + + /** \brief Set to true if you want to be able to extract the clusters that are too large or too small (default = false) */ + bool extract_removed_clusters_; + + /** \brief The resultant clusters that contain less than min_cluster_size points */ + pcl::IndicesClustersPtr small_clusters_; + + /** \brief The resultant clusters that contain more than max_cluster_size points */ + pcl::IndicesClustersPtr large_clusters_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_SEGMENTATION_CONDITIONAL_EUCLIDEAN_CLUSTERING_H_ + diff --git a/pcl-1.7/pcl/segmentation/crf_normal_segmentation.h b/pcl-1.7/pcl/segmentation/crf_normal_segmentation.h new file mode 100644 index 0000000..d51606b --- /dev/null +++ b/pcl-1.7/pcl/segmentation/crf_normal_segmentation.h @@ -0,0 +1,83 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_CRF_NORMAL_SEGMENTATION_H_ +#define PCL_CRF_NORMAL_SEGMENTATION_H_ + +#include + +namespace pcl +{ + /** \brief + * \author Christian Potthast + * + */ + template + class PCL_EXPORTS CrfNormalSegmentation + { + public: + + /** \brief Constructor that sets default values for member variables. */ + CrfNormalSegmentation (); + + /** \brief Destructor that frees memory. */ + ~CrfNormalSegmentation (); + + /** \brief This method sets the input cloud. + * \param[in] input_cloud input point cloud + */ + void + setCloud (typename pcl::PointCloud::Ptr input_cloud); + + /** \brief This method simply launches the segmentation algorithm */ + void + segmentPoints (); + + protected: + + protected: + + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/segmentation/edge_aware_plane_comparator.h b/pcl-1.7/pcl/segmentation/edge_aware_plane_comparator.h new file mode 100644 index 0000000..fb91542 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/edge_aware_plane_comparator.h @@ -0,0 +1,214 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: extract_clusters.h 5027 2012-03-12 03:10:45Z rusu $ + * + */ + +#ifndef PCL_SEGMENTATION_EDGE_AWARE_PLANE_COMPARATOR_H_ +#define PCL_SEGMENTATION_EDGE_AWARE_PLANE_COMPARATOR_H_ + +#include +#include + +namespace pcl +{ + /** \brief EdgeAwarePlaneComparator is a Comparator that operates on plane coefficients, + * for use in planar segmentation. + * In conjunction with OrganizedConnectedComponentSegmentation, this allows planes to be segmented from organized data. + * + * \author Stefan Holzer, Alex Trevor + */ + template + class EdgeAwarePlaneComparator: public PlaneCoefficientComparator + { + public: + typedef typename Comparator::PointCloud PointCloud; + typedef typename Comparator::PointCloudConstPtr PointCloudConstPtr; + + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using pcl::PlaneCoefficientComparator::input_; + using pcl::PlaneCoefficientComparator::normals_; + using pcl::PlaneCoefficientComparator::plane_coeff_d_; + using pcl::PlaneCoefficientComparator::angular_threshold_; + using pcl::PlaneCoefficientComparator::distance_threshold_; + using pcl::PlaneCoefficientComparator::depth_dependent_; + using pcl::PlaneCoefficientComparator::z_axis_; + + /** \brief Empty constructor for PlaneCoefficientComparator. */ + EdgeAwarePlaneComparator () : + distance_map_threshold_ (5), + curvature_threshold_ (0.04f), + euclidean_distance_threshold_ (0.04f) + { + } + + /** \brief Empty constructor for PlaneCoefficientComparator. + * \param[in] distance_map the distance map to use + */ + EdgeAwarePlaneComparator (const float *distance_map) : + distance_map_ (distance_map), + distance_map_threshold_ (5), + curvature_threshold_ (0.04f), + euclidean_distance_threshold_ (0.04f) + { + } + + /** \brief Destructor for PlaneCoefficientComparator. */ + virtual + ~EdgeAwarePlaneComparator () + { + } + + /** \brief Set a distance map to use. For an example of a valid distance map see + * \ref OrganizedIntegralImageNormalEstimation + * \param[in] distance_map the distance map to use + */ + inline void + setDistanceMap (const float *distance_map) + { + distance_map_ = distance_map; + } + + /** \brief Return the distance map used. */ + const float* + getDistanceMap () const + { + return (distance_map_); + } + + /** \brief Set the curvature threshold for creating a new segment + * \param[in] curvature_threshold a threshold for the curvature + */ + void + setCurvatureThreshold (float curvature_threshold) + { + curvature_threshold_ = curvature_threshold; + } + + /** \brief Get the curvature threshold. */ + inline float + getCurvatureThreshold () const + { + return (curvature_threshold_); + } + + /** \brief Set the distance map threshold -- the number of pixel away from a border / nan + * \param[in] distance_map_threshold the distance map threshold + */ + void + setDistanceMapThreshold (float distance_map_threshold) + { + distance_map_threshold_ = distance_map_threshold; + } + + /** \brief Get the distance map threshold (in pixels). */ + inline float + getDistanceMapThreshold () const + { + return (distance_map_threshold_); + } + + /** \brief Set the euclidean distance threshold. + * \param[in] euclidean_distance_threshold the euclidean distance threshold in meters + */ + void + setEuclideanDistanceThreshold (float euclidean_distance_threshold) + { + euclidean_distance_threshold_ = euclidean_distance_threshold; + } + + /** \brief Get the euclidean distance threshold. */ + inline float + getEuclideanDistanceThreshold () const + { + return (euclidean_distance_threshold_); + } + + protected: + /** \brief Compare two neighboring points, by using normal information, curvature, and euclidean distance information. + * \param[in] idx1 The index of the first point. + * \param[in] idx2 The index of the second point. + */ + bool + compare (int idx1, int idx2) const + { + // Note: there are two distance thresholds here that make sense to scale with depth. + // dist_threshold is on the perpendicular distance to the plane, as in plane comparator + // We additionally check euclidean distance to ensure that we don't have neighboring coplanar points + // that aren't close in euclidean space (think two tables separated by a meter, viewed from an angle + // where the surfaces are adjacent in image space). + float dist_threshold = distance_threshold_; + float euclidean_dist_threshold = euclidean_distance_threshold_; + if (depth_dependent_) + { + Eigen::Vector3f vec = input_->points[idx1].getVector3fMap (); + float z = vec.dot (z_axis_); + dist_threshold *= z * z; + euclidean_dist_threshold *= z * z; + } + + float dx = input_->points[idx1].x - input_->points[idx2].x; + float dy = input_->points[idx1].y - input_->points[idx2].y; + float dz = input_->points[idx1].z - input_->points[idx2].z; + float dist = sqrtf (dx*dx + dy*dy + dz*dz); + + bool normal_ok = (normals_->points[idx1].getNormalVector3fMap ().dot (normals_->points[idx2].getNormalVector3fMap () ) > angular_threshold_ ); + bool dist_ok = (dist < euclidean_dist_threshold); + + bool curvature_ok = normals_->points[idx1].curvature < curvature_threshold_; + bool plane_d_ok = fabs ((*plane_coeff_d_)[idx1] - (*plane_coeff_d_)[idx2]) < dist_threshold; + + if (distance_map_[idx1] < distance_map_threshold_) + curvature_ok = false; + + return (dist_ok && normal_ok && curvature_ok && plane_d_ok); + } + + protected: + const float* distance_map_; + int distance_map_threshold_; + float curvature_threshold_; + float euclidean_distance_threshold_; + }; +} + +#endif // PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ diff --git a/pcl-1.7/pcl/segmentation/euclidean_cluster_comparator.h b/pcl-1.7/pcl/segmentation/euclidean_cluster_comparator.h new file mode 100644 index 0000000..1f11ec6 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/euclidean_cluster_comparator.h @@ -0,0 +1,210 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + * + */ + +#ifndef PCL_SEGMENTATION_EUCLIDEAN_CLUSTER_COMPARATOR_H_ +#define PCL_SEGMENTATION_EUCLIDEAN_CLUSTER_COMPARATOR_H_ + +#include +#include + +namespace pcl +{ + /** \brief EuclideanClusterComparator is a comparator used for finding clusters supported by planar surfaces. + * This needs to be run as a second pass after extracting planar surfaces, using MultiPlaneSegmentation for example. + * + * \author Alex Trevor + */ + template + class EuclideanClusterComparator: public Comparator + { + public: + typedef typename Comparator::PointCloud PointCloud; + typedef typename Comparator::PointCloudConstPtr PointCloudConstPtr; + + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + + typedef typename pcl::PointCloud PointCloudL; + typedef typename PointCloudL::Ptr PointCloudLPtr; + typedef typename PointCloudL::ConstPtr PointCloudLConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using pcl::Comparator::input_; + + /** \brief Empty constructor for EuclideanClusterComparator. */ + EuclideanClusterComparator () + : normals_ () + , angular_threshold_ (0.0f) + , distance_threshold_ (0.005f) + , depth_dependent_ () + , z_axis_ () + { + } + + /** \brief Destructor for EuclideanClusterComparator. */ + virtual + ~EuclideanClusterComparator () + { + } + + virtual void + setInputCloud (const PointCloudConstPtr& cloud) + { + input_ = cloud; + Eigen::Matrix3f rot = input_->sensor_orientation_.toRotationMatrix (); + z_axis_ = rot.col (2); + } + + /** \brief Provide a pointer to the input normals. + * \param[in] normals the input normal cloud + */ + inline void + setInputNormals (const PointCloudNConstPtr &normals) + { + normals_ = normals; + } + + /** \brief Get the input normals. */ + inline PointCloudNConstPtr + getInputNormals () const + { + return (normals_); + } + + /** \brief Set the tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane. + * \param[in] angular_threshold the tolerance in radians + */ + virtual inline void + setAngularThreshold (float angular_threshold) + { + angular_threshold_ = cosf (angular_threshold); + } + + /** \brief Get the angular threshold in radians for difference in normal direction between neighboring points, to be considered part of the same plane. */ + inline float + getAngularThreshold () const + { + return (acos (angular_threshold_) ); + } + + /** \brief Set the tolerance in meters for difference in perpendicular distance (d component of plane equation) to the plane between neighboring points, to be considered part of the same plane. + * \param[in] distance_threshold the tolerance in meters + * \param depth_dependent + */ + inline void + setDistanceThreshold (float distance_threshold, bool depth_dependent) + { + distance_threshold_ = distance_threshold; + depth_dependent_ = depth_dependent; + } + + /** \brief Get the distance threshold in meters (d component of plane equation) between neighboring points, to be considered part of the same plane. */ + inline float + getDistanceThreshold () const + { + return (distance_threshold_); + } + + /** \brief Set label cloud + * \param[in] labels The label cloud + */ + void + setLabels (PointCloudLPtr& labels) + { + labels_ = labels; + } + + /** \brief Set labels in the label cloud to exclude. + * \param exclude_labels a vector of bools corresponding to whether or not a given label should be considered + */ + void + setExcludeLabels (std::vector& exclude_labels) + { + exclude_labels_ = boost::make_shared >(exclude_labels); + } + + /** \brief Compare points at two indices by their plane equations. True if the angle between the normals is less than the angular threshold, + * and the difference between the d component of the normals is less than distance threshold, else false + * \param idx1 The first index for the comparison + * \param idx2 The second index for the comparison + */ + virtual bool + compare (int idx1, int idx2) const + { + int label1 = labels_->points[idx1].label; + int label2 = labels_->points[idx2].label; + + if (label1 == -1 || label2 == -1) + return false; + + if ( (*exclude_labels_)[label1] || (*exclude_labels_)[label2]) + return false; + + float dist_threshold = distance_threshold_; + if (depth_dependent_) + { + Eigen::Vector3f vec = input_->points[idx1].getVector3fMap (); + float z = vec.dot (z_axis_); + dist_threshold *= z * z; + } + + float dx = input_->points[idx1].x - input_->points[idx2].x; + float dy = input_->points[idx1].y - input_->points[idx2].y; + float dz = input_->points[idx1].z - input_->points[idx2].z; + float dist = sqrtf (dx*dx + dy*dy + dz*dz); + + return (dist < dist_threshold); + } + + protected: + PointCloudNConstPtr normals_; + PointCloudLPtr labels_; + + boost::shared_ptr > exclude_labels_; + float angular_threshold_; + float distance_threshold_; + bool depth_dependent_; + Eigen::Vector3f z_axis_; + }; +} + +#endif // PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ diff --git a/pcl-1.7/pcl/segmentation/euclidean_plane_coefficient_comparator.h b/pcl-1.7/pcl/segmentation/euclidean_plane_coefficient_comparator.h new file mode 100644 index 0000000..4f22138 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/euclidean_plane_coefficient_comparator.h @@ -0,0 +1,101 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + * + */ + +#ifndef PCL_EUCLIDEAN_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ +#define PCL_EUCLIDEAN_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ + +#include +#include + +namespace pcl +{ + /** \brief EuclideanPlaneCoefficientComparator is a Comparator that operates on plane coefficients, + * for use in planar segmentation. + * In conjunction with OrganizedConnectedComponentSegmentation, this allows planes to be segmented from organized data. + * + * \author Alex Trevor + */ + template + class EuclideanPlaneCoefficientComparator: public PlaneCoefficientComparator + { + public: + typedef typename Comparator::PointCloud PointCloud; + typedef typename Comparator::PointCloudConstPtr PointCloudConstPtr; + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using pcl::Comparator::input_; + using pcl::PlaneCoefficientComparator::normals_; + using pcl::PlaneCoefficientComparator::angular_threshold_; + using pcl::PlaneCoefficientComparator::distance_threshold_; + + /** \brief Empty constructor for PlaneCoefficientComparator. */ + EuclideanPlaneCoefficientComparator () + { + } + + /** \brief Destructor for PlaneCoefficientComparator. */ + virtual + ~EuclideanPlaneCoefficientComparator () + { + } + + /** \brief Compare two neighboring points, by using normal information, and euclidean distance information. + * \param[in] idx1 The index of the first point. + * \param[in] idx2 The index of the second point. + */ + virtual bool + compare (int idx1, int idx2) const + { + float dx = input_->points[idx1].x - input_->points[idx2].x; + float dy = input_->points[idx1].y - input_->points[idx2].y; + float dz = input_->points[idx1].z - input_->points[idx2].z; + float dist = sqrtf (dx*dx + dy*dy + dz*dz); + + return ( (dist < distance_threshold_) + && (normals_->points[idx1].getNormalVector3fMap ().dot (normals_->points[idx2].getNormalVector3fMap () ) > angular_threshold_ ) ); + } + }; +} + +#endif // PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ diff --git a/pcl-1.7/pcl/segmentation/extract_clusters.h b/pcl-1.7/pcl/segmentation/extract_clusters.h new file mode 100644 index 0000000..841c451 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/extract_clusters.h @@ -0,0 +1,428 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_EXTRACT_CLUSTERS_H_ +#define PCL_EXTRACT_CLUSTERS_H_ + +#include + +#include + +namespace pcl +{ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Decompose a region of space into clusters based on the Euclidean distance between points + * \param cloud the point cloud message + * \param tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching + * \note the tree has to be created as a spatial locator on \a cloud + * \param tolerance the spatial cluster tolerance as a measure in L2 Euclidean space + * \param clusters the resultant clusters containing point indices (as a vector of PointIndices) + * \param min_pts_per_cluster minimum number of points that a cluster may contain (default: 1) + * \param max_pts_per_cluster maximum number of points that a cluster may contain (default: max int) + * \ingroup segmentation + */ + template void + extractEuclideanClusters ( + const PointCloud &cloud, const boost::shared_ptr > &tree, + float tolerance, std::vector &clusters, + unsigned int min_pts_per_cluster = 1, unsigned int max_pts_per_cluster = (std::numeric_limits::max) ()); + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Decompose a region of space into clusters based on the Euclidean distance between points + * \param cloud the point cloud message + * \param indices a list of point indices to use from \a cloud + * \param tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching + * \note the tree has to be created as a spatial locator on \a cloud and \a indices + * \param tolerance the spatial cluster tolerance as a measure in L2 Euclidean space + * \param clusters the resultant clusters containing point indices (as a vector of PointIndices) + * \param min_pts_per_cluster minimum number of points that a cluster may contain (default: 1) + * \param max_pts_per_cluster maximum number of points that a cluster may contain (default: max int) + * \ingroup segmentation + */ + template void + extractEuclideanClusters ( + const PointCloud &cloud, const std::vector &indices, + const boost::shared_ptr > &tree, float tolerance, std::vector &clusters, + unsigned int min_pts_per_cluster = 1, unsigned int max_pts_per_cluster = (std::numeric_limits::max) ()); + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Decompose a region of space into clusters based on the euclidean distance between points, and the normal + * angular deviation + * \param cloud the point cloud message + * \param normals the point cloud message containing normal information + * \param tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching + * \note the tree has to be created as a spatial locator on \a cloud + * \param tolerance the spatial cluster tolerance as a measure in the L2 Euclidean space + * \param clusters the resultant clusters containing point indices (as a vector of PointIndices) + * \param eps_angle the maximum allowed difference between normals in radians for cluster/region growing + * \param min_pts_per_cluster minimum number of points that a cluster may contain (default: 1) + * \param max_pts_per_cluster maximum number of points that a cluster may contain (default: max int) + * \ingroup segmentation + */ + template void + extractEuclideanClusters ( + const PointCloud &cloud, const PointCloud &normals, + float tolerance, const boost::shared_ptr > &tree, + std::vector &clusters, double eps_angle, + unsigned int min_pts_per_cluster = 1, + unsigned int max_pts_per_cluster = (std::numeric_limits::max) ()) + { + if (tree->getInputCloud ()->points.size () != cloud.points.size ()) + { + PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset (%lu) than the input cloud (%lu)!\n", tree->getInputCloud ()->points.size (), cloud.points.size ()); + return; + } + if (cloud.points.size () != normals.points.size ()) + { + PCL_ERROR ("[pcl::extractEuclideanClusters] Number of points in the input point cloud (%lu) different than normals (%lu)!\n", cloud.points.size (), normals.points.size ()); + return; + } + + // Create a bool vector of processed point indices, and initialize it to false + std::vector processed (cloud.points.size (), false); + + std::vector nn_indices; + std::vector nn_distances; + // Process all points in the indices vector + for (size_t i = 0; i < cloud.points.size (); ++i) + { + if (processed[i]) + continue; + + std::vector seed_queue; + int sq_idx = 0; + seed_queue.push_back (static_cast (i)); + + processed[i] = true; + + while (sq_idx < static_cast (seed_queue.size ())) + { + // Search for sq_idx + if (!tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances)) + { + sq_idx++; + continue; + } + + for (size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx + { + if (processed[nn_indices[j]]) // Has this point been processed before ? + continue; + + //processed[nn_indices[j]] = true; + // [-1;1] + double dot_p = normals.points[i].normal[0] * normals.points[nn_indices[j]].normal[0] + + normals.points[i].normal[1] * normals.points[nn_indices[j]].normal[1] + + normals.points[i].normal[2] * normals.points[nn_indices[j]].normal[2]; + if ( fabs (acos (dot_p)) < eps_angle ) + { + processed[nn_indices[j]] = true; + seed_queue.push_back (nn_indices[j]); + } + } + + sq_idx++; + } + + // If this queue is satisfactory, add to the clusters + if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster) + { + pcl::PointIndices r; + r.indices.resize (seed_queue.size ()); + for (size_t j = 0; j < seed_queue.size (); ++j) + r.indices[j] = seed_queue[j]; + + // These two lines should not be needed: (can anyone confirm?) -FF + std::sort (r.indices.begin (), r.indices.end ()); + r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ()); + + r.header = cloud.header; + clusters.push_back (r); // We could avoid a copy by working directly in the vector + } + } + } + + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Decompose a region of space into clusters based on the euclidean distance between points, and the normal + * angular deviation + * \param cloud the point cloud message + * \param normals the point cloud message containing normal information + * \param indices a list of point indices to use from \a cloud + * \param tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching + * \note the tree has to be created as a spatial locator on \a cloud + * \param tolerance the spatial cluster tolerance as a measure in the L2 Euclidean space + * \param clusters the resultant clusters containing point indices (as PointIndices) + * \param eps_angle the maximum allowed difference between normals in degrees for cluster/region growing + * \param min_pts_per_cluster minimum number of points that a cluster may contain (default: 1) + * \param max_pts_per_cluster maximum number of points that a cluster may contain (default: max int) + * \ingroup segmentation + */ + template + void extractEuclideanClusters ( + const PointCloud &cloud, const PointCloud &normals, + const std::vector &indices, const boost::shared_ptr > &tree, + float tolerance, std::vector &clusters, double eps_angle, + unsigned int min_pts_per_cluster = 1, + unsigned int max_pts_per_cluster = (std::numeric_limits::max) ()) + { + // \note If the tree was created over , we guarantee a 1-1 mapping between what the tree returns + //and indices[i] + if (tree->getInputCloud ()->points.size () != cloud.points.size ()) + { + PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset (%lu) than the input cloud (%lu)!\n", tree->getInputCloud ()->points.size (), cloud.points.size ()); + return; + } + if (tree->getIndices ()->size () != indices.size ()) + { + PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different set of indices (%lu) than the input set (%lu)!\n", tree->getIndices ()->size (), indices.size ()); + return; + } + if (cloud.points.size () != normals.points.size ()) + { + PCL_ERROR ("[pcl::extractEuclideanClusters] Number of points in the input point cloud (%lu) different than normals (%lu)!\n", cloud.points.size (), normals.points.size ()); + return; + } + // Create a bool vector of processed point indices, and initialize it to false + std::vector processed (cloud.points.size (), false); + + std::vector nn_indices; + std::vector nn_distances; + // Process all points in the indices vector + for (size_t i = 0; i < indices.size (); ++i) + { + if (processed[indices[i]]) + continue; + + std::vector seed_queue; + int sq_idx = 0; + seed_queue.push_back (indices[i]); + + processed[indices[i]] = true; + + while (sq_idx < static_cast (seed_queue.size ())) + { + // Search for sq_idx + if (!tree->radiusSearch (cloud.points[seed_queue[sq_idx]], tolerance, nn_indices, nn_distances)) + { + sq_idx++; + continue; + } + + for (size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx + { + if (processed[nn_indices[j]]) // Has this point been processed before ? + continue; + + //processed[nn_indices[j]] = true; + // [-1;1] + double dot_p = + normals.points[indices[i]].normal[0] * normals.points[indices[nn_indices[j]]].normal[0] + + normals.points[indices[i]].normal[1] * normals.points[indices[nn_indices[j]]].normal[1] + + normals.points[indices[i]].normal[2] * normals.points[indices[nn_indices[j]]].normal[2]; + if ( fabs (acos (dot_p)) < eps_angle ) + { + processed[nn_indices[j]] = true; + seed_queue.push_back (nn_indices[j]); + } + } + + sq_idx++; + } + + // If this queue is satisfactory, add to the clusters + if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster) + { + pcl::PointIndices r; + r.indices.resize (seed_queue.size ()); + for (size_t j = 0; j < seed_queue.size (); ++j) + r.indices[j] = seed_queue[j]; + + // These two lines should not be needed: (can anyone confirm?) -FF + std::sort (r.indices.begin (), r.indices.end ()); + r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ()); + + r.header = cloud.header; + clusters.push_back (r); + } + } + } + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense. + * \author Radu Bogdan Rusu + * \ingroup segmentation + */ + template + class EuclideanClusterExtraction: public PCLBase + { + typedef PCLBase BasePCLBase; + + public: + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename pcl::search::Search KdTree; + typedef typename pcl::search::Search::Ptr KdTreePtr; + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Empty constructor. */ + EuclideanClusterExtraction () : tree_ (), + cluster_tolerance_ (0), + min_pts_per_cluster_ (1), + max_pts_per_cluster_ (std::numeric_limits::max ()) + {}; + + /** \brief Provide a pointer to the search object. + * \param[in] tree a pointer to the spatial search object. + */ + inline void + setSearchMethod (const KdTreePtr &tree) + { + tree_ = tree; + } + + /** \brief Get a pointer to the search method used. + * @todo fix this for a generic search tree + */ + inline KdTreePtr + getSearchMethod () const + { + return (tree_); + } + + /** \brief Set the spatial cluster tolerance as a measure in the L2 Euclidean space + * \param[in] tolerance the spatial cluster tolerance as a measure in the L2 Euclidean space + */ + inline void + setClusterTolerance (double tolerance) + { + cluster_tolerance_ = tolerance; + } + + /** \brief Get the spatial cluster tolerance as a measure in the L2 Euclidean space. */ + inline double + getClusterTolerance () const + { + return (cluster_tolerance_); + } + + /** \brief Set the minimum number of points that a cluster needs to contain in order to be considered valid. + * \param[in] min_cluster_size the minimum cluster size + */ + inline void + setMinClusterSize (int min_cluster_size) + { + min_pts_per_cluster_ = min_cluster_size; + } + + /** \brief Get the minimum number of points that a cluster needs to contain in order to be considered valid. */ + inline int + getMinClusterSize () const + { + return (min_pts_per_cluster_); + } + + /** \brief Set the maximum number of points that a cluster needs to contain in order to be considered valid. + * \param[in] max_cluster_size the maximum cluster size + */ + inline void + setMaxClusterSize (int max_cluster_size) + { + max_pts_per_cluster_ = max_cluster_size; + } + + /** \brief Get the maximum number of points that a cluster needs to contain in order to be considered valid. */ + inline int + getMaxClusterSize () const + { + return (max_pts_per_cluster_); + } + + /** \brief Cluster extraction in a PointCloud given by + * \param[out] clusters the resultant point clusters + */ + void + extract (std::vector &clusters); + + protected: + // Members derived from the base class + using BasePCLBase::input_; + using BasePCLBase::indices_; + using BasePCLBase::initCompute; + using BasePCLBase::deinitCompute; + + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + + /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */ + double cluster_tolerance_; + + /** \brief The minimum number of points that a cluster needs to contain in order to be considered valid (default = 1). */ + int min_pts_per_cluster_; + + /** \brief The maximum number of points that a cluster needs to contain in order to be considered valid (default = MAXINT). */ + int max_pts_per_cluster_; + + /** \brief Class getName method. */ + virtual std::string getClassName () const { return ("EuclideanClusterExtraction"); } + + }; + + /** \brief Sort clusters method (for std::sort). + * \ingroup segmentation + */ + inline bool + comparePointClusters (const pcl::PointIndices &a, const pcl::PointIndices &b) + { + return (a.indices.size () < b.indices.size ()); + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_EXTRACT_CLUSTERS_H_ diff --git a/pcl-1.7/pcl/segmentation/extract_labeled_clusters.h b/pcl-1.7/pcl/segmentation/extract_labeled_clusters.h new file mode 100644 index 0000000..648b561 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/extract_labeled_clusters.h @@ -0,0 +1,193 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_EXTRACT_LABELED_CLUSTERS_H_ +#define PCL_EXTRACT_LABELED_CLUSTERS_H_ + +#include +#include + +namespace pcl +{ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Decompose a region of space into clusters based on the Euclidean distance between points + * \param[in] cloud the point cloud message + * \param[in] tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching + * \note the tree has to be created as a spatial locator on \a cloud + * \param[in] tolerance the spatial cluster tolerance as a measure in L2 Euclidean space + * \param[out] labeled_clusters the resultant clusters containing point indices (as a vector of PointIndices) + * \param[in] min_pts_per_cluster minimum number of points that a cluster may contain (default: 1) + * \param[in] max_pts_per_cluster maximum number of points that a cluster may contain (default: max int) + * \param[in] max_label + * \ingroup segmentation + */ + template void + extractLabeledEuclideanClusters ( + const PointCloud &cloud, const boost::shared_ptr > &tree, + float tolerance, std::vector > &labeled_clusters, + unsigned int min_pts_per_cluster = 1, unsigned int max_pts_per_cluster = std::numeric_limits::max (), + unsigned int max_label = std::numeric_limits::max ()); + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b LabeledEuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense, with label info. + * \author Koen Buys + * \ingroup segmentation + */ + template + class LabeledEuclideanClusterExtraction: public PCLBase + { + typedef PCLBase BasePCLBase; + + public: + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename pcl::search::Search KdTree; + typedef typename pcl::search::Search::Ptr KdTreePtr; + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Empty constructor. */ + LabeledEuclideanClusterExtraction () : + tree_ (), + cluster_tolerance_ (0), + min_pts_per_cluster_ (1), + max_pts_per_cluster_ (std::numeric_limits::max ()), + max_label_ (std::numeric_limits::max ()) + {}; + + /** \brief Provide a pointer to the search object. + * \param[in] tree a pointer to the spatial search object. + */ + inline void + setSearchMethod (const KdTreePtr &tree) { tree_ = tree; } + + /** \brief Get a pointer to the search method used. */ + inline KdTreePtr + getSearchMethod () const { return (tree_); } + + /** \brief Set the spatial cluster tolerance as a measure in the L2 Euclidean space + * \param[in] tolerance the spatial cluster tolerance as a measure in the L2 Euclidean space + */ + inline void + setClusterTolerance (double tolerance) { cluster_tolerance_ = tolerance; } + + /** \brief Get the spatial cluster tolerance as a measure in the L2 Euclidean space. */ + inline double + getClusterTolerance () const { return (cluster_tolerance_); } + + /** \brief Set the minimum number of points that a cluster needs to contain in order to be considered valid. + * \param[in] min_cluster_size the minimum cluster size + */ + inline void + setMinClusterSize (int min_cluster_size) { min_pts_per_cluster_ = min_cluster_size; } + + /** \brief Get the minimum number of points that a cluster needs to contain in order to be considered valid. */ + inline int + getMinClusterSize () const { return (min_pts_per_cluster_); } + + /** \brief Set the maximum number of points that a cluster needs to contain in order to be considered valid. + * \param[in] max_cluster_size the maximum cluster size + */ + inline void + setMaxClusterSize (int max_cluster_size) { max_pts_per_cluster_ = max_cluster_size; } + + /** \brief Get the maximum number of points that a cluster needs to contain in order to be considered valid. */ + inline int + getMaxClusterSize () const { return (max_pts_per_cluster_); } + + /** \brief Set the maximum number of labels in the cloud. + * \param[in] max_label the maximum + */ + inline void + setMaxLabels (unsigned int max_label) { max_label_ = max_label; } + + /** \brief Get the maximum number of labels */ + inline unsigned int + getMaxLabels () const { return (max_label_); } + + /** \brief Cluster extraction in a PointCloud given by + * \param[out] labeled_clusters the resultant point clusters + */ + void + extract (std::vector > &labeled_clusters); + + protected: + // Members derived from the base class + using BasePCLBase::input_; + using BasePCLBase::indices_; + using BasePCLBase::initCompute; + using BasePCLBase::deinitCompute; + + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + + /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */ + double cluster_tolerance_; + + /** \brief The minimum number of points that a cluster needs to contain in order to be considered valid (default = 1). */ + int min_pts_per_cluster_; + + /** \brief The maximum number of points that a cluster needs to contain in order to be considered valid (default = MAXINT). */ + int max_pts_per_cluster_; + + /** \brief The maximum number of labels we can find in this pointcloud (default = MAXINT)*/ + unsigned int max_label_; + + /** \brief Class getName method. */ + virtual std::string getClassName () const { return ("LabeledEuclideanClusterExtraction"); } + + }; + + /** \brief Sort clusters method (for std::sort). + * \ingroup segmentation + */ + inline bool + compareLabeledPointClusters (const pcl::PointIndices &a, const pcl::PointIndices &b) + { + return (a.indices.size () < b.indices.size ()); + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_EXTRACT_LABELED_CLUSTERS_H_ diff --git a/pcl-1.7/pcl/segmentation/extract_polygonal_prism_data.h b/pcl-1.7/pcl/segmentation/extract_polygonal_prism_data.h new file mode 100644 index 0000000..d2b92fd --- /dev/null +++ b/pcl-1.7/pcl/segmentation/extract_polygonal_prism_data.h @@ -0,0 +1,217 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_EXTRACT_POLYGONAL_PRISM_DATA_H_ +#define PCL_EXTRACT_POLYGONAL_PRISM_DATA_H_ + +#include +#include + +namespace pcl +{ + /** \brief General purpose method for checking if a 3D point is inside or + * outside a given 2D polygon. + * \note this method accepts any general 3D point that is projected onto the + * 2D polygon, but performs an internal XY projection of both the polygon and the point. + * \param point a 3D point projected onto the same plane as the polygon + * \param polygon a polygon + * \ingroup segmentation + */ + template bool + isPointIn2DPolygon (const PointT &point, const pcl::PointCloud &polygon); + + /** \brief Check if a 2d point (X and Y coordinates considered only!) is + * inside or outside a given polygon. This method assumes that both the point + * and the polygon are projected onto the XY plane. + * + * \note (This is highly optimized code taken from http://www.visibone.com/inpoly/) + * Copyright (c) 1995-1996 Galacticomm, Inc. Freeware source code. + * \param point a 3D point projected onto the same plane as the polygon + * \param polygon a polygon + * \ingroup segmentation + */ + template bool + isXYPointIn2DXYPolygon (const PointT &point, const pcl::PointCloud &polygon); + + //////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b ExtractPolygonalPrismData uses a set of point indices that + * represent a planar model, and together with a given height, generates a 3D + * polygonal prism. The polygonal prism is then used to segment all points + * lying inside it. + * + * An example of its usage is to extract the data lying within a set of 3D + * boundaries (e.g., objects supported by a plane). + * + * Example usage: + * \code{.cpp} + * double z_min = 0., z_max = 0.05; // we want the points above the plane, no farther than 5 cm from the surface + * pcl::PointCloud::Ptr hull_points (new pcl::PointCloud ()); + * pcl::ConvexHull hull; + * // hull.setDimension (2); // not necessarily needed, but we need to check the dimensionality of the output + * hull.setInputCloud (cloud); + * hull.reconstruct (hull_points); + * if (hull.getDimension () == 2) + * { + * pcl::ExtractPolygonalPrismData prism; + * prism.setInputCloud (point_cloud); + * prism.setInputPlanarHull (hull_points); + * prism.setHeightLimits (z_min, z_max); + * prism.segment (cloud_indices); + * } + * else + * PCL_ERROR ("The input cloud does not represent a planar surface.\n"); + * \endcode + * \author Radu Bogdan Rusu + * \ingroup segmentation + */ + template + class ExtractPolygonalPrismData : public PCLBase + { + using PCLBase::input_; + using PCLBase::indices_; + using PCLBase::initCompute; + using PCLBase::deinitCompute; + + public: + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + /** \brief Empty constructor. */ + ExtractPolygonalPrismData () : planar_hull_ (), min_pts_hull_ (3), + height_limit_min_ (0), height_limit_max_ (FLT_MAX), + vpx_ (0), vpy_ (0), vpz_ (0) + {}; + + /** \brief Provide a pointer to the input planar hull dataset. + * \note Please see the example in the class description for how to obtain this. + * \param[in] hull the input planar hull dataset + */ + inline void + setInputPlanarHull (const PointCloudConstPtr &hull) { planar_hull_ = hull; } + + /** \brief Get a pointer the input planar hull dataset. */ + inline PointCloudConstPtr + getInputPlanarHull () const { return (planar_hull_); } + + /** \brief Set the height limits. All points having distances to the + * model outside this interval will be discarded. + * + * \param[in] height_min the minimum allowed distance to the plane model value + * \param[in] height_max the maximum allowed distance to the plane model value + */ + inline void + setHeightLimits (double height_min, double height_max) + { + height_limit_min_ = height_min; + height_limit_max_ = height_max; + } + + /** \brief Get the height limits (min/max) as set by the user. The + * default values are -FLT_MAX, FLT_MAX. + * \param[out] height_min the resultant min height limit + * \param[out] height_max the resultant max height limit + */ + inline void + getHeightLimits (double &height_min, double &height_max) const + { + height_min = height_limit_min_; + height_max = height_limit_max_; + } + + /** \brief Set the viewpoint. + * \param[in] vpx the X coordinate of the viewpoint + * \param[in] vpy the Y coordinate of the viewpoint + * \param[in] vpz the Z coordinate of the viewpoint + */ + inline void + setViewPoint (float vpx, float vpy, float vpz) + { + vpx_ = vpx; + vpy_ = vpy; + vpz_ = vpz; + } + + /** \brief Get the viewpoint. */ + inline void + getViewPoint (float &vpx, float &vpy, float &vpz) const + { + vpx = vpx_; + vpy = vpy_; + vpz = vpz_; + } + + /** \brief Cluster extraction in a PointCloud given by + * \param[out] output the resultant point indices that support the model found (inliers) + */ + void + segment (PointIndices &output); + + protected: + /** \brief A pointer to the input planar hull dataset. */ + PointCloudConstPtr planar_hull_; + + /** \brief The minimum number of points needed on the convex hull. */ + int min_pts_hull_; + + /** \brief The minimum allowed height (distance to the model) a point + * will be considered from. + */ + double height_limit_min_; + + /** \brief The maximum allowed height (distance to the model) a point + * will be considered from. + */ + double height_limit_max_; + + /** \brief Values describing the data acquisition viewpoint. Default: 0,0,0. */ + float vpx_, vpy_, vpz_; + + /** \brief Class getName method. */ + virtual std::string + getClassName () const { return ("ExtractPolygonalPrismData"); } + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_EXTRACT_POLYGONAL_PRISM_DATA_H_ diff --git a/pcl-1.7/pcl/segmentation/grabcut_segmentation.h b/pcl-1.7/pcl/segmentation/grabcut_segmentation.h new file mode 100644 index 0000000..9319f87 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/grabcut_segmentation.h @@ -0,0 +1,483 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SEGMENTATION_GRABCUT +#define PCL_SEGMENTATION_GRABCUT + +#include +#include +#include +#include +#include + +namespace pcl +{ + namespace segmentation + { + namespace grabcut + { + /** boost implementation of Boykov and Kolmogorov's maxflow algorithm doesn't support + * negative flows which makes it inappropriate for this conext. + * This implementation of Boykov and Kolmogorov's maxflow algorithm by Stephen Gould + * in DARWIN under BSD does the trick however solwer than original + * implementation. + */ + class PCL_EXPORTS BoykovKolmogorov + { + public: + typedef int vertex_descriptor; + typedef double edge_capacity_type; + + /// construct a maxflow/mincut problem with estimated max_nodes + BoykovKolmogorov (std::size_t max_nodes = 0); + /// destructor + virtual ~BoykovKolmogorov () {} + /// get number of nodes in the graph + size_t + numNodes () const { return nodes_.size (); } + /// reset all edge capacities to zero (but don't free the graph) + void + reset (); + /// clear the graph and internal datastructures + void + clear (); + /// add nodes to the graph (returns the id of the first node added) + int + addNodes (std::size_t n = 1); + /// add constant flow to graph + void + addConstant (double c) { flow_value_ += c; } + /// add edge from s to nodeId + void + addSourceEdge (int u, double cap); + /// add edge from nodeId to t + void + addTargetEdge (int u, double cap); + /// add edge from u to v and edge from v to u + /// (requires cap_uv + cap_vu >= 0) + void + addEdge (int u, int v, double cap_uv, double cap_vu = 0.0); + /// solve the max-flow problem and return the flow + double + solve (); + /// return true if \p u is in the s-set after calling \ref solve. + bool + inSourceTree (int u) const { return (cut_[u] == SOURCE); } + /// return true if \p u is in the t-set after calling \ref solve + bool + inSinkTree (int u) const { return (cut_[u] == TARGET); } + /// returns the residual capacity for an edge (use -1 for terminal (-1,-1) is the current flow + double + operator() (int u, int v) const; + + double + getSourceEdgeCapacity (int u) const; + + double + getTargetEdgeCapacity (int u) const; + + protected: + /// tree states + typedef enum { FREE = 0x00, SOURCE = 0x01, TARGET = 0x02 } nodestate; + /// capacitated edge + typedef std::map capacitated_edge; + /// edge pair + typedef std::pair edge_pair; + /// pre-augment s-u-t and s-u-v-t paths + void + preAugmentPaths (); + /// initialize trees from source and target + void + initializeTrees (); + /// expand trees until a path is found (or no path (-1, -1)) + std::pair + expandTrees (); + /// augment the path found by expandTrees; return orphaned subtrees + void + augmentPath (const std::pair& path, std::deque& orphans); + /// adopt orphaned subtrees + void + adoptOrphans (std::deque& orphans); + /// clear active set + void clearActive (); + /// \return true if active set is empty + inline bool + isActiveSetEmpty () const { return (active_head_ == TERMINAL); } + /// active if head or previous node is not the terminal + inline bool + isActive (int u) const { return ((u == active_head_) || (active_list_[u].first != TERMINAL)); } + /// mark vertex as active + void + markActive (int u); + /// mark vertex as inactive + void + markInactive (int u); + /// edges leaving the source + std::vector source_edges_; + /// edges entering the target + std::vector target_edges_; + /// nodes and their outgoing internal edges + std::vector nodes_; + /// current flow value (includes constant) + double flow_value_; + /// identifies which side of the cut a node falls + std::vector cut_; + + private: + /// parents_ flag for terminal state + static const int TERMINAL = -1; + /// search tree (also uses cut_) + std::vector > parents_; + /// doubly-linked list (prev, next) + std::vector > active_list_; + int active_head_, active_tail_; + }; + + /**\brief Structure to save RGB colors into floats */ + struct Color + { + Color () : r (0), g (0), b (0) {} + Color (float _r, float _g, float _b) : r(_r), g(_g), b(_b) {} + Color (const pcl::RGB& color) : r (color.r), g (color.g), b (color.b) {} + + template + Color (const PointT& p); + + template + operator PointT () const; + + float r, g, b; + }; + /// An Image is a point cloud of Color + typedef pcl::PointCloud Image; + /** \brief Compute squared distance between two colors + * \param[in] c1 first color + * \param[in] c2 second color + * \return the squared distance measure in RGB space + */ + float + colorDistance (const Color& c1, const Color& c2); + /// User supplied Trimap values + enum TrimapValue { TrimapUnknown = -1, TrimapForeground, TrimapBackground }; + /// Grabcut derived hard segementation values + enum SegmentationValue { SegmentationForeground = 0, SegmentationBackground }; + /// Gaussian structure + struct Gaussian + { + Gaussian () {} + /// mean of the gaussian + Color mu; + /// covariance matrix of the gaussian + Eigen::Matrix3f covariance; + /// determinant of the covariance matrix + float determinant; + /// inverse of the covariance matrix + Eigen::Matrix3f inverse; + /// weighting of this gaussian in the GMM. + float pi; + /// heighest eigenvalue of covariance matrix + float eigenvalue; + /// eigenvector corresponding to the heighest eigenvector + Eigen::Vector3f eigenvector; + }; + + class PCL_EXPORTS GMM + { + public: + /// Initialize GMM with ddesired number of gaussians. + GMM () : gaussians_ (0) {} + /// Initialize GMM with ddesired number of gaussians. + GMM (std::size_t K) : gaussians_ (K) {} + /// Destructor + ~GMM () {} + /// \return K + std::size_t + getK () const { return gaussians_.size (); } + /// resize gaussians + void + resize (std::size_t K) { gaussians_.resize (K); } + /// \return a reference to the gaussian at a given position + Gaussian& + operator[] (std::size_t pos) { return (gaussians_[pos]); } + /// \return a const reference to the gaussian at a given position + const Gaussian& + operator[] (std::size_t pos) const { return (gaussians_[pos]); } + /// \brief \return the computed probability density of a color in this GMM + float + probabilityDensity (const Color &c); + /// \brief \return the computed probability density of a color in just one Gaussian + float + probabilityDensity(std::size_t i, const Color &c); + + private: + /// array of gaussians + std::vector gaussians_; + }; + + /** Helper class that fits a single Gaussian to color samples */ + class GaussianFitter + { + public: + GaussianFitter (float epsilon = 0.0001) + : sum_ (Eigen::Vector3f::Zero ()) + , accumulator_ (Eigen::Matrix3f::Zero ()) + , count_ (0) + , epsilon_ (epsilon) + { } + + /// Add a color sample + void + add (const Color &c); + /// Build the gaussian out of all the added color samples + void + fit (Gaussian& g, std::size_t total_count, bool compute_eigens = false) const; + /// \return epsilon + float + getEpsilon () { return (epsilon_); } + /** set epsilon which will be added to the covariance matrix diagonal which avoids singular + * covariance matrix + * \param[in] epsilon user defined epsilon + */ + void + setEpsilon (float epsilon) { epsilon_ = epsilon; } + + private: + /// sum of r,g, and b + Eigen::Vector3f sum_; + /// matrix of products (i.e. r*r, r*g, r*b), some values are duplicated. + Eigen::Matrix3f accumulator_; + /// count of color samples added to the gaussian + uint32_t count_; + /// small value to add to covariance matrix diagonal to avoid singular values + float epsilon_; + }; + + /** Build the initial GMMs using the Orchard and Bouman color clustering algorithm */ + PCL_EXPORTS void + buildGMMs (const Image &image, + const std::vector& indices, + const std::vector &hardSegmentation, + std::vector &components, + GMM &background_GMM, GMM &foreground_GMM); + /** Iteratively learn GMMs using GrabCut updating algorithm */ + PCL_EXPORTS void + learnGMMs (const Image& image, + const std::vector& indices, + const std::vector& hard_segmentation, + std::vector& components, + GMM& background_GMM, GMM& foreground_GMM); + } + }; + + /** \brief Implementation of the GrabCut segmentation in + * "GrabCut — Interactive Foreground Extraction using Iterated Graph Cuts" by + * Carsten Rother, Vladimir Kolmogorov and Andrew Blake. + * + * \author Justin Talbot, jtalbot@stanford.edu placed in Public Domain, 2010 + * \author Nizar Sallem port to PCL and adaptation of original code. + * \ingroup segmentation + */ + template + class GrabCut : public pcl::PCLBase + { + public: + typedef typename pcl::search::Search KdTree; + typedef typename pcl::search::Search::Ptr KdTreePtr; + typedef typename PCLBase::PointCloudConstPtr PointCloudConstPtr; + typedef typename PCLBase::PointCloudPtr PointCloudPtr; + using PCLBase::input_; + using PCLBase::indices_; + using PCLBase::fake_indices_; + + /// Constructor + GrabCut (uint32_t K = 5, float lambda = 50.f) + : K_ (K) + , lambda_ (lambda) + , nb_neighbours_ (9) + , initialized_ (false) + {} + /// Desctructor + virtual ~GrabCut () {}; + // /// Set input cloud + void + setInputCloud (const PointCloudConstPtr& cloud); + /// Set background points, foreground points = points \ background points + void + setBackgroundPoints (const PointCloudConstPtr& background_points); + /// Set background indices, foreground indices = indices \ background indices + void + setBackgroundPointsIndices (int x1, int y1, int x2, int y2); + /// Set background indices, foreground indices = indices \ background indices + void + setBackgroundPointsIndices (const PointIndicesConstPtr& indices); + /// Run Grabcut refinement on the hard segmentation + virtual void + refine (); + /// \return the number of pixels that have changed from foreground to background or vice versa + virtual int + refineOnce (); + /// \return lambda + float + getLambda () { return (lambda_); } + /** Set lambda parameter to user given value. Suggested value by the authors is 50 + * \param[in] lambda + */ + void + setLambda (float lambda) { lambda_ = lambda; } + /// \return the number of components in the GMM + uint32_t + getK () { return (K_); } + /** Set K parameter to user given value. Suggested value by the authors is 5 + * \param[in] K the number of components used in GMM + */ + void + setK (uint32_t K) { K_ = K; } + /** \brief Provide a pointer to the search object. + * \param tree a pointer to the spatial search object. + */ + inline void + setSearchMethod (const KdTreePtr &tree) { tree_ = tree; } + /** \brief Get a pointer to the search method used. */ + inline KdTreePtr + getSearchMethod () { return (tree_); } + /** \brief Allows to set the number of neighbours to find. + * \param[in] nb_neighbours new number of neighbours + */ + void + setNumberOfNeighbours (int nb_neighbours) { nb_neighbours_ = nb_neighbours; } + /** \brief Returns the number of neighbours to find. */ + int + getNumberOfNeighbours () const { return (nb_neighbours_); } + /** \brief This method launches the segmentation algorithm and returns the clusters that were + * obtained during the segmentation. The indices of points belonging to the object will be stored + * in the cluster with index 1, other indices will be stored in the cluster with index 0. + * \param[out] clusters clusters that were obtained. Each cluster is an array of point indices. + */ + void + extract (std::vector& clusters); + + protected: + // Storage for N-link weights, each pixel stores links to nb_neighbours + struct NLinks + { + NLinks () : nb_links (0), indices (0), dists (0), weights (0) {} + + int nb_links; + std::vector indices; + std::vector dists; + std::vector weights; + }; + bool + initCompute (); + typedef pcl::segmentation::grabcut::BoykovKolmogorov::vertex_descriptor vertex_descriptor; + /// Compute beta from image + void + computeBetaOrganized (); + /// Compute beta from cloud + void + computeBetaNonOrganized (); + /// Compute L parameter from given lambda + void + computeL (); + /// Compute NLinks from image + void + computeNLinksOrganized (); + /// Compute NLinks from cloud + void + computeNLinksNonOrganized (); + /// Edit Trimap + void + setTrimap (const PointIndicesConstPtr &indices, segmentation::grabcut::TrimapValue t); + int + updateHardSegmentation (); + /// Fit Gaussian Multi Models + virtual void + fitGMMs (); + /// Build the graph for GraphCut + void + initGraph (); + /// Add an edge to the graph, graph must be oriented so we add the edge and its reverse + void + addEdge (vertex_descriptor v1, vertex_descriptor v2, float capacity, float rev_capacity); + /// Set the weights of SOURCE --> v and v --> SINK + void + setTerminalWeights (vertex_descriptor v, float source_capacity, float sink_capacity); + /// \return true if v is in source tree + inline bool + isSource (vertex_descriptor v) { return (graph_.inSourceTree (v)); } + /// image width + uint32_t width_; + /// image height + uint32_t height_; + // Variables used in formulas from the paper. + /// Number of GMM components + uint32_t K_; + /// lambda = 50. This value was suggested the GrabCut paper. + float lambda_; + /// beta = 1/2 * average of the squared color distances between all pairs of 8-neighboring pixels. + float beta_; + /// L = a large value to force a pixel to be foreground or background + float L_; + /// Pointer to the spatial search object. + KdTreePtr tree_; + /// Number of neighbours + int nb_neighbours_; + /// is segmentation initialized + bool initialized_; + /// Precomputed N-link weights + std::vector n_links_; + /// Converted input + segmentation::grabcut::Image::Ptr image_; + std::vector trimap_; + std::vector GMM_component_; + std::vector hard_segmentation_; + // Not yet implemented (this would be interpreted as alpha) + std::vector soft_segmentation_; + segmentation::grabcut::GMM background_GMM_, foreground_GMM_; + // Graph part + /// Graph for Graphcut + pcl::segmentation::grabcut::BoykovKolmogorov graph_; + /// Graph nodes + std::vector graph_nodes_; + }; +} + +#include + +#endif diff --git a/pcl-1.7/pcl/segmentation/ground_plane_comparator.h b/pcl-1.7/pcl/segmentation/ground_plane_comparator.h new file mode 100644 index 0000000..e39354d --- /dev/null +++ b/pcl-1.7/pcl/segmentation/ground_plane_comparator.h @@ -0,0 +1,250 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + * + */ + +#ifndef PCL_SEGMENTATION_GROUND_PLANE_COMPARATOR_H_ +#define PCL_SEGMENTATION_GROUND_PLANE_COMPARATOR_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief GroundPlaneComparator is a Comparator for detecting smooth surfaces suitable for driving. + * In conjunction with OrganizedConnectedComponentSegmentation, this allows smooth groundplanes / road surfaces to be segmented from point clouds. + * + * \author Alex Trevor + */ + template + class GroundPlaneComparator: public Comparator + { + public: + typedef typename Comparator::PointCloud PointCloud; + typedef typename Comparator::PointCloudConstPtr PointCloudConstPtr; + + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using pcl::Comparator::input_; + + /** \brief Empty constructor for GroundPlaneComparator. */ + GroundPlaneComparator () + : normals_ () + , plane_coeff_d_ () + , angular_threshold_ (cosf (pcl::deg2rad (2.0f))) + , road_angular_threshold_ ( cosf(pcl::deg2rad (10.0f))) + , distance_threshold_ (0.1f) + , depth_dependent_ (true) + , z_axis_ (Eigen::Vector3f (0.0, 0.0, 1.0) ) + , desired_road_axis_ (Eigen::Vector3f(0.0, -1.0, 0.0)) + { + } + + /** \brief Constructor for GroundPlaneComparator. + * \param[in] plane_coeff_d a reference to a vector of d coefficients of plane equations. Must be the same size as the input cloud and input normals. a, b, and c coefficients are in the input normals. + */ + GroundPlaneComparator (boost::shared_ptr >& plane_coeff_d) + : normals_ () + , plane_coeff_d_ (plane_coeff_d) + , angular_threshold_ (cosf (pcl::deg2rad (3.0f))) + , distance_threshold_ (0.1f) + , depth_dependent_ (true) + , z_axis_ (Eigen::Vector3f (0.0f, 0.0f, 1.0f)) + , road_angular_threshold_ ( cosf(pcl::deg2rad (40.0f))) + , desired_road_axis_ (Eigen::Vector3f(0.0, -1.0, 0.0)) + { + } + + /** \brief Destructor for GroundPlaneComparator. */ + virtual + ~GroundPlaneComparator () + { + } + /** \brief Provide the input cloud. + * \param[in] cloud the input point cloud. + */ + virtual void + setInputCloud (const PointCloudConstPtr& cloud) + { + input_ = cloud; + } + + /** \brief Provide a pointer to the input normals. + * \param[in] normals the input normal cloud. + */ + inline void + setInputNormals (const PointCloudNConstPtr &normals) + { + normals_ = normals; + } + + /** \brief Get the input normals. */ + inline PointCloudNConstPtr + getInputNormals () const + { + return (normals_); + } + + /** \brief Provide a pointer to a vector of the d-coefficient of the planes' hessian normal form. a, b, and c are provided by the normal cloud. + * \param[in] plane_coeff_d a pointer to the plane coefficients. + */ + void + setPlaneCoeffD (boost::shared_ptr >& plane_coeff_d) + { + plane_coeff_d_ = plane_coeff_d; + } + + /** \brief Provide a pointer to a vector of the d-coefficient of the planes' hessian normal form. a, b, and c are provided by the normal cloud. + * \param[in] plane_coeff_d a pointer to the plane coefficients. + */ + void + setPlaneCoeffD (std::vector& plane_coeff_d) + { + plane_coeff_d_ = boost::make_shared >(plane_coeff_d); + } + + /** \brief Get a pointer to the vector of the d-coefficient of the planes' hessian normal form. */ + const std::vector& + getPlaneCoeffD () const + { + return (plane_coeff_d_); + } + + /** \brief Set the tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane. + * \param[in] angular_threshold the tolerance in radians + */ + virtual void + setAngularThreshold (float angular_threshold) + { + angular_threshold_ = cosf (angular_threshold); + } + + /** \brief Set the tolerance in radians for difference in normal direction between a point and the expected ground normal. + * \param[in] angular_threshold the + */ + virtual void + setGroundAngularThreshold (float angular_threshold) + { + road_angular_threshold_ = cosf (angular_threshold); + } + + /** \brief Set the expected ground plane normal with respect to the sensor. Pixels labeled as ground must be within ground_angular_threshold radians of this normal to be labeled as ground. + * \param[in] normal The normal direction of the expected ground plane. + */ + void + setExpectedGroundNormal (Eigen::Vector3f normal) + { + desired_road_axis_ = normal; + } + + + /** \brief Get the angular threshold in radians for difference in normal direction between neighboring points, to be considered part of the same plane. */ + inline float + getAngularThreshold () const + { + return (acosf (angular_threshold_) ); + } + + /** \brief Set the tolerance in meters for difference in perpendicular distance (d component of plane equation) to the plane between neighboring points, to be considered part of the same plane. + * \param[in] distance_threshold the tolerance in meters (at 1m) + * \param[in] depth_dependent whether to scale the threshold based on range from the sensor (default: false) + */ + void + setDistanceThreshold (float distance_threshold, + bool depth_dependent = false) + { + distance_threshold_ = distance_threshold; + depth_dependent_ = depth_dependent; + } + + /** \brief Get the distance threshold in meters (d component of plane equation) between neighboring points, to be considered part of the same plane. */ + inline float + getDistanceThreshold () const + { + return distance_threshold_; + } + + /** \brief Compare points at two indices by their plane equations. True if the angle between the normals is less than the angular threshold, + * and the difference between the d component of the normals is less than distance threshold, else false + * \param idx1 The first index for the comparison + * \param idx2 The second index for the comparison + */ + virtual bool + compare (int idx1, int idx2) const + { + // Normal must be similar to neighbor + // Normal must be similar to expected normal + float threshold = distance_threshold_; + if (depth_dependent_) + { + Eigen::Vector3f vec = input_->points[idx1].getVector3fMap (); + + float z = vec.dot (z_axis_); + threshold *= z * z; + } + + return ( (normals_->points[idx1].getNormalVector3fMap ().dot (desired_road_axis_) > road_angular_threshold_) && + (normals_->points[idx1].getNormalVector3fMap ().dot (normals_->points[idx2].getNormalVector3fMap () ) > angular_threshold_ )); + + // Euclidean proximity of neighbors does not seem to be required -- pixel adjacency handles this well enough + //return ( (normals_->points[idx1].getNormalVector3fMap ().dot (desired_road_axis_) > road_angular_threshold_) && + // (normals_->points[idx1].getNormalVector3fMap ().dot (normals_->points[idx2].getNormalVector3fMap () ) > angular_threshold_ ) && + // (pcl::euclideanDistance (input_->points[idx1], input_->points[idx2]) < distance_threshold_ )); + } + + protected: + PointCloudNConstPtr normals_; + boost::shared_ptr > plane_coeff_d_; + float angular_threshold_; + float road_angular_threshold_; + float distance_threshold_; + bool depth_dependent_; + Eigen::Vector3f z_axis_; + Eigen::Vector3f desired_road_axis_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#endif // PCL_SEGMENTATION_GROUND_PLANE_COMPARATOR_H_ diff --git a/pcl-1.7/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp b/pcl-1.7/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp new file mode 100644 index 0000000..0660e40 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp @@ -0,0 +1,264 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2014, RadiantBlue Technologies, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_SEGMENTATION_APPROXIMATE_PROGRESSIVE_MORPHOLOGICAL_FILTER_HPP_ +#define PCL_SEGMENTATION_APPROXIMATE_PROGRESSIVE_MORPHOLOGICAL_FILTER_HPP_ + +#include +#include +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::ApproximateProgressiveMorphologicalFilter::ApproximateProgressiveMorphologicalFilter () : + max_window_size_ (33), + slope_ (0.7f), + max_distance_ (10.0f), + initial_distance_ (0.15f), + cell_size_ (1.0f), + base_ (2.0f), + exponential_ (true), + threads_ (0) +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::ApproximateProgressiveMorphologicalFilter::~ApproximateProgressiveMorphologicalFilter () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ApproximateProgressiveMorphologicalFilter::extract (std::vector& ground) +{ + bool segmentation_is_possible = initCompute (); + if (!segmentation_is_possible) + { + deinitCompute (); + return; + } + + // Compute the series of window sizes and height thresholds + std::vector height_thresholds; + std::vector window_sizes; + std::vector half_sizes; + int iteration = 0; + int half_size = 0.0f; + float window_size = 0.0f; + float height_threshold = 0.0f; + + while (window_size < max_window_size_) + { + // Determine the initial window size. + if (exponential_) + half_size = static_cast (std::pow (static_cast (base_), iteration)); + else + half_size = (iteration+1) * base_; + + window_size = 2 * half_size + 1; + + // Calculate the height threshold to be used in the next iteration. + if (iteration == 0) + height_threshold = initial_distance_; + else + height_threshold = slope_ * (window_size - window_sizes[iteration-1]) * cell_size_ + initial_distance_; + + // Enforce max distance on height threshold + if (height_threshold > max_distance_) + height_threshold = max_distance_; + + half_sizes.push_back (half_size); + window_sizes.push_back (window_size); + height_thresholds.push_back (height_threshold); + + iteration++; + } + + // setup grid based on scale and extents + Eigen::Vector4f global_max, global_min; + pcl::getMinMax3D (*input_, global_min, global_max); + + float xextent = global_max.x () - global_min.x (); + float yextent = global_max.y () - global_min.y (); + + int rows = static_cast (std::floor (yextent / cell_size_) + 1); + int cols = static_cast (std::floor (xextent / cell_size_) + 1); + + Eigen::MatrixXf A (rows, cols); + A.setConstant (std::numeric_limits::quiet_NaN ()); + + Eigen::MatrixXf Z (rows, cols); + Z.setConstant (std::numeric_limits::quiet_NaN ()); + + Eigen::MatrixXf Zf (rows, cols); + Zf.setConstant (std::numeric_limits::quiet_NaN ()); + +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int i = 0; i < (int)input_->points.size (); ++i) + { + // ...then test for lower points within the cell + PointT p = input_->points[i]; + int row = std::floor(p.y - global_min.y ()); + int col = std::floor(p.x - global_min.x ()); + + if (p.z < A (row, col) || pcl_isnan (A (row, col))) + { + A (row, col) = p.z; + } + } + + // Ground indices are initially limited to those points in the input cloud we + // wish to process + ground = *indices_; + + // Progressively filter ground returns using morphological open + for (size_t i = 0; i < window_sizes.size (); ++i) + { + PCL_DEBUG (" Iteration %d (height threshold = %f, window size = %f, half size = %d)...", + i, height_thresholds[i], window_sizes[i], half_sizes[i]); + + // Limit filtering to those points currently considered ground returns + typename pcl::PointCloud::Ptr cloud (new pcl::PointCloud); + pcl::copyPointCloud (*input_, ground, *cloud); + + // Apply the morphological opening operation at the current window size. +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int row = 0; row < rows; ++row) + { + int rs, re; + rs = ((row - half_sizes[i]) < 0) ? 0 : row - half_sizes[i]; + re = ((row + half_sizes[i]) > (rows-1)) ? (rows-1) : row + half_sizes[i]; + + for (int col = 0; col < cols; ++col) + { + int cs, ce; + cs = ((col - half_sizes[i]) < 0) ? 0 : col - half_sizes[i]; + ce = ((col + half_sizes[i]) > (cols-1)) ? (cols-1) : col + half_sizes[i]; + + float min_coeff = std::numeric_limits::max (); + + for (int j = rs; j < (re + 1); ++j) + { + for (int k = cs; k < (ce + 1); ++k) + { + if (A (j, k) != std::numeric_limits::quiet_NaN ()) + { + if (A (j, k) < min_coeff) + min_coeff = A (j, k); + } + } + } + + if (min_coeff != std::numeric_limits::max ()) + Z(row, col) = min_coeff; + } + } + +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int row = 0; row < rows; ++row) + { + int rs, re; + rs = ((row - half_sizes[i]) < 0) ? 0 : row - half_sizes[i]; + re = ((row + half_sizes[i]) > (rows-1)) ? (rows-1) : row + half_sizes[i]; + + for (int col = 0; col < cols; ++col) + { + int cs, ce; + cs = ((col - half_sizes[i]) < 0) ? 0 : col - half_sizes[i]; + ce = ((col + half_sizes[i]) > (cols-1)) ? (cols-1) : col + half_sizes[i]; + + float max_coeff = -std::numeric_limits::max (); + + for (int j = rs; j < (re + 1); ++j) + { + for (int k = cs; k < (ce + 1); ++k) + { + if (Z (j, k) != std::numeric_limits::quiet_NaN ()) + { + if (Z (j, k) > max_coeff) + max_coeff = Z (j, k); + } + } + } + + if (max_coeff != -std::numeric_limits::max ()) + Zf (row, col) = max_coeff; + } + } + + // Find indices of the points whose difference between the source and + // filtered point clouds is less than the current height threshold. + std::vector pt_indices; + for (size_t p_idx = 0; p_idx < ground.size (); ++p_idx) + { + PointT p = cloud->points[p_idx]; + int erow = static_cast (std::floor ((p.y - global_min.y ()) / cell_size_)); + int ecol = static_cast (std::floor ((p.x - global_min.x ()) / cell_size_)); + + float diff = p.z - Zf (erow, ecol); + if (diff < height_thresholds[i]) + pt_indices.push_back (ground[p_idx]); + } + + A.swap (Zf); + + // Ground is now limited to pt_indices + ground.swap (pt_indices); + + PCL_DEBUG ("ground now has %d points\n", ground.size ()); + } + + deinitCompute (); +} + + +#define PCL_INSTANTIATE_ApproximateProgressiveMorphologicalFilter(T) template class pcl::ApproximateProgressiveMorphologicalFilter; + +#endif // PCL_SEGMENTATION_APPROXIMATE_PROGRESSIVE_MORPHOLOGICAL_FILTER_HPP_ + diff --git a/pcl-1.7/pcl/segmentation/impl/conditional_euclidean_clustering.hpp b/pcl-1.7/pcl/segmentation/impl/conditional_euclidean_clustering.hpp new file mode 100644 index 0000000..d1634b5 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/conditional_euclidean_clustering.hpp @@ -0,0 +1,144 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SEGMENTATION_IMPL_CONDITIONAL_EUCLIDEAN_CLUSTERING_HPP_ +#define PCL_SEGMENTATION_IMPL_CONDITIONAL_EUCLIDEAN_CLUSTERING_HPP_ + +#include + +template void +pcl::ConditionalEuclideanClustering::segment (pcl::IndicesClusters &clusters) +{ + // Prepare output (going to use push_back) + clusters.clear (); + if (extract_removed_clusters_) + { + small_clusters_->clear (); + large_clusters_->clear (); + } + + // Validity checks + if (!initCompute () || input_->points.empty () || indices_->empty () || !condition_function_) + return; + + // Initialize the search class + if (!searcher_) + { + if (input_->isOrganized ()) + searcher_.reset (new pcl::search::OrganizedNeighbor ()); + else + searcher_.reset (new pcl::search::KdTree ()); + } + searcher_->setInputCloud (input_, indices_); + + // Temp variables used by search class + std::vector nn_indices; + std::vector nn_distances; + + // Create a bool vector of processed point indices, and initialize it to false + // Need to have it contain all possible points because radius search can not return indices into indices + std::vector processed (input_->points.size (), false); + + // Process all points indexed by indices_ + for (int iii = 0; iii < static_cast (indices_->size ()); ++iii) // iii = input indices iterator + { + // Has this point been processed before? + if ((*indices_)[iii] == -1 || processed[(*indices_)[iii]]) + continue; + + // Set up a new growing cluster + std::vector current_cluster; + int cii = 0; // cii = cluster indices iterator + + // Add the point to the cluster + current_cluster.push_back ((*indices_)[iii]); + processed[(*indices_)[iii]] = true; + + // Process the current cluster (it can be growing in size as it is being processed) + while (cii < static_cast (current_cluster.size ())) + { + // Search for neighbors around the current seed point of the current cluster + if (searcher_->radiusSearch (input_->points[current_cluster[cii]], cluster_tolerance_, nn_indices, nn_distances) < 1) + { + cii++; + continue; + } + + // Process the neighbors + for (int nii = 1; nii < static_cast (nn_indices.size ()); ++nii) // nii = neighbor indices iterator + { + // Has this point been processed before? + if (nn_indices[nii] == -1 || processed[nn_indices[nii]]) + continue; + + // Validate if condition holds + if (condition_function_ (input_->points[current_cluster[cii]], input_->points[nn_indices[nii]], nn_distances[nii])) + { + // Add the point to the cluster + current_cluster.push_back (nn_indices[nii]); + processed[nn_indices[nii]] = true; + } + } + cii++; + } + + // If extracting removed clusters, all clusters need to be saved, otherwise only the ones within the given cluster size range + if (extract_removed_clusters_ || + (static_cast (current_cluster.size ()) >= min_cluster_size_ && + static_cast (current_cluster.size ()) <= max_cluster_size_)) + { + pcl::PointIndices pi; + pi.header = input_->header; + pi.indices.resize (current_cluster.size ()); + for (int ii = 0; ii < static_cast (current_cluster.size ()); ++ii) // ii = indices iterator + pi.indices[ii] = current_cluster[ii]; + + if (extract_removed_clusters_ && static_cast (current_cluster.size ()) < min_cluster_size_) + small_clusters_->push_back (pi); + else if (extract_removed_clusters_ && static_cast (current_cluster.size ()) > max_cluster_size_) + large_clusters_->push_back (pi); + else + clusters.push_back (pi); + } + } + + deinitCompute (); +} + +#define PCL_INSTANTIATE_ConditionalEuclideanClustering(T) template class PCL_EXPORTS pcl::ConditionalEuclideanClustering; + +#endif // PCL_SEGMENTATION_IMPL_CONDITIONAL_EUCLIDEAN_CLUSTERING_HPP_ + diff --git a/pcl-1.7/pcl/segmentation/impl/crf_normal_segmentation.hpp b/pcl-1.7/pcl/segmentation/impl/crf_normal_segmentation.hpp new file mode 100644 index 0000000..360749e --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/crf_normal_segmentation.hpp @@ -0,0 +1,80 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : Christian Potthast + * Email : potthast@usc.edu + * + */ + +#ifndef PCL_CRF_NORMAL_SEGMENTATION_HPP_ +#define PCL_CRF_NORMAL_SEGMENTATION_HPP_ + +#include + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::CrfNormalSegmentation::CrfNormalSegmentation () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::CrfNormalSegmentation::~CrfNormalSegmentation () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::CrfNormalSegmentation::setCloud (typename pcl::PointCloud::Ptr ) +{ +/* + if (cloud_for_segmentation_ != 0) + cloud_for_segmentation_.reset (); + + cloud_for_segmentation_ = input_cloud; +*/ +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::CrfNormalSegmentation::segmentPoints () +{ +} + +#define PCL_INSTANTIATE_CrfNormalSegmentation(T) template class pcl::CrfNormalSegmentation; + +#endif // PCL_CRF_NORMAL_SEGMENTATION_HPP_ diff --git a/pcl-1.7/pcl/segmentation/impl/extract_clusters.hpp b/pcl-1.7/pcl/segmentation/impl/extract_clusters.hpp new file mode 100644 index 0000000..002d3ed --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/extract_clusters.hpp @@ -0,0 +1,246 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SEGMENTATION_IMPL_EXTRACT_CLUSTERS_H_ +#define PCL_SEGMENTATION_IMPL_EXTRACT_CLUSTERS_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::extractEuclideanClusters (const PointCloud &cloud, + const boost::shared_ptr > &tree, + float tolerance, std::vector &clusters, + unsigned int min_pts_per_cluster, + unsigned int max_pts_per_cluster) +{ + if (tree->getInputCloud ()->points.size () != cloud.points.size ()) + { + PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset (%lu) than the input cloud (%lu)!\n", tree->getInputCloud ()->points.size (), cloud.points.size ()); + return; + } + // Check if the tree is sorted -- if it is we don't need to check the first element + int nn_start_idx = tree->getSortedResults () ? 1 : 0; + // Create a bool vector of processed point indices, and initialize it to false + std::vector processed (cloud.points.size (), false); + + std::vector nn_indices; + std::vector nn_distances; + // Process all points in the indices vector + for (int i = 0; i < static_cast (cloud.points.size ()); ++i) + { + if (processed[i]) + continue; + + std::vector seed_queue; + int sq_idx = 0; + seed_queue.push_back (i); + + processed[i] = true; + + while (sq_idx < static_cast (seed_queue.size ())) + { + // Search for sq_idx + if (!tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances)) + { + sq_idx++; + continue; + } + + for (size_t j = nn_start_idx; j < nn_indices.size (); ++j) // can't assume sorted (default isn't!) + { + if (nn_indices[j] == -1 || processed[nn_indices[j]]) // Has this point been processed before ? + continue; + + // Perform a simple Euclidean clustering + seed_queue.push_back (nn_indices[j]); + processed[nn_indices[j]] = true; + } + + sq_idx++; + } + + // If this queue is satisfactory, add to the clusters + if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster) + { + pcl::PointIndices r; + r.indices.resize (seed_queue.size ()); + for (size_t j = 0; j < seed_queue.size (); ++j) + r.indices[j] = seed_queue[j]; + + // These two lines should not be needed: (can anyone confirm?) -FF + std::sort (r.indices.begin (), r.indices.end ()); + r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ()); + + r.header = cloud.header; + clusters.push_back (r); // We could avoid a copy by working directly in the vector + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +/** @todo: fix the return value, make sure the exit is not needed anymore*/ +template void +pcl::extractEuclideanClusters (const PointCloud &cloud, + const std::vector &indices, + const boost::shared_ptr > &tree, + float tolerance, std::vector &clusters, + unsigned int min_pts_per_cluster, + unsigned int max_pts_per_cluster) +{ + // \note If the tree was created over , we guarantee a 1-1 mapping between what the tree returns + //and indices[i] + if (tree->getInputCloud ()->points.size () != cloud.points.size ()) + { + PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset (%lu) than the input cloud (%lu)!\n", tree->getInputCloud ()->points.size (), cloud.points.size ()); + return; + } + if (tree->getIndices ()->size () != indices.size ()) + { + PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different set of indices (%lu) than the input set (%lu)!\n", tree->getIndices ()->size (), indices.size ()); + return; + } + // Check if the tree is sorted -- if it is we don't need to check the first element + int nn_start_idx = tree->getSortedResults () ? 1 : 0; + + // Create a bool vector of processed point indices, and initialize it to false + std::vector processed (cloud.points.size (), false); + + std::vector nn_indices; + std::vector nn_distances; + // Process all points in the indices vector + for (int i = 0; i < static_cast (indices.size ()); ++i) + { + if (processed[indices[i]]) + continue; + + std::vector seed_queue; + int sq_idx = 0; + seed_queue.push_back (indices[i]); + + processed[indices[i]] = true; + + while (sq_idx < static_cast (seed_queue.size ())) + { + // Search for sq_idx + int ret = tree->radiusSearch (cloud.points[seed_queue[sq_idx]], tolerance, nn_indices, nn_distances); + if( ret == -1) + { + PCL_ERROR("[pcl::extractEuclideanClusters] Received error code -1 from radiusSearch\n"); + exit(0); + } + if (!ret) + { + sq_idx++; + continue; + } + + for (size_t j = nn_start_idx; j < nn_indices.size (); ++j) // can't assume sorted (default isn't!) + { + if (nn_indices[j] == -1 || processed[nn_indices[j]]) // Has this point been processed before ? + continue; + + // Perform a simple Euclidean clustering + seed_queue.push_back (nn_indices[j]); + processed[nn_indices[j]] = true; + } + + sq_idx++; + } + + // If this queue is satisfactory, add to the clusters + if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster) + { + pcl::PointIndices r; + r.indices.resize (seed_queue.size ()); + for (size_t j = 0; j < seed_queue.size (); ++j) + // This is the only place where indices come into play + r.indices[j] = seed_queue[j]; + + // These two lines should not be needed: (can anyone confirm?) -FF + //r.indices.assign(seed_queue.begin(), seed_queue.end()); + std::sort (r.indices.begin (), r.indices.end ()); + r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ()); + + r.header = cloud.header; + clusters.push_back (r); // We could avoid a copy by working directly in the vector + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// + +template void +pcl::EuclideanClusterExtraction::extract (std::vector &clusters) +{ + if (!initCompute () || + (input_ != 0 && input_->points.empty ()) || + (indices_ != 0 && indices_->empty ())) + { + clusters.clear (); + return; + } + + // Initialize the spatial locator + if (!tree_) + { + if (input_->isOrganized ()) + tree_.reset (new pcl::search::OrganizedNeighbor ()); + else + tree_.reset (new pcl::search::KdTree (false)); + } + + // Send the input dataset to the spatial locator + tree_->setInputCloud (input_, indices_); + extractEuclideanClusters (*input_, *indices_, tree_, static_cast (cluster_tolerance_), clusters, min_pts_per_cluster_, max_pts_per_cluster_); + + //tree_->setInputCloud (input_); + //extractEuclideanClusters (*input_, tree_, cluster_tolerance_, clusters, min_pts_per_cluster_, max_pts_per_cluster_); + + // Sort the clusters based on their size (largest one first) + std::sort (clusters.rbegin (), clusters.rend (), comparePointClusters); + + deinitCompute (); +} + +#define PCL_INSTANTIATE_EuclideanClusterExtraction(T) template class PCL_EXPORTS pcl::EuclideanClusterExtraction; +#define PCL_INSTANTIATE_extractEuclideanClusters(T) template void PCL_EXPORTS pcl::extractEuclideanClusters(const pcl::PointCloud &, const boost::shared_ptr > &, float , std::vector &, unsigned int, unsigned int); +#define PCL_INSTANTIATE_extractEuclideanClusters_indices(T) template void PCL_EXPORTS pcl::extractEuclideanClusters(const pcl::PointCloud &, const std::vector &, const boost::shared_ptr > &, float , std::vector &, unsigned int, unsigned int); + +#endif // PCL_EXTRACT_CLUSTERS_IMPL_H_ diff --git a/pcl-1.7/pcl/segmentation/impl/extract_labeled_clusters.hpp b/pcl-1.7/pcl/segmentation/impl/extract_labeled_clusters.hpp new file mode 100644 index 0000000..9fde093 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/extract_labeled_clusters.hpp @@ -0,0 +1,156 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $id $ + */ + +#ifndef PCL_SEGMENTATION_IMPL_EXTRACT_LABELED_CLUSTERS_H_ +#define PCL_SEGMENTATION_IMPL_EXTRACT_LABELED_CLUSTERS_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::extractLabeledEuclideanClusters (const PointCloud &cloud, + const boost::shared_ptr > &tree, + float tolerance, + std::vector > &labeled_clusters, + unsigned int min_pts_per_cluster, + unsigned int max_pts_per_cluster, + unsigned int) +{ + if (tree->getInputCloud ()->points.size () != cloud.points.size ()) + { + PCL_ERROR ("[pcl::extractLabeledEuclideanClusters] Tree built for a different point cloud dataset (%lu) than the input cloud (%lu)!\n", tree->getInputCloud ()->points.size (), cloud.points.size ()); + return; + } + // Create a bool vector of processed point indices, and initialize it to false + std::vector processed (cloud.points.size (), false); + + std::vector nn_indices; + std::vector nn_distances; + + // Process all points in the indices vector + for (int i = 0; i < static_cast (cloud.points.size ()); ++i) + { + if (processed[i]) + continue; + + std::vector seed_queue; + int sq_idx = 0; + seed_queue.push_back (i); + + processed[i] = true; + + while (sq_idx < static_cast (seed_queue.size ())) + { + // Search for sq_idx + int ret = tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances, std::numeric_limits::max()); + if(ret == -1) + PCL_ERROR("radiusSearch on tree came back with error -1"); + if (!ret) + { + sq_idx++; + continue; + } + + for (size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx + { + if (processed[nn_indices[j]]) // Has this point been processed before ? + continue; + if (cloud.points[i].label == cloud.points[nn_indices[j]].label) + { + // Perform a simple Euclidean clustering + seed_queue.push_back (nn_indices[j]); + processed[nn_indices[j]] = true; + } + } + + sq_idx++; + } + + // If this queue is satisfactory, add to the clusters + if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster) + { + pcl::PointIndices r; + r.indices.resize (seed_queue.size ()); + for (size_t j = 0; j < seed_queue.size (); ++j) + r.indices[j] = seed_queue[j]; + + std::sort (r.indices.begin (), r.indices.end ()); + r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ()); + + r.header = cloud.header; + labeled_clusters[cloud.points[i].label].push_back (r); // We could avoid a copy by working directly in the vector + } + } +} +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// + +template void +pcl::LabeledEuclideanClusterExtraction::extract (std::vector > &labeled_clusters) +{ + if (!initCompute () || + (input_ != 0 && input_->points.empty ()) || + (indices_ != 0 && indices_->empty ())) + { + labeled_clusters.clear (); + return; + } + + // Initialize the spatial locator + if (!tree_) + { + if (input_->isOrganized ()) + tree_.reset (new pcl::search::OrganizedNeighbor ()); + else + tree_.reset (new pcl::search::KdTree (false)); + } + + // Send the input dataset to the spatial locator + tree_->setInputCloud (input_); + extractLabeledEuclideanClusters (*input_, tree_, static_cast (cluster_tolerance_), labeled_clusters, min_pts_per_cluster_, max_pts_per_cluster_, max_label_); + + // Sort the clusters based on their size (largest one first) + for (int i = 0; i < static_cast (labeled_clusters.size ()); i++) + std::sort (labeled_clusters[i].rbegin (), labeled_clusters[i].rend (), comparePointClusters); + + deinitCompute (); +} + +#define PCL_INSTANTIATE_LabeledEuclideanClusterExtraction(T) template class PCL_EXPORTS pcl::LabeledEuclideanClusterExtraction; +#define PCL_INSTANTIATE_extractLabeledEuclideanClusters(T) template void PCL_EXPORTS pcl::extractLabeledEuclideanClusters(const pcl::PointCloud &, const boost::shared_ptr > &, float , std::vector > &, unsigned int, unsigned int, unsigned int); + +#endif // PCL_EXTRACT_CLUSTERS_IMPL_H_ diff --git a/pcl-1.7/pcl/segmentation/impl/extract_polygonal_prism_data.hpp b/pcl-1.7/pcl/segmentation/impl/extract_polygonal_prism_data.hpp new file mode 100644 index 0000000..f4d95ee --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/extract_polygonal_prism_data.hpp @@ -0,0 +1,280 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SEGMENTATION_IMPL_EXTRACT_POLYGONAL_PRISM_DATA_H_ +#define PCL_SEGMENTATION_IMPL_EXTRACT_POLYGONAL_PRISM_DATA_H_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::isPointIn2DPolygon (const PointT &point, const pcl::PointCloud &polygon) +{ + // Compute the plane coefficients + Eigen::Vector4f model_coefficients; + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix; + Eigen::Vector4f xyz_centroid; + + computeMeanAndCovarianceMatrix (polygon, covariance_matrix, xyz_centroid); + + // Compute the model coefficients + EIGEN_ALIGN16 Eigen::Vector3f::Scalar eigen_value; + EIGEN_ALIGN16 Eigen::Vector3f eigen_vector; + eigen33 (covariance_matrix, eigen_value, eigen_vector); + + model_coefficients[0] = eigen_vector [0]; + model_coefficients[1] = eigen_vector [1]; + model_coefficients[2] = eigen_vector [2]; + model_coefficients[3] = 0; + + // Hessian form (D = nc . p_plane (centroid here) + p) + model_coefficients[3] = -1 * model_coefficients.dot (xyz_centroid); + + float distance_to_plane = model_coefficients[0] * point.x + + model_coefficients[1] * point.y + + model_coefficients[2] * point.z + + model_coefficients[3]; + PointT ppoint; + // Calculate the projection of the point on the plane + ppoint.x = point.x - distance_to_plane * model_coefficients[0]; + ppoint.y = point.y - distance_to_plane * model_coefficients[1]; + ppoint.z = point.z - distance_to_plane * model_coefficients[2]; + + // Create a X-Y projected representation for within bounds polygonal checking + int k0, k1, k2; + // Determine the best plane to project points onto + k0 = (fabs (model_coefficients[0] ) > fabs (model_coefficients[1])) ? 0 : 1; + k0 = (fabs (model_coefficients[k0]) > fabs (model_coefficients[2])) ? k0 : 2; + k1 = (k0 + 1) % 3; + k2 = (k0 + 2) % 3; + // Project the convex hull + pcl::PointCloud xy_polygon; + xy_polygon.points.resize (polygon.points.size ()); + for (size_t i = 0; i < polygon.points.size (); ++i) + { + Eigen::Vector4f pt (polygon.points[i].x, polygon.points[i].y, polygon.points[i].z, 0); + xy_polygon.points[i].x = pt[k1]; + xy_polygon.points[i].y = pt[k2]; + xy_polygon.points[i].z = 0; + } + PointT xy_point; + xy_point.z = 0; + Eigen::Vector4f pt (ppoint.x, ppoint.y, ppoint.z, 0); + xy_point.x = pt[k1]; + xy_point.y = pt[k2]; + + return (pcl::isXYPointIn2DXYPolygon (xy_point, xy_polygon)); +} + +////////////////////////////////////////////////////////////////////////// +template bool +pcl::isXYPointIn2DXYPolygon (const PointT &point, const pcl::PointCloud &polygon) +{ + bool in_poly = false; + double x1, x2, y1, y2; + + int nr_poly_points = static_cast (polygon.points.size ()); + double xold = polygon.points[nr_poly_points - 1].x; + double yold = polygon.points[nr_poly_points - 1].y; + for (int i = 0; i < nr_poly_points; i++) + { + double xnew = polygon.points[i].x; + double ynew = polygon.points[i].y; + if (xnew > xold) + { + x1 = xold; + x2 = xnew; + y1 = yold; + y2 = ynew; + } + else + { + x1 = xnew; + x2 = xold; + y1 = ynew; + y2 = yold; + } + + if ( (xnew < point.x) == (point.x <= xold) && (point.y - y1) * (x2 - x1) < (y2 - y1) * (point.x - x1) ) + { + in_poly = !in_poly; + } + xold = xnew; + yold = ynew; + } + + // And a last check for the polygon line formed by the last and the first points + double xnew = polygon.points[0].x; + double ynew = polygon.points[0].y; + if (xnew > xold) + { + x1 = xold; + x2 = xnew; + y1 = yold; + y2 = ynew; + } + else + { + x1 = xnew; + x2 = xold; + y1 = ynew; + y2 = yold; + } + + if ( (xnew < point.x) == (point.x <= xold) && (point.y - y1) * (x2 - x1) < (y2 - y1) * (point.x - x1) ) + { + in_poly = !in_poly; + } + + return (in_poly); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::ExtractPolygonalPrismData::segment (pcl::PointIndices &output) +{ + output.header = input_->header; + + if (!initCompute ()) + { + output.indices.clear (); + return; + } + + if (static_cast (planar_hull_->points.size ()) < min_pts_hull_) + { + PCL_ERROR ("[pcl::%s::segment] Not enough points (%lu) in the hull!\n", getClassName ().c_str (), planar_hull_->points.size ()); + output.indices.clear (); + return; + } + + // Compute the plane coefficients + Eigen::Vector4f model_coefficients; + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix; + Eigen::Vector4f xyz_centroid; + + computeMeanAndCovarianceMatrix (*planar_hull_, covariance_matrix, xyz_centroid); + + // Compute the model coefficients + EIGEN_ALIGN16 Eigen::Vector3f::Scalar eigen_value; + EIGEN_ALIGN16 Eigen::Vector3f eigen_vector; + eigen33 (covariance_matrix, eigen_value, eigen_vector); + + model_coefficients[0] = eigen_vector [0]; + model_coefficients[1] = eigen_vector [1]; + model_coefficients[2] = eigen_vector [2]; + model_coefficients[3] = 0; + + // Hessian form (D = nc . p_plane (centroid here) + p) + model_coefficients[3] = -1 * model_coefficients.dot (xyz_centroid); + + // Need to flip the plane normal towards the viewpoint + Eigen::Vector4f vp (vpx_, vpy_, vpz_, 0); + // See if we need to flip any plane normals + vp -= planar_hull_->points[0].getVector4fMap (); + vp[3] = 0; + // Dot product between the (viewpoint - point) and the plane normal + float cos_theta = vp.dot (model_coefficients); + // Flip the plane normal + if (cos_theta < 0) + { + model_coefficients *= -1; + model_coefficients[3] = 0; + // Hessian form (D = nc . p_plane (centroid here) + p) + model_coefficients[3] = -1 * (model_coefficients.dot (planar_hull_->points[0].getVector4fMap ())); + } + + // Project all points + PointCloud projected_points; + SampleConsensusModelPlane sacmodel (input_); + sacmodel.projectPoints (*indices_, model_coefficients, projected_points, false); + + // Create a X-Y projected representation for within bounds polygonal checking + int k0, k1, k2; + // Determine the best plane to project points onto + k0 = (fabs (model_coefficients[0] ) > fabs (model_coefficients[1])) ? 0 : 1; + k0 = (fabs (model_coefficients[k0]) > fabs (model_coefficients[2])) ? k0 : 2; + k1 = (k0 + 1) % 3; + k2 = (k0 + 2) % 3; + // Project the convex hull + pcl::PointCloud polygon; + polygon.points.resize (planar_hull_->points.size ()); + for (size_t i = 0; i < planar_hull_->points.size (); ++i) + { + Eigen::Vector4f pt (planar_hull_->points[i].x, planar_hull_->points[i].y, planar_hull_->points[i].z, 0); + polygon.points[i].x = pt[k1]; + polygon.points[i].y = pt[k2]; + polygon.points[i].z = 0; + } + + PointT pt_xy; + pt_xy.z = 0; + + output.indices.resize (indices_->size ()); + int l = 0; + for (size_t i = 0; i < projected_points.points.size (); ++i) + { + // Check the distance to the user imposed limits from the table planar model + double distance = pointToPlaneDistanceSigned (input_->points[(*indices_)[i]], model_coefficients); + if (distance < height_limit_min_ || distance > height_limit_max_) + continue; + + // Check what points are inside the hull + Eigen::Vector4f pt (projected_points.points[i].x, + projected_points.points[i].y, + projected_points.points[i].z, 0); + pt_xy.x = pt[k1]; + pt_xy.y = pt[k2]; + + if (!pcl::isXYPointIn2DXYPolygon (pt_xy, polygon)) + continue; + + output.indices[l++] = (*indices_)[i]; + } + output.indices.resize (l); + + deinitCompute (); +} + +#define PCL_INSTANTIATE_ExtractPolygonalPrismData(T) template class PCL_EXPORTS pcl::ExtractPolygonalPrismData; +#define PCL_INSTANTIATE_isPointIn2DPolygon(T) template bool PCL_EXPORTS pcl::isPointIn2DPolygon(const T&, const pcl::PointCloud &); +#define PCL_INSTANTIATE_isXYPointIn2DXYPolygon(T) template bool PCL_EXPORTS pcl::isXYPointIn2DXYPolygon(const T &, const pcl::PointCloud &); + +#endif // PCL_SEGMENTATION_IMPL_EXTRACT_POLYGONAL_PRISM_DATA_H_ + diff --git a/pcl-1.7/pcl/segmentation/impl/grabcut_segmentation.hpp b/pcl-1.7/pcl/segmentation/impl/grabcut_segmentation.hpp new file mode 100644 index 0000000..3d8ebe9 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/grabcut_segmentation.hpp @@ -0,0 +1,515 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SEGMENTATION_IMPL_GRABCUT_HPP +#define PCL_SEGMENTATION_IMPL_GRABCUT_HPP + +#include +#include +#include + +namespace pcl +{ + template <> + float squaredEuclideanDistance (const pcl::segmentation::grabcut::Color &c1, + const pcl::segmentation::grabcut::Color &c2) + { + return ((c1.r-c2.r)*(c1.r-c2.r)+(c1.g-c2.g)*(c1.g-c2.g)+(c1.b-c2.b)*(c1.b-c2.b)); + } +} + +template +pcl::segmentation::grabcut::Color::Color (const PointT& p) +{ + r = static_cast (p.r) / 255.0; + g = static_cast (p.g) / 255.0; + b = static_cast (p.b) / 255.0; +} + +template +pcl::segmentation::grabcut::Color::operator PointT () const +{ + PointT p; + p.r = static_cast (r * 255); + p.g = static_cast (g * 255); + p.b = static_cast (b * 255); + return (p); +} + +template void +pcl::GrabCut::setInputCloud (const PointCloudConstPtr &cloud) +{ + input_ = cloud; +} + +template bool +pcl::GrabCut::initCompute () +{ + using namespace pcl::segmentation::grabcut; + if (!pcl::PCLBase::initCompute ()) + { + PCL_ERROR ("[pcl::GrabCut::initCompute ()] Init failed!"); + return (false); + } + + std::vector in_fields_; + if ((pcl::getFieldIndex (*input_, "rgb", in_fields_) == -1) && + (pcl::getFieldIndex (*input_, "rgba", in_fields_) == -1)) + { + PCL_ERROR ("[pcl::GrabCut::initCompute ()] No RGB data available, aborting!"); + return (false); + } + + // Initialize the working image + image_.reset (new Image (input_->width, input_->height)); + for (std::size_t i = 0; i < input_->size (); ++i) + { + (*image_) [i] = Color (input_->points[i]); + } + width_ = image_->width; + height_ = image_->height; + + // Initialize the spatial locator + if (!tree_ && !input_->isOrganized ()) + { + tree_.reset (new pcl::search::KdTree (true)); + tree_->setInputCloud (input_); + } + + const std::size_t indices_size = indices_->size (); + trimap_ = std::vector (indices_size, TrimapUnknown); + hard_segmentation_ = std::vector (indices_size, + SegmentationBackground); + GMM_component_.resize (indices_size); + n_links_.resize (indices_size); + + // soft_segmentation_ = 0; // Not yet implemented + foreground_GMM_.resize (K_); + background_GMM_.resize (K_); + + //set some constants + computeL (); + + if (image_->isOrganized ()) + { + computeBetaOrganized (); + computeNLinksOrganized (); + } + else + { + computeBetaNonOrganized (); + computeNLinksNonOrganized (); + } + + initialized_ = false; + return (true); +} + +template void +pcl::GrabCut::addEdge (vertex_descriptor v1, vertex_descriptor v2, float capacity, float rev_capacity) +{ + graph_.addEdge (v1, v2, capacity, rev_capacity); +} + +template void +pcl::GrabCut::setTerminalWeights (vertex_descriptor v, float source_capacity, float sink_capacity) +{ + graph_.addSourceEdge (v, source_capacity); + graph_.addTargetEdge (v, sink_capacity); +} + +template void +pcl::GrabCut::setBackgroundPointsIndices (const PointIndicesConstPtr &indices) +{ + using namespace pcl::segmentation::grabcut; + if (!initCompute ()) + return; + + std::fill (trimap_.begin (), trimap_.end (), TrimapBackground); + std::fill (hard_segmentation_.begin (), hard_segmentation_.end (), SegmentationBackground); + for (std::vector::const_iterator idx = indices->indices.begin (); idx != indices->indices.end (); ++idx) + { + trimap_[*idx] = TrimapUnknown; + hard_segmentation_[*idx] = SegmentationForeground; + } + + if (!initialized_) + { + fitGMMs (); + initialized_ = true; + } +} + +template void +pcl::GrabCut::fitGMMs () +{ + // Step 3: Build GMMs using Orchard-Bouman clustering algorithm + buildGMMs (*image_, *indices_, hard_segmentation_, GMM_component_, background_GMM_, foreground_GMM_); + + // Initialize the graph for graphcut (do this here so that the T-Link debugging image will be initialized) + initGraph (); +} + +template int +pcl::GrabCut::refineOnce () +{ + // Steps 4 and 5: Learn new GMMs from current segmentation + learnGMMs (*image_, *indices_, hard_segmentation_, GMM_component_, background_GMM_, foreground_GMM_); + + // Step 6: Run GraphCut and update segmentation + initGraph (); + + float flow = graph_.solve (); + + int changed = updateHardSegmentation (); + PCL_INFO ("%d pixels changed segmentation (max flow = %f)\n", changed, flow); + + return (changed); +} + +template void +pcl::GrabCut::refine () +{ + std::size_t changed = indices_->size (); + + while (changed) + changed = refineOnce (); +} + +template int +pcl::GrabCut::updateHardSegmentation () +{ + using namespace pcl::segmentation::grabcut; + + int changed = 0; + + const int number_of_indices = static_cast (indices_->size ()); + for (int i_point = 0; i_point < number_of_indices; ++i_point) + { + SegmentationValue old_value = hard_segmentation_ [i_point]; + + if (trimap_ [i_point] == TrimapBackground) + hard_segmentation_ [i_point] = SegmentationBackground; + else + if (trimap_ [i_point] == TrimapForeground) + hard_segmentation_ [i_point] = SegmentationForeground; + else // TrimapUnknown + { + if (isSource (graph_nodes_[i_point])) + hard_segmentation_ [i_point] = SegmentationForeground; + else + hard_segmentation_ [i_point] = SegmentationBackground; + } + + if (old_value != hard_segmentation_ [i_point]) + ++changed; + } + return (changed); +} + +template void +pcl::GrabCut::setTrimap (const PointIndicesConstPtr &indices, segmentation::grabcut::TrimapValue t) +{ + using namespace pcl::segmentation::grabcut; + std::vector::const_iterator idx = indices->indices.begin (); + for (; idx != indices->indices.end (); ++idx) + trimap_[*idx] = t; + + // Immediately set the hard segmentation as well so that the display will update. + if (t == TrimapForeground) + for (idx = indices->indices.begin (); idx != indices->indices.end (); ++idx) + hard_segmentation_[*idx] = SegmentationForeground; + else + if (t == TrimapBackground) + for (idx = indices->indices.begin (); idx != indices->indices.end (); ++idx) + hard_segmentation_[*idx] = SegmentationBackground; +} + +template void +pcl::GrabCut::initGraph () +{ + using namespace pcl::segmentation::grabcut; + const int number_of_indices = static_cast (indices_->size ()); + // Set up the graph (it can only be used once, so we have to recreate it each time the graph is updated) + graph_.clear (); + graph_nodes_.clear (); + graph_nodes_.resize (indices_->size ()); + int start = graph_.addNodes (indices_->size ()); + for (int idx = 0; idx < indices_->size (); ++idx) + { + graph_nodes_[idx] = start; + ++start; + } + + // Set T-Link weights + for (int i_point = 0; i_point < number_of_indices; ++i_point) + { + int point_index = (*indices_) [i_point]; + float back, fore; + + switch (trimap_[point_index]) + { + case TrimapUnknown : + { + fore = static_cast (-log (background_GMM_.probabilityDensity (image_->points[point_index]))); + back = static_cast (-log (foreground_GMM_.probabilityDensity (image_->points[point_index]))); + break; + } + case TrimapBackground : + { + fore = 0; + back = L_; + break; + } + default : + { + fore = L_; + back = 0; + } + } + + setTerminalWeights (graph_nodes_[i_point], fore, back); + } + + // Set N-Link weights from precomputed values + for (int i_point = 0; i_point < number_of_indices; ++i_point) + { + const NLinks &n_link = n_links_[i_point]; + if (n_link.nb_links > 0) + { + int point_index = (*indices_) [i_point]; + std::vector::const_iterator indices_it = n_link.indices.begin (); + std::vector::const_iterator weights_it = n_link.weights.begin (); + for (; indices_it != n_link.indices.end (); ++indices_it, ++weights_it) + { + if ((*indices_it != point_index) && (*indices_it > -1)) + { + addEdge (graph_nodes_[i_point], graph_nodes_[*indices_it], *weights_it, *weights_it); + } + } + } + } +} + +template void +pcl::GrabCut::computeNLinksNonOrganized () +{ + const int number_of_indices = static_cast (indices_->size ()); + for (int i_point = 0; i_point < number_of_indices; ++i_point) + { + NLinks &n_link = n_links_[i_point]; + if (n_link.nb_links > 0) + { + int point_index = (*indices_) [i_point]; + std::vector::const_iterator indices_it = n_link.indices.begin (); + std::vector::const_iterator dists_it = n_link.dists.begin (); + std::vector::iterator weights_it = n_link.weights.begin (); + for (; indices_it != n_link.indices.end (); ++indices_it, ++dists_it, ++weights_it) + { + if (*indices_it != point_index) + { + // We saved the color distance previously at the computeBeta stage for optimization purpose + float color_distance = *weights_it; + // Set the real weight + *weights_it = static_cast (lambda_ * exp (-beta_ * color_distance) / sqrt (*dists_it)); + } + } + } + } +} + +template void +pcl::GrabCut::computeNLinksOrganized () +{ + for( unsigned int y = 0; y < image_->height; ++y ) + { + for( unsigned int x = 0; x < image_->width; ++x ) + { + // We saved the color and euclidean distance previously at the computeBeta stage for + // optimization purpose but here we compute the real weight + std::size_t point_index = y * input_->width + x; + NLinks &links = n_links_[point_index]; + + if( x > 0 && y < image_->height-1 ) + links.weights[0] = lambda_ * exp (-beta_ * links.weights[0]) / links.dists[0]; + + if( y < image_->height-1 ) + links.weights[1] = lambda_ * exp (-beta_ * links.weights[1]) / links.dists[1]; + + if( x < image_->width-1 && y < image_->height-1 ) + links.weights[2] = lambda_ * exp (-beta_ * links.weights[2]) / links.dists[2]; + + if( x < image_->width-1 ) + links.weights[3] = lambda_ * exp (-beta_ * links.weights[3]) / links.dists[3]; + } + } +} + +template void +pcl::GrabCut::computeBetaNonOrganized () +{ + float result = 0; + std::size_t edges = 0; + + const int number_of_indices = static_cast (indices_->size ()); + + for (int i_point = 0; i_point < number_of_indices; i_point++) + { + int point_index = (*indices_)[i_point]; + const PointT& point = input_->points [point_index]; + if (pcl::isFinite (point)) + { + NLinks &links = n_links_[i_point]; + int found = tree_->nearestKSearch (point, nb_neighbours_, links.indices, links.dists); + if (found > 1) + { + links.nb_links = found - 1; + links.weights.reserve (links.nb_links); + for (std::vector::const_iterator nn_it = links.indices.begin (); nn_it != links.indices.end (); ++nn_it) + { + if (*nn_it != point_index) + { + float color_distance = squaredEuclideanDistance (image_->points[point_index], image_->points[*nn_it]); + links.weights.push_back (color_distance); + result+= color_distance; + ++edges; + } + else + links.weights.push_back (0.f); + } + } + } + } + + beta_ = 1e5 / (2*result / edges); +} + +template void +pcl::GrabCut::computeBetaOrganized () +{ + float result = 0; + std::size_t edges = 0; + + for (unsigned int y = 0; y < input_->height; ++y) + { + for (unsigned int x = 0; x < input_->width; ++x) + { + std::size_t point_index = y * input_->width + x; + NLinks &links = n_links_[point_index]; + links.nb_links = 4; + links.weights.resize (links.nb_links, 0); + links.dists.resize (links.nb_links, 0); + links.indices.resize (links.nb_links, -1); + + if (x > 0 && y < input_->height-1) + { + std::size_t upleft = (y+1) * input_->width + x - 1; + links.indices[0] = upleft; + links.dists[0] = sqrt (2.f); + float color_dist = squaredEuclideanDistance (image_->points[point_index], + image_->points[upleft]); + links.weights[0] = color_dist; + result+= color_dist; + edges++; + } + + if (y < input_->height-1) + { + std::size_t up = (y+1) * input_->width + x; + links.indices[1] = up; + links.dists[1] = 1; + float color_dist = squaredEuclideanDistance (image_->points[point_index], + image_->points[up]); + links.weights[1] = color_dist; + result+= color_dist; + edges++; + } + + if (x < input_->width-1 && y < input_->height-1) + { + std::size_t upright = (y+1) * input_->width + x + 1; + links.indices[2] = upright; + links.dists[2] = sqrt (2.f); + float color_dist = squaredEuclideanDistance (image_->points[point_index], + image_->points [upright]); + links.weights[2] = color_dist; + result+= color_dist; + edges++; + } + + if (x < input_->width-1) + { + std::size_t right = y * input_->width + x + 1; + links.indices[3] = right; + links.dists[3] = 1; + float color_dist = squaredEuclideanDistance (image_->points[point_index], + image_->points[right]); + links.weights[3] = color_dist; + result+= color_dist; + edges++; + } + } + } + + beta_ = 1e5 / (2*result / edges); +} + +template void +pcl::GrabCut::computeL () +{ + L_ = 8*lambda_ + 1; +} + +template void +pcl::GrabCut::extract (std::vector& clusters) +{ + using namespace pcl::segmentation::grabcut; + clusters.clear (); + clusters.resize (2); + clusters[0].indices.reserve (indices_->size ()); + clusters[1].indices.reserve (indices_->size ()); + refine (); + assert (hard_segmentation_.size () == indices_->size ()); + const int indices_size = static_cast (indices_->size ()); + for (int i = 0; i < indices_size; ++i) + if (hard_segmentation_[i] == SegmentationForeground) + clusters[1].indices.push_back (i); + else + clusters[0].indices.push_back (i); +} + +#endif diff --git a/pcl-1.7/pcl/segmentation/impl/min_cut_segmentation.hpp b/pcl-1.7/pcl/segmentation/impl/min_cut_segmentation.hpp new file mode 100644 index 0000000..ca566db --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/min_cut_segmentation.hpp @@ -0,0 +1,639 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id:$ + * + */ + +#ifndef PCL_SEGMENTATION_MIN_CUT_SEGMENTATION_HPP_ +#define PCL_SEGMENTATION_MIN_CUT_SEGMENTATION_HPP_ + +#include +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::MinCutSegmentation::MinCutSegmentation () : + inverse_sigma_ (16.0), + binary_potentials_are_valid_ (false), + epsilon_ (0.0001), + radius_ (16.0), + unary_potentials_are_valid_ (false), + source_weight_ (0.8), + search_ (), + number_of_neighbours_ (14), + graph_is_valid_ (false), + foreground_points_ (0), + background_points_ (0), + clusters_ (0), + graph_ (), + capacity_ (), + reverse_edges_ (), + vertices_ (0), + edge_marker_ (0), + source_ (),///////////////////////////////// + sink_ (),/////////////////////////////////// + max_flow_ (0.0) +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::MinCutSegmentation::~MinCutSegmentation () +{ + if (search_ != 0) + search_.reset (); + if (graph_ != 0) + graph_.reset (); + if (capacity_ != 0) + capacity_.reset (); + if (reverse_edges_ != 0) + reverse_edges_.reset (); + + foreground_points_.clear (); + background_points_.clear (); + clusters_.clear (); + vertices_.clear (); + edge_marker_.clear (); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MinCutSegmentation::setInputCloud (const PointCloudConstPtr &cloud) +{ + input_ = cloud; + graph_is_valid_ = false; + unary_potentials_are_valid_ = false; + binary_potentials_are_valid_ = false; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::MinCutSegmentation::getSigma () const +{ + return (pow (1.0 / inverse_sigma_, 0.5)); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MinCutSegmentation::setSigma (double sigma) +{ + if (sigma > epsilon_) + { + inverse_sigma_ = 1.0 / (sigma * sigma); + binary_potentials_are_valid_ = false; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::MinCutSegmentation::getRadius () const +{ + return (pow (radius_, 0.5)); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MinCutSegmentation::setRadius (double radius) +{ + if (radius > epsilon_) + { + radius_ = radius * radius; + unary_potentials_are_valid_ = false; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::MinCutSegmentation::getSourceWeight () const +{ + return (source_weight_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MinCutSegmentation::setSourceWeight (double weight) +{ + if (weight > epsilon_) + { + source_weight_ = weight; + unary_potentials_are_valid_ = false; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::MinCutSegmentation::KdTreePtr +pcl::MinCutSegmentation::getSearchMethod () const +{ + return (search_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MinCutSegmentation::setSearchMethod (const KdTreePtr& tree) +{ + if (search_ != 0) + search_.reset (); + + search_ = tree; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template unsigned int +pcl::MinCutSegmentation::getNumberOfNeighbours () const +{ + return (number_of_neighbours_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MinCutSegmentation::setNumberOfNeighbours (unsigned int neighbour_number) +{ + if (number_of_neighbours_ != neighbour_number && neighbour_number != 0) + { + number_of_neighbours_ = neighbour_number; + graph_is_valid_ = false; + unary_potentials_are_valid_ = false; + binary_potentials_are_valid_ = false; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template std::vector > +pcl::MinCutSegmentation::getForegroundPoints () const +{ + return (foreground_points_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MinCutSegmentation::setForegroundPoints (typename pcl::PointCloud::Ptr foreground_points) +{ + foreground_points_.clear (); + foreground_points_.reserve (foreground_points->points.size ()); + for (size_t i_point = 0; i_point < foreground_points->points.size (); i_point++) + foreground_points_.push_back (foreground_points->points[i_point]); + + unary_potentials_are_valid_ = false; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template std::vector > +pcl::MinCutSegmentation::getBackgroundPoints () const +{ + return (background_points_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MinCutSegmentation::setBackgroundPoints (typename pcl::PointCloud::Ptr background_points) +{ + background_points_.clear (); + background_points_.reserve (background_points->points.size ()); + for (size_t i_point = 0; i_point < background_points->points.size (); i_point++) + background_points_.push_back (background_points->points[i_point]); + + unary_potentials_are_valid_ = false; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MinCutSegmentation::extract (std::vector & clusters) +{ + clusters.clear (); + + bool segmentation_is_possible = initCompute (); + if ( !segmentation_is_possible ) + { + deinitCompute (); + return; + } + + if ( graph_is_valid_ && unary_potentials_are_valid_ && binary_potentials_are_valid_ ) + { + clusters.reserve (clusters_.size ()); + std::copy (clusters_.begin (), clusters_.end (), std::back_inserter (clusters)); + deinitCompute (); + return; + } + + clusters_.clear (); + bool success = true; + + if ( !graph_is_valid_ ) + { + success = buildGraph (); + if (success == false) + { + deinitCompute (); + return; + } + graph_is_valid_ = true; + unary_potentials_are_valid_ = true; + binary_potentials_are_valid_ = true; + } + + if ( !unary_potentials_are_valid_ ) + { + success = recalculateUnaryPotentials (); + if (success == false) + { + deinitCompute (); + return; + } + unary_potentials_are_valid_ = true; + } + + if ( !binary_potentials_are_valid_ ) + { + success = recalculateBinaryPotentials (); + if (success == false) + { + deinitCompute (); + return; + } + binary_potentials_are_valid_ = true; + } + + //IndexMap index_map = boost::get (boost::vertex_index, *graph_); + ResidualCapacityMap residual_capacity = boost::get (boost::edge_residual_capacity, *graph_); + + max_flow_ = boost::boykov_kolmogorov_max_flow (*graph_, source_, sink_); + + assembleLabels (residual_capacity); + + clusters.reserve (clusters_.size ()); + std::copy (clusters_.begin (), clusters_.end (), std::back_inserter (clusters)); + + deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::MinCutSegmentation::getMaxFlow () const +{ + return (max_flow_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename boost::shared_ptr::mGraph> +pcl::MinCutSegmentation::getGraph () const +{ + return (graph_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::MinCutSegmentation::buildGraph () +{ + int number_of_points = static_cast (input_->points.size ()); + int number_of_indices = static_cast (indices_->size ()); + + if (input_->points.size () == 0 || number_of_points == 0 || foreground_points_.empty () == true ) + return (false); + + if (search_ == 0) + search_ = boost::shared_ptr > (new pcl::search::KdTree); + + graph_.reset (); + graph_ = boost::shared_ptr< mGraph > (new mGraph ()); + + capacity_.reset (); + capacity_ = boost::shared_ptr (new CapacityMap ()); + *capacity_ = boost::get (boost::edge_capacity, *graph_); + + reverse_edges_.reset (); + reverse_edges_ = boost::shared_ptr (new ReverseEdgeMap ()); + *reverse_edges_ = boost::get (boost::edge_reverse, *graph_); + + VertexDescriptor vertex_descriptor(0); + vertices_.clear (); + vertices_.resize (number_of_points + 2, vertex_descriptor); + + std::set out_edges_marker; + edge_marker_.clear (); + edge_marker_.resize (number_of_points + 2, out_edges_marker); + + for (int i_point = 0; i_point < number_of_points + 2; i_point++) + vertices_[i_point] = boost::add_vertex (*graph_); + + source_ = vertices_[number_of_points]; + sink_ = vertices_[number_of_points + 1]; + + for (int i_point = 0; i_point < number_of_indices; i_point++) + { + int point_index = (*indices_)[i_point]; + double source_weight = 0.0; + double sink_weight = 0.0; + calculateUnaryPotential (point_index, source_weight, sink_weight); + addEdge (static_cast (source_), point_index, source_weight); + addEdge (point_index, static_cast (sink_), sink_weight); + } + + std::vector neighbours; + std::vector distances; + search_->setInputCloud (input_, indices_); + for (int i_point = 0; i_point < number_of_indices; i_point++) + { + int point_index = (*indices_)[i_point]; + search_->nearestKSearch (i_point, number_of_neighbours_, neighbours, distances); + for (size_t i_nghbr = 1; i_nghbr < neighbours.size (); i_nghbr++) + { + double weight = calculateBinaryPotential (point_index, neighbours[i_nghbr]); + addEdge (point_index, neighbours[i_nghbr], weight); + addEdge (neighbours[i_nghbr], point_index, weight); + } + neighbours.clear (); + distances.clear (); + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MinCutSegmentation::calculateUnaryPotential (int point, double& source_weight, double& sink_weight) const +{ + double min_dist_to_foreground = std::numeric_limits::max (); + //double min_dist_to_background = std::numeric_limits::max (); + double closest_foreground_point[2]; + closest_foreground_point[0] = closest_foreground_point[1] = 0; + //double closest_background_point[] = {0.0, 0.0}; + double initial_point[] = {0.0, 0.0}; + + initial_point[0] = input_->points[point].x; + initial_point[1] = input_->points[point].y; + + for (size_t i_point = 0; i_point < foreground_points_.size (); i_point++) + { + double dist = 0.0; + dist += (foreground_points_[i_point].x - initial_point[0]) * (foreground_points_[i_point].x - initial_point[0]); + dist += (foreground_points_[i_point].y - initial_point[1]) * (foreground_points_[i_point].y - initial_point[1]); + if (min_dist_to_foreground > dist) + { + min_dist_to_foreground = dist; + closest_foreground_point[0] = foreground_points_[i_point].x; + closest_foreground_point[1] = foreground_points_[i_point].y; + } + } + + sink_weight = pow (min_dist_to_foreground / radius_, 0.5); + + source_weight = source_weight_; + return; +/* + if (background_points_.size () == 0) + return; + + for (int i_point = 0; i_point < background_points_.size (); i_point++) + { + double dist = 0.0; + dist += (background_points_[i_point].x - initial_point[0]) * (background_points_[i_point].x - initial_point[0]); + dist += (background_points_[i_point].y - initial_point[1]) * (background_points_[i_point].y - initial_point[1]); + if (min_dist_to_background > dist) + { + min_dist_to_background = dist; + closest_background_point[0] = background_points_[i_point].x; + closest_background_point[1] = background_points_[i_point].y; + } + } + + if (min_dist_to_background <= epsilon_) + { + source_weight = 0.0; + sink_weight = 1.0; + return; + } + + source_weight = 1.0 / (1.0 + pow (min_dist_to_background / min_dist_to_foreground, 0.5)); + sink_weight = 1 - source_weight; +*/ +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::MinCutSegmentation::addEdge (int source, int target, double weight) +{ + std::set::iterator iter_out = edge_marker_[source].find (target); + if ( iter_out != edge_marker_[source].end () ) + return (false); + + EdgeDescriptor edge; + EdgeDescriptor reverse_edge; + bool edge_was_added, reverse_edge_was_added; + + boost::tie (edge, edge_was_added) = boost::add_edge ( vertices_[source], vertices_[target], *graph_ ); + boost::tie (reverse_edge, reverse_edge_was_added) = boost::add_edge ( vertices_[target], vertices_[source], *graph_ ); + if ( !edge_was_added || !reverse_edge_was_added ) + return (false); + + (*capacity_)[edge] = weight; + (*capacity_)[reverse_edge] = 0.0; + (*reverse_edges_)[edge] = reverse_edge; + (*reverse_edges_)[reverse_edge] = edge; + edge_marker_[source].insert (target); + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::MinCutSegmentation::calculateBinaryPotential (int source, int target) const +{ + double weight = 0.0; + double distance = 0.0; + distance += (input_->points[source].x - input_->points[target].x) * (input_->points[source].x - input_->points[target].x); + distance += (input_->points[source].y - input_->points[target].y) * (input_->points[source].y - input_->points[target].y); + distance += (input_->points[source].z - input_->points[target].z) * (input_->points[source].z - input_->points[target].z); + distance *= inverse_sigma_; + weight = exp (-distance); + + return (weight); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::MinCutSegmentation::recalculateUnaryPotentials () +{ + OutEdgeIterator src_edge_iter; + OutEdgeIterator src_edge_end; + std::pair sink_edge; + + for (boost::tie (src_edge_iter, src_edge_end) = boost::out_edges (source_, *graph_); src_edge_iter != src_edge_end; src_edge_iter++) + { + double source_weight = 0.0; + double sink_weight = 0.0; + sink_edge.second = false; + calculateUnaryPotential (static_cast (boost::target (*src_edge_iter, *graph_)), source_weight, sink_weight); + sink_edge = boost::lookup_edge (boost::target (*src_edge_iter, *graph_), sink_, *graph_); + if (!sink_edge.second) + return (false); + + (*capacity_)[*src_edge_iter] = source_weight; + (*capacity_)[sink_edge.first] = sink_weight; + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::MinCutSegmentation::recalculateBinaryPotentials () +{ + int number_of_points = static_cast (indices_->size ()); + + VertexIterator vertex_iter; + VertexIterator vertex_end; + OutEdgeIterator edge_iter; + OutEdgeIterator edge_end; + + std::vector< std::set > edge_marker; + std::set out_edges_marker; + edge_marker.clear (); + edge_marker.resize (number_of_points + 2, out_edges_marker); + + for (boost::tie (vertex_iter, vertex_end) = boost::vertices (*graph_); vertex_iter != vertex_end; vertex_iter++) + { + VertexDescriptor source_vertex = *vertex_iter; + if (source_vertex == source_ || source_vertex == sink_) + continue; + for (boost::tie (edge_iter, edge_end) = boost::out_edges (source_vertex, *graph_); edge_iter != edge_end; edge_iter++) + { + //If this is not the edge of the graph, but the reverse fictitious edge that is needed for the algorithm then continue + EdgeDescriptor reverse_edge = (*reverse_edges_)[*edge_iter]; + if ((*capacity_)[reverse_edge] != 0.0) + continue; + + //If we already changed weight for this edge then continue + VertexDescriptor target_vertex = boost::target (*edge_iter, *graph_); + std::set::iterator iter_out = edge_marker[static_cast (source_vertex)].find (target_vertex); + if ( iter_out != edge_marker[static_cast (source_vertex)].end () ) + continue; + + if (target_vertex != source_ && target_vertex != sink_) + { + //Change weight and remember that this edges were updated + double weight = calculateBinaryPotential (static_cast (target_vertex), static_cast (source_vertex)); + (*capacity_)[*edge_iter] = weight; + edge_marker[static_cast (source_vertex)].insert (target_vertex); + } + } + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MinCutSegmentation::assembleLabels (ResidualCapacityMap& residual_capacity) +{ + std::vector labels; + labels.resize (input_->points.size (), 0); + int number_of_indices = static_cast (indices_->size ()); + for (int i_point = 0; i_point < number_of_indices; i_point++) + labels[(*indices_)[i_point]] = 1; + + clusters_.clear (); + + pcl::PointIndices segment; + clusters_.resize (2, segment); + + OutEdgeIterator edge_iter, edge_end; + for ( boost::tie (edge_iter, edge_end) = boost::out_edges (source_, *graph_); edge_iter != edge_end; edge_iter++ ) + { + if (labels[edge_iter->m_target] == 1) + { + if (residual_capacity[*edge_iter] > epsilon_) + clusters_[1].indices.push_back (static_cast (edge_iter->m_target)); + else + clusters_[0].indices.push_back (static_cast (edge_iter->m_target)); + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template pcl::PointCloud::Ptr +pcl::MinCutSegmentation::getColoredCloud () +{ + pcl::PointCloud::Ptr colored_cloud; + + if (!clusters_.empty ()) + { + int num_of_pts_in_first_cluster = static_cast (clusters_[0].indices.size ()); + int num_of_pts_in_second_cluster = static_cast (clusters_[1].indices.size ()); + int number_of_points = num_of_pts_in_first_cluster + num_of_pts_in_second_cluster; + colored_cloud = (new pcl::PointCloud)->makeShared (); + unsigned char foreground_color[3] = {255, 255, 255}; + unsigned char background_color[3] = {255, 0, 0}; + colored_cloud->width = number_of_points; + colored_cloud->height = 1; + colored_cloud->is_dense = input_->is_dense; + + pcl::PointXYZRGB point; + int point_index = 0; + for (int i_point = 0; i_point < num_of_pts_in_first_cluster; i_point++) + { + point_index = clusters_[0].indices[i_point]; + point.x = *(input_->points[point_index].data); + point.y = *(input_->points[point_index].data + 1); + point.z = *(input_->points[point_index].data + 2); + point.r = background_color[0]; + point.g = background_color[1]; + point.b = background_color[2]; + colored_cloud->points.push_back (point); + } + + for (int i_point = 0; i_point < num_of_pts_in_second_cluster; i_point++) + { + point_index = clusters_[1].indices[i_point]; + point.x = *(input_->points[point_index].data); + point.y = *(input_->points[point_index].data + 1); + point.z = *(input_->points[point_index].data + 2); + point.r = foreground_color[0]; + point.g = foreground_color[1]; + point.b = foreground_color[2]; + colored_cloud->points.push_back (point); + } + } + + return (colored_cloud); +} + +#define PCL_INSTANTIATE_MinCutSegmentation(T) template class pcl::MinCutSegmentation; + +#endif // PCL_SEGMENTATION_MIN_CUT_SEGMENTATION_HPP_ diff --git a/pcl-1.7/pcl/segmentation/impl/organized_connected_component_segmentation.hpp b/pcl-1.7/pcl/segmentation/impl/organized_connected_component_segmentation.hpp new file mode 100644 index 0000000..76b6245 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/organized_connected_component_segmentation.hpp @@ -0,0 +1,231 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + * + */ + +#ifndef PCL_SEGMENTATION_IMPL_ORGANIZED_CONNECTED_COMPONENT_SEGMENTATION_H_ +#define PCL_SEGMENTATION_IMPL_ORGANIZED_CONNECTED_COMPONENT_SEGMENTATION_H_ + +#include + +/** + * Directions: 1 2 3 + * 0 x 4 + * 7 6 5 + * e.g. direction y means we came from pixel with label y to the center pixel x + */ +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedConnectedComponentSegmentation::findLabeledRegionBoundary (int start_idx, PointCloudLPtr labels, pcl::PointIndices& boundary_indices) +{ + boundary_indices.indices.clear (); + int curr_idx = start_idx; + int curr_x = start_idx % labels->width; + int curr_y = start_idx / labels->width; + unsigned label = labels->points[start_idx].label; + + // fill lookup table for next points to visit + Neighbor directions [8] = {Neighbor(-1, 0, -1), + Neighbor(-1, -1, -labels->width - 1), + Neighbor( 0, -1, -labels->width ), + Neighbor( 1, -1, -labels->width + 1), + Neighbor( 1, 0, 1), + Neighbor( 1, 1, labels->width + 1), + Neighbor( 0, 1, labels->width ), + Neighbor(-1, 1, labels->width - 1)}; + + // find one pixel with other label in the neighborhood -> assume thats the one we came from + int direction = -1; + int x; + int y; + int index; + for (unsigned dIdx = 0; dIdx < 8; ++dIdx) + { + x = curr_x + directions [dIdx].d_x; + y = curr_y + directions [dIdx].d_y; + index = curr_idx + directions [dIdx].d_index; + if (x >= 0 && x < int(labels->width) && y >= 0 && y < int(labels->height) && labels->points[index].label != label) + { + direction = dIdx; + break; + } + } + + // no connection to outer regions => start_idx is not on the border + if (direction == -1) + return; + + boundary_indices.indices.push_back (start_idx); + + do { + unsigned nIdx; + for (unsigned dIdx = 1; dIdx <= 8; ++dIdx) + { + nIdx = (direction + dIdx) & 7; + + x = curr_x + directions [nIdx].d_x; + y = curr_y + directions [nIdx].d_y; + index = curr_idx + directions [nIdx].d_index; + if (x >= 0 && y < int(labels->width) && y >= 0 && y < int(labels->height) && labels->points[index].label == label) + break; + } + + // update the direction + direction = (nIdx + 4) & 7; + curr_idx += directions [nIdx].d_index; + curr_x += directions [nIdx].d_x; + curr_y += directions [nIdx].d_y; + boundary_indices.indices.push_back(curr_idx); + } while ( curr_idx != start_idx); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedConnectedComponentSegmentation::segment (pcl::PointCloud& labels, std::vector& label_indices) const +{ + std::vector run_ids; + + unsigned invalid_label = std::numeric_limits::max (); + pcl::Label invalid_pt; + invalid_pt.label = std::numeric_limits::max (); + labels.points.resize (input_->points.size (), invalid_pt); + labels.width = input_->width; + labels.height = input_->height; + unsigned int clust_id = 0; + + //First pixel + if (pcl_isfinite (input_->points[0].x)) + { + labels[0].label = clust_id++; + run_ids.push_back (labels[0].label ); + } + + // First row + for (int colIdx = 1; colIdx < static_cast (input_->width); ++colIdx) + { + if (!pcl_isfinite (input_->points[colIdx].x)) + continue; + else if (compare_->compare (colIdx, colIdx - 1 )) + { + labels[colIdx].label = labels[colIdx - 1].label; + } + else + { + labels[colIdx].label = clust_id++; + run_ids.push_back (labels[colIdx].label ); + } + } + + // Everything else + unsigned int current_row = input_->width; + unsigned int previous_row = 0; + for (size_t rowIdx = 1; rowIdx < input_->height; ++rowIdx, previous_row = current_row, current_row += input_->width) + { + // First pixel + if (pcl_isfinite (input_->points[current_row].x)) + { + if (compare_->compare (current_row, previous_row)) + { + labels[current_row].label = labels[previous_row].label; + } + else + { + labels[current_row].label = clust_id++; + run_ids.push_back (labels[current_row].label); + } + } + + // Rest of row + for (int colIdx = 1; colIdx < static_cast (input_->width); ++colIdx) + { + if (pcl_isfinite (input_->points[current_row + colIdx].x)) + { + if (compare_->compare (current_row + colIdx, current_row + colIdx - 1)) + { + labels[current_row + colIdx].label = labels[current_row + colIdx - 1].label; + } + if (compare_->compare (current_row + colIdx, previous_row + colIdx) ) + { + if (labels[current_row + colIdx].label == invalid_label) + labels[current_row + colIdx].label = labels[previous_row + colIdx].label; + else if (labels[previous_row + colIdx].label != invalid_label) + { + unsigned root1 = findRoot (run_ids, labels[current_row + colIdx].label); + unsigned root2 = findRoot (run_ids, labels[previous_row + colIdx].label); + + if (root1 < root2) + run_ids[root2] = root1; + else + run_ids[root1] = root2; + } + } + + if (labels[current_row + colIdx].label == invalid_label) + { + labels[current_row + colIdx].label = clust_id++; + run_ids.push_back (labels[current_row + colIdx].label); + } + + } + } + } + + std::vector map (clust_id); + unsigned max_id = 0; + for (unsigned runIdx = 0; runIdx < run_ids.size (); ++runIdx) + { + // if it is its own root -> new region + if (run_ids[runIdx] == runIdx) + map[runIdx] = max_id++; + else // assign this sub-segment to the region (root) it belongs + map [runIdx] = map [findRoot (run_ids, runIdx)]; + } + + label_indices.resize (max_id + 1); + for (unsigned idx = 0; idx < input_->points.size (); idx++) + { + if (labels[idx].label != invalid_label) + { + labels[idx].label = map[labels[idx].label]; + label_indices[labels[idx].label].indices.push_back (idx); + } + } +} + +#define PCL_INSTANTIATE_OrganizedConnectedComponentSegmentation(T,LT) template class PCL_EXPORTS pcl::OrganizedConnectedComponentSegmentation; + +#endif //#ifndef PCL_SEGMENTATION_IMPL_ORGANIZED_CONNECTED_COMPONENT_SEGMENTATION_H_ diff --git a/pcl-1.7/pcl/segmentation/impl/organized_multi_plane_segmentation.hpp b/pcl-1.7/pcl/segmentation/impl/organized_multi_plane_segmentation.hpp new file mode 100644 index 0000000..211d44c --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/organized_multi_plane_segmentation.hpp @@ -0,0 +1,414 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + * + */ + +#ifndef PCL_SEGMENTATION_IMPL_ORGANIZED_MULTI_PLANE_SEGMENTATION_H_ +#define PCL_SEGMENTATION_IMPL_ORGANIZED_MULTI_PLANE_SEGMENTATION_H_ + +#include +#include +#include +#include +#include + +///////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template pcl::PointCloud +projectToPlaneFromViewpoint (pcl::PointCloud& cloud, Eigen::Vector4f& normal, Eigen::Vector3f& centroid, Eigen::Vector3f& vp) +{ + Eigen::Vector3f norm (normal[0], normal[1], normal[2]); //(region.coefficients_[0], region.coefficients_[1], region.coefficients_[2]); + pcl::PointCloud projected_cloud; + projected_cloud.resize (cloud.points.size ()); + for (size_t i = 0; i < cloud.points.size (); i++) + { + Eigen::Vector3f pt (cloud.points[i].x, cloud.points[i].y, cloud.points[i].z); + //Eigen::Vector3f intersection = (vp, pt, norm, centroid); + float u = norm.dot ((centroid - vp)) / norm.dot ((pt - vp)); + Eigen::Vector3f intersection (vp + u * (pt - vp)); + projected_cloud[i].x = intersection[0]; + projected_cloud[i].y = intersection[1]; + projected_cloud[i].z = intersection[2]; + } + + return (projected_cloud); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedMultiPlaneSegmentation::segment (std::vector& model_coefficients, + std::vector& inlier_indices) +{ + pcl::PointCloud labels; + std::vector label_indices; + std::vector > centroids; + std::vector > covariances; + segment (model_coefficients, inlier_indices, centroids, covariances, labels, label_indices); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedMultiPlaneSegmentation::segment (std::vector& model_coefficients, + std::vector& inlier_indices, + std::vector >& centroids, + std::vector >& covariances, + pcl::PointCloud& labels, + std::vector& label_indices) +{ + if (!initCompute ()) + return; + + // Check that we got the same number of points and normals + if (static_cast (normals_->points.size ()) != static_cast (input_->points.size ())) + { + PCL_ERROR ("[pcl::%s::segment] Number of points in input cloud (%lu) and normal cloud (%lu) do not match!\n", + getClassName ().c_str (), input_->points.size (), + normals_->points.size ()); + return; + } + + // Check that the cloud is organized + if (!input_->isOrganized ()) + { + PCL_ERROR ("[pcl::%s::segment] Organized point cloud is required for this plane extraction method!\n", + getClassName ().c_str ()); + return; + } + + // Calculate range part of planes' hessian normal form + std::vector plane_d (input_->points.size ()); + + for (unsigned int i = 0; i < input_->size (); ++i) + plane_d[i] = input_->points[i].getVector3fMap ().dot (normals_->points[i].getNormalVector3fMap ()); + + // Make a comparator + //PlaneCoefficientComparator plane_comparator (plane_d); + compare_->setPlaneCoeffD (plane_d); + compare_->setInputCloud (input_); + compare_->setInputNormals (normals_); + compare_->setAngularThreshold (static_cast (angular_threshold_)); + compare_->setDistanceThreshold (static_cast (distance_threshold_), true); + + // Set up the output + OrganizedConnectedComponentSegmentation connected_component (compare_); + connected_component.setInputCloud (input_); + connected_component.segment (labels, label_indices); + + Eigen::Vector4f clust_centroid = Eigen::Vector4f::Zero (); + Eigen::Vector4f vp = Eigen::Vector4f::Zero (); + Eigen::Matrix3f clust_cov; + pcl::ModelCoefficients model; + model.values.resize (4); + + // Fit Planes to each cluster + for (size_t i = 0; i < label_indices.size (); i++) + { + if (static_cast (label_indices[i].indices.size ()) > min_inliers_) + { + pcl::computeMeanAndCovarianceMatrix (*input_, label_indices[i].indices, clust_cov, clust_centroid); + Eigen::Vector4f plane_params; + + EIGEN_ALIGN16 Eigen::Vector3f::Scalar eigen_value; + EIGEN_ALIGN16 Eigen::Vector3f eigen_vector; + pcl::eigen33 (clust_cov, eigen_value, eigen_vector); + plane_params[0] = eigen_vector[0]; + plane_params[1] = eigen_vector[1]; + plane_params[2] = eigen_vector[2]; + plane_params[3] = 0; + plane_params[3] = -1 * plane_params.dot (clust_centroid); + + vp -= clust_centroid; + float cos_theta = vp.dot (plane_params); + if (cos_theta < 0) + { + plane_params *= -1; + plane_params[3] = 0; + plane_params[3] = -1 * plane_params.dot (clust_centroid); + } + + // Compute the curvature surface change + float curvature; + float eig_sum = clust_cov.coeff (0) + clust_cov.coeff (4) + clust_cov.coeff (8); + if (eig_sum != 0) + curvature = fabsf (eigen_value / eig_sum); + else + curvature = 0; + + if (curvature < maximum_curvature_) + { + model.values[0] = plane_params[0]; + model.values[1] = plane_params[1]; + model.values[2] = plane_params[2]; + model.values[3] = plane_params[3]; + model_coefficients.push_back (model); + inlier_indices.push_back (label_indices[i]); + centroids.push_back (clust_centroid); + covariances.push_back (clust_cov); + } + } + } + deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedMultiPlaneSegmentation::segment (std::vector, Eigen::aligned_allocator > >& regions) +{ + std::vector model_coefficients; + std::vector inlier_indices; + PointCloudLPtr labels (new PointCloudL); + std::vector label_indices; + std::vector boundary_indices; + pcl::PointCloud boundary_cloud; + std::vector > centroids; + std::vector > covariances; + segment (model_coefficients, inlier_indices, centroids, covariances, *labels, label_indices); + regions.resize (model_coefficients.size ()); + boundary_indices.resize (model_coefficients.size ()); + + for (size_t i = 0; i < model_coefficients.size (); i++) + { + boundary_cloud.resize (0); + pcl::OrganizedConnectedComponentSegmentation::findLabeledRegionBoundary (inlier_indices[i].indices[0], labels, boundary_indices[i]); + boundary_cloud.points.resize (boundary_indices[i].indices.size ()); + for (unsigned j = 0; j < boundary_indices[i].indices.size (); j++) + boundary_cloud.points[j] = input_->points[boundary_indices[i].indices[j]]; + + Eigen::Vector3f centroid = Eigen::Vector3f (centroids[i][0],centroids[i][1],centroids[i][2]); + Eigen::Vector4f model = Eigen::Vector4f (model_coefficients[i].values[0], + model_coefficients[i].values[1], + model_coefficients[i].values[2], + model_coefficients[i].values[3]); + regions[i] = PlanarRegion (centroid, + covariances[i], + static_cast (inlier_indices[i].indices.size ()), + boundary_cloud.points, + model); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedMultiPlaneSegmentation::segmentAndRefine (std::vector, Eigen::aligned_allocator > >& regions) +{ + std::vector model_coefficients; + std::vector inlier_indices; + PointCloudLPtr labels (new PointCloudL); + std::vector label_indices; + std::vector boundary_indices; + pcl::PointCloud boundary_cloud; + std::vector > centroids; + std::vector > covariances; + segment (model_coefficients, inlier_indices, centroids, covariances, *labels, label_indices); + refine (model_coefficients, inlier_indices, centroids, covariances, labels, label_indices); + regions.resize (model_coefficients.size ()); + boundary_indices.resize (model_coefficients.size ()); + + for (size_t i = 0; i < model_coefficients.size (); i++) + { + boundary_cloud.resize (0); + int max_inlier_idx = static_cast (inlier_indices[i].indices.size ()) - 1; + pcl::OrganizedConnectedComponentSegmentation::findLabeledRegionBoundary (inlier_indices[i].indices[max_inlier_idx], labels, boundary_indices[i]); + boundary_cloud.points.resize (boundary_indices[i].indices.size ()); + for (unsigned j = 0; j < boundary_indices[i].indices.size (); j++) + boundary_cloud.points[j] = input_->points[boundary_indices[i].indices[j]]; + + Eigen::Vector3f centroid = Eigen::Vector3f (centroids[i][0],centroids[i][1],centroids[i][2]); + Eigen::Vector4f model = Eigen::Vector4f (model_coefficients[i].values[0], + model_coefficients[i].values[1], + model_coefficients[i].values[2], + model_coefficients[i].values[3]); + + Eigen::Vector3f vp (0.0, 0.0, 0.0); + if (project_points_) + boundary_cloud = projectToPlaneFromViewpoint (boundary_cloud, model, centroid, vp); + + regions[i] = PlanarRegion (centroid, + covariances[i], + static_cast (inlier_indices[i].indices.size ()), + boundary_cloud.points, + model); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedMultiPlaneSegmentation::segmentAndRefine (std::vector, Eigen::aligned_allocator > >& regions, + std::vector& model_coefficients, + std::vector& inlier_indices, + PointCloudLPtr& labels, + std::vector& label_indices, + std::vector& boundary_indices) +{ + pcl::PointCloud boundary_cloud; + std::vector > centroids; + std::vector > covariances; + segment (model_coefficients, inlier_indices, centroids, covariances, *labels, label_indices); + refine (model_coefficients, inlier_indices, centroids, covariances, labels, label_indices); + regions.resize (model_coefficients.size ()); + boundary_indices.resize (model_coefficients.size ()); + + for (size_t i = 0; i < model_coefficients.size (); i++) + { + boundary_cloud.resize (0); + int max_inlier_idx = static_cast (inlier_indices[i].indices.size ()) - 1; + pcl::OrganizedConnectedComponentSegmentation::findLabeledRegionBoundary (inlier_indices[i].indices[max_inlier_idx], labels, boundary_indices[i]); + boundary_cloud.points.resize (boundary_indices[i].indices.size ()); + for (unsigned j = 0; j < boundary_indices[i].indices.size (); j++) + boundary_cloud.points[j] = input_->points[boundary_indices[i].indices[j]]; + + Eigen::Vector3f centroid = Eigen::Vector3f (centroids[i][0],centroids[i][1],centroids[i][2]); + Eigen::Vector4f model = Eigen::Vector4f (model_coefficients[i].values[0], + model_coefficients[i].values[1], + model_coefficients[i].values[2], + model_coefficients[i].values[3]); + + Eigen::Vector3f vp (0.0, 0.0, 0.0); + if (project_points_ && boundary_cloud.points.size () > 0) + boundary_cloud = projectToPlaneFromViewpoint (boundary_cloud, model, centroid, vp); + + regions[i] = PlanarRegion (centroid, + covariances[i], + static_cast (inlier_indices[i].indices.size ()), + boundary_cloud.points, + model); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedMultiPlaneSegmentation::refine (std::vector& model_coefficients, + std::vector& inlier_indices, + std::vector >&, + std::vector >&, + PointCloudLPtr& labels, + std::vector& label_indices) +{ + //List of lables to grow, and index of model corresponding to each label + std::vector grow_labels; + std::vector label_to_model; + grow_labels.resize (label_indices.size (), false); + label_to_model.resize (label_indices.size (), 0); + + for (size_t i = 0; i < model_coefficients.size (); i++) + { + int model_label = (*labels)[inlier_indices[i].indices[0]].label; + label_to_model[model_label] = static_cast (i); + grow_labels[model_label] = true; + } + + //refinement_compare_->setDistanceThreshold (0.015f, true); + refinement_compare_->setInputCloud (input_); + refinement_compare_->setLabels (labels); + refinement_compare_->setModelCoefficients (model_coefficients); + refinement_compare_->setRefineLabels (grow_labels); + refinement_compare_->setLabelToModel (label_to_model); + + //Do a first pass over the image, top to bottom, left to right + unsigned int current_row = 0; + unsigned int next_row = labels->width; + for (size_t rowIdx = 0; rowIdx < labels->height - 1; ++rowIdx, current_row = next_row, next_row += labels->width) + { + + for (unsigned colIdx = 0; colIdx < labels->width - 1; ++colIdx) + { + int current_label = (*labels)[current_row+colIdx].label; + int right_label = (*labels)[current_row+colIdx+1].label; + if (current_label < 0 || right_label < 0) + continue; + + //Check right + //bool test1 = false; + if (refinement_compare_->compare (current_row+colIdx, current_row+colIdx+1)) + { + //test1 = true; + labels->points[current_row+colIdx+1].label = current_label; + label_indices[label_to_model[current_label]].indices.push_back (current_row+colIdx+1); + inlier_indices[label_to_model[current_label]].indices.push_back (current_row+colIdx+1); + } + + int lower_label = (*labels)[next_row+colIdx].label; + if (lower_label < 0) + continue; + + //Check down + if (refinement_compare_->compare (current_row+colIdx, next_row+colIdx)) + { + labels->points[next_row+colIdx].label = current_label; + label_indices[label_to_model[current_label]].indices.push_back (next_row+colIdx); + inlier_indices[label_to_model[current_label]].indices.push_back (next_row+colIdx); + } + + }//col + }//row + + //Do a second pass over the image + current_row = labels->width * (labels->height - 1); + unsigned int prev_row = current_row - labels->width; + for (size_t rowIdx = 0; rowIdx < labels->height - 1; ++rowIdx, current_row = prev_row, prev_row -= labels->width) + { + for (int colIdx = labels->width - 1; colIdx >= 0; --colIdx) + { + int current_label = (*labels)[current_row+colIdx].label; + int left_label = (*labels)[current_row+colIdx-1].label; + if (current_label < 0 || left_label < 0) + continue; + + //Check left + if (refinement_compare_->compare (current_row+colIdx, current_row+colIdx-1)) + { + labels->points[current_row+colIdx-1].label = current_label; + label_indices[label_to_model[current_label]].indices.push_back (current_row+colIdx-1); + inlier_indices[label_to_model[current_label]].indices.push_back (current_row+colIdx-1); + } + + int upper_label = (*labels)[prev_row+colIdx].label; + if (upper_label < 0) + continue; + //Check up + if (refinement_compare_->compare (current_row+colIdx, prev_row+colIdx)) + { + labels->points[prev_row+colIdx].label = current_label; + label_indices[label_to_model[current_label]].indices.push_back (prev_row+colIdx); + inlier_indices[label_to_model[current_label]].indices.push_back (prev_row+colIdx); + } + }//col + }//row +} + +#define PCL_INSTANTIATE_OrganizedMultiPlaneSegmentation(T,NT,LT) template class PCL_EXPORTS pcl::OrganizedMultiPlaneSegmentation; + +#endif // PCL_SEGMENTATION_IMPL_MULTI_PLANE_SEGMENTATION_H_ diff --git a/pcl-1.7/pcl/segmentation/impl/planar_polygon_fusion.hpp b/pcl-1.7/pcl/segmentation/impl/planar_polygon_fusion.hpp new file mode 100644 index 0000000..971bb3f --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/planar_polygon_fusion.hpp @@ -0,0 +1,48 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SEGMENTATION_PLANAR_POLYGON_FUSION_HPP_ +#define PCL_SEGMENTATION_PLANAR_POLYGON_FUSION_HPP_ + +#include + + +///////////////////////////////////////////////////////////////////////////////////////////////////////////////// + +#define PCL_INSTANTIATE_PlanarPolygonFusion(T) template class PCL_EXPORTS pcl::PlanarPolygonFusion; + +#endif // PCL_SEGMENTATION_PLANAR_POLYGON_FUSION_HPP_ diff --git a/pcl-1.7/pcl/segmentation/impl/progressive_morphological_filter.hpp b/pcl-1.7/pcl/segmentation/impl/progressive_morphological_filter.hpp new file mode 100644 index 0000000..eaadf65 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/progressive_morphological_filter.hpp @@ -0,0 +1,152 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2014, RadiantBlue Technologies, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_SEGMENTATION_PROGRESSIVE_MORPHOLOGICAL_FILTER_HPP_ +#define PCL_SEGMENTATION_PROGRESSIVE_MORPHOLOGICAL_FILTER_HPP_ + +#include +#include +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::ProgressiveMorphologicalFilter::ProgressiveMorphologicalFilter () : + max_window_size_ (33), + slope_ (0.7f), + max_distance_ (10.0f), + initial_distance_ (0.15f), + cell_size_ (1.0f), + base_ (2.0f), + exponential_ (true) +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::ProgressiveMorphologicalFilter::~ProgressiveMorphologicalFilter () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ProgressiveMorphologicalFilter::extract (std::vector& ground) +{ + bool segmentation_is_possible = initCompute (); + if (!segmentation_is_possible) + { + deinitCompute (); + return; + } + + // Compute the series of window sizes and height thresholds + std::vector height_thresholds; + std::vector window_sizes; + int iteration = 0; + float window_size = 0.0f; + float height_threshold = 0.0f; + + while (window_size < max_window_size_) + { + // Determine the initial window size. + if (exponential_) + window_size = cell_size_ * (2.0f * std::pow (base_, iteration) + 1.0f); + else + window_size = cell_size_ * (2.0f * (iteration+1) * base_ + 1.0f); + + // Calculate the height threshold to be used in the next iteration. + if (iteration == 0) + height_threshold = initial_distance_; + else + height_threshold = slope_ * (window_size - window_sizes[iteration-1]) * cell_size_ + initial_distance_; + + // Enforce max distance on height threshold + if (height_threshold > max_distance_) + height_threshold = max_distance_; + + window_sizes.push_back (window_size); + height_thresholds.push_back (height_threshold); + + iteration++; + } + + // Ground indices are initially limited to those points in the input cloud we + // wish to process + ground = *indices_; + + // Progressively filter ground returns using morphological open + for (size_t i = 0; i < window_sizes.size (); ++i) + { + PCL_DEBUG (" Iteration %d (height threshold = %f, window size = %f)...", + i, height_thresholds[i], window_sizes[i]); + + // Limit filtering to those points currently considered ground returns + typename pcl::PointCloud::Ptr cloud (new pcl::PointCloud); + pcl::copyPointCloud (*input_, ground, *cloud); + + // Create new cloud to hold the filtered results. Apply the morphological + // opening operation at the current window size. + typename pcl::PointCloud::Ptr cloud_f (new pcl::PointCloud); + pcl::applyMorphologicalOperator (cloud, window_sizes[i], MORPH_OPEN, *cloud_f); + + // Find indices of the points whose difference between the source and + // filtered point clouds is less than the current height threshold. + std::vector pt_indices; + for (size_t p_idx = 0; p_idx < ground.size (); ++p_idx) + { + float diff = cloud->points[p_idx].z - cloud_f->points[p_idx].z; + if (diff < height_thresholds[i]) + pt_indices.push_back (ground[p_idx]); + } + + // Ground is now limited to pt_indices + ground.swap (pt_indices); + + PCL_DEBUG ("ground now has %d points\n", ground.size ()); + } + + deinitCompute (); +} + +#define PCL_INSTANTIATE_ProgressiveMorphologicalFilter(T) template class pcl::ProgressiveMorphologicalFilter; + +#endif // PCL_SEGMENTATION_PROGRESSIVE_MORPHOLOGICAL_FILTER_HPP_ + diff --git a/pcl-1.7/pcl/segmentation/impl/region_growing.hpp b/pcl-1.7/pcl/segmentation/impl/region_growing.hpp new file mode 100644 index 0000000..a682fe8 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/region_growing.hpp @@ -0,0 +1,758 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : Sergey Ushakov + * Email : mine_all_mine@bk.ru + * + */ + +#ifndef PCL_SEGMENTATION_REGION_GROWING_HPP_ +#define PCL_SEGMENTATION_REGION_GROWING_HPP_ + +#include + +#include +#include +#include +#include + +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::RegionGrowing::RegionGrowing () : + min_pts_per_cluster_ (1), + max_pts_per_cluster_ (std::numeric_limits::max ()), + smooth_mode_flag_ (true), + curvature_flag_ (true), + residual_flag_ (false), + theta_threshold_ (30.0f / 180.0f * static_cast (M_PI)), + residual_threshold_ (0.05f), + curvature_threshold_ (0.05f), + neighbour_number_ (30), + search_ (), + normals_ (), + point_neighbours_ (0), + point_labels_ (0), + normal_flag_ (true), + num_pts_in_segment_ (0), + clusters_ (0), + number_of_segments_ (0) +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::RegionGrowing::~RegionGrowing () +{ + if (search_ != 0) + search_.reset (); + if (normals_ != 0) + normals_.reset (); + + point_neighbours_.clear (); + point_labels_.clear (); + num_pts_in_segment_.clear (); + clusters_.clear (); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::RegionGrowing::getMinClusterSize () +{ + return (min_pts_per_cluster_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::setMinClusterSize (int min_cluster_size) +{ + min_pts_per_cluster_ = min_cluster_size; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::RegionGrowing::getMaxClusterSize () +{ + return (max_pts_per_cluster_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::setMaxClusterSize (int max_cluster_size) +{ + max_pts_per_cluster_ = max_cluster_size; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::RegionGrowing::getSmoothModeFlag () const +{ + return (smooth_mode_flag_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::setSmoothModeFlag (bool value) +{ + smooth_mode_flag_ = value; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::RegionGrowing::getCurvatureTestFlag () const +{ + return (curvature_flag_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::setCurvatureTestFlag (bool value) +{ + curvature_flag_ = value; + + if (curvature_flag_ == false && residual_flag_ == false) + residual_flag_ = true; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::RegionGrowing::getResidualTestFlag () const +{ + return (residual_flag_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::setResidualTestFlag (bool value) +{ + residual_flag_ = value; + + if (curvature_flag_ == false && residual_flag_ == false) + curvature_flag_ = true; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::RegionGrowing::getSmoothnessThreshold () const +{ + return (theta_threshold_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::setSmoothnessThreshold (float theta) +{ + theta_threshold_ = theta; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::RegionGrowing::getResidualThreshold () const +{ + return (residual_threshold_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::setResidualThreshold (float residual) +{ + residual_threshold_ = residual; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::RegionGrowing::getCurvatureThreshold () const +{ + return (curvature_threshold_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::setCurvatureThreshold (float curvature) +{ + curvature_threshold_ = curvature; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template unsigned int +pcl::RegionGrowing::getNumberOfNeighbours () const +{ + return (neighbour_number_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::setNumberOfNeighbours (unsigned int neighbour_number) +{ + neighbour_number_ = neighbour_number; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::RegionGrowing::KdTreePtr +pcl::RegionGrowing::getSearchMethod () const +{ + return (search_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::setSearchMethod (const KdTreePtr& tree) +{ + if (search_ != 0) + search_.reset (); + + search_ = tree; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::RegionGrowing::NormalPtr +pcl::RegionGrowing::getInputNormals () const +{ + return (normals_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::setInputNormals (const NormalPtr& norm) +{ + if (normals_ != 0) + normals_.reset (); + + normals_ = norm; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::extract (std::vector & clusters) +{ + clusters_.clear (); + clusters.clear (); + point_neighbours_.clear (); + point_labels_.clear (); + num_pts_in_segment_.clear (); + number_of_segments_ = 0; + + bool segmentation_is_possible = initCompute (); + if ( !segmentation_is_possible ) + { + deinitCompute (); + return; + } + + segmentation_is_possible = prepareForSegmentation (); + if ( !segmentation_is_possible ) + { + deinitCompute (); + return; + } + + findPointNeighbours (); + applySmoothRegionGrowingAlgorithm (); + assembleRegions (); + + clusters.resize (clusters_.size ()); + std::vector::iterator cluster_iter_input = clusters.begin (); + for (std::vector::const_iterator cluster_iter = clusters_.begin (); cluster_iter != clusters_.end (); cluster_iter++) + { + if ((static_cast (cluster_iter->indices.size ()) >= min_pts_per_cluster_) && + (static_cast (cluster_iter->indices.size ()) <= max_pts_per_cluster_)) + { + *cluster_iter_input = *cluster_iter; + cluster_iter_input++; + } + } + + clusters_ = std::vector (clusters.begin (), cluster_iter_input); + clusters.resize(clusters_.size()); + + deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::RegionGrowing::prepareForSegmentation () +{ + // if user forgot to pass point cloud or if it is empty + if ( input_->points.size () == 0 ) + return (false); + + // if user forgot to pass normals or the sizes of point and normal cloud are different + if ( normals_ == 0 || input_->points.size () != normals_->points.size () ) + return (false); + + // if residual test is on then we need to check if all needed parameters were correctly initialized + if (residual_flag_) + { + if (residual_threshold_ <= 0.0f) + return (false); + } + + // if curvature test is on ... + // if (curvature_flag_) + // { + // in this case we do not need to check anything that related to it + // so we simply commented it + // } + + // from here we check those parameters that are always valuable + if (neighbour_number_ == 0) + return (false); + + // if user didn't set search method + if (!search_) + search_.reset (new pcl::search::KdTree); + + if (indices_) + { + if (indices_->empty ()) + PCL_ERROR ("[pcl::RegionGrowing::prepareForSegmentation] Empty given indices!\n"); + search_->setInputCloud (input_, indices_); + } + else + search_->setInputCloud (input_); + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::findPointNeighbours () +{ + int point_number = static_cast (indices_->size ()); + std::vector neighbours; + std::vector distances; + + point_neighbours_.resize (input_->points.size (), neighbours); + if (input_->is_dense) + { + for (int i_point = 0; i_point < point_number; i_point++) + { + int point_index = (*indices_)[i_point]; + neighbours.clear (); + search_->nearestKSearch (i_point, neighbour_number_, neighbours, distances); + point_neighbours_[point_index].swap (neighbours); + } + } + else + { + for (int i_point = 0; i_point < point_number; i_point++) + { + neighbours.clear (); + int point_index = (*indices_)[i_point]; + if (!pcl::isFinite (input_->points[point_index])) + continue; + search_->nearestKSearch (i_point, neighbour_number_, neighbours, distances); + point_neighbours_[point_index].swap (neighbours); + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::applySmoothRegionGrowingAlgorithm () +{ + int num_of_pts = static_cast (indices_->size ()); + point_labels_.resize (input_->points.size (), -1); + + std::vector< std::pair > point_residual; + std::pair pair; + point_residual.resize (num_of_pts, pair); + + if (normal_flag_ == true) + { + for (int i_point = 0; i_point < num_of_pts; i_point++) + { + int point_index = (*indices_)[i_point]; + point_residual[i_point].first = normals_->points[point_index].curvature; + point_residual[i_point].second = point_index; + } + std::sort (point_residual.begin (), point_residual.end (), comparePair); + } + else + { + for (int i_point = 0; i_point < num_of_pts; i_point++) + { + int point_index = (*indices_)[i_point]; + point_residual[i_point].first = 0; + point_residual[i_point].second = point_index; + } + } + int seed_counter = 0; + int seed = point_residual[seed_counter].second; + + int segmented_pts_num = 0; + int number_of_segments = 0; + while (segmented_pts_num < num_of_pts) + { + int pts_in_segment; + pts_in_segment = growRegion (seed, number_of_segments); + segmented_pts_num += pts_in_segment; + num_pts_in_segment_.push_back (pts_in_segment); + number_of_segments++; + + //find next point that is not segmented yet + for (int i_seed = seed_counter + 1; i_seed < num_of_pts; i_seed++) + { + int index = point_residual[i_seed].second; + if (point_labels_[index] == -1) + { + seed = index; + break; + } + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::RegionGrowing::growRegion (int initial_seed, int segment_number) +{ + std::queue seeds; + seeds.push (initial_seed); + point_labels_[initial_seed] = segment_number; + + int num_pts_in_segment = 1; + + while (!seeds.empty ()) + { + int curr_seed; + curr_seed = seeds.front (); + seeds.pop (); + + size_t i_nghbr = 0; + while ( i_nghbr < neighbour_number_ && i_nghbr < point_neighbours_[curr_seed].size () ) + { + int index = point_neighbours_[curr_seed][i_nghbr]; + if (point_labels_[index] != -1) + { + i_nghbr++; + continue; + } + + bool is_a_seed = false; + bool belongs_to_segment = validatePoint (initial_seed, curr_seed, index, is_a_seed); + + if (belongs_to_segment == false) + { + i_nghbr++; + continue; + } + + point_labels_[index] = segment_number; + num_pts_in_segment++; + + if (is_a_seed) + { + seeds.push (index); + } + + i_nghbr++; + }// next neighbour + }// next seed + + return (num_pts_in_segment); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::RegionGrowing::validatePoint (int initial_seed, int point, int nghbr, bool& is_a_seed) const +{ + is_a_seed = true; + + float cosine_threshold = cosf (theta_threshold_); + float data[4]; + + data[0] = input_->points[point].data[0]; + data[1] = input_->points[point].data[1]; + data[2] = input_->points[point].data[2]; + data[3] = input_->points[point].data[3]; + Eigen::Map initial_point (static_cast (data)); + Eigen::Map initial_normal (static_cast (normals_->points[point].normal)); + + //check the angle between normals + if (smooth_mode_flag_ == true) + { + Eigen::Map nghbr_normal (static_cast (normals_->points[nghbr].normal)); + float dot_product = fabsf (nghbr_normal.dot (initial_normal)); + if (dot_product < cosine_threshold) + { + return (false); + } + } + else + { + Eigen::Map nghbr_normal (static_cast (normals_->points[nghbr].normal)); + Eigen::Map initial_seed_normal (static_cast (normals_->points[initial_seed].normal)); + float dot_product = fabsf (nghbr_normal.dot (initial_seed_normal)); + if (dot_product < cosine_threshold) + return (false); + } + + // check the curvature if needed + if (curvature_flag_ && normals_->points[nghbr].curvature > curvature_threshold_) + { + is_a_seed = false; + } + + // check the residual if needed + data[0] = input_->points[nghbr].data[0]; + data[1] = input_->points[nghbr].data[1]; + data[2] = input_->points[nghbr].data[2]; + data[3] = input_->points[nghbr].data[3]; + Eigen::Map nghbr_point (static_cast (data)); + float residual = fabsf (initial_normal.dot (initial_point - nghbr_point)); + if (residual_flag_ && residual > residual_threshold_) + is_a_seed = false; + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::assembleRegions () +{ + int number_of_segments = static_cast (num_pts_in_segment_.size ()); + int number_of_points = static_cast (input_->points.size ()); + + pcl::PointIndices segment; + clusters_.resize (number_of_segments, segment); + + for (int i_seg = 0; i_seg < number_of_segments; i_seg++) + { + clusters_[i_seg].indices.resize ( num_pts_in_segment_[i_seg], 0); + } + + std::vector counter; + counter.resize (number_of_segments, 0); + + for (int i_point = 0; i_point < number_of_points; i_point++) + { + int segment_index = point_labels_[i_point]; + if (segment_index != -1) + { + int point_index = counter[segment_index]; + clusters_[segment_index].indices[point_index] = i_point; + counter[segment_index] = point_index + 1; + } + } + + number_of_segments_ = number_of_segments; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowing::getSegmentFromPoint (int index, pcl::PointIndices& cluster) +{ + cluster.indices.clear (); + + bool segmentation_is_possible = initCompute (); + if ( !segmentation_is_possible ) + { + deinitCompute (); + return; + } + + // first of all we need to find out if this point belongs to cloud + bool point_was_found = false; + int number_of_points = static_cast (indices_->size ()); + for (int point = 0; point < number_of_points; point++) + if ( (*indices_)[point] == index) + { + point_was_found = true; + break; + } + + if (point_was_found) + { + if (clusters_.empty ()) + { + point_neighbours_.clear (); + point_labels_.clear (); + num_pts_in_segment_.clear (); + number_of_segments_ = 0; + + segmentation_is_possible = prepareForSegmentation (); + if ( !segmentation_is_possible ) + { + deinitCompute (); + return; + } + + findPointNeighbours (); + applySmoothRegionGrowingAlgorithm (); + assembleRegions (); + } + // if we have already made the segmentation, then find the segment + // to which this point belongs + std::vector ::iterator i_segment; + for (i_segment = clusters_.begin (); i_segment != clusters_.end (); i_segment++) + { + bool segment_was_found = false; + for (size_t i_point = 0; i_point < i_segment->indices.size (); i_point++) + { + if (i_segment->indices[i_point] == index) + { + segment_was_found = true; + cluster.indices.clear (); + cluster.indices.reserve (i_segment->indices.size ()); + std::copy (i_segment->indices.begin (), i_segment->indices.end (), std::back_inserter (cluster.indices)); + break; + } + } + if (segment_was_found) + { + break; + } + }// next segment + }// end if point was found + + deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template pcl::PointCloud::Ptr +pcl::RegionGrowing::getColoredCloud () +{ + pcl::PointCloud::Ptr colored_cloud; + + if (!clusters_.empty ()) + { + colored_cloud = (new pcl::PointCloud)->makeShared (); + + srand (static_cast (time (0))); + std::vector colors; + for (size_t i_segment = 0; i_segment < clusters_.size (); i_segment++) + { + colors.push_back (static_cast (rand () % 256)); + colors.push_back (static_cast (rand () % 256)); + colors.push_back (static_cast (rand () % 256)); + } + + colored_cloud->width = input_->width; + colored_cloud->height = input_->height; + colored_cloud->is_dense = input_->is_dense; + for (size_t i_point = 0; i_point < input_->points.size (); i_point++) + { + pcl::PointXYZRGB point; + point.x = *(input_->points[i_point].data); + point.y = *(input_->points[i_point].data + 1); + point.z = *(input_->points[i_point].data + 2); + point.r = 255; + point.g = 0; + point.b = 0; + colored_cloud->points.push_back (point); + } + + std::vector< pcl::PointIndices >::iterator i_segment; + int next_color = 0; + for (i_segment = clusters_.begin (); i_segment != clusters_.end (); i_segment++) + { + std::vector::iterator i_point; + for (i_point = i_segment->indices.begin (); i_point != i_segment->indices.end (); i_point++) + { + int index; + index = *i_point; + colored_cloud->points[index].r = colors[3 * next_color]; + colored_cloud->points[index].g = colors[3 * next_color + 1]; + colored_cloud->points[index].b = colors[3 * next_color + 2]; + } + next_color++; + } + } + + return (colored_cloud); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template pcl::PointCloud::Ptr +pcl::RegionGrowing::getColoredCloudRGBA () +{ + pcl::PointCloud::Ptr colored_cloud; + + if (!clusters_.empty ()) + { + colored_cloud = (new pcl::PointCloud)->makeShared (); + + srand (static_cast (time (0))); + std::vector colors; + for (size_t i_segment = 0; i_segment < clusters_.size (); i_segment++) + { + colors.push_back (static_cast (rand () % 256)); + colors.push_back (static_cast (rand () % 256)); + colors.push_back (static_cast (rand () % 256)); + } + + colored_cloud->width = input_->width; + colored_cloud->height = input_->height; + colored_cloud->is_dense = input_->is_dense; + for (size_t i_point = 0; i_point < input_->points.size (); i_point++) + { + pcl::PointXYZRGBA point; + point.x = *(input_->points[i_point].data); + point.y = *(input_->points[i_point].data + 1); + point.z = *(input_->points[i_point].data + 2); + point.r = 255; + point.g = 0; + point.b = 0; + point.a = 0; + colored_cloud->points.push_back (point); + } + + std::vector< pcl::PointIndices >::iterator i_segment; + int next_color = 0; + for (i_segment = clusters_.begin (); i_segment != clusters_.end (); i_segment++) + { + std::vector::iterator i_point; + for (i_point = i_segment->indices.begin (); i_point != i_segment->indices.end (); i_point++) + { + int index; + index = *i_point; + colored_cloud->points[index].r = colors[3 * next_color]; + colored_cloud->points[index].g = colors[3 * next_color + 1]; + colored_cloud->points[index].b = colors[3 * next_color + 2]; + } + next_color++; + } + } + + return (colored_cloud); +} + +#define PCL_INSTANTIATE_RegionGrowing(T) template class pcl::RegionGrowing; + +#endif // PCL_SEGMENTATION_REGION_GROWING_HPP_ diff --git a/pcl-1.7/pcl/segmentation/impl/region_growing_rgb.hpp b/pcl-1.7/pcl/segmentation/impl/region_growing_rgb.hpp new file mode 100644 index 0000000..a49fa68 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/region_growing_rgb.hpp @@ -0,0 +1,767 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : Sergey Ushakov + * Email : mine_all_mine@bk.ru + * + */ + +#ifndef PCL_SEGMENTATION_REGION_GROWING_RGB_HPP_ +#define PCL_SEGMENTATION_REGION_GROWING_RGB_HPP_ + +#include +#include +#include + +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::RegionGrowingRGB::RegionGrowingRGB () : + color_p2p_threshold_ (1225.0f), + color_r2r_threshold_ (10.0f), + distance_threshold_ (0.05f), + region_neighbour_number_ (100), + point_distances_ (0), + segment_neighbours_ (0), + segment_distances_ (0), + segment_labels_ (0) +{ + normal_flag_ = false; + curvature_flag_ = false; + residual_flag_ = false; + min_pts_per_cluster_ = 10; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::RegionGrowingRGB::~RegionGrowingRGB () +{ + point_distances_.clear (); + segment_neighbours_.clear (); + segment_distances_.clear (); + segment_labels_.clear (); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::RegionGrowingRGB::getPointColorThreshold () const +{ + return (powf (color_p2p_threshold_, 0.5f)); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::setPointColorThreshold (float thresh) +{ + color_p2p_threshold_ = thresh * thresh; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::RegionGrowingRGB::getRegionColorThreshold () const +{ + return (powf (color_r2r_threshold_, 0.5f)); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::setRegionColorThreshold (float thresh) +{ + color_r2r_threshold_ = thresh * thresh; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::RegionGrowingRGB::getDistanceThreshold () const +{ + return (powf (distance_threshold_, 0.5f)); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::setDistanceThreshold (float thresh) +{ + distance_threshold_ = thresh * thresh; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template unsigned int +pcl::RegionGrowingRGB::getNumberOfRegionNeighbours () const +{ + return (region_neighbour_number_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::setNumberOfRegionNeighbours (unsigned int nghbr_number) +{ + region_neighbour_number_ = nghbr_number; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::RegionGrowingRGB::getNormalTestFlag () const +{ + return (normal_flag_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::setNormalTestFlag (bool value) +{ + normal_flag_ = value; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::setCurvatureTestFlag (bool value) +{ + curvature_flag_ = value; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::setResidualTestFlag (bool value) +{ + residual_flag_ = value; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::extract (std::vector & clusters) +{ + clusters_.clear (); + clusters.clear (); + point_neighbours_.clear (); + point_labels_.clear (); + num_pts_in_segment_.clear (); + point_distances_.clear (); + segment_neighbours_.clear (); + segment_distances_.clear (); + segment_labels_.clear (); + number_of_segments_ = 0; + + bool segmentation_is_possible = initCompute (); + if ( !segmentation_is_possible ) + { + deinitCompute (); + return; + } + + segmentation_is_possible = prepareForSegmentation (); + if ( !segmentation_is_possible ) + { + deinitCompute (); + return; + } + + findPointNeighbours (); + applySmoothRegionGrowingAlgorithm (); + RegionGrowing::assembleRegions (); + + findSegmentNeighbours (); + applyRegionMergingAlgorithm (); + + std::vector::iterator cluster_iter = clusters_.begin (); + while (cluster_iter != clusters_.end ()) + { + if (static_cast (cluster_iter->indices.size ()) < min_pts_per_cluster_ || + static_cast (cluster_iter->indices.size ()) > max_pts_per_cluster_) + { + cluster_iter = clusters_.erase (cluster_iter); + } + else + cluster_iter++; + } + + clusters.reserve (clusters_.size ()); + std::copy (clusters_.begin (), clusters_.end (), std::back_inserter (clusters)); + + deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::RegionGrowingRGB::prepareForSegmentation () +{ + // if user forgot to pass point cloud or if it is empty + if ( input_->points.size () == 0 ) + return (false); + + // if normal/smoothness test is on then we need to check if all needed variables and parameters + // were correctly initialized + if (normal_flag_) + { + // if user forgot to pass normals or the sizes of point and normal cloud are different + if ( normals_ == 0 || input_->points.size () != normals_->points.size () ) + return (false); + } + + // if residual test is on then we need to check if all needed parameters were correctly initialized + if (residual_flag_) + { + if (residual_threshold_ <= 0.0f) + return (false); + } + + // if curvature test is on ... + // if (curvature_flag_) + // { + // in this case we do not need to check anything that related to it + // so we simply commented it + // } + + // here we check the parameters related to color-based segmentation + if ( region_neighbour_number_ == 0 || color_p2p_threshold_ < 0.0f || color_r2r_threshold_ < 0.0f || distance_threshold_ < 0.0f ) + return (false); + + // from here we check those parameters that are always valuable + if (neighbour_number_ == 0) + return (false); + + // if user didn't set search method + if (!search_) + search_.reset (new pcl::search::KdTree); + + if (indices_) + { + if (indices_->empty ()) + PCL_ERROR ("[pcl::RegionGrowingRGB::prepareForSegmentation] Empty given indices!\n"); + search_->setInputCloud (input_, indices_); + } + else + search_->setInputCloud (input_); + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::findPointNeighbours () +{ + int point_number = static_cast (indices_->size ()); + std::vector neighbours; + std::vector distances; + + point_neighbours_.resize (input_->points.size (), neighbours); + point_distances_.resize (input_->points.size (), distances); + + for (int i_point = 0; i_point < point_number; i_point++) + { + int point_index = (*indices_)[i_point]; + neighbours.clear (); + distances.clear (); + search_->nearestKSearch (i_point, region_neighbour_number_, neighbours, distances); + point_neighbours_[point_index].swap (neighbours); + point_distances_[point_index].swap (distances); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::findSegmentNeighbours () +{ + std::vector neighbours; + std::vector distances; + segment_neighbours_.resize (number_of_segments_, neighbours); + segment_distances_.resize (number_of_segments_, distances); + + for (int i_seg = 0; i_seg < number_of_segments_; i_seg++) + { + std::vector nghbrs; + std::vector dist; + findRegionsKNN (i_seg, region_neighbour_number_, nghbrs, dist); + segment_neighbours_[i_seg].swap (nghbrs); + segment_distances_[i_seg].swap (dist); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::findRegionsKNN (int index, int nghbr_number, std::vector& nghbrs, std::vector& dist) +{ + std::vector distances; + float max_dist = std::numeric_limits::max (); + distances.resize (clusters_.size (), max_dist); + + int number_of_points = num_pts_in_segment_[index]; + //loop throug every point in this segment and check neighbours + for (int i_point = 0; i_point < number_of_points; i_point++) + { + int point_index = clusters_[index].indices[i_point]; + int number_of_neighbours = static_cast (point_neighbours_[point_index].size ()); + //loop throug every neighbour of the current point, find out to which segment it belongs + //and if it belongs to neighbouring segment and is close enough then remember segment and its distance + for (int i_nghbr = 0; i_nghbr < number_of_neighbours; i_nghbr++) + { + // find segment + int segment_index = -1; + segment_index = point_labels_[ point_neighbours_[point_index][i_nghbr] ]; + + if ( segment_index != index ) + { + // try to push it to the queue + if (distances[segment_index] > point_distances_[point_index][i_nghbr]) + distances[segment_index] = point_distances_[point_index][i_nghbr]; + } + } + }// next point + + std::priority_queue > segment_neighbours; + for (int i_seg = 0; i_seg < number_of_segments_; i_seg++) + { + if (distances[i_seg] < max_dist) + { + segment_neighbours.push (std::make_pair (distances[i_seg], i_seg) ); + if (int (segment_neighbours.size ()) > nghbr_number) + segment_neighbours.pop (); + } + } + + int size = std::min (static_cast (segment_neighbours.size ()), nghbr_number); + nghbrs.resize (size, 0); + dist.resize (size, 0); + int counter = 0; + while ( !segment_neighbours.empty () && counter < nghbr_number ) + { + dist[counter] = segment_neighbours.top ().first; + nghbrs[counter] = segment_neighbours.top ().second; + segment_neighbours.pop (); + counter++; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::applyRegionMergingAlgorithm () +{ + int number_of_points = static_cast (indices_->size ()); + + // calculate color of each segment + std::vector< std::vector > segment_color; + std::vector color; + color.resize (3, 0); + segment_color.resize (number_of_segments_, color); + + for (int i_point = 0; i_point < number_of_points; i_point++) + { + int point_index = (*indices_)[i_point]; + int segment_index = point_labels_[point_index]; + segment_color[segment_index][0] += input_->points[point_index].r; + segment_color[segment_index][1] += input_->points[point_index].g; + segment_color[segment_index][2] += input_->points[point_index].b; + } + for (int i_seg = 0; i_seg < number_of_segments_; i_seg++) + { + segment_color[i_seg][0] = static_cast (static_cast (segment_color[i_seg][0]) / static_cast (num_pts_in_segment_[i_seg])); + segment_color[i_seg][1] = static_cast (static_cast (segment_color[i_seg][1]) / static_cast (num_pts_in_segment_[i_seg])); + segment_color[i_seg][2] = static_cast (static_cast (segment_color[i_seg][2]) / static_cast (num_pts_in_segment_[i_seg])); + } + + // now it is time to find out if there are segments with a similar color + // and merge them together + std::vector num_pts_in_homogeneous_region; + std::vector num_seg_in_homogeneous_region; + + segment_labels_.resize (number_of_segments_, -1); + + float dist_thresh = distance_threshold_; + int homogeneous_region_number = 0; + int curr_homogeneous_region = 0; + for (int i_seg = 0; i_seg < number_of_segments_; i_seg++) + { + curr_homogeneous_region = 0; + if (segment_labels_[i_seg] == -1) + { + segment_labels_[i_seg] = homogeneous_region_number; + curr_homogeneous_region = homogeneous_region_number; + num_pts_in_homogeneous_region.push_back (num_pts_in_segment_[i_seg]); + num_seg_in_homogeneous_region.push_back (1); + homogeneous_region_number++; + } + else + curr_homogeneous_region = segment_labels_[i_seg]; + + unsigned int i_nghbr = 0; + while ( i_nghbr < region_neighbour_number_ && i_nghbr < segment_neighbours_[i_seg].size () ) + { + int index = segment_neighbours_[i_seg][i_nghbr]; + if (segment_distances_[i_seg][i_nghbr] > dist_thresh) + { + i_nghbr++; + continue; + } + if ( segment_labels_[index] == -1 ) + { + float difference = calculateColorimetricalDifference (segment_color[i_seg], segment_color[index]); + if (difference < color_r2r_threshold_) + { + segment_labels_[index] = curr_homogeneous_region; + num_pts_in_homogeneous_region[curr_homogeneous_region] += num_pts_in_segment_[index]; + num_seg_in_homogeneous_region[curr_homogeneous_region] += 1; + } + } + i_nghbr++; + }// next neighbour + }// next segment + + segment_color.clear (); + color.clear (); + + std::vector< std::vector > final_segments; + std::vector region; + final_segments.resize (homogeneous_region_number, region); + for (int i_reg = 0; i_reg < homogeneous_region_number; i_reg++) + { + final_segments[i_reg].resize (num_seg_in_homogeneous_region[i_reg], 0); + } + + std::vector counter; + counter.resize (homogeneous_region_number, 0); + for (int i_seg = 0; i_seg < number_of_segments_; i_seg++) + { + int index = segment_labels_[i_seg]; + final_segments[ index ][ counter[index] ] = i_seg; + counter[index] += 1; + } + + std::vector< std::vector< std::pair > > region_neighbours; + findRegionNeighbours (region_neighbours, final_segments); + + int final_segment_number = homogeneous_region_number; + for (int i_reg = 0; i_reg < homogeneous_region_number; i_reg++) + { + if (static_cast (num_pts_in_homogeneous_region[i_reg]) < min_pts_per_cluster_) + { + if ( region_neighbours[i_reg].empty () ) + continue; + int nearest_neighbour = region_neighbours[i_reg][0].second; + if ( region_neighbours[i_reg][0].first == std::numeric_limits::max () ) + continue; + int reg_index = segment_labels_[nearest_neighbour]; + int num_seg_in_reg = num_seg_in_homogeneous_region[i_reg]; + for (int i_seg = 0; i_seg < num_seg_in_reg; i_seg++) + { + int segment_index = final_segments[i_reg][i_seg]; + final_segments[reg_index].push_back (segment_index); + segment_labels_[segment_index] = reg_index; + } + final_segments[i_reg].clear (); + num_pts_in_homogeneous_region[reg_index] += num_pts_in_homogeneous_region[i_reg]; + num_pts_in_homogeneous_region[i_reg] = 0; + num_seg_in_homogeneous_region[reg_index] += num_seg_in_homogeneous_region[i_reg]; + num_seg_in_homogeneous_region[i_reg] = 0; + final_segment_number -= 1; + + int nghbr_number = static_cast (region_neighbours[reg_index].size ()); + for (int i_nghbr = 0; i_nghbr < nghbr_number; i_nghbr++) + { + if ( segment_labels_[ region_neighbours[reg_index][i_nghbr].second ] == reg_index ) + { + region_neighbours[reg_index][i_nghbr].first = std::numeric_limits::max (); + region_neighbours[reg_index][i_nghbr].second = 0; + } + } + nghbr_number = static_cast (region_neighbours[i_reg].size ()); + for (int i_nghbr = 0; i_nghbr < nghbr_number; i_nghbr++) + { + if ( segment_labels_[ region_neighbours[i_reg][i_nghbr].second ] != reg_index ) + { + std::pair pair; + pair.first = region_neighbours[i_reg][i_nghbr].first; + pair.second = region_neighbours[i_reg][i_nghbr].second; + region_neighbours[reg_index].push_back (pair); + } + } + region_neighbours[i_reg].clear (); + std::sort (region_neighbours[reg_index].begin (), region_neighbours[reg_index].end (), comparePair); + } + } + + assembleRegions (num_pts_in_homogeneous_region, static_cast (num_pts_in_homogeneous_region.size ())); + + number_of_segments_ = final_segment_number; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::RegionGrowingRGB::calculateColorimetricalDifference (std::vector& first_color, std::vector& second_color) const +{ + float difference = 0.0f; + difference += float ((first_color[0] - second_color[0]) * (first_color[0] - second_color[0])); + difference += float ((first_color[1] - second_color[1]) * (first_color[1] - second_color[1])); + difference += float ((first_color[2] - second_color[2]) * (first_color[2] - second_color[2])); + return (difference); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::findRegionNeighbours (std::vector< std::vector< std::pair > >& neighbours_out, std::vector< std::vector >& regions_in) +{ + int region_number = static_cast (regions_in.size ()); + neighbours_out.clear (); + neighbours_out.resize (region_number); + + for (int i_reg = 0; i_reg < region_number; i_reg++) + { + int segment_num = static_cast (regions_in[i_reg].size ()); + neighbours_out[i_reg].reserve (segment_num * region_neighbour_number_); + for (int i_seg = 0; i_seg < segment_num; i_seg++) + { + int curr_segment = regions_in[i_reg][i_seg]; + int nghbr_number = static_cast (segment_neighbours_[curr_segment].size ()); + std::pair pair; + for (int i_nghbr = 0; i_nghbr < nghbr_number; i_nghbr++) + { + int segment_index = segment_neighbours_[curr_segment][i_nghbr]; + if ( segment_distances_[curr_segment][i_nghbr] == std::numeric_limits::max () ) + continue; + if (segment_labels_[segment_index] != i_reg) + { + pair.first = segment_distances_[curr_segment][i_nghbr]; + pair.second = segment_index; + neighbours_out[i_reg].push_back (pair); + } + }// next neighbour + }// next segment + std::sort (neighbours_out[i_reg].begin (), neighbours_out[i_reg].end (), comparePair); + }// next homogeneous region +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::assembleRegions (std::vector& num_pts_in_region, int num_regions) +{ + clusters_.clear (); + pcl::PointIndices segment; + clusters_.resize (num_regions, segment); + for (int i_seg = 0; i_seg < num_regions; i_seg++) + { + clusters_[i_seg].indices.resize (num_pts_in_region[i_seg]); + } + + std::vector counter; + counter.resize (num_regions, 0); + int point_number = static_cast (indices_->size ()); + for (int i_point = 0; i_point < point_number; i_point++) + { + int point_index = (*indices_)[i_point]; + int index = point_labels_[point_index]; + index = segment_labels_[index]; + clusters_[index].indices[ counter[index] ] = point_index; + counter[index] += 1; + } + + // now we need to erase empty regions + if (clusters_.empty ()) + return; + + std::vector::iterator itr1, itr2; + itr1 = clusters_.begin (); + itr2 = clusters_.end () - 1; + + while (itr1 < itr2) + { + while (!(itr1->indices.empty ()) && itr1 < itr2) + itr1++; + while ( itr2->indices.empty () && itr1 < itr2) + itr2--; + + if (itr1 != itr2) + itr1->indices.swap (itr2->indices); + } + + if (itr2->indices.empty ()) + clusters_.erase (itr2, clusters_.end ()); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::RegionGrowingRGB::validatePoint (int initial_seed, int point, int nghbr, bool& is_a_seed) const +{ + is_a_seed = true; + + // check the color difference + std::vector point_color; + point_color.resize (3, 0); + std::vector nghbr_color; + nghbr_color.resize (3, 0); + point_color[0] = input_->points[point].r; + point_color[1] = input_->points[point].g; + point_color[2] = input_->points[point].b; + nghbr_color[0] = input_->points[nghbr].r; + nghbr_color[1] = input_->points[nghbr].g; + nghbr_color[2] = input_->points[nghbr].b; + float difference = calculateColorimetricalDifference (point_color, nghbr_color); + if (difference > color_p2p_threshold_) + return (false); + + float cosine_threshold = cosf (theta_threshold_); + + // check the angle between normals if needed + if (normal_flag_) + { + float data[4]; + data[0] = input_->points[point].data[0]; + data[1] = input_->points[point].data[1]; + data[2] = input_->points[point].data[2]; + data[3] = input_->points[point].data[3]; + + Eigen::Map initial_point (static_cast (data)); + Eigen::Map initial_normal (static_cast (normals_->points[point].normal)); + if (smooth_mode_flag_ == true) + { + Eigen::Map nghbr_normal (static_cast (normals_->points[nghbr].normal)); + float dot_product = fabsf (nghbr_normal.dot (initial_normal)); + if (dot_product < cosine_threshold) + return (false); + } + else + { + Eigen::Map nghbr_normal (static_cast (normals_->points[nghbr].normal)); + Eigen::Map initial_seed_normal (static_cast (normals_->points[initial_seed].normal)); + float dot_product = fabsf (nghbr_normal.dot (initial_seed_normal)); + if (dot_product < cosine_threshold) + return (false); + } + } + + // check the curvature if needed + if (curvature_flag_ && normals_->points[nghbr].curvature > curvature_threshold_) + is_a_seed = false; + + // check the residual if needed + if (residual_flag_) + { + float data_p[4]; + data_p[0] = input_->points[point].data[0]; + data_p[1] = input_->points[point].data[1]; + data_p[2] = input_->points[point].data[2]; + data_p[3] = input_->points[point].data[3]; + float data_n[4]; + data_n[0] = input_->points[nghbr].data[0]; + data_n[1] = input_->points[nghbr].data[1]; + data_n[2] = input_->points[nghbr].data[2]; + data_n[3] = input_->points[nghbr].data[3]; + Eigen::Map nghbr_point (static_cast (data_n)); + Eigen::Map initial_point (static_cast (data_p)); + Eigen::Map initial_normal (static_cast (normals_->points[point].normal)); + float residual = fabsf (initial_normal.dot (initial_point - nghbr_point)); + if (residual > residual_threshold_) + is_a_seed = false; + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegionGrowingRGB::getSegmentFromPoint (int index, pcl::PointIndices& cluster) +{ + cluster.indices.clear (); + + bool segmentation_is_possible = initCompute (); + if ( !segmentation_is_possible ) + { + deinitCompute (); + return; + } + + // first of all we need to find out if this point belongs to cloud + bool point_was_found = false; + int number_of_points = static_cast (indices_->size ()); + for (int point = 0; point < number_of_points; point++) + if ( (*indices_)[point] == index) + { + point_was_found = true; + break; + } + + if (point_was_found) + { + if (clusters_.empty ()) + { + clusters_.clear (); + point_neighbours_.clear (); + point_labels_.clear (); + num_pts_in_segment_.clear (); + point_distances_.clear (); + segment_neighbours_.clear (); + segment_distances_.clear (); + segment_labels_.clear (); + number_of_segments_ = 0; + + segmentation_is_possible = prepareForSegmentation (); + if ( !segmentation_is_possible ) + { + deinitCompute (); + return; + } + + findPointNeighbours (); + applySmoothRegionGrowingAlgorithm (); + RegionGrowing::assembleRegions (); + + findSegmentNeighbours (); + applyRegionMergingAlgorithm (); + } + // if we have already made the segmentation, then find the segment + // to which this point belongs + std::vector ::iterator i_segment; + for (i_segment = clusters_.begin (); i_segment != clusters_.end (); i_segment++) + { + bool segment_was_found = false; + for (size_t i_point = 0; i_point < i_segment->indices.size (); i_point++) + { + if (i_segment->indices[i_point] == index) + { + segment_was_found = true; + cluster.indices.clear (); + cluster.indices.reserve (i_segment->indices.size ()); + std::copy (i_segment->indices.begin (), i_segment->indices.end (), std::back_inserter (cluster.indices)); + break; + } + } + if (segment_was_found) + { + break; + } + }// next segment + }// end if point was found + + deinitCompute (); +} + +#endif // PCL_SEGMENTATION_REGION_GROWING_RGB_HPP_ diff --git a/pcl-1.7/pcl/segmentation/impl/sac_segmentation.hpp b/pcl-1.7/pcl/segmentation/impl/sac_segmentation.hpp new file mode 100644 index 0000000..7c817e5 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/sac_segmentation.hpp @@ -0,0 +1,506 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SEGMENTATION_IMPL_SAC_SEGMENTATION_H_ +#define PCL_SEGMENTATION_IMPL_SAC_SEGMENTATION_H_ + +#include + +// Sample Consensus methods +#include +#include +#include +#include +#include +#include +#include +#include + +// Sample Consensus models +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SACSegmentation::segment (PointIndices &inliers, ModelCoefficients &model_coefficients) +{ + // Copy the header information + inliers.header = model_coefficients.header = input_->header; + + if (!initCompute ()) + { + inliers.indices.clear (); model_coefficients.values.clear (); + return; + } + + // Initialize the Sample Consensus model and set its parameters + if (!initSACModel (model_type_)) + { + PCL_ERROR ("[pcl::%s::segment] Error initializing the SAC model!\n", getClassName ().c_str ()); + deinitCompute (); + inliers.indices.clear (); model_coefficients.values.clear (); + return; + } + // Initialize the Sample Consensus method and set its parameters + initSAC (method_type_); + + if (!sac_->computeModel (0)) + { + PCL_ERROR ("[pcl::%s::segment] Error segmenting the model! No solution found.\n", getClassName ().c_str ()); + deinitCompute (); + inliers.indices.clear (); model_coefficients.values.clear (); + return; + } + + // Get the model inliers + sac_->getInliers (inliers.indices); + + // Get the model coefficients + Eigen::VectorXf coeff; + sac_->getModelCoefficients (coeff); + + // If the user needs optimized coefficients + if (optimize_coefficients_) + { + Eigen::VectorXf coeff_refined; + model_->optimizeModelCoefficients (inliers.indices, coeff, coeff_refined); + model_coefficients.values.resize (coeff_refined.size ()); + memcpy (&model_coefficients.values[0], &coeff_refined[0], coeff_refined.size () * sizeof (float)); + // Refine inliers + model_->selectWithinDistance (coeff_refined, threshold_, inliers.indices); + } + else + { + model_coefficients.values.resize (coeff.size ()); + memcpy (&model_coefficients.values[0], &coeff[0], coeff.size () * sizeof (float)); + } + + deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SACSegmentation::initSACModel (const int model_type) +{ + if (model_) + model_.reset (); + + // Build the model + switch (model_type) + { + case SACMODEL_PLANE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_PLANE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelPlane (input_, *indices_, random_)); + break; + } + case SACMODEL_LINE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_LINE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelLine (input_, *indices_, random_)); + break; + } + case SACMODEL_STICK: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_STICK\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelStick (input_, *indices_)); + double min_radius, max_radius; + model_->getRadiusLimits (min_radius, max_radius); + if (radius_min_ != min_radius && radius_max_ != max_radius) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting radius limits to %f/%f\n", getClassName ().c_str (), radius_min_, radius_max_); + model_->setRadiusLimits (radius_min_, radius_max_); + } + break; + } + case SACMODEL_CIRCLE2D: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_CIRCLE2D\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelCircle2D (input_, *indices_, random_)); + typename SampleConsensusModelCircle2D::Ptr model_circle = boost::static_pointer_cast > (model_); + double min_radius, max_radius; + model_circle->getRadiusLimits (min_radius, max_radius); + if (radius_min_ != min_radius && radius_max_ != max_radius) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting radius limits to %f/%f\n", getClassName ().c_str (), radius_min_, radius_max_); + model_circle->setRadiusLimits (radius_min_, radius_max_); + } + break; + } + case SACMODEL_CIRCLE3D: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_CIRCLE3D\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelCircle3D (input_, *indices_)); + typename SampleConsensusModelCircle3D::Ptr model_circle3d = boost::static_pointer_cast > (model_); + double min_radius, max_radius; + model_circle3d->getRadiusLimits (min_radius, max_radius); + if (radius_min_ != min_radius && radius_max_ != max_radius) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting radius limits to %f/%f\n", getClassName ().c_str (), radius_min_, radius_max_); + model_circle3d->setRadiusLimits (radius_min_, radius_max_); + } + break; + } + case SACMODEL_SPHERE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_SPHERE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelSphere (input_, *indices_, random_)); + typename SampleConsensusModelSphere::Ptr model_sphere = boost::static_pointer_cast > (model_); + double min_radius, max_radius; + model_sphere->getRadiusLimits (min_radius, max_radius); + if (radius_min_ != min_radius && radius_max_ != max_radius) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting radius limits to %f/%f\n", getClassName ().c_str (), radius_min_, radius_max_); + model_sphere->setRadiusLimits (radius_min_, radius_max_); + } + break; + } + case SACMODEL_PARALLEL_LINE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_PARALLEL_LINE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelParallelLine (input_, *indices_, random_)); + typename SampleConsensusModelParallelLine::Ptr model_parallel = boost::static_pointer_cast > (model_); + if (axis_ != Eigen::Vector3f::Zero () && model_parallel->getAxis () != axis_) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting the axis to %f, %f, %f\n", getClassName ().c_str (), axis_[0], axis_[1], axis_[2]); + model_parallel->setAxis (axis_); + } + if (eps_angle_ != 0.0 && model_parallel->getEpsAngle () != eps_angle_) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting the epsilon angle to %f (%f degrees)\n", getClassName ().c_str (), eps_angle_, eps_angle_ * 180.0 / M_PI); + model_parallel->setEpsAngle (eps_angle_); + } + break; + } + case SACMODEL_PERPENDICULAR_PLANE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_PERPENDICULAR_PLANE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelPerpendicularPlane (input_, *indices_, random_)); + typename SampleConsensusModelPerpendicularPlane::Ptr model_perpendicular = boost::static_pointer_cast > (model_); + if (axis_ != Eigen::Vector3f::Zero () && model_perpendicular->getAxis () != axis_) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting the axis to %f, %f, %f\n", getClassName ().c_str (), axis_[0], axis_[1], axis_[2]); + model_perpendicular->setAxis (axis_); + } + if (eps_angle_ != 0.0 && model_perpendicular->getEpsAngle () != eps_angle_) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting the epsilon angle to %f (%f degrees)\n", getClassName ().c_str (), eps_angle_, eps_angle_ * 180.0 / M_PI); + model_perpendicular->setEpsAngle (eps_angle_); + } + break; + } + case SACMODEL_PARALLEL_PLANE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_PARALLEL_PLANE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelParallelPlane (input_, *indices_, random_)); + typename SampleConsensusModelParallelPlane::Ptr model_parallel = boost::static_pointer_cast > (model_); + if (axis_ != Eigen::Vector3f::Zero () && model_parallel->getAxis () != axis_) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting the axis to %f, %f, %f\n", getClassName ().c_str (), axis_[0], axis_[1], axis_[2]); + model_parallel->setAxis (axis_); + } + if (eps_angle_ != 0.0 && model_parallel->getEpsAngle () != eps_angle_) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting the epsilon angle to %f (%f degrees)\n", getClassName ().c_str (), eps_angle_, eps_angle_ * 180.0 / M_PI); + model_parallel->setEpsAngle (eps_angle_); + } + break; + } + default: + { + PCL_ERROR ("[pcl::%s::initSACModel] No valid model given!\n", getClassName ().c_str ()); + return (false); + } + } + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SACSegmentation::initSAC (const int method_type) +{ + if (sac_) + sac_.reset (); + // Build the sample consensus method + switch (method_type) + { + case SAC_RANSAC: + default: + { + PCL_DEBUG ("[pcl::%s::initSAC] Using a method of type: SAC_RANSAC with a model threshold of %f\n", getClassName ().c_str (), threshold_); + sac_.reset (new RandomSampleConsensus (model_, threshold_)); + break; + } + case SAC_LMEDS: + { + PCL_DEBUG ("[pcl::%s::initSAC] Using a method of type: SAC_LMEDS with a model threshold of %f\n", getClassName ().c_str (), threshold_); + sac_.reset (new LeastMedianSquares (model_, threshold_)); + break; + } + case SAC_MSAC: + { + PCL_DEBUG ("[pcl::%s::initSAC] Using a method of type: SAC_MSAC with a model threshold of %f\n", getClassName ().c_str (), threshold_); + sac_.reset (new MEstimatorSampleConsensus (model_, threshold_)); + break; + } + case SAC_RRANSAC: + { + PCL_DEBUG ("[pcl::%s::initSAC] Using a method of type: SAC_RRANSAC with a model threshold of %f\n", getClassName ().c_str (), threshold_); + sac_.reset (new RandomizedRandomSampleConsensus (model_, threshold_)); + break; + } + case SAC_RMSAC: + { + PCL_DEBUG ("[pcl::%s::initSAC] Using a method of type: SAC_RMSAC with a model threshold of %f\n", getClassName ().c_str (), threshold_); + sac_.reset (new RandomizedMEstimatorSampleConsensus (model_, threshold_)); + break; + } + case SAC_MLESAC: + { + PCL_DEBUG ("[pcl::%s::initSAC] Using a method of type: SAC_MLESAC with a model threshold of %f\n", getClassName ().c_str (), threshold_); + sac_.reset (new MaximumLikelihoodSampleConsensus (model_, threshold_)); + break; + } + case SAC_PROSAC: + { + PCL_DEBUG ("[pcl::%s::initSAC] Using a method of type: SAC_PROSAC with a model threshold of %f\n", getClassName ().c_str (), threshold_); + sac_.reset (new ProgressiveSampleConsensus (model_, threshold_)); + break; + } + } + // Set the Sample Consensus parameters if they are given/changed + if (sac_->getProbability () != probability_) + { + PCL_DEBUG ("[pcl::%s::initSAC] Setting the desired probability to %f\n", getClassName ().c_str (), probability_); + sac_->setProbability (probability_); + } + if (max_iterations_ != -1 && sac_->getMaxIterations () != max_iterations_) + { + PCL_DEBUG ("[pcl::%s::initSAC] Setting the maximum number of iterations to %d\n", getClassName ().c_str (), max_iterations_); + sac_->setMaxIterations (max_iterations_); + } + if (samples_radius_ > 0.) + { + PCL_DEBUG ("[pcl::%s::initSAC] Setting the maximum sample radius to %f\n", getClassName ().c_str (), samples_radius_); + // Set maximum distance for radius search during random sampling + model_->setSamplesMaxDist (samples_radius_, samples_radius_search_); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SACSegmentationFromNormals::initSACModel (const int model_type) +{ + if (!input_ || !normals_) + { + PCL_ERROR ("[pcl::%s::initSACModel] Input data (XYZ or normals) not given! Cannot continue.\n", getClassName ().c_str ()); + return (false); + } + // Check if input is synced with the normals + if (input_->points.size () != normals_->points.size ()) + { + PCL_ERROR ("[pcl::%s::initSACModel] The number of points inthe input point cloud differs than the number of points in the normals!\n", getClassName ().c_str ()); + return (false); + } + + if (model_) + model_.reset (); + + // Build the model + switch (model_type) + { + case SACMODEL_CYLINDER: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_CYLINDER\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelCylinder (input_, *indices_, random_)); + typename SampleConsensusModelCylinder::Ptr model_cylinder = boost::static_pointer_cast > (model_); + + // Set the input normals + model_cylinder->setInputNormals (normals_); + double min_radius, max_radius; + model_cylinder->getRadiusLimits (min_radius, max_radius); + if (radius_min_ != min_radius && radius_max_ != max_radius) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting radius limits to %f/%f\n", getClassName ().c_str (), radius_min_, radius_max_); + model_cylinder->setRadiusLimits (radius_min_, radius_max_); + } + if (distance_weight_ != model_cylinder->getNormalDistanceWeight ()) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting normal distance weight to %f\n", getClassName ().c_str (), distance_weight_); + model_cylinder->setNormalDistanceWeight (distance_weight_); + } + if (axis_ != Eigen::Vector3f::Zero () && model_cylinder->getAxis () != axis_) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting the axis to %f, %f, %f\n", getClassName ().c_str (), axis_[0], axis_[1], axis_[2]); + model_cylinder->setAxis (axis_); + } + if (eps_angle_ != 0.0 && model_cylinder->getEpsAngle () != eps_angle_) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting the epsilon angle to %f (%f degrees)\n", getClassName ().c_str (), eps_angle_, eps_angle_ * 180.0 / M_PI); + model_cylinder->setEpsAngle (eps_angle_); + } + break; + } + case SACMODEL_NORMAL_PLANE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_NORMAL_PLANE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelNormalPlane (input_, *indices_, random_)); + typename SampleConsensusModelNormalPlane::Ptr model_normals = boost::static_pointer_cast > (model_); + // Set the input normals + model_normals->setInputNormals (normals_); + if (distance_weight_ != model_normals->getNormalDistanceWeight ()) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting normal distance weight to %f\n", getClassName ().c_str (), distance_weight_); + model_normals->setNormalDistanceWeight (distance_weight_); + } + break; + } + case SACMODEL_NORMAL_PARALLEL_PLANE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_NORMAL_PARALLEL_PLANE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelNormalParallelPlane (input_, *indices_, random_)); + typename SampleConsensusModelNormalParallelPlane::Ptr model_normals = boost::static_pointer_cast > (model_); + // Set the input normals + model_normals->setInputNormals (normals_); + if (distance_weight_ != model_normals->getNormalDistanceWeight ()) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting normal distance weight to %f\n", getClassName ().c_str (), distance_weight_); + model_normals->setNormalDistanceWeight (distance_weight_); + } + if (distance_from_origin_ != model_normals->getDistanceFromOrigin ()) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting the distance to origin to %f\n", getClassName ().c_str (), distance_from_origin_); + model_normals->setDistanceFromOrigin (distance_from_origin_); + } + if (axis_ != Eigen::Vector3f::Zero () && model_normals->getAxis () != axis_) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting the axis to %f, %f, %f\n", getClassName ().c_str (), axis_[0], axis_[1], axis_[2]); + model_normals->setAxis (axis_); + } + if (eps_angle_ != 0.0 && model_normals->getEpsAngle () != eps_angle_) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting the epsilon angle to %f (%f degrees)\n", getClassName ().c_str (), eps_angle_, eps_angle_ * 180.0 / M_PI); + model_normals->setEpsAngle (eps_angle_); + } + break; + } + case SACMODEL_CONE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_CONE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelCone (input_, *indices_, random_)); + typename SampleConsensusModelCone::Ptr model_cone = boost::static_pointer_cast > (model_); + + // Set the input normals + model_cone->setInputNormals (normals_); + double min_angle, max_angle; + model_cone->getMinMaxOpeningAngle(min_angle, max_angle); + if (min_angle_ != min_angle && max_angle_ != max_angle) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting minimum and maximum opening angle to %f and %f \n", getClassName ().c_str (), min_angle_, max_angle_); + model_cone->setMinMaxOpeningAngle (min_angle_, max_angle_); + } + + if (distance_weight_ != model_cone->getNormalDistanceWeight ()) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting normal distance weight to %f\n", getClassName ().c_str (), distance_weight_); + model_cone->setNormalDistanceWeight (distance_weight_); + } + if (axis_ != Eigen::Vector3f::Zero () && model_cone->getAxis () != axis_) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting the axis to %f, %f, %f\n", getClassName ().c_str (), axis_[0], axis_[1], axis_[2]); + model_cone->setAxis (axis_); + } + if (eps_angle_ != 0.0 && model_cone->getEpsAngle () != eps_angle_) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting the epsilon angle to %f (%f degrees)\n", getClassName ().c_str (), eps_angle_, eps_angle_ * 180.0 / M_PI); + model_cone->setEpsAngle (eps_angle_); + } + break; + } + case SACMODEL_NORMAL_SPHERE: + { + PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_NORMAL_SPHERE\n", getClassName ().c_str ()); + model_.reset (new SampleConsensusModelNormalSphere (input_, *indices_, random_)); + typename SampleConsensusModelNormalSphere::Ptr model_normals_sphere = boost::static_pointer_cast > (model_); + // Set the input normals + model_normals_sphere->setInputNormals (normals_); + double min_radius, max_radius; + model_normals_sphere->getRadiusLimits (min_radius, max_radius); + if (radius_min_ != min_radius && radius_max_ != max_radius) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting radius limits to %f/%f\n", getClassName ().c_str (), radius_min_, radius_max_); + model_normals_sphere->setRadiusLimits (radius_min_, radius_max_); + } + + if (distance_weight_ != model_normals_sphere->getNormalDistanceWeight ()) + { + PCL_DEBUG ("[pcl::%s::initSACModel] Setting normal distance weight to %f\n", getClassName ().c_str (), distance_weight_); + model_normals_sphere->setNormalDistanceWeight (distance_weight_); + } + break; + } + // If nothing else, try SACSegmentation + default: + { + return (pcl::SACSegmentation::initSACModel (model_type)); + } + } + + return (true); +} + +#define PCL_INSTANTIATE_SACSegmentation(T) template class PCL_EXPORTS pcl::SACSegmentation; +#define PCL_INSTANTIATE_SACSegmentationFromNormals(T,NT) template class PCL_EXPORTS pcl::SACSegmentationFromNormals; + +#endif // PCL_SEGMENTATION_IMPL_SAC_SEGMENTATION_H_ + diff --git a/pcl-1.7/pcl/segmentation/impl/seeded_hue_segmentation.hpp b/pcl-1.7/pcl/segmentation/impl/seeded_hue_segmentation.hpp new file mode 100644 index 0000000..2980ee1 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/seeded_hue_segmentation.hpp @@ -0,0 +1,224 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $id $ + */ + +#ifndef PCL_SEGMENTATION_IMPL_SEEDED_HUE_SEGMENTATION_H_ +#define PCL_SEGMENTATION_IMPL_SEEDED_HUE_SEGMENTATION_H_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +void +pcl::seededHueSegmentation (const PointCloud &cloud, + const boost::shared_ptr > &tree, + float tolerance, + PointIndices &indices_in, + PointIndices &indices_out, + float delta_hue) +{ + if (tree->getInputCloud ()->points.size () != cloud.points.size ()) + { + PCL_ERROR ("[pcl::seededHueSegmentation] Tree built for a different point cloud dataset (%lu) than the input cloud (%lu)!\n", tree->getInputCloud ()->points.size (), cloud.points.size ()); + return; + } + // Create a bool vector of processed point indices, and initialize it to false + std::vector processed (cloud.points.size (), false); + + std::vector nn_indices; + std::vector nn_distances; + + // Process all points in the indices vector + for (size_t k = 0; k < indices_in.indices.size (); ++k) + { + int i = indices_in.indices[k]; + if (processed[i]) + continue; + + processed[i] = true; + + std::vector seed_queue; + int sq_idx = 0; + seed_queue.push_back (i); + + PointXYZRGB p; + p = cloud.points[i]; + PointXYZHSV h; + PointXYZRGBtoXYZHSV(p, h); + + while (sq_idx < static_cast (seed_queue.size ())) + { + int ret = tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances, std::numeric_limits::max()); + if(ret == -1) + PCL_ERROR("[pcl::seededHueSegmentation] radiusSearch returned error code -1"); + // Search for sq_idx + if (!ret) + { + sq_idx++; + continue; + } + + for (size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx + { + if (processed[nn_indices[j]]) // Has this point been processed before ? + continue; + + PointXYZRGB p_l; + p_l = cloud.points[nn_indices[j]]; + PointXYZHSV h_l; + PointXYZRGBtoXYZHSV(p_l, h_l); + + if (fabs(h_l.h - h.h) < delta_hue) + { + seed_queue.push_back (nn_indices[j]); + processed[nn_indices[j]] = true; + } + } + + sq_idx++; + } + // Copy the seed queue into the output indices + for (size_t l = 0; l < seed_queue.size (); ++l) + indices_out.indices.push_back(seed_queue[l]); + } + // This is purely esthetical, can be removed for speed purposes + std::sort (indices_out.indices.begin (), indices_out.indices.end ()); +} +////////////////////////////////////////////////////////////////////////////////////////////// +void +pcl::seededHueSegmentation (const PointCloud &cloud, + const boost::shared_ptr > &tree, + float tolerance, + PointIndices &indices_in, + PointIndices &indices_out, + float delta_hue) +{ + if (tree->getInputCloud ()->points.size () != cloud.points.size ()) + { + PCL_ERROR ("[pcl::seededHueSegmentation] Tree built for a different point cloud dataset (%lu) than the input cloud (%lu)!\n", tree->getInputCloud ()->points.size (), cloud.points.size ()); + return; + } + // Create a bool vector of processed point indices, and initialize it to false + std::vector processed (cloud.points.size (), false); + + std::vector nn_indices; + std::vector nn_distances; + + // Process all points in the indices vector + for (size_t k = 0; k < indices_in.indices.size (); ++k) + { + int i = indices_in.indices[k]; + if (processed[i]) + continue; + + processed[i] = true; + + std::vector seed_queue; + int sq_idx = 0; + seed_queue.push_back (i); + + PointXYZRGB p; + p = cloud.points[i]; + PointXYZHSV h; + PointXYZRGBtoXYZHSV(p, h); + + while (sq_idx < static_cast (seed_queue.size ())) + { + int ret = tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances, std::numeric_limits::max()); + if(ret == -1) + PCL_ERROR("[pcl::seededHueSegmentation] radiusSearch returned error code -1"); + // Search for sq_idx + if (!ret) + { + sq_idx++; + continue; + } + for (size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx + { + if (processed[nn_indices[j]]) // Has this point been processed before ? + continue; + + PointXYZRGB p_l; + p_l = cloud.points[nn_indices[j]]; + PointXYZHSV h_l; + PointXYZRGBtoXYZHSV(p_l, h_l); + + if (fabs(h_l.h - h.h) < delta_hue) + { + seed_queue.push_back (nn_indices[j]); + processed[nn_indices[j]] = true; + } + } + + sq_idx++; + } + // Copy the seed queue into the output indices + for (size_t l = 0; l < seed_queue.size (); ++l) + indices_out.indices.push_back(seed_queue[l]); + } + // This is purely esthetical, can be removed for speed purposes + std::sort (indices_out.indices.begin (), indices_out.indices.end ()); +} +////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////// + +void +pcl::SeededHueSegmentation::segment (PointIndices &indices_in, PointIndices &indices_out) +{ + if (!initCompute () || + (input_ != 0 && input_->points.empty ()) || + (indices_ != 0 && indices_->empty ())) + { + indices_out.indices.clear (); + return; + } + + // Initialize the spatial locator + if (!tree_) + { + if (input_->isOrganized ()) + tree_.reset (new pcl::search::OrganizedNeighbor ()); + else + tree_.reset (new pcl::search::KdTree (false)); + } + + // Send the input dataset to the spatial locator + tree_->setInputCloud (input_); + seededHueSegmentation (*input_, tree_, static_cast (cluster_tolerance_), indices_in, indices_out, delta_hue_); + deinitCompute (); +} + +#endif // PCL_EXTRACT_CLUSTERS_IMPL_H_ diff --git a/pcl-1.7/pcl/segmentation/impl/segment_differences.hpp b/pcl-1.7/pcl/segmentation/impl/segment_differences.hpp new file mode 100644 index 0000000..2c206f0 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/segment_differences.hpp @@ -0,0 +1,133 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SEGMENTATION_IMPL_SEGMENT_DIFFERENCES_H_ +#define PCL_SEGMENTATION_IMPL_SEGMENT_DIFFERENCES_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////// +template void +pcl::getPointCloudDifference ( + const pcl::PointCloud &src, + const pcl::PointCloud &, + double threshold, const boost::shared_ptr > &tree, + pcl::PointCloud &output) +{ + // We're interested in a single nearest neighbor only + std::vector nn_indices (1); + std::vector nn_distances (1); + + // The src indices that do not have a neighbor in tgt + std::vector src_indices; + + // Iterate through the source data set + for (int i = 0; i < static_cast (src.points.size ()); ++i) + { + if (!isFinite (src.points[i])) + continue; + // Search for the closest point in the target data set (number of neighbors to find = 1) + if (!tree->nearestKSearch (src.points[i], 1, nn_indices, nn_distances)) + { + PCL_WARN ("No neighbor found for point %lu (%f %f %f)!\n", i, src.points[i].x, src.points[i].y, src.points[i].z); + continue; + } + + if (nn_distances[0] > threshold) + src_indices.push_back (i); + } + + // Allocate enough space and copy the basics + output.points.resize (src_indices.size ()); + output.header = src.header; + output.width = static_cast (src_indices.size ()); + output.height = 1; + //if (src.is_dense) + output.is_dense = true; + //else + // It's not necessarily true that is_dense is false if cloud_in.is_dense is false + // To verify this, we would need to iterate over all points and check for NaNs + //output.is_dense = false; + + // Copy all the data fields from the input cloud to the output one + copyPointCloud (src, src_indices, output); +} + +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////// +template void +pcl::SegmentDifferences::segment (PointCloud &output) +{ + output.header = input_->header; + + if (!initCompute ()) + { + output.width = output.height = 0; + output.points.clear (); + return; + } + + // If target is empty, input - target = input + if (target_->points.empty ()) + { + output = *input_; + return; + } + + // Initialize the spatial locator + if (!tree_) + { + if (target_->isOrganized ()) + tree_.reset (new pcl::search::OrganizedNeighbor ()); + else + tree_.reset (new pcl::search::KdTree (false)); + } + // Send the input dataset to the spatial locator + tree_->setInputCloud (target_); + + getPointCloudDifference (*input_, *target_, distance_threshold_, tree_, output); + + deinitCompute (); +} + +#define PCL_INSTANTIATE_SegmentDifferences(T) template class PCL_EXPORTS pcl::SegmentDifferences; +#define PCL_INSTANTIATE_getPointCloudDifference(T) template PCL_EXPORTS void pcl::getPointCloudDifference(const pcl::PointCloud &, const pcl::PointCloud &, double, const boost::shared_ptr > &, pcl::PointCloud &); + +#endif // PCL_SEGMENTATION_IMPL_SEGMENT_DIFFERENCES_H_ + diff --git a/pcl-1.7/pcl/segmentation/impl/supervoxel_clustering.hpp b/pcl-1.7/pcl/segmentation/impl/supervoxel_clustering.hpp new file mode 100644 index 0000000..1c7386f --- /dev/null +++ b/pcl-1.7/pcl/segmentation/impl/supervoxel_clustering.hpp @@ -0,0 +1,1095 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : jpapon@gmail.com + * Email : jpapon@gmail.com + * + */ + +#ifndef PCL_SEGMENTATION_SUPERVOXEL_CLUSTERING_HPP_ +#define PCL_SEGMENTATION_SUPERVOXEL_CLUSTERING_HPP_ + +#include + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::SupervoxelClustering::SupervoxelClustering (float voxel_resolution, float seed_resolution, bool use_single_camera_transform) : + resolution_ (voxel_resolution), + seed_resolution_ (seed_resolution), + adjacency_octree_ (), + voxel_centroid_cloud_ (), + color_importance_(0.1f), + spatial_importance_(0.4f), + normal_importance_(1.0f), + label_colors_ (0) +{ + adjacency_octree_.reset (new OctreeAdjacencyT (resolution_)); + if (use_single_camera_transform) + adjacency_octree_->setTransformFunction (boost::bind (&SupervoxelClustering::transformFunction, this, _1)); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::SupervoxelClustering::~SupervoxelClustering () +{ + +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::setInputCloud (const typename pcl::PointCloud::ConstPtr& cloud) +{ + if ( cloud->size () == 0 ) + { + PCL_ERROR ("[pcl::SupervoxelClustering::setInputCloud] Empty cloud set, doing nothing \n"); + return; + } + + input_ = cloud; + adjacency_octree_->setInputCloud (cloud); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::setNormalCloud (typename NormalCloudT::ConstPtr normal_cloud) +{ + if ( normal_cloud->size () == 0 ) + { + PCL_ERROR ("[pcl::SupervoxelClustering::setNormalCloud] Empty cloud set, doing nothing \n"); + return; + } + + input_normals_ = normal_cloud; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::extract (std::map::Ptr > &supervoxel_clusters) +{ + //timer_.reset (); + //double t_start = timer_.getTime (); + //std::cout << "Init compute \n"; + bool segmentation_is_possible = initCompute (); + if ( !segmentation_is_possible ) + { + deinitCompute (); + return; + } + + //std::cout << "Preparing for segmentation \n"; + segmentation_is_possible = prepareForSegmentation (); + if ( !segmentation_is_possible ) + { + deinitCompute (); + return; + } + + //double t_prep = timer_.getTime (); + //std::cout << "Placing Seeds" << std::endl; + std::vector > seed_points; + selectInitialSupervoxelSeeds (seed_points); + //std::cout << "Creating helpers "< (1.8f*seed_resolution_/resolution_); + expandSupervoxels (max_depth); + //double t_iterate = timer_.getTime (); + + //std::cout << "Making Supervoxel structures" << std::endl; + makeSupervoxels (supervoxel_clusters); + //double t_supervoxels = timer_.getTime (); + + // std::cout << "--------------------------------- Timing Report --------------------------------- \n"; + // std::cout << "Time to prep (normals, neighbors, voxelization)="< void +pcl::SupervoxelClustering::refineSupervoxels (int num_itr, std::map::Ptr > &supervoxel_clusters) +{ + if (supervoxel_helpers_.size () == 0) + { + PCL_ERROR ("[pcl::SupervoxelClustering::refineVoxelNormals] Supervoxels not extracted, doing nothing - (Call extract first!) \n"); + return; + } + + int max_depth = static_cast (1.8f*seed_resolution_/resolution_); + for (int i = 0; i < num_itr; ++i) + { + for (typename HelperListT::iterator sv_itr = supervoxel_helpers_.begin (); sv_itr != supervoxel_helpers_.end (); ++sv_itr) + { + sv_itr->refineNormals (); + } + + reseedSupervoxels (); + expandSupervoxels (max_depth); + } + + + makeSupervoxels (supervoxel_clusters); + +} +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + +template bool +pcl::SupervoxelClustering::prepareForSegmentation () +{ + + // if user forgot to pass point cloud or if it is empty + if ( input_->points.size () == 0 ) + return (false); + + //Add the new cloud of data to the octree + //std::cout << "Populating adjacency octree with new cloud \n"; + //double prep_start = timer_.getTime (); + adjacency_octree_->addPointsFromInputCloud (); + //double prep_end = timer_.getTime (); + //std::cout<<"Time elapsed populating octree with next frame ="< void +pcl::SupervoxelClustering::computeVoxelData () +{ + voxel_centroid_cloud_.reset (new PointCloudT); + voxel_centroid_cloud_->resize (adjacency_octree_->getLeafCount ()); + typename LeafVectorT::iterator leaf_itr = adjacency_octree_->begin (); + typename PointCloudT::iterator cent_cloud_itr = voxel_centroid_cloud_->begin (); + for (int idx = 0 ; leaf_itr != adjacency_octree_->end (); ++leaf_itr, ++cent_cloud_itr, ++idx) + { + VoxelData& new_voxel_data = (*leaf_itr)->getData (); + //Add the point to the centroid cloud + new_voxel_data.getPoint (*cent_cloud_itr); + //voxel_centroid_cloud_->push_back(new_voxel_data.getPoint ()); + new_voxel_data.idx_ = idx; + } + + //If normals were provided + if (input_normals_) + { + //Verify that input normal cloud size is same as input cloud size + assert (input_normals_->size () == input_->size ()); + //For every point in the input cloud, find its corresponding leaf + typename NormalCloudT::const_iterator normal_itr = input_normals_->begin (); + for (typename PointCloudT::const_iterator input_itr = input_->begin (); input_itr != input_->end (); ++input_itr, ++normal_itr) + { + //If the point is not finite we ignore it + if ( !pcl::isFinite (*input_itr)) + continue; + //Otherwise look up its leaf container + LeafContainerT* leaf = adjacency_octree_->getLeafContainerAtPoint (*input_itr); + + //Get the voxel data object + VoxelData& voxel_data = leaf->getData (); + //Add this normal in (we will normalize at the end) + voxel_data.normal_ += normal_itr->getNormalVector4fMap (); + voxel_data.curvature_ += normal_itr->curvature; + } + //Now iterate through the leaves and normalize + for (leaf_itr = adjacency_octree_->begin (); leaf_itr != adjacency_octree_->end (); ++leaf_itr) + { + VoxelData& voxel_data = (*leaf_itr)->getData (); + voxel_data.normal_.normalize (); + voxel_data.owner_ = 0; + voxel_data.distance_ = std::numeric_limits::max (); + //Get the number of points in this leaf + int num_points = (*leaf_itr)->getPointCounter (); + voxel_data.curvature_ /= num_points; + } + } + else //Otherwise just compute the normals + { + for (leaf_itr = adjacency_octree_->begin (); leaf_itr != adjacency_octree_->end (); ++leaf_itr) + { + VoxelData& new_voxel_data = (*leaf_itr)->getData (); + //For every point, get its neighbors, build an index vector, compute normal + std::vector indices; + indices.reserve (81); + //Push this point + indices.push_back (new_voxel_data.idx_); + for (typename LeafContainerT::iterator neighb_itr=(*leaf_itr)->begin (); neighb_itr!=(*leaf_itr)->end (); ++neighb_itr) + { + VoxelData& neighb_voxel_data = (*neighb_itr)->getData (); + //Push neighbor index + indices.push_back (neighb_voxel_data.idx_); + //Get neighbors neighbors, push onto cloud + for (typename LeafContainerT::iterator neighb_neighb_itr=(*neighb_itr)->begin (); neighb_neighb_itr!=(*neighb_itr)->end (); ++neighb_neighb_itr) + { + VoxelData& neighb2_voxel_data = (*neighb_neighb_itr)->getData (); + indices.push_back (neighb2_voxel_data.idx_); + } + } + //Compute normal + pcl::computePointNormal (*voxel_centroid_cloud_, indices, new_voxel_data.normal_, new_voxel_data.curvature_); + pcl::flipNormalTowardsViewpoint (voxel_centroid_cloud_->points[new_voxel_data.idx_], 0.0f,0.0f,0.0f, new_voxel_data.normal_); + new_voxel_data.normal_[3] = 0.0f; + new_voxel_data.normal_.normalize (); + new_voxel_data.owner_ = 0; + new_voxel_data.distance_ = std::numeric_limits::max (); + } + } + + +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::expandSupervoxels ( int depth ) +{ + + + for (int i = 1; i < depth; ++i) + { + //Expand the the supervoxels by one iteration + for (typename HelperListT::iterator sv_itr = supervoxel_helpers_.begin (); sv_itr != supervoxel_helpers_.end (); ++sv_itr) + { + sv_itr->expand (); + } + + //Update the centers to reflect new centers + for (typename HelperListT::iterator sv_itr = supervoxel_helpers_.begin (); sv_itr != supervoxel_helpers_.end (); ) + { + if (sv_itr->size () == 0) + { + sv_itr = supervoxel_helpers_.erase (sv_itr); + } + else + { + sv_itr->updateCentroid (); + ++sv_itr; + } + } + + } + +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::makeSupervoxels (std::map::Ptr > &supervoxel_clusters) +{ + supervoxel_clusters.clear (); + for (typename HelperListT::iterator sv_itr = supervoxel_helpers_.begin (); sv_itr != supervoxel_helpers_.end (); ++sv_itr) + { + uint32_t label = sv_itr->getLabel (); + supervoxel_clusters[label].reset (new Supervoxel); + sv_itr->getXYZ (supervoxel_clusters[label]->centroid_.x,supervoxel_clusters[label]->centroid_.y,supervoxel_clusters[label]->centroid_.z); + sv_itr->getRGB (supervoxel_clusters[label]->centroid_.rgba); + sv_itr->getNormal (supervoxel_clusters[label]->normal_); + sv_itr->getVoxels (supervoxel_clusters[label]->voxels_); + sv_itr->getNormals (supervoxel_clusters[label]->normals_); + } + //Make sure that color vector is big enough + initializeLabelColors (); +} + + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::createSupervoxelHelpers (std::vector > &seed_points) +{ + + supervoxel_helpers_.clear (); + for (size_t i = 0; i < seed_points.size (); ++i) + { + supervoxel_helpers_.push_back (new SupervoxelHelper(i+1,this)); + //Find which leaf corresponds to this seed index + LeafContainerT* seed_leaf = adjacency_octree_->getLeafContainerAtPoint (seed_points[i]); + if (seed_leaf) + { + supervoxel_helpers_.back ().addLeaf (seed_leaf); + } + else + { + PCL_WARN ("Could not find leaf in pcl::SupervoxelClustering::createSupervoxelHelpers - supervoxel will be deleted \n"); + } + } + +} +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::selectInitialSupervoxelSeeds (std::vector > &seed_points) +{ + //TODO THIS IS BAD - SEEDING SHOULD BE BETTER + //TODO Switch to assigning leaves! Don't use Octree! + + // std::cout << "Size of centroid cloud="<size ()<<", seeding resolution="< seed_octree (seed_resolution_); + seed_octree.setInputCloud (voxel_centroid_cloud_); + seed_octree.addPointsFromInputCloud (); + // std::cout << "Size of octree ="< > voxel_centers; + int num_seeds = seed_octree.getOccupiedVoxelCenters(voxel_centers); + //std::cout << "Number of seed points before filtering="< seed_indices_orig; + seed_indices_orig.resize (num_seeds, 0); + seed_points.clear (); + std::vector closest_index; + std::vector distance; + closest_index.resize(1,0); + distance.resize(1,0); + if (voxel_kdtree_ == 0) + { + voxel_kdtree_.reset (new pcl::search::KdTree); + voxel_kdtree_ ->setInputCloud (voxel_centroid_cloud_); + } + + for (int i = 0; i < num_seeds; ++i) + { + voxel_kdtree_->nearestKSearch (voxel_centers[i], 1, closest_index, distance); + seed_indices_orig[i] = closest_index[0]; + } + + std::vector neighbors; + std::vector sqr_distances; + seed_points.reserve (seed_indices_orig.size ()); + float search_radius = 0.5f*seed_resolution_; + // This is number of voxels which fit in a planar slice through search volume + // Area of planar slice / area of voxel side + float min_points = 0.05f * (search_radius)*(search_radius) * 3.1415926536f / (resolution_*resolution_); + for (size_t i = 0; i < seed_indices_orig.size (); ++i) + { + int num = voxel_kdtree_->radiusSearch (seed_indices_orig[i], search_radius , neighbors, sqr_distances); + int min_index = seed_indices_orig[i]; + if ( num > min_points) + { + seed_points.push_back (voxel_centroid_cloud_->points[min_index]); + } + + } + // std::cout << "Number of seed points after filtering="< void +pcl::SupervoxelClustering::reseedSupervoxels () +{ + //Go through each supervoxel and remove all it's leaves + for (typename HelperListT::iterator sv_itr = supervoxel_helpers_.begin (); sv_itr != supervoxel_helpers_.end (); ++sv_itr) + { + sv_itr->removeAllLeaves (); + } + + std::vector closest_index; + std::vector distance; + //Now go through each supervoxel, find voxel closest to its center, add it in + for (typename HelperListT::iterator sv_itr = supervoxel_helpers_.begin (); sv_itr != supervoxel_helpers_.end (); ++sv_itr) + { + PointT point; + sv_itr->getXYZ (point.x, point.y, point.z); + voxel_kdtree_->nearestKSearch (point, 1, closest_index, distance); + + LeafContainerT* seed_leaf = adjacency_octree_->getLeafContainerAtPoint (voxel_centroid_cloud_->points[closest_index[0]]); + if (seed_leaf) + { + sv_itr->addLeaf (seed_leaf); + } + } + +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::transformFunction (PointT &p) +{ + p.x /= p.z; + p.y /= p.z; + p.z = std::log (p.z); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::SupervoxelClustering::voxelDataDistance (const VoxelData &v1, const VoxelData &v2) const +{ + + float spatial_dist = (v1.xyz_ - v2.xyz_).norm () / seed_resolution_; + float color_dist = (v1.rgb_ - v2.rgb_).norm () / 255.0f; + float cos_angle_normal = 1.0f - std::abs (v1.normal_.dot (v2.normal_)); + // std::cout << "s="< void +pcl::SupervoxelClustering::getSupervoxelAdjacencyList (VoxelAdjacencyList &adjacency_list_arg) const +{ + adjacency_list_arg.clear (); + //Add a vertex for each label, store ids in map + std::map label_ID_map; + for (typename HelperListT::const_iterator sv_itr = supervoxel_helpers_.cbegin (); sv_itr != supervoxel_helpers_.cend (); ++sv_itr) + { + VoxelID node_id = add_vertex (adjacency_list_arg); + adjacency_list_arg[node_id] = (sv_itr->getLabel ()); + label_ID_map.insert (std::make_pair (sv_itr->getLabel (), node_id)); + } + + for (typename HelperListT::const_iterator sv_itr = supervoxel_helpers_.cbegin (); sv_itr != supervoxel_helpers_.cend (); ++sv_itr) + { + uint32_t label = sv_itr->getLabel (); + std::set neighbor_labels; + sv_itr->getNeighborLabels (neighbor_labels); + for (std::set::iterator label_itr = neighbor_labels.begin (); label_itr != neighbor_labels.end (); ++label_itr) + { + bool edge_added; + EdgeID edge; + VoxelID u = (label_ID_map.find (label))->second; + VoxelID v = (label_ID_map.find (*label_itr))->second; + boost::tie (edge, edge_added) = add_edge (u,v,adjacency_list_arg); + //Calc distance between centers, set as edge weight + if (edge_added) + { + VoxelData centroid_data = (sv_itr)->getCentroid (); + //Find the neighbhor with this label + VoxelData neighb_centroid_data; + + for (typename HelperListT::const_iterator neighb_itr = supervoxel_helpers_.cbegin (); neighb_itr != supervoxel_helpers_.cend (); ++neighb_itr) + { + if (neighb_itr->getLabel () == (*label_itr)) + { + neighb_centroid_data = neighb_itr->getCentroid (); + break; + } + } + + float length = voxelDataDistance (centroid_data, neighb_centroid_data); + adjacency_list_arg[edge] = length; + } + } + + } + +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::getSupervoxelAdjacency (std::multimap &label_adjacency) const +{ + label_adjacency.clear (); + for (typename HelperListT::const_iterator sv_itr = supervoxel_helpers_.cbegin (); sv_itr != supervoxel_helpers_.cend (); ++sv_itr) + { + uint32_t label = sv_itr->getLabel (); + std::set neighbor_labels; + sv_itr->getNeighborLabels (neighbor_labels); + for (std::set::iterator label_itr = neighbor_labels.begin (); label_itr != neighbor_labels.end (); ++label_itr) + label_adjacency.insert (std::pair (label, *label_itr) ); + //if (neighbor_labels.size () == 0) + // std::cout << label<<"(size="<size () << ") has "< pcl::PointCloud::Ptr +pcl::SupervoxelClustering::getColoredCloud () const +{ + pcl::PointCloud::Ptr colored_cloud (new pcl::PointCloud); + pcl::copyPointCloud (*input_,*colored_cloud); + + pcl::PointCloud ::iterator i_colored; + typename pcl::PointCloud ::const_iterator i_input = input_->begin (); + std::vector indices; + std::vector sqr_distances; + for (i_colored = colored_cloud->begin (); i_colored != colored_cloud->end (); ++i_colored,++i_input) + { + if ( !pcl::isFinite (*i_input)) + i_colored->rgb = 0; + else + { + i_colored->rgb = 0; + LeafContainerT *leaf = adjacency_octree_->getLeafContainerAtPoint (*i_input); + VoxelData& voxel_data = leaf->getData (); + if (voxel_data.owner_) + i_colored->rgba = label_colors_[voxel_data.owner_->getLabel ()]; + + } + + } + + return (colored_cloud); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template pcl::PointCloud::Ptr +pcl::SupervoxelClustering::getColoredVoxelCloud () const +{ + pcl::PointCloud::Ptr colored_cloud (new pcl::PointCloud); + for (typename HelperListT::const_iterator sv_itr = supervoxel_helpers_.cbegin (); sv_itr != supervoxel_helpers_.cend (); ++sv_itr) + { + typename PointCloudT::Ptr voxels; + sv_itr->getVoxels (voxels); + pcl::PointCloud rgb_copy; + copyPointCloud (*voxels, rgb_copy); + + pcl::PointCloud::iterator rgb_copy_itr = rgb_copy.begin (); + for ( ; rgb_copy_itr != rgb_copy.end (); ++rgb_copy_itr) + rgb_copy_itr->rgba = label_colors_ [sv_itr->getLabel ()]; + + *colored_cloud += rgb_copy; + } + + return colored_cloud; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template typename pcl::PointCloud::Ptr +pcl::SupervoxelClustering::getVoxelCentroidCloud () const +{ + typename PointCloudT::Ptr centroid_copy (new PointCloudT); + copyPointCloud (*voxel_centroid_cloud_, *centroid_copy); + return centroid_copy; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template pcl::PointCloud::Ptr +pcl::SupervoxelClustering::getLabeledVoxelCloud () const +{ + pcl::PointCloud::Ptr labeled_voxel_cloud (new pcl::PointCloud); + for (typename HelperListT::const_iterator sv_itr = supervoxel_helpers_.cbegin (); sv_itr != supervoxel_helpers_.cend (); ++sv_itr) + { + typename PointCloudT::Ptr voxels; + sv_itr->getVoxels (voxels); + pcl::PointCloud xyzl_copy; + copyPointCloud (*voxels, xyzl_copy); + + pcl::PointCloud::iterator xyzl_copy_itr = xyzl_copy.begin (); + for ( ; xyzl_copy_itr != xyzl_copy.end (); ++xyzl_copy_itr) + xyzl_copy_itr->label = sv_itr->getLabel (); + + *labeled_voxel_cloud += xyzl_copy; + } + + return labeled_voxel_cloud; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template pcl::PointCloud::Ptr +pcl::SupervoxelClustering::getLabeledCloud () const +{ + pcl::PointCloud::Ptr labeled_cloud (new pcl::PointCloud); + pcl::copyPointCloud (*input_,*labeled_cloud); + + pcl::PointCloud ::iterator i_labeled; + typename pcl::PointCloud ::const_iterator i_input = input_->begin (); + std::vector indices; + std::vector sqr_distances; + for (i_labeled = labeled_cloud->begin (); i_labeled != labeled_cloud->end (); ++i_labeled,++i_input) + { + if ( !pcl::isFinite (*i_input)) + i_labeled->label = 0; + else + { + i_labeled->label = 0; + LeafContainerT *leaf = adjacency_octree_->getLeafContainerAtPoint (*i_input); + VoxelData& voxel_data = leaf->getData (); + if (voxel_data.owner_) + i_labeled->label = voxel_data.owner_->getLabel (); + + } + + } + + return (labeled_cloud); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template pcl::PointCloud::Ptr +pcl::SupervoxelClustering::makeSupervoxelNormalCloud (std::map::Ptr > &supervoxel_clusters) +{ + pcl::PointCloud::Ptr normal_cloud (new pcl::PointCloud); + normal_cloud->resize (supervoxel_clusters.size ()); + typename std::map ::Ptr>::iterator sv_itr,sv_itr_end; + sv_itr = supervoxel_clusters.begin (); + sv_itr_end = supervoxel_clusters.end (); + pcl::PointCloud::iterator normal_cloud_itr = normal_cloud->begin (); + for ( ; sv_itr != sv_itr_end; ++sv_itr, ++normal_cloud_itr) + { + (sv_itr->second)->getCentroidPointNormal (*normal_cloud_itr); + } + return normal_cloud; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::SupervoxelClustering::getVoxelResolution () const +{ + return (resolution_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::setVoxelResolution (float resolution) +{ + resolution_ = resolution; + +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::SupervoxelClustering::getSeedResolution () const +{ + return (resolution_); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::setSeedResolution (float seed_resolution) +{ + seed_resolution_ = seed_resolution; +} + + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::setColorImportance (float val) +{ + color_importance_ = val; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::setSpatialImportance (float val) +{ + spatial_importance_ = val; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::setNormalImportance (float val) +{ + normal_importance_ = val; +} + + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::initializeLabelColors () +{ + uint32_t max_label = static_cast (getMaxLabel ()); + //If we already have enough colors, return + if (label_colors_.size () > max_label) + return; + + //Otherwise, generate new colors until we have enough + label_colors_.reserve (max_label + 1); + srand (static_cast (time (0))); + while (label_colors_.size () <= max_label ) + { + uint8_t r = static_cast( (rand () % 256)); + uint8_t g = static_cast( (rand () % 256)); + uint8_t b = static_cast( (rand () % 256)); + label_colors_.push_back (static_cast(r) << 16 | static_cast(g) << 8 | static_cast(b)); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::SupervoxelClustering::getMaxLabel () const +{ + int max_label = 0; + for (typename HelperListT::const_iterator sv_itr = supervoxel_helpers_.cbegin (); sv_itr != supervoxel_helpers_.cend (); ++sv_itr) + { + int temp = sv_itr->getLabel (); + if (temp > max_label) + max_label = temp; + } + return max_label; +} + +namespace pcl +{ + + namespace octree + { + //Explicit overloads for RGB types + template<> + void + pcl::octree::OctreePointCloudAdjacencyContainer::VoxelData>::addPoint (const pcl::PointXYZRGB &new_point) + { + ++num_points_; + //Same as before here + data_.xyz_[0] += new_point.x; + data_.xyz_[1] += new_point.y; + data_.xyz_[2] += new_point.z; + //Separate sums for r,g,b since we cant sum in uchars + data_.rgb_[0] += static_cast (new_point.r); + data_.rgb_[1] += static_cast (new_point.g); + data_.rgb_[2] += static_cast (new_point.b); + } + + template<> + void + pcl::octree::OctreePointCloudAdjacencyContainer::VoxelData>::addPoint (const pcl::PointXYZRGBA &new_point) + { + ++num_points_; + //Same as before here + data_.xyz_[0] += new_point.x; + data_.xyz_[1] += new_point.y; + data_.xyz_[2] += new_point.z; + //Separate sums for r,g,b since we cant sum in uchars + data_.rgb_[0] += static_cast (new_point.r); + data_.rgb_[1] += static_cast (new_point.g); + data_.rgb_[2] += static_cast (new_point.b); + } + + + + //Explicit overloads for RGB types + template<> void + pcl::octree::OctreePointCloudAdjacencyContainer::VoxelData>::computeData () + { + data_.rgb_[0] /= (static_cast (num_points_)); + data_.rgb_[1] /= (static_cast (num_points_)); + data_.rgb_[2] /= (static_cast (num_points_)); + data_.xyz_[0] /= (static_cast (num_points_)); + data_.xyz_[1] /= (static_cast (num_points_)); + data_.xyz_[2] /= (static_cast (num_points_)); + } + + template<> void + pcl::octree::OctreePointCloudAdjacencyContainer::VoxelData>::computeData () + { + data_.rgb_[0] /= (static_cast (num_points_)); + data_.rgb_[1] /= (static_cast (num_points_)); + data_.rgb_[2] /= (static_cast (num_points_)); + data_.xyz_[0] /= (static_cast (num_points_)); + data_.xyz_[1] /= (static_cast (num_points_)); + data_.xyz_[2] /= (static_cast (num_points_)); + } + + //Explicit overloads for XYZ types + template<> + void + pcl::octree::OctreePointCloudAdjacencyContainer::VoxelData>::addPoint (const pcl::PointXYZ &new_point) + { + ++num_points_; + //Same as before here + data_.xyz_[0] += new_point.x; + data_.xyz_[1] += new_point.y; + data_.xyz_[2] += new_point.z; + } + + template<> void + pcl::octree::OctreePointCloudAdjacencyContainer::VoxelData>::computeData () + { + data_.xyz_[0] /= (static_cast (num_points_)); + data_.xyz_[1] /= (static_cast (num_points_)); + data_.xyz_[2] /= (static_cast (num_points_)); + } + + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +namespace pcl +{ + + template<> void + pcl::SupervoxelClustering::VoxelData::getPoint (pcl::PointXYZRGB &point_arg) const + { + point_arg.rgba = static_cast(rgb_[0]) << 16 | + static_cast(rgb_[1]) << 8 | + static_cast(rgb_[2]); + point_arg.x = xyz_[0]; + point_arg.y = xyz_[1]; + point_arg.z = xyz_[2]; + } + + template<> void + pcl::SupervoxelClustering::VoxelData::getPoint (pcl::PointXYZRGBA &point_arg ) const + { + point_arg.rgba = static_cast(rgb_[0]) << 16 | + static_cast(rgb_[1]) << 8 | + static_cast(rgb_[2]); + point_arg.x = xyz_[0]; + point_arg.y = xyz_[1]; + point_arg.z = xyz_[2]; + } + + template void + pcl::SupervoxelClustering::VoxelData::getPoint (PointT &point_arg ) const + { + //XYZ is required or this doesn't make much sense... + point_arg.x = xyz_[0]; + point_arg.y = xyz_[1]; + point_arg.z = xyz_[2]; + } + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template void + pcl::SupervoxelClustering::VoxelData::getNormal (Normal &normal_arg) const + { + normal_arg.normal_x = normal_[0]; + normal_arg.normal_y = normal_[1]; + normal_arg.normal_z = normal_[2]; + normal_arg.curvature = curvature_; + } +} + + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::SupervoxelHelper::addLeaf (LeafContainerT* leaf_arg) +{ + leaves_.insert (leaf_arg); + VoxelData& voxel_data = leaf_arg->getData (); + voxel_data.owner_ = this; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::SupervoxelHelper::removeLeaf (LeafContainerT* leaf_arg) +{ + leaves_.erase (leaf_arg); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::SupervoxelHelper::removeAllLeaves () +{ + typename std::set::iterator leaf_itr; + for (leaf_itr = leaves_.begin (); leaf_itr != leaves_.end (); ++leaf_itr) + { + VoxelData& voxel = ((*leaf_itr)->getData ()); + voxel.owner_ = 0; + voxel.distance_ = std::numeric_limits::max (); + } + leaves_.clear (); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::SupervoxelHelper::expand () +{ + //std::cout << "Expanding sv "< new_owned; + new_owned.reserve (leaves_.size () * 9); + //For each leaf belonging to this supervoxel + typename std::set::iterator leaf_itr; + for (leaf_itr = leaves_.begin (); leaf_itr != leaves_.end (); ++leaf_itr) + { + //for each neighbor of the leaf + for (typename LeafContainerT::iterator neighb_itr=(*leaf_itr)->begin (); neighb_itr!=(*leaf_itr)->end (); ++neighb_itr) + { + //Get a reference to the data contained in the leaf + VoxelData& neighbor_voxel = ((*neighb_itr)->getData ()); + //TODO this is a shortcut, really we should always recompute distance + if(neighbor_voxel.owner_ == this) + continue; + //Compute distance to the neighbor + float dist = parent_->voxelDataDistance (centroid_, neighbor_voxel); + //If distance is less than previous, we remove it from its owner's list + //and change the owner to this and distance (we *steal* it!) + if (dist < neighbor_voxel.distance_) + { + neighbor_voxel.distance_ = dist; + if (neighbor_voxel.owner_ != this) + { + if (neighbor_voxel.owner_) + (neighbor_voxel.owner_)->removeLeaf(*neighb_itr); + neighbor_voxel.owner_ = this; + new_owned.push_back (*neighb_itr); + } + } + } + } + //Push all new owned onto the owned leaf set + typename std::vector::iterator new_owned_itr; + for (new_owned_itr=new_owned.begin (); new_owned_itr!=new_owned.end (); ++new_owned_itr) + { + leaves_.insert (*new_owned_itr); + } + +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::SupervoxelHelper::refineNormals () +{ + typename std::set::iterator leaf_itr; + //For each leaf belonging to this supervoxel, get its neighbors, build an index vector, compute normal + for (leaf_itr = leaves_.begin (); leaf_itr != leaves_.end (); ++leaf_itr) + { + VoxelData& voxel_data = (*leaf_itr)->getData (); + std::vector indices; + indices.reserve (81); + //Push this point + indices.push_back (voxel_data.idx_); + for (typename LeafContainerT::iterator neighb_itr=(*leaf_itr)->begin (); neighb_itr!=(*leaf_itr)->end (); ++neighb_itr) + { + //Get a reference to the data contained in the leaf + VoxelData& neighbor_voxel_data = ((*neighb_itr)->getData ()); + //If the neighbor is in this supervoxel, use it + if (neighbor_voxel_data.owner_ == this) + { + indices.push_back (neighbor_voxel_data.idx_); + //Also check its neighbors + for (typename LeafContainerT::iterator neighb_neighb_itr=(*neighb_itr)->begin (); neighb_neighb_itr!=(*neighb_itr)->end (); ++neighb_neighb_itr) + { + VoxelData& neighb_neighb_voxel_data = (*neighb_neighb_itr)->getData (); + if (neighb_neighb_voxel_data.owner_ == this) + indices.push_back (neighb_neighb_voxel_data.idx_); + } + + + } + } + //Compute normal + pcl::computePointNormal (*parent_->voxel_centroid_cloud_, indices, voxel_data.normal_, voxel_data.curvature_); + pcl::flipNormalTowardsViewpoint (parent_->voxel_centroid_cloud_->points[voxel_data.idx_], 0.0f,0.0f,0.0f, voxel_data.normal_); + voxel_data.normal_[3] = 0.0f; + voxel_data.normal_.normalize (); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::SupervoxelHelper::updateCentroid () +{ + centroid_.normal_ = Eigen::Vector4f::Zero (); + centroid_.xyz_ = Eigen::Vector3f::Zero (); + centroid_.rgb_ = Eigen::Vector3f::Zero (); + typename std::set::iterator leaf_itr = leaves_.begin (); + for ( ; leaf_itr!= leaves_.end (); ++leaf_itr) + { + const VoxelData& leaf_data = (*leaf_itr)->getData (); + centroid_.normal_ += leaf_data.normal_; + centroid_.xyz_ += leaf_data.xyz_; + centroid_.rgb_ += leaf_data.rgb_; + } + centroid_.normal_.normalize (); + centroid_.xyz_ /= static_cast (leaves_.size ()); + centroid_.rgb_ /= static_cast (leaves_.size ()); + +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::SupervoxelHelper::getVoxels (typename pcl::PointCloud::Ptr &voxels) const +{ + voxels.reset (new pcl::PointCloud); + voxels->clear (); + voxels->resize (leaves_.size ()); + typename pcl::PointCloud::iterator voxel_itr = voxels->begin (); + //typename std::set::iterator leaf_itr; + for (typename std::set::const_iterator leaf_itr = leaves_.begin (); + leaf_itr != leaves_.end (); + ++leaf_itr, ++voxel_itr) + { + const VoxelData& leaf_data = (*leaf_itr)->getData (); + leaf_data.getPoint (*voxel_itr); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::SupervoxelHelper::getNormals (typename pcl::PointCloud::Ptr &normals) const +{ + normals.reset (new pcl::PointCloud); + normals->clear (); + normals->resize (leaves_.size ()); + typename std::set::const_iterator leaf_itr; + typename pcl::PointCloud::iterator normal_itr = normals->begin (); + for (leaf_itr = leaves_.begin (); leaf_itr != leaves_.end (); ++leaf_itr, ++normal_itr) + { + const VoxelData& leaf_data = (*leaf_itr)->getData (); + leaf_data.getNormal (*normal_itr); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SupervoxelClustering::SupervoxelHelper::getNeighborLabels (std::set &neighbor_labels) const +{ + neighbor_labels.clear (); + //For each leaf belonging to this supervoxel + typename std::set::const_iterator leaf_itr; + for (leaf_itr = leaves_.begin (); leaf_itr != leaves_.end (); ++leaf_itr) + { + //for each neighbor of the leaf + for (typename LeafContainerT::iterator neighb_itr=(*leaf_itr)->begin (); neighb_itr!=(*leaf_itr)->end (); ++neighb_itr) + { + //Get a reference to the data contained in the leaf + VoxelData& neighbor_voxel = ((*neighb_itr)->getData ()); + //If it has an owner, and it's not us - get it's owner's label insert into set + if (neighbor_voxel.owner_ != this && neighbor_voxel.owner_) + { + neighbor_labels.insert (neighbor_voxel.owner_->getLabel ()); + } + } + } +} + + +#endif // PCL_SUPERVOXEL_CLUSTERING_HPP_ + diff --git a/pcl-1.7/pcl/segmentation/min_cut_segmentation.h b/pcl-1.7/pcl/segmentation/min_cut_segmentation.h new file mode 100644 index 0000000..884180d --- /dev/null +++ b/pcl-1.7/pcl/segmentation/min_cut_segmentation.h @@ -0,0 +1,330 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id:$ + * + */ + +#ifndef PCL_MIN_CUT_SEGMENTATION_H_ +#define PCL_MIN_CUT_SEGMENTATION_H_ + +#include +#if (BOOST_VERSION >= 104400) +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief This class implements the segmentation algorithm based on minimal cut of the graph. + * The description can be found in the article: + * "Min-Cut Based Segmentation of Point Clouds" + * \author: Aleksey Golovinskiy and Thomas Funkhouser. + */ + template + class PCL_EXPORTS MinCutSegmentation : public pcl::PCLBase + { + public: + + typedef pcl::search::Search KdTree; + typedef typename KdTree::Ptr KdTreePtr; + typedef pcl::PointCloud< PointT > PointCloud; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + using PCLBase ::input_; + using PCLBase ::indices_; + using PCLBase ::initCompute; + using PCLBase ::deinitCompute; + + public: + + typedef boost::adjacency_list_traits< boost::vecS, boost::vecS, boost::directedS > Traits; + + typedef boost::adjacency_list< boost::vecS, boost::vecS, boost::directedS, + boost::property< boost::vertex_name_t, std::string, + boost::property< boost::vertex_index_t, long, + boost::property< boost::vertex_color_t, boost::default_color_type, + boost::property< boost::vertex_distance_t, long, + boost::property< boost::vertex_predecessor_t, Traits::edge_descriptor > > > > >, + boost::property< boost::edge_capacity_t, double, + boost::property< boost::edge_residual_capacity_t, double, + boost::property< boost::edge_reverse_t, Traits::edge_descriptor > > > > mGraph; + + typedef boost::property_map< mGraph, boost::edge_capacity_t >::type CapacityMap; + + typedef boost::property_map< mGraph, boost::edge_reverse_t>::type ReverseEdgeMap; + + typedef Traits::vertex_descriptor VertexDescriptor; + + typedef boost::graph_traits< mGraph >::edge_descriptor EdgeDescriptor; + + typedef boost::graph_traits< mGraph >::out_edge_iterator OutEdgeIterator; + + typedef boost::graph_traits< mGraph >::vertex_iterator VertexIterator; + + typedef boost::property_map< mGraph, boost::edge_residual_capacity_t >::type ResidualCapacityMap; + + typedef boost::property_map< mGraph, boost::vertex_index_t >::type IndexMap; + + typedef boost::graph_traits< mGraph >::in_edge_iterator InEdgeIterator; + + public: + + /** \brief Constructor that sets default values for member variables. */ + MinCutSegmentation (); + + /** \brief Destructor that frees memory. */ + virtual + ~MinCutSegmentation (); + + /** \brief This method simply sets the input point cloud. + * \param[in] cloud the const boost shared pointer to a PointCloud + */ + virtual void + setInputCloud (const PointCloudConstPtr &cloud); + + /** \brief Returns normalization value for binary potentials. For more information see the article. */ + double + getSigma () const; + + /** \brief Allows to set the normalization value for the binary potentials as described in the article. + * \param[in] sigma new normalization value + */ + void + setSigma (double sigma); + + /** \brief Returns radius to the background. */ + double + getRadius () const; + + /** \brief Allows to set the radius to the background. + * \param[in] radius new radius to the background + */ + void + setRadius (double radius); + + /** \brief Returns weight that every edge from the source point has. */ + double + getSourceWeight () const; + + /** \brief Allows to set weight for source edges. Every edge that comes from the source point will have that weight. + * \param[in] weight new weight + */ + void + setSourceWeight (double weight); + + /** \brief Returns search method that is used for finding KNN. + * The graph is build such way that it contains the edges that connect point and its KNN. + */ + KdTreePtr + getSearchMethod () const; + + /** \brief Allows to set search method for finding KNN. + * The graph is build such way that it contains the edges that connect point and its KNN. + * \param[in] search search method that will be used for finding KNN. + */ + void + setSearchMethod (const KdTreePtr& tree); + + /** \brief Returns the number of neighbours to find. */ + unsigned int + getNumberOfNeighbours () const; + + /** \brief Allows to set the number of neighbours to find. + * \param[in] number_of_neighbours new number of neighbours + */ + void + setNumberOfNeighbours (unsigned int neighbour_number); + + /** \brief Returns the points that must belong to foreground. */ + std::vector > + getForegroundPoints () const; + + /** \brief Allows to specify points which are known to be the points of the object. + * \param[in] foreground_points point cloud that contains foreground points. At least one point must be specified. + */ + void + setForegroundPoints (typename pcl::PointCloud::Ptr foreground_points); + + /** \brief Returns the points that must belong to background. */ + std::vector > + getBackgroundPoints () const; + + /** \brief Allows to specify points which are known to be the points of the background. + * \param[in] background_points point cloud that contains background points. + */ + void + setBackgroundPoints (typename pcl::PointCloud::Ptr background_points); + + /** \brief This method launches the segmentation algorithm and returns the clusters that were + * obtained during the segmentation. The indices of points that belong to the object will be stored + * in the cluster with index 1, other indices will be stored in the cluster with index 0. + * \param[out] clusters clusters that were obtained. Each cluster is an array of point indices. + */ + void + extract (std::vector & clusters); + + /** \brief Returns that flow value that was calculated during the segmentation. */ + double + getMaxFlow () const; + + /** \brief Returns the graph that was build for finding the minimum cut. */ + typename boost::shared_ptr::mGraph> + getGraph () const; + + /** \brief Returns the colored cloud. Points that belong to the object have the same color. */ + pcl::PointCloud::Ptr + getColoredCloud (); + + protected: + + /** \brief This method simply builds the graph that will be used during the segmentation. */ + bool + buildGraph (); + + /** \brief Returns unary potential(data cost) for the given point index. + * In other words it calculates weights for (source, point) and (point, sink) edges. + * \param[in] point index of the point for which weights will be calculated + * \param[out] source_weight calculated weight for the (source, point) edge + * \param[out] sink_weight calculated weight for the (point, sink) edge + */ + void + calculateUnaryPotential (int point, double& source_weight, double& sink_weight) const; + + /** \brief This method simply adds the edge from the source point to the target point with a given weight. + * \param[in] source index of the source point of the edge + * \param[in] target index of the target point of the edge + * \param[in] weight weight that will be assigned to the (source, target) edge + */ + bool + addEdge (int source, int target, double weight); + + /** \brief Returns the binary potential(smooth cost) for the given indices of points. + * In other words it returns weight that must be assigned to the edge from source to target point. + * \param[in] source index of the source point of the edge + * \param[in] target index of the target point of the edge + */ + double + calculateBinaryPotential (int source, int target) const; + + /** \brief This method recalculates unary potentials(data cost) if some changes were made, instead of creating new graph. */ + bool + recalculateUnaryPotentials (); + + /** \brief This method recalculates binary potentials(smooth cost) if some changes were made, instead of creating new graph. */ + bool + recalculateBinaryPotentials (); + + /** \brief This method analyzes the residual network and assigns a label to every point in the cloud. + * \param[in] residual_capacity residual network that was obtained during the segmentation + */ + void + assembleLabels (ResidualCapacityMap& residual_capacity); + + protected: + + /** \brief Stores the sigma coefficient. It is used for finding smooth costs. More information can be found in the article. */ + double inverse_sigma_; + + /** \brief Signalizes if the binary potentials are valid. */ + bool binary_potentials_are_valid_; + + /** \brief Used for comparison of the floating point numbers. */ + double epsilon_; + + /** \brief Stores the distance to the background. */ + double radius_; + + /** \brief Signalizes if the unary potentials are valid. */ + bool unary_potentials_are_valid_; + + /** \brief Stores the weight for every edge that comes from source point. */ + double source_weight_; + + /** \brief Stores the search method that will be used for finding K nearest neighbors. Neighbours are used for building the graph. */ + KdTreePtr search_; + + /** \brief Stores the number of neighbors to find. */ + unsigned int number_of_neighbours_; + + /** \brief Signalizes if the graph is valid. */ + bool graph_is_valid_; + + /** \brief Stores the points that are known to be in the foreground. */ + std::vector > foreground_points_; + + /** \brief Stores the points that are known to be in the background. */ + std::vector > background_points_; + + /** \brief After the segmentation it will contain the segments. */ + std::vector clusters_; + + /** \brief Stores the graph for finding the maximum flow. */ + boost::shared_ptr graph_; + + /** \brief Stores the capacity of every edge in the graph. */ + boost::shared_ptr capacity_; + + /** \brief Stores reverse edges for every edge in the graph. */ + boost::shared_ptr reverse_edges_; + + /** \brief Stores the vertices of the graph. */ + std::vector< VertexDescriptor > vertices_; + + /** \brief Stores the information about the edges that were added to the graph. It is used to avoid the duplicate edges. */ + std::vector< std::set > edge_marker_; + + /** \brief Stores the vertex that serves as source. */ + VertexDescriptor source_; + + /** \brief Stores the vertex that serves as sink. */ + VertexDescriptor sink_; + + /** \brief Stores the maximum flow value that was calculated during the segmentation. */ + double max_flow_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif +#endif diff --git a/pcl-1.7/pcl/segmentation/organized_connected_component_segmentation.h b/pcl-1.7/pcl/segmentation/organized_connected_component_segmentation.h new file mode 100644 index 0000000..ed186e4 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/organized_connected_component_segmentation.h @@ -0,0 +1,155 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + * + */ + +#ifndef PCL_SEGMENTATION_ORGANIZED_CONNECTED_COMPONENT_SEGMENTATION_H_ +#define PCL_SEGMENTATION_ORGANIZED_CONNECTED_COMPONENT_SEGMENTATION_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief OrganizedConnectedComponentSegmentation allows connected + * components to be found within organized point cloud data, given a + * comparison function. Given an input cloud and a comparator, it will + * output a PointCloud of labels, giving each connected component a unique + * id, along with a vector of PointIndices corresponding to each component. + * See OrganizedMultiPlaneSegmentation for an example application. + * + * \author Alex Trevor, Suat Gedikli + */ + template + class OrganizedConnectedComponentSegmentation : public PCLBase + { + using PCLBase::input_; + using PCLBase::indices_; + using PCLBase::initCompute; + using PCLBase::deinitCompute; + + public: + typedef typename pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename pcl::PointCloud PointCloudL; + typedef typename PointCloudL::Ptr PointCloudLPtr; + typedef typename PointCloudL::ConstPtr PointCloudLConstPtr; + + typedef typename pcl::Comparator Comparator; + typedef typename Comparator::Ptr ComparatorPtr; + typedef typename Comparator::ConstPtr ComparatorConstPtr; + + /** \brief Constructor for OrganizedConnectedComponentSegmentation + * \param[in] compare A pointer to the comparator to be used for segmentation. Must be an instance of pcl::Comparator. + */ + OrganizedConnectedComponentSegmentation (const ComparatorConstPtr& compare) + : compare_ (compare) + { + } + + /** \brief Destructor for OrganizedConnectedComponentSegmentation. */ + virtual + ~OrganizedConnectedComponentSegmentation () + { + } + + /** \brief Provide a pointer to the comparator to be used for segmentation. + * \param[in] compare the comparator + */ + void + setComparator (const ComparatorConstPtr& compare) + { + compare_ = compare; + } + + /** \brief Get the comparator.*/ + ComparatorConstPtr + getComparator () const { return (compare_); } + + /** \brief Perform the connected component segmentation. + * \param[out] labels a PointCloud of labels: each connected component will have a unique id. + * \param[out] label_indices a vector of PointIndices corresponding to each label / component id. + */ + void + segment (pcl::PointCloud& labels, std::vector& label_indices) const; + + /** \brief Find the boundary points / contour of a connected component + * \param[in] start_idx the first (lowest) index of the connected component for which a boundary shoudl be returned + * \param[in] labels the Label cloud produced by segmentation + * \param[out] boundary_indices the indices of the boundary points for the label corresponding to start_idx + */ + static void + findLabeledRegionBoundary (int start_idx, PointCloudLPtr labels, pcl::PointIndices& boundary_indices); + + + protected: + ComparatorConstPtr compare_; + + inline unsigned + findRoot (const std::vector& runs, unsigned index) const + { + register unsigned idx = index; + while (runs[idx] != idx) + idx = runs[idx]; + + return (idx); + } + + private: + struct Neighbor + { + Neighbor (int dx, int dy, int didx) + : d_x (dx) + , d_y (dy) + , d_index (didx) + {} + + int d_x; + int d_y; + int d_index; // = dy * width + dx: pre-calculated + }; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_ORGANIZED_CONNECTED_COMPONENT_SEGMENTATION_H_ diff --git a/pcl-1.7/pcl/segmentation/organized_multi_plane_segmentation.h b/pcl-1.7/pcl/segmentation/organized_multi_plane_segmentation.h new file mode 100644 index 0000000..f89805c --- /dev/null +++ b/pcl-1.7/pcl/segmentation/organized_multi_plane_segmentation.h @@ -0,0 +1,324 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SEGMENTATION_ORGANIZED_MULTI_PLANE_SEGMENTATION_H_ +#define PCL_SEGMENTATION_ORGANIZED_MULTI_PLANE_SEGMENTATION_H_ + +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief OrganizedMultiPlaneSegmentation finds all planes present in the + * input cloud, and outputs a vector of plane equations, as well as a vector + * of point clouds corresponding to the inliers of each detected plane. Only + * planes with more than min_inliers points are detected. + * Templated on point type, normal type, and label type + * + * \author Alex Trevor, Suat Gedikli + */ + template + class OrganizedMultiPlaneSegmentation : public PCLBase + { + using PCLBase::input_; + using PCLBase::indices_; + using PCLBase::initCompute; + using PCLBase::deinitCompute; + + public: + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + + typedef typename pcl::PointCloud PointCloudL; + typedef typename PointCloudL::Ptr PointCloudLPtr; + typedef typename PointCloudL::ConstPtr PointCloudLConstPtr; + + typedef typename pcl::PlaneCoefficientComparator PlaneComparator; + typedef typename PlaneComparator::Ptr PlaneComparatorPtr; + typedef typename PlaneComparator::ConstPtr PlaneComparatorConstPtr; + + typedef typename pcl::PlaneRefinementComparator PlaneRefinementComparator; + typedef typename PlaneRefinementComparator::Ptr PlaneRefinementComparatorPtr; + typedef typename PlaneRefinementComparator::ConstPtr PlaneRefinementComparatorConstPtr; + + /** \brief Constructor for OrganizedMultiPlaneSegmentation. */ + OrganizedMultiPlaneSegmentation () : + normals_ (), + min_inliers_ (1000), + angular_threshold_ (pcl::deg2rad (3.0)), + distance_threshold_ (0.02), + maximum_curvature_ (0.001), + project_points_ (false), + compare_ (new PlaneComparator ()), refinement_compare_ (new PlaneRefinementComparator ()) + { + } + + /** \brief Destructor for OrganizedMultiPlaneSegmentation. */ + virtual + ~OrganizedMultiPlaneSegmentation () + { + } + + /** \brief Provide a pointer to the input normals. + * \param[in] normals the input normal cloud + */ + inline void + setInputNormals (const PointCloudNConstPtr &normals) + { + normals_ = normals; + } + + /** \brief Get the input normals. */ + inline PointCloudNConstPtr + getInputNormals () const + { + return (normals_); + } + + /** \brief Set the minimum number of inliers required for a plane + * \param[in] min_inliers the minimum number of inliers required per plane + */ + inline void + setMinInliers (unsigned min_inliers) + { + min_inliers_ = min_inliers; + } + + /** \brief Get the minimum number of inliers required per plane. */ + inline unsigned + getMinInliers () const + { + return (min_inliers_); + } + + /** \brief Set the tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane. + * \param[in] angular_threshold the tolerance in radians + */ + inline void + setAngularThreshold (double angular_threshold) + { + angular_threshold_ = angular_threshold; + } + + /** \brief Get the angular threshold in radians for difference in normal direction between neighboring points, to be considered part of the same plane. */ + inline double + getAngularThreshold () const + { + return (angular_threshold_); + } + + /** \brief Set the tolerance in meters for difference in perpendicular distance (d component of plane equation) to the plane between neighboring points, to be considered part of the same plane. + * \param[in] distance_threshold the tolerance in meters + */ + inline void + setDistanceThreshold (double distance_threshold) + { + distance_threshold_ = distance_threshold; + } + + /** \brief Get the distance threshold in meters (d component of plane equation) between neighboring points, to be considered part of the same plane. */ + inline double + getDistanceThreshold () const + { + return (distance_threshold_); + } + + /** \brief Set the maximum curvature allowed for a planar region. + * \param[in] maximum_curvature the maximum curvature + */ + inline void + setMaximumCurvature (double maximum_curvature) + { + maximum_curvature_ = maximum_curvature; + } + + /** \brief Get the maximum curvature allowed for a planar region. */ + inline double + getMaximumCurvature () const + { + return (maximum_curvature_); + } + + /** \brief Provide a pointer to the comparator to be used for segmentation. + * \param[in] compare A pointer to the comparator to be used for segmentation. + */ + void + setComparator (const PlaneComparatorPtr& compare) + { + compare_ = compare; + } + + /** \brief Provide a pointer to the comparator to be used for refinement. + * \param[in] compare A pointer to the comparator to be used for refinement. + */ + void + setRefinementComparator (const PlaneRefinementComparatorPtr& compare) + { + refinement_compare_ = compare; + } + + /** \brief Set whether or not to project boundary points to the plane, or leave them in the original 3D space. + * \param[in] project_points true if points should be projected, false if not. + */ + void + setProjectPoints (bool project_points) + { + project_points_ = project_points; + } + + /** \brief Segmentation of all planes in a point cloud given by setInputCloud(), setIndices() + * \param[out] model_coefficients a vector of model_coefficients for each plane found in the input cloud + * \param[out] inlier_indices a vector of inliers for each detected plane + * \param[out] centroids a vector of centroids for each plane + * \param[out] covariances a vector of covariance matricies for the inliers of each plane + * \param[out] labels a point cloud for the connected component labels of each pixel + * \param[out] label_indices a vector of PointIndices for each labeled component + */ + void + segment (std::vector& model_coefficients, + std::vector& inlier_indices, + std::vector >& centroids, + std::vector >& covariances, + pcl::PointCloud& labels, + std::vector& label_indices); + + /** \brief Segmentation of all planes in a point cloud given by setInputCloud(), setIndices() + * \param[out] model_coefficients a vector of model_coefficients for each plane found in the input cloud + * \param[out] inlier_indices a vector of inliers for each detected plane + */ + void + segment (std::vector& model_coefficients, + std::vector& inlier_indices); + + /** \brief Segmentation of all planes in a point cloud given by setInputCloud(), setIndices() + * \param[out] regions a list of resultant planar polygonal regions + */ + void + segment (std::vector, Eigen::aligned_allocator > >& regions); + + /** \brief Perform a segmentation, as well as an additional refinement step. This helps with including points whose normals may not match neighboring points well, but may match the planar model well. + * \param[out] regions A list of regions generated by segmentation and refinement. + */ + void + segmentAndRefine (std::vector, Eigen::aligned_allocator > >& regions); + + /** \brief Perform a segmentation, as well as additional refinement step. Returns intermediate data structures for use in + * subsequent processing. + * \param[out] regions A vector of PlanarRegions generated by segmentation + * \param[out] model_coefficients A vector of model coefficients for each segmented plane + * \param[out] inlier_indices A vector of PointIndices, indicating the inliers to each segmented plane + * \param[out] labels A PointCloud corresponding to the resulting segmentation. + * \param[out] label_indices A vector of PointIndices for each label + * \param[out] boundary_indices A vector of PointIndices corresponding to the outer boundary / contour of each label + */ + void + segmentAndRefine (std::vector, Eigen::aligned_allocator > >& regions, + std::vector& model_coefficients, + std::vector& inlier_indices, + PointCloudLPtr& labels, + std::vector& label_indices, + std::vector& boundary_indices); + + /** \brief Perform a refinement of an initial segmentation, by comparing points to adjacent regions detected by the initial segmentation. + * \param [in] model_coefficients The list of segmented model coefficients + * \param [in] inlier_indices The list of segmented inlier indices, corresponding to each model + * \param [in] centroids The list of centroids corresponding to each segmented plane + * \param [in] covariances The list of covariances corresponding to each segemented plane + * \param [in] labels The labels produced by the initial segmentation + * \param [in] label_indices The list of indices corresponding to each label + */ + void + refine (std::vector& model_coefficients, + std::vector& inlier_indices, + std::vector >& centroids, + std::vector >& covariances, + PointCloudLPtr& labels, + std::vector& label_indices); + + protected: + + /** \brief A pointer to the input normals */ + PointCloudNConstPtr normals_; + + /** \brief The minimum number of inliers required for each plane. */ + unsigned min_inliers_; + + /** \brief The tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane. */ + double angular_threshold_; + + /** \brief The tolerance in meters for difference in perpendicular distance (d component of plane equation) to the plane between neighboring points, to be considered part of the same plane. */ + double distance_threshold_; + + /** \brief The tolerance for maximum curvature after fitting a plane. Used to remove smooth, but non-planar regions. */ + double maximum_curvature_; + + /** \brief Whether or not points should be projected to the plane, or left in the original 3D space. */ + bool project_points_; + + /** \brief A comparator for comparing neighboring pixels' plane equations. */ + PlaneComparatorPtr compare_; + + /** \brief A comparator for use on the refinement step. Compares points to regions segmented in the first pass. */ + PlaneRefinementComparatorPtr refinement_compare_; + + /** \brief Class getName method. */ + virtual std::string + getClassName () const + { + return ("OrganizedMultiPlaneSegmentation"); + } + }; + +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SEGMENTATION_ORGANIZED_MULTI_PLANE_SEGMENTATION_H_ diff --git a/pcl-1.7/pcl/segmentation/planar_polygon_fusion.h b/pcl-1.7/pcl/segmentation/planar_polygon_fusion.h new file mode 100644 index 0000000..82bf51a --- /dev/null +++ b/pcl-1.7/pcl/segmentation/planar_polygon_fusion.h @@ -0,0 +1,90 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SEGMENTATION_PLANAR_POLYGON_FUSION_H_ +#define PCL_SEGMENTATION_PLANAR_POLYGON_FUSION_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief PlanarPolygonFusion takes a list of 2D planar polygons and + * attempts to reduce them to a minimum set that best represents the scene, + * based on various given comparators. + */ + template + class PlanarPolygonFusion + { + public: + /** \brief Constructor */ + PlanarPolygonFusion () : regions_ () {} + + /** \brief Destructor */ + virtual ~PlanarPolygonFusion () {} + + /** \brief Reset the state (clean the list of planar models). */ + void + reset () + { + regions_.clear (); + } + + /** \brief Set the list of 2D planar polygons to refine. + * \param[in] input the list of 2D planar polygons to refine + */ + void + addInputPolygons (const std::vector, Eigen::aligned_allocator > > &input) + { + int start = static_cast (regions_.size ()); + regions_.resize (regions_.size () + input.size ()); + for(size_t i = 0; i < input.size (); i++) + regions_[start+i] = input[i]; + } + + protected: + /** \brief Internal list of planar states. */ + std::vector, Eigen::aligned_allocator > > regions_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_SEGMENTATION_PLANAR_POLYGON_FUSION_H_ diff --git a/pcl-1.7/pcl/segmentation/planar_region.h b/pcl-1.7/pcl/segmentation/planar_region.h new file mode 100644 index 0000000..d0b3300 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/planar_region.h @@ -0,0 +1,111 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SEGMENTATION_PLANAR_REGION_H_ +#define PCL_SEGMENTATION_PLANAR_REGION_H_ + +#include +#include + +namespace pcl +{ + /** \brief PlanarRegion represents a set of points that lie in a plane. Inherits summary statistics about these points from Region3D, and summary statistics of a 3D collection of points. + * \author Alex Trevor + */ + template + class PlanarRegion : public pcl::Region3D, public pcl::PlanarPolygon + { + protected: + using Region3D::centroid_; + using Region3D::covariance_; + using Region3D::count_; + using PlanarPolygon::contour_; + using PlanarPolygon::coefficients_; + + public: + /** \brief Empty constructor for PlanarRegion. */ + PlanarRegion () : contour_labels_ () + {} + + /** \brief Constructor for Planar region from a Region3D and a PlanarPolygon. + * \param[in] region a Region3D for the input data + * \param[in] polygon a PlanarPolygon for the input region + */ + PlanarRegion (const pcl::Region3D& region, const pcl::PlanarPolygon& polygon) : + contour_labels_ () + { + centroid_ = region.centroid; + covariance_ = region.covariance; + count_ = region.count; + contour_ = polygon.contour; + coefficients_ = polygon.coefficients; + } + + /** \brief Destructor. */ + virtual ~PlanarRegion () {} + + /** \brief Constructor for PlanarRegion. + * \param[in] centroid the centroid of the region. + * \param[in] covariance the covariance of the region. + * \param[in] count the number of points in the region. + * \param[in] contour the contour / boudnary for the region + * \param[in] coefficients the model coefficients (a,b,c,d) for the plane + */ + PlanarRegion (const Eigen::Vector3f& centroid, const Eigen::Matrix3f& covariance, unsigned count, + const typename pcl::PointCloud::VectorType& contour, + const Eigen::Vector4f& coefficients) : + contour_labels_ () + { + centroid_ = centroid; + covariance_ = covariance; + count_ = count; + contour_ = contour; + coefficients_ = coefficients; + } + + private: + /** \brief The labels (good=true, bad=false) for whether or not this boundary was observed, + * or was due to edge of frame / occlusion boundary. + */ + std::vector contour_labels_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#endif //PCL_SEGMENTATION_PLANAR_REGION_H_ diff --git a/pcl-1.7/pcl/segmentation/plane_coefficient_comparator.h b/pcl-1.7/pcl/segmentation/plane_coefficient_comparator.h new file mode 100644 index 0000000..9c94813 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/plane_coefficient_comparator.h @@ -0,0 +1,215 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ +#define PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief PlaneCoefficientComparator is a Comparator that operates on plane coefficients, for use in planar segmentation. + * In conjunction with OrganizedConnectedComponentSegmentation, this allows planes to be segmented from organized data. + * + * \author Alex Trevor + */ + template + class PlaneCoefficientComparator: public Comparator + { + public: + typedef typename Comparator::PointCloud PointCloud; + typedef typename Comparator::PointCloudConstPtr PointCloudConstPtr; + + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using pcl::Comparator::input_; + + /** \brief Empty constructor for PlaneCoefficientComparator. */ + PlaneCoefficientComparator () + : normals_ () + , plane_coeff_d_ () + , angular_threshold_ (pcl::deg2rad (2.0f)) + , distance_threshold_ (0.02f) + , depth_dependent_ (true) + , z_axis_ (Eigen::Vector3f (0.0, 0.0, 1.0) ) + { + } + + /** \brief Constructor for PlaneCoefficientComparator. + * \param[in] plane_coeff_d a reference to a vector of d coefficients of plane equations. Must be the same size as the input cloud and input normals. a, b, and c coefficients are in the input normals. + */ + PlaneCoefficientComparator (boost::shared_ptr >& plane_coeff_d) + : normals_ () + , plane_coeff_d_ (plane_coeff_d) + , angular_threshold_ (pcl::deg2rad (2.0f)) + , distance_threshold_ (0.02f) + , depth_dependent_ (true) + , z_axis_ (Eigen::Vector3f (0.0f, 0.0f, 1.0f) ) + { + } + + /** \brief Destructor for PlaneCoefficientComparator. */ + virtual + ~PlaneCoefficientComparator () + { + } + + virtual void + setInputCloud (const PointCloudConstPtr& cloud) + { + input_ = cloud; + } + + /** \brief Provide a pointer to the input normals. + * \param[in] normals the input normal cloud + */ + inline void + setInputNormals (const PointCloudNConstPtr &normals) + { + normals_ = normals; + } + + /** \brief Get the input normals. */ + inline PointCloudNConstPtr + getInputNormals () const + { + return (normals_); + } + + /** \brief Provide a pointer to a vector of the d-coefficient of the planes' hessian normal form. a, b, and c are provided by the normal cloud. + * \param[in] plane_coeff_d a pointer to the plane coefficients. + */ + void + setPlaneCoeffD (boost::shared_ptr >& plane_coeff_d) + { + plane_coeff_d_ = plane_coeff_d; + } + + /** \brief Provide a pointer to a vector of the d-coefficient of the planes' hessian normal form. a, b, and c are provided by the normal cloud. + * \param[in] plane_coeff_d a pointer to the plane coefficients. + */ + void + setPlaneCoeffD (std::vector& plane_coeff_d) + { + plane_coeff_d_ = boost::make_shared >(plane_coeff_d); + } + + /** \brief Get a pointer to the vector of the d-coefficient of the planes' hessian normal form. */ + const std::vector& + getPlaneCoeffD () const + { + return (plane_coeff_d_); + } + + /** \brief Set the tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane. + * \param[in] angular_threshold the tolerance in radians + */ + virtual void + setAngularThreshold (float angular_threshold) + { + angular_threshold_ = cosf (angular_threshold); + } + + /** \brief Get the angular threshold in radians for difference in normal direction between neighboring points, to be considered part of the same plane. */ + inline float + getAngularThreshold () const + { + return (acosf (angular_threshold_) ); + } + + /** \brief Set the tolerance in meters for difference in perpendicular distance (d component of plane equation) to the plane between neighboring points, to be considered part of the same plane. + * \param[in] distance_threshold the tolerance in meters (at 1m) + * \param[in] depth_dependent whether to scale the threshold based on range from the sensor (default: false) + */ + void + setDistanceThreshold (float distance_threshold, + bool depth_dependent = false) + { + distance_threshold_ = distance_threshold; + depth_dependent_ = depth_dependent; + } + + /** \brief Get the distance threshold in meters (d component of plane equation) between neighboring points, to be considered part of the same plane. */ + inline float + getDistanceThreshold () const + { + return (distance_threshold_); + } + + /** \brief Compare points at two indices by their plane equations. True if the angle between the normals is less than the angular threshold, + * and the difference between the d component of the normals is less than distance threshold, else false + * \param idx1 The first index for the comparison + * \param idx2 The second index for the comparison + */ + virtual bool + compare (int idx1, int idx2) const + { + float threshold = distance_threshold_; + if (depth_dependent_) + { + Eigen::Vector3f vec = input_->points[idx1].getVector3fMap (); + + float z = vec.dot (z_axis_); + threshold *= z * z; + } + return ( (fabs ((*plane_coeff_d_)[idx1] - (*plane_coeff_d_)[idx2]) < threshold) + && (normals_->points[idx1].getNormalVector3fMap ().dot (normals_->points[idx2].getNormalVector3fMap () ) > angular_threshold_ ) ); + } + + protected: + PointCloudNConstPtr normals_; + boost::shared_ptr > plane_coeff_d_; + float angular_threshold_; + float distance_threshold_; + bool depth_dependent_; + Eigen::Vector3f z_axis_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#endif // PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ diff --git a/pcl-1.7/pcl/segmentation/plane_refinement_comparator.h b/pcl-1.7/pcl/segmentation/plane_refinement_comparator.h new file mode 100644 index 0000000..ded8c76 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/plane_refinement_comparator.h @@ -0,0 +1,223 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: extract_clusters.h 5027 2012-03-12 03:10:45Z rusu $ + * + */ + +#ifndef PCL_SEGMENTATION_PLANAR_REFINEMENT_COMPARATOR_H_ +#define PCL_SEGMENTATION_PLANAR_REFINEMENT_COMPARATOR_H_ + +#include +#include + +namespace pcl +{ + /** \brief PlaneRefinementComparator is a Comparator that operates on plane coefficients, + * for use in planar segmentation. + * In conjunction with OrganizedConnectedComponentSegmentation, this allows planes to be segmented from organized data. + * + * \author Alex Trevor, Suat Gedikli + */ + template + class PlaneRefinementComparator: public PlaneCoefficientComparator + { + public: + typedef typename Comparator::PointCloud PointCloud; + typedef typename Comparator::PointCloudConstPtr PointCloudConstPtr; + + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + + typedef typename pcl::PointCloud PointCloudL; + typedef typename PointCloudL::Ptr PointCloudLPtr; + typedef typename PointCloudL::ConstPtr PointCloudLConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using pcl::PlaneCoefficientComparator::input_; + using pcl::PlaneCoefficientComparator::normals_; + using pcl::PlaneCoefficientComparator::distance_threshold_; + using pcl::PlaneCoefficientComparator::plane_coeff_d_; + + + /** \brief Empty constructor for PlaneCoefficientComparator. */ + PlaneRefinementComparator () + : models_ () + , labels_ () + , refine_labels_ () + , label_to_model_ () + , depth_dependent_ (false) + { + } + + /** \brief Empty constructor for PlaneCoefficientComparator. + * \param[in] models + * \param[in] refine_labels + */ + PlaneRefinementComparator (boost::shared_ptr >& models, + boost::shared_ptr >& refine_labels) + : models_ (models) + , labels_ () + , refine_labels_ (refine_labels) + , label_to_model_ () + , depth_dependent_ (false) + { + } + + /** \brief Destructor for PlaneCoefficientComparator. */ + virtual + ~PlaneRefinementComparator () + { + } + + /** \brief Set the vector of model coefficients to which we will compare. + * \param[in] models a vector of model coefficients produced by the initial segmentation step. + */ + void + setModelCoefficients (boost::shared_ptr >& models) + { + models_ = models; + } + + /** \brief Set the vector of model coefficients to which we will compare. + * \param[in] models a vector of model coefficients produced by the initial segmentation step. + */ + void + setModelCoefficients (std::vector& models) + { + models_ = boost::make_shared >(models); + } + + /** \brief Set which labels should be refined. This is a vector of bools 0-max_label, true if the label should be refined. + * \param[in] refine_labels A vector of bools 0-max_label, true if the label should be refined. + */ + void + setRefineLabels (boost::shared_ptr >& refine_labels) + { + refine_labels_ = refine_labels; + } + + /** \brief Set which labels should be refined. This is a vector of bools 0-max_label, true if the label should be refined. + * \param[in] refine_labels A vector of bools 0-max_label, true if the label should be refined. + */ + void + setRefineLabels (std::vector& refine_labels) + { + refine_labels_ = boost::make_shared >(refine_labels); + } + + /** \brief A mapping from label to index in the vector of models, allowing the model coefficients of a label to be accessed. + * \param[in] label_to_model A vector of size max_label, with the index of each corresponding model in models + */ + inline void + setLabelToModel (boost::shared_ptr >& label_to_model) + { + label_to_model_ = label_to_model; + } + + /** \brief A mapping from label to index in the vector of models, allowing the model coefficients of a label to be accessed. + * \param[in] label_to_model A vector of size max_label, with the index of each corresponding model in models + */ + inline void + setLabelToModel (std::vector& label_to_model) + { + label_to_model_ = boost::make_shared >(label_to_model); + } + + /** \brief Get the vector of model coefficients to which we will compare. */ + inline boost::shared_ptr > + getModelCoefficients () const + { + return (models_); + } + + /** \brief ... + * \param[in] labels + */ + inline void + setLabels (PointCloudLPtr& labels) + { + labels_ = labels; + } + + /** \brief Compare two neighboring points + * \param[in] idx1 The index of the first point. + * \param[in] idx2 The index of the second point. + */ + virtual bool + compare (int idx1, int idx2) const + { + int current_label = labels_->points[idx1].label; + int next_label = labels_->points[idx2].label; + + if (!((*refine_labels_)[current_label] && !(*refine_labels_)[next_label])) + return (false); + + const pcl::ModelCoefficients& model_coeff = (*models_)[(*label_to_model_)[current_label]]; + + PointT pt = input_->points[idx2]; + double ptp_dist = fabs (model_coeff.values[0] * pt.x + + model_coeff.values[1] * pt.y + + model_coeff.values[2] * pt.z + + model_coeff.values[3]); + + // depth dependent + float threshold = distance_threshold_; + if (depth_dependent_) + { + //Eigen::Vector4f origin = input_->sensor_origin_; + Eigen::Vector3f vec = input_->points[idx1].getVector3fMap ();// - origin.head<3> (); + + float z = vec.dot (z_axis_); + threshold *= z * z; + } + + return (ptp_dist < threshold); + } + + protected: + boost::shared_ptr > models_; + PointCloudLPtr labels_; + boost::shared_ptr > refine_labels_; + boost::shared_ptr > label_to_model_; + bool depth_dependent_; + using PlaneCoefficientComparator::z_axis_; + }; +} + +#endif // PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ diff --git a/pcl-1.7/pcl/segmentation/progressive_morphological_filter.h b/pcl-1.7/pcl/segmentation/progressive_morphological_filter.h new file mode 100644 index 0000000..5935e8a --- /dev/null +++ b/pcl-1.7/pcl/segmentation/progressive_morphological_filter.h @@ -0,0 +1,169 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * Copyright (c) 2014, RadiantBlue Technologies, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PCL_PROGRESSIVE_MORPHOLOGICAL_FILTER_H_ +#define PCL_PROGRESSIVE_MORPHOLOGICAL_FILTER_H_ + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief + * Implements the Progressive Morphological Filter for segmentation of ground points. + * Description can be found in the article + * "A Progressive Morphological Filter for Removing Nonground Measurements from + * Airborne LIDAR Data" + * by K. Zhang, S. Chen, D. Whitman, M. Shyu, J. Yan, and C. Zhang. + */ + template + class PCL_EXPORTS ProgressiveMorphologicalFilter : public pcl::PCLBase + { + public: + + typedef pcl::PointCloud PointCloud; + + using PCLBase ::input_; + using PCLBase ::indices_; + using PCLBase ::initCompute; + using PCLBase ::deinitCompute; + + public: + + /** \brief Constructor that sets default values for member variables. */ + ProgressiveMorphologicalFilter (); + + virtual + ~ProgressiveMorphologicalFilter (); + + /** \brief Get the maximum window size to be used in filtering ground returns. */ + inline int + getMaxWindowSize () const { return (max_window_size_); } + + /** \brief Set the maximum window size to be used in filtering ground returns. */ + inline void + setMaxWindowSize (int max_window_size) { max_window_size_ = max_window_size; } + + /** \brief Get the slope value to be used in computing the height threshold. */ + inline float + getSlope () const { return (slope_); } + + /** \brief Set the slope value to be used in computing the height threshold. */ + inline void + setSlope (float slope) { slope_ = slope; } + + /** \brief Get the maximum height above the parameterized ground surface to be considered a ground return. */ + inline float + getMaxDistance () const { return (max_distance_); } + + /** \brief Set the maximum height above the parameterized ground surface to be considered a ground return. */ + inline void + setMaxDistance (float max_distance) { max_distance_ = max_distance; } + + /** \brief Get the initial height above the parameterized ground surface to be considered a ground return. */ + inline float + getInitialDistance () const { return (initial_distance_); } + + /** \brief Set the initial height above the parameterized ground surface to be considered a ground return. */ + inline void + setInitialDistance (float initial_distance) { initial_distance_ = initial_distance; } + + /** \brief Get the cell size. */ + inline float + getCellSize () const { return (cell_size_); } + + /** \brief Set the cell size. */ + inline void + setCellSize (float cell_size) { cell_size_ = cell_size; } + + /** \brief Get the base to be used in computing progressive window sizes. */ + inline float + getBase () const { return (base_); } + + /** \brief Set the base to be used in computing progressive window sizes. */ + inline void + setBase (float base) { base_ = base; } + + /** \brief Get flag indicating whether or not to exponentially grow window sizes? */ + inline bool + getExponential () const { return (exponential_); } + + /** \brief Set flag indicating whether or not to exponentially grow window sizes? */ + inline void + setExponential (bool exponential) { exponential_ = exponential; } + + /** \brief This method launches the segmentation algorithm and returns indices of + * points determined to be ground returns. + * \param[out] ground indices of points determined to be ground returns. + */ + virtual void + extract (std::vector& ground); + + protected: + + /** \brief Maximum window size to be used in filtering ground returns. */ + int max_window_size_; + + /** \brief Slope value to be used in computing the height threshold. */ + float slope_; + + /** \brief Maximum height above the parameterized ground surface to be considered a ground return. */ + float max_distance_; + + /** \brief Initial height above the parameterized ground surface to be considered a ground return. */ + float initial_distance_; + + /** \brief Cell size. */ + float cell_size_; + + /** \brief Base to be used in computing progressive window sizes. */ + float base_; + + /** \brief Exponentially grow window sizes? */ + bool exponential_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif + diff --git a/pcl-1.7/pcl/segmentation/region_3d.h b/pcl-1.7/pcl/segmentation/region_3d.h new file mode 100644 index 0000000..52df2e3 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/region_3d.h @@ -0,0 +1,124 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SEGMENTATION_REGION_3D_H_ +#define PCL_SEGMENTATION_REGION_3D_H_ + +#include +#include + +namespace pcl +{ + /** \brief Region3D represents summary statistics of a 3D collection of points. + * \author Alex Trevor + */ + template + class Region3D + { + public: + /** \brief Empty constructor for Region3D. */ + Region3D () : centroid_ (Eigen::Vector3f::Zero ()), covariance_ (Eigen::Matrix3f::Identity ()), count_ (0) + { + } + + /** \brief Constructor for Region3D. + * \param[in] centroid The centroid of the region. + * \param[in] covariance The covariance of the region. + * \param[in] count The number of points in the region. + */ + Region3D (Eigen::Vector3f& centroid, Eigen::Matrix3f& covariance, unsigned count) + : centroid_ (centroid), covariance_ (covariance), count_ (count) + { + } + + /** \brief Destructor. */ + virtual ~Region3D () {} + + /** \brief Get the centroid of the region. */ + inline Eigen::Vector3f + getCentroid () const + { + return (centroid_); + } + + /** \brief Get the covariance of the region. */ + inline Eigen::Matrix3f + getCovariance () const + { + return (covariance_); + } + + /** \brief Get the number of points in the region. */ + unsigned + getCount () const + { + return (count_); + } + + /** \brief Get the curvature of the region. */ + float + getCurvature () const + { + return (curvature_); + } + + /** \brief Set the curvature of the region. */ + void + setCurvature (float curvature) + { + curvature_ = curvature; + } + + protected: + /** \brief The centroid of the region. */ + Eigen::Vector3f centroid_; + + /** \brief The covariance of the region. */ + Eigen::Matrix3f covariance_; + + /** \brief The number of points in the region. */ + unsigned count_; + + /** \brief The mean curvature of the region. */ + float curvature_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#endif //#ifndef PCL_SEGMENTATION_REGION_3D_H_ diff --git a/pcl-1.7/pcl/segmentation/region_growing.h b/pcl-1.7/pcl/segmentation/region_growing.h new file mode 100644 index 0000000..7a5afff --- /dev/null +++ b/pcl-1.7/pcl/segmentation/region_growing.h @@ -0,0 +1,351 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : Sergey Ushakov + * Email : mine_all_mine@bk.ru + * + */ + +#ifndef PCL_REGION_GROWING_H_ +#define PCL_REGION_GROWING_H_ + +#include +#include +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief + * Implements the well known Region Growing algorithm used for segmentation. + * Description can be found in the article + * "Segmentation of point clouds using smoothness constraint" + * by T. Rabbania, F. A. van den Heuvelb, G. Vosselmanc. + * In addition to residual test, the possibility to test curvature is added. + */ + template + class PCL_EXPORTS RegionGrowing : public pcl::PCLBase + { + public: + + typedef pcl::search::Search KdTree; + typedef typename KdTree::Ptr KdTreePtr; + typedef pcl::PointCloud Normal; + typedef typename Normal::Ptr NormalPtr; + typedef pcl::PointCloud PointCloud; + + using PCLBase ::input_; + using PCLBase ::indices_; + using PCLBase ::initCompute; + using PCLBase ::deinitCompute; + + public: + + /** \brief Constructor that sets default values for member variables. */ + RegionGrowing (); + + /** \brief This destructor destroys the cloud, normals and search method used for + * finding KNN. In other words it frees memory. + */ + virtual + ~RegionGrowing (); + + /** \brief Get the minimum number of points that a cluster needs to contain in order to be considered valid. */ + int + getMinClusterSize (); + + /** \brief Set the minimum number of points that a cluster needs to contain in order to be considered valid. */ + void + setMinClusterSize (int min_cluster_size); + + /** \brief Get the maximum number of points that a cluster needs to contain in order to be considered valid. */ + int + getMaxClusterSize (); + + /** \brief Set the maximum number of points that a cluster needs to contain in order to be considered valid. */ + void + setMaxClusterSize (int max_cluster_size); + + /** \brief Returns the flag value. This flag signalizes which mode of algorithm will be used. + * If it is set to true than it will work as said in the article. This means that + * it will be testing the angle between normal of the current point and it's neighbours normal. + * Otherwise, it will be testing the angle between normal of the current point + * and normal of the initial point that was chosen for growing new segment. + */ + bool + getSmoothModeFlag () const; + + /** \brief This function allows to turn on/off the smoothness constraint. + * \param[in] value new mode value, if set to true then the smooth version will be used. + */ + void + setSmoothModeFlag (bool value); + + /** \brief Returns the flag that signalize if the curvature test is turned on/off. */ + bool + getCurvatureTestFlag () const; + + /** \brief Allows to turn on/off the curvature test. Note that at least one test + * (residual or curvature) must be turned on. If you are turning curvature test off + * then residual test will be turned on automatically. + * \param[in] value new value for curvature test. If set to true then the test will be turned on + */ + virtual void + setCurvatureTestFlag (bool value); + + /** \brief Returns the flag that signalize if the residual test is turned on/off. */ + bool + getResidualTestFlag () const; + + /** \brief + * Allows to turn on/off the residual test. Note that at least one test + * (residual or curvature) must be turned on. If you are turning residual test off + * then curvature test will be turned on automatically. + * \param[in] value new value for residual test. If set to true then the test will be turned on + */ + virtual void + setResidualTestFlag (bool value); + + /** \brief Returns smoothness threshold. */ + float + getSmoothnessThreshold () const; + + /** \brief Allows to set smoothness threshold used for testing the points. + * \param[in] theta new threshold value for the angle between normals + */ + void + setSmoothnessThreshold (float theta); + + /** \brief Returns residual threshold. */ + float + getResidualThreshold () const; + + /** \brief Allows to set residual threshold used for testing the points. + * \param[in] residual new threshold value for residual testing + */ + void + setResidualThreshold (float residual); + + /** \brief Returns curvature threshold. */ + float + getCurvatureThreshold () const; + + /** \brief Allows to set curvature threshold used for testing the points. + * \param[in] curvature new threshold value for curvature testing + */ + void + setCurvatureThreshold (float curvature); + + /** \brief Returns the number of nearest neighbours used for KNN. */ + unsigned int + getNumberOfNeighbours () const; + + /** \brief Allows to set the number of neighbours. For more information check the article. + * \param[in] neighbour_number number of neighbours to use + */ + void + setNumberOfNeighbours (unsigned int neighbour_number); + + /** \brief Returns the pointer to the search method that is used for KNN. */ + KdTreePtr + getSearchMethod () const; + + /** \brief Allows to set search method that will be used for finding KNN. + * \param[in] tree pointer to a KdTree + */ + void + setSearchMethod (const KdTreePtr& tree); + + /** \brief Returns normals. */ + NormalPtr + getInputNormals () const; + + /** \brief This method sets the normals. They are needed for the algorithm, so if + * no normals will be set, the algorithm would not be able to segment the points. + * \param[in] norm normals that will be used in the algorithm + */ + void + setInputNormals (const NormalPtr& norm); + + /** \brief This method launches the segmentation algorithm and returns the clusters that were + * obtained during the segmentation. + * \param[out] clusters clusters that were obtained. Each cluster is an array of point indices. + */ + virtual void + extract (std::vector & clusters); + + /** \brief For a given point this function builds a segment to which it belongs and returns this segment. + * \param[in] index index of the initial point which will be the seed for growing a segment. + * \param[out] cluster cluster to which the point belongs. + */ + virtual void + getSegmentFromPoint (int index, pcl::PointIndices& cluster); + + /** \brief If the cloud was successfully segmented, then function + * returns colored cloud. Otherwise it returns an empty pointer. + * Points that belong to the same segment have the same color. + * But this function doesn't guarantee that different segments will have different + * color(it all depends on RNG). Points that were not listed in the indices array will have red color. + */ + pcl::PointCloud::Ptr + getColoredCloud (); + + /** \brief If the cloud was successfully segmented, then function + * returns colored cloud. Otherwise it returns an empty pointer. + * Points that belong to the same segment have the same color. + * But this function doesn't guarantee that different segments will have different + * color(it all depends on RNG). Points that were not listed in the indices array will have red color. + */ + pcl::PointCloud::Ptr + getColoredCloudRGBA (); + + protected: + + /** \brief This method simply checks if it is possible to execute the segmentation algorithm with + * the current settings. If it is possible then it returns true. + */ + virtual bool + prepareForSegmentation (); + + /** \brief This method finds KNN for each point and saves them to the array + * because the algorithm needs to find KNN a few times. + */ + virtual void + findPointNeighbours (); + + /** \brief This function implements the algorithm described in the article + * "Segmentation of point clouds using smoothness constraint" + * by T. Rabbania, F. A. van den Heuvelb, G. Vosselmanc. + */ + void + applySmoothRegionGrowingAlgorithm (); + + /** \brief This method grows a segment for the given seed point. And returns the number of its points. + * \param[in] initial_seed index of the point that will serve as the seed point + * \param[in] segment_number indicates which number this segment will have + */ + int + growRegion (int initial_seed, int segment_number); + + /** \brief This function is checking if the point with index 'nghbr' belongs to the segment. + * If so, then it returns true. It also checks if this point can serve as the seed. + * \param[in] initial_seed index of the initial point that was passed to the growRegion() function + * \param[in] point index of the current seed point + * \param[in] nghbr index of the point that is neighbour of the current seed + * \param[out] is_a_seed this value is set to true if the point with index 'nghbr' can serve as the seed + */ + virtual bool + validatePoint (int initial_seed, int point, int nghbr, bool& is_a_seed) const; + + /** \brief This function simply assembles the regions from list of point labels. + * Each cluster is an array of point indices. + */ + void + assembleRegions (); + + protected: + + /** \brief Stores the minimum number of points that a cluster needs to contain in order to be considered valid. */ + int min_pts_per_cluster_; + + /** \brief Stores the maximum number of points that a cluster needs to contain in order to be considered valid. */ + int max_pts_per_cluster_; + + /** \brief Flag that signalizes if the smoothness constraint will be used. */ + bool smooth_mode_flag_; + + /** \brief If set to true then curvature test will be done during segmentation. */ + bool curvature_flag_; + + /** \brief If set to true then residual test will be done during segmentation. */ + bool residual_flag_; + + /** \brief Thershold used for testing the smoothness between points. */ + float theta_threshold_; + + /** \brief Thershold used in residual test. */ + float residual_threshold_; + + /** \brief Thershold used in curvature test. */ + float curvature_threshold_; + + /** \brief Number of neighbours to find. */ + unsigned int neighbour_number_; + + /** \brief Serch method that will be used for KNN. */ + KdTreePtr search_; + + /** \brief Contains normals of the points that will be segmented. */ + NormalPtr normals_; + + /** \brief Contains neighbours of each point. */ + std::vector > point_neighbours_; + + /** \brief Point labels that tells to which segment each point belongs. */ + std::vector point_labels_; + + /** \brief If set to true then normal/smoothness test will be done during segmentation. + * It is always set to true for the usual region growing algorithm. It is used for turning on/off the test + * for smoothness in the child class RegionGrowingRGB.*/ + bool normal_flag_; + + /** \brief Tells how much points each segment contains. Used for reserving memory. */ + std::vector num_pts_in_segment_; + + /** \brief After the segmentation it will contain the segments. */ + std::vector clusters_; + + /** \brief Stores the number of segments. */ + int number_of_segments_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + /** \brief This function is used as a comparator for sorting. */ + inline bool + comparePair (std::pair i, std::pair j) + { + return (i.first < j.first); + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/segmentation/region_growing_rgb.h b/pcl-1.7/pcl/segmentation/region_growing_rgb.h new file mode 100644 index 0000000..e4cee10 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/region_growing_rgb.h @@ -0,0 +1,285 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : Sergey Ushakov + * Email : mine_all_mine@bk.ru + * + */ + +#ifndef PCL_REGION_GROWING_RGB_H_ +#define PCL_REGION_GROWING_RGB_H_ + +#include + +namespace pcl +{ + /** \brief + * Implements the well known Region Growing algorithm used for segmentation based on color of points. + * Description can be found in the article + * "Color-based segmentation of point clouds" + * by Qingming Zhan, Yubin Liang, Yinghui Xiao + */ + template + class PCL_EXPORTS RegionGrowingRGB : public RegionGrowing + { + public: + + using RegionGrowing::input_; + using RegionGrowing::indices_; + using RegionGrowing::initCompute; + using RegionGrowing::deinitCompute; + using RegionGrowing::normals_; + using RegionGrowing::normal_flag_; + using RegionGrowing::curvature_flag_; + using RegionGrowing::residual_flag_; + using RegionGrowing::residual_threshold_; + using RegionGrowing::neighbour_number_; + using RegionGrowing::search_; + using RegionGrowing::min_pts_per_cluster_; + using RegionGrowing::max_pts_per_cluster_; + using RegionGrowing::smooth_mode_flag_; + using RegionGrowing::theta_threshold_; + using RegionGrowing::curvature_threshold_; + using RegionGrowing::point_neighbours_; + using RegionGrowing::point_labels_; + using RegionGrowing::num_pts_in_segment_; + using RegionGrowing::clusters_; + using RegionGrowing::number_of_segments_; + using RegionGrowing::applySmoothRegionGrowingAlgorithm; + using RegionGrowing::assembleRegions; + + public: + + /** \brief Constructor that sets default values for member variables. */ + RegionGrowingRGB (); + + /** \brief Destructor that frees memory. */ + virtual + ~RegionGrowingRGB (); + + /** \brief Returns the color threshold value used for testing if points belong to the same region. */ + float + getPointColorThreshold () const; + + /** \brief This method specifies the threshold value for color test between the points. + * This kind of testing is made at the first stage of the algorithm(region growing). + * If the difference between points color is less than threshold value, then they are considered + * to be in the same region. + * \param[in] thresh new threshold value for color test + */ + void + setPointColorThreshold (float thresh); + + /** \brief Returns the color threshold value used for testing if regions can be merged. */ + float + getRegionColorThreshold () const; + + /** \brief This method specifies the threshold value for color test between the regions. + * This kind of testing is made at the second stage of the algorithm(region merging). + * If the difference between segments color is less than threshold value, then they are merged together. + * \param[in] thresh new threshold value for color test + */ + void + setRegionColorThreshold (float thresh); + + /** \brief Returns the distance threshold. If the distance between two points is less or equal to + * distance threshold value, then those points assumed to be neighbouring points. + */ + float + getDistanceThreshold () const; + + /** \brief Allows to set distance threshold. + * \param[in] thresh new threshold value for neighbour test + */ + void + setDistanceThreshold (float thresh); + + /** \brief Returns the number of nearest neighbours used for searching K nearest segments. + * Note that here it refers to the segments(not the points). + */ + unsigned int + getNumberOfRegionNeighbours () const; + + /** \brief This method allows to set the number of neighbours that is used for finding + * neighbouring segments. Neighbouring segments are needed for the merging process. + * \param[in] nghbr_number the number of neighbouring segments to find + */ + void + setNumberOfRegionNeighbours (unsigned int nghbr_number); + + /** \brief Returns the flag that signalize if the smoothness test is turned on/off. */ + bool + getNormalTestFlag () const; + + /** \brief + * Allows to turn on/off the smoothness test. + * \param[in] value new value for normal/smoothness test. If set to true then the test will be turned on + */ + void + setNormalTestFlag (bool value); + + /** \brief Allows to turn on/off the curvature test. + * \param[in] value new value for curvature test. If set to true then the test will be turned on + */ + virtual void + setCurvatureTestFlag (bool value); + + /** \brief + * Allows to turn on/off the residual test. + * \param[in] value new value for residual test. If set to true then the test will be turned on + */ + virtual void + setResidualTestFlag (bool value); + + /** \brief This method launches the segmentation algorithm and returns the clusters that were + * obtained during the segmentation. + * \param[out] clusters clusters that were obtained. Each cluster is an array of point indices. + */ + virtual void + extract (std::vector & clusters); + + /** \brief For a given point this function builds a segment to which it belongs and returns this segment. + * \param[in] index index of the initial point which will be the seed for growing a segment. + * \param cluster + */ + virtual void + getSegmentFromPoint (int index, pcl::PointIndices& cluster); + + protected: + + /** \brief This method simply checks if it is possible to execute the segmentation algorithm with + * the current settings. If it is possible then it returns true. + */ + virtual bool + prepareForSegmentation (); + + /** \brief This method finds KNN for each point and saves them to the array + * because the algorithm needs to find KNN a few times. + */ + virtual void + findPointNeighbours (); + + /** \brief This method simply calls the findRegionsKNN for each segment and + * saves the results for later use. + */ + void + findSegmentNeighbours (); + + /** \brief This method finds K nearest neighbours of the given segment. + * \param[in] index index of the segment for which neighbours will be found + * \param[in] nghbr_number the number of neighbours to find + * \param[out] nghbrs the array of indices of the neighbours that were found + * \param[out] dist the array of distances to the corresponding neighbours + */ + void + findRegionsKNN (int index, int nghbr_number, std::vector& nghbrs, std::vector& dist); + + /** \brief This function implements the merging algorithm described in the article + * "Color-based segmentation of point clouds" + * by Qingming Zhan, Yubin Liang, Yinghui Xiao + */ + void + applyRegionMergingAlgorithm (); + + /** \brief This method calculates the colorimetrical difference between two points. + * In this case it simply returns the euclidean distance between two colors. + * \param[in] first_color the color of the first point + * \param[in] second_color the color of the second point + */ + float + calculateColorimetricalDifference (std::vector& first_color, std::vector& second_color) const; + + /** \brief This method assembles the array containing neighbours of each homogeneous region. + * Homogeneous region is the union of some segments. This array is used when the regions + * with a few points need to be merged with the neighbouring region. + * \param[out] neighbours_out vector of lists of neighbours for every homogeneous region + * \param[in] regions_in vector of lists, each list contains indices of segments that belong + * to the corresponding homogeneous region. + */ + void + findRegionNeighbours (std::vector< std::vector< std::pair > >& neighbours_out, std::vector< std::vector >& regions_in); + + /** \brief This function simply assembles the regions from list of point labels. + * \param[in] num_pts_in_region for each final region it stores the corresponding number of points in it + * \param[in] num_regions number of regions to assemble + */ + void + assembleRegions (std::vector& num_pts_in_region, int num_regions); + + /** \brief This function is checking if the point with index 'nghbr' belongs to the segment. + * If so, then it returns true. It also checks if this point can serve as the seed. + * \param[in] initial_seed index of the initial point that was passed to the growRegion() function + * \param[in] point index of the current seed point + * \param[in] nghbr index of the point that is neighbour of the current seed + * \param[out] is_a_seed this value is set to true if the point with index 'nghbr' can serve as the seed + */ + virtual bool + validatePoint (int initial_seed, int point, int nghbr, bool& is_a_seed) const; + + protected: + + /** \brief Thershold used in color test for points. */ + float color_p2p_threshold_; + + /** \brief Thershold used in color test for regions. */ + float color_r2r_threshold_; + + /** \brief Threshold that tells which points we need to assume neighbouring. */ + float distance_threshold_; + + /** \brief Number of neighbouring segments to find. */ + unsigned int region_neighbour_number_; + + /** \brief Stores distances for the point neighbours from point_neighbours_ */ + std::vector< std::vector > point_distances_; + + /** \brief Stores the neighboures for the corresponding segments. */ + std::vector< std::vector > segment_neighbours_; + + /** \brief Stores distances for the segment neighbours from segment_neighbours_ */ + std::vector< std::vector > segment_distances_; + + /** \brief Stores new indices for segments that were obtained at the region growing stage. */ + std::vector segment_labels_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/segmentation/rgb_plane_coefficient_comparator.h b/pcl-1.7/pcl/segmentation/rgb_plane_coefficient_comparator.h new file mode 100644 index 0000000..dc5d637 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/rgb_plane_coefficient_comparator.h @@ -0,0 +1,135 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + * + */ + +#ifndef PCL_RGB_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ +#define PCL_RGB_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ + +#include +#include + +namespace pcl +{ + /** \brief RGBPlaneCoefficientComparator is a Comparator that operates on plane coefficients, + * for use in planar segmentation. Also takes into account RGB, so we can segmented different colored co-planar regions. + * In conjunction with OrganizedConnectedComponentSegmentation, this allows planes to be segmented from organized data. + * + * \author Alex Trevor + */ + template + class RGBPlaneCoefficientComparator: public PlaneCoefficientComparator + { + public: + typedef typename Comparator::PointCloud PointCloud; + typedef typename Comparator::PointCloudConstPtr PointCloudConstPtr; + + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using pcl::Comparator::input_; + using pcl::PlaneCoefficientComparator::normals_; + using pcl::PlaneCoefficientComparator::angular_threshold_; + using pcl::PlaneCoefficientComparator::distance_threshold_; + + /** \brief Empty constructor for RGBPlaneCoefficientComparator. */ + RGBPlaneCoefficientComparator () + : color_threshold_ (50.0f) + { + } + + /** \brief Constructor for RGBPlaneCoefficientComparator. + * \param[in] plane_coeff_d a reference to a vector of d coefficients of plane equations. Must be the same size as the input cloud and input normals. a, b, and c coefficients are in the input normals. + */ + RGBPlaneCoefficientComparator (boost::shared_ptr >& plane_coeff_d) + : PlaneCoefficientComparator (plane_coeff_d), color_threshold_ (50.0f) + { + } + + /** \brief Destructor for RGBPlaneCoefficientComparator. */ + virtual + ~RGBPlaneCoefficientComparator () + { + } + + /** \brief Set the tolerance in color space between neighboring points, to be considered part of the same plane. + * \param[in] color_threshold The distance in color space + */ + inline void + setColorThreshold (float color_threshold) + { + color_threshold_ = color_threshold * color_threshold; + } + + /** \brief Get the color threshold between neighboring points, to be considered part of the same plane. */ + inline float + getColorThreshold () const + { + return (color_threshold_); + } + + /** \brief Compare two neighboring points, by using normal information, euclidean distance, and color information. + * \param[in] idx1 The index of the first point. + * \param[in] idx2 The index of the second point. + */ + bool + compare (int idx1, int idx2) const + { + float dx = input_->points[idx1].x - input_->points[idx2].x; + float dy = input_->points[idx1].y - input_->points[idx2].y; + float dz = input_->points[idx1].z - input_->points[idx2].z; + float dist = sqrtf (dx*dx + dy*dy + dz*dz); + int dr = input_->points[idx1].r - input_->points[idx2].r; + int dg = input_->points[idx1].g - input_->points[idx2].g; + int db = input_->points[idx1].b - input_->points[idx2].b; + //Note: This is not the best metric for color comparisons, we should probably use HSV space. + float color_dist = static_cast (dr*dr + dg*dg + db*db); + return ( (dist < distance_threshold_) + && (normals_->points[idx1].getNormalVector3fMap ().dot (normals_->points[idx2].getNormalVector3fMap () ) > angular_threshold_ ) + && (color_dist < color_threshold_)); + } + + protected: + float color_threshold_; + }; +} + +#endif // PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ diff --git a/pcl-1.7/pcl/segmentation/sac_segmentation.h b/pcl-1.7/pcl/segmentation/sac_segmentation.h new file mode 100644 index 0000000..9db82f2 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/sac_segmentation.h @@ -0,0 +1,433 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SEGMENTATION_SAC_SEGMENTATION_H_ +#define PCL_SEGMENTATION_SAC_SEGMENTATION_H_ + +#include +#include +#include + +// Sample Consensus methods +#include +#include +// Sample Consensus models +#include +#include + +#include + +namespace pcl +{ + /** \brief @b SACSegmentation represents the Nodelet segmentation class for + * Sample Consensus methods and models, in the sense that it just creates a + * Nodelet wrapper for generic-purpose SAC-based segmentation. + * \author Radu Bogdan Rusu + * \ingroup segmentation + */ + template + class SACSegmentation : public PCLBase + { + using PCLBase::initCompute; + using PCLBase::deinitCompute; + + public: + using PCLBase::input_; + using PCLBase::indices_; + + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + typedef typename pcl::search::Search::Ptr SearchPtr; + + typedef typename SampleConsensus::Ptr SampleConsensusPtr; + typedef typename SampleConsensusModel::Ptr SampleConsensusModelPtr; + + /** \brief Empty constructor. + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SACSegmentation (bool random = false) + : model_ () + , sac_ () + , model_type_ (-1) + , method_type_ (0) + , threshold_ (0) + , optimize_coefficients_ (true) + , radius_min_ (-std::numeric_limits::max ()) + , radius_max_ (std::numeric_limits::max ()) + , samples_radius_ (0.0) + , samples_radius_search_ () + , eps_angle_ (0.0) + , axis_ (Eigen::Vector3f::Zero ()) + , max_iterations_ (50) + , probability_ (0.99) + , random_ (random) + { + } + + /** \brief Empty destructor. */ + virtual ~SACSegmentation () { /*srv_.reset ();*/ }; + + /** \brief The type of model to use (user given parameter). + * \param[in] model the model type (check \a model_types.h) + */ + inline void + setModelType (int model) { model_type_ = model; } + + /** \brief Get the type of SAC model used. */ + inline int + getModelType () const { return (model_type_); } + + /** \brief Get a pointer to the SAC method used. */ + inline SampleConsensusPtr + getMethod () const { return (sac_); } + + /** \brief Get a pointer to the SAC model used. */ + inline SampleConsensusModelPtr + getModel () const { return (model_); } + + /** \brief The type of sample consensus method to use (user given parameter). + * \param[in] method the method type (check \a method_types.h) + */ + inline void + setMethodType (int method) { method_type_ = method; } + + /** \brief Get the type of sample consensus method used. */ + inline int + getMethodType () const { return (method_type_); } + + /** \brief Distance to the model threshold (user given parameter). + * \param[in] threshold the distance threshold to use + */ + inline void + setDistanceThreshold (double threshold) { threshold_ = threshold; } + + /** \brief Get the distance to the model threshold. */ + inline double + getDistanceThreshold () const { return (threshold_); } + + /** \brief Set the maximum number of iterations before giving up. + * \param[in] max_iterations the maximum number of iterations the sample consensus method will run + */ + inline void + setMaxIterations (int max_iterations) { max_iterations_ = max_iterations; } + + /** \brief Get maximum number of iterations before giving up. */ + inline int + getMaxIterations () const { return (max_iterations_); } + + /** \brief Set the probability of choosing at least one sample free from outliers. + * \param[in] probability the model fitting probability + */ + inline void + setProbability (double probability) { probability_ = probability; } + + /** \brief Get the probability of choosing at least one sample free from outliers. */ + inline double + getProbability () const { return (probability_); } + + /** \brief Set to true if a coefficient refinement is required. + * \param[in] optimize true for enabling model coefficient refinement, false otherwise + */ + inline void + setOptimizeCoefficients (bool optimize) { optimize_coefficients_ = optimize; } + + /** \brief Get the coefficient refinement internal flag. */ + inline bool + getOptimizeCoefficients () const { return (optimize_coefficients_); } + + /** \brief Set the minimum and maximum allowable radius limits for the model (applicable to models that estimate + * a radius) + * \param[in] min_radius the minimum radius model + * \param[in] max_radius the maximum radius model + */ + inline void + setRadiusLimits (const double &min_radius, const double &max_radius) + { + radius_min_ = min_radius; + radius_max_ = max_radius; + } + + /** \brief Get the minimum and maximum allowable radius limits for the model as set by the user. + * \param[out] min_radius the resultant minimum radius model + * \param[out] max_radius the resultant maximum radius model + */ + inline void + getRadiusLimits (double &min_radius, double &max_radius) + { + min_radius = radius_min_; + max_radius = radius_max_; + } + + /** \brief Set the maximum distance allowed when drawing random samples + * \param[in] radius the maximum distance (L2 norm) + * \param search + */ + inline void + setSamplesMaxDist (const double &radius, SearchPtr search) + { + samples_radius_ = radius; + samples_radius_search_ = search; + } + + /** \brief Get maximum distance allowed when drawing random samples + * + * \param[out] radius the maximum distance (L2 norm) + */ + inline void + getSamplesMaxDist (double &radius) + { + radius = samples_radius_; + } + + /** \brief Set the axis along which we need to search for a model perpendicular to. + * \param[in] ax the axis along which we need to search for a model perpendicular to + */ + inline void + setAxis (const Eigen::Vector3f &ax) { axis_ = ax; } + + /** \brief Get the axis along which we need to search for a model perpendicular to. */ + inline Eigen::Vector3f + getAxis () const { return (axis_); } + + /** \brief Set the angle epsilon (delta) threshold. + * \param[in] ea the maximum allowed difference between the model normal and the given axis in radians. + */ + inline void + setEpsAngle (double ea) { eps_angle_ = ea; } + + /** \brief Get the epsilon (delta) model angle threshold in radians. */ + inline double + getEpsAngle () const { return (eps_angle_); } + + /** \brief Base method for segmentation of a model in a PointCloud given by + * \param[in] inliers the resultant point indices that support the model found (inliers) + * \param[out] model_coefficients the resultant model coefficients + */ + virtual void + segment (PointIndices &inliers, ModelCoefficients &model_coefficients); + + protected: + /** \brief Initialize the Sample Consensus model and set its parameters. + * \param[in] model_type the type of SAC model that is to be used + */ + virtual bool + initSACModel (const int model_type); + + /** \brief Initialize the Sample Consensus method and set its parameters. + * \param[in] method_type the type of SAC method to be used + */ + virtual void + initSAC (const int method_type); + + /** \brief The model that needs to be segmented. */ + SampleConsensusModelPtr model_; + + /** \brief The sample consensus segmentation method. */ + SampleConsensusPtr sac_; + + /** \brief The type of model to use (user given parameter). */ + int model_type_; + + /** \brief The type of sample consensus method to use (user given parameter). */ + int method_type_; + + /** \brief Distance to the model threshold (user given parameter). */ + double threshold_; + + /** \brief Set to true if a coefficient refinement is required. */ + bool optimize_coefficients_; + + /** \brief The minimum and maximum radius limits for the model. Applicable to all models that estimate a radius. */ + double radius_min_, radius_max_; + + /** \brief The maximum distance of subsequent samples from the first (radius search) */ + double samples_radius_; + + /** \brief The search object for picking subsequent samples using radius search */ + SearchPtr samples_radius_search_; + + /** \brief The maximum allowed difference between the model normal and the given axis. */ + double eps_angle_; + + /** \brief The axis along which we need to search for a model perpendicular to. */ + Eigen::Vector3f axis_; + + /** \brief Maximum number of iterations before giving up (user given parameter). */ + int max_iterations_; + + /** \brief Desired probability of choosing at least one sample free from outliers (user given parameter). */ + double probability_; + + /** \brief Set to true if we need a random seed. */ + bool random_; + + /** \brief Class get name method. */ + virtual std::string + getClassName () const { return ("SACSegmentation"); } + }; + + /** \brief @b SACSegmentationFromNormals represents the PCL nodelet segmentation class for Sample Consensus methods and + * models that require the use of surface normals for estimation. + * \ingroup segmentation + */ + template + class SACSegmentationFromNormals: public SACSegmentation + { + using SACSegmentation::model_; + using SACSegmentation::model_type_; + using SACSegmentation::radius_min_; + using SACSegmentation::radius_max_; + using SACSegmentation::eps_angle_; + using SACSegmentation::axis_; + using SACSegmentation::random_; + + public: + using PCLBase::input_; + using PCLBase::indices_; + + typedef typename SACSegmentation::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename pcl::PointCloud PointCloudN; + typedef typename PointCloudN::Ptr PointCloudNPtr; + typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + + typedef typename SampleConsensus::Ptr SampleConsensusPtr; + typedef typename SampleConsensusModel::Ptr SampleConsensusModelPtr; + typedef typename SampleConsensusModelFromNormals::Ptr SampleConsensusModelFromNormalsPtr; + + /** \brief Empty constructor. + * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) + */ + SACSegmentationFromNormals (bool random = false) + : SACSegmentation (random) + , normals_ () + , distance_weight_ (0.1) + , distance_from_origin_ (0) + , min_angle_ () + , max_angle_ () + {}; + + /** \brief Provide a pointer to the input dataset that contains the point normals of + * the XYZ dataset. + * \param[in] normals the const boost shared pointer to a PointCloud message + */ + inline void + setInputNormals (const PointCloudNConstPtr &normals) { normals_ = normals; } + + /** \brief Get a pointer to the normals of the input XYZ point cloud dataset. */ + inline PointCloudNConstPtr + getInputNormals () const { return (normals_); } + + /** \brief Set the relative weight (between 0 and 1) to give to the angular + * distance (0 to pi/2) between point normals and the plane normal. + * \param[in] distance_weight the distance/angular weight + */ + inline void + setNormalDistanceWeight (double distance_weight) { distance_weight_ = distance_weight; } + + /** \brief Get the relative weight (between 0 and 1) to give to the angular distance (0 to pi/2) between point + * normals and the plane normal. */ + inline double + getNormalDistanceWeight () const { return (distance_weight_); } + + /** \brief Set the minimum opning angle for a cone model. + * \param min_angle the opening angle which we need minumum to validate a cone model. + * \param max_angle the opening angle which we need maximum to validate a cone model. + */ + inline void + setMinMaxOpeningAngle (const double &min_angle, const double &max_angle) + { + min_angle_ = min_angle; + max_angle_ = max_angle; + } + + /** \brief Get the opening angle which we need minumum to validate a cone model. */ + inline void + getMinMaxOpeningAngle (double &min_angle, double &max_angle) + { + min_angle = min_angle_; + max_angle = max_angle_; + } + + /** \brief Set the distance we expect a plane model to be from the origin + * \param[in] d distance from the template plane modl to the origin + */ + inline void + setDistanceFromOrigin (const double d) { distance_from_origin_ = d; } + + /** \brief Get the distance of a plane model from the origin. */ + inline double + getDistanceFromOrigin () const { return (distance_from_origin_); } + + protected: + /** \brief A pointer to the input dataset that contains the point normals of the XYZ dataset. */ + PointCloudNConstPtr normals_; + + /** \brief The relative weight (between 0 and 1) to give to the angular + * distance (0 to pi/2) between point normals and the plane normal. + */ + double distance_weight_; + + /** \brief The distance from the template plane to the origin. */ + double distance_from_origin_; + + /** \brief The minimum and maximum allowed opening angle of valid cone model. */ + double min_angle_; + double max_angle_; + + /** \brief Initialize the Sample Consensus model and set its parameters. + * \param[in] model_type the type of SAC model that is to be used + */ + virtual bool + initSACModel (const int model_type); + + /** \brief Class get name method. */ + virtual std::string + getClassName () const { return ("SACSegmentationFromNormals"); } + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SEGMENTATION_SAC_SEGMENTATION_H_ diff --git a/pcl-1.7/pcl/segmentation/seeded_hue_segmentation.h b/pcl-1.7/pcl/segmentation/seeded_hue_segmentation.h new file mode 100644 index 0000000..23627c0 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/seeded_hue_segmentation.h @@ -0,0 +1,176 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $id: $ + */ + +#ifndef PCL_SEEDED_HUE_SEGMENTATION_H_ +#define PCL_SEEDED_HUE_SEGMENTATION_H_ + +#include +#include +#include + +namespace pcl +{ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Decompose a region of space into clusters based on the Euclidean distance between points + * \param[in] cloud the point cloud message + * \param[in] tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching + * \note the tree has to be created as a spatial locator on \a cloud + * \param[in] tolerance the spatial cluster tolerance as a measure in L2 Euclidean space + * \param[in] indices_in the cluster containing the seed point indices (as a vector of PointIndices) + * \param[out] indices_out + * \param[in] delta_hue + * \todo look how to make this templated! + * \ingroup segmentation + */ + void + seededHueSegmentation (const PointCloud &cloud, + const boost::shared_ptr > &tree, + float tolerance, + PointIndices &indices_in, + PointIndices &indices_out, + float delta_hue = 0.0); + + /** \brief Decompose a region of space into clusters based on the Euclidean distance between points + * \param[in] cloud the point cloud message + * \param[in] tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching + * \note the tree has to be created as a spatial locator on \a cloud + * \param[in] tolerance the spatial cluster tolerance as a measure in L2 Euclidean space + * \param[in] indices_in the cluster containing the seed point indices (as a vector of PointIndices) + * \param[out] indices_out + * \param[in] delta_hue + * \todo look how to make this templated! + * \ingroup segmentation + */ + void + seededHueSegmentation (const PointCloud &cloud, + const boost::shared_ptr > &tree, + float tolerance, + PointIndices &indices_in, + PointIndices &indices_out, + float delta_hue = 0.0); + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief SeededHueSegmentation + * \author Koen Buys + * \ingroup segmentation + */ + class SeededHueSegmentation: public PCLBase + { + typedef PCLBase BasePCLBase; + + public: + typedef pcl::PointCloud PointCloud; + typedef PointCloud::Ptr PointCloudPtr; + typedef PointCloud::ConstPtr PointCloudConstPtr; + + typedef pcl::search::Search KdTree; + typedef pcl::search::Search::Ptr KdTreePtr; + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Empty constructor. */ + SeededHueSegmentation () : tree_ (), cluster_tolerance_ (0), delta_hue_ (0.0) + {}; + + /** \brief Provide a pointer to the search object. + * \param[in] tree a pointer to the spatial search object. + */ + inline void + setSearchMethod (const KdTreePtr &tree) { tree_ = tree; } + + /** \brief Get a pointer to the search method used. */ + inline KdTreePtr + getSearchMethod () const { return (tree_); } + + /** \brief Set the spatial cluster tolerance as a measure in the L2 Euclidean space + * \param[in] tolerance the spatial cluster tolerance as a measure in the L2 Euclidean space + */ + inline void + setClusterTolerance (double tolerance) { cluster_tolerance_ = tolerance; } + + /** \brief Get the spatial cluster tolerance as a measure in the L2 Euclidean space. */ + inline double + getClusterTolerance () const { return (cluster_tolerance_); } + + /** \brief Set the tollerance on the hue + * \param[in] delta_hue the new delta hue + */ + inline void + setDeltaHue (float delta_hue) { delta_hue_ = delta_hue; } + + /** \brief Get the tolerance on the hue */ + inline float + getDeltaHue () const { return (delta_hue_); } + + /** \brief Cluster extraction in a PointCloud given by + * \param[in] indices_in + * \param[out] indices_out + */ + void + segment (PointIndices &indices_in, PointIndices &indices_out); + + protected: + // Members derived from the base class + using BasePCLBase::input_; + using BasePCLBase::indices_; + using BasePCLBase::initCompute; + using BasePCLBase::deinitCompute; + + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + + /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */ + double cluster_tolerance_; + + /** \brief The allowed difference on the hue*/ + float delta_hue_; + + /** \brief Class getName method. */ + virtual std::string getClassName () const { return ("seededHueSegmentation"); } + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SEEDED_HUE_SEGMENTATION_H_ diff --git a/pcl-1.7/pcl/segmentation/segment_differences.h b/pcl-1.7/pcl/segmentation/segment_differences.h new file mode 100644 index 0000000..316d064 --- /dev/null +++ b/pcl-1.7/pcl/segmentation/segment_differences.h @@ -0,0 +1,162 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SEGMENT_DIFFERENCES_H_ +#define PCL_SEGMENT_DIFFERENCES_H_ + +#include +#include + +namespace pcl +{ + //////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Obtain the difference between two aligned point clouds as another point cloud, given a distance threshold. + * \param src the input point cloud source + * \param tgt the input point cloud target we need to obtain the difference against + * \param threshold the distance threshold (tolerance) for point correspondences. (e.g., check if f a point p1 from + * src has a correspondence > threshold than a point p2 from tgt) + * \param tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching built over \a tgt + * \param output the resultant output point cloud difference + * \ingroup segmentation + */ + template + void getPointCloudDifference ( + const pcl::PointCloud &src, const pcl::PointCloud &tgt, + double threshold, const boost::shared_ptr > &tree, + pcl::PointCloud &output); + + //////////////////////////////////////////////////////////////////////////////////////////// + //////////////////////////////////////////////////////////////////////////////////////////// + //////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b SegmentDifferences obtains the difference between two spatially + * aligned point clouds and returns the difference between them for a maximum + * given distance threshold. + * \author Radu Bogdan Rusu + * \ingroup segmentation + */ + template + class SegmentDifferences: public PCLBase + { + typedef PCLBase BasePCLBase; + + public: + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename pcl::search::Search KdTree; + typedef typename pcl::search::Search::Ptr KdTreePtr; + + typedef PointIndices::Ptr PointIndicesPtr; + typedef PointIndices::ConstPtr PointIndicesConstPtr; + + /** \brief Empty constructor. */ + SegmentDifferences () : + tree_ (), target_ (), distance_threshold_ (0) + {}; + + /** \brief Provide a pointer to the target dataset against which we + * compare the input cloud given in setInputCloud + * + * \param cloud the target PointCloud dataset + */ + inline void + setTargetCloud (const PointCloudConstPtr &cloud) { target_ = cloud; } + + /** \brief Get a pointer to the input target point cloud dataset. */ + inline PointCloudConstPtr const + getTargetCloud () { return (target_); } + + /** \brief Provide a pointer to the search object. + * \param tree a pointer to the spatial search object. + */ + inline void + setSearchMethod (const KdTreePtr &tree) { tree_ = tree; } + + /** \brief Get a pointer to the search method used. */ + inline KdTreePtr + getSearchMethod () { return (tree_); } + + /** \brief Set the maximum distance tolerance (squared) between corresponding + * points in the two input datasets. + * + * \param sqr_threshold the squared distance tolerance as a measure in L2 Euclidean space + */ + inline void + setDistanceThreshold (double sqr_threshold) { distance_threshold_ = sqr_threshold; } + + /** \brief Get the squared distance tolerance between corresponding points as a + * measure in the L2 Euclidean space. + */ + inline double + getDistanceThreshold () { return (distance_threshold_); } + + /** \brief Segment differences between two input point clouds. + * \param output the resultant difference between the two point clouds as a PointCloud + */ + void + segment (PointCloud &output); + + protected: + // Members derived from the base class + using BasePCLBase::input_; + using BasePCLBase::indices_; + using BasePCLBase::initCompute; + using BasePCLBase::deinitCompute; + + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + + /** \brief The input target point cloud dataset. */ + PointCloudConstPtr target_; + + /** \brief The distance tolerance (squared) as a measure in the L2 + * Euclidean space between corresponding points. + */ + double distance_threshold_; + + /** \brief Class getName method. */ + virtual std::string + getClassName () const { return ("SegmentDifferences"); } + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_SEGMENT_DIFFERENCES_H_ diff --git a/pcl-1.7/pcl/segmentation/supervoxel_clustering.h b/pcl-1.7/pcl/segmentation/supervoxel_clustering.h new file mode 100644 index 0000000..09ea59d --- /dev/null +++ b/pcl-1.7/pcl/segmentation/supervoxel_clustering.h @@ -0,0 +1,512 @@ + +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author : jpapon@gmail.com + * Email : jpapon@gmail.com + * + */ + +#ifndef PCL_SEGMENTATION_SUPERVOXEL_CLUSTERING_H_ +#define PCL_SEGMENTATION_SUPERVOXEL_CLUSTERING_H_ + +#include +#include +#include +#include +#include +#include +#include +#include + + + +//DEBUG TODO REMOVE +#include + + +namespace pcl +{ + /** \brief Supervoxel container class - stores a cluster extracted using supervoxel clustering + */ + template + class Supervoxel + { + public: + Supervoxel () : + voxels_ (new pcl::PointCloud ()), + normals_ (new pcl::PointCloud ()) + { } + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Gets the centroid of the supervoxel + * \param[out] centroid_arg centroid of the supervoxel + */ + void + getCentroidPoint (PointXYZRGBA ¢roid_arg) + { + centroid_arg = centroid_; + } + + /** \brief Gets the point normal for the supervoxel + * \param[out] normal_arg Point normal of the supervoxel + * \note This isn't an average, it is a normal computed using all of the voxels in the supervoxel as support + */ + void + getCentroidPointNormal (PointNormal &normal_arg) + { + normal_arg.x = centroid_.x; + normal_arg.y = centroid_.y; + normal_arg.z = centroid_.z; + normal_arg.normal_x = normal_.normal_x; + normal_arg.normal_y = normal_.normal_y; + normal_arg.normal_z = normal_.normal_z; + normal_arg.curvature = normal_.curvature; + } + + /** \brief The normal calculated for the voxels contained in the supervoxel */ + pcl::Normal normal_; + /** \brief The centroid of the supervoxel - average voxel */ + pcl::PointXYZRGBA centroid_; + /** \brief A Pointcloud of the voxels in the supervoxel */ + typename pcl::PointCloud::Ptr voxels_; + /** \brief A Pointcloud of the normals for the points in the supervoxel */ + typename pcl::PointCloud::Ptr normals_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + /** \brief Implements a supervoxel algorithm based on voxel structure, normals, and rgb values + * \note Supervoxels are oversegmented volumetric patches (usually surfaces) + * \note Usually, color isn't needed (and can be detrimental)- spatial structure is mainly used + * - J. Papon, A. Abramov, M. Schoeler, F. Woergoetter + * Voxel Cloud Connectivity Segmentation - Supervoxels from PointClouds + * In Proceedings of the IEEE Conference on Computer Vision and Pattern Recognition (CVPR) 2013 + * \author Jeremie Papon (jpapon@gmail.com) + */ + template + class PCL_EXPORTS SupervoxelClustering : public pcl::PCLBase + { + //Forward declaration of friended helper class + class SupervoxelHelper; + friend class SupervoxelHelper; + public: + /** \brief VoxelData is a structure used for storing data within a pcl::octree::OctreePointCloudAdjacencyContainer + * \note It stores xyz, rgb, normal, distance, an index, and an owner. + */ + class VoxelData + { + public: + VoxelData (): + xyz_ (0.0f, 0.0f, 0.0f), + rgb_ (0.0f, 0.0f, 0.0f), + normal_ (0.0f, 0.0f, 0.0f, 0.0f), + curvature_ (0.0f), + owner_ (0) + {} + + /** \brief Gets the data of in the form of a point + * \param[out] point_arg Will contain the point value of the voxeldata + */ + void + getPoint (PointT &point_arg) const; + + /** \brief Gets the data of in the form of a normal + * \param[out] normal_arg Will contain the normal value of the voxeldata + */ + void + getNormal (Normal &normal_arg) const; + + Eigen::Vector3f xyz_; + Eigen::Vector3f rgb_; + Eigen::Vector4f normal_; + float curvature_; + float distance_; + int idx_; + SupervoxelHelper* owner_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + typedef pcl::octree::OctreePointCloudAdjacencyContainer LeafContainerT; + typedef std::vector LeafVectorT; + + typedef typename pcl::PointCloud PointCloudT; + typedef typename pcl::PointCloud NormalCloudT; + typedef typename pcl::octree::OctreePointCloudAdjacency OctreeAdjacencyT; + typedef typename pcl::octree::OctreePointCloudSearch OctreeSearchT; + typedef typename pcl::search::KdTree KdTreeT; + typedef boost::shared_ptr > IndicesPtr; + + using PCLBase ::initCompute; + using PCLBase ::deinitCompute; + using PCLBase ::input_; + + typedef boost::adjacency_list VoxelAdjacencyList; + typedef VoxelAdjacencyList::vertex_descriptor VoxelID; + typedef VoxelAdjacencyList::edge_descriptor EdgeID; + + + public: + + /** \brief Constructor that sets default values for member variables. + * \param[in] voxel_resolution The resolution (in meters) of voxels used + * \param[in] seed_resolution The average size (in meters) of resulting supervoxels + * \param[in] use_single_camera_transform Set to true if point density in cloud falls off with distance from origin (such as with a cloud coming from one stationary camera), set false if input cloud is from multiple captures from multiple locations. + */ + SupervoxelClustering (float voxel_resolution, float seed_resolution, bool use_single_camera_transform = true); + + /** \brief This destructor destroys the cloud, normals and search method used for + * finding neighbors. In other words it frees memory. + */ + virtual + ~SupervoxelClustering (); + + /** \brief Set the resolution of the octree voxels */ + void + setVoxelResolution (float resolution); + + /** \brief Get the resolution of the octree voxels */ + float + getVoxelResolution () const; + + /** \brief Set the resolution of the octree seed voxels */ + void + setSeedResolution (float seed_resolution); + + /** \brief Get the resolution of the octree seed voxels */ + float + getSeedResolution () const; + + /** \brief Set the importance of color for supervoxels */ + void + setColorImportance (float val); + + /** \brief Set the importance of spatial distance for supervoxels */ + void + setSpatialImportance (float val); + + /** \brief Set the importance of scalar normal product for supervoxels */ + void + setNormalImportance (float val); + + /** \brief This method launches the segmentation algorithm and returns the supervoxels that were + * obtained during the segmentation. + * \param[out] supervoxel_clusters A map of labels to pointers to supervoxel structures + */ + virtual void + extract (std::map::Ptr > &supervoxel_clusters); + + /** \brief This method sets the cloud to be supervoxelized + * \param[in] cloud The cloud to be supervoxelize + */ + virtual void + setInputCloud (const typename pcl::PointCloud::ConstPtr& cloud); + + /** \brief This method sets the normals to be used for supervoxels (should be same size as input cloud) + * \param[in] normal_cloud The input normals + */ + virtual void + setNormalCloud (typename NormalCloudT::ConstPtr normal_cloud); + + /** \brief This method refines the calculated supervoxels - may only be called after extract + * \param[in] num_itr The number of iterations of refinement to be done (2 or 3 is usually sufficient) + * \param[out] supervoxel_clusters The resulting refined supervoxels + */ + virtual void + refineSupervoxels (int num_itr, std::map::Ptr > &supervoxel_clusters); + + //////////////////////////////////////////////////////////// + /** \brief Returns an RGB colorized cloud showing superpixels + * Otherwise it returns an empty pointer. + * Points that belong to the same supervoxel have the same color. + * But this function doesn't guarantee that different segments will have different + * color(it's random). Points that are unlabeled will be black + * \note This will expand the label_colors_ vector so that it can accomodate all labels + */ + typename pcl::PointCloud::Ptr + getColoredCloud () const; + + /** \brief Returns a deep copy of the voxel centroid cloud */ + typename pcl::PointCloud::Ptr + getVoxelCentroidCloud () const; + + /** \brief Returns labeled cloud + * Points that belong to the same supervoxel have the same label. + * Labels for segments start from 1, unlabled points have label 0 + */ + typename pcl::PointCloud::Ptr + getLabeledCloud () const; + + /** \brief Returns an RGB colorized voxelized cloud showing superpixels + * Otherwise it returns an empty pointer. + * Points that belong to the same supervoxel have the same color. + * But this function doesn't guarantee that different segments will have different + * color(it's random). Points that are unlabeled will be black + * \note This will expand the label_colors_ vector so that it can accomodate all labels + */ + pcl::PointCloud::Ptr + getColoredVoxelCloud () const; + + /** \brief Returns labeled voxelized cloud + * Points that belong to the same supervoxel have the same label. + * Labels for segments start from 1, unlabled points have label 0 + */ + pcl::PointCloud::Ptr + getLabeledVoxelCloud () const; + + /** \brief Gets the adjacency list (Boost Graph library) which gives connections between supervoxels + * \param[out] adjacency_list_arg BGL graph where supervoxel labels are vertices, edges are touching relationships + */ + void + getSupervoxelAdjacencyList (VoxelAdjacencyList &adjacency_list_arg) const; + + /** \brief Get a multimap which gives supervoxel adjacency + * \param[out] label_adjacency Multi-Map which maps a supervoxel label to all adjacent supervoxel labels + */ + void + getSupervoxelAdjacency (std::multimap &label_adjacency) const; + + /** \brief Static helper function which returns a pointcloud of normals for the input supervoxels + * \param[in] supervoxel_clusters Supervoxel cluster map coming from this class + * \returns Cloud of PointNormals of the supervoxels + * + */ + static pcl::PointCloud::Ptr + makeSupervoxelNormalCloud (std::map::Ptr > &supervoxel_clusters); + + /** \brief Returns the current maximum (highest) label */ + int + getMaxLabel () const; + + private: + + /** \brief This method initializes the label_colors_ vector (assigns random colors to labels) + * \note Checks to see if it is already big enough - if so, does not reinitialize it + */ + void + initializeLabelColors (); + + /** \brief This method simply checks if it is possible to execute the segmentation algorithm with + * the current settings. If it is possible then it returns true. + */ + virtual bool + prepareForSegmentation (); + + /** \brief This selects points to use as initial supervoxel centroids + * \param[out] seed_points The selected points + */ + void + selectInitialSupervoxelSeeds (std::vector > &seed_points); + + /** \brief This method creates the internal supervoxel helpers based on the provided seed points + * \param[in] seed_points The selected points + */ + void + createSupervoxelHelpers (std::vector > &seed_points); + + /** \brief This performs the superpixel evolution */ + void + expandSupervoxels (int depth); + + /** \brief This sets the data of the voxels in the tree */ + void + computeVoxelData (); + + /** \brief Reseeds the supervoxels by finding the voxel closest to current centroid */ + void + reseedSupervoxels (); + + /** \brief Constructs the map of supervoxel clusters from the internal supervoxel helpers */ + void + makeSupervoxels (std::map::Ptr > &supervoxel_clusters); + + /** \brief Stores the resolution used in the octree */ + float resolution_; + + /** \brief Stores the resolution used to seed the superpixels */ + float seed_resolution_; + + /** \brief Distance function used for comparing voxelDatas */ + float + voxelDataDistance (const VoxelData &v1, const VoxelData &v2) const; + + /** \brief Transform function used to normalize voxel density versus distance from camera */ + void + transformFunction (PointT &p); + + /** \brief Contains a KDtree for the voxelized cloud */ + typename pcl::search::KdTree::Ptr voxel_kdtree_; + + /** \brief Octree Adjacency structure with leaves at voxel resolution */ + typename OctreeAdjacencyT::Ptr adjacency_octree_; + + /** \brief Contains the Voxelized centroid Cloud */ + typename PointCloudT::Ptr voxel_centroid_cloud_; + + /** \brief Contains the Voxelized centroid Cloud */ + typename NormalCloudT::ConstPtr input_normals_; + + /** \brief Importance of color in clustering */ + float color_importance_; + /** \brief Importance of distance from seed center in clustering */ + float spatial_importance_; + /** \brief Importance of similarity in normals for clustering */ + float normal_importance_; + + /** \brief Stores the colors used for the superpixel labels*/ + std::vector label_colors_; + + /** \brief Internal storage class for supervoxels + * \note Stores pointers to leaves of clustering internal octree, + * \note so should not be used outside of clustering class + */ + class SupervoxelHelper + { + public: + SupervoxelHelper (uint32_t label, SupervoxelClustering* parent_arg): + label_ (label), + parent_ (parent_arg) + { } + + void + addLeaf (LeafContainerT* leaf_arg); + + void + removeLeaf (LeafContainerT* leaf_arg); + + void + removeAllLeaves (); + + void + expand (); + + void + refineNormals (); + + void + updateCentroid (); + + void + getVoxels (typename pcl::PointCloud::Ptr &voxels) const; + + void + getNormals (typename pcl::PointCloud::Ptr &normals) const; + + typedef float (SupervoxelClustering::*DistFuncPtr)(const VoxelData &v1, const VoxelData &v2); + + uint32_t + getLabel () const + { return label_; } + + Eigen::Vector4f + getNormal () const + { return centroid_.normal_; } + + Eigen::Vector3f + getRGB () const + { return centroid_.rgb_; } + + Eigen::Vector3f + getXYZ () const + { return centroid_.xyz_;} + + void + getXYZ (float &x, float &y, float &z) const + { x=centroid_.xyz_[0]; y=centroid_.xyz_[1]; z=centroid_.xyz_[2]; } + + void + getRGB (uint32_t &rgba) const + { + rgba = static_cast(centroid_.rgb_[0]) << 16 | + static_cast(centroid_.rgb_[1]) << 8 | + static_cast(centroid_.rgb_[2]); + } + + void + getNormal (pcl::Normal &normal_arg) const + { + normal_arg.normal_x = centroid_.normal_[0]; + normal_arg.normal_y = centroid_.normal_[1]; + normal_arg.normal_z = centroid_.normal_[2]; + normal_arg.curvature = centroid_.curvature_; + } + + void + getNeighborLabels (std::set &neighbor_labels) const; + + VoxelData + getCentroid () const + { return centroid_; } + + + size_t + size () const { return leaves_.size (); } + private: + //Stores leaves + std::set leaves_; + uint32_t label_; + VoxelData centroid_; + SupervoxelClustering* parent_; + public: + //Type VoxelData may have fixed-size Eigen objects inside + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + //Make boost::ptr_list can access the private class SupervoxelHelper + friend void boost::checked_delete<> (const typename pcl::SupervoxelClustering::SupervoxelHelper *); + + typedef boost::ptr_list HelperListT; + HelperListT supervoxel_helpers_; + + //TODO DEBUG REMOVE + StopWatch timer_; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + + + }; + +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/sse.h b/pcl-1.7/pcl/sse.h new file mode 100644 index 0000000..dc84aa8 --- /dev/null +++ b/pcl-1.7/pcl/sse.h @@ -0,0 +1,99 @@ +/* + * Software License Agreement (Simplified BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2013-, Open Perception, Inc. + * Copyright (c) 2012, Piotr Dollar & Ron Appel.[pdollar-at-caltech.edu] + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + *list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + *this list of conditions and the following disclaimer in the documentation + *and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + * The views and conclusions contained in the software and documentation are those + * of the authors and should not be interpreted as representing official policies, + * either expressed or implied, of the FreeBSD Project. + * + * Taken from Piotr Dollar's MATLAB Image&Video ToolboxVersion 3.00. + * + */ + +#ifndef PCL_SSE_H_ +#define PCL_SSE_H_ +#if defined(__SSE2__) +#include // SSE2:, SSE3:, SSE4: + +#define RETf inline __m128 +#define RETi inline __m128i + +namespace pcl { + +// set, load and store values +RETf sse_set( const float &x ) { return _mm_set1_ps(x); } +RETf sse_set( float x, float y, float z, float w ) { return _mm_set_ps(x,y,z,w); } +RETi sse_set( const int &x ) { return _mm_set1_epi32(x); } +RETf sse_ld( const float &x ) { return _mm_load_ps(&x); } +RETf sse_ldu( const float &x ) { return _mm_loadu_ps(&x); } +RETf sse_str( float &x, const __m128 y ) { _mm_store_ps(&x,y); return y; } +RETf sse_str1( float &x, const __m128 y ) { _mm_store_ss(&x,y); return y; } +RETf sse_stru( float &x, const __m128 y ) { _mm_storeu_ps(&x,y); return y; } +RETf sse_str( float &x, const float y ) { return sse_str(x,sse_set(y)); } + +// arithmetic operators +RETi sse_add( const __m128i x, const __m128i y ) { return _mm_add_epi32(x,y); } +RETf sse_add( const __m128 x, const __m128 y ) { return _mm_add_ps(x,y); } +RETf sse_add( const __m128 x, const __m128 y, const __m128 z ) { + return sse_add(sse_add(x,y),z); } +RETf sse_add( const __m128 a, const __m128 b, const __m128 c, const __m128 &d ) { + return sse_add(sse_add(sse_add(a,b),c),d); } +RETf sse_sub( const __m128 x, const __m128 y ) { return _mm_sub_ps(x,y); } +RETf sse_mul( const __m128 x, const __m128 y ) { return _mm_mul_ps(x,y); } +RETf sse_mul( const __m128 x, const float y ) { return sse_mul(x,sse_set(y)); } +RETf sse_mul( const float x, const __m128 y ) { return sse_mul(sse_set(x),y); } +RETf sse_inc( __m128 &x, const __m128 y ) { return x = sse_add(x,y); } +RETf sse_inc( float &x, const __m128 y ) { __m128 t=sse_add(sse_ld(x),y); return sse_str(x,t); } +RETf sse_dec( __m128 &x, const __m128 y ) { return x = sse_sub(x,y); } +RETf sse_dec( float &x, const __m128 y ) { __m128 t=sse_sub(sse_ld(x),y); return sse_str(x,t); } +RETf sse_min( const __m128 x, const __m128 y ) { return _mm_min_ps(x,y); } +RETf sse_rcp( const __m128 x ) { return _mm_rcp_ps(x); } +RETf sse_rcpsqrt( const __m128 x ) { return _mm_rsqrt_ps(x); } + +// logical operators +RETf sse_and( const __m128 x, const __m128 y ) { return _mm_and_ps(x,y); } +RETi sse_and( const __m128i x, const __m128i y ) { return _mm_and_si128(x,y); } +RETf sse_andnot( const __m128 x, const __m128 y ) { return _mm_andnot_ps(x,y); } +RETf sse_or( const __m128 x, const __m128 y ) { return _mm_or_ps(x,y); } +RETf sse_xor( const __m128 x, const __m128 y ) { return _mm_xor_ps(x,y); } + +// comparison operators +RETf sse_cmpgt( const __m128 x, const __m128 y ) { return _mm_cmpgt_ps(x,y); } +RETi sse_cmpgt( const __m128i x, const __m128i y ) { return _mm_cmpgt_epi32(x,y); } + +// conversion operators +RETf sse_cvt( const __m128i x ) { return _mm_cvtepi32_ps(x); } +RETi sse_cvt( const __m128 x ) { return _mm_cvttps_epi32(x); } + +} // namespace pcl + +#undef RETf +#undef RETi +#endif /* defined(__SSE2__) */ +#endif /* PCL_SSE_H_ */ diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/allocator.h b/pcl-1.7/pcl/surface/3rdparty/poisson4/allocator.h new file mode 100644 index 0000000..1b5cb0a --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/allocator.h @@ -0,0 +1,168 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#ifndef ALLOCATOR_INCLUDED +#define ALLOCATOR_INCLUDED +#include + +namespace pcl +{ + namespace poisson + { + class AllocatorState{ + public: + int index,remains; + }; + /** This templated class assists in memory allocation and is well suited for instances + * when it is known that the sequence of memory allocations is performed in a stack-based + * manner, so that memory allocated last is released first. It also preallocates memory + * in chunks so that multiple requests for small chunks of memory do not require separate + * system calls to the memory manager. + * The allocator is templated off of the class of objects that we would like it to allocate, + * ensuring that appropriate constructors and destructors are called as necessary. + */ + template + class Allocator{ + int blockSize; + int index,remains; + std::vector memory; + public: + Allocator(void){ + blockSize=index=remains=0; + } + ~Allocator(void){ + reset(); + } + + /** This method is the allocators destructor. It frees up any of the memory that + * it has allocated. */ + void reset(void){ + for(size_t i=0;iblockSize=blockSize; + index=-1; + remains=0; + } + + /** This method returns a pointer to an array of elements objects. If there is left over pre-allocated + * memory, this method simply returns a pointer to the next free piece of memory, otherwise it pre-allocates + * more memory. Note that if the number of objects requested is larger than the value blockSize with which + * the allocator was initialized, the request for memory will fail. + */ + T* newElements( int elements=1){ + T* mem; + if(!elements){return NULL;} + if(elements>blockSize){ + fprintf(stderr,"Allocator Error, elements bigger than block-size: %d>%d\n",elements,blockSize); + return NULL; + } + if(remains + class BinaryNode + { + public: + static inline int CenterCount( int depth ) { return 1<>= 1; + depth++; + } +#if MSVC_2010_FIX + depth--; +#endif // MSVC_2010_FIX + offset = ( idx+1 ) - (1< + class BSplineData + { + bool useDotRatios; + bool reflectBoundary; + public: + struct BSplineComponents + { + Polynomial< Degree > polys[Degree+1]; + Polynomial< Degree >& operator[] ( int idx ) { return polys[idx]; } + const Polynomial< Degree >& operator[] ( int idx ) const { return polys[idx]; } + void printnl( void ) const { for( int d=0 ; d<=Degree ; d++ ) polys[d].printnl(); } + BSplineComponents scale( double s ) const { BSplineComponents b ; for( int d=0 ; d<=Degree ; d++ ) b[d] = polys[d].scale(s) ; return b; } + BSplineComponents shift( double s ) const { BSplineComponents b ; for( int d=0 ; d<=Degree ; d++ ) b[d] = polys[d].shift(s) ; return b; } + }; + const static int VV_DOT_FLAG = 1; + const static int DV_DOT_FLAG = 2; + const static int DD_DOT_FLAG = 4; + const static int VALUE_FLAG = 1; + const static int D_VALUE_FLAG = 2; + + int depth , functionCount , sampleCount; + Real *vvDotTable , *dvDotTable , *ddDotTable; + Real *valueTables , *dValueTables; + PPolynomial< Degree > baseFunction , leftBaseFunction , rightBaseFunction; + PPolynomial< Degree-1 > dBaseFunction , dLeftBaseFunction , dRightBaseFunction; + BSplineComponents baseBSpline, leftBSpline , rightBSpline; + PPolynomial* baseFunctions; + BSplineComponents* baseBSplines; + + BSplineData(void); + ~BSplineData(void); + + virtual void setDotTables( int flags ); + virtual void clearDotTables( int flags ); + + virtual void setValueTables( int flags,double smooth=0); + virtual void setValueTables( int flags,double valueSmooth,double normalSmooth); + virtual void clearValueTables(void); + + void setSampleSpan( int idx , int& start , int& end , double smooth=0 ) const; + + /******************************************************** + * Sets the translates and scales of the basis function + * up to the prescribed depth + * the maximum depth + * specifies if dot-products of derivatives + * should be pre-divided by function integrals + * spcifies if function space should be + * forced to be reflectively symmetric across the boundary + ********************************************************/ + void set( int maxDepth , bool useDotRatios=true , bool reflectBoundary=false ); + + inline int Index( int i1 , int i2 ) const; + static inline int SymmetricIndex( int i1 , int i2 ); + static inline int SymmetricIndex( int i1 , int i2 , int& index ); + }; + + template< int Degree > + struct BSplineElementCoefficients + { + int coeffs[Degree+1]; + BSplineElementCoefficients( void ) { memset( coeffs , 0 , sizeof( int ) * ( Degree+1 ) ); } + int& operator[]( int idx ){ return coeffs[idx]; } + const int& operator[]( int idx ) const { return coeffs[idx]; } + }; + template< int Degree > + struct BSplineElements : public std::vector< BSplineElementCoefficients< Degree > > + { + static const int _off = (Degree+1)/2; + void _addLeft ( int offset , int boundary ); + void _addRight( int offset , int boundary ); + public: + enum + { + NONE = 0, + DIRICHLET = -1, + NEUMANN = 1 + }; + // Coefficients are ordered as "/" "-" "\" + int denominator; + + BSplineElements( void ) { denominator = 1; } + BSplineElements( int res , int offset , int boundary=NONE ); + + void upSample( BSplineElements& high ) const; + void differentiate( BSplineElements< Degree-1 >& d ) const; + + void print( FILE* fp=stdout ) const + { + for( int i=0 ; isize() ; i++ ) + { + printf( "%d]" , i ); + for( int j=0 ; j<=Degree ; j++ ) printf( " %d" , (*this)[i][j] ); + printf( " (%d)\n" , denominator ); + } + } + }; + template< int Degree1 , int Degree2 > void SetBSplineElementIntegrals( double integrals[Degree1+1][Degree2+1] ); + + + } +} + + +#include "bspline_data.hpp" + +#endif // BSPLINE_DATA_INCLUDED diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/bspline_data.hpp b/pcl-1.7/pcl/surface/3rdparty/poisson4/bspline_data.hpp new file mode 100644 index 0000000..6e688c5 --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/bspline_data.hpp @@ -0,0 +1,528 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + + +namespace pcl +{ + namespace poisson + { + + ///////////////// + // BSplineData // + ///////////////// + // Support[i]: + // Odd: i +/- 0.5 * ( 1 + Degree ) + // i - 0.5 * ( 1 + Degree ) < 0 + // <=> i < 0.5 * ( 1 + Degree ) + // i + 0.5 * ( 1 + Degree ) > 0 + // <=> i > - 0.5 * ( 1 + Degree ) + // i + 0.5 * ( 1 + Degree ) > r + // <=> i > r - 0.5 * ( 1 + Degree ) + // i - 0.5 * ( 1 + Degree ) < r + // <=> i < r + 0.5 * ( 1 + Degree ) + // Even: i + 0.5 +/- 0.5 * ( 1 + Degree ) + // i - 0.5 * Degree < 0 + // <=> i < 0.5 * Degree + // i + 1 + 0.5 * Degree > 0 + // <=> i > -1 - 0.5 * Degree + // i + 1 + 0.5 * Degree > r + // <=> i > r - 1 - 0.5 * Degree + // i - 0.5 * Degree < r + // <=> i < r + 0.5 * Degree + template< int Degree > inline bool LeftOverlap( unsigned int depth , int offset ) + { + offset <<= 1; + if( Degree & 1 ) return (offset < 1+Degree) && (offset > -1-Degree ); + else return (offset < Degree) && (offset > -2-Degree ); + } + template< int Degree > inline bool RightOverlap( unsigned int depth , int offset ) + { + offset <<= 1; + int r = 1<<(depth+1); + if( Degree & 1 ) return (offset > 2-1-Degree) && (offset < 2+1+Degree ); + else return (offset > 2-2-Degree) && (offset < 2+ Degree ); + } + template< int Degree > inline int ReflectLeft( unsigned int depth , int offset ) + { + if( Degree&1 ) return -offset; + else return -1-offset; + } + template< int Degree > inline int ReflectRight( unsigned int depth , int offset ) + { + int r = 1<<(depth+1); + if( Degree&1 ) return r -offset; + else return r-1-offset; + } + + template< int Degree , class Real > + BSplineData::BSplineData( void ) + { + vvDotTable = dvDotTable = ddDotTable = NULL; + valueTables = dValueTables = NULL; + functionCount = sampleCount = 0; + } + + template< int Degree , class Real > + BSplineData< Degree , Real >::~BSplineData(void) + { + if( functionCount ) + { + if( vvDotTable ) delete[] vvDotTable; + if( dvDotTable ) delete[] dvDotTable; + if( ddDotTable ) delete[] ddDotTable; + + if( valueTables ) delete[] valueTables; + if( dValueTables ) delete[] dValueTables; + } + vvDotTable = dvDotTable = ddDotTable = NULL; + valueTables = dValueTables=NULL; + functionCount = 0; + } + + template + void BSplineData::set( int maxDepth , bool useDotRatios , bool reflectBoundary ) + { + this->useDotRatios = useDotRatios; + this->reflectBoundary = reflectBoundary; + + depth = maxDepth; + // [Warning] This assumes that the functions spacing is dual + functionCount = BinaryNode< double >::CumulativeCenterCount( depth ); + sampleCount = BinaryNode< double >::CenterCount( depth ) + BinaryNode< double >::CornerCount( depth ); + baseFunctions = new PPolynomial[functionCount]; + baseBSplines = new BSplineComponents[functionCount]; + + baseFunction = PPolynomial< Degree >::BSpline(); + for( int i=0 ; i<=Degree ; i++ ) baseBSpline[i] = Polynomial< Degree >::BSplineComponent( i ).shift( double(-(Degree+1)/2) + i - 0.5 ); + dBaseFunction = baseFunction.derivative(); + StartingPolynomial< Degree > sPolys[Degree+3]; + + for( int i=0 ; i=1 && i<=Degree+1 ) sPolys[i].p += baseBSpline[i-1]; + for( int j=0 ; j=1 && i<=Degree+1 ) sPolys[i].p += baseBSpline[i-1].shift( 1 ); + for( int j=0 ; j::CenterAndWidth( i , c , w ); + baseFunctions[i] = baseFunction.scale(w).shift(c); + baseBSplines[i] = baseBSpline.scale(w).shift(c); + if( reflectBoundary ) + { + int d , off , r; + BinaryNode< double >::DepthAndOffset( i , d , off ); + r = 1< + void BSplineData::setDotTables( int flags ) + { + clearDotTables( flags ); + int size = ( functionCount*functionCount + functionCount )>>1; + int fullSize = functionCount*functionCount; + if( flags & VV_DOT_FLAG ) + { + vvDotTable = new Real[size]; + memset( vvDotTable , 0 , sizeof(Real)*size ); + } + if( flags & DV_DOT_FLAG ) + { + dvDotTable = new Real[fullSize]; + memset( dvDotTable , 0 , sizeof(Real)*fullSize ); + } + if( flags & DD_DOT_FLAG ) + { + ddDotTable = new Real[size]; + memset( ddDotTable , 0 , sizeof(Real)*size ); + } + double vvIntegrals[Degree+1][Degree+1]; + double vdIntegrals[Degree+1][Degree ]; + double dvIntegrals[Degree ][Degree+1]; + double ddIntegrals[Degree ][Degree ]; + int vvSums[Degree+1][Degree+1]; + int vdSums[Degree+1][Degree ]; + int dvSums[Degree ][Degree+1]; + int ddSums[Degree ][Degree ]; + SetBSplineElementIntegrals< Degree , Degree >( vvIntegrals ); + SetBSplineElementIntegrals< Degree , Degree-1 >( vdIntegrals ); + SetBSplineElementIntegrals< Degree-1 , Degree >( dvIntegrals ); + SetBSplineElementIntegrals< Degree-1 , Degree-1 >( ddIntegrals ); + + for( int d1=0 ; d1<=depth ; d1++ ) + for( int off1=0 ; off1<(1<::CenterIndex( d1 , off1 ); + BSplineElements< Degree > b1( 1<::NEUMANN : BSplineElements< Degree>::NONE ); + BSplineElements< Degree-1 > db1; + b1.differentiate( db1 ); + + int start1 , end1; + + start1 = -1; + for( int i=0 ; i=end1 || start1>=end2 ) continue; + start2 = std::max< int >( start1 , start2 ); + end2 = std::min< int >( end1 , end2 ); + if( d1==d2 && off2::CenterIndex( d2 , off2 ); + BSplineElements< Degree > b2( 1<::NEUMANN : BSplineElements< Degree>::NONE ); + BSplineElements< Degree-1 > db2; + b2.differentiate( db2 ); + + int idx = SymmetricIndex( ii , jj ); + int idx1 = Index( ii , jj ) , idx2 = Index( jj , ii ); + + memset( vvSums , 0 , sizeof( int ) * ( Degree+1 ) * ( Degree+1 ) ); + memset( vdSums , 0 , sizeof( int ) * ( Degree+1 ) * ( Degree ) ); + memset( dvSums , 0 , sizeof( int ) * ( Degree ) * ( Degree+1 ) ); + memset( ddSums , 0 , sizeof( int ) * ( Degree ) * ( Degree ) ); + for( int i=start2 ; i b; + b = b1; + b.upSample( b1 ); + b1.differentiate( db1 ); + start1 = -1; + for( int i=0 ; i + void BSplineData::clearDotTables( int flags ) + { + if( (flags & VV_DOT_FLAG) && vvDotTable ) delete[] vvDotTable , vvDotTable = NULL; + if( (flags & DV_DOT_FLAG) && dvDotTable ) delete[] dvDotTable , dvDotTable = NULL; + if( (flags & DD_DOT_FLAG) && ddDotTable ) delete[] ddDotTable , ddDotTable = NULL; + } + template< int Degree , class Real > + void BSplineData< Degree , Real >::setSampleSpan( int idx , int& start , int& end , double smooth ) const + { + int d , off , res; + BinaryNode< double >::DepthAndOffset( idx , d , off ); + res = 1<_start && (start-1)/(sampleCount-1)<=_start + // => start > _start * (sampleCount-1 ) && start <= _start*(sampleCount-1) + 1 + // => _start * (sampleCount-1) + 1 >= start > _start * (sampleCount-1) + start = int( floor( _start * (sampleCount-1) + 1 ) ); + if( start<0 ) start = 0; + // (end)/(sampleCount-1)<_end && (end+1)/(sampleCount-1)>=_end + // => end < _end * (sampleCount-1 ) && end >= _end*(sampleCount-1) - 1 + // => _end * (sampleCount-1) > end >= _end * (sampleCount-1) - 1 + end = int( ceil( _end * (sampleCount-1) - 1 ) ); + if( end>=sampleCount ) end = sampleCount-1; + } + template + void BSplineData::setValueTables( int flags , double smooth ) + { + clearValueTables(); + if( flags & VALUE_FLAG ) valueTables = new Real[functionCount*sampleCount]; + if( flags & D_VALUE_FLAG ) dValueTables = new Real[functionCount*sampleCount]; + PPolynomial function; + PPolynomial dFunction; + for( int i=0 ; i0) + { + function = baseFunctions[i].MovingAverage(smooth); + dFunction = baseFunctions[i].derivative().MovingAverage(smooth); + } + else + { + function = baseFunctions[i]; + dFunction = baseFunctions[i].derivative(); + } + for( int j=0 ; j + void BSplineData::setValueTables(int flags,double valueSmooth,double normalSmooth){ + clearValueTables(); + if(flags & VALUE_FLAG){ valueTables=new Real[functionCount*sampleCount];} + if(flags & D_VALUE_FLAG){dValueTables=new Real[functionCount*sampleCount];} + PPolynomial function; + PPolynomial dFunction; + for(int i=0;i0) { function=baseFunctions[i].MovingAverage(valueSmooth);} + else { function=baseFunctions[i];} + if(normalSmooth>0) {dFunction=baseFunctions[i].derivative().MovingAverage(normalSmooth);} + else {dFunction=baseFunctions[i].derivative();} + + for(int j=0;j + void BSplineData::clearValueTables(void){ + if( valueTables){delete[] valueTables;} + if(dValueTables){delete[] dValueTables;} + valueTables=dValueTables=NULL; + } + + template + inline int BSplineData::Index( int i1 , int i2 ) const { return i1*functionCount+i2; } + template + inline int BSplineData::SymmetricIndex( int i1 , int i2 ) + { + if( i1>i2 ) return ((i1*i1+i1)>>1)+i2; + else return ((i2*i2+i2)>>1)+i1; + } + template + inline int BSplineData::SymmetricIndex( int i1 , int i2 , int& index ) + { + if( i1>1)+i1; + return 1; + } + else + { + index = ((i1*i1+i1)>>1)+i2; + return 0; + } + } + + + //////////////////////// + // BSplineElementData // + //////////////////////// + template< int Degree > + BSplineElements< Degree >::BSplineElements( int res , int offset , int boundary ) + { + denominator = 1; + this->resize( res , BSplineElementCoefficients() ); + + for( int i=0 ; i<=Degree ; i++ ) + { + int idx = -_off + offset + i; + if( idx>=0 && idx + void BSplineElements< Degree >::_addLeft( int offset , int boundary ) + { + int res = int( this->size() ); + bool set = false; + for( int i=0 ; i<=Degree ; i++ ) + { + int idx = -_off + offset + i; + if( idx>=0 && idx + void BSplineElements< Degree >::_addRight( int offset , int boundary ) + { + int res = int( this->size() ); + bool set = false; + for( int i=0 ; i<=Degree ; i++ ) + { + int idx = -_off + offset + i; + if( idx>=0 && idx + void BSplineElements< Degree >::upSample( BSplineElements< Degree >& high ) const + { + fprintf( stderr , "[ERROR] B-spline up-sampling not supported for degree %d\n" , Degree ); + exit( 0 ); + } + template<> + void BSplineElements< 1 >::upSample( BSplineElements< 1 >& high ) const + { + high.resize( size()*2 ); + high.assign( high.size() , BSplineElementCoefficients<1>() ); + for( int i=0 ; i + void BSplineElements< 2 >::upSample( BSplineElements< 2 >& high ) const + { + // /----\ + // / \ + // / \ = 1 /--\ +3 /--\ +3 /--\ +1 /--\ + // / \ / \ / \ / \ / \ + // |----------| |----------| |----------| |----------| |----------| + + high.resize( size()*2 ); + high.assign( high.size() , BSplineElementCoefficients<2>() ); + for( int i=0 ; i + void BSplineElements< Degree >::differentiate( BSplineElements< Degree-1 >& d ) const + { + d.resize( this->size() ); + d.assign( d.size() , BSplineElementCoefficients< Degree-1 >() ); + for( int i=0 ; isize()) ; i++ ) for( int j=0 ; j<=Degree ; j++ ) + { + if( j-1>=0 ) d[i][j-1] -= (*this)[i][j]; + if( j + void SetBSplineElementIntegrals( double integrals[Degree1+1][Degree2+1] ) + { + for( int i=0 ; i<=Degree1 ; i++ ) + { + Polynomial< Degree1 > p1 = Polynomial< Degree1 >::BSplineComponent( i ); + for( int j=0 ; j<=Degree2 ; j++ ) + { + Polynomial< Degree2 > p2 = Polynomial< Degree2 >::BSplineComponent( j ); + integrals[i][j] = ( p1 * p2 ).integral( 0 , 1 ); + } + } + } + + + } +} diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/factor.h b/pcl-1.7/pcl/surface/3rdparty/poisson4/factor.h new file mode 100644 index 0000000..747c8f0 --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/factor.h @@ -0,0 +1,60 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#ifndef FACTOR_INCLUDED +#define FACTOR_INCLUDED + +#include + +#define PI 3.1415926535897932384 +#define SQRT_3 1.7320508075688772935 + +namespace pcl +{ + namespace poisson + { + PCL_EXPORTS double ArcTan2(double y,double x); + PCL_EXPORTS double Angle(const double in[2]); + PCL_EXPORTS void Sqrt(const double in[2],double out[2]); + PCL_EXPORTS void Add(const double in1[2],const double in2[2],double out[2]); + PCL_EXPORTS void Subtract(const double in1[2],const double in2[2],double out[2]); + PCL_EXPORTS void Multiply(const double in1[2],const double in2[2],double out[2]); + PCL_EXPORTS void Divide(const double in1[2],const double in2[2],double out[2]); + + PCL_EXPORTS int Factor(double a1,double a0,double roots[1][2],double EPS); + PCL_EXPORTS int Factor(double a2,double a1,double a0,double roots[2][2],double EPS); + PCL_EXPORTS int Factor(double a3,double a2,double a1,double a0,double roots[3][2],double EPS); + PCL_EXPORTS int Factor(double a4,double a3,double a2,double a1,double a0,double roots[4][2],double EPS); + + PCL_EXPORTS int Solve(const double* eqns,const double* values,double* solutions, int dim); + + } +} + + +#endif // FACTOR_INCLUDED diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/function_data.h b/pcl-1.7/pcl/surface/3rdparty/poisson4/function_data.h new file mode 100644 index 0000000..fc1634e --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/function_data.h @@ -0,0 +1,123 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#ifndef FUNCTION_DATA_INCLUDED +#define FUNCTION_DATA_INCLUDED + +#define BOUNDARY_CONDITIONS 1 + +#if defined __GNUC__ +# pragma GCC system_header +#endif + + +#include "ppolynomial.h" + +namespace pcl +{ + namespace poisson + { + + template + class FunctionData{ + bool useDotRatios; + int normalize; +#if BOUNDARY_CONDITIONS + bool reflectBoundary; +#endif // BOUNDARY_CONDITIONS + public: + const static int DOT_FLAG = 1; + const static int D_DOT_FLAG = 2; + const static int D2_DOT_FLAG = 4; + const static int VALUE_FLAG = 1; + const static int D_VALUE_FLAG = 2; + + int depth , res , res2; + Real *dotTable , *dDotTable , *d2DotTable; + Real *valueTables , *dValueTables; +#if BOUNDARY_CONDITIONS + PPolynomial baseFunction , leftBaseFunction , rightBaseFunction; + PPolynomial dBaseFunction , dLeftBaseFunction , dRightBaseFunction; +#else // !BOUNDARY_CONDITIONS + PPolynomial baseFunction; + PPolynomial dBaseFunction; +#endif // BOUNDARY_CONDITIONS + PPolynomial* baseFunctions; + + FunctionData(void); + ~FunctionData(void); + + virtual void setDotTables(const int& flags); + virtual void clearDotTables(const int& flags); + + virtual void setValueTables(const int& flags,const double& smooth=0); + virtual void setValueTables(const int& flags,const double& valueSmooth,const double& normalSmooth); + virtual void clearValueTables(void); + + /******************************************************** + * Sets the translates and scales of the basis function + * up to the prescribed depth + * the maximum depth + * the basis function + * how the functions should be scaled + * 0] Value at zero equals 1 + * 1] Integral equals 1 + * 2] L2-norm equals 1 + * specifies if dot-products of derivatives + * should be pre-divided by function integrals + * spcifies if function space should be + * forced to be reflectively symmetric across the boundary + ********************************************************/ +#if BOUNDARY_CONDITIONS + void set( const int& maxDepth , const PPolynomial& F , const int& normalize , bool useDotRatios=true , bool reflectBoundary=false ); +#else // !BOUNDARY_CONDITIONS + void set(const int& maxDepth,const PPolynomial& F,const int& normalize , bool useDotRatios=true ); +#endif // BOUNDARY_CONDITIONS + +#if BOUNDARY_CONDITIONS + Real dotProduct( const double& center1 , const double& width1 , const double& center2 , const double& width2 , int boundary1 , int boundary2 ) const; + Real dDotProduct( const double& center1 , const double& width1 , const double& center2 , const double& width2 , int boundary1 , int boundary2 ) const; + Real d2DotProduct( const double& center1 , const double& width1 , const double& center2 , const double& width2 , int boundary1 , int boundary2 ) const; +#else // !BOUNDARY_CONDITIONS + Real dotProduct( const double& center1 , const double& width1 , const double& center2 , const double& width2 ) const; + Real dDotProduct( const double& center1 , const double& width1 , const double& center2 , const double& width2 ) const; + Real d2DotProduct( const double& center1 , const double& width1 , const double& center2 , const double& width2 ) const; +#endif // BOUNDARY_CONDITIONS + + static inline int SymmetricIndex( const int& i1 , const int& i2 ); + static inline int SymmetricIndex( const int& i1 , const int& i2 , int& index ); + }; + + + } +} + + +#include "function_data.hpp" + +#endif // FUNCTION_DATA_INCLUDED diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/function_data.hpp b/pcl-1.7/pcl/surface/3rdparty/poisson4/function_data.hpp new file mode 100644 index 0000000..8fa4cdc --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/function_data.hpp @@ -0,0 +1,423 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +////////////////// +// FunctionData // +////////////////// + +namespace pcl +{ + namespace poisson + { + + template + FunctionData::FunctionData(void) + { + dotTable=dDotTable=d2DotTable=NULL; + valueTables=dValueTables=NULL; + res=0; + } + + template + FunctionData::~FunctionData(void) + { + if(res) + { + if( dotTable) delete[] dotTable; + if( dDotTable) delete[] dDotTable; + if(d2DotTable) delete[] d2DotTable; + if( valueTables) delete[] valueTables; + if(dValueTables) delete[] dValueTables; + } + dotTable=dDotTable=d2DotTable=NULL; + valueTables=dValueTables=NULL; + res=0; + } + + template +#if BOUNDARY_CONDITIONS + void FunctionData::set( const int& maxDepth , const PPolynomial& F , const int& normalize , bool useDotRatios , bool reflectBoundary ) +#else // !BOUNDARY_CONDITIONS + void FunctionData::set(const int& maxDepth,const PPolynomial& F,const int& normalize , bool useDotRatios ) +#endif // BOUNDARY_CONDITIONS + { + this->normalize = normalize; + this->useDotRatios = useDotRatios; +#if BOUNDARY_CONDITIONS + this->reflectBoundary = reflectBoundary; +#endif // BOUNDARY_CONDITIONS + + depth = maxDepth; + res = BinaryNode::CumulativeCenterCount( depth ); + res2 = (1<<(depth+1))+1; + baseFunctions = new PPolynomial[res]; + // Scale the function so that it has: + // 0] Value 1 at 0 + // 1] Integral equal to 1 + // 2] Square integral equal to 1 + switch( normalize ) + { + case 2: + baseFunction=F/sqrt((F*F).integral(F.polys[0].start,F.polys[F.polyCount-1].start)); + break; + case 1: + baseFunction=F/F.integral(F.polys[0].start,F.polys[F.polyCount-1].start); + break; + default: + baseFunction=F/F(0); + } + dBaseFunction = baseFunction.derivative(); +#if BOUNDARY_CONDITIONS + leftBaseFunction = baseFunction + baseFunction.shift( -1 ); + rightBaseFunction = baseFunction + baseFunction.shift( 1 ); + dLeftBaseFunction = leftBaseFunction.derivative(); + dRightBaseFunction = rightBaseFunction.derivative(); +#endif // BOUNDARY_CONDITIONS + double c1,w1; + for( int i=0 ; i::CenterAndWidth( i , c1 , w1 ); +#if BOUNDARY_CONDITIONS + if( reflectBoundary ) + { + int d , off; + BinaryNode< double >::DepthAndOffset( i , d , off ); + if ( off==0 ) baseFunctions[i] = leftBaseFunction.scale( w1 ).shift( c1 ); + else if( off==((1< + void FunctionData::setDotTables( const int& flags ) + { + clearDotTables( flags ); + int size; + size = ( res*res + res )>>1; + if( flags & DOT_FLAG ) + { + dotTable = new Real[size]; + memset( dotTable , 0 , sizeof(Real)*size ); + } + if( flags & D_DOT_FLAG ) + { + dDotTable = new Real[size]; + memset( dDotTable , 0 , sizeof(Real)*size ); + } + if( flags & D2_DOT_FLAG ) + { + d2DotTable = new Real[size]; + memset( d2DotTable , 0 , sizeof(Real)*size ); + } + double t1 , t2; + t1 = baseFunction.polys[0].start; + t2 = baseFunction.polys[baseFunction.polyCount-1].start; + for( int i=0 ; i::CenterAndWidth( i , c1 , w1 ); +#if BOUNDARY_CONDITIONS + int d1 , d2 , off1 , off2; + BinaryNode< double >::DepthAndOffset( i , d1 , off1 ); + int boundary1 = 0; + if ( reflectBoundary && off1==0 ) boundary1 = -1; + else if( reflectBoundary && off1==( (1<::CenterAndWidth( j , c2 , w2 ); +#if BOUNDARY_CONDITIONS + BinaryNode< double >::DepthAndOffset( j , d2 , off2 ); + int boundary2 = 0; + if ( reflectBoundary && off2==0 ) boundary2 = -1; + else if( reflectBoundary && off2==( (1<1 ) start = 1; + if( end <0 ) end = 0; + if( end >1 ) end = 1; + } +#endif // BOUNDARY_CONDITIONS + + if( start< start1 ) start = start1; + if( end > end1 ) end = end1; + if( start>= end ) continue; + +#if BOUNDARY_CONDITIONS + Real dot = dotProduct( c1 , w1 , c2 , w2 , boundary1 , boundary2 ); +#else // !BOUNDARY_CONDITIONS + Real dot = dotProduct( c1 , w1 , c2 , w2 ); +#endif // BOUNDARY_CONDITIONS + if( fabs(dot)<1e-15 ) continue; + if( flags & DOT_FLAG ) dotTable[idx]=dot; + if( useDotRatios ) + { +#if BOUNDARY_CONDITIONS + if( flags & D_DOT_FLAG ) dDotTable[idx] = -dDotProduct( c1 , w1 , c2 , w2 , boundary1 , boundary2 ) / dot; + if( flags & D2_DOT_FLAG ) d2DotTable[idx] = d2DotProduct( c1 , w1 , c2 , w2 , boundary1 , boundary2 ) / dot; +#else // !BOUNDARY_CONDITIONS + if( flags & D_DOT_FLAG ) dDotTable[idx] = -dDotProduct(c1,w1,c2,w2)/dot; + if( flags & D2_DOT_FLAG ) d2DotTable[idx] = d2DotProduct(c1,w1,c2,w2)/dot; +#endif // BOUNDARY_CONDITIONS + } + else + { +#if BOUNDARY_CONDITIONS + if( flags & D_DOT_FLAG ) dDotTable[idx] = dDotProduct( c1 , w1 , c2 , w2 , boundary1 , boundary2 ); + if( flags & D2_DOT_FLAG ) d2DotTable[idx] = d2DotProduct( c1 , w1 , c2 , w2 , boundary1 , boundary2 ); +#else // !BOUNDARY_CONDTIONS + if( flags & D_DOT_FLAG ) dDotTable[idx] = dDotProduct(c1,w1,c2,w2); + if( flags & D2_DOT_FLAG ) d2DotTable[idx] = d2DotProduct(c1,w1,c2,w2); +#endif // BOUNDARY_CONDITIONS + } + } + } + } + template + void FunctionData::clearDotTables( const int& flags ) + { + if((flags & DOT_FLAG) && dotTable) + { + delete[] dotTable; + dotTable=NULL; + } + if((flags & D_DOT_FLAG) && dDotTable) + { + delete[] dDotTable; + dDotTable=NULL; + } + if((flags & D2_DOT_FLAG) && d2DotTable) + { + delete[] d2DotTable; + d2DotTable=NULL; + } + } + template + void FunctionData::setValueTables( const int& flags , const double& smooth ) + { + clearValueTables(); + if( flags & VALUE_FLAG ) valueTables = new Real[res*res2]; + if( flags & D_VALUE_FLAG ) dValueTables = new Real[res*res2]; + PPolynomial function; + PPolynomial dFunction; + for( int i=0 ; i0) + { + function=baseFunctions[i].MovingAverage(smooth); + dFunction=baseFunctions[i].derivative().MovingAverage(smooth); + } + else + { + function=baseFunctions[i]; + dFunction=baseFunctions[i].derivative(); + } + for( int j=0 ; j + void FunctionData::setValueTables(const int& flags,const double& valueSmooth,const double& normalSmooth){ + clearValueTables(); + if(flags & VALUE_FLAG){ valueTables=new Real[res*res2];} + if(flags & D_VALUE_FLAG){dValueTables=new Real[res*res2];} + PPolynomial function; + PPolynomial dFunction; + for(int i=0;i0) { function=baseFunctions[i].MovingAverage(valueSmooth);} + else { function=baseFunctions[i];} + if(normalSmooth>0) {dFunction=baseFunctions[i].derivative().MovingAverage(normalSmooth);} + else {dFunction=baseFunctions[i].derivative();} + + for(int j=0;j + void FunctionData::clearValueTables(void){ + if( valueTables){delete[] valueTables;} + if(dValueTables){delete[] dValueTables;} + valueTables=dValueTables=NULL; + } + +#if BOUNDARY_CONDITIONS + template + Real FunctionData::dotProduct( const double& center1 , const double& width1 , const double& center2 , const double& width2 , int boundary1 , int boundary2 ) const + { + const PPolynomial< Degree > *b1 , *b2; + if ( boundary1==-1 ) b1 = & leftBaseFunction; + else if( boundary1== 0 ) b1 = & baseFunction; + else if( boundary1== 1 ) b1 = &rightBaseFunction; + if ( boundary2==-1 ) b2 = & leftBaseFunction; + else if( boundary2== 0 ) b2 = & baseFunction; + else if( boundary2== 1 ) b2 = &rightBaseFunction; + double r=fabs( baseFunction.polys[0].start ); + switch( normalize ) + { + case 2: + return Real(((*b1)*b2->scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)*width1/sqrt(width1*width2)); + case 1: + return Real(((*b1)*b2->scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)*width1/(width1*width2)); + default: + return Real(((*b1)*b2->scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)*width1); + } + } + template + Real FunctionData::dDotProduct( const double& center1 , const double& width1 , const double& center2 , const double& width2 , int boundary1 , int boundary2 ) const + { + const PPolynomial< Degree-1 > *b1; + const PPolynomial< Degree > *b2; + if ( boundary1==-1 ) b1 = & dLeftBaseFunction; + else if( boundary1== 0 ) b1 = & dBaseFunction; + else if( boundary1== 1 ) b1 = &dRightBaseFunction; + if ( boundary2==-1 ) b2 = & leftBaseFunction; + else if( boundary2== 0 ) b2 = & baseFunction; + else if( boundary2== 1 ) b2 = & rightBaseFunction; + double r=fabs(baseFunction.polys[0].start); + switch(normalize){ + case 2: + return Real(((*b1)*b2->scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)/sqrt(width1*width2)); + case 1: + return Real(((*b1)*b2->scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)/(width1*width2)); + default: + return Real(((*b1)*b2->scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)); + } + } + template + Real FunctionData::d2DotProduct( const double& center1 , const double& width1 , const double& center2 , const double& width2 , int boundary1 , int boundary2 ) const + { + const PPolynomial< Degree-1 > *b1 , *b2; + if ( boundary1==-1 ) b1 = & dLeftBaseFunction; + else if( boundary1== 0 ) b1 = & dBaseFunction; + else if( boundary1== 1 ) b1 = &dRightBaseFunction; + if ( boundary2==-1 ) b2 = & dLeftBaseFunction; + else if( boundary2== 0 ) b2 = & dBaseFunction; + else if( boundary2== 1 ) b2 = &dRightBaseFunction; + double r=fabs(baseFunction.polys[0].start); + switch( normalize ) + { + case 2: + return Real(((*b1)*b2->scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)/width2/sqrt(width1*width2)); + case 1: + return Real(((*b1)*b2->scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)/width2/(width1*width2)); + default: + return Real(((*b1)*b2->scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)/width2); + } + } +#else // !BOUNDARY_CONDITIONS + template + Real FunctionData::dotProduct(const double& center1,const double& width1,const double& center2,const double& width2) const{ + double r=fabs(baseFunction.polys[0].start); + switch( normalize ) + { + case 2: + return Real((baseFunction*baseFunction.scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)*width1/sqrt(width1*width2)); + case 1: + return Real((baseFunction*baseFunction.scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)*width1/(width1*width2)); + default: + return Real((baseFunction*baseFunction.scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)*width1); + } + } + template + Real FunctionData::dDotProduct(const double& center1,const double& width1,const double& center2,const double& width2) const{ + double r=fabs(baseFunction.polys[0].start); + switch(normalize){ + case 2: + return Real((dBaseFunction*baseFunction.scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)/sqrt(width1*width2)); + case 1: + return Real((dBaseFunction*baseFunction.scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)/(width1*width2)); + default: + return Real((dBaseFunction*baseFunction.scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)); + } + } + template + Real FunctionData::d2DotProduct(const double& center1,const double& width1,const double& center2,const double& width2) const{ + double r=fabs(baseFunction.polys[0].start); + switch(normalize){ + case 2: + return Real((dBaseFunction*dBaseFunction.scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)/width2/sqrt(width1*width2)); + case 1: + return Real((dBaseFunction*dBaseFunction.scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)/width2/(width1*width2)); + default: + return Real((dBaseFunction*dBaseFunction.scale(width2/width1).shift((center2-center1)/width1)).integral(-2*r,2*r)/width2); + } + } +#endif // BOUNDARY_CONDITIONS + template + inline int FunctionData::SymmetricIndex( const int& i1 , const int& i2 ) + { + if( i1>i2 ) return ((i1*i1+i1)>>1)+i2; + else return ((i2*i2+i2)>>1)+i1; + } + template + inline int FunctionData::SymmetricIndex( const int& i1 , const int& i2 , int& index ) + { + if( i1>1)+i1; + return 1; + } + else{ + index = ((i1*i1+i1)>>1)+i2; + return 0; + } + } + } +} diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/geometry.h b/pcl-1.7/pcl/surface/3rdparty/poisson4/geometry.h new file mode 100644 index 0000000..a2978e3 --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/geometry.h @@ -0,0 +1,333 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#ifndef GEOMETRY_INCLUDED +#define GEOMETRY_INCLUDED + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include +#include +#include "hash.h" + +namespace pcl +{ + namespace poisson + { + + template + Real Random(void); + + template< class Real > + struct Point3D + { + Real coords[3]; + Point3D( void ) { coords[0] = coords[1] = coords[2] = Real(0); } + inline Real& operator[] ( int i ) { return coords[i]; } + inline const Real& operator[] ( int i ) const { return coords[i]; } + inline Point3D& operator += ( Point3D p ){ coords[0] += p.coords[0] , coords[1] += p.coords[1] , coords[2] += p.coords[2] ; return *this; } + inline Point3D& operator -= ( Point3D p ){ coords[0] -= p.coords[0] , coords[1] -= p.coords[1] , coords[2] -= p.coords[2] ; return *this; } + inline Point3D& operator *= ( Real r ){ coords[0] *= r , coords[1] *= r , coords[2] *= r ; return *this; } + inline Point3D& operator /= ( Real r ){ coords[0] /= r , coords[1] /= r , coords[2] /= r ; return *this; } + inline Point3D operator + ( Point3D p ) const { Point3D q ; q.coords[0] = coords[0] + p.coords[0] , q.coords[1] = coords[1] + p.coords[1] , q.coords[2] = coords[2] + p.coords[2] ; return q; } + inline Point3D operator - ( Point3D p ) const { Point3D q ; q.coords[0] = coords[0] - p.coords[0] , q.coords[1] = coords[1] - p.coords[1] , q.coords[2] = coords[2] - p.coords[2] ; return q; } + inline Point3D operator * ( Real r ) const { Point3D q ; q.coords[0] = coords[0] * r , q.coords[1] = coords[1] * r , q.coords[2] = coords[2] * r ; return q; } + inline Point3D operator / ( Real r ) const { return (*this) * ( Real(1.)/r ); } + }; + + template + Point3D RandomBallPoint(void); + + template + Point3D RandomSpherePoint(void); + + template + double Length(const Point3D& p); + + template + double SquareLength(const Point3D& p); + + template + double Distance(const Point3D& p1,const Point3D& p2); + + template + double SquareDistance(const Point3D& p1,const Point3D& p2); + + template + void CrossProduct(const Point3D& p1,const Point3D& p2,Point3D& p); + + class Edge + { + public: + double p[2][2]; + double Length(void) const + { + double d[2]; + d[0]=p[0][0]-p[1][0]; + d[1]=p[0][1]-p[1][1]; + + return sqrt(d[0]*d[0]+d[1]*d[1]); + } + }; + class Triangle + { + public: + double p[3][3]; + double Area(void) const + { + double v1[3] , v2[3] , v[3]; + for( int d=0 ; d<3 ; d++ ) + { + v1[d] = p[1][d] - p[0][d]; + v2[d] = p[2][d] - p[0][d]; + } + v[0] = v1[1]*v2[2] - v1[2]*v2[1]; + v[1] = -v1[0]*v2[2] + v1[2]*v2[0]; + v[2] = v1[0]*v2[1] - v1[1]*v2[0]; + return sqrt( v[0]*v[0] + v[1]*v[1] + v[2]*v[2] ) / 2; + } + double AspectRatio(void) const + { + double d=0; + int i,j; + for(i=0;i<3;i++){ + for(i=0;i<3;i++) + for(j=0;j<3;j++){d+=(p[(i+1)%3][j]-p[i][j])*(p[(i+1)%3][j]-p[i][j]);} + } + return Area()/d; + } + + }; + class PCL_EXPORTS CoredPointIndex + { + public: + int index; + char inCore; + + int operator == (const CoredPointIndex& cpi) const {return (index==cpi.index) && (inCore==cpi.inCore);}; + int operator != (const CoredPointIndex& cpi) const {return (index!=cpi.index) || (inCore!=cpi.inCore);}; + }; + class EdgeIndex{ + public: + int idx[2]; + }; + class CoredEdgeIndex{ + public: + CoredPointIndex idx[2]; + }; + class TriangleIndex{ + public: + int idx[3]; + }; + + class TriangulationEdge + { + public: + TriangulationEdge(void); + int pIndex[2]; + int tIndex[2]; + }; + + class TriangulationTriangle + { + public: + TriangulationTriangle(void); + int eIndex[3]; + }; + + template + class Triangulation + { + public: + + std::vector > points; + std::vector edges; + std::vector triangles; + + int factor( int tIndex,int& p1,int& p2,int& p3); + double area(void); + double area( int tIndex ); + double area( int p1 , int p2 , int p3 ); + int flipMinimize( int eIndex); + int addTriangle( int p1 , int p2 , int p3 ); + + protected: + hash_map edgeMap; + static long long EdgeIndex( int p1 , int p2 ); + double area(const Triangle& t); + }; + + + template + void EdgeCollapse(const Real& edgeRatio,std::vector& triangles,std::vector< Point3D >& positions,std::vector >* normals); + template + void TriangleCollapse(const Real& edgeRatio,std::vector& triangles,std::vector >& positions,std::vector >* normals); + + struct CoredVertexIndex + { + int idx; + bool inCore; + }; + class PCL_EXPORTS CoredMeshData + { + public: + std::vector > inCorePoints; + virtual void resetIterator( void ) = 0; + + virtual int addOutOfCorePoint( const Point3D& p ) = 0; + virtual int addPolygon( const std::vector< CoredVertexIndex >& vertices ) = 0; + + virtual int nextOutOfCorePoint( Point3D& p )=0; + virtual int nextPolygon( std::vector< CoredVertexIndex >& vertices ) = 0; + + virtual int outOfCorePointCount(void)=0; + virtual int polygonCount( void ) = 0; + }; + // Stores the iso-span of each vertex, rather than it's position + class PCL_EXPORTS CoredMeshData2 + { + public: + struct Vertex + { + Point3D< float > start , end; + float value; + Vertex( void ) { ; } + Vertex( Point3D< float > s , Point3D< float > e , float v ) { start = s , end = e , value = v; } + Vertex( Point3D< float > s , Point3D< float > e , Point3D< float > p ) + { + start = s , end = e; + // < p , e-s > = < s + v*(e-s) , e-s > + // < p , e-s > - < s , e-s > = v || e-s || ^2 + // v = < p-s , e-s > / || e-s ||^2 + Point3D< float > p1 = p-s , p2 = e-s; + value = ( p1[0] * p2[0] + p1[1] * p2[1] + p1[2] * p2[2] ) / ( p2[0] * p2[0] + p2[1] * p2[1] + p2[2] * p2[2] ); + } + }; + std::vector< Vertex > inCorePoints; + virtual void resetIterator( void ) = 0; + + virtual int addOutOfCorePoint( const Vertex& v ) = 0; + virtual int addPolygon( const std::vector< CoredVertexIndex >& vertices ) = 0; + + virtual int nextOutOfCorePoint( Vertex& v ) = 0; + virtual int nextPolygon( std::vector< CoredVertexIndex >& vertices ) = 0; + + virtual int outOfCorePointCount( void )=0; + virtual int polygonCount( void ) = 0; + }; + + class PCL_EXPORTS CoredVectorMeshData : public CoredMeshData + { + std::vector > oocPoints; + std::vector< std::vector< int > > polygons; + int polygonIndex; + int oocPointIndex; + public: + CoredVectorMeshData(void); + + void resetIterator(void); + + int addOutOfCorePoint( const Point3D& p ); + int addPolygon( const std::vector< CoredVertexIndex >& vertices ); + + int nextOutOfCorePoint( Point3D& p ); + int nextPolygon( std::vector< CoredVertexIndex >& vertices ); + + int outOfCorePointCount(void); + int polygonCount( void ); + }; + class PCL_EXPORTS CoredVectorMeshData2 : public CoredMeshData2 + { + std::vector< CoredMeshData2::Vertex > oocPoints; + std::vector< std::vector< int > > polygons; + int polygonIndex; + int oocPointIndex; + public: + CoredVectorMeshData2( void ); + + void resetIterator(void); + + int addOutOfCorePoint( const CoredMeshData2::Vertex& v ); + int addPolygon( const std::vector< CoredVertexIndex >& vertices ); + + int nextOutOfCorePoint( CoredMeshData2::Vertex& v ); + int nextPolygon( std::vector< CoredVertexIndex >& vertices ); + + int outOfCorePointCount( void ); + int polygonCount( void ); + }; + class CoredFileMeshData : public CoredMeshData + { + FILE *oocPointFile , *polygonFile; + int oocPoints , polygons; + public: + CoredFileMeshData(void); + ~CoredFileMeshData(void); + + void resetIterator(void); + + int addOutOfCorePoint(const Point3D& p); + int addPolygon( const std::vector< CoredVertexIndex >& vertices ); + + int nextOutOfCorePoint(Point3D& p); + int nextPolygon( std::vector< CoredVertexIndex >& vertices ); + + int outOfCorePointCount(void); + int polygonCount( void ); + }; + class CoredFileMeshData2 : public CoredMeshData2 + { + FILE *oocPointFile , *polygonFile; + int oocPoints , polygons; + public: + CoredFileMeshData2( void ); + ~CoredFileMeshData2( void ); + + void resetIterator( void ); + + int addOutOfCorePoint( const CoredMeshData2::Vertex& v ); + int addPolygon( const std::vector< CoredVertexIndex >& vertices ); + + int nextOutOfCorePoint( CoredMeshData2::Vertex& v ); + int nextPolygon( std::vector< CoredVertexIndex >& vertices ); + + int outOfCorePointCount( void ); + int polygonCount( void ); + }; + } +} + +#include "geometry.hpp" + + + + +#endif // GEOMETRY_INCLUDED diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/geometry.hpp b/pcl-1.7/pcl/surface/3rdparty/poisson4/geometry.hpp new file mode 100644 index 0000000..dcc9c9c --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/geometry.hpp @@ -0,0 +1,433 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#include + +namespace pcl +{ + namespace poisson + { + + + template + Real Random(void){return Real(rand())/RAND_MAX;} + + template + Point3D RandomBallPoint(void){ + Point3D p; + while(1){ + p.coords[0]=Real(1.0-2.0*Random()); + p.coords[1]=Real(1.0-2.0*Random()); + p.coords[2]=Real(1.0-2.0*Random()); + double l=SquareLength(p); + if(l<=1){return p;} + } + } + template + Point3D RandomSpherePoint(void){ + Point3D p=RandomBallPoint(); + Real l=Real(Length(p)); + p.coords[0]/=l; + p.coords[1]/=l; + p.coords[2]/=l; + return p; + } + + template + double SquareLength(const Point3D& p){return p.coords[0]*p.coords[0]+p.coords[1]*p.coords[1]+p.coords[2]*p.coords[2];} + + template + double Length(const Point3D& p){return sqrt(SquareLength(p));} + + template + double SquareDistance(const Point3D& p1,const Point3D& p2){ + return (p1.coords[0]-p2.coords[0])*(p1.coords[0]-p2.coords[0])+(p1.coords[1]-p2.coords[1])*(p1.coords[1]-p2.coords[1])+(p1.coords[2]-p2.coords[2])*(p1.coords[2]-p2.coords[2]); + } + + template + double Distance(const Point3D& p1,const Point3D& p2){return sqrt(SquareDistance(p1,p2));} + + template + void CrossProduct(const Point3D& p1,const Point3D& p2,Point3D& p){ + p.coords[0]= p1.coords[1]*p2.coords[2]-p1.coords[2]*p2.coords[1]; + p.coords[1]=-p1.coords[0]*p2.coords[2]+p1.coords[2]*p2.coords[0]; + p.coords[2]= p1.coords[0]*p2.coords[1]-p1.coords[1]*p2.coords[0]; + } + template + void EdgeCollapse(const Real& edgeRatio,std::vector& triangles,std::vector< Point3D >& positions,std::vector< Point3D >* normals){ + int i,j,*remapTable,*pointCount,idx[3]; + Point3D p[3],q[2],c; + double d[3],a; + double Ratio=12.0/sqrt(3.0); // (Sum of Squares Length / Area) for and equilateral triangle + + remapTable=new int[positions.size()]; + pointCount=new int[positions.size()]; + for(i=0;i=0;i--){ + for(j=0;j<3;j++){ + idx[j]=triangles[i].idx[j]; + while(remapTable[idx[j]] a*Ratio){ + // Find the smallest edge + j=0; + if(d[1]=0;i--){ + for(j=0;j<3;j++){ + idx[j]=triangles[i].idx[j]; + while(remapTable[idx[j]] + void TriangleCollapse(const Real& edgeRatio,std::vector& triangles,std::vector< Point3D >& positions,std::vector< Point3D >* normals){ + int i,j,*remapTable,*pointCount,idx[3]; + Point3D p[3],q[2],c; + double d[3],a; + double Ratio=12.0/sqrt(3.0); // (Sum of Squares Length / Area) for and equilateral triangle + + remapTable=new int[positions.size()]; + pointCount=new int[positions.size()]; + for(i=0;i=0;i--){ + for(j=0;j<3;j++){ + idx[j]=triangles[i].idx[j]; + while(remapTable[idx[j]] a*Ratio){ + // Find the smallest edge + j=0; + if(d[1]=0;i--){ + for(j=0;j<3;j++){ + idx[j]=triangles[i].idx[j]; + while(remapTable[idx[j]] + long long Triangulation::EdgeIndex( int p1 , int p2 ) + { + if(p1>p2) {return ((long long)(p1)<<32) | ((long long)(p2));} + else {return ((long long)(p2)<<32) | ((long long)(p1));} + } + + template + int Triangulation::factor(int tIndex,int& p1,int& p2,int & p3){ + if(triangles[tIndex].eIndex[0]<0 || triangles[tIndex].eIndex[1]<0 || triangles[tIndex].eIndex[2]<0){return 0;} + if(edges[triangles[tIndex].eIndex[0]].tIndex[0]==tIndex){p1=edges[triangles[tIndex].eIndex[0]].pIndex[0];} + else {p1=edges[triangles[tIndex].eIndex[0]].pIndex[1];} + if(edges[triangles[tIndex].eIndex[1]].tIndex[0]==tIndex){p2=edges[triangles[tIndex].eIndex[1]].pIndex[0];} + else {p2=edges[triangles[tIndex].eIndex[1]].pIndex[1];} + if(edges[triangles[tIndex].eIndex[2]].tIndex[0]==tIndex){p3=edges[triangles[tIndex].eIndex[2]].pIndex[0];} + else {p3=edges[triangles[tIndex].eIndex[2]].pIndex[1];} + return 1; + } + template + double Triangulation::area(int p1,int p2,int p3){ + Point3D q1,q2,q; + for(int i=0;i<3;i++){ + q1.coords[i]=points[p2].coords[i]-points[p1].coords[i]; + q2.coords[i]=points[p3].coords[i]-points[p1].coords[i]; + } + CrossProduct(q1,q2,q); + return Length(q); + } + template + double Triangulation::area(int tIndex){ + int p1,p2,p3; + factor(tIndex,p1,p2,p3); + return area(p1,p2,p3); + } + template + double Triangulation::area(void){ + double a=0; + for(int i=0;i + int Triangulation::addTriangle(int p1,int p2,int p3){ + hash_map::iterator iter; + int tIdx,eIdx,p[3]; + p[0]=p1; + p[1]=p2; + p[2]=p3; + triangles.push_back(TriangulationTriangle()); + tIdx=int(triangles.size())-1; + + for(int i=0;i<3;i++) + { + long long e = EdgeIndex(p[i],p[(i+1)%3]); + iter=edgeMap.find(e); + if(iter==edgeMap.end()) + { + TriangulationEdge edge; + edge.pIndex[0]=p[i]; + edge.pIndex[1]=p[(i+1)%3]; + edges.push_back(edge); + eIdx=int(edges.size())-1; + edgeMap[e]=eIdx; + edges[eIdx].tIndex[0]=tIdx; + } + else{ + eIdx=edgeMap[e]; + if(edges[eIdx].pIndex[0]==p[i]){ + if(edges[eIdx].tIndex[0]<0){edges[eIdx].tIndex[0]=tIdx;} + else{PCL_DEBUG("Edge Triangle in use 1\n");return 0;} + } + else{ + if(edges[eIdx].tIndex[1]<0){edges[eIdx].tIndex[1]=tIdx;} + else{PCL_DEBUG("Edge Triangle in use 2\n");return 0;} + } + + } + triangles[tIdx].eIndex[i]=eIdx; + } + return tIdx; + } + template + int Triangulation::flipMinimize(int eIndex){ + double oldArea,newArea; + int oldP[3],oldQ[3],newP[3],newQ[3]; + TriangulationEdge newEdge; + + if(edges[eIndex].tIndex[0]<0 || edges[eIndex].tIndex[1]<0){return 0;} + + if(!factor(edges[eIndex].tIndex[0],oldP[0],oldP[1],oldP[2])){return 0;} + if(!factor(edges[eIndex].tIndex[1],oldQ[0],oldQ[1],oldQ[2])){return 0;} + + oldArea=area(oldP[0],oldP[1],oldP[2])+area(oldQ[0],oldQ[1],oldQ[2]); + int idxP,idxQ; + for(idxP=0;idxP<3;idxP++){ + int i; + for(i=0;i<3;i++){if(oldP[idxP]==oldQ[i]){break;}} + if(i==3){break;} + } + for(idxQ=0;idxQ<3;idxQ++){ + int i; + for(i=0;i<3;i++){if(oldP[i]==oldQ[idxQ]){break;}} + if(i==3){break;} + } + if(idxP==3 || idxQ==3){return 0;} + newP[0]=oldP[idxP]; + newP[1]=oldP[(idxP+1)%3]; + newP[2]=oldQ[idxQ]; + newQ[0]=oldQ[idxQ]; + newQ[1]=oldP[(idxP+2)%3]; + newQ[2]=oldP[idxP]; + + newArea=area(newP[0],newP[1],newP[2])+area(newQ[0],newQ[1],newQ[2]); + if(oldArea<=newArea){return 0;} + + // Remove the entry in the hash_table for the old edge + edgeMap.erase(EdgeIndex(edges[eIndex].pIndex[0],edges[eIndex].pIndex[1])); + // Set the new edge so that the zero-side is newQ + edges[eIndex].pIndex[0]=newP[0]; + edges[eIndex].pIndex[1]=newQ[0]; + // Insert the entry into the hash_table for the new edge + edgeMap[EdgeIndex(newP[0],newQ[0])]=eIndex; + // Update the triangle information + for(int i=0;i<3;i++){ + int idx; + idx=edgeMap[EdgeIndex(newQ[i],newQ[(i+1)%3])]; + triangles[edges[eIndex].tIndex[0]].eIndex[i]=idx; + if(idx!=eIndex){ + if(edges[idx].tIndex[0]==edges[eIndex].tIndex[1]){edges[idx].tIndex[0]=edges[eIndex].tIndex[0];} + if(edges[idx].tIndex[1]==edges[eIndex].tIndex[1]){edges[idx].tIndex[1]=edges[eIndex].tIndex[0];} + } + + idx=edgeMap[EdgeIndex(newP[i],newP[(i+1)%3])]; + triangles[edges[eIndex].tIndex[1]].eIndex[i]=idx; + if(idx!=eIndex){ + if(edges[idx].tIndex[0]==edges[eIndex].tIndex[0]){edges[idx].tIndex[0]=edges[eIndex].tIndex[1];} + if(edges[idx].tIndex[1]==edges[eIndex].tIndex[0]){edges[idx].tIndex[1]=edges[eIndex].tIndex[1];} + } + } + return 1; + } + + } +} diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/hash.h b/pcl-1.7/pcl/surface/3rdparty/poisson4/hash.h new file mode 100644 index 0000000..07e3006 --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/hash.h @@ -0,0 +1,31 @@ +#ifndef HASH_INCLUDED +#define HASH_INCLUDED +#if defined _WIN32 && !defined __MINGW32__ +#include +using namespace stdext; +#else // !_WIN32 || __MINGW32__ +#define _GLIBCXX_PERMIT_BACKWARD_HASH +#include +using namespace __gnu_cxx; + + +namespace __gnu_cxx +{ + template<> struct hash { + size_t operator()(long long __x) const { return __x; } + }; + template<> struct hash { + size_t operator()(const long long __x) const { return __x; } + }; + + + template<> struct hash { + size_t operator()(unsigned long long __x) const { return __x; } + }; + template<> struct hash { + size_t operator()(const unsigned long long __x) const { return __x; } + }; +} +#endif // _WIN32 && !__MINGW32__ +#endif // HASH_INCLUDED + diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/marching_cubes_poisson.h b/pcl-1.7/pcl/surface/3rdparty/poisson4/marching_cubes_poisson.h new file mode 100644 index 0000000..26fedac --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/marching_cubes_poisson.h @@ -0,0 +1,144 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#ifndef MARCHING_CUBES_INCLUDED +#define MARCHING_CUBES_INCLUDED +#include +#include +#include "geometry.h" + + +namespace pcl +{ + namespace poisson + { + + class PCL_EXPORTS Square + { + public: + enum { CORNERS=4,EDGES=4,NEIGHBORS=4 }; + static int CornerIndex (int x,int y); + static int AntipodalCornerIndex(int idx); + static void FactorCornerIndex (int idx,int& x,int& y); + static int EdgeIndex (int orientation,int i); + static void FactorEdgeIndex (int idx,int& orientation,int& i); + + static int ReflectCornerIndex (int idx,int edgeIndex); + static int ReflectEdgeIndex (int idx,int edgeIndex); + + static void EdgeCorners(int idx,int& c1,int &c2); + }; + + class PCL_EXPORTS Cube + { + public: + enum { CORNERS=8,EDGES=12,NEIGHBORS=6 }; + + static int CornerIndex (int x,int y,int z); + static void FactorCornerIndex (int idx,int& x,int& y,int& z); + static int EdgeIndex (int orientation,int i,int j); + static void FactorEdgeIndex (int idx,int& orientation,int& i,int &j); + static int FaceIndex (int dir,int offSet); + static int FaceIndex (int x,int y,int z); + static void FactorFaceIndex (int idx,int& x,int &y,int& z); + static void FactorFaceIndex (int idx,int& dir,int& offSet); + + static int AntipodalCornerIndex (int idx); + static int FaceReflectCornerIndex (int idx,int faceIndex); + static int FaceReflectEdgeIndex (int idx,int faceIndex); + static int FaceReflectFaceIndex (int idx,int faceIndex); + static int EdgeReflectCornerIndex (int idx,int edgeIndex); + static int EdgeReflectEdgeIndex (int edgeIndex); + + static int FaceAdjacentToEdges (int eIndex1,int eIndex2); + static void FacesAdjacentToEdge (int eIndex,int& f1Index,int& f2Index); + + static void EdgeCorners(int idx,int& c1,int &c2); + static void FaceCorners(int idx,int& c1,int &c2,int& c3,int& c4); + }; + + class PCL_EXPORTS MarchingSquares + { + static double Interpolate(double v1,double v2); + static void SetVertex(int e,const double values[Square::CORNERS],double iso); + public: + enum { MAX_EDGES=2 }; + static const int* edgeMask(); + static int edges(int i, int j); + static double& vertexList(int i, int j); + + static int GetIndex(const double values[Square::CORNERS],double iso); + static int IsAmbiguous(const double v[Square::CORNERS],double isoValue); + static int AddEdges(const double v[Square::CORNERS],double isoValue,Edge* edges); + static int AddEdgeIndices(const double v[Square::CORNERS],double isoValue,int* edges); + }; + + class PCL_EXPORTS MarchingCubes + { + static void SetVertex(int e,const double values[Cube::CORNERS],double iso); + static int GetFaceIndex(const double values[Cube::CORNERS],double iso,int faceIndex); + + static void SetVertex(int e,const float values[Cube::CORNERS],float iso); + static int GetFaceIndex(const float values[Cube::CORNERS],float iso,int faceIndex); + + static int GetFaceIndex(int mcIndex,int faceIndex); + public: + static double Interpolate(double v1,double v2); + static float Interpolate(float v1,float v2); + enum { MAX_TRIANGLES=5 }; + static const int* edgeMask(); + static int triangles(int i, int j); + static const int* cornerMap(); + static double& vertexList(int i, int j); + + static int AddTriangleIndices(int mcIndex,int* triangles); + + static int GetIndex(const double values[Cube::CORNERS],double iso); + static int IsAmbiguous(const double v[Cube::CORNERS],double isoValue,int faceIndex); + static int HasRoots(const double v[Cube::CORNERS],double isoValue); + static int HasRoots(const double v[Cube::CORNERS],double isoValue,int faceIndex); + static int AddTriangles(const double v[Cube::CORNERS],double isoValue,Triangle* triangles); + static int AddTriangleIndices(const double v[Cube::CORNERS],double isoValue,int* triangles); + + static int GetIndex(const float values[Cube::CORNERS],float iso); + static int IsAmbiguous(const float v[Cube::CORNERS],float isoValue,int faceIndex); + static int HasRoots(const float v[Cube::CORNERS],float isoValue); + static int HasRoots(const float v[Cube::CORNERS],float isoValue,int faceIndex); + static int AddTriangles(const float v[Cube::CORNERS],float isoValue,Triangle* triangles); + static int AddTriangleIndices(const float v[Cube::CORNERS],float isoValue,int* triangles); + + static int IsAmbiguous(int mcIndex,int faceIndex); + static int HasRoots(int mcIndex); + static int HasFaceRoots(int mcIndex,int faceIndex); + static int HasEdgeRoots(int mcIndex,int edgeIndex); + }; + } +} + + +#endif //MARCHING_CUBES_INCLUDED diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/mat.h b/pcl-1.7/pcl/surface/3rdparty/poisson4/mat.h new file mode 100644 index 0000000..102482c --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/mat.h @@ -0,0 +1,59 @@ +/* +Copyright (c) 2007, Michael Kazhdan +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ +#ifndef MAT_INCLUDED +#define MAT_INCLUDED +#include "geometry.h" + + +namespace pcl +{ + namespace poisson + { + + template + class MinimalAreaTriangulation + { + Real* bestTriangulation; + int* midPoint; + Real GetArea(const size_t& i,const size_t& j,const std::vector >& vertices); + void GetTriangulation(const size_t& i,const size_t& j,const std::vector >& vertices,std::vector& triangles); + public: + MinimalAreaTriangulation(void); + ~MinimalAreaTriangulation(void); + Real GetArea(const std::vector >& vertices); + void GetTriangulation(const std::vector >& vertices,std::vector& triangles); + }; + + } +} + +#include "mat.hpp" + + + +#endif // MAT_INCLUDED diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/mat.hpp b/pcl-1.7/pcl/surface/3rdparty/poisson4/mat.hpp new file mode 100644 index 0000000..400d387 --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/mat.hpp @@ -0,0 +1,223 @@ +/* +Copyright (c) 2007, Michael Kazhdan +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ +////////////////////////////// +// MinimalAreaTriangulation // +////////////////////////////// + +namespace pcl +{ + namespace poisson + { + + template + MinimalAreaTriangulation::MinimalAreaTriangulation(void) + { + bestTriangulation=NULL; + midPoint=NULL; + } + template + MinimalAreaTriangulation::~MinimalAreaTriangulation(void) + { + if(bestTriangulation) + delete[] bestTriangulation; + bestTriangulation=NULL; + if(midPoint) + delete[] midPoint; + midPoint=NULL; + } + template + void MinimalAreaTriangulation::GetTriangulation(const std::vector >& vertices,std::vector& triangles) + { + if(vertices.size()==3) + { + triangles.resize(1); + triangles[0].idx[0]=0; + triangles[0].idx[1]=1; + triangles[0].idx[2]=2; + return; + } + else if(vertices.size()==4) + { + TriangleIndex tIndex[2][2]; + Real area[2]; + + area[0]=area[1]=0; + triangles.resize(2); + + tIndex[0][0].idx[0]=0; + tIndex[0][0].idx[1]=1; + tIndex[0][0].idx[2]=2; + tIndex[0][1].idx[0]=2; + tIndex[0][1].idx[1]=3; + tIndex[0][1].idx[2]=0; + + tIndex[1][0].idx[0]=0; + tIndex[1][0].idx[1]=1; + tIndex[1][0].idx[2]=3; + tIndex[1][1].idx[0]=3; + tIndex[1][1].idx[1]=1; + tIndex[1][1].idx[2]=2; + + Point3D n,p1,p2; + for(int i=0;i<2;i++) + for(int j=0;j<2;j++) + { + p1=vertices[tIndex[i][j].idx[1]]-vertices[tIndex[i][j].idx[0]]; + p2=vertices[tIndex[i][j].idx[2]]-vertices[tIndex[i][j].idx[0]]; + CrossProduct(p1,p2,n); + area[i] += Real( Length(n) ); + } + if(area[0]>area[1]) + { + triangles[0]=tIndex[1][0]; + triangles[1]=tIndex[1][1]; + } + else + { + triangles[0]=tIndex[0][0]; + triangles[1]=tIndex[0][1]; + } + return; + } + if(bestTriangulation) + delete[] bestTriangulation; + if(midPoint) + delete[] midPoint; + bestTriangulation=NULL; + midPoint=NULL; + size_t eCount=vertices.size(); + bestTriangulation=new Real[eCount*eCount]; + midPoint=new int[eCount*eCount]; + for(size_t i=0;i + Real MinimalAreaTriangulation::GetArea(const std::vector >& vertices) + { + if(bestTriangulation) + delete[] bestTriangulation; + if(midPoint) + delete[] midPoint; + bestTriangulation=NULL; + midPoint=NULL; + int eCount=vertices.size(); + bestTriangulation=new double[eCount*eCount]; + midPoint=new int[eCount*eCount]; + for(int i=0;i + void MinimalAreaTriangulation::GetTriangulation(const size_t& i,const size_t& j,const std::vector >& vertices,std::vector& triangles) + { + TriangleIndex tIndex; + size_t eCount=vertices.size(); + size_t ii=i; + if(i=ii) + return; + ii=midPoint[i*eCount+j]; + if(ii>=0) + { + tIndex.idx[0] = int( i ); + tIndex.idx[1] = int( j ); + tIndex.idx[2] = int( ii ); + triangles.push_back(tIndex); + GetTriangulation(i,ii,vertices,triangles); + GetTriangulation(ii,j,vertices,triangles); + } + } + + template + Real MinimalAreaTriangulation::GetArea(const size_t& i,const size_t& j,const std::vector >& vertices) + { + Real a=FLT_MAX,temp; + size_t eCount=vertices.size(); + size_t idx=i*eCount+j; + size_t ii=i; + if(i=ii) + { + bestTriangulation[idx]=0; + return 0; + } + if(midPoint[idx]!=-1) + return bestTriangulation[idx]; + int mid=-1; + for(size_t r=j+1;r p,p1,p2; + p1=vertices[i]-vertices[rr]; + p2=vertices[j]-vertices[rr]; + CrossProduct(p1,p2,p); + temp = Real( Length(p) ); + if(bestTriangulation[idx1]>=0) + { + temp+=bestTriangulation[idx1]; + if(temp>a) + continue; + if(bestTriangulation[idx2]>0) + temp+=bestTriangulation[idx2]; + else + temp+=GetArea(rr,j,vertices); + } + else + { + if(bestTriangulation[idx2]>=0) + temp+=bestTriangulation[idx2]; + else + temp+=GetArea(rr,j,vertices); + if(temp>a) + continue; + temp+=GetArea(i,rr,vertices); + } + + if(temp +// b_1[i] = < \nabla B_i(p) , V(p) > +// 2] Formulate this as a Poisson equation: +// \sum_i x_i \Delta B_i(p) = \nabla \cdot V(p) +// which is solved by the system A_2x = b_2 where: +// A_2[i,j] = - < \Delta B_i(p) , B_j(p) > +// b_2[i] = - < B_i(p) , \nabla \cdot V(p) > +// Although the two system matrices should be the same (assuming that the B_i satisfy dirichlet/neumann boundary conditions) +// the constraint vectors can differ when V does not satisfy the Neumann boundary conditions: +// A_1[i,j] = \int_R < \nabla B_i(p) , \nabla B_j(p) > +// = \int_R [ \nabla \cdot ( B_i(p) \nabla B_j(p) ) - B_i(p) \Delta B_j(p) ] +// = \int_dR < N(p) , B_i(p) \nabla B_j(p) > + A_2[i,j] +// and the first integral is zero if either f_i is zero on the boundary dR or the derivative of B_i across the boundary is zero. +// However, for the constraints we have: +// b_1(i) = \int_R < \nabla B_i(p) , V(p) > +// = \int_R [ \nabla \cdot ( B_i(p) V(p) ) - B_i(p) \nabla \cdot V(p) ] +// = \int_dR < N(p) , B_i(p) V(p) > + b_2[i] +// In particular, this implies that if the B_i satisfy the Neumann boundary conditions (rather than Dirichlet), +// and V is not zero across the boundary, then the two constraints are different. +// Forcing the < V(p) , N(p) > = 0 on the boundary, by killing off the component of the vector-field in the normal direction +// (FORCE_NEUMANN_FIELD), makes the two systems equal, and the value of this flag should be immaterial. +// Note that under interpretation 1, we have: +// \sum_i b_1(i) = < \nabla \sum_ i B_i(p) , V(p) > = 0 +// because the B_i's sum to one. However, in general, we could have +// \sum_i b_2(i) \neq 0. +// This could cause trouble because the constant functions are in the kernel of the matrix A, so CG will misbehave if the constraint +// has a non-zero DC term. (Again, forcing < V(p) , N(p) > = 0 along the boundary resolves this problem.) + +#define FORCE_NEUMANN_FIELD 1 // This flag forces the normal component across the boundary of the integration domain to be zero. +// This should be enabled if GRADIENT_DOMAIN_SOLUTION is not, so that CG doesn't run into trouble. + + +#include "hash.h" +#include "bspline_data.h" + + + +namespace pcl +{ + namespace poisson + { + + typedef float Real; + typedef float BSplineDataReal; + typedef pcl::poisson::OctNode< class TreeNodeData , Real > TreeOctNode; + + + + class RootInfo + { + public: + const TreeOctNode* node; + int edgeIndex; + long long key; + }; + + class VertexData + { + public: + static long long EdgeIndex( const TreeOctNode* node , int eIndex , int maxDepth , int index[DIMENSION] ); + static long long EdgeIndex( const TreeOctNode* node , int eIndex , int maxDepth ); + static long long FaceIndex( const TreeOctNode* node , int fIndex , int maxDepth,int index[DIMENSION] ); + static long long FaceIndex( const TreeOctNode* node , int fIndex , int maxDepth ); + static long long CornerIndex( int depth , const int offSet[DIMENSION] , int cIndex , int maxDepth , int index[DIMENSION] ); + static long long CornerIndex( const TreeOctNode* node , int cIndex , int maxDepth , int index[DIMENSION] ); + static long long CornerIndex( const TreeOctNode* node , int cIndex , int maxDepth ); + static long long CenterIndex( int depth , const int offSet[DIMENSION] , int maxDepth , int index[DIMENSION] ); + static long long CenterIndex( const TreeOctNode* node , int maxDepth , int index[DIMENSION] ); + static long long CenterIndex( const TreeOctNode* node , int maxDepth ); + static long long CornerIndexKey( const int index[DIMENSION] ); + }; + class SortedTreeNodes + { + public: + TreeOctNode** treeNodes; + int *nodeCount; + int maxDepth; + SortedTreeNodes( void ); + ~SortedTreeNodes( void ); + void set( TreeOctNode& root ); + struct CornerIndices + { + int idx[pcl::poisson::Cube::CORNERS]; + CornerIndices( void ) { memset( idx , -1 , sizeof( int ) * pcl::poisson::Cube::CORNERS ); } + int& operator[] ( int i ) { return idx[i]; } + const int& operator[] ( int i ) const { return idx[i]; } + }; + struct CornerTableData + { + CornerTableData( void ) { cCount=0; } + ~CornerTableData( void ) { clear(); } + void clear( void ) { cTable.clear() ; cCount = 0; } + CornerIndices& operator[] ( const TreeOctNode* node ); + const CornerIndices& operator[] ( const TreeOctNode* node ) const; + CornerIndices& cornerIndices( const TreeOctNode* node ); + const CornerIndices& cornerIndices( const TreeOctNode* node ) const; + int cCount; + std::vector< CornerIndices > cTable; + std::vector< int > offsets; + }; + void setCornerTable( CornerTableData& cData , const TreeOctNode* rootNode , int depth , int threads ) const; + void setCornerTable( CornerTableData& cData , const TreeOctNode* rootNode , int threads ) const { setCornerTable( cData , rootNode , maxDepth-1 , threads ); } + void setCornerTable( CornerTableData& cData , int threads ) const { setCornerTable( cData , treeNodes[0] , maxDepth-1 , threads ); } + int getMaxCornerCount( const TreeOctNode* rootNode , int depth , int maxDepth , int threads ) const ; + struct EdgeIndices + { + int idx[pcl::poisson::Cube::EDGES]; + EdgeIndices( void ) { memset( idx , -1 , sizeof( int ) * pcl::poisson::Cube::EDGES ); } + int& operator[] ( int i ) { return idx[i]; } + const int& operator[] ( int i ) const { return idx[i]; } + }; + struct EdgeTableData + { + EdgeTableData( void ) { eCount=0; } + ~EdgeTableData( void ) { clear(); } + void clear( void ) { eTable.clear() , eCount=0; } + EdgeIndices& operator[] ( const TreeOctNode* node ); + const EdgeIndices& operator[] ( const TreeOctNode* node ) const; + EdgeIndices& edgeIndices( const TreeOctNode* node ); + const EdgeIndices& edgeIndices( const TreeOctNode* node ) const; + int eCount; + std::vector< EdgeIndices > eTable; + std::vector< int > offsets; + }; + void setEdgeTable( EdgeTableData& eData , const TreeOctNode* rootNode , int depth , int threads ); + void setEdgeTable( EdgeTableData& eData , const TreeOctNode* rootNode , int threads ) { setEdgeTable( eData , rootNode , maxDepth-1 , threads ); } + void setEdgeTable( EdgeTableData& eData , int threads ) { setEdgeTable( eData , treeNodes[0] , maxDepth-1 , threads ); } + int getMaxEdgeCount( const TreeOctNode* rootNode , int depth , int threads ) const ; + }; + + class TreeNodeData + { + public: + static int UseIndex; + int nodeIndex; + union + { + int mcIndex; + struct + { + Real centerWeightContribution; + int normalIndex; + }; + }; + Real constraint , solution; + int pointIndex; + + TreeNodeData(void); + ~TreeNodeData(void); + }; + + template< int Degree > + class Octree + { + SortedTreeNodes _sNodes; + int _minDepth; + bool _constrainValues; + std::vector< int > _pointCount; + struct PointData + { + pcl::poisson::Point3D< Real > position; + Real weight; + Real value; + PointData( pcl::poisson::Point3D< Real > p , Real w , Real v=0 ) { position = p , weight = w , value = v; } + }; + std::vector< PointData > _points; + TreeOctNode::NeighborKey3 neighborKey; + TreeOctNode::ConstNeighborKey3 neighborKey2; + + Real radius; + int width; + Real GetLaplacian( const int index[DIMENSION] ) const; + // Note that this is a slight misnomer. We're only taking the diveregence/Laplacian in the weak sense, so there is a change of sign. + Real GetLaplacian( const TreeOctNode* node1 , const TreeOctNode* node2 ) const; + Real GetDivergence( const TreeOctNode* node1 , const TreeOctNode* node2 , const pcl::poisson::Point3D& normal1 ) const; + Real GetDivergenceMinusLaplacian( const TreeOctNode* node1 , const TreeOctNode* node2 , Real value1 , const pcl::poisson::Point3D& normal1 ) const; + struct PointInfo + { + float splineValues[3][3]; + float weightedValue; + }; + Real GetValue( const PointInfo points[3][3][3] , const bool hasPoints[3][3] , const int d[3] ) const; + + class AdjacencyCountFunction + { + public: + int adjacencyCount; + void Function(const TreeOctNode* node1,const TreeOctNode* node2); + }; + class AdjacencySetFunction{ + public: + int *adjacencies,adjacencyCount; + void Function(const TreeOctNode* node1,const TreeOctNode* node2); + }; + + class RefineFunction{ + public: + int depth; + void Function(TreeOctNode* node1,const TreeOctNode* node2); + }; + class FaceEdgesFunction + { + public: + int fIndex , maxDepth; + std::vector< std::pair< RootInfo , RootInfo > >* edges; + hash_map< long long , std::pair< RootInfo , int > >* vertexCount; + void Function( const TreeOctNode* node1 , const TreeOctNode* node2 ); + }; + + int SolveFixedDepthMatrix( int depth , const SortedTreeNodes& sNodes , Real* subConstraints , bool showResidual , int minIters , double accuracy ); + int SolveFixedDepthMatrix( int depth , const SortedTreeNodes& sNodes , Real* subConstraints , int startingDepth , bool showResidual , int minIters , double accuracy ); + + void SetMatrixRowBounds( const TreeOctNode* node , int rDepth , const int rOff[3] , int& xStart , int& xEnd , int& yStart , int& yEnd , int& zStart , int& zEnd ) const; + int GetMatrixRowSize( const TreeOctNode::Neighbors5& neighbors5 ) const; + int GetMatrixRowSize( const TreeOctNode::Neighbors5& neighbors5 , int xStart , int xEnd , int yStart , int yEnd , int zStart , int zEnd ) const; + int SetMatrixRow( const TreeOctNode::Neighbors5& neighbors5 , pcl::poisson::MatrixEntry< float >* row , int offset , const double stencil[5][5][5] ) const; + int SetMatrixRow( const TreeOctNode::Neighbors5& neighbors5 , pcl::poisson::MatrixEntry< float >* row , int offset , const double stencil[5][5][5] , int xStart , int xEnd , int yStart , int yEnd , int zStart , int zEnd ) const; + void SetDivergenceStencil( int depth , pcl::poisson::Point3D< double > *stencil , bool scatter ) const; + void SetLaplacianStencil( int depth , double stencil[5][5][5] ) const; + template< class C , int N > struct Stencil{ C values[N][N][N]; }; + void SetLaplacianStencils( int depth , Stencil< double , 5 > stencil[2][2][2] ) const; + void SetDivergenceStencils( int depth , Stencil< pcl::poisson::Point3D< double > , 5 > stencil[2][2][2] , bool scatter ) const; + void SetEvaluationStencils( int depth , Stencil< double , 3 > stencil1[8] , Stencil< double , 3 > stencil2[8][8] ) const; + + static void UpdateCoarserSupportBounds( const TreeOctNode* node , int& startX , int& endX , int& startY , int& endY , int& startZ , int& endZ ); + void UpdateConstraintsFromCoarser( const TreeOctNode::NeighborKey5& neighborKey5 , TreeOctNode* node , Real* metSolution , const Stencil< double , 5 >& stencil ) const; + void SetCoarserPointValues( int depth , const SortedTreeNodes& sNodes , Real* metSolution ); + Real WeightedCoarserFunctionValue( const TreeOctNode::NeighborKey3& neighborKey3 , const TreeOctNode* node , Real* metSolution ) const; + void UpSampleCoarserSolution( int depth , const SortedTreeNodes& sNodes , pcl::poisson::Vector< Real >& solution ) const; + void DownSampleFinerConstraints( int depth , SortedTreeNodes& sNodes ) const; + template< class C > void DownSample( int depth , const SortedTreeNodes& sNodes , C* constraints ) const; + template< class C > void UpSample( int depth , const SortedTreeNodes& sNodes , C* coefficients ) const; + int GetFixedDepthLaplacian( pcl::poisson::SparseSymmetricMatrix& matrix , int depth , const SortedTreeNodes& sNodes , Real* subConstraints ); + int GetRestrictedFixedDepthLaplacian( pcl::poisson::SparseSymmetricMatrix& matrix , int depth , const int* entries , int entryCount , const TreeOctNode* rNode, Real radius , const SortedTreeNodes& sNodes , Real* subConstraints ); + + void SetIsoCorners( Real isoValue , TreeOctNode* leaf , SortedTreeNodes::CornerTableData& cData , char* valuesSet , Real* values , TreeOctNode::ConstNeighborKey3& nKey , const Real* metSolution , const Stencil< double , 3 > stencil1[8] , const Stencil< double , 3 > stencil2[8][8] ); + static int IsBoundaryFace( const TreeOctNode* node , int faceIndex , int subdivideDepth ); + static int IsBoundaryEdge( const TreeOctNode* node , int edgeIndex , int subdivideDepth ); + static int IsBoundaryEdge( const TreeOctNode* node , int dir , int x , int y , int subidivideDepth ); + + // For computing the iso-surface there is a lot of re-computation of information across shared geometry. + // For function values we don't care so much. + // For edges we need to be careful so that the mesh remains water-tight + struct RootData : public SortedTreeNodes::CornerTableData , public SortedTreeNodes::EdgeTableData + { + // Edge to iso-vertex map + hash_map< long long , int > boundaryRoots; + // Vertex to ( value , normal ) map + hash_map< long long , std::pair< Real , pcl::poisson::Point3D< Real > > > *boundaryValues; + int* interiorRoots; + Real *cornerValues; + pcl::poisson::Point3D< Real >* cornerNormals; + char *cornerValuesSet , *cornerNormalsSet , *edgesSet; + }; + + int SetBoundaryMCRootPositions( int sDepth , Real isoValue , RootData& rootData , pcl::poisson::CoredMeshData* mesh , int nonLinearFit ); + int SetMCRootPositions( TreeOctNode* node , int sDepth , Real isoValue , TreeOctNode::ConstNeighborKey5& neighborKey5 , RootData& rootData , + std::vector< pcl::poisson::Point3D< float > >* interiorPositions , pcl::poisson::CoredMeshData* mesh , const Real* metSolution , int nonLinearFit ); +#if MISHA_DEBUG + int GetMCIsoTriangles( TreeOctNode* node , pcl::poisson::CoredMeshData* mesh , RootData& rootData , + std::vector< pcl::poisson::Point3D< float > >* interiorPositions , int offSet , int sDepth , bool polygonMesh , std::vector< pcl::poisson::Point3D< float > >* barycenters ); + static int AddTriangles( pcl::poisson::CoredMeshData* mesh , std::vector& edges , std::vector >* interiorPositions , int offSet , bool polygonMesh , std::vector< pcl::poisson::Point3D< float > >* barycenters ); +#else // !MISHA_DEBUG + int GetMCIsoTriangles( TreeOctNode* node , pcl::poisson::CoredMeshData* mesh , RootData& rootData , + std::vector< pcl::poisson::Point3D< float > >* interiorPositions , int offSet , int sDepth , bool addBarycenter , bool polygonMesh ); + static int AddTriangles( pcl::poisson::CoredMeshData* mesh , std::vector& edges , std::vector >* interiorPositions , int offSet , bool addBarycenter , bool polygonMesh ); +#endif // MISHA_DEBUG + + + void GetMCIsoEdges( TreeOctNode* node , int sDepth , std::vector< std::pair< RootInfo , RootInfo > >& edges ); + static int GetEdgeLoops( std::vector< std::pair< RootInfo , RootInfo > >& edges , std::vector< std::vector< std::pair< RootInfo , RootInfo > > >& loops); + static int InteriorFaceRootCount( const TreeOctNode* node , const int &faceIndex , int maxDepth ); + static int EdgeRootCount( const TreeOctNode* node , int edgeIndex , int maxDepth ); + static void GetRootSpan( const RootInfo& ri , pcl::poisson::Point3D< float >& start , pcl::poisson::Point3D< float >& end ); + int GetRoot( const RootInfo& ri , Real isoValue , TreeOctNode::ConstNeighborKey5& neighborKey5 , pcl::poisson::Point3D & position , RootData& rootData , int sDepth , const Real* metSolution , int nonLinearFit ); + static int GetRootIndex( const TreeOctNode* node , int edgeIndex , int maxDepth , RootInfo& ri ); + static int GetRootIndex( const TreeOctNode* node , int edgeIndex , int maxDepth , int sDepth , RootInfo& ri ); + static int GetRootIndex( const RootInfo& ri , RootData& rootData , pcl::poisson::CoredPointIndex& index ); + static int GetRootPair( const RootInfo& root , int maxDepth , RootInfo& pair ); + + int NonLinearUpdateWeightContribution(TreeOctNode* node,const pcl::poisson::Point3D& position,Real weight=Real(1.0)); + Real NonLinearGetSampleWeight(TreeOctNode* node,const pcl::poisson::Point3D& position); + void NonLinearGetSampleDepthAndWeight(TreeOctNode* node,const pcl::poisson::Point3D& position,Real samplesPerNode,Real& depth,Real& weight); + int NonLinearSplatOrientedPoint(TreeOctNode* node,const pcl::poisson::Point3D& point,const pcl::poisson::Point3D& normal); + Real NonLinearSplatOrientedPoint(const pcl::poisson::Point3D& point,const pcl::poisson::Point3D& normal , int kernelDepth , Real samplesPerNode , int minDepth , int maxDepth); + + int HasNormals(TreeOctNode* node,Real epsilon); + Real getCornerValue( const TreeOctNode::ConstNeighborKey3& neighborKey3 , const TreeOctNode* node , int corner , const Real* metSolution ); + pcl::poisson::Point3D< Real > getCornerNormal( const TreeOctNode::ConstNeighborKey5& neighborKey5 , const TreeOctNode* node , int corner , const Real* metSolution ); + Real getCornerValue( const TreeOctNode::ConstNeighborKey3& neighborKey3 , const TreeOctNode* node , int corner , const Real* metSolution , const double stencil1[3][3][3] , const double stencil2[3][3][3] ); + Real getCenterValue( const TreeOctNode::ConstNeighborKey3& neighborKey3 , const TreeOctNode* node ); + public: + int threads; + static double maxMemoryUsage; + static double MemoryUsage( void ); + std::vector< pcl::poisson::Point3D >* normals; + Real postNormalSmooth; + TreeOctNode tree; + pcl::poisson::BSplineData fData; + Octree( void ); + + void setBSplineData( int maxDepth , Real normalSmooth=-1 , bool reflectBoundary=false ); + void finalize( void ); + void RefineBoundary( int subdivisionDepth ); + Real* GetWeightGrid( int& res , int depth=-1 ); + Real* GetSolutionGrid( int& res , float isoValue=0.f , int depth=-1 ); + + template int + setTree( boost::shared_ptr > input_ , int maxDepth , int minDepth , + int kernelDepth , Real samplesPerNode , Real scaleFactor , Point3D& center , Real& scale , + int useConfidence , Real constraintWeight , bool adaptiveWeights ); + + void SetLaplacianConstraints(void); + void ClipTree(void); + int LaplacianMatrixIteration( int subdivideDepth , bool showResidual , int minIters , double accuracy ); + + Real GetIsoValue(void); + void GetMCIsoTriangles( Real isoValue , int subdivideDepth , pcl::poisson::CoredMeshData* mesh , int fullDepthIso=0 , int nonLinearFit=1 , bool addBarycenter=false , bool polygonMesh=false ); + }; + + + } +} + + + + +#include "multi_grid_octree_data.hpp" +#endif // MULTI_GRID_OCTREE_DATA_INCLUDED diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/multi_grid_octree_data.hpp b/pcl-1.7/pcl/surface/3rdparty/poisson4/multi_grid_octree_data.hpp new file mode 100644 index 0000000..7cfe20c --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/multi_grid_octree_data.hpp @@ -0,0 +1,3918 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#include "octree_poisson.h" +#include "mat.h" + +#if defined WIN32 || defined _WIN32 + #if !defined __MINGW32__ + #include + #include + #endif +#endif + + +#define ITERATION_POWER 1.0/3 +#define MEMORY_ALLOCATOR_BLOCK_SIZE 1<<12 +#define SPLAT_ORDER 2 + +#ifndef _MSC_VER +namespace std +{ + using namespace __gnu_cxx; +} +#endif + +namespace pcl +{ + namespace poisson + { + + const Real MATRIX_ENTRY_EPSILON = Real(0); + const Real EPSILON=Real(1e-6); + const Real ROUND_EPS=Real(1e-5); + +#if defined _WIN32 && !defined __MINGW32__ + using stdext::hash_map; +#else + using std::hash_map; +#endif + + + void atomicOr(volatile int& dest, int value) + { +#if defined _WIN32 && !defined __MINGW32__ + #if defined (_M_IX86) + _InterlockedOr( (long volatile*)&dest, value ); + #else + InterlockedOr( (long volatile*)&dest , value ); + #endif +#else // !_WIN32 || __MINGW32__ + #pragma omp atomic + dest |= value; +#endif // _WIN32 && !__MINGW32__ + } + + + ///////////////////// + // SortedTreeNodes // + ///////////////////// + SortedTreeNodes::SortedTreeNodes(void) + { + nodeCount=NULL; + treeNodes=NULL; + maxDepth=0; + } + SortedTreeNodes::~SortedTreeNodes(void){ + if( nodeCount ) delete[] nodeCount; + if( treeNodes ) delete[] treeNodes; + nodeCount = NULL; + treeNodes = NULL; + } + + void SortedTreeNodes::set( TreeOctNode& root ) + { + if( nodeCount ) delete[] nodeCount; + if( treeNodes ) delete[] treeNodes; + maxDepth = root.maxDepth()+1; + nodeCount = new int[ maxDepth+1 ]; + treeNodes = new TreeOctNode*[ root.nodes() ]; + + nodeCount[0] = 0 , nodeCount[1] = 1; + treeNodes[0] = &root; + for( int d=1 ; dchildren ) for( int c=0 ; c<8 ; c++ ) treeNodes[ nodeCount[d+1]++ ] = temp->children + c; + } + } + for( int i=0 ; inodeData.nodeIndex = i; + } + SortedTreeNodes::CornerIndices& SortedTreeNodes::CornerTableData::operator[] ( const TreeOctNode* node ) { return cTable[ node->nodeData.nodeIndex + offsets[node->d] ]; } + const SortedTreeNodes::CornerIndices& SortedTreeNodes::CornerTableData::operator[] ( const TreeOctNode* node ) const { return cTable[ node->nodeData.nodeIndex + offsets[node->d] ]; } + SortedTreeNodes::CornerIndices& SortedTreeNodes::CornerTableData::cornerIndices( const TreeOctNode* node ) { return cTable[ node->nodeData.nodeIndex + offsets[node->d] ]; } + const SortedTreeNodes::CornerIndices& SortedTreeNodes::CornerTableData::cornerIndices( const TreeOctNode* node ) const { return cTable[ node->nodeData.nodeIndex + offsets[node->d] ]; } + void SortedTreeNodes::setCornerTable( CornerTableData& cData , const TreeOctNode* rootNode , int maxDepth , int threads ) const + { + if( threads<=0 ) threads = 1; + // The vector of per-depth node spans + std::vector< std::pair< int , int > > spans( this->maxDepth , std::pair< int , int >( -1 , -1 ) ); + int minDepth , off[3]; + rootNode->depthAndOffset( minDepth , off ); + cData.offsets.resize( this->maxDepth , -1 ); + int nodeCount = 0; + { + int start=rootNode->nodeData.nodeIndex , end=start; + for( int d=minDepth ; d<=maxDepth ; d++ ) + { + spans[d] = std::pair< int , int >( start , end+1 ); + cData.offsets[d] = nodeCount - spans[d].first; + nodeCount += spans[d].second - spans[d].first; + if( dchildren ) start++; + while( end> start && !treeNodes[end ]->children ) end--; + if( start==end && !treeNodes[start]->children ) break; + start = treeNodes[start]->children[0].nodeData.nodeIndex; + end = treeNodes[end ]->children[7].nodeData.nodeIndex; + } + } + } + cData.cTable.resize( nodeCount ); + std::vector< int > count( threads ); +#pragma omp parallel for num_threads( threads ) + for( int t=0 ; tchildren ) continue; + const TreeOctNode::ConstNeighbors3& neighbors = neighborKey.getNeighbors( node , minDepth ); + for( int c=0 ; cchildren ) ) + { + int _d , _off[3]; + neighbors.neighbors[xx][yy][zz]->depthAndOffset( _d , _off ); + _off[0] >>= (d-minDepth) , _off[1] >>= (d-minDepth) , _off[2] >>= (d-minDepth); + if( _off[0]==off[0] && _off[1]==off[1] && _off[2]==off[2] ) + { + cornerOwner = false; + break; + } + else fprintf( stderr , "[WARNING] How did we leave the subtree?\n" ); + } + } + if( cornerOwner ) + { + const TreeOctNode* n = node; + int d = n->depth(); + do + { + const TreeOctNode::ConstNeighbors3& neighbors = neighborKey.neighbors[d]; + // Set all the corner indices at the current depth + for( int cc=0 ; ccparent->children+c) ) break; + n = n->parent; + d--; + } + while( 1 ); + count[t]++; + } + } + } + } + } + cData.cCount = 0; + std::vector< int > offsets( threads+1 ); + offsets[0] = 0; + for( int t=0 ; tnodeData.nodeIndex , c , idx , minDepth , maxDepth ); + int _d , _off[3]; + treeNodes[i]->depthAndOffset( _d , _off ); + printf( "(%d [%d %d %d) <-> (%d [%d %d %d])\n" , minDepth , off[0] , off[1] , off[2] , _d , _off[0] , _off[1] , _off[2] ); + printf( "[%d %d]\n" , spans[d].first , spans[d].second ); + exit( 0 ); + } + else + { + int div = idx / ( nodeCount*Cube::CORNERS ); + int rem = idx % ( nodeCount*Cube::CORNERS ); + idx = rem + offsets[div]; + } + } + } + } + int SortedTreeNodes::getMaxCornerCount( const TreeOctNode* rootNode , int depth , int maxDepth , int threads ) const + { + if( threads<=0 ) threads = 1; + int res = 1< > cornerCount( threads ); + for( int t=0 ; t& _cornerCount = cornerCount[t]; + TreeOctNode::ConstNeighborKey3 neighborKey; + neighborKey.set( maxDepth ); + int start = nodeCount[depth] , end = nodeCount[maxDepth+1] , range = end-start; + for( int i=(range*t)/threads ; i<(range*(t+1))/threads ; i++ ) + { + TreeOctNode* node = treeNodes[start+i]; + int d , off[3]; + node->depthAndOffset( d , off ); + if( dchildren ) continue; + + const TreeOctNode::ConstNeighbors3& neighbors = neighborKey.getNeighbors( node , depth ); + for( int c=0 ; cchildren ) ) + { + cornerOwner = false; + break; + } + } + if( cornerOwner ) _cornerCount[ ( ( off[0]>>(d-depth) ) * res * res) + ( ( off[1]>>(d-depth) ) * res) + ( off[2]>>(d-depth) ) ]++; + } + } + } + int maxCount = 0; + for( int i=0 ; i( maxCount , c ); + } + return maxCount; + } + SortedTreeNodes::EdgeIndices& SortedTreeNodes::EdgeTableData::operator[] ( const TreeOctNode* node ) { return eTable[ node->nodeData.nodeIndex + offsets[node->d] ]; } + const SortedTreeNodes::EdgeIndices& SortedTreeNodes::EdgeTableData::operator[] ( const TreeOctNode* node ) const { return eTable[ node->nodeData.nodeIndex + offsets[node->d] ]; } + SortedTreeNodes::EdgeIndices& SortedTreeNodes::EdgeTableData::edgeIndices( const TreeOctNode* node ) { return eTable[ node->nodeData.nodeIndex + offsets[node->d] ]; } + const SortedTreeNodes::EdgeIndices& SortedTreeNodes::EdgeTableData::edgeIndices( const TreeOctNode* node ) const { return eTable[ node->nodeData.nodeIndex + offsets[node->d] ]; } + void SortedTreeNodes::setEdgeTable( EdgeTableData& eData , const TreeOctNode* rootNode , int maxDepth , int threads ) + { + if( threads<=0 ) threads = 1; + std::vector< std::pair< int , int > > spans( this->maxDepth , std::pair< int , int >( -1 , -1 ) ); + + int minDepth , off[3]; + rootNode->depthAndOffset( minDepth , off ); + eData.offsets.resize( this->maxDepth , -1 ); + int nodeCount = 0; + { + int start=rootNode->nodeData.nodeIndex , end=start; + for( int d=minDepth ; d<=maxDepth ; d++ ) + { + spans[d] = std::pair< int , int >( start , end+1 ); + eData.offsets[d] = nodeCount - spans[d].first; + nodeCount += spans[d].second - spans[d].first; + if( dchildren ) start++; + while( end> start && !treeNodes[end ]->children ) end--; + if( start==end && !treeNodes[start]->children ) break; + start = treeNodes[start]->children[0].nodeData.nodeIndex; + end = treeNodes[end ]->children[7].nodeData.nodeIndex; + } + } + } + eData.eTable.resize( nodeCount ); + std::vector< int > count( threads ); +#pragma omp parallel for num_threads( threads ) + for( int t=0 ; t offsets( threads+1 ); + offsets[0] = 0; + for( int t=0 ; t > edgeCount( threads ); + for( int t=0 ; t& _edgeCount = edgeCount[t]; + TreeOctNode::ConstNeighborKey3 neighborKey; + neighborKey.set( maxDepth-1 ); + int start = nodeCount[depth] , end = nodeCount[maxDepth] , range = end-start; + for( int i=(range*t)/threads ; i<(range*(t+1))/threads ; i++ ) + { + TreeOctNode* node = treeNodes[start+i]; + const TreeOctNode::ConstNeighbors3& neighbors = neighborKey.getNeighbors( node , depth ); + int d , off[3]; + node->depthAndOffset( d , off ); + + for( int e=0 ; e>(d-depth) ) * res * res) + ( ( off[1]>>(d-depth) ) * res) + ( off[2]>>(d-depth) ) ]++; + } + } + } + int maxCount = 0; + for( int i=0 ; i( maxCount , c ); + } + return maxCount; + } + + + + ////////////////// + // TreeNodeData // + ////////////////// + int TreeNodeData::UseIndex=1; + TreeNodeData::TreeNodeData( void ) + { + if( UseIndex ) + { + nodeIndex = -1; + centerWeightContribution=0; + } + else mcIndex=0; + normalIndex = -1; + constraint = solution = 0; + pointIndex = -1; + } + TreeNodeData::~TreeNodeData( void ) { } + + + //////////// + // Octree // + //////////// + template + double Octree::maxMemoryUsage=0; + + + + template + double Octree::MemoryUsage(void){ + double mem = 0;//double( MemoryInfo::Usage() ) / (1<<20); + if(mem>maxMemoryUsage){maxMemoryUsage=mem;} + return mem; + } + + template + Octree::Octree(void) + { + threads = 1; + radius = 0; + width = 0; + postNormalSmooth = 0; + _constrainValues = false; + } + + template + int Octree::NonLinearSplatOrientedPoint( TreeOctNode* node , const Point3D& position , const Point3D& normal ) + { + double x , dxdy , dxdydz , dx[DIMENSION][SPLAT_ORDER+1]; + int off[3]; + TreeOctNode::Neighbors3& neighbors = neighborKey.setNeighbors( node ); + double width; + Point3D center; + Real w; + node->centerAndWidth( center , w ); + width=w; + for( int i=0 ; i<3 ; i++ ) + { +#if SPLAT_ORDER==2 + off[i] = 0; + x = ( center[i] - position[i] - width ) / width; + dx[i][0] = 1.125+1.500*x+0.500*x*x; + x = ( center[i] - position[i] ) / width; + dx[i][1] = 0.750 - x*x; + + dx[i][2] = 1. - dx[i][1] - dx[i][0]; +#elif SPLAT_ORDER==1 + x = ( position[i] - center[i] ) / width; + if( x<0 ) + { + off[i] = 0; + dx[i][0] = -x; + } + else + { + off[i] = 1; + dx[i][0] = 1. - x; + } + dx[i][1] = 1. - dx[i][0]; +#elif SPLAT_ORDER==0 + off[i] = 1; + dx[i][0] = 1.; +#else +# error Splat order not supported +#endif // SPLAT_ORDER + } + for( int i=off[0] ; i<=off[0]+SPLAT_ORDER ; i++ ) for( int j=off[1] ; j<=off[1]+SPLAT_ORDER ; j++ ) + { + dxdy = dx[0][i] * dx[1][j]; + for( int k=off[2] ; k<=off[2]+SPLAT_ORDER ; k++ ) + if( neighbors.neighbors[i][j][k] ) + { + dxdydz = dxdy * dx[2][k]; + TreeOctNode* _node = neighbors.neighbors[i][j][k]; + int idx =_node->nodeData.normalIndex; + if( idx<0 ) + { + Point3D n; + n[0] = n[1] = n[2] = 0; + _node->nodeData.nodeIndex = 0; + idx = _node->nodeData.normalIndex = int(normals->size()); + normals->push_back(n); + } + (*normals)[idx] += normal * Real( dxdydz ); + } + } + return 0; + } + template + Real Octree::NonLinearSplatOrientedPoint( const Point3D& position , const Point3D& normal , int splatDepth , Real samplesPerNode , + int minDepth , int maxDepth ) + { + double dx; + Point3D n; + TreeOctNode* temp; + int cnt=0; + double width; + Point3D< Real > myCenter; + Real myWidth; + myCenter[0] = myCenter[1] = myCenter[2] = Real(0.5); + myWidth = Real(1.0); + + temp = &tree; + while( temp->depth()children ) + { + fprintf( stderr , "Octree::NonLinearSplatOrientedPoint error\n" ); + return -1; + } + int cIndex=TreeOctNode::CornerIndex(myCenter,position); + temp=&temp->children[cIndex]; + myWidth/=2; + if(cIndex&1) myCenter[0] += myWidth/2; + else myCenter[0] -= myWidth/2; + if(cIndex&2) myCenter[1] += myWidth/2; + else myCenter[1] -= myWidth/2; + if(cIndex&4) myCenter[2] += myWidth/2; + else myCenter[2] -= myWidth/2; + } + Real alpha,newDepth; + NonLinearGetSampleDepthAndWeight( temp , position , samplesPerNode , newDepth , alpha ); + + if( newDepthmaxDepth ) newDepth=Real(maxDepth); + int topDepth=int(ceil(newDepth)); + + dx = 1.0-(topDepth-newDepth); + if( topDepth<=minDepth ) + { + topDepth=minDepth; + dx=1; + } + else if( topDepth>maxDepth ) + { + topDepth=maxDepth; + dx=1; + } + while( temp->depth()>topDepth ) temp=temp->parent; + while( temp->depth()children) temp->initChildren(); + int cIndex=TreeOctNode::CornerIndex(myCenter,position); + temp=&temp->children[cIndex]; + myWidth/=2; + if(cIndex&1) myCenter[0] += myWidth/2; + else myCenter[0] -= myWidth/2; + if(cIndex&2) myCenter[1] += myWidth/2; + else myCenter[1] -= myWidth/2; + if(cIndex&4) myCenter[2] += myWidth/2; + else myCenter[2] -= myWidth/2; + } + width = 1.0 / ( 1<depth() ); + n = normal * alpha / Real( pow( width , 3 ) ) * Real( dx ); + NonLinearSplatOrientedPoint( temp , position , n ); + if( fabs(1.0-dx) > EPSILON ) + { + dx = Real(1.0-dx); + temp = temp->parent; + width = 1.0 / ( 1<depth() ); + + n = normal * alpha / Real( pow( width , 3 ) ) * Real( dx ); + NonLinearSplatOrientedPoint( temp , position , n ); + } + return alpha; + } + template + void Octree::NonLinearGetSampleDepthAndWeight(TreeOctNode* node,const Point3D& position,Real samplesPerNode,Real& depth,Real& weight){ + TreeOctNode* temp=node; + weight = Real(1.0)/NonLinearGetSampleWeight(temp,position); + if( weight>=samplesPerNode ) depth=Real( temp->depth() + log( weight / samplesPerNode ) / log(double(1<<(DIMENSION-1))) ); + else + { + Real oldAlpha,newAlpha; + oldAlpha=newAlpha=weight; + while( newAlphaparent ) + { + temp=temp->parent; + oldAlpha=newAlpha; + newAlpha=Real(1.0)/NonLinearGetSampleWeight(temp,position); + } + depth = Real( temp->depth() + log( newAlpha / samplesPerNode ) / log( newAlpha / oldAlpha ) ); + } + weight=Real(pow(double(1<<(DIMENSION-1)),-double(depth))); + } + + template + Real Octree::NonLinearGetSampleWeight( TreeOctNode* node , const Point3D& position ) + { + Real weight=0; + double x,dxdy,dx[DIMENSION][3]; + TreeOctNode::Neighbors3& neighbors=neighborKey.setNeighbors( node ); + double width; + Point3D center; + Real w; + node->centerAndWidth(center,w); + width=w; + + for( int i=0 ; inodeData.centerWeightContribution ); + } + return Real( 1.0 / weight ); + } + + template + int Octree::NonLinearUpdateWeightContribution( TreeOctNode* node , const Point3D& position , Real weight ) + { + TreeOctNode::Neighbors3& neighbors = neighborKey.setNeighbors( node ); + double x,dxdy,dx[DIMENSION][3]; + double width; + Point3D center; + Real w; + node->centerAndWidth( center , w ); + width=w; + const double SAMPLE_SCALE = 1. / ( 0.125 * 0.125 + 0.75 * 0.75 + 0.125 * 0.125 ); + + for( int i=0 ; inodeData.centerWeightContribution += Real( dxdy * dx[2][k] ); + } + return 0; + } + + template< int Degree > template int + Octree::setTree( boost::shared_ptr > input_, int maxDepth , int minDepth , + int kernelDepth , Real samplesPerNode , Real scaleFactor , Point3D& center , Real& scale , + int useConfidence , Real constraintWeight , bool adaptiveWeights ) + { + _minDepth = std::min< int >( std::max< int >( 0 , minDepth ) , maxDepth ); + _constrainValues = (constraintWeight>0); + double pointWeightSum = 0; + Point3D min , max , position , normal , myCenter; + Real myWidth; + int i , cnt=0; + TreeOctNode* temp; + int splatDepth=0; + + TreeNodeData::UseIndex = 1; + neighborKey.set( maxDepth ); + splatDepth = kernelDepth; + if( splatDepth<0 ) splatDepth = 0; + + + tree.setFullDepth( _minDepth ); + // Read through once to get the center and scale + while (cnt != input_->size ()) + { + Point3D< Real > p; + p[0] = input_->points[cnt].x; + p[1] = input_->points[cnt].y; + p[2] = input_->points[cnt].z; + + for (i = 0; i < DIMENSION; i++) + { + if( !cnt || p[i]max[i] ) max[i] = p[i]; + } + cnt++; + } + + scale = std::max< Real >( max[0]-min[0] , std::max< Real >( max[1]-min[1] , max[2]-min[2] ) ); + center = ( max+min ) /2; + + scale *= scaleFactor; + for( i=0 ; i0 ) + { + cnt = 0; + while (cnt != input_->size ()) + { + position[0] = input_->points[cnt].x; + position[1] = input_->points[cnt].y; + position[2] = input_->points[cnt].z; + normal[0] = input_->points[cnt].normal_x; + normal[1] = input_->points[cnt].normal_y; + normal[2] = input_->points[cnt].normal_z; + + for( i=0 ; imyCenter[i]+myWidth/2 ) break; + if( i!=DIMENSION ) continue; + Real weight=Real( 1. ); + if( useConfidence ) weight = Real( Length(normal) ); + temp = &tree; + int d=0; + while( dchildren ) temp->initChildren(); + int cIndex=TreeOctNode::CornerIndex(myCenter,position); + temp=&temp->children[cIndex]; + myWidth/=2; + if(cIndex&1) myCenter[0] += myWidth/2; + else myCenter[0] -= myWidth/2; + if(cIndex&2) myCenter[1] += myWidth/2; + else myCenter[1] -= myWidth/2; + if(cIndex&4) myCenter[2] += myWidth/2; + else myCenter[2] -= myWidth/2; + d++; + } + NonLinearUpdateWeightContribution( temp , position , weight ); + cnt++; + } + } + + normals = new std::vector< Point3D >(); + cnt=0; + while (cnt != input_->size ()) + { + position[0] = input_->points[cnt].x; + position[1] = input_->points[cnt].y; + position[2] = input_->points[cnt].z; + normal[0] = input_->points[cnt].normal_x; + normal[1] = input_->points[cnt].normal_y; + normal[2] = input_->points[cnt].normal_z; + cnt ++; + for( i=0 ; imyCenter[i]+myWidth/2) break; + if( i!=DIMENSION ) continue; + Real l = Real( Length( normal ) ); + if( l!=l || l<=EPSILON ) continue; + if( !useConfidence ) normal /= l; + + l = Real(1.); + Real pointWeight = Real(1.f); + if( samplesPerNode>0 && splatDepth ) + { + pointWeight = NonLinearSplatOrientedPoint( position , normal , splatDepth , samplesPerNode , _minDepth , maxDepth ); + } + else + { + Real alpha=1; + temp = &tree; + int d=0; + if( splatDepth ) + { + while( dchildren[cIndex]; + myWidth/=2; + if(cIndex&1) myCenter[0]+=myWidth/2; + else myCenter[0]-=myWidth/2; + if(cIndex&2) myCenter[1]+=myWidth/2; + else myCenter[1]-=myWidth/2; + if(cIndex&4) myCenter[2]+=myWidth/2; + else myCenter[2]-=myWidth/2; + d++; + } + alpha = NonLinearGetSampleWeight( temp , position ); + } + for( i=0 ; ichildren){temp->initChildren();} + int cIndex=TreeOctNode::CornerIndex(myCenter,position); + temp=&temp->children[cIndex]; + myWidth/=2; + if(cIndex&1) myCenter[0]+=myWidth/2; + else myCenter[0]-=myWidth/2; + if(cIndex&2) myCenter[1]+=myWidth/2; + else myCenter[1]-=myWidth/2; + if(cIndex&4) myCenter[2]+=myWidth/2; + else myCenter[2]-=myWidth/2; + d++; + } + NonLinearSplatOrientedPoint( temp , position , normal ); + pointWeight = alpha; + } + pointWeight = 1; + pointWeightSum += pointWeight; + if( _constrainValues ) + { + int d = 0; + TreeOctNode* temp = &tree; + myCenter[0] = myCenter[1] = myCenter[2] = Real(0.5); + myWidth = Real(1.0); + while( 1 ) + { + int idx = temp->nodeData.pointIndex; + if( idx==-1 ) + { + Point3D< Real > p; + p[0] = p[1] = p[2] = 0; + idx = int( _points.size() ); + _points.push_back( PointData( position*pointWeight , pointWeight ) ); + temp->nodeData.pointIndex = idx; + } + else + { + _points[idx].weight += pointWeight; + _points[idx].position += position * pointWeight; + } + + int cIndex = TreeOctNode::CornerIndex( myCenter , position ); + if( !temp->children ) break; + temp = &temp->children[cIndex]; + myWidth /= 2; + if( cIndex&1 ) myCenter[0] += myWidth/2; + else myCenter[0] -= myWidth/2; + if( cIndex&2 ) myCenter[1] += myWidth/2; + else myCenter[1] -= myWidth/2; + if( cIndex&4 ) myCenter[2] += myWidth/2; + else myCenter[2] -= myWidth/2; + d++; + } + } + } + + + if( _constrainValues ) + for( TreeOctNode* n=tree.nextNode() ; n ; n=tree.nextNode(n) ) + if( n->nodeData.pointIndex!=-1 ) + { + int idx = n->nodeData.pointIndex; + _points[idx].position /= _points[idx].weight; + if( adaptiveWeights ) _points[idx].weight *= (1<d); + else _points[idx].weight *= (1<depthAndOffset( d , off ); + res = 1<nodeData.normalIndex<0 ) continue; + Point3D< Real >& normal = (*normals)[node->nodeData.normalIndex]; + for( int d=0 ; d<3 ; d++ ) if( off[d]==0 || off[d]==res-1 ) normal[d] = 0; + } +#endif // FORCE_NEUMANN_FIELD + _sNodes.set( tree ); + + + return cnt; + } + + + template + void Octree::setBSplineData( int maxDepth , Real normalSmooth , bool reflectBoundary ) + { + radius = 0.5 + 0.5 * Degree; + width=int(double(radius+0.5-EPSILON)*2); + if( normalSmooth>0 ) postNormalSmooth = normalSmooth; + fData.set( maxDepth , true , reflectBoundary ); + } + + template + void Octree::finalize( void ) + { + int maxDepth = tree.maxDepth( ); + TreeOctNode::NeighborKey5 nKey; + nKey.set( maxDepth ); + for( int d=maxDepth ; d>0 ; d-- ) + for( TreeOctNode* node=tree.nextNode() ; node ; node=tree.nextNode( node ) ) + if( node->d==d ) + { + int xStart=0 , xEnd=5 , yStart=0 , yEnd=5 , zStart=0 , zEnd=5; + int c = int( node - node->parent->children ); + int x , y , z; + Cube::FactorCornerIndex( c , x , y , z ); + if( x ) xStart = 1; + else xEnd = 4; + if( y ) yStart = 1; + else yEnd = 4; + if( z ) zStart = 1; + else zEnd = 4; + nKey.setNeighbors( node->parent , xStart , xEnd , yStart , yEnd , zStart , zEnd ); + } + _sNodes.set( tree ); + MemoryUsage(); + } + template< int Degree > + Real Octree< Degree >::GetValue( const PointInfo points[3][3][3] , const bool hasPoints[3][3] , const int d[3] ) const + { + double v = 0.; + const int min[] = { std::max( 0 , d[0]+0 ) , std::max( 0 , d[1]+0 ) , std::max( 0 , d[2]+0 ) }; + const int max[] = { std::min( 2 , d[0]+2 ) , std::min( 2 , d[1]+2 ) , std::min( 2 , d[2]+2 ) }; + for( int i=min[0] ; i<=max[0] ; i++ ) for( int j=min[1] ; j<=max[1] ; j++ ) + { + if( !hasPoints[i][j] ) continue; + const PointInfo* pInfo = points[i][j]; + int ii = -d[0]+i; + int jj = -d[1]+j; + for( int k=min[2] ; k<=max[2] ; k++ ) + if( pInfo[k].weightedValue ) + v += pInfo[k].splineValues[0][ii] * pInfo[k].splineValues[1][jj] * pInfo[k].splineValues[2][-d[2]+k]; + } + return Real( v ); + } + template + Real Octree::GetLaplacian( const int idx[DIMENSION] ) const + { + return Real( fData.vvDotTable[idx[0]] * fData.vvDotTable[idx[1]] * fData.vvDotTable[idx[2]] * (fData.ddDotTable[idx[0]]+fData.ddDotTable[idx[1]]+fData.ddDotTable[idx[2]] ) ); + } + template< int Degree > + Real Octree< Degree >::GetLaplacian( const TreeOctNode* node1 , const TreeOctNode* node2 ) const + { + int symIndex[] = + { + BSplineData< Degree , Real >::SymmetricIndex( node1->off[0] , node2->off[0] ) , + BSplineData< Degree , Real >::SymmetricIndex( node1->off[1] , node2->off[1] ) , + BSplineData< Degree , Real >::SymmetricIndex( node1->off[2] , node2->off[2] ) + }; + return GetLaplacian( symIndex ); + } + template< int Degree > + Real Octree< Degree >::GetDivergence( const TreeOctNode* node1 , const TreeOctNode* node2 , const Point3D< Real >& normal1 ) const + { + int symIndex[] = + { + BSplineData< Degree , Real >::SymmetricIndex( node1->off[0] , node2->off[0] ) , + BSplineData< Degree , Real >::SymmetricIndex( node1->off[1] , node2->off[1] ) , + BSplineData< Degree , Real >::SymmetricIndex( node1->off[2] , node2->off[2] ) , + }; + int aSymIndex[] = + { + #if GRADIENT_DOMAIN_SOLUTION + // Take the dot-product of the vector-field with the gradient of the basis function + fData.Index( node2->off[0] , node1->off[0] ) , + fData.Index( node2->off[1] , node1->off[1] ) , + fData.Index( node2->off[2] , node1->off[2] ) + #else // !GRADIENT_DOMAIN_SOLUTION + // Take the dot-product of the divergence of the vector-field with the basis function + fData.Index( node1->off[0] , node2->off[0] ) , + fData.Index( node1->off[1] , node2->off[1] ) , + fData.Index( node1->off[2] , node2->off[2] ) + #endif // GRADIENT_DOMAIN_SOLUTION + }; + double dot = fData.vvDotTable[symIndex[0]] * fData.vvDotTable[symIndex[1]] * fData.vvDotTable[symIndex[2]]; +#if GRADIENT_DOMAIN_SOLUTION + return Real( dot * ( fData.dvDotTable[aSymIndex[0]]*normal1[0] + fData.dvDotTable[aSymIndex[1]]*normal1[1] + fData.dvDotTable[aSymIndex[2]]*normal1[2] ) ); +#else // !GRADIENT_DOMAIN_SOLUTION + return -Real( dot * ( fData.dvDotTable[aSymIndex[0]]*normal1[0] + fData.dvDotTable[aSymIndex[1]]*normal1[1] + fData.dvDotTable[aSymIndex[2]]*normal1[2] ) ); +#endif // GRADIENT_DOMAIN_SOLUTION + } + template< int Degree > + Real Octree< Degree >::GetDivergenceMinusLaplacian( const TreeOctNode* node1 , const TreeOctNode* node2 , Real value1 , const Point3D& normal1 ) const + { + int symIndex[] = + { + BSplineData< Degree , Real >::SymmetricIndex( node1->off[0] , node2->off[0] ) , + BSplineData< Degree , Real >::SymmetricIndex( node1->off[1] , node2->off[1] ) , + BSplineData< Degree , Real >::SymmetricIndex( node1->off[2] , node2->off[2] ) + }; + int aSymIndex[] = + { + #if GRADIENT_DOMAIN_SOLUTION + // Take the dot-product of the vector-field with the gradient of the basis function + fData.Index( node2->off[0] , node1->off[0] ) , + fData.Index( node2->off[1] , node1->off[1] ) , + fData.Index( node2->off[2] , node1->off[2] ) + #else // !GRADIENT_DOMAIN_SOLUTION + // Take the dot-product of the divergence of the vector-field with the basis function + fData.Index( node1->off[0] , node2->off[0] ) , + fData.Index( node1->off[1] , node2->off[1] ) , + fData.Index( node1->off[2] , node2->off[2] ) + #endif // GRADIENT_DOMAIN_SOLUTION + }; + double dot = fData.vvDotTable[symIndex[0]] * fData.vvDotTable[symIndex[1]] * fData.vvDotTable[symIndex[2]]; + return Real( dot * + ( + #if GRADIENT_DOMAIN_SOLUTION + - ( fData.ddDotTable[ symIndex[0]] + fData.ddDotTable[ symIndex[1]] + fData.ddDotTable[ symIndex[2]] ) * value1 + + ( fData.dvDotTable[aSymIndex[0]]*normal1[0] + fData.dvDotTable[aSymIndex[1]]*normal1[1] + fData.dvDotTable[aSymIndex[2]]*normal1[2] ) + #else // !GRADIENT_DOMAIN_SOLUTION + - ( fData.ddDotTable[ symIndex[0]] + fData.ddDotTable[ symIndex[1]] + fData.ddDotTable[ symIndex[2]] ) * value1 + - ( fData.dvDotTable[aSymIndex[0]]*normal1[0] + fData.dvDotTable[aSymIndex[1]]*normal1[1] + fData.dvDotTable[aSymIndex[2]]*normal1[2] ) + #endif // GRADIENT_DOMAIN_SOLUTION + ) + ); + } + template< int Degree > + void Octree< Degree >::SetMatrixRowBounds( const TreeOctNode* node , int rDepth , const int rOff[3] , int& xStart , int& xEnd , int& yStart , int& yEnd , int& zStart , int& zEnd ) const + { + xStart = 0 , yStart = 0 , zStart = 0 , xEnd = 5 , yEnd = 5 , zEnd = 5; + int depth , off[3]; + node->depthAndOffset( depth , off ); + int width = 1 << ( depth-rDepth ); + off[0] -= rOff[0] << ( depth-rDepth ) , off[1] -= rOff[1] << ( depth-rDepth ) , off[2] -= rOff[2] << ( depth-rDepth ); + if( off[0]<0 ) xStart = -off[0]; + if( off[1]<0 ) yStart = -off[1]; + if( off[2]<0 ) zStart = -off[2]; + if( off[0]>=width ) xEnd = 4 - ( off[0]-width ); + if( off[1]>=width ) yEnd = 4 - ( off[1]-width ); + if( off[2]>=width ) zEnd = 4 - ( off[2]-width ); + } + template< int Degree > + int Octree< Degree >::GetMatrixRowSize( const OctNode< TreeNodeData , Real >::Neighbors5& neighbors5 ) const { return GetMatrixRowSize( neighbors5 , 0 , 5 , 0 , 5 , 0 , 5 ); } + template< int Degree > + int Octree< Degree >::GetMatrixRowSize( const OctNode< TreeNodeData , Real >::Neighbors5& neighbors5 , int xStart , int xEnd , int yStart , int yEnd , int zStart , int zEnd ) const + { + int count = 0; + for( int x=xStart ; x<=2 ; x++ ) + for( int y=yStart ; y2 ) continue; + else for( int z=zStart ; z2 ) continue; + else if( neighbors5.neighbors[x][y][z] && neighbors5.neighbors[x][y][z]->nodeData.nodeIndex>=0 ) + count++; + return count; + } + template< int Degree > + int Octree< Degree >::SetMatrixRow( const OctNode< TreeNodeData , Real >::Neighbors5& neighbors5 , MatrixEntry< float >* row , int offset , const double stencil[5][5][5] ) const + { + return SetMatrixRow( neighbors5 , row , offset , stencil , 0 , 5 , 0 , 5 , 0 , 5 ); + } + template< int Degree > + int Octree< Degree >::SetMatrixRow( const OctNode< TreeNodeData , Real >::Neighbors5& neighbors5 , MatrixEntry< float >* row , int offset , const double stencil[5][5][5] , int xStart , int xEnd , int yStart , int yEnd , int zStart , int zEnd ) const + { + bool hasPoints[3][3]; + Real diagonal = 0; + PointInfo samples[3][3][3]; + + int count = 0; + const TreeOctNode* node = neighbors5.neighbors[2][2][2]; + int index[] = { int( node->off[0] ) , int( node->off[1] ), int( node->off[2] ) }; + + if( _constrainValues ) + { + int d , idx[3]; + node->depthAndOffset( d , idx ); + idx[0] = BinaryNode< double >::CenterIndex( d , idx[0] ); + idx[1] = BinaryNode< double >::CenterIndex( d , idx[1] ); + idx[2] = BinaryNode< double >::CenterIndex( d , idx[2] ); + for( int j=0 ; j<3 ; j++ ) for( int k=0 ; k<3 ; k++ ) + { + hasPoints[j][k] = false; + for( int l=0 ; l<3 ; l++ ) + { + const TreeOctNode* _node = neighbors5.neighbors[j+1][k+1][l+1]; + if( _node && _node->nodeData.pointIndex!=-1 ) + { + const PointData& pData = _points[ _node->nodeData.pointIndex ]; + PointInfo& pointInfo = samples[j][k][l]; + Real weight = pData.weight; + Point3D< Real > p = pData.position; + for( int s=0 ; s<3 ; s++ ) + { + pointInfo.splineValues[0][s] = float( fData.baseBSplines[ idx[0]+j-s][s]( p[0] ) ); + pointInfo.splineValues[1][s] = float( fData.baseBSplines[ idx[1]+k-s][s]( p[1] ) ); + pointInfo.splineValues[2][s] = float( fData.baseBSplines[ idx[2]+l-s][s]( p[2] ) ); + } + float value = pointInfo.splineValues[0][j] * pointInfo.splineValues[1][k] * pointInfo.splineValues[2][l]; + diagonal += value * value * weight; + pointInfo.weightedValue = value * weight; + for( int s=0 ; s<3 ; s++ ) pointInfo.splineValues[0][s] *= pointInfo.weightedValue; + hasPoints[j][k] = true; + } + else samples[j][k][l].weightedValue = 0; + } + } + } + + bool isInterior; + int d , off[3]; + neighbors5.neighbors[2][2][2]->depthAndOffset( d , off ); + int mn = 2 , mx = (1<=mn && off[0]=mn && off[1]=mn && off[2]2 ) continue; + else for( int z=zStart ; z2 ) continue; + else if( neighbors5.neighbors[x][y][z] && neighbors5.neighbors[x][y][z]->nodeData.nodeIndex>=0 ) + { + const TreeOctNode* _node = neighbors5.neighbors[x][y][z]; + int _index[] = { int( _node->off[0] ) , int( _node->off[1] ), int( _node->off[2] ) }; + Real temp; + if( isInterior ) temp = Real( stencil[x][y][z] ); + else temp = GetLaplacian( node , _node ); + if( _constrainValues ) + { + int _d[] = { _index[0]-index[0] , _index[1]-index[1] , _index[2]-index[2] }; + if( x==2 && y==2 && z==2 ) temp += diagonal; + else temp += GetValue( samples , hasPoints , _d ); + } + if( x==2 && y==2 && z==2 ) temp /= 2; + if( fabs(temp)>MATRIX_ENTRY_EPSILON ) + { + row[count].N = _node->nodeData.nodeIndex-offset; + row[count].Value = temp; + count++; + } + } + return count; + } + template< int Degree > + void Octree< Degree >::SetDivergenceStencil( int depth , Point3D< double > *stencil , bool scatter ) const + { + int offset[] = { 2 , 2 , 2 }; + short d , off[3]; + TreeOctNode::Index( depth , offset , d , off ); + int index1[3] , index2[3]; + if( scatter ) index2[0] = int( off[0] ) , index2[1] = int( off[1] ) , index2[2] = int( off[2] ); + else index1[0] = int( off[0] ) , index1[1] = int( off[1] ) , index1[2] = int( off[2] ); + for( int x=0 ; x<5 ; x++ ) for( int y=0 ; y<5 ; y++ ) for( int z=0 ; z<5 ; z++ ) + { + int _offset[] = { x , y , z }; + TreeOctNode::Index( depth , _offset , d , off ); + if( scatter ) index1[0] = int( off[0] ) , index1[1] = int( off[1] ) , index1[2] = int( off[2] ); + else index2[0] = int( off[0] ) , index2[1] = int( off[1] ) , index2[2] = int( off[2] ); + int symIndex[] = + { + BSplineData< Degree , Real >::SymmetricIndex( index1[0] , index2[0] ) , + BSplineData< Degree , Real >::SymmetricIndex( index1[1] , index2[1] ) , + BSplineData< Degree , Real >::SymmetricIndex( index1[2] , index2[2] ) , + }; + int aSymIndex[] = + { + #if GRADIENT_DOMAIN_SOLUTION + // Take the dot-product of the vector-field with the gradient of the basis function + fData.Index( index1[0] , index2[0] ) , + fData.Index( index1[1] , index2[1] ) , + fData.Index( index1[2] , index2[2] ) + #else // !GRADIENT_DOMAIN_SOLUTION + // Take the dot-product of the divergence of the vector-field with the basis function + fData.Index( index2[0] , index1[0] ) , + fData.Index( index2[1] , index1[1] ) , + fData.Index( index2[2] , index1[2] ) + #endif // GRADIENT_DOMAIN_SOLUTION + }; + + double dot = fData.vvDotTable[symIndex[0]] * fData.vvDotTable[symIndex[1]] * fData.vvDotTable[symIndex[2]]; +#if GRADIENT_DOMAIN_SOLUTION + Point3D temp; + temp[0] = fData.dvDotTable[aSymIndex[0]] * dot; + temp[1] = fData.dvDotTable[aSymIndex[1]] * dot; + temp[2] = fData.dvDotTable[aSymIndex[2]] * dot; + stencil[25*x + 5*y + z] = temp; + // stencil[x][y][z][0] = fData.dvDotTable[aSymIndex[0]] * dot; + // stencil[x][y][z][1] = fData.dvDotTable[aSymIndex[1]] * dot; + // stencil[x][y][z][2] = fData.dvDotTable[aSymIndex[2]] * dot; +#else // !GRADIENT_DOMAIN_SOLUTION + Point3D temp; + temp[0] = -fData.dvDotTable[aSymIndex[0]] * dot; + temp[1] = -fData.dvDotTable[aSymIndex[1]] * dot; + temp[2] = -fData.dvDotTable[aSymIndex[2]] * dot; + stencil[25*x + 5*y + z] = temp; + // stencil[x][y][z][0] = -fData.dvDotTable[aSymIndex[0]] * dot; + // stencil[x][y][z][1] = -fData.dvDotTable[aSymIndex[1]] * dot; + // stencil[x][y][z][2] = -fData.dvDotTable[aSymIndex[2]] * dot; +#endif // GRADIENT_DOMAIN_SOLUTION + } + } + template< int Degree > + void Octree< Degree >::SetLaplacianStencil( int depth , double stencil[5][5][5] ) const + { + int offset[] = { 2 , 2 , 2 }; + short d , off[3]; + TreeOctNode::Index( depth , offset , d , off ); + int index[] = { int( off[0] ) , int( off[1] ) , int( off[2] ) }; + for( int x=0 ; x<5 ; x++ ) for( int y=0 ; y<5 ; y++ ) for( int z=0 ; z<5 ; z++ ) + { + int _offset[] = { x , y , z }; + short _d , _off[3]; + TreeOctNode::Index( depth , _offset , _d , _off ); + int _index[] = { int( _off[0] ) , int( _off[1] ) , int( _off[2] ) }; + int symIndex[3]; + symIndex[0] = BSplineData< Degree , Real >::SymmetricIndex( index[0] , _index[0] ); + symIndex[1] = BSplineData< Degree , Real >::SymmetricIndex( index[1] , _index[1] ); + symIndex[2] = BSplineData< Degree , Real >::SymmetricIndex( index[2] , _index[2] ); + stencil[x][y][z] = GetLaplacian( symIndex ); + } + } + template< int Degree > + void Octree< Degree >::SetLaplacianStencils( int depth , Stencil< double , 5 > stencils[2][2][2] ) const + { + if( depth<=1 ) return; + for( int i=0 ; i<2 ; i++ ) for( int j=0 ; j<2 ; j++ ) for( int k=0 ; k<2 ; k++ ) + { + short d , off[3]; + int offset[] = { 4+i , 4+j , 4+k }; + TreeOctNode::Index( depth , offset , d , off ); + int index[] = { int( off[0] ) , int( off[1] ) , int( off[2] ) }; + for( int x=0 ; x<5 ; x++ ) for( int y=0 ; y<5 ; y++ ) for( int z=0 ; z<5 ; z++ ) + { + int _offset[] = { x , y , z }; + short _d , _off[3]; + TreeOctNode::Index( depth-1 , _offset , _d , _off ); + int _index[] = { int( _off[0] ) , int( _off[1] ) , int( _off[2] ) }; + int symIndex[3]; + symIndex[0] = BSplineData< Degree , Real >::SymmetricIndex( index[0] , _index[0] ); + symIndex[1] = BSplineData< Degree , Real >::SymmetricIndex( index[1] , _index[1] ); + symIndex[2] = BSplineData< Degree , Real >::SymmetricIndex( index[2] , _index[2] ); + stencils[i][j][k].values[x][y][z] = GetLaplacian( symIndex ); + } + } + } + template< int Degree > + void Octree< Degree >::SetDivergenceStencils( int depth , Stencil< Point3D< double > , 5 > stencils[2][2][2] , bool scatter ) const + { + if( depth<=1 ) return; + int index1[3] , index2[3]; + for( int i=0 ; i<2 ; i++ ) for( int j=0 ; j<2 ; j++ ) for( int k=0 ; k<2 ; k++ ) + { + short d , off[3]; + int offset[] = { 4+i , 4+j , 4+k }; + TreeOctNode::Index( depth , offset , d , off ); + if( scatter ) index2[0] = int( off[0] ) , index2[1] = int( off[1] ) , index2[2] = int( off[2] ); + else index1[0] = int( off[0] ) , index1[1] = int( off[1] ) , index1[2] = int( off[2] ); + for( int x=0 ; x<5 ; x++ ) for( int y=0 ; y<5 ; y++ ) for( int z=0 ; z<5 ; z++ ) + { + int _offset[] = { x , y , z }; + TreeOctNode::Index( depth-1 , _offset , d , off ); + if( scatter ) index1[0] = int( off[0] ) , index1[1] = int( off[1] ) , index1[2] = int( off[2] ); + else index2[0] = int( off[0] ) , index2[1] = int( off[1] ) , index2[2] = int( off[2] ); + + int symIndex[] = + { + BSplineData< Degree , Real >::SymmetricIndex( index1[0] , index2[0] ) , + BSplineData< Degree , Real >::SymmetricIndex( index1[1] , index2[1] ) , + BSplineData< Degree , Real >::SymmetricIndex( index1[2] , index2[2] ) , + }; + int aSymIndex[] = + { + #if GRADIENT_DOMAIN_SOLUTION + // Take the dot-product of the vector-field with the gradient of the basis function + fData.Index( index1[0] , index2[0] ) , + fData.Index( index1[1] , index2[1] ) , + fData.Index( index1[2] , index2[2] ) + #else // !GRADIENT_DOMAIN_SOLUTION + // Take the dot-product of the divergence of the vector-field with the basis function + fData.Index( index2[0] , index1[0] ) , + fData.Index( index2[1] , index1[1] ) , + fData.Index( index2[2] , index1[2] ) + #endif // GRADIENT_DOMAIN_SOLUTION + }; + double dot = fData.vvDotTable[symIndex[0]] * fData.vvDotTable[symIndex[1]] * fData.vvDotTable[symIndex[2]]; +#if GRADIENT_DOMAIN_SOLUTION + stencils[i][j][k].values[x][y][z][0] = fData.dvDotTable[aSymIndex[0]] * dot; + stencils[i][j][k].values[x][y][z][1] = fData.dvDotTable[aSymIndex[1]] * dot; + stencils[i][j][k].values[x][y][z][2] = fData.dvDotTable[aSymIndex[2]] * dot; +#else // !GRADIENT_DOMAIN_SOLUTION + stencils[i][j][k].values[x][y][z][0] = -fData.dvDotTable[aSymIndex[0]] * dot; + stencils[i][j][k].values[x][y][z][1] = -fData.dvDotTable[aSymIndex[1]] * dot; + stencils[i][j][k].values[x][y][z][2] = -fData.dvDotTable[aSymIndex[2]] * dot; +#endif // GRADIENT_DOMAIN_SOLUTION + } + } + } + template< int Degree > + void Octree< Degree >::SetEvaluationStencils( int depth , Stencil< double , 3 > stencil1[8] , Stencil< double , 3 > stencil2[8][8] ) const + { + if( depth>2 ) + { + int idx[3]; + int off[] = { 2 , 2 , 2 }; + for( int c=0 ; c<8 ; c++ ) + { + VertexData::CornerIndex( depth , off , c , fData.depth , idx ); + idx[0] *= fData.functionCount , idx[1] *= fData.functionCount , idx[2] *= fData.functionCount; + for( int x=0 ; x<3 ; x++ ) for( int y=0 ; y<3 ; y++ ) for( int z=0 ; z<3 ; z++ ) + { + short _d , _off[3]; + int _offset[] = { x+1 , y+1 , z+1 }; + TreeOctNode::Index( depth , _offset , _d , _off ); + stencil1[c].values[x][y][z] = fData.valueTables[ idx[0]+int(_off[0]) ] * fData.valueTables[ idx[1]+int(_off[1]) ] * fData.valueTables[ idx[2]+int(_off[2]) ]; + } + } + } + if( depth>3 ) + for( int _c=0 ; _c<8 ; _c++ ) + { + int idx[3]; + int _cx , _cy , _cz; + Cube::FactorCornerIndex( _c , _cx , _cy , _cz ); + int off[] = { 4+_cx , 4+_cy , 4+_cz }; + for( int c=0 ; c<8 ; c++ ) + { + VertexData::CornerIndex( depth , off , c , fData.depth , idx ); + idx[0] *= fData.functionCount , idx[1] *= fData.functionCount , idx[2] *= fData.functionCount; + for( int x=0 ; x<3 ; x++ ) for( int y=0 ; y<3 ; y++ ) for( int z=0 ; z<3 ; z++ ) + { + short _d , _off[3]; + int _offset[] = { x+1 , y+1 , z+1 }; + TreeOctNode::Index( depth-1 , _offset , _d , _off ); + stencil2[_c][c].values[x][y][z] = fData.valueTables[ idx[0]+int(_off[0]) ] * fData.valueTables[ idx[1]+int(_off[1]) ] * fData.valueTables[ idx[2]+int(_off[2]) ]; + } + } + } + } + template< int Degree > + void Octree< Degree >::UpdateCoarserSupportBounds( const TreeOctNode* node , int& startX , int& endX , int& startY , int& endY , int& startZ , int& endZ ) + { + if( node->parent ) + { + int x , y , z , c = int( node - node->parent->children ); + Cube::FactorCornerIndex( c , x , y , z ); + if( x==0 ) endX = 4; + else startX = 1; + if( y==0 ) endY = 4; + else startY = 1; + if( z==0 ) endZ = 4; + else startZ = 1; + } + } + + template< int Degree > + void Octree< Degree >::UpdateConstraintsFromCoarser( const OctNode< TreeNodeData , Real >::NeighborKey5& neighborKey5 , TreeOctNode* node , Real* metSolution , const Stencil< double , 5 >& lapStencil ) const + { + bool isInterior; + { + int d , off[3]; + node->depthAndOffset( d , off ); + int mn = 4 , mx = (1<=mn && off[0]=mn && off[1]=mn && off[2]depth(); + if( depth<=_minDepth ) return; + int i = node->nodeData.nodeIndex; + // Offset the constraints using the solution from lower resolutions. + int startX = 0 , endX = 5 , startY = 0 , endY = 5 , startZ = 0 , endZ = 5; + UpdateCoarserSupportBounds( node , startX , endX , startY , endY , startZ , endZ ); + + const TreeOctNode::Neighbors5& neighbors5 = neighborKey5.neighbors[depth-1]; + for( int x=startX ; xnodeData.nodeIndex>=0 ) + { + const TreeOctNode* _node = neighbors5.neighbors[x][y][z]; + Real _solution = metSolution[ _node->nodeData.nodeIndex ]; + { + if( isInterior ) node->nodeData.constraint -= Real( lapStencil.values[x][y][z] * _solution ); + else node->nodeData.constraint -= GetLaplacian( _node , node ) * _solution; + } + } + if( _constrainValues ) + { + int d , idx[3]; + node->depthAndOffset( d, idx ); + idx[0] = BinaryNode< double >::CenterIndex( d , idx[0] ); + idx[1] = BinaryNode< double >::CenterIndex( d , idx[1] ); + idx[2] = BinaryNode< double >::CenterIndex( d , idx[2] ); + const TreeOctNode::Neighbors5& neighbors5 = neighborKey5.neighbors[depth]; + for( int x=1 ; x<4 ; x++ ) for( int y=1 ; y<4 ; y++ ) for( int z=1 ; z<4 ; z++ ) + if( neighbors5.neighbors[x][y][z] && neighbors5.neighbors[x][y][z]->nodeData.pointIndex!=-1 ) + { + const PointData& pData = _points[ neighbors5.neighbors[x][y][z]->nodeData.pointIndex ]; + Real pointValue = pData.value; + Point3D< Real > p = pData.position; + node->nodeData.constraint -= + Real( + fData.baseBSplines[idx[0]][x-1]( p[0] ) * + fData.baseBSplines[idx[1]][y-1]( p[1] ) * + fData.baseBSplines[idx[2]][z-1]( p[2] ) * + pointValue + ); + } + } + } + struct UpSampleData + { + int start; + double v[2]; + UpSampleData( void ) { start = 0 , v[0] = v[1] = 0.; } + UpSampleData( int s , double v1 , double v2 ) { start = s , v[0] = v1 , v[1] = v2; } + }; + template< int Degree > + void Octree< Degree >::UpSampleCoarserSolution( int depth , const SortedTreeNodes& sNodes , Vector< Real >& Solution ) const + { + int start = sNodes.nodeCount[depth] , end = sNodes.nodeCount[depth+1] , range = end-start; + Solution.Resize( range ); + if( !depth ) return; + else if( depth==1 ) for( int i=start ; inodeData.solution; + else + { + // For every node at the current depth +#pragma omp parallel for num_threads( threads ) + for( int t=0 ; tdepthAndOffset( d , off ); + for( int d=0 ; d<3 ; d++ ) + { + if ( off[d] ==0 ) usData[d] = UpSampleData( 1 , 1.00 , 0.00 ); + else if( off[d]+1==(1<nodeData.solution * dxyz ); + } + } + } + } + } + } + // Clear the coarser solution + start = sNodes.nodeCount[depth-1] , end = sNodes.nodeCount[depth] , range = end-start; +#pragma omp parallel for num_threads( threads ) + for( int i=start ; inodeData.solution = Real( 0. ); + } + template< int Degree > + void Octree< Degree >::DownSampleFinerConstraints( int depth , SortedTreeNodes& sNodes ) const + { + if( !depth ) return; +#pragma omp parallel for num_threads( threads ) + for( int i=sNodes.nodeCount[depth-1] ; inodeData.constraint = Real( 0 ); + + if( depth==1 ) + { + sNodes.treeNodes[0]->nodeData.constraint = Real( 0 ); + for( int i=sNodes.nodeCount[depth] ; inodeData.constraint += sNodes.treeNodes[i]->nodeData.constraint; + return; + } + std::vector< Vector< double > > constraints( threads ); + for( int t=0 ; tdepthAndOffset( d , off ); + for( int d=0 ; d<3 ; d++ ) + { + if ( off[d] ==0 ) usData[d] = UpSampleData( 1 , 1.00 , 0.00 ); + else if( off[d]+1==(1<nodeData.nodeIndex-lStart] += sNodes.treeNodes[i]->nodeData.constraint * dxyz; + } + } + } + } + } +#pragma omp parallel for num_threads( threads ) + for( int i=lStart ; inodeData.constraint += cSum; + } + } + template< int Degree > + template< class C > + void Octree< Degree >::DownSample( int depth , const SortedTreeNodes& sNodes , C* constraints ) const + { + if( depth==0 ) return; + if( depth==1 ) + { + for( int i=sNodes.nodeCount[1] ; i > _constraints( threads ); + for( int t=0 ; tdepthAndOffset( d , off ); + for( int d=0 ; d<3 ; d++ ) + { + if ( off[d] ==0 ) usData[d] = UpSampleData( 1 , 1.00 , 0.00 ); + else if( off[d]+1==(1<parent ); + C c = constraints[i]; + for( int ii=0 ; ii<2 ; ii++ ) + { + int _ii = ii + usData[0].start; + C cx = C( c*usData[0].v[ii] ); + for( int jj=0 ; jj<2 ; jj++ ) + { + int _jj = jj + usData[1].start; + C cxy = C( cx*usData[1].v[jj] ); + for( int kk=0 ; kk<2 ; kk++ ) + { + int _kk = kk + usData[2].start; + if( neighbors.neighbors[_ii][_jj][_kk] ) + _constraints[t][neighbors.neighbors[_ii][_jj][_kk]->nodeData.nodeIndex-lStart] += C( cxy*usData[2].v[kk] ); + } + } + } + } + } +#pragma omp parallel for num_threads( threads ) + for( int i=lStart ; i + template< class C > + void Octree< Degree >::UpSample( int depth , const SortedTreeNodes& sNodes , C* coefficients ) const + { + if ( depth==0 ) return; + else if( depth==1 ) + { + for( int i=sNodes.nodeCount[1] ; idepthAndOffset( d , off ); + for( int d=0 ; d<3 ; d++ ) + { + if ( off[d] ==0 ) usData[d] = UpSampleData( 1 , 1.00 , 0.00 ); + else if( off[d]+1==(1<parent ); + for( int ii=0 ; ii<2 ; ii++ ) + { + int _ii = ii + usData[0].start; + double dx = usData[0].v[ii]; + for( int jj=0 ; jj<2 ; jj++ ) + { + int _jj = jj + usData[1].start; + double dxy = dx * usData[1].v[jj]; + for( int kk=0 ; kk<2 ; kk++ ) + { + int _kk = kk + usData[2].start; + if( neighbors.neighbors[_ii][_jj][_kk] ) + { + double dxyz = dxy * usData[2].v[kk]; + int _i = neighbors.neighbors[_ii][_jj][_kk]->nodeData.nodeIndex; + coefficients[i] += coefficients[_i] * Real( dxyz ); + } + } + } + } + } + } + } + template< int Degree > + void Octree< Degree >::SetCoarserPointValues( int depth , const SortedTreeNodes& sNodes , Real* metSolution ) + { + int start = sNodes.nodeCount[depth] , end = sNodes.nodeCount[depth+1] , range = end-start; + // For every node at the current depth +#pragma omp parallel for num_threads( threads ) + for( int t=0 ; tnodeData.pointIndex; + if( pIdx!=-1 ) + { + neighborKey.getNeighbors( sNodes.treeNodes[i] ); + _points[ pIdx ].value = WeightedCoarserFunctionValue( neighborKey , sNodes.treeNodes[i] , metSolution ); + } + } + } + } + template< int Degree > + Real Octree< Degree >::WeightedCoarserFunctionValue( const OctNode< TreeNodeData , Real >::NeighborKey3& neighborKey , const TreeOctNode* pointNode , Real* metSolution ) const + { + int depth = pointNode->depth(); + if( !depth || pointNode->nodeData.pointIndex==-1 ) return Real(0.); + double pointValue = 0; + + Real weight = _points[ pointNode->nodeData.pointIndex ].weight; + Point3D< Real > p = _points[ pointNode->nodeData.pointIndex ].position; + + // Iterate over all basis functions that overlap the point at the coarser resolutions + { + int d , _idx[3]; + const TreeOctNode::Neighbors3& neighbors = neighborKey.neighbors[depth-1]; + neighbors.neighbors[1][1][1]->depthAndOffset( d , _idx ); + _idx[0] = BinaryNode< double >::CenterIndex( d , _idx[0]-1 ); + _idx[1] = BinaryNode< double >::CenterIndex( d , _idx[1]-1 ); + _idx[2] = BinaryNode< double >::CenterIndex( d , _idx[2]-1 ); + for( int j=0 ; j<3 ; j++ ) for( int k=0 ; k<3 ; k++ ) for( int l=0 ; l<3 ; l++ ) + if( neighbors.neighbors[j][k][l] && neighbors.neighbors[j][k][l]->nodeData.nodeIndex>=0 ) + { + // Accumulate the contribution from these basis nodes + const TreeOctNode* basisNode = neighbors.neighbors[j][k][l]; + int idx[] = { _idx[0]+j , _idx[1]+k , _idx[2]+l }; + pointValue += + fData.baseBSplines[ idx[0] ][2-j]( p[0] ) * + fData.baseBSplines[ idx[1] ][2-k]( p[1] ) * + fData.baseBSplines[ idx[2] ][2-l]( p[2] ) * + metSolution[basisNode->nodeData.nodeIndex]; + } + } + return Real( pointValue * weight ); + } + template + int Octree::GetFixedDepthLaplacian( SparseSymmetricMatrix< Real >& matrix , int depth , const SortedTreeNodes& sNodes , Real* metSolution ) + { + int start = sNodes.nodeCount[depth] , end = sNodes.nodeCount[depth+1] , range = end-start; + double stencil[5][5][5]; + SetLaplacianStencil( depth , stencil ); + Stencil< double , 5 > stencils[2][2][2]; + SetLaplacianStencils( depth , stencils ); + matrix.Resize( range ); +#pragma omp parallel for num_threads( threads ) + for( int t=0 ; tparent ) + { + c = int( node - node->parent->children ); + Cube::FactorCornerIndex( c , x , y , z ); + } + else x = y = z = 0; + UpdateConstraintsFromCoarser( neighborKey5 , node , metSolution , stencils[x][y][z] ); + } + } + return 1; + } + template + int Octree::GetRestrictedFixedDepthLaplacian( SparseSymmetricMatrix< Real >& matrix,int depth,const int* entries,int entryCount, + const TreeOctNode* rNode , Real radius , + const SortedTreeNodes& sNodes , Real* metSolution ) + { + for( int i=0 ; inodeData.nodeIndex = i; + double stencil[5][5][5]; + int rDepth , rOff[3]; + rNode->depthAndOffset( rDepth , rOff ); + matrix.Resize( entryCount ); + SetLaplacianStencil( depth , stencil ); + Stencil< double , 5 > stencils[2][2][2]; + SetLaplacianStencils( depth , stencils ); +#pragma omp parallel for num_threads( threads ) + for( int t=0 ; tdepthAndOffset( d , off ); + off[0] >>= (depth-rDepth) , off[1] >>= (depth-rDepth) , off[2] >>= (depth-rDepth); + bool isInterior = ( off[0]==rOff[0] && off[1]==rOff[1] && off[2]==rOff[2] ); + + neighborKey5.getNeighbors( node ); + + int xStart=0 , xEnd=5 , yStart=0 , yEnd=5 , zStart=0 , zEnd=5; + if( !isInterior ) SetMatrixRowBounds( neighborKey5.neighbors[depth].neighbors[2][2][2] , rDepth , rOff , xStart , xEnd , yStart , yEnd , zStart , zEnd ); + + // Get the matrix row size + int count = GetMatrixRowSize( neighborKey5.neighbors[depth] , xStart , xEnd , yStart , yEnd , zStart , zEnd ); + + // Allocate memory for the row +#pragma omp critical (matrix_set_row_size) + { + matrix.SetRowSize( i , count ); + } + + // Set the matrix row entries + matrix.rowSizes[i] = SetMatrixRow( neighborKey5.neighbors[depth] , matrix[i] , 0 , stencil , xStart , xEnd , yStart , yEnd , zStart , zEnd ); + // Adjust the system constraints + int x , y , z , c; + if( node->parent ) + { + c = int( node - node->parent->children ); + Cube::FactorCornerIndex( c , x , y , z ); + } + else x = y = z = 0; + UpdateConstraintsFromCoarser( neighborKey5 , node , metSolution , stencils[x][y][z] ); + } + } + for( int i=0 ; inodeData.nodeIndex = entries[i]; + return 1; + } + + template + int Octree::LaplacianMatrixIteration( int subdivideDepth , bool showResidual , int minIters , double accuracy ) + { + int i,iter=0; + double t = 0; + fData.setDotTables( fData.DD_DOT_FLAG | fData.DV_DOT_FLAG ); + + SparseMatrix< float >::SetAllocator( MEMORY_ALLOCATOR_BLOCK_SIZE ); + _sNodes.treeNodes[0]->nodeData.solution = 0; + + std::vector< Real > metSolution( _sNodes.nodeCount[ _sNodes.maxDepth ] , 0 ); + + for( i=1 ; i<_sNodes.maxDepth ; i++ ) + { + if( subdivideDepth>0 ) iter += SolveFixedDepthMatrix( i , _sNodes , &metSolution[0] , subdivideDepth , showResidual , minIters , accuracy ); + else iter += SolveFixedDepthMatrix( i , _sNodes , &metSolution[0] , showResidual , minIters , accuracy ); + } + SparseMatrix< float >::internalAllocator.reset(); + fData.clearDotTables( fData.VV_DOT_FLAG | fData.DV_DOT_FLAG | fData.DD_DOT_FLAG ); + + return iter; + } + + template + int Octree::SolveFixedDepthMatrix( int depth , const SortedTreeNodes& sNodes , Real* metSolution , bool showResidual , int minIters , double accuracy ) + { + int iter = 0; + Vector< Real > X , B; + SparseSymmetricMatrix< Real > M; + double systemTime=0. , solveTime=0. , updateTime=0. , evaluateTime = 0.; + + X.Resize( sNodes.nodeCount[depth+1]-sNodes.nodeCount[depth] ); + if( depth<=_minDepth ) UpSampleCoarserSolution( depth , sNodes , X ); + else + { + // Up-sample the cumulative solution into the previous depth + UpSample( depth-1 , sNodes , metSolution ); + // Add in the solution from that depth + if( depth ) +#pragma omp parallel for num_threads( threads ) + for( int i=_sNodes.nodeCount[depth-1] ; i<_sNodes.nodeCount[depth] ; i++ ) metSolution[i] += _sNodes.treeNodes[i]->nodeData.solution; + } + if( _constrainValues ) + { + SetCoarserPointValues( depth , sNodes , metSolution ); + } + + SparseSymmetricMatrix< Real >::internalAllocator.rollBack(); + { + int maxECount = ( (2*Degree+1)*(2*Degree+1)*(2*Degree+1) + 1 ) / 2; + maxECount = ( ( maxECount + 15 ) / 16 ) * 16; + M.Resize( sNodes.nodeCount[depth+1]-sNodes.nodeCount[depth] ); + for( int i=0 ; i::internalAllocator.rollBack(); + GetFixedDepthLaplacian( M , depth , sNodes , metSolution ); + // Set the constraint vector + B.Resize( sNodes.nodeCount[depth+1]-sNodes.nodeCount[depth] ); + for( int i=sNodes.nodeCount[depth] ; inodeData.constraint; + } + + // Solve the linear system + iter += SparseSymmetricMatrix< Real >::Solve( M , B , std::max< int >( int( pow( M.rows , ITERATION_POWER ) ) , minIters ) , X , Real(accuracy) , 0 , threads , (depth<=_minDepth) && !_constrainValues ); + + if( showResidual ) + { + double mNorm = 0; + for( int i=0 ; i %g (%f) [%d]\n" , M.Entries() , sqrt(mNorm) , bNorm , rNorm , rNorm/bNorm , iter ); + } + + // Copy the solution back into the tree (over-writing the constraints) + for( int i=sNodes.nodeCount[depth] ; inodeData.solution = Real( X[i-sNodes.nodeCount[depth]] ); + + return iter; + } + template + int Octree::SolveFixedDepthMatrix( int depth , const SortedTreeNodes& sNodes , Real* metSolution , int startingDepth , bool showResidual , int minIters , double accuracy ) + { + if( startingDepth>=depth ) return SolveFixedDepthMatrix( depth , sNodes , metSolution , showResidual , minIters , accuracy ); + + int i , j , d , tIter=0; + SparseSymmetricMatrix< Real > _M; + Vector< Real > B , B_ , X_; + AdjacencySetFunction asf; + AdjacencyCountFunction acf; + double systemTime = 0 , solveTime = 0 , memUsage = 0 , evaluateTime = 0 , gTime = 0, sTime = 0; + Real myRadius , myRadius2; + + if( depth>_minDepth ) + { + // Up-sample the cumulative solution into the previous depth + UpSample( depth-1 , sNodes , metSolution ); + // Add in the solution from that depth + if( depth ) +#pragma omp parallel for num_threads( threads ) + for( int i=_sNodes.nodeCount[depth-1] ; i<_sNodes.nodeCount[depth] ; i++ ) metSolution[i] += _sNodes.treeNodes[i]->nodeData.solution; + } + + if( _constrainValues ) + { + SetCoarserPointValues( depth , sNodes , metSolution ); + } + B.Resize( sNodes.nodeCount[depth+1] - sNodes.nodeCount[depth] ); + + // Back-up the constraints + for( i=sNodes.nodeCount[depth] ; inodeData.constraint; + sNodes.treeNodes[i]->nodeData.constraint = 0; + } + + myRadius = 2*radius-Real(0.5); + myRadius = int(myRadius-ROUND_EPS)+ROUND_EPS; + myRadius2 = Real(radius+ROUND_EPS-0.5); + d = depth-startingDepth; + std::vector< int > subDimension( sNodes.nodeCount[d+1]-sNodes.nodeCount[d] ); + int maxDimension = 0; + for( i=sNodes.nodeCount[d] ; inextNode() ; temp ; ) + { + if( temp->depth()==depth ) acf.adjacencyCount++ , temp = sNodes.treeNodes[i]->nextBranch( temp ); + else temp = sNodes.treeNodes[i]->nextNode ( temp ); + } + for( j=sNodes.nodeCount[d] ; j( maxDimension , subDimension[i-sNodes.nodeCount[d]] ); + } + asf.adjacencies = new int[maxDimension]; + MapReduceVector< Real > mrVector; + mrVector.resize( threads , maxDimension ); + // Iterate through the coarse-level nodes + for( i=sNodes.nodeCount[d] ; inextNode() ; temp ; ) + { + if( temp->depth()==depth ) asf.adjacencies[ asf.adjacencyCount++ ] = temp->nodeData.nodeIndex , temp = sNodes.treeNodes[i]->nextBranch( temp ); + else temp = sNodes.treeNodes[i]->nextNode ( temp ); + } + for( j=sNodes.nodeCount[d] ; jnodeData.solution; + } + // Get the associated matrix + SparseSymmetricMatrix< Real >::internalAllocator.rollBack(); + GetRestrictedFixedDepthLaplacian( _M , depth , asf.adjacencies , asf.adjacencyCount , sNodes.treeNodes[i] , myRadius , sNodes , metSolution ); +#pragma omp parallel for num_threads( threads ) schedule( static ) + for( j=0 ; jnodeData.constraint; + sNodes.treeNodes[ asf.adjacencies[j] ]->nodeData.constraint = 0; + } + + // Solve the matrix + // Since we don't have the full matrix, the system shouldn't be singular, so we shouldn't have to correct it + iter += SparseSymmetricMatrix< Real >::Solve( _M , B_ , std::max< int >( int( pow( _M.rows , ITERATION_POWER ) ) , minIters ) , X_ , mrVector , Real(accuracy) , 0 ); + + if( showResidual ) + { + double mNorm = 0; + for( int i=0 ; i<_M.rows ; i++ ) for( int j=0 ; j<_M.rowSizes[i] ; j++ ) mNorm += _M[i][j].Value * _M[i][j].Value; + double bNorm = B_.Norm( 2 ) , rNorm = ( B_ - _M * X_ ).Norm( 2 ); + printf( "\t\tResidual: (%d %g) %g -> %g (%f) [%d]\n" , _M.Entries() , sqrt(mNorm) , bNorm , rNorm , rNorm/bNorm , iter ); + } + + // Update the solution for all nodes in the sub-tree + for( j=0 ; jdepth()>sNodes.treeNodes[i]->depth() ) temp=temp->parent; + if( temp->nodeData.nodeIndex>=sNodes.treeNodes[i]->nodeData.nodeIndex ) sNodes.treeNodes[ asf.adjacencies[j] ]->nodeData.solution = Real( X_[j] ); + } + systemTime += gTime; + solveTime += sTime; + memUsage = std::max< double >( MemoryUsage() , memUsage ); + tIter += iter; + } + delete[] asf.adjacencies; + return tIter; + } + template + int Octree::HasNormals(TreeOctNode* node,Real epsilon) + { + int hasNormals=0; + if( node->nodeData.normalIndex>=0 && ( (*normals)[node->nodeData.normalIndex][0]!=0 || (*normals)[node->nodeData.normalIndex][1]!=0 || (*normals)[node->nodeData.normalIndex][2]!=0 ) ) hasNormals=1; + if( node->children ) for(int i=0;ichildren[i],epsilon); + + return hasNormals; + } + template + void Octree::ClipTree( void ) + { + int maxDepth = tree.maxDepth(); + for( TreeOctNode* temp=tree.nextNode() ; temp ; temp=tree.nextNode(temp) ) + if( temp->children && temp->d>=_minDepth ) + { + int hasNormals=0; + for( int i=0 ; ichildren[i] , EPSILON/(1<children=NULL; + } + MemoryUsage(); + } + template + void Octree::SetLaplacianConstraints( void ) + { + // To set the Laplacian constraints, we iterate over the + // splatted normals and compute the dot-product of the + // divergence of the normal field with all the basis functions. + // Within the same depth: set directly as a gather + // Coarser depths + fData.setDotTables( fData.VV_DOT_FLAG | fData.DV_DOT_FLAG ); + + int maxDepth = _sNodes.maxDepth-1; + Point3D< Real > zeroPoint; + zeroPoint[0] = zeroPoint[1] = zeroPoint[2] = 0; + std::vector< Real > constraints( _sNodes.nodeCount[maxDepth] , Real(0) ); + std::vector< Point3D< Real > > coefficients( _sNodes.nodeCount[maxDepth] , zeroPoint ); + + // Clear the constraints +#pragma omp parallel for num_threads( threads ) + for( int i=0 ; i<_sNodes.nodeCount[maxDepth+1] ; i++ ) _sNodes.treeNodes[i]->nodeData.constraint = Real( 0. ); + + // For the scattering part of the operation, we parallelize by duplicating the constraints and then summing at the end. + std::vector< std::vector< Real > > _constraints( threads ); + for( int t=0 ; t=0 ; d-- ) + { + Point3D< double > stencil[5][5][5]; + SetDivergenceStencil( d , &stencil[0][0][0] , false ); + Stencil< Point3D< double > , 5 > stencils[2][2][2]; + SetDivergenceStencils( d , stencils , true ); +#pragma omp parallel for num_threads( threads ) + for( int t=0 ; tdepth(); + neighborKey5.getNeighbors( node ); + + bool isInterior , isInterior2; + { + int d , off[3]; + node->depthAndOffset( d , off ); + int mn = 2 , mx = (1<=mn && off[0]=mn && off[1]=mn && off[2]=mn && off[0]=mn && off[1]=mn && off[2]parent->children ); + Cube::FactorCornerIndex( c , cx , cy , cz ); + } + else cx = cy = cz = 0; + Stencil< Point3D< double > , 5 >& _stencil = stencils[cx][cy][cz]; + + // Set constraints from current depth + { + const TreeOctNode::Neighbors5& neighbors5 = neighborKey5.neighbors[depth]; + + if( isInterior ) + for( int x=startX ; xnodeData.normalIndex>=0 ) + { + const Point3D< Real >& _normal = (*normals)[_node->nodeData.normalIndex]; + node->nodeData.constraint += Real( stencil[x][y][z][0] * _normal[0] + stencil[x][y][z][1] * _normal[1] + stencil[x][y][z][2] * _normal[2] ); + } + } + else + for( int x=startX ; xnodeData.normalIndex>=0 ) + { + const Point3D< Real >& _normal = (*normals)[_node->nodeData.normalIndex]; + node->nodeData.constraint += GetDivergence( _node , node , _normal ); + } + } + UpdateCoarserSupportBounds( neighbors5.neighbors[2][2][2] , startX , endX , startY , endY , startZ , endZ ); + } + if( node->nodeData.nodeIndex<0 || node->nodeData.normalIndex<0 ) continue; + const Point3D< Real >& normal = (*normals)[node->nodeData.normalIndex]; + if( normal[0]==0 && normal[1]==0 && normal[2]==0 ) continue; + if( depth& div = _stencil.values[x][y][z]; + _constraints[t][ _node->nodeData.nodeIndex ] += Real( div[0] * normal[0] + div[1] * normal[1] + div[2] * normal[2] ); + } + else _constraints[t][ _node->nodeData.nodeIndex ] += GetDivergence( node , _node , normal ); + } + } + } + } + } +#pragma omp parallel for num_threads( threads ) schedule( static ) + for( int i=0 ; i<_sNodes.nodeCount[maxDepth] ; i++ ) + { + Real cSum = Real(0.); + for( int t=0 ; t=0 ; d-- ) DownSample( d , _sNodes , &constraints[0] ); + + // Coarse-to-fine up-sampling of coefficients + for( int d=0 ; dnodeData.constraint += constraints[i]; + + // Compute the contribution from all coarser depths + for( int d=0 ; d<=maxDepth ; d++ ) + { + int start = _sNodes.nodeCount[d] , end = _sNodes.nodeCount[d+1] , range = end - start; + Stencil< Point3D< double > , 5 > stencils[2][2][2]; + SetDivergenceStencils( d , stencils , false ); +#pragma omp parallel for num_threads( threads ) + for( int t=0 ; tdepth(); + if( !depth ) continue; + int startX=0 , endX=5 , startY=0 , endY=5 , startZ=0 , endZ=5; + UpdateCoarserSupportBounds( node , startX , endX , startY , endY , startZ , endZ ); + const TreeOctNode::Neighbors5& neighbors5 = neighborKey5.getNeighbors( node->parent ); + + bool isInterior; + { + int d , off[3]; + node->depthAndOffset( d , off ); + int mn = 4 , mx = (1<=mn && off[0]=mn && off[1]=mn && off[2]parent->children ); + Cube::FactorCornerIndex( c , cx , cy , cz ); + } + else cx = cy = cz = 0; + Stencil< Point3D< double > , 5 >& _stencil = stencils[cx][cy][cz]; + + Real constraint = Real(0); + for( int x=startX ; xnodeData.nodeIndex; + if( isInterior ) + { + Point3D< double >& div = _stencil.values[x][y][z]; + Point3D< Real >& normal = coefficients[_i]; + constraint += Real( div[0] * normal[0] + div[1] * normal[1] + div[2] * normal[2] ); + } + else constraint += GetDivergence( _node , node , coefficients[_i] ); + } + node->nodeData.constraint += constraint; + } + } + } + + fData.clearDotTables( fData.DV_DOT_FLAG ); + + // Set the point weights for evaluating the iso-value +#pragma omp parallel for num_threads( threads ) + for( int t=0 ; tnodeData.nodeIndex<0 || temp->nodeData.normalIndex<0 ) temp->nodeData.centerWeightContribution = 0; + else temp->nodeData.centerWeightContribution = Real( Length((*normals)[temp->nodeData.normalIndex]) ); + } + MemoryUsage(); + delete normals; + normals = NULL; + } + template + void Octree::AdjacencyCountFunction::Function(const TreeOctNode* node1,const TreeOctNode* node2){adjacencyCount++;} + template + void Octree::AdjacencySetFunction::Function(const TreeOctNode* node1,const TreeOctNode* node2){adjacencies[adjacencyCount++]=node1->nodeData.nodeIndex;} + template + void Octree::RefineFunction::Function( TreeOctNode* node1 , const TreeOctNode* node2 ) + { + if( !node1->children && node1->depth()initChildren(); + } + template< int Degree > + void Octree< Degree >::FaceEdgesFunction::Function( const TreeOctNode* node1 , const TreeOctNode* node2 ) + { + if( !node1->children && MarchingCubes::HasRoots( node1->nodeData.mcIndex ) ) + { + RootInfo ri1 , ri2; + hash_map< long long , std::pair< RootInfo , int > >::iterator iter; + int isoTri[DIMENSION*MarchingCubes::MAX_TRIANGLES]; + int count=MarchingCubes::AddTriangleIndices( node1->nodeData.mcIndex , isoTri ); + + for( int j=0 ; jpush_back( std::pair< RootInfo , RootInfo >( ri2 , ri1 ) ); + iter = vertexCount->find( key1 ); + if( iter==vertexCount->end() ) + { + (*vertexCount)[key1].first = ri1; + (*vertexCount)[key1].second=0; + } + iter=vertexCount->find(key2); + if( iter==vertexCount->end() ) + { + (*vertexCount)[key2].first = ri2; + (*vertexCount)[key2].second=0; + } + (*vertexCount)[key1].second--; + (*vertexCount)[key2].second++; + } + else fprintf( stderr , "Bad Edge 1: %d %d\n" , ri1.key , ri2.key ); + } + } + + template< int Degree > + void Octree< Degree >::RefineBoundary( int subdivideDepth ) + { + // This implementation is somewhat tricky. + // We would like to ensure that leaf-nodes across a subdivision boundary have the same depth. + // We do this by calling the setNeighbors function. + // The key is to implement this in a single pass through the leaves, ensuring that refinements don't propogate. + // To this end, we do the minimal refinement that ensures that a cross boundary neighbor, and any of its cross-boundary + // neighbors are all refined simultaneously. + // For this reason, the implementation can only support nodes deeper than sDepth. + bool flags[3][3][3]; + int maxDepth = tree.maxDepth(); + + int sDepth; + if( subdivideDepth<=0 ) sDepth = 0; + else sDepth = maxDepth-subdivideDepth; + if( sDepth<=0 ) return; + + // Ensure that face adjacent neighbors across the subdivision boundary exist to allow for + // a consistent definition of the iso-surface + TreeOctNode::NeighborKey3 nKey; + nKey.set( maxDepth ); + for( TreeOctNode* leaf=tree.nextLeaf() ; leaf ; leaf=tree.nextLeaf( leaf ) ) + if( leaf->depth()>sDepth ) + { + int d , off[3] , _off[3]; + leaf->depthAndOffset( d , off ); + int res = (1< + void Octree::GetMCIsoTriangles( Real isoValue , int subdivideDepth , CoredMeshData* mesh , int fullDepthIso , int nonLinearFit , bool addBarycenter , bool polygonMesh ) + { + fData.setValueTables( fData.VALUE_FLAG | fData.D_VALUE_FLAG , 0 , postNormalSmooth ); + + // Ensure that the subtrees are self-contained + RefineBoundary( subdivideDepth ); + + RootData rootData , coarseRootData; + std::vector< Point3D< float > >* interiorPoints; + int maxDepth = tree.maxDepth(); + + int sDepth = subdivideDepth<=0 ? 0 : std::max< int >( 0 , maxDepth-subdivideDepth ); + + std::vector< Real > metSolution( _sNodes.nodeCount[maxDepth] , 0 ); +#pragma omp parallel for num_threads( threads ) + for( int i=_sNodes.nodeCount[_minDepth] ; i<_sNodes.nodeCount[maxDepth] ; i++ ) metSolution[i] = _sNodes.treeNodes[i]->nodeData.solution; + for( int d=0 ; dnodeData.mcIndex = 0; + + rootData.boundaryValues = new hash_map< long long , std::pair< Real , Point3D< Real > > >(); + int offSet = 0; + + int maxCCount = _sNodes.getMaxCornerCount( &tree , sDepth , maxDepth , threads ); + int maxECount = _sNodes.getMaxEdgeCount ( &tree , sDepth , threads ); + rootData.cornerValues = new Real [ maxCCount ]; + rootData.cornerNormals = new Point3D< Real >[ maxCCount ]; + rootData.interiorRoots = new int [ maxECount ]; + rootData.cornerValuesSet = new char[ maxCCount ]; + rootData.cornerNormalsSet = new char[ maxCCount ]; + rootData.edgesSet = new char[ maxECount ]; + _sNodes.setCornerTable( coarseRootData , &tree , sDepth , threads ); + coarseRootData.cornerValues = new Real[ coarseRootData.cCount ]; + coarseRootData.cornerNormals = new Point3D< Real >[ coarseRootData.cCount ]; + coarseRootData.cornerValuesSet = new char[ coarseRootData.cCount ]; + coarseRootData.cornerNormalsSet = new char[ coarseRootData.cCount ]; + memset( coarseRootData.cornerValuesSet , 0 , sizeof( char ) * coarseRootData.cCount ); + memset( coarseRootData.cornerNormalsSet , 0 , sizeof( char ) * coarseRootData.cCount ); + MemoryUsage(); + + std::vector< TreeOctNode::ConstNeighborKey3 > nKeys( threads ); + for( int t=0 ; t nKeys5( threads ); + for( int t=0 ; tchildren ) continue; + + _sNodes.setCornerTable( rootData , _sNodes.treeNodes[i] , threads ); + _sNodes.setEdgeTable ( rootData , _sNodes.treeNodes[i] , threads ); + memset( rootData.cornerValuesSet , 0 , sizeof( char ) * rootData.cCount ); + memset( rootData.cornerNormalsSet , 0 , sizeof( char ) * rootData.cCount ); + memset( rootData.edgesSet , 0 , sizeof( char ) * rootData.eCount ); + interiorPoints = new std::vector< Point3D< float > >(); + for( int d=maxDepth ; d>sDepth ; d-- ) + { + int leafNodeCount = 0; + std::vector< TreeOctNode* > leafNodes; + for( TreeOctNode* node=_sNodes.treeNodes[i]->nextLeaf() ; node ; node=_sNodes.treeNodes[i]->nextLeaf( node ) ) if( node->d==d ) leafNodeCount++; + leafNodes.reserve( leafNodeCount ); + for( TreeOctNode* node=_sNodes.treeNodes[i]->nextLeaf() ; node ; node=_sNodes.treeNodes[i]->nextLeaf( node ) ) if( node->d==d ) leafNodes.push_back( node ); + Stencil< double , 3 > stencil1[8] , stencil2[8][8]; + SetEvaluationStencils( d , stencil1 , stencil2 ); + + // First set the corner values and associated marching-cube indices +#pragma omp parallel for num_threads( threads ) + for( int t=0 ; tdepthAndOffset( d , off ); + int res = 1<<(d-sDepth); + off[0] %= res , off[1] %=res , off[2] %= res; + res--; + if( !(off[0]%res) && !(off[1]%res) && !(off[2]%res) ) + { + const TreeOctNode* temp = leaf; + while( temp->d!=sDepth ) temp = temp->parent; + int x = off[0]==0 ? 0 : 1 , y = off[1]==0 ? 0 : 1 , z = off[2]==0 ? 0 : 1; + int c = Cube::CornerIndex( x , y , z ); + int idx = coarseRootData.cornerIndices( temp )[ c ]; + coarseRootData.cornerValues[ idx ] = rootData.cornerValues[ rootData.cornerIndices( leaf )[c] ]; + coarseRootData.cornerValuesSet[ idx ] = true; + } + + // Compute the iso-vertices + if( MarchingCubes::HasRoots( leaf->nodeData.mcIndex ) ) + SetMCRootPositions( leaf , sDepth , isoValue , nKeys5[t] , rootData , interiorPoints , mesh , &metSolution[0] , nonLinearFit ); + } + // Note that this should be broken off for multi-threading as + // the SetMCRootPositions writes to interiorPoints (with lockupdateing) + // while GetMCIsoTriangles reads from interiorPoints (without locking) +#if MISHA_DEBUG + std::vector< Point3D< float > > barycenters; + std::vector< Point3D< float > >* barycenterPtr = addBarycenter ? & barycenters : NULL; +#endif // MISHA_DEBUG +#pragma omp parallel for num_threads( threads ) + for( int t=0 ; tnodeData.mcIndex ) ) +#if MISHA_DEBUG + GetMCIsoTriangles( leaf , mesh , rootData , interiorPoints , offSet , sDepth , polygonMesh , barycenterPtr ); +#else // !MISHA_DEBUG + GetMCIsoTriangles( leaf , mesh , rootData , interiorPoints , offSet , sDepth , addBarycenter , polygonMesh ); +#endif // MISHA_DEBUG + } +#if MISHA_DEBUG + for( int i=0 ; ipush_back( barycenters[i] ); +#endif // MISHA_DEBUG + } + offSet = mesh->outOfCorePointCount(); +#if 1 + delete interiorPoints; +#endif + } + MemoryUsage(); + delete[] rootData.cornerValues , delete[] rootData.cornerNormals , rootData.cornerValues = NULL , rootData.cornerNormals = NULL; + delete[] rootData.cornerValuesSet , delete[] rootData.cornerNormalsSet , rootData.cornerValuesSet = NULL , rootData.cornerNormalsSet = NULL; + delete[] rootData.interiorRoots ; rootData.interiorRoots = NULL; + delete[] rootData.edgesSet ; rootData.edgesSet = NULL; + coarseRootData.interiorRoots = NULL; + coarseRootData.boundaryValues = rootData.boundaryValues; + for( poisson::hash_map< long long , int >::iterator iter=rootData.boundaryRoots.begin() ; iter!=rootData.boundaryRoots.end() ; iter++ ) + coarseRootData.boundaryRoots[iter->first] = iter->second; + + for( int d=sDepth ; d>=0 ; d-- ) + { + Stencil< double , 3 > stencil1[8] , stencil2[8][8]; + SetEvaluationStencils( d , stencil1 , stencil2 ); +#if MISHA_DEBUG + std::vector< Point3D< float > > barycenters; + std::vector< Point3D< float > >* barycenterPtr = addBarycenter ? &barycenters : NULL; +#endif // MISHA_DEBUG + for( int i=_sNodes.nodeCount[d] ; i<_sNodes.nodeCount[d+1] ; i++ ) + { + TreeOctNode* leaf = _sNodes.treeNodes[i]; + if( leaf->children ) continue; + + // First set the corner values and associated marching-cube indices + SetIsoCorners( isoValue , leaf , coarseRootData , coarseRootData.cornerValuesSet , coarseRootData.cornerValues , nKey , &metSolution[0] , stencil1 , stencil2 ); + + // Now compute the iso-vertices + if( MarchingCubes::HasRoots( leaf->nodeData.mcIndex ) ) + { + SetMCRootPositions( leaf , 0 , isoValue , nKey5 , coarseRootData , NULL , mesh , &metSolution[0] , nonLinearFit ); +#if MISHA_DEBUG + GetMCIsoTriangles( leaf , mesh , coarseRootData , NULL , 0 , 0 , polygonMesh , barycenterPtr ); +#else // !MISHA_DEBUG + GetMCIsoTriangles( leaf , mesh , coarseRootData , NULL , 0 , 0 , addBarycenter , polygonMesh ); +#endif // MISHA_DEBUG + } + } + } + MemoryUsage(); + + delete[] coarseRootData.cornerValues , delete[] coarseRootData.cornerNormals; + delete[] coarseRootData.cornerValuesSet , delete[] coarseRootData.cornerNormalsSet; + delete rootData.boundaryValues; + } + template + Real Octree::getCenterValue( const OctNode< TreeNodeData , Real >::ConstNeighborKey3& neighborKey , const TreeOctNode* node){ + int idx[3]; + Real value=0; + + VertexData::CenterIndex(node,fData.depth,idx); + idx[0]*=fData.functionCount; + idx[1]*=fData.functionCount; + idx[2]*=fData.functionCount; + int minDepth = std::max< int >( 0 , std::min< int >( _minDepth , node->depth()-1 ) ); + for( int i=minDepth ; i<=node->depth() ; i++ ) + for(int j=0;j<3;j++) + for(int k=0;k<3;k++) + for(int l=0;l<3;l++) + { + const TreeOctNode* n=neighborKey.neighbors[i].neighbors[j][k][l]; + if( n ) + { + Real temp=n->nodeData.solution; + value+=temp*Real( + fData.valueTables[idx[0]+int(n->off[0])]* + fData.valueTables[idx[1]+int(n->off[1])]* + fData.valueTables[idx[2]+int(n->off[2])]); + } + } + if(node->children) + { + for(int i=0;ichildren[i]; + while(1){ + value+=n->nodeData.solution*Real( + fData.valueTables[idx[0]+int(n->off[0])]* + fData.valueTables[idx[1]+int(n->off[1])]* + fData.valueTables[idx[2]+int(n->off[2])]); + if( n->children ) n=&n->children[ii]; + else break; + } + } + } + return value; + } + template< int Degree > + Real Octree< Degree >::getCornerValue( const OctNode< TreeNodeData , Real >::ConstNeighborKey3& neighborKey3 , const TreeOctNode* node , int corner , const Real* metSolution ) + { + int idx[3]; + double value = 0; + + VertexData::CornerIndex( node , corner , fData.depth , idx ); + idx[0] *= fData.functionCount; + idx[1] *= fData.functionCount; + idx[2] *= fData.functionCount; + + int d = node->depth(); + int cx , cy , cz; + int startX = 0 , endX = 3 , startY = 0 , endY = 3 , startZ = 0 , endZ = 3; + Cube::FactorCornerIndex( corner , cx , cy , cz ); + { + TreeOctNode::ConstNeighbors3& neighbors = neighborKey3.neighbors[d]; + if( cx==0 ) endX = 2; + else startX = 1; + if( cy==0 ) endY = 2; + else startY = 1; + if( cz==0 ) endZ = 2; + else startZ = 1; + for( int x=startX ; xoff[0]) ]* + fData.valueTables[ idx[1]+int(n->off[1]) ]* + fData.valueTables[ idx[2]+int(n->off[2]) ]; + value += n->nodeData.solution * v; + } + } + } + if( d>0 && d>_minDepth ) + { + int _corner = int( node - node->parent->children ); + int _cx , _cy , _cz; + Cube::FactorCornerIndex( _corner , _cx , _cy , _cz ); + if( cx!=_cx ) startX = 0 , endX = 3; + if( cy!=_cy ) startY = 0 , endY = 3; + if( cz!=_cz ) startZ = 0 , endZ = 3; + TreeOctNode::ConstNeighbors3& neighbors = neighborKey3.neighbors[d-1]; + for( int x=startX ; xoff[0]) ]* + fData.valueTables[ idx[1]+int(n->off[1]) ]* + fData.valueTables[ idx[2]+int(n->off[2]) ]; + value += metSolution[ n->nodeData.nodeIndex ] * v; + } + } + } + return Real( value ); + } + template< int Degree > + Real Octree< Degree >::getCornerValue( const OctNode< TreeNodeData , Real >::ConstNeighborKey3& neighborKey3 , const TreeOctNode* node , int corner , const Real* metSolution , const double stencil1[3][3][3] , const double stencil2[3][3][3] ) + { + double value = 0; + int d = node->depth(); + int cx , cy , cz; + int startX = 0 , endX = 3 , startY = 0 , endY = 3 , startZ = 0 , endZ = 3; + Cube::FactorCornerIndex( corner , cx , cy , cz ); + { + TreeOctNode::ConstNeighbors3& neighbors = neighborKey3.neighbors[d]; + if( cx==0 ) endX = 2; + else startX = 1; + if( cy==0 ) endY = 2; + else startY = 1; + if( cz==0 ) endZ = 2; + else startZ = 1; + for( int x=startX ; xnodeData.solution * stencil1[x][y][z]; + } + } + if( d>0 && d>_minDepth ) + { + int _corner = int( node - node->parent->children ); + int _cx , _cy , _cz; + Cube::FactorCornerIndex( _corner , _cx , _cy , _cz ); + if( cx!=_cx ) startX = 0 , endX = 3; + if( cy!=_cy ) startY = 0 , endY = 3; + if( cz!=_cz ) startZ = 0 , endZ = 3; + TreeOctNode::ConstNeighbors3& neighbors = neighborKey3.neighbors[d-1]; + for( int x=startX ; xnodeData.nodeIndex ] * stencil2[x][y][z]; + } + } + return Real( value ); + } + template< int Degree > + Point3D< Real > Octree< Degree >::getCornerNormal( const OctNode< TreeNodeData , Real >::ConstNeighborKey5& neighborKey5 , const TreeOctNode* node , int corner , const Real* metSolution ) + { + int idx[3]; + Point3D< Real > normal; + normal[0] = normal[1] = normal[2] = 0.; + + VertexData::CornerIndex( node , corner , fData.depth , idx ); + idx[0] *= fData.functionCount; + idx[1] *= fData.functionCount; + idx[2] *= fData.functionCount; + + int d = node->depth(); + // Iterate over all ancestors that can overlap the corner + { + TreeOctNode::ConstNeighbors5& neighbors = neighborKey5.neighbors[d]; + for( int j=0 ; j<5 ; j++ ) for( int k=0 ; k<5 ; k++ ) for( int l=0 ; l<5 ; l++ ) + { + const TreeOctNode* n=neighbors.neighbors[j][k][l]; + if( n ) + { + int _idx[] = { idx[0] + n->off[0] , idx[1] + n->off[1] , idx[2] + n->off[2] }; + double values[] = { fData.valueTables[_idx[0]] , fData.valueTables[_idx[1]] , fData.valueTables[_idx[2]] }; + double dValues[] = { fData.dValueTables[_idx[0]] , fData.dValueTables[_idx[1]] , fData.dValueTables[_idx[2]] }; + Real solution = n->nodeData.solution; + normal[0] += Real( dValues[0] * values[1] * values[2] * solution ); + normal[1] += Real( values[0] * dValues[1] * values[2] * solution ); + normal[2] += Real( values[0] * values[1] * dValues[2] * solution ); + } + } + } + if( d>0 && d>_minDepth ) + { + TreeOctNode::ConstNeighbors5& neighbors = neighborKey5.neighbors[d-1]; + for( int j=0 ; j<5 ; j++ ) for( int k=0 ; k<5 ; k++ ) for( int l=0 ; l<5 ; l++ ) + { + const TreeOctNode* n=neighbors.neighbors[j][k][l]; + if( n ) + { + int _idx[] = { idx[0] + n->off[0] , idx[1] + n->off[1] , idx[2] + n->off[2] }; + double values[] = { fData.valueTables[_idx[0]] , fData.valueTables[_idx[1]] , fData.valueTables[_idx[2]] }; + double dValues[] = { fData.dValueTables[_idx[0]] , fData.dValueTables[_idx[1]] , fData.dValueTables[_idx[2]] }; + Real solution = metSolution[ n->nodeData.nodeIndex ]; + normal[0] += Real( dValues[0] * values[1] * values[2] * solution ); + normal[1] += Real( values[0] * dValues[1] * values[2] * solution ); + normal[2] += Real( values[0] * values[1] * dValues[2] * solution ); + } + } + } + return normal; + } + template< int Degree > + Real Octree::GetIsoValue( void ) + { + Real isoValue , weightSum; + + neighborKey2.set( fData.depth ); + fData.setValueTables( fData.VALUE_FLAG , 0 ); + + isoValue = weightSum = 0; +#pragma omp parallel for num_threads( threads ) reduction( + : isoValue , weightSum ) + for( int t=0 ; tnodeData.centerWeightContribution; + if( w!=0 ) + { + isoValue += getCenterValue( nKey , temp ) * w; + weightSum += w; + } + } + } + return isoValue/weightSum; + } + + template< int Degree > + void Octree< Degree >::SetIsoCorners( Real isoValue , TreeOctNode* leaf , SortedTreeNodes::CornerTableData& cData , char* valuesSet , Real* values , TreeOctNode::ConstNeighborKey3& nKey , const Real* metSolution , const Stencil< double , 3 > stencil1[8] , const Stencil< double , 3 > stencil2[8][8] ) + { + Real cornerValues[ Cube::CORNERS ]; + const SortedTreeNodes::CornerIndices& cIndices = cData[ leaf ]; + + bool isInterior; + int d , off[3]; + leaf->depthAndOffset( d , off ); + int mn = 2 , mx = (1<=mn && off[0]=mn && off[1]=mn && off[2]parent->children)][c].values ); + else cornerValues[c] = getCornerValue( nKey , leaf , c , metSolution ); + values[vIndex] = cornerValues[c]; + valuesSet[vIndex] = 1; + } + } + + leaf->nodeData.mcIndex = MarchingCubes::GetIndex( cornerValues , isoValue ); + + // Set the marching cube indices for all interior nodes. + if( leaf->parent ) + { + TreeOctNode* parent = leaf->parent; + int c = int( leaf - leaf->parent->children ); + int mcid = leaf->nodeData.mcIndex & (1<nodeData.mcIndex, mcid); + + while( 1 ) + { + if( parent->parent && parent->parent->d>=_minDepth && (parent-parent->parent->children)==c ) + { + poisson::atomicOr(parent->parent->nodeData.mcIndex, mcid); + parent = parent->parent; + } + else break; + } + } + } + } + + + template + int Octree::InteriorFaceRootCount(const TreeOctNode* node,const int &faceIndex,int maxDepth){ + int c1,c2,e1,e2,dir,off,cnt=0; + int corners[Cube::CORNERS/2]; + if(node->children){ + Cube::FaceCorners(faceIndex,corners[0],corners[1],corners[2],corners[3]); + Cube::FactorFaceIndex(faceIndex,dir,off); + c1=corners[0]; + c2=corners[3]; + switch(dir){ + case 0: + e1=Cube::EdgeIndex(1,off,1); + e2=Cube::EdgeIndex(2,off,1); + break; + case 1: + e1=Cube::EdgeIndex(0,off,1); + e2=Cube::EdgeIndex(2,1,off); + break; + case 2: + e1=Cube::EdgeIndex(0,1,off); + e2=Cube::EdgeIndex(1,1,off); + break; + }; + cnt+=EdgeRootCount(&node->children[c1],e1,maxDepth)+EdgeRootCount(&node->children[c1],e2,maxDepth); + switch(dir){ + case 0: + e1=Cube::EdgeIndex(1,off,0); + e2=Cube::EdgeIndex(2,off,0); + break; + case 1: + e1=Cube::EdgeIndex(0,off,0); + e2=Cube::EdgeIndex(2,0,off); + break; + case 2: + e1=Cube::EdgeIndex(0,0,off); + e2=Cube::EdgeIndex(1,0,off); + break; + }; + cnt+=EdgeRootCount(&node->children[c2],e1,maxDepth)+EdgeRootCount(&node->children[c2],e2,maxDepth); + for(int i=0;ichildren[corners[i]].children){cnt+=InteriorFaceRootCount(&node->children[corners[i]],faceIndex,maxDepth);}} + } + return cnt; + } + + template + int Octree::EdgeRootCount(const TreeOctNode* node,int edgeIndex,int maxDepth){ + int f1,f2,c1,c2; + const TreeOctNode* temp; + Cube::FacesAdjacentToEdge(edgeIndex,f1,f2); + + int eIndex; + const TreeOctNode* finest=node; + eIndex=edgeIndex; + if(node->depth()faceNeighbor(f1); + if(temp && temp->children){ + finest=temp; + eIndex=Cube::FaceReflectEdgeIndex(edgeIndex,f1); + } + else{ + temp=node->faceNeighbor(f2); + if(temp && temp->children){ + finest=temp; + eIndex=Cube::FaceReflectEdgeIndex(edgeIndex,f2); + } + else{ + temp=node->edgeNeighbor(edgeIndex); + if(temp && temp->children){ + finest=temp; + eIndex=Cube::EdgeReflectEdgeIndex(edgeIndex); + } + } + } + } + + Cube::EdgeCorners(eIndex,c1,c2); + if(finest->children) return EdgeRootCount(&finest->children[c1],eIndex,maxDepth)+EdgeRootCount(&finest->children[c2],eIndex,maxDepth); + else return MarchingCubes::HasEdgeRoots(finest->nodeData.mcIndex,eIndex); + } + template + int Octree::IsBoundaryFace(const TreeOctNode* node,int faceIndex,int subdivideDepth){ + int dir,offset,d,o[3],idx; + + if(subdivideDepth<0){return 0;} + if(node->d<=subdivideDepth){return 1;} + Cube::FactorFaceIndex(faceIndex,dir,offset); + node->depthAndOffset(d,o); + + idx=(int(o[dir])<<1) + (offset<<1); + return !(idx%(2<<(int(node->d)-subdivideDepth))); + } + template + int Octree::IsBoundaryEdge(const TreeOctNode* node,int edgeIndex,int subdivideDepth){ + int dir,x,y; + Cube::FactorEdgeIndex(edgeIndex,dir,x,y); + return IsBoundaryEdge(node,dir,x,y,subdivideDepth); + } + template + int Octree::IsBoundaryEdge( const TreeOctNode* node , int dir , int x , int y , int subdivideDepth ) + { + int d , o[3] , idx1 , idx2 , mask; + + if( subdivideDepth<0 ) return 0; + if( node->d<=subdivideDepth ) return 1; + node->depthAndOffset( d , o ); + + switch( dir ) + { + case 0: + idx1 = o[1] + x; + idx2 = o[2] + y; + break; + case 1: + idx1 = o[0] + x; + idx2 = o[2] + y; + break; + case 2: + idx1 = o[0] + x; + idx2 = o[1] + y; + break; + } + mask = 1<<( int(node->d) - subdivideDepth ); + return !(idx1%(mask)) || !(idx2%(mask)); + } + template< int Degree > + void Octree< Degree >::GetRootSpan( const RootInfo& ri , Point3D< float >& start , Point3D< float >& end ) + { + int o , i1 , i2; + Real width; + Point3D< Real > c; + + Cube::FactorEdgeIndex( ri.edgeIndex , o , i1 , i2 ); + ri.node->centerAndWidth( c , width ); + switch(o) + { + case 0: + start[0] = c[0] - width/2; + end [0] = c[0] + width/2; + start[1] = end[1] = c[1] - width/2 + width*i1; + start[2] = end[2] = c[2] - width/2 + width*i2; + break; + case 1: + start[0] = end[0] = c[0] - width/2 + width*i1; + start[1] = c[1] - width/2; + end [1] = c[1] + width/2; + start[2] = end[2] = c[2] - width/2 + width*i2; + break; + case 2: + start[0] = end[0] = c[0] - width/2 + width*i1; + start[1] = end[1] = c[1] - width/2 + width*i2; + start[2] = c[2] - width/2; + end [2] = c[2] + width/2; + break; + } + } + ////////////////////////////////////////////////////////////////////////////////////// + // The assumption made when calling this code is that the edge has at most one root // + ////////////////////////////////////////////////////////////////////////////////////// + template< int Degree > + int Octree< Degree >::GetRoot( const RootInfo& ri , Real isoValue , TreeOctNode::ConstNeighborKey5& neighborKey5 , Point3D< Real > & position , RootData& rootData , int sDepth , const Real* metSolution , int nonLinearFit ) + { + if( !MarchingCubes::HasRoots( ri.node->nodeData.mcIndex ) ) return 0; + int c1 , c2; + Cube::EdgeCorners( ri.edgeIndex , c1 , c2 ); + if( !MarchingCubes::HasEdgeRoots( ri.node->nodeData.mcIndex , ri.edgeIndex ) ) return 0; + + long long key1 , key2; + Point3D< Real > n[2]; + + int i , o , i1 , i2 , rCount=0; + Polynomial<2> P; + std::vector< double > roots; + double x0 , x1; + Real center , width; + Real averageRoot=0; + Cube::FactorEdgeIndex( ri.edgeIndex , o , i1 , i2 ); + int idx1[3] , idx2[3]; + key1 = VertexData::CornerIndex( ri.node , c1 , fData.depth , idx1 ); + key2 = VertexData::CornerIndex( ri.node , c2 , fData.depth , idx2 ); + + bool isBoundary = ( IsBoundaryEdge( ri.node , ri.edgeIndex , sDepth )!=0 ); + bool haveKey1 , haveKey2; + std::pair< Real , Point3D< Real > > keyValue1 , keyValue2; + int iter1 , iter2; + { + iter1 = rootData.cornerIndices( ri.node )[ c1 ]; + iter2 = rootData.cornerIndices( ri.node )[ c2 ]; + keyValue1.first = rootData.cornerValues[iter1]; + keyValue2.first = rootData.cornerValues[iter2]; + if( isBoundary ) + { +#pragma omp critical (normal_hash_access) + { + haveKey1 = ( rootData.boundaryValues->find( key1 )!=rootData.boundaryValues->end() ); + haveKey2 = ( rootData.boundaryValues->find( key2 )!=rootData.boundaryValues->end() ); + if( haveKey1 ) keyValue1 = (*rootData.boundaryValues)[key1]; + if( haveKey2 ) keyValue2 = (*rootData.boundaryValues)[key2]; + } + } + else + { + haveKey1 = ( rootData.cornerNormalsSet[ iter1 ] != 0 ); + haveKey2 = ( rootData.cornerNormalsSet[ iter2 ] != 0 ); + keyValue1.first = rootData.cornerValues[iter1]; + keyValue2.first = rootData.cornerValues[iter2]; + if( haveKey1 ) keyValue1.second = rootData.cornerNormals[iter1]; + if( haveKey2 ) keyValue2.second = rootData.cornerNormals[iter2]; + } + } + if( !haveKey1 || !haveKey2 ) neighborKey5.getNeighbors( ri.node ); + if( !haveKey1 ) keyValue1.second = getCornerNormal( neighborKey5 , ri.node , c1 , metSolution ); + x0 = keyValue1.first; + n[0] = keyValue1.second; + + if( !haveKey2 ) keyValue2.second = getCornerNormal( neighborKey5 , ri.node , c2 , metSolution ); + x1 = keyValue2.first; + n[1] = keyValue2.second; + + if( !haveKey1 || !haveKey2 ) + { + if( isBoundary ) + { +#pragma omp critical (normal_hash_access) + { + if( !haveKey1 ) (*rootData.boundaryValues)[key1] = keyValue1; + if( !haveKey2 ) (*rootData.boundaryValues)[key2] = keyValue2; + } + } + else + { + if( !haveKey1 ) rootData.cornerNormals[iter1] = keyValue1.second , rootData.cornerNormalsSet[ iter1 ] = 1; + if( !haveKey2 ) rootData.cornerNormals[iter2] = keyValue2.second , rootData.cornerNormalsSet[ iter2 ] = 1; + } + } + + Point3D< Real > c; + ri.node->centerAndWidth(c,width); + center=c[o]; + for( i=0 ; i=0 && roots[i]<=1 ) + { + averageRoot += Real( roots[i] ); + rCount++; + } + if( rCount && nonLinearFit ) averageRoot /= rCount; + else averageRoot = Real((x0-isoValue)/(x0-x1)); + if( averageRoot<0 || averageRoot>1 ) + { + fprintf( stderr , "[WARNING] Bad average root: %f\n" , averageRoot ); + fprintf( stderr , "\t(%f %f) , (%f %f) (%f)\n" , x0 , x1 , dx0 , dx1 , isoValue ); + if( averageRoot<0 ) averageRoot = 0; + if( averageRoot>1 ) averageRoot = 1; + } + position[o] = Real(center-width/2+width*averageRoot); + return 1; + } + template< int Degree > + int Octree< Degree >::GetRootIndex( const TreeOctNode* node , int edgeIndex , int maxDepth , int sDepth,RootInfo& ri ) + { + int c1,c2,f1,f2; + const TreeOctNode *temp,*finest; + int finestIndex; + + Cube::FacesAdjacentToEdge(edgeIndex,f1,f2); + + finest=node; + finestIndex=edgeIndex; + if(node->depth()faceNeighbor(f1);} + if(temp && temp->children){ + finest=temp; + finestIndex=Cube::FaceReflectEdgeIndex(edgeIndex,f1); + } + else{ + if(IsBoundaryFace(node,f2,sDepth)){temp=NULL;} + else{temp=node->faceNeighbor(f2);} + if(temp && temp->children){ + finest=temp; + finestIndex=Cube::FaceReflectEdgeIndex(edgeIndex,f2); + } + else{ + if(IsBoundaryEdge(node,edgeIndex,sDepth)){temp=NULL;} + else{temp=node->edgeNeighbor(edgeIndex);} + if(temp && temp->children){ + finest=temp; + finestIndex=Cube::EdgeReflectEdgeIndex(edgeIndex); + } + } + } + } + + Cube::EdgeCorners(finestIndex,c1,c2); + if(finest->children){ + if (GetRootIndex(&finest->children[c1],finestIndex,maxDepth,sDepth,ri)) {return 1;} + else if (GetRootIndex(&finest->children[c2],finestIndex,maxDepth,sDepth,ri)) {return 1;} + else + { + fprintf( stderr , "[WARNING] Couldn't find root index with either child\n" ); + return 0; + } + } + else + { + if( !(MarchingCubes::edgeMask()[finest->nodeData.mcIndex] & (1<depthAndOffset(d,off); + ri.node=finest; + ri.edgeIndex=finestIndex; + int eIndex[2],offset; + offset=BinaryNode::Index( d , off[o] ); + switch(o) + { + case 0: + eIndex[0]=BinaryNode::CornerIndex(maxDepth+1,d,off[1],i1); + eIndex[1]=BinaryNode::CornerIndex(maxDepth+1,d,off[2],i2); + break; + case 1: + eIndex[0]=BinaryNode::CornerIndex(maxDepth+1,d,off[0],i1); + eIndex[1]=BinaryNode::CornerIndex(maxDepth+1,d,off[2],i2); + break; + case 2: + eIndex[0]=BinaryNode::CornerIndex(maxDepth+1,d,off[0],i1); + eIndex[1]=BinaryNode::CornerIndex(maxDepth+1,d,off[1],i2); + break; + } + ri.key = (long long)(o) | (long long)(eIndex[0])<<5 | (long long)(eIndex[1])<<25 | (long long)(offset)<<45; + return 1; + } + } + template + int Octree::GetRootIndex( const TreeOctNode* node , int edgeIndex , int maxDepth , RootInfo& ri ) + { + int c1,c2,f1,f2; + const TreeOctNode *temp,*finest; + int finestIndex; + + + // The assumption is that the super-edge has a root along it. + if(!(MarchingCubes::edgeMask()[node->nodeData.mcIndex] & (1<depth()children ) + { + temp=node->faceNeighbor( f1 ); + if( temp && temp->children ) finest = temp , finestIndex = Cube::FaceReflectEdgeIndex( edgeIndex , f1 ); + else + { + temp = node->faceNeighbor( f2 ); + if( temp && temp->children ) finest = temp , finestIndex = Cube::FaceReflectEdgeIndex( edgeIndex , f2 ); + else + { + temp = node->edgeNeighbor( edgeIndex ); + if( temp && temp->children ) finest = temp , finestIndex = Cube::EdgeReflectEdgeIndex( edgeIndex ); + } + } + } + + Cube::EdgeCorners( finestIndex , c1 , c2 ); + if( finest->children ) + { + if ( GetRootIndex( finest->children + c1 , finestIndex , maxDepth , ri ) ) return 1; + else if( GetRootIndex( finest->children + c2 , finestIndex , maxDepth , ri ) ) return 1; + else + { + int d1 , off1[3] , d2 , off2[3]; + node->depthAndOffset( d1 , off1 ); + finest->depthAndOffset( d2 , off2 ); + fprintf( stderr , "[WARNING] Couldn't find root index with either child [%d] (%d %d %d) -> [%d] (%d %d %d) (%d %d)\n" , d1 , off1[0] , off1[1] , off1[2] , d2 , off2[0] , off2[1] , off2[2] , node->children!=NULL , finest->children!=NULL ); + printf( "\t" ); + for( int i=0 ; i<8 ; i++ ) if( node->nodeData.mcIndex & (1<nodeData.mcIndex & (1<depthAndOffset(d,off); + ri.node=finest; + ri.edgeIndex=finestIndex; + int offset,eIndex[2]; + offset = BinaryNode< Real >::CenterIndex( d , off[o] ); + switch(o){ + case 0: + eIndex[0]=BinaryNode::CornerIndex(maxDepth+1,d,off[1],i1); + eIndex[1]=BinaryNode::CornerIndex(maxDepth+1,d,off[2],i2); + break; + case 1: + eIndex[0]=BinaryNode::CornerIndex(maxDepth+1,d,off[0],i1); + eIndex[1]=BinaryNode::CornerIndex(maxDepth+1,d,off[2],i2); + break; + case 2: + eIndex[0]=BinaryNode::CornerIndex(maxDepth+1,d,off[0],i1); + eIndex[1]=BinaryNode::CornerIndex(maxDepth+1,d,off[1],i2); + break; + } + ri.key= (long long)(o) | (long long)(eIndex[0])<<5 | (long long)(eIndex[1])<<25 | (long long)(offset)<<45; + return 1; + } + } + template + int Octree::GetRootPair(const RootInfo& ri,int maxDepth,RootInfo& pair){ + const TreeOctNode* node=ri.node; + int c1,c2,c; + Cube::EdgeCorners(ri.edgeIndex,c1,c2); + while(node->parent){ + c=int(node-node->parent->children); + if(c!=c1 && c!=c2){return 0;} + if(!MarchingCubes::HasEdgeRoots(node->parent->nodeData.mcIndex,ri.edgeIndex)){ + if(c==c1){return GetRootIndex(&node->parent->children[c2],ri.edgeIndex,maxDepth,pair);} + else{return GetRootIndex(&node->parent->children[c1],ri.edgeIndex,maxDepth,pair);} + } + node=node->parent; + } + return 0; + + } + template + int Octree< Degree >::GetRootIndex( const RootInfo& ri , RootData& rootData , CoredPointIndex& index ) + { + long long key = ri.key; + hash_map< long long , int >::iterator rootIter; + rootIter = rootData.boundaryRoots.find( key ); + if( rootIter!=rootData.boundaryRoots.end() ) + { + index.inCore = 1; + index.index = rootIter->second; + return 1; + } + else if( rootData.interiorRoots ) + { + int eIndex = rootData.edgeIndices( ri.node )[ ri.edgeIndex ]; + if( rootData.edgesSet[ eIndex ] ) + { + index.inCore = 0; + index.index = rootData.interiorRoots[ eIndex ]; + return 1; + } + } + return 0; + } + template< int Degree > + int Octree< Degree >::SetMCRootPositions( TreeOctNode* node , int sDepth , Real isoValue , TreeOctNode::ConstNeighborKey5& neighborKey5 , RootData& rootData , + std::vector< Point3D< float > >* interiorPositions , CoredMeshData* mesh , const Real* metSolution , int nonLinearFit ) + { + Point3D< Real > position; + int eIndex; + RootInfo ri; + int count=0; + if( !MarchingCubes::HasRoots( node->nodeData.mcIndex ) ) return 0; + for( int i=0 ; i::iterator iter , end; + // Check if the root has already been set +#pragma omp critical (boundary_roots_hash_access) + { + iter = rootData.boundaryRoots.find( key ); + end = rootData.boundaryRoots.end(); + } + if( iter==end ) + { + // Get the root information + GetRoot( ri , isoValue , neighborKey5 , position , rootData , sDepth , metSolution , nonLinearFit ); + // Add the root if it hasn't been added already +#pragma omp critical (boundary_roots_hash_access) + { + iter = rootData.boundaryRoots.find( key ); + end = rootData.boundaryRoots.end(); + if( iter==end ) + { + mesh->inCorePoints.push_back( position ); + rootData.boundaryRoots[key] = int( mesh->inCorePoints.size() ) - 1; + } + } + if( iter==end ) count++; + } + } + else + { + int nodeEdgeIndex = rootData.edgeIndices( ri.node )[ ri.edgeIndex ]; + if( !rootData.edgesSet[ nodeEdgeIndex ] ) + { + // Get the root information + GetRoot( ri , isoValue , neighborKey5 , position , rootData , sDepth , metSolution , nonLinearFit ); + // Add the root if it hasn't been added already +#pragma omp critical (add_point_access) + { + if( !rootData.edgesSet[ nodeEdgeIndex ] ) + { + rootData.interiorRoots[ nodeEdgeIndex ] = mesh->addOutOfCorePoint( position ); + interiorPositions->push_back( position ); + rootData.edgesSet[ nodeEdgeIndex ] = 1; + count++; + } + } + } + } + } + } + return count; + } + template + int Octree< Degree >::SetBoundaryMCRootPositions( int sDepth , Real isoValue , RootData& rootData , CoredMeshData* mesh , int nonLinearFit ) + { + Point3D< Real > position; + int i,j,k,eIndex,hits=0; + RootInfo ri; + int count=0; + TreeOctNode* node; + + node = tree.nextLeaf(); + while( node ) + { + if( MarchingCubes::HasRoots( node->nodeData.mcIndex ) ) + { + hits=0; + for( i=0 ; iinCorePoints.push_back( position ); + rootData.boundaryRoots[key] = int( mesh->inCorePoints.size() )-1; + count++; + } + } + } + } + if( hits ) node=tree.nextLeaf(node); + else node=tree.nextBranch(node); + } + return count; + } + template + void Octree< Degree >::GetMCIsoEdges( TreeOctNode* node , int sDepth , std::vector< std::pair< RootInfo , RootInfo > >& edges ) + { + TreeOctNode* temp; + int count=0 , tris=0; + int isoTri[ DIMENSION * MarchingCubes::MAX_TRIANGLES ]; + FaceEdgesFunction fef; + int ref , fIndex; + hash_map< long long , std::pair< RootInfo , int > >::iterator iter; + hash_map< long long , std::pair< RootInfo , int > > vertexCount; + + fef.edges = &edges; + fef.maxDepth = fData.depth; + fef.vertexCount = &vertexCount; + count = MarchingCubes::AddTriangleIndices( node->nodeData.mcIndex , isoTri ); + for( fIndex=0 ; fIndexfaceNeighbor( fIndex ); + // If the face neighbor exists and has higher resolution than the current node, + // get the iso-curve from the neighbor + if( temp && temp->children && !IsBoundaryFace( node , fIndex , sDepth ) ) temp->processNodeFaces( temp , &fef , ref ); + // Otherwise, get it from the node + else + { + RootInfo ri1 , ri2; + for( int j=0 ; j( ri1 , ri2 ) ); + iter=vertexCount.find( key1 ); + if( iter==vertexCount.end() ) + { + vertexCount[key1].first = ri1; + vertexCount[key1].second = 0; + } + iter=vertexCount.find( key2 ); + if( iter==vertexCount.end() ) + { + vertexCount[key2].first = ri2; + vertexCount[key2].second = 0; + } + vertexCount[key1].second++; + vertexCount[key2].second--; + } + else + { + int r1 = MarchingCubes::HasEdgeRoots( node->nodeData.mcIndex , isoTri[j*3+k] ); + int r2 = MarchingCubes::HasEdgeRoots( node->nodeData.mcIndex , isoTri[j*3+((k+1)%3)] ); + fprintf( stderr , "Bad Edge 2: %d %d\t%d %d\n" , ri1.key , ri2.key , r1 , r2 ); + } + } + } + for( int i=0 ; idepthAndOffset( d , off ); + printf( "Vertex pair not in list 1 (%lld) %d\t[%d] (%d %d %d)\n" , key , IsBoundaryEdge( ri.node , ri.edgeIndex , sDepth ) , d , off[0] , off[1] , off[2] ); + } + else + { + edges.push_back( std::pair< RootInfo , RootInfo >( ri , edges[i].first ) ); + vertexCount[ key ].second++; + vertexCount[ edges[i].first.key ].second--; + } + } + + iter = vertexCount.find( edges[i].second.key ); + if( iter==vertexCount.end() ) printf( "Could not find vertex: %lld\n" , edges[i].second ); + else if( vertexCount[edges[i].second.key].second ) + { + RootInfo ri; + GetRootPair( vertexCount[edges[i].second.key].first , fData.depth , ri ); + long long key = ri.key; + iter=vertexCount.find( key ); + if( iter==vertexCount.end() ) + { + int d , off[3]; + node->depthAndOffset( d , off ); + printf( "Vertex pair not in list 2\t[%d] (%d %d %d)\n" , d , off[0] , off[1] , off[2] ); + } + else + { + edges.push_back( std::pair< RootInfo , RootInfo >( edges[i].second , ri ) ); + vertexCount[key].second--; + vertexCount[ edges[i].second.key ].second++; + } + } + } + } + template +#if MISHA_DEBUG + int Octree< Degree >::GetMCIsoTriangles( TreeOctNode* node , CoredMeshData* mesh , RootData& rootData , std::vector< Point3D< float > >* interiorPositions , int offSet , int sDepth , bool polygonMesh , std::vector< Point3D< float > >* barycenters ) +#else // !MISHA_DEBUG + int Octree< Degree >::GetMCIsoTriangles( TreeOctNode* node , CoredMeshData* mesh , RootData& rootData , std::vector< Point3D< float > >* interiorPositions , int offSet , int sDepth , bool addBarycenter , bool polygonMesh ) +#endif // MISHA_DEBUG + { + int tris=0; + std::vector< std::pair< RootInfo , RootInfo > > edges; + std::vector< std::vector< std::pair< RootInfo , RootInfo > > > edgeLoops; + GetMCIsoEdges( node , sDepth , edges ); + + GetEdgeLoops( edges , edgeLoops ); + for( int i=0 ; i edgeIndices; + for( int j=0 ; j + int Octree< Degree >::GetEdgeLoops( std::vector< std::pair< RootInfo , RootInfo > >& edges , std::vector< std::vector< std::pair< RootInfo , RootInfo > > >& loops ) + { + int loopSize=0; + long long frontIdx , backIdx; + std::pair< RootInfo , RootInfo > e , temp; + loops.clear(); + + while( edges.size() ) + { + std::vector< std::pair< RootInfo , RootInfo > > front , back; + e = edges[0]; + loops.resize( loopSize+1 ); + edges[0] = edges.back(); + edges.pop_back(); + frontIdx = e.second.key; + backIdx = e.first.key; + for( int j=int(edges.size())-1 ; j>=0 ; j-- ) + { + if( edges[j].first.key==frontIdx || edges[j].second.key==frontIdx ) + { + if( edges[j].first.key==frontIdx ) temp = edges[j]; + else temp.first = edges[j].second , temp.second = edges[j].first; + frontIdx = temp.second.key; + front.push_back(temp); + edges[j] = edges.back(); + edges.pop_back(); + j = int(edges.size()); + } + else if( edges[j].first.key==backIdx || edges[j].second.key==backIdx ) + { + if( edges[j].second.key==backIdx ) temp = edges[j]; + else temp.first = edges[j].second , temp.second = edges[j].first; + backIdx = temp.first.key; + back.push_back(temp); + edges[j] = edges.back(); + edges.pop_back(); + j = int(edges.size()); + } + } + for( int j=int(back.size())-1 ; j>=0 ; j-- ) loops[loopSize].push_back( back[j] ); + loops[loopSize].push_back(e); + for( int j=0 ; j +#if MISHA_DEBUG + int Octree::AddTriangles( CoredMeshData* mesh , std::vector& edges , std::vector >* interiorPositions , int offSet , bool polygonMesh , std::vector< Point3D< float > >* barycenters ) +#else // !MISHA_DEBUG + int Octree::AddTriangles( CoredMeshData* mesh , std::vector& edges , std::vector >* interiorPositions , int offSet , bool addBarycenter , bool polygonMesh ) +#endif // MISHA_DEBUG + { + MinimalAreaTriangulation< float > MAT; + std::vector< Point3D< float > > vertices; + std::vector< TriangleIndex > triangles; + if( polygonMesh ) + { + std::vector< CoredVertexIndex > vertices( edges.size() ); + for( int i=0 ; iaddPolygon( vertices ); + } + return 1; + } + if( edges.size()>3 ) + { + bool isCoplanar = false; + +#if MISHA_DEBUG + if( barycenters ) +#else // !MISHA_DEBUG + if( addBarycenter ) +#endif // MISHA_DEBUG + for( int i=0 ; i v1 , v2; + if( edges[i].inCore ) v1 = mesh->inCorePoints[ edges[i].index ]; + else v1 = (*interiorPositions)[ edges[i].index-offSet ]; + if( edges[j].inCore ) v2 = mesh->inCorePoints[ edges[j].index ]; + else v2 = (*interiorPositions)[ edges[j].index-offSet ]; + for( int k=0 ; k<3 ; k++ ) if( v1[k]==v2[k] ) isCoplanar = true; + } + if( isCoplanar ) + { + Point3D< Real > c; + c[0] = c[1] = c[2] = 0; + for( int i=0 ; i p; + if(edges[i].inCore) p = mesh->inCorePoints[edges[i].index ]; + else p = (*interiorPositions)[edges[i].index-offSet]; + c += p; + } + c /= Real( edges.size() ); + int cIdx; +#pragma omp critical (add_point_access) + { + cIdx = mesh->addOutOfCorePoint( c ); +#if MISHA_DEBUG + barycenters->push_back( c ); +#else // !MISHA_DEBUG + interiorPositions->push_back( c ); +#endif // MISHA_DEBUG + } + for( int i=0 ; i vertices( 3 ); + vertices[0].idx = edges[i ].index; + vertices[1].idx = edges[(i+1)%edges.size()].index; + vertices[2].idx = cIdx; + vertices[0].inCore = (edges[i ].inCore!=0); + vertices[1].inCore = (edges[(i+1)%edges.size()].inCore!=0); + vertices[2].inCore = 0; +#pragma omp critical (add_polygon_access) + { + mesh->addPolygon( vertices ); + } + } + return int( edges.size() ); + } + else + { + vertices.resize( edges.size() ); + // Add the points + for( int i=0 ; i p; + if( edges[i].inCore ) p = mesh->inCorePoints[edges[i].index ]; + else p = (*interiorPositions)[edges[i].index-offSet]; + vertices[i] = p; + } + MAT.GetTriangulation( vertices , triangles ); + for( int i=0 ; i _vertices( 3 ); + for( int j=0 ; j<3 ; j++ ) + { + _vertices[j].idx = edges[ triangles[i].idx[j] ].index; + _vertices[j].inCore = (edges[ triangles[i].idx[j] ].inCore!=0); + } +#pragma omp critical (add_polygon_access) + { + mesh->addPolygon( _vertices ); + } + } + } + } + else if( edges.size()==3 ) + { + std::vector< CoredVertexIndex > vertices( 3 ); + for( int i=0 ; i<3 ; i++ ) + { + vertices[i].idx = edges[i].index; + vertices[i].inCore = (edges[i].inCore!=0); + } +#pragma omp critical (add_polygon_access) + mesh->addPolygon( vertices ); + } + return int(edges.size())-2; + } + template< int Degree > + Real* Octree< Degree >::GetSolutionGrid( int& res , float isoValue , int depth ) + { + if( depth<=0 || depth>tree.maxDepth() ) depth = tree.maxDepth(); + BSplineData< Degree , Real > fData; + fData.set( depth ); + fData.setValueTables( fData.VALUE_FLAG ); + res = 1<d>depth ) continue; + if( n->d<_minDepth ) continue; + int d , idx[3] , start[3] , end[3]; + n->depthAndOffset( d , idx ); + for( int i=0 ; i<3 ; i++ ) + { + // Get the index of the functions + idx[i] = BinaryNode< double >::CenterIndex( d , idx[i] ); + // Figure out which samples fall into the range + fData.setSampleSpan( idx[i] , start[i] , end[i] ); + // We only care about the odd indices + if( !(start[i]&1) ) start[i]++; + if( !( end[i]&1) ) end[i]--; + } + Real coefficient = n->nodeData.solution; + for( int x=start[0] ; x<=end[0] ; x+=2 ) + for( int y=start[1] ; y<=end[1] ; y+=2 ) + for( int z=start[2] ; z<=end[2] ; z+=2 ) + { + int xx = (x-1)>>1 , yy = (y-1)>>1 , zz = (z-1)>>1; + values[ zz*res*res + yy*res + xx ] += + coefficient * + fData.valueTables[ idx[0]+x*fData.functionCount ] * + fData.valueTables[ idx[1]+y*fData.functionCount ] * + fData.valueTables[ idx[2]+z*fData.functionCount ]; + } + } + for( int i=0 ; i + Real* Octree< Degree >::GetWeightGrid( int& res , int depth ) + { + if( depth<=0 || depth>tree.maxDepth() ) depth = tree.maxDepth(); + res = 1<d>depth ) continue; + int d , idx[3] , start[3] , end[3]; + n->depthAndOffset( d , idx ); + for( int i=0 ; i<3 ; i++ ) + { + // Get the index of the functions + idx[i] = BinaryNode< double >::CenterIndex( d , idx[i] ); + // Figure out which samples fall into the range + fData.setSampleSpan( idx[i] , start[i] , end[i] ); + // We only care about the odd indices + if( !(start[i]&1) ) start[i]++; + if( !( end[i]&1) ) end[i]--; + } + for( int x=start[0] ; x<=end[0] ; x+=2 ) + for( int y=start[1] ; y<=end[1] ; y+=2 ) + for( int z=start[2] ; z<=end[2] ; z+=2 ) + { + int xx = (x-1)>>1 , yy = (y-1)>>1 , zz = (z-1)>>1; + values[ zz*res*res + yy*res + xx ] += + n->nodeData.centerWeightContribution * + fData.valueTables[ idx[0]+x*fData.functionCount ] * + fData.valueTables[ idx[1]+y*fData.functionCount ] * + fData.valueTables[ idx[2]+z*fData.functionCount ]; + } + } + return values; + } + + //////////////// + // VertexData // + //////////////// + long long VertexData::CenterIndex(const TreeOctNode* node,int maxDepth){ + int idx[DIMENSION]; + return CenterIndex(node,maxDepth,idx); + } + long long VertexData::CenterIndex(const TreeOctNode* node,int maxDepth,int idx[DIMENSION]){ + int d,o[3]; + node->depthAndOffset(d,o); + for(int i=0;i::CornerIndex(maxDepth+1,d+1,o[i]<<1,1);} + return (long long)(idx[0]) | (long long)(idx[1])<<15 | (long long)(idx[2])<<30; + } + long long VertexData::CenterIndex(int depth,const int offSet[DIMENSION],int maxDepth,int idx[DIMENSION]){ + for(int i=0;i::CornerIndex(maxDepth+1,depth+1,offSet[i]<<1,1);} + return (long long)(idx[0]) | (long long)(idx[1])<<15 | (long long)(idx[2])<<30; + } + long long VertexData::CornerIndex(const TreeOctNode* node,int cIndex,int maxDepth){ + int idx[DIMENSION]; + return CornerIndex(node,cIndex,maxDepth,idx); + } + long long VertexData::CornerIndex( const TreeOctNode* node , int cIndex , int maxDepth , int idx[DIMENSION] ) + { + int x[DIMENSION]; + Cube::FactorCornerIndex( cIndex , x[0] , x[1] , x[2] ); + int d , o[3]; + node->depthAndOffset( d , o ); + for( int i=0 ; i::CornerIndex( maxDepth+1 , d , o[i] , x[i] ); + return CornerIndexKey( idx ); + } + long long VertexData::CornerIndex( int depth , const int offSet[DIMENSION] , int cIndex , int maxDepth , int idx[DIMENSION] ) + { + int x[DIMENSION]; + Cube::FactorCornerIndex( cIndex , x[0] , x[1] , x[2] ); + for( int i=0 ; i::CornerIndex( maxDepth+1 , depth , offSet[i] , x[i] ); + return CornerIndexKey( idx ); + } + long long VertexData::CornerIndexKey( const int idx[DIMENSION] ) + { + return (long long)(idx[0]) | (long long)(idx[1])<<15 | (long long)(idx[2])<<30; + } + long long VertexData::FaceIndex(const TreeOctNode* node,int fIndex,int maxDepth){ + int idx[DIMENSION]; + return FaceIndex(node,fIndex,maxDepth,idx); + } + long long VertexData::FaceIndex(const TreeOctNode* node,int fIndex,int maxDepth,int idx[DIMENSION]){ + int dir,offset; + Cube::FactorFaceIndex(fIndex,dir,offset); + int d,o[3]; + node->depthAndOffset(d,o); + for(int i=0;i::CornerIndex(maxDepth+1,d+1,o[i]<<1,1);} + idx[dir]=BinaryNode::CornerIndex(maxDepth+1,d,o[dir],offset); + return (long long)(idx[0]) | (long long)(idx[1])<<15 | (long long)(idx[2])<<30; + } + long long VertexData::EdgeIndex(const TreeOctNode* node,int eIndex,int maxDepth){ + int idx[DIMENSION]; + return EdgeIndex(node,eIndex,maxDepth,idx); + } + long long VertexData::EdgeIndex(const TreeOctNode* node,int eIndex,int maxDepth,int idx[DIMENSION]){ + int o,i1,i2; + int d,off[3]; + node->depthAndOffset(d,off); + for(int i=0;i::CornerIndex(maxDepth+1,d+1,off[i]<<1,1);} + Cube::FactorEdgeIndex(eIndex,o,i1,i2); + switch(o){ + case 0: + idx[1]=BinaryNode::CornerIndex(maxDepth+1,d,off[1],i1); + idx[2]=BinaryNode::CornerIndex(maxDepth+1,d,off[2],i2); + break; + case 1: + idx[0]=BinaryNode::CornerIndex(maxDepth+1,d,off[0],i1); + idx[2]=BinaryNode::CornerIndex(maxDepth+1,d,off[2],i2); + break; + case 2: + idx[0]=BinaryNode::CornerIndex(maxDepth+1,d,off[0],i1); + idx[1]=BinaryNode::CornerIndex(maxDepth+1,d,off[1],i2); + break; + }; + return (long long)(idx[0]) | (long long)(idx[1])<<15 | (long long)(idx[2])<<30; + } + + + } +} + + diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/octree_poisson.h b/pcl-1.7/pcl/surface/3rdparty/poisson4/octree_poisson.h new file mode 100644 index 0000000..68e082a --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/octree_poisson.h @@ -0,0 +1,287 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#ifndef OCT_NODE_INCLUDED +#define OCT_NODE_INCLUDED + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include "allocator.h" +#include "binary_node.h" +#include "marching_cubes_poisson.h" + +#define DIMENSION 3 + +namespace pcl +{ + namespace poisson + { + + template< class NodeData , class Real=float > + class OctNode + { + private: + static int UseAlloc; + + class AdjacencyCountFunction + { + public: + int count; + void Function( const OctNode* node1 , const OctNode* node2 ); + }; + template + void __processNodeFaces(OctNode* node,NodeAdjacencyFunction* F,int cIndex1,int cIndex2,int cIndex3,int cIndex4); + template + void __processNodeEdges(OctNode* node,NodeAdjacencyFunction* F,int cIndex1,int cIndex2); + template + void __processNodeNodes(OctNode* node,NodeAdjacencyFunction* F); + template + static void __ProcessNodeAdjacentNodes(int dx,int dy,int dz,OctNode* node1,int radius1,OctNode* node2,int radius2,int cWidth2,NodeAdjacencyFunction* F); + template + static void __ProcessTerminatingNodeAdjacentNodes(int dx,int dy,int dz,OctNode* node1,int radius1,OctNode* node2,int radius2,int cWidth2,TerminatingNodeAdjacencyFunction* F); + template + static void __ProcessPointAdjacentNodes(int dx,int dy,int dz,OctNode* node2,int radius2,int cWidth2,PointAdjacencyFunction* F); + template + static void __ProcessFixedDepthNodeAdjacentNodes(int dx,int dy,int dz,OctNode* node1,int radius1,OctNode* node2,int radius2,int cWidth2,int depth,NodeAdjacencyFunction* F); + template + static void __ProcessMaxDepthNodeAdjacentNodes(int dx,int dy,int dz,OctNode* node1,int radius1,OctNode* node2,int radius2,int cWidth2,int depth,NodeAdjacencyFunction* F); + + // This is made private because the division by two has been pulled out. + static inline int Overlap(int c1,int c2,int c3,int dWidth); + inline static int ChildOverlap(int dx,int dy,int dz,int d,int cRadius2); + + const OctNode* __faceNeighbor(int dir,int off) const; + const OctNode* __edgeNeighbor(int o,const int i[2],const int idx[2]) const; + OctNode* __faceNeighbor(int dir,int off,int forceChildren); + OctNode* __edgeNeighbor(int o,const int i[2],const int idx[2],int forceChildren); + public: + static const int DepthShift,OffsetShift,OffsetShift1,OffsetShift2,OffsetShift3; + static const int DepthMask,OffsetMask; + + static Allocator internalAllocator; + static int UseAllocator(void); + static void SetAllocator(int blockSize); + + OctNode* parent; + OctNode* children; + short d , off[DIMENSION]; + NodeData nodeData; + + OctNode(void); + ~OctNode(void); + int initChildren(void); + + void depthAndOffset(int& depth,int offset[DIMENSION]) const; + int depth(void) const; + static inline void DepthAndOffset(const long long& index,int& depth,int offset[DIMENSION]); + static inline void CenterAndWidth(const long long& index,Point3D& center,Real& width); + static inline int Depth(const long long& index); + static inline void Index(int depth,const int offset[3],short& d,short off[DIMENSION]); + void centerAndWidth( Point3D& center , Real& width ) const; + bool isInside( Point3D< Real > p ) const; + + int leaves(void) const; + int maxDepthLeaves(int maxDepth) const; + int nodes(void) const; + int maxDepth(void) const; + + const OctNode* root(void) const; + + const OctNode* nextLeaf(const OctNode* currentLeaf=NULL) const; + OctNode* nextLeaf(OctNode* currentLeaf=NULL); + const OctNode* nextNode(const OctNode* currentNode=NULL) const; + OctNode* nextNode(OctNode* currentNode=NULL); + const OctNode* nextBranch(const OctNode* current) const; + OctNode* nextBranch(OctNode* current); + const OctNode* prevBranch(const OctNode* current) const; + OctNode* prevBranch(OctNode* current); + + void setFullDepth(int maxDepth); + + void printLeaves(void) const; + void printRange(void) const; + + template + void processNodeFaces(OctNode* node,NodeAdjacencyFunction* F,int fIndex,int processCurrent=1); + template + void processNodeEdges(OctNode* node,NodeAdjacencyFunction* F,int eIndex,int processCurrent=1); + template + void processNodeCorners(OctNode* node,NodeAdjacencyFunction* F,int cIndex,int processCurrent=1); + template + void processNodeNodes(OctNode* node,NodeAdjacencyFunction* F,int processCurrent=1); + + template + static void ProcessNodeAdjacentNodes(int maxDepth,OctNode* node1,int width1,OctNode* node2,int width2,NodeAdjacencyFunction* F,int processCurrent=1); + template + static void ProcessNodeAdjacentNodes(int dx,int dy,int dz,OctNode* node1,int radius1,OctNode* node2,int radius2,int width2,NodeAdjacencyFunction* F,int processCurrent=1); + template + static void ProcessTerminatingNodeAdjacentNodes(int maxDepth,OctNode* node1,int width1,OctNode* node2,int width2,TerminatingNodeAdjacencyFunction* F,int processCurrent=1); + template + static void ProcessTerminatingNodeAdjacentNodes(int dx,int dy,int dz,OctNode* node1,int radius1,OctNode* node2,int radius2,int width2,TerminatingNodeAdjacencyFunction* F,int processCurrent=1); + template + static void ProcessPointAdjacentNodes(int maxDepth,const int center1[3],OctNode* node2,int width2,PointAdjacencyFunction* F,int processCurrent=1); + template + static void ProcessPointAdjacentNodes(int dx,int dy,int dz,OctNode* node2,int radius2,int width2,PointAdjacencyFunction* F,int processCurrent=1); + template + static void ProcessFixedDepthNodeAdjacentNodes(int maxDepth,OctNode* node1,int width1,OctNode* node2,int width2,int depth,NodeAdjacencyFunction* F,int processCurrent=1); + template + static void ProcessFixedDepthNodeAdjacentNodes(int dx,int dy,int dz,OctNode* node1,int radius1,OctNode* node2,int radius2,int width2,int depth,NodeAdjacencyFunction* F,int processCurrent=1); + template + static void ProcessMaxDepthNodeAdjacentNodes(int maxDepth,OctNode* node1,int width1,OctNode* node2,int width2,int depth,NodeAdjacencyFunction* F,int processCurrent=1); + template + static void ProcessMaxDepthNodeAdjacentNodes(int dx,int dy,int dz,OctNode* node1,int radius1,OctNode* node2,int radius2,int width2,int depth,NodeAdjacencyFunction* F,int processCurrent=1); + + static int CornerIndex(const Point3D& center,const Point3D &p); + + OctNode* faceNeighbor(int faceIndex,int forceChildren=0); + const OctNode* faceNeighbor(int faceIndex) const; + OctNode* edgeNeighbor(int edgeIndex,int forceChildren=0); + const OctNode* edgeNeighbor(int edgeIndex) const; + OctNode* cornerNeighbor(int cornerIndex,int forceChildren=0); + const OctNode* cornerNeighbor(int cornerIndex) const; + + OctNode* getNearestLeaf(const Point3D& p); + const OctNode* getNearestLeaf(const Point3D& p) const; + + static int CommonEdge(const OctNode* node1,int eIndex1,const OctNode* node2,int eIndex2); + static int CompareForwardDepths(const void* v1,const void* v2); + static int CompareByDepthAndXYZ( const void* v1 , const void* v2 ); + static int CompareByDepthAndZIndex( const void* v1 , const void* v2 ); + static int CompareForwardPointerDepths(const void* v1,const void* v2); + static int CompareBackwardDepths(const void* v1,const void* v2); + static int CompareBackwardPointerDepths(const void* v1,const void* v2); + + + template + OctNode& operator = (const OctNode& node); + + static inline int Overlap2(const int &depth1,const int offSet1[DIMENSION],const Real& multiplier1,const int &depth2,const int offSet2[DIMENSION],const Real& multiplier2); + + + int write(const char* fileName) const; + int write(FILE* fp) const; + int read(const char* fileName); + int read(FILE* fp); + + class Neighbors3 + { + public: + OctNode* neighbors[3][3][3]; + Neighbors3( void ); + void clear( void ); + }; + class NeighborKey3 + { + public: + Neighbors3* neighbors; + + NeighborKey3( void ); + ~NeighborKey3( void ); + + void set( int depth ); + Neighbors3& setNeighbors( OctNode* root , Point3D< Real > p , int d ); + Neighbors3& getNeighbors( OctNode* root , Point3D< Real > p , int d ); + Neighbors3& setNeighbors( OctNode* node , bool flags[3][3][3] ); + Neighbors3& setNeighbors( OctNode* node ); + Neighbors3& getNeighbors( OctNode* node ); + }; + class ConstNeighbors3 + { + public: + const OctNode* neighbors[3][3][3]; + ConstNeighbors3( void ); + void clear( void ); + }; + class ConstNeighborKey3 + { + public: + ConstNeighbors3* neighbors; + + ConstNeighborKey3(void); + ~ConstNeighborKey3(void); + + void set(int depth); + ConstNeighbors3& getNeighbors( const OctNode* node ); + ConstNeighbors3& getNeighbors( const OctNode* node , int minDepth ); + }; + class Neighbors5 + { + public: + OctNode* neighbors[5][5][5]; + Neighbors5( void ); + void clear( void ); + }; + class ConstNeighbors5 + { + public: + const OctNode* neighbors[5][5][5]; + ConstNeighbors5( void ); + void clear( void ); + }; + + class NeighborKey5 + { + int _depth; + public: + Neighbors5* neighbors; + + NeighborKey5( void ); + ~NeighborKey5( void ); + + void set( int depth ); + Neighbors5& getNeighbors( OctNode* node ); + Neighbors5& setNeighbors( OctNode* node , int xStart=0 , int xEnd=5 , int yStart=0 , int yEnd=5 , int zStart=0 , int zEnd=5 ); + }; + class ConstNeighborKey5 + { + int _depth; + public: + ConstNeighbors5* neighbors; + + ConstNeighborKey5( void ); + ~ConstNeighborKey5( void ); + + void set( int depth ); + ConstNeighbors5& getNeighbors( const OctNode* node ); + }; + + void centerIndex(int maxDepth,int index[DIMENSION]) const; + int width(int maxDepth) const; + }; + + + } +} + +#include "octree_poisson.hpp" + + + +#endif // OCT_NODE diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/octree_poisson.hpp b/pcl-1.7/pcl/surface/3rdparty/poisson4/octree_poisson.hpp new file mode 100644 index 0000000..d9115ce --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/octree_poisson.hpp @@ -0,0 +1,1911 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#include +#include +#include + +///////////// +// OctNode // +///////////// + +namespace pcl +{ + namespace poisson + { + + template const int OctNode::DepthShift=5; + template const int OctNode::OffsetShift=19; + template const int OctNode::DepthMask=(1< const int OctNode::OffsetMask=(1< const int OctNode::OffsetShift1=DepthShift; + template const int OctNode::OffsetShift2=OffsetShift1+OffsetShift; + template const int OctNode::OffsetShift3=OffsetShift2+OffsetShift; + + template int OctNode::UseAlloc=0; + template Allocator > OctNode::internalAllocator; + + template + void OctNode::SetAllocator(int blockSize) + { + if(blockSize>0) + { + UseAlloc=1; + internalAllocator.set(blockSize); + } + else{UseAlloc=0;} + } + template + int OctNode::UseAllocator(void){return UseAlloc;} + + template + OctNode::OctNode(void){ + parent=children=NULL; + d=off[0]=off[1]=off[2]=0; + } + + template + OctNode::~OctNode(void){ + if(!UseAlloc){if(children){delete[] children;}} + parent=children=NULL; + } + template + void OctNode::setFullDepth(int maxDepth){ + if( maxDepth ) + { + if( !children ) initChildren(); + for( int i=0 ; i<8 ; i++ ) children[i].setFullDepth( maxDepth-1 ); + } + } + + template + int OctNode::initChildren(void){ + int i,j,k; + + if(UseAlloc){children=internalAllocator.newElements(8);} + else{ + if(children){delete[] children;} + children=NULL; + children=new OctNode[Cube::CORNERS]; + } + if(!children){ + fprintf(stderr,"Failed to initialize children in OctNode::initChildren\n"); + exit(0); + return 0; + } + int d,off[3]; + depthAndOffset(d,off); + for(i=0;i<2;i++){ + for(j=0;j<2;j++){ + for(k=0;k<2;k++){ + int idx=Cube::CornerIndex(i,j,k); + children[idx].parent=this; + children[idx].children=NULL; + int off2[3]; + off2[0]=(off[0]<<1)+i; + off2[1]=(off[1]<<1)+j; + off2[2]=(off[2]<<1)+k; + Index(d+1,off2,children[idx].d,children[idx].off); + } + } + } + return 1; + } + template + inline void OctNode::Index(int depth,const int offset[3],short& d,short off[3]){ + d=short(depth); + off[0]=short((1< + inline void OctNode::depthAndOffset(int& depth,int offset[3]) const { + depth=int(d); + offset[0]=(int(off[0])+1)&(~(1< + inline int OctNode::depth(void) const {return int(d);} + template + inline void OctNode::DepthAndOffset(const long long& index,int& depth,int offset[3]){ + depth=int(index&DepthMask); + offset[0]=(int((index>>OffsetShift1)&OffsetMask)+1)&(~(1<>OffsetShift2)&OffsetMask)+1)&(~(1<>OffsetShift3)&OffsetMask)+1)&(~(1< + inline int OctNode::Depth(const long long& index){return int(index&DepthMask);} + template + void OctNode::centerAndWidth(Point3D& center,Real& width) const{ + int depth,offset[3]; + depth=int(d); + offset[0]=(int(off[0])+1)&(~(1< + bool OctNode< NodeData , Real >::isInside( Point3D< Real > p ) const + { + Point3D< Real > c; + Real w; + centerAndWidth( c , w ); + w /= 2; + return (c[0]-w) + inline void OctNode::CenterAndWidth(const long long& index,Point3D& center,Real& width){ + int depth,offset[3]; + depth=index&DepthMask; + offset[0]=(int((index>>OffsetShift1)&OffsetMask)+1)&(~(1<>OffsetShift2)&OffsetMask)+1)&(~(1<>OffsetShift3)&OffsetMask)+1)&(~(1< + int OctNode::maxDepth(void) const{ + if(!children){return 0;} + else{ + int c,d; + for(int i=0;ic){c=d;} + } + return c+1; + } + } + template + int OctNode::nodes(void) const{ + if(!children){return 1;} + else{ + int c=0; + for(int i=0;i + int OctNode::leaves(void) const{ + if(!children){return 1;} + else{ + int c=0; + for(int i=0;i + int OctNode::maxDepthLeaves(int maxDepth) const{ + if(depth()>maxDepth){return 0;} + if(!children){return 1;} + else{ + int c=0; + for(int i=0;i + const OctNode* OctNode::root(void) const{ + const OctNode* temp=this; + while(temp->parent){temp=temp->parent;} + return temp; + } + + + template + const OctNode* OctNode::nextBranch( const OctNode* current ) const + { + if( !current->parent || current==this ) return NULL; + if(current-current->parent->children==Cube::CORNERS-1) return nextBranch( current->parent ); + else return current+1; + } + template + OctNode* OctNode::nextBranch(OctNode* current){ + if(!current->parent || current==this){return NULL;} + if(current-current->parent->children==Cube::CORNERS-1){return nextBranch(current->parent);} + else{return current+1;} + } + template< class NodeData , class Real > + const OctNode< NodeData , Real >* OctNode< NodeData , Real >::prevBranch( const OctNode* current ) const + { + if( !current->parent || current==this ) return NULL; + if( current-current->parent->children==0 ) return prevBranch( current->parent ); + else return current-1; + } + template< class NodeData , class Real > + OctNode< NodeData , Real >* OctNode< NodeData , Real >::prevBranch( OctNode* current ) + { + if( !current->parent || current==this ) return NULL; + if( current-current->parent->children==0 ) return prevBranch( current->parent ); + else return current-1; + } + template + const OctNode* OctNode::nextLeaf(const OctNode* current) const{ + if(!current){ + const OctNode* temp=this; + while(temp->children){temp=&temp->children[0];} + return temp; + } + if(current->children){return current->nextLeaf();} + const OctNode* temp=nextBranch(current); + if(!temp){return NULL;} + else{return temp->nextLeaf();} + } + template + OctNode* OctNode::nextLeaf(OctNode* current){ + if(!current){ + OctNode* temp=this; + while(temp->children){temp=&temp->children[0];} + return temp; + } + if(current->children){return current->nextLeaf();} + OctNode* temp=nextBranch(current); + if(!temp){return NULL;} + else{return temp->nextLeaf();} + } + + template + const OctNode* OctNode::nextNode( const OctNode* current ) const + { + if( !current ) return this; + else if( current->children ) return ¤t->children[0]; + else return nextBranch(current); + } + template + OctNode* OctNode::nextNode( OctNode* current ) + { + if( !current ) return this; + else if( current->children ) return ¤t->children[0]; + else return nextBranch( current ); + } + + template + void OctNode::printRange(void) const{ + Point3D center; + Real width; + centerAndWidth(center,width); + for(int dim=0;dim + void OctNode::AdjacencyCountFunction::Function(const OctNode* node1,const OctNode* node2){count++;} + + template + template + void OctNode::processNodeNodes(OctNode* node,NodeAdjacencyFunction* F,int processCurrent){ + if(processCurrent){F->Function(this,node);} + if(children){__processNodeNodes(node,F);} + } + template + template + void OctNode::processNodeFaces(OctNode* node,NodeAdjacencyFunction* F,int fIndex,int processCurrent){ + if(processCurrent){F->Function(this,node);} + if(children){ + int c1,c2,c3,c4; + Cube::FaceCorners(fIndex,c1,c2,c3,c4); + __processNodeFaces(node,F,c1,c2,c3,c4); + } + } + template + template + void OctNode::processNodeEdges(OctNode* node,NodeAdjacencyFunction* F,int eIndex,int processCurrent){ + if(processCurrent){F->Function(this,node);} + if(children){ + int c1,c2; + Cube::EdgeCorners(eIndex,c1,c2); + __processNodeEdges(node,F,c1,c2); + } + } + template + template + void OctNode::processNodeCorners(OctNode* node,NodeAdjacencyFunction* F,int cIndex,int processCurrent){ + if(processCurrent){F->Function(this,node);} + OctNode* temp=this; + while(temp->children){ + temp=&temp->children[cIndex]; + F->Function(temp,node); + } + } + template + template + void OctNode::__processNodeNodes(OctNode* node,NodeAdjacencyFunction* F){ + F->Function(&children[0],node); + F->Function(&children[1],node); + F->Function(&children[2],node); + F->Function(&children[3],node); + F->Function(&children[4],node); + F->Function(&children[5],node); + F->Function(&children[6],node); + F->Function(&children[7],node); + if(children[0].children){children[0].__processNodeNodes(node,F);} + if(children[1].children){children[1].__processNodeNodes(node,F);} + if(children[2].children){children[2].__processNodeNodes(node,F);} + if(children[3].children){children[3].__processNodeNodes(node,F);} + if(children[4].children){children[4].__processNodeNodes(node,F);} + if(children[5].children){children[5].__processNodeNodes(node,F);} + if(children[6].children){children[6].__processNodeNodes(node,F);} + if(children[7].children){children[7].__processNodeNodes(node,F);} + } + template + template + void OctNode::__processNodeEdges(OctNode* node,NodeAdjacencyFunction* F,int cIndex1,int cIndex2){ + F->Function(&children[cIndex1],node); + F->Function(&children[cIndex2],node); + if(children[cIndex1].children){children[cIndex1].__processNodeEdges(node,F,cIndex1,cIndex2);} + if(children[cIndex2].children){children[cIndex2].__processNodeEdges(node,F,cIndex1,cIndex2);} + } + template + template + void OctNode::__processNodeFaces(OctNode* node,NodeAdjacencyFunction* F,int cIndex1,int cIndex2,int cIndex3,int cIndex4){ + F->Function(&children[cIndex1],node); + F->Function(&children[cIndex2],node); + F->Function(&children[cIndex3],node); + F->Function(&children[cIndex4],node); + if(children[cIndex1].children){children[cIndex1].__processNodeFaces(node,F,cIndex1,cIndex2,cIndex3,cIndex4);} + if(children[cIndex2].children){children[cIndex2].__processNodeFaces(node,F,cIndex1,cIndex2,cIndex3,cIndex4);} + if(children[cIndex3].children){children[cIndex3].__processNodeFaces(node,F,cIndex1,cIndex2,cIndex3,cIndex4);} + if(children[cIndex4].children){children[cIndex4].__processNodeFaces(node,F,cIndex1,cIndex2,cIndex3,cIndex4);} + } + template + template + void OctNode::ProcessNodeAdjacentNodes(int maxDepth,OctNode* node1,int width1,OctNode* node2,int width2,NodeAdjacencyFunction* F,int processCurrent){ + int c1[3],c2[3],w1,w2; + node1->centerIndex(maxDepth+1,c1); + node2->centerIndex(maxDepth+1,c2); + w1=node1->width(maxDepth+1); + w2=node2->width(maxDepth+1); + + ProcessNodeAdjacentNodes(c1[0]-c2[0],c1[1]-c2[1],c1[2]-c2[2],node1,(width1*w1)>>1,node2,(width2*w2)>>1,w2,F,processCurrent); + } + template + template + void OctNode::ProcessNodeAdjacentNodes(int dx,int dy,int dz, + OctNode* node1,int radius1, + OctNode* node2,int radius2,int width2, + NodeAdjacencyFunction* F,int processCurrent){ + if(!Overlap(dx,dy,dz,radius1+radius2)){return;} + if(processCurrent){F->Function(node2,node1);} + if(!node2->children){return;} + __ProcessNodeAdjacentNodes(-dx,-dy,-dz,node1,radius1,node2,radius2,width2/2,F); + } + template + template + void OctNode::ProcessTerminatingNodeAdjacentNodes(int maxDepth,OctNode* node1,int width1,OctNode* node2,int width2,TerminatingNodeAdjacencyFunction* F,int processCurrent){ + int c1[3],c2[3],w1,w2; + node1->centerIndex(maxDepth+1,c1); + node2->centerIndex(maxDepth+1,c2); + w1=node1->width(maxDepth+1); + w2=node2->width(maxDepth+1); + + ProcessTerminatingNodeAdjacentNodes(c1[0]-c2[0],c1[1]-c2[1],c1[2]-c2[2],node1,(width1*w1)>>1,node2,(width2*w2)>>1,w2,F,processCurrent); + } + template + template + void OctNode::ProcessTerminatingNodeAdjacentNodes(int dx,int dy,int dz, + OctNode* node1,int radius1, + OctNode* node2,int radius2,int width2, + TerminatingNodeAdjacencyFunction* F,int processCurrent) + { + if(!Overlap(dx,dy,dz,radius1+radius2)){return;} + if(processCurrent){F->Function(node2,node1);} + if(!node2->children){return;} + __ProcessTerminatingNodeAdjacentNodes(-dx,-dy,-dz,node1,radius1,node2,radius2,width2/2,F); + } + template + template + void OctNode::ProcessPointAdjacentNodes( int maxDepth , const int c1[3] , OctNode* node2 , int width2 , PointAdjacencyFunction* F , int processCurrent ) + { + int c2[3] , w2; + node2->centerIndex( maxDepth+1 , c2 ); + w2 = node2->width( maxDepth+1 ); + ProcessPointAdjacentNodes( c1[0]-c2[0] , c1[1]-c2[1] , c1[2]-c2[2] , node2 , (width2*w2)>>1 , w2 , F , processCurrent ); + } + template + template + void OctNode::ProcessPointAdjacentNodes(int dx,int dy,int dz, + OctNode* node2,int radius2,int width2, + PointAdjacencyFunction* F,int processCurrent) + { + if( !Overlap(dx,dy,dz,radius2) ) return; + if( processCurrent ) F->Function(node2); + if( !node2->children ) return; + __ProcessPointAdjacentNodes( -dx , -dy , -dz , node2 , radius2 , width2>>1 , F ); + } + template + template + void OctNode::ProcessFixedDepthNodeAdjacentNodes(int maxDepth, + OctNode* node1,int width1, + OctNode* node2,int width2, + int depth,NodeAdjacencyFunction* F,int processCurrent) + { + int c1[3],c2[3],w1,w2; + node1->centerIndex(maxDepth+1,c1); + node2->centerIndex(maxDepth+1,c2); + w1=node1->width(maxDepth+1); + w2=node2->width(maxDepth+1); + + ProcessFixedDepthNodeAdjacentNodes(c1[0]-c2[0],c1[1]-c2[1],c1[2]-c2[2],node1,(width1*w1)>>1,node2,(width2*w2)>>1,w2,depth,F,processCurrent); + } + template + template + void OctNode::ProcessFixedDepthNodeAdjacentNodes(int dx,int dy,int dz, + OctNode* node1,int radius1, + OctNode* node2,int radius2,int width2, + int depth,NodeAdjacencyFunction* F,int processCurrent) + { + int d=node2->depth(); + if(d>depth){return;} + if(!Overlap(dx,dy,dz,radius1+radius2)){return;} + if(d==depth){if(processCurrent){F->Function(node2,node1);}} + else{ + if(!node2->children){return;} + __ProcessFixedDepthNodeAdjacentNodes(-dx,-dy,-dz,node1,radius1,node2,radius2,width2/2,depth-1,F); + } + } + template + template + void OctNode::ProcessMaxDepthNodeAdjacentNodes(int maxDepth, + OctNode* node1,int width1, + OctNode* node2,int width2, + int depth,NodeAdjacencyFunction* F,int processCurrent) + { + int c1[3],c2[3],w1,w2; + node1->centerIndex(maxDepth+1,c1); + node2->centerIndex(maxDepth+1,c2); + w1=node1->width(maxDepth+1); + w2=node2->width(maxDepth+1); + ProcessMaxDepthNodeAdjacentNodes(c1[0]-c2[0],c1[1]-c2[1],c1[2]-c2[2],node1,(width1*w1)>>1,node2,(width2*w2)>>1,w2,depth,F,processCurrent); + } + template + template + void OctNode::ProcessMaxDepthNodeAdjacentNodes(int dx,int dy,int dz, + OctNode* node1,int radius1, + OctNode* node2,int radius2,int width2, + int depth,NodeAdjacencyFunction* F,int processCurrent) + { + int d=node2->depth(); + if(d>depth){return;} + if(!Overlap(dx,dy,dz,radius1+radius2)){return;} + if(processCurrent){F->Function(node2,node1);} + if(dchildren){__ProcessMaxDepthNodeAdjacentNodes(-dx,-dy,-dz,node1,radius1,node2,radius2,width2>>1,depth-1,F);} + } + template + template + void OctNode::__ProcessNodeAdjacentNodes(int dx,int dy,int dz, + OctNode* node1,int radius1, + OctNode* node2,int radius2,int cWidth2, + NodeAdjacencyFunction* F) + { + int cWidth=cWidth2>>1; + int radius=radius2>>1; + int o=ChildOverlap(dx,dy,dz,radius1+radius,cWidth); + if(o){ + int dx1=dx-cWidth; + int dx2=dx+cWidth; + int dy1=dy-cWidth; + int dy2=dy+cWidth; + int dz1=dz-cWidth; + int dz2=dz+cWidth; + if(o& 1){F->Function(&node2->children[0],node1);if(node2->children[0].children){__ProcessNodeAdjacentNodes(dx1,dy1,dz1,node1,radius1,&node2->children[0],radius,cWidth,F);}} + if(o& 2){F->Function(&node2->children[1],node1);if(node2->children[1].children){__ProcessNodeAdjacentNodes(dx2,dy1,dz1,node1,radius1,&node2->children[1],radius,cWidth,F);}} + if(o& 4){F->Function(&node2->children[2],node1);if(node2->children[2].children){__ProcessNodeAdjacentNodes(dx1,dy2,dz1,node1,radius1,&node2->children[2],radius,cWidth,F);}} + if(o& 8){F->Function(&node2->children[3],node1);if(node2->children[3].children){__ProcessNodeAdjacentNodes(dx2,dy2,dz1,node1,radius1,&node2->children[3],radius,cWidth,F);}} + if(o& 16){F->Function(&node2->children[4],node1);if(node2->children[4].children){__ProcessNodeAdjacentNodes(dx1,dy1,dz2,node1,radius1,&node2->children[4],radius,cWidth,F);}} + if(o& 32){F->Function(&node2->children[5],node1);if(node2->children[5].children){__ProcessNodeAdjacentNodes(dx2,dy1,dz2,node1,radius1,&node2->children[5],radius,cWidth,F);}} + if(o& 64){F->Function(&node2->children[6],node1);if(node2->children[6].children){__ProcessNodeAdjacentNodes(dx1,dy2,dz2,node1,radius1,&node2->children[6],radius,cWidth,F);}} + if(o&128){F->Function(&node2->children[7],node1);if(node2->children[7].children){__ProcessNodeAdjacentNodes(dx2,dy2,dz2,node1,radius1,&node2->children[7],radius,cWidth,F);}} + } + } + template + template + void OctNode::__ProcessTerminatingNodeAdjacentNodes(int dx,int dy,int dz, + OctNode* node1,int radius1, + OctNode* node2,int radius2,int cWidth2, + TerminatingNodeAdjacencyFunction* F) + { + int cWidth=cWidth2>>1; + int radius=radius2>>1; + int o=ChildOverlap(dx,dy,dz,radius1+radius,cWidth); + if(o){ + int dx1=dx-cWidth; + int dx2=dx+cWidth; + int dy1=dy-cWidth; + int dy2=dy+cWidth; + int dz1=dz-cWidth; + int dz2=dz+cWidth; + if(o& 1){if(F->Function(&node2->children[0],node1) && node2->children[0].children){__ProcessTerminatingNodeAdjacentNodes(dx1,dy1,dz1,node1,radius1,&node2->children[0],radius,cWidth,F);}} + if(o& 2){if(F->Function(&node2->children[1],node1) && node2->children[1].children){__ProcessTerminatingNodeAdjacentNodes(dx2,dy1,dz1,node1,radius1,&node2->children[1],radius,cWidth,F);}} + if(o& 4){if(F->Function(&node2->children[2],node1) && node2->children[2].children){__ProcessTerminatingNodeAdjacentNodes(dx1,dy2,dz1,node1,radius1,&node2->children[2],radius,cWidth,F);}} + if(o& 8){if(F->Function(&node2->children[3],node1) && node2->children[3].children){__ProcessTerminatingNodeAdjacentNodes(dx2,dy2,dz1,node1,radius1,&node2->children[3],radius,cWidth,F);}} + if(o& 16){if(F->Function(&node2->children[4],node1) && node2->children[4].children){__ProcessTerminatingNodeAdjacentNodes(dx1,dy1,dz2,node1,radius1,&node2->children[4],radius,cWidth,F);}} + if(o& 32){if(F->Function(&node2->children[5],node1) && node2->children[5].children){__ProcessTerminatingNodeAdjacentNodes(dx2,dy1,dz2,node1,radius1,&node2->children[5],radius,cWidth,F);}} + if(o& 64){if(F->Function(&node2->children[6],node1) && node2->children[6].children){__ProcessTerminatingNodeAdjacentNodes(dx1,dy2,dz2,node1,radius1,&node2->children[6],radius,cWidth,F);}} + if(o&128){if(F->Function(&node2->children[7],node1) && node2->children[7].children){__ProcessTerminatingNodeAdjacentNodes(dx2,dy2,dz2,node1,radius1,&node2->children[7],radius,cWidth,F);}} + } + } + template + template + void OctNode::__ProcessPointAdjacentNodes(int dx,int dy,int dz, + OctNode* node2,int radius2,int cWidth2, + PointAdjacencyFunction* F) + { + int cWidth=cWidth2>>1; + int radius=radius2>>1; + int o=ChildOverlap(dx,dy,dz,radius,cWidth); + if( o ) + { + int dx1=dx-cWidth; + int dx2=dx+cWidth; + int dy1=dy-cWidth; + int dy2=dy+cWidth; + int dz1=dz-cWidth; + int dz2=dz+cWidth; + if(o& 1){F->Function(&node2->children[0]);if(node2->children[0].children){__ProcessPointAdjacentNodes(dx1,dy1,dz1,&node2->children[0],radius,cWidth,F);}} + if(o& 2){F->Function(&node2->children[1]);if(node2->children[1].children){__ProcessPointAdjacentNodes(dx2,dy1,dz1,&node2->children[1],radius,cWidth,F);}} + if(o& 4){F->Function(&node2->children[2]);if(node2->children[2].children){__ProcessPointAdjacentNodes(dx1,dy2,dz1,&node2->children[2],radius,cWidth,F);}} + if(o& 8){F->Function(&node2->children[3]);if(node2->children[3].children){__ProcessPointAdjacentNodes(dx2,dy2,dz1,&node2->children[3],radius,cWidth,F);}} + if(o& 16){F->Function(&node2->children[4]);if(node2->children[4].children){__ProcessPointAdjacentNodes(dx1,dy1,dz2,&node2->children[4],radius,cWidth,F);}} + if(o& 32){F->Function(&node2->children[5]);if(node2->children[5].children){__ProcessPointAdjacentNodes(dx2,dy1,dz2,&node2->children[5],radius,cWidth,F);}} + if(o& 64){F->Function(&node2->children[6]);if(node2->children[6].children){__ProcessPointAdjacentNodes(dx1,dy2,dz2,&node2->children[6],radius,cWidth,F);}} + if(o&128){F->Function(&node2->children[7]);if(node2->children[7].children){__ProcessPointAdjacentNodes(dx2,dy2,dz2,&node2->children[7],radius,cWidth,F);}} + } + } + template + template + void OctNode::__ProcessFixedDepthNodeAdjacentNodes(int dx,int dy,int dz, + OctNode* node1,int radius1, + OctNode* node2,int radius2,int cWidth2, + int depth,NodeAdjacencyFunction* F) + { + int cWidth=cWidth2>>1; + int radius=radius2>>1; + int o=ChildOverlap(dx,dy,dz,radius1+radius,cWidth); + if(o){ + int dx1=dx-cWidth; + int dx2=dx+cWidth; + int dy1=dy-cWidth; + int dy2=dy+cWidth; + int dz1=dz-cWidth; + int dz2=dz+cWidth; + if(node2->depth()==depth){ + if(o& 1){F->Function(&node2->children[0],node1);} + if(o& 2){F->Function(&node2->children[1],node1);} + if(o& 4){F->Function(&node2->children[2],node1);} + if(o& 8){F->Function(&node2->children[3],node1);} + if(o& 16){F->Function(&node2->children[4],node1);} + if(o& 32){F->Function(&node2->children[5],node1);} + if(o& 64){F->Function(&node2->children[6],node1);} + if(o&128){F->Function(&node2->children[7],node1);} + } + else{ + if(o& 1){if(node2->children[0].children){__ProcessFixedDepthNodeAdjacentNodes(dx1,dy1,dz1,node1,radius1,&node2->children[0],radius,cWidth,depth,F);}} + if(o& 2){if(node2->children[1].children){__ProcessFixedDepthNodeAdjacentNodes(dx2,dy1,dz1,node1,radius1,&node2->children[1],radius,cWidth,depth,F);}} + if(o& 4){if(node2->children[2].children){__ProcessFixedDepthNodeAdjacentNodes(dx1,dy2,dz1,node1,radius1,&node2->children[2],radius,cWidth,depth,F);}} + if(o& 8){if(node2->children[3].children){__ProcessFixedDepthNodeAdjacentNodes(dx2,dy2,dz1,node1,radius1,&node2->children[3],radius,cWidth,depth,F);}} + if(o& 16){if(node2->children[4].children){__ProcessFixedDepthNodeAdjacentNodes(dx1,dy1,dz2,node1,radius1,&node2->children[4],radius,cWidth,depth,F);}} + if(o& 32){if(node2->children[5].children){__ProcessFixedDepthNodeAdjacentNodes(dx2,dy1,dz2,node1,radius1,&node2->children[5],radius,cWidth,depth,F);}} + if(o& 64){if(node2->children[6].children){__ProcessFixedDepthNodeAdjacentNodes(dx1,dy2,dz2,node1,radius1,&node2->children[6],radius,cWidth,depth,F);}} + if(o&128){if(node2->children[7].children){__ProcessFixedDepthNodeAdjacentNodes(dx2,dy2,dz2,node1,radius1,&node2->children[7],radius,cWidth,depth,F);}} + } + } + } + template + template + void OctNode::__ProcessMaxDepthNodeAdjacentNodes(int dx,int dy,int dz, + OctNode* node1,int radius1, + OctNode* node2,int radius2,int cWidth2, + int depth,NodeAdjacencyFunction* F) + { + int cWidth=cWidth2>>1; + int radius=radius2>>1; + int o=ChildOverlap(dx,dy,dz,radius1+radius,cWidth); + if(o){ + int dx1=dx-cWidth; + int dx2=dx+cWidth; + int dy1=dy-cWidth; + int dy2=dy+cWidth; + int dz1=dz-cWidth; + int dz2=dz+cWidth; + if(node2->depth()<=depth){ + if(o& 1){F->Function(&node2->children[0],node1);} + if(o& 2){F->Function(&node2->children[1],node1);} + if(o& 4){F->Function(&node2->children[2],node1);} + if(o& 8){F->Function(&node2->children[3],node1);} + if(o& 16){F->Function(&node2->children[4],node1);} + if(o& 32){F->Function(&node2->children[5],node1);} + if(o& 64){F->Function(&node2->children[6],node1);} + if(o&128){F->Function(&node2->children[7],node1);} + } + if(node2->depth()children[0].children){__ProcessMaxDepthNodeAdjacentNodes(dx1,dy1,dz1,node1,radius1,&node2->children[0],radius,cWidth,depth,F);}} + if(o& 2){if(node2->children[1].children){__ProcessMaxDepthNodeAdjacentNodes(dx2,dy1,dz1,node1,radius1,&node2->children[1],radius,cWidth,depth,F);}} + if(o& 4){if(node2->children[2].children){__ProcessMaxDepthNodeAdjacentNodes(dx1,dy2,dz1,node1,radius1,&node2->children[2],radius,cWidth,depth,F);}} + if(o& 8){if(node2->children[3].children){__ProcessMaxDepthNodeAdjacentNodes(dx2,dy2,dz1,node1,radius1,&node2->children[3],radius,cWidth,depth,F);}} + if(o& 16){if(node2->children[4].children){__ProcessMaxDepthNodeAdjacentNodes(dx1,dy1,dz2,node1,radius1,&node2->children[4],radius,cWidth,depth,F);}} + if(o& 32){if(node2->children[5].children){__ProcessMaxDepthNodeAdjacentNodes(dx2,dy1,dz2,node1,radius1,&node2->children[5],radius,cWidth,depth,F);}} + if(o& 64){if(node2->children[6].children){__ProcessMaxDepthNodeAdjacentNodes(dx1,dy2,dz2,node1,radius1,&node2->children[6],radius,cWidth,depth,F);}} + if(o&128){if(node2->children[7].children){__ProcessMaxDepthNodeAdjacentNodes(dx2,dy2,dz2,node1,radius1,&node2->children[7],radius,cWidth,depth,F);}} + } + } + } + template + inline int OctNode::ChildOverlap(int dx,int dy,int dz,int d,int cRadius2) + { + int w1=d-cRadius2; + int w2=d+cRadius2; + int overlap=0; + + int test=0,test1=0; + if(dx-w1){test =1;} + if(dx-w2){test|=2;} + + if(!test){return 0;} + if(dz-w1){test1 =test;} + if(dz-w2){test1|=test<<4;} + + if(!test1){return 0;} + if(dy-w1){overlap =test1;} + if(dy-w2){overlap|=test1<<2;} + return overlap; + } + + template + OctNode* OctNode::getNearestLeaf(const Point3D& p){ + Point3D center; + Real width; + OctNode* temp; + int cIndex; + if(!children){return this;} + centerAndWidth(center,width); + temp=this; + while(temp->children){ + cIndex=CornerIndex(center,p); + temp=&temp->children[cIndex]; + width/=2; + if(cIndex&1){center.coords[0]+=width/2;} + else {center.coords[0]-=width/2;} + if(cIndex&2){center.coords[1]+=width/2;} + else {center.coords[1]-=width/2;} + if(cIndex&4){center.coords[2]+=width/2;} + else {center.coords[2]-=width/2;} + } + return temp; + } + template + const OctNode* OctNode::getNearestLeaf(const Point3D& p) const{ + int nearest; + Real temp,dist2; + if(!children){return this;} + for(int i=0;i + int OctNode::CommonEdge(const OctNode* node1,int eIndex1,const OctNode* node2,int eIndex2){ + int o1,o2,i1,i2,j1,j2; + + Cube::FactorEdgeIndex(eIndex1,o1,i1,j1); + Cube::FactorEdgeIndex(eIndex2,o2,i2,j2); + if(o1!=o2){return 0;} + + int dir[2]; + int idx1[2]; + int idx2[2]; + switch(o1){ + case 0: dir[0]=1; dir[1]=2; break; + case 1: dir[0]=0; dir[1]=2; break; + case 2: dir[0]=0; dir[1]=1; break; + }; + int d1,d2,off1[3],off2[3]; + node1->depthAndOffset(d1,off1); + node2->depthAndOffset(d2,off2); + idx1[0]=off1[dir[0]]+(1<d2){ + idx2[0]<<=(d1-d2); + idx2[1]<<=(d1-d2); + } + else{ + idx1[0]<<=(d2-d1); + idx1[1]<<=(d2-d1); + } + if(idx1[0]==idx2[0] && idx1[1]==idx2[1]){return 1;} + else {return 0;} + } + template + int OctNode::CornerIndex(const Point3D& center,const Point3D& p){ + int cIndex=0; + if(p.coords[0]>center.coords[0]){cIndex|=1;} + if(p.coords[1]>center.coords[1]){cIndex|=2;} + if(p.coords[2]>center.coords[2]){cIndex|=4;} + return cIndex; + } + template + template + OctNode& OctNode::operator = (const OctNode& node){ + int i; + if(children){delete[] children;} + children=NULL; + + d=node.depth (); + for(i=0;ioffset[i] = node.offset[i];} + if(node.children){ + initChildren(); + for(i=0;i + int OctNode::CompareForwardDepths(const void* v1,const void* v2){ + return ((const OctNode*)v1)->depth-((const OctNode*)v2)->depth; + } + template< class NodeData , class Real > + int OctNode< NodeData , Real >::CompareByDepthAndXYZ( const void* v1 , const void* v2 ) + { + const OctNode *n1 = (*(const OctNode< NodeData , Real >**)v1); + const OctNode *n2 = (*(const OctNode< NodeData , Real >**)v2); + if( n1->d!=n2->d ) return int(n1->d)-int(n2->d); + else if( n1->off[0]!=n2->off[0] ) return int(n1->off[0]) - int(n2->off[0]); + else if( n1->off[1]!=n2->off[1] ) return int(n1->off[1]) - int(n2->off[1]); + else if( n1->off[2]!=n2->off[2] ) return int(n1->off[2]) - int(n2->off[2]); + return 0; + } + + long long _InterleaveBits( int p[3] ) + { + long long key = 0; + for( int i=0 ; i<32 ; i++ ) key |= ( ( p[0] & (1< + int OctNode::CompareByDepthAndZIndex( const void* v1 , const void* v2 ) + { + const OctNode* n1 = (*(const OctNode**)v1); + const OctNode* n2 = (*(const OctNode**)v2); + int d1 , off1[3] , d2 , off2[3]; + n1->depthAndOffset( d1 , off1 ) , n2->depthAndOffset( d2 , off2 ); + if ( d1>d2 ) return 1; + else if( d1k2 ) return 1; + else if( k1 + int OctNode::CompareForwardPointerDepths( const void* v1 , const void* v2 ) + { + const OctNode* n1 = (*(const OctNode**)v1); + const OctNode* n2 = (*(const OctNode**)v2); + if(n1->d!=n2->d){return int(n1->d)-int(n2->d);} + while( n1->parent!=n2->parent ) + { + n1=n1->parent; + n2=n2->parent; + } + if(n1->off[0]!=n2->off[0]){return int(n1->off[0])-int(n2->off[0]);} + if(n1->off[1]!=n2->off[1]){return int(n1->off[1])-int(n2->off[1]);} + return int(n1->off[2])-int(n2->off[2]); + return 0; + } + template + int OctNode::CompareBackwardDepths(const void* v1,const void* v2){ + return ((const OctNode*)v2)->depth-((const OctNode*)v1)->depth; + } + template + int OctNode::CompareBackwardPointerDepths(const void* v1,const void* v2){ + return (*(const OctNode**)v2)->depth()-(*(const OctNode**)v1)->depth(); + } + template + inline int OctNode::Overlap2(const int &depth1,const int offSet1[DIMENSION],const Real& multiplier1,const int &depth2,const int offSet2[DIMENSION],const Real& multiplier2){ + int d=depth2-depth1; + Real w=multiplier2+multiplier1*(1<=w || + fabs(Real(offSet2[1]-(offSet1[1]<=w || + fabs(Real(offSet2[2]-(offSet1[2]<=w + ){return 0;} + return 1; + } + template + inline int OctNode::Overlap(int c1,int c2,int c3,int dWidth){ + if(c1>=dWidth || c1<=-dWidth || c2>=dWidth || c2<=-dWidth || c3>=dWidth || c3<=-dWidth){return 0;} + else{return 1;} + } + template + OctNode* OctNode::faceNeighbor(int faceIndex,int forceChildren){return __faceNeighbor(faceIndex>>1,faceIndex&1,forceChildren);} + template + const OctNode* OctNode::faceNeighbor(int faceIndex) const {return __faceNeighbor(faceIndex>>1,faceIndex&1);} + template + OctNode* OctNode::__faceNeighbor(int dir,int off,int forceChildren){ + if(!parent){return NULL;} + int pIndex=int(this-parent->children); + pIndex^=(1<children[pIndex];} + else{ + OctNode* temp=parent->__faceNeighbor(dir,off,forceChildren); + if(!temp){return NULL;} + if(!temp->children){ + if(forceChildren){temp->initChildren();} + else{return temp;} + } + return &temp->children[pIndex]; + } + } + template + const OctNode* OctNode::__faceNeighbor(int dir,int off) const { + if(!parent){return NULL;} + int pIndex=int(this-parent->children); + pIndex^=(1<children[pIndex];} + else{ + const OctNode* temp=parent->__faceNeighbor(dir,off); + if(!temp || !temp->children){return temp;} + else{return &temp->children[pIndex];} + } + } + + template + OctNode* OctNode::edgeNeighbor(int edgeIndex,int forceChildren){ + int idx[2],o,i[2]; + Cube::FactorEdgeIndex(edgeIndex,o,i[0],i[1]); + switch(o){ + case 0: idx[0]=1; idx[1]=2; break; + case 1: idx[0]=0; idx[1]=2; break; + case 2: idx[0]=0; idx[1]=1; break; + }; + return __edgeNeighbor(o,i,idx,forceChildren); + } + template + const OctNode* OctNode::edgeNeighbor(int edgeIndex) const { + int idx[2],o,i[2]; + Cube::FactorEdgeIndex(edgeIndex,o,i[0],i[1]); + switch(o){ + case 0: idx[0]=1; idx[1]=2; break; + case 1: idx[0]=0; idx[1]=2; break; + case 2: idx[0]=0; idx[1]=1; break; + }; + return __edgeNeighbor(o,i,idx); + } + template + const OctNode* OctNode::__edgeNeighbor(int o,const int i[2],const int idx[2]) const{ + if(!parent){return NULL;} + int pIndex=int(this-parent->children); + int aIndex,x[DIMENSION]; + + Cube::FactorCornerIndex(pIndex,x[0],x[1],x[2]); + aIndex=(~((i[0] ^ x[idx[0]]) | ((i[1] ^ x[idx[1]])<<1))) & 3; + pIndex^=(7 ^ (1<__faceNeighbor(idx[0],i[0]); + if(!temp || !temp->children){return NULL;} + else{return &temp->children[pIndex];} + } + else if(aIndex==2) { // I can get the neighbor from the parent's face adjacent neighbor + const OctNode* temp=parent->__faceNeighbor(idx[1],i[1]); + if(!temp || !temp->children){return NULL;} + else{return &temp->children[pIndex];} + } + else if(aIndex==0) { // I can get the neighbor from the parent + return &parent->children[pIndex]; + } + else if(aIndex==3) { // I can get the neighbor from the parent's edge adjacent neighbor + const OctNode* temp=parent->__edgeNeighbor(o,i,idx); + if(!temp || !temp->children){return temp;} + else{return &temp->children[pIndex];} + } + else{return NULL;} + } + template + OctNode* OctNode::__edgeNeighbor(int o,const int i[2],const int idx[2],int forceChildren){ + if(!parent){return NULL;} + int pIndex=int(this-parent->children); + int aIndex,x[DIMENSION]; + + Cube::FactorCornerIndex(pIndex,x[0],x[1],x[2]); + aIndex=(~((i[0] ^ x[idx[0]]) | ((i[1] ^ x[idx[1]])<<1))) & 3; + pIndex^=(7 ^ (1<__faceNeighbor(idx[0],i[0],0); + if(!temp || !temp->children){return NULL;} + else{return &temp->children[pIndex];} + } + else if(aIndex==2) { // I can get the neighbor from the parent's face adjacent neighbor + OctNode* temp=parent->__faceNeighbor(idx[1],i[1],0); + if(!temp || !temp->children){return NULL;} + else{return &temp->children[pIndex];} + } + else if(aIndex==0) { // I can get the neighbor from the parent + return &parent->children[pIndex]; + } + else if(aIndex==3) { // I can get the neighbor from the parent's edge adjacent neighbor + OctNode* temp=parent->__edgeNeighbor(o,i,idx,forceChildren); + if(!temp){return NULL;} + if(!temp->children){ + if(forceChildren){temp->initChildren();} + else{return temp;} + } + return &temp->children[pIndex]; + } + else{return NULL;} + } + + template + const OctNode* OctNode::cornerNeighbor(int cornerIndex) const { + int pIndex,aIndex=0; + if(!parent){return NULL;} + + pIndex=int(this-parent->children); + aIndex=(cornerIndex ^ pIndex); // The disagreement bits + pIndex=(~pIndex)&7; // The antipodal point + if(aIndex==7){ // Agree on no bits + return &parent->children[pIndex]; + } + else if(aIndex==0){ // Agree on all bits + const OctNode* temp=((const OctNode*)parent)->cornerNeighbor(cornerIndex); + if(!temp || !temp->children){return temp;} + else{return &temp->children[pIndex];} + } + else if(aIndex==6){ // Agree on face 0 + const OctNode* temp=((const OctNode*)parent)->__faceNeighbor(0,cornerIndex & 1); + if(!temp || !temp->children){return NULL;} + else{return & temp->children[pIndex];} + } + else if(aIndex==5){ // Agree on face 1 + const OctNode* temp=((const OctNode*)parent)->__faceNeighbor(1,(cornerIndex & 2)>>1); + if(!temp || !temp->children){return NULL;} + else{return & temp->children[pIndex];} + } + else if(aIndex==3){ // Agree on face 2 + const OctNode* temp=((const OctNode*)parent)->__faceNeighbor(2,(cornerIndex & 4)>>2); + if(!temp || !temp->children){return NULL;} + else{return & temp->children[pIndex];} + } + else if(aIndex==4){ // Agree on edge 2 + const OctNode* temp=((const OctNode*)parent)->edgeNeighbor(8 | (cornerIndex & 1) | (cornerIndex & 2) ); + if(!temp || !temp->children){return NULL;} + else{return & temp->children[pIndex];} + } + else if(aIndex==2){ // Agree on edge 1 + const OctNode* temp=((const OctNode*)parent)->edgeNeighbor(4 | (cornerIndex & 1) | ((cornerIndex & 4)>>1) ); + if(!temp || !temp->children){return NULL;} + else{return & temp->children[pIndex];} + } + else if(aIndex==1){ // Agree on edge 0 + const OctNode* temp=((const OctNode*)parent)->edgeNeighbor(((cornerIndex & 2) | (cornerIndex & 4))>>1 ); + if(!temp || !temp->children){return NULL;} + else{return & temp->children[pIndex];} + } + else{return NULL;} + } + template + OctNode* OctNode::cornerNeighbor(int cornerIndex,int forceChildren){ + int pIndex,aIndex=0; + if(!parent){return NULL;} + + pIndex=int(this-parent->children); + aIndex=(cornerIndex ^ pIndex); // The disagreement bits + pIndex=(~pIndex)&7; // The antipodal point + if(aIndex==7){ // Agree on no bits + return &parent->children[pIndex]; + } + else if(aIndex==0){ // Agree on all bits + OctNode* temp=((OctNode*)parent)->cornerNeighbor(cornerIndex,forceChildren); + if(!temp){return NULL;} + if(!temp->children){ + if(forceChildren){temp->initChildren();} + else{return temp;} + } + return &temp->children[pIndex]; + } + else if(aIndex==6){ // Agree on face 0 + OctNode* temp=((OctNode*)parent)->__faceNeighbor(0,cornerIndex & 1,0); + if(!temp || !temp->children){return NULL;} + else{return & temp->children[pIndex];} + } + else if(aIndex==5){ // Agree on face 1 + OctNode* temp=((OctNode*)parent)->__faceNeighbor(1,(cornerIndex & 2)>>1,0); + if(!temp || !temp->children){return NULL;} + else{return & temp->children[pIndex];} + } + else if(aIndex==3){ // Agree on face 2 + OctNode* temp=((OctNode*)parent)->__faceNeighbor(2,(cornerIndex & 4)>>2,0); + if(!temp || !temp->children){return NULL;} + else{return & temp->children[pIndex];} + } + else if(aIndex==4){ // Agree on edge 2 + OctNode* temp=((OctNode*)parent)->edgeNeighbor(8 | (cornerIndex & 1) | (cornerIndex & 2) ); + if(!temp || !temp->children){return NULL;} + else{return & temp->children[pIndex];} + } + else if(aIndex==2){ // Agree on edge 1 + OctNode* temp=((OctNode*)parent)->edgeNeighbor(4 | (cornerIndex & 1) | ((cornerIndex & 4)>>1) ); + if(!temp || !temp->children){return NULL;} + else{return & temp->children[pIndex];} + } + else if(aIndex==1){ // Agree on edge 0 + OctNode* temp=((OctNode*)parent)->edgeNeighbor(((cornerIndex & 2) | (cornerIndex & 4))>>1 ); + if(!temp || !temp->children){return NULL;} + else{return & temp->children[pIndex];} + } + else{return NULL;} + } + //////////////////////// + // OctNodeNeighborKey // + //////////////////////// + template + OctNode::Neighbors3::Neighbors3(void){clear();} + template + void OctNode::Neighbors3::clear(void){ + for(int i=0;i<3;i++){for(int j=0;j<3;j++){for(int k=0;k<3;k++){neighbors[i][j][k]=NULL;}}} + } + template + OctNode::NeighborKey3::NeighborKey3(void){ neighbors=NULL; } + template + OctNode::NeighborKey3::~NeighborKey3(void) + { + if( neighbors ) delete[] neighbors; + neighbors = NULL; + } + + template + void OctNode::NeighborKey3::set( int d ) + { + if( neighbors ) delete[] neighbors; + neighbors = NULL; + if( d<0 ) return; + neighbors = new Neighbors3[d+1]; + } + template< class NodeData , class Real > + typename OctNode::Neighbors3& OctNode::NeighborKey3::setNeighbors( OctNode* root , Point3D< Real > p , int d ) + { + if( !neighbors[d].neighbors[1][1][1] || !neighbors[d].neighbors[1][1][1]->isInside( p ) ) + { + neighbors[d].clear(); + + if( !d ) neighbors[d].neighbors[1][1][1] = root; + else + { + Neighbors3& temp = setNeighbors( root , p , d-1 ); + + int i , j , k , x1 , y1 , z1 , x2 , y2 , z2; + Point3D< Real > c; + Real w; + temp.neighbors[1][1][1]->centerAndWidth( c , w ); + int idx = CornerIndex( c , p ); + Cube::FactorCornerIndex( idx , x1 , y1 , z1 ); + Cube::FactorCornerIndex( (~idx)&7 , x2 , y2 , z2 ); + + if( !temp.neighbors[1][1][1]->children ) temp.neighbors[1][1][1]->initChildren(); + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + neighbors[d].neighbors[x2+i][y2+j][z2+k] = &temp.neighbors[1][1][1]->children[Cube::CornerIndex(i,j,k)]; + + + // Set the neighbors from across the faces + i=x1<<1; + if( temp.neighbors[i][1][1] ) + { + if( !temp.neighbors[i][1][1]->children ) temp.neighbors[i][1][1]->initChildren(); + for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) neighbors[d].neighbors[i][y2+j][z2+k] = &temp.neighbors[i][1][1]->children[Cube::CornerIndex(x2,j,k)]; + } + j=y1<<1; + if( temp.neighbors[1][j][1] ) + { + if( !temp.neighbors[1][j][1]->children ) temp.neighbors[1][j][1]->initChildren(); + for( i=0 ; i<2 ; i++ ) for( k=0 ; k<2 ; k++ ) neighbors[d].neighbors[x2+i][j][z2+k] = &temp.neighbors[1][j][1]->children[Cube::CornerIndex(i,y2,k)]; + } + k=z1<<1; + if( temp.neighbors[1][1][k] ) + { + if( !temp.neighbors[1][1][k]->children ) temp.neighbors[1][1][k]->initChildren(); + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) neighbors[d].neighbors[x2+i][y2+j][k] = &temp.neighbors[1][1][k]->children[Cube::CornerIndex(i,j,z2)]; + } + + // Set the neighbors from across the edges + i=x1<<1 , j=y1<<1; + if( temp.neighbors[i][j][1] ) + { + if( !temp.neighbors[i][j][1]->children ) temp.neighbors[i][j][1]->initChildren(); + for( k=0 ; k<2 ; k++ ) neighbors[d].neighbors[i][j][z2+k] = &temp.neighbors[i][j][1]->children[Cube::CornerIndex(x2,y2,k)]; + } + i=x1<<1 , k=z1<<1; + if( temp.neighbors[i][1][k] ) + { + if( !temp.neighbors[i][1][k]->children ) temp.neighbors[i][1][k]->initChildren(); + for( j=0 ; j<2 ; j++ ) neighbors[d].neighbors[i][y2+j][k] = &temp.neighbors[i][1][k]->children[Cube::CornerIndex(x2,j,z2)]; + } + j=y1<<1 , k=z1<<1; + if( temp.neighbors[1][j][k] ) + { + if( !temp.neighbors[1][j][k]->children ) temp.neighbors[1][j][k]->initChildren(); + for( i=0 ; i<2 ; i++ ) neighbors[d].neighbors[x2+i][j][k] = &temp.neighbors[1][j][k]->children[Cube::CornerIndex(i,y2,z2)]; + } + + // Set the neighbor from across the corner + i=x1<<1 , j=y1<<1 , k=z1<<1; + if( temp.neighbors[i][j][k] ) + { + if( !temp.neighbors[i][j][k]->children ) temp.neighbors[i][j][k]->initChildren(); + neighbors[d].neighbors[i][j][k] = &temp.neighbors[i][j][k]->children[Cube::CornerIndex(x2,y2,z2)]; + } + } + } + return neighbors[d]; + } + template< class NodeData , class Real > + typename OctNode::Neighbors3& OctNode::NeighborKey3::getNeighbors( OctNode* root , Point3D< Real > p , int d ) + { + if( !neighbors[d].neighbors[1][1][1] || !neighbors[d].neighbors[1][1][1]->isInside( p ) ) + { + neighbors[d].clear(); + + if( !d ) neighbors[d].neighbors[1][1][1] = root; + else + { + Neighbors3& temp = getNeighbors( root , p , d-1 ); + + int i , j , k , x1 , y1 , z1 , x2 , y2 , z2; + Point3D< Real > c; + Real w; + temp.neighbors[1][1][1]->centerAndWidth( c , w ); + int idx = CornerIndex( c , p ); + Cube::FactorCornerIndex( idx , x1 , y1 , z1 ); + Cube::FactorCornerIndex( (~idx)&7 , x2 , y2 , z2 ); + + if( !temp.neighbors[1][1][1] || !temp.neighbors[1][1][1]->children ) + { + fprintf( stderr , "[ERROR] Couldn't find node at appropriate depth\n" ); + exit( 0 ); + } + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + neighbors[d].neighbors[x2+i][y2+j][z2+k] = &temp.neighbors[1][1][1]->children[Cube::CornerIndex(i,j,k)]; + + + // Set the neighbors from across the faces + i=x1<<1; + if( temp.neighbors[i][1][1] ) + for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) neighbors[d].neighbors[i][y2+j][z2+k] = &temp.neighbors[i][1][1]->children[Cube::CornerIndex(x2,j,k)]; + j=y1<<1; + if( temp.neighbors[1][j][1] ) + for( i=0 ; i<2 ; i++ ) for( k=0 ; k<2 ; k++ ) neighbors[d].neighbors[x2+i][j][z2+k] = &temp.neighbors[1][j][1]->children[Cube::CornerIndex(i,y2,k)]; + k=z1<<1; + if( temp.neighbors[1][1][k] ) + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) neighbors[d].neighbors[x2+i][y2+j][k] = &temp.neighbors[1][1][k]->children[Cube::CornerIndex(i,j,z2)]; + + // Set the neighbors from across the edges + i=x1<<1 , j=y1<<1; + if( temp.neighbors[i][j][1] ) + for( k=0 ; k<2 ; k++ ) neighbors[d].neighbors[i][j][z2+k] = &temp.neighbors[i][j][1]->children[Cube::CornerIndex(x2,y2,k)]; + i=x1<<1 , k=z1<<1; + if( temp.neighbors[i][1][k] ) + for( j=0 ; j<2 ; j++ ) neighbors[d].neighbors[i][y2+j][k] = &temp.neighbors[i][1][k]->children[Cube::CornerIndex(x2,j,z2)]; + j=y1<<1 , k=z1<<1; + if( temp.neighbors[1][j][k] ) + for( i=0 ; i<2 ; i++ ) neighbors[d].neighbors[x2+i][j][k] = &temp.neighbors[1][j][k]->children[Cube::CornerIndex(i,y2,z2)]; + + // Set the neighbor from across the corner + i=x1<<1 , j=y1<<1 , k=z1<<1; + if( temp.neighbors[i][j][k] ) + neighbors[d].neighbors[i][j][k] = &temp.neighbors[i][j][k]->children[Cube::CornerIndex(x2,y2,z2)]; + } + } + return neighbors[d]; + } + + template< class NodeData , class Real > + typename OctNode::Neighbors3& OctNode::NeighborKey3::setNeighbors( OctNode* node ) + { + int d = node->depth(); + if( node==neighbors[d].neighbors[1][1][1] ) + { + bool reset = false; + for( int i=0 ; i<3 ; i++ ) for( int j=0 ; j<3 ; j++ ) for( int k=0 ; k<3 ; k++ ) if( !neighbors[d].neighbors[i][j][k] ) reset = true; + if( reset ) neighbors[d].neighbors[1][1][1] = NULL; + } + if( node!=neighbors[d].neighbors[1][1][1] ) + { + neighbors[d].clear(); + + if( !node->parent ) neighbors[d].neighbors[1][1][1] = node; + else + { + int i,j,k,x1,y1,z1,x2,y2,z2; + int idx=int(node-node->parent->children); + Cube::FactorCornerIndex( idx ,x1,y1,z1); + Cube::FactorCornerIndex((~idx)&7,x2,y2,z2); + for(i=0;i<2;i++){ + for(j=0;j<2;j++){ + for(k=0;k<2;k++){ + neighbors[d].neighbors[x2+i][y2+j][z2+k]=&node->parent->children[Cube::CornerIndex(i,j,k)]; + } + } + } + Neighbors3& temp=setNeighbors(node->parent); + + // Set the neighbors from across the faces + i=x1<<1; + if(temp.neighbors[i][1][1]){ + if(!temp.neighbors[i][1][1]->children){temp.neighbors[i][1][1]->initChildren();} + for(j=0;j<2;j++){for(k=0;k<2;k++){neighbors[d].neighbors[i][y2+j][z2+k]=&temp.neighbors[i][1][1]->children[Cube::CornerIndex(x2,j,k)];}} + } + j=y1<<1; + if(temp.neighbors[1][j][1]){ + if(!temp.neighbors[1][j][1]->children){temp.neighbors[1][j][1]->initChildren();} + for(i=0;i<2;i++){for(k=0;k<2;k++){neighbors[d].neighbors[x2+i][j][z2+k]=&temp.neighbors[1][j][1]->children[Cube::CornerIndex(i,y2,k)];}} + } + k=z1<<1; + if(temp.neighbors[1][1][k]){ + if(!temp.neighbors[1][1][k]->children){temp.neighbors[1][1][k]->initChildren();} + for(i=0;i<2;i++){for(j=0;j<2;j++){neighbors[d].neighbors[x2+i][y2+j][k]=&temp.neighbors[1][1][k]->children[Cube::CornerIndex(i,j,z2)];}} + } + + // Set the neighbors from across the edges + i=x1<<1; j=y1<<1; + if(temp.neighbors[i][j][1]){ + if(!temp.neighbors[i][j][1]->children){temp.neighbors[i][j][1]->initChildren();} + for(k=0;k<2;k++){neighbors[d].neighbors[i][j][z2+k]=&temp.neighbors[i][j][1]->children[Cube::CornerIndex(x2,y2,k)];} + } + i=x1<<1; k=z1<<1; + if(temp.neighbors[i][1][k]){ + if(!temp.neighbors[i][1][k]->children){temp.neighbors[i][1][k]->initChildren();} + for(j=0;j<2;j++){neighbors[d].neighbors[i][y2+j][k]=&temp.neighbors[i][1][k]->children[Cube::CornerIndex(x2,j,z2)];} + } + j=y1<<1; k=z1<<1; + if(temp.neighbors[1][j][k]){ + if(!temp.neighbors[1][j][k]->children){temp.neighbors[1][j][k]->initChildren();} + for(i=0;i<2;i++){neighbors[d].neighbors[x2+i][j][k]=&temp.neighbors[1][j][k]->children[Cube::CornerIndex(i,y2,z2)];} + } + + // Set the neighbor from across the corner + i=x1<<1; j=y1<<1; k=z1<<1; + if(temp.neighbors[i][j][k]){ + if(!temp.neighbors[i][j][k]->children){temp.neighbors[i][j][k]->initChildren();} + neighbors[d].neighbors[i][j][k]=&temp.neighbors[i][j][k]->children[Cube::CornerIndex(x2,y2,z2)]; + } + } + } + return neighbors[d]; + } + // Note the assumption is that if you enable an edge, you also enable adjacent faces. + // And, if you enable a corner, you enable adjacent edges and faces. + template< class NodeData , class Real > + typename OctNode::Neighbors3& OctNode::NeighborKey3::setNeighbors( OctNode* node , bool flags[3][3][3] ) + { + int d = node->depth(); + if( node==neighbors[d].neighbors[1][1][1] ) + { + bool reset = false; + for( int i=0 ; i<3 ; i++ ) for( int j=0 ; j<3 ; j++ ) for( int k=0 ; k<3 ; k++ ) if( flags[i][j][k] && !neighbors[d].neighbors[i][j][k] ) reset = true; + if( reset ) neighbors[d].neighbors[1][1][1] = NULL; + } + if( node!=neighbors[d].neighbors[1][1][1] ) + { + neighbors[d].clear(); + + if( !node->parent ) neighbors[d].neighbors[1][1][1] = node; + else + { + int x1,y1,z1,x2,y2,z2; + int idx=int(node-node->parent->children); + Cube::FactorCornerIndex( idx ,x1,y1,z1); + Cube::FactorCornerIndex((~idx)&7,x2,y2,z2); + for( int i=0 ; i<2 ; i++ ) + for( int j=0 ; j<2 ; j++ ) + for( int k=0 ; k<2 ; k++ ) + neighbors[d].neighbors[x2+i][y2+j][z2+k]=&node->parent->children[Cube::CornerIndex(i,j,k)]; + + Neighbors3& temp=setNeighbors( node->parent , flags ); + + // Set the neighbors from across the faces + { + int i=x1<<1; + if( temp.neighbors[i][1][1] ) + { + if( flags[i][1][1] && !temp.neighbors[i][1][1]->children ) temp.neighbors[i][1][1]->initChildren(); + if( temp.neighbors[i][1][1]->children ) for( int j=0 ; j<2 ; j++ ) for( int k=0 ; k<2 ; k++ ) neighbors[d].neighbors[i][y2+j][z2+k] = &temp.neighbors[i][1][1]->children[Cube::CornerIndex(x2,j,k)]; + } + } + { + int j = y1<<1; + if( temp.neighbors[1][j][1] ) + { + if( flags[1][j][1] && !temp.neighbors[1][j][1]->children ) temp.neighbors[1][j][1]->initChildren(); + if( temp.neighbors[1][j][1]->children ) for( int i=0 ; i<2 ; i++ ) for( int k=0 ; k<2 ; k++ ) neighbors[d].neighbors[x2+i][j][z2+k] = &temp.neighbors[1][j][1]->children[Cube::CornerIndex(i,y2,k)]; + } + } + { + int k = z1<<1; + if( temp.neighbors[1][1][k] ) + { + if( flags[1][1][k] && !temp.neighbors[1][1][k]->children ) temp.neighbors[1][1][k]->initChildren(); + if( temp.neighbors[1][1][k]->children ) for( int i=0 ; i<2 ; i++ ) for( int j=0 ; j<2 ; j++ ) neighbors[d].neighbors[x2+i][y2+j][k] = &temp.neighbors[1][1][k]->children[Cube::CornerIndex(i,j,z2)]; + } + } + + // Set the neighbors from across the edges + { + int i=x1<<1 , j=y1<<1; + if( temp.neighbors[i][j][1] ) + { + if( flags[i][j][1] && !temp.neighbors[i][j][1]->children ) temp.neighbors[i][j][1]->initChildren(); + if( temp.neighbors[i][j][1]->children ) for( int k=0 ; k<2 ; k++ ) neighbors[d].neighbors[i][j][z2+k] = &temp.neighbors[i][j][1]->children[Cube::CornerIndex(x2,y2,k)]; + } + } + { + int i=x1<<1 , k=z1<<1; + if( temp.neighbors[i][1][k] ) + { + if( flags[i][1][k] && !temp.neighbors[i][1][k]->children ) temp.neighbors[i][1][k]->initChildren(); + if( temp.neighbors[i][1][k]->children ) for( int j=0 ; j<2 ; j++ ) neighbors[d].neighbors[i][y2+j][k] = &temp.neighbors[i][1][k]->children[Cube::CornerIndex(x2,j,z2)]; + } + } + { + int j=y1<<1 , k=z1<<1; + if( temp.neighbors[1][j][k] ) + { + if( flags[1][j][k] && !temp.neighbors[1][j][k]->children ) temp.neighbors[1][j][k]->initChildren(); + if( temp.neighbors[1][j][k]->children ) for( int i=0 ; i<2 ; i++ ) neighbors[d].neighbors[x2+i][j][k] = &temp.neighbors[1][j][k]->children[Cube::CornerIndex(i,y2,z2)]; + } + } + + // Set the neighbor from across the corner + { + int i=x1<<1 , j=y1<<1 , k=z1<<1; + if( temp.neighbors[i][j][k] ) + { + if( flags[i][j][k] && !temp.neighbors[i][j][k]->children ) temp.neighbors[i][j][k]->initChildren(); + if( temp.neighbors[i][j][k]->children ) neighbors[d].neighbors[i][j][k] = &temp.neighbors[i][j][k]->children[Cube::CornerIndex(x2,y2,z2)]; + } + } + } + } + return neighbors[d]; + } + + template + typename OctNode::Neighbors3& OctNode::NeighborKey3::getNeighbors(OctNode* node){ + int d=node->depth(); + if(node!=neighbors[d].neighbors[1][1][1]){ + neighbors[d].clear(); + + if(!node->parent){neighbors[d].neighbors[1][1][1]=node;} + else{ + int i,j,k,x1,y1,z1,x2,y2,z2; + int idx=int(node-node->parent->children); + Cube::FactorCornerIndex( idx ,x1,y1,z1); + Cube::FactorCornerIndex((~idx)&7,x2,y2,z2); + for(i=0;i<2;i++){ + for(j=0;j<2;j++){ + for(k=0;k<2;k++){ + neighbors[d].neighbors[x2+i][y2+j][z2+k]=&node->parent->children[Cube::CornerIndex(i,j,k)]; + } + } + } + Neighbors3& temp=getNeighbors(node->parent); + + // Set the neighbors from across the faces + i=x1<<1; + if(temp.neighbors[i][1][1] && temp.neighbors[i][1][1]->children){ + for(j=0;j<2;j++){for(k=0;k<2;k++){neighbors[d].neighbors[i][y2+j][z2+k]=&temp.neighbors[i][1][1]->children[Cube::CornerIndex(x2,j,k)];}} + } + j=y1<<1; + if(temp.neighbors[1][j][1] && temp.neighbors[1][j][1]->children){ + for(i=0;i<2;i++){for(k=0;k<2;k++){neighbors[d].neighbors[x2+i][j][z2+k]=&temp.neighbors[1][j][1]->children[Cube::CornerIndex(i,y2,k)];}} + } + k=z1<<1; + if(temp.neighbors[1][1][k] && temp.neighbors[1][1][k]->children){ + for(i=0;i<2;i++){for(j=0;j<2;j++){neighbors[d].neighbors[x2+i][y2+j][k]=&temp.neighbors[1][1][k]->children[Cube::CornerIndex(i,j,z2)];}} + } + + // Set the neighbors from across the edges + i=x1<<1; j=y1<<1; + if(temp.neighbors[i][j][1] && temp.neighbors[i][j][1]->children){ + for(k=0;k<2;k++){neighbors[d].neighbors[i][j][z2+k]=&temp.neighbors[i][j][1]->children[Cube::CornerIndex(x2,y2,k)];} + } + i=x1<<1; k=z1<<1; + if(temp.neighbors[i][1][k] && temp.neighbors[i][1][k]->children){ + for(j=0;j<2;j++){neighbors[d].neighbors[i][y2+j][k]=&temp.neighbors[i][1][k]->children[Cube::CornerIndex(x2,j,z2)];} + } + j=y1<<1; k=z1<<1; + if(temp.neighbors[1][j][k] && temp.neighbors[1][j][k]->children){ + for(i=0;i<2;i++){neighbors[d].neighbors[x2+i][j][k]=&temp.neighbors[1][j][k]->children[Cube::CornerIndex(i,y2,z2)];} + } + + // Set the neighbor from across the corner + i=x1<<1; j=y1<<1; k=z1<<1; + if(temp.neighbors[i][j][k] && temp.neighbors[i][j][k]->children){ + neighbors[d].neighbors[i][j][k]=&temp.neighbors[i][j][k]->children[Cube::CornerIndex(x2,y2,z2)]; + } + } + } + return neighbors[node->depth()]; + } + + /////////////////////// + // ConstNeighborKey3 // + /////////////////////// + template + OctNode::ConstNeighbors3::ConstNeighbors3(void){clear();} + template + void OctNode::ConstNeighbors3::clear(void){ + for(int i=0;i<3;i++){for(int j=0;j<3;j++){for(int k=0;k<3;k++){neighbors[i][j][k]=NULL;}}} + } + template + OctNode::ConstNeighborKey3::ConstNeighborKey3(void){neighbors=NULL;} + template + OctNode::ConstNeighborKey3::~ConstNeighborKey3(void){ + if(neighbors){delete[] neighbors;} + neighbors=NULL; + } + + template + void OctNode::ConstNeighborKey3::set(int d){ + if(neighbors){delete[] neighbors;} + neighbors=NULL; + if(d<0){return;} + neighbors=new ConstNeighbors3[d+1]; + } + template + typename OctNode::ConstNeighbors3& OctNode::ConstNeighborKey3::getNeighbors(const OctNode* node){ + int d=node->depth(); + if(node!=neighbors[d].neighbors[1][1][1]){ + neighbors[d].clear(); + + if(!node->parent){neighbors[d].neighbors[1][1][1]=node;} + else{ + int i,j,k,x1,y1,z1,x2,y2,z2; + int idx=int(node-node->parent->children); + Cube::FactorCornerIndex( idx ,x1,y1,z1); + Cube::FactorCornerIndex((~idx)&7,x2,y2,z2); + for(i=0;i<2;i++){ + for(j=0;j<2;j++){ + for(k=0;k<2;k++){ + neighbors[d].neighbors[x2+i][y2+j][z2+k]=&node->parent->children[Cube::CornerIndex(i,j,k)]; + } + } + } + ConstNeighbors3& temp=getNeighbors(node->parent); + + // Set the neighbors from across the faces + i=x1<<1; + if(temp.neighbors[i][1][1] && temp.neighbors[i][1][1]->children){ + for(j=0;j<2;j++){for(k=0;k<2;k++){neighbors[d].neighbors[i][y2+j][z2+k]=&temp.neighbors[i][1][1]->children[Cube::CornerIndex(x2,j,k)];}} + } + j=y1<<1; + if(temp.neighbors[1][j][1] && temp.neighbors[1][j][1]->children){ + for(i=0;i<2;i++){for(k=0;k<2;k++){neighbors[d].neighbors[x2+i][j][z2+k]=&temp.neighbors[1][j][1]->children[Cube::CornerIndex(i,y2,k)];}} + } + k=z1<<1; + if(temp.neighbors[1][1][k] && temp.neighbors[1][1][k]->children){ + for(i=0;i<2;i++){for(j=0;j<2;j++){neighbors[d].neighbors[x2+i][y2+j][k]=&temp.neighbors[1][1][k]->children[Cube::CornerIndex(i,j,z2)];}} + } + + // Set the neighbors from across the edges + i=x1<<1; j=y1<<1; + if(temp.neighbors[i][j][1] && temp.neighbors[i][j][1]->children){ + for(k=0;k<2;k++){neighbors[d].neighbors[i][j][z2+k]=&temp.neighbors[i][j][1]->children[Cube::CornerIndex(x2,y2,k)];} + } + i=x1<<1; k=z1<<1; + if(temp.neighbors[i][1][k] && temp.neighbors[i][1][k]->children){ + for(j=0;j<2;j++){neighbors[d].neighbors[i][y2+j][k]=&temp.neighbors[i][1][k]->children[Cube::CornerIndex(x2,j,z2)];} + } + j=y1<<1; k=z1<<1; + if(temp.neighbors[1][j][k] && temp.neighbors[1][j][k]->children){ + for(i=0;i<2;i++){neighbors[d].neighbors[x2+i][j][k]=&temp.neighbors[1][j][k]->children[Cube::CornerIndex(i,y2,z2)];} + } + + // Set the neighbor from across the corner + i=x1<<1; j=y1<<1; k=z1<<1; + if(temp.neighbors[i][j][k] && temp.neighbors[i][j][k]->children){ + neighbors[d].neighbors[i][j][k]=&temp.neighbors[i][j][k]->children[Cube::CornerIndex(x2,y2,z2)]; + } + } + } + return neighbors[node->depth()]; + } + template + typename OctNode::ConstNeighbors3& OctNode::ConstNeighborKey3::getNeighbors( const OctNode* node , int minDepth ) + { + int d=node->depth(); + if( dparent->children); + Cube::FactorCornerIndex( idx ,x1,y1,z1); + Cube::FactorCornerIndex((~idx)&7,x2,y2,z2); + + ConstNeighbors3& temp=getNeighbors( node->parent , minDepth ); + + // Set the syblings + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + neighbors[d].neighbors[x2+i][y2+j][z2+k] = &node->parent->children[ Cube::CornerIndex(i,j,k) ]; + + // Set the neighbors from across the faces + i=x1<<1; + if( temp.neighbors[i][1][1] && temp.neighbors[i][1][1]->children ) + for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) neighbors[d].neighbors[i][y2+j][z2+k] = &temp.neighbors[i][1][1]->children[Cube::CornerIndex(x2,j,k)]; + + j=y1<<1; + if( temp.neighbors[1][j][1] && temp.neighbors[1][j][1]->children ) + for( i=0 ; i<2 ; i++ ) for( k=0 ; k<2 ; k++ ) neighbors[d].neighbors[x2+i][j][z2+k] = &temp.neighbors[1][j][1]->children[Cube::CornerIndex(i,y2,k)]; + + k=z1<<1; + if( temp.neighbors[1][1][k] && temp.neighbors[1][1][k]->children ) + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) neighbors[d].neighbors[x2+i][y2+j][k] = &temp.neighbors[1][1][k]->children[Cube::CornerIndex(i,j,z2)]; + + // Set the neighbors from across the edges + i=x1<<1 , j=y1<<1; + if( temp.neighbors[i][j][1] && temp.neighbors[i][j][1]->children ) + for( k=0 ; k<2 ; k++ ) neighbors[d].neighbors[i][j][z2+k] = &temp.neighbors[i][j][1]->children[Cube::CornerIndex(x2,y2,k)]; + + i=x1<<1 , k=z1<<1; + if( temp.neighbors[i][1][k] && temp.neighbors[i][1][k]->children ) + for( j=0 ; j<2 ; j++ ) neighbors[d].neighbors[i][y2+j][k] = &temp.neighbors[i][1][k]->children[Cube::CornerIndex(x2,j,z2)]; + + j=y1<<1 , k=z1<<1; + if( temp.neighbors[1][j][k] && temp.neighbors[1][j][k]->children ) + for( i=0 ; i<2 ; i++ ) neighbors[d].neighbors[x2+i][j][k] = &temp.neighbors[1][j][k]->children[Cube::CornerIndex(i,y2,z2)]; + + // Set the neighbor from across the corner + i=x1<<1 , j=y1<<1 , k=z1<<1; + if( temp.neighbors[i][j][k] && temp.neighbors[i][j][k]->children ) + neighbors[d].neighbors[i][j][k] = &temp.neighbors[i][j][k]->children[Cube::CornerIndex(x2,y2,z2)]; + } + } + return neighbors[node->depth()]; + } + + template< class NodeData , class Real > OctNode< NodeData , Real >::Neighbors5::Neighbors5( void ){ clear(); } + template< class NodeData , class Real > OctNode< NodeData , Real >::ConstNeighbors5::ConstNeighbors5( void ){ clear(); } + template< class NodeData , class Real > + void OctNode< NodeData , Real >::Neighbors5::clear( void ) + { + for( int i=0 ; i<5 ; i++ ) for( int j=0 ; j<5 ; j++ ) for( int k=0 ; k<5 ; k++ ) neighbors[i][j][k] = NULL; + } + template< class NodeData , class Real > + void OctNode< NodeData , Real >::ConstNeighbors5::clear( void ) + { + for( int i=0 ; i<5 ; i++ ) for( int j=0 ; j<5 ; j++ ) for( int k=0 ; k<5 ; k++ ) neighbors[i][j][k] = NULL; + } + template< class NodeData , class Real > + OctNode< NodeData , Real >::NeighborKey5::NeighborKey5( void ) + { + _depth = -1; + neighbors = NULL; + } + template< class NodeData , class Real > + OctNode< NodeData , Real >::ConstNeighborKey5::ConstNeighborKey5( void ) + { + _depth = -1; + neighbors = NULL; + } + template< class NodeData , class Real > + OctNode< NodeData , Real >::NeighborKey5::~NeighborKey5( void ) + { + if( neighbors ) delete[] neighbors; + neighbors = NULL; + } + template< class NodeData , class Real > + OctNode< NodeData , Real >::ConstNeighborKey5::~ConstNeighborKey5( void ) + { + if( neighbors ) delete[] neighbors; + neighbors = NULL; + } + template< class NodeData , class Real > + void OctNode< NodeData , Real >::NeighborKey5::set( int d ) + { + if( neighbors ) delete[] neighbors; + neighbors = NULL; + if(d<0) return; + _depth = d; + neighbors=new Neighbors5[d+1]; + } + template< class NodeData , class Real > + void OctNode< NodeData , Real >::ConstNeighborKey5::set( int d ) + { + if( neighbors ) delete[] neighbors; + neighbors = NULL; + if(d<0) return; + _depth = d; + neighbors=new ConstNeighbors5[d+1]; + } + template< class NodeData , class Real > + typename OctNode< NodeData , Real >::Neighbors5& OctNode< NodeData , Real >::NeighborKey5::getNeighbors( OctNode* node ) + { + int d=node->depth(); + if( node!=neighbors[d].neighbors[2][2][2] ) + { + neighbors[d].clear(); + + if( !node->parent ) neighbors[d].neighbors[2][2][2]=node; + else + { + getNeighbors( node->parent ); + Neighbors5& temp = neighbors[d-1]; + int x1 , y1 , z1 , x2 , y2 , z2; + int idx = int( node - node->parent->children ); + Cube::FactorCornerIndex( idx , x1 , y1 , z1 ); + + Neighbors5& n = neighbors[d]; + Cube::FactorCornerIndex( (~idx)&7 , x2 , y2 , z2 ); + int i , j , k; + int fx0 = x2+1 , fy0 = y2+1 , fz0 = z2+1; // Indices of the bottom left corner of the parent within the 5x5x5 + int cx1 = x1*2+1 , cy1 = y1*2+1 , cz1 = z1*2+1; + int cx2 = x2*2+1 , cy2 = y2*2+1 , cz2 = z2*2+1; + int fx1 = x1*3 , fy1 = y1*3 , fz1 = z1*3; + int fx2 = x2*4 , fy2 = y2*4 , fz2 = z2*4; + + // Set the syblings + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx0+i][fy0+j][fz0+k] = node->parent->children + Cube::CornerIndex( i , j , k ); + + // Set the neighbors from across the faces + if( temp.neighbors[cx1][2][2] && temp.neighbors[cx1][2][2]->children ) + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx1+i][fy0+j][fz0+k] = temp.neighbors[cx1][2][2]->children + Cube::CornerIndex( i , j , k ); + if( temp.neighbors[2][cy1][2] && temp.neighbors[2][cy1][2]->children ) + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx0+i][fy1+j][fz0+k] = temp.neighbors[2][cy1][2]->children + Cube::CornerIndex( i , j , k ); + if( temp.neighbors[2][2][cz1] && temp.neighbors[2][2][cz1]->children ) + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx0+i][fy0+j][fz1+k] = temp.neighbors[2][2][cz1]->children + Cube::CornerIndex( i , j , k ); + if( temp.neighbors[cx2][2][2] && temp.neighbors[cx2][2][2]->children ) + for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx2 ][fy0+j][fz0+k] = temp.neighbors[cx2][2][2]->children + Cube::CornerIndex( x1 , j , k ); + if( temp.neighbors[2][cy2][2] && temp.neighbors[2][cy2][2]->children ) + for( i=0 ; i<2 ; i++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx0+i][fy2 ][fz0+k] = temp.neighbors[2][cy2][2]->children + Cube::CornerIndex( i , y1 , k ); + if( temp.neighbors[2][2][cz2] && temp.neighbors[2][2][cz2]->children ) + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) + n.neighbors[fx0+i][fy0+j][fz2 ] = temp.neighbors[2][2][cz2]->children + Cube::CornerIndex( i , j , z1 ); + + // Set the neighbors from across the edges + if( temp.neighbors[cx1][cy1][2] && temp.neighbors[cx1][cy1][2]->children ) + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx1+i][fy1+j][fz0+k] = temp.neighbors[cx1][cy1][2]->children + Cube::CornerIndex( i , j , k ); + if( temp.neighbors[cx1][2][cz1] && temp.neighbors[cx1][2][cz1]->children ) + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx1+i][fy0+j][fz1+k] = temp.neighbors[cx1][2][cz1]->children + Cube::CornerIndex( i , j , k ); + if( temp.neighbors[2][cy1][cz1] && temp.neighbors[2][cy1][cz1]->children ) + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx0+i][fy1+j][fz1+k] = temp.neighbors[2][cy1][cz1]->children + Cube::CornerIndex( i , j , k ); + if( temp.neighbors[cx1][cy2][2] && temp.neighbors[cx1][cy2][2]->children ) + for( i=0 ; i<2 ; i++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx1+i][fy2 ][fz0+k] = temp.neighbors[cx1][cy2][2]->children + Cube::CornerIndex( i , y1 , k ); + if( temp.neighbors[cx1][2][cz2] && temp.neighbors[cx1][2][cz2]->children ) + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) + n.neighbors[fx1+i][fy0+j][fz2 ] = temp.neighbors[cx1][2][cz2]->children + Cube::CornerIndex( i , j , z1 ); + if( temp.neighbors[cx2][cy1][2] && temp.neighbors[cx2][cy1][2]->children ) + for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx2 ][fy1+j][fz0+k] = temp.neighbors[cx2][cy1][2]->children + Cube::CornerIndex( x1 , j , k ); + if( temp.neighbors[2][cy1][cz2] && temp.neighbors[2][cy1][cz2]->children ) + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) + n.neighbors[fx0+i][fy1+j][fz2 ] = temp.neighbors[2][cy1][cz2]->children + Cube::CornerIndex( i , j , z1 ); + if( temp.neighbors[cx2][2][cz1] && temp.neighbors[cx2][2][cz1]->children ) + for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx2 ][fy0+j][fz1+k] = temp.neighbors[cx2][2][cz1]->children + Cube::CornerIndex( x1 , j , k ); + if( temp.neighbors[2][cy2][cz1] && temp.neighbors[2][cy2][cz1]->children ) + for( i=0 ; i<2 ; i++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx0+i][fy2 ][fz1+k] = temp.neighbors[2][cy2][cz1]->children + Cube::CornerIndex( i , y1 , k ); + if( temp.neighbors[cx2][cy2][2] && temp.neighbors[cx2][cy2][2]->children ) + for( k=0 ; k<2 ; k++ ) + n.neighbors[fx2 ][fy2 ][fz0+k] = temp.neighbors[cx2][cy2][2]->children + Cube::CornerIndex( x1 , y1 , k ); + if( temp.neighbors[cx2][2][cz2] && temp.neighbors[cx2][2][cz2]->children ) + for( j=0 ; j<2 ; j++ ) + n.neighbors[fx2 ][fy0+j][fz2 ] = temp.neighbors[cx2][2][cz2]->children + Cube::CornerIndex( x1 , j , z1 ); + if( temp.neighbors[2][cy2][cz2] && temp.neighbors[2][cy2][cz2]->children ) + for( i=0 ; i<2 ; i++ ) + n.neighbors[fx0+i][fy2 ][fz2 ] = temp.neighbors[2][cy2][cz2]->children + Cube::CornerIndex( i , y1 , z1 ); + + // Set the neighbor from across the corners + if( temp.neighbors[cx1][cy1][cz1] && temp.neighbors[cx1][cy1][cz1]->children ) + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx1+i][fy1+j][fz1+k] = temp.neighbors[cx1][cy1][cz1]->children + Cube::CornerIndex( i , j , k ); + if( temp.neighbors[cx1][cy1][cz2] && temp.neighbors[cx1][cy1][cz2]->children ) + for( i=0 ; i<2 ; i++ ) for( j=0 ; j<2 ; j++ ) + n.neighbors[fx1+i][fy1+j][fz2 ] = temp.neighbors[cx1][cy1][cz2]->children + Cube::CornerIndex( i , j , z1 ); + if( temp.neighbors[cx1][cy2][cz1] && temp.neighbors[cx1][cy2][cz1]->children ) + for( i=0 ; i<2 ; i++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx1+i][fy2 ][fz1+k] = temp.neighbors[cx1][cy2][cz1]->children + Cube::CornerIndex( i , y1 , k ); + if( temp.neighbors[cx2][cy1][cz1] && temp.neighbors[cx2][cy1][cz1]->children ) + for( j=0 ; j<2 ; j++ ) for( k=0 ; k<2 ; k++ ) + n.neighbors[fx2 ][fy1+j][fz1+k] = temp.neighbors[cx2][cy1][cz1]->children + Cube::CornerIndex( x1 , j , k ); + if( temp.neighbors[cx1][cy2][cz2] && temp.neighbors[cx1][cy2][cz2]->children ) + for( i=0 ; i<2 ; i++ ) + n.neighbors[fx1+i][fy2 ][fz2 ] = temp.neighbors[cx1][cy2][cz2]->children + Cube::CornerIndex( i , y1 , z1 ); + if( temp.neighbors[cx2][cy1][cz2] && temp.neighbors[cx2][cy1][cz2]->children ) + for( j=0 ; j<2 ; j++ ) + n.neighbors[fx2 ][fy1+j][fz2 ] = temp.neighbors[cx2][cy1][cz2]->children + Cube::CornerIndex( x1 , j , z1 ); + if( temp.neighbors[cx2][cy2][cz1] && temp.neighbors[cx2][cy2][cz1]->children ) + for( k=0 ; k<2 ; k++ ) + n.neighbors[fx2 ][fy2 ][fz1+k] = temp.neighbors[cx2][cy2][cz1]->children + Cube::CornerIndex( x1 , y1 , k ); + if( temp.neighbors[cx2][cy2][cz2] && temp.neighbors[cx2][cy2][cz2]->children ) + n.neighbors[fx2 ][fy2 ][fz2 ] = temp.neighbors[cx2][cy2][cz2]->children + Cube::CornerIndex( x1 , y1 , z1 ); + } + } + return neighbors[d]; + } + template< class NodeData , class Real > + typename OctNode< NodeData , Real >::Neighbors5& OctNode< NodeData , Real >::NeighborKey5::setNeighbors( OctNode* node , int xStart , int xEnd , int yStart , int yEnd , int zStart , int zEnd ) + { + int d=node->depth(); + if( node!=neighbors[d].neighbors[2][2][2] ) + { + neighbors[d].clear(); + + if( !node->parent ) neighbors[d].neighbors[2][2][2]=node; + else + { + setNeighbors( node->parent , xStart , xEnd , yStart , yEnd , zStart , zEnd ); + Neighbors5& temp = neighbors[d-1]; + int x1 , y1 , z1 , x2 , y2 , z2 , ii , jj , kk; + int idx = int( node-node->parent->children ); + Cube::FactorCornerIndex( idx , x1 , y1 , z1 ); + + for( int i=xStart ; i>1); + for( int j=yStart ; j>1); + for( int k=zStart ; k>1); + if(temp.neighbors[x2][y2][z2] ) + { + if( !temp.neighbors[x2][y2][z2]->children ) temp.neighbors[x2][y2][z2]->initChildren(); + neighbors[d].neighbors[i][j][k] = temp.neighbors[x2][y2][z2]->children + Cube::CornerIndex(ii,jj,kk); + } + } + } + } + } + } + return neighbors[d]; + } + template< class NodeData , class Real > + typename OctNode< NodeData , Real >::ConstNeighbors5& OctNode< NodeData , Real >::ConstNeighborKey5::getNeighbors( const OctNode* node ) + { + int d=node->depth(); + if( node!=neighbors[d].neighbors[2][2][2] ) + { + neighbors[d].clear(); + + if(!node->parent) neighbors[d].neighbors[2][2][2]=node; + else + { + getNeighbors( node->parent ); + ConstNeighbors5& temp = neighbors[d-1]; + int x1,y1,z1,x2,y2,z2,ii,jj,kk; + int idx=int(node-node->parent->children); + Cube::FactorCornerIndex(idx,x1,y1,z1); + + for(int i=0;i<5;i++) + { + x2=i+x1; + ii=x2&1; + x2=1+(x2>>1); + for(int j=0;j<5;j++) + { + y2=j+y1; + jj=y2&1; + y2=1+(y2>>1); + for(int k=0;k<5;k++) + { + z2=k+z1; + kk=z2&1; + z2=1+(z2>>1); + if(temp.neighbors[x2][y2][z2] && temp.neighbors[x2][y2][z2]->children) + neighbors[d].neighbors[i][j][k] = temp.neighbors[x2][y2][z2]->children + Cube::CornerIndex(ii,jj,kk); + } + } + } + } + } + return neighbors[d]; + } + + + template + int OctNode::write(const char* fileName) const{ + FILE* fp=fopen(fileName,"wb"); + if(!fp){return 0;} + int ret=write(fp); + fclose(fp); + return ret; + } + template + int OctNode::write(FILE* fp) const{ + fwrite(this,sizeof(OctNode),1,fp); + if(children){for(int i=0;i + int OctNode::read(const char* fileName){ + FILE* fp=fopen(fileName,"rb"); + if(!fp){return 0;} + int ret=read(fp); + fclose(fp); + return ret; + } + template + int OctNode::read(FILE* fp){ + fread(this,sizeof(OctNode),1,fp); + parent=NULL; + if(children){ + children=NULL; + initChildren(); + for(int i=0;i + int OctNode::width(int maxDepth) const { + int d=depth(); + return 1<<(maxDepth-d); + } + template + void OctNode::centerIndex(int maxDepth,int index[DIMENSION]) const { + int d,o[3]; + depthAndOffset(d,o); + for(int i=0;i::CornerIndex(maxDepth,d+1,o[i]<<1,1);} + } + + } +} diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/polynomial.h b/pcl-1.7/pcl/surface/3rdparty/poisson4/polynomial.h new file mode 100644 index 0000000..f43f5db --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/polynomial.h @@ -0,0 +1,102 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#ifndef POLYNOMIAL_INCLUDED +#define POLYNOMIAL_INCLUDED + +#include + +namespace pcl +{ + namespace poisson + { + + template< int Degree > + class Polynomial{ + public: + double coefficients[Degree+1]; + + Polynomial(void); + template + Polynomial(const Polynomial& P); + double operator()( double t ) const; + double integral( double tMin , double tMax ) const; + + int operator == (const Polynomial& p) const; + int operator != (const Polynomial& p) const; + int isZero(void) const; + void setZero(void); + + template + Polynomial& operator = (const Polynomial &p); + Polynomial& operator += (const Polynomial& p); + Polynomial& operator -= (const Polynomial& p); + Polynomial operator - (void) const; + Polynomial operator + (const Polynomial& p) const; + Polynomial operator - (const Polynomial& p) const; + template + Polynomial operator * (const Polynomial& p) const; + + Polynomial& operator += ( double s ); + Polynomial& operator -= ( double s ); + Polynomial& operator *= ( double s ); + Polynomial& operator /= ( double s ); + Polynomial operator + ( double s ) const; + Polynomial operator - ( double s ) const; + Polynomial operator * ( double s ) const; + Polynomial operator / ( double s ) const; + + Polynomial scale( double s ) const; + Polynomial shift( double t ) const; + + Polynomial derivative(void) const; + Polynomial integral(void) const; + + void printnl(void) const; + + Polynomial& addScaled(const Polynomial& p,double scale); + + static void Negate(const Polynomial& in,Polynomial& out); + static void Subtract(const Polynomial& p1,const Polynomial& p2,Polynomial& q); + static void Scale(const Polynomial& p,double w,Polynomial& q); + static void AddScaled(const Polynomial& p1,double w1,const Polynomial& p2,double w2,Polynomial& q); + static void AddScaled(const Polynomial& p1,const Polynomial& p2,double w2,Polynomial& q); + static void AddScaled(const Polynomial& p1,double w1,const Polynomial& p2,Polynomial& q); + + void getSolutions(double c,std::vector& roots,double EPS) const; + + static Polynomial BSplineComponent( int i ); + }; + + + } +} + + +#include "polynomial.hpp" +#endif // POLYNOMIAL_INCLUDED diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/polynomial.hpp b/pcl-1.7/pcl/surface/3rdparty/poisson4/polynomial.hpp new file mode 100644 index 0000000..45973db --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/polynomial.hpp @@ -0,0 +1,325 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#include +#include +#include +#include "factor.h" + +//////////////// +// Polynomial // +//////////////// + +namespace pcl +{ + namespace poisson + { + + + template + Polynomial::Polynomial(void){memset(coefficients,0,sizeof(double)*(Degree+1));} + template + template + Polynomial::Polynomial(const Polynomial& P){ + memset(coefficients,0,sizeof(double)*(Degree+1)); + for(int i=0;i<=Degree && i<=Degree2;i++){coefficients[i]=P.coefficients[i];} + } + + + template + template + Polynomial& Polynomial::operator = (const Polynomial &p){ + int d=Degree + Polynomial Polynomial::derivative(void) const{ + Polynomial p; + for(int i=0;i + Polynomial Polynomial::integral(void) const{ + Polynomial p; + p.coefficients[0]=0; + for(int i=0;i<=Degree;i++){p.coefficients[i+1]=coefficients[i]/(i+1);} + return p; + } + template<> double Polynomial< 0 >::operator() ( double t ) const { return coefficients[0]; } + template<> double Polynomial< 1 >::operator() ( double t ) const { return coefficients[0]+coefficients[1]*t; } + template<> double Polynomial< 2 >::operator() ( double t ) const { return coefficients[0]+(coefficients[1]+coefficients[2]*t)*t; } + template + double Polynomial::operator() ( double t ) const{ + double v=coefficients[Degree]; + for( int d=Degree-1 ; d>=0 ; d-- ) v = v*t + coefficients[d]; + return v; + } + template + double Polynomial::integral( double tMin , double tMax ) const + { + double v=0; + double t1,t2; + t1=tMin; + t2=tMax; + for(int i=0;i<=Degree;i++){ + v+=coefficients[i]*(t2-t1)/(i+1); + if(t1!=-DBL_MAX && t1!=DBL_MAX){t1*=tMin;} + if(t2!=-DBL_MAX && t2!=DBL_MAX){t2*=tMax;} + } + return v; + } + template + int Polynomial::operator == (const Polynomial& p) const{ + for(int i=0;i<=Degree;i++){if(coefficients[i]!=p.coefficients[i]){return 0;}} + return 1; + } + template + int Polynomial::operator != (const Polynomial& p) const{ + for(int i=0;i<=Degree;i++){if(coefficients[i]==p.coefficients[i]){return 0;}} + return 1; + } + template + int Polynomial::isZero(void) const{ + for(int i=0;i<=Degree;i++){if(coefficients[i]!=0){return 0;}} + return 1; + } + template + void Polynomial::setZero(void){memset(coefficients,0,sizeof(double)*(Degree+1));} + + template + Polynomial& Polynomial::addScaled(const Polynomial& p,double s){ + for(int i=0;i<=Degree;i++){coefficients[i]+=p.coefficients[i]*s;} + return *this; + } + template + Polynomial& Polynomial::operator += (const Polynomial& p){ + for(int i=0;i<=Degree;i++){coefficients[i]+=p.coefficients[i];} + return *this; + } + template + Polynomial& Polynomial::operator -= (const Polynomial& p){ + for(int i=0;i<=Degree;i++){coefficients[i]-=p.coefficients[i];} + return *this; + } + template + Polynomial Polynomial::operator + (const Polynomial& p) const{ + Polynomial q; + for(int i=0;i<=Degree;i++){q.coefficients[i]=(coefficients[i]+p.coefficients[i]);} + return q; + } + template + Polynomial Polynomial::operator - (const Polynomial& p) const{ + Polynomial q; + for(int i=0;i<=Degree;i++) {q.coefficients[i]=coefficients[i]-p.coefficients[i];} + return q; + } + template + void Polynomial::Scale(const Polynomial& p,double w,Polynomial& q){ + for(int i=0;i<=Degree;i++){q.coefficients[i]=p.coefficients[i]*w;} + } + template + void Polynomial::AddScaled(const Polynomial& p1,double w1,const Polynomial& p2,double w2,Polynomial& q){ + for(int i=0;i<=Degree;i++){q.coefficients[i]=p1.coefficients[i]*w1+p2.coefficients[i]*w2;} + } + template + void Polynomial::AddScaled(const Polynomial& p1,double w1,const Polynomial& p2,Polynomial& q){ + for(int i=0;i<=Degree;i++){q.coefficients[i]=p1.coefficients[i]*w1+p2.coefficients[i];} + } + template + void Polynomial::AddScaled(const Polynomial& p1,const Polynomial& p2,double w2,Polynomial& q){ + for(int i=0;i<=Degree;i++){q.coefficients[i]=p1.coefficients[i]+p2.coefficients[i]*w2;} + } + + template + void Polynomial::Subtract(const Polynomial &p1,const Polynomial& p2,Polynomial& q){ + for(int i=0;i<=Degree;i++){q.coefficients[i]=p1.coefficients[i]-p2.coefficients[i];} + } + template + void Polynomial::Negate(const Polynomial& in,Polynomial& out){ + out=in; + for(int i=0;i<=Degree;i++){out.coefficients[i]=-out.coefficients[i];} + } + + template + Polynomial Polynomial::operator - (void) const{ + Polynomial q=*this; + for(int i=0;i<=Degree;i++){q.coefficients[i]=-q.coefficients[i];} + return q; + } + template + template + Polynomial Polynomial::operator * (const Polynomial& p) const{ + Polynomial q; + for(int i=0;i<=Degree;i++){for(int j=0;j<=Degree2;j++){q.coefficients[i+j]+=coefficients[i]*p.coefficients[j];}} + return q; + } + + template + Polynomial& Polynomial::operator += ( double s ) + { + coefficients[0]+=s; + return *this; + } + template + Polynomial& Polynomial::operator -= ( double s ) + { + coefficients[0]-=s; + return *this; + } + template + Polynomial& Polynomial::operator *= ( double s ) + { + for(int i=0;i<=Degree;i++){coefficients[i]*=s;} + return *this; + } + template + Polynomial& Polynomial::operator /= ( double s ) + { + for(int i=0;i<=Degree;i++){coefficients[i]/=s;} + return *this; + } + template + Polynomial Polynomial::operator + ( double s ) const + { + Polynomial q=*this; + q.coefficients[0]+=s; + return q; + } + template + Polynomial Polynomial::operator - ( double s ) const + { + Polynomial q=*this; + q.coefficients[0]-=s; + return q; + } + template + Polynomial Polynomial::operator * ( double s ) const + { + Polynomial q; + for(int i=0;i<=Degree;i++){q.coefficients[i]=coefficients[i]*s;} + return q; + } + template + Polynomial Polynomial::operator / ( double s ) const + { + Polynomial q; + for( int i=0 ; i<=Degree ; i++ ) q.coefficients[i] = coefficients[i]/s; + return q; + } + template + Polynomial Polynomial::scale( double s ) const + { + Polynomial q=*this; + double s2=1.0; + for(int i=0;i<=Degree;i++){ + q.coefficients[i]*=s2; + s2/=s; + } + return q; + } + template + Polynomial Polynomial::shift( double t ) const + { + Polynomial q; + for(int i=0;i<=Degree;i++){ + double temp=1; + for(int j=i;j>=0;j--){ + q.coefficients[j]+=coefficients[i]*temp; + temp*=-t*j; + temp/=(i-j+1); + } + } + return q; + } + template + void Polynomial::printnl(void) const{ + for(int j=0;j<=Degree;j++){ + printf("%6.4f x^%d ",coefficients[j],j); + if(j=0){printf("+");} + } + printf("\n"); + } + template + void Polynomial::getSolutions(double c,std::vector& roots,double EPS) const + { + double r[4][2]; + int rCount=0; + roots.clear(); + switch(Degree){ + case 1: + rCount=Factor(coefficients[1],coefficients[0]-c,r,EPS); + break; + case 2: + rCount=Factor(coefficients[2],coefficients[1],coefficients[0]-c,r,EPS); + break; + case 3: + rCount=Factor(coefficients[3],coefficients[2],coefficients[1],coefficients[0]-c,r,EPS); + break; + // case 4: + // rCount=Factor(coefficients[4],coefficients[3],coefficients[2],coefficients[1],coefficients[0]-c,r,EPS); + // break; + default: + printf("Can't solve polynomial of degree: %d\n",Degree); + } + for(int i=0;i + Polynomial< 0 > Polynomial< 0 >::BSplineComponent( int i ) + { + Polynomial p; + p.coefficients[0] = 1.; + return p; + } + template< int Degree > + Polynomial< Degree > Polynomial< Degree >::BSplineComponent( int i ) + { + Polynomial p; + if( i>0 ) + { + Polynomial< Degree > _p = Polynomial< Degree-1 >::BSplineComponent( i-1 ).integral(); + p -= _p; + p.coefficients[0] += _p(1); + } + if( i _p = Polynomial< Degree-1 >::BSplineComponent( i ).integral(); + p += _p; + } + return p; + } + + } +} diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/ppolynomial.h b/pcl-1.7/pcl/surface/3rdparty/poisson4/ppolynomial.h new file mode 100644 index 0000000..0f7a443 --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/ppolynomial.h @@ -0,0 +1,128 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#ifndef P_POLYNOMIAL_INCLUDED +#define P_POLYNOMIAL_INCLUDED + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include "polynomial.h" + +namespace pcl +{ + namespace poisson + { + template + class StartingPolynomial{ + public: + Polynomial p; + double start; + + template + StartingPolynomial operator * (const StartingPolynomial& p) const; + StartingPolynomial scale(double s) const; + StartingPolynomial shift(double t) const; + int operator < (const StartingPolynomial& sp) const; + static int Compare(const void* v1,const void* v2); + }; + + template + class PPolynomial + { + public: + size_t polyCount; + StartingPolynomial* polys; + + PPolynomial(void); + PPolynomial(const PPolynomial& p); + ~PPolynomial(void); + + PPolynomial& operator = (const PPolynomial& p); + + int size(void) const; + + void set( size_t size ); + // Note: this method will sort the elements in sps + void set( StartingPolynomial* sps , int count ); + void reset( size_t newSize ); + + + double operator()( double t ) const; + double integral( double tMin , double tMax ) const; + double Integral( void ) const; + + template + PPolynomial& operator = (const PPolynomial& p); + + PPolynomial operator + (const PPolynomial& p) const; + PPolynomial operator - (const PPolynomial& p) const; + + template + PPolynomial operator * (const Polynomial& p) const; + + template + PPolynomial operator * (const PPolynomial& p) const; + + + PPolynomial& operator += ( double s ); + PPolynomial& operator -= ( double s ); + PPolynomial& operator *= ( double s ); + PPolynomial& operator /= ( double s ); + PPolynomial operator + ( double s ) const; + PPolynomial operator - ( double s ) const; + PPolynomial operator * ( double s ) const; + PPolynomial operator / ( double s ) const; + + PPolynomial& addScaled(const PPolynomial& poly,double scale); + + PPolynomial scale( double s ) const; + PPolynomial shift( double t ) const; + + PPolynomial< Degree-1 > derivative(void) const; + PPolynomial< Degree+1 > integral(void) const; + + void getSolutions(double c,std::vector& roots,double EPS,double min=-DBL_MAX,double max=DBL_MAX) const; + + void printnl( void ) const; + + PPolynomial< Degree+1 > MovingAverage( double radius ); + static PPolynomial BSpline( double radius=0.5 ); + + void write( FILE* fp , int samples , double min , double max ) const; + }; + + + } +} + + +#include "ppolynomial.hpp" +#endif // P_POLYNOMIAL_INCLUDED diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/ppolynomial.hpp b/pcl-1.7/pcl/surface/3rdparty/poisson4/ppolynomial.hpp new file mode 100644 index 0000000..dd64bce --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/ppolynomial.hpp @@ -0,0 +1,441 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#include "factor.h" + +//////////////////////// +// StartingPolynomial // +//////////////////////// + +namespace pcl +{ + namespace poisson + { + + + template + template + StartingPolynomial StartingPolynomial::operator * (const StartingPolynomial& p) const{ + StartingPolynomial sp; + if(start>p.start){sp.start=start;} + else{sp.start=p.start;} + sp.p=this->p*p.p; + return sp; + } + template + StartingPolynomial StartingPolynomial::scale(double s) const{ + StartingPolynomial q; + q.start=start*s; + q.p=p.scale(s); + return q; + } + template + StartingPolynomial StartingPolynomial::shift(double s) const{ + StartingPolynomial q; + q.start=start+s; + q.p=p.shift(s); + return q; + } + + + template + int StartingPolynomial::operator < (const StartingPolynomial& sp) const{ + if(start + int StartingPolynomial::Compare(const void* v1,const void* v2){ + double d=((StartingPolynomial*)(v1))->start-((StartingPolynomial*)(v2))->start; + if (d<0) {return -1;} + else if (d>0) {return 1;} + else {return 0;} + } + + ///////////////// + // PPolynomial // + ///////////////// + template + PPolynomial::PPolynomial(void){ + polyCount=0; + polys=NULL; + } + template + PPolynomial::PPolynomial(const PPolynomial& p){ + polyCount=0; + polys=NULL; + set(p.polyCount); + memcpy(polys,p.polys,sizeof(StartingPolynomial)*p.polyCount); + } + + template + PPolynomial::~PPolynomial(void){ + if(polyCount){free(polys);} + polyCount=0; + polys=NULL; + } + template + void PPolynomial::set(StartingPolynomial* sps,int count){ + int i,c=0; + set(count); + qsort(sps,count,sizeof(StartingPolynomial),StartingPolynomial::Compare); + for( i=0 ; i + int PPolynomial::size(void) const{return int(sizeof(StartingPolynomial)*polyCount);} + + template + void PPolynomial::set( size_t size ) + { + if(polyCount){free(polys);} + polyCount=0; + polys=NULL; + polyCount=size; + if(size){ + polys=(StartingPolynomial*)malloc(sizeof(StartingPolynomial)*size); + memset(polys,0,sizeof(StartingPolynomial)*size); + } + } + template + void PPolynomial::reset( size_t newSize ) + { + polyCount=newSize; + polys=(StartingPolynomial*)realloc(polys,sizeof(StartingPolynomial)*newSize); + } + + template + PPolynomial& PPolynomial::operator = (const PPolynomial& p){ + set(p.polyCount); + memcpy(polys,p.polys,sizeof(StartingPolynomial)*p.polyCount); + return *this; + } + + template + template + PPolynomial& PPolynomial::operator = (const PPolynomial& p){ + set(p.polyCount); + for(int i=0;i + double PPolynomial::operator ()( double t ) const + { + double v=0; + for( int i=0 ; ipolys[i].start ; i++ ) v+=polys[i].p(t); + return v; + } + + template + double PPolynomial::integral( double tMin , double tMax ) const + { + int m=1; + double start,end,s,v=0; + start=tMin; + end=tMax; + if(tMin>tMax){ + m=-1; + start=tMax; + end=tMin; + } + for(int i=0;i + double PPolynomial::Integral(void) const{return integral(polys[0].start,polys[polyCount-1].start);} + template + PPolynomial PPolynomial::operator + (const PPolynomial& p) const{ + PPolynomial q; + int i,j; + size_t idx=0; + q.set(polyCount+p.polyCount); + i=j=-1; + + while(idx=int(p.polyCount)-1) {q.polys[idx]= polys[++i];} + else if (i>=int( polyCount)-1) {q.polys[idx]=p.polys[++j];} + else if(polys[i+1].start + PPolynomial PPolynomial::operator - (const PPolynomial& p) const{ + PPolynomial q; + int i,j; + size_t idx=0; + q.set(polyCount+p.polyCount); + i=j=-1; + + while(idx=int(p.polyCount)-1) {q.polys[idx]= polys[++i];} + else if (i>=int( polyCount)-1) {q.polys[idx].start=p.polys[++j].start;q.polys[idx].p=p.polys[j].p*(-1.0);} + else if(polys[i+1].start + PPolynomial& PPolynomial::addScaled(const PPolynomial& p,double scale){ + int i,j; + StartingPolynomial* oldPolys=polys; + size_t idx=0,cnt=0,oldPolyCount=polyCount; + polyCount=0; + polys=NULL; + set(oldPolyCount+p.polyCount); + i=j=-1; + while(cnt=int( p.polyCount)-1) {polys[idx]=oldPolys[++i];} + else if (i>=int(oldPolyCount)-1) {polys[idx].start= p.polys[++j].start;polys[idx].p=p.polys[j].p*scale;} + else if (oldPolys[i+1].start + template + PPolynomial PPolynomial::operator * (const PPolynomial& p) const{ + PPolynomial q; + StartingPolynomial *sp; + int i,j,spCount=int(polyCount*p.polyCount); + + sp=(StartingPolynomial*)malloc(sizeof(StartingPolynomial)*spCount); + for(i=0;i + template + PPolynomial PPolynomial::operator * (const Polynomial& p) const{ + PPolynomial q; + q.set(polyCount); + for(int i=0;i + PPolynomial PPolynomial::scale( double s ) const + { + PPolynomial q; + q.set(polyCount); + for(size_t i=0;i + PPolynomial PPolynomial::shift( double s ) const + { + PPolynomial q; + q.set(polyCount); + for(size_t i=0;i + PPolynomial PPolynomial::derivative(void) const{ + PPolynomial q; + q.set(polyCount); + for(size_t i=0;i + PPolynomial PPolynomial::integral(void) const{ + int i; + PPolynomial q; + q.set(polyCount); + for(i=0;i + PPolynomial& PPolynomial::operator += ( double s ) {polys[0].p+=s;} + template + PPolynomial& PPolynomial::operator -= ( double s ) {polys[0].p-=s;} + template + PPolynomial& PPolynomial::operator *= ( double s ) + { + for(int i=0;i + PPolynomial& PPolynomial::operator /= ( double s ) + { + for(size_t i=0;i + PPolynomial PPolynomial::operator + ( double s ) const + { + PPolynomial q=*this; + q+=s; + return q; + } + template + PPolynomial PPolynomial::operator - ( double s ) const + { + PPolynomial q=*this; + q-=s; + return q; + } + template + PPolynomial PPolynomial::operator * ( double s ) const + { + PPolynomial q=*this; + q*=s; + return q; + } + template + PPolynomial PPolynomial::operator / ( double s ) const + { + PPolynomial q=*this; + q/=s; + return q; + } + + template + void PPolynomial::printnl(void) const{ + Polynomial p; + + if(!polyCount){ + Polynomial p; + printf("[-Infinity,Infinity]\n"); + } + else{ + for(size_t i=0;i + PPolynomial< 0 > PPolynomial< 0 >::BSpline( double radius ) + { + PPolynomial q; + q.set(2); + + q.polys[0].start=-radius; + q.polys[1].start= radius; + + q.polys[0].p.coefficients[0]= 1.0; + q.polys[1].p.coefficients[0]=-1.0; + return q; + } + template< int Degree > + PPolynomial< Degree > PPolynomial::BSpline( double radius ) + { + return PPolynomial< Degree-1 >::BSpline().MovingAverage( radius ); + } + template + PPolynomial PPolynomial::MovingAverage( double radius ) + { + PPolynomial A; + Polynomial p; + StartingPolynomial* sps; + + sps=(StartingPolynomial*)malloc(sizeof(StartingPolynomial)*polyCount*2); + + for(int i=0;i + void PPolynomial::getSolutions(double c,std::vector& roots,double EPS,double min,double max) const{ + Polynomial p; + std::vector tempRoots; + + p.setZero(); + for(size_t i=0;imax){break;} + if(ipolys[i].start && (i+1==polyCount || tempRoots[j]<=polys[i+1].start)){ + if(tempRoots[j]>min && tempRoots[j] + void PPolynomial::write(FILE* fp,int samples,double min,double max) const{ + fwrite(&samples,sizeof(int),1,fp); + for(int i=0;i + struct MatrixEntry + { + MatrixEntry( void ) { N =-1; Value = 0; } + MatrixEntry( int i ) { N = i; Value = 0; } + int N; + T Value; + }; + + template class SparseMatrix + { + private: + bool _contiguous; + int _maxEntriesPerRow; + static int UseAlloc; + public: + static Allocator > internalAllocator; + static int UseAllocator(void); + static void SetAllocator( int blockSize ); + + int rows; + int* rowSizes; + MatrixEntry** m_ppElements; + MatrixEntry< T >* operator[] ( int idx ) { return m_ppElements[idx]; } + const MatrixEntry< T >* operator[] ( int idx ) const { return m_ppElements[idx]; } + + SparseMatrix( void ); + SparseMatrix( int rows ); + SparseMatrix( int rows , int maxEntriesPerRow ); + void Resize( int rows ); + void Resize( int rows , int maxEntriesPerRow ); + void SetRowSize( int row , int count ); + int Entries( void ) const; + + SparseMatrix( const SparseMatrix& M ); + ~SparseMatrix(); + + void SetZero(); + void SetIdentity(); + + SparseMatrix& operator = (const SparseMatrix& M); + + SparseMatrix operator * (const T& V) const; + SparseMatrix& operator *= (const T& V); + + + SparseMatrix operator * (const SparseMatrix& M) const; + SparseMatrix Multiply( const SparseMatrix& M ) const; + SparseMatrix MultiplyTranspose( const SparseMatrix& Mt ) const; + + template + Vector operator * (const Vector& V) const; + template + Vector Multiply( const Vector& V ) const; + template + void Multiply( const Vector& In , Vector& Out , int threads=1 ) const; + + + SparseMatrix Transpose() const; + + static int Solve (const SparseMatrix& M,const Vector& b, int iters,Vector& solution,const T eps=1e-8); + + template + static int SolveSymmetric( const SparseMatrix& M , const Vector& b , int iters , Vector& solution , const T2 eps=1e-8 , int reset=1 , int threads=1 ); + + bool write( FILE* fp ) const; + bool write( const char* fileName ) const; + bool read( FILE* fp ); + bool read( const char* fileName ); + }; + + template< class T2 > + struct MapReduceVector + { + private: + int _dim; + public: + std::vector< T2* > out; + MapReduceVector( void ) { _dim = 0; } + ~MapReduceVector( void ) + { + if( _dim ) for( int t=0 ; t + class SparseSymmetricMatrix : public SparseMatrix< T > + { + public: + + template< class T2 > + Vector< T2 > operator * ( const Vector& V ) const; + + template< class T2 > + Vector< T2 > Multiply( const Vector& V ) const; + + template< class T2 > + void Multiply( const Vector& In, Vector& Out , bool addDCTerm=false ) const; + + template< class T2 > + void Multiply( const Vector& In, Vector& Out , MapReduceVector< T2 >& OutScratch , bool addDCTerm=false ) const; + + template< class T2 > + void Multiply( const Vector& In, Vector& Out , std::vector< T2* >& OutScratch , const std::vector< int >& bounds ) const; + + template< class T2 > + static int Solve( const SparseSymmetricMatrix& M , const Vector& b , int iters , Vector& solution , T2 eps=1e-8 , int reset=1 , int threads=0 , bool addDCTerm=false , bool solveNormal=false ); + + template< class T2 > + static int Solve( const SparseSymmetricMatrix& M , const Vector& b , int iters , Vector& solution , MapReduceVector& scratch , T2 eps=1e-8 , int reset=1 , bool addDCTerm=false , bool solveNormal=false ); +#if defined _WIN32 && !defined __MINGW32__ + template< class T2 > + static int SolveAtomic( const SparseSymmetricMatrix& M , const Vector& b , int iters , Vector& solution , T2 eps=1e-8 , int reset=1 , int threads=0 , bool solveNormal=false ); +#endif // _WIN32 || __MINGW32__ + template + static int Solve( const SparseSymmetricMatrix& M , const Vector& diagonal , const Vector& b , int iters , Vector& solution , int reset=1 ); + + template< class T2 > + void getDiagonal( Vector< T2 >& diagonal ) const; + }; + + + } +} + + +#include "sparse_matrix.hpp" + +#endif + diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/sparse_matrix.hpp b/pcl-1.7/pcl/surface/3rdparty/poisson4/sparse_matrix.hpp new file mode 100644 index 0000000..dd059bf --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/sparse_matrix.hpp @@ -0,0 +1,970 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#include +#ifdef _WIN32 +# ifndef WIN32_LEAN_AND_MEAN +# define WIN32_LEAN_AND_MEAN +# endif // WIN32_LEAN_AND_MEAN +# ifndef NOMINMAX +# define NOMINMAX +# endif // NOMINMAX +# include +#endif //_WIN32 + +/////////////////// +// SparseMatrix // +/////////////////// +/////////////////////////////////////////// +// Static Allocator Methods and Memebers // +/////////////////////////////////////////// + +namespace pcl +{ + namespace poisson + { + + + template int SparseMatrix::UseAlloc=0; + template Allocator > SparseMatrix::internalAllocator; + template int SparseMatrix::UseAllocator(void){return UseAlloc;} + template + void SparseMatrix::SetAllocator( int blockSize ) + { + if(blockSize>0){ + UseAlloc=1; + internalAllocator.set(blockSize); + } + else{UseAlloc=0;} + } + /////////////////////////////////////// + // SparseMatrix Methods and Memebers // + /////////////////////////////////////// + + template< class T > + SparseMatrix< T >::SparseMatrix( void ) + { + _contiguous = false; + _maxEntriesPerRow = 0; + rows = 0; + rowSizes = NULL; + m_ppElements = NULL; + } + + template< class T > SparseMatrix< T >::SparseMatrix( int rows ) : SparseMatrix< T >() { Resize( rows ); } + template< class T > SparseMatrix< T >::SparseMatrix( int rows , int maxEntriesPerRow ) : SparseMatrix< T >() { Resize( rows , maxEntriesPerRow ); } + + template< class T > + SparseMatrix< T >::SparseMatrix( const SparseMatrix& M ) : SparseMatrix< T >() + { + if( M._contiguous ) Resize( M.rows , M._maxEntriesPerRow ); + else Resize( M.rows ); + for( int i=0 ; i ) * rowSizes[i] ); + } + } + template + int SparseMatrix::Entries( void ) const + { + int e = 0; + for( int i=0 ; i + SparseMatrix& SparseMatrix::operator = (const SparseMatrix& M) + { + if( M._contiguous ) Resize( M.rows , M._maxEntriesPerRow ); + else Resize( M.rows ); + for( int i=0 ; i ) * rowSizes[i] ); + } + return *this; + } + + template + SparseMatrix::~SparseMatrix( void ){ Resize( 0 ); } + + template< class T > + bool SparseMatrix< T >::write( const char* fileName ) const + { + FILE* fp = fopen( fileName , "wb" ); + if( !fp ) return false; + bool ret = write( fp ); + fclose( fp ); + return ret; + } + template< class T > + bool SparseMatrix< T >::read( const char* fileName ) + { + FILE* fp = fopen( fileName , "rb" ); + if( !fp ) return false; + bool ret = read( fp ); + fclose( fp ); + return ret; + } + template< class T > + bool SparseMatrix< T >::write( FILE* fp ) const + { + if( fwrite( &rows , sizeof( int ) , 1 , fp )!=1 ) return false; + if( fwrite( rowSizes , sizeof( int ) , rows , fp )!=rows ) return false; + for( int i=0 ; i ) , rowSizes[i] , fp )!=rowSizes[i] ) return false; + return true; + } + template< class T > + bool SparseMatrix< T >::read( FILE* fp ) + { + int r; + if( fread( &r , sizeof( int ) , 1 , fp )!=1 ) return false; + Resize( r ); + if( fread( rowSizes , sizeof( int ) , rows , fp )!=rows ) return false; + for( int i=0 ; i ) , rowSizes[i] , fp )!=rowSizes[i] ) return false; + } + return true; + } + + + template< class T > + void SparseMatrix< T >::Resize( int r ) + { + if( rows>0 ) + { + + if( !UseAlloc ) + if( _contiguous ){ if( _maxEntriesPerRow ) free( m_ppElements[0] ); } + else for( int i=0 ; i** )malloc( sizeof( MatrixEntry< T >* ) * r ); + } + _contiguous = false; + _maxEntriesPerRow = 0; + } + template< class T > + void SparseMatrix< T >::Resize( int r , int e ) + { + if( rows>0 ) + { + if( !UseAlloc ) + if( _contiguous ){ if( _maxEntriesPerRow ) free( m_ppElements[0] ); } + else for( int i=0 ; i** )malloc( sizeof( MatrixEntry< T >* ) * r ); + m_ppElements[0] = ( MatrixEntry< T >* )malloc( sizeof( MatrixEntry< T > ) * r * e ); + for( int i=1 ; i + void SparseMatrix< T >::SetRowSize( int row , int count ) + { + if( _contiguous ) + { + if( count>_maxEntriesPerRow ) fprintf( stderr , "[ERROR] Cannot set row size on contiguous matrix: %d<=%d\n" , count , _maxEntriesPerRow ) , exit( 0 ); + rowSizes[row] = count; + } + else if( row>=0 && row0 ) m_ppElements[row] = ( MatrixEntry< T >* )malloc( sizeof( MatrixEntry< T > ) * count ); + } + } + } + + + template + void SparseMatrix::SetZero() + { + Resize(this->m_N, this->m_M); + } + + template + void SparseMatrix::SetIdentity() + { + SetZero(); + for(int ij=0; ij < Min( this->Rows(), this->Columns() ); ij++) + (*this)(ij,ij) = T(1); + } + + template + SparseMatrix SparseMatrix::operator * (const T& V) const + { + SparseMatrix M(*this); + M *= V; + return M; + } + + template + SparseMatrix& SparseMatrix::operator *= (const T& V) + { + for (int i=0; iRows(); i++) + { + for(int ii=0;ii + SparseMatrix SparseMatrix::Multiply( const SparseMatrix& M ) const + { + SparseMatrix R( this->Rows(), M.Columns() ); + for(int i=0; i + template + Vector SparseMatrix::Multiply( const Vector& V ) const + { + Vector R( rows ); + + for (int i=0; i + template + void SparseMatrix::Multiply( const Vector& In , Vector& Out , int threads ) const + { +#pragma omp parallel for num_threads( threads ) schedule( static ) + for( int i=0 ; i + SparseMatrix SparseMatrix::operator * (const SparseMatrix& M) const + { + return Multiply(M); + } + template + template + Vector SparseMatrix::operator * (const Vector& V) const + { + return Multiply(V); + } + + template + SparseMatrix SparseMatrix::Transpose() const + { + SparseMatrix M( this->Columns(), this->Rows() ); + + for (int i=0; iRows(); i++) + { + for(int ii=0;ii + template + int SparseMatrix::SolveSymmetric( const SparseMatrix& M , const Vector& b , int iters , Vector& solution , const T2 eps , int reset , int threads ) + { + if( reset ) + { + solution.Resize( b.Dimensions() ); + solution.SetZero(); + } + Vector< T2 > r; + r.Resize( solution.Dimensions() ); + M.Multiply( solution , r ); + r = b - r; + Vector< T2 > d = r; + double delta_new , delta_0; + for( int i=0 ; i q; + q.Resize( d.Dimensions() ); + for( ii=0; iieps*delta_0 ; ii++ ) + { + M.Multiply( d , q , threads ); + double dDotQ = 0 , alpha = 0; + for( int i=0 ; i + int SparseMatrix::Solve(const SparseMatrix& M,const Vector& b,int iters,Vector& solution,const T eps){ + SparseMatrix mTranspose=M.Transpose(); + Vector bb=mTranspose*b; + Vector d,r,Md; + T alpha,beta,rDotR; + int i; + + solution.Resize(M.Columns()); + solution.SetZero(); + + d=r=bb; + rDotR=r.Dot(r); + for(i=0;ieps;i++){ + T temp; + Md=mTranspose*(M*d); + alpha=rDotR/d.Dot(Md); + solution+=d*alpha; + r-=Md*alpha; + temp=r.Dot(r); + beta=temp/rDotR; + rDotR=temp; + d=r+d*beta; + } + return i; + } + + + + + /////////////////////////// + // SparseSymmetricMatrix // + /////////////////////////// + template + template + Vector SparseSymmetricMatrix::operator * (const Vector& V) const {return Multiply(V);} + template + template + Vector SparseSymmetricMatrix::Multiply( const Vector& V ) const + { + Vector R( SparseMatrix::rows ); + + for(int i=0; i::rows; i++){ + for(int ii=0;ii::rowSizes[i];ii++){ + int j=SparseMatrix::m_ppElements[i][ii].N; + R(i)+=SparseMatrix::m_ppElements[i][ii].Value * V.m_pV[j]; + R(j)+=SparseMatrix::m_ppElements[i][ii].Value * V.m_pV[i]; + } + } + return R; + } + + template + template + void SparseSymmetricMatrix::Multiply( const Vector& In , Vector& Out , bool addDCTerm ) const + { + Out.SetZero(); + const T2* in = &In[0]; + T2* out = &Out[0]; + T2 dcTerm = T2( 0 ); + if( addDCTerm ) + { + for( int i=0 ; i::rows ; i++ ) dcTerm += in[i]; + dcTerm /= SparseMatrix::rows; + } + for( int i=0 ; iSparseMatrix::rows ; i++ ) + { + const MatrixEntry* temp = SparseMatrix::m_ppElements[i]; + const MatrixEntry* end = temp + SparseMatrix::rowSizes[i]; + const T2& in_i_ = in[i]; + T2 out_i = T2(0); + for( ; temp!=end ; temp++ ) + { + int j=temp->N; + T2 v=temp->Value; + out_i += v * in[j]; + out[j] += v * in_i_; + } + out[i] += out_i; + } + if( addDCTerm ) for( int i=0 ; i::rows ; i++ ) out[i] += dcTerm; + } + template + template + void SparseSymmetricMatrix::Multiply( const Vector& In , Vector& Out , MapReduceVector< T2 >& OutScratch , bool addDCTerm ) const + { + int dim = int( In.Dimensions() ); + const T2* in = &In[0]; + int threads = OutScratch.threads(); + if( addDCTerm ) + { + T2 dcTerm = 0; +#pragma omp parallel for num_threads( threads ) reduction ( + : dcTerm ) + for( int t=0 ; t::rows*t)/threads ; i<(SparseMatrix::rows*(t+1))/threads ; i++ ) + { + const T2& in_i_ = in[i]; + T2& out_i_ = out[i]; + for( const MatrixEntry< T > *temp = SparseMatrix::m_ppElements[i] , *end = temp+SparseMatrix::rowSizes[i] ; temp!=end ; temp++ ) + { + int j = temp->N; + T2 v = temp->Value; + out_i_ += v * in[j]; + out[j] += v * in_i_; + } + dcTerm += in_i_; + } + } + dcTerm /= dim; + dim = int( Out.Dimensions() ); + T2* out = &Out[0]; +#pragma omp parallel for num_threads( threads ) schedule( static ) + for( int i=0 ; i::rows*t)/threads ; i<(SparseMatrix::rows*(t+1))/threads ; i++ ) + { + const T2& in_i_ = in[i]; + T2& out_i_ = out[i]; + for( const MatrixEntry< T > *temp = SparseMatrix::m_ppElements[i] , *end = temp+SparseMatrix::rowSizes[i] ; temp!=end ; temp++ ) + { + int j = temp->N; + T2 v = temp->Value; + out_i_ += v * in[j]; + out[j] += v * in_i_; + } + } + } + dim = int( Out.Dimensions() ); + T2* out = &Out[0]; +#pragma omp parallel for num_threads( threads ) schedule( static ) + for( int i=0 ; i + template + void SparseSymmetricMatrix::Multiply( const Vector& In , Vector& Out , std::vector< T2* >& OutScratch , const std::vector< int >& bounds ) const + { + int dim = In.Dimensions(); + const T2* in = &In[0]; + int threads = OutScratch.size(); +#pragma omp parallel for num_threads( threads ) + for( int t=0 ; t* temp = SparseMatrix::m_ppElements[i]; + const MatrixEntry* end = temp + SparseMatrix::rowSizes[i]; + const T2& in_i_ = in[i]; + T2& out_i_ = out[i]; + for( ; temp!=end ; temp++ ) + { + int j = temp->N; + T2 v = temp->Value; + out_i_ += v * in[j]; + out[j] += v * in_i_; + } + } + } + T2* out = &Out[0]; +#pragma omp parallel for num_threads( threads ) schedule( static ) + for( int i=0 ; i + void MultiplyAtomic( const SparseSymmetricMatrix< T >& A , const Vector< float >& In , Vector< float >& Out , int threads , const int* partition=NULL ) + { + Out.SetZero(); + const float* in = &In[0]; + float* out = &Out[0]; + if( partition ) +#pragma omp parallel for num_threads( threads ) + for( int t=0 ; t* temp = A[i]; + const MatrixEntry< T >* end = temp + A.rowSizes[i]; + const float& in_i = in[i]; + float out_i = 0.; + for( ; temp!=end ; temp++ ) + { + int j = temp->N; + float v = temp->Value; + out_i += v * in[j]; + AtomicIncrement( out+j , v * in_i ); + } + AtomicIncrement( out+i , out_i ); + } + else +#pragma omp parallel for num_threads( threads ) + for( int i=0 ; i* temp = A[i]; + const MatrixEntry< T >* end = temp + A.rowSizes[i]; + const float& in_i = in[i]; + float out_i = 0.f; + for( ; temp!=end ; temp++ ) + { + int j = temp->N; + float v = temp->Value; + out_i += v * in[j]; + AtomicIncrement( out+j , v * in_i ); + } + AtomicIncrement( out+i , out_i ); + } + } + template< class T > + void MultiplyAtomic( const SparseSymmetricMatrix< T >& A , const Vector< double >& In , Vector< double >& Out , int threads , const int* partition=NULL ) + { + Out.SetZero(); + const double* in = &In[0]; + double* out = &Out[0]; + + if( partition ) +#pragma omp parallel for num_threads( threads ) + for( int t=0 ; t* temp = A[i]; + const MatrixEntry< T >* end = temp + A.rowSizes[i]; + const double& in_i = in[i]; + double out_i = 0.; + for( ; temp!=end ; temp++ ) + { + int j = temp->N; + T v = temp->Value; + out_i += v * in[j]; + AtomicIncrement( out+j , v * in_i ); + } + AtomicIncrement( out+i , out_i ); + } + else +#pragma omp parallel for num_threads( threads ) + for( int i=0 ; i* temp = A[i]; + const MatrixEntry< T >* end = temp + A.rowSizes[i]; + const double& in_i = in[i]; + double out_i = 0.; + for( ; temp!=end ; temp++ ) + { + int j = temp->N; + T v = temp->Value; + out_i += v * in[j]; + AtomicIncrement( out+j , v * in_i ); + } + AtomicIncrement( out+i , out_i ); + } + } + + template< class T > + template< class T2 > + int SparseSymmetricMatrix< T >::SolveAtomic( const SparseSymmetricMatrix< T >& A , const Vector< T2 >& b , int iters , Vector< T2 >& x , T2 eps , int reset , int threads , bool solveNormal ) + { + eps *= eps; + int dim = b.Dimensions(); + if( reset ) + { + x.Resize( dim ); + x.SetZero(); + } + Vector< T2 > r( dim ) , d( dim ) , q( dim ); + Vector< T2 > temp; + if( solveNormal ) temp.Resize( dim ); + T2 *_x = &x[0] , *_r = &r[0] , *_d = &d[0] , *_q = &q[0]; + const T2* _b = &b[0]; + + std::vector< int > partition( threads+1 ); + { + int eCount = 0; + for( int i=0 ; i=eCount*(t+1) ) + { + partition[t+1] = i; + break; + } + } + } + partition[threads] = A.rows; + } + if( solveNormal ) + { + MultiplyAtomic( A , x , temp , threads , &partition[0] ); + MultiplyAtomic( A , temp , r , threads , &partition[0] ); + MultiplyAtomic( A , b , temp , threads , &partition[0] ); +#pragma omp parallel for num_threads( threads ) schedule( static ) + for( int i=0 ; ieps*delta_0 ; ii++ ) + { + if( solveNormal ) MultiplyAtomic( A , d , temp , threads , &partition[0] ) , MultiplyAtomic( A , temp , q , threads , &partition[0] ); + else MultiplyAtomic( A , d , q , threads , &partition[0] ); + double dDotQ = 0; + for( int i=0 ; i + template< class T2 > + int SparseSymmetricMatrix< T >::Solve( const SparseSymmetricMatrix& A , const Vector& b , int iters , Vector& x , MapReduceVector< T2 >& scratch , T2 eps , int reset , bool addDCTerm , bool solveNormal ) + { + int threads = scratch.threads(); + eps *= eps; + int dim = int( b.Dimensions() ); + Vector< T2 > r( dim ) , d( dim ) , q( dim ) , temp; + if( reset ) x.Resize( dim ); + if( solveNormal ) temp.Resize( dim ); + T2 *_x = &x[0] , *_r = &r[0] , *_d = &d[0] , *_q = &q[0]; + const T2* _b = &b[0]; + + double delta_new = 0 , delta_0; + if( solveNormal ) + { + A.Multiply( x , temp , scratch , addDCTerm ) , A.Multiply( temp , r , scratch , addDCTerm ) , A.Multiply( b , temp , scratch , addDCTerm ); +#pragma omp parallel for num_threads( threads ) reduction( + : delta_new ) + for( int i=0 ; ieps*delta_0 ; ii++ ) + { + if( solveNormal ) A.Multiply( d , temp , scratch , addDCTerm ) , A.Multiply( temp , q , scratch , addDCTerm ); + else A.Multiply( d , q , scratch , addDCTerm ); + double dDotQ = 0; +#pragma omp parallel for num_threads( threads ) reduction( + : dDotQ ) + for( int i=0 ; i + template< class T2 > + int SparseSymmetricMatrix::Solve( const SparseSymmetricMatrix& A , const Vector& b , int iters , Vector& x , T2 eps , int reset , int threads , bool addDCTerm , bool solveNormal ) + { + eps *= eps; + int dim = int( b.Dimensions() ); + MapReduceVector< T2 > outScratch; + if( threads<1 ) threads = 1; + if( threads>1 ) outScratch.resize( threads , dim ); + if( reset ) x.Resize( dim ); + Vector< T2 > r( dim ) , d( dim ) , q( dim ); + Vector< T2 > temp; + if( solveNormal ) temp.Resize( dim ); + T2 *_x = &x[0] , *_r = &r[0] , *_d = &d[0] , *_q = &q[0]; + const T2* _b = &b[0]; + + double delta_new = 0 , delta_0; + + if( solveNormal ) + { + if( threads>1 ) A.Multiply( x , temp , outScratch , addDCTerm ) , A.Multiply( temp , r , outScratch , addDCTerm ) , A.Multiply( b , temp , outScratch , addDCTerm ); + else A.Multiply( x , temp , addDCTerm ) , A.Multiply( temp , r , addDCTerm ) , A.Multiply( b , temp , addDCTerm ); +#pragma omp parallel for num_threads( threads ) reduction( + : delta_new ) + for( int i=0 ; i1 ) A.Multiply( x , r , outScratch , addDCTerm ); + else A.Multiply( x , r , addDCTerm ); +#pragma omp parallel for num_threads( threads ) reduction( + : delta_new ) + for( int i=0 ; ieps*delta_0 ; ii++ ) + { + if( solveNormal ) + { + if( threads>1 ) A.Multiply( d , temp , outScratch , addDCTerm ) , A.Multiply( temp , q , outScratch , addDCTerm ); + else A.Multiply( d , temp , addDCTerm ) , A.Multiply( temp , q , addDCTerm ); + } + else + { + if( threads>1 ) A.Multiply( d , q , outScratch , addDCTerm ); + else A.Multiply( d , q , addDCTerm ); + } + double dDotQ = 0; +#pragma omp parallel for num_threads( threads ) reduction( + : dDotQ ) + for( int i=0 ; i1 ) A.Multiply( x , temp , outScratch , addDCTerm ) , A.Multiply( temp , r , outScratch , addDCTerm ); + else A.Multiply( x , temp , addDCTerm ) , A.Multiply( temp , r , addDCTerm ); + } + else + { + if( threads>1 ) A.Multiply( x , r , outScratch , addDCTerm ); + else A.Multiply( x , r , addDCTerm ); + } +#pragma omp parallel for num_threads( threads ) reduction ( + : delta_new ) + for( int i=0 ; i + template + int SparseSymmetricMatrix::Solve( const SparseSymmetricMatrix& M , const Vector& diagonal , const Vector& b , int iters , Vector& solution , int reset ) + { + Vector d,r,Md; + + if(reset) + { + solution.Resize(b.Dimensions()); + solution.SetZero(); + } + Md.Resize(M.rows); + for( int i=0 ; i + template< class T2 > + void SparseSymmetricMatrix< T >::getDiagonal( Vector< T2 >& diagonal ) const + { + diagonal.Resize( SparseMatrix::rows ); + for( int i=0 ; i::rows ; i++ ) + { + diagonal[i] = 0.; + for( int j=0 ; j::rowSizes[i] ; j++ ) if( SparseMatrix::m_ppElements[i][j].N==i ) diagonal[i] += SparseMatrix::m_ppElements[i][j].Value * 2; + } + } + + } +} diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/vector.h b/pcl-1.7/pcl/surface/3rdparty/poisson4/vector.h new file mode 100644 index 0000000..bbf6b40 --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/vector.h @@ -0,0 +1,155 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#ifndef __VECTOR_HPP +#define __VECTOR_HPP + +#define Assert assert +#include + + +namespace pcl +{ + namespace poisson + { + template + class Vector + { + public: + Vector(); + Vector( const Vector& V ); + Vector( size_t N ); + Vector( size_t N, T* pV ); + ~Vector(); + + const T& operator () (size_t i) const; + T& operator () (size_t i); + const T& operator [] (size_t i) const; + T& operator [] (size_t i); + + void SetZero(); + + size_t Dimensions() const; + void Resize( size_t N ); + + Vector operator * (const T& A) const; + Vector operator / (const T& A) const; + Vector operator - (const Vector& V) const; + Vector operator + (const Vector& V) const; + + Vector& operator *= (const T& A); + Vector& operator /= (const T& A); + Vector& operator += (const Vector& V); + Vector& operator -= (const Vector& V); + + Vector& AddScaled(const Vector& V,const T& scale); + Vector& SubtractScaled(const Vector& V,const T& scale); + static void Add(const Vector& V1,const T& scale1,const Vector& V2,const T& scale2,Vector& Out); + static void Add(const Vector& V1,const T& scale1,const Vector& V2,Vector& Out); + + Vector operator - () const; + + Vector& operator = (const Vector& V); + + T Dot( const Vector& V ) const; + + T Length() const; + + T Norm( size_t Ln ) const; + void Normalize(); + + bool write( FILE* fp ) const; + bool write( const char* fileName ) const; + bool read( FILE* fp ); + bool read( const char* fileName ); + + T* m_pV; + protected: + size_t m_N; + + }; + + template + class NVector + { + public: + NVector(); + NVector( const NVector& V ); + NVector( size_t N ); + NVector( size_t N, T* pV ); + ~NVector(); + + const T* operator () (size_t i) const; + T* operator () (size_t i); + const T* operator [] (size_t i) const; + T* operator [] (size_t i); + + void SetZero(); + + size_t Dimensions() const; + void Resize( size_t N ); + + NVector operator * (const T& A) const; + NVector operator / (const T& A) const; + NVector operator - (const NVector& V) const; + NVector operator + (const NVector& V) const; + + NVector& operator *= (const T& A); + NVector& operator /= (const T& A); + NVector& operator += (const NVector& V); + NVector& operator -= (const NVector& V); + + NVector& AddScaled(const NVector& V,const T& scale); + NVector& SubtractScaled(const NVector& V,const T& scale); + static void Add(const NVector& V1,const T& scale1,const NVector& V2,const T& scale2,NVector& Out); + static void Add(const NVector& V1,const T& scale1,const NVector& V2, NVector& Out); + + NVector operator - () const; + + NVector& operator = (const NVector& V); + + T Dot( const NVector& V ) const; + + T Length() const; + + T Norm( size_t Ln ) const; + void Normalize(); + + T* m_pV; + protected: + size_t m_N; + + }; + + } +} + + +#include "vector.hpp" + +#endif diff --git a/pcl-1.7/pcl/surface/3rdparty/poisson4/vector.hpp b/pcl-1.7/pcl/surface/3rdparty/poisson4/vector.hpp new file mode 100644 index 0000000..f8a5bd8 --- /dev/null +++ b/pcl-1.7/pcl/surface/3rdparty/poisson4/vector.hpp @@ -0,0 +1,492 @@ +/* +Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of +conditions and the following disclaimer. Redistributions in binary form must reproduce +the above copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the distribution. + +Neither the name of the Johns Hopkins University nor the names of its contributors +may be used to endorse or promote products derived from this software without specific +prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES +OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR +BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +DAMAGE. +*/ + +#ifndef __VECTORIMPL_HPP +#define __VECTORIMPL_HPP + +//////////// +// Vector // +//////////// +namespace pcl +{ + namespace poisson + { + + + template + Vector::Vector() + { + m_N = 0; + m_pV = 0; + } + template + Vector::Vector( const Vector& V ) + { + m_N = 0; + m_pV = 0; + Resize(V.m_N); + memcpy( m_pV, V.m_pV, m_N*sizeof(T) ); + } + template + Vector::Vector( size_t N ) + { + m_N=0; + m_pV=0; + Resize(N); + } + template + void Vector::Resize( size_t N ) + { + if(m_N!=N){ + if(m_N){delete[] m_pV;} + m_pV=NULL; + m_N = N; + if(N){m_pV = new T[N];} + } + memset( m_pV, 0, N*sizeof(T) ); + } + template + Vector::Vector( size_t N, T* pV ) + { + Resize(N); + memcpy( m_pV, pV, N*sizeof(T) ); + } + template + Vector::~Vector(){Resize(0);} + template + Vector& Vector::operator = (const Vector& V) + { + Resize(V.m_N); + memcpy( m_pV, V.m_pV, m_N*sizeof(T) ); + return *this; + } + template + size_t Vector::Dimensions() const{return m_N;} + template + void Vector::SetZero(void){for (size_t i=0; i + const T& Vector::operator () (size_t i) const + { + Assert( i < m_N ); + return m_pV[i]; + } + template + T& Vector::operator () (size_t i) + { + return m_pV[i]; + } + template + const T& Vector::operator [] (size_t i) const + { + return m_pV[i]; + } + template + T& Vector::operator [] (size_t i) + { + return m_pV[i]; + } + template + Vector Vector::operator * (const T& A) const + { + Vector V(*this); + for (size_t i=0; i + Vector& Vector::operator *= (const T& A) + { + for (size_t i=0; i + Vector Vector::operator / (const T& A) const + { + Vector V(*this); + for (size_t i=0; i + Vector& Vector::operator /= (const T& A) + { + for (size_t i=0; i + Vector Vector::operator + (const Vector& V0) const + { + Vector V(m_N); + for (size_t i=0; i + Vector& Vector::AddScaled(const Vector& V,const T& scale) + { + for (size_t i=0; i + Vector& Vector::SubtractScaled(const Vector& V,const T& scale) + { + for (size_t i=0; i + void Vector::Add(const Vector& V1,const T& scale1,const Vector& V2,const T& scale2,Vector& Out){ + for (size_t i=0; i + void Vector::Add(const Vector& V1,const T& scale1,const Vector& V2,Vector& Out){ + for (size_t i=0; i + Vector& Vector::operator += (const Vector& V) + { + for (size_t i=0; i + Vector Vector::operator - (const Vector& V0) const + { + Vector V(m_N); + for (size_t i=0; i + Vector Vector::operator - (void) const + { + Vector V(m_N); + + for (size_t i=0; i + Vector& Vector::operator -= (const Vector& V) + { + for (size_t i=0; i + T Vector::Norm( size_t Ln ) const + { + T N = T(); + for (size_t i = 0; i + void Vector::Normalize() + { + T N = 1.0f/Norm(2); + for (size_t i = 0; i + T Vector::Length() const + { + T N = T(); + for (size_t i = 0; i + T Vector::Dot( const Vector& V ) const + { + T V0 = T(); + for (size_t i=0; i + bool Vector< T >::read( const char* fileName ) + { + FILE* fp = fopen( fileName , "rb" ); + if( !fp ) return false; + bool ret = read( fp ); + fclose( fp ); + return ret; + } + template< class T > + bool Vector< T >::write( const char* fileName ) const + { + FILE* fp = fopen( fileName , "wb" ); + if( !fp ) return false; + bool ret = write( fp ); + fclose( fp ); + return ret; + } + template< class T > + bool Vector< T >::read( FILE* fp ) + { + int d; + if( fread( &d , sizeof(int) , 1 , fp )!=1 ) return false; + Resize( d ); + if( fread( &(*this)[0] , sizeof( T ) , d , fp )!=d ) return false; + return true; + } + template< class T > + bool Vector< T >::write( FILE* fp ) const + { + if( fwrite( &m_N , sizeof( int ) , 1 , fp )!=1 ) return false; + if( fwrite( &(*this)[0] , sizeof( T ) , m_N , fp )!=m_N ) return false; + return true; + } + + + ///////////// + // NVector // + ///////////// + template + NVector::NVector() + { + m_N = 0; + m_pV = 0; + } + template + NVector::NVector( const NVector& V ) + { + m_N = 0; + m_pV = 0; + Resize(V.m_N); + memcpy( m_pV, V.m_pV, m_N*sizeof(T)*Dim ); + } + template + NVector::NVector( size_t N ) + { + m_N=0; + m_pV=0; + Resize(N); + } + template + void NVector::Resize( size_t N ) + { + if(m_N!=N){ + if(m_N){delete[] m_pV;} + m_pV=NULL; + m_N = N; + if(N){m_pV = new T[Dim*N];} + } + memset( m_pV, 0, N*sizeof(T)*Dim ); + } + template + NVector::NVector( size_t N, T* pV ) + { + Resize(N); + memcpy( m_pV, pV, N*sizeof(T)*Dim ); + } + template + NVector::~NVector(){Resize(0);} + template + NVector& NVector::operator = (const NVector& V) + { + Resize(V.m_N); + memcpy( m_pV, V.m_pV, m_N*sizeof(T)*Dim ); + return *this; + } + template + size_t NVector::Dimensions() const{return m_N;} + template + void NVector::SetZero(void){for (size_t i=0; i + const T* NVector::operator () (size_t i) const + { + Assert( i < m_N ); + return &m_pV[i*Dim]; + } + template + T* NVector::operator () (size_t i) + { + return &m_pV[i*Dim]; + } + template + const T* NVector::operator [] (size_t i) const + { + return &m_pV[i*Dim]; + } + template + T* NVector::operator [] (size_t i) + { + return &m_pV[i*Dim]; + } + template + NVector NVector::operator * (const T& A) const + { + NVector V(*this); + for (size_t i=0; i + NVector& NVector::operator *= (const T& A) + { + for (size_t i=0; i + NVector NVector::operator / (const T& A) const + { + NVector V(*this); + for (size_t i=0; i + NVector& NVector::operator /= (const T& A) + { + for (size_t i=0; i + NVector NVector::operator + (const NVector& V0) const + { + NVector V(m_N); + for (size_t i=0; i + NVector& NVector::AddScaled(const NVector& V,const T& scale) + { + for (size_t i=0; i + NVector& NVector::SubtractScaled(const NVector& V,const T& scale) + { + for (size_t i=0; i + void NVector::Add(const NVector& V1,const T& scale1,const NVector& V2,const T& scale2,NVector& Out){ + for (size_t i=0; i + void NVector::Add(const NVector& V1,const T& scale1,const NVector& V2,NVector& Out){ + for (size_t i=0; i + NVector& NVector::operator += (const NVector& V) + { + for (size_t i=0; i + NVector NVector::operator - (const NVector& V0) const + { + NVector V(m_N); + for (size_t i=0; i + NVector NVector::operator - (void) const + { + NVector V(m_N); + + for (size_t i=0; i + NVector& NVector::operator -= (const NVector& V) + { + for (size_t i=0; i + T NVector::Norm( size_t Ln ) const + { + T N = T(); + for (size_t i = 0; i + void NVector::Normalize() + { + T N = 1.0f/Norm(2); + for (size_t i = 0; i + T NVector::Length() const + { + T N = T(); + for (size_t i = 0; i + T NVector::Dot( const NVector& V ) const + { + T V0 = T(); + for (size_t i=0; i + +namespace pcl +{ + + /** \brief Bilateral filtering implementation, based on the following paper: + * * Kopf, Johannes and Cohen, Michael F. and Lischinski, Dani and Uyttendaele, Matt - Joint Bilateral Upsampling, + * * ACM Transations in Graphics, July 2007 + * + * Takes in a colored organized point cloud (i.e. PointXYZRGB or PointXYZRGBA), that might contain nan values for the + * depth information, and it will return an upsampled version of this cloud, based on the formula: + * \f[ + * \tilde{S}_p = \frac{1}{k_p} \sum_{q_d \in \Omega} {S_{q_d} f(||p_d - q_d|| g(||\tilde{I}_p-\tilde{I}_q||}) + * \f] + * + * where S is the depth image, I is the RGB image and f and g are Gaussian functions centered at 0 and with + * standard deviations \f$\sigma_{color}\f$ and \f$\sigma_{depth}\f$ + */ + template + class BilateralUpsampling: public CloudSurfaceProcessing + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using PCLBase::input_; + using PCLBase::indices_; + using PCLBase::initCompute; + using PCLBase::deinitCompute; + using CloudSurfaceProcessing::process; + + typedef pcl::PointCloud PointCloudOut; + + Eigen::Matrix3f KinectVGAProjectionMatrix, KinectSXGAProjectionMatrix; + + /** \brief Constructor. */ + BilateralUpsampling () + : KinectVGAProjectionMatrix () + , KinectSXGAProjectionMatrix () + , window_size_ (5) + , sigma_color_ (15.0f) + , sigma_depth_ (0.5f) + , projection_matrix_ () + , unprojection_matrix_ () + { + KinectVGAProjectionMatrix << 525.0f, 0.0f, 320.0f, + 0.0f, 525.0f, 240.0f, + 0.0f, 0.0f, 1.0f; + KinectSXGAProjectionMatrix << 1050.0f, 0.0f, 640.0f, + 0.0f, 1050.0f, 480.0f, + 0.0f, 0.0f, 1.0f; + }; + + /** \brief Method that sets the window size for the filter + * \param[in] window_size the given window size + */ + inline void + setWindowSize (int window_size) { window_size_ = window_size; } + + /** \brief Returns the filter window size */ + inline int + getWindowSize () const { return (window_size_); } + + /** \brief Method that sets the sigma color parameter + * \param[in] sigma_color the new value to be set + */ + inline void + setSigmaColor (const float &sigma_color) { sigma_color_ = sigma_color; } + + /** \brief Returns the current sigma color value */ + inline float + getSigmaColor () const { return (sigma_color_); } + + /** \brief Method that sets the sigma depth parameter + * \param[in] sigma_depth the new value to be set + */ + inline void + setSigmaDepth (const float &sigma_depth) { sigma_depth_ = sigma_depth; } + + /** \brief Returns the current sigma depth value */ + inline float + getSigmaDepth () const { return (sigma_depth_); } + + /** \brief Method that sets the projection matrix to be used when unprojecting the points in the depth image + * back to (x,y,z) positions. + * \note There are 2 matrices already set in the class, used for the 2 modes available for the Kinect. They + * are tuned to be the same as the ones in the OpenNiGrabber + * \param[in] projection_matrix the new projection matrix to be set */ + inline void + setProjectionMatrix (const Eigen::Matrix3f &projection_matrix) { projection_matrix_ = projection_matrix; } + + /** \brief Returns the current projection matrix */ + inline Eigen::Matrix3f + getProjectionMatrix () const { return (projection_matrix_); } + + /** \brief Method that does the actual processing on the input cloud. + * \param[out] output the container of the resulting upsampled cloud */ + void + process (pcl::PointCloud &output); + + protected: + void + performProcessing (pcl::PointCloud &output); + + /** \brief Computes the distance for depth and RGB. + * \param[out] val_exp_depth distance values for depth + * \param[out] val_exp_rgb distance values for RGB */ + void + computeDistances (Eigen::MatrixXf &val_exp_depth, Eigen::VectorXf &val_exp_rgb); + + private: + int window_size_; + float sigma_color_, sigma_depth_; + Eigen::Matrix3f projection_matrix_, unprojection_matrix_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#endif /* PCL_SURFACE_BILATERAL_UPSAMPLING_H_ */ diff --git a/pcl-1.7/pcl/surface/boost.h b/pcl-1.7/pcl/surface/boost.h new file mode 100644 index 0000000..b8e4b66 --- /dev/null +++ b/pcl-1.7/pcl/surface/boost.h @@ -0,0 +1,54 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $ + * + */ + +#ifndef PCL_SURFACE_BOOST_H_ +#define PCL_SURFACE_BOOST_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include +#include +#include +#include +#include + +#endif // PCL_SURFACE_BOOST_H_ diff --git a/pcl-1.7/pcl/surface/concave_hull.h b/pcl-1.7/pcl/surface/concave_hull.h new file mode 100644 index 0000000..3ff21b1 --- /dev/null +++ b/pcl-1.7/pcl/surface/concave_hull.h @@ -0,0 +1,208 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#include +#ifdef HAVE_QHULL + +#ifndef PCL_CONCAVE_HULL_H +#define PCL_CONCAVE_HULL_H + +#include + +namespace pcl +{ + //////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b ConcaveHull (alpha shapes) using libqhull library. + * \author Aitor Aldoma + * \ingroup surface + */ + template + class ConcaveHull : public MeshConstruction + { + protected: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using PCLBase::input_; + using PCLBase::indices_; + using PCLBase::initCompute; + using PCLBase::deinitCompute; + + public: + using MeshConstruction::reconstruct; + + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + /** \brief Empty constructor. */ + ConcaveHull () : alpha_ (0), keep_information_ (false), voronoi_centers_ (), dim_(0) + { + }; + + /** \brief Empty destructor */ + virtual ~ConcaveHull () {} + + /** \brief Compute a concave hull for all points given + * + * \param points the resultant points lying on the concave hull + * \param polygons the resultant concave hull polygons, as a set of + * vertices. The Vertices structure contains an array of point indices. + */ + void + reconstruct (PointCloud &points, + std::vector &polygons); + + /** \brief Compute a concave hull for all points given + * \param output the resultant concave hull vertices + */ + void + reconstruct (PointCloud &output); + + /** \brief Set the alpha value, which limits the size of the resultant + * hull segments (the smaller the more detailed the hull). + * + * \param alpha positive, non-zero value, defining the maximum length + * from a vertex to the facet center (center of the voronoi cell). + */ + inline void + setAlpha (double alpha) + { + alpha_ = alpha; + } + + /** \brief Returns the alpha parameter, see setAlpha(). */ + inline double + getAlpha () + { + return (alpha_); + } + + /** \brief If set, the voronoi cells center will be saved in _voronoi_centers_ + * \param voronoi_centers + */ + inline void + setVoronoiCenters (PointCloudPtr voronoi_centers) + { + voronoi_centers_ = voronoi_centers; + } + + /** \brief If keep_information_is set to true the convex hull + * points keep other information like rgb, normals, ... + * \param value where to keep the information or not, default is false + */ + void + setKeepInformation (bool value) + { + keep_information_ = value; + } + + /** \brief Returns the dimensionality (2 or 3) of the calculated hull. */ + PCL_DEPRECATED ("[pcl::ConcaveHull::getDim] This method is deprecated. Please use getDimension () instead.") + int + getDim () const; + + /** \brief Returns the dimensionality (2 or 3) of the calculated hull. */ + inline int + getDimension () const + { + return (dim_); + } + + /** \brief Sets the dimension on the input data, 2D or 3D. + * \param[in] dimension The dimension of the input data. If not set, this will be determined automatically. + */ + void + setDimension (int dimension) + { + if ((dimension == 2) || (dimension == 3)) + dim_ = dimension; + else + PCL_ERROR ("[pcl::%s::setDimension] Invalid input dimension specified!\n", getClassName ().c_str ()); + } + + protected: + /** \brief Class get name method. */ + std::string + getClassName () const + { + return ("ConcaveHull"); + } + + protected: + /** \brief The actual reconstruction method. + * + * \param points the resultant points lying on the concave hull + * \param polygons the resultant concave hull polygons, as a set of + * vertices. The Vertices structure contains an array of point indices. + */ + void + performReconstruction (PointCloud &points, + std::vector &polygons); + + virtual void + performReconstruction (PolygonMesh &output); + + virtual void + performReconstruction (std::vector &polygons); + + /** \brief The method accepts facets only if the distance from any vertex to the facet->center + * (center of the voronoi cell) is smaller than alpha + */ + double alpha_; + + /** \brief If set to true, the reconstructed point cloud describing the hull is obtained from + * the original input cloud by performing a nearest neighbor search from Qhull output. + */ + bool keep_information_; + + /** \brief the centers of the voronoi cells */ + PointCloudPtr voronoi_centers_; + + /** \brief the dimensionality of the concave hull */ + int dim_; + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_CONCAVE_HULL +#endif diff --git a/pcl-1.7/pcl/surface/convex_hull.h b/pcl-1.7/pcl/surface/convex_hull.h new file mode 100644 index 0000000..afcc332 --- /dev/null +++ b/pcl-1.7/pcl/surface/convex_hull.h @@ -0,0 +1,268 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#include +#ifdef HAVE_QHULL + +#ifndef PCL_CONVEX_HULL_2D_H_ +#define PCL_CONVEX_HULL_2D_H_ + +// PCL includes +#include +#include +#include + +namespace pcl +{ + /** \brief Sort 2D points in a vector structure + * \param p1 the first point + * \param p2 the second point + * \ingroup surface + */ + inline bool + comparePoints2D (const std::pair & p1, const std::pair & p2) + { + double angle1 = atan2 (p1.second[1], p1.second[0]) + M_PI; + double angle2 = atan2 (p2.second[1], p2.second[0]) + M_PI; + return (angle1 > angle2); + } + + //////////////////////////////////////////////////////////////////////////////////////////// + /** \brief @b ConvexHull using libqhull library. + * \author Aitor Aldoma, Alex Trevor + * \ingroup surface + */ + template + class ConvexHull : public MeshConstruction + { + protected: + using PCLBase::input_; + using PCLBase::indices_; + using PCLBase::initCompute; + using PCLBase::deinitCompute; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using MeshConstruction::reconstruct; + + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + /** \brief Empty constructor. */ + ConvexHull () : compute_area_ (false), total_area_ (0), total_volume_ (0), dimension_ (0), + projection_angle_thresh_ (cos (0.174532925) ), qhull_flags ("qhull "), + x_axis_ (1.0, 0.0, 0.0), y_axis_ (0.0, 1.0, 0.0), z_axis_ (0.0, 0.0, 1.0) + { + }; + + /** \brief Empty destructor */ + virtual ~ConvexHull () {} + + /** \brief Compute a convex hull for all points given. + * + * \note In 2D case (i.e. if the input points belong to one plane) + * the \a polygons vector will have a single item, whereas in 3D + * case it will contain one item for each hull facet. + * + * \param[out] points the resultant points lying on the convex hull. + * \param[out] polygons the resultant convex hull polygons, as a set of + * vertices. The Vertices structure contains an array of point indices. + */ + void + reconstruct (PointCloud &points, + std::vector &polygons); + + /** \brief Compute a convex hull for all points given. + * \param[out] points the resultant points lying on the convex hull. + */ + void + reconstruct (PointCloud &points); + + /** \brief If set to true, the qhull library is called to compute the total area and volume of the convex hull. + * NOTE: When this option is activated, the qhull library produces output to the console. + * \param[in] value wheter to compute the area and the volume, default is false + */ + void + setComputeAreaVolume (bool value) + { + compute_area_ = value; + if (compute_area_) + qhull_flags = std::string ("qhull FA"); + else + qhull_flags = std::string ("qhull "); + } + + /** \brief Returns the total area of the convex hull. */ + double + getTotalArea () const + { + return (total_area_); + } + + /** \brief Returns the total volume of the convex hull. Only valid for 3-dimensional sets. + * For 2D-sets volume is zero. + */ + double + getTotalVolume () const + { + return (total_volume_); + } + + /** \brief Sets the dimension on the input data, 2D or 3D. + * \param[in] dimension The dimension of the input data. If not set, this will be determined automatically. + */ + void + setDimension (int dimension) + { + if ((dimension == 2) || (dimension == 3)) + dimension_ = dimension; + else + PCL_ERROR ("[pcl::%s::setDimension] Invalid input dimension specified!\n", getClassName ().c_str ()); + } + + /** \brief Returns the dimensionality (2 or 3) of the calculated hull. */ + inline int + getDimension () const + { + return (dimension_); + } + + protected: + /** \brief The actual reconstruction method. + * + * \param[out] points the resultant points lying on the convex hull + * \param[out] polygons the resultant convex hull polygons, as a set of + * vertices. The Vertices structure contains an array of point indices. + * \param[in] fill_polygon_data true if polygons should be filled, false otherwise + */ + void + performReconstruction (PointCloud &points, + std::vector &polygons, + bool fill_polygon_data = false); + + /** \brief The reconstruction method for 2D data. Does not require dimension to be set. + * + * \param[out] points the resultant points lying on the convex hull + * \param[out] polygons the resultant convex hull polygons, as a set of + * vertices. The Vertices structure contains an array of point indices. + * \param[in] fill_polygon_data true if polygons should be filled, false otherwise + */ + void + performReconstruction2D (PointCloud &points, + std::vector &polygons, + bool fill_polygon_data = false); + + /** \brief The reconstruction method for 3D data. Does not require dimension to be set. + * + * \param[out] points the resultant points lying on the convex hull + * \param[out] polygons the resultant convex hull polygons, as a set of + * vertices. The Vertices structure contains an array of point indices. + * \param[in] fill_polygon_data true if polygons should be filled, false otherwise + */ + void + performReconstruction3D (PointCloud &points, + std::vector &polygons, + bool fill_polygon_data = false); + + /** \brief A reconstruction method that returns a polygonmesh. + * + * \param[out] output a PolygonMesh representing the convex hull of the input data. + */ + virtual void + performReconstruction (PolygonMesh &output); + + /** \brief A reconstruction method that returns the polygon of the convex hull. + * + * \param[out] polygons the polygon(s) representing the convex hull of the input data. + */ + virtual void + performReconstruction (std::vector &polygons); + + /** \brief Automatically determines the dimension of input data - 2D or 3D. */ + void + calculateInputDimension (); + + /** \brief Class get name method. */ + std::string + getClassName () const + { + return ("ConvexHull"); + } + + /* \brief True if we should compute the area and volume of the convex hull. */ + bool compute_area_; + + /* \brief The area of the convex hull. */ + double total_area_; + + /* \brief The volume of the convex hull (only for 3D hulls, zero for 2D). */ + double total_volume_; + + /** \brief The dimensionality of the concave hull (2D or 3D). */ + int dimension_; + + /** \brief How close can a 2D plane's normal be to an axis to make projection problematic. */ + double projection_angle_thresh_; + + /** \brief Option flag string to be used calling qhull. */ + std::string qhull_flags; + + /* \brief x-axis - for checking valid projections. */ + const Eigen::Vector3d x_axis_; + + /* \brief y-axis - for checking valid projections. */ + const Eigen::Vector3d y_axis_; + + /* \brief z-axis - for checking valid projections. */ + const Eigen::Vector3d z_axis_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_CONVEX_HULL_2D_H_ +#endif diff --git a/pcl-1.7/pcl/surface/ear_clipping.h b/pcl-1.7/pcl/surface/ear_clipping.h new file mode 100644 index 0000000..870608e --- /dev/null +++ b/pcl-1.7/pcl/surface/ear_clipping.h @@ -0,0 +1,128 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SURFACE_EAR_CLIPPING_H_ +#define PCL_SURFACE_EAR_CLIPPING_H_ + +#include +#include + +namespace pcl +{ + + /** \brief The ear clipping triangulation algorithm. + * The code is inspired by Flavien Brebion implementation, which is + * in n^3 and does not handle holes. + * \author Nicolas Burrus + * \ingroup surface + */ + class PCL_EXPORTS EarClipping : public MeshProcessing + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + using MeshProcessing::input_mesh_; + using MeshProcessing::initCompute; + /** \brief Empty constructor */ + EarClipping () : MeshProcessing (), points_ () + { + }; + + protected: + /** \brief a Pointer to the point cloud data. */ + pcl::PointCloud::Ptr points_; + + /** \brief This method should get called before starting the actual computation. */ + bool + initCompute (); + + /** \brief The actual surface reconstruction method. + * \param[out] output the output polygonal mesh + */ + void + performProcessing (pcl::PolygonMesh &output); + + /** \brief Triangulate one polygon. + * \param[in] vertices the set of vertices + * \param[out] output the resultant polygonal mesh + */ + void + triangulate (const Vertices& vertices, PolygonMesh& output); + + /** \brief Compute the signed area of a polygon. + * \param[in] vertices the vertices representing the polygon + */ + float + area (const std::vector& vertices); + + /** \brief Check if the triangle (u,v,w) is an ear. + * \param[in] u the first triangle vertex + * \param[in] v the second triangle vertex + * \param[in] w the third triangle vertex + * \param[in] vertices a set of input vertices + */ + bool + isEar (int u, int v, int w, const std::vector& vertices); + + /** \brief Check if p is inside the triangle (u,v,w). + * \param[in] u the first triangle vertex + * \param[in] v the second triangle vertex + * \param[in] w the third triangle vertex + * \param[in] p the point to check + */ + bool + isInsideTriangle (const Eigen::Vector3f& u, + const Eigen::Vector3f& v, + const Eigen::Vector3f& w, + const Eigen::Vector3f& p); + + /** \brief Compute the cross product between 2D vectors. + * \param[in] p1 the first 2D vector + * \param[in] p2 the first 2D vector + */ + float + crossProduct (const Eigen::Vector2f& p1, const Eigen::Vector2f& p2) const + { + return p1[0]*p2[1] - p1[1]*p2[0]; + } + + }; + +} + +#endif // #ifndef PCL_SURFACE_EAR_CLIPPING_H_ diff --git a/pcl-1.7/pcl/surface/eigen.h b/pcl-1.7/pcl/surface/eigen.h new file mode 100644 index 0000000..91f925e --- /dev/null +++ b/pcl-1.7/pcl/surface/eigen.h @@ -0,0 +1,49 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $ + * + */ + +#ifndef PCL_SURFACE_EIGEN_H_ +#define PCL_SURFACE_EIGEN_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include + +#endif // PCL_SURFACE_EIGEN_H_ diff --git a/pcl-1.7/pcl/surface/gp3.h b/pcl-1.7/pcl/surface/gp3.h new file mode 100644 index 0000000..e62b05e --- /dev/null +++ b/pcl-1.7/pcl/surface/gp3.h @@ -0,0 +1,548 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_GP3_H_ +#define PCL_GP3_H_ + +// PCL includes +#include +#include + +#include +#include +#include +#include + +#include +#include + + + +namespace pcl +{ + /** \brief Returns if a point X is visible from point R (or the origin) + * when taking into account the segment between the points S1 and S2 + * \param X 2D coordinate of the point + * \param S1 2D coordinate of the segment's first point + * \param S2 2D coordinate of the segment's secont point + * \param R 2D coorddinate of the reference point (defaults to 0,0) + * \ingroup surface + */ + inline bool + isVisible (const Eigen::Vector2f &X, const Eigen::Vector2f &S1, const Eigen::Vector2f &S2, + const Eigen::Vector2f &R = Eigen::Vector2f::Zero ()) + { + double a0 = S1[1] - S2[1]; + double b0 = S2[0] - S1[0]; + double c0 = S1[0]*S2[1] - S2[0]*S1[1]; + double a1 = -X[1]; + double b1 = X[0]; + double c1 = 0; + if (R != Eigen::Vector2f::Zero()) + { + a1 += R[1]; + b1 -= R[0]; + c1 = R[0]*X[1] - X[0]*R[1]; + } + double div = a0*b1 - b0*a1; + double x = (b0*c1 - b1*c0) / div; + double y = (a1*c0 - a0*c1) / div; + + bool intersection_outside_XR; + if (R == Eigen::Vector2f::Zero()) + { + if (X[0] > 0) + intersection_outside_XR = (x <= 0) || (x >= X[0]); + else if (X[0] < 0) + intersection_outside_XR = (x >= 0) || (x <= X[0]); + else if (X[1] > 0) + intersection_outside_XR = (y <= 0) || (y >= X[1]); + else if (X[1] < 0) + intersection_outside_XR = (y >= 0) || (y <= X[1]); + else + intersection_outside_XR = true; + } + else + { + if (X[0] > R[0]) + intersection_outside_XR = (x <= R[0]) || (x >= X[0]); + else if (X[0] < R[0]) + intersection_outside_XR = (x >= R[0]) || (x <= X[0]); + else if (X[1] > R[1]) + intersection_outside_XR = (y <= R[1]) || (y >= X[1]); + else if (X[1] < R[1]) + intersection_outside_XR = (y >= R[1]) || (y <= X[1]); + else + intersection_outside_XR = true; + } + if (intersection_outside_XR) + return true; + else + { + if (S1[0] > S2[0]) + return (x <= S2[0]) || (x >= S1[0]); + else if (S1[0] < S2[0]) + return (x >= S2[0]) || (x <= S1[0]); + else if (S1[1] > S2[1]) + return (y <= S2[1]) || (y >= S1[1]); + else if (S1[1] < S2[1]) + return (y >= S2[1]) || (y <= S1[1]); + else + return false; + } + } + + /** \brief GreedyProjectionTriangulation is an implementation of a greedy triangulation algorithm for 3D points + * based on local 2D projections. It assumes locally smooth surfaces and relatively smooth transitions between + * areas with different point densities. + * \author Zoltan Csaba Marton + * \ingroup surface + */ + template + class GreedyProjectionTriangulation : public MeshConstruction + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using MeshConstruction::tree_; + using MeshConstruction::input_; + using MeshConstruction::indices_; + + typedef typename pcl::KdTree KdTree; + typedef typename pcl::KdTree::Ptr KdTreePtr; + + typedef pcl::PointCloud PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + enum GP3Type + { + NONE = -1, // not-defined + FREE = 0, + FRINGE = 1, + BOUNDARY = 2, + COMPLETED = 3 + }; + + /** \brief Empty constructor. */ + GreedyProjectionTriangulation () : + mu_ (0), + search_radius_ (0), // must be set by user + nnn_ (100), + minimum_angle_ (M_PI/18), // 10 degrees + maximum_angle_ (2*M_PI/3), // 120 degrees + eps_angle_(M_PI/4), //45 degrees, + consistent_(false), + consistent_ordering_ (false), + triangle_ (), + coords_ (), + angles_ (), + R_ (), + state_ (), + source_ (), + ffn_ (), + sfn_ (), + part_ (), + fringe_queue_ (), + is_current_free_ (false), + current_index_ (), + prev_is_ffn_ (false), + prev_is_sfn_ (false), + next_is_ffn_ (false), + next_is_sfn_ (false), + changed_1st_fn_ (false), + changed_2nd_fn_ (false), + new2boundary_ (), + already_connected_ (false), + proj_qp_ (), + u_ (), + v_ (), + uvn_ffn_ (), + uvn_sfn_ (), + uvn_next_ffn_ (), + uvn_next_sfn_ (), + tmp_ () + {}; + + /** \brief Set the multiplier of the nearest neighbor distance to obtain the final search radius for each point + * (this will make the algorithm adapt to different point densities in the cloud). + * \param[in] mu the multiplier + */ + inline void + setMu (double mu) { mu_ = mu; } + + /** \brief Get the nearest neighbor distance multiplier. */ + inline double + getMu () const { return (mu_); } + + /** \brief Set the maximum number of nearest neighbors to be searched for. + * \param[in] nnn the maximum number of nearest neighbors + */ + inline void + setMaximumNearestNeighbors (int nnn) { nnn_ = nnn; } + + /** \brief Get the maximum number of nearest neighbors to be searched for. */ + inline int + getMaximumNearestNeighbors () const { return (nnn_); } + + /** \brief Set the sphere radius that is to be used for determining the k-nearest neighbors used for triangulating. + * \param[in] radius the sphere radius that is to contain all k-nearest neighbors + * \note This distance limits the maximum edge length! + */ + inline void + setSearchRadius (double radius) { search_radius_ = radius; } + + /** \brief Get the sphere radius used for determining the k-nearest neighbors. */ + inline double + getSearchRadius () const { return (search_radius_); } + + /** \brief Set the minimum angle each triangle should have. + * \param[in] minimum_angle the minimum angle each triangle should have + * \note As this is a greedy approach, this will have to be violated from time to time + */ + inline void + setMinimumAngle (double minimum_angle) { minimum_angle_ = minimum_angle; } + + /** \brief Get the parameter for distance based weighting of neighbors. */ + inline double + getMinimumAngle () const { return (minimum_angle_); } + + /** \brief Set the maximum angle each triangle can have. + * \param[in] maximum_angle the maximum angle each triangle can have + * \note For best results, its value should be around 120 degrees + */ + inline void + setMaximumAngle (double maximum_angle) { maximum_angle_ = maximum_angle; } + + /** \brief Get the parameter for distance based weighting of neighbors. */ + inline double + getMaximumAngle () const { return (maximum_angle_); } + + /** \brief Don't consider points for triangulation if their normal deviates more than this value from the query point's normal. + * \param[in] eps_angle maximum surface angle + * \note As normal estimation methods usually give smooth transitions at sharp edges, this ensures correct triangulation + * by avoiding connecting points from one side to points from the other through forcing the use of the edge points. + */ + inline void + setMaximumSurfaceAngle (double eps_angle) { eps_angle_ = eps_angle; } + + /** \brief Get the maximum surface angle. */ + inline double + getMaximumSurfaceAngle () const { return (eps_angle_); } + + /** \brief Set the flag if the input normals are oriented consistently. + * \param[in] consistent set it to true if the normals are consistently oriented + */ + inline void + setNormalConsistency (bool consistent) { consistent_ = consistent; } + + /** \brief Get the flag for consistently oriented normals. */ + inline bool + getNormalConsistency () const { return (consistent_); } + + /** \brief Set the flag to order the resulting triangle vertices consistently (positive direction around normal). + * @note Assumes consistently oriented normals (towards the viewpoint) -- see setNormalConsistency () + * \param[in] consistent_ordering set it to true if triangle vertices should be ordered consistently + */ + inline void + setConsistentVertexOrdering (bool consistent_ordering) { consistent_ordering_ = consistent_ordering; } + + /** \brief Get the flag signaling consistently ordered triangle vertices. */ + inline bool + getConsistentVertexOrdering () const { return (consistent_ordering_); } + + /** \brief Get the state of each point after reconstruction. + * \note Options are defined as constants: FREE, FRINGE, COMPLETED, BOUNDARY and NONE + */ + inline std::vector + getPointStates () const { return (state_); } + + /** \brief Get the ID of each point after reconstruction. + * \note parts are numbered from 0, a -1 denotes unconnected points + */ + inline std::vector + getPartIDs () const { return (part_); } + + + /** \brief Get the sfn list. */ + inline std::vector + getSFN () const { return (sfn_); } + + /** \brief Get the ffn list. */ + inline std::vector + getFFN () const { return (ffn_); } + + protected: + /** \brief The nearest neighbor distance multiplier to obtain the final search radius. */ + double mu_; + + /** \brief The nearest neighbors search radius for each point and the maximum edge length. */ + double search_radius_; + + /** \brief The maximum number of nearest neighbors accepted by searching. */ + int nnn_; + + /** \brief The preferred minimum angle for the triangles. */ + double minimum_angle_; + + /** \brief The maximum angle for the triangles. */ + double maximum_angle_; + + /** \brief Maximum surface angle. */ + double eps_angle_; + + /** \brief Set this to true if the normals of the input are consistently oriented. */ + bool consistent_; + + /** \brief Set this to true if the output triangle vertices should be consistently oriented. */ + bool consistent_ordering_; + + private: + /** \brief Struct for storing the angles to nearest neighbors **/ + struct nnAngle + { + double angle; + int index; + int nnIndex; + bool visible; + }; + + /** \brief Struct for storing the edges starting from a fringe point **/ + struct doubleEdge + { + doubleEdge () : index (0), first (), second () {} + int index; + Eigen::Vector2f first; + Eigen::Vector2f second; + }; + + // Variables made global to decrease the number of parameters to helper functions + + /** \brief Temporary variable to store a triangle (as a set of point indices) **/ + pcl::Vertices triangle_; + /** \brief Temporary variable to store point coordinates **/ + std::vector coords_; + + /** \brief A list of angles to neighbors **/ + std::vector angles_; + /** \brief Index of the current query point **/ + int R_; + /** \brief List of point states **/ + std::vector state_; + /** \brief List of sources **/ + std::vector source_; + /** \brief List of fringe neighbors in one direction **/ + std::vector ffn_; + /** \brief List of fringe neighbors in other direction **/ + std::vector sfn_; + /** \brief Connected component labels for each point **/ + std::vector part_; + /** \brief Points on the outer edge from which the mesh has to be grown **/ + std::vector fringe_queue_; + + /** \brief Flag to set if the current point is free **/ + bool is_current_free_; + /** \brief Current point's index **/ + int current_index_; + /** \brief Flag to set if the previous point is the first fringe neighbor **/ + bool prev_is_ffn_; + /** \brief Flag to set if the next point is the second fringe neighbor **/ + bool prev_is_sfn_; + /** \brief Flag to set if the next point is the first fringe neighbor **/ + bool next_is_ffn_; + /** \brief Flag to set if the next point is the second fringe neighbor **/ + bool next_is_sfn_; + /** \brief Flag to set if the first fringe neighbor was changed **/ + bool changed_1st_fn_; + /** \brief Flag to set if the second fringe neighbor was changed **/ + bool changed_2nd_fn_; + /** \brief New boundary point **/ + int new2boundary_; + + /** \brief Flag to set if the next neighbor was already connected in the previous step. + * To avoid inconsistency it should not be connected again. + */ + bool already_connected_; + + /** \brief Point coordinates projected onto the plane defined by the point normal **/ + Eigen::Vector3f proj_qp_; + /** \brief First coordinate vector of the 2D coordinate frame **/ + Eigen::Vector3f u_; + /** \brief Second coordinate vector of the 2D coordinate frame **/ + Eigen::Vector3f v_; + /** \brief 2D coordinates of the first fringe neighbor **/ + Eigen::Vector2f uvn_ffn_; + /** \brief 2D coordinates of the second fringe neighbor **/ + Eigen::Vector2f uvn_sfn_; + /** \brief 2D coordinates of the first fringe neighbor of the next point **/ + Eigen::Vector2f uvn_next_ffn_; + /** \brief 2D coordinates of the second fringe neighbor of the next point **/ + Eigen::Vector2f uvn_next_sfn_; + + /** \brief Temporary variable to store 3 coordiantes **/ + Eigen::Vector3f tmp_; + + /** \brief The actual surface reconstruction method. + * \param[out] output the resultant polygonal mesh + */ + void + performReconstruction (pcl::PolygonMesh &output); + + /** \brief The actual surface reconstruction method. + * \param[out] polygons the resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices. + */ + void + performReconstruction (std::vector &polygons); + + /** \brief The actual surface reconstruction method. + * \param[out] polygons the resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices. + */ + bool + reconstructPolygons (std::vector &polygons); + + /** \brief Class get name method. */ + std::string + getClassName () const { return ("GreedyProjectionTriangulation"); } + + /** \brief Forms a new triangle by connecting the current neighbor to the query point + * and the previous neighbor + * \param[out] polygons the polygon mesh to be updated + * \param[in] prev_index index of the previous point + * \param[in] next_index index of the next point + * \param[in] next_next_index index of the point after the next one + * \param[in] uvn_current 2D coordinate of the current point + * \param[in] uvn_prev 2D coordinates of the previous point + * \param[in] uvn_next 2D coordinates of the next point + */ + void + connectPoint (std::vector &polygons, + const int prev_index, + const int next_index, + const int next_next_index, + const Eigen::Vector2f &uvn_current, + const Eigen::Vector2f &uvn_prev, + const Eigen::Vector2f &uvn_next); + + /** \brief Whenever a query point is part of a boundary loop containing 3 points, that triangle is created + * (called if angle constraints make it possible) + * \param[out] polygons the polygon mesh to be updated + */ + void + closeTriangle (std::vector &polygons); + + /** \brief Get the list of containing triangles for each vertex in a PolygonMesh + * \param[in] polygonMesh the input polygon mesh + */ + std::vector > + getTriangleList (const pcl::PolygonMesh &input); + + /** \brief Add a new triangle to the current polygon mesh + * \param[in] a index of the first vertex + * \param[in] b index of the second vertex + * \param[in] c index of the third vertex + * \param[out] polygons the polygon mesh to be updated + */ + inline void + addTriangle (int a, int b, int c, std::vector &polygons) + { + triangle_.vertices.resize (3); + if (consistent_ordering_) + { + const PointInT p = input_->at (indices_->at (a)); + const Eigen::Vector3f pv = p.getVector3fMap (); + if (p.getNormalVector3fMap ().dot ( + (pv - input_->at (indices_->at (b)).getVector3fMap ()).cross ( + pv - input_->at (indices_->at (c)).getVector3fMap ()) ) > 0) + { + triangle_.vertices[0] = a; + triangle_.vertices[1] = b; + triangle_.vertices[2] = c; + } + else + { + triangle_.vertices[0] = a; + triangle_.vertices[1] = c; + triangle_.vertices[2] = b; + } + } + else + { + triangle_.vertices[0] = a; + triangle_.vertices[1] = b; + triangle_.vertices[2] = c; + } + polygons.push_back (triangle_); + } + + /** \brief Add a new vertex to the advancing edge front and set its source point + * \param[in] v index of the vertex that was connected + * \param[in] s index of the source point + */ + inline void + addFringePoint (int v, int s) + { + source_[v] = s; + part_[v] = part_[s]; + fringe_queue_.push_back(v); + } + + /** \brief Function for ascending sort of nnAngle, taking visibility into account + * (angles to visible neighbors will be first, to the invisible ones after). + * \param[in] a1 the first angle + * \param[in] a2 the second angle + */ + static inline bool + nnAngleSortAsc (const nnAngle& a1, const nnAngle& a2) + { + if (a1.visible == a2.visible) + return (a1.angle < a2.angle); + else + return a1.visible; + } + }; + +} // namespace pcl + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //#ifndef PCL_GP3_H_ + diff --git a/pcl-1.7/pcl/surface/grid_projection.h b/pcl-1.7/pcl/surface/grid_projection.h new file mode 100644 index 0000000..ce5dd83 --- /dev/null +++ b/pcl-1.7/pcl/surface/grid_projection.h @@ -0,0 +1,506 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SURFACE_GRID_PROJECTION_H_ +#define PCL_SURFACE_GRID_PROJECTION_H_ + +#include +#include + +namespace pcl +{ + /** \brief The 12 edges of a cell. */ + const int I_SHIFT_EP[12][2] = { + {0, 4}, {1, 5}, {2, 6}, {3, 7}, + {0, 1}, {1, 2}, {2, 3}, {3, 0}, + {4, 5}, {5, 6}, {6, 7}, {7, 4} + }; + + const int I_SHIFT_PT[4] = { + 0, 4, 5, 7 + }; + + const int I_SHIFT_EDGE[3][2] = { + {0,1}, {1,3}, {1,2} + }; + + + /** \brief Grid projection surface reconstruction method. + * \author Rosie Li + * + * \note If you use this code in any academic work, please cite: + * - Ruosi Li, Lu Liu, Ly Phan, Sasakthi Abeysinghe, Cindy Grimm, Tao Ju. + * Polygonizing extremal surfaces with manifold guarantees. + * In Proceedings of the 14th ACM Symposium on Solid and Physical Modeling, 2010. + * \ingroup surface + */ + template + class GridProjection : public SurfaceReconstruction + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using SurfaceReconstruction::input_; + using SurfaceReconstruction::tree_; + + typedef typename pcl::PointCloud::Ptr PointCloudPtr; + + typedef typename pcl::KdTree KdTree; + typedef typename pcl::KdTree::Ptr KdTreePtr; + + /** \brief Data leaf. */ + struct Leaf + { + Leaf () : data_indices (), pt_on_surface (), vect_at_grid_pt () {} + + std::vector data_indices; + Eigen::Vector4f pt_on_surface; + Eigen::Vector3f vect_at_grid_pt; + }; + + typedef boost::unordered_map, std::equal_to, Eigen::aligned_allocator > HashMap; + + /** \brief Constructor. */ + GridProjection (); + + /** \brief Constructor. + * \param in_resolution set the resolution of the grid + */ + GridProjection (double in_resolution); + + /** \brief Destructor. */ + ~GridProjection (); + + /** \brief Set the size of the grid cell + * \param resolution the size of the grid cell + */ + inline void + setResolution (double resolution) + { + leaf_size_ = resolution; + } + + inline double + getResolution () const + { + return (leaf_size_); + } + + /** \brief When averaging the vectors, we find the union of all the input data + * points within the padding area,and do a weighted average. Say if the padding + * size is 1, when we process cell (x,y,z), we will find union of input data points + * from (x-1) to (x+1), (y-1) to (y+1), (z-1) to (z+1)(in total, 27 cells). In this + * way, even the cells itself doesnt contain any data points, we will stil process it + * because there are data points in the padding area. This can help us fix holes which + * is smaller than the padding size. + * \param padding_size The num of padding cells we want to create + */ + inline void + setPaddingSize (int padding_size) + { + padding_size_ = padding_size; + } + inline int + getPaddingSize () const + { + return (padding_size_); + } + + /** \brief Set this only when using the k nearest neighbors search + * instead of finding the point union + * \param k The number of nearest neighbors we are looking for + */ + inline void + setNearestNeighborNum (int k) + { + k_ = k; + } + inline int + getNearestNeighborNum () const + { + return (k_); + } + + /** \brief Binary search is used in projection. given a point x, we find another point + * which is 3*cell_size_ far away from x. Then we do a binary search between these + * two points to find where the projected point should be. + */ + inline void + setMaxBinarySearchLevel (int max_binary_search_level) + { + max_binary_search_level_ = max_binary_search_level; + } + inline int + getMaxBinarySearchLevel () const + { + return (max_binary_search_level_); + } + + /////////////////////////////////////////////////////////// + inline const HashMap& + getCellHashMap () const + { + return (cell_hash_map_); + } + + inline const std::vector >& + getVectorAtDataPoint () const + { + return (vector_at_data_point_); + } + + inline const std::vector >& + getSurface () const + { + return (surface_); + } + + protected: + /** \brief Get the bounding box for the input data points, also calculating the + * cell size, and the gaussian scale factor + */ + void + getBoundingBox (); + + /** \brief The actual surface reconstruction method. + * \param[out] polygons the resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices. + */ + bool + reconstructPolygons (std::vector &polygons); + + /** \brief Create the surface. + * + * The 1st step is filling the padding, so that all the cells in the padding + * area are in the hash map. The 2nd step is store the vector, and projected + * point. The 3rd step is finding all the edges intersects the surface, and + * creating surface. + * + * \param[out] output the resultant polygonal mesh + */ + void + performReconstruction (pcl::PolygonMesh &output); + + /** \brief Create the surface. + * + * The 1st step is filling the padding, so that all the cells in the padding + * area are in the hash map. The 2nd step is store the vector, and projected + * point. The 3rd step is finding all the edges intersects the surface, and + * creating surface. + * + * \param[out] points the resultant points lying on the surface + * \param[out] polygons the resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices. + */ + void + performReconstruction (pcl::PointCloud &points, + std::vector &polygons); + + /** \brief When the input data points don't fill into the 1*1*1 box, + * scale them so that they can be filled in the unit box. Otherwise, + * it will be some drawing problem when doing visulization + * \param scale_factor scale all the input data point by scale_factor + */ + void + scaleInputDataPoint (double scale_factor); + + /** \brief Get the 3d index (x,y,z) of the cell based on the location of + * the cell + * \param p the coordinate of the input point + * \param index the output 3d index + */ + inline void + getCellIndex (const Eigen::Vector4f &p, Eigen::Vector3i& index) const + { + for (int i = 0; i < 3; ++i) + index[i] = static_cast ((p[i] - min_p_(i)) / leaf_size_); + } + + /** \brief Given the 3d index (x, y, z) of the cell, get the + * coordinates of the cell center + * \param index the output 3d index + * \param center the resultant cell center + */ + inline void + getCellCenterFromIndex (const Eigen::Vector3i &index, Eigen::Vector4f ¢er) const + { + for (int i = 0; i < 3; ++i) + center[i] = + min_p_[i] + static_cast (index[i]) * + static_cast (leaf_size_) + + static_cast (leaf_size_) / 2.0f; + } + + /** \brief Given cell center, caluate the coordinates of the eight vertices of the cell + * \param cell_center the coordinates of the cell center + * \param pts the coordinates of the 8 vertices + */ + void + getVertexFromCellCenter (const Eigen::Vector4f &cell_center, + std::vector > &pts) const; + + /** \brief Given an index (x, y, z) in 3d, translate it into the index + * in 1d + * \param index the index of the cell in (x,y,z) 3d format + */ + inline int + getIndexIn1D (const Eigen::Vector3i &index) const + { + //assert(data_size_ > 0); + return (index[0] * data_size_ * data_size_ + + index[1] * data_size_ + index[2]); + } + + /** \brief Given an index in 1d, translate it into the index (x, y, z) + * in 3d + * \param index_1d the input 1d index + * \param index_3d the output 3d index + */ + inline void + getIndexIn3D (int index_1d, Eigen::Vector3i& index_3d) const + { + //assert(data_size_ > 0); + index_3d[0] = index_1d / (data_size_ * data_size_); + index_1d -= index_3d[0] * data_size_ * data_size_; + index_3d[1] = index_1d / data_size_; + index_1d -= index_3d[1] * data_size_; + index_3d[2] = index_1d; + } + + /** \brief For a given 3d index of a cell, test whether the cells within its + * padding area exist in the hash table, if no, create an entry for that cell. + * \param index the index of the cell in (x,y,z) format + */ + void + fillPad (const Eigen::Vector3i &index); + + /** \brief Obtain the index of a cell and the pad size. + * \param index the input index + * \param pt_union_indices the union of input data points within the cell and padding cells + */ + void + getDataPtsUnion (const Eigen::Vector3i &index, std::vector &pt_union_indices); + + /** \brief Given the index of a cell, exam it's up, left, front edges, and add + * the vectices to m_surface list.the up, left, front edges only share 4 + * points, we first get the vectors at these 4 points and exam whether those + * three edges are intersected by the surface \param index the input index + * \param pt_union_indices the union of input data points within the cell and padding cells + */ + void + createSurfaceForCell (const Eigen::Vector3i &index, std::vector &pt_union_indices); + + + /** \brief Given the coordinates of one point, project it onto the surface, + * return the projected point. Do a binary search between p and p+projection_distance + * to find the projected point + * \param p the coordinates of the input point + * \param pt_union_indices the union of input data points within the cell and padding cells + * \param projection the resultant point projected + */ + void + getProjection (const Eigen::Vector4f &p, std::vector &pt_union_indices, Eigen::Vector4f &projection); + + /** \brief Given the coordinates of one point, project it onto the surface, + * return the projected point. Find the plane which fits all the points in + * pt_union_indices, projected p to the plane to get the projected point. + * \param p the coordinates of the input point + * \param pt_union_indices the union of input data points within the cell and padding cells + * \param projection the resultant point projected + */ + void + getProjectionWithPlaneFit (const Eigen::Vector4f &p, + std::vector &pt_union_indices, + Eigen::Vector4f &projection); + + + /** \brief Given the location of a point, get it's vector + * \param p the coordinates of the input point + * \param pt_union_indices the union of input data points within the cell and padding cells + * \param vo the resultant vector + */ + void + getVectorAtPoint (const Eigen::Vector4f &p, + std::vector &pt_union_indices, Eigen::Vector3f &vo); + + /** \brief Given the location of a point, get it's vector + * \param p the coordinates of the input point + * \param k_indices the k nearest neighbors of the query point + * \param k_squared_distances the squared distances of the k nearest + * neighbors to the query point + * \param vo the resultant vector + */ + void + getVectorAtPointKNN (const Eigen::Vector4f &p, + std::vector &k_indices, + std::vector &k_squared_distances, + Eigen::Vector3f &vo); + + /** \brief Get the magnitude of the vector by summing up the distance. + * \param p the coordinate of the input point + * \param pt_union_indices the union of input data points within the cell and padding cells + */ + double + getMagAtPoint (const Eigen::Vector4f &p, const std::vector &pt_union_indices); + + /** \brief Get the 1st derivative + * \param p the coordinate of the input point + * \param vec the vector at point p + * \param pt_union_indices the union of input data points within the cell and padding cells + */ + double + getD1AtPoint (const Eigen::Vector4f &p, const Eigen::Vector3f &vec, + const std::vector &pt_union_indices); + + /** \brief Get the 2nd derivative + * \param p the coordinate of the input point + * \param vec the vector at point p + * \param pt_union_indices the union of input data points within the cell and padding cells + */ + double + getD2AtPoint (const Eigen::Vector4f &p, const Eigen::Vector3f &vec, + const std::vector &pt_union_indices); + + /** \brief Test whether the edge is intersected by the surface by + * doing the dot product of the vector at two end points. Also test + * whether the edge is intersected by the maximum surface by examing + * the 2nd derivative of the intersection point + * \param end_pts the two points of the edge + * \param vect_at_end_pts + * \param pt_union_indices the union of input data points within the cell and padding cells + */ + bool + isIntersected (const std::vector > &end_pts, + std::vector > &vect_at_end_pts, + std::vector &pt_union_indices); + + /** \brief Find point where the edge intersects the surface. + * \param level binary search level + * \param end_pts the two end points on the edge + * \param vect_at_end_pts the vectors at the two end points + * \param start_pt the starting point we use for binary search + * \param pt_union_indices the union of input data points within the cell and padding cells + * \param intersection the resultant intersection point + */ + void + findIntersection (int level, + const std::vector > &end_pts, + const std::vector > &vect_at_end_pts, + const Eigen::Vector4f &start_pt, + std::vector &pt_union_indices, + Eigen::Vector4f &intersection); + + /** \brief Go through all the entries in the hash table and update the + * cellData. + * + * When creating the hash table, the pt_on_surface field store the center + * point of the cell.After calling this function, the projection operator will + * project the center point onto the surface, and the pt_on_surface field will + * be updated using the projected point.Also the vect_at_grid_pt field will be + * updated using the vector at the upper left front vertex of the cell. + * + * \param index_1d the index of the cell after flatting it's 3d index into a 1d array + * \param index_3d the index of the cell in (x,y,z) 3d format + * \param pt_union_indices the union of input data points within the cell and pads + * \param cell_data information stored in the cell + */ + void + storeVectAndSurfacePoint (int index_1d, const Eigen::Vector3i &index_3d, + std::vector &pt_union_indices, const Leaf &cell_data); + + /** \brief Go through all the entries in the hash table and update the cellData. + * When creating the hash table, the pt_on_surface field store the center point + * of the cell.After calling this function, the projection operator will project the + * center point onto the surface, and the pt_on_surface field will be updated + * using the projected point.Also the vect_at_grid_pt field will be updated using + * the vector at the upper left front vertex of the cell. When projecting the point + * and calculating the vector, using K nearest neighbors instead of using the + * union of input data point within the cell and pads. + * + * \param index_1d the index of the cell after flatting it's 3d index into a 1d array + * \param index_3d the index of the cell in (x,y,z) 3d format + * \param cell_data information stored in the cell + */ + void + storeVectAndSurfacePointKNN (int index_1d, const Eigen::Vector3i &index_3d, const Leaf &cell_data); + + private: + /** \brief Map containing the set of leaves. */ + HashMap cell_hash_map_; + + /** \brief Min and max data points. */ + Eigen::Vector4f min_p_, max_p_; + + /** \brief The size of a leaf. */ + double leaf_size_; + + /** \brief Gaussian scale. */ + double gaussian_scale_; + + /** \brief Data size. */ + int data_size_; + + /** \brief Max binary search level. */ + int max_binary_search_level_; + + /** \brief Number of neighbors (k) to use. */ + int k_; + + /** \brief Padding size. */ + int padding_size_; + + /** \brief The point cloud input (XYZ+Normals). */ + PointCloudPtr data_; + + /** \brief Store the surface normal(vector) at the each input data point. */ + std::vector > vector_at_data_point_; + + /** \brief An array of points which lay on the output surface. */ + std::vector > surface_; + + /** \brief Bit map which tells if there is any input data point in the cell. */ + boost::dynamic_bitset<> occupied_cell_list_; + + /** \brief Class get name method. */ + std::string getClassName () const { return ("GridProjection"); } + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#endif // PCL_SURFACE_GRID_PROJECTION_H_ + diff --git a/pcl-1.7/pcl/surface/impl/bilateral_upsampling.hpp b/pcl-1.7/pcl/surface/impl/bilateral_upsampling.hpp new file mode 100644 index 0000000..b355f23 --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/bilateral_upsampling.hpp @@ -0,0 +1,185 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + + +#ifndef PCL_SURFACE_IMPL_BILATERAL_UPSAMPLING_H_ +#define PCL_SURFACE_IMPL_BILATERAL_UPSAMPLING_H_ + +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BilateralUpsampling::process (pcl::PointCloud &output) +{ + // Copy the header + output.header = input_->header; + + if (!initCompute ()) + { + output.width = output.height = 0; + output.points.clear (); + return; + } + + if (input_->isOrganized () == false) + { + PCL_ERROR ("Input cloud is not organized.\n"); + return; + } + + // Invert projection matrix + unprojection_matrix_ = projection_matrix_.inverse (); + + for (int i = 0; i < 3; ++i) + { + for (int j = 0; j < 3; ++j) + printf ("%f ", unprojection_matrix_(i, j)); + + printf ("\n"); + } + + + // Perform the actual surface reconstruction + performProcessing (output); + + deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::BilateralUpsampling::performProcessing (PointCloudOut &output) +{ + output.resize (input_->size ()); + float nan = std::numeric_limits::quiet_NaN (); + + Eigen::MatrixXf val_exp_depth_matrix; + Eigen::VectorXf val_exp_rgb_vector; + computeDistances (val_exp_depth_matrix, val_exp_rgb_vector); + + for (int x = 0; x < static_cast (input_->width); ++x) + for (int y = 0; y < static_cast (input_->height); ++y) + { + int start_window_x = std::max (x - window_size_, 0), + start_window_y = std::max (y - window_size_, 0), + end_window_x = std::min (x + window_size_, static_cast (input_->width)), + end_window_y = std::min (y + window_size_, static_cast (input_->height)); + + float sum = 0.0f, + norm_sum = 0.0f; + + for (int x_w = start_window_x; x_w < end_window_x; ++ x_w) + for (int y_w = start_window_y; y_w < end_window_y; ++ y_w) + { + float dx = float (x - x_w), + dy = float (y - y_w); + + float val_exp_depth = val_exp_depth_matrix(dx+window_size_, dy+window_size_); + + float d_color = static_cast ( + abs (input_->points[y_w * input_->width + x_w].r - input_->points[y * input_->width + x].r) + + abs (input_->points[y_w * input_->width + x_w].g - input_->points[y * input_->width + x].g) + + abs (input_->points[y_w * input_->width + x_w].b - input_->points[y * input_->width + x].b)); + + float val_exp_rgb = val_exp_rgb_vector(d_color); + + if (pcl_isfinite (input_->points[y_w*input_->width + x_w].z)) + { + sum += val_exp_depth * val_exp_rgb * input_->points[y_w*input_->width + x_w].z; + norm_sum += val_exp_depth * val_exp_rgb; + } + } + + output.points[y*input_->width + x].r = input_->points[y*input_->width + x].r; + output.points[y*input_->width + x].g = input_->points[y*input_->width + x].g; + output.points[y*input_->width + x].b = input_->points[y*input_->width + x].b; + + if (norm_sum != 0.0f) + { + float depth = sum / norm_sum; + Eigen::Vector3f pc (static_cast (x) * depth, static_cast (y) * depth, depth); + Eigen::Vector3f pw (unprojection_matrix_ * pc); + output.points[y*input_->width + x].x = pw[0]; + output.points[y*input_->width + x].y = pw[1]; + output.points[y*input_->width + x].z = pw[2]; + } + else + { + output.points[y*input_->width + x].x = nan; + output.points[y*input_->width + x].y = nan; + output.points[y*input_->width + x].z = nan; + } + } + + output.header = input_->header; + output.width = input_->width; + output.height = input_->height; +} + + +template void +pcl::BilateralUpsampling::computeDistances (Eigen::MatrixXf &val_exp_depth, Eigen::VectorXf &val_exp_rgb) +{ + val_exp_depth.resize (2*window_size_+1,2*window_size_+1); + val_exp_rgb.resize (3*255); + + int j = 0; + for (int dx = -window_size_; dx < window_size_+1; ++dx) + { + int i = 0; + for (int dy = -window_size_; dy < window_size_+1; ++dy) + { + float val_exp = expf (- (dx*dx + dy*dy) / (2.0f * static_cast (sigma_depth_ * sigma_depth_))); + val_exp_depth(i,j) = val_exp; + i++; + } + j++; + } + + for (int d_color = 0; d_color < 3*255; d_color++) + { + float val_exp = expf (- d_color * d_color / (2.0f * sigma_color_ * sigma_color_)); + val_exp_rgb(d_color) = val_exp; + } +} + + +#define PCL_INSTANTIATE_BilateralUpsampling(T,OutT) template class PCL_EXPORTS pcl::BilateralUpsampling; + + +#endif /* PCL_SURFACE_IMPL_BILATERAL_UPSAMPLING_H_ */ diff --git a/pcl-1.7/pcl/surface/impl/concave_hull.hpp b/pcl-1.7/pcl/surface/impl/concave_hull.hpp new file mode 100644 index 0000000..7900104 --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/concave_hull.hpp @@ -0,0 +1,624 @@ +/** + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#include +#ifdef HAVE_QHULL + +#ifndef PCL_SURFACE_IMPL_CONCAVE_HULL_H_ +#define PCL_SURFACE_IMPL_CONCAVE_HULL_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////// +/** \brief Get dimension of concave hull + * \return dimension + */ +template int +pcl::ConcaveHull::getDim () const +{ + return (getDimension ()); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConcaveHull::reconstruct (PointCloud &output) +{ + output.header = input_->header; + if (alpha_ <= 0) + { + PCL_ERROR ("[pcl::%s::reconstruct] Alpha parameter must be set to a positive number!\n", getClassName ().c_str ()); + output.points.clear (); + return; + } + + if (!initCompute ()) + { + output.points.clear (); + return; + } + + // Perform the actual surface reconstruction + std::vector polygons; + performReconstruction (output, polygons); + + output.width = static_cast (output.points.size ()); + output.height = 1; + output.is_dense = true; + + deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConcaveHull::reconstruct (PointCloud &output, std::vector &polygons) +{ + output.header = input_->header; + if (alpha_ <= 0) + { + PCL_ERROR ("[pcl::%s::reconstruct] Alpha parameter must be set to a positive number!\n", getClassName ().c_str ()); + output.points.clear (); + return; + } + + if (!initCompute ()) + { + output.points.clear (); + return; + } + + // Perform the actual surface reconstruction + performReconstruction (output, polygons); + + output.width = static_cast (output.points.size ()); + output.height = 1; + output.is_dense = true; + + deinitCompute (); +} + +#ifdef __GNUC__ +#pragma GCC diagnostic ignored "-Wold-style-cast" +#endif +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConcaveHull::performReconstruction (PointCloud &alpha_shape, std::vector &polygons) +{ + EIGEN_ALIGN16 Eigen::Matrix3d covariance_matrix; + Eigen::Vector4d xyz_centroid; + computeMeanAndCovarianceMatrix (*input_, *indices_, covariance_matrix, xyz_centroid); + + // Check if the covariance matrix is finite or not. + for (int i = 0; i < 3; ++i) + for (int j = 0; j < 3; ++j) + if (!pcl_isfinite (covariance_matrix.coeffRef (i, j))) + return; + + EIGEN_ALIGN16 Eigen::Vector3d eigen_values; + EIGEN_ALIGN16 Eigen::Matrix3d eigen_vectors; + pcl::eigen33 (covariance_matrix, eigen_vectors, eigen_values); + + Eigen::Affine3d transform1; + transform1.setIdentity (); + + // If no input dimension is specified, determine automatically + if (dim_ == 0) + { + PCL_DEBUG ("[pcl::%s] WARNING: Input dimension not specified. Automatically determining input dimension.\n", getClassName ().c_str ()); + if (eigen_values[0] / eigen_values[2] < 1.0e-3) + dim_ = 2; + else + dim_ = 3; + } + + if (dim_ == 2) + { + // we have points laying on a plane, using 2d convex hull + // compute transformation bring eigen_vectors.col(i) to z-axis + + transform1 (2, 0) = eigen_vectors (0, 0); + transform1 (2, 1) = eigen_vectors (1, 0); + transform1 (2, 2) = eigen_vectors (2, 0); + + transform1 (1, 0) = eigen_vectors (0, 1); + transform1 (1, 1) = eigen_vectors (1, 1); + transform1 (1, 2) = eigen_vectors (2, 1); + transform1 (0, 0) = eigen_vectors (0, 2); + transform1 (0, 1) = eigen_vectors (1, 2); + transform1 (0, 2) = eigen_vectors (2, 2); + } + else + { + transform1.setIdentity (); + } + + PointCloud cloud_transformed; + pcl::demeanPointCloud (*input_, *indices_, xyz_centroid, cloud_transformed); + pcl::transformPointCloud (cloud_transformed, cloud_transformed, transform1); + + // True if qhull should free points in qh_freeqhull() or reallocation + boolT ismalloc = True; + // option flags for qhull, see qh_opt.htm + char flags[] = "qhull d QJ"; + // output from qh_produce_output(), use NULL to skip qh_produce_output() + FILE *outfile = NULL; + // error messages from qhull code + FILE *errfile = stderr; + // 0 if no error from qhull + int exitcode; + + // Array of coordinates for each point + coordT *points = reinterpret_cast (calloc (cloud_transformed.points.size () * dim_, sizeof(coordT))); + + for (size_t i = 0; i < cloud_transformed.points.size (); ++i) + { + points[i * dim_ + 0] = static_cast (cloud_transformed.points[i].x); + points[i * dim_ + 1] = static_cast (cloud_transformed.points[i].y); + + if (dim_ > 2) + points[i * dim_ + 2] = static_cast (cloud_transformed.points[i].z); + } + + // Compute concave hull + exitcode = qh_new_qhull (dim_, static_cast (cloud_transformed.points.size ()), points, ismalloc, flags, outfile, errfile); + + if (exitcode != 0) + { + PCL_ERROR ("[pcl::%s::performReconstrution] ERROR: qhull was unable to compute a concave hull for the given point cloud (%lu)!\n", getClassName ().c_str (), cloud_transformed.points.size ()); + + //check if it fails because of NaN values... + if (!cloud_transformed.is_dense) + { + bool NaNvalues = false; + for (size_t i = 0; i < cloud_transformed.size (); ++i) + { + if (!pcl_isfinite (cloud_transformed.points[i].x) || + !pcl_isfinite (cloud_transformed.points[i].y) || + !pcl_isfinite (cloud_transformed.points[i].z)) + { + NaNvalues = true; + break; + } + } + + if (NaNvalues) + PCL_ERROR ("[pcl::%s::performReconstruction] ERROR: point cloud contains NaN values, consider running pcl::PassThrough filter first to remove NaNs!\n", getClassName ().c_str ()); + } + + alpha_shape.points.resize (0); + alpha_shape.width = alpha_shape.height = 0; + polygons.resize (0); + + qh_freeqhull (!qh_ALL); + int curlong, totlong; + qh_memfreeshort (&curlong, &totlong); + + return; + } + + qh_setvoronoi_all (); + + int num_vertices = qh num_vertices; + alpha_shape.points.resize (num_vertices); + + vertexT *vertex; + // Max vertex id + int max_vertex_id = 0; + FORALLvertices + { + if (vertex->id + 1 > max_vertex_id) + max_vertex_id = vertex->id + 1; + } + + facetT *facet; // set by FORALLfacets + + ++max_vertex_id; + std::vector qhid_to_pcidx (max_vertex_id); + + int num_facets = qh num_facets; + int dd = 0; + + if (dim_ == 3) + { + setT *triangles_set = qh_settemp (4 * num_facets); + if (voronoi_centers_) + voronoi_centers_->points.resize (num_facets); + + int non_upper = 0; + FORALLfacets + { + // Facets are tetrahedrons (3d) + if (!facet->upperdelaunay) + { + vertexT *anyVertex = static_cast (facet->vertices->e[0].p); + double *center = facet->center; + double r = qh_pointdist (anyVertex->point,center,dim_); + facetT *neighb; + + if (voronoi_centers_) + { + voronoi_centers_->points[non_upper].x = static_cast (facet->center[0]); + voronoi_centers_->points[non_upper].y = static_cast (facet->center[1]); + voronoi_centers_->points[non_upper].z = static_cast (facet->center[2]); + } + + non_upper++; + + if (r <= alpha_) + { + // all triangles in tetrahedron are good, add them all to the alpha shape (triangles_set) + qh_makeridges (facet); + facet->good = true; + facet->visitid = qh visit_id; + ridgeT *ridge, **ridgep; + FOREACHridge_ (facet->ridges) + { + neighb = otherfacet_ (ridge, facet); + if ((neighb->visitid != qh visit_id)) + qh_setappend (&triangles_set, ridge); + } + } + else + { + // consider individual triangles from the tetrahedron... + facet->good = false; + facet->visitid = qh visit_id; + qh_makeridges (facet); + ridgeT *ridge, **ridgep; + FOREACHridge_ (facet->ridges) + { + facetT *neighb; + neighb = otherfacet_ (ridge, facet); + if ((neighb->visitid != qh visit_id)) + { + // check if individual triangle is good and add it to triangles_set + + PointInT a, b, c; + a.x = static_cast ((static_cast(ridge->vertices->e[0].p))->point[0]); + a.y = static_cast ((static_cast(ridge->vertices->e[0].p))->point[1]); + a.z = static_cast ((static_cast(ridge->vertices->e[0].p))->point[2]); + b.x = static_cast ((static_cast(ridge->vertices->e[1].p))->point[0]); + b.y = static_cast ((static_cast(ridge->vertices->e[1].p))->point[1]); + b.z = static_cast ((static_cast(ridge->vertices->e[1].p))->point[2]); + c.x = static_cast ((static_cast(ridge->vertices->e[2].p))->point[0]); + c.y = static_cast ((static_cast(ridge->vertices->e[2].p))->point[1]); + c.z = static_cast ((static_cast(ridge->vertices->e[2].p))->point[2]); + + double r = pcl::getCircumcircleRadius (a, b, c); + if (r <= alpha_) + qh_setappend (&triangles_set, ridge); + } + } + } + } + } + + if (voronoi_centers_) + voronoi_centers_->points.resize (non_upper); + + // filter, add points to alpha_shape and create polygon structure + + int num_good_triangles = 0; + ridgeT *ridge, **ridgep; + FOREACHridge_ (triangles_set) + { + if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good) + num_good_triangles++; + } + + polygons.resize (num_good_triangles); + + int vertices = 0; + std::vector added_vertices (max_vertex_id, false); + + int triangles = 0; + FOREACHridge_ (triangles_set) + { + if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good) + { + polygons[triangles].vertices.resize (3); + int vertex_n, vertex_i; + FOREACHvertex_i_ ((*ridge).vertices) //3 vertices per ridge! + { + if (!added_vertices[vertex->id]) + { + alpha_shape.points[vertices].x = static_cast (vertex->point[0]); + alpha_shape.points[vertices].y = static_cast (vertex->point[1]); + alpha_shape.points[vertices].z = static_cast (vertex->point[2]); + + qhid_to_pcidx[vertex->id] = vertices; //map the vertex id of qhull to the point cloud index + added_vertices[vertex->id] = true; + vertices++; + } + + polygons[triangles].vertices[vertex_i] = qhid_to_pcidx[vertex->id]; + + } + + triangles++; + } + } + + alpha_shape.points.resize (vertices); + alpha_shape.width = static_cast (alpha_shape.points.size ()); + alpha_shape.height = 1; + } + else + { + // Compute the alpha complex for the set of points + // Filters the delaunay triangles + setT *edges_set = qh_settemp (3 * num_facets); + if (voronoi_centers_) + voronoi_centers_->points.resize (num_facets); + + FORALLfacets + { + // Facets are the delaunay triangles (2d) + if (!facet->upperdelaunay) + { + // Check if the distance from any vertex to the facet->center + // (center of the voronoi cell) is smaller than alpha + vertexT *anyVertex = static_cast(facet->vertices->e[0].p); + double r = (sqrt ((anyVertex->point[0] - facet->center[0]) * + (anyVertex->point[0] - facet->center[0]) + + (anyVertex->point[1] - facet->center[1]) * + (anyVertex->point[1] - facet->center[1]))); + if (r <= alpha_) + { + pcl::Vertices facet_vertices; //TODO: is not used!! + qh_makeridges (facet); + facet->good = true; + + ridgeT *ridge, **ridgep; + FOREACHridge_ (facet->ridges) + qh_setappend (&edges_set, ridge); + + if (voronoi_centers_) + { + voronoi_centers_->points[dd].x = static_cast (facet->center[0]); + voronoi_centers_->points[dd].y = static_cast (facet->center[1]); + voronoi_centers_->points[dd].z = 0.0f; + } + + ++dd; + } + else + facet->good = false; + } + } + + int vertices = 0; + std::vector added_vertices (max_vertex_id, false); + std::map > edges; + + ridgeT *ridge, **ridgep; + FOREACHridge_ (edges_set) + { + if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good) + { + int vertex_n, vertex_i; + int vertices_in_ridge=0; + std::vector pcd_indices; + pcd_indices.resize (2); + + FOREACHvertex_i_ ((*ridge).vertices) //in 2-dim, 2 vertices per ridge! + { + if (!added_vertices[vertex->id]) + { + alpha_shape.points[vertices].x = static_cast (vertex->point[0]); + alpha_shape.points[vertices].y = static_cast (vertex->point[1]); + + if (dim_ > 2) + alpha_shape.points[vertices].z = static_cast (vertex->point[2]); + else + alpha_shape.points[vertices].z = 0; + + qhid_to_pcidx[vertex->id] = vertices; //map the vertex id of qhull to the point cloud index + added_vertices[vertex->id] = true; + pcd_indices[vertices_in_ridge] = vertices; + vertices++; + } + else + { + pcd_indices[vertices_in_ridge] = qhid_to_pcidx[vertex->id]; + } + + vertices_in_ridge++; + } + + // make edges bidirectional and pointing to alpha_shape pointcloud... + edges[pcd_indices[0]].push_back (pcd_indices[1]); + edges[pcd_indices[1]].push_back (pcd_indices[0]); + } + } + + alpha_shape.points.resize (vertices); + + std::vector > connected; + PointCloud alpha_shape_sorted; + alpha_shape_sorted.points.resize (vertices); + + // iterate over edges until they are empty! + std::map >::iterator curr = edges.begin (); + int next = - 1; + std::vector used (vertices, false); // used to decide which direction should we take! + std::vector pcd_idx_start_polygons; + pcd_idx_start_polygons.push_back (0); + + // start following edges and removing elements + int sorted_idx = 0; + while (!edges.empty ()) + { + alpha_shape_sorted.points[sorted_idx] = alpha_shape.points[(*curr).first]; + // check where we can go from (*curr).first + for (size_t i = 0; i < (*curr).second.size (); i++) + { + if (!used[((*curr).second)[i]]) + { + // we can go there + next = ((*curr).second)[i]; + break; + } + } + + used[(*curr).first] = true; + edges.erase (curr); // remove edges starting from curr + + sorted_idx++; + + if (edges.empty ()) + break; + + // reassign current + curr = edges.find (next); // if next is not found, then we have unconnected polygons. + if (curr == edges.end ()) + { + // set current to any of the remaining in edge! + curr = edges.begin (); + pcd_idx_start_polygons.push_back (sorted_idx); + } + } + + pcd_idx_start_polygons.push_back (sorted_idx); + + alpha_shape.points = alpha_shape_sorted.points; + + polygons.reserve (pcd_idx_start_polygons.size () - 1); + + for (size_t poly_id = 0; poly_id < pcd_idx_start_polygons.size () - 1; poly_id++) + { + // Check if we actually have a polygon, and not some degenerated output from QHull + if (pcd_idx_start_polygons[poly_id + 1] - pcd_idx_start_polygons[poly_id] >= 3) + { + pcl::Vertices vertices; + vertices.vertices.resize (pcd_idx_start_polygons[poly_id + 1] - pcd_idx_start_polygons[poly_id]); + // populate points in the corresponding polygon + for (int j = pcd_idx_start_polygons[poly_id]; j < pcd_idx_start_polygons[poly_id + 1]; ++j) + vertices.vertices[j - pcd_idx_start_polygons[poly_id]] = static_cast (j); + + polygons.push_back (vertices); + } + } + + if (voronoi_centers_) + voronoi_centers_->points.resize (dd); + } + + qh_freeqhull (!qh_ALL); + int curlong, totlong; + qh_memfreeshort (&curlong, &totlong); + + Eigen::Affine3d transInverse = transform1.inverse (); + pcl::transformPointCloud (alpha_shape, alpha_shape, transInverse); + xyz_centroid[0] = - xyz_centroid[0]; + xyz_centroid[1] = - xyz_centroid[1]; + xyz_centroid[2] = - xyz_centroid[2]; + pcl::demeanPointCloud (alpha_shape, xyz_centroid, alpha_shape); + + // also transform voronoi_centers_... + if (voronoi_centers_) + { + pcl::transformPointCloud (*voronoi_centers_, *voronoi_centers_, transInverse); + pcl::demeanPointCloud (*voronoi_centers_, xyz_centroid, *voronoi_centers_); + } + + if (keep_information_) + { + // build a tree with the original points + pcl::KdTreeFLANN tree (true); + tree.setInputCloud (input_, indices_); + + std::vector neighbor; + std::vector distances; + neighbor.resize (1); + distances.resize (1); + + // for each point in the concave hull, search for the nearest neighbor in the original point cloud + + std::vector indices; + indices.resize (alpha_shape.points.size ()); + + for (size_t i = 0; i < alpha_shape.points.size (); i++) + { + tree.nearestKSearch (alpha_shape.points[i], 1, neighbor, distances); + indices[i] = neighbor[0]; + } + + // replace point with the closest neighbor in the original point cloud + pcl::copyPointCloud (*input_, indices, alpha_shape); + } +} +#ifdef __GNUC__ +#pragma GCC diagnostic warning "-Wold-style-cast" +#endif + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ConcaveHull::performReconstruction (PolygonMesh &output) +{ + // Perform reconstruction + pcl::PointCloud hull_points; + performReconstruction (hull_points, output.polygons); + + // Convert the PointCloud into a PCLPointCloud2 + pcl::toPCLPointCloud2 (hull_points, output.cloud); +} + +////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::ConcaveHull::performReconstruction (std::vector &polygons) +{ + pcl::PointCloud hull_points; + performReconstruction (hull_points, polygons); +} + + +#define PCL_INSTANTIATE_ConcaveHull(T) template class PCL_EXPORTS pcl::ConcaveHull; + +#endif // PCL_SURFACE_IMPL_CONCAVE_HULL_H_ +#endif diff --git a/pcl-1.7/pcl/surface/impl/convex_hull.hpp b/pcl-1.7/pcl/surface/impl/convex_hull.hpp new file mode 100644 index 0000000..c1552b5 --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/convex_hull.hpp @@ -0,0 +1,488 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#include +#ifdef HAVE_QHULL + +#ifndef PCL_SURFACE_IMPL_CONVEX_HULL_H_ +#define PCL_SURFACE_IMPL_CONVEX_HULL_H_ + +#include +#include +#include +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConvexHull::calculateInputDimension () +{ + PCL_DEBUG ("[pcl::%s::calculateInputDimension] WARNING: Input dimension not specified. Automatically determining input dimension.\n", getClassName ().c_str ()); + EIGEN_ALIGN16 Eigen::Matrix3d covariance_matrix; + Eigen::Vector4d xyz_centroid; + computeMeanAndCovarianceMatrix (*input_, *indices_, covariance_matrix, xyz_centroid); + + EIGEN_ALIGN16 Eigen::Vector3d eigen_values; + pcl::eigen33 (covariance_matrix, eigen_values); + + if (eigen_values[0] / eigen_values[2] < 1.0e-3) + dimension_ = 2; + else + dimension_ = 3; +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConvexHull::performReconstruction2D (PointCloud &hull, std::vector &polygons, + bool) +{ + int dimension = 2; + bool xy_proj_safe = true; + bool yz_proj_safe = true; + bool xz_proj_safe = true; + + // Check the input's normal to see which projection to use + PointInT p0 = input_->points[(*indices_)[0]]; + PointInT p1 = input_->points[(*indices_)[indices_->size () - 1]]; + PointInT p2 = input_->points[(*indices_)[indices_->size () / 2]]; + Eigen::Array4f dy1dy2 = (p1.getArray4fMap () - p0.getArray4fMap ()) / (p2.getArray4fMap () - p0.getArray4fMap ()); + while (!( (dy1dy2[0] != dy1dy2[1]) || (dy1dy2[2] != dy1dy2[1]) ) ) + { + p0 = input_->points[(*indices_)[rand () % indices_->size ()]]; + p1 = input_->points[(*indices_)[rand () % indices_->size ()]]; + p2 = input_->points[(*indices_)[rand () % indices_->size ()]]; + dy1dy2 = (p1.getArray4fMap () - p0.getArray4fMap ()) / (p2.getArray4fMap () - p0.getArray4fMap ()); + } + + pcl::PointCloud normal_calc_cloud; + normal_calc_cloud.points.resize (3); + normal_calc_cloud.points[0] = p0; + normal_calc_cloud.points[1] = p1; + normal_calc_cloud.points[2] = p2; + + Eigen::Vector4d normal_calc_centroid; + Eigen::Matrix3d normal_calc_covariance; + pcl::computeMeanAndCovarianceMatrix (normal_calc_cloud, normal_calc_covariance, normal_calc_centroid); + // Need to set -1 here. See eigen33 for explanations. + Eigen::Vector3d::Scalar eigen_value; + Eigen::Vector3d plane_params; + pcl::eigen33 (normal_calc_covariance, eigen_value, plane_params); + float theta_x = fabsf (static_cast (plane_params.dot (x_axis_))); + float theta_y = fabsf (static_cast (plane_params.dot (y_axis_))); + float theta_z = fabsf (static_cast (plane_params.dot (z_axis_))); + + // Check for degenerate cases of each projection + // We must avoid projections in which the plane projects as a line + if (theta_z > projection_angle_thresh_) + { + xz_proj_safe = false; + yz_proj_safe = false; + } + if (theta_x > projection_angle_thresh_) + { + xz_proj_safe = false; + xy_proj_safe = false; + } + if (theta_y > projection_angle_thresh_) + { + xy_proj_safe = false; + yz_proj_safe = false; + } + + // True if qhull should free points in qh_freeqhull() or reallocation + boolT ismalloc = True; + // output from qh_produce_output(), use NULL to skip qh_produce_output() + FILE *outfile = NULL; + +#ifndef HAVE_QHULL_2011 + if (compute_area_) + outfile = stderr; +#endif + + // option flags for qhull, see qh_opt.htm + const char* flags = qhull_flags.c_str (); + // error messages from qhull code + FILE *errfile = stderr; + + // Array of coordinates for each point + coordT *points = reinterpret_cast (calloc (indices_->size () * dimension, sizeof (coordT))); + + // Build input data, using appropriate projection + int j = 0; + if (xy_proj_safe) + { + for (size_t i = 0; i < indices_->size (); ++i, j+=dimension) + { + points[j + 0] = static_cast (input_->points[(*indices_)[i]].x); + points[j + 1] = static_cast (input_->points[(*indices_)[i]].y); + } + } + else if (yz_proj_safe) + { + for (size_t i = 0; i < indices_->size (); ++i, j+=dimension) + { + points[j + 0] = static_cast (input_->points[(*indices_)[i]].y); + points[j + 1] = static_cast (input_->points[(*indices_)[i]].z); + } + } + else if (xz_proj_safe) + { + for (size_t i = 0; i < indices_->size (); ++i, j+=dimension) + { + points[j + 0] = static_cast (input_->points[(*indices_)[i]].x); + points[j + 1] = static_cast (input_->points[(*indices_)[i]].z); + } + } + else + { + // This should only happen if we had invalid input + PCL_ERROR ("[pcl::%s::performReconstruction2D] Invalid input!\n", getClassName ().c_str ()); + } + + // Compute convex hull + int exitcode = qh_new_qhull (dimension, static_cast (indices_->size ()), points, ismalloc, const_cast (flags), outfile, errfile); +#ifdef HAVE_QHULL_2011 + if (compute_area_) + { + qh_prepare_output(); + } +#endif + + // 0 if no error from qhull or it doesn't find any vertices + if (exitcode != 0 || qh num_vertices == 0) + { + PCL_ERROR ("[pcl::%s::performReconstrution2D] ERROR: qhull was unable to compute a convex hull for the given point cloud (%lu)!\n", getClassName ().c_str (), indices_->size ()); + + hull.points.resize (0); + hull.width = hull.height = 0; + polygons.resize (0); + + qh_freeqhull (!qh_ALL); + int curlong, totlong; + qh_memfreeshort (&curlong, &totlong); + + return; + } + + // Qhull returns the area in volume for 2D + if (compute_area_) + { + total_area_ = qh totvol; + total_volume_ = 0.0; + } + + int num_vertices = qh num_vertices; + hull.points.resize (num_vertices); + memset (&hull.points[0], static_cast (hull.points.size ()), sizeof (PointInT)); + + vertexT * vertex; + int i = 0; + + std::vector, Eigen::aligned_allocator > > idx_points (num_vertices); + idx_points.resize (hull.points.size ()); + memset (&idx_points[0], static_cast (hull.points.size ()), sizeof (std::pair)); + + FORALLvertices + { + hull.points[i] = input_->points[(*indices_)[qh_pointid (vertex->point)]]; + idx_points[i].first = qh_pointid (vertex->point); + ++i; + } + + // Sort + Eigen::Vector4f centroid; + pcl::compute3DCentroid (hull, centroid); + if (xy_proj_safe) + { + for (size_t j = 0; j < hull.points.size (); j++) + { + idx_points[j].second[0] = hull.points[j].x - centroid[0]; + idx_points[j].second[1] = hull.points[j].y - centroid[1]; + } + } + else if (yz_proj_safe) + { + for (size_t j = 0; j < hull.points.size (); j++) + { + idx_points[j].second[0] = hull.points[j].y - centroid[1]; + idx_points[j].second[1] = hull.points[j].z - centroid[2]; + } + } + else if (xz_proj_safe) + { + for (size_t j = 0; j < hull.points.size (); j++) + { + idx_points[j].second[0] = hull.points[j].x - centroid[0]; + idx_points[j].second[1] = hull.points[j].z - centroid[2]; + } + } + std::sort (idx_points.begin (), idx_points.end (), comparePoints2D); + + polygons.resize (1); + polygons[0].vertices.resize (hull.points.size ()); + + for (int j = 0; j < static_cast (hull.points.size ()); j++) + { + hull.points[j] = input_->points[(*indices_)[idx_points[j].first]]; + polygons[0].vertices[j] = static_cast (j); + } + + qh_freeqhull (!qh_ALL); + int curlong, totlong; + qh_memfreeshort (&curlong, &totlong); + + hull.width = static_cast (hull.points.size ()); + hull.height = 1; + hull.is_dense = false; + return; +} + +#ifdef __GNUC__ +#pragma GCC diagnostic ignored "-Wold-style-cast" +#endif +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConvexHull::performReconstruction3D ( + PointCloud &hull, std::vector &polygons, bool fill_polygon_data) +{ + int dimension = 3; + + // True if qhull should free points in qh_freeqhull() or reallocation + boolT ismalloc = True; + // output from qh_produce_output(), use NULL to skip qh_produce_output() + FILE *outfile = NULL; + +#ifndef HAVE_QHULL_2011 + if (compute_area_) + outfile = stderr; +#endif + + // option flags for qhull, see qh_opt.htm + const char *flags = qhull_flags.c_str (); + // error messages from qhull code + FILE *errfile = stderr; + + // Array of coordinates for each point + coordT *points = reinterpret_cast (calloc (indices_->size () * dimension, sizeof (coordT))); + + int j = 0; + for (size_t i = 0; i < indices_->size (); ++i, j+=dimension) + { + points[j + 0] = static_cast (input_->points[(*indices_)[i]].x); + points[j + 1] = static_cast (input_->points[(*indices_)[i]].y); + points[j + 2] = static_cast (input_->points[(*indices_)[i]].z); + } + + // Compute convex hull + int exitcode = qh_new_qhull (dimension, static_cast (indices_->size ()), points, ismalloc, const_cast (flags), outfile, errfile); +#ifdef HAVE_QHULL_2011 + if (compute_area_) + { + qh_prepare_output(); + } +#endif + + // 0 if no error from qhull + if (exitcode != 0) + { + PCL_ERROR ("[pcl::%s::performReconstrution3D] ERROR: qhull was unable to compute a convex hull for the given point cloud (%lu)!\n", getClassName ().c_str (), input_->points.size ()); + + hull.points.resize (0); + hull.width = hull.height = 0; + polygons.resize (0); + + qh_freeqhull (!qh_ALL); + int curlong, totlong; + qh_memfreeshort (&curlong, &totlong); + + return; + } + + qh_triangulate (); + + int num_facets = qh num_facets; + + int num_vertices = qh num_vertices; + hull.points.resize (num_vertices); + + vertexT * vertex; + int i = 0; + // Max vertex id + unsigned int max_vertex_id = 0; + FORALLvertices + { + if (vertex->id + 1 > max_vertex_id) + max_vertex_id = vertex->id + 1; + } + + ++max_vertex_id; + std::vector qhid_to_pcidx (max_vertex_id); + + FORALLvertices + { + // Add vertices to hull point_cloud + hull.points[i] = input_->points[(*indices_)[qh_pointid (vertex->point)]]; + + qhid_to_pcidx[vertex->id] = i; // map the vertex id of qhull to the point cloud index + ++i; + } + + if (compute_area_) + { + total_area_ = qh totarea; + total_volume_ = qh totvol; + } + + if (fill_polygon_data) + { + polygons.resize (num_facets); + int dd = 0; + + facetT * facet; + FORALLfacets + { + polygons[dd].vertices.resize (3); + + // Needed by FOREACHvertex_i_ + int vertex_n, vertex_i; + FOREACHvertex_i_ ((*facet).vertices) + //facet_vertices.vertices.push_back (qhid_to_pcidx[vertex->id]); + polygons[dd].vertices[vertex_i] = qhid_to_pcidx[vertex->id]; + ++dd; + } + } + // Deallocates memory (also the points) + qh_freeqhull (!qh_ALL); + int curlong, totlong; + qh_memfreeshort (&curlong, &totlong); + + hull.width = static_cast (hull.points.size ()); + hull.height = 1; + hull.is_dense = false; +} +#ifdef __GNUC__ +#pragma GCC diagnostic warning "-Wold-style-cast" +#endif + +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConvexHull::performReconstruction (PointCloud &hull, std::vector &polygons, + bool fill_polygon_data) +{ + if (dimension_ == 0) + calculateInputDimension (); + if (dimension_ == 2) + performReconstruction2D (hull, polygons, fill_polygon_data); + else if (dimension_ == 3) + performReconstruction3D (hull, polygons, fill_polygon_data); + else + PCL_ERROR ("[pcl::%s::performReconstruction] Error: invalid input dimension requested: %d\n",getClassName ().c_str (),dimension_); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConvexHull::reconstruct (PointCloud &points) +{ + points.header = input_->header; + if (!initCompute () || input_->points.empty () || indices_->empty ()) + { + points.points.clear (); + return; + } + + // Perform the actual surface reconstruction + std::vector polygons; + performReconstruction (points, polygons, false); + + points.width = static_cast (points.points.size ()); + points.height = 1; + points.is_dense = true; + + deinitCompute (); +} + + +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConvexHull::performReconstruction (PolygonMesh &output) +{ + // Perform reconstruction + pcl::PointCloud hull_points; + performReconstruction (hull_points, output.polygons, true); + + // Convert the PointCloud into a PCLPointCloud2 + pcl::toPCLPointCloud2 (hull_points, output.cloud); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConvexHull::performReconstruction (std::vector &polygons) +{ + pcl::PointCloud hull_points; + performReconstruction (hull_points, polygons, true); +} + +////////////////////////////////////////////////////////////////////////// +template void +pcl::ConvexHull::reconstruct (PointCloud &points, std::vector &polygons) +{ + points.header = input_->header; + if (!initCompute () || input_->points.empty () || indices_->empty ()) + { + points.points.clear (); + return; + } + + // Perform the actual surface reconstruction + performReconstruction (points, polygons, true); + + points.width = static_cast (points.points.size ()); + points.height = 1; + points.is_dense = true; + + deinitCompute (); +} + +#define PCL_INSTANTIATE_ConvexHull(T) template class PCL_EXPORTS pcl::ConvexHull; + +#endif // PCL_SURFACE_IMPL_CONVEX_HULL_H_ +#endif diff --git a/pcl-1.7/pcl/surface/impl/gp3.hpp b/pcl-1.7/pcl/surface/impl/gp3.hpp new file mode 100644 index 0000000..9e915b6 --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/gp3.hpp @@ -0,0 +1,1681 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SURFACE_IMPL_GP3_H_ +#define PCL_SURFACE_IMPL_GP3_H_ + +#include +#include + +///////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GreedyProjectionTriangulation::performReconstruction (pcl::PolygonMesh &output) +{ + output.polygons.clear (); + output.polygons.reserve (2 * indices_->size ()); /// NOTE: usually the number of triangles is around twice the number of vertices + if (!reconstructPolygons (output.polygons)) + { + PCL_ERROR ("[pcl::%s::performReconstruction] Reconstruction failed. Check parameters: search radius (%f) or mu (%f) before continuing.\n", getClassName ().c_str (), search_radius_, mu_); + output.cloud.width = output.cloud.height = 0; + output.cloud.data.clear (); + return; + } +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GreedyProjectionTriangulation::performReconstruction (std::vector &polygons) +{ + polygons.clear (); + polygons.reserve (2 * indices_->size ()); /// NOTE: usually the number of triangles is around twice the number of vertices + if (!reconstructPolygons (polygons)) + { + PCL_ERROR ("[pcl::%s::performReconstruction] Reconstruction failed. Check parameters: search radius (%f) or mu (%f) before continuing.\n", getClassName ().c_str (), search_radius_, mu_); + return; + } +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::GreedyProjectionTriangulation::reconstructPolygons (std::vector &polygons) +{ + if (search_radius_ <= 0 || mu_ <= 0) + { + polygons.clear (); + return (false); + } + const double sqr_mu = mu_*mu_; + const double sqr_max_edge = search_radius_*search_radius_; + if (nnn_ > static_cast (indices_->size ())) + nnn_ = static_cast (indices_->size ()); + + // Variables to hold the results of nearest neighbor searches + std::vector nnIdx (nnn_); + std::vector sqrDists (nnn_); + + // current number of connected components + int part_index = 0; + + // 2D coordinates of points + const Eigen::Vector2f uvn_nn_qp_zero = Eigen::Vector2f::Zero(); + Eigen::Vector2f uvn_current; + Eigen::Vector2f uvn_prev; + Eigen::Vector2f uvn_next; + + // initializing fields + already_connected_ = false; // see declaration for comments :P + + // initializing states and fringe neighbors + part_.clear (); + state_.clear (); + source_.clear (); + ffn_.clear (); + sfn_.clear (); + part_.resize(indices_->size (), -1); // indices of point's part + state_.resize(indices_->size (), FREE); + source_.resize(indices_->size (), NONE); + ffn_.resize(indices_->size (), NONE); + sfn_.resize(indices_->size (), NONE); + fringe_queue_.clear (); + int fqIdx = 0; // current fringe's index in the queue to be processed + + // Avoiding NaN coordinates if needed + if (!input_->is_dense) + { + // Skip invalid points from the indices list + for (std::vector::const_iterator it = indices_->begin (); it != indices_->end (); ++it) + if (!pcl_isfinite (input_->points[*it].x) || + !pcl_isfinite (input_->points[*it].y) || + !pcl_isfinite (input_->points[*it].z)) + state_[*it] = NONE; + } + + // Saving coordinates and point to index mapping + coords_.clear (); + coords_.reserve (indices_->size ()); + std::vector point2index (input_->points.size (), -1); + for (int cp = 0; cp < static_cast (indices_->size ()); ++cp) + { + coords_.push_back(input_->points[(*indices_)[cp]].getVector3fMap()); + point2index[(*indices_)[cp]] = cp; + } + + // Initializing + int is_free=0, nr_parts=0, increase_nnn4fn=0, increase_nnn4s=0, increase_dist=0, nr_touched = 0; + bool is_fringe; + angles_.resize(nnn_); + std::vector uvn_nn (nnn_); + Eigen::Vector2f uvn_s; + + // iterating through fringe points and finishing them until everything is done + while (is_free != NONE) + { + R_ = is_free; + if (state_[R_] == FREE) + { + state_[R_] = NONE; + part_[R_] = part_index++; + + // creating starting triangle + //searchForNeighbors ((*indices_)[R_], nnIdx, sqrDists); + //tree_->nearestKSearch (input_->points[(*indices_)[R_]], nnn_, nnIdx, sqrDists); + tree_->nearestKSearch (indices_->at (R_), nnn_, nnIdx, sqrDists); + double sqr_dist_threshold = (std::min)(sqr_max_edge, sqr_mu * sqrDists[1]); + + // Search tree returns indices into the original cloud, but we are working with indices. TODO: make that optional! + for (int i = 1; i < nnn_; i++) + { + //if (point2index[nnIdx[i]] == -1) + // std::cerr << R_ << " [" << indices_->at (R_) << "] " << i << ": " << nnIdx[i] << " / " << point2index[nnIdx[i]] << std::endl; + nnIdx[i] = point2index[nnIdx[i]]; + } + + // Get the normal estimate at the current point + const Eigen::Vector3f nc = input_->points[(*indices_)[R_]].getNormalVector3fMap (); + + // Get a coordinate system that lies on a plane defined by its normal + v_ = nc.unitOrthogonal (); + u_ = nc.cross (v_); + + // Projecting point onto the surface + float dist = nc.dot (coords_[R_]); + proj_qp_ = coords_[R_] - dist * nc; + + // Converting coords, calculating angles and saving the projected near boundary edges + int nr_edge = 0; + std::vector doubleEdges; + for (int i = 1; i < nnn_; i++) // nearest neighbor with index 0 is the query point R_ itself + { + // Transforming coordinates + tmp_ = coords_[nnIdx[i]] - proj_qp_; + uvn_nn[i][0] = tmp_.dot(u_); + uvn_nn[i][1] = tmp_.dot(v_); + // Computing the angle between each neighboring point and the query point itself + angles_[i].angle = atan2(uvn_nn[i][1], uvn_nn[i][0]); + // initializing angle descriptors + angles_[i].index = nnIdx[i]; + if ( + (state_[nnIdx[i]] == COMPLETED) || (state_[nnIdx[i]] == BOUNDARY) + || (state_[nnIdx[i]] == NONE) || (nnIdx[i] == -1) /// NOTE: discarding NaN points and those that are not in indices_ + || (sqrDists[i] > sqr_dist_threshold) + ) + angles_[i].visible = false; + else + angles_[i].visible = true; + // Saving the edges between nearby boundary points + if ((state_[nnIdx[i]] == FRINGE) || (state_[nnIdx[i]] == BOUNDARY)) + { + doubleEdge e; + e.index = i; + nr_edge++; + tmp_ = coords_[ffn_[nnIdx[i]]] - proj_qp_; + e.first[0] = tmp_.dot(u_); + e.first[1] = tmp_.dot(v_); + tmp_ = coords_[sfn_[nnIdx[i]]] - proj_qp_; + e.second[0] = tmp_.dot(u_); + e.second[1] = tmp_.dot(v_); + doubleEdges.push_back(e); + } + } + angles_[0].visible = false; + + // Verify the visibility of each potential new vertex + for (int i = 1; i < nnn_; i++) // nearest neighbor with index 0 is the query point R_ itself + if ((angles_[i].visible) && (ffn_[R_] != nnIdx[i]) && (sfn_[R_] != nnIdx[i])) + { + bool visibility = true; + for (int j = 0; j < nr_edge; j++) + { + if (ffn_[nnIdx[doubleEdges[j].index]] != nnIdx[i]) + visibility = isVisible(uvn_nn[i], uvn_nn[doubleEdges[j].index], doubleEdges[j].first, Eigen::Vector2f::Zero()); + if (!visibility) + break; + if (sfn_[nnIdx[doubleEdges[j].index]] != nnIdx[i]) + visibility = isVisible(uvn_nn[i], uvn_nn[doubleEdges[j].index], doubleEdges[j].second, Eigen::Vector2f::Zero()); + if (!visibility == false) + break; + } + angles_[i].visible = visibility; + } + + // Selecting first two visible free neighbors + bool not_found = true; + int left = 1; + do + { + while ((left < nnn_) && ((!angles_[left].visible) || (state_[nnIdx[left]] > FREE))) left++; + if (left >= nnn_) + break; + else + { + int right = left+1; + do + { + while ((right < nnn_) && ((!angles_[right].visible) || (state_[nnIdx[right]] > FREE))) right++; + if (right >= nnn_) + break; + else if ((coords_[nnIdx[left]] - coords_[nnIdx[right]]).squaredNorm () > sqr_max_edge) + right++; + else + { + addFringePoint (nnIdx[right], R_); + addFringePoint (nnIdx[left], nnIdx[right]); + addFringePoint (R_, nnIdx[left]); + state_[R_] = state_[nnIdx[left]] = state_[nnIdx[right]] = FRINGE; + ffn_[R_] = nnIdx[left]; + sfn_[R_] = nnIdx[right]; + ffn_[nnIdx[left]] = nnIdx[right]; + sfn_[nnIdx[left]] = R_; + ffn_[nnIdx[right]] = R_; + sfn_[nnIdx[right]] = nnIdx[left]; + addTriangle (R_, nnIdx[left], nnIdx[right], polygons); + nr_parts++; + not_found = false; + break; + } + } + while (true); + left++; + } + } + while (not_found); + } + + is_free = NONE; + for (unsigned temp = 0; temp < indices_->size (); temp++) + { + if (state_[temp] == FREE) + { + is_free = temp; + break; + } + } + + is_fringe = true; + while (is_fringe) + { + is_fringe = false; + + int fqSize = static_cast (fringe_queue_.size ()); + while ((fqIdx < fqSize) && (state_[fringe_queue_[fqIdx]] != FRINGE)) + fqIdx++; + + // an unfinished fringe point is found + if (fqIdx >= fqSize) + { + continue; + } + + R_ = fringe_queue_[fqIdx]; + is_fringe = true; + + if (ffn_[R_] == sfn_[R_]) + { + state_[R_] = COMPLETED; + continue; + } + //searchForNeighbors ((*indices_)[R_], nnIdx, sqrDists); + //tree_->nearestKSearch (input_->points[(*indices_)[R_]], nnn_, nnIdx, sqrDists); + tree_->nearestKSearch (indices_->at (R_), nnn_, nnIdx, sqrDists); + + // Search tree returns indices into the original cloud, but we are working with indices TODO: make that optional! + for (int i = 1; i < nnn_; i++) + { + //if (point2index[nnIdx[i]] == -1) + // std::cerr << R_ << " [" << indices_->at (R_) << "] " << i << ": " << nnIdx[i] << " / " << point2index[nnIdx[i]] << std::endl; + nnIdx[i] = point2index[nnIdx[i]]; + } + + // Locating FFN and SFN to adapt distance threshold + double sqr_source_dist = (coords_[R_] - coords_[source_[R_]]).squaredNorm (); + double sqr_ffn_dist = (coords_[R_] - coords_[ffn_[R_]]).squaredNorm (); + double sqr_sfn_dist = (coords_[R_] - coords_[sfn_[R_]]).squaredNorm (); + double max_sqr_fn_dist = (std::max)(sqr_ffn_dist, sqr_sfn_dist); + double sqr_dist_threshold = (std::min)(sqr_max_edge, sqr_mu * sqrDists[1]); //sqr_mu * sqr_avg_conn_dist); + if (max_sqr_fn_dist > sqrDists[nnn_-1]) + { + if (0 == increase_nnn4fn) + PCL_WARN("Not enough neighbors are considered: ffn or sfn out of range! Consider increasing nnn_... Setting R=%d to be BOUNDARY!\n", R_); + increase_nnn4fn++; + state_[R_] = BOUNDARY; + continue; + } + double max_sqr_fns_dist = (std::max)(sqr_source_dist, max_sqr_fn_dist); + if (max_sqr_fns_dist > sqrDists[nnn_-1]) + { + if (0 == increase_nnn4s) + PCL_WARN("Not enough neighbors are considered: source of R=%d is out of range! Consider increasing nnn_...\n", R_); + increase_nnn4s++; + } + + // Get the normal estimate at the current point + const Eigen::Vector3f nc = input_->points[(*indices_)[R_]].getNormalVector3fMap (); + + // Get a coordinate system that lies on a plane defined by its normal + v_ = nc.unitOrthogonal (); + u_ = nc.cross (v_); + + // Projecting point onto the surface + float dist = nc.dot (coords_[R_]); + proj_qp_ = coords_[R_] - dist * nc; + + // Converting coords, calculating angles and saving the projected near boundary edges + int nr_edge = 0; + std::vector doubleEdges; + for (int i = 1; i < nnn_; i++) // nearest neighbor with index 0 is the query point R_ itself + { + tmp_ = coords_[nnIdx[i]] - proj_qp_; + uvn_nn[i][0] = tmp_.dot(u_); + uvn_nn[i][1] = tmp_.dot(v_); + + // Computing the angle between each neighboring point and the query point itself + angles_[i].angle = atan2(uvn_nn[i][1], uvn_nn[i][0]); + // initializing angle descriptors + angles_[i].index = nnIdx[i]; + angles_[i].nnIndex = i; + if ( + (state_[nnIdx[i]] == COMPLETED) || (state_[nnIdx[i]] == BOUNDARY) + || (state_[nnIdx[i]] == NONE) || (nnIdx[i] == -1) /// NOTE: discarding NaN points and those that are not in indices_ + || (sqrDists[i] > sqr_dist_threshold) + ) + angles_[i].visible = false; + else + angles_[i].visible = true; + if ((ffn_[R_] == nnIdx[i]) || (sfn_[R_] == nnIdx[i])) + angles_[i].visible = true; + bool same_side = true; + const Eigen::Vector3f neighbor_normal = input_->points[(*indices_)[nnIdx[i]]].getNormalVector3fMap (); /// NOTE: nnIdx was reset + double cosine = nc.dot (neighbor_normal); + if (cosine > 1) cosine = 1; + if (cosine < -1) cosine = -1; + double angle = acos (cosine); + if ((!consistent_) && (angle > M_PI/2)) + angle = M_PI - angle; + if (angle > eps_angle_) + { + angles_[i].visible = false; + same_side = false; + } + // Saving the edges between nearby boundary points + if ((i!=0) && (same_side) && ((state_[nnIdx[i]] == FRINGE) || (state_[nnIdx[i]] == BOUNDARY))) + { + doubleEdge e; + e.index = i; + nr_edge++; + tmp_ = coords_[ffn_[nnIdx[i]]] - proj_qp_; + e.first[0] = tmp_.dot(u_); + e.first[1] = tmp_.dot(v_); + tmp_ = coords_[sfn_[nnIdx[i]]] - proj_qp_; + e.second[0] = tmp_.dot(u_); + e.second[1] = tmp_.dot(v_); + doubleEdges.push_back(e); + // Pruning by visibility criterion + if ((state_[nnIdx[i]] == FRINGE) && (ffn_[R_] != nnIdx[i]) && (sfn_[R_] != nnIdx[i])) + { + double angle1 = atan2(e.first[1] - uvn_nn[i][1], e.first[0] - uvn_nn[i][0]); + double angle2 = atan2(e.second[1] - uvn_nn[i][1], e.second[0] - uvn_nn[i][0]); + double angleMin, angleMax; + if (angle1 < angle2) + { + angleMin = angle1; + angleMax = angle2; + } + else + { + angleMin = angle2; + angleMax = angle1; + } + double angleR = angles_[i].angle + M_PI; + if (angleR >= 2*M_PI) + angleR -= 2*M_PI; + if ((source_[nnIdx[i]] == ffn_[nnIdx[i]]) || (source_[nnIdx[i]] == sfn_[nnIdx[i]])) + { + if ((angleMax - angleMin) < M_PI) + { + if ((angleMin < angleR) && (angleR < angleMax)) + angles_[i].visible = false; + } + else + { + if ((angleR < angleMin) || (angleMax < angleR)) + angles_[i].visible = false; + } + } + else + { + tmp_ = coords_[source_[nnIdx[i]]] - proj_qp_; + uvn_s[0] = tmp_.dot(u_); + uvn_s[1] = tmp_.dot(v_); + double angleS = atan2(uvn_s[1] - uvn_nn[i][1], uvn_s[0] - uvn_nn[i][0]); + if ((angleMin < angleS) && (angleS < angleMax)) + { + if ((angleMin < angleR) && (angleR < angleMax)) + angles_[i].visible = false; + } + else + { + if ((angleR < angleMin) || (angleMax < angleR)) + angles_[i].visible = false; + } + } + } + } + } + angles_[0].visible = false; + + // Verify the visibility of each potential new vertex + for (int i = 1; i < nnn_; i++) // nearest neighbor with index 0 is the query point R_ itself + if ((angles_[i].visible) && (ffn_[R_] != nnIdx[i]) && (sfn_[R_] != nnIdx[i])) + { + bool visibility = true; + for (int j = 0; j < nr_edge; j++) + { + if (doubleEdges[j].index != i) + { + int f = ffn_[nnIdx[doubleEdges[j].index]]; + if ((f != nnIdx[i]) && (f != R_)) + visibility = isVisible(uvn_nn[i], uvn_nn[doubleEdges[j].index], doubleEdges[j].first, Eigen::Vector2f::Zero()); + if (visibility == false) + break; + + int s = sfn_[nnIdx[doubleEdges[j].index]]; + if ((s != nnIdx[i]) && (s != R_)) + visibility = isVisible(uvn_nn[i], uvn_nn[doubleEdges[j].index], doubleEdges[j].second, Eigen::Vector2f::Zero()); + if (visibility == false) + break; + } + } + angles_[i].visible = visibility; + } + + // Sorting angles + std::sort (angles_.begin (), angles_.end (), GreedyProjectionTriangulation::nnAngleSortAsc); + + // Triangulating + if (angles_[2].visible == false) + { + if ( !( (angles_[0].index == ffn_[R_] && angles_[1].index == sfn_[R_]) || (angles_[0].index == sfn_[R_] && angles_[1].index == ffn_[R_]) ) ) + { + state_[R_] = BOUNDARY; + } + else + { + if ((source_[R_] == angles_[0].index) || (source_[R_] == angles_[1].index)) + state_[R_] = BOUNDARY; + else + { + if (sqr_max_edge < (coords_[ffn_[R_]] - coords_[sfn_[R_]]).squaredNorm ()) + { + state_[R_] = BOUNDARY; + } + else + { + tmp_ = coords_[source_[R_]] - proj_qp_; + uvn_s[0] = tmp_.dot(u_); + uvn_s[1] = tmp_.dot(v_); + double angleS = atan2(uvn_s[1], uvn_s[0]); + double dif = angles_[1].angle - angles_[0].angle; + if ((angles_[0].angle < angleS) && (angleS < angles_[1].angle)) + { + if (dif < 2*M_PI - maximum_angle_) + state_[R_] = BOUNDARY; + else + closeTriangle (polygons); + } + else + { + if (dif >= maximum_angle_) + state_[R_] = BOUNDARY; + else + closeTriangle (polygons); + } + } + } + } + continue; + } + + // Finding the FFN and SFN + int start = -1, end = -1; + for (int i=0; i end)) + need_invert = true; + } + else + { + if (nCB != NONE) + { + if ((nCB == start) || (nCB == end)) + { + bool inside_CB = false; + bool outside_CB = false; + for (int i=0; i angles_[start].angle) && (angles_[nCB].angle < angles_[end].angle)) + need_invert = true; + } + } + else + { + if (start == end-1) + need_invert = true; + } + } + } + else if ((angles_[start].angle < angles_[sourceIdx].angle) && (angles_[sourceIdx].angle < angles_[end].angle)) + need_invert = true; + } + + // switching start and end if necessary + if (need_invert) + { + int tmp = start; + start = end; + end = tmp; + } + + // Arranging visible nnAngles in the order they need to be connected and + // compute the maximal angle difference between two consecutive visible angles + bool is_boundary = false, is_skinny = false; + std::vector gaps (nnn_, false); + std::vector skinny (nnn_, false); + std::vector dif (nnn_); + std::vector angleIdx; angleIdx.reserve (nnn_); + if (start > end) + { + for (int j=start; j::iterator first_gap_after = angleIdx.end (); + std::vector::iterator last_gap_before = angleIdx.begin (); + int nr_gaps = 0; + for (std::vector::iterator it = angleIdx.begin (); it != angleIdx.end () - 1; it++) + { + if (gaps[*it]) + { + nr_gaps++; + if (first_gap_after == angleIdx.end()) + first_gap_after = it; + last_gap_before = it+1; + } + } + if (nr_gaps > 1) + { + angleIdx.erase(first_gap_after+1, last_gap_before); + } + + // Neglecting points that would form skinny triangles (if possible) + if (is_skinny) + { + double angle_so_far = 0, angle_would_be; + double max_combined_angle = (std::min)(maximum_angle_, M_PI-2*minimum_angle_); + Eigen::Vector2f X; + Eigen::Vector2f S1; + Eigen::Vector2f S2; + std::vector to_erase; + for (std::vector::iterator it = angleIdx.begin()+1; it != angleIdx.end()-1; it++) + { + if (gaps[*(it-1)]) + angle_so_far = 0; + else + angle_so_far += dif[*(it-1)]; + if (gaps[*it]) + angle_would_be = angle_so_far; + else + angle_would_be = angle_so_far + dif[*it]; + if ( + (skinny[*it] || skinny[*(it-1)]) && + ((state_[angles_[*it].index] <= FREE) || (state_[angles_[*(it-1)].index] <= FREE)) && + ((!gaps[*it]) || (angles_[*it].nnIndex > angles_[*(it-1)].nnIndex)) && + ((!gaps[*(it-1)]) || (angles_[*it].nnIndex > angles_[*(it+1)].nnIndex)) && + (angle_would_be < max_combined_angle) + ) + { + if (gaps[*(it-1)]) + { + gaps[*it] = true; + to_erase.push_back(*it); + } + else if (gaps[*it]) + { + gaps[*(it-1)] = true; + to_erase.push_back(*it); + } + else + { + std::vector::iterator prev_it; + int erased_idx = static_cast (to_erase.size ()) -1; + for (prev_it = it-1; (erased_idx != -1) && (it != angleIdx.begin()); it--) + if (*it == to_erase[erased_idx]) + erased_idx--; + else + break; + bool can_delete = true; + for (std::vector::iterator curr_it = prev_it+1; curr_it != it+1; curr_it++) + { + tmp_ = coords_[angles_[*curr_it].index] - proj_qp_; + X[0] = tmp_.dot(u_); + X[1] = tmp_.dot(v_); + tmp_ = coords_[angles_[*prev_it].index] - proj_qp_; + S1[0] = tmp_.dot(u_); + S1[1] = tmp_.dot(v_); + tmp_ = coords_[angles_[*(it+1)].index] - proj_qp_; + S2[0] = tmp_.dot(u_); + S2[1] = tmp_.dot(v_); + // check for inclusions + if (isVisible(X,S1,S2)) + { + can_delete = false; + angle_so_far = 0; + break; + } + } + if (can_delete) + { + to_erase.push_back(*it); + } + } + } + else + angle_so_far = 0; + } + for (std::vector::iterator it = to_erase.begin(); it != to_erase.end(); it++) + { + for (std::vector::iterator iter = angleIdx.begin(); iter != angleIdx.end(); iter++) + if (*it == *iter) + { + angleIdx.erase(iter); + break; + } + } + } + + // Writing edges and updating edge-front + changed_1st_fn_ = false; + changed_2nd_fn_ = false; + new2boundary_ = NONE; + for (std::vector::iterator it = angleIdx.begin()+1; it != angleIdx.end()-1; it++) + { + current_index_ = angles_[*it].index; + + is_current_free_ = false; + if (state_[current_index_] <= FREE) + { + state_[current_index_] = FRINGE; + is_current_free_ = true; + } + else if (!already_connected_) + { + prev_is_ffn_ = (ffn_[current_index_] == angles_[*(it-1)].index) && (!gaps[*(it-1)]); + prev_is_sfn_ = (sfn_[current_index_] == angles_[*(it-1)].index) && (!gaps[*(it-1)]); + next_is_ffn_ = (ffn_[current_index_] == angles_[*(it+1)].index) && (!gaps[*it]); + next_is_sfn_ = (sfn_[current_index_] == angles_[*(it+1)].index) && (!gaps[*it]); + if (!prev_is_ffn_ && !next_is_sfn_ && !prev_is_sfn_ && !next_is_ffn_) + { + nr_touched++; + } + } + + if (gaps[*it]) + if (gaps[*(it-1)]) + { + if (is_current_free_) + state_[current_index_] = NONE; /// TODO: document! + } + + else // (gaps[*it]) && ^(gaps[*(it-1)]) + { + addTriangle (current_index_, angles_[*(it-1)].index, R_, polygons); + addFringePoint (current_index_, R_); + new2boundary_ = current_index_; + if (!already_connected_) + connectPoint (polygons, angles_[*(it-1)].index, R_, + angles_[*(it+1)].index, + uvn_nn[angles_[*it].nnIndex], uvn_nn[angles_[*(it-1)].nnIndex], uvn_nn_qp_zero); + else already_connected_ = false; + if (ffn_[R_] == angles_[*(angleIdx.begin())].index) + { + ffn_[R_] = new2boundary_; + } + else if (sfn_[R_] == angles_[*(angleIdx.begin())].index) + { + sfn_[R_] = new2boundary_; + } + } + + else // ^(gaps[*it]) + if (gaps[*(it-1)]) + { + addFringePoint (current_index_, R_); + new2boundary_ = current_index_; + if (!already_connected_) connectPoint (polygons, R_, angles_[*(it+1)].index, + (it+2) == angleIdx.end() ? -1 : angles_[*(it+2)].index, + uvn_nn[angles_[*it].nnIndex], uvn_nn_qp_zero, + uvn_nn[angles_[*(it+1)].nnIndex]); + else already_connected_ = false; + if (ffn_[R_] == angles_[*(angleIdx.end()-1)].index) + { + ffn_[R_] = new2boundary_; + } + else if (sfn_[R_] == angles_[*(angleIdx.end()-1)].index) + { + sfn_[R_] = new2boundary_; + } + } + + else // ^(gaps[*it]) && ^(gaps[*(it-1)]) + { + addTriangle (current_index_, angles_[*(it-1)].index, R_, polygons); + addFringePoint (current_index_, R_); + if (!already_connected_) connectPoint (polygons, angles_[*(it-1)].index, angles_[*(it+1)].index, + (it+2) == angleIdx.end() ? -1 : gaps[*(it+1)] ? R_ : angles_[*(it+2)].index, + uvn_nn[angles_[*it].nnIndex], + uvn_nn[angles_[*(it-1)].nnIndex], + uvn_nn[angles_[*(it+1)].nnIndex]); + else already_connected_ = false; + } + } + + // Finishing up R_ + if (ffn_[R_] == sfn_[R_]) + { + state_[R_] = COMPLETED; + } + if (!gaps[*(angleIdx.end()-2)]) + { + addTriangle (angles_[*(angleIdx.end()-2)].index, angles_[*(angleIdx.end()-1)].index, R_, polygons); + addFringePoint (angles_[*(angleIdx.end()-2)].index, R_); + if (R_ == ffn_[angles_[*(angleIdx.end()-1)].index]) + { + if (angles_[*(angleIdx.end()-2)].index == sfn_[angles_[*(angleIdx.end()-1)].index]) + { + state_[angles_[*(angleIdx.end()-1)].index] = COMPLETED; + } + else + { + ffn_[angles_[*(angleIdx.end()-1)].index] = angles_[*(angleIdx.end()-2)].index; + } + } + else if (R_ == sfn_[angles_[*(angleIdx.end()-1)].index]) + { + if (angles_[*(angleIdx.end()-2)].index == ffn_[angles_[*(angleIdx.end()-1)].index]) + { + state_[angles_[*(angleIdx.end()-1)].index] = COMPLETED; + } + else + { + sfn_[angles_[*(angleIdx.end()-1)].index] = angles_[*(angleIdx.end()-2)].index; + } + } + } + if (!gaps[*(angleIdx.begin())]) + { + if (R_ == ffn_[angles_[*(angleIdx.begin())].index]) + { + if (angles_[*(angleIdx.begin()+1)].index == sfn_[angles_[*(angleIdx.begin())].index]) + { + state_[angles_[*(angleIdx.begin())].index] = COMPLETED; + } + else + { + ffn_[angles_[*(angleIdx.begin())].index] = angles_[*(angleIdx.begin()+1)].index; + } + } + else if (R_ == sfn_[angles_[*(angleIdx.begin())].index]) + { + if (angles_[*(angleIdx.begin()+1)].index == ffn_[angles_[*(angleIdx.begin())].index]) + { + state_[angles_[*(angleIdx.begin())].index] = COMPLETED; + } + else + { + sfn_[angles_[*(angleIdx.begin())].index] = angles_[*(angleIdx.begin()+1)].index; + } + } + } + } + } + PCL_DEBUG ("Number of triangles: %lu\n", polygons.size()); + PCL_DEBUG ("Number of unconnected parts: %d\n", nr_parts); + if (increase_nnn4fn > 0) + PCL_WARN ("Number of neighborhood size increase requests for fringe neighbors: %d\n", increase_nnn4fn); + if (increase_nnn4s > 0) + PCL_WARN ("Number of neighborhood size increase requests for source: %d\n", increase_nnn4s); + if (increase_dist > 0) + PCL_WARN ("Number of automatic maximum distance increases: %d\n", increase_dist); + + // sorting and removing doubles from fringe queue + std::sort (fringe_queue_.begin (), fringe_queue_.end ()); + fringe_queue_.erase (std::unique (fringe_queue_.begin (), fringe_queue_.end ()), fringe_queue_.end ()); + PCL_DEBUG ("Number of processed points: %lu / %lu\n", fringe_queue_.size(), indices_->size ()); + return (true); +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GreedyProjectionTriangulation::closeTriangle (std::vector &polygons) +{ + state_[R_] = COMPLETED; + addTriangle (angles_[0].index, angles_[1].index, R_, polygons); + for (int aIdx=0; aIdx<2; aIdx++) + { + if (ffn_[angles_[aIdx].index] == R_) + { + if (sfn_[angles_[aIdx].index] == angles_[(aIdx+1)%2].index) + { + state_[angles_[aIdx].index] = COMPLETED; + } + else + { + ffn_[angles_[aIdx].index] = angles_[(aIdx+1)%2].index; + } + } + else if (sfn_[angles_[aIdx].index] == R_) + { + if (ffn_[angles_[aIdx].index] == angles_[(aIdx+1)%2].index) + { + state_[angles_[aIdx].index] = COMPLETED; + } + else + { + sfn_[angles_[aIdx].index] = angles_[(aIdx+1)%2].index; + } + } + } +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GreedyProjectionTriangulation::connectPoint ( + std::vector &polygons, + const int prev_index, const int next_index, const int next_next_index, + const Eigen::Vector2f &uvn_current, + const Eigen::Vector2f &uvn_prev, + const Eigen::Vector2f &uvn_next) +{ + if (is_current_free_) + { + ffn_[current_index_] = prev_index; + sfn_[current_index_] = next_index; + } + else + { + if ((prev_is_ffn_ && next_is_sfn_) || (prev_is_sfn_ && next_is_ffn_)) + state_[current_index_] = COMPLETED; + else if (prev_is_ffn_ && !next_is_sfn_) + ffn_[current_index_] = next_index; + else if (next_is_ffn_ && !prev_is_sfn_) + ffn_[current_index_] = prev_index; + else if (prev_is_sfn_ && !next_is_ffn_) + sfn_[current_index_] = next_index; + else if (next_is_sfn_ && !prev_is_ffn_) + sfn_[current_index_] = prev_index; + else + { + bool found_triangle = false; + if ((prev_index != R_) && ((ffn_[current_index_] == ffn_[prev_index]) || (ffn_[current_index_] == sfn_[prev_index]))) + { + found_triangle = true; + addTriangle (current_index_, ffn_[current_index_], prev_index, polygons); + state_[prev_index] = COMPLETED; + state_[ffn_[current_index_]] = COMPLETED; + ffn_[current_index_] = next_index; + } + else if ((prev_index != R_) && ((sfn_[current_index_] == ffn_[prev_index]) || (sfn_[current_index_] == sfn_[prev_index]))) + { + found_triangle = true; + addTriangle (current_index_, sfn_[current_index_], prev_index, polygons); + state_[prev_index] = COMPLETED; + state_[sfn_[current_index_]] = COMPLETED; + sfn_[current_index_] = next_index; + } + else if (state_[next_index] > FREE) + { + if ((ffn_[current_index_] == ffn_[next_index]) || (ffn_[current_index_] == sfn_[next_index])) + { + found_triangle = true; + addTriangle (current_index_, ffn_[current_index_], next_index, polygons); + + if (ffn_[current_index_] == ffn_[next_index]) + { + ffn_[next_index] = current_index_; + } + else + { + sfn_[next_index] = current_index_; + } + state_[ffn_[current_index_]] = COMPLETED; + ffn_[current_index_] = prev_index; + } + else if ((sfn_[current_index_] == ffn_[next_index]) || (sfn_[current_index_] == sfn_[next_index])) + { + found_triangle = true; + addTriangle (current_index_, sfn_[current_index_], next_index, polygons); + + if (sfn_[current_index_] == ffn_[next_index]) + { + ffn_[next_index] = current_index_; + } + else + { + sfn_[next_index] = current_index_; + } + state_[sfn_[current_index_]] = COMPLETED; + sfn_[current_index_] = prev_index; + } + } + + if (found_triangle) + { + } + else + { + tmp_ = coords_[ffn_[current_index_]] - proj_qp_; + uvn_ffn_[0] = tmp_.dot(u_); + uvn_ffn_[1] = tmp_.dot(v_); + tmp_ = coords_[sfn_[current_index_]] - proj_qp_; + uvn_sfn_[0] = tmp_.dot(u_); + uvn_sfn_[1] = tmp_.dot(v_); + bool prev_ffn = isVisible(uvn_prev, uvn_next, uvn_current, uvn_ffn_) && isVisible(uvn_prev, uvn_sfn_, uvn_current, uvn_ffn_); + bool prev_sfn = isVisible(uvn_prev, uvn_next, uvn_current, uvn_sfn_) && isVisible(uvn_prev, uvn_ffn_, uvn_current, uvn_sfn_); + bool next_ffn = isVisible(uvn_next, uvn_prev, uvn_current, uvn_ffn_) && isVisible(uvn_next, uvn_sfn_, uvn_current, uvn_ffn_); + bool next_sfn = isVisible(uvn_next, uvn_prev, uvn_current, uvn_sfn_) && isVisible(uvn_next, uvn_ffn_, uvn_current, uvn_sfn_); + int min_dist = -1; + if (prev_ffn && next_sfn && prev_sfn && next_ffn) + { + /* should be never the case */ + double prev2f = (coords_[ffn_[current_index_]] - coords_[prev_index]).squaredNorm (); + double next2s = (coords_[sfn_[current_index_]] - coords_[next_index]).squaredNorm (); + double prev2s = (coords_[sfn_[current_index_]] - coords_[prev_index]).squaredNorm (); + double next2f = (coords_[ffn_[current_index_]] - coords_[next_index]).squaredNorm (); + if (prev2f < prev2s) + { + if (prev2f < next2f) + { + if (prev2f < next2s) + min_dist = 0; + else + min_dist = 3; + } + else + { + if (next2f < next2s) + min_dist = 2; + else + min_dist = 3; + } + } + else + { + if (prev2s < next2f) + { + if (prev2s < next2s) + min_dist = 1; + else + min_dist = 3; + } + else + { + if (next2f < next2s) + min_dist = 2; + else + min_dist = 3; + } + } + } + else if (prev_ffn && next_sfn) + { + /* a clear case */ + double prev2f = (coords_[ffn_[current_index_]] - coords_[prev_index]).squaredNorm (); + double next2s = (coords_[sfn_[current_index_]] - coords_[next_index]).squaredNorm (); + if (prev2f < next2s) + min_dist = 0; + else + min_dist = 3; + } + else if (prev_sfn && next_ffn) + { + /* a clear case */ + double prev2s = (coords_[sfn_[current_index_]] - coords_[prev_index]).squaredNorm (); + double next2f = (coords_[ffn_[current_index_]] - coords_[next_index]).squaredNorm (); + if (prev2s < next2f) + min_dist = 1; + else + min_dist = 2; + } + /* straightforward cases */ + else if (prev_ffn && !next_sfn && !prev_sfn && !next_ffn) + min_dist = 0; + else if (!prev_ffn && !next_sfn && prev_sfn && !next_ffn) + min_dist = 1; + else if (!prev_ffn && !next_sfn && !prev_sfn && next_ffn) + min_dist = 2; + else if (!prev_ffn && next_sfn && !prev_sfn && !next_ffn) + min_dist = 3; + /* messed up cases */ + else if (prev_ffn) + { + double prev2f = (coords_[ffn_[current_index_]] - coords_[prev_index]).squaredNorm (); + if (prev_sfn) + { + double prev2s = (coords_[sfn_[current_index_]] - coords_[prev_index]).squaredNorm (); + if (prev2s < prev2f) + min_dist = 1; + else + min_dist = 0; + } + else if (next_ffn) + { + double next2f = (coords_[ffn_[current_index_]] - coords_[next_index]).squaredNorm (); + if (next2f < prev2f) + min_dist = 2; + else + min_dist = 0; + } + } + else if (next_sfn) + { + double next2s = (coords_[sfn_[current_index_]] - coords_[next_index]).squaredNorm (); + if (prev_sfn) + { + double prev2s = (coords_[sfn_[current_index_]] - coords_[prev_index]).squaredNorm (); + if (prev2s < next2s) + min_dist = 1; + else + min_dist = 3; + } + else if (next_ffn) + { + double next2f = (coords_[ffn_[current_index_]] - coords_[next_index]).squaredNorm (); + if (next2f < next2s) + min_dist = 2; + else + min_dist = 3; + } + } + switch (min_dist) + { + case 0://prev2f: + { + addTriangle (current_index_, ffn_[current_index_], prev_index, polygons); + + /* updating prev_index */ + if (ffn_[prev_index] == current_index_) + { + ffn_[prev_index] = ffn_[current_index_]; + } + else if (sfn_[prev_index] == current_index_) + { + sfn_[prev_index] = ffn_[current_index_]; + } + else if (ffn_[prev_index] == R_) + { + changed_1st_fn_ = true; + ffn_[prev_index] = ffn_[current_index_]; + } + else if (sfn_[prev_index] == R_) + { + changed_1st_fn_ = true; + sfn_[prev_index] = ffn_[current_index_]; + } + else if (prev_index == R_) + { + new2boundary_ = ffn_[current_index_]; + } + + /* updating ffn */ + if (ffn_[ffn_[current_index_]] == current_index_) + { + ffn_[ffn_[current_index_]] = prev_index; + } + else if (sfn_[ffn_[current_index_]] == current_index_) + { + sfn_[ffn_[current_index_]] = prev_index; + } + + /* updating current */ + ffn_[current_index_] = next_index; + + break; + } + case 1://prev2s: + { + addTriangle (current_index_, sfn_[current_index_], prev_index, polygons); + + /* updating prev_index */ + if (ffn_[prev_index] == current_index_) + { + ffn_[prev_index] = sfn_[current_index_]; + } + else if (sfn_[prev_index] == current_index_) + { + sfn_[prev_index] = sfn_[current_index_]; + } + else if (ffn_[prev_index] == R_) + { + changed_1st_fn_ = true; + ffn_[prev_index] = sfn_[current_index_]; + } + else if (sfn_[prev_index] == R_) + { + changed_1st_fn_ = true; + sfn_[prev_index] = sfn_[current_index_]; + } + else if (prev_index == R_) + { + new2boundary_ = sfn_[current_index_]; + } + + /* updating sfn */ + if (ffn_[sfn_[current_index_]] == current_index_) + { + ffn_[sfn_[current_index_]] = prev_index; + } + else if (sfn_[sfn_[current_index_]] == current_index_) + { + sfn_[sfn_[current_index_]] = prev_index; + } + + /* updating current */ + sfn_[current_index_] = next_index; + + break; + } + case 2://next2f: + { + addTriangle (current_index_, ffn_[current_index_], next_index, polygons); + int neighbor_update = next_index; + + /* updating next_index */ + if (state_[next_index] <= FREE) + { + state_[next_index] = FRINGE; + ffn_[next_index] = current_index_; + sfn_[next_index] = ffn_[current_index_]; + } + else + { + if (ffn_[next_index] == R_) + { + changed_2nd_fn_ = true; + ffn_[next_index] = ffn_[current_index_]; + } + else if (sfn_[next_index] == R_) + { + changed_2nd_fn_ = true; + sfn_[next_index] = ffn_[current_index_]; + } + else if (next_index == R_) + { + new2boundary_ = ffn_[current_index_]; + if (next_next_index == new2boundary_) + already_connected_ = true; + } + else if (ffn_[next_index] == next_next_index) + { + already_connected_ = true; + ffn_[next_index] = ffn_[current_index_]; + } + else if (sfn_[next_index] == next_next_index) + { + already_connected_ = true; + sfn_[next_index] = ffn_[current_index_]; + } + else + { + tmp_ = coords_[ffn_[next_index]] - proj_qp_; + uvn_next_ffn_[0] = tmp_.dot(u_); + uvn_next_ffn_[1] = tmp_.dot(v_); + tmp_ = coords_[sfn_[next_index]] - proj_qp_; + uvn_next_sfn_[0] = tmp_.dot(u_); + uvn_next_sfn_[1] = tmp_.dot(v_); + + bool ffn_next_ffn = isVisible(uvn_next_ffn_, uvn_next, uvn_current, uvn_ffn_) && isVisible(uvn_next_ffn_, uvn_next, uvn_next_sfn_, uvn_ffn_); + bool sfn_next_ffn = isVisible(uvn_next_sfn_, uvn_next, uvn_current, uvn_ffn_) && isVisible(uvn_next_sfn_, uvn_next, uvn_next_ffn_, uvn_ffn_); + + int connect2ffn = -1; + if (ffn_next_ffn && sfn_next_ffn) + { + double fn2f = (coords_[ffn_[current_index_]] - coords_[ffn_[next_index]]).squaredNorm (); + double sn2f = (coords_[ffn_[current_index_]] - coords_[sfn_[next_index]]).squaredNorm (); + if (fn2f < sn2f) connect2ffn = 0; + else connect2ffn = 1; + } + else if (ffn_next_ffn) connect2ffn = 0; + else if (sfn_next_ffn) connect2ffn = 1; + + switch (connect2ffn) + { + case 0: // ffn[next] + { + addTriangle (next_index, ffn_[current_index_], ffn_[next_index], polygons); + neighbor_update = ffn_[next_index]; + + /* ffn[next_index] */ + if ((ffn_[ffn_[next_index]] == ffn_[current_index_]) || (sfn_[ffn_[next_index]] == ffn_[current_index_])) + { + state_[ffn_[next_index]] = COMPLETED; + } + else if (ffn_[ffn_[next_index]] == next_index) + { + ffn_[ffn_[next_index]] = ffn_[current_index_]; + } + else if (sfn_[ffn_[next_index]] == next_index) + { + sfn_[ffn_[next_index]] = ffn_[current_index_]; + } + + ffn_[next_index] = current_index_; + + break; + } + case 1: // sfn[next] + { + addTriangle (next_index, ffn_[current_index_], sfn_[next_index], polygons); + neighbor_update = sfn_[next_index]; + + /* sfn[next_index] */ + if ((ffn_[sfn_[next_index]] = ffn_[current_index_]) || (sfn_[sfn_[next_index]] == ffn_[current_index_])) + { + state_[sfn_[next_index]] = COMPLETED; + } + else if (ffn_[sfn_[next_index]] == next_index) + { + ffn_[sfn_[next_index]] = ffn_[current_index_]; + } + else if (sfn_[sfn_[next_index]] == next_index) + { + sfn_[sfn_[next_index]] = ffn_[current_index_]; + } + + sfn_[next_index] = current_index_; + + break; + } + default:; + } + } + } + + /* updating ffn */ + if ((ffn_[ffn_[current_index_]] == neighbor_update) || (sfn_[ffn_[current_index_]] == neighbor_update)) + { + state_[ffn_[current_index_]] = COMPLETED; + } + else if (ffn_[ffn_[current_index_]] == current_index_) + { + ffn_[ffn_[current_index_]] = neighbor_update; + } + else if (sfn_[ffn_[current_index_]] == current_index_) + { + sfn_[ffn_[current_index_]] = neighbor_update; + } + + /* updating current */ + ffn_[current_index_] = prev_index; + + break; + } + case 3://next2s: + { + addTriangle (current_index_, sfn_[current_index_], next_index, polygons); + int neighbor_update = next_index; + + /* updating next_index */ + if (state_[next_index] <= FREE) + { + state_[next_index] = FRINGE; + ffn_[next_index] = current_index_; + sfn_[next_index] = sfn_[current_index_]; + } + else + { + if (ffn_[next_index] == R_) + { + changed_2nd_fn_ = true; + ffn_[next_index] = sfn_[current_index_]; + } + else if (sfn_[next_index] == R_) + { + changed_2nd_fn_ = true; + sfn_[next_index] = sfn_[current_index_]; + } + else if (next_index == R_) + { + new2boundary_ = sfn_[current_index_]; + if (next_next_index == new2boundary_) + already_connected_ = true; + } + else if (ffn_[next_index] == next_next_index) + { + already_connected_ = true; + ffn_[next_index] = sfn_[current_index_]; + } + else if (sfn_[next_index] == next_next_index) + { + already_connected_ = true; + sfn_[next_index] = sfn_[current_index_]; + } + else + { + tmp_ = coords_[ffn_[next_index]] - proj_qp_; + uvn_next_ffn_[0] = tmp_.dot(u_); + uvn_next_ffn_[1] = tmp_.dot(v_); + tmp_ = coords_[sfn_[next_index]] - proj_qp_; + uvn_next_sfn_[0] = tmp_.dot(u_); + uvn_next_sfn_[1] = tmp_.dot(v_); + + bool ffn_next_sfn = isVisible(uvn_next_ffn_, uvn_next, uvn_current, uvn_sfn_) && isVisible(uvn_next_ffn_, uvn_next, uvn_next_sfn_, uvn_sfn_); + bool sfn_next_sfn = isVisible(uvn_next_sfn_, uvn_next, uvn_current, uvn_sfn_) && isVisible(uvn_next_sfn_, uvn_next, uvn_next_ffn_, uvn_sfn_); + + int connect2sfn = -1; + if (ffn_next_sfn && sfn_next_sfn) + { + double fn2s = (coords_[sfn_[current_index_]] - coords_[ffn_[next_index]]).squaredNorm (); + double sn2s = (coords_[sfn_[current_index_]] - coords_[sfn_[next_index]]).squaredNorm (); + if (fn2s < sn2s) connect2sfn = 0; + else connect2sfn = 1; + } + else if (ffn_next_sfn) connect2sfn = 0; + else if (sfn_next_sfn) connect2sfn = 1; + + switch (connect2sfn) + { + case 0: // ffn[next] + { + addTriangle (next_index, sfn_[current_index_], ffn_[next_index], polygons); + neighbor_update = ffn_[next_index]; + + /* ffn[next_index] */ + if ((ffn_[ffn_[next_index]] == sfn_[current_index_]) || (sfn_[ffn_[next_index]] == sfn_[current_index_])) + { + state_[ffn_[next_index]] = COMPLETED; + } + else if (ffn_[ffn_[next_index]] == next_index) + { + ffn_[ffn_[next_index]] = sfn_[current_index_]; + } + else if (sfn_[ffn_[next_index]] == next_index) + { + sfn_[ffn_[next_index]] = sfn_[current_index_]; + } + + ffn_[next_index] = current_index_; + + break; + } + case 1: // sfn[next] + { + addTriangle (next_index, sfn_[current_index_], sfn_[next_index], polygons); + neighbor_update = sfn_[next_index]; + + /* sfn[next_index] */ + if ((ffn_[sfn_[next_index]] == sfn_[current_index_]) || (sfn_[sfn_[next_index]] == sfn_[current_index_])) + { + state_[sfn_[next_index]] = COMPLETED; + } + else if (ffn_[sfn_[next_index]] == next_index) + { + ffn_[sfn_[next_index]] = sfn_[current_index_]; + } + else if (sfn_[sfn_[next_index]] == next_index) + { + sfn_[sfn_[next_index]] = sfn_[current_index_]; + } + + sfn_[next_index] = current_index_; + + break; + } + default:; + } + } + } + + /* updating sfn */ + if ((ffn_[sfn_[current_index_]] == neighbor_update) || (sfn_[sfn_[current_index_]] == neighbor_update)) + { + state_[sfn_[current_index_]] = COMPLETED; + } + else if (ffn_[sfn_[current_index_]] == current_index_) + { + ffn_[sfn_[current_index_]] = neighbor_update; + } + else if (sfn_[sfn_[current_index_]] == current_index_) + { + sfn_[sfn_[current_index_]] = neighbor_update; + } + + sfn_[current_index_] = prev_index; + + break; + } + default:; + } + } + } + } +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template std::vector > +pcl::GreedyProjectionTriangulation::getTriangleList (const pcl::PolygonMesh &input) +{ + std::vector > triangleList (input.cloud.width * input.cloud.height); + + for (size_t i=0; i < input.polygons.size (); ++i) + for (size_t j=0; j < input.polygons[i].vertices.size (); ++j) + triangleList[j].push_back (i); + return (triangleList); +} + +#define PCL_INSTANTIATE_GreedyProjectionTriangulation(T) \ + template class PCL_EXPORTS pcl::GreedyProjectionTriangulation; + +#endif // PCL_SURFACE_IMPL_GP3_H_ + + diff --git a/pcl-1.7/pcl/surface/impl/grid_projection.hpp b/pcl-1.7/pcl/surface/impl/grid_projection.hpp new file mode 100644 index 0000000..cfb5a81 --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/grid_projection.hpp @@ -0,0 +1,780 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SURFACE_IMPL_GRID_PROJECTION_H_ +#define PCL_SURFACE_IMPL_GRID_PROJECTION_H_ + +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::GridProjection::GridProjection () : + cell_hash_map_ (), min_p_ (), max_p_ (), leaf_size_ (0.001), gaussian_scale_ (), + data_size_ (0), max_binary_search_level_ (10), k_ (50), padding_size_ (3), data_ (), + vector_at_data_point_ (), surface_ (), occupied_cell_list_ () +{} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::GridProjection::GridProjection (double resolution) : + cell_hash_map_ (), min_p_ (), max_p_ (), leaf_size_ (resolution), gaussian_scale_ (), + data_size_ (0), max_binary_search_level_ (10), k_ (50), padding_size_ (3), data_ (), + vector_at_data_point_ (), surface_ (), occupied_cell_list_ () +{} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::GridProjection::~GridProjection () +{ + vector_at_data_point_.clear (); + surface_.clear (); + cell_hash_map_.clear (); + occupied_cell_list_.clear (); + data_.reset (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::scaleInputDataPoint (double scale_factor) +{ + for (size_t i = 0; i < data_->points.size(); ++i) + { + data_->points[i].x /= static_cast (scale_factor); + data_->points[i].y /= static_cast (scale_factor); + data_->points[i].z /= static_cast (scale_factor); + } + max_p_ /= static_cast (scale_factor); + min_p_ /= static_cast (scale_factor); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::getBoundingBox () +{ + pcl::getMinMax3D (*data_, min_p_, max_p_); + + Eigen::Vector4f bounding_box_size = max_p_ - min_p_; + double scale_factor = (std::max)((std::max)(bounding_box_size.x (), + bounding_box_size.y ()), + bounding_box_size.z ()); + if (scale_factor > 1) + scaleInputDataPoint (scale_factor); + + // Round the max_p_, min_p_ so that they are aligned with the cells vertices + int upper_right_index[3]; + int lower_left_index[3]; + for (size_t i = 0; i < 3; ++i) + { + upper_right_index[i] = static_cast (max_p_(i) / leaf_size_ + 5); + lower_left_index[i] = static_cast (min_p_(i) / leaf_size_ - 5); + max_p_(i) = static_cast (upper_right_index[i] * leaf_size_); + min_p_(i) = static_cast (lower_left_index[i] * leaf_size_); + } + bounding_box_size = max_p_ - min_p_; + PCL_DEBUG ("[pcl::GridProjection::getBoundingBox] Size of Bounding Box is [%f, %f, %f]\n", + bounding_box_size.x (), bounding_box_size.y (), bounding_box_size.z ()); + double max_size = + (std::max) ((std::max)(bounding_box_size.x (), bounding_box_size.y ()), + bounding_box_size.z ()); + + data_size_ = static_cast (max_size / leaf_size_); + PCL_DEBUG ("[pcl::GridProjection::getBoundingBox] Lower left point is [%f, %f, %f]\n", + min_p_.x (), min_p_.y (), min_p_.z ()); + PCL_DEBUG ("[pcl::GridProjection::getBoundingBox] Upper left point is [%f, %f, %f]\n", + max_p_.x (), max_p_.y (), max_p_.z ()); + PCL_DEBUG ("[pcl::GridProjection::getBoundingBox] Padding size: %d\n", padding_size_); + PCL_DEBUG ("[pcl::GridProjection::getBoundingBox] Leaf size: %f\n", leaf_size_); + occupied_cell_list_.resize (data_size_ * data_size_ * data_size_); + gaussian_scale_ = pow ((padding_size_+1) * leaf_size_ / 2.0, 2.0); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::getVertexFromCellCenter ( + const Eigen::Vector4f &cell_center, + std::vector > &pts) const +{ + assert (pts.size () == 8); + + float sz = static_cast (leaf_size_) / 2.0f; + + pts[0] = cell_center + Eigen::Vector4f (-sz, sz, -sz, 0); + pts[1] = cell_center + Eigen::Vector4f (-sz, -sz, -sz, 0); + pts[2] = cell_center + Eigen::Vector4f (sz, -sz, -sz, 0); + pts[3] = cell_center + Eigen::Vector4f (sz, sz, -sz, 0); + pts[4] = cell_center + Eigen::Vector4f (-sz, sz, sz, 0); + pts[5] = cell_center + Eigen::Vector4f (-sz, -sz, sz, 0); + pts[6] = cell_center + Eigen::Vector4f (sz, -sz, sz, 0); + pts[7] = cell_center + Eigen::Vector4f (sz, sz, sz, 0); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::getDataPtsUnion (const Eigen::Vector3i &index, + std::vector &pt_union_indices) +{ + for (int i = index[0] - padding_size_; i <= index[0] + padding_size_; ++i) + { + for (int j = index[1] - padding_size_; j <= index[1] + padding_size_; ++j) + { + for (int k = index[2] - padding_size_; k <= index[2] + padding_size_; ++k) + { + Eigen::Vector3i cell_index_3d (i, j, k); + int cell_index_1d = getIndexIn1D (cell_index_3d); + if (cell_hash_map_.find (cell_index_1d) != cell_hash_map_.end ()) + { + // Get the indices of the input points within the cell(i,j,k), which + // is stored in the hash map + pt_union_indices.insert (pt_union_indices.end (), + cell_hash_map_.at (cell_index_1d).data_indices.begin (), + cell_hash_map_.at (cell_index_1d).data_indices.end ()); + } + } + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::createSurfaceForCell (const Eigen::Vector3i &index, + std::vector &pt_union_indices) +{ + // 8 vertices of the cell + std::vector > vertices (8); + + // 4 end points that shared by 3 edges connecting the upper left front points + Eigen::Vector4f pts[4]; + Eigen::Vector3f vector_at_pts[4]; + + // Given the index of cell, caluate the coordinates of the eight vertices of the cell + // index the index of the cell in (x,y,z) 3d format + Eigen::Vector4f cell_center = Eigen::Vector4f::Zero (); + getCellCenterFromIndex (index, cell_center); + getVertexFromCellCenter (cell_center, vertices); + + // Get the indices of the cells which stores the 4 end points. + Eigen::Vector3i indices[4]; + indices[0] = Eigen::Vector3i (index[0], index[1], index[2] - 1); + indices[1] = Eigen::Vector3i (index[0], index[1], index[2]); + indices[2] = Eigen::Vector3i (index[0], index[1] - 1, index[2]); + indices[3] = Eigen::Vector3i (index[0] + 1, index[1], index[2]); + + // Get the coordinate of the 4 end points, and the corresponding vectors + for (size_t i = 0; i < 4; ++i) + { + pts[i] = vertices[I_SHIFT_PT[i]]; + unsigned int index_1d = getIndexIn1D (indices[i]); + if (cell_hash_map_.find (index_1d) == cell_hash_map_.end () || + occupied_cell_list_[index_1d] == 0) + return; + else + vector_at_pts[i] = cell_hash_map_.at (index_1d).vect_at_grid_pt; + } + + // Go through the 3 edges, test whether they are intersected by the surface + for (size_t i = 0; i < 3; ++i) + { + std::vector > end_pts (2); + std::vector > vect_at_end_pts (2); + for (size_t j = 0; j < 2; ++j) + { + end_pts[j] = pts[I_SHIFT_EDGE[i][j]]; + vect_at_end_pts[j] = vector_at_pts[I_SHIFT_EDGE[i][j]]; + } + + if (isIntersected (end_pts, vect_at_end_pts, pt_union_indices)) + { + // Indices of cells that contains points which will be connected to + // create a polygon + Eigen::Vector3i polygon[4]; + Eigen::Vector4f polygon_pts[4]; + int polygon_indices_1d[4]; + bool is_all_in_hash_map = true; + switch (i) + { + case 0: + polygon[0] = Eigen::Vector3i (index[0] - 1, index[1] + 1, index[2]); + polygon[1] = Eigen::Vector3i (index[0] - 1, index[1], index[2]); + polygon[2] = Eigen::Vector3i (index[0], index[1], index[2]); + polygon[3] = Eigen::Vector3i (index[0], index[1] + 1, index[2]); + break; + case 1: + polygon[0] = Eigen::Vector3i (index[0], index[1] + 1, index[2] + 1); + polygon[1] = Eigen::Vector3i (index[0], index[1] + 1, index[2]); + polygon[2] = Eigen::Vector3i (index[0], index[1], index[2]); + polygon[3] = Eigen::Vector3i (index[0], index[1], index[2] + 1); + break; + case 2: + polygon[0] = Eigen::Vector3i (index[0] - 1, index[1], index[2] + 1); + polygon[1] = Eigen::Vector3i (index[0] - 1, index[1], index[2]); + polygon[2] = Eigen::Vector3i (index[0], index[1], index[2]); + polygon[3] = Eigen::Vector3i (index[0], index[1], index[2] + 1); + break; + default: + break; + } + for (size_t k = 0; k < 4; k++) + { + polygon_indices_1d[k] = getIndexIn1D (polygon[k]); + if (!occupied_cell_list_[polygon_indices_1d[k]]) + { + is_all_in_hash_map = false; + break; + } + } + if (is_all_in_hash_map) + { + for (size_t k = 0; k < 4; k++) + { + polygon_pts[k] = cell_hash_map_.at (polygon_indices_1d[k]).pt_on_surface; + surface_.push_back (polygon_pts[k]); + } + } + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::getProjection (const Eigen::Vector4f &p, + std::vector &pt_union_indices, Eigen::Vector4f &projection) +{ + const double projection_distance = leaf_size_ * 3; + std::vector > end_pt (2); + std::vector > end_pt_vect (2); + end_pt[0] = p; + getVectorAtPoint (end_pt[0], pt_union_indices, end_pt_vect[0]); + end_pt_vect[0].normalize(); + + double dSecond = getD2AtPoint (end_pt[0], end_pt_vect[0], pt_union_indices); + + // Find another point which is projection_distance away from the p, do a + // binary search between these two points, to find the projected point on the + // surface + if (dSecond > 0) + end_pt[1] = end_pt[0] + Eigen::Vector4f ( + end_pt_vect[0][0] * static_cast (projection_distance), + end_pt_vect[0][1] * static_cast (projection_distance), + end_pt_vect[0][2] * static_cast (projection_distance), + 0.0f); + else + end_pt[1] = end_pt[0] - Eigen::Vector4f ( + end_pt_vect[0][0] * static_cast (projection_distance), + end_pt_vect[0][1] * static_cast (projection_distance), + end_pt_vect[0][2] * static_cast (projection_distance), + 0.0f); + getVectorAtPoint (end_pt[1], pt_union_indices, end_pt_vect[1]); + if (end_pt_vect[1].dot (end_pt_vect[0]) < 0) + { + Eigen::Vector4f mid_pt = end_pt[0] + (end_pt[1] - end_pt[0]) * 0.5; + findIntersection (0, end_pt, end_pt_vect, mid_pt, pt_union_indices, projection); + } + else + projection = p; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::getProjectionWithPlaneFit (const Eigen::Vector4f &p, + std::vector (&pt_union_indices), + Eigen::Vector4f &projection) +{ + // Compute the plane coefficients + Eigen::Vector4f model_coefficients; + /// @remark iterative weighted least squares or sac might give better results + Eigen::Matrix3f covariance_matrix; + Eigen::Vector4f xyz_centroid; + + computeMeanAndCovarianceMatrix (*data_, pt_union_indices, covariance_matrix, xyz_centroid); + + // Get the plane normal + EIGEN_ALIGN16 Eigen::Vector3f::Scalar eigen_value; + EIGEN_ALIGN16 Eigen::Vector3f eigen_vector; + pcl::eigen33 (covariance_matrix, eigen_value, eigen_vector); + + // The normalization is not necessary, since the eigenvectors from libeigen are already normalized + model_coefficients[0] = eigen_vector [0]; + model_coefficients[1] = eigen_vector [1]; + model_coefficients[2] = eigen_vector [2]; + model_coefficients[3] = 0; + // Hessian form (D = nc . p_plane (centroid here) + p) + model_coefficients[3] = -1 * model_coefficients.dot (xyz_centroid); + + // Projected point + Eigen::Vector3f point (p.x (), p.y (), p.z ()); //= Eigen::Vector3f::MapAligned (&output.points[cp].x, 3); + float distance = point.dot (model_coefficients.head <3> ()) + model_coefficients[3]; + point -= distance * model_coefficients.head < 3 > (); + + projection = Eigen::Vector4f (point[0], point[1], point[2], 0); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::getVectorAtPoint (const Eigen::Vector4f &p, + std::vector &pt_union_indices, + Eigen::Vector3f &vo) +{ + std::vector pt_union_dist (pt_union_indices.size ()); + std::vector pt_union_weight (pt_union_indices.size ()); + Eigen::Vector3f out_vector (0, 0, 0); + double sum = 0.0; + double mag = 0.0; + + for (size_t i = 0; i < pt_union_indices.size (); ++i) + { + Eigen::Vector4f pp (data_->points[pt_union_indices[i]].x, data_->points[pt_union_indices[i]].y, data_->points[pt_union_indices[i]].z, 0); + pt_union_dist[i] = (pp - p).squaredNorm (); + pt_union_weight[i] = pow (M_E, -pow (pt_union_dist[i], 2.0) / gaussian_scale_); + mag += pow (M_E, -pow (sqrt (pt_union_dist[i]), 2.0) / gaussian_scale_); + sum += pt_union_weight[i]; + } + + pcl::VectorAverage3f vector_average; + + Eigen::Vector3f v ( + data_->points[pt_union_indices[0]].normal[0], + data_->points[pt_union_indices[0]].normal[1], + data_->points[pt_union_indices[0]].normal[2]); + + for (size_t i = 0; i < pt_union_weight.size (); ++i) + { + pt_union_weight[i] /= sum; + Eigen::Vector3f vec (data_->points[pt_union_indices[i]].normal[0], + data_->points[pt_union_indices[i]].normal[1], + data_->points[pt_union_indices[i]].normal[2]); + if (vec.dot (v) < 0) + vec = -vec; + vector_average.add (vec, static_cast (pt_union_weight[i])); + } + out_vector = vector_average.getMean (); + // vector_average.getEigenVector1(out_vector); + + out_vector.normalize (); + double d1 = getD1AtPoint (p, out_vector, pt_union_indices); + out_vector *= static_cast (sum); + vo = ((d1 > 0) ? -1 : 1) * out_vector; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::getVectorAtPointKNN (const Eigen::Vector4f &p, + std::vector &k_indices, + std::vector &k_squared_distances, + Eigen::Vector3f &vo) +{ + Eigen::Vector3f out_vector (0, 0, 0); + std::vector k_weight; + k_weight.resize (k_); + float sum = 0.0; + for (int i = 0; i < k_; i++) + { + //k_weight[i] = pow (M_E, -pow (k_squared_distances[i], 2.0) / gaussian_scale_); + k_weight[i] = std::pow (static_cast(M_E), static_cast(-pow (static_cast(k_squared_distances[i]), 2.0f) / gaussian_scale_)); + sum += k_weight[i]; + } + pcl::VectorAverage3f vector_average; + for (int i = 0; i < k_; i++) + { + k_weight[i] /= sum; + Eigen::Vector3f vec (data_->points[k_indices[i]].normal[0], + data_->points[k_indices[i]].normal[1], + data_->points[k_indices[i]].normal[2]); + vector_average.add (vec, k_weight[i]); + } + vector_average.getEigenVector1 (out_vector); + out_vector.normalize (); + double d1 = getD1AtPoint (p, out_vector, k_indices); + out_vector = out_vector * sum; + vo = ((d1 > 0) ? -1 : 1) * out_vector; + +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::GridProjection::getMagAtPoint (const Eigen::Vector4f &p, + const std::vector &pt_union_indices) +{ + std::vector pt_union_dist (pt_union_indices.size ()); + std::vector pt_union_weight (pt_union_indices.size ()); + double sum = 0.0; + for (size_t i = 0; i < pt_union_indices.size (); ++i) + { + Eigen::Vector4f pp (data_->points[pt_union_indices[i]].x, data_->points[pt_union_indices[i]].y, data_->points[pt_union_indices[i]].z, 0); + pt_union_dist[i] = (pp - p).norm (); + sum += pow (M_E, -pow (pt_union_dist[i], 2.0) / gaussian_scale_); + } + return (sum); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::GridProjection::getD1AtPoint (const Eigen::Vector4f &p, const Eigen::Vector3f &vec, + const std::vector &pt_union_indices) +{ + double sz = 0.01 * leaf_size_; + Eigen::Vector3f v = vec * static_cast (sz); + + double forward = getMagAtPoint (p + Eigen::Vector4f (v[0], v[1], v[2], 0), pt_union_indices); + double backward = getMagAtPoint (p - Eigen::Vector4f (v[0], v[1], v[2], 0), pt_union_indices); + return ((forward - backward) / (0.02 * leaf_size_)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::GridProjection::getD2AtPoint (const Eigen::Vector4f &p, const Eigen::Vector3f &vec, + const std::vector &pt_union_indices) +{ + double sz = 0.01 * leaf_size_; + Eigen::Vector3f v = vec * static_cast (sz); + + double forward = getD1AtPoint (p + Eigen::Vector4f (v[0], v[1], v[2], 0), vec, pt_union_indices); + double backward = getD1AtPoint (p - Eigen::Vector4f (v[0], v[1], v[2], 0), vec, pt_union_indices); + return ((forward - backward) / (0.02 * leaf_size_)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::GridProjection::isIntersected (const std::vector > &end_pts, + std::vector > &vect_at_end_pts, + std::vector &pt_union_indices) +{ + assert (end_pts.size () == 2); + assert (vect_at_end_pts.size () == 2); + + double length[2]; + for (size_t i = 0; i < 2; ++i) + { + length[i] = vect_at_end_pts[i].norm (); + vect_at_end_pts[i].normalize (); + } + double dot_prod = vect_at_end_pts[0].dot (vect_at_end_pts[1]); + if (dot_prod < 0) + { + double ratio = length[0] / (length[0] + length[1]); + Eigen::Vector4f start_pt = + end_pts[0] + (end_pts[1] - end_pts[0]) * static_cast (ratio); + Eigen::Vector4f intersection_pt = Eigen::Vector4f::Zero (); + findIntersection (0, end_pts, vect_at_end_pts, start_pt, pt_union_indices, intersection_pt); + + Eigen::Vector3f vec; + getVectorAtPoint (intersection_pt, pt_union_indices, vec); + vec.normalize (); + + double d2 = getD2AtPoint (intersection_pt, vec, pt_union_indices); + if (d2 < 0) + return (true); + } + return (false); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::findIntersection (int level, + const std::vector > &end_pts, + const std::vector > &vect_at_end_pts, + const Eigen::Vector4f &start_pt, + std::vector &pt_union_indices, + Eigen::Vector4f &intersection) +{ + assert (end_pts.size () == 2); + assert (vect_at_end_pts.size () == 2); + + Eigen::Vector3f vec; + getVectorAtPoint (start_pt, pt_union_indices, vec); + double d1 = getD1AtPoint (start_pt, vec, pt_union_indices); + std::vector > new_end_pts (2); + std::vector > new_vect_at_end_pts (2); + if ((fabs (d1) < 10e-3) || (level == max_binary_search_level_)) + { + intersection = start_pt; + return; + } + else + { + vec.normalize (); + if (vec.dot (vect_at_end_pts[0]) < 0) + { + Eigen::Vector4f new_start_pt = end_pts[0] + (start_pt - end_pts[0]) * 0.5; + new_end_pts[0] = end_pts[0]; + new_end_pts[1] = start_pt; + new_vect_at_end_pts[0] = vect_at_end_pts[0]; + new_vect_at_end_pts[1] = vec; + findIntersection (level + 1, new_end_pts, new_vect_at_end_pts, new_start_pt, pt_union_indices, intersection); + return; + } + if (vec.dot (vect_at_end_pts[1]) < 0) + { + Eigen::Vector4f new_start_pt = start_pt + (end_pts[1] - start_pt) * 0.5; + new_end_pts[0] = start_pt; + new_end_pts[1] = end_pts[1]; + new_vect_at_end_pts[0] = vec; + new_vect_at_end_pts[1] = vect_at_end_pts[1]; + findIntersection (level + 1, new_end_pts, new_vect_at_end_pts, new_start_pt, pt_union_indices, intersection); + return; + } + intersection = start_pt; + return; + } +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::fillPad (const Eigen::Vector3i &index) +{ + for (int i = index[0] - padding_size_; i < index[0] + padding_size_; ++i) + { + for (int j = index[1] - padding_size_; j < index[1] + padding_size_; ++j) + { + for (int k = index[2] - padding_size_; k < index[2] + padding_size_; ++k) + { + Eigen::Vector3i cell_index_3d (i, j, k); + unsigned int cell_index_1d = getIndexIn1D (cell_index_3d); + if (cell_hash_map_.find (cell_index_1d) == cell_hash_map_.end ()) + { + cell_hash_map_[cell_index_1d].data_indices.resize (0); + getCellCenterFromIndex (cell_index_3d, cell_hash_map_[cell_index_1d].pt_on_surface); + } + } + } + } +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::storeVectAndSurfacePoint (int index_1d, + const Eigen::Vector3i &, + std::vector &pt_union_indices, + const Leaf &cell_data) +{ + // Get point on grid + Eigen::Vector4f grid_pt ( + cell_data.pt_on_surface.x () - static_cast (leaf_size_) / 2.0f, + cell_data.pt_on_surface.y () + static_cast (leaf_size_) / 2.0f, + cell_data.pt_on_surface.z () + static_cast (leaf_size_) / 2.0f, 0.0f); + + // Save the vector and the point on the surface + getVectorAtPoint (grid_pt, pt_union_indices, cell_hash_map_[index_1d].vect_at_grid_pt); + getProjection (cell_data.pt_on_surface, pt_union_indices, cell_hash_map_[index_1d].pt_on_surface); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::storeVectAndSurfacePointKNN (int index_1d, const Eigen::Vector3i &, + const Leaf &cell_data) +{ + Eigen::Vector4f cell_center = cell_data.pt_on_surface; + Eigen::Vector4f grid_pt ( + cell_center.x () - static_cast (leaf_size_) / 2.0f, + cell_center.y () + static_cast (leaf_size_) / 2.0f, + cell_center.z () + static_cast (leaf_size_) / 2.0f, 0.0f); + + std::vector k_indices; + k_indices.resize (k_); + std::vector k_squared_distances; + k_squared_distances.resize (k_); + + PointNT pt; pt.x = grid_pt.x (); pt.y = grid_pt.y (); pt.z = grid_pt.z (); + tree_->nearestKSearch (pt, k_, k_indices, k_squared_distances); + + getVectorAtPointKNN (grid_pt, k_indices, k_squared_distances, cell_hash_map_[index_1d].vect_at_grid_pt); + getProjectionWithPlaneFit (cell_center, k_indices, cell_hash_map_[index_1d].pt_on_surface); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::GridProjection::reconstructPolygons (std::vector &polygons) +{ + data_.reset (new pcl::PointCloud (*input_)); + getBoundingBox (); + + // Store the point cloud data into the voxel grid, and at the same time + // create a hash map to store the information for each cell + cell_hash_map_.max_load_factor (2.0); + cell_hash_map_.rehash (data_->points.size () / static_cast (cell_hash_map_.max_load_factor ())); + + // Go over all points and insert them into the right leaf + for (int cp = 0; cp < static_cast (data_->points.size ()); ++cp) + { + // Check if the point is invalid + if (!pcl_isfinite (data_->points[cp].x) || + !pcl_isfinite (data_->points[cp].y) || + !pcl_isfinite (data_->points[cp].z)) + continue; + + Eigen::Vector3i index_3d; + getCellIndex (data_->points[cp].getVector4fMap (), index_3d); + int index_1d = getIndexIn1D (index_3d); + if (cell_hash_map_.find (index_1d) == cell_hash_map_.end ()) + { + Leaf cell_data; + cell_data.data_indices.push_back (cp); + getCellCenterFromIndex (index_3d, cell_data.pt_on_surface); + cell_hash_map_[index_1d] = cell_data; + occupied_cell_list_[index_1d] = 1; + } + else + { + Leaf cell_data = cell_hash_map_.at (index_1d); + cell_data.data_indices.push_back (cp); + cell_hash_map_[index_1d] = cell_data; + } + } + + Eigen::Vector3i index; + int numOfFilledPad = 0; + + for (int i = 0; i < data_size_; ++i) + { + for (int j = 0; j < data_size_; ++j) + { + for (int k = 0; k < data_size_; ++k) + { + index[0] = i; + index[1] = j; + index[2] = k; + if (occupied_cell_list_[getIndexIn1D (index)]) + { + fillPad (index); + numOfFilledPad++; + } + } + } + } + + // Update the hashtable and store the vector and point + BOOST_FOREACH (typename HashMap::value_type entry, cell_hash_map_) + { + getIndexIn3D (entry.first, index); + std::vector pt_union_indices; + getDataPtsUnion (index, pt_union_indices); + + // Needs at least 10 points (?) + // NOTE: set as parameter later + if (pt_union_indices.size () > 10) + { + storeVectAndSurfacePoint (entry.first, index, pt_union_indices, entry.second); + //storeVectAndSurfacePointKNN(entry.first, index, entry.second); + occupied_cell_list_[entry.first] = 1; + } + } + + // Go through the hash table another time to extract surface + BOOST_FOREACH (typename HashMap::value_type entry, cell_hash_map_) + { + getIndexIn3D (entry.first, index); + std::vector pt_union_indices; + getDataPtsUnion (index, pt_union_indices); + + // Needs at least 10 points (?) + // NOTE: set as parameter later + if (pt_union_indices.size () > 10) + createSurfaceForCell (index, pt_union_indices); + } + + polygons.resize (surface_.size () / 4); + // Copy the data from surface_ to polygons + for (int i = 0; i < static_cast (polygons.size ()); ++i) + { + pcl::Vertices v; + v.vertices.resize (4); + for (int j = 0; j < 4; ++j) + v.vertices[j] = i*4+j; + polygons[i] = v; + } + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::performReconstruction (pcl::PolygonMesh &output) +{ + if (!reconstructPolygons (output.polygons)) + return; + + // The mesh surface is held in surface_. Copy it to the output format + output.header = input_->header; + + pcl::PointCloud cloud; + cloud.width = static_cast (surface_.size ()); + cloud.height = 1; + cloud.is_dense = true; + + cloud.points.resize (surface_.size ()); + // Copy the data from surface_ to cloud + for (size_t i = 0; i < cloud.points.size (); ++i) + { + cloud.points[i].x = surface_[i].x (); + cloud.points[i].y = surface_[i].y (); + cloud.points[i].z = surface_[i].z (); + } + pcl::toPCLPointCloud2 (cloud, output.cloud); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::GridProjection::performReconstruction (pcl::PointCloud &points, + std::vector &polygons) +{ + if (!reconstructPolygons (polygons)) + return; + + // The mesh surface is held in surface_. Copy it to the output format + points.header = input_->header; + points.width = static_cast (surface_.size ()); + points.height = 1; + points.is_dense = true; + + points.resize (surface_.size ()); + // Copy the data from surface_ to cloud + for (size_t i = 0; i < points.size (); ++i) + { + points[i].x = surface_[i].x (); + points[i].y = surface_[i].y (); + points[i].z = surface_[i].z (); + } +} + +#define PCL_INSTANTIATE_GridProjection(T) template class PCL_EXPORTS pcl::GridProjection; + +#endif // PCL_SURFACE_IMPL_GRID_PROJECTION_H_ + diff --git a/pcl-1.7/pcl/surface/impl/marching_cubes.hpp b/pcl-1.7/pcl/surface/impl/marching_cubes.hpp new file mode 100644 index 0000000..12c0ca5 --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/marching_cubes.hpp @@ -0,0 +1,332 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SURFACE_IMPL_MARCHING_CUBES_H_ +#define PCL_SURFACE_IMPL_MARCHING_CUBES_H_ + +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::MarchingCubes::MarchingCubes () +: min_p_ (), max_p_ (), percentage_extend_grid_ (), iso_level_ () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::MarchingCubes::~MarchingCubes () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MarchingCubes::getBoundingBox () +{ + pcl::getMinMax3D (*input_, min_p_, max_p_); + + min_p_ -= (max_p_ - min_p_) * percentage_extend_grid_/2; + max_p_ += (max_p_ - min_p_) * percentage_extend_grid_/2; + + Eigen::Vector4f bounding_box_size = max_p_ - min_p_; + + bounding_box_size = max_p_ - min_p_; + PCL_DEBUG ("[pcl::MarchingCubesHoppe::getBoundingBox] Size of Bounding Box is [%f, %f, %f]\n", + bounding_box_size.x (), bounding_box_size.y (), bounding_box_size.z ()); + double max_size = + (std::max) ((std::max)(bounding_box_size.x (), bounding_box_size.y ()), + bounding_box_size.z ()); + (void)max_size; + // ???? + // data_size_ = static_cast (max_size / leaf_size_); + PCL_DEBUG ("[pcl::MarchingCubesHoppe::getBoundingBox] Lower left point is [%f, %f, %f]\n", + min_p_.x (), min_p_.y (), min_p_.z ()); + PCL_DEBUG ("[pcl::MarchingCubesHoppe::getBoundingBox] Upper left point is [%f, %f, %f]\n", + max_p_.x (), max_p_.y (), max_p_.z ()); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MarchingCubes::interpolateEdge (Eigen::Vector3f &p1, + Eigen::Vector3f &p2, + float val_p1, + float val_p2, + Eigen::Vector3f &output) +{ + float mu = (iso_level_ - val_p1) / (val_p2-val_p1); + output = p1 + mu * (p2 - p1); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MarchingCubes::createSurface (std::vector &leaf_node, + Eigen::Vector3i &index_3d, + pcl::PointCloud &cloud) +{ + int cubeindex = 0; + Eigen::Vector3f vertex_list[12]; + if (leaf_node[0] < iso_level_) cubeindex |= 1; + if (leaf_node[1] < iso_level_) cubeindex |= 2; + if (leaf_node[2] < iso_level_) cubeindex |= 4; + if (leaf_node[3] < iso_level_) cubeindex |= 8; + if (leaf_node[4] < iso_level_) cubeindex |= 16; + if (leaf_node[5] < iso_level_) cubeindex |= 32; + if (leaf_node[6] < iso_level_) cubeindex |= 64; + if (leaf_node[7] < iso_level_) cubeindex |= 128; + + // Cube is entirely in/out of the surface + if (edgeTable[cubeindex] == 0) + return; + + //Eigen::Vector4f index_3df (index_3d[0], index_3d[1], index_3d[2], 0.0f); + Eigen::Vector3f center;// TODO coeff wise product = min_p_ + Eigen::Vector4f (1.0f/res_x_, 1.0f/res_y_, 1.0f/res_z_) * index_3df * (max_p_ - min_p_); + center[0] = min_p_[0] + (max_p_[0] - min_p_[0]) * float (index_3d[0]) / float (res_x_); + center[1] = min_p_[1] + (max_p_[1] - min_p_[1]) * float (index_3d[1]) / float (res_y_); + center[2] = min_p_[2] + (max_p_[2] - min_p_[2]) * float (index_3d[2]) / float (res_z_); + + std::vector p; + p.resize (8); + for (int i = 0; i < 8; ++i) + { + Eigen::Vector3f point = center; + if(i & 0x4) + point[1] = static_cast (center[1] + (max_p_[1] - min_p_[1]) / float (res_y_)); + + if(i & 0x2) + point[2] = static_cast (center[2] + (max_p_[2] - min_p_[2]) / float (res_z_)); + + if((i & 0x1) ^ ((i >> 1) & 0x1)) + point[0] = static_cast (center[0] + (max_p_[0] - min_p_[0]) / float (res_x_)); + + p[i] = point; + } + + + // Find the vertices where the surface intersects the cube + if (edgeTable[cubeindex] & 1) + interpolateEdge (p[0], p[1], leaf_node[0], leaf_node[1], vertex_list[0]); + if (edgeTable[cubeindex] & 2) + interpolateEdge (p[1], p[2], leaf_node[1], leaf_node[2], vertex_list[1]); + if (edgeTable[cubeindex] & 4) + interpolateEdge (p[2], p[3], leaf_node[2], leaf_node[3], vertex_list[2]); + if (edgeTable[cubeindex] & 8) + interpolateEdge (p[3], p[0], leaf_node[3], leaf_node[0], vertex_list[3]); + if (edgeTable[cubeindex] & 16) + interpolateEdge (p[4], p[5], leaf_node[4], leaf_node[5], vertex_list[4]); + if (edgeTable[cubeindex] & 32) + interpolateEdge (p[5], p[6], leaf_node[5], leaf_node[6], vertex_list[5]); + if (edgeTable[cubeindex] & 64) + interpolateEdge (p[6], p[7], leaf_node[6], leaf_node[7], vertex_list[6]); + if (edgeTable[cubeindex] & 128) + interpolateEdge (p[7], p[4], leaf_node[7], leaf_node[4], vertex_list[7]); + if (edgeTable[cubeindex] & 256) + interpolateEdge (p[0], p[4], leaf_node[0], leaf_node[4], vertex_list[8]); + if (edgeTable[cubeindex] & 512) + interpolateEdge (p[1], p[5], leaf_node[1], leaf_node[5], vertex_list[9]); + if (edgeTable[cubeindex] & 1024) + interpolateEdge (p[2], p[6], leaf_node[2], leaf_node[6], vertex_list[10]); + if (edgeTable[cubeindex] & 2048) + interpolateEdge (p[3], p[7], leaf_node[3], leaf_node[7], vertex_list[11]); + + // Create the triangle + for (int i = 0; triTable[cubeindex][i] != -1; i+=3) + { + PointNT p1,p2,p3; + p1.x = vertex_list[triTable[cubeindex][i ]][0]; + p1.y = vertex_list[triTable[cubeindex][i ]][1]; + p1.z = vertex_list[triTable[cubeindex][i ]][2]; + cloud.push_back (p1); + p2.x = vertex_list[triTable[cubeindex][i+1]][0]; + p2.y = vertex_list[triTable[cubeindex][i+1]][1]; + p2.z = vertex_list[triTable[cubeindex][i+1]][2]; + cloud.push_back (p2); + p3.x = vertex_list[triTable[cubeindex][i+2]][0]; + p3.y = vertex_list[triTable[cubeindex][i+2]][1]; + p3.z = vertex_list[triTable[cubeindex][i+2]][2]; + cloud.push_back (p3); + } +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MarchingCubes::getNeighborList1D (std::vector &leaf, + Eigen::Vector3i &index3d) +{ + leaf = std::vector (8, 0.0f); + + leaf[0] = getGridValue (index3d); + leaf[1] = getGridValue (index3d + Eigen::Vector3i (1, 0, 0)); + leaf[2] = getGridValue (index3d + Eigen::Vector3i (1, 0, 1)); + leaf[3] = getGridValue (index3d + Eigen::Vector3i (0, 0, 1)); + leaf[4] = getGridValue (index3d + Eigen::Vector3i (0, 1, 0)); + leaf[5] = getGridValue (index3d + Eigen::Vector3i (1, 1, 0)); + leaf[6] = getGridValue (index3d + Eigen::Vector3i (1, 1, 1)); + leaf[7] = getGridValue (index3d + Eigen::Vector3i (0, 1, 1)); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::MarchingCubes::getGridValue (Eigen::Vector3i pos) +{ + /// TODO what to return? + if (pos[0] < 0 || pos[0] >= res_x_) + return -1.0f; + if (pos[1] < 0 || pos[1] >= res_y_) + return -1.0f; + if (pos[2] < 0 || pos[2] >= res_z_) + return -1.0f; + + return grid_[pos[0]*res_y_*res_z_ + pos[1]*res_z_ + pos[2]]; +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MarchingCubes::performReconstruction (pcl::PolygonMesh &output) +{ + if (!(iso_level_ >= 0 && iso_level_ < 1)) + { + PCL_ERROR ("[pcl::%s::performReconstruction] Invalid iso level %f! Please use a number between 0 and 1.\n", getClassName ().c_str (), iso_level_); + output.cloud.width = output.cloud.height = 0; + output.cloud.data.clear (); + output.polygons.clear (); + return; + } + + // Create grid + grid_ = std::vector (res_x_*res_y_*res_z_, 0.0f); + + // Populate tree + tree_->setInputCloud (input_); + + getBoundingBox (); + + // Transform the point cloud into a voxel grid + // This needs to be implemented in a child class + voxelizeData (); + + + + // Run the actual marching cubes algorithm, store it into a point cloud, + // and copy the point cloud + connectivity into output + pcl::PointCloud cloud; + + for (int x = 1; x < res_x_-1; ++x) + for (int y = 1; y < res_y_-1; ++y) + for (int z = 1; z < res_z_-1; ++z) + { + Eigen::Vector3i index_3d (x, y, z); + std::vector leaf_node; + getNeighborList1D (leaf_node, index_3d); + createSurface (leaf_node, index_3d, cloud); + } + pcl::toPCLPointCloud2 (cloud, output.cloud); + + output.polygons.resize (cloud.size () / 3); + for (size_t i = 0; i < output.polygons.size (); ++i) + { + pcl::Vertices v; + v.vertices.resize (3); + for (int j = 0; j < 3; ++j) + v.vertices[j] = static_cast (i) * 3 + j; + output.polygons[i] = v; + } +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MarchingCubes::performReconstruction (pcl::PointCloud &points, + std::vector &polygons) +{ + if (!(iso_level_ >= 0 && iso_level_ < 1)) + { + PCL_ERROR ("[pcl::%s::performReconstruction] Invalid iso level %f! Please use a number between 0 and 1.\n", getClassName ().c_str (), iso_level_); + points.width = points.height = 0; + points.points.clear (); + polygons.clear (); + return; + } + + // Create grid + grid_ = std::vector (res_x_*res_y_*res_z_, 0.0f); + + // Populate tree + tree_->setInputCloud (input_); + + getBoundingBox (); + + // Transform the point cloud into a voxel grid + // This needs to be implemented in a child class + voxelizeData (); + + // Run the actual marching cubes algorithm, store it into a point cloud, + // and copy the point cloud + connectivity into output + points.clear (); + for (int x = 1; x < res_x_-1; ++x) + for (int y = 1; y < res_y_-1; ++y) + for (int z = 1; z < res_z_-1; ++z) + { + Eigen::Vector3i index_3d (x, y, z); + std::vector leaf_node; + getNeighborList1D (leaf_node, index_3d); + createSurface (leaf_node, index_3d, points); + } + + polygons.resize (points.size () / 3); + for (size_t i = 0; i < polygons.size (); ++i) + { + pcl::Vertices v; + v.vertices.resize (3); + for (int j = 0; j < 3; ++j) + v.vertices[j] = static_cast (i) * 3 + j; + polygons[i] = v; + } +} + + + +#define PCL_INSTANTIATE_MarchingCubes(T) template class PCL_EXPORTS pcl::MarchingCubes; + +#endif // PCL_SURFACE_IMPL_MARCHING_CUBES_H_ + diff --git a/pcl-1.7/pcl/surface/impl/marching_cubes_hoppe.hpp b/pcl-1.7/pcl/surface/impl/marching_cubes_hoppe.hpp new file mode 100644 index 0000000..7e4b4b5 --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/marching_cubes_hoppe.hpp @@ -0,0 +1,90 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SURFACE_IMPL_MARCHING_CUBES_HOPPE_H_ +#define PCL_SURFACE_IMPL_MARCHING_CUBES_HOPPE_H_ + +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::MarchingCubesHoppe::MarchingCubesHoppe () + : MarchingCubes () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::MarchingCubesHoppe::~MarchingCubesHoppe () +{ +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MarchingCubesHoppe::voxelizeData () +{ + for (int x = 0; x < res_x_; ++x) + for (int y = 0; y < res_y_; ++y) + for (int z = 0; z < res_z_; ++z) + { + std::vector nn_indices; + std::vector nn_sqr_dists; + + Eigen::Vector3f point; + point[0] = min_p_[0] + (max_p_[0] - min_p_[0]) * float (x) / float (res_x_); + point[1] = min_p_[1] + (max_p_[1] - min_p_[1]) * float (y) / float (res_y_); + point[2] = min_p_[2] + (max_p_[2] - min_p_[2]) * float (z) / float (res_z_); + + PointNT p; + p.getVector3fMap () = point; + + tree_->nearestKSearch (p, 1, nn_indices, nn_sqr_dists); + + grid_[x * res_y_*res_z_ + y * res_z_ + z] = input_->points[nn_indices[0]].getNormalVector3fMap ().dot ( + point - input_->points[nn_indices[0]].getVector3fMap ()); + } +} + + + +#define PCL_INSTANTIATE_MarchingCubesHoppe(T) template class PCL_EXPORTS pcl::MarchingCubesHoppe; + +#endif // PCL_SURFACE_IMPL_MARCHING_CUBES_HOPPE_H_ + diff --git a/pcl-1.7/pcl/surface/impl/marching_cubes_rbf.hpp b/pcl-1.7/pcl/surface/impl/marching_cubes_rbf.hpp new file mode 100644 index 0000000..4f52ca5 --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/marching_cubes_rbf.hpp @@ -0,0 +1,132 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SURFACE_IMPL_MARCHING_CUBES_RBF_H_ +#define PCL_SURFACE_IMPL_MARCHING_CUBES_RBF_H_ + +#include +#include +#include +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::MarchingCubesRBF::MarchingCubesRBF () + : MarchingCubes (), + off_surface_epsilon_ (0.1f) +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::MarchingCubesRBF::~MarchingCubesRBF () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MarchingCubesRBF::voxelizeData () +{ + // Initialize data structures + unsigned int N = static_cast (input_->size ()); + Eigen::MatrixXd M (2*N, 2*N), + d (2*N, 1); + + for (unsigned int row_i = 0; row_i < 2*N; ++row_i) + { + // boolean variable to determine whether we are in the off_surface domain for the rows + bool row_off = (row_i >= N) ? 1 : 0; + for (unsigned int col_i = 0; col_i < 2*N; ++col_i) + { + // boolean variable to determine whether we are in the off_surface domain for the columns + bool col_off = (col_i >= N) ? 1 : 0; + M (row_i, col_i) = kernel (Eigen::Vector3f (input_->points[col_i%N].getVector3fMap ()).cast () + Eigen::Vector3f (input_->points[col_i%N].getNormalVector3fMap ()).cast () * col_off * off_surface_epsilon_, + Eigen::Vector3f (input_->points[row_i%N].getVector3fMap ()).cast () + Eigen::Vector3f (input_->points[row_i%N].getNormalVector3fMap ()).cast () * row_off * off_surface_epsilon_); + } + + d (row_i, 0) = row_off * off_surface_epsilon_; + } + + // Solve for the weights + Eigen::MatrixXd w (2*N, 1); + + // Solve_linear_system (M, d, w); + w = M.fullPivLu ().solve (d); + + std::vector weights (2*N); + std::vector centers (2*N); + for (unsigned int i = 0; i < N; ++i) + { + centers[i] = Eigen::Vector3f (input_->points[i].getVector3fMap ()).cast (); + centers[i + N] = Eigen::Vector3f (input_->points[i].getVector3fMap ()).cast () + Eigen::Vector3f (input_->points[i].getNormalVector3fMap ()).cast () * off_surface_epsilon_; + weights[i] = w (i, 0); + weights[i + N] = w (i + N, 0); + } + + for (int x = 0; x < res_x_; ++x) + for (int y = 0; y < res_y_; ++y) + for (int z = 0; z < res_z_; ++z) + { + Eigen::Vector3d point; + point[0] = min_p_[0] + (max_p_[0] - min_p_[0]) * float (x) / float (res_x_); + point[1] = min_p_[1] + (max_p_[1] - min_p_[1]) * float (y) / float (res_y_); + point[2] = min_p_[2] + (max_p_[2] - min_p_[2]) * float (z) / float (res_z_); + + double f = 0.0; + std::vector::const_iterator w_it (weights.begin()); + for (std::vector::const_iterator c_it = centers.begin (); + c_it != centers.end (); ++c_it, ++w_it) + f += *w_it * kernel (*c_it, point); + + grid_[x * res_y_*res_z_ + y * res_z_ + z] = float (f); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template double +pcl::MarchingCubesRBF::kernel (Eigen::Vector3d c, Eigen::Vector3d x) +{ + double r = (x - c).norm (); + return (r * r * r); +} + +#define PCL_INSTANTIATE_MarchingCubesRBF(T) template class PCL_EXPORTS pcl::MarchingCubesRBF; + +#endif // PCL_SURFACE_IMPL_MARCHING_CUBES_HOPPE_H_ + diff --git a/pcl-1.7/pcl/surface/impl/mls.hpp b/pcl-1.7/pcl/surface/impl/mls.hpp new file mode 100644 index 0000000..374dc24 --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/mls.hpp @@ -0,0 +1,786 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SURFACE_IMPL_MLS_H_ +#define PCL_SURFACE_IMPL_MLS_H_ + +#include +#include +#include +#include +#include +#include +#include + +#ifdef _OPENMP +#include +#endif + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MovingLeastSquares::process (PointCloudOut &output) +{ + // Reset or initialize the collection of indices + corresponding_input_indices_.reset (new PointIndices); + + // Check if normals have to be computed/saved + if (compute_normals_) + { + normals_.reset (new NormalCloud); + // Copy the header + normals_->header = input_->header; + // Clear the fields in case the method exits before computation + normals_->width = normals_->height = 0; + normals_->points.clear (); + } + + + // Copy the header + output.header = input_->header; + output.width = output.height = 0; + output.points.clear (); + + if (search_radius_ <= 0 || sqr_gauss_param_ <= 0) + { + PCL_ERROR ("[pcl::%s::process] Invalid search radius (%f) or Gaussian parameter (%f)!\n", getClassName ().c_str (), search_radius_, sqr_gauss_param_); + return; + } + + // Check if distinct_cloud_ was set + if (upsample_method_ == DISTINCT_CLOUD && !distinct_cloud_) + { + PCL_ERROR ("[pcl::%s::process] Upsample method was set to DISTINCT_CLOUD, but no distinct cloud was specified.\n", getClassName ().c_str ()); + return; + } + + if (!initCompute ()) + return; + + + // Initialize the spatial locator + if (!tree_) + { + KdTreePtr tree; + if (input_->isOrganized ()) + tree.reset (new pcl::search::OrganizedNeighbor ()); + else + tree.reset (new pcl::search::KdTree (false)); + setSearchMethod (tree); + } + + // Send the surface dataset to the spatial locator + tree_->setInputCloud (input_); + + switch (upsample_method_) + { + // Initialize random number generator if necessary + case (RANDOM_UNIFORM_DENSITY): + { + rng_alg_.seed (static_cast (std::time (0))); + float tmp = static_cast (search_radius_ / 2.0f); + boost::uniform_real uniform_distrib (-tmp, tmp); + rng_uniform_distribution_.reset (new boost::variate_generator > (rng_alg_, uniform_distrib)); + + mls_results_.resize (1); // Need to have a reference to a single dummy result. + + break; + } + case (VOXEL_GRID_DILATION): + case (DISTINCT_CLOUD): + { + mls_results_.resize (input_->size ()); + break; + } + default: + { + mls_results_.resize (1); // Need to have a reference to a single dummy result. + break; + } + } + + // Perform the actual surface reconstruction + performProcessing (output); + + if (compute_normals_) + { + normals_->height = 1; + normals_->width = static_cast (normals_->size ()); + + for (unsigned int i = 0; i < output.size (); ++i) + { + typedef typename pcl::traits::fieldList::type FieldList; + pcl::for_each_type (SetIfFieldExists (output.points[i], "normal_x", normals_->points[i].normal_x)); + pcl::for_each_type (SetIfFieldExists (output.points[i], "normal_y", normals_->points[i].normal_y)); + pcl::for_each_type (SetIfFieldExists (output.points[i], "normal_z", normals_->points[i].normal_z)); + pcl::for_each_type (SetIfFieldExists (output.points[i], "curvature", normals_->points[i].curvature)); + } + + } + + // Set proper widths and heights for the clouds + output.height = 1; + output.width = static_cast (output.size ()); + + deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MovingLeastSquares::computeMLSPointNormal (int index, + const std::vector &nn_indices, + std::vector &nn_sqr_dists, + PointCloudOut &projected_points, + NormalCloud &projected_points_normals, + PointIndices &corresponding_input_indices, + MLSResult &mls_result) const +{ + // Note: this method is const because it needs to be thread-safe + // (MovingLeastSquaresOMP calls it from multiple threads) + + // Compute the plane coefficients + EIGEN_ALIGN16 Eigen::Matrix3d covariance_matrix; + Eigen::Vector4d xyz_centroid; + + // Estimate the XYZ centroid + pcl::compute3DCentroid (*input_, nn_indices, xyz_centroid); + + // Compute the 3x3 covariance matrix + pcl::computeCovarianceMatrix (*input_, nn_indices, xyz_centroid, covariance_matrix); + EIGEN_ALIGN16 Eigen::Vector3d::Scalar eigen_value; + EIGEN_ALIGN16 Eigen::Vector3d eigen_vector; + Eigen::Vector4d model_coefficients; + pcl::eigen33 (covariance_matrix, eigen_value, eigen_vector); + model_coefficients.head<3> ().matrix () = eigen_vector; + model_coefficients[3] = 0; + model_coefficients[3] = -1 * model_coefficients.dot (xyz_centroid); + + // Projected query point + Eigen::Vector3d point = input_->points[index].getVector3fMap ().template cast (); + double distance = point.dot (model_coefficients.head<3> ()) + model_coefficients[3]; + point -= distance * model_coefficients.head<3> (); + + float curvature = static_cast (covariance_matrix.trace ()); + // Compute the curvature surface change + if (curvature != 0) + curvature = fabsf (float (eigen_value / double (curvature))); + + + // Get a copy of the plane normal easy access + Eigen::Vector3d plane_normal = model_coefficients.head<3> (); + // Vector in which the polynomial coefficients will be put + Eigen::VectorXd c_vec; + // Local coordinate system (Darboux frame) + Eigen::Vector3d v_axis (0.0f, 0.0f, 0.0f), u_axis (0.0f, 0.0f, 0.0f); + + + + // Perform polynomial fit to update point and normal + //////////////////////////////////////////////////// + if (polynomial_fit_ && static_cast (nn_indices.size ()) >= nr_coeff_) + { + // Update neighborhood, since point was projected, and computing relative + // positions. Note updating only distances for the weights for speed + std::vector de_meaned (nn_indices.size ()); + for (size_t ni = 0; ni < nn_indices.size (); ++ni) + { + de_meaned[ni][0] = input_->points[nn_indices[ni]].x - point[0]; + de_meaned[ni][1] = input_->points[nn_indices[ni]].y - point[1]; + de_meaned[ni][2] = input_->points[nn_indices[ni]].z - point[2]; + nn_sqr_dists[ni] = static_cast (de_meaned[ni].dot (de_meaned[ni])); + } + + // Allocate matrices and vectors to hold the data used for the polynomial fit + Eigen::VectorXd weight_vec (nn_indices.size ()); + Eigen::MatrixXd P (nr_coeff_, nn_indices.size ()); + Eigen::VectorXd f_vec (nn_indices.size ()); + Eigen::MatrixXd P_weight; // size will be (nr_coeff_, nn_indices.size ()); + Eigen::MatrixXd P_weight_Pt (nr_coeff_, nr_coeff_); + + // Get local coordinate system (Darboux frame) + v_axis = plane_normal.unitOrthogonal (); + u_axis = plane_normal.cross (v_axis); + + // Go through neighbors, transform them in the local coordinate system, + // save height and the evaluation of the polynome's terms + double u_coord, v_coord, u_pow, v_pow; + for (size_t ni = 0; ni < nn_indices.size (); ++ni) + { + // (Re-)compute weights + weight_vec (ni) = exp (-nn_sqr_dists[ni] / sqr_gauss_param_); + + // Transforming coordinates + u_coord = de_meaned[ni].dot (u_axis); + v_coord = de_meaned[ni].dot (v_axis); + f_vec (ni) = de_meaned[ni].dot (plane_normal); + + // Compute the polynomial's terms at the current point + int j = 0; + u_pow = 1; + for (int ui = 0; ui <= order_; ++ui) + { + v_pow = 1; + for (int vi = 0; vi <= order_ - ui; ++vi) + { + P (j++, ni) = u_pow * v_pow; + v_pow *= v_coord; + } + u_pow *= u_coord; + } + } + + // Computing coefficients + P_weight = P * weight_vec.asDiagonal (); + P_weight_Pt = P_weight * P.transpose (); + c_vec = P_weight * f_vec; + P_weight_Pt.llt ().solveInPlace (c_vec); + } + + switch (upsample_method_) + { + case (NONE): + { + Eigen::Vector3d normal = plane_normal; + + if (polynomial_fit_ && static_cast (nn_indices.size ()) >= nr_coeff_ && pcl_isfinite (c_vec[0])) + { + point += (c_vec[0] * plane_normal); + + // Compute tangent vectors using the partial derivates evaluated at (0,0) which is c_vec[order_+1] and c_vec[1] + if (compute_normals_) + normal = plane_normal - c_vec[order_ + 1] * u_axis - c_vec[1] * v_axis; + } + + PointOutT aux; + aux.x = static_cast (point[0]); + aux.y = static_cast (point[1]); + aux.z = static_cast (point[2]); + projected_points.push_back (aux); + + if (compute_normals_) + { + pcl::Normal aux_normal; + aux_normal.normal_x = static_cast (normal[0]); + aux_normal.normal_y = static_cast (normal[1]); + aux_normal.normal_z = static_cast (normal[2]); + aux_normal.curvature = curvature; + projected_points_normals.push_back (aux_normal); + corresponding_input_indices.indices.push_back (index); + } + + break; + } + + case (SAMPLE_LOCAL_PLANE): + { + // Uniformly sample a circle around the query point using the radius and step parameters + for (float u_disp = -static_cast (upsampling_radius_); u_disp <= upsampling_radius_; u_disp += static_cast (upsampling_step_)) + for (float v_disp = -static_cast (upsampling_radius_); v_disp <= upsampling_radius_; v_disp += static_cast (upsampling_step_)) + if (u_disp*u_disp + v_disp*v_disp < upsampling_radius_*upsampling_radius_) + { + PointOutT projected_point; + pcl::Normal projected_normal; + projectPointToMLSSurface (u_disp, v_disp, u_axis, v_axis, plane_normal, point, + curvature, c_vec, + static_cast (nn_indices.size ()), + projected_point, projected_normal); + + projected_points.push_back (projected_point); + corresponding_input_indices.indices.push_back (index); + if (compute_normals_) + projected_points_normals.push_back (projected_normal); + } + break; + } + + case (RANDOM_UNIFORM_DENSITY): + { + // Compute the local point density and add more samples if necessary + int num_points_to_add = static_cast (floor (desired_num_points_in_radius_ / 2.0 / static_cast (nn_indices.size ()))); + + // Just add the query point, because the density is good + if (num_points_to_add <= 0) + { + // Just add the current point + Eigen::Vector3d normal = plane_normal; + if (polynomial_fit_ && static_cast (nn_indices.size ()) >= nr_coeff_ && pcl_isfinite (c_vec[0])) + { + // Projection onto MLS surface along Darboux normal to the height at (0,0) + point += (c_vec[0] * plane_normal); + // Compute tangent vectors using the partial derivates evaluated at (0,0) which is c_vec[order_+1] and c_vec[1] + if (compute_normals_) + normal = plane_normal - c_vec[order_ + 1] * u_axis - c_vec[1] * v_axis; + } + PointOutT aux; + aux.x = static_cast (point[0]); + aux.y = static_cast (point[1]); + aux.z = static_cast (point[2]); + projected_points.push_back (aux); + corresponding_input_indices.indices.push_back (index); + + if (compute_normals_) + { + pcl::Normal aux_normal; + aux_normal.normal_x = static_cast (normal[0]); + aux_normal.normal_y = static_cast (normal[1]); + aux_normal.normal_z = static_cast (normal[2]); + aux_normal.curvature = curvature; + projected_points_normals.push_back (aux_normal); + } + } + else + { + // Sample the local plane + for (int num_added = 0; num_added < num_points_to_add;) + { + float u_disp = (*rng_uniform_distribution_) (), + v_disp = (*rng_uniform_distribution_) (); + // Check if inside circle; if not, try another coin flip + if (u_disp * u_disp + v_disp * v_disp > search_radius_ * search_radius_/4) + continue; + + + PointOutT projected_point; + pcl::Normal projected_normal; + projectPointToMLSSurface (u_disp, v_disp, u_axis, v_axis, plane_normal, point, + curvature, c_vec, + static_cast (nn_indices.size ()), + projected_point, projected_normal); + + projected_points.push_back (projected_point); + corresponding_input_indices.indices.push_back (index); + if (compute_normals_) + projected_points_normals.push_back (projected_normal); + + num_added ++; + } + } + break; + } + + case (VOXEL_GRID_DILATION): + case (DISTINCT_CLOUD): + { + // Take all point pairs and sample space between them in a grid-fashion + // \note consider only point pairs with increasing indices + mls_result = MLSResult (point, plane_normal, u_axis, v_axis, c_vec, static_cast (nn_indices.size ()), curvature); + break; + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MovingLeastSquares::projectPointToMLSSurface (float &u_disp, float &v_disp, + Eigen::Vector3d &u, Eigen::Vector3d &v, + Eigen::Vector3d &plane_normal, + Eigen::Vector3d &mean, + float &curvature, + Eigen::VectorXd &c_vec, + int num_neighbors, + PointOutT &result_point, + pcl::Normal &result_normal) const +{ + double n_disp = 0.0f; + double d_u = 0.0f, d_v = 0.0f; + + // HARDCODED 5*nr_coeff_ to guarantee that the computed polynomial had a proper point set basis + if (polynomial_fit_ && num_neighbors >= 5*nr_coeff_ && pcl_isfinite (c_vec[0])) + { + // Compute the displacement along the normal using the fitted polynomial + // and compute the partial derivatives needed for estimating the normal + int j = 0; + float u_pow = 1.0f, v_pow = 1.0f, u_pow_prev = 1.0f, v_pow_prev = 1.0f; + for (int ui = 0; ui <= order_; ++ui) + { + v_pow = 1; + for (int vi = 0; vi <= order_ - ui; ++vi) + { + // Compute displacement along normal + n_disp += u_pow * v_pow * c_vec[j++]; + + // Compute partial derivatives + if (ui >= 1) + d_u += c_vec[j-1] * ui * u_pow_prev * v_pow; + if (vi >= 1) + d_v += c_vec[j-1] * vi * u_pow * v_pow_prev; + + v_pow_prev = v_pow; + v_pow *= v_disp; + } + u_pow_prev = u_pow; + u_pow *= u_disp; + } + } + + result_point.x = static_cast (mean[0] + u[0] * u_disp + v[0] * v_disp + plane_normal[0] * n_disp); + result_point.y = static_cast (mean[1] + u[1] * u_disp + v[1] * v_disp + plane_normal[1] * n_disp); + result_point.z = static_cast (mean[2] + u[2] * u_disp + v[2] * v_disp + plane_normal[2] * n_disp); + + Eigen::Vector3d normal = plane_normal - d_u * u - d_v * v; + normal.normalize (); + + result_normal.normal_x = static_cast (normal[0]); + result_normal.normal_y = static_cast (normal[1]); + result_normal.normal_z = static_cast (normal[2]); + result_normal.curvature = curvature; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MovingLeastSquares::performProcessing (PointCloudOut &output) +{ + // Compute the number of coefficients + nr_coeff_ = (order_ + 1) * (order_ + 2) / 2; + + // Allocate enough space to hold the results of nearest neighbor searches + // \note resize is irrelevant for a radiusSearch (). + std::vector nn_indices; + std::vector nn_sqr_dists; + + size_t mls_result_index = 0; + + // For all points + for (size_t cp = 0; cp < indices_->size (); ++cp) + { + // Get the initial estimates of point positions and their neighborhoods + if (!searchForNeighbors ((*indices_)[cp], nn_indices, nn_sqr_dists)) + continue; + + + // Check the number of nearest neighbors for normal estimation (and later + // for polynomial fit as well) + if (nn_indices.size () < 3) + continue; + + + PointCloudOut projected_points; + NormalCloud projected_points_normals; + // Get a plane approximating the local surface's tangent and project point onto it + int index = (*indices_)[cp]; + + if (upsample_method_ == VOXEL_GRID_DILATION || upsample_method_ == DISTINCT_CLOUD) + mls_result_index = index; // otherwise we give it a dummy location. + + computeMLSPointNormal (index, nn_indices, nn_sqr_dists, projected_points, projected_points_normals, *corresponding_input_indices_, mls_results_[mls_result_index]); + + + // Copy all information from the input cloud to the output points (not doing any interpolation) + for (size_t pp = 0; pp < projected_points.size (); ++pp) + copyMissingFields (input_->points[(*indices_)[cp]], projected_points[pp]); + + + // Append projected points to output + output.insert (output.end (), projected_points.begin (), projected_points.end ()); + if (compute_normals_) + normals_->insert (normals_->end (), projected_points_normals.begin (), projected_points_normals.end ()); + } + + // Perform the distinct-cloud or voxel-grid upsampling + performUpsampling (output); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +#ifdef _OPENMP +template void +pcl::MovingLeastSquaresOMP::performProcessing (PointCloudOut &output) +{ + // Compute the number of coefficients + nr_coeff_ = (order_ + 1) * (order_ + 2) / 2; + + // (Maximum) number of threads + unsigned int threads = threads_ == 0 ? 1 : threads_; + + // Create temporaries for each thread in order to avoid synchronization + typename PointCloudOut::CloudVectorType projected_points (threads); + typename NormalCloud::CloudVectorType projected_points_normals (threads); + std::vector corresponding_input_indices (threads); + + // For all points +#pragma omp parallel for schedule (dynamic,1000) num_threads (threads) + for (int cp = 0; cp < static_cast (indices_->size ()); ++cp) + { + // Allocate enough space to hold the results of nearest neighbor searches + // \note resize is irrelevant for a radiusSearch (). + std::vector nn_indices; + std::vector nn_sqr_dists; + + // Get the initial estimates of point positions and their neighborhoods + if (this->searchForNeighbors ((*indices_)[cp], nn_indices, nn_sqr_dists)) + { + // Check the number of nearest neighbors for normal estimation (and later + // for polynomial fit as well) + if (nn_indices.size () >= 3) + { + // This thread's ID (range 0 to threads-1) + int tn = omp_get_thread_num (); + + // Size of projected points before computeMLSPointNormal () adds points + size_t pp_size = projected_points[tn].size (); + + // Get a plane approximating the local surface's tangent and project point onto it + int index = (*indices_)[cp]; + size_t mls_result_index = 0; + + if (upsample_method_ == VOXEL_GRID_DILATION || upsample_method_ == DISTINCT_CLOUD) + mls_result_index = index; // otherwise we give it a dummy location. + + this->computeMLSPointNormal (index, nn_indices, nn_sqr_dists, projected_points[tn], projected_points_normals[tn], corresponding_input_indices[tn], this->mls_results_[mls_result_index]); + + // Copy all information from the input cloud to the output points (not doing any interpolation) + for (size_t pp = pp_size; pp < projected_points[tn].size (); ++pp) + this->copyMissingFields (input_->points[(*indices_)[cp]], projected_points[tn][pp]); + } + } + } + + + // Combine all threads' results into the output vectors + for (unsigned int tn = 0; tn < threads; ++tn) + { + output.insert (output.end (), projected_points[tn].begin (), projected_points[tn].end ()); + corresponding_input_indices_->indices.insert (corresponding_input_indices_->indices.end (), + corresponding_input_indices[tn].indices.begin (), corresponding_input_indices[tn].indices.end ()); + if (compute_normals_) + normals_->insert (normals_->end (), projected_points_normals[tn].begin (), projected_points_normals[tn].end ()); + } + + // Perform the distinct-cloud or voxel-grid upsampling + this->performUpsampling (output); +} +#endif + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MovingLeastSquares::performUpsampling (PointCloudOut &output) +{ + if (upsample_method_ == DISTINCT_CLOUD) + { + for (size_t dp_i = 0; dp_i < distinct_cloud_->size (); ++dp_i) // dp_i = distinct_point_i + { + // Distinct cloud may have nan points, skip them + if (!pcl_isfinite (distinct_cloud_->points[dp_i].x)) + continue; + + // Get 3D position of point + //Eigen::Vector3f pos = distinct_cloud_->points[dp_i].getVector3fMap (); + std::vector nn_indices; + std::vector nn_dists; + tree_->nearestKSearch (distinct_cloud_->points[dp_i], 1, nn_indices, nn_dists); + int input_index = nn_indices.front (); + + // If the closest point did not have a valid MLS fitting result + // OR if it is too far away from the sampled point + if (mls_results_[input_index].valid == false) + continue; + + Eigen::Vector3d add_point = distinct_cloud_->points[dp_i].getVector3fMap ().template cast (); + + float u_disp = static_cast ((add_point - mls_results_[input_index].mean).dot (mls_results_[input_index].u_axis)), + v_disp = static_cast ((add_point - mls_results_[input_index].mean).dot (mls_results_[input_index].v_axis)); + + PointOutT result_point; + pcl::Normal result_normal; + projectPointToMLSSurface (u_disp, v_disp, + mls_results_[input_index].u_axis, mls_results_[input_index].v_axis, + mls_results_[input_index].plane_normal, + mls_results_[input_index].mean, + mls_results_[input_index].curvature, + mls_results_[input_index].c_vec, + mls_results_[input_index].num_neighbors, + result_point, result_normal); + + // Copy additional point information if available + copyMissingFields (input_->points[input_index], result_point); + + // Store the id of the original point + corresponding_input_indices_->indices.push_back (input_index); + + output.push_back (result_point); + if (compute_normals_) + normals_->push_back (result_normal); + } + } + + // For the voxel grid upsampling method, generate the voxel grid and dilate it + // Then, project the newly obtained points to the MLS surface + if (upsample_method_ == VOXEL_GRID_DILATION) + { + MLSVoxelGrid voxel_grid (input_, indices_, voxel_size_); + for (int iteration = 0; iteration < dilation_iteration_num_; ++iteration) + voxel_grid.dilate (); + + for (typename MLSVoxelGrid::HashMap::iterator m_it = voxel_grid.voxel_grid_.begin (); m_it != voxel_grid.voxel_grid_.end (); ++m_it) + { + // Get 3D position of point + Eigen::Vector3f pos; + voxel_grid.getPosition (m_it->first, pos); + + PointInT p; + p.x = pos[0]; + p.y = pos[1]; + p.z = pos[2]; + + std::vector nn_indices; + std::vector nn_dists; + tree_->nearestKSearch (p, 1, nn_indices, nn_dists); + int input_index = nn_indices.front (); + + // If the closest point did not have a valid MLS fitting result + // OR if it is too far away from the sampled point + if (mls_results_[input_index].valid == false) + continue; + + Eigen::Vector3d add_point = p.getVector3fMap ().template cast (); + float u_disp = static_cast ((add_point - mls_results_[input_index].mean).dot (mls_results_[input_index].u_axis)), + v_disp = static_cast ((add_point - mls_results_[input_index].mean).dot (mls_results_[input_index].v_axis)); + + PointOutT result_point; + pcl::Normal result_normal; + projectPointToMLSSurface (u_disp, v_disp, + mls_results_[input_index].u_axis, mls_results_[input_index].v_axis, + mls_results_[input_index].plane_normal, + mls_results_[input_index].mean, + mls_results_[input_index].curvature, + mls_results_[input_index].c_vec, + mls_results_[input_index].num_neighbors, + result_point, result_normal); + + // Copy additional point information if available + copyMissingFields (input_->points[input_index], result_point); + + // Store the id of the original point + corresponding_input_indices_->indices.push_back (input_index); + + output.push_back (result_point); + + if (compute_normals_) + normals_->push_back (result_normal); + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::MovingLeastSquares::MLSResult::MLSResult (const Eigen::Vector3d &a_mean, + const Eigen::Vector3d &a_plane_normal, + const Eigen::Vector3d &a_u, + const Eigen::Vector3d &a_v, + const Eigen::VectorXd a_c_vec, + const int a_num_neighbors, + const float &a_curvature) : + mean (a_mean), plane_normal (a_plane_normal), u_axis (a_u), v_axis (a_v), c_vec (a_c_vec), num_neighbors (a_num_neighbors), + curvature (a_curvature), valid (true) +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::MovingLeastSquares::MLSVoxelGrid::MLSVoxelGrid (PointCloudInConstPtr& cloud, + IndicesPtr &indices, + float voxel_size) : + voxel_grid_ (), bounding_min_ (), bounding_max_ (), data_size_ (), voxel_size_ (voxel_size) +{ + pcl::getMinMax3D (*cloud, *indices, bounding_min_, bounding_max_); + + Eigen::Vector4f bounding_box_size = bounding_max_ - bounding_min_; + double max_size = (std::max) ((std::max)(bounding_box_size.x (), bounding_box_size.y ()), bounding_box_size.z ()); + // Put initial cloud in voxel grid + data_size_ = static_cast (1.5 * max_size / voxel_size_); + for (unsigned int i = 0; i < indices->size (); ++i) + if (pcl_isfinite (cloud->points[(*indices)[i]].x)) + { + Eigen::Vector3i pos; + getCellIndex (cloud->points[(*indices)[i]].getVector3fMap (), pos); + + uint64_t index_1d; + getIndexIn1D (pos, index_1d); + Leaf leaf; + voxel_grid_[index_1d] = leaf; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MovingLeastSquares::MLSVoxelGrid::dilate () +{ + HashMap new_voxel_grid = voxel_grid_; + for (typename MLSVoxelGrid::HashMap::iterator m_it = voxel_grid_.begin (); m_it != voxel_grid_.end (); ++m_it) + { + Eigen::Vector3i index; + getIndexIn3D (m_it->first, index); + + // Now dilate all of its voxels + for (int x = -1; x <= 1; ++x) + for (int y = -1; y <= 1; ++y) + for (int z = -1; z <= 1; ++z) + if (x != 0 || y != 0 || z != 0) + { + Eigen::Vector3i new_index; + new_index = index + Eigen::Vector3i (x, y, z); + + uint64_t index_1d; + getIndexIn1D (new_index, index_1d); + Leaf leaf; + new_voxel_grid[index_1d] = leaf; + } + } + voxel_grid_ = new_voxel_grid; +} + + +///////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MovingLeastSquares::copyMissingFields (const PointInT &point_in, + PointOutT &point_out) const +{ + PointOutT temp = point_out; + copyPoint (point_in, point_out); + point_out.x = temp.x; + point_out.y = temp.y; + point_out.z = temp.z; +} + + +#define PCL_INSTANTIATE_MovingLeastSquares(T,OutT) template class PCL_EXPORTS pcl::MovingLeastSquares; + +#ifdef _OPENMP +#define PCL_INSTANTIATE_MovingLeastSquaresOMP(T,OutT) template class PCL_EXPORTS pcl::MovingLeastSquaresOMP; +#endif + +#endif // PCL_SURFACE_IMPL_MLS_H_ diff --git a/pcl-1.7/pcl/surface/impl/organized_fast_mesh.hpp b/pcl-1.7/pcl/surface/impl/organized_fast_mesh.hpp new file mode 100644 index 0000000..074b232 --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/organized_fast_mesh.hpp @@ -0,0 +1,283 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Dirk Holz (University of Bonn) + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SURFACE_ORGANIZED_FAST_MESH_HPP_ +#define PCL_SURFACE_ORGANIZED_FAST_MESH_HPP_ + +#include + +///////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedFastMesh::performReconstruction (pcl::PolygonMesh &output) +{ + reconstructPolygons (output.polygons); + + // Get the field names + int x_idx = pcl::getFieldIndex (output.cloud, "x"); + int y_idx = pcl::getFieldIndex (output.cloud, "y"); + int z_idx = pcl::getFieldIndex (output.cloud, "z"); + if (x_idx == -1 || y_idx == -1 || z_idx == -1) + return; + // correct all measurements, + // (running over complete image since some rows and columns are left out + // depending on triangle_pixel_size) + // avoid to do that here (only needed for ASCII mesh file output, e.g., in vtk files + for (unsigned int i = 0; i < input_->points.size (); ++i) + if (!isFinite (input_->points[i])) + resetPointData (i, output, 0.0f, x_idx, y_idx, z_idx); +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedFastMesh::performReconstruction (std::vector &polygons) +{ + reconstructPolygons (polygons); +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedFastMesh::reconstructPolygons (std::vector &polygons) +{ + if (triangulation_type_ == TRIANGLE_RIGHT_CUT) + makeRightCutMesh (polygons); + else if (triangulation_type_ == TRIANGLE_LEFT_CUT) + makeLeftCutMesh (polygons); + else if (triangulation_type_ == TRIANGLE_ADAPTIVE_CUT) + makeAdaptiveCutMesh (polygons); + else if (triangulation_type_ == QUAD_MESH) + makeQuadMesh (polygons); +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedFastMesh::makeQuadMesh (std::vector& polygons) +{ + int last_column = input_->width - triangle_pixel_size_columns_; + int last_row = input_->height - triangle_pixel_size_rows_; + + int i = 0, index_down = 0, index_right = 0, index_down_right = 0, idx = 0; + int y_big_incr = triangle_pixel_size_rows_ * input_->width, + x_big_incr = y_big_incr + triangle_pixel_size_columns_; + // Reserve enough space + polygons.resize (input_->width * input_->height); + + // Go over the rows first + for (int y = 0; y < last_row; y += triangle_pixel_size_rows_) + { + // Initialize a new row + i = y * input_->width; + index_right = i + triangle_pixel_size_columns_; + index_down = i + y_big_incr; + index_down_right = i + x_big_incr; + + // Go over the columns + for (int x = 0; x < last_column; x += triangle_pixel_size_columns_, + i += triangle_pixel_size_columns_, + index_right += triangle_pixel_size_columns_, + index_down += triangle_pixel_size_columns_, + index_down_right += triangle_pixel_size_columns_) + { + if (isValidQuad (i, index_right, index_down_right, index_down)) + if (store_shadowed_faces_ || !isShadowedQuad (i, index_right, index_down_right, index_down)) + addQuad (i, index_right, index_down_right, index_down, idx++, polygons); + } + } + polygons.resize (idx); +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedFastMesh::makeRightCutMesh (std::vector& polygons) +{ + int last_column = input_->width - triangle_pixel_size_columns_; + int last_row = input_->height - triangle_pixel_size_rows_; + + int i = 0, index_down = 0, index_right = 0, index_down_right = 0, idx = 0; + int y_big_incr = triangle_pixel_size_rows_ * input_->width, + x_big_incr = y_big_incr + triangle_pixel_size_columns_; + // Reserve enough space + polygons.resize (input_->width * input_->height * 2); + + // Go over the rows first + for (int y = 0; y < last_row; y += triangle_pixel_size_rows_) + { + // Initialize a new row + i = y * input_->width; + index_right = i + triangle_pixel_size_columns_; + index_down = i + y_big_incr; + index_down_right = i + x_big_incr; + + // Go over the columns + for (int x = 0; x < last_column; x += triangle_pixel_size_columns_, + i += triangle_pixel_size_columns_, + index_right += triangle_pixel_size_columns_, + index_down += triangle_pixel_size_columns_, + index_down_right += triangle_pixel_size_columns_) + { + if (isValidTriangle (i, index_down_right, index_right)) + if (store_shadowed_faces_ || !isShadowedTriangle (i, index_down_right, index_right)) + addTriangle (i, index_down_right, index_right, idx++, polygons); + + if (isValidTriangle (i, index_down, index_down_right)) + if (store_shadowed_faces_ || !isShadowedTriangle (i, index_down, index_down_right)) + addTriangle (i, index_down, index_down_right, idx++, polygons); + } + } + polygons.resize (idx); +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedFastMesh::makeLeftCutMesh (std::vector& polygons) +{ + int last_column = input_->width - triangle_pixel_size_columns_; + int last_row = input_->height - triangle_pixel_size_rows_; + + int i = 0, index_down = 0, index_right = 0, index_down_right = 0, idx = 0; + int y_big_incr = triangle_pixel_size_rows_ * input_->width, + x_big_incr = y_big_incr + triangle_pixel_size_columns_; + // Reserve enough space + polygons.resize (input_->width * input_->height * 2); + + // Go over the rows first + for (int y = 0; y < last_row; y += triangle_pixel_size_rows_) + { + // Initialize a new row + i = y * input_->width; + index_right = i + triangle_pixel_size_columns_; + index_down = i + y_big_incr; + index_down_right = i + x_big_incr; + + // Go over the columns + for (int x = 0; x < last_column; x += triangle_pixel_size_columns_, + i += triangle_pixel_size_columns_, + index_right += triangle_pixel_size_columns_, + index_down += triangle_pixel_size_columns_, + index_down_right += triangle_pixel_size_columns_) + { + if (isValidTriangle (i, index_down, index_right)) + if (store_shadowed_faces_ || !isShadowedTriangle (i, index_down, index_right)) + addTriangle (i, index_down, index_right, idx++, polygons); + + if (isValidTriangle (index_right, index_down, index_down_right)) + if (store_shadowed_faces_ || !isShadowedTriangle (index_right, index_down, index_down_right)) + addTriangle (index_right, index_down, index_down_right, idx++, polygons); + } + } + polygons.resize (idx); +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::OrganizedFastMesh::makeAdaptiveCutMesh (std::vector& polygons) +{ + int last_column = input_->width - triangle_pixel_size_columns_; + int last_row = input_->height - triangle_pixel_size_rows_; + + int i = 0, index_down = 0, index_right = 0, index_down_right = 0, idx = 0; + int y_big_incr = triangle_pixel_size_rows_ * input_->width, + x_big_incr = y_big_incr + triangle_pixel_size_columns_; + // Reserve enough space + polygons.resize (input_->width * input_->height * 2); + + // Go over the rows first + for (int y = 0; y < last_row; y += triangle_pixel_size_rows_) + { + // Initialize a new row + i = y * input_->width; + index_right = i + triangle_pixel_size_columns_; + index_down = i + y_big_incr; + index_down_right = i + x_big_incr; + + // Go over the columns + for (int x = 0; x < last_column; x += triangle_pixel_size_columns_, + i += triangle_pixel_size_columns_, + index_right += triangle_pixel_size_columns_, + index_down += triangle_pixel_size_columns_, + index_down_right += triangle_pixel_size_columns_) + { + const bool right_cut_upper = isValidTriangle (i, index_down_right, index_right); + const bool right_cut_lower = isValidTriangle (i, index_down, index_down_right); + const bool left_cut_upper = isValidTriangle (i, index_down, index_right); + const bool left_cut_lower = isValidTriangle (index_right, index_down, index_down_right); + + if (right_cut_upper && right_cut_lower && left_cut_upper && left_cut_lower) + { + float dist_right_cut = fabsf (input_->points[index_down].z - input_->points[index_right].z); + float dist_left_cut = fabsf (input_->points[i].z - input_->points[index_down_right].z); + if (dist_right_cut >= dist_left_cut) + { + if (store_shadowed_faces_ || !isShadowedTriangle (i, index_down_right, index_right)) + addTriangle (i, index_down_right, index_right, idx++, polygons); + if (store_shadowed_faces_ || !isShadowedTriangle (i, index_down, index_down_right)) + addTriangle (i, index_down, index_down_right, idx++, polygons); + } + else + { + if (store_shadowed_faces_ || !isShadowedTriangle (i, index_down, index_right)) + addTriangle (i, index_down, index_right, idx++, polygons); + if (store_shadowed_faces_ || !isShadowedTriangle (index_right, index_down, index_down_right)) + addTriangle (index_right, index_down, index_down_right, idx++, polygons); + } + } + else + { + if (right_cut_upper) + if (store_shadowed_faces_ || !isShadowedTriangle (i, index_down_right, index_right)) + addTriangle (i, index_down_right, index_right, idx++, polygons); + if (right_cut_lower) + if (store_shadowed_faces_ || !isShadowedTriangle (i, index_down, index_down_right)) + addTriangle (i, index_down, index_down_right, idx++, polygons); + if (left_cut_upper) + if (store_shadowed_faces_ || !isShadowedTriangle (i, index_down, index_right)) + addTriangle (i, index_down, index_right, idx++, polygons); + if (left_cut_lower) + if (store_shadowed_faces_ || !isShadowedTriangle (index_right, index_down, index_down_right)) + addTriangle (index_right, index_down, index_down_right, idx++, polygons); + } + } + } + polygons.resize (idx); +} + +#define PCL_INSTANTIATE_OrganizedFastMesh(T) \ + template class PCL_EXPORTS pcl::OrganizedFastMesh; + +#endif // PCL_SURFACE_ORGANIZED_FAST_MESH_HPP_ diff --git a/pcl-1.7/pcl/surface/impl/poisson.hpp b/pcl-1.7/pcl/surface/impl/poisson.hpp new file mode 100644 index 0000000..97848d3 --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/poisson.hpp @@ -0,0 +1,315 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SURFACE_IMPL_POISSON_H_ +#define PCL_SURFACE_IMPL_POISSON_H_ + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#define MEMORY_ALLOCATOR_BLOCK_SIZE 1<<12 + +#include +#include + +using namespace pcl; + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::Poisson::Poisson () + : depth_ (8) + , min_depth_ (5) + , point_weight_ (4) + , scale_ (1.1f) + , solver_divide_ (8) + , iso_divide_ (8) + , samples_per_node_ (1.0) + , confidence_ (false) + , output_polygons_ (false) + , no_reset_samples_ (false) + , no_clip_tree_ (false) + , manifold_ (true) + , refine_ (3) + , kernel_depth_ (8) + , degree_ (2) + , non_adaptive_weights_ (false) + , show_residual_ (false) + , min_iterations_ (8) + , solver_accuracy_ (1e-3f) +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::Poisson::~Poisson () +{ +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template template void +pcl::Poisson::execute (poisson::CoredVectorMeshData &mesh, + poisson::Point3D ¢er, + float &scale) +{ + pcl::poisson::Real iso_value = 0; + poisson::TreeNodeData::UseIndex = 1; + poisson::Octree tree; + + /// TODO OPENMP stuff + // tree.threads = Threads.value; + center.coords[0] = center.coords[1] = center.coords[2] = 0; + + + if (solver_divide_ < min_depth_) + { + PCL_WARN ("[pcl::Poisson] solver_divide_ must be at least as large as min_depth_: %d >= %d\n", solver_divide_, min_depth_); + solver_divide_ = min_depth_; + } + if (iso_divide_< min_depth_) + { + PCL_WARN ("[pcl::Poisson] iso_divide_ must be at least as large as min_depth_: %d >= %d\n", iso_divide_, min_depth_); + iso_divide_ = min_depth_; + } + + pcl::poisson::TreeOctNode::SetAllocator (MEMORY_ALLOCATOR_BLOCK_SIZE); + + kernel_depth_ = depth_ - 2; + + tree.setBSplineData (depth_, pcl::poisson::Real (1.0 / (1 << depth_)), true); + + tree.maxMemoryUsage = 0; + + + int point_count = tree.setTree (input_, depth_, min_depth_, kernel_depth_, samples_per_node_, + scale_, center, scale, confidence_, point_weight_, !non_adaptive_weights_); + + tree.ClipTree (); + tree.finalize (); + tree.RefineBoundary (iso_divide_); + + PCL_DEBUG ("Input Points: %d\n" , point_count ); + PCL_DEBUG ("Leaves/Nodes: %d/%d\n" , tree.tree.leaves() , tree.tree.nodes() ); + + tree.maxMemoryUsage = 0; + tree.SetLaplacianConstraints (); + + tree.maxMemoryUsage = 0; + tree.LaplacianMatrixIteration (solver_divide_, show_residual_, min_iterations_, solver_accuracy_); + + iso_value = tree.GetIsoValue (); + + tree.GetMCIsoTriangles (iso_value, iso_divide_, &mesh, 0, 1, manifold_, output_polygons_); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::Poisson::performReconstruction (PolygonMesh &output) +{ + poisson::CoredVectorMeshData mesh; + poisson::Point3D center; + float scale = 1.0f; + + switch (degree_) + { + case 1: + { + execute<1> (mesh, center, scale); + break; + } + case 2: + { + execute<2> (mesh, center, scale); + break; + } + case 3: + { + execute<3> (mesh, center, scale); + break; + } + case 4: + { + execute<4> (mesh, center, scale); + break; + } + case 5: + { + execute<5> (mesh, center, scale); + break; + } + default: + { + PCL_ERROR (stderr, "Degree %d not supported\n", degree_); + } + } + + // Write output PolygonMesh + pcl::PointCloud cloud; + cloud.points.resize (int (mesh.outOfCorePointCount () + mesh.inCorePoints.size ())); + poisson::Point3D p; + for (int i = 0; i < int (mesh.inCorePoints.size ()); i++) + { + p = mesh.inCorePoints[i]; + cloud.points[i].x = p.coords[0]*scale+center.coords[0]; + cloud.points[i].y = p.coords[1]*scale+center.coords[1]; + cloud.points[i].z = p.coords[2]*scale+center.coords[2]; + } + for (int i = int (mesh.inCorePoints.size ()); i < int (mesh.outOfCorePointCount () + mesh.inCorePoints.size ()); i++) + { + mesh.nextOutOfCorePoint (p); + cloud.points[i].x = p.coords[0]*scale+center.coords[0]; + cloud.points[i].y = p.coords[1]*scale+center.coords[1]; + cloud.points[i].z = p.coords[2]*scale+center.coords[2]; + } + pcl::toPCLPointCloud2 (cloud, output.cloud); + output.polygons.resize (mesh.polygonCount ()); + + // Write faces + std::vector polygon; + for (int p_i = 0; p_i < mesh.polygonCount (); p_i++) + { + pcl::Vertices v; + mesh.nextPolygon (polygon); + v.vertices.resize (polygon.size ()); + + for (int i = 0; i < static_cast (polygon.size ()); ++i) + if (polygon[i].inCore ) + v.vertices[i] = polygon[i].idx; + else + v.vertices[i] = polygon[i].idx + int (mesh.inCorePoints.size ()); + + output.polygons[p_i] = v; + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::Poisson::performReconstruction (pcl::PointCloud &points, + std::vector &polygons) +{ + poisson::CoredVectorMeshData mesh; + poisson::Point3D center; + float scale = 1.0f; + + switch (degree_) + { + case 1: + { + execute<1> (mesh, center, scale); + break; + } + case 2: + { + execute<2> (mesh, center, scale); + break; + } + case 3: + { + execute<3> (mesh, center, scale); + break; + } + case 4: + { + execute<4> (mesh, center, scale); + break; + } + case 5: + { + execute<5> (mesh, center, scale); + break; + } + default: + { + PCL_ERROR (stderr, "Degree %d not supported\n", degree_); + } + } + + // Write output PolygonMesh + // Write vertices + points.resize (int (mesh.outOfCorePointCount () + mesh.inCorePoints.size ())); + poisson::Point3D p; + for (int i = 0; i < int(mesh.inCorePoints.size ()); i++) + { + p = mesh.inCorePoints[i]; + points.points[i].x = p.coords[0]*scale+center.coords[0]; + points.points[i].y = p.coords[1]*scale+center.coords[1]; + points.points[i].z = p.coords[2]*scale+center.coords[2]; + } + for (int i = int(mesh.inCorePoints.size()); i < int (mesh.outOfCorePointCount() + mesh.inCorePoints.size ()); i++) + { + mesh.nextOutOfCorePoint (p); + points.points[i].x = p.coords[0]*scale+center.coords[0]; + points.points[i].y = p.coords[1]*scale+center.coords[1]; + points.points[i].z = p.coords[2]*scale+center.coords[2]; + } + + polygons.resize (mesh.polygonCount ()); + + // Write faces + std::vector polygon; + for (int p_i = 0; p_i < mesh.polygonCount (); p_i++) + { + pcl::Vertices v; + mesh.nextPolygon (polygon); + v.vertices.resize (polygon.size ()); + + for (int i = 0; i < static_cast (polygon.size ()); ++i) + if (polygon[i].inCore ) + v.vertices[i] = polygon[i].idx; + else + v.vertices[i] = polygon[i].idx + int (mesh.inCorePoints.size ()); + + polygons[p_i] = v; + } +} + + +#define PCL_INSTANTIATE_Poisson(T) template class PCL_EXPORTS pcl::Poisson; + +#endif // PCL_SURFACE_IMPL_POISSON_H_ + diff --git a/pcl-1.7/pcl/surface/impl/processing.hpp b/pcl-1.7/pcl/surface/impl/processing.hpp new file mode 100644 index 0000000..1cdaa82 --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/processing.hpp @@ -0,0 +1,59 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::CloudSurfaceProcessing::process (pcl::PointCloud &output) +{ + // Copy the header + output.header = input_->header; + + if (!initCompute ()) + { + output.width = output.height = 0; + output.points.clear (); + return; + } + + // Perform the actual surface reconstruction + performProcessing (output); + + deinitCompute (); +} diff --git a/pcl-1.7/pcl/surface/impl/reconstruction.hpp b/pcl-1.7/pcl/surface/impl/reconstruction.hpp new file mode 100644 index 0000000..6c35756 --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/reconstruction.hpp @@ -0,0 +1,200 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SURFACE_RECONSTRUCTION_IMPL_H_ +#define PCL_SURFACE_RECONSTRUCTION_IMPL_H_ +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SurfaceReconstruction::reconstruct (pcl::PolygonMesh &output) +{ + // Copy the header + output.header = input_->header; + + if (!initCompute ()) + { + output.cloud.width = output.cloud.height = 0; + output.cloud.data.clear (); + output.polygons.clear (); + return; + } + + // Check if a space search locator was given + if (check_tree_) + { + if (!tree_) + { + if (input_->isOrganized ()) + tree_.reset (new pcl::search::OrganizedNeighbor ()); + else + tree_.reset (new pcl::search::KdTree (false)); + } + + // Send the surface dataset to the spatial locator + tree_->setInputCloud (input_, indices_); + } + + // Set up the output dataset + pcl::toPCLPointCloud2 (*input_, output.cloud); /// NOTE: passing in boost shared pointer with * as const& should be OK here + output.polygons.clear (); + output.polygons.reserve (2*indices_->size ()); /// NOTE: usually the number of triangles is around twice the number of vertices + // Perform the actual surface reconstruction + performReconstruction (output); + + deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SurfaceReconstruction::reconstruct (pcl::PointCloud &points, + std::vector &polygons) +{ + // Copy the header + points.header = input_->header; + + if (!initCompute ()) + { + points.width = points.height = 0; + points.clear (); + polygons.clear (); + return; + } + + // Check if a space search locator was given + if (check_tree_) + { + if (!tree_) + { + if (input_->isOrganized ()) + tree_.reset (new pcl::search::OrganizedNeighbor ()); + else + tree_.reset (new pcl::search::KdTree (false)); + } + + // Send the surface dataset to the spatial locator + tree_->setInputCloud (input_, indices_); + } + + // Set up the output dataset + polygons.clear (); + polygons.reserve (2 * indices_->size ()); /// NOTE: usually the number of triangles is around twice the number of vertices + // Perform the actual surface reconstruction + performReconstruction (points, polygons); + + deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MeshConstruction::reconstruct (pcl::PolygonMesh &output) +{ + // Copy the header + output.header = input_->header; + + if (!initCompute ()) + { + output.cloud.width = output.cloud.height = 1; + output.cloud.data.clear (); + output.polygons.clear (); + return; + } + + // Check if a space search locator was given + if (check_tree_) + { + if (!tree_) + { + if (input_->isOrganized ()) + tree_.reset (new pcl::search::OrganizedNeighbor ()); + else + tree_.reset (new pcl::search::KdTree (false)); + } + + // Send the surface dataset to the spatial locator + tree_->setInputCloud (input_, indices_); + } + + // Set up the output dataset + pcl::toPCLPointCloud2 (*input_, output.cloud); /// NOTE: passing in boost shared pointer with * as const& should be OK here + // output.polygons.clear (); + // output.polygons.reserve (2*indices_->size ()); /// NOTE: usually the number of triangles is around twice the number of vertices + // Perform the actual surface reconstruction + performReconstruction (output); + + deinitCompute (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::MeshConstruction::reconstruct (std::vector &polygons) +{ + if (!initCompute ()) + { + polygons.clear (); + return; + } + + // Check if a space search locator was given + if (check_tree_) + { + if (!tree_) + { + if (input_->isOrganized ()) + tree_.reset (new pcl::search::OrganizedNeighbor ()); + else + tree_.reset (new pcl::search::KdTree (false)); + } + + // Send the surface dataset to the spatial locator + tree_->setInputCloud (input_, indices_); + } + + // Set up the output dataset + //polygons.clear (); + //polygons.reserve (2 * indices_->size ()); /// NOTE: usually the number of triangles is around twice the number of vertices + // Perform the actual surface reconstruction + performReconstruction (polygons); + + deinitCompute (); +} + + +#endif // PCL_SURFACE_RECONSTRUCTION_IMPL_H_ + diff --git a/pcl-1.7/pcl/surface/impl/surfel_smoothing.hpp b/pcl-1.7/pcl/surface/impl/surfel_smoothing.hpp new file mode 100644 index 0000000..77bc74e --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/surfel_smoothing.hpp @@ -0,0 +1,317 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Willow Garage, Inc + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_SURFACE_IMPL_SURFEL_SMOOTHING_H_ +#define PCL_SURFACE_IMPL_SURFEL_SMOOTHING_H_ + +#include +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::SurfelSmoothing::initCompute () +{ + if (!PCLBase::initCompute ()) + return false; + + if (!normals_) + { + PCL_ERROR ("SurfelSmoothing: normal cloud not set\n"); + return false; + } + + if (input_->points.size () != normals_->points.size ()) + { + PCL_ERROR ("SurfelSmoothing: number of input points different from the number of given normals\n"); + return false; + } + + // Initialize the spatial locator + if (!tree_) + { + if (input_->isOrganized ()) + tree_.reset (new pcl::search::OrganizedNeighbor ()); + else + tree_.reset (new pcl::search::KdTree (false)); + } + + // create internal copies of the input - these will be modified + interm_cloud_ = PointCloudInPtr (new PointCloudIn (*input_)); + interm_normals_ = NormalCloudPtr (new NormalCloud (*normals_)); + + return (true); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template float +pcl::SurfelSmoothing::smoothCloudIteration (PointCloudInPtr &output_positions, + NormalCloudPtr &output_normals) +{ +// PCL_INFO ("SurfelSmoothing: cloud smoothing iteration starting ...\n"); + + output_positions = PointCloudInPtr (new PointCloudIn); + output_positions->points.resize (interm_cloud_->points.size ()); + output_normals = NormalCloudPtr (new NormalCloud); + output_normals->points.resize (interm_cloud_->points.size ()); + + std::vector nn_indices; + std::vector nn_distances; + + std::vector diffs (interm_cloud_->points.size ()); + float total_residual = 0.0f; + + for (size_t i = 0; i < interm_cloud_->points.size (); ++i) + { + Eigen::Vector4f smoothed_point = Eigen::Vector4f::Zero (); + Eigen::Vector4f smoothed_normal = Eigen::Vector4f::Zero (); + + // get neighbors + // @todo using 5x the scale for searching instead of all the points to avoid O(N^2) + tree_->radiusSearch (interm_cloud_->points[i], 5*scale_, nn_indices, nn_distances); + + float theta_normalization_factor = 0.0; + std::vector theta (nn_indices.size ()); + for (size_t nn_index_i = 0; nn_index_i < nn_indices.size (); ++nn_index_i) + { + float dist = pcl::squaredEuclideanDistance (interm_cloud_->points[i], input_->points[nn_indices[nn_index_i]]);//interm_cloud_->points[nn_indices[nn_index_i]]); + float theta_i = expf ( (-1) * dist / scale_squared_); + theta_normalization_factor += theta_i; + + smoothed_normal += theta_i * interm_normals_->points[nn_indices[nn_index_i]].getNormalVector4fMap (); + + theta[nn_index_i] = theta_i; + } + + smoothed_normal /= theta_normalization_factor; + smoothed_normal(3) = 0.0f; + smoothed_normal.normalize (); + + + // find minimum along the normal + float e_residual; + smoothed_point = interm_cloud_->points[i].getVector4fMap (); + while (1) + { + e_residual = 0.0f; + smoothed_point(3) = 0.0f; + for (size_t nn_index_i = 0; nn_index_i < nn_indices.size (); ++nn_index_i) + { + Eigen::Vector4f neighbor = input_->points[nn_indices[nn_index_i]].getVector4fMap ();//interm_cloud_->points[nn_indices[nn_index_i]].getVector4fMap (); + neighbor(3) = 0.0f; + float dot_product = smoothed_normal.dot (neighbor - smoothed_point); + e_residual += theta[nn_index_i] * dot_product;// * dot_product; + } + e_residual /= theta_normalization_factor; + if (e_residual < 1e-5) break; + + smoothed_point = smoothed_point + e_residual * smoothed_normal; + } + + total_residual += e_residual; + + output_positions->points[i].getVector4fMap () = smoothed_point; + output_normals->points[i].getNormalVector4fMap () = normals_->points[i].getNormalVector4fMap ();//smoothed_normal; + } + +// std::cerr << "Total residual after iteration: " << total_residual << std::endl; +// PCL_INFO("SurfelSmoothing done iteration\n"); + return total_residual; +} + + +template void +pcl::SurfelSmoothing::smoothPoint (size_t &point_index, + PointT &output_point, + PointNT &output_normal) +{ + Eigen::Vector4f average_normal = Eigen::Vector4f::Zero (); + Eigen::Vector4f result_point = input_->points[point_index].getVector4fMap (); + result_point(3) = 0.0f; + + // @todo parameter + float error_residual_threshold_ = 1e-3f; + float error_residual = error_residual_threshold_ + 1; + float last_error_residual = error_residual + 100.0f; + + std::vector nn_indices; + std::vector nn_distances; + + int big_iterations = 0; + int max_big_iterations = 500; + + while (fabs (error_residual) < fabs (last_error_residual) -error_residual_threshold_ && + big_iterations < max_big_iterations) + { + average_normal = Eigen::Vector4f::Zero (); + big_iterations ++; + PointT aux_point; aux_point.x = result_point(0); aux_point.y = result_point(1); aux_point.z = result_point(2); + tree_->radiusSearch (aux_point, 5*scale_, nn_indices, nn_distances); + + float theta_normalization_factor = 0.0; + std::vector theta (nn_indices.size ()); + for (size_t nn_index_i = 0; nn_index_i < nn_indices.size (); ++nn_index_i) + { + float dist = nn_distances[nn_index_i]; + float theta_i = expf ( (-1) * dist / scale_squared_); + theta_normalization_factor += theta_i; + + average_normal += theta_i * normals_->points[nn_indices[nn_index_i]].getNormalVector4fMap (); + theta[nn_index_i] = theta_i; + } + average_normal /= theta_normalization_factor; + average_normal(3) = 0.0f; + average_normal.normalize (); + + // find minimum along the normal + float e_residual_along_normal = 2, last_e_residual_along_normal = 3; + int small_iterations = 0; + int max_small_iterations = 10; + while ( fabs (e_residual_along_normal) < fabs (last_e_residual_along_normal) && + small_iterations < max_small_iterations) + { + small_iterations ++; + + e_residual_along_normal = 0.0f; + for (size_t nn_index_i = 0; nn_index_i < nn_indices.size (); ++nn_index_i) + { + Eigen::Vector4f neighbor = input_->points[nn_indices[nn_index_i]].getVector4fMap (); + neighbor(3) = 0.0f; + float dot_product = average_normal.dot (neighbor - result_point); + e_residual_along_normal += theta[nn_index_i] * dot_product; + } + e_residual_along_normal /= theta_normalization_factor; + if (e_residual_along_normal < 1e-3) break; + + result_point = result_point + e_residual_along_normal * average_normal; + } + +// if (small_iterations == max_small_iterations) +// PCL_INFO ("passed the number of small iterations %d\n", small_iterations); + + last_error_residual = error_residual; + error_residual = e_residual_along_normal; + +// PCL_INFO ("last %f current %f\n", last_error_residual, error_residual); + } + + output_point.x = result_point(0); + output_point.y = result_point(1); + output_point.z = result_point(2); + output_normal = normals_->points[point_index]; + + if (big_iterations == max_big_iterations) + PCL_DEBUG ("[pcl::SurfelSmoothing::smoothPoint] Passed the number of BIG iterations: %d\n", big_iterations); +} + + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SurfelSmoothing::computeSmoothedCloud (PointCloudInPtr &output_positions, + NormalCloudPtr &output_normals) +{ + if (!initCompute ()) + { + PCL_ERROR ("[pcl::SurfelSmoothing::computeSmoothedCloud]: SurfelSmoothing not initialized properly, skipping computeSmoothedCloud ().\n"); + return; + } + + tree_->setInputCloud (input_); + + output_positions->header = input_->header; + output_positions->height = input_->height; + output_positions->width = input_->width; + + output_normals->header = input_->header; + output_normals->height = input_->height; + output_normals->width = input_->width; + + output_positions->points.resize (input_->points.size ()); + output_normals->points.resize (input_->points.size ()); + for (size_t i = 0; i < input_->points.size (); ++i) + { + smoothPoint (i, output_positions->points[i], output_normals->points[i]); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SurfelSmoothing::extractSalientFeaturesBetweenScales (PointCloudInPtr &cloud2, + NormalCloudPtr &cloud2_normals, + boost::shared_ptr > &output_features) +{ + if (interm_cloud_->points.size () != cloud2->points.size () || + cloud2->points.size () != cloud2_normals->points.size ()) + { + PCL_ERROR ("[pcl::SurfelSmoothing::extractSalientFeaturesBetweenScales]: Number of points in the clouds does not match.\n"); + return; + } + + std::vector diffs (cloud2->points.size ()); + for (size_t i = 0; i < cloud2->points.size (); ++i) + diffs[i] = cloud2_normals->points[i].getNormalVector4fMap ().dot (cloud2->points[i].getVector4fMap () - + interm_cloud_->points[i].getVector4fMap ()); + + std::vector nn_indices; + std::vector nn_distances; + + output_features->resize (cloud2->points.size ()); + for (int point_i = 0; point_i < static_cast (cloud2->points.size ()); ++point_i) + { + // Get neighbors + tree_->radiusSearch (point_i, scale_, nn_indices, nn_distances); + + bool largest = true; + bool smallest = true; + for (std::vector::iterator nn_index_it = nn_indices.begin (); nn_index_it != nn_indices.end (); ++nn_index_it) + { + if (diffs[point_i] < diffs[*nn_index_it]) + largest = false; + else + smallest = false; + } + + if (largest == true || smallest == true) + (*output_features)[point_i] = point_i; + } +} + + + +#define PCL_INSTANTIATE_SurfelSmoothing(PointT,PointNT) template class PCL_EXPORTS pcl::SurfelSmoothing; + +#endif /* PCL_SURFACE_IMPL_SURFEL_SMOOTHING_H_ */ diff --git a/pcl-1.7/pcl/surface/impl/texture_mapping.hpp b/pcl-1.7/pcl/surface/impl/texture_mapping.hpp new file mode 100644 index 0000000..6d8dfff --- /dev/null +++ b/pcl-1.7/pcl/surface/impl/texture_mapping.hpp @@ -0,0 +1,1122 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SURFACE_IMPL_TEXTURE_MAPPING_HPP_ +#define PCL_SURFACE_IMPL_TEXTURE_MAPPING_HPP_ + +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////////// +template std::vector +pcl::TextureMapping::mapTexture2Face ( + const Eigen::Vector3f &p1, + const Eigen::Vector3f &p2, + const Eigen::Vector3f &p3) +{ + std::vector tex_coordinates; + // process for each face + Eigen::Vector3f p1p2 (p2[0] - p1[0], p2[1] - p1[1], p2[2] - p1[2]); + Eigen::Vector3f p1p3 (p3[0] - p1[0], p3[1] - p1[1], p3[2] - p1[2]); + Eigen::Vector3f p2p3 (p3[0] - p2[0], p3[1] - p2[1], p3[2] - p2[2]); + + // Normalize + p1p2 = p1p2 / std::sqrt (p1p2.dot (p1p2)); + p1p3 = p1p3 / std::sqrt (p1p3.dot (p1p3)); + p2p3 = p2p3 / std::sqrt (p2p3.dot (p2p3)); + + // compute vector normal of a face + Eigen::Vector3f f_normal = p1p2.cross (p1p3); + f_normal = f_normal / std::sqrt (f_normal.dot (f_normal)); + + // project vector field onto the face: vector v1_projected = v1 - Dot(v1, n) * n; + Eigen::Vector3f f_vector_field = vector_field_ - vector_field_.dot (f_normal) * f_normal; + + // Normalize + f_vector_field = f_vector_field / std::sqrt (f_vector_field.dot (f_vector_field)); + + // texture coordinates + Eigen::Vector2f tp1, tp2, tp3; + + double alpha = std::acos (f_vector_field.dot (p1p2)); + + // distance between 3 vertices of triangles + double e1 = (p2 - p3).norm () / f_; + double e2 = (p1 - p3).norm () / f_; + double e3 = (p1 - p2).norm () / f_; + + // initialize + tp1[0] = 0.0; + tp1[1] = 0.0; + + tp2[0] = static_cast (e3); + tp2[1] = 0.0; + + // determine texture coordinate tp3; + double cos_p1 = (e2 * e2 + e3 * e3 - e1 * e1) / (2 * e2 * e3); + double sin_p1 = sqrt (1 - (cos_p1 * cos_p1)); + + tp3[0] = static_cast (cos_p1 * e2); + tp3[1] = static_cast (sin_p1 * e2); + + // rotating by alpha (angle between V and pp1 & pp2) + Eigen::Vector2f r_tp2, r_tp3; + r_tp2[0] = static_cast (tp2[0] * std::cos (alpha) - tp2[1] * std::sin (alpha)); + r_tp2[1] = static_cast (tp2[0] * std::sin (alpha) + tp2[1] * std::cos (alpha)); + + r_tp3[0] = static_cast (tp3[0] * std::cos (alpha) - tp3[1] * std::sin (alpha)); + r_tp3[1] = static_cast (tp3[0] * std::sin (alpha) + tp3[1] * std::cos (alpha)); + + // shifting + tp1[0] = tp1[0]; + tp2[0] = r_tp2[0]; + tp3[0] = r_tp3[0]; + tp1[1] = tp1[1]; + tp2[1] = r_tp2[1]; + tp3[1] = r_tp3[1]; + + float min_x = tp1[0]; + float min_y = tp1[1]; + if (min_x > tp2[0]) + min_x = tp2[0]; + if (min_x > tp3[0]) + min_x = tp3[0]; + if (min_y > tp2[1]) + min_y = tp2[1]; + if (min_y > tp3[1]) + min_y = tp3[1]; + + if (min_x < 0) + { + tp1[0] = tp1[0] - min_x; + tp2[0] = tp2[0] - min_x; + tp3[0] = tp3[0] - min_x; + } + if (min_y < 0) + { + tp1[1] = tp1[1] - min_y; + tp2[1] = tp2[1] - min_y; + tp3[1] = tp3[1] - min_y; + } + + tex_coordinates.push_back (tp1); + tex_coordinates.push_back (tp2); + tex_coordinates.push_back (tp3); + return (tex_coordinates); +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::TextureMapping::mapTexture2Mesh (pcl::TextureMesh &tex_mesh) +{ + // mesh information + int nr_points = tex_mesh.cloud.width * tex_mesh.cloud.height; + int point_size = static_cast (tex_mesh.cloud.data.size ()) / nr_points; + + // temporary PointXYZ + float x, y, z; + // temporary face + Eigen::Vector3f facet[3]; + + // texture coordinates for each mesh + std::vector > texture_map; + + for (size_t m = 0; m < tex_mesh.tex_polygons.size (); ++m) + { + // texture coordinates for each mesh + std::vector texture_map_tmp; + + // processing for each face + for (size_t i = 0; i < tex_mesh.tex_polygons[m].size (); ++i) + { + size_t idx; + + // get facet information + for (size_t j = 0; j < tex_mesh.tex_polygons[m][i].vertices.size (); ++j) + { + idx = tex_mesh.tex_polygons[m][i].vertices[j]; + memcpy (&x, &tex_mesh.cloud.data[idx * point_size + tex_mesh.cloud.fields[0].offset], sizeof(float)); + memcpy (&y, &tex_mesh.cloud.data[idx * point_size + tex_mesh.cloud.fields[1].offset], sizeof(float)); + memcpy (&z, &tex_mesh.cloud.data[idx * point_size + tex_mesh.cloud.fields[2].offset], sizeof(float)); + facet[j][0] = x; + facet[j][1] = y; + facet[j][2] = z; + } + + // get texture coordinates of each face + std::vector tex_coordinates = mapTexture2Face (facet[0], facet[1], facet[2]); + for (size_t n = 0; n < tex_coordinates.size (); ++n) + texture_map_tmp.push_back (tex_coordinates[n]); + }// end faces + + // texture materials + std::stringstream tex_name; + tex_name << "material_" << m; + tex_name >> tex_material_.tex_name; + tex_material_.tex_file = tex_files_[m]; + tex_mesh.tex_materials.push_back (tex_material_); + + // texture coordinates + tex_mesh.tex_coordinates.push_back (texture_map_tmp); + }// end meshes +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::TextureMapping::mapTexture2MeshUV (pcl::TextureMesh &tex_mesh) +{ + // mesh information + int nr_points = tex_mesh.cloud.width * tex_mesh.cloud.height; + int point_size = static_cast (tex_mesh.cloud.data.size ()) / nr_points; + + float x_lowest = 100000; + float x_highest = 0; + float y_lowest = 100000; + //float y_highest = 0 ; + float z_lowest = 100000; + float z_highest = 0; + float x_, y_, z_; + + for (int i = 0; i < nr_points; ++i) + { + memcpy (&x_, &tex_mesh.cloud.data[i * point_size + tex_mesh.cloud.fields[0].offset], sizeof(float)); + memcpy (&y_, &tex_mesh.cloud.data[i * point_size + tex_mesh.cloud.fields[1].offset], sizeof(float)); + memcpy (&z_, &tex_mesh.cloud.data[i * point_size + tex_mesh.cloud.fields[2].offset], sizeof(float)); + // x + if (x_ <= x_lowest) + x_lowest = x_; + if (x_ > x_lowest) + x_highest = x_; + + // y + if (y_ <= y_lowest) + y_lowest = y_; + //if (y_ > y_lowest) y_highest = y_; + + // z + if (z_ <= z_lowest) + z_lowest = z_; + if (z_ > z_lowest) + z_highest = z_; + } + // x + float x_range = (x_lowest - x_highest) * -1; + float x_offset = 0 - x_lowest; + // x + // float y_range = (y_lowest - y_highest)*-1; + // float y_offset = 0 - y_lowest; + // z + float z_range = (z_lowest - z_highest) * -1; + float z_offset = 0 - z_lowest; + + // texture coordinates for each mesh + std::vector > texture_map; + + for (size_t m = 0; m < tex_mesh.tex_polygons.size (); ++m) + { + // texture coordinates for each mesh + std::vector texture_map_tmp; + + // processing for each face + for (size_t i = 0; i < tex_mesh.tex_polygons[m].size (); ++i) + { + size_t idx; + Eigen::Vector2f tmp_VT; + for (size_t j = 0; j < tex_mesh.tex_polygons[m][i].vertices.size (); ++j) + { + idx = tex_mesh.tex_polygons[m][i].vertices[j]; + memcpy (&x_, &tex_mesh.cloud.data[idx * point_size + tex_mesh.cloud.fields[0].offset], sizeof(float)); + memcpy (&y_, &tex_mesh.cloud.data[idx * point_size + tex_mesh.cloud.fields[1].offset], sizeof(float)); + memcpy (&z_, &tex_mesh.cloud.data[idx * point_size + tex_mesh.cloud.fields[2].offset], sizeof(float)); + + // calculate uv coordinates + tmp_VT[0] = (x_ + x_offset) / x_range; + tmp_VT[1] = (z_ + z_offset) / z_range; + texture_map_tmp.push_back (tmp_VT); + } + }// end faces + + // texture materials + std::stringstream tex_name; + tex_name << "material_" << m; + tex_name >> tex_material_.tex_name; + tex_material_.tex_file = tex_files_[m]; + tex_mesh.tex_materials.push_back (tex_material_); + + // texture coordinates + tex_mesh.tex_coordinates.push_back (texture_map_tmp); + }// end meshes +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::TextureMapping::mapMultipleTexturesToMeshUV (pcl::TextureMesh &tex_mesh, pcl::texture_mapping::CameraVector &cams) +{ + + if (tex_mesh.tex_polygons.size () != cams.size () + 1) + { + PCL_ERROR ("The mesh should be divided into nbCamera+1 sub-meshes.\n"); + PCL_ERROR ("You provided %d cameras and a mesh containing %d sub-meshes.\n", cams.size (), tex_mesh.tex_polygons.size ()); + return; + } + + PCL_INFO ("You provided %d cameras and a mesh containing %d sub-meshes.\n", cams.size (), tex_mesh.tex_polygons.size ()); + + pcl::PointCloud::Ptr originalCloud (new pcl::PointCloud); + pcl::PointCloud::Ptr camera_transformed_cloud (new pcl::PointCloud); + + // convert mesh's cloud to pcl format for ease + pcl::fromPCLPointCloud2 (tex_mesh.cloud, *originalCloud); + + // texture coordinates for each mesh + std::vector > texture_map; + + for (size_t m = 0; m < cams.size (); ++m) + { + // get current camera parameters + Camera current_cam = cams[m]; + + // get camera transform + Eigen::Affine3f cam_trans = current_cam.pose; + + // transform cloud into current camera frame + pcl::transformPointCloud (*originalCloud, *camera_transformed_cloud, cam_trans.inverse ()); + + // vector of texture coordinates for each face + std::vector texture_map_tmp; + + // processing each face visible by this camera + pcl::PointXYZ pt; + size_t idx; + for (size_t i = 0; i < tex_mesh.tex_polygons[m].size (); ++i) + { + Eigen::Vector2f tmp_VT; + // for each point of this face + for (size_t j = 0; j < tex_mesh.tex_polygons[m][i].vertices.size (); ++j) + { + // get point + idx = tex_mesh.tex_polygons[m][i].vertices[j]; + pt = camera_transformed_cloud->points[idx]; + + // compute UV coordinates for this point + getPointUVCoordinates (pt, current_cam, tmp_VT); + texture_map_tmp.push_back (tmp_VT); + + }// end points + }// end faces + + // texture materials + std::stringstream tex_name; + tex_name << "material_" << m; + tex_name >> tex_material_.tex_name; + tex_material_.tex_file = current_cam.texture_file; + tex_mesh.tex_materials.push_back (tex_material_); + + // texture coordinates + tex_mesh.tex_coordinates.push_back (texture_map_tmp); + }// end cameras + + // push on extra empty UV map (for unseen faces) so that obj writer does not crash! + std::vector texture_map_tmp; + for (size_t i = 0; i < tex_mesh.tex_polygons[cams.size ()].size (); ++i) + for (size_t j = 0; j < tex_mesh.tex_polygons[cams.size ()][i].vertices.size (); ++j) + { + Eigen::Vector2f tmp_VT; + tmp_VT[0] = -1; + tmp_VT[1] = -1; + texture_map_tmp.push_back (tmp_VT); + } + + tex_mesh.tex_coordinates.push_back (texture_map_tmp); + + // push on an extra dummy material for the same reason + std::stringstream tex_name; + tex_name << "material_" << cams.size (); + tex_name >> tex_material_.tex_name; + tex_material_.tex_file = "occluded.jpg"; + tex_mesh.tex_materials.push_back (tex_material_); + +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::TextureMapping::isPointOccluded (const pcl::PointXYZ &pt, OctreePtr octree) +{ + Eigen::Vector3f direction; + direction (0) = pt.x; + direction (1) = pt.y; + direction (2) = pt.z; + + std::vector indices; + + PointCloudConstPtr cloud (new PointCloud()); + cloud = octree->getInputCloud(); + + double distance_threshold = octree->getResolution(); + + // raytrace + octree->getIntersectedVoxelIndices(direction, -direction, indices); + + int nbocc = static_cast (indices.size ()); + for (size_t j = 0; j < indices.size (); j++) + { + // if intersected point is on the over side of the camera + if (pt.z * cloud->points[indices[j]].z < 0) + { + nbocc--; + continue; + } + + if (fabs (cloud->points[indices[j]].z - pt.z) <= distance_threshold) + { + // points are very close to each-other, we do not consider the occlusion + nbocc--; + } + } + + if (nbocc == 0) + return (false); + else + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::TextureMapping::removeOccludedPoints (const PointCloudPtr &input_cloud, + PointCloudPtr &filtered_cloud, + const double octree_voxel_size, std::vector &visible_indices, + std::vector &occluded_indices) +{ + // variable used to filter occluded points by depth + double maxDeltaZ = octree_voxel_size; + + // create an octree to perform rayTracing + OctreePtr octree (new Octree (octree_voxel_size)); + // create octree structure + octree->setInputCloud (input_cloud); + // update bounding box automatically + octree->defineBoundingBox (); + // add points in the tree + octree->addPointsFromInputCloud (); + + visible_indices.clear (); + + // for each point of the cloud, raycast toward camera and check intersected voxels. + Eigen::Vector3f direction; + std::vector indices; + for (size_t i = 0; i < input_cloud->points.size (); ++i) + { + direction (0) = input_cloud->points[i].x; + direction (1) = input_cloud->points[i].y; + direction (2) = input_cloud->points[i].z; + + // if point is not occluded + octree->getIntersectedVoxelIndices (direction, -direction, indices); + + int nbocc = static_cast (indices.size ()); + for (size_t j = 0; j < indices.size (); j++) + { + // if intersected point is on the over side of the camera + if (input_cloud->points[i].z * input_cloud->points[indices[j]].z < 0) + { + nbocc--; + continue; + } + + if (fabs (input_cloud->points[indices[j]].z - input_cloud->points[i].z) <= maxDeltaZ) + { + // points are very close to each-other, we do not consider the occlusion + nbocc--; + } + } + + if (nbocc == 0) + { + // point is added in the filtered mesh + filtered_cloud->points.push_back (input_cloud->points[i]); + visible_indices.push_back (static_cast (i)); + } + else + { + occluded_indices.push_back (static_cast (i)); + } + } + +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::TextureMapping::removeOccludedPoints (const pcl::TextureMesh &tex_mesh, pcl::TextureMesh &cleaned_mesh, const double octree_voxel_size) +{ + // copy mesh + cleaned_mesh = tex_mesh; + + pcl::PointCloud::Ptr cloud (new pcl::PointCloud); + pcl::PointCloud::Ptr filtered_cloud (new pcl::PointCloud); + + // load points into a PCL format + pcl::fromPCLPointCloud2 (tex_mesh.cloud, *cloud); + + std::vector visible, occluded; + removeOccludedPoints (cloud, filtered_cloud, octree_voxel_size, visible, occluded); + + // Now that we know which points are visible, let's iterate over each face. + // if the face has one invisible point => out! + for (size_t polygons = 0; polygons < cleaned_mesh.tex_polygons.size (); ++polygons) + { + // remove all faces from cleaned mesh + cleaned_mesh.tex_polygons[polygons].clear (); + // iterate over faces + for (size_t faces = 0; faces < tex_mesh.tex_polygons[polygons].size (); ++faces) + { + // check if all the face's points are visible + bool faceIsVisible = true; + std::vector::iterator it; + + // iterate over face's vertex + for (size_t points = 0; points < tex_mesh.tex_polygons[polygons][faces].vertices.size (); ++points) + { + it = find (occluded.begin (), occluded.end (), tex_mesh.tex_polygons[polygons][faces].vertices[points]); + + if (it == occluded.end ()) + { + // point is not in the occluded vector + // PCL_INFO (" VISIBLE!\n"); + } + else + { + // point was occluded + // PCL_INFO(" OCCLUDED!\n"); + faceIsVisible = false; + } + } + + if (faceIsVisible) + { + cleaned_mesh.tex_polygons[polygons].push_back (tex_mesh.tex_polygons[polygons][faces]); + } + + } + } +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::TextureMapping::removeOccludedPoints (const pcl::TextureMesh &tex_mesh, PointCloudPtr &filtered_cloud, + const double octree_voxel_size) +{ + PointCloudPtr cloud (new PointCloud); + + // load points into a PCL format + pcl::fromPCLPointCloud2 (tex_mesh.cloud, *cloud); + + std::vector visible, occluded; + removeOccludedPoints (cloud, filtered_cloud, octree_voxel_size, visible, occluded); + +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template int +pcl::TextureMapping::sortFacesByCamera (pcl::TextureMesh &tex_mesh, pcl::TextureMesh &sorted_mesh, + const pcl::texture_mapping::CameraVector &cameras, const double octree_voxel_size, + PointCloud &visible_pts) +{ + if (tex_mesh.tex_polygons.size () != 1) + { + PCL_ERROR ("The mesh must contain only 1 sub-mesh!\n"); + return (-1); + } + + if (cameras.size () == 0) + { + PCL_ERROR ("Must provide at least one camera info!\n"); + return (-1); + } + + // copy mesh + sorted_mesh = tex_mesh; + // clear polygons from cleaned_mesh + sorted_mesh.tex_polygons.clear (); + + pcl::PointCloud::Ptr original_cloud (new pcl::PointCloud); + pcl::PointCloud::Ptr transformed_cloud (new pcl::PointCloud); + pcl::PointCloud::Ptr filtered_cloud (new pcl::PointCloud); + + // load points into a PCL format + pcl::fromPCLPointCloud2 (tex_mesh.cloud, *original_cloud); + + // for each camera + for (size_t cam = 0; cam < cameras.size (); ++cam) + { + // get camera pose as transform + Eigen::Affine3f cam_trans = cameras[cam].pose; + + // transform original cloud in camera coordinates + pcl::transformPointCloud (*original_cloud, *transformed_cloud, cam_trans.inverse ()); + + // find occlusions on transformed cloud + std::vector visible, occluded; + removeOccludedPoints (transformed_cloud, filtered_cloud, octree_voxel_size, visible, occluded); + visible_pts = *filtered_cloud; + + // find visible faces => add them to polygon N for camera N + // add polygon group for current camera in clean + std::vector visibleFaces_currentCam; + // iterate over the faces of the current mesh + for (size_t faces = 0; faces < tex_mesh.tex_polygons[0].size (); ++faces) + { + // check if all the face's points are visible + bool faceIsVisible = true; + std::vector::iterator it; + + // iterate over face's vertex + for (size_t current_pt_indice = 0; faceIsVisible && current_pt_indice < tex_mesh.tex_polygons[0][faces].vertices.size (); ++current_pt_indice) + { + // TODO this is far too long! Better create an helper function that raycasts here. + it = find (occluded.begin (), occluded.end (), tex_mesh.tex_polygons[0][faces].vertices[current_pt_indice]); + + if (it == occluded.end ()) + { + // point is not occluded + // does it land on the camera's image plane? + pcl::PointXYZ pt = transformed_cloud->points[tex_mesh.tex_polygons[0][faces].vertices[current_pt_indice]]; + Eigen::Vector2f dummy_UV; + if (!getPointUVCoordinates (pt, cameras[cam], dummy_UV)) + { + // point is not visible by the camera + faceIsVisible = false; + } + } + else + { + faceIsVisible = false; + } + } + + if (faceIsVisible) + { + // push current visible face into the sorted mesh + visibleFaces_currentCam.push_back (tex_mesh.tex_polygons[0][faces]); + // remove it from the unsorted mesh + tex_mesh.tex_polygons[0].erase (tex_mesh.tex_polygons[0].begin () + faces); + faces--; + } + + } + sorted_mesh.tex_polygons.push_back (visibleFaces_currentCam); + } + + // we should only have occluded and non-visible faces left in tex_mesh.tex_polygons[0] + // we need to add them as an extra polygon in the sorted mesh + sorted_mesh.tex_polygons.push_back (tex_mesh.tex_polygons[0]); + return (0); +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::TextureMapping::showOcclusions (const PointCloudPtr &input_cloud, + pcl::PointCloud::Ptr &colored_cloud, + const double octree_voxel_size, const bool show_nb_occlusions, + const int max_occlusions) + { + // variable used to filter occluded points by depth + double maxDeltaZ = octree_voxel_size * 2.0; + + // create an octree to perform rayTracing + pcl::octree::OctreePointCloudSearch *octree; + octree = new pcl::octree::OctreePointCloudSearch (octree_voxel_size); + // create octree structure + octree->setInputCloud (input_cloud); + // update bounding box automatically + octree->defineBoundingBox (); + // add points in the tree + octree->addPointsFromInputCloud (); + + // ray direction + Eigen::Vector3f direction; + + std::vector indices; + // point from where we ray-trace + pcl::PointXYZI pt; + + std::vector zDist; + std::vector ptDist; + // for each point of the cloud, ray-trace toward the camera and check intersected voxels. + for (size_t i = 0; i < input_cloud->points.size (); ++i) + { + direction (0) = input_cloud->points[i].x; + pt.x = input_cloud->points[i].x; + direction (1) = input_cloud->points[i].y; + pt.y = input_cloud->points[i].y; + direction (2) = input_cloud->points[i].z; + pt.z = input_cloud->points[i].z; + + // get number of occlusions for that point + indices.clear (); + int nbocc = octree->getIntersectedVoxelIndices (direction, -direction, indices); + + nbocc = static_cast (indices.size ()); + + // TODO need to clean this up and find tricks to get remove aliasaing effect on planes + for (size_t j = 0; j < indices.size (); j++) + { + // if intersected point is on the over side of the camera + if (pt.z * input_cloud->points[indices[j]].z < 0) + { + nbocc--; + } + else if (fabs (input_cloud->points[indices[j]].z - pt.z) <= maxDeltaZ) + { + // points are very close to each-other, we do not consider the occlusion + nbocc--; + } + else + { + zDist.push_back (fabs (input_cloud->points[indices[j]].z - pt.z)); + ptDist.push_back (pcl::euclideanDistance (input_cloud->points[indices[j]], pt)); + } + } + + if (show_nb_occlusions) + (nbocc <= max_occlusions) ? (pt.intensity = static_cast (nbocc)) : (pt.intensity = static_cast (max_occlusions)); + else + (nbocc == 0) ? (pt.intensity = 0) : (pt.intensity = 1); + + colored_cloud->points.push_back (pt); + } + + if (zDist.size () >= 2) + { + std::sort (zDist.begin (), zDist.end ()); + std::sort (ptDist.begin (), ptDist.end ()); + } +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::TextureMapping::showOcclusions (pcl::TextureMesh &tex_mesh, pcl::PointCloud::Ptr &colored_cloud, + double octree_voxel_size, bool show_nb_occlusions, int max_occlusions) +{ + // load points into a PCL format + pcl::PointCloud::Ptr cloud (new pcl::PointCloud); + pcl::fromPCLPointCloud2 (tex_mesh.cloud, *cloud); + + showOcclusions (cloud, colored_cloud, octree_voxel_size, show_nb_occlusions, max_occlusions); +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::TextureMapping::textureMeshwithMultipleCameras (pcl::TextureMesh &mesh, const pcl::texture_mapping::CameraVector &cameras) +{ + + if (mesh.tex_polygons.size () != 1) + return; + + pcl::PointCloud::Ptr mesh_cloud (new pcl::PointCloud); + + pcl::fromPCLPointCloud2 (mesh.cloud, *mesh_cloud); + + std::vector faces; + + for (int current_cam = 0; current_cam < static_cast (cameras.size ()); ++current_cam) + { + PCL_INFO ("Processing camera %d of %d.\n", current_cam+1, cameras.size ()); + + // transform mesh into camera's frame + pcl::PointCloud::Ptr camera_cloud (new pcl::PointCloud); + pcl::transformPointCloud (*mesh_cloud, *camera_cloud, cameras[current_cam].pose.inverse ()); + + // CREATE UV MAP FOR CURRENT FACES + pcl::PointCloud::Ptr projections (new pcl::PointCloud); + std::vector::iterator current_face; + std::vector visibility; + visibility.resize (mesh.tex_polygons[current_cam].size ()); + std::vector indexes_uv_to_points; + // for each current face + + //TODO change this + pcl::PointXY nan_point; + nan_point.x = std::numeric_limits::quiet_NaN (); + nan_point.y = std::numeric_limits::quiet_NaN (); + UvIndex u_null; + u_null.idx_cloud = -1; + u_null.idx_face = -1; + + int cpt_invisible=0; + for (int idx_face = 0; idx_face < static_cast (mesh.tex_polygons[current_cam].size ()); ++idx_face) + { + //project each vertice, if one is out of view, stop + pcl::PointXY uv_coord1; + pcl::PointXY uv_coord2; + pcl::PointXY uv_coord3; + + if (isFaceProjected (cameras[current_cam], + camera_cloud->points[mesh.tex_polygons[current_cam][idx_face].vertices[0]], + camera_cloud->points[mesh.tex_polygons[current_cam][idx_face].vertices[1]], + camera_cloud->points[mesh.tex_polygons[current_cam][idx_face].vertices[2]], + uv_coord1, + uv_coord2, + uv_coord3)) + { + // face is in the camera's FOV + + // add UV coordinates + projections->points.push_back (uv_coord1); + projections->points.push_back (uv_coord2); + projections->points.push_back (uv_coord3); + + // remember corresponding face + UvIndex u1, u2, u3; + u1.idx_cloud = mesh.tex_polygons[current_cam][idx_face].vertices[0]; + u2.idx_cloud = mesh.tex_polygons[current_cam][idx_face].vertices[1]; + u3.idx_cloud = mesh.tex_polygons[current_cam][idx_face].vertices[2]; + u1.idx_face = idx_face; u2.idx_face = idx_face; u3.idx_face = idx_face; + indexes_uv_to_points.push_back (u1); + indexes_uv_to_points.push_back (u2); + indexes_uv_to_points.push_back (u3); + + //keep track of visibility + visibility[idx_face] = true; + } + else + { + projections->points.push_back (nan_point); + projections->points.push_back (nan_point); + projections->points.push_back (nan_point); + indexes_uv_to_points.push_back (u_null); + indexes_uv_to_points.push_back (u_null); + indexes_uv_to_points.push_back (u_null); + //keep track of visibility + visibility[idx_face] = false; + cpt_invisible++; + } + } + + // projections contains all UV points of the current faces + // indexes_uv_to_points links a uv point to its point in the camera cloud + // visibility contains tells if a face was in the camera FOV (false = skip) + + // TODO handle case were no face could be projected + if (visibility.size () - cpt_invisible !=0) + { + //create kdtree + pcl::KdTreeFLANN kdtree; + kdtree.setInputCloud (projections); + + std::vector idxNeighbors; + std::vector neighborsSquaredDistance; + // af first (idx_pcan < current_cam), check if some of the faces attached to previous cameras occlude the current faces + // then (idx_pcam == current_cam), check for self occlusions. At this stage, we skip faces that were already marked as occluded + cpt_invisible = 0; + for (int idx_pcam = 0 ; idx_pcam <= current_cam ; ++idx_pcam) + { + // project all faces + for (int idx_face = 0; idx_face < static_cast (mesh.tex_polygons[idx_pcam].size ()); ++idx_face) + { + + if (idx_pcam == current_cam && !visibility[idx_face]) + { + // we are now checking for self occlusions within the current faces + // the current face was already declared as occluded. + // therefore, it cannot occlude another face anymore => we skip it + continue; + } + + // project each vertice, if one is out of view, stop + pcl::PointXY uv_coord1; + pcl::PointXY uv_coord2; + pcl::PointXY uv_coord3; + + if (isFaceProjected (cameras[current_cam], + camera_cloud->points[mesh.tex_polygons[idx_pcam][idx_face].vertices[0]], + camera_cloud->points[mesh.tex_polygons[idx_pcam][idx_face].vertices[1]], + camera_cloud->points[mesh.tex_polygons[idx_pcam][idx_face].vertices[2]], + uv_coord1, + uv_coord2, + uv_coord3)) + { + // face is in the camera's FOV + //get its circumsribed circle + double radius; + pcl::PointXY center; + // getTriangleCircumcenterAndSize (uv_coord1, uv_coord2, uv_coord3, center, radius); + getTriangleCircumcscribedCircleCentroid(uv_coord1, uv_coord2, uv_coord3, center, radius); // this function yields faster results than getTriangleCircumcenterAndSize + + // get points inside circ.circle + if (kdtree.radiusSearch (center, radius, idxNeighbors, neighborsSquaredDistance) > 0 ) + { + // for each neighbor + for (size_t i = 0; i < idxNeighbors.size (); ++i) + { + if (std::max (camera_cloud->points[mesh.tex_polygons[idx_pcam][idx_face].vertices[0]].z, + std::max (camera_cloud->points[mesh.tex_polygons[idx_pcam][idx_face].vertices[1]].z, + camera_cloud->points[mesh.tex_polygons[idx_pcam][idx_face].vertices[2]].z)) + < camera_cloud->points[indexes_uv_to_points[idxNeighbors[i]].idx_cloud].z) + { + // neighbor is farther than all the face's points. Check if it falls into the triangle + if (checkPointInsideTriangle(uv_coord1, uv_coord2, uv_coord3, projections->points[idxNeighbors[i]])) + { + // current neighbor is inside triangle and is closer => the corresponding face + visibility[indexes_uv_to_points[idxNeighbors[i]].idx_face] = false; + cpt_invisible++; + //TODO we could remove the projections of this face from the kd-tree cloud, but I fond it slower, and I need the point to keep ordered to querry UV coordinates later + } + } + } + } + } + } + } + } + + // now, visibility is true for each face that belongs to the current camera + // if a face is not visible, we push it into the next one. + + if (static_cast (mesh.tex_coordinates.size ()) <= current_cam) + { + std::vector dummy_container; + mesh.tex_coordinates.push_back (dummy_container); + } + mesh.tex_coordinates[current_cam].resize (3 * visibility.size ()); + + std::vector occluded_faces; + occluded_faces.resize (visibility.size ()); + std::vector visible_faces; + visible_faces.resize (visibility.size ()); + + int cpt_occluded_faces = 0; + int cpt_visible_faces = 0; + + for (size_t idx_face = 0 ; idx_face < visibility.size () ; ++idx_face) + { + if (visibility[idx_face]) + { + // face is visible by the current camera copy UV coordinates + mesh.tex_coordinates[current_cam][cpt_visible_faces * 3](0) = projections->points[idx_face*3].x; + mesh.tex_coordinates[current_cam][cpt_visible_faces * 3](1) = projections->points[idx_face*3].y; + + mesh.tex_coordinates[current_cam][cpt_visible_faces * 3 + 1](0) = projections->points[idx_face*3 + 1].x; + mesh.tex_coordinates[current_cam][cpt_visible_faces * 3 + 1](1) = projections->points[idx_face*3 + 1].y; + + mesh.tex_coordinates[current_cam][cpt_visible_faces * 3 + 2](0) = projections->points[idx_face*3 + 2].x; + mesh.tex_coordinates[current_cam][cpt_visible_faces * 3 + 2](1) = projections->points[idx_face*3 + 2].y; + + visible_faces[cpt_visible_faces] = mesh.tex_polygons[current_cam][idx_face]; + + cpt_visible_faces++; + } + else + { + // face is occluded copy face into temp vector + occluded_faces[cpt_occluded_faces] = mesh.tex_polygons[current_cam][idx_face]; + cpt_occluded_faces++; + } + } + mesh.tex_coordinates[current_cam].resize (cpt_visible_faces*3); + + occluded_faces.resize (cpt_occluded_faces); + mesh.tex_polygons.push_back (occluded_faces); + + visible_faces.resize (cpt_visible_faces); + mesh.tex_polygons[current_cam].clear (); + mesh.tex_polygons[current_cam] = visible_faces; + + int nb_faces = 0; + for (int i = 0; i < static_cast (mesh.tex_polygons.size ()); i++) + nb_faces += static_cast (mesh.tex_polygons[i].size ()); + } + + // we have been through all the cameras. + // if any faces are left, they were not visible by any camera + // we still need to produce uv coordinates for them + + if (mesh.tex_coordinates.size() <= cameras.size ()) + { + std::vector dummy_container; + mesh.tex_coordinates.push_back(dummy_container); + } + + + for(size_t idx_face = 0 ; idx_face < mesh.tex_polygons[cameras.size()].size() ; ++idx_face) + { + Eigen::Vector2f UV1, UV2, UV3; + UV1(0) = -1.0; UV1(1) = -1.0; + UV2(0) = -1.0; UV2(1) = -1.0; + UV3(0) = -1.0; UV3(1) = -1.0; + mesh.tex_coordinates[cameras.size()].push_back(UV1); + mesh.tex_coordinates[cameras.size()].push_back(UV2); + mesh.tex_coordinates[cameras.size()].push_back(UV3); + } + +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::TextureMapping::getTriangleCircumcenterAndSize(const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circomcenter, double &radius) +{ + // we simplify the problem by translating the triangle's origin to its first point + pcl::PointXY ptB, ptC; + ptB.x = p2.x - p1.x; ptB.y = p2.y - p1.y; // B'=B-A + ptC.x = p3.x - p1.x; ptC.y = p3.y - p1.y; // C'=C-A + + double D = 2.0*(ptB.x*ptC.y - ptB.y*ptC.x); // D'=2(B'x*C'y - B'y*C'x) + + // Safety check to avoid division by zero + if(D == 0) + { + circomcenter.x = p1.x; + circomcenter.y = p1.y; + } + else + { + // compute squares once + double bx2 = ptB.x * ptB.x; // B'x^2 + double by2 = ptB.y * ptB.y; // B'y^2 + double cx2 = ptC.x * ptC.x; // C'x^2 + double cy2 = ptC.y * ptC.y; // C'y^2 + + // compute circomcenter's coordinates (translate back to original coordinates) + circomcenter.x = static_cast (p1.x + (ptC.y*(bx2 + by2) - ptB.y*(cx2 + cy2)) / D); + circomcenter.y = static_cast (p1.y + (ptB.x*(cx2 + cy2) - ptC.x*(bx2 + by2)) / D); + } + + radius = sqrt( (circomcenter.x - p1.x)*(circomcenter.x - p1.x) + (circomcenter.y - p1.y)*(circomcenter.y - p1.y));//2.0* (p1.x*(p2.y - p3.y) + p2.x*(p3.y - p1.y) + p3.x*(p1.y - p2.y)); +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::TextureMapping::getTriangleCircumcscribedCircleCentroid ( const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circumcenter, double &radius) +{ + // compute centroid's coordinates (translate back to original coordinates) + circumcenter.x = static_cast (p1.x + p2.x + p3.x ) / 3; + circumcenter.y = static_cast (p1.y + p2.y + p3.y ) / 3; + double r1 = (circumcenter.x - p1.x) * (circumcenter.x - p1.x) + (circumcenter.y - p1.y) * (circumcenter.y - p1.y) ; + double r2 = (circumcenter.x - p2.x) * (circumcenter.x - p2.x) + (circumcenter.y - p2.y) * (circumcenter.y - p2.y) ; + double r3 = (circumcenter.x - p3.x) * (circumcenter.x - p3.x) + (circumcenter.y - p3.y) * (circumcenter.y - p3.y) ; + + // radius + radius = std::sqrt( std::max( r1, std::max( r2, r3) )) ; +} + + +/////////////////////////////////////////////////////////////////////////////////////////////// +template inline bool +pcl::TextureMapping::getPointUVCoordinates(const pcl::PointXYZ &pt, const Camera &cam, pcl::PointXY &UV_coordinates) +{ + if (pt.z > 0) + { + // compute image center and dimension + double sizeX = cam.width; + double sizeY = cam.height; + double cx, cy; + if (cam.center_w > 0) + cx = cam.center_w; + else + cx = sizeX / 2.0; + if (cam.center_h > 0) + cy = cam.center_h; + else + cy = sizeY / 2.0; + + double focal_x, focal_y; + if (cam.focal_length_w > 0) + focal_x = cam.focal_length_w; + else + focal_x = cam.focal_length; + if (cam.focal_length_h > 0) + focal_y = cam.focal_length_h; + else + focal_y = cam.focal_length; + + // project point on camera's image plane + UV_coordinates.x = static_cast ((focal_x * (pt.x / pt.z) + cx) / sizeX); //horizontal + UV_coordinates.y = 1.0f - static_cast ((focal_y * (pt.y / pt.z) + cy) / sizeY); //vertical + + // point is visible! + if (UV_coordinates.x >= 0.0 && UV_coordinates.x <= 1.0 && UV_coordinates.y >= 0.0 && UV_coordinates.y <= 1.0) + return (true); // point was visible by the camera + } + + // point is NOT visible by the camera + UV_coordinates.x = -1.0f; + UV_coordinates.y = -1.0f; + return (false); // point was not visible by the camera +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template inline bool +pcl::TextureMapping::checkPointInsideTriangle(const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, const pcl::PointXY &pt) +{ + // Compute vectors + Eigen::Vector2d v0, v1, v2; + v0(0) = p3.x - p1.x; v0(1) = p3.y - p1.y; // v0= C - A + v1(0) = p2.x - p1.x; v1(1) = p2.y - p1.y; // v1= B - A + v2(0) = pt.x - p1.x; v2(1) = pt.y - p1.y; // v2= P - A + + // Compute dot products + double dot00 = v0.dot(v0); // dot00 = dot(v0, v0) + double dot01 = v0.dot(v1); // dot01 = dot(v0, v1) + double dot02 = v0.dot(v2); // dot02 = dot(v0, v2) + double dot11 = v1.dot(v1); // dot11 = dot(v1, v1) + double dot12 = v1.dot(v2); // dot12 = dot(v1, v2) + + // Compute barycentric coordinates + double invDenom = 1.0 / (dot00*dot11 - dot01*dot01); + double u = (dot11*dot02 - dot01*dot12) * invDenom; + double v = (dot00*dot12 - dot01*dot02) * invDenom; + + // Check if point is in triangle + return ((u >= 0) && (v >= 0) && (u + v < 1)); +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template inline bool +pcl::TextureMapping::isFaceProjected (const Camera &camera, const pcl::PointXYZ &p1, const pcl::PointXYZ &p2, const pcl::PointXYZ &p3, pcl::PointXY &proj1, pcl::PointXY &proj2, pcl::PointXY &proj3) +{ + return (getPointUVCoordinates(p1, camera, proj1) + && + getPointUVCoordinates(p2, camera, proj2) + && + getPointUVCoordinates(p3, camera, proj3) + ); +} + +#define PCL_INSTANTIATE_TextureMapping(T) \ + template class PCL_EXPORTS pcl::TextureMapping; + +#endif /* TEXTURE_MAPPING_HPP_ */ + diff --git a/pcl-1.7/pcl/surface/marching_cubes.h b/pcl-1.7/pcl/surface/marching_cubes.h new file mode 100644 index 0000000..a640ad9 --- /dev/null +++ b/pcl-1.7/pcl/surface/marching_cubes.h @@ -0,0 +1,521 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SURFACE_MARCHING_CUBES_H_ +#define PCL_SURFACE_MARCHING_CUBES_H_ + +#include +#include + +namespace pcl +{ + /* + * Tables, and functions, derived from Paul Bourke's Marching Cubes implementation: + * http://paulbourke.net/geometry/polygonise/ + * Cube vertex indices: + * y_dir 4 ________ 5 + * /| /| + * / | / | + * 7 /_______ / | + * | | |6 | + * | 0|__|_____|1 x_dir + * | / | / + * | / | / + z_dir|/_______|/ + * 3 2 + */ + const unsigned int edgeTable[256] = { + 0x0 , 0x109, 0x203, 0x30a, 0x406, 0x50f, 0x605, 0x70c, + 0x80c, 0x905, 0xa0f, 0xb06, 0xc0a, 0xd03, 0xe09, 0xf00, + 0x190, 0x99 , 0x393, 0x29a, 0x596, 0x49f, 0x795, 0x69c, + 0x99c, 0x895, 0xb9f, 0xa96, 0xd9a, 0xc93, 0xf99, 0xe90, + 0x230, 0x339, 0x33 , 0x13a, 0x636, 0x73f, 0x435, 0x53c, + 0xa3c, 0xb35, 0x83f, 0x936, 0xe3a, 0xf33, 0xc39, 0xd30, + 0x3a0, 0x2a9, 0x1a3, 0xaa , 0x7a6, 0x6af, 0x5a5, 0x4ac, + 0xbac, 0xaa5, 0x9af, 0x8a6, 0xfaa, 0xea3, 0xda9, 0xca0, + 0x460, 0x569, 0x663, 0x76a, 0x66 , 0x16f, 0x265, 0x36c, + 0xc6c, 0xd65, 0xe6f, 0xf66, 0x86a, 0x963, 0xa69, 0xb60, + 0x5f0, 0x4f9, 0x7f3, 0x6fa, 0x1f6, 0xff , 0x3f5, 0x2fc, + 0xdfc, 0xcf5, 0xfff, 0xef6, 0x9fa, 0x8f3, 0xbf9, 0xaf0, + 0x650, 0x759, 0x453, 0x55a, 0x256, 0x35f, 0x55 , 0x15c, + 0xe5c, 0xf55, 0xc5f, 0xd56, 0xa5a, 0xb53, 0x859, 0x950, + 0x7c0, 0x6c9, 0x5c3, 0x4ca, 0x3c6, 0x2cf, 0x1c5, 0xcc , + 0xfcc, 0xec5, 0xdcf, 0xcc6, 0xbca, 0xac3, 0x9c9, 0x8c0, + 0x8c0, 0x9c9, 0xac3, 0xbca, 0xcc6, 0xdcf, 0xec5, 0xfcc, + 0xcc , 0x1c5, 0x2cf, 0x3c6, 0x4ca, 0x5c3, 0x6c9, 0x7c0, + 0x950, 0x859, 0xb53, 0xa5a, 0xd56, 0xc5f, 0xf55, 0xe5c, + 0x15c, 0x55 , 0x35f, 0x256, 0x55a, 0x453, 0x759, 0x650, + 0xaf0, 0xbf9, 0x8f3, 0x9fa, 0xef6, 0xfff, 0xcf5, 0xdfc, + 0x2fc, 0x3f5, 0xff , 0x1f6, 0x6fa, 0x7f3, 0x4f9, 0x5f0, + 0xb60, 0xa69, 0x963, 0x86a, 0xf66, 0xe6f, 0xd65, 0xc6c, + 0x36c, 0x265, 0x16f, 0x66 , 0x76a, 0x663, 0x569, 0x460, + 0xca0, 0xda9, 0xea3, 0xfaa, 0x8a6, 0x9af, 0xaa5, 0xbac, + 0x4ac, 0x5a5, 0x6af, 0x7a6, 0xaa , 0x1a3, 0x2a9, 0x3a0, + 0xd30, 0xc39, 0xf33, 0xe3a, 0x936, 0x83f, 0xb35, 0xa3c, + 0x53c, 0x435, 0x73f, 0x636, 0x13a, 0x33 , 0x339, 0x230, + 0xe90, 0xf99, 0xc93, 0xd9a, 0xa96, 0xb9f, 0x895, 0x99c, + 0x69c, 0x795, 0x49f, 0x596, 0x29a, 0x393, 0x99 , 0x190, + 0xf00, 0xe09, 0xd03, 0xc0a, 0xb06, 0xa0f, 0x905, 0x80c, + 0x70c, 0x605, 0x50f, 0x406, 0x30a, 0x203, 0x109, 0x0 + }; + const int triTable[256][16] = { + {-1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {0, 8, 3, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {0, 1, 9, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {1, 8, 3, 9, 8, 1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {1, 2, 10, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {0, 8, 3, 1, 2, 10, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {9, 2, 10, 0, 2, 9, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {2, 8, 3, 2, 10, 8, 10, 9, 8, -1, -1, -1, -1, -1, -1, -1}, + {3, 11, 2, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {0, 11, 2, 8, 11, 0, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {1, 9, 0, 2, 3, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {1, 11, 2, 1, 9, 11, 9, 8, 11, -1, -1, -1, -1, -1, -1, -1}, + {3, 10, 1, 11, 10, 3, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {0, 10, 1, 0, 8, 10, 8, 11, 10, -1, -1, -1, -1, -1, -1, -1}, + {3, 9, 0, 3, 11, 9, 11, 10, 9, -1, -1, -1, -1, -1, -1, -1}, + {9, 8, 10, 10, 8, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {4, 7, 8, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {4, 3, 0, 7, 3, 4, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {0, 1, 9, 8, 4, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {4, 1, 9, 4, 7, 1, 7, 3, 1, -1, -1, -1, -1, -1, -1, -1}, + {1, 2, 10, 8, 4, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {3, 4, 7, 3, 0, 4, 1, 2, 10, -1, -1, -1, -1, -1, -1, -1}, + {9, 2, 10, 9, 0, 2, 8, 4, 7, -1, -1, -1, -1, -1, -1, -1}, + {2, 10, 9, 2, 9, 7, 2, 7, 3, 7, 9, 4, -1, -1, -1, -1}, + {8, 4, 7, 3, 11, 2, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {11, 4, 7, 11, 2, 4, 2, 0, 4, -1, -1, -1, -1, -1, -1, -1}, + {9, 0, 1, 8, 4, 7, 2, 3, 11, -1, -1, -1, -1, -1, -1, -1}, + {4, 7, 11, 9, 4, 11, 9, 11, 2, 9, 2, 1, -1, -1, -1, -1}, + {3, 10, 1, 3, 11, 10, 7, 8, 4, -1, -1, -1, -1, -1, -1, -1}, + {1, 11, 10, 1, 4, 11, 1, 0, 4, 7, 11, 4, -1, -1, -1, -1}, + {4, 7, 8, 9, 0, 11, 9, 11, 10, 11, 0, 3, -1, -1, -1, -1}, + {4, 7, 11, 4, 11, 9, 9, 11, 10, -1, -1, -1, -1, -1, -1, -1}, + {9, 5, 4, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {9, 5, 4, 0, 8, 3, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {0, 5, 4, 1, 5, 0, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {8, 5, 4, 8, 3, 5, 3, 1, 5, -1, -1, -1, -1, -1, -1, -1}, + {1, 2, 10, 9, 5, 4, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {3, 0, 8, 1, 2, 10, 4, 9, 5, -1, -1, -1, -1, -1, -1, -1}, + {5, 2, 10, 5, 4, 2, 4, 0, 2, -1, -1, -1, -1, -1, -1, -1}, + {2, 10, 5, 3, 2, 5, 3, 5, 4, 3, 4, 8, -1, -1, -1, -1}, + {9, 5, 4, 2, 3, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {0, 11, 2, 0, 8, 11, 4, 9, 5, -1, -1, -1, -1, -1, -1, -1}, + {0, 5, 4, 0, 1, 5, 2, 3, 11, -1, -1, -1, -1, -1, -1, -1}, + {2, 1, 5, 2, 5, 8, 2, 8, 11, 4, 8, 5, -1, -1, -1, -1}, + {10, 3, 11, 10, 1, 3, 9, 5, 4, -1, -1, -1, -1, -1, -1, -1}, + {4, 9, 5, 0, 8, 1, 8, 10, 1, 8, 11, 10, -1, -1, -1, -1}, + {5, 4, 0, 5, 0, 11, 5, 11, 10, 11, 0, 3, -1, -1, -1, -1}, + {5, 4, 8, 5, 8, 10, 10, 8, 11, -1, -1, -1, -1, -1, -1, -1}, + {9, 7, 8, 5, 7, 9, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {9, 3, 0, 9, 5, 3, 5, 7, 3, -1, -1, -1, -1, -1, -1, -1}, + {0, 7, 8, 0, 1, 7, 1, 5, 7, -1, -1, -1, -1, -1, -1, -1}, + {1, 5, 3, 3, 5, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {9, 7, 8, 9, 5, 7, 10, 1, 2, -1, -1, -1, -1, -1, -1, -1}, + {10, 1, 2, 9, 5, 0, 5, 3, 0, 5, 7, 3, -1, -1, -1, -1}, + {8, 0, 2, 8, 2, 5, 8, 5, 7, 10, 5, 2, -1, -1, -1, -1}, + {2, 10, 5, 2, 5, 3, 3, 5, 7, -1, -1, -1, -1, -1, -1, -1}, + {7, 9, 5, 7, 8, 9, 3, 11, 2, -1, -1, -1, -1, -1, -1, -1}, + {9, 5, 7, 9, 7, 2, 9, 2, 0, 2, 7, 11, -1, -1, -1, -1}, + {2, 3, 11, 0, 1, 8, 1, 7, 8, 1, 5, 7, -1, -1, -1, -1}, + {11, 2, 1, 11, 1, 7, 7, 1, 5, -1, -1, -1, -1, -1, -1, -1}, + {9, 5, 8, 8, 5, 7, 10, 1, 3, 10, 3, 11, -1, -1, -1, -1}, + {5, 7, 0, 5, 0, 9, 7, 11, 0, 1, 0, 10, 11, 10, 0, -1}, + {11, 10, 0, 11, 0, 3, 10, 5, 0, 8, 0, 7, 5, 7, 0, -1}, + {11, 10, 5, 7, 11, 5, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {10, 6, 5, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {0, 8, 3, 5, 10, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {9, 0, 1, 5, 10, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {1, 8, 3, 1, 9, 8, 5, 10, 6, -1, -1, -1, -1, -1, -1, -1}, + {1, 6, 5, 2, 6, 1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {1, 6, 5, 1, 2, 6, 3, 0, 8, -1, -1, -1, -1, -1, -1, -1}, + {9, 6, 5, 9, 0, 6, 0, 2, 6, -1, -1, -1, -1, -1, -1, -1}, + {5, 9, 8, 5, 8, 2, 5, 2, 6, 3, 2, 8, -1, -1, -1, -1}, + {2, 3, 11, 10, 6, 5, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {11, 0, 8, 11, 2, 0, 10, 6, 5, -1, -1, -1, -1, -1, -1, -1}, + {0, 1, 9, 2, 3, 11, 5, 10, 6, -1, -1, -1, -1, -1, -1, -1}, + {5, 10, 6, 1, 9, 2, 9, 11, 2, 9, 8, 11, -1, -1, -1, -1}, + {6, 3, 11, 6, 5, 3, 5, 1, 3, -1, -1, -1, -1, -1, -1, -1}, + {0, 8, 11, 0, 11, 5, 0, 5, 1, 5, 11, 6, -1, -1, -1, -1}, + {3, 11, 6, 0, 3, 6, 0, 6, 5, 0, 5, 9, -1, -1, -1, -1}, + {6, 5, 9, 6, 9, 11, 11, 9, 8, -1, -1, -1, -1, -1, -1, -1}, + {5, 10, 6, 4, 7, 8, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {4, 3, 0, 4, 7, 3, 6, 5, 10, -1, -1, -1, -1, -1, -1, -1}, + {1, 9, 0, 5, 10, 6, 8, 4, 7, -1, -1, -1, -1, -1, -1, -1}, + {10, 6, 5, 1, 9, 7, 1, 7, 3, 7, 9, 4, -1, -1, -1, -1}, + {6, 1, 2, 6, 5, 1, 4, 7, 8, -1, -1, -1, -1, -1, -1, -1}, + {1, 2, 5, 5, 2, 6, 3, 0, 4, 3, 4, 7, -1, -1, -1, -1}, + {8, 4, 7, 9, 0, 5, 0, 6, 5, 0, 2, 6, -1, -1, -1, -1}, + {7, 3, 9, 7, 9, 4, 3, 2, 9, 5, 9, 6, 2, 6, 9, -1}, + {3, 11, 2, 7, 8, 4, 10, 6, 5, -1, -1, -1, -1, -1, -1, -1}, + {5, 10, 6, 4, 7, 2, 4, 2, 0, 2, 7, 11, -1, -1, -1, -1}, + {0, 1, 9, 4, 7, 8, 2, 3, 11, 5, 10, 6, -1, -1, -1, -1}, + {9, 2, 1, 9, 11, 2, 9, 4, 11, 7, 11, 4, 5, 10, 6, -1}, + {8, 4, 7, 3, 11, 5, 3, 5, 1, 5, 11, 6, -1, -1, -1, -1}, + {5, 1, 11, 5, 11, 6, 1, 0, 11, 7, 11, 4, 0, 4, 11, -1}, + {0, 5, 9, 0, 6, 5, 0, 3, 6, 11, 6, 3, 8, 4, 7, -1}, + {6, 5, 9, 6, 9, 11, 4, 7, 9, 7, 11, 9, -1, -1, -1, -1}, + {10, 4, 9, 6, 4, 10, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {4, 10, 6, 4, 9, 10, 0, 8, 3, -1, -1, -1, -1, -1, -1, -1}, + {10, 0, 1, 10, 6, 0, 6, 4, 0, -1, -1, -1, -1, -1, -1, -1}, + {8, 3, 1, 8, 1, 6, 8, 6, 4, 6, 1, 10, -1, -1, -1, -1}, + {1, 4, 9, 1, 2, 4, 2, 6, 4, -1, -1, -1, -1, -1, -1, -1}, + {3, 0, 8, 1, 2, 9, 2, 4, 9, 2, 6, 4, -1, -1, -1, -1}, + {0, 2, 4, 4, 2, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {8, 3, 2, 8, 2, 4, 4, 2, 6, -1, -1, -1, -1, -1, -1, -1}, + {10, 4, 9, 10, 6, 4, 11, 2, 3, -1, -1, -1, -1, -1, -1, -1}, + {0, 8, 2, 2, 8, 11, 4, 9, 10, 4, 10, 6, -1, -1, -1, -1}, + {3, 11, 2, 0, 1, 6, 0, 6, 4, 6, 1, 10, -1, -1, -1, -1}, + {6, 4, 1, 6, 1, 10, 4, 8, 1, 2, 1, 11, 8, 11, 1, -1}, + {9, 6, 4, 9, 3, 6, 9, 1, 3, 11, 6, 3, -1, -1, -1, -1}, + {8, 11, 1, 8, 1, 0, 11, 6, 1, 9, 1, 4, 6, 4, 1, -1}, + {3, 11, 6, 3, 6, 0, 0, 6, 4, -1, -1, -1, -1, -1, -1, -1}, + {6, 4, 8, 11, 6, 8, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {7, 10, 6, 7, 8, 10, 8, 9, 10, -1, -1, -1, -1, -1, -1, -1}, + {0, 7, 3, 0, 10, 7, 0, 9, 10, 6, 7, 10, -1, -1, -1, -1}, + {10, 6, 7, 1, 10, 7, 1, 7, 8, 1, 8, 0, -1, -1, -1, -1}, + {10, 6, 7, 10, 7, 1, 1, 7, 3, -1, -1, -1, -1, -1, -1, -1}, + {1, 2, 6, 1, 6, 8, 1, 8, 9, 8, 6, 7, -1, -1, -1, -1}, + {2, 6, 9, 2, 9, 1, 6, 7, 9, 0, 9, 3, 7, 3, 9, -1}, + {7, 8, 0, 7, 0, 6, 6, 0, 2, -1, -1, -1, -1, -1, -1, -1}, + {7, 3, 2, 6, 7, 2, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {2, 3, 11, 10, 6, 8, 10, 8, 9, 8, 6, 7, -1, -1, -1, -1}, + {2, 0, 7, 2, 7, 11, 0, 9, 7, 6, 7, 10, 9, 10, 7, -1}, + {1, 8, 0, 1, 7, 8, 1, 10, 7, 6, 7, 10, 2, 3, 11, -1}, + {11, 2, 1, 11, 1, 7, 10, 6, 1, 6, 7, 1, -1, -1, -1, -1}, + {8, 9, 6, 8, 6, 7, 9, 1, 6, 11, 6, 3, 1, 3, 6, -1}, + {0, 9, 1, 11, 6, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {7, 8, 0, 7, 0, 6, 3, 11, 0, 11, 6, 0, -1, -1, -1, -1}, + {7, 11, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {7, 6, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {3, 0, 8, 11, 7, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {0, 1, 9, 11, 7, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {8, 1, 9, 8, 3, 1, 11, 7, 6, -1, -1, -1, -1, -1, -1, -1}, + {10, 1, 2, 6, 11, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {1, 2, 10, 3, 0, 8, 6, 11, 7, -1, -1, -1, -1, -1, -1, -1}, + {2, 9, 0, 2, 10, 9, 6, 11, 7, -1, -1, -1, -1, -1, -1, -1}, + {6, 11, 7, 2, 10, 3, 10, 8, 3, 10, 9, 8, -1, -1, -1, -1}, + {7, 2, 3, 6, 2, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {7, 0, 8, 7, 6, 0, 6, 2, 0, -1, -1, -1, -1, -1, -1, -1}, + {2, 7, 6, 2, 3, 7, 0, 1, 9, -1, -1, -1, -1, -1, -1, -1}, + {1, 6, 2, 1, 8, 6, 1, 9, 8, 8, 7, 6, -1, -1, -1, -1}, + {10, 7, 6, 10, 1, 7, 1, 3, 7, -1, -1, -1, -1, -1, -1, -1}, + {10, 7, 6, 1, 7, 10, 1, 8, 7, 1, 0, 8, -1, -1, -1, -1}, + {0, 3, 7, 0, 7, 10, 0, 10, 9, 6, 10, 7, -1, -1, -1, -1}, + {7, 6, 10, 7, 10, 8, 8, 10, 9, -1, -1, -1, -1, -1, -1, -1}, + {6, 8, 4, 11, 8, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {3, 6, 11, 3, 0, 6, 0, 4, 6, -1, -1, -1, -1, -1, -1, -1}, + {8, 6, 11, 8, 4, 6, 9, 0, 1, -1, -1, -1, -1, -1, -1, -1}, + {9, 4, 6, 9, 6, 3, 9, 3, 1, 11, 3, 6, -1, -1, -1, -1}, + {6, 8, 4, 6, 11, 8, 2, 10, 1, -1, -1, -1, -1, -1, -1, -1}, + {1, 2, 10, 3, 0, 11, 0, 6, 11, 0, 4, 6, -1, -1, -1, -1}, + {4, 11, 8, 4, 6, 11, 0, 2, 9, 2, 10, 9, -1, -1, -1, -1}, + {10, 9, 3, 10, 3, 2, 9, 4, 3, 11, 3, 6, 4, 6, 3, -1}, + {8, 2, 3, 8, 4, 2, 4, 6, 2, -1, -1, -1, -1, -1, -1, -1}, + {0, 4, 2, 4, 6, 2, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {1, 9, 0, 2, 3, 4, 2, 4, 6, 4, 3, 8, -1, -1, -1, -1}, + {1, 9, 4, 1, 4, 2, 2, 4, 6, -1, -1, -1, -1, -1, -1, -1}, + {8, 1, 3, 8, 6, 1, 8, 4, 6, 6, 10, 1, -1, -1, -1, -1}, + {10, 1, 0, 10, 0, 6, 6, 0, 4, -1, -1, -1, -1, -1, -1, -1}, + {4, 6, 3, 4, 3, 8, 6, 10, 3, 0, 3, 9, 10, 9, 3, -1}, + {10, 9, 4, 6, 10, 4, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {4, 9, 5, 7, 6, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {0, 8, 3, 4, 9, 5, 11, 7, 6, -1, -1, -1, -1, -1, -1, -1}, + {5, 0, 1, 5, 4, 0, 7, 6, 11, -1, -1, -1, -1, -1, -1, -1}, + {11, 7, 6, 8, 3, 4, 3, 5, 4, 3, 1, 5, -1, -1, -1, -1}, + {9, 5, 4, 10, 1, 2, 7, 6, 11, -1, -1, -1, -1, -1, -1, -1}, + {6, 11, 7, 1, 2, 10, 0, 8, 3, 4, 9, 5, -1, -1, -1, -1}, + {7, 6, 11, 5, 4, 10, 4, 2, 10, 4, 0, 2, -1, -1, -1, -1}, + {3, 4, 8, 3, 5, 4, 3, 2, 5, 10, 5, 2, 11, 7, 6, -1}, + {7, 2, 3, 7, 6, 2, 5, 4, 9, -1, -1, -1, -1, -1, -1, -1}, + {9, 5, 4, 0, 8, 6, 0, 6, 2, 6, 8, 7, -1, -1, -1, -1}, + {3, 6, 2, 3, 7, 6, 1, 5, 0, 5, 4, 0, -1, -1, -1, -1}, + {6, 2, 8, 6, 8, 7, 2, 1, 8, 4, 8, 5, 1, 5, 8, -1}, + {9, 5, 4, 10, 1, 6, 1, 7, 6, 1, 3, 7, -1, -1, -1, -1}, + {1, 6, 10, 1, 7, 6, 1, 0, 7, 8, 7, 0, 9, 5, 4, -1}, + {4, 0, 10, 4, 10, 5, 0, 3, 10, 6, 10, 7, 3, 7, 10, -1}, + {7, 6, 10, 7, 10, 8, 5, 4, 10, 4, 8, 10, -1, -1, -1, -1}, + {6, 9, 5, 6, 11, 9, 11, 8, 9, -1, -1, -1, -1, -1, -1, -1}, + {3, 6, 11, 0, 6, 3, 0, 5, 6, 0, 9, 5, -1, -1, -1, -1}, + {0, 11, 8, 0, 5, 11, 0, 1, 5, 5, 6, 11, -1, -1, -1, -1}, + {6, 11, 3, 6, 3, 5, 5, 3, 1, -1, -1, -1, -1, -1, -1, -1}, + {1, 2, 10, 9, 5, 11, 9, 11, 8, 11, 5, 6, -1, -1, -1, -1}, + {0, 11, 3, 0, 6, 11, 0, 9, 6, 5, 6, 9, 1, 2, 10, -1}, + {11, 8, 5, 11, 5, 6, 8, 0, 5, 10, 5, 2, 0, 2, 5, -1}, + {6, 11, 3, 6, 3, 5, 2, 10, 3, 10, 5, 3, -1, -1, -1, -1}, + {5, 8, 9, 5, 2, 8, 5, 6, 2, 3, 8, 2, -1, -1, -1, -1}, + {9, 5, 6, 9, 6, 0, 0, 6, 2, -1, -1, -1, -1, -1, -1, -1}, + {1, 5, 8, 1, 8, 0, 5, 6, 8, 3, 8, 2, 6, 2, 8, -1}, + {1, 5, 6, 2, 1, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {1, 3, 6, 1, 6, 10, 3, 8, 6, 5, 6, 9, 8, 9, 6, -1}, + {10, 1, 0, 10, 0, 6, 9, 5, 0, 5, 6, 0, -1, -1, -1, -1}, + {0, 3, 8, 5, 6, 10, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {10, 5, 6, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {11, 5, 10, 7, 5, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {11, 5, 10, 11, 7, 5, 8, 3, 0, -1, -1, -1, -1, -1, -1, -1}, + {5, 11, 7, 5, 10, 11, 1, 9, 0, -1, -1, -1, -1, -1, -1, -1}, + {10, 7, 5, 10, 11, 7, 9, 8, 1, 8, 3, 1, -1, -1, -1, -1}, + {11, 1, 2, 11, 7, 1, 7, 5, 1, -1, -1, -1, -1, -1, -1, -1}, + {0, 8, 3, 1, 2, 7, 1, 7, 5, 7, 2, 11, -1, -1, -1, -1}, + {9, 7, 5, 9, 2, 7, 9, 0, 2, 2, 11, 7, -1, -1, -1, -1}, + {7, 5, 2, 7, 2, 11, 5, 9, 2, 3, 2, 8, 9, 8, 2, -1}, + {2, 5, 10, 2, 3, 5, 3, 7, 5, -1, -1, -1, -1, -1, -1, -1}, + {8, 2, 0, 8, 5, 2, 8, 7, 5, 10, 2, 5, -1, -1, -1, -1}, + {9, 0, 1, 5, 10, 3, 5, 3, 7, 3, 10, 2, -1, -1, -1, -1}, + {9, 8, 2, 9, 2, 1, 8, 7, 2, 10, 2, 5, 7, 5, 2, -1}, + {1, 3, 5, 3, 7, 5, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {0, 8, 7, 0, 7, 1, 1, 7, 5, -1, -1, -1, -1, -1, -1, -1}, + {9, 0, 3, 9, 3, 5, 5, 3, 7, -1, -1, -1, -1, -1, -1, -1}, + {9, 8, 7, 5, 9, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {5, 8, 4, 5, 10, 8, 10, 11, 8, -1, -1, -1, -1, -1, -1, -1}, + {5, 0, 4, 5, 11, 0, 5, 10, 11, 11, 3, 0, -1, -1, -1, -1}, + {0, 1, 9, 8, 4, 10, 8, 10, 11, 10, 4, 5, -1, -1, -1, -1}, + {10, 11, 4, 10, 4, 5, 11, 3, 4, 9, 4, 1, 3, 1, 4, -1}, + {2, 5, 1, 2, 8, 5, 2, 11, 8, 4, 5, 8, -1, -1, -1, -1}, + {0, 4, 11, 0, 11, 3, 4, 5, 11, 2, 11, 1, 5, 1, 11, -1}, + {0, 2, 5, 0, 5, 9, 2, 11, 5, 4, 5, 8, 11, 8, 5, -1}, + {9, 4, 5, 2, 11, 3, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {2, 5, 10, 3, 5, 2, 3, 4, 5, 3, 8, 4, -1, -1, -1, -1}, + {5, 10, 2, 5, 2, 4, 4, 2, 0, -1, -1, -1, -1, -1, -1, -1}, + {3, 10, 2, 3, 5, 10, 3, 8, 5, 4, 5, 8, 0, 1, 9, -1}, + {5, 10, 2, 5, 2, 4, 1, 9, 2, 9, 4, 2, -1, -1, -1, -1}, + {8, 4, 5, 8, 5, 3, 3, 5, 1, -1, -1, -1, -1, -1, -1, -1}, + {0, 4, 5, 1, 0, 5, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {8, 4, 5, 8, 5, 3, 9, 0, 5, 0, 3, 5, -1, -1, -1, -1}, + {9, 4, 5, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {4, 11, 7, 4, 9, 11, 9, 10, 11, -1, -1, -1, -1, -1, -1, -1}, + {0, 8, 3, 4, 9, 7, 9, 11, 7, 9, 10, 11, -1, -1, -1, -1}, + {1, 10, 11, 1, 11, 4, 1, 4, 0, 7, 4, 11, -1, -1, -1, -1}, + {3, 1, 4, 3, 4, 8, 1, 10, 4, 7, 4, 11, 10, 11, 4, -1}, + {4, 11, 7, 9, 11, 4, 9, 2, 11, 9, 1, 2, -1, -1, -1, -1}, + {9, 7, 4, 9, 11, 7, 9, 1, 11, 2, 11, 1, 0, 8, 3, -1}, + {11, 7, 4, 11, 4, 2, 2, 4, 0, -1, -1, -1, -1, -1, -1, -1}, + {11, 7, 4, 11, 4, 2, 8, 3, 4, 3, 2, 4, -1, -1, -1, -1}, + {2, 9, 10, 2, 7, 9, 2, 3, 7, 7, 4, 9, -1, -1, -1, -1}, + {9, 10, 7, 9, 7, 4, 10, 2, 7, 8, 7, 0, 2, 0, 7, -1}, + {3, 7, 10, 3, 10, 2, 7, 4, 10, 1, 10, 0, 4, 0, 10, -1}, + {1, 10, 2, 8, 7, 4, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {4, 9, 1, 4, 1, 7, 7, 1, 3, -1, -1, -1, -1, -1, -1, -1}, + {4, 9, 1, 4, 1, 7, 0, 8, 1, 8, 7, 1, -1, -1, -1, -1}, + {4, 0, 3, 7, 4, 3, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {4, 8, 7, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {9, 10, 8, 10, 11, 8, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {3, 0, 9, 3, 9, 11, 11, 9, 10, -1, -1, -1, -1, -1, -1, -1}, + {0, 1, 10, 0, 10, 8, 8, 10, 11, -1, -1, -1, -1, -1, -1, -1}, + {3, 1, 10, 11, 3, 10, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {1, 2, 11, 1, 11, 9, 9, 11, 8, -1, -1, -1, -1, -1, -1, -1}, + {3, 0, 9, 3, 9, 11, 1, 2, 9, 2, 11, 9, -1, -1, -1, -1}, + {0, 2, 11, 8, 0, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {3, 2, 11, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {2, 3, 8, 2, 8, 10, 10, 8, 9, -1, -1, -1, -1, -1, -1, -1}, + {9, 10, 2, 0, 9, 2, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {2, 3, 8, 2, 8, 10, 0, 1, 8, 1, 10, 8, -1, -1, -1, -1}, + {1, 10, 2, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {1, 3, 8, 9, 1, 8, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {0, 9, 1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {0, 3, 8, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1}, + {-1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1} + }; + + + /** \brief The marching cubes surface reconstruction algorithm. This is an abstract class that takes a grid and + * extracts the isosurface as a mesh, based on the original marching cubes paper: + * + * Lorensen W.E., Cline H.E., "Marching cubes: A high resolution 3d surface construction algorithm", + * SIGGRAPH '87 + * + * \author Alexandru E. Ichim + * \ingroup surface + */ + template + class MarchingCubes : public SurfaceReconstruction + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using SurfaceReconstruction::input_; + using SurfaceReconstruction::tree_; + + typedef typename pcl::PointCloud::Ptr PointCloudPtr; + + typedef typename pcl::KdTree KdTree; + typedef typename pcl::KdTree::Ptr KdTreePtr; + + + /** \brief Constructor. */ + MarchingCubes (); + + /** \brief Destructor. */ + virtual ~MarchingCubes (); + + + /** \brief Method that sets the iso level of the surface to be extracted. + * \param[in] iso_level the iso level. + */ + inline void + setIsoLevel (float iso_level) + { iso_level_ = iso_level; } + + /** \brief Method that returns the iso level of the surface to be extracted. */ + inline float + getIsoLevel () + { return iso_level_; } + + /** \brief Method that sets the marching cubes grid resolution. + * \param[in] res_x the resolution of the grid along the x-axis + * \param[in] res_y the resolution of the grid along the y-axis + * \param[in] res_z the resolution of the grid along the z-axis + */ + inline void + setGridResolution (int res_x, int res_y, int res_z) + { res_x_ = res_x; res_y_ = res_y; res_z_ = res_z; } + + + /** \brief Method to get the marching cubes grid resolution. + * \param[in] res_x the resolution of the grid along the x-axis + * \param[in] res_y the resolution of the grid along the y-axis + * \param[in] res_z the resolution of the grid along the z-axis + */ + inline void + getGridResolution (int &res_x, int &res_y, int &res_z) + { res_x = res_x_; res_y = res_y_; res_z = res_z_; } + + /** \brief Method that sets the parameter that defines how much free space should be left inside the grid between + * the bounding box of the point cloud and the grid limits. Does not affect the resolution of the grid, it just + * changes the voxel size accordingly. + * \param[in] percentage the percentage of the bounding box that should be left empty between the bounding box and + * the grid limits. + */ + inline void + setPercentageExtendGrid (float percentage) + { percentage_extend_grid_ = percentage; } + + /** \brief Method that gets the parameter that defines how much free space should be left inside the grid between + * the bounding box of the point cloud and the grid limits, as a percentage of the bounding box. + */ + inline float + getPercentageExtendGrid () + { return percentage_extend_grid_; } + + protected: + /** \brief The data structure storing the 3D grid */ + std::vector grid_; + + /** \brief The grid resolution */ + int res_x_, res_y_, res_z_; + + /** \brief Min and max data points. */ + Eigen::Vector4f min_p_, max_p_; + + /** \brief Parameter that defines how much free space should be left inside the grid between + * the bounding box of the point cloud and the grid limits, as a percentage of the bounding box.*/ + float percentage_extend_grid_; + + /** \brief The iso level to be extracted. */ + float iso_level_; + + /** \brief Convert the point cloud into voxel data. */ + virtual void + voxelizeData () = 0; + + /** \brief Interpolate along the voxel edge. + * \param[in] p1 The first point on the edge + * \param[in] p2 The second point on the edge + * \param[in] val_p1 The scalar value at p1 + * \param[in] val_p2 The scalar value at p2 + * \param[out] output The interpolated point along the edge + */ + void + interpolateEdge (Eigen::Vector3f &p1, Eigen::Vector3f &p2, float val_p1, float val_p2, Eigen::Vector3f &output); + + + /** \brief Calculate out the corresponding polygons in the leaf node + * \param leaf_node the leaf node to be checked + * \param index_3d the 3d index of the leaf node to be checked + * \param cloud point cloud to store the vertices of the polygon + */ + void + createSurface (std::vector &leaf_node, + Eigen::Vector3i &index_3d, + pcl::PointCloud &cloud); + + /** \brief Get the bounding box for the input data points. */ + void + getBoundingBox (); + + + /** \brief Method that returns the scalar value at the given grid position. + * \param[in] pos The 3D position in the grid + */ + virtual float + getGridValue (Eigen::Vector3i pos); + + /** \brief Method that returns the scalar values of the neighbors of a given 3D position in the grid. + * \param[in] index3d the point in the grid + * \param[out] leaf the set of values + */ + void + getNeighborList1D (std::vector &leaf, + Eigen::Vector3i &index3d); + + /** \brief Class get name method. */ + std::string getClassName () const { return ("MarchingCubes"); } + + /** \brief Extract the surface. + * \param[out] output the resultant polygonal mesh + */ + virtual void + performReconstruction (pcl::PolygonMesh &output); + + /** \brief Extract the surface. + * \param[out] points the points of the extracted mesh + * \param[out] polygons the connectivity between the point of the extracted mesh. + */ + virtual void + performReconstruction (pcl::PointCloud &points, + std::vector &polygons); + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_SURFACE_MARCHING_CUBES_H_ + diff --git a/pcl-1.7/pcl/surface/marching_cubes_hoppe.h b/pcl-1.7/pcl/surface/marching_cubes_hoppe.h new file mode 100644 index 0000000..5ff5a8d --- /dev/null +++ b/pcl-1.7/pcl/surface/marching_cubes_hoppe.h @@ -0,0 +1,94 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SURFACE_MARCHING_CUBES_HOPPE_H_ +#define PCL_SURFACE_MARCHING_CUBES_HOPPE_H_ + +#include +#include + +namespace pcl +{ + /** \brief The marching cubes surface reconstruction algorithm, using a signed distance function based on the distance + * from tangent planes, proposed by Hoppe et. al. in: + * Hoppe H., DeRose T., Duchamp T., MC-Donald J., Stuetzle W., "Surface reconstruction from unorganized points", + * SIGGRAPH '92 + * \author Alexandru E. Ichim + * \ingroup surface + */ + template + class MarchingCubesHoppe : public MarchingCubes + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using SurfaceReconstruction::input_; + using SurfaceReconstruction::tree_; + using MarchingCubes::grid_; + using MarchingCubes::res_x_; + using MarchingCubes::res_y_; + using MarchingCubes::res_z_; + using MarchingCubes::min_p_; + using MarchingCubes::max_p_; + + typedef typename pcl::PointCloud::Ptr PointCloudPtr; + + typedef typename pcl::KdTree KdTree; + typedef typename pcl::KdTree::Ptr KdTreePtr; + + + /** \brief Constructor. */ + MarchingCubesHoppe (); + + /** \brief Destructor. */ + ~MarchingCubesHoppe (); + + /** \brief Convert the point cloud into voxel data. */ + void + voxelizeData (); + + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_SURFACE_MARCHING_CUBES_HOPPE_H_ + diff --git a/pcl-1.7/pcl/surface/marching_cubes_rbf.h b/pcl-1.7/pcl/surface/marching_cubes_rbf.h new file mode 100644 index 0000000..8b99dd8 --- /dev/null +++ b/pcl-1.7/pcl/surface/marching_cubes_rbf.h @@ -0,0 +1,117 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_SURFACE_MARCHING_CUBES_RBF_H_ +#define PCL_SURFACE_MARCHING_CUBES_RBF_H_ + +#include +#include + +namespace pcl +{ + /** \brief The marching cubes surface reconstruction algorithm, using a signed distance function based on radial + * basis functions. Partially based on: + * Carr J.C., Beatson R.K., Cherrie J.B., Mitchell T.J., Fright W.R., McCallum B.C. and Evans T.R., + * "Reconstruction and representation of 3D objects with radial basis functions" + * SIGGRAPH '01 + * + * \author Alexandru E. Ichim + * \ingroup surface + */ + template + class MarchingCubesRBF : public MarchingCubes + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using SurfaceReconstruction::input_; + using SurfaceReconstruction::tree_; + using MarchingCubes::grid_; + using MarchingCubes::res_x_; + using MarchingCubes::res_y_; + using MarchingCubes::res_z_; + using MarchingCubes::min_p_; + using MarchingCubes::max_p_; + + typedef typename pcl::PointCloud::Ptr PointCloudPtr; + + typedef typename pcl::KdTree KdTree; + typedef typename pcl::KdTree::Ptr KdTreePtr; + + + /** \brief Constructor. */ + MarchingCubesRBF (); + + /** \brief Destructor. */ + ~MarchingCubesRBF (); + + /** \brief Convert the point cloud into voxel data. */ + void + voxelizeData (); + + + /** \brief Set the off-surface points displacement value. + * \param[in] epsilon the value + */ + inline void + setOffSurfaceDisplacement (float epsilon) + { off_surface_epsilon_ = epsilon; } + + /** \brief Get the off-surface points displacement value. */ + inline float + getOffSurfaceDisplacement () + { return off_surface_epsilon_; } + + + protected: + /** \brief the Radial Basis Function kernel. */ + double + kernel (Eigen::Vector3d c, Eigen::Vector3d x); + + /** \brief The off-surface displacement value. */ + float off_surface_epsilon_; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_SURFACE_MARCHING_CUBES_RBF_H_ + diff --git a/pcl-1.7/pcl/surface/mls.h b/pcl-1.7/pcl/surface/mls.h new file mode 100644 index 0000000..8aeb9a2 --- /dev/null +++ b/pcl-1.7/pcl/surface/mls.h @@ -0,0 +1,595 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_MLS_H_ +#define PCL_MLS_H_ + +// PCL includes +#include +#include +#include + +#include +#include +#include +#include + +namespace pcl +{ + /** \brief MovingLeastSquares represent an implementation of the MLS (Moving Least Squares) algorithm + * for data smoothing and improved normal estimation. It also contains methods for upsampling the + * resulting cloud based on the parametric fit. + * Reference paper: "Computing and Rendering Point Set Surfaces" by Marc Alexa, Johannes Behr, + * Daniel Cohen-Or, Shachar Fleishman, David Levin and Claudio T. Silva + * www.sci.utah.edu/~shachar/Publications/crpss.pdf + * \author Zoltan Csaba Marton, Radu B. Rusu, Alexandru E. Ichim, Suat Gedikli + * \ingroup surface + */ + template + class MovingLeastSquares: public CloudSurfaceProcessing + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using PCLBase::input_; + using PCLBase::indices_; + using PCLBase::fake_indices_; + using PCLBase::initCompute; + using PCLBase::deinitCompute; + + typedef typename pcl::search::Search KdTree; + typedef typename pcl::search::Search::Ptr KdTreePtr; + typedef pcl::PointCloud NormalCloud; + typedef pcl::PointCloud::Ptr NormalCloudPtr; + + typedef pcl::PointCloud PointCloudOut; + typedef typename PointCloudOut::Ptr PointCloudOutPtr; + typedef typename PointCloudOut::ConstPtr PointCloudOutConstPtr; + + typedef pcl::PointCloud PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + typedef boost::function &, std::vector &)> SearchMethod; + + enum UpsamplingMethod {NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION}; + + /** \brief Empty constructor. */ + MovingLeastSquares () : CloudSurfaceProcessing (), + normals_ (), + distinct_cloud_ (), + search_method_ (), + tree_ (), + order_ (2), + polynomial_fit_ (true), + search_radius_ (0.0), + sqr_gauss_param_ (0.0), + compute_normals_ (false), + upsample_method_ (NONE), + upsampling_radius_ (0.0), + upsampling_step_ (0.0), + desired_num_points_in_radius_ (0), + mls_results_ (), + voxel_size_ (1.0), + dilation_iteration_num_ (0), + nr_coeff_ (), + corresponding_input_indices_ (), + rng_alg_ (), + rng_uniform_distribution_ () + {}; + + /** \brief Empty destructor */ + virtual ~MovingLeastSquares () {} + + + /** \brief Set whether the algorithm should also store the normals computed + * \note This is optional, but need a proper output cloud type + */ + inline void + setComputeNormals (bool compute_normals) { compute_normals_ = compute_normals; } + + /** \brief Provide a pointer to the search object. + * \param[in] tree a pointer to the spatial search object. + */ + inline void + setSearchMethod (const KdTreePtr &tree) + { + tree_ = tree; + // Declare the search locator definition + int (KdTree::*radiusSearch)(int index, double radius, std::vector &k_indices, std::vector &k_sqr_distances, unsigned int max_nn) const = &KdTree::radiusSearch; + search_method_ = boost::bind (radiusSearch, boost::ref (tree_), _1, _2, _3, _4, 0); + } + + /** \brief Get a pointer to the search method used. */ + inline KdTreePtr + getSearchMethod () { return (tree_); } + + /** \brief Set the order of the polynomial to be fit. + * \param[in] order the order of the polynomial + */ + inline void + setPolynomialOrder (int order) { order_ = order; } + + /** \brief Get the order of the polynomial to be fit. */ + inline int + getPolynomialOrder () { return (order_); } + + /** \brief Sets whether the surface and normal are approximated using a polynomial, or only via tangent estimation. + * \param[in] polynomial_fit set to true for polynomial fit + */ + inline void + setPolynomialFit (bool polynomial_fit) { polynomial_fit_ = polynomial_fit; } + + /** \brief Get the polynomial_fit value (true if the surface and normal are approximated using a polynomial). */ + inline bool + getPolynomialFit () { return (polynomial_fit_); } + + /** \brief Set the sphere radius that is to be used for determining the k-nearest neighbors used for fitting. + * \param[in] radius the sphere radius that is to contain all k-nearest neighbors + * \note Calling this method resets the squared Gaussian parameter to radius * radius ! + */ + inline void + setSearchRadius (double radius) { search_radius_ = radius; sqr_gauss_param_ = search_radius_ * search_radius_; } + + /** \brief Get the sphere radius used for determining the k-nearest neighbors. */ + inline double + getSearchRadius () { return (search_radius_); } + + /** \brief Set the parameter used for distance based weighting of neighbors (the square of the search radius works + * best in general). + * \param[in] sqr_gauss_param the squared Gaussian parameter + */ + inline void + setSqrGaussParam (double sqr_gauss_param) { sqr_gauss_param_ = sqr_gauss_param; } + + /** \brief Get the parameter for distance based weighting of neighbors. */ + inline double + getSqrGaussParam () const { return (sqr_gauss_param_); } + + /** \brief Set the upsampling method to be used + * \param method + * \note Options are: * NONE - no upsampling will be done, only the input points will be projected to their own + * MLS surfaces + * * DISTINCT_CLOUD - will project the points of the distinct cloud to the closest point on + * the MLS surface + * * SAMPLE_LOCAL_PLANE - the local plane of each input point will be sampled in a circular + * fashion using the \ref upsampling_radius_ and the \ref upsampling_step_ + * parameters + * * RANDOM_UNIFORM_DENSITY - the local plane of each input point will be sampled using an + * uniform random distribution such that the density of points is + * constant throughout the cloud - given by the \ref desired_num_points_in_radius_ + * parameter + * * VOXEL_GRID_DILATION - the input cloud will be inserted into a voxel grid with voxels of + * size \ref voxel_size_; this voxel grid will be dilated \ref dilation_iteration_num_ + * times and the resulting points will be projected to the MLS surface + * of the closest point in the input cloud; the result is a point cloud + * with filled holes and a constant point density + */ + inline void + setUpsamplingMethod (UpsamplingMethod method) { upsample_method_ = method; } + + /** \brief Set the distinct cloud used for the DISTINCT_CLOUD upsampling method. */ + inline void + setDistinctCloud (PointCloudInConstPtr distinct_cloud) { distinct_cloud_ = distinct_cloud; } + + /** \brief Get the distinct cloud used for the DISTINCT_CLOUD upsampling method. */ + inline PointCloudInConstPtr + getDistinctCloud () { return distinct_cloud_; } + + + /** \brief Set the radius of the circle in the local point plane that will be sampled + * \note Used only in the case of SAMPLE_LOCAL_PLANE upsampling + * \param[in] radius the radius of the circle + */ + inline void + setUpsamplingRadius (double radius) { upsampling_radius_ = radius; } + + /** \brief Get the radius of the circle in the local point plane that will be sampled + * \note Used only in the case of SAMPLE_LOCAL_PLANE upsampling + */ + inline double + getUpsamplingRadius () { return upsampling_radius_; } + + /** \brief Set the step size for the local plane sampling + * \note Used only in the case of SAMPLE_LOCAL_PLANE upsampling + * \param[in] step_size the step size + */ + inline void + setUpsamplingStepSize (double step_size) { upsampling_step_ = step_size; } + + + /** \brief Get the step size for the local plane sampling + * \note Used only in the case of SAMPLE_LOCAL_PLANE upsampling + */ + inline double + getUpsamplingStepSize () { return upsampling_step_; } + + /** \brief Set the parameter that specifies the desired number of points within the search radius + * \note Used only in the case of RANDOM_UNIFORM_DENSITY upsampling + * \param[in] desired_num_points_in_radius the desired number of points in the output cloud in a sphere of + * radius \ref search_radius_ around each point + */ + inline void + setPointDensity (int desired_num_points_in_radius) { desired_num_points_in_radius_ = desired_num_points_in_radius; } + + + /** \brief Get the parameter that specifies the desired number of points within the search radius + * \note Used only in the case of RANDOM_UNIFORM_DENSITY upsampling + */ + inline int + getPointDensity () { return desired_num_points_in_radius_; } + + /** \brief Set the voxel size for the voxel grid + * \note Used only in the VOXEL_GRID_DILATION upsampling method + * \param[in] voxel_size the edge length of a cubic voxel in the voxel grid + */ + inline void + setDilationVoxelSize (float voxel_size) { voxel_size_ = voxel_size; } + + + /** \brief Get the voxel size for the voxel grid + * \note Used only in the VOXEL_GRID_DILATION upsampling method + */ + inline float + getDilationVoxelSize () { return voxel_size_; } + + /** \brief Set the number of dilation steps of the voxel grid + * \note Used only in the VOXEL_GRID_DILATION upsampling method + * \param[in] iterations the number of dilation iterations + */ + inline void + setDilationIterations (int iterations) { dilation_iteration_num_ = iterations; } + + /** \brief Get the number of dilation steps of the voxel grid + * \note Used only in the VOXEL_GRID_DILATION upsampling method + */ + inline int + getDilationIterations () { return dilation_iteration_num_; } + + /** \brief Base method for surface reconstruction for all points given in + * \param[out] output the resultant reconstructed surface model + */ + void + process (PointCloudOut &output); + + + /** \brief Get the set of indices with each point in output having the + * corresponding point in input */ + inline PointIndicesPtr + getCorrespondingIndices () { return (corresponding_input_indices_); } + + protected: + /** \brief The point cloud that will hold the estimated normals, if set. */ + NormalCloudPtr normals_; + + /** \brief The distinct point cloud that will be projected to the MLS surface. */ + PointCloudInConstPtr distinct_cloud_; + + /** \brief The search method template for indices. */ + SearchMethod search_method_; + + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + + /** \brief The order of the polynomial to be fit. */ + int order_; + + /** True if the surface and normal be approximated using a polynomial, false if tangent estimation is sufficient. */ + bool polynomial_fit_; + + /** \brief The nearest neighbors search radius for each point. */ + double search_radius_; + + /** \brief Parameter for distance based weighting of neighbors (search_radius_ * search_radius_ works fine) */ + double sqr_gauss_param_; + + /** \brief Parameter that specifies whether the normals should be computed for the input cloud or not */ + bool compute_normals_; + + /** \brief Parameter that specifies the upsampling method to be used */ + UpsamplingMethod upsample_method_; + + /** \brief Radius of the circle in the local point plane that will be sampled + * \note Used only in the case of SAMPLE_LOCAL_PLANE upsampling + */ + double upsampling_radius_; + + /** \brief Step size for the local plane sampling + * \note Used only in the case of SAMPLE_LOCAL_PLANE upsampling + */ + double upsampling_step_; + + /** \brief Parameter that specifies the desired number of points within the search radius + * \note Used only in the case of RANDOM_UNIFORM_DENSITY upsampling + */ + int desired_num_points_in_radius_; + + + /** \brief Data structure used to store the results of the MLS fitting + * \note Used only in the case of VOXEL_GRID_DILATION or DISTINCT_CLOUD upsampling + */ + struct MLSResult + { + MLSResult () : mean (), plane_normal (), u_axis (), v_axis (), c_vec (), num_neighbors (), curvature (), valid (false) {} + + MLSResult (const Eigen::Vector3d &a_mean, + const Eigen::Vector3d &a_plane_normal, + const Eigen::Vector3d &a_u, + const Eigen::Vector3d &a_v, + const Eigen::VectorXd a_c_vec, + const int a_num_neighbors, + const float &a_curvature); + + Eigen::Vector3d mean, plane_normal, u_axis, v_axis; + Eigen::VectorXd c_vec; + int num_neighbors; + float curvature; + bool valid; + }; + + /** \brief Stores the MLS result for each point in the input cloud + * \note Used only in the case of VOXEL_GRID_DILATION or DISTINCT_CLOUD upsampling + */ + std::vector mls_results_; + + + /** \brief A minimalistic implementation of a voxel grid, necessary for the point cloud upsampling + * \note Used only in the case of VOXEL_GRID_DILATION upsampling + */ + class MLSVoxelGrid + { + public: + struct Leaf { Leaf () : valid (true) {} bool valid; }; + + MLSVoxelGrid (PointCloudInConstPtr& cloud, + IndicesPtr &indices, + float voxel_size); + + void + dilate (); + + inline void + getIndexIn1D (const Eigen::Vector3i &index, uint64_t &index_1d) const + { + index_1d = index[0] * data_size_ * data_size_ + + index[1] * data_size_ + index[2]; + } + + inline void + getIndexIn3D (uint64_t index_1d, Eigen::Vector3i& index_3d) const + { + index_3d[0] = static_cast (index_1d / (data_size_ * data_size_)); + index_1d -= index_3d[0] * data_size_ * data_size_; + index_3d[1] = static_cast (index_1d / data_size_); + index_1d -= index_3d[1] * data_size_; + index_3d[2] = static_cast (index_1d); + } + + inline void + getCellIndex (const Eigen::Vector3f &p, Eigen::Vector3i& index) const + { + for (int i = 0; i < 3; ++i) + index[i] = static_cast ((p[i] - bounding_min_(i)) / voxel_size_); + } + + inline void + getPosition (const uint64_t &index_1d, Eigen::Vector3f &point) const + { + Eigen::Vector3i index_3d; + getIndexIn3D (index_1d, index_3d); + for (int i = 0; i < 3; ++i) + point[i] = static_cast (index_3d[i]) * voxel_size_ + bounding_min_[i]; + } + + typedef std::map HashMap; + HashMap voxel_grid_; + Eigen::Vector4f bounding_min_, bounding_max_; + uint64_t data_size_; + float voxel_size_; + }; + + + /** \brief Voxel size for the VOXEL_GRID_DILATION upsampling method */ + float voxel_size_; + + /** \brief Number of dilation steps for the VOXEL_GRID_DILATION upsampling method */ + int dilation_iteration_num_; + + /** \brief Number of coefficients, to be computed from the requested order.*/ + int nr_coeff_; + + /** \brief Collects for each point in output the corrseponding point in the input. */ + PointIndicesPtr corresponding_input_indices_; + + /** \brief Search for the closest nearest neighbors of a given point using a radius search + * \param[in] index the index of the query point + * \param[out] indices the resultant vector of indices representing the k-nearest neighbors + * \param[out] sqr_distances the resultant squared distances from the query point to the k-nearest neighbors + */ + inline int + searchForNeighbors (int index, std::vector &indices, std::vector &sqr_distances) const + { + return (search_method_ (index, search_radius_, indices, sqr_distances)); + } + + /** \brief Smooth a given point and its neighborghood using Moving Least Squares. + * \param[in] index the inex of the query point in the input cloud + * \param[in] nn_indices the set of nearest neighbors indices for pt + * \param[in] nn_sqr_dists the set of nearest neighbors squared distances for pt + * \param[out] projected_points the set of points projected points around the query point + * (in the case of upsampling method NONE, only the query point projected to its own fitted surface will be returned, + * in the case of the other upsampling methods, multiple points will be returned) + * \param[out] projected_points_normals the normals corresponding to the projected points + * \param[out] corresponding_input_indices the set of indices with each point in output having the corresponding point in input + * \param[out] mls_result stores the MLS result for each point in the input cloud + * (used only in the case of VOXEL_GRID_DILATION or DISTINCT_CLOUD upsampling) + */ + void + computeMLSPointNormal (int index, + const std::vector &nn_indices, + std::vector &nn_sqr_dists, + PointCloudOut &projected_points, + NormalCloud &projected_points_normals, + PointIndices &corresponding_input_indices, + MLSResult &mls_result) const; + + /** \brief Fits a point (sample point) given in the local plane coordinates of an input point (query point) to + * the MLS surface of the input point + * \param[in] u_disp the u coordinate of the sample point in the local plane of the query point + * \param[in] v_disp the v coordinate of the sample point in the local plane of the query point + * \param[in] u_axis the axis corresponding to the u-coordinates of the local plane of the query point + * \param[in] v_axis the axis corresponding to the v-coordinates of the local plane of the query point + * \param[in] n_axis + * \param mean + * \param[in] curvature the curvature of the surface at the query point + * \param[in] c_vec the coefficients of the polynomial fit on the MLS surface of the query point + * \param[in] num_neighbors the number of neighbors of the query point in the input cloud + * \param[out] result_point the absolute 3D position of the resulting projected point + * \param[out] result_normal the normal of the resulting projected point + */ + void + projectPointToMLSSurface (float &u_disp, float &v_disp, + Eigen::Vector3d &u_axis, Eigen::Vector3d &v_axis, + Eigen::Vector3d &n_axis, + Eigen::Vector3d &mean, + float &curvature, + Eigen::VectorXd &c_vec, + int num_neighbors, + PointOutT &result_point, + pcl::Normal &result_normal) const; + + void + copyMissingFields (const PointInT &point_in, + PointOutT &point_out) const; + + /** \brief Abstract surface reconstruction method. + * \param[out] output the result of the reconstruction + */ + virtual void performProcessing (PointCloudOut &output); + + /** \brief Perform upsampling for the distinct-cloud and voxel-grid methods + * \param[out] output the result of the reconstruction + */ + void performUpsampling (PointCloudOut &output); + + private: + /** \brief Boost-based random number generator algorithm. */ + boost::mt19937 rng_alg_; + + /** \brief Random number generator using an uniform distribution of floats + * \note Used only in the case of RANDOM_UNIFORM_DENSITY upsampling + */ + boost::shared_ptr > + > rng_uniform_distribution_; + + /** \brief Abstract class get name method. */ + std::string getClassName () const { return ("MovingLeastSquares"); } + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + +#ifdef _OPENMP + /** \brief MovingLeastSquaresOMP is a parallelized version of MovingLeastSquares, using the OpenMP standard. + * \note Compared to MovingLeastSquares, an overhead is incurred in terms of runtime and memory usage. + * \note The upsampling methods DISTINCT_CLOUD and VOXEL_GRID_DILATION are not parallelized completely, i.e. parts of the algorithm run on a single thread only. + * \author Robert Huitl + * \ingroup surface + */ + template + class MovingLeastSquaresOMP: public MovingLeastSquares + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using PCLBase::input_; + using PCLBase::indices_; + using MovingLeastSquares::normals_; + using MovingLeastSquares::corresponding_input_indices_; + using MovingLeastSquares::nr_coeff_; + using MovingLeastSquares::order_; + using MovingLeastSquares::compute_normals_; + using MovingLeastSquares::upsample_method_; + using MovingLeastSquares::VOXEL_GRID_DILATION; + using MovingLeastSquares::DISTINCT_CLOUD; + + typedef pcl::PointCloud NormalCloud; + typedef pcl::PointCloud::Ptr NormalCloudPtr; + + typedef pcl::PointCloud PointCloudOut; + typedef typename PointCloudOut::Ptr PointCloudOutPtr; + typedef typename PointCloudOut::ConstPtr PointCloudOutConstPtr; + + /** \brief Constructor for parallelized Moving Least Squares + * \param threads the maximum number of hardware threads to use (0 sets the value to 1) + */ + MovingLeastSquaresOMP (unsigned int threads = 0) : threads_ (threads) + { + + } + + /** \brief Set the maximum number of threads to use + * \param threads the maximum number of hardware threads to use (0 sets the value to 1) + */ + inline void + setNumberOfThreads (unsigned int threads = 0) + { + threads_ = threads; + } + + protected: + /** \brief Abstract surface reconstruction method. + * \param[out] output the result of the reconstruction + */ + virtual void performProcessing (PointCloudOut &output); + + /** \brief The maximum number of threads the scheduler should use. */ + unsigned int threads_; + }; +#endif +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif /* #ifndef PCL_MLS_H_ */ diff --git a/pcl-1.7/pcl/surface/organized_fast_mesh.h b/pcl-1.7/pcl/surface/organized_fast_mesh.h new file mode 100644 index 0000000..f645236 --- /dev/null +++ b/pcl-1.7/pcl/surface/organized_fast_mesh.h @@ -0,0 +1,364 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Dirk Holz, University of Bonn. + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SURFACE_ORGANIZED_FAST_MESH_H_ +#define PCL_SURFACE_ORGANIZED_FAST_MESH_H_ + +#include +#include + +namespace pcl +{ + + /** \brief Simple triangulation/surface reconstruction for organized point + * clouds. Neighboring points (pixels in image space) are connected to + * construct a triangular (or quad) mesh. + * + * \note If you use this code in any academic work, please cite: + * D. Holz and S. Behnke. + * Fast Range Image Segmentation and Smoothing using Approximate Surface Reconstruction and Region Growing. + * In Proceedings of the 12th International Conference on Intelligent Autonomous Systems (IAS), + * Jeju Island, Korea, June 26-29 2012. + * http://purl.org/holz/papers/holz_2012_ias.pdf + * + * \author Dirk Holz, Radu B. Rusu + * \ingroup surface + */ + template + class OrganizedFastMesh : public MeshConstruction + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using MeshConstruction::input_; + using MeshConstruction::check_tree_; + + typedef typename pcl::PointCloud::Ptr PointCloudPtr; + + typedef std::vector Polygons; + + enum TriangulationType + { + TRIANGLE_RIGHT_CUT, // _always_ "cuts" a quad from top left to bottom right + TRIANGLE_LEFT_CUT, // _always_ "cuts" a quad from top right to bottom left + TRIANGLE_ADAPTIVE_CUT, // "cuts" where possible and prefers larger differences in 'z' direction + QUAD_MESH // create a simple quad mesh + }; + + /** \brief Constructor. Triangulation type defaults to \a QUAD_MESH. */ + OrganizedFastMesh () + : max_edge_length_squared_ (0.025f) + , triangle_pixel_size_rows_ (1) + , triangle_pixel_size_columns_ (1) + , triangulation_type_ (QUAD_MESH) + , store_shadowed_faces_ (false) + , cos_angle_tolerance_ (fabsf (cosf (pcl::deg2rad (12.5f)))) + { + check_tree_ = false; + }; + + /** \brief Destructor. */ + virtual ~OrganizedFastMesh () {}; + + /** \brief Set a maximum edge length. TODO: Implement! + * \param[in] max_edge_length the maximum edge length + */ + inline void + setMaxEdgeLength (float max_edge_length) + { + max_edge_length_squared_ = max_edge_length * max_edge_length; + }; + + /** \brief Set the edge length (in pixels) used for constructing the fixed mesh. + * \param[in] triangle_size edge length in pixels + * (Default: 1 = neighboring pixels are connected) + */ + inline void + setTrianglePixelSize (int triangle_size) + { + setTrianglePixelSizeRows (triangle_size); + setTrianglePixelSizeColumns (triangle_size); + } + + /** \brief Set the edge length (in pixels) used for iterating over rows when constructing the fixed mesh. + * \param[in] triangle_size edge length in pixels + * (Default: 1 = neighboring pixels are connected) + */ + inline void + setTrianglePixelSizeRows (int triangle_size) + { + triangle_pixel_size_rows_ = std::max (1, (triangle_size - 1)); + } + + /** \brief Set the edge length (in pixels) used for iterating over columns when constructing the fixed mesh. + * \param[in] triangle_size edge length in pixels + * (Default: 1 = neighboring pixels are connected) + */ + inline void + setTrianglePixelSizeColumns (int triangle_size) + { + triangle_pixel_size_columns_ = std::max (1, (triangle_size - 1)); + } + + /** \brief Set the triangulation type (see \a TriangulationType) + * \param[in] type quad mesh, triangle mesh with fixed left, right cut, + * or adaptive cut (splits a quad w.r.t. the depth (z) of the points) + */ + inline void + setTriangulationType (TriangulationType type) + { + triangulation_type_ = type; + } + + /** \brief Store shadowed faces or not. + * \param[in] enable set to true to store shadowed faces + */ + inline void + storeShadowedFaces (bool enable) + { + store_shadowed_faces_ = enable; + } + + protected: + /** \brief max (squared) length of edge */ + float max_edge_length_squared_; + + /** \brief size of triangle edges (in pixels) for iterating over rows. */ + int triangle_pixel_size_rows_; + + /** \brief size of triangle edges (in pixels) for iterating over columns*/ + int triangle_pixel_size_columns_; + + /** \brief Type of meshing scheme (quads vs. triangles, left cut vs. right cut ... */ + TriangulationType triangulation_type_; + + /** \brief Whether or not shadowed faces are stored, e.g., for exploration */ + bool store_shadowed_faces_; + + /** \brief (Cosine of the) angle tolerance used when checking whether or not an edge between two points is shadowed. */ + float cos_angle_tolerance_; + + /** \brief Perform the actual polygonal reconstruction. + * \param[out] polygons the resultant polygons + */ + void + reconstructPolygons (std::vector& polygons); + + /** \brief Create the surface. + * \param[out] polygons the resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices. + */ + virtual void + performReconstruction (std::vector &polygons); + + /** \brief Create the surface. + * + * Simply uses image indices to create an initial polygonal mesh for organized point clouds. + * \a indices_ are ignored! + * + * \param[out] output the resultant polygonal mesh + */ + void + performReconstruction (pcl::PolygonMesh &output); + + /** \brief Add a new triangle to the current polygon mesh + * \param[in] a index of the first vertex + * \param[in] b index of the second vertex + * \param[in] c index of the third vertex + * \param[in] idx the index in the set of polygon vertices (assumes \a idx is valid in \a polygons) + * \param[out] polygons the polygon mesh to be updated + */ + inline void + addTriangle (int a, int b, int c, int idx, std::vector& polygons) + { + assert (idx < static_cast (polygons.size ())); + polygons[idx].vertices.resize (3); + polygons[idx].vertices[0] = a; + polygons[idx].vertices[1] = b; + polygons[idx].vertices[2] = c; + } + + /** \brief Add a new quad to the current polygon mesh + * \param[in] a index of the first vertex + * \param[in] b index of the second vertex + * \param[in] c index of the third vertex + * \param[in] d index of the fourth vertex + * \param[in] idx the index in the set of polygon vertices (assumes \a idx is valid in \a polygons) + * \param[out] polygons the polygon mesh to be updated + */ + inline void + addQuad (int a, int b, int c, int d, int idx, std::vector& polygons) + { + assert (idx < static_cast (polygons.size ())); + polygons[idx].vertices.resize (4); + polygons[idx].vertices[0] = a; + polygons[idx].vertices[1] = b; + polygons[idx].vertices[2] = c; + polygons[idx].vertices[3] = d; + } + + /** \brief Set (all) coordinates of a particular point to the specified value + * \param[in] point_index index of point + * \param[out] mesh to modify + * \param[in] value value to use when re-setting + * \param[in] field_x_idx the X coordinate of the point + * \param[in] field_y_idx the Y coordinate of the point + * \param[in] field_z_idx the Z coordinate of the point + */ + inline void + resetPointData (const int &point_index, pcl::PolygonMesh &mesh, const float &value = 0.0f, + int field_x_idx = 0, int field_y_idx = 1, int field_z_idx = 2) + { + float new_value = value; + memcpy (&mesh.cloud.data[point_index * mesh.cloud.point_step + mesh.cloud.fields[field_x_idx].offset], &new_value, sizeof (float)); + memcpy (&mesh.cloud.data[point_index * mesh.cloud.point_step + mesh.cloud.fields[field_y_idx].offset], &new_value, sizeof (float)); + memcpy (&mesh.cloud.data[point_index * mesh.cloud.point_step + mesh.cloud.fields[field_z_idx].offset], &new_value, sizeof (float)); + } + + /** \brief Check if a point is shadowed by another point + * \param[in] point_a the first point + * \param[in] point_b the second point + */ + inline bool + isShadowed (const PointInT& point_a, const PointInT& point_b) + { + Eigen::Vector3f viewpoint = Eigen::Vector3f::Zero (); // TODO: allow for passing viewpoint information + Eigen::Vector3f dir_a = viewpoint - point_a.getVector3fMap (); + Eigen::Vector3f dir_b = point_b.getVector3fMap () - point_a.getVector3fMap (); + float distance_to_points = dir_a.norm (); + float distance_between_points = dir_b.norm (); + float cos_angle = dir_a.dot (dir_b) / (distance_to_points*distance_between_points); + if (cos_angle != cos_angle) + cos_angle = 1.0f; + return (fabs (cos_angle) >= cos_angle_tolerance_); + // TODO: check for both: angle almost 0/180 _and_ distance between points larger than noise level + } + + /** \brief Check if a triangle is valid. + * \param[in] a index of the first vertex + * \param[in] b index of the second vertex + * \param[in] c index of the third vertex + */ + inline bool + isValidTriangle (const int& a, const int& b, const int& c) + { + if (!pcl::isFinite (input_->points[a])) return (false); + if (!pcl::isFinite (input_->points[b])) return (false); + if (!pcl::isFinite (input_->points[c])) return (false); + return (true); + } + + /** \brief Check if a triangle is shadowed. + * \param[in] a index of the first vertex + * \param[in] b index of the second vertex + * \param[in] c index of the third vertex + */ + inline bool + isShadowedTriangle (const int& a, const int& b, const int& c) + { + if (isShadowed (input_->points[a], input_->points[b])) return (true); + if (isShadowed (input_->points[b], input_->points[c])) return (true); + if (isShadowed (input_->points[c], input_->points[a])) return (true); + return (false); + } + + /** \brief Check if a quad is valid. + * \param[in] a index of the first vertex + * \param[in] b index of the second vertex + * \param[in] c index of the third vertex + * \param[in] d index of the fourth vertex + */ + inline bool + isValidQuad (const int& a, const int& b, const int& c, const int& d) + { + if (!pcl::isFinite (input_->points[a])) return (false); + if (!pcl::isFinite (input_->points[b])) return (false); + if (!pcl::isFinite (input_->points[c])) return (false); + if (!pcl::isFinite (input_->points[d])) return (false); + return (true); + } + + /** \brief Check if a triangle is shadowed. + * \param[in] a index of the first vertex + * \param[in] b index of the second vertex + * \param[in] c index of the third vertex + * \param[in] d index of the fourth vertex + */ + inline bool + isShadowedQuad (const int& a, const int& b, const int& c, const int& d) + { + if (isShadowed (input_->points[a], input_->points[b])) return (true); + if (isShadowed (input_->points[b], input_->points[c])) return (true); + if (isShadowed (input_->points[c], input_->points[d])) return (true); + if (isShadowed (input_->points[d], input_->points[a])) return (true); + return (false); + } + + /** \brief Create a quad mesh. + * \param[out] polygons the resultant mesh + */ + void + makeQuadMesh (std::vector& polygons); + + /** \brief Create a right cut mesh. + * \param[out] polygons the resultant mesh + */ + void + makeRightCutMesh (std::vector& polygons); + + /** \brief Create a left cut mesh. + * \param[out] polygons the resultant mesh + */ + void + makeLeftCutMesh (std::vector& polygons); + + /** \brief Create an adaptive cut mesh. + * \param[out] polygons the resultant mesh + */ + void + makeAdaptiveCutMesh (std::vector& polygons); + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_SURFACE_ORGANIZED_FAST_MESH_H_ diff --git a/pcl-1.7/pcl/surface/poisson.h b/pcl-1.7/pcl/surface/poisson.h new file mode 100644 index 0000000..5b2b1ff --- /dev/null +++ b/pcl-1.7/pcl/surface/poisson.h @@ -0,0 +1,260 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SURFACE_POISSON_H_ +#define PCL_SURFACE_POISSON_H_ + +#include + +namespace pcl +{ + namespace poisson + { + class CoredVectorMeshData; + template struct Point3D; + } + + /** \brief The Poisson surface reconstruction algorithm. + * \note Code adapted from Misha Kazhdan: http://www.cs.jhu.edu/~misha/Code/PoissonRecon/ + * \note Based on the paper: + * * Michael Kazhdan, Matthew Bolitho, Hugues Hoppe, "Poisson surface reconstruction", + * SGP '06 Proceedings of the fourth Eurographics symposium on Geometry processing + * \author Alexandru-Eugen Ichim + * \ingroup surface + */ + template + class Poisson : public SurfaceReconstruction + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using SurfaceReconstruction::input_; + using SurfaceReconstruction::tree_; + + typedef typename pcl::PointCloud::Ptr PointCloudPtr; + + typedef typename pcl::KdTree KdTree; + typedef typename pcl::KdTree::Ptr KdTreePtr; + + /** \brief Constructor that sets all the parameters to working default values. */ + Poisson (); + + /** \brief Destructor. */ + ~Poisson (); + + /** \brief Create the surface. + * \param[out] output the resultant polygonal mesh + */ + void + performReconstruction (pcl::PolygonMesh &output); + + /** \brief Create the surface. + * \param[out] points the vertex positions of the resulting mesh + * \param[out] polygons the connectivity of the resulting mesh + */ + void + performReconstruction (pcl::PointCloud &points, + std::vector &polygons); + + /** \brief Set the maximum depth of the tree that will be used for surface reconstruction. + * \note Running at depth d corresponds to solving on a voxel grid whose resolution is no larger than + * 2^d x 2^d x 2^d. Note that since the reconstructor adapts the octree to the sampling density, the specified + * reconstruction depth is only an upper bound. + * \param[in] depth the depth parameter + */ + inline void + setDepth (int depth) { depth_ = depth; } + + /** \brief Get the depth parameter */ + inline int + getDepth () { return depth_; } + + inline void + setMinDepth (int min_depth) { min_depth_ = min_depth; } + + inline int + getMinDepth () { return min_depth_; } + + inline void + setPointWeight (float point_weight) { point_weight_ = point_weight; } + + inline float + getPointWeight () { return point_weight_; } + + /** \brief Set the ratio between the diameter of the cube used for reconstruction and the diameter of the + * samples' bounding cube. + * \param[in] scale the given parameter value + */ + inline void + setScale (float scale) { scale_ = scale; } + + /** Get the ratio between the diameter of the cube used for reconstruction and the diameter of the + * samples' bounding cube. + */ + inline float + getScale () { return scale_; } + + /** \brief Set the the depth at which a block Gauss-Seidel solver is used to solve the Laplacian equation + * \note Using this parameter helps reduce the memory overhead at the cost of a small increase in + * reconstruction time. (In practice, we have found that for reconstructions of depth 9 or higher a subdivide + * depth of 7 or 8 can greatly reduce the memory usage.) + * \param[in] solver_divide the given parameter value + */ + inline void + setSolverDivide (int solver_divide) { solver_divide_ = solver_divide; } + + /** \brief Get the the depth at which a block Gauss-Seidel solver is used to solve the Laplacian equation */ + inline int + getSolverDivide () { return solver_divide_; } + + /** \brief Set the depth at which a block iso-surface extractor should be used to extract the iso-surface + * \note Using this parameter helps reduce the memory overhead at the cost of a small increase in extraction + * time. (In practice, we have found that for reconstructions of depth 9 or higher a subdivide depth of 7 or 8 + * can greatly reduce the memory usage.) + * \param[in] iso_divide the given parameter value + */ + inline void + setIsoDivide (int iso_divide) { iso_divide_ = iso_divide; } + + /** \brief Get the depth at which a block iso-surface extractor should be used to extract the iso-surface */ + inline int + getIsoDivide () { return iso_divide_; } + + /** \brief Set the minimum number of sample points that should fall within an octree node as the octree + * construction is adapted to sampling density + * \note For noise-free samples, small values in the range [1.0 - 5.0] can be used. For more noisy samples, + * larger values in the range [15.0 - 20.0] may be needed to provide a smoother, noise-reduced, reconstruction. + * \param[in] samples_per_node the given parameter value + */ + inline void + setSamplesPerNode (float samples_per_node) { samples_per_node_ = samples_per_node; } + + /** \brief Get the minimum number of sample points that should fall within an octree node as the octree + * construction is adapted to sampling density + */ + inline float + getSamplesPerNode () { return samples_per_node_; } + + /** \brief Set the confidence flag + * \note Enabling this flag tells the reconstructor to use the size of the normals as confidence information. + * When the flag is not enabled, all normals are normalized to have unit-length prior to reconstruction. + * \param[in] confidence the given flag + */ + inline void + setConfidence (bool confidence) { confidence_ = confidence; } + + /** \brief Get the confidence flag */ + inline bool + getConfidence () { return confidence_; } + + /** \brief Enabling this flag tells the reconstructor to output a polygon mesh (rather than triangulating the + * results of Marching Cubes). + * \param[in] output_polygons the given flag + */ + inline void + setOutputPolygons (bool output_polygons) { output_polygons_ = output_polygons; } + + /** \brief Get whether the algorithm outputs a polygon mesh or a triangle mesh */ + inline bool + getOutputPolygons () { return output_polygons_; } + + /** \brief Set the degree parameter + * \param[in] degree the given degree + */ + inline void + setDegree (int degree) { degree_ = degree; } + + /** \brief Get the degree parameter */ + inline int + getDegree () { return degree_; } + + /** \brief Set the manifold flag. + * \note Enabling this flag tells the reconstructor to add the polygon barycenter when triangulating polygons + * with more than three vertices. + * \param[in] manifold the given flag + */ + inline void + setManifold (bool manifold) { manifold_ = manifold; } + + /** \brief Get the manifold flag */ + inline bool + getManifold () { return manifold_; } + + protected: + /** \brief Class get name method. */ + std::string + getClassName () const { return ("Poisson"); } + + private: + int depth_; + int min_depth_; + float point_weight_; + float scale_; + int solver_divide_; + int iso_divide_; + float samples_per_node_; + bool confidence_; + bool output_polygons_; + + bool no_reset_samples_; + bool no_clip_tree_; + bool manifold_; + + int refine_; + int kernel_depth_; + int degree_; + bool non_adaptive_weights_; + bool show_residual_; + int min_iterations_; + float solver_accuracy_; + + template void + execute (poisson::CoredVectorMeshData &mesh, + poisson::Point3D &translate, + float &scale); + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_SURFACE_POISSON_H_ diff --git a/pcl-1.7/pcl/surface/processing.h b/pcl-1.7/pcl/surface/processing.h new file mode 100644 index 0000000..bc4396c --- /dev/null +++ b/pcl-1.7/pcl/surface/processing.h @@ -0,0 +1,154 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_MESH_PROCESSING_H_ +#define PCL_MESH_PROCESSING_H_ + +#include +#include +#include + +namespace pcl +{ + /** \brief @b CloudSurfaceProcessing represents the base class for algorithms that takes a point cloud as input and + * produces a new output cloud that has been modified towards a better surface representation. These types of + * algorithms include surface smoothing, hole filling, cloud upsampling etc. + * + * \author Alexandru E. Ichim + * \ingroup surface + */ + template + class CloudSurfaceProcessing : public PCLBase + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using PCLBase::input_; + using PCLBase::indices_; + using PCLBase::initCompute; + using PCLBase::deinitCompute; + + public: + /** \brief Constructor. */ + CloudSurfaceProcessing () : PCLBase () + {}; + + /** \brief Empty destructor */ + virtual ~CloudSurfaceProcessing () {} + + /** \brief Process the input cloud and store the results + * \param[out] output the cloud where the results will be stored + */ + virtual void + process (pcl::PointCloud &output); + + protected: + /** \brief Abstract cloud processing method */ + virtual void + performProcessing (pcl::PointCloud &output) = 0; + + }; + + + /** \brief @b MeshProcessing represents the base class for mesh processing algorithms. + * \author Alexandru E. Ichim + * \ingroup surface + */ + class PCL_EXPORTS MeshProcessing + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef PolygonMesh::ConstPtr PolygonMeshConstPtr; + + /** \brief Constructor. */ + MeshProcessing () : input_mesh_ () {} + + /** \brief Destructor. */ + virtual ~MeshProcessing () {} + + /** \brief Set the input mesh that we want to process + * \param[in] input the input polygonal mesh + */ + inline void + setInputMesh (const pcl::PolygonMeshConstPtr &input) + { input_mesh_ = input; } + + /** \brief Get the input mesh to be processed + * \returns the mesh + */ + inline pcl::PolygonMeshConstPtr + getInputMesh () const + { return input_mesh_; } + + /** \brief Process the input surface mesh and store the results + * \param[out] output the resultant processed surface model + */ + void + process (pcl::PolygonMesh &output); + + protected: + /** \brief Initialize computation. Must be called before processing starts. */ + virtual bool + initCompute (); + + /** \brief UnInitialize computation. Must be called after processing ends. */ + virtual void + deinitCompute (); + + /** \brief Abstract surface processing method. */ + virtual void + performProcessing (pcl::PolygonMesh &output) = 0; + + /** \brief Abstract class get name method. */ + virtual std::string + getClassName () const + { return (""); } + + /** \brief Input polygonal mesh. */ + pcl::PolygonMeshConstPtr input_mesh_; + }; +} + +#include "pcl/surface/impl/processing.hpp" + +#endif /* PCL_MESH_PROCESSING_H_ */ + diff --git a/pcl-1.7/pcl/surface/qhull.h b/pcl-1.7/pcl/surface/qhull.h new file mode 100644 index 0000000..ac73899 --- /dev/null +++ b/pcl-1.7/pcl/surface/qhull.h @@ -0,0 +1,75 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: concave_hull.h 5027 2012-03-12 03:10:45Z rusu $ + * + */ + +#include +#ifdef HAVE_QHULL + +#ifndef PCL_QHULL_H +#define PCL_QHULL_H + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +extern "C" +{ +#ifdef HAVE_QHULL_2011 +# include "libqhull/libqhull.h" +# include "libqhull/mem.h" +# include "libqhull/qset.h" +# include "libqhull/geom.h" +# include "libqhull/merge.h" +# include "libqhull/poly.h" +# include "libqhull/io.h" +# include "libqhull/stat.h" +#else +# include "qhull/qhull.h" +# include "qhull/mem.h" +# include "qhull/qset.h" +# include "qhull/geom.h" +# include "qhull/merge.h" +# include "qhull/poly.h" +# include "qhull/io.h" +# include "qhull/stat.h" +#endif +} + +#endif // PCL_QHULL_H +#endif + diff --git a/pcl-1.7/pcl/surface/reconstruction.h b/pcl-1.7/pcl/surface/reconstruction.h new file mode 100644 index 0000000..13a9bb3 --- /dev/null +++ b/pcl-1.7/pcl/surface/reconstruction.h @@ -0,0 +1,249 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SURFACE_RECONSTRUCTION_H_ +#define PCL_SURFACE_RECONSTRUCTION_H_ + +#include +#include +#include +#include +#include + +namespace pcl +{ + /** \brief Pure abstract class. All types of meshing/reconstruction + * algorithms in \b libpcl_surface must inherit from this, in order to make + * sure we have a consistent API. The methods that we care about here are: + * + * - \b setSearchMethod(&SearchPtr): passes a search locator + * - \b reconstruct(&PolygonMesh): creates a PolygonMesh object from the input data + * + * \author Radu B. Rusu, Michael Dixon, Alexandru E. Ichim + */ + template + class PCLSurfaceBase: public PCLBase + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef typename pcl::search::Search KdTree; + typedef typename pcl::search::Search::Ptr KdTreePtr; + + /** \brief Empty constructor. */ + PCLSurfaceBase () : tree_ () {} + + /** \brief Empty destructor */ + virtual ~PCLSurfaceBase () {} + + /** \brief Provide an optional pointer to a search object. + * \param[in] tree a pointer to the spatial search object. + */ + inline void + setSearchMethod (const KdTreePtr &tree) + { + tree_ = tree; + } + + /** \brief Get a pointer to the search method used. */ + inline KdTreePtr + getSearchMethod () { return (tree_); } + + /** \brief Base method for surface reconstruction for all points given in + * + * \param[out] output the resultant reconstructed surface model + */ + virtual void + reconstruct (pcl::PolygonMesh &output) = 0; + + protected: + /** \brief A pointer to the spatial search object. */ + KdTreePtr tree_; + + /** \brief Abstract class get name method. */ + virtual std::string + getClassName () const { return (""); } + }; + + /** \brief SurfaceReconstruction represents a base surface reconstruction + * class. All \b surface reconstruction methods take in a point cloud and + * generate a new surface from it, by either re-sampling the data or + * generating new data altogether. These methods are thus \b not preserving + * the topology of the original data. + * + * \note Reconstruction methods that always preserve the original input + * point cloud data as the surface vertices and simply construct the mesh on + * top should inherit from \ref MeshConstruction. + * + * \author Radu B. Rusu, Michael Dixon, Alexandru E. Ichim + * \ingroup surface + */ + template + class SurfaceReconstruction: public PCLSurfaceBase + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using PCLSurfaceBase::input_; + using PCLSurfaceBase::indices_; + using PCLSurfaceBase::initCompute; + using PCLSurfaceBase::deinitCompute; + using PCLSurfaceBase::tree_; + using PCLSurfaceBase::getClassName; + + /** \brief Constructor. */ + SurfaceReconstruction () : check_tree_ (true) {} + + /** \brief Destructor. */ + virtual ~SurfaceReconstruction () {} + + /** \brief Base method for surface reconstruction for all points given in + * + * \param[out] output the resultant reconstructed surface model + */ + virtual void + reconstruct (pcl::PolygonMesh &output); + + /** \brief Base method for surface reconstruction for all points given in + * + * \param[out] points the resultant points lying on the new surface + * \param[out] polygons the resultant polygons, as a set of + * vertices. The Vertices structure contains an array of point indices. + */ + virtual void + reconstruct (pcl::PointCloud &points, + std::vector &polygons); + + protected: + /** \brief A flag specifying whether or not the derived reconstruction + * algorithm needs the search object \a tree.*/ + bool check_tree_; + + /** \brief Abstract surface reconstruction method. + * \param[out] output the output polygonal mesh + */ + virtual void + performReconstruction (pcl::PolygonMesh &output) = 0; + + /** \brief Abstract surface reconstruction method. + * \param[out] points the resultant points lying on the surface + * \param[out] polygons the resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices. + */ + virtual void + performReconstruction (pcl::PointCloud &points, + std::vector &polygons) = 0; + }; + + /** \brief MeshConstruction represents a base surface reconstruction + * class. All \b mesh constructing methods that take in a point cloud and + * generate a surface that uses the original data as vertices should inherit + * from this class. + * + * \note Reconstruction methods that generate a new surface or create new + * vertices in locations different than the input data should inherit from + * \ref SurfaceReconstruction. + * + * \author Radu B. Rusu, Michael Dixon, Alexandru E. Ichim + * \ingroup surface + */ + template + class MeshConstruction: public PCLSurfaceBase + { + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + using PCLSurfaceBase::input_; + using PCLSurfaceBase::indices_; + using PCLSurfaceBase::initCompute; + using PCLSurfaceBase::deinitCompute; + using PCLSurfaceBase::tree_; + using PCLSurfaceBase::getClassName; + + /** \brief Constructor. */ + MeshConstruction () : check_tree_ (true) {} + + /** \brief Destructor. */ + virtual ~MeshConstruction () {} + + /** \brief Base method for surface reconstruction for all points given in + * + * \param[out] output the resultant reconstructed surface model + * + * \note This method copies the input point cloud data from + * PointCloud to PCLPointCloud2, and is implemented here for backwards + * compatibility only! + * + */ + virtual void + reconstruct (pcl::PolygonMesh &output); + + /** \brief Base method for mesh construction for all points given in + * + * \param[out] polygons the resultant polygons, as a set of + * vertices. The Vertices structure contains an array of point indices. + */ + virtual void + reconstruct (std::vector &polygons); + + protected: + /** \brief A flag specifying whether or not the derived reconstruction + * algorithm needs the search object \a tree.*/ + bool check_tree_; + + /** \brief Abstract surface reconstruction method. + * \param[out] output the output polygonal mesh + */ + virtual void + performReconstruction (pcl::PolygonMesh &output) = 0; + + /** \brief Abstract surface reconstruction method. + * \param[out] polygons the resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices. + */ + virtual void + performReconstruction (std::vector &polygons) = 0; + }; +} + +#include + +#endif // PCL_SURFACE_RECONSTRUCTION_H_ + diff --git a/pcl-1.7/pcl/surface/simplification_remove_unused_vertices.h b/pcl-1.7/pcl/surface/simplification_remove_unused_vertices.h new file mode 100644 index 0000000..33a50e3 --- /dev/null +++ b/pcl-1.7/pcl/surface/simplification_remove_unused_vertices.h @@ -0,0 +1,83 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Dirk Holz, University of Bonn. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SURFACE_SIMPLIFICATION_REMOVE_UNUSED_VERTICES_H_ +#define PCL_SURFACE_SIMPLIFICATION_REMOVE_UNUSED_VERTICES_H_ + +#include +#include +#include + +namespace pcl +{ + namespace surface + { + class PCL_EXPORTS SimplificationRemoveUnusedVertices + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + /** \brief Constructor. */ + SimplificationRemoveUnusedVertices () {}; + /** \brief Destructor. */ + ~SimplificationRemoveUnusedVertices () {}; + + /** \brief Simply a polygonal mesh. + * \param[in] input the input mesh + * \param[out] output the output mesh + */ + inline void + simplify (const pcl::PolygonMesh& input, pcl::PolygonMesh& output) + { + std::vector indices; + simplify (input, output, indices); + } + + /** \brief Perform simplification (remove unused vertices). + * \param[in] input the input mesh + * \param[out] output the output mesh + * \param[out] indices the resultant vector of indices + */ + void + simplify (const pcl::PolygonMesh& input, pcl::PolygonMesh& output, std::vector& indices); + + }; + } +} + +#endif /* PCL_SURFACE_SIMPLIFICATION_REMOVE_UNUSED_VERTICES_H_ */ diff --git a/pcl-1.7/pcl/surface/surfel_smoothing.h b/pcl-1.7/pcl/surface/surfel_smoothing.h new file mode 100644 index 0000000..a22c4af --- /dev/null +++ b/pcl-1.7/pcl/surface/surfel_smoothing.h @@ -0,0 +1,118 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Alexandru-Eugen Ichim + * Willow Garage, Inc + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#ifndef PCL_SURFEL_SMOOTHING_H_ +#define PCL_SURFEL_SMOOTHING_H_ + +#include +#include + +namespace pcl +{ + template + class SurfelSmoothing : public PCLBase + { + using PCLBase::input_; + using PCLBase::initCompute; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + typedef pcl::PointCloud PointCloudIn; + typedef typename pcl::PointCloud::Ptr PointCloudInPtr; + typedef pcl::PointCloud NormalCloud; + typedef typename pcl::PointCloud::Ptr NormalCloudPtr; + typedef pcl::search::Search CloudKdTree; + typedef typename pcl::search::Search::Ptr CloudKdTreePtr; + + SurfelSmoothing (float a_scale = 0.01) + : PCLBase () + , scale_ (a_scale) + , scale_squared_ (a_scale * a_scale) + , normals_ () + , interm_cloud_ () + , interm_normals_ () + , tree_ () + { + } + + void + setInputNormals (NormalCloudPtr &a_normals) { normals_ = a_normals; }; + + void + setSearchMethod (const CloudKdTreePtr &a_tree) { tree_ = a_tree; }; + + bool + initCompute (); + + float + smoothCloudIteration (PointCloudInPtr &output_positions, + NormalCloudPtr &output_normals); + + void + computeSmoothedCloud (PointCloudInPtr &output_positions, + NormalCloudPtr &output_normals); + + + void + smoothPoint (size_t &point_index, + PointT &output_point, + PointNT &output_normal); + + void + extractSalientFeaturesBetweenScales (PointCloudInPtr &cloud2, + NormalCloudPtr &cloud2_normals, + boost::shared_ptr > &output_features); + + private: + float scale_, scale_squared_; + NormalCloudPtr normals_; + + PointCloudInPtr interm_cloud_; + NormalCloudPtr interm_normals_; + + CloudKdTreePtr tree_; + + }; +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_SURFEL_SMOOTHING_H_ diff --git a/pcl-1.7/pcl/surface/texture_mapping.h b/pcl-1.7/pcl/surface/texture_mapping.h new file mode 100644 index 0000000..17bddcc --- /dev/null +++ b/pcl-1.7/pcl/surface/texture_mapping.h @@ -0,0 +1,427 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SURFACE_TEXTURE_MAPPING_H_ +#define PCL_SURFACE_TEXTURE_MAPPING_H_ + +#include +#include +#include + + +namespace pcl +{ + namespace texture_mapping + { + + /** \brief Structure to store camera pose and focal length. + * + * One can assign a value to focal_length, to be used along + * both camera axes or, optionally, axis-specific values + * (focal_length_w and focal_length_h). Optionally, one can + * also specify center-of-focus using parameters + * center_w and center_h. If the center-of-focus is not + * specified, it will be set to the geometric center of + * the camera, as defined by the width and height parameters. + */ + struct Camera + { + Camera () : pose (), focal_length (), focal_length_w (-1), focal_length_h (-1), + center_w (-1), center_h (-1), height (), width (), texture_file () {} + Eigen::Affine3f pose; + double focal_length; + double focal_length_w; // optional + double focal_length_h; // optinoal + double center_w; // optional + double center_h; // optional + double height; + double width; + std::string texture_file; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + /** \brief Structure that links a uv coordinate to its 3D point and face. + */ + struct UvIndex + { + UvIndex () : idx_cloud (), idx_face () {} + int idx_cloud; // Index of the PointXYZ in the camera's cloud + int idx_face; // Face corresponding to that projection + }; + + typedef std::vector > CameraVector; + + } + + /** \brief The texture mapping algorithm + * \author Khai Tran, Raphael Favier + * \ingroup surface + */ + template + class TextureMapping + { + public: + + typedef boost::shared_ptr< PointInT > Ptr; + typedef boost::shared_ptr< const PointInT > ConstPtr; + + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef pcl::octree::OctreePointCloudSearch Octree; + typedef typename Octree::Ptr OctreePtr; + typedef typename Octree::ConstPtr OctreeConstPtr; + + typedef pcl::texture_mapping::Camera Camera; + typedef pcl::texture_mapping::UvIndex UvIndex; + + /** \brief Constructor. */ + TextureMapping () : + f_ (), vector_field_ (), tex_files_ (), tex_material_ () + { + } + + /** \brief Destructor. */ + ~TextureMapping () + { + } + + /** \brief Set mesh scale control + * \param[in] f + */ + inline void + setF (float f) + { + f_ = f; + } + + /** \brief Set vector field + * \param[in] x data point x + * \param[in] y data point y + * \param[in] z data point z + */ + inline void + setVectorField (float x, float y, float z) + { + vector_field_ = Eigen::Vector3f (x, y, z); + // normalize vector field + vector_field_ = vector_field_ / std::sqrt (vector_field_.dot (vector_field_)); + } + + /** \brief Set texture files + * \param[in] tex_files list of texture files + */ + inline void + setTextureFiles (std::vector tex_files) + { + tex_files_ = tex_files; + } + + /** \brief Set texture materials + * \param[in] tex_material texture material + */ + inline void + setTextureMaterials (TexMaterial tex_material) + { + tex_material_ = tex_material; + } + + /** \brief Map texture to a mesh synthesis algorithm + * \param[in] tex_mesh texture mesh + */ + void + mapTexture2Mesh (pcl::TextureMesh &tex_mesh); + + /** \brief Map texture to a mesh UV mapping + * \param[in] tex_mesh texture mesh + */ + void + mapTexture2MeshUV (pcl::TextureMesh &tex_mesh); + + /** \brief Map textures acquired from a set of cameras onto a mesh. + * \details With UV mapping, the mesh must be divided into NbCamera + 1 sub-meshes. + * Each sub-mesh corresponding to the faces visible by one camera. The last submesh containing all non-visible faces + * \param[in] tex_mesh texture mesh + * \param[in] cams cameras used for UV mapping + */ + void + mapMultipleTexturesToMeshUV (pcl::TextureMesh &tex_mesh, + pcl::texture_mapping::CameraVector &cams); + + /** \brief computes UV coordinates of point, observed by one particular camera + * \param[in] pt XYZ point to project on camera plane + * \param[in] cam the camera used for projection + * \param[out] UV_coordinates the resulting uv coordinates. Set to (-1.0,-1.0) if the point is not visible by the camera + * \returns false if the point is not visible by the camera + */ + inline bool + getPointUVCoordinates (const pcl::PointXYZ &pt, const Camera &cam, Eigen::Vector2f &UV_coordinates) + { + // if the point is in front of the camera + if (pt.z > 0) + { + // compute image center and dimension + double sizeX = cam.width; + double sizeY = cam.height; + double cx, cy; + if (cam.center_w > 0) + cx = cam.center_w; + else + cx = (sizeX) / 2.0; + if (cam.center_h > 0) + cy = cam.center_h; + else + cy = (sizeY) / 2.0; + + double focal_x, focal_y; + if (cam.focal_length_w > 0) + focal_x = cam.focal_length_w; + else + focal_x = cam.focal_length; + if (cam.focal_length_h>0) + focal_y = cam.focal_length_h; + else + focal_y = cam.focal_length; + + // project point on image frame + UV_coordinates[0] = static_cast ((focal_x * (pt.x / pt.z) + cx) / sizeX); //horizontal + UV_coordinates[1] = 1.0f - static_cast (((focal_y * (pt.y / pt.z) + cy) / sizeY)); //vertical + + // point is visible! + if (UV_coordinates[0] >= 0.0 && UV_coordinates[0] <= 1.0 && UV_coordinates[1] >= 0.0 && UV_coordinates[1] + <= 1.0) + return (true); + } + + // point is NOT visible by the camera + UV_coordinates[0] = -1.0; + UV_coordinates[1] = -1.0; + return (false); + } + + /** \brief Check if a point is occluded using raycasting on octree. + * \param[in] pt XYZ from which the ray will start (toward the camera) + * \param[in] octree the octree used for raycasting. It must be initialized with a cloud transformed into the camera's frame + * \returns true if the point is occluded. + */ + inline bool + isPointOccluded (const pcl::PointXYZ &pt, const OctreePtr octree); + + /** \brief Remove occluded points from a point cloud + * \param[in] input_cloud the cloud on which to perform occlusion detection + * \param[out] filtered_cloud resulting cloud, containing only visible points + * \param[in] octree_voxel_size octree resolution (in meters) + * \param[out] visible_indices will contain indices of visible points + * \param[out] occluded_indices will contain indices of occluded points + */ + void + removeOccludedPoints (const PointCloudPtr &input_cloud, + PointCloudPtr &filtered_cloud, const double octree_voxel_size, + std::vector &visible_indices, std::vector &occluded_indices); + + /** \brief Remove occluded points from a textureMesh + * \param[in] tex_mesh input mesh, on witch to perform occlusion detection + * \param[out] cleaned_mesh resulting mesh, containing only visible points + * \param[in] octree_voxel_size octree resolution (in meters) + */ + void + removeOccludedPoints (const pcl::TextureMesh &tex_mesh, pcl::TextureMesh &cleaned_mesh, const double octree_voxel_size); + + + /** \brief Remove occluded points from a textureMesh + * \param[in] tex_mesh input mesh, on witch to perform occlusion detection + * \param[out] filtered_cloud resulting cloud, containing only visible points + * \param[in] octree_voxel_size octree resolution (in meters) + */ + void + removeOccludedPoints (const pcl::TextureMesh &tex_mesh, PointCloudPtr &filtered_cloud, const double octree_voxel_size); + + + /** \brief Segment faces by camera visibility. Point-based segmentation. + * \details With N camera, faces will be arranged into N+1 groups: 1 for each camera, plus 1 for faces not visible from any camera. + * \param[in] tex_mesh input mesh that needs sorting. Must contain only 1 sub-mesh. + * \param[in] sorted_mesh resulting mesh, will contain nbCamera + 1 sub-mesh. + * \param[in] cameras vector containing the cameras used for texture mapping. + * \param[in] octree_voxel_size octree resolution (in meters) + * \param[out] visible_pts cloud containing only visible points + */ + int + sortFacesByCamera (pcl::TextureMesh &tex_mesh, + pcl::TextureMesh &sorted_mesh, + const pcl::texture_mapping::CameraVector &cameras, + const double octree_voxel_size, PointCloud &visible_pts); + + /** \brief Colors a point cloud, depending on its occlusions. + * \details If showNbOcclusions is set to True, each point is colored depending on the number of points occluding it. + * Else, each point is given a different a 0 value is not occluded, 1 if occluded. + * By default, the number of occlusions is bounded to 4. + * \param[in] input_cloud input cloud on which occlusions will be computed. + * \param[out] colored_cloud resulting colored cloud showing the number of occlusions per point. + * \param[in] octree_voxel_size octree resolution (in meters). + * \param[in] show_nb_occlusions If false, color information will only represent. + * \param[in] max_occlusions Limit the number of occlusions per point. + */ + void + showOcclusions (const PointCloudPtr &input_cloud, + pcl::PointCloud::Ptr &colored_cloud, + const double octree_voxel_size, + const bool show_nb_occlusions = true, + const int max_occlusions = 4); + + /** \brief Colors the point cloud of a Mesh, depending on its occlusions. + * \details If showNbOcclusions is set to True, each point is colored depending on the number of points occluding it. + * Else, each point is given a different a 0 value is not occluded, 1 if occluded. + * By default, the number of occlusions is bounded to 4. + * \param[in] tex_mesh input mesh on which occlusions will be computed. + * \param[out] colored_cloud resulting colored cloud showing the number of occlusions per point. + * \param[in] octree_voxel_size octree resolution (in meters). + * \param[in] show_nb_occlusions If false, color information will only represent. + * \param[in] max_occlusions Limit the number of occlusions per point. + */ + void + showOcclusions (pcl::TextureMesh &tex_mesh, + pcl::PointCloud::Ptr &colored_cloud, + double octree_voxel_size, + bool show_nb_occlusions = true, + int max_occlusions = 4); + + /** \brief Segment and texture faces by camera visibility. Face-based segmentation. + * \details With N camera, faces will be arranged into N+1 groups: 1 for each camera, plus 1 for faces not visible from any camera. + * The mesh will also contain uv coordinates for each face + * \param mesh input mesh that needs sorting. Should contain only 1 sub-mesh. + * \param[in] cameras vector containing the cameras used for texture mapping. + */ + void + textureMeshwithMultipleCameras (pcl::TextureMesh &mesh, + const pcl::texture_mapping::CameraVector &cameras); + + protected: + /** \brief mesh scale control. */ + float f_; + + /** \brief vector field */ + Eigen::Vector3f vector_field_; + + /** \brief list of texture files */ + std::vector tex_files_; + + /** \brief list of texture materials */ + TexMaterial tex_material_; + + /** \brief Map texture to a face + * \param[in] p1 the first point + * \param[in] p2 the second point + * \param[in] p3 the third point + */ + std::vector + mapTexture2Face (const Eigen::Vector3f &p1, const Eigen::Vector3f &p2, const Eigen::Vector3f &p3); + + /** \brief Returns the circumcenter of a triangle and the circle's radius. + * \details see http://en.wikipedia.org/wiki/Circumcenter for formulas. + * \param[in] p1 first point of the triangle. + * \param[in] p2 second point of the triangle. + * \param[in] p3 third point of the triangle. + * \param[out] circumcenter resulting circumcenter + * \param[out] radius the radius of the circumscribed circle. + */ + inline void + getTriangleCircumcenterAndSize (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circumcenter, double &radius); + + + /** \brief Returns the centroid of a triangle and the corresponding circumscribed circle's radius. + * \details yield a tighter circle than getTriangleCircumcenterAndSize. + * \param[in] p1 first point of the triangle. + * \param[in] p2 second point of the triangle. + * \param[in] p3 third point of the triangle. + * \param[out] circumcenter resulting circumcenter + * \param[out] radius the radius of the circumscribed circle. + */ + inline void + getTriangleCircumcscribedCircleCentroid ( const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circumcenter, double &radius); + + + /** \brief computes UV coordinates of point, observed by one particular camera + * \param[in] pt XYZ point to project on camera plane + * \param[in] cam the camera used for projection + * \param[out] UV_coordinates the resulting UV coordinates. Set to (-1.0,-1.0) if the point is not visible by the camera + * \returns false if the point is not visible by the camera + */ + inline bool + getPointUVCoordinates (const pcl::PointXYZ &pt, const Camera &cam, pcl::PointXY &UV_coordinates); + + /** \brief Returns true if all the vertices of one face are projected on the camera's image plane. + * \param[in] camera camera on which to project the face. + * \param[in] p1 first point of the face. + * \param[in] p2 second point of the face. + * \param[in] p3 third point of the face. + * \param[out] proj1 UV coordinates corresponding to p1. + * \param[out] proj2 UV coordinates corresponding to p2. + * \param[out] proj3 UV coordinates corresponding to p3. + */ + inline bool + isFaceProjected (const Camera &camera, + const pcl::PointXYZ &p1, const pcl::PointXYZ &p2, const pcl::PointXYZ &p3, + pcl::PointXY &proj1, pcl::PointXY &proj2, pcl::PointXY &proj3); + + /** \brief Returns True if a point lays within a triangle + * \details see http://www.blackpawn.com/texts/pointinpoly/default.html + * \param[in] p1 first point of the triangle. + * \param[in] p2 second point of the triangle. + * \param[in] p3 third point of the triangle. + * \param[in] pt the querry point. + */ + inline bool + checkPointInsideTriangle (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, const pcl::PointXY &pt); + + /** \brief Class get name method. */ + std::string + getClassName () const + { + return ("TextureMapping"); + } + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} + +#endif /* TEXTURE_MAPPING_H_ */ + diff --git a/pcl-1.7/pcl/surface/vtk_smoothing/vtk.h b/pcl-1.7/pcl/surface/vtk_smoothing/vtk.h new file mode 100644 index 0000000..2721e37 --- /dev/null +++ b/pcl-1.7/pcl/surface/vtk_smoothing/vtk.h @@ -0,0 +1,50 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_SURFACE_VTK_H_ +#define PCL_SURFACE_VTK_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include + +#endif // PCL_SURFACE_VTK_H_ + diff --git a/pcl-1.7/pcl/surface/vtk_smoothing/vtk_mesh_quadric_decimation.h b/pcl-1.7/pcl/surface/vtk_smoothing/vtk_mesh_quadric_decimation.h new file mode 100644 index 0000000..eae4fcb --- /dev/null +++ b/pcl-1.7/pcl/surface/vtk_smoothing/vtk_mesh_quadric_decimation.h @@ -0,0 +1,84 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef VTK_MESH_QUADRIC_DECIMATION_H_ +#define VTK_MESH_QUADRIC_DECIMATION_H_ + +#include +#include + +namespace pcl +{ + /** \brief PCL mesh decimation based on vtkQuadricDecimation from the VTK library. + * Please check out the original documentation for more details on the inner workings of the algorithm + * Warning: This wrapper does two fairly computationally expensive conversions from the PCL PolygonMesh + * data structure to the vtkPolyData data structure and back. + */ + class PCL_EXPORTS MeshQuadricDecimationVTK : public MeshProcessing + { + public: + /** \brief Empty constructor */ + MeshQuadricDecimationVTK (); + + /** \brief Set the percentage of faces that should be removed. + * \param[in] factor the factor + */ + inline void + setTargetReductionFactor (float factor) + { + target_reduction_factor_ = factor; + } + + /** \brief Get the target reduction factor */ + inline float + getTargetReductionFactor () + { + return target_reduction_factor_; + } + + protected: + void + performProcessing (pcl::PolygonMesh &output); + + private: + float target_reduction_factor_; + + vtkSmartPointer vtk_polygons_; + }; +} +#endif /* VTK_MESH_QUADRIC_DECIMATION_H_ */ diff --git a/pcl-1.7/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_laplacian.h b/pcl-1.7/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_laplacian.h new file mode 100644 index 0000000..98e63fa --- /dev/null +++ b/pcl-1.7/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_laplacian.h @@ -0,0 +1,200 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef VTK_MESH_SMOOTHING_LAPLACIAN_H_ +#define VTK_MESH_SMOOTHING_LAPLACIAN_H_ + +#include +#include + +namespace pcl +{ + /** \brief PCL mesh smoothing based on the vtkSmoothPolyDataFilter algorithm from the VTK library. + * Please check out the original documentation for more details on the inner workings of the algorithm + * Warning: This wrapper does two fairly computationally expensive conversions from the PCL PolygonMesh + * data structure to the vtkPolyData data structure and back. + */ + class PCL_EXPORTS MeshSmoothingLaplacianVTK : public MeshProcessing + { + public: + /** \brief Empty constructor that sets the values of the algorithm parameters to the VTK defaults */ + MeshSmoothingLaplacianVTK () + : MeshProcessing () + , vtk_polygons_ () + , num_iter_ (20) + , convergence_ (0.0f) + , relaxation_factor_ (0.01f) + , feature_edge_smoothing_ (false) + , feature_angle_ (45.f) + , edge_angle_ (15.f) + , boundary_smoothing_ (true) + {}; + + /** \brief Set the number of iterations for the smoothing filter. + * \param[in] num_iter the number of iterations + */ + inline void + setNumIter (int num_iter) + { + num_iter_ = num_iter; + }; + + /** \brief Get the number of iterations. */ + inline int + getNumIter () + { + return num_iter_; + }; + + /** \brief Specify a convergence criterion for the iteration process. Smaller numbers result in more smoothing iterations. + * \param[in] convergence convergence criterion for the Laplacian smoothing + */ + inline void + setConvergence (float convergence) + { + convergence_ = convergence; + }; + + /** \brief Get the convergence criterion. */ + inline float + getConvergence () + { + return convergence_; + }; + + /** \brief Specify the relaxation factor for Laplacian smoothing. As in all iterative methods, + * the stability of the process is sensitive to this parameter. + * In general, small relaxation factors and large numbers of iterations are more stable than larger relaxation + * factors and smaller numbers of iterations. + * \param[in] relaxation_factor the relaxation factor of the Laplacian smoothing algorithm + */ + inline void + setRelaxationFactor (float relaxation_factor) + { + relaxation_factor_ = relaxation_factor; + }; + + /** \brief Get the relaxation factor of the Laplacian smoothing */ + inline float + getRelaxationFactor () + { + return relaxation_factor_; + }; + + /** \brief Turn on/off smoothing along sharp interior edges. + * \param[in] feature_edge_smoothing whether to enable/disable smoothing along sharp interior edges + */ + inline void + setFeatureEdgeSmoothing (bool feature_edge_smoothing) + { + feature_edge_smoothing_ = feature_edge_smoothing; + }; + + /** \brief Get the status of the feature edge smoothing */ + inline bool + getFeatureEdgeSmoothing () + { + return feature_edge_smoothing_; + }; + + /** \brief Specify the feature angle for sharp edge identification. + * \param[in] feature_angle the angle threshold for considering an edge to be sharp + */ + inline void + setFeatureAngle (float feature_angle) + { + feature_angle_ = feature_angle; + }; + + /** \brief Get the angle threshold for considering an edge to be sharp */ + inline float + getFeatureAngle () + { + return feature_angle_; + }; + + /** \brief Specify the edge angle to control smoothing along edges (either interior or boundary). + * \param[in] edge_angle the angle to control smoothing along edges + */ + inline void + setEdgeAngle (float edge_angle) + { + edge_angle_ = edge_angle; + }; + + /** \brief Get the edge angle to control smoothing along edges */ + inline float + getEdgeAngle () + { + return edge_angle_; + }; + + /** \brief Turn on/off the smoothing of vertices on the boundary of the mesh. + * \param[in] boundary_smoothing decision whether boundary smoothing is on or off + */ + inline void + setBoundarySmoothing (bool boundary_smoothing) + { + boundary_smoothing_ = boundary_smoothing; + }; + + /** \brief Get the status of the boundary smoothing */ + inline bool + getBoundarySmoothing () + { + return boundary_smoothing_; + } + + protected: + void + performProcessing (pcl::PolygonMesh &output); + + private: + vtkSmartPointer vtk_polygons_; + + /// Parameters + int num_iter_; + float convergence_; + float relaxation_factor_; + bool feature_edge_smoothing_; + float feature_angle_; + float edge_angle_; + bool boundary_smoothing_; + }; +} +#endif /* VTK_MESH_SMOOTHING_LAPLACIAN_H_ */ diff --git a/pcl-1.7/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_windowed_sinc.h b/pcl-1.7/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_windowed_sinc.h new file mode 100644 index 0000000..b25bb94 --- /dev/null +++ b/pcl-1.7/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_windowed_sinc.h @@ -0,0 +1,199 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef VTK_MESH_SMOOTHING_WINDOWED_SINC_H_ +#define VTK_MESH_SMOOTHING_WINDOWED_SINC_H_ + +#include +#include + +namespace pcl +{ + /** \brief PCL mesh smoothing based on the vtkWindowedSincPolyDataFilter algorithm from the VTK library. + * Please check out the original documentation for more details on the inner workings of the algorithm + * Warning: This wrapper does two fairly computationally expensive conversions from the PCL PolygonMesh + * data structure to the vtkPolyData data structure and back. + */ + class PCL_EXPORTS MeshSmoothingWindowedSincVTK : public MeshProcessing + { + public: + /** \brief Empty constructor that sets the values of the algorithm parameters to the VTK defaults */ + MeshSmoothingWindowedSincVTK () + : MeshProcessing (), + num_iter_ (20), + pass_band_ (0.1f), + feature_edge_smoothing_ (false), + feature_angle_ (45.f), + edge_angle_ (15.f), + boundary_smoothing_ (true), + normalize_coordinates_ (false) + {}; + + /** \brief Set the number of iterations for the smoothing filter. + * \param[in] num_iter the number of iterations + */ + inline void + setNumIter (int num_iter) + { + num_iter_ = num_iter; + }; + + /** \brief Get the number of iterations. */ + inline int + getNumIter () + { + return num_iter_; + }; + + /** \brief Set the pass band value for windowed sinc filtering. + * \param[in] pass_band value for the pass band. + */ + inline void + setPassBand (float pass_band) + { + pass_band_ = pass_band; + }; + + /** \brief Get the pass band value. */ + inline float + getPassBand () + { + return pass_band_; + }; + + /** \brief Turn on/off coordinate normalization. The positions can be translated and scaled such that they fit + * within a [-1, 1] prior to the smoothing computation. The default is off. The numerical stability of the + * solution can be improved by turning normalization on. If normalization is on, the coordinates will be rescaled + * to the original coordinate system after smoothing has completed. + * \param[in] normalize_coordinates decision whether to normalize coordinates or not + */ + inline void + setNormalizeCoordinates (bool normalize_coordinates) + { + normalize_coordinates_ = normalize_coordinates; + } + + /** \brief Get whether the coordinate normalization is active or not */ + inline bool + getNormalizeCoordinates () + { + return normalize_coordinates_; + } + + /** \brief Turn on/off smoothing along sharp interior edges. + * \param[in] feature_edge_smoothing whether to enable/disable smoothing along sharp interior edges + */ + inline void + setFeatureEdgeSmoothing (bool feature_edge_smoothing) + { + feature_edge_smoothing_ = feature_edge_smoothing; + }; + + /** \brief Get the status of the feature edge smoothing */ + inline bool + getFeatureEdgeSmoothing () + { + return feature_edge_smoothing_; + }; + + /** \brief Specify the feature angle for sharp edge identification. + * \param[in] feature_angle the angle threshold for considering an edge to be sharp + */ + inline void + setFeatureAngle (float feature_angle) + { + feature_angle_ = feature_angle; + }; + + /** \brief Get the angle threshold for considering an edge to be sharp */ + inline float + getFeatureAngle () + { + return feature_angle_; + }; + + /** \brief Specify the edge angle to control smoothing along edges (either interior or boundary). + * \param[in] edge_angle the angle to control smoothing along edges + */ + inline void + setEdgeAngle (float edge_angle) + { + edge_angle_ = edge_angle; + }; + + /** \brief Get the edge angle to control smoothing along edges */ + inline float + getEdgeAngle () + { + return edge_angle_; + }; + + + /** \brief Turn on/off the smoothing of vertices on the boundary of the mesh. + * \param[in] boundary_smoothing decision whether boundary smoothing is on or off + */ + inline void + setBoundarySmoothing (bool boundary_smoothing) + { + boundary_smoothing_ = boundary_smoothing; + }; + + /** \brief Get the status of the boundary smoothing */ + inline bool + getBoundarySmoothing () + { + return boundary_smoothing_; + } + + + protected: + void + performProcessing (pcl::PolygonMesh &output); + + private: + vtkSmartPointer vtk_polygons_; + int num_iter_; + float pass_band_; + bool feature_edge_smoothing_; + float feature_angle_; + float edge_angle_; + bool boundary_smoothing_; + bool normalize_coordinates_; + }; +} +#endif /* VTK_MESH_SMOOTHING_WINDOWED_SINC_H_ */ diff --git a/pcl-1.7/pcl/surface/vtk_smoothing/vtk_mesh_subdivision.h b/pcl-1.7/pcl/surface/vtk_smoothing/vtk_mesh_subdivision.h new file mode 100644 index 0000000..378a68c --- /dev/null +++ b/pcl-1.7/pcl/surface/vtk_smoothing/vtk_mesh_subdivision.h @@ -0,0 +1,88 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef VTK_MESH_SUBDIVISION_H_ +#define VTK_MESH_SUBDIVISION_H_ + +#include +#include + +namespace pcl +{ + /** \brief PCL mesh smoothing based on the vtkLinearSubdivisionFilter, vtkLoopSubdivisionFilter, vtkButterflySubdivisionFilter + * depending on the selected MeshSubdivisionVTKFilterType algorithm from the VTK library. + * Please check out the original documentation for more details on the inner workings of the algorithm + * Warning: This wrapper does two fairly computationally expensive conversions from the PCL PolygonMesh + * data structure to the vtkPolyData data structure and back. + */ + class PCL_EXPORTS MeshSubdivisionVTK : public MeshProcessing + { + public: + /** \brief Empty constructor */ + MeshSubdivisionVTK (); + + enum MeshSubdivisionVTKFilterType + { LINEAR, LOOP, BUTTERFLY }; + + /** \brief Set the mesh subdivision filter type + * \param[in] type the filter type + */ + inline void + setFilterType (MeshSubdivisionVTKFilterType type) + { + filter_type_ = type; + }; + + /** \brief Get the mesh subdivision filter type */ + inline MeshSubdivisionVTKFilterType + getFilterType () + { + return filter_type_; + }; + + protected: + void + performProcessing (pcl::PolygonMesh &output); + + private: + MeshSubdivisionVTKFilterType filter_type_; + + vtkSmartPointer vtk_polygons_; + }; +} +#endif /* VTK_MESH_SUBDIVISION_H_ */ diff --git a/pcl-1.7/pcl/surface/vtk_smoothing/vtk_utils.h b/pcl-1.7/pcl/surface/vtk_smoothing/vtk_utils.h new file mode 100644 index 0000000..c28adbf --- /dev/null +++ b/pcl-1.7/pcl/surface/vtk_smoothing/vtk_utils.h @@ -0,0 +1,83 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef VTK_UTILS_H_ +#define VTK_UTILS_H_ + +#include +#include +#include + +namespace pcl +{ + class PCL_EXPORTS VTKUtils + { + public: + /** \brief Convert a PCL PolygonMesh to a VTK vtkPolyData. + * \param[in] triangles PolygonMesh to be converted to vtkPolyData, stored in the object. + * \param[out] triangles_out_vtk + */ + static int + convertToVTK (const pcl::PolygonMesh &triangles, vtkSmartPointer &triangles_out_vtk); + + /** \brief Convert the vtkPolyData object back to PolygonMesh. + * \param[in] vtk_polygons + * \param[out] triangles the PolygonMesh to store the vtkPolyData in. + */ + static void + convertToPCL (vtkSmartPointer &vtk_polygons, pcl::PolygonMesh &triangles); + + /** \brief Convert vtkPolyData object to a PCL PolygonMesh + * \param[in] poly_data Pointer (vtkSmartPointer) to a vtkPolyData object + * \param[out] mesh PCL Polygon Mesh to fill + * \return Number of points in the point cloud of mesh. + */ + static int + vtk2mesh (const vtkSmartPointer& poly_data, pcl::PolygonMesh& mesh); + + /** \brief Convert a PCL PolygonMesh to a vtkPolyData object + * \param[in] mesh Reference to PCL Polygon Mesh + * \param[out] poly_data Pointer (vtkSmartPointer) to a vtkPolyData object + * \return Number of points in the point cloud of mesh. + */ + static int + mesh2vtk (const pcl::PolygonMesh& mesh, vtkSmartPointer &poly_data); + }; +} + +#endif /* VTK_UTILS_H_ */ diff --git a/pcl-1.7/pcl/tracking/approx_nearest_pair_point_cloud_coherence.h b/pcl-1.7/pcl/tracking/approx_nearest_pair_point_cloud_coherence.h new file mode 100644 index 0000000..114d87d --- /dev/null +++ b/pcl-1.7/pcl/tracking/approx_nearest_pair_point_cloud_coherence.h @@ -0,0 +1,55 @@ +#ifndef PCL_TRACKING_APPROX_NEAREST_PAIR_POINT_CLOUD_COHERENCE_H_ +#define PCL_TRACKING_APPROX_NEAREST_PAIR_POINT_CLOUD_COHERENCE_H_ + +#include +#include +#include +namespace pcl +{ + namespace tracking + { + /** \brief @b ApproxNearestPairPointCloudCoherence computes coherence between two pointclouds using the + approximate nearest point pairs. + * \author Ryohei Ueda + * \ingroup tracking + */ + template + class ApproxNearestPairPointCloudCoherence: public NearestPairPointCloudCoherence + { + public: + typedef typename NearestPairPointCloudCoherence::PointCoherencePtr PointCoherencePtr; + typedef typename NearestPairPointCloudCoherence::PointCloudInConstPtr PointCloudInConstPtr; + //using NearestPairPointCloudCoherence::search_; + using NearestPairPointCloudCoherence::maximum_distance_; + using NearestPairPointCloudCoherence::target_input_; + using NearestPairPointCloudCoherence::point_coherences_; + using NearestPairPointCloudCoherence::coherence_name_; + using NearestPairPointCloudCoherence::new_target_; + using NearestPairPointCloudCoherence::getClassName; + + /** \brief empty constructor */ + ApproxNearestPairPointCloudCoherence () : + NearestPairPointCloudCoherence (), search_ () + { + coherence_name_ = "ApproxNearestPairPointCloudCoherence"; + } + + protected: + /** \brief This method should get called before starting the actual computation. */ + virtual bool initCompute (); + + /** \brief compute the nearest pairs and compute coherence using point_coherences_ */ + virtual void + computeCoherence (const PointCloudInConstPtr &cloud, const IndicesConstPtr &indices, float &w_j); + + typename boost::shared_ptr > search_; + }; + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif + diff --git a/pcl-1.7/pcl/tracking/boost.h b/pcl-1.7/pcl/tracking/boost.h new file mode 100644 index 0000000..24f3bb6 --- /dev/null +++ b/pcl-1.7/pcl/tracking/boost.h @@ -0,0 +1,49 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $ + * + */ + +#ifndef PCL_TRACKING_BOOST_H_ +#define PCL_TRACKING_BOOST_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include + +#endif // PCL_TRACKING_BOOST_H_ diff --git a/pcl-1.7/pcl/tracking/coherence.h b/pcl-1.7/pcl/tracking/coherence.h new file mode 100644 index 0000000..e56ee3e --- /dev/null +++ b/pcl-1.7/pcl/tracking/coherence.h @@ -0,0 +1,136 @@ +#ifndef PCL_TRACKING_COHERENCE_H_ +#define PCL_TRACKING_COHERENCE_H_ + +#include + +namespace pcl +{ + + namespace tracking + { + + /** \brief @b PointCoherence is a base class to compute coherence between the two points. + * \author Ryohei Ueda + * \ingroup tracking + */ + template + class PointCoherence + { + public: + typedef boost::shared_ptr< PointCoherence > Ptr; + typedef boost::shared_ptr< const PointCoherence > ConstPtr; + + public: + /** \brief empty constructor */ + PointCoherence () : coherence_name_ () {} + + /** \brief empty distructor */ + virtual ~PointCoherence () {} + + /** \brief compute coherence from the source point to the target point. + * \param source instance of source point. + * \param target instance of target point. + */ + inline double + compute (PointInT &source, PointInT &target); + + protected: + + /** \brief The coherence name. */ + std::string coherence_name_; + + /** \brief abstract method to calculate coherence. + * \param[in] source instance of source point. + * \param[in] target instance of target point. + */ + virtual double + computeCoherence (PointInT &source, PointInT &target) = 0; + + /** \brief Get a string representation of the name of this class. */ + inline const std::string& + getClassName () const { return (coherence_name_); } + + }; + + /** \brief @b PointCloudCoherence is a base class to compute coherence between the two PointClouds. + * \author Ryohei Ueda + * \ingroup tracking + */ + template + class PointCloudCoherence + { + public: + typedef boost::shared_ptr< PointCloudCoherence > Ptr; + typedef boost::shared_ptr< const PointCloudCoherence > ConstPtr; + + typedef pcl::PointCloud PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + typedef typename PointCoherence::Ptr PointCoherencePtr; + /** \brief Constructor. */ + PointCloudCoherence () : coherence_name_ (), target_input_ (), point_coherences_ () {} + + /** \brief Destructor. */ + virtual ~PointCloudCoherence () {} + + /** \brief compute coherence between two pointclouds. */ + inline void + compute (const PointCloudInConstPtr &cloud, const IndicesConstPtr &indices, + float &w_i); + + /** \brief get a list of pcl::tracking::PointCoherence.*/ + inline std::vector + getPointCoherences () { return point_coherences_; } + + /** \brief set a list of pcl::tracking::PointCoherence. + * \param coherences a list of pcl::tracking::PointCoherence. + */ + inline void + setPointCoherences (std::vector coherences) { point_coherences_ = coherences; } + + /** \brief This method should get called before starting the actual computation. */ + virtual bool initCompute (); + + /** \brief add a PointCoherence to the PointCloudCoherence. + * \param coherence a pointer to PointCoherence. + */ + inline void + addPointCoherence (PointCoherencePtr coherence) { point_coherences_.push_back (coherence); } + + /** \brief add a PointCoherence to the PointCloudCoherence. + * \param cloud a pointer to PointCoherence. + */ + virtual inline void + setTargetCloud (const PointCloudInConstPtr &cloud) { target_input_ = cloud; } + + protected: + /** \brief Abstract method to compute coherence. */ + virtual void + computeCoherence (const PointCloudInConstPtr &cloud, const IndicesConstPtr &indices, float &w_j) = 0; + + inline double calcPointCoherence (PointInT &source, PointInT &target); + + /** \brief Get a string representation of the name of this class. */ + inline const std::string& + getClassName () const { return (coherence_name_); } + + + /** \brief The coherence name. */ + std::string coherence_name_; + + /** \brief a pointer to target point cloud*/ + PointCloudInConstPtr target_input_; + + /** \brief a list of pointers to PointCoherence.*/ + std::vector point_coherences_; + }; + + } +} + + +#include + + +#endif diff --git a/pcl-1.7/pcl/tracking/distance_coherence.h b/pcl-1.7/pcl/tracking/distance_coherence.h new file mode 100644 index 0000000..9c7415a --- /dev/null +++ b/pcl-1.7/pcl/tracking/distance_coherence.h @@ -0,0 +1,54 @@ +#ifndef PCL_TRACKING_DISTANCE_COHERENCE_H_ +#define PCL_TRACKING_DISTANCE_COHERENCE_H_ + +#include + +namespace pcl +{ + namespace tracking + { + /** \brief @b DistanceCoherence computes coherence between two points from the distance + between them. the coherence is calculated by 1 / (1 + weight * d^2 ). + * \author Ryohei Ueda + * \ingroup tracking + */ + template + class DistanceCoherence: public PointCoherence + { + public: + + /** \brief initialize the weight to 1.0. */ + DistanceCoherence () + : PointCoherence () + , weight_ (1.0) + {} + + /** \brief set the weight of coherence. + * \param weight the value of the wehgit. + */ + inline void setWeight (double weight) { weight_ = weight; } + + /** \brief get the weight of coherence.*/ + inline double getWeight () { return weight_; } + + protected: + + /** \brief return the distance coherence between the two points. + * \param source instance of source point. + * \param target instance of target point. + */ + double computeCoherence (PointInT &source, PointInT &target); + + /** \brief the weight of coherence.*/ + double weight_; + }; + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +// #include + +#endif diff --git a/pcl-1.7/pcl/tracking/hsv_color_coherence.h b/pcl-1.7/pcl/tracking/hsv_color_coherence.h new file mode 100644 index 0000000..1fb5092 --- /dev/null +++ b/pcl-1.7/pcl/tracking/hsv_color_coherence.h @@ -0,0 +1,104 @@ +#ifndef PCL_TRACKING_HSV_COLOR_COHERENCE_H_ +#define PCL_TRACKING_HSV_COLOR_COHERENCE_H_ + +#include + +namespace pcl +{ + namespace tracking + { + /** \brief @b HSVColorCoherence computes coherence between the two points from + the color difference between them. the color difference is calculated in HSV color space. + the coherence is calculated by 1 / ( 1 + w * (w_h^2 * h_diff^2 + w_s^2 * s_diff^2 + w_v^2 * v_diff^2)) + * \author Ryohei Ueda + * \ingroup tracking + */ + template + class HSVColorCoherence: public PointCoherence + { + public: + + /** \brief initialize the weights of the computation. + weight_, h_weight_, s_weight_ default to 1.0 and + v_weight_ defaults to 0.0. + */ + HSVColorCoherence () + : PointCoherence () + , weight_ (1.0) + , h_weight_ (1.0) + , s_weight_ (1.0) + , v_weight_ (0.0) + {} + + /** \brief set the weight of coherence + * \param[in] weight the weight of coherence. + */ + inline void + setWeight (double weight) { weight_ = weight; } + + /** \brief get the weight (w) of coherence */ + inline double + getWeight () { return weight_; } + + /** \brief set the hue weight (w_h) of coherence + * \param[in] weight the hue weight (w_h) of coherence. + */ + inline void + setHWeight (double weight) { h_weight_ = weight; } + + /** \brief get the hue weight (w_h) of coherence */ + inline double + getHWeight () { return h_weight_; } + + /** \brief set the saturation weight (w_s) of coherence + * \param[in] weight the saturation weight (w_s) of coherence. + */ + inline void + setSWeight (double weight) { s_weight_ = weight; } + + /** \brief get the saturation weight (w_s) of coherence */ + inline double + getSWeight () { return s_weight_; } + + /** \brief set the value weight (w_v) of coherence + * \param[in] weight the value weight (w_v) of coherence. + */ + inline void + setVWeight (double weight) { v_weight_ = weight; } + + /** \brief get the value weight (w_v) of coherence */ + inline double + getVWeight () { return v_weight_; } + + protected: + + /** \brief return the color coherence between the two points. + * \param[in] source instance of source point. + * \param[in] target instance of target point. + */ + double + computeCoherence (PointInT &source, PointInT &target); + + /** \brief the weight of coherence (w) */ + double weight_; + + /** \brief the hue weight (w_h) */ + double h_weight_; + + /** \brief the saturation weight (w_s) */ + double s_weight_; + + /** \brief the value weight (w_v) */ + double v_weight_; + + }; + } +} + +// #include + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/tracking/impl/approx_nearest_pair_point_cloud_coherence.hpp b/pcl-1.7/pcl/tracking/impl/approx_nearest_pair_point_cloud_coherence.hpp new file mode 100644 index 0000000..8302a85 --- /dev/null +++ b/pcl-1.7/pcl/tracking/impl/approx_nearest_pair_point_cloud_coherence.hpp @@ -0,0 +1,68 @@ +#ifndef PCL_TRACKING_IMPL_APPROX_NEAREST_PAIR_POINT_CLOUD_COHERENCE_H_ +#define PCL_TRACKING_IMPL_APPROX_NEAREST_PAIR_POINT_CLOUD_COHERENCE_H_ + +#include +#include + +namespace pcl +{ + namespace tracking + { + template void + ApproxNearestPairPointCloudCoherence::computeCoherence ( + const PointCloudInConstPtr &cloud, const IndicesConstPtr &, float &w) + { + double val = 0.0; + //for (size_t i = 0; i < indices->size (); i++) + for (size_t i = 0; i < cloud->points.size (); i++) + { + int k_index = 0; + float k_distance = 0.0; + //PointInT input_point = cloud->points[(*indices)[i]]; + PointInT input_point = cloud->points[i]; + search_->approxNearestSearch(input_point, k_index, k_distance); + if (k_distance < maximum_distance_ * maximum_distance_) + { + PointInT target_point = target_input_->points[k_index]; + double coherence_val = 1.0; + for (size_t i = 0; i < point_coherences_.size (); i++) + { + PointCoherencePtr coherence = point_coherences_[i]; + double w = coherence->compute (input_point, target_point); + coherence_val *= w; + } + val += coherence_val; + } + } + w = - static_cast (val); + } + + template bool + ApproxNearestPairPointCloudCoherence::initCompute () + { + if (!PointCloudCoherence::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] PointCloudCoherence::Init failed.\n", getClassName ().c_str ()); + //deinitCompute (); + return (false); + } + + // initialize tree + if (!search_) + search_.reset (new pcl::search::Octree (0.01)); + + if (new_target_ && target_input_) + { + search_->setInputCloud (target_input_); + new_target_ = false; + } + + return true; + } + + } +} + +#define PCL_INSTANTIATE_ApproxNearestPairPointCloudCoherence(T) template class PCL_EXPORTS pcl::tracking::ApproxNearestPairPointCloudCoherence; + +#endif diff --git a/pcl-1.7/pcl/tracking/impl/coherence.hpp b/pcl-1.7/pcl/tracking/impl/coherence.hpp new file mode 100644 index 0000000..6307538 --- /dev/null +++ b/pcl-1.7/pcl/tracking/impl/coherence.hpp @@ -0,0 +1,61 @@ +#ifndef PCL_TRACKING_IMPL_COHERENCE_H_ +#define PCL_TRACKING_IMPL_COHERENCE_H_ + +#include +#include + +namespace pcl +{ + namespace tracking + { + + template double + PointCoherence::compute (PointInT &source, PointInT &target) + { + return computeCoherence (source, target); + } + + template double + PointCloudCoherence::calcPointCoherence (PointInT &source, PointInT &target) + { + double val = 0.0; + for (size_t i = 0; i < point_coherences_.size (); i++) + { + PointCoherencePtr coherence = point_coherences_[i]; + double d = log(coherence->compute (source, target)); + //double d = coherence->compute (source, target); + if (! pcl_isnan(d)) + val += d; + else + PCL_WARN ("nan!\n"); + } + return val; + } + + template bool + PointCloudCoherence::initCompute () + { + if (!target_input_ || target_input_->points.empty ()) + { + PCL_ERROR ("[pcl::%s::compute] target_input_ is empty!\n", getClassName ().c_str ()); + return false; + } + + return true; + + } + + template void + PointCloudCoherence::compute (const PointCloudInConstPtr &cloud, const IndicesConstPtr &indices, float &w) + { + if (!initCompute ()) + { + PCL_ERROR ("[pcl::%s::compute] Init failed.\n", getClassName ().c_str ()); + return; + } + computeCoherence (cloud, indices, w); + } + } +} + +#endif diff --git a/pcl-1.7/pcl/tracking/impl/distance_coherence.hpp b/pcl-1.7/pcl/tracking/impl/distance_coherence.hpp new file mode 100644 index 0000000..7b68e9e --- /dev/null +++ b/pcl-1.7/pcl/tracking/impl/distance_coherence.hpp @@ -0,0 +1,24 @@ +#ifndef PCL_TRACKING_IMPL_DISTANCE_COHERENCE_H_ +#define PCL_TRACKING_IMPL_DISTANCE_COHERENCE_H_ + +#include +#include + +namespace pcl +{ + namespace tracking + { + template double + DistanceCoherence::computeCoherence (PointInT &source, PointInT &target) + { + Eigen::Vector4f p = source.getVector4fMap (); + Eigen::Vector4f p_dash = target.getVector4fMap (); + double d = (p - p_dash).norm (); + return 1.0 / (1.0 + d * d * weight_); + } + } +} + +#define PCL_INSTANTIATE_DistanceCoherence(T) template class PCL_EXPORTS pcl::tracking::DistanceCoherence; + +#endif diff --git a/pcl-1.7/pcl/tracking/impl/hsv_color_coherence.hpp b/pcl-1.7/pcl/tracking/impl/hsv_color_coherence.hpp new file mode 100644 index 0000000..49ef897 --- /dev/null +++ b/pcl-1.7/pcl/tracking/impl/hsv_color_coherence.hpp @@ -0,0 +1,184 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_TRACKING_IMPL_HSV_COLOR_COHERENCE_H_ +#define PCL_TRACKING_IMPL_HSV_COLOR_COHERENCE_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include + +namespace pcl +{ + namespace tracking + { + // utility + typedef union + { + struct /*anonymous*/ + { + unsigned char Blue; // Blue channel + unsigned char Green; // Green channel + unsigned char Red; // Red channel + }; + float float_value; + int int_value; + } RGBValue; + + /** \brief Convert a RGB tuple to an HSV one. + * \param[in] r the input Red component + * \param[in] g the input Green component + * \param[in] b the input Blue component + * \param[out] fh the output Hue component + * \param[out] fs the output Saturation component + * \param[out] fv the output Value component + */ + void + RGB2HSV (int r, int g, int b, float& fh, float& fs, float& fv) + { + // mostly copied from opencv-svn/modules/imgproc/src/color.cpp + // revision is 4351 + const int hsv_shift = 12; + + static const int div_table[] = + { + 0, 1044480, 522240, 348160, 261120, 208896, 174080, 149211, + 130560, 116053, 104448, 94953, 87040, 80345, 74606, 69632, + 65280, 61440, 58027, 54973, 52224, 49737, 47476, 45412, + 43520, 41779, 40172, 38684, 37303, 36017, 34816, 33693, + 32640, 31651, 30720, 29842, 29013, 28229, 27486, 26782, + 26112, 25475, 24869, 24290, 23738, 23211, 22706, 22223, + 21760, 21316, 20890, 20480, 20086, 19707, 19342, 18991, + 18651, 18324, 18008, 17703, 17408, 17123, 16846, 16579, + 16320, 16069, 15825, 15589, 15360, 15137, 14921, 14711, + 14507, 14308, 14115, 13926, 13743, 13565, 13391, 13221, + 13056, 12895, 12738, 12584, 12434, 12288, 12145, 12006, + 11869, 11736, 11605, 11478, 11353, 11231, 11111, 10995, + 10880, 10768, 10658, 10550, 10445, 10341, 10240, 10141, + 10043, 9947, 9854, 9761, 9671, 9582, 9495, 9410, + 9326, 9243, 9162, 9082, 9004, 8927, 8852, 8777, + 8704, 8632, 8561, 8492, 8423, 8356, 8290, 8224, + 8160, 8097, 8034, 7973, 7913, 7853, 7795, 7737, + 7680, 7624, 7569, 7514, 7461, 7408, 7355, 7304, + 7253, 7203, 7154, 7105, 7057, 7010, 6963, 6917, + 6872, 6827, 6782, 6739, 6695, 6653, 6611, 6569, + 6528, 6487, 6447, 6408, 6369, 6330, 6292, 6254, + 6217, 6180, 6144, 6108, 6073, 6037, 6003, 5968, + 5935, 5901, 5868, 5835, 5803, 5771, 5739, 5708, + 5677, 5646, 5615, 5585, 5556, 5526, 5497, 5468, + 5440, 5412, 5384, 5356, 5329, 5302, 5275, 5249, + 5222, 5196, 5171, 5145, 5120, 5095, 5070, 5046, + 5022, 4998, 4974, 4950, 4927, 4904, 4881, 4858, + 4836, 4813, 4791, 4769, 4748, 4726, 4705, 4684, + 4663, 4642, 4622, 4601, 4581, 4561, 4541, 4522, + 4502, 4483, 4464, 4445, 4426, 4407, 4389, 4370, + 4352, 4334, 4316, 4298, 4281, 4263, 4246, 4229, + 4212, 4195, 4178, 4161, 4145, 4128, 4112, 4096 + }; + int hr = 180, hscale = 15; + int h, s, v = b; + int vmin = b, diff; + int vr, vg; + + v = std::max (v, g); + v = std::max (v, r); + vmin = std::min (vmin, g); + vmin = std::min (vmin, r); + + diff = v - vmin; + vr = v == r ? -1 : 0; + vg = v == g ? -1 : 0; + + s = diff * div_table[v] >> hsv_shift; + h = (vr & (g - b)) + + (~vr & ((vg & (b - r + 2 * diff)) + + ((~vg) & (r - g + 4 * diff)))); + h = (h * div_table[diff] * hscale + + (1 << (hsv_shift + 6))) >> (7 + hsv_shift); + + h += h < 0 ? hr : 0; + fh = static_cast (h) / 180.0f; + fs = static_cast (s) / 255.0f; + fv = static_cast (v) / 255.0f; + } + + /////////////////////////////////////////////////////////////////////////////////////////////////////////////// + template double + HSVColorCoherence::computeCoherence (PointInT &source, PointInT &target) + { + // convert color space from RGB to HSV + RGBValue source_rgb, target_rgb; + source_rgb.int_value = source.rgba; + target_rgb.int_value = target.rgba; + + float source_h, source_s, source_v, target_h, target_s, target_v; + RGB2HSV (source_rgb.Red, source_rgb.Blue, source_rgb.Green, + source_h, source_s, source_v); + RGB2HSV (target_rgb.Red, target_rgb.Blue, target_rgb.Green, + target_h, target_s, target_v); + // hue value is in 0 ~ 2pi, but circulated. + const float _h_diff = fabsf (source_h - target_h); + // Also need to compute distance other way around circle - but need to check which is closer to 0 + float _h_diff2; + if (source_h < target_h) + _h_diff2 = fabsf (1.0f + source_h - target_h); //Add 2pi to source, subtract target + else + _h_diff2 = fabsf (1.0f + target_h - source_h); //Add 2pi to target, subtract source + + float h_diff; + //Now we need to choose the smaller distance + if (_h_diff < _h_diff2) + h_diff = static_cast (h_weight_) * _h_diff * _h_diff; + else + h_diff = static_cast (h_weight_) * _h_diff2 * _h_diff2; + + const float s_diff = static_cast (s_weight_) * (source_s - target_s) * (source_s - target_s); + const float v_diff = static_cast (v_weight_) * (source_v - target_v) * (source_v - target_v); + const float diff2 = h_diff + s_diff + v_diff; + + return (1.0 / (1.0 + weight_ * diff2)); + } + } +} + +#define PCL_INSTANTIATE_HSVColorCoherence(T) template class PCL_EXPORTS pcl::tracking::HSVColorCoherence; + +#endif diff --git a/pcl-1.7/pcl/tracking/impl/kld_adaptive_particle_filter.hpp b/pcl-1.7/pcl/tracking/impl/kld_adaptive_particle_filter.hpp new file mode 100644 index 0000000..79e392c --- /dev/null +++ b/pcl-1.7/pcl/tracking/impl/kld_adaptive_particle_filter.hpp @@ -0,0 +1,94 @@ +#ifndef PCL_TRACKING_IMPL_KLD_ADAPTIVE_PARTICLE_FILTER_H_ +#define PCL_TRACKING_IMPL_KLD_ADAPTIVE_PARTICLE_FILTER_H_ + +#include + +template bool +pcl::tracking::KLDAdaptiveParticleFilterTracker::initCompute () +{ + if (!Tracker::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + if (transed_reference_vector_.empty ()) + { + // only one time allocation + transed_reference_vector_.resize (maximum_particle_number_); + for (unsigned int i = 0; i < maximum_particle_number_; i++) + { + transed_reference_vector_[i] = PointCloudInPtr (new PointCloudIn ()); + } + } + + coherence_->setTargetCloud (input_); + + if (!change_detector_) + change_detector_ = boost::shared_ptr >(new pcl::octree::OctreePointCloudChangeDetector (change_detector_resolution_)); + + if (!particles_ || particles_->points.empty ()) + initParticles (true); + return (true); +} + +template bool +pcl::tracking::KLDAdaptiveParticleFilterTracker::insertIntoBins +(std::vector bin, std::vector > &B) +{ + for (size_t i = 0; i < B.size (); i++) + { + if (equalBin (bin, B[i])) + return false; + } + B.push_back (bin); + return true; +} + +template void +pcl::tracking::KLDAdaptiveParticleFilterTracker::resample () +{ + unsigned int k = 0; + unsigned int n = 0; + PointCloudStatePtr S (new PointCloudState); + std::vector > B; // bins + + // initializing for sampling without replacement + std::vector a (particles_->points.size ()); + std::vector q (particles_->points.size ()); + this->genAliasTable (a, q, particles_); + + const std::vector zero_mean (StateT::stateDimension (), 0.0); + + // select the particles with KLD sampling + do + { + int j_n = sampleWithReplacement (a, q); + StateT x_t = particles_->points[j_n]; + x_t.sample (zero_mean, step_noise_covariance_); + + // motion + if (rand () / double (RAND_MAX) < motion_ratio_) + x_t = x_t + motion_; + + S->points.push_back (x_t); + // calc bin + std::vector bin (StateT::stateDimension ()); + for (int i = 0; i < StateT::stateDimension (); i++) + bin[i] = static_cast (x_t[i] / bin_size_[i]); + + // calc bin index... how? + if (insertIntoBins (bin, B)) + ++k; + ++n; + } + while (k < 2 || (n < maximum_particle_number_ && n < calcKLBound (k))); + + particles_ = S; // swap + particle_num_ = static_cast (particles_->points.size ()); +} + + +#define PCL_INSTANTIATE_KLDAdaptiveParticleFilterTracker(T,ST) template class PCL_EXPORTS pcl::tracking::KLDAdaptiveParticleFilterTracker; + +#endif diff --git a/pcl-1.7/pcl/tracking/impl/kld_adaptive_particle_filter_omp.hpp b/pcl-1.7/pcl/tracking/impl/kld_adaptive_particle_filter_omp.hpp new file mode 100644 index 0000000..0c018e4 --- /dev/null +++ b/pcl-1.7/pcl/tracking/impl/kld_adaptive_particle_filter_omp.hpp @@ -0,0 +1,89 @@ +#ifndef PCL_TRACKING_IMPL_KLD_ADAPTIVE_PARTICLE_OMP_FILTER_H_ +#define PCL_TRACKING_IMPL_KLD_ADAPTIVE_PARTICLE_OMP_FILTER_H_ + +#include + +template void +pcl::tracking::KLDAdaptiveParticleFilterOMPTracker::weight () +{ + if (!use_normal_) + { +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int i = 0; i < particle_num_; i++) + this->computeTransformedPointCloudWithoutNormal (particles_->points[i], *transed_reference_vector_[i]); + + PointCloudInPtr coherence_input (new PointCloudIn); + this->cropInputPointCloud (input_, *coherence_input); + if (change_counter_ == 0) + { + // test change detector + if (!use_change_detector_ || this->testChangeDetection (coherence_input)) + { + changed_ = true; + change_counter_ = change_detector_interval_; + coherence_->setTargetCloud (coherence_input); + coherence_->initCompute (); +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int i = 0; i < particle_num_; i++) + { + IndicesPtr indices; + coherence_->compute (transed_reference_vector_[i], indices, particles_->points[i].weight); + } + } + else + changed_ = false; + } + else + { + --change_counter_; + coherence_->setTargetCloud (coherence_input); + coherence_->initCompute (); +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int i = 0; i < particle_num_; i++) + { + IndicesPtr indices; + coherence_->compute (transed_reference_vector_[i], indices, particles_->points[i].weight); + } + } + } + else + { + std::vector indices_list (particle_num_); + for (int i = 0; i < particle_num_; i++) + { + indices_list[i] = IndicesPtr (new std::vector); + } +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int i = 0; i < particle_num_; i++) + { + this->computeTransformedPointCloudWithNormal (particles_->points[i], *indices_list[i], *transed_reference_vector_[i]); + } + + PointCloudInPtr coherence_input (new PointCloudIn); + this->cropInputPointCloud (input_, *coherence_input); + + coherence_->setTargetCloud (coherence_input); + coherence_->initCompute (); +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int i = 0; i < particle_num_; i++) + { + coherence_->compute (transed_reference_vector_[i], indices_list[i], particles_->points[i].weight); + } + } + + normalizeWeight (); +} + +#define PCL_INSTANTIATE_KLDAdaptiveParticleFilterOMPTracker(T,ST) template class PCL_EXPORTS pcl::tracking::KLDAdaptiveParticleFilterOMPTracker; + +#endif diff --git a/pcl-1.7/pcl/tracking/impl/nearest_pair_point_cloud_coherence.hpp b/pcl-1.7/pcl/tracking/impl/nearest_pair_point_cloud_coherence.hpp new file mode 100644 index 0000000..dd341b5 --- /dev/null +++ b/pcl-1.7/pcl/tracking/impl/nearest_pair_point_cloud_coherence.hpp @@ -0,0 +1,71 @@ +#ifndef PCL_TRACKING_IMPL_NEAREST_PAIR_POINT_CLOUD_COHERENCE_H_ +#define PCL_TRACKING_IMPL_NEAREST_PAIR_POINT_CLOUD_COHERENCE_H_ + +#include +#include +#include + +namespace pcl +{ + namespace tracking + { + template void + NearestPairPointCloudCoherence::computeCoherence ( + const PointCloudInConstPtr &cloud, const IndicesConstPtr &, float &w) + { + double val = 0.0; + //for (size_t i = 0; i < indices->size (); i++) + for (size_t i = 0; i < cloud->points.size (); i++) + { + PointInT input_point = cloud->points[i]; + std::vector k_indices(1); + std::vector k_distances(1); + search_->nearestKSearch (input_point, 1, k_indices, k_distances); + int k_index = k_indices[0]; + float k_distance = k_distances[0]; + if (k_distance < maximum_distance_ * maximum_distance_) + { + // nearest_targets.push_back (k_index); + // nearest_inputs.push_back (i); + PointInT target_point = target_input_->points[k_index]; + double coherence_val = 1.0; + for (size_t i = 0; i < point_coherences_.size (); i++) + { + PointCoherencePtr coherence = point_coherences_[i]; + double w = coherence->compute (input_point, target_point); + coherence_val *= w; + } + val += coherence_val; + } + } + w = - static_cast (val); + } + + template bool + NearestPairPointCloudCoherence::initCompute () + { + if (!PointCloudCoherence::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] PointCloudCoherence::Init failed.\n", getClassName ().c_str ()); + //deinitCompute (); + return (false); + } + + // initialize tree + if (!search_) + search_.reset (new pcl::search::KdTree (false)); + + if (new_target_ && target_input_) + { + search_->setInputCloud (target_input_); + new_target_ = false; + } + + return true; + } + } +} + +#define PCL_INSTANTIATE_NearestPairPointCloudCoherence(T) template class PCL_EXPORTS pcl::tracking::NearestPairPointCloudCoherence; + +#endif diff --git a/pcl-1.7/pcl/tracking/impl/normal_coherence.hpp b/pcl-1.7/pcl/tracking/impl/normal_coherence.hpp new file mode 100644 index 0000000..19e0272 --- /dev/null +++ b/pcl-1.7/pcl/tracking/impl/normal_coherence.hpp @@ -0,0 +1,36 @@ +#ifndef PCL_TRACKING_IMPL_NORMAL_COHERENCE_H_ +#define PCL_TRACKING_IMPL_NORMAL_COHERENCE_H_ + +#include +#include +#include + +template double +pcl::tracking::NormalCoherence::computeCoherence (PointInT &source, PointInT &target) +{ + Eigen::Vector4f n = source.getNormalVector4fMap (); + Eigen::Vector4f n_dash = target.getNormalVector4fMap (); + if ( n.norm () <= 1e-5 || n_dash.norm () <= 1e-5 ) + { + PCL_ERROR("norm might be ZERO!\n"); + std::cout << "source: " << source << std::endl; + std::cout << "target: " << target << std::endl; + exit (1); + return 0.0; + } + else + { + n.normalize (); + n_dash.normalize (); + double theta = pcl::getAngle3D (n, n_dash); + if (!pcl_isnan (theta)) + return 1.0 / (1.0 + weight_ * theta * theta); + else + return 0.0; + } +} + + +#define PCL_INSTANTIATE_NormalCoherence(T) template class PCL_EXPORTS pcl::tracking::NormalCoherence; + +#endif diff --git a/pcl-1.7/pcl/tracking/impl/particle_filter.hpp b/pcl-1.7/pcl/tracking/impl/particle_filter.hpp new file mode 100644 index 0000000..a86e37d --- /dev/null +++ b/pcl-1.7/pcl/tracking/impl/particle_filter.hpp @@ -0,0 +1,413 @@ +#ifndef PCL_TRACKING_IMPL_PARTICLE_FILTER_H_ +#define PCL_TRACKING_IMPL_PARTICLE_FILTER_H_ + +#include +#include +#include +#include +#include + +template bool +pcl::tracking::ParticleFilterTracker::initCompute () +{ + if (!Tracker::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ()); + return (false); + } + + if (transed_reference_vector_.empty ()) + { + // only one time allocation + transed_reference_vector_.resize (particle_num_); + for (int i = 0; i < particle_num_; i++) + { + transed_reference_vector_[i] = PointCloudInPtr (new PointCloudIn ()); + } + } + + coherence_->setTargetCloud (input_); + + if (!change_detector_) + change_detector_ = boost::shared_ptr >(new pcl::octree::OctreePointCloudChangeDetector (change_detector_resolution_)); + + if (!particles_ || particles_->points.empty ()) + initParticles (true); + return (true); +} + +template int +pcl::tracking::ParticleFilterTracker::sampleWithReplacement +(const std::vector& a, const std::vector& q) +{ + using namespace boost; + static mt19937 gen (static_cast(time (0))); + uniform_real<> dst (0.0, 1.0); + variate_generator > rand (gen, dst); + double rU = rand () * static_cast (particles_->points.size ()); + int k = static_cast (rU); + rU -= k; /* rU - [rU] */ + if ( rU < q[k] ) + return k; + else + return a[k]; +} + +template void +pcl::tracking::ParticleFilterTracker::genAliasTable (std::vector &a, std::vector &q, + const PointCloudStateConstPtr &particles) +{ + /* generate an alias table, a and q */ + std::vector HL (particles->points.size ()); + std::vector::iterator H = HL.begin (); + std::vector::iterator L = HL.end () - 1; + size_t num = particles->points.size (); + for ( size_t i = 0; i < num; i++ ) + q[i] = particles->points[i].weight * static_cast (num); + for ( size_t i = 0; i < num; i++ ) + a[i] = static_cast (i); + // setup H and L + for ( size_t i = 0; i < num; i++ ) + if ( q[i] >= 1.0 ) + *H++ = static_cast (i); + else + *L-- = static_cast (i); + + while ( H != HL.begin() && L != HL.end() - 1 ) + { + int j = *(L + 1); + int k = *(H - 1); + a[j] = k; + q[k] += q[j] - 1; + L++; + if ( q[k] < 1.0 ) + { + *L-- = k; + --H; + } + } +} + +template void +pcl::tracking::ParticleFilterTracker::initParticles (bool reset) +{ + particles_.reset (new PointCloudState ()); + std::vector initial_noise_mean; + if (reset) + { + representative_state_.zero (); + StateT offset = StateT::toState (trans_); + representative_state_ = offset; + representative_state_.weight = 1.0f / static_cast (particle_num_); + } + + // sampling... + for ( int i = 0; i < particle_num_; i++ ) + { + StateT p; + p.zero (); + p.sample (initial_noise_mean_, initial_noise_covariance_); + p = p + representative_state_; + p.weight = 1.0f / static_cast (particle_num_); + particles_->points.push_back (p); // update + } +} + +template void +pcl::tracking::ParticleFilterTracker::normalizeWeight () +{ + // apply exponential function + double w_min = std::numeric_limits::max (); + double w_max = - std::numeric_limits::max (); + for ( size_t i = 0; i < particles_->points.size (); i++ ) + { + double weight = particles_->points[i].weight; + if (w_min > weight) + w_min = weight; + if (weight != 0.0 && w_max < weight) + w_max = weight; + } + + fit_ratio_ = w_min; + if (w_max != w_min) + { + for ( size_t i = 0; i < particles_->points.size (); i++ ) + { + if (particles_->points[i].weight != 0.0) + { + particles_->points[i].weight = static_cast (normalizeParticleWeight (particles_->points[i].weight, w_min, w_max)); + } + } + } + else + { + for ( size_t i = 0; i < particles_->points.size (); i++ ) + particles_->points[i].weight = 1.0f / static_cast (particles_->points.size ()); + } + + double sum = 0.0; + for ( size_t i = 0; i < particles_->points.size (); i++ ) + { + sum += particles_->points[i].weight; + } + + if (sum != 0.0) + { + for ( size_t i = 0; i < particles_->points.size (); i++ ) + particles_->points[i].weight = particles_->points[i].weight / static_cast (sum); + } + else + { + for ( size_t i = 0; i < particles_->points.size (); i++ ) + particles_->points[i].weight = 1.0f / static_cast (particles_->points.size ()); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::ParticleFilterTracker::cropInputPointCloud ( + const PointCloudInConstPtr &, PointCloudIn &output) +{ + double x_min, y_min, z_min, x_max, y_max, z_max; + calcBoundingBox (x_min, x_max, y_min, y_max, z_min, z_max); + pass_x_.setFilterLimits (float (x_min), float (x_max)); + pass_y_.setFilterLimits (float (y_min), float (y_max)); + pass_z_.setFilterLimits (float (z_min), float (z_max)); + + // x + PointCloudInPtr xcloud (new PointCloudIn); + pass_x_.setInputCloud (input_); + pass_x_.filter (*xcloud); + // y + PointCloudInPtr ycloud (new PointCloudIn); + pass_y_.setInputCloud (xcloud); + pass_y_.filter (*ycloud); + // z + pass_z_.setInputCloud (ycloud); + pass_z_.filter (output); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::ParticleFilterTracker::calcBoundingBox ( + double &x_min, double &x_max, double &y_min, double &y_max, double &z_min, double &z_max) +{ + x_min = y_min = z_min = std::numeric_limits::max (); + x_max = y_max = z_max = - std::numeric_limits::max (); + + for (size_t i = 0; i < transed_reference_vector_.size (); i++) + { + PointCloudInPtr target = transed_reference_vector_[i]; + PointInT Pmin, Pmax; + pcl::getMinMax3D (*target, Pmin, Pmax); + if (x_min > Pmin.x) + x_min = Pmin.x; + if (x_max < Pmax.x) + x_max = Pmax.x; + if (y_min > Pmin.y) + y_min = Pmin.y; + if (y_max < Pmax.y) + y_max = Pmax.y; + if (z_min > Pmin.z) + z_min = Pmin.z; + if (z_max < Pmax.z) + z_max = Pmax.z; + } +} + +template bool +pcl::tracking::ParticleFilterTracker::testChangeDetection +(const PointCloudInConstPtr &input) +{ + change_detector_->setInputCloud (input); + change_detector_->addPointsFromInputCloud (); + std::vector newPointIdxVector; + change_detector_->getPointIndicesFromNewVoxels (newPointIdxVector, change_detector_filter_); + change_detector_->switchBuffers (); + return newPointIdxVector.size () > 0; +} + +template void +pcl::tracking::ParticleFilterTracker::weight () +{ + if (!use_normal_) + { + for (size_t i = 0; i < particles_->points.size (); i++) + { + computeTransformedPointCloudWithoutNormal (particles_->points[i], *transed_reference_vector_[i]); + } + + PointCloudInPtr coherence_input (new PointCloudIn); + cropInputPointCloud (input_, *coherence_input); + + coherence_->setTargetCloud (coherence_input); + coherence_->initCompute (); + for (size_t i = 0; i < particles_->points.size (); i++) + { + IndicesPtr indices; + coherence_->compute (transed_reference_vector_[i], indices, particles_->points[i].weight); + } + } + else + { + for (size_t i = 0; i < particles_->points.size (); i++) + { + IndicesPtr indices (new std::vector); + computeTransformedPointCloudWithNormal (particles_->points[i], *indices, *transed_reference_vector_[i]); + } + + PointCloudInPtr coherence_input (new PointCloudIn); + cropInputPointCloud (input_, *coherence_input); + + coherence_->setTargetCloud (coherence_input); + coherence_->initCompute (); + for (size_t i = 0; i < particles_->points.size (); i++) + { + IndicesPtr indices (new std::vector); + coherence_->compute (transed_reference_vector_[i], indices, particles_->points[i].weight); + } + } + + normalizeWeight (); +} + +template void +pcl::tracking::ParticleFilterTracker::computeTransformedPointCloud +(const StateT& hypothesis, std::vector& indices, PointCloudIn &cloud) +{ + if (use_normal_) + computeTransformedPointCloudWithNormal (hypothesis, indices, cloud); + else + computeTransformedPointCloudWithoutNormal (hypothesis, cloud); +} + +template void +pcl::tracking::ParticleFilterTracker::computeTransformedPointCloudWithoutNormal +(const StateT& hypothesis, PointCloudIn &cloud) +{ + const Eigen::Affine3f trans = toEigenMatrix (hypothesis); + // destructively assigns to cloud + pcl::transformPointCloud (*ref_, cloud, trans); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::ParticleFilterTracker::computeTransformedPointCloudWithNormal ( +#ifdef PCL_TRACKING_NORMAL_SUPPORTED + const StateT& hypothesis, std::vector& indices, PointCloudIn &cloud) +#else + const StateT&, std::vector&, PointCloudIn &) +#endif +{ +#ifdef PCL_TRACKING_NORMAL_SUPPORTED + const Eigen::Affine3f trans = toEigenMatrix (hypothesis); + // destructively assigns to cloud + pcl::transformPointCloudWithNormals (*ref_, cloud, trans); + for ( size_t i = 0; i < cloud.points.size (); i++ ) + { + PointInT input_point = cloud.points[i]; + + if (!pcl_isfinite(input_point.x) || !pcl_isfinite(input_point.y) || !pcl_isfinite(input_point.z)) + continue; + // take occlusion into account + Eigen::Vector4f p = input_point.getVector4fMap (); + Eigen::Vector4f n = input_point.getNormalVector4fMap (); + double theta = pcl::getAngle3D (p, n); + if ( theta > occlusion_angle_thr_ ) + indices.push_back (i); + } +#else + PCL_WARN ("[pcl::%s::computeTransformedPointCloudWithoutNormal] use_normal_ == true is not supported in this Point Type.", + getClassName ().c_str ()); +#endif +} + +template void +pcl::tracking::ParticleFilterTracker::resample () +{ + resampleWithReplacement (); +} + +template void +pcl::tracking::ParticleFilterTracker::resampleWithReplacement () +{ + std::vector a (particles_->points.size ()); + std::vector q (particles_->points.size ()); + genAliasTable (a, q, particles_); + + const std::vector zero_mean (StateT::stateDimension (), 0.0); + // memoize the original list of particles + PointCloudStatePtr origparticles = particles_; + particles_->points.clear (); + // the first particle, it is a just copy of the maximum result + StateT p = representative_state_; + particles_->points.push_back (p); + + // with motion + int motion_num = static_cast (particles_->points.size ()) * static_cast (motion_ratio_); + for ( int i = 1; i < motion_num; i++ ) + { + int target_particle_index = sampleWithReplacement (a, q); + StateT p = origparticles->points[target_particle_index]; + // add noise using gaussian + p.sample (zero_mean, step_noise_covariance_); + p = p + motion_; + particles_->points.push_back (p); + } + + // no motion + for ( int i = motion_num; i < particle_num_; i++ ) + { + int target_particle_index = sampleWithReplacement (a, q); + StateT p = origparticles->points[target_particle_index]; + // add noise using gaussian + p.sample (zero_mean, step_noise_covariance_); + particles_->points.push_back (p); + } +} + +template void +pcl::tracking::ParticleFilterTracker::update () +{ + + StateT orig_representative = representative_state_; + representative_state_.zero (); + representative_state_.weight = 0.0; + for ( size_t i = 0; i < particles_->points.size (); i++) + { + StateT p = particles_->points[i]; + representative_state_ = representative_state_ + p * p.weight; + } + representative_state_.weight = 1.0f / static_cast (particles_->points.size ()); + motion_ = representative_state_ - orig_representative; +} + +template void +pcl::tracking::ParticleFilterTracker::computeTracking () +{ + + for (int i = 0; i < iteration_num_; i++) + { + if (changed_) + { + resample (); + } + + weight (); // likelihood is called in it + + if (changed_) + { + update (); + } + } + + // if ( getResult ().weight < resample_likelihood_thr_ ) + // { + // PCL_WARN ("too small likelihood, re-initializing...\n"); + // initParticles (false); + // } +} + +#define PCL_INSTANTIATE_ParticleFilterTracker(T,ST) template class PCL_EXPORTS pcl::tracking::ParticleFilterTracker; + +#endif diff --git a/pcl-1.7/pcl/tracking/impl/particle_filter_omp.hpp b/pcl-1.7/pcl/tracking/impl/particle_filter_omp.hpp new file mode 100644 index 0000000..092c5d1 --- /dev/null +++ b/pcl-1.7/pcl/tracking/impl/particle_filter_omp.hpp @@ -0,0 +1,89 @@ +#ifndef PCL_TRACKING_IMPL_PARTICLE_OMP_FILTER_H_ +#define PCL_TRACKING_IMPL_PARTICLE_OMP_FILTER_H_ + +#include + +template void +pcl::tracking::ParticleFilterOMPTracker::weight () +{ + if (!use_normal_) + { +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int i = 0; i < particle_num_; i++) + this->computeTransformedPointCloudWithoutNormal (particles_->points[i], *transed_reference_vector_[i]); + + PointCloudInPtr coherence_input (new PointCloudIn); + this->cropInputPointCloud (input_, *coherence_input); + if (change_counter_ == 0) + { + // test change detector + if (!use_change_detector_ || this->testChangeDetection (coherence_input)) + { + changed_ = true; + change_counter_ = change_detector_interval_; + coherence_->setTargetCloud (coherence_input); + coherence_->initCompute (); +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int i = 0; i < particle_num_; i++) + { + IndicesPtr indices; // dummy + coherence_->compute (transed_reference_vector_[i], indices, particles_->points[i].weight); + } + } + else + changed_ = false; + } + else + { + --change_counter_; + coherence_->setTargetCloud (coherence_input); + coherence_->initCompute (); +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int i = 0; i < particle_num_; i++) + { + IndicesPtr indices; // dummy + coherence_->compute (transed_reference_vector_[i], indices, particles_->points[i].weight); + } + } + } + else + { + std::vector indices_list (particle_num_); + for (int i = 0; i < particle_num_; i++) + { + indices_list[i] = IndicesPtr (new std::vector); + } +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int i = 0; i < particle_num_; i++) + { + this->computeTransformedPointCloudWithNormal (particles_->points[i], *indices_list[i], *transed_reference_vector_[i]); + } + + PointCloudInPtr coherence_input (new PointCloudIn); + this->cropInputPointCloud (input_, *coherence_input); + + coherence_->setTargetCloud (coherence_input); + coherence_->initCompute (); +#ifdef _OPENMP +#pragma omp parallel for num_threads(threads_) +#endif + for (int i = 0; i < particle_num_; i++) + { + coherence_->compute (transed_reference_vector_[i], indices_list[i], particles_->points[i].weight); + } + } + + normalizeWeight (); +} + +#define PCL_INSTANTIATE_ParticleFilterOMPTracker(T,ST) template class PCL_EXPORTS pcl::tracking::ParticleFilterOMPTracker; + +#endif diff --git a/pcl-1.7/pcl/tracking/impl/pyramidal_klt.hpp b/pcl-1.7/pcl/tracking/impl/pyramidal_klt.hpp new file mode 100644 index 0000000..6d782db --- /dev/null +++ b/pcl-1.7/pcl/tracking/impl/pyramidal_klt.hpp @@ -0,0 +1,645 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2014-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_TRACKING_IMPL_PYRAMIDAL_KLT_HPP +#define PCL_TRACKING_IMPL_PYRAMIDAL_KLT_HPP + +#include +#include +#include +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::tracking::PyramidalKLTTracker::setTrackingWindowSize (int width, int height) +{ + track_width_ = width; + track_height_ = height; +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::tracking::PyramidalKLTTracker::setPointsToTrack (const pcl::PointCloud::ConstPtr& keypoints) +{ + if (keypoints->size () <= keypoints_nbr_) + keypoints_ = keypoints; + else + { + pcl::PointCloud::Ptr p (new pcl::PointCloud); + p->reserve (keypoints_nbr_); + for (std::size_t i = 0; i < keypoints_nbr_; ++i) + p->push_back (keypoints->points[i]); + keypoints_ = p; + } + + keypoints_status_.reset (new pcl::PointIndices); + keypoints_status_->indices.resize (keypoints_->size (), 0); +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template inline void +pcl::tracking::PyramidalKLTTracker::setPointsToTrack (const pcl::PointIndicesConstPtr& points) +{ + assert ((input_ || ref_) && "[pcl::tracking::PyramidalKLTTracker] CALL setInputCloud FIRST!"); + + pcl::PointCloud::Ptr keypoints (new pcl::PointCloud); + keypoints->reserve (keypoints_nbr_); + for (std::size_t i = 0; i < keypoints_nbr_; ++i) + { + pcl::PointUV uv; + uv.u = points->indices[i] % input_->width; + uv.v = points->indices[i] / input_->width; + keypoints->push_back (uv); + } + setPointsToTrack (keypoints); +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::tracking::PyramidalKLTTracker::initCompute () +{ + // std::cout << ">>> [PyramidalKLTTracker::initCompute]" << std::endl; + if (!PCLBase::initCompute ()) + { + PCL_ERROR ("[pcl::tracking::%s::initCompute] PCLBase::Init failed.\n", + tracker_name_.c_str ()); + return (false); + } + + if (!input_->isOrganized ()) + { + PCL_ERROR ("[pcl::tracking::%s::initCompute] Need an organized point cloud to proceed!", + tracker_name_.c_str ()); + return (false); + } + + if (!keypoints_ || keypoints_->empty ()) + { + PCL_ERROR ("[pcl::tracking::%s::initCompute] No keypoints aborting!", + tracker_name_.c_str ()); + return (false); + } + + // This is the first call + if (!ref_) + { + ref_ = input_; + // std::cout << "First run!!!" << std::endl; + + if ((track_height_ * track_width_)%2 == 0) + { + PCL_ERROR ("[pcl::tracking::%s::initCompute] Tracking window (%dx%d) must be odd!\n", + tracker_name_.c_str (), track_width_, track_height_); + return (false); + } + + if (track_height_ < 3 || track_width_ < 3) + { + PCL_ERROR ("[pcl::tracking::%s::initCompute] Tracking window (%dx%d) must be >= 3x3!\n", + tracker_name_.c_str (), track_width_, track_height_); + return (false); + } + + track_width_2_ = track_width_ / 2; + track_height_2_ = track_height_ / 2; + + if (nb_levels_ < 2) + { + PCL_ERROR ("[pcl::tracking::%s::initCompute] Number of pyramid levels should be at least 2!", + tracker_name_.c_str ()); + return (false); + } + + if (nb_levels_ > 5) + { + PCL_ERROR ("[pcl::tracking::%s::initCompute] Number of pyramid levels should not exceed 5!", + tracker_name_.c_str ()); + return (false); + } + + computePyramids (ref_, ref_pyramid_, pcl::BORDER_REFLECT_101); + return (true); + } + else + initialized_ = true; + + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::PyramidalKLTTracker::derivatives (const FloatImage& src, FloatImage& grad_x, FloatImage& grad_y) const +{ + // std::cout << ">>> derivatives" << std::endl; + //////////////////////////////////////////////////////// + // Use Shcarr operator to compute derivatives. // + // Vertical kernel +3 +10 +3 = [1 0 -1]T * [3 10 3] // + // 0 0 0 // + // -3 -10 -3 // + // Horizontal kernel +3 0 -3 = [3 10 3]T * [1 0 -1] // + // +10 0 -10 // + // +3 0 -3 // + //////////////////////////////////////////////////////// + if (grad_x.size () != src.size () || grad_x.width != src.width || grad_x.height != src.height) + grad_x = FloatImage (src.width, src.height); + if (grad_y.size () != src.size () || grad_y.width != src.width || grad_y.height != src.height) + grad_y = FloatImage (src.width, src.height); + + int height = src.height, width = src.width; + float *row0 = new float [src.width + 2]; + float *row1 = new float [src.width + 2]; + float *trow0 = row0; ++trow0; + float *trow1 = row1; ++trow1; + const float* src_ptr = &(src.points[0]); + + for (int y = 0; y < height; y++) + { + const float* srow0 = src_ptr + (y > 0 ? y-1 : height > 1 ? 1 : 0) * width; + const float* srow1 = src_ptr + y * width; + const float* srow2 = src_ptr + (y < height-1 ? y+1 : height > 1 ? height-2 : 0) * width; + float* grad_x_row = &(grad_x.points[y * width]); + float* grad_y_row = &(grad_y.points[y * width]); + + // do vertical convolution + for (int x = 0; x < width; x++) + { + trow0[x] = (srow0[x] + srow2[x])*3 + srow1[x]*10; + trow1[x] = srow2[x] - srow0[x]; + } + + // make border + int x0 = width > 1 ? 1 : 0, x1 = width > 1 ? width-2 : 0; + trow0[-1] = trow0[x0]; trow0[width] = trow0[x1]; + trow1[-1] = trow1[x0]; trow1[width] = trow1[x1]; + + // do horizontal convolution and store results + for (int x = 0; x < width; x++) + { + grad_x_row[x] = trow0[x+1] - trow0[x-1]; + grad_y_row[x] = (trow1[x+1] + trow1[x-1])*3 + trow1[x]*10; + } + } +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::PyramidalKLTTracker::downsample (const FloatImageConstPtr& input, + FloatImageConstPtr& output) const +{ + FloatImage smoothed (input->width, input->height); + convolve (input, smoothed); + + int width = (smoothed.width +1) / 2; + int height = (smoothed.height +1) / 2; + + int *ii = new int[width]; + int *ii_ptr = ii; + for (int i = 0; i < width; ++i) + *ii_ptr++ = 2*i; + + FloatImagePtr down (new FloatImage (width, height)); +#ifdef _OPENMP +#pragma omp parallel for shared (output) private (ii) num_threads (threads_) +#endif + for (int j = 0; j < height; ++j) + { + int jj = 2*j; + for (int i = 0; i < width; ++i) + (*down) (i,j) = smoothed (ii[i],jj); + } + + output = down; +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::PyramidalKLTTracker::downsample (const FloatImageConstPtr& input, + FloatImageConstPtr& output, + FloatImageConstPtr& output_grad_x, + FloatImageConstPtr& output_grad_y) const +{ + downsample (input, output); + FloatImagePtr grad_x (new FloatImage (input->width, input->height)); + FloatImagePtr grad_y (new FloatImage (input->width, input->height)); + derivatives (*output, *grad_x, *grad_y); + output_grad_x = grad_x; + output_grad_y = grad_y; +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::PyramidalKLTTracker::convolve (const FloatImageConstPtr& input, FloatImage& output) const +{ + FloatImagePtr tmp (new FloatImage (input->width, input->height)); + convolveRows (input, *tmp); + convolveCols (tmp, output); +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::PyramidalKLTTracker::convolveRows (const FloatImageConstPtr& input, FloatImage& output) const +{ + int width = input->width; + int height = input->height; + int last = input->width - kernel_size_2_; + int w = last - 1; + +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads (threads_) +#endif + for (int j = 0; j < height; ++j) + { + for (int i = kernel_size_2_; i < last; ++i) + { + double result = 0; + for (int k = kernel_last_, l = i - kernel_size_2_; k > -1; --k, ++l) + result+= kernel_[k] * (*input) (l,j); + + output (i,j) = static_cast (result); + } + + for (int i = last; i < width; ++i) + output (i,j) = output (w, j); + + for (int i = 0; i < kernel_size_2_; ++i) + output (i,j) = output (kernel_size_2_, j); + } +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::PyramidalKLTTracker::convolveCols (const FloatImageConstPtr& input, FloatImage& output) const +{ + output = FloatImage (input->width, input->height); + + int width = input->width; + int height = input->height; + int last = input->height - kernel_size_2_; + int h = last -1; + +#ifdef _OPENMP +#pragma omp parallel for shared (output) num_threads (threads_) +#endif + for (int i = 0; i < width; ++i) + { + for (int j = kernel_size_2_; j < last; ++j) + { + double result = 0; + for (int k = kernel_last_, l = j - kernel_size_2_; k > -1; --k, ++l) + result += kernel_[k] * (*input) (i,l); + output (i,j) = static_cast (result); + } + + for (int j = last; j < height; ++j) + output (i,j) = output (i,h); + + for (int j = 0; j < kernel_size_2_; ++j) + output (i,j) = output (i, kernel_size_2_); + } +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::PyramidalKLTTracker::computePyramids (const PointCloudInConstPtr& input, + std::vector& pyramid, + pcl::InterpolationType border_type) const +{ + int step = 3; + pyramid.resize (step * nb_levels_); + + FloatImageConstPtr previous; + FloatImagePtr tmp (new FloatImage (input->width, input->height)); +#ifdef _OPENMP +#pragma omp parallel for num_threads (threads_) +#endif + for (int i = 0; i < static_cast (input->size ()); ++i) + tmp->points[i] = intensity_ (input->points[i]); + previous = tmp; + + FloatImagePtr img (new FloatImage (previous->width + 2*track_width_, + previous->height + 2*track_height_)); + + pcl::copyPointCloud (*tmp, *img, track_height_, track_height_, track_width_, track_width_, + border_type, 0.f); + pyramid[0] = img; + + // compute first level gradients + FloatImagePtr g_x (new FloatImage (input->width, input->height)); + FloatImagePtr g_y (new FloatImage (input->width, input->height)); + derivatives (*img, *g_x, *g_y); + // copy to bigger clouds + FloatImagePtr grad_x (new FloatImage (previous->width + 2*track_width_, + previous->height + 2*track_height_)); + pcl::copyPointCloud (*g_x, *grad_x, track_height_, track_height_, track_width_, track_width_, + pcl::BORDER_CONSTANT, 0.f); + pyramid[1] = grad_x; + + FloatImagePtr grad_y (new FloatImage (previous->width + 2*track_width_, + previous->height + 2*track_height_)); + pcl::copyPointCloud (*g_y, *grad_y, track_height_, track_height_, track_width_, track_width_, + pcl::BORDER_CONSTANT, 0.f); + pyramid[2] = grad_y; + + for (int level = 1; level < nb_levels_; ++level) + { + // compute current level and current level gradients + FloatImageConstPtr current; + FloatImageConstPtr g_x; + FloatImageConstPtr g_y; + downsample (previous, current, g_x, g_y); + // copy to bigger clouds + FloatImagePtr image (new FloatImage (current->width + 2*track_width_, + current->height + 2*track_height_)); + pcl::copyPointCloud (*current, *image, track_height_, track_height_, track_width_, track_width_, + border_type, 0.f); + pyramid[level*step] = image; + FloatImagePtr gradx (new FloatImage (g_x->width + 2*track_width_, g_x->height + 2*track_height_)); + pcl::copyPointCloud (*g_x, *gradx, track_height_, track_height_, track_width_, track_width_, + pcl::BORDER_CONSTANT, 0.f); + pyramid[level*step + 1] = gradx; + FloatImagePtr grady (new FloatImage (g_y->width + 2*track_width_, g_y->height + 2*track_height_)); + pcl::copyPointCloud (*g_y, *grady, track_height_, track_height_, track_width_, track_width_, + pcl::BORDER_CONSTANT, 0.f); + pyramid[level*step + 2] = grady; + // set the new level + previous = current; + } +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::PyramidalKLTTracker::spatialGradient (const FloatImage& img, + const FloatImage& grad_x, + const FloatImage& grad_y, + const Eigen::Array2i& location, + const Eigen::Array4f& weight, + Eigen::ArrayXXf& win, + Eigen::ArrayXXf& grad_x_win, + Eigen::ArrayXXf& grad_y_win, + Eigen::Array3f &covariance) const +{ + const int step = img.width; + covariance.setZero (); + + for (int y = 0; y < track_height_; y++) + { + const float* img_ptr = &(img.points[0]) + (y + location[1])*step + location[0]; + const float* grad_x_ptr = &(grad_x.points[0]) + (y + location[1])*step + location[0]; + const float* grad_y_ptr = &(grad_y.points[0]) + (y + location[1])*step + location[0]; + + float* win_ptr = win.data () + y*win.cols (); + float* grad_x_win_ptr = grad_x_win.data () + y*grad_x_win.cols (); + float* grad_y_win_ptr = grad_y_win.data () + y*grad_y_win.cols (); + + for (int x =0; x < track_width_; ++x, ++grad_x_ptr, ++grad_y_ptr) + { + *win_ptr++ = img_ptr[x]*weight[0] + img_ptr[x+1]*weight[1] + img_ptr[x+step]*weight[2] + img_ptr[x+step+1]*weight[3]; + float ixval = grad_x_ptr[0]*weight[0] + grad_x_ptr[1]*weight[1] + grad_x_ptr[step]*weight[2] + grad_x_ptr[step+1]*weight[3]; + float iyval = grad_y_ptr[0]*weight[0] + grad_y_ptr[1]*weight[1] + grad_y_ptr[step]*weight[2] + grad_y_ptr[step+1]*weight[3]; + //!!! store those + *grad_x_win_ptr++ = ixval; + *grad_y_win_ptr++ = iyval; + //covariance components + covariance[0] += ixval*ixval; + covariance[1] += ixval*iyval; + covariance[2] += iyval*iyval; + } + } +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::PyramidalKLTTracker::mismatchVector (const Eigen::ArrayXXf& prev, + const Eigen::ArrayXXf& prev_grad_x, + const Eigen::ArrayXXf& prev_grad_y, + const FloatImage& next, + const Eigen::Array2i& location, + const Eigen::Array4f& weight, + Eigen::Array2f &b) const +{ + const int step = next.width; + b.setZero (); + for (int y = 0; y < track_height_; y++) + { + const float* next_ptr = &(next.points[0]) + (y + location[1])*step + location[0]; + const float* prev_ptr = prev.data () + y*prev.cols (); + const float* prev_grad_x_ptr = prev_grad_x.data () + y*prev_grad_x.cols (); + const float* prev_grad_y_ptr = prev_grad_y.data () + y*prev_grad_y.cols (); + + for (int x = 0; x < track_width_; ++x, ++prev_grad_y_ptr, ++prev_grad_x_ptr) + { + float diff = next_ptr[x]*weight[0] + next_ptr[x+1]*weight[1] + + next_ptr[x+step]*weight[2] + next_ptr[x+step+1]*weight[3] - prev_ptr[x]; + b[0] += *prev_grad_x_ptr * diff; + b[1] += *prev_grad_y_ptr * diff; + } + } +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::PyramidalKLTTracker::track (const PointCloudInConstPtr& prev_input, + const PointCloudInConstPtr& input, + const std::vector& prev_pyramid, + const std::vector& pyramid, + const pcl::PointCloud::ConstPtr& prev_keypoints, + pcl::PointCloud::Ptr& keypoints, + std::vector& status, + Eigen::Affine3f& motion) const +{ + std::vector next_pts (prev_keypoints->size ()); + Eigen::Array2f half_win ((track_width_-1)*0.5f, (track_height_-1)*0.5f); + pcl::TransformationFromCorrespondences transformation_computer; + const int nb_points = prev_keypoints->size (); + for (int level = nb_levels_ - 1; level >= 0; --level) + { + const FloatImage& prev = *(prev_pyramid[level*3]); + const FloatImage& next = *(pyramid[level*3]); + const FloatImage& grad_x = *(prev_pyramid[level*3+1]); + const FloatImage& grad_y = *(prev_pyramid[level*3+2]); + + Eigen::ArrayXXf prev_win (track_height_, track_width_); + Eigen::ArrayXXf grad_x_win (track_height_, track_width_); + Eigen::ArrayXXf grad_y_win (track_height_, track_width_); + float ratio (1./(1 << level)); + for (int ptidx = 0; ptidx < nb_points; ptidx++) + { + Eigen::Array2f prev_pt (prev_keypoints->points[ptidx].u * ratio, + prev_keypoints->points[ptidx].v * ratio); + Eigen::Array2f next_pt; + if (level == nb_levels_ -1) + next_pt = prev_pt; + else + next_pt = next_pts[ptidx]*2.f; + + next_pts[ptidx] = next_pt; + + Eigen::Array2i iprev_point, inext_pt; + prev_pt -= half_win; + iprev_point[0] = floor (prev_pt[0]); + iprev_point[1] = floor (prev_pt[1]); + + if (iprev_point[0] < -track_width_ || iprev_point[0] >= grad_x.width || + iprev_point[1] < -track_height_ || iprev_point[1] >= grad_y.height) + { + if (level == 0) + status [ptidx] = -1; + continue; + } + + float a = prev_pt[0] - iprev_point[0]; + float b = prev_pt[1] - iprev_point[1]; + Eigen::Array4f weight; + weight[0] = (1.f - a)*(1.f - b); + weight[1] = a*(1.f - b); + weight[2] = (1.f - a)*b; + weight[3] = 1 - weight[0] - weight[1] - weight[2]; + + Eigen::Array3f covar = Eigen::Array3f::Zero (); + spatialGradient (prev, grad_x, grad_y, iprev_point, weight, prev_win, grad_x_win, grad_y_win, covar); + + float det = covar[0]*covar[2] - covar[1]*covar[1]; + float min_eigenvalue = (covar[2] + covar[0] - std::sqrt ((covar[0]-covar[2])*(covar[0]-covar[2]) + 4.f*covar[1]*covar[1]))/2.f; + + if (min_eigenvalue < min_eigenvalue_threshold_ || det < std::numeric_limits::epsilon ()) + { + status[ptidx] = -2; + continue; + } + + det = 1.f/det; + next_pt -= half_win; + + Eigen::Array2f prev_delta; + for (int j = 0; j < max_iterations_; j++) + { + inext_pt[0] = floor (next_pt[0]); + inext_pt[1] = floor (next_pt[1]); + + if (inext_pt[0] < -track_width_ || inext_pt[0] >= next.width || + inext_pt[1] < -track_height_ || inext_pt[1] >= next.height) + { + if (level == 0) + status[ptidx] = -1; + break; + } + + a = next_pt[0] - inext_pt[0]; + b = next_pt[1] - inext_pt[1]; + weight[0] = (1.f - a)*(1.f - b); + weight[1] = a*(1.f - b); + weight[2] = (1.f - a)*b; + weight[3] = 1 - weight[0] - weight[1] - weight[2]; + // compute mismatch vector + Eigen::Array2f beta = Eigen::Array2f::Zero (); + mismatchVector (prev_win, grad_x_win, grad_y_win, next, inext_pt, weight, beta); + // optical flow resolution + Eigen::Vector2f delta ((covar[1]*beta[1] - covar[2]*beta[0])*det, (covar[1]*beta[0] - covar[0]*beta[1])*det); + // update position + next_pt[0] += delta[0]; next_pt[1] += delta[1]; + next_pts[ptidx] = next_pt + half_win; + + if (delta.squaredNorm () <= epsilon_) + break; + + if (j > 0 && std::abs (delta[0] + prev_delta[0]) < 0.01 && + std::abs (delta[1] + prev_delta[1]) < 0.01 ) + { + next_pts[ptidx][0] -= delta[0]*0.5f; + next_pts[ptidx][1] -= delta[1]*0.5f; + break; + } + // update delta + prev_delta = delta; + } + + // update tracked points + if (level == 0 && !status[ptidx]) + { + Eigen::Array2f next_point = next_pts[ptidx] - half_win; + Eigen::Array2i inext_point; + + inext_point[0] = floor (next_point[0]); + inext_point[1] = floor (next_point[1]); + + if (inext_point[0] < -track_width_ || inext_point[0] >= next.width || + inext_point[1] < -track_height_ || inext_point[1] >= next.height) + { + status[ptidx] = -1; + continue; + } + // insert valid keypoint + pcl::PointUV n; + n.u = next_pts[ptidx][0]; + n.v = next_pts[ptidx][1]; + keypoints->push_back (n); + // add points pair to compute transformation + inext_point[0] = floor (next_pts[ptidx][0]); + inext_point[1] = floor (next_pts[ptidx][1]); + iprev_point[0] = floor (prev_keypoints->points[ptidx].u); + iprev_point[1] = floor (prev_keypoints->points[ptidx].v); + const PointInT& prev_pt = prev_input->points[iprev_point[1]*prev_input->width + iprev_point[0]]; + const PointInT& next_pt = input->points[inext_pt[1]*input->width + inext_pt[0]]; + transformation_computer.add (prev_pt.getVector3fMap (), next_pt.getVector3fMap (), 1.0); + } + } + } + motion = transformation_computer.getTransformation (); +} + +/////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::PyramidalKLTTracker::computeTracking () +{ + if (!initialized_) + return; + + std::vector pyramid; + computePyramids (input_, pyramid, pcl::BORDER_REFLECT_101); + pcl::PointCloud::Ptr keypoints (new pcl::PointCloud); + keypoints->reserve (keypoints_->size ()); + std::vector status (keypoints_->size (), 0); + track (ref_, input_, ref_pyramid_, pyramid, keypoints_, keypoints, status, motion_); + //swap reference and input + ref_ = input_; + ref_pyramid_ = pyramid; + keypoints_ = keypoints; + keypoints_status_->indices = status; +} + +#endif diff --git a/pcl-1.7/pcl/tracking/impl/tracker.hpp b/pcl-1.7/pcl/tracking/impl/tracker.hpp new file mode 100644 index 0000000..869fd11 --- /dev/null +++ b/pcl-1.7/pcl/tracking/impl/tracker.hpp @@ -0,0 +1,40 @@ +#ifndef PCL_TRACKING_IMPL_TRACKER_H_ +#define PCL_TRACKING_IMPL_TRACKER_H_ + +#include +#include +#include +#include + +template bool +pcl::tracking::Tracker::initCompute () +{ + if (!PCLBase::initCompute ()) + { + PCL_ERROR ("[pcl::%s::initCompute] PCLBase::Init failed.\n", getClassName ().c_str ()); + return (false); + } + + // If the dataset is empty, just return + if (input_->points.empty ()) + { + PCL_ERROR ("[pcl::%s::compute] input_ is empty!\n", getClassName ().c_str ()); + // Cleanup + deinitCompute (); + return (false); + } + + return (true); +} + +template void +pcl::tracking::Tracker::compute () +{ + if (!initCompute ()) + return; + + computeTracking (); + deinitCompute (); +} + +#endif diff --git a/pcl-1.7/pcl/tracking/impl/tracking.hpp b/pcl-1.7/pcl/tracking/impl/tracking.hpp new file mode 100644 index 0000000..f714877 --- /dev/null +++ b/pcl-1.7/pcl/tracking/impl/tracking.hpp @@ -0,0 +1,783 @@ +#ifndef PCL_TRACKING_IMPL_TRACKING_H_ +#define PCL_TRACKING_IMPL_TRACKING_H_ + +#include +#include +#include +#include + +namespace pcl +{ + namespace tracking + { + struct _ParticleXYZRPY + { + PCL_ADD_POINT4D; + union + { + struct + { + float roll; + float pitch; + float yaw; + float weight; + }; + float data_c[4]; + }; + }; + + // particle definition + struct EIGEN_ALIGN16 ParticleXYZRPY : public _ParticleXYZRPY + { + inline ParticleXYZRPY () + { + x = y = z = roll = pitch = yaw = 0.0; + data[3] = 1.0f; + } + + inline ParticleXYZRPY (float _x, float _y, float _z) + { + x = _x; y = _y; z = _z; + roll = pitch = yaw = 0.0; + data[3] = 1.0f; + } + + inline ParticleXYZRPY (float _x, float _y, float _z, float _roll, float _pitch, float _yaw) + { + x = _x; y = _y; z = _z; + roll = _roll; pitch = _pitch; yaw = _yaw; + data[3] = 1.0f; + } + + inline static int + stateDimension () { return 6; } + + void + sample (const std::vector& mean, const std::vector& cov) + { + x += static_cast (sampleNormal (mean[0], cov[0])); + y += static_cast (sampleNormal (mean[1], cov[1])); + z += static_cast (sampleNormal (mean[2], cov[2])); + roll += static_cast (sampleNormal (mean[3], cov[3])); + pitch += static_cast (sampleNormal (mean[4], cov[4])); + yaw += static_cast (sampleNormal (mean[5], cov[5])); + } + + void + zero () + { + x = 0.0; + y = 0.0; + z = 0.0; + roll = 0.0; + pitch = 0.0; + yaw = 0.0; + } + + inline Eigen::Affine3f + toEigenMatrix () const + { + return getTransformation(x, y, z, roll, pitch, yaw); + } + + static pcl::tracking::ParticleXYZRPY + toState (const Eigen::Affine3f &trans) + { + float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw; + getTranslationAndEulerAngles (trans, + trans_x, trans_y, trans_z, + trans_roll, trans_pitch, trans_yaw); + return pcl::tracking::ParticleXYZRPY (trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw); + } + + // a[i] + inline float operator [] (unsigned int i) + { + switch (i) + { + case 0: return x; + case 1: return y; + case 2: return z; + case 3: return roll; + case 4: return pitch; + case 5: return yaw; + default: return 0.0; + } + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + inline std::ostream& operator << (std::ostream& os, const ParticleXYZRPY& p) + { + os << "(" << p.x << "," << p.y << "," << p.z << "," + << p.roll << "," << p.pitch << "," << p.yaw << ")"; + return (os); + } + + // a * k + inline pcl::tracking::ParticleXYZRPY operator * (const ParticleXYZRPY& p, double val) + { + pcl::tracking::ParticleXYZRPY newp; + newp.x = static_cast (p.x * val); + newp.y = static_cast (p.y * val); + newp.z = static_cast (p.z * val); + newp.roll = static_cast (p.roll * val); + newp.pitch = static_cast (p.pitch * val); + newp.yaw = static_cast (p.yaw * val); + return (newp); + } + + // a + b + inline pcl::tracking::ParticleXYZRPY operator + (const ParticleXYZRPY& a, const ParticleXYZRPY& b) + { + pcl::tracking::ParticleXYZRPY newp; + newp.x = a.x + b.x; + newp.y = a.y + b.y; + newp.z = a.z + b.z; + newp.roll = a.roll + b.roll; + newp.pitch = a.pitch + b.pitch; + newp.yaw = a.yaw + b.yaw; + return (newp); + } + + // a - b + inline pcl::tracking::ParticleXYZRPY operator - (const ParticleXYZRPY& a, const ParticleXYZRPY& b) + { + pcl::tracking::ParticleXYZRPY newp; + newp.x = a.x - b.x; + newp.y = a.y - b.y; + newp.z = a.z - b.z; + newp.roll = a.roll - b.roll; + newp.pitch = a.pitch - b.pitch; + newp.yaw = a.yaw - b.yaw; + return (newp); + } + + } +} + + +//########################################################################33 + + +namespace pcl +{ + namespace tracking + { + struct _ParticleXYZR + { + PCL_ADD_POINT4D; + union + { + struct + { + float roll; + float pitch; + float yaw; + float weight; + }; + float data_c[4]; + }; + }; + + // particle definition + struct EIGEN_ALIGN16 ParticleXYZR : public _ParticleXYZR + { + inline ParticleXYZR () + { + x = y = z = roll = pitch = yaw = 0.0; + data[3] = 1.0f; + } + + inline ParticleXYZR (float _x, float _y, float _z) + { + x = _x; y = _y; z = _z; + roll = pitch = yaw = 0.0; + data[3] = 1.0f; + } + + inline ParticleXYZR (float _x, float _y, float _z, float, float _pitch, float) + { + x = _x; y = _y; z = _z; + roll = 0; pitch = _pitch; yaw = 0; + data[3] = 1.0f; + } + + inline static int + stateDimension () { return 6; } + + void + sample (const std::vector& mean, const std::vector& cov) + { + x += static_cast (sampleNormal (mean[0], cov[0])); + y += static_cast (sampleNormal (mean[1], cov[1])); + z += static_cast (sampleNormal (mean[2], cov[2])); + roll = 0; + pitch += static_cast (sampleNormal (mean[4], cov[4])); + yaw = 0; + } + + void + zero () + { + x = 0.0; + y = 0.0; + z = 0.0; + roll = 0.0; + pitch = 0.0; + yaw = 0.0; + } + + inline Eigen::Affine3f + toEigenMatrix () const + { + return getTransformation(x, y, z, roll, pitch, yaw); + } + + static pcl::tracking::ParticleXYZR + toState (const Eigen::Affine3f &trans) + { + float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw; + getTranslationAndEulerAngles (trans, + trans_x, trans_y, trans_z, + trans_roll, trans_pitch, trans_yaw); + return (pcl::tracking::ParticleXYZR (trans_x, trans_y, trans_z, 0, trans_pitch, 0)); + } + + // a[i] + inline float operator [] (unsigned int i) + { + switch (i) + { + case 0: return x; + case 1: return y; + case 2: return z; + case 3: return roll; + case 4: return pitch; + case 5: return yaw; + default: return 0.0; + } + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + inline std::ostream& operator << (std::ostream& os, const ParticleXYZR& p) + { + os << "(" << p.x << "," << p.y << "," << p.z << "," + << p.roll << "," << p.pitch << "," << p.yaw << ")"; + return (os); + } + + // a * k + inline pcl::tracking::ParticleXYZR operator * (const ParticleXYZR& p, double val) + { + pcl::tracking::ParticleXYZR newp; + newp.x = static_cast (p.x * val); + newp.y = static_cast (p.y * val); + newp.z = static_cast (p.z * val); + newp.roll = static_cast (p.roll * val); + newp.pitch = static_cast (p.pitch * val); + newp.yaw = static_cast (p.yaw * val); + return (newp); + } + + // a + b + inline pcl::tracking::ParticleXYZR operator + (const ParticleXYZR& a, const ParticleXYZR& b) + { + pcl::tracking::ParticleXYZR newp; + newp.x = a.x + b.x; + newp.y = a.y + b.y; + newp.z = a.z + b.z; + newp.roll = 0; + newp.pitch = a.pitch + b.pitch; + newp.yaw = 0.0; + return (newp); + } + + // a - b + inline pcl::tracking::ParticleXYZR operator - (const ParticleXYZR& a, const ParticleXYZR& b) + { + pcl::tracking::ParticleXYZR newp; + newp.x = a.x - b.x; + newp.y = a.y - b.y; + newp.z = a.z - b.z; + newp.roll = 0.0; + newp.pitch = a.pitch - b.pitch; + newp.yaw = 0.0; + return (newp); + } + + } +} + +//########################################################################33 + + + +namespace pcl +{ + namespace tracking + { + struct _ParticleXYRPY + { + PCL_ADD_POINT4D; + union + { + struct + { + float roll; + float pitch; + float yaw; + float weight; + }; + float data_c[4]; + }; + }; + + // particle definition + struct EIGEN_ALIGN16 ParticleXYRPY : public _ParticleXYRPY + { + inline ParticleXYRPY () + { + x = y = z = roll = pitch = yaw = 0.0; + data[3] = 1.0f; + } + + inline ParticleXYRPY (float _x, float, float _z) + { + x = _x; y = 0; z = _z; + roll = pitch = yaw = 0.0; + data[3] = 1.0f; + } + + inline ParticleXYRPY (float _x, float, float _z, float _roll, float _pitch, float _yaw) + { + x = _x; y = 0; z = _z; + roll = _roll; pitch = _pitch; yaw = _yaw; + data[3] = 1.0f; + } + + inline static int + stateDimension () { return 6; } + + void + sample (const std::vector& mean, const std::vector& cov) + { + x += static_cast (sampleNormal (mean[0], cov[0])); + y = 0; + z += static_cast (sampleNormal (mean[2], cov[2])); + roll += static_cast (sampleNormal (mean[3], cov[3])); + pitch += static_cast (sampleNormal (mean[4], cov[4])); + yaw += static_cast (sampleNormal (mean[5], cov[5])); + } + + void + zero () + { + x = 0.0; + y = 0.0; + z = 0.0; + roll = 0.0; + pitch = 0.0; + yaw = 0.0; + } + + inline Eigen::Affine3f + toEigenMatrix () const + { + return getTransformation(x, y, z, roll, pitch, yaw); + } + + static pcl::tracking::ParticleXYRPY + toState (const Eigen::Affine3f &trans) + { + float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw; + getTranslationAndEulerAngles (trans, + trans_x, trans_y, trans_z, + trans_roll, trans_pitch, trans_yaw); + return (pcl::tracking::ParticleXYRPY (trans_x, 0, trans_z, trans_roll, trans_pitch, trans_yaw)); + } + + // a[i] + inline float operator [] (unsigned int i) + { + switch (i) + { + case 0: return x; + case 1: return y; + case 2: return z; + case 3: return roll; + case 4: return pitch; + case 5: return yaw; + default: return 0.0; + } + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + inline std::ostream& operator << (std::ostream& os, const ParticleXYRPY& p) + { + os << "(" << p.x << "," << p.y << "," << p.z << "," + << p.roll << "," << p.pitch << "," << p.yaw << ")"; + return (os); + } + + // a * k + inline pcl::tracking::ParticleXYRPY operator * (const ParticleXYRPY& p, double val) + { + pcl::tracking::ParticleXYRPY newp; + newp.x = static_cast (p.x * val); + newp.y = static_cast (p.y * val); + newp.z = static_cast (p.z * val); + newp.roll = static_cast (p.roll * val); + newp.pitch = static_cast (p.pitch * val); + newp.yaw = static_cast (p.yaw * val); + return (newp); + } + + // a + b + inline pcl::tracking::ParticleXYRPY operator + (const ParticleXYRPY& a, const ParticleXYRPY& b) + { + pcl::tracking::ParticleXYRPY newp; + newp.x = a.x + b.x; + newp.y = 0; + newp.z = a.z + b.z; + newp.roll = a.roll + b.roll; + newp.pitch = a.pitch + b.pitch; + newp.yaw = a.yaw + b.yaw; + return (newp); + } + + // a - b + inline pcl::tracking::ParticleXYRPY operator - (const ParticleXYRPY& a, const ParticleXYRPY& b) + { + pcl::tracking::ParticleXYRPY newp; + newp.x = a.x - b.x; + newp.z = a.z - b.z; + newp.y = 0; + newp.roll = a.roll - b.roll; + newp.pitch = a.pitch - b.pitch; + newp.yaw = a.yaw - b.yaw; + return (newp); + } + + } +} + +//########################################################################33 + +namespace pcl +{ + namespace tracking + { + struct _ParticleXYRP + { + PCL_ADD_POINT4D; + union + { + struct + { + float roll; + float pitch; + float yaw; + float weight; + }; + float data_c[4]; + }; + }; + + // particle definition + struct EIGEN_ALIGN16 ParticleXYRP : public _ParticleXYRP + { + inline ParticleXYRP () + { + x = y = z = roll = pitch = yaw = 0.0; + data[3] = 1.0f; + } + + inline ParticleXYRP (float _x, float, float _z) + { + x = _x; y = 0; z = _z; + roll = pitch = yaw = 0.0; + data[3] = 1.0f; + } + + inline ParticleXYRP (float _x, float, float _z, float, float _pitch, float _yaw) + { + x = _x; y = 0; z = _z; + roll = 0; pitch = _pitch; yaw = _yaw; + data[3] = 1.0f; + } + + inline static int + stateDimension () { return 6; } + + void + sample (const std::vector& mean, const std::vector& cov) + { + x += static_cast (sampleNormal (mean[0], cov[0])); + y = 0; + z += static_cast (sampleNormal (mean[2], cov[2])); + roll = 0; + pitch += static_cast (sampleNormal (mean[4], cov[4])); + yaw += static_cast (sampleNormal (mean[5], cov[5])); + } + + void + zero () + { + x = 0.0; + y = 0.0; + z = 0.0; + roll = 0.0; + pitch = 0.0; + yaw = 0.0; + } + + inline Eigen::Affine3f + toEigenMatrix () const + { + return getTransformation(x, y, z, roll, pitch, yaw); + } + + static pcl::tracking::ParticleXYRP + toState (const Eigen::Affine3f &trans) + { + float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw; + getTranslationAndEulerAngles (trans, + trans_x, trans_y, trans_z, + trans_roll, trans_pitch, trans_yaw); + return (pcl::tracking::ParticleXYRP (trans_x, 0, trans_z, 0, trans_pitch, trans_yaw)); + } + + // a[i] + inline float operator [] (unsigned int i) + { + switch (i) + { + case 0: return x; + case 1: return y; + case 2: return z; + case 3: return roll; + case 4: return pitch; + case 5: return yaw; + default: return 0.0; + } + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + inline std::ostream& operator << (std::ostream& os, const ParticleXYRP& p) + { + os << "(" << p.x << "," << p.y << "," << p.z << "," + << p.roll << "," << p.pitch << "," << p.yaw << ")"; + return (os); + } + + // a * k + inline pcl::tracking::ParticleXYRP operator * (const ParticleXYRP& p, double val) + { + pcl::tracking::ParticleXYRP newp; + newp.x = static_cast (p.x * val); + newp.y = static_cast (p.y * val); + newp.z = static_cast (p.z * val); + newp.roll = static_cast (p.roll * val); + newp.pitch = static_cast (p.pitch * val); + newp.yaw = static_cast (p.yaw * val); + return (newp); + } + + // a + b + inline pcl::tracking::ParticleXYRP operator + (const ParticleXYRP& a, const ParticleXYRP& b) + { + pcl::tracking::ParticleXYRP newp; + newp.x = a.x + b.x; + newp.y = 0; + newp.z = a.z + b.z; + newp.roll = 0; + newp.pitch = a.pitch + b.pitch; + newp.yaw = a.yaw + b.yaw; + return (newp); + } + + // a - b + inline pcl::tracking::ParticleXYRP operator - (const ParticleXYRP& a, const ParticleXYRP& b) + { + pcl::tracking::ParticleXYRP newp; + newp.x = a.x - b.x; + newp.z = a.z - b.z; + newp.y = 0; + newp.roll = 0.0; + newp.pitch = a.pitch - b.pitch; + newp.yaw = a.yaw - b.yaw; + return (newp); + } + + } +} + +//########################################################################33 + +namespace pcl +{ + namespace tracking + { + struct _ParticleXYR + { + PCL_ADD_POINT4D; + union + { + struct + { + float roll; + float pitch; + float yaw; + float weight; + }; + float data_c[4]; + }; + }; + + // particle definition + struct EIGEN_ALIGN16 ParticleXYR : public _ParticleXYR + { + inline ParticleXYR () + { + x = y = z = roll = pitch = yaw = 0.0; + data[3] = 1.0f; + } + + inline ParticleXYR (float _x, float, float _z) + { + x = _x; y = 0; z = _z; + roll = pitch = yaw = 0.0; + data[3] = 1.0f; + } + + inline ParticleXYR (float _x, float, float _z, float, float _pitch, float) + { + x = _x; y = 0; z = _z; + roll = 0; pitch = _pitch; yaw = 0; + data[3] = 1.0f; + } + + inline static int + stateDimension () { return 6; } + + void + sample (const std::vector& mean, const std::vector& cov) + { + x += static_cast (sampleNormal (mean[0], cov[0])); + y = 0; + z += static_cast (sampleNormal (mean[2], cov[2])); + roll = 0; + pitch += static_cast (sampleNormal (mean[4], cov[4])); + yaw = 0; + } + + void + zero () + { + x = 0.0; + y = 0.0; + z = 0.0; + roll = 0.0; + pitch = 0.0; + yaw = 0.0; + } + + inline Eigen::Affine3f + toEigenMatrix () const + { + return getTransformation(x, y, z, roll, pitch, yaw); + } + + static pcl::tracking::ParticleXYR + toState (const Eigen::Affine3f &trans) + { + float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw; + getTranslationAndEulerAngles (trans, + trans_x, trans_y, trans_z, + trans_roll, trans_pitch, trans_yaw); + return (pcl::tracking::ParticleXYR (trans_x, 0, trans_z, 0, trans_pitch, 0)); + } + + // a[i] + inline float operator [] (unsigned int i) + { + switch (i) + { + case 0: return x; + case 1: return y; + case 2: return z; + case 3: return roll; + case 4: return pitch; + case 5: return yaw; + default: return 0.0; + } + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + inline std::ostream& operator << (std::ostream& os, const ParticleXYR& p) + { + os << "(" << p.x << "," << p.y << "," << p.z << "," + << p.roll << "," << p.pitch << "," << p.yaw << ")"; + return (os); + } + + // a * k + inline pcl::tracking::ParticleXYR operator * (const ParticleXYR& p, double val) + { + pcl::tracking::ParticleXYR newp; + newp.x = static_cast (p.x * val); + newp.y = static_cast (p.y * val); + newp.z = static_cast (p.z * val); + newp.roll = static_cast (p.roll * val); + newp.pitch = static_cast (p.pitch * val); + newp.yaw = static_cast (p.yaw * val); + return (newp); + } + + // a + b + inline pcl::tracking::ParticleXYR operator + (const ParticleXYR& a, const ParticleXYR& b) + { + pcl::tracking::ParticleXYR newp; + newp.x = a.x + b.x; + newp.y = 0; + newp.z = a.z + b.z; + newp.roll = 0; + newp.pitch = a.pitch + b.pitch; + newp.yaw = 0.0; + return (newp); + } + + // a - b + inline pcl::tracking::ParticleXYR operator - (const ParticleXYR& a, const ParticleXYR& b) + { + pcl::tracking::ParticleXYR newp; + newp.x = a.x - b.x; + newp.z = a.z - b.z; + newp.y = 0; + newp.roll = 0.0; + newp.pitch = a.pitch - b.pitch; + newp.yaw = 0.0; + return (newp); + } + + } +} + +#define PCL_STATE_POINT_TYPES \ + (pcl::tracking::ParticleXYR) \ + (pcl::tracking::ParticleXYZRPY) \ + (pcl::tracking::ParticleXYZR) \ + (pcl::tracking::ParticleXYRPY) \ + (pcl::tracking::ParticleXYRP) + +#endif // diff --git a/pcl-1.7/pcl/tracking/kld_adaptive_particle_filter.h b/pcl-1.7/pcl/tracking/kld_adaptive_particle_filter.h new file mode 100644 index 0000000..6593dee --- /dev/null +++ b/pcl-1.7/pcl/tracking/kld_adaptive_particle_filter.h @@ -0,0 +1,218 @@ +#ifndef PCL_TRACKING_KLD_ADAPTIVE_PARTICLE_FILTER_H_ +#define PCL_TRACKING_KLD_ADAPTIVE_PARTICLE_FILTER_H_ + +#include +#include +#include + +namespace pcl +{ + namespace tracking + { + + /** \brief @b KLDAdaptiveParticleFilterTracker tracks the PointCloud which is given by + setReferenceCloud within the measured PointCloud using particle filter method. + The number of the particles changes adaptively based on KLD sampling [D. Fox, NIPS-01], [D.Fox, IJRR03]. + * \author Ryohei Ueda + * \ingroup tracking + */ + template + class KLDAdaptiveParticleFilterTracker: public ParticleFilterTracker + { + public: + using Tracker::tracker_name_; + using Tracker::search_; + using Tracker::input_; + using Tracker::getClassName; + using ParticleFilterTracker::transed_reference_vector_; + using ParticleFilterTracker::coherence_; + using ParticleFilterTracker::initParticles; + using ParticleFilterTracker::weight; + using ParticleFilterTracker::update; + using ParticleFilterTracker::iteration_num_; + using ParticleFilterTracker::particle_num_; + using ParticleFilterTracker::particles_; + using ParticleFilterTracker::use_normal_; + using ParticleFilterTracker::use_change_detector_; + using ParticleFilterTracker::change_detector_resolution_; + using ParticleFilterTracker::change_detector_; + using ParticleFilterTracker::motion_; + using ParticleFilterTracker::motion_ratio_; + using ParticleFilterTracker::step_noise_covariance_; + using ParticleFilterTracker::representative_state_; + using ParticleFilterTracker::sampleWithReplacement; + + typedef Tracker BaseClass; + + typedef typename Tracker::PointCloudIn PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + typedef typename Tracker::PointCloudState PointCloudState; + typedef typename PointCloudState::Ptr PointCloudStatePtr; + typedef typename PointCloudState::ConstPtr PointCloudStateConstPtr; + + typedef PointCoherence Coherence; + typedef boost::shared_ptr< Coherence > CoherencePtr; + typedef boost::shared_ptr< const Coherence > CoherenceConstPtr; + + typedef PointCloudCoherence CloudCoherence; + typedef boost::shared_ptr< CloudCoherence > CloudCoherencePtr; + typedef boost::shared_ptr< const CloudCoherence > CloudCoherenceConstPtr; + + /** \brief Empty constructor. */ + KLDAdaptiveParticleFilterTracker () + : ParticleFilterTracker () + , maximum_particle_number_ () + , epsilon_ (0) + , delta_ (0.99) + , bin_size_ () + { + tracker_name_ = "KLDAdaptiveParticleFilterTracker"; + } + + /** \brief set the bin size. + * \param bin_size the size of a bin + */ + inline void setBinSize (const StateT& bin_size) { bin_size_ = bin_size; } + + /** \brief get the bin size. */ + inline StateT getBinSize () const { return (bin_size_); } + + /** \brief set the maximum number of the particles. + * \param nr the maximum number of the particles. + */ + inline void setMaximumParticleNum (unsigned int nr) { maximum_particle_number_ = nr; } + + /** \brief get the maximum number of the particles.*/ + inline unsigned int getMaximumParticleNum () const { return (maximum_particle_number_); } + + /** \brief set epsilon to be used to calc K-L boundary. + * \param eps epsilon + */ + inline void setEpsilon (double eps) { epsilon_ = eps; } + + /** \brief get epsilon to be used to calc K-L boundary. */ + inline double getEpsilon () const { return (epsilon_); } + + /** \brief set delta to be used in chi-squared distribution. + * \param delta delta of chi-squared distribution. + */ + inline void setDelta (double delta) { delta_ = delta; } + + /** \brief get delta to be used in chi-squared distribution.*/ + inline double getDelta () const { return (delta_); } + + protected: + + /** \brief return true if the two bins are equal. + * \param a index of the bin + * \param b index of the bin + */ + virtual bool + equalBin (std::vector a, std::vector b) + { + int dimension = StateT::stateDimension (); + for (int i = 0; i < dimension; i++) + if (a[i] != b[i]) + return (false); + return (true); + } + + /** \brief return upper quantile of standard normal distribution. + * \param[in] u ratio of quantile. + */ + double + normalQuantile (double u) + { + const double a[9] = { 1.24818987e-4, -1.075204047e-3, 5.198775019e-3, + -0.019198292004, 0.059054035642,-0.151968751364, + 0.319152932694,-0.5319230073, 0.797884560593}; + const double b[15] = { -4.5255659e-5, 1.5252929e-4, -1.9538132e-5, + -6.76904986e-4, 1.390604284e-3,-7.9462082e-4, + -2.034254874e-3, 6.549791214e-3,-0.010557625006, + 0.011630447319,-9.279453341e-3, 5.353579108e-3, + -2.141268741e-3, 5.35310549e-4, 0.999936657524}; + double w, y, z; + int i; + + if (u == 0.) + return (0.5); + y = u / 2.0; + if (y < -6.) + return (0.0); + if (y > 6.) + return (1.0); + if (y < 0.0) + y = - y; + if (y < 1.0) + { + w = y * y; + z = a[0]; + for (i = 1; i < 9; i++) + z = z * w + a[i]; + z *= (y * 2.0); + } + else + { + y -= 2.0; + z = b[0]; + for (i = 1; i < 15; i++) + z = z * y + b[i]; + } + + if (u < 0.0) + return ((1. - z) / 2.0); + return ((1. + z) / 2.0); + } + + /** \brief calculate K-L boundary. K-L boundary follows 1/2e*chi(k-1, 1-d)^2. + * \param[in] k the number of bins and the first parameter of chi distribution. + */ + virtual + double calcKLBound (int k) + { + double z = normalQuantile (delta_); + double chi = 1.0 - 2.0 / (9.0 * (k - 1)) + sqrt (2.0 / (9.0 * (k - 1))) * z; + return ((k - 1.0) / (2.0 * epsilon_) * chi * chi * chi); + } + + /** \brief insert a bin into the set of the bins. if that bin is already registered, + return false. if not, return true. + * \param bin a bin to be inserted. + * \param B a set of the bins + */ + virtual bool + insertIntoBins (std::vector bin, std::vector > &B); + + /** \brief This method should get called before starting the actual computation. */ + virtual bool + initCompute (); + + /** \brief resampling phase of particle filter method. + sampling the particles according to the weights calculated in weight method. + in particular, "sample with replacement" is archieved by walker's alias method. + */ + virtual void + resample (); + + /** \brief the maximum number of the particles. */ + unsigned int maximum_particle_number_; + + /** \brief error between K-L distance and MLE*/ + double epsilon_; + + /** \brief probability of distance between K-L distance and MLE is less than epsilon_*/ + double delta_; + + /** \brief the size of a bin.*/ + StateT bin_size_; + }; + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/tracking/kld_adaptive_particle_filter_omp.h b/pcl-1.7/pcl/tracking/kld_adaptive_particle_filter_omp.h new file mode 100644 index 0000000..64559ad --- /dev/null +++ b/pcl-1.7/pcl/tracking/kld_adaptive_particle_filter_omp.h @@ -0,0 +1,100 @@ +#ifndef PCL_TRACKING_KLD_ADAPTIVE_PARTICLE_FILTER_OMP_H_ +#define PCL_TRACKING_KLD_ADAPTIVE_PARTICLE_FILTER_OMP_H_ + +#include +#include +#include + +namespace pcl +{ + namespace tracking + { + /** \brief @b KLDAdaptiveParticleFilterOMPTracker tracks the PointCloud which is given by + setReferenceCloud within the measured PointCloud using particle filter method. + The number of the particles changes adaptively based on KLD sampling [D. Fox, NIPS-01], [D.Fox, IJRR03]. + and the computation of the weights of the particles is parallelized using OpenMP. + * \author Ryohei Ueda + * \ingroup tracking + */ + template + class KLDAdaptiveParticleFilterOMPTracker: public KLDAdaptiveParticleFilterTracker + { + public: + using Tracker::tracker_name_; + using Tracker::search_; + using Tracker::input_; + using Tracker::indices_; + using Tracker::getClassName; + using KLDAdaptiveParticleFilterTracker::particles_; + using KLDAdaptiveParticleFilterTracker::change_detector_; + using KLDAdaptiveParticleFilterTracker::change_counter_; + using KLDAdaptiveParticleFilterTracker::change_detector_interval_; + using KLDAdaptiveParticleFilterTracker::use_change_detector_; + using KLDAdaptiveParticleFilterTracker::pass_x_; + using KLDAdaptiveParticleFilterTracker::pass_y_; + using KLDAdaptiveParticleFilterTracker::pass_z_; + using KLDAdaptiveParticleFilterTracker::alpha_; + using KLDAdaptiveParticleFilterTracker::changed_; + using KLDAdaptiveParticleFilterTracker::coherence_; + using KLDAdaptiveParticleFilterTracker::use_normal_; + using KLDAdaptiveParticleFilterTracker::particle_num_; + using KLDAdaptiveParticleFilterTracker::change_detector_filter_; + using KLDAdaptiveParticleFilterTracker::transed_reference_vector_; + //using KLDAdaptiveParticleFilterTracker::calcLikelihood; + using KLDAdaptiveParticleFilterTracker::normalizeWeight; + using KLDAdaptiveParticleFilterTracker::normalizeParticleWeight; + using KLDAdaptiveParticleFilterTracker::calcBoundingBox; + + typedef Tracker BaseClass; + + typedef typename Tracker::PointCloudIn PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + typedef typename Tracker::PointCloudState PointCloudState; + typedef typename PointCloudState::Ptr PointCloudStatePtr; + typedef typename PointCloudState::ConstPtr PointCloudStateConstPtr; + + typedef PointCoherence Coherence; + typedef boost::shared_ptr< Coherence > CoherencePtr; + typedef boost::shared_ptr< const Coherence > CoherenceConstPtr; + + typedef PointCloudCoherence CloudCoherence; + typedef boost::shared_ptr< CloudCoherence > CloudCoherencePtr; + typedef boost::shared_ptr< const CloudCoherence > CloudCoherenceConstPtr; + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + KLDAdaptiveParticleFilterOMPTracker (unsigned int nr_threads = 0) + : KLDAdaptiveParticleFilterTracker () + , threads_ (nr_threads) + { + tracker_name_ = "KLDAdaptiveParticleFilterOMPTracker"; + } + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + + protected: + /** \brief The number of threads the scheduler should use. */ + unsigned int threads_; + + /** \brief weighting phase of particle filter method. + calculate the likelihood of all of the particles and set the weights. + */ + virtual void weight (); + + }; + } +} + +//#include +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/tracking/nearest_pair_point_cloud_coherence.h b/pcl-1.7/pcl/tracking/nearest_pair_point_cloud_coherence.h new file mode 100644 index 0000000..d2070f0 --- /dev/null +++ b/pcl-1.7/pcl/tracking/nearest_pair_point_cloud_coherence.h @@ -0,0 +1,100 @@ +#ifndef PCL_TRACKING_NEAREST_PAIR_POINT_CLOUD_COHERENCE_H_ +#define PCL_TRACKING_NEAREST_PAIR_POINT_CLOUD_COHERENCE_H_ + +#include + +#include + +namespace pcl +{ + namespace tracking + { + /** \brief @b NearestPairPointCloudCoherence computes coherence between two pointclouds using the + nearest point pairs. + * \author Ryohei Ueda + * \ingroup tracking + */ + template + class NearestPairPointCloudCoherence: public PointCloudCoherence + { + public: + using PointCloudCoherence::getClassName; + using PointCloudCoherence::coherence_name_; + using PointCloudCoherence::target_input_; + + typedef typename PointCloudCoherence::PointCoherencePtr PointCoherencePtr; + typedef typename PointCloudCoherence::PointCloudInConstPtr PointCloudInConstPtr; + typedef PointCloudCoherence BaseClass; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + typedef boost::shared_ptr > SearchPtr; + typedef boost::shared_ptr > SearchConstPtr; + + /** \brief empty constructor */ + NearestPairPointCloudCoherence () + : new_target_ (false) + , search_ () + , maximum_distance_ (std::numeric_limits::max ()) + { + coherence_name_ = "NearestPairPointCloudCoherence"; + } + + /** \brief Provide a pointer to a dataset to add additional information + * to estimate the features for every point in the input dataset. This + * is optional, if this is not set, it will only use the data in the + * input cloud to estimate the features. This is useful when you only + * need to compute the features for a downsampled cloud. + * \param search a pointer to a PointCloud message + */ + inline void + setSearchMethod (const SearchPtr &search) { search_ = search; } + + /** \brief Get a pointer to the point cloud dataset. */ + inline SearchPtr + getSearchMethod () { return (search_); } + + /** \brief add a PointCoherence to the PointCloudCoherence. + * \param[in] cloud coherence a pointer to PointCoherence. + */ + virtual inline void + setTargetCloud (const PointCloudInConstPtr &cloud) + { + new_target_ = true; + PointCloudCoherence::setTargetCloud (cloud); + } + + /** \brief set maximum distance to be taken into account. + * \param[in] val maximum distance. + */ + inline void setMaximumDistance (double val) { maximum_distance_ = val; } + + protected: + using PointCloudCoherence::point_coherences_; + + /** \brief This method should get called before starting the actual computation. */ + virtual bool initCompute (); + + /** \brief A flag which is true if target_input_ is updated */ + bool new_target_; + + /** \brief A pointer to the spatial search object. */ + SearchPtr search_; + + /** \brief max of distance for points to be taken into account*/ + double maximum_distance_; + + /** \brief compute the nearest pairs and compute coherence using point_coherences_ */ + virtual void + computeCoherence (const PointCloudInConstPtr &cloud, const IndicesConstPtr &indices, float &w_j); + + }; + } +} + +// #include +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/tracking/normal_coherence.h b/pcl-1.7/pcl/tracking/normal_coherence.h new file mode 100644 index 0000000..f693347 --- /dev/null +++ b/pcl-1.7/pcl/tracking/normal_coherence.h @@ -0,0 +1,53 @@ +#ifndef PCL_TRACKING_NORMAL_COHERENCE_H_ +#define PCL_TRACKING_NORMAL_COHERENCE_H_ + +#include +namespace pcl +{ + namespace tracking + { + /** \brief @b NormalCoherence computes coherence between two points from the angle + between their normals. the coherence is calculated by 1 / (1 + weight * theta^2 ). + * \author Ryohei Ueda + * \ingroup tracking + */ + template + class NormalCoherence: public PointCoherence + { + public: + + /** \brief initialize the weight to 1.0. */ + NormalCoherence () + : PointCoherence () + , weight_ (1.0) + {} + + /** \brief set the weight of coherence + * \param weight the weight of coherence + */ + inline void setWeight (double weight) { weight_ = weight; } + + /** \brief get the weight of coherence */ + inline double getWeight () { return weight_; } + + protected: + + /** \brief return the normal coherence between the two points. + * \param source instance of source point. + * \param target instance of target point. + */ + double computeCoherence (PointInT &source, PointInT &target); + + /** \brief the weight of coherence */ + double weight_; + + }; + } +} + +// #include +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/tracking/particle_filter.h b/pcl-1.7/pcl/tracking/particle_filter.h new file mode 100644 index 0000000..7221caa --- /dev/null +++ b/pcl-1.7/pcl/tracking/particle_filter.h @@ -0,0 +1,512 @@ +#ifndef PCL_TRACKING_PARTICLE_FILTER_H_ +#define PCL_TRACKING_PARTICLE_FILTER_H_ + +#include +#include +#include +#include +#include + +#include + +namespace pcl +{ + + namespace tracking + { + /** \brief @b ParticleFilterTracker tracks the PointCloud which is given by + setReferenceCloud within the measured PointCloud using particle filter method. + * \author Ryohei Ueda + * \ingroup tracking + */ + template + class ParticleFilterTracker: public Tracker + { + protected: + using Tracker::deinitCompute; + + public: + using Tracker::tracker_name_; + using Tracker::search_; + using Tracker::input_; + using Tracker::indices_; + using Tracker::getClassName; + + typedef Tracker BaseClass; + + typedef typename Tracker::PointCloudIn PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + typedef typename Tracker::PointCloudState PointCloudState; + typedef typename PointCloudState::Ptr PointCloudStatePtr; + typedef typename PointCloudState::ConstPtr PointCloudStateConstPtr; + + typedef PointCoherence Coherence; + typedef boost::shared_ptr< Coherence > CoherencePtr; + typedef boost::shared_ptr< const Coherence > CoherenceConstPtr; + + typedef PointCloudCoherence CloudCoherence; + typedef boost::shared_ptr< CloudCoherence > CloudCoherencePtr; + typedef boost::shared_ptr< const CloudCoherence > CloudCoherenceConstPtr; + + /** \brief Empty constructor. */ + ParticleFilterTracker () + : iteration_num_ (1) + , particle_num_ () + , min_indices_ (1) + , ref_ () + , particles_ () + , coherence_ () + , step_noise_covariance_ () + , initial_noise_covariance_ () + , initial_noise_mean_ () + , resample_likelihood_thr_ (0.0) + , occlusion_angle_thr_ (M_PI / 2.0) + , alpha_ (15.0) + , representative_state_ () + , trans_ () + , use_normal_ (false) + , motion_ () + , motion_ratio_ (0.25) + , pass_x_ () + , pass_y_ () + , pass_z_ () + , transed_reference_vector_ () + , change_detector_ () + , changed_ (false) + , change_counter_ (0) + , change_detector_filter_ (10) + , change_detector_interval_ (10) + , change_detector_resolution_ (0.01) + , use_change_detector_ (false) + { + tracker_name_ = "ParticleFilterTracker"; + pass_x_.setFilterFieldName ("x"); + pass_y_.setFilterFieldName ("y"); + pass_z_.setFilterFieldName ("z"); + pass_x_.setKeepOrganized (false); + pass_y_.setKeepOrganized (false); + pass_z_.setKeepOrganized (false); + } + + /** \brief Set the number of iteration. + * \param[in] iteration_num the number of iteration. + */ + inline void + setIterationNum (const int iteration_num) { iteration_num_ = iteration_num; } + + /** \brief Get the number of iteration. */ + inline int + getIterationNum () const { return iteration_num_; } + + /** \brief Set the number of the particles. + * \param[in] particle_num the number of the particles. + */ + inline void + setParticleNum (const int particle_num) { particle_num_ = particle_num; } + + /** \brief Get the number of the particles. */ + inline int + getParticleNum () const { return particle_num_; } + + /** \brief Set a pointer to a reference dataset to be tracked. + * \param[in] ref a pointer to a PointCloud message + */ + inline void + setReferenceCloud (const PointCloudInConstPtr &ref) { ref_ = ref; } + + /** \brief Get a pointer to a reference dataset to be tracked. */ + inline PointCloudInConstPtr const + getReferenceCloud () { return ref_; } + + /** \brief Set the PointCloudCoherence as likelihood. + * \param[in] coherence a pointer to PointCloudCoherence. + */ + inline void + setCloudCoherence (const CloudCoherencePtr &coherence) { coherence_ = coherence; } + + /** \brief Get the PointCloudCoherence to compute likelihood. */ + inline CloudCoherencePtr + getCloudCoherence () const { return coherence_; } + + + /** \brief Set the covariance of step noise. + * \param[in] step_noise_covariance the diagonal elements of covariance matrix of step noise. + */ + inline void + setStepNoiseCovariance (const std::vector &step_noise_covariance) + { + step_noise_covariance_ = step_noise_covariance; + } + + /** \brief Set the covariance of the initial noise. It will be used when initializing the particles. + * \param[in] initial_noise_covariance the diagonal elements of covariance matrix of initial noise. + */ + inline void + setInitialNoiseCovariance (const std::vector &initial_noise_covariance) + { + initial_noise_covariance_ = initial_noise_covariance; + } + + /** \brief Set the mean of the initial noise. It will be used when initializing the particles. + * \param[in] initial_noise_mean the mean values of initial noise. + */ + inline void + setInitialNoiseMean (const std::vector &initial_noise_mean) + { + initial_noise_mean_ = initial_noise_mean; + } + + /** \brief Set the threshold to re-initialize the particles. + * \param[in] resample_likelihood_thr threshold to re-initialize. + */ + inline void + setResampleLikelihoodThr (const double resample_likelihood_thr) + { + resample_likelihood_thr_ = resample_likelihood_thr; + } + + /** \brief Set the threshold of angle to be considered occlusion (default: pi/2). + * ParticleFilterTracker does not take the occluded points into account according to the angle + * between the normal and the position. + * \param[in] occlusion_angle_thr threshold of angle to be considered occlusion. + */ + inline void + setOcclusionAngleThe (const double occlusion_angle_thr) + { + occlusion_angle_thr_ = occlusion_angle_thr; + } + + /** \brief Set the minimum number of indices (default: 1). + * ParticleFilterTracker does not take into account the hypothesis + * whose the number of points is smaller than the minimum indices. + * \param[in] min_indices the minimum number of indices. + */ + inline void + setMinIndices (const int min_indices) { min_indices_ = min_indices; } + + /** \brief Set the transformation from the world coordinates to the frame of the particles. + * \param[in] trans Affine transformation from the worldcoordinates to the frame of the particles. + */ + inline void setTrans (const Eigen::Affine3f &trans) { trans_ = trans; } + + /** \brief Get the transformation from the world coordinates to the frame of the particles. */ + inline Eigen::Affine3f getTrans () const { return trans_; } + + /** \brief Get an instance of the result of tracking. + * This function returns the particle that represents the transform between the reference point cloud at the + * beginning and the best guess about its location in the most recent frame. + */ + virtual inline StateT getResult () const { return representative_state_; } + + /** \brief Convert a state to affine transformation from the world coordinates frame. + * \param[in] particle an instance of StateT. + */ + Eigen::Affine3f toEigenMatrix (const StateT& particle) + { + return particle.toEigenMatrix (); + } + + /** \brief Get a pointer to a pointcloud of the particles. */ + inline PointCloudStatePtr getParticles () const { return particles_; } + + /** \brief Normalize the weight of a particle using \f$ exp(1- alpha ( w - w_{min}) / (w_max - w_min)) \f$ + * \note This method is described in [P.Azad et. al, ICRA11]. + * \param[in] w the weight to be normalized + * \param[in] w_min the minimum weight of the particles + * \param[in] w_max the maximum weight of the particles + */ + inline double normalizeParticleWeight (double w, double w_min, double w_max) + { + return exp (1.0 - alpha_ * (w - w_min) / (w_max - w_min)); + } + + /** \brief Set the value of alpha. + * \param[in] alpha the value of alpha + */ + inline void setAlpha (double alpha) { alpha_ = alpha; } + + /** \brief Get the value of alpha. */ + inline double getAlpha () { return alpha_; } + + /** \brief Set the value of use_normal_. + * \param[in] use_normal the value of use_normal_. + */ + inline void setUseNormal (bool use_normal) { use_normal_ = use_normal; } + + /** \brief Get the value of use_normal_. */ + inline bool getUseNormal () { return use_normal_; } + + /** \brief Set the value of use_change_detector_. + * \param[in] use_change_detector the value of use_change_detector_. + */ + inline void setUseChangeDetector (bool use_change_detector) { use_change_detector_ = use_change_detector; } + + /** \brief Get the value of use_change_detector_. */ + inline bool getUseChangeDetector () { return use_change_detector_; } + + /** \brief Set the motion ratio + * \param[in] motion_ratio the ratio of hypothesis to use motion model. + */ + inline void setMotionRatio (double motion_ratio) { motion_ratio_ = motion_ratio; } + + /** \brief Get the motion ratio. */ + inline double getMotionRatio () { return motion_ratio_;} + + /** \brief Set the number of interval frames to run change detection. + * \param[in] change_detector_interval the number of interval frames. + */ + inline void setIntervalOfChangeDetection (unsigned int change_detector_interval) + { + change_detector_interval_ = change_detector_interval; + } + + /** \brief Get the number of interval frames to run change detection. */ + inline unsigned int getIntervalOfChangeDetection () + { + return change_detector_interval_; + } + + /** \brief Set the minimum amount of points required within leaf node to become serialized in change detection + * \param[in] change_detector_filter the minimum amount of points required within leaf node + */ + inline void setMinPointsOfChangeDetection (unsigned int change_detector_filter) + { + change_detector_filter_ = change_detector_filter; + } + + /** \brief Set the resolution of change detection. + * \param[in] resolution resolution of change detection octree + */ + inline void setResolutionOfChangeDetection (double resolution) { change_detector_resolution_ = resolution; } + + /** \brief Get the resolution of change detection. */ + inline double getResolutionOfChangeDetection () { return change_detector_resolution_; } + + /** \brief Get the minimum amount of points required within leaf node to become serialized in change detection. */ + inline unsigned int getMinPointsOfChangeDetection () + { + return change_detector_filter_; + } + + /** \brief Get the adjustment ratio. */ + inline double + getFitRatio() const { return fit_ratio_; } + + /** \brief Reset the particles to restart tracking*/ + virtual inline void resetTracking () + { + if (particles_) + particles_->points.clear (); + } + + protected: + + /** \brief Compute the parameters for the bounding box of hypothesis pointclouds. + * \param[out] x_min the minimum value of x axis. + * \param[out] x_max the maximum value of x axis. + * \param[out] y_min the minimum value of y axis. + * \param[out] y_max the maximum value of y axis. + * \param[out] z_min the minimum value of z axis. + * \param[out] z_max the maximum value of z axis. + */ + void calcBoundingBox (double &x_min, double &x_max, + double &y_min, double &y_max, + double &z_min, double &z_max); + + /** \brief Crop the pointcloud by the bounding box calculated from hypothesis and the reference pointcloud. + * \param[in] cloud a pointer to pointcloud to be cropped. + * \param[out] output a pointer to be assigned the cropped pointcloud. + */ + void cropInputPointCloud (const PointCloudInConstPtr &cloud, PointCloudIn &output); + + + + /** \brief Compute a reference pointcloud transformed to the pose that hypothesis represents. + * \param[in] hypothesis a particle which represents a hypothesis. + * \param[in] indices the indices which should be taken into account. + * \param[out] cloud the resultant point cloud model dataset which is transformed to hypothesis. + **/ + void computeTransformedPointCloud (const StateT& hypothesis, + std::vector& indices, + PointCloudIn &cloud); + + /** \brief Compute a reference pointcloud transformed to the pose that hypothesis represents and calculate + * indices taking occlusion into account. + * \param[in] hypothesis a particle which represents a hypothesis. + * \param[in] indices the indices which should be taken into account. + * \param[out] cloud the resultant point cloud model dataset which is transformed to hypothesis. + **/ + void computeTransformedPointCloudWithNormal (const StateT& hypothesis, + std::vector& indices, + PointCloudIn &cloud); + + /** \brief Compute a reference pointcloud transformed to the pose that hypothesis represents and calculate + * indices without taking occlusion into account. + * \param[in] hypothesis a particle which represents a hypothesis. + * \param[out] cloud the resultant point cloud model dataset which is transformed to hypothesis. + **/ + void computeTransformedPointCloudWithoutNormal (const StateT& hypothesis, + PointCloudIn &cloud); + + + /** \brief This method should get called before starting the actual computation. */ + virtual bool initCompute (); + + /** \brief Weighting phase of particle filter method. Calculate the likelihood of all of the particles and set the weights. */ + virtual void weight (); + + /** \brief Resampling phase of particle filter method. Sampling the particles according to the weights calculated + * in weight method. In particular, "sample with replacement" is archieved by walker's alias method. + */ + virtual void resample (); + + /** \brief Calculate the weighted mean of the particles and set it as the result. */ + virtual void update (); + + /** \brief Normalize the weights of all the particels. */ + virtual void normalizeWeight (); + + /** \brief Initialize the particles. initial_noise_covariance_ and initial_noise_mean_ are used for Gaussian sampling. */ + void initParticles (bool reset); + + /** \brief Track the pointcloud using particle filter method. */ + virtual void computeTracking (); + + /** \brief Implementation of "sample with replacement" using Walker's alias method. + about Walker's alias method, you can check the paper below: + article{355749}, + author = {Walker, Alastair J.}, + title = {An Efficient Method for Generating Discrete + Random Variables with General Distributions}, + journal = {ACM Trans. Math. Softw.}, + volume = {3}, + number = {3}, + year = {1977}, + issn = {0098-3500}, + pages = {253--256}, + doi = {http://doi.acm.org/10.1145/355744.355749}, + publisher = {ACM}, + address = {New York, NY, USA}, + } + \param a an alias table, which generated by genAliasTable. + \param q a table of weight, which generated by genAliasTable. + */ + int sampleWithReplacement (const std::vector& a, const std::vector& q); + + /** \brief Generate the tables for walker's alias method. */ + void genAliasTable (std::vector &a, std::vector &q, const PointCloudStateConstPtr &particles); + + /** \brief Resampling the particle with replacement. */ + void + resampleWithReplacement (); + + /** \brief Resampling the particle in deterministic way. */ + void + resampleDeterministic (); + + /** \brief Run change detection and return true if there is a change. + * \param[in] input a pointer to the input pointcloud. + */ + bool + testChangeDetection (const PointCloudInConstPtr &input); + + /** \brief The number of iteration of particlefilter. */ + int iteration_num_; + + /** \brief The number of the particles. */ + int particle_num_; + + /** \brief The minimum number of points which the hypothesis should have. */ + int min_indices_; + + /** \brief Adjustment of the particle filter. */ + double fit_ratio_; + + /** \brief A pointer to reference point cloud. */ + PointCloudInConstPtr ref_; + + /** \brief A pointer to the particles */ + PointCloudStatePtr particles_; + + /** \brief A pointer to PointCloudCoherence. */ + CloudCoherencePtr coherence_; + + /** \brief The diagonal elements of covariance matrix of the step noise. the covariance matrix is used + * at every resample method. + */ + std::vector step_noise_covariance_; + + /** \brief The diagonal elements of covariance matrix of the initial noise. the covariance matrix is used + * when initialize the particles. + */ + std::vector initial_noise_covariance_; + + /** \brief The mean values of initial noise. */ + std::vector initial_noise_mean_; + + /** \brief The threshold for the particles to be re-initialized. */ + double resample_likelihood_thr_; + + /** \brief The threshold for the points to be considered as occluded. */ + double occlusion_angle_thr_; + + /** \brief The weight to be used in normalization of the weights of the particles. */ + double alpha_; + + /** \brief The result of tracking. */ + StateT representative_state_; + + /** \brief An affine transformation from the world coordinates frame to the origin of the particles. */ + Eigen::Affine3f trans_; + + /** \brief A flag to use normal or not. defaults to false. */ + bool use_normal_; + + /** \brief Difference between the result in t and t-1. */ + StateT motion_; + + /** \brief Ratio of hypothesis to use motion model. */ + double motion_ratio_; + + /** \brief Pass through filter to crop the pointclouds within the hypothesis bounding box. */ + pcl::PassThrough pass_x_; + /** \brief Pass through filter to crop the pointclouds within the hypothesis bounding box. */ + pcl::PassThrough pass_y_; + /** \brief Pass through filter to crop the pointclouds within the hypothesis bounding box. */ + pcl::PassThrough pass_z_; + + /** \brief A list of the pointers to pointclouds. */ + std::vector transed_reference_vector_; + + /** \brief Change detector used as a trigger to track. */ + boost::shared_ptr > change_detector_; + + /** \brief A flag to be true when change of pointclouds is detected. */ + bool changed_; + + /** \brief A counter to skip change detection. */ + unsigned int change_counter_; + + /** \brief Minimum points in a leaf when calling change detector. defaults to 10. */ + unsigned int change_detector_filter_; + + /** \brief The number of interval frame to run change detection. defaults to 10. */ + unsigned int change_detector_interval_; + + /** \brief Resolution of change detector. defaults to 0.01. */ + double change_detector_resolution_; + + /** \brief The flag which will be true if using change detection. */ + bool use_change_detector_; + }; + } +} + +// #include +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif //PCL_TRACKING_PARTICLE_FILTER_H_ diff --git a/pcl-1.7/pcl/tracking/particle_filter_omp.h b/pcl-1.7/pcl/tracking/particle_filter_omp.h new file mode 100644 index 0000000..208815e --- /dev/null +++ b/pcl-1.7/pcl/tracking/particle_filter_omp.h @@ -0,0 +1,96 @@ +#ifndef PCL_TRACKING_PARTICLE_FILTER_OMP_H_ +#define PCL_TRACKING_PARTICLE_FILTER_OMP_H_ + +#include +#include +#include + +namespace pcl +{ + namespace tracking + { + /** \brief @b ParticleFilterOMPTracker tracks the PointCloud which is given by + setReferenceCloud within the measured PointCloud using particle filter method + in parallel, using the OpenMP standard. + * \author Ryohei Ueda + * \ingroup tracking + */ + template + class ParticleFilterOMPTracker: public ParticleFilterTracker + { + public: + using Tracker::tracker_name_; + using Tracker::search_; + using Tracker::input_; + using Tracker::indices_; + using Tracker::getClassName; + using ParticleFilterTracker::particles_; + using ParticleFilterTracker::change_detector_; + using ParticleFilterTracker::change_counter_; + using ParticleFilterTracker::change_detector_interval_; + using ParticleFilterTracker::use_change_detector_; + using ParticleFilterTracker::alpha_; + using ParticleFilterTracker::changed_; + using ParticleFilterTracker::coherence_; + using ParticleFilterTracker::use_normal_; + using ParticleFilterTracker::particle_num_; + using ParticleFilterTracker::change_detector_filter_; + using ParticleFilterTracker::transed_reference_vector_; + //using ParticleFilterTracker::calcLikelihood; + using ParticleFilterTracker::normalizeWeight; + using ParticleFilterTracker::normalizeParticleWeight; + using ParticleFilterTracker::calcBoundingBox; + + typedef Tracker BaseClass; + + typedef typename Tracker::PointCloudIn PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + typedef typename Tracker::PointCloudState PointCloudState; + typedef typename PointCloudState::Ptr PointCloudStatePtr; + typedef typename PointCloudState::ConstPtr PointCloudStateConstPtr; + + typedef PointCoherence Coherence; + typedef boost::shared_ptr< Coherence > CoherencePtr; + typedef boost::shared_ptr< const Coherence > CoherenceConstPtr; + + typedef PointCloudCoherence CloudCoherence; + typedef boost::shared_ptr< CloudCoherence > CloudCoherencePtr; + typedef boost::shared_ptr< const CloudCoherence > CloudCoherenceConstPtr; + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + ParticleFilterOMPTracker (unsigned int nr_threads = 0) + : ParticleFilterTracker () + , threads_ (nr_threads) + { + tracker_name_ = "ParticleFilterOMPTracker"; + } + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + + protected: + /** \brief The number of threads the scheduler should use. */ + unsigned int threads_; + + /** \brief weighting phase of particle filter method. + calculate the likelihood of all of the particles and set the weights. + */ + virtual void weight (); + + }; + } +} + +//#include +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/tracking/pyramidal_klt.h b/pcl-1.7/pcl/tracking/pyramidal_klt.h new file mode 100644 index 0000000..b15c60f --- /dev/null +++ b/pcl-1.7/pcl/tracking/pyramidal_klt.h @@ -0,0 +1,377 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2014-, Open Perception. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_TRACKING_PYRAMIDAL_KLT_H +#define PCL_TRACKING_PYRAMIDAL_KLT_H + +#include +#include +#include +#include + +namespace pcl +{ + namespace tracking + { + /** Pyramidal Kanade Lucas Tomasi tracker. + * This is an implemntation of the Pyramidal Kanade Lucas Tomasi tracker that operates on + * organized 3D keypoints with color/intensity information (this is the default behaviour but you + * can alterate it by providing another operator as second template argument). It is an affine + * tracker that iteratively computes the optical flow to find the best guess for a point p at t + * given its location at t-1. + * User is advised to respect the Tomasi condition: the response computed is the maximum eigenvalue + * of the second moment matrix but no restrictin are applied to points to track so you can use a + * detector of your choice to indicate points to track. + * + * \author Nizar Sallem + */ + template > + class PyramidalKLTTracker : public Tracker + { + public: + typedef pcl::tracking::Tracker TrackerBase; + typedef typename TrackerBase::PointCloudIn PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + typedef pcl::PointCloud FloatImage; + typedef FloatImage::Ptr FloatImagePtr; + typedef FloatImage::ConstPtr FloatImageConstPtr; + + using TrackerBase::tracker_name_; + using TrackerBase::input_; + using TrackerBase::indices_; + + /// Constructor + PyramidalKLTTracker (int nb_levels = 5, int tracking_window_width = 7, int tracking_window_height = 7) + : ref_ () + , nb_levels_ (nb_levels) + , track_width_ (tracking_window_width) + , track_height_ (tracking_window_height) + , threads_ (0) + , initialized_ (false) + { + tracker_name_ = "PyramidalKLTTracker"; + accuracy_ = 0.1; + epsilon_ = 1e-3; + max_iterations_ = 10; + keypoints_nbr_ = 100; + min_eigenvalue_threshold_ = 1e-4; + kernel_ << 1.f/16 ,1.f/4 ,3.f/8 ,1.f/4 ,1.f/16; + kernel_size_2_ = kernel_.size () / 2; + kernel_last_ = kernel_.size () -1; + } + + /// Destructor + virtual ~PyramidalKLTTracker () {} + + /** \brief Set the number of pyramid levels + * \param levels desired number of pyramid levels + */ + inline void + setNumberOfPyramidLevels (int levels) { nb_levels_ = levels; } + + /// \brief \return the number of pyramid levels + inline int + getNumberOfPyramidLevels () const { return (nb_levels_); } + + /** Set accuracy + * \param[in] accuracy desired accuracy. + */ + inline void + setAccuracy (float accuracy) { accuracy_ = accuracy; } + + /// \return the accuracy + inline float + getAccuracy () const { return (accuracy_); } + + /** Set epsilon + * \param[in] epsilon desired epsilon. + */ + inline void + setEpsilon (float epsilon) { epsilon_ = epsilon; } + + /// \return the epsilon + inline float + getEpsilon () const { return (epsilon_); } + + /** \brief Set the maximum number of points to track. Only the first keypoints_nbr_ + * are used as points to track after sorting detected keypoints according to their + * response measure. + * \param[in] number the desired number of points to detect. + */ + inline void + setNumberOfKeypoints (std::size_t number) { keypoints_nbr_ = number; } + + /// \return the maximum number of keypoints to keep + inline std::size_t + getNumberOfKeypoints () { return (keypoints_nbr_); } + + /** \brief set the tracking window size + * \param[in] width the tracking window width + * \param[in] height the tracking window height + */ + inline void + setTrackingWindowSize (int width, int height); + + /// \brief Set tracking window width + inline void + setTrackingWindowWidth (int width) {track_width_ = width; }; + + /// \brief \return the tracking window size + inline int + getTrackingWindowWidth () { return (track_width_); } + + /// \brief Set tracking window height + inline void + setTrackingWindowHeight (int height) {track_height_ = height; }; + + /// \brief \return the tracking window size + inline int + getTrackingWindowHeight () { return (track_height_); } + + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to + * automatic). + */ + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + + /** \brief Get a pointer of the cloud at t-1. */ + inline PointCloudInConstPtr + getReferenceCloud () const { return (ref_); } + + /** \brief Set the maximum number of iterations in the Lucas Kanade loop. + * \param[in] max the desired maximum number of iterations + */ + inline void + setMaxIterationsNumber (unsigned int max) { max_iterations_ = max; } + + /// \brief \return the maximum iterations number + inline unsigned int + getMaxIterationsNumber () const { return (max_iterations_); } + + /** \brief Provide a pointer to points to track. + * \param points the const boost shared pointer to a PointIndices message + */ + inline void + setPointsToTrack (const pcl::PointIndicesConstPtr& points); + + /** \brief Provide a pointer to points to track. + * \param points the const boost shared pointer to a PointIndices message + */ + inline void + setPointsToTrack (const pcl::PointCloud::ConstPtr& points); + + /// \brief \return a pointer to the points succesfully tracked. + inline pcl::PointCloud::ConstPtr + getTrackedPoints () const { return (keypoints_); }; + + /** \brief \return the status of points to track. + * Status == 0 --> points succesfully tracked; + * Status < 0 --> point is lost; + * Status == -1 --> point is out of bond; + * Status == -2 --> optical flow can not be computed for this point. + */ + inline pcl::PointIndicesConstPtr + getPointsToTrackStatus () const { return (keypoints_status_); } + + /** \brief Return the computed transfromation from tracked points. */ + Eigen::Affine3f + getResult () const { return (motion_); } + + /// \brief \return initialization state + bool + getInitialized () const { return (initialized_); } + + protected: + virtual bool + initCompute (); + + /** \brief compute Scharr derivatives of a source cloud. + * \param[in] src the image for which gradients are to be computed + * \param[out] grad_x image gradient along X direction + * \param[out] grad_y image gradient along Y direction + */ + void + derivatives (const FloatImage& src, FloatImage& grad_x, FloatImage& grad_y) const; + + /** \brief downsample input + * \param[in] input the image to downsample + * \param[out] output the downsampled image + */ + void + downsample (const FloatImageConstPtr& input, FloatImageConstPtr& output) const; + + /** \brief downsample input and compute output gradients. + * \param[in] input the image to downsample + * \param[out] output the downsampled image + * \param[out] output_grad_x downsampled image gradient along X direction + * \param[out] output_grad_y downsampled image gradient along Y direction + */ + void + downsample (const FloatImageConstPtr& input, FloatImageConstPtr& output, + FloatImageConstPtr& output_grad_x, FloatImageConstPtr& output_grad_y) const; + + /** \brief Separately convolve image with decomposable convolution kernel. + * \param[in] input input the image to convolve + * \param[out] output output the convolved image + */ + void + convolve (const FloatImageConstPtr& input, FloatImage& output) const; + + /** \brief Convolve image columns. + * \param[in] input input the image to convolve + * \param[out] output output the convolved image + */ + void + convolveCols (const FloatImageConstPtr& input, FloatImage& output) const; + + /** \brief Convolve image rows. + * \param[in] input input the image to convolve + * \param[out] output output the convolved image + */ + void + convolveRows (const FloatImageConstPtr& input, FloatImage& output) const; + + /** \brief extract the patch from the previous image, previous image gradients surrounding + * pixel alocation while interpolating image and gradients data and compute covariation + * matrix of derivatives. + * \param[in] img original image + * \param[in] grad_x original image gradient along X direction + * \param[in] grad_y original image gradient along Y direction + * \param[in] location pixel at the center of the patch + * \param[in] weights bilinear interpolation weights at this location computed from subpixel + * location + * \param[out] win patch with interpolated intensity values + * \param[out] grad_x_win patch with interpolated gradient along X values + * \param[out] grad_y_win patch with interpolated gradient along Y values + * \param[out] covariance covariance matrix coefficents + */ + virtual void + spatialGradient (const FloatImage& img, + const FloatImage& grad_x, + const FloatImage& grad_y, + const Eigen::Array2i& location, + const Eigen::Array4f& weights, + Eigen::ArrayXXf& win, + Eigen::ArrayXXf& grad_x_win, + Eigen::ArrayXXf& grad_y_win, + Eigen::Array3f & covariance) const; + void + mismatchVector (const Eigen::ArrayXXf& prev, + const Eigen::ArrayXXf& prev_grad_x, + const Eigen::ArrayXXf& prev_grad_y, + const FloatImage& next, + const Eigen::Array2i& location, + const Eigen::Array4f& weights, + Eigen::Array2f &b) const; + + /** \brief Compute the pyramidal representation of an image. + * \param[in] input the input cloud + * \param[out] pyramid computed pyramid levels along with their respective gradients + * \param[in] border_type + */ + virtual void + computePyramids (const PointCloudInConstPtr& input, + std::vector& pyramid, + pcl::InterpolationType border_type) const; + + virtual void + track (const PointCloudInConstPtr& previous_input, + const PointCloudInConstPtr& current_input, + const std::vector& previous_pyramid, + const std::vector& current_pyramid, + const pcl::PointCloud::ConstPtr& previous_keypoints, + pcl::PointCloud::Ptr& current_keypoints, + std::vector& status, + Eigen::Affine3f& motion) const; + + virtual void + computeTracking (); + + /// \brief input pyranid at t-1 + std::vector ref_pyramid_; + /// \brief point cloud at t-1 + PointCloudInConstPtr ref_; + /// \brief number of pyramid levels + int nb_levels_; + /// \brief detected keypoints 2D coordinates + pcl::PointCloud::ConstPtr keypoints_; + /// \brief status of keypoints of t-1 at t + pcl::PointIndicesPtr keypoints_status_; + /// \brief number of points to detect + std::size_t keypoints_nbr_; + /// \brief tracking width + int track_width_; + /// \brief half of tracking window width + int track_width_2_; + /// \brief tracking height + int track_height_; + /// \brief half of tracking window height + int track_height_2_; + /// \brief maximum number of iterations + unsigned int max_iterations_; + /// \brief accuracy criterion to stop iterating + float accuracy_; + float min_eigenvalue_threshold_; + /// \brief epsilon for subpixel computation + float epsilon_; + float max_residue_; + /// \brief number of hardware threads + unsigned int threads_; + /// \brief intensity accessor + IntensityT intensity_; + /// \brief is the tracker initialized ? + bool initialized_; + /// \brief compute transformation from successfully tracked points + pcl::TransformationFromCorrespondences transformation_computer_; + /// \brief computed transformation between tracked points + Eigen::Affine3f motion_; + /// \brief smoothing kernel + Eigen::Array kernel_; + /// \brief smoothing kernel half size + int kernel_size_2_; + /// \brief index of last element in kernel + int kernel_last_; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } +} + +#include +#endif diff --git a/pcl-1.7/pcl/tracking/tracker.h b/pcl-1.7/pcl/tracking/tracker.h new file mode 100644 index 0000000..10ee245 --- /dev/null +++ b/pcl-1.7/pcl/tracking/tracker.h @@ -0,0 +1,136 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: point_cloud.h 4696 2012-02-23 06:12:55Z rusu $ + * + */ + +#ifndef PCL_TRACKING_TRACKER_H_ +#define PCL_TRACKING_TRACKER_H_ + +#include +#include +#include + +namespace pcl +{ + namespace tracking + { + /** \brief @b Tracker represents the base tracker class. + * \author Ryohei Ueda + * \ingroup tracking + */ + template + class Tracker: public PCLBase + { + protected: + using PCLBase::deinitCompute; + + public: + using PCLBase::indices_; + using PCLBase::input_; + + typedef PCLBase BaseClass; + typedef boost::shared_ptr< Tracker > Ptr; + typedef boost::shared_ptr< const Tracker > ConstPtr; + + typedef boost::shared_ptr > SearchPtr; + typedef boost::shared_ptr > SearchConstPtr; + + typedef pcl::PointCloud PointCloudIn; + typedef typename PointCloudIn::Ptr PointCloudInPtr; + typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; + + typedef pcl::PointCloud PointCloudState; + typedef typename PointCloudState::Ptr PointCloudStatePtr; + typedef typename PointCloudState::ConstPtr PointCloudStateConstPtr; + + public: + /** \brief Empty constructor. */ + Tracker (): tracker_name_ (), search_ () {} + + /** \brief Base method for tracking for all points given in + * using the indices in setIndices () + */ + void + compute (); + + protected: + /** \brief The tracker name. */ + std::string tracker_name_; + + /** \brief A pointer to the spatial search object. */ + SearchPtr search_; + + /** \brief Get a string representation of the name of this class. */ + inline const std::string& + getClassName () const { return (tracker_name_); } + + /** \brief This method should get called before starting the actual computation. */ + virtual bool + initCompute (); + + /** \brief Provide a pointer to a dataset to add additional information + * to estimate the features for every point in the input dataset. This + * is optional, if this is not set, it will only use the data in the + * input cloud to estimate the features. This is useful when you only + * need to compute the features for a downsampled cloud. + * \param search a pointer to a PointCloud message + */ + inline void + setSearchMethod (const SearchPtr &search) { search_ = search; } + + /** \brief Get a pointer to the point cloud dataset. */ + inline SearchPtr + getSearchMethod () { return (search_); } + + /** \brief Get an instance of the result of tracking. */ + virtual StateT + getResult () const = 0; + + private: + /** \brief Abstract tracking method. */ + virtual void + computeTracking () = 0; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } +} + +#include + +#endif diff --git a/pcl-1.7/pcl/tracking/tracking.h b/pcl-1.7/pcl/tracking/tracking.h new file mode 100644 index 0000000..08f0aaf --- /dev/null +++ b/pcl-1.7/pcl/tracking/tracking.h @@ -0,0 +1,135 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: point_cloud.h 4696 2012-02-23 06:12:55Z rusu $ + * + */ + +#ifndef PCL_TRACKING_TRACKING_H_ +#define PCL_TRACKING_TRACKING_H_ + +#include + +#ifdef BUILD_Maintainer +# if defined __GNUC__ +# pragma GCC system_header +# elif defined _MSC_VER +# pragma warning(push, 1) +# endif +#endif + +namespace pcl +{ + namespace tracking + { + /* state definition */ + struct ParticleXYZRPY; + struct ParticleXYR; + + /* \brief return the value of normal distribution */ + PCL_EXPORTS double + sampleNormal (double mean, double sigma); + } +} + +#include + +// ============================== +// =====POINT_CLOUD_REGISTER===== +// ============================== +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::tracking::_ParticleXYZRPY, + (float, x, x) + (float, y, y) + (float, z, z) + (float, roll, roll) + (float, pitch, pitch) + (float, yaw, yaw) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::tracking::ParticleXYZRPY, pcl::tracking::_ParticleXYZRPY) + + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::tracking::_ParticleXYRPY, + (float, x, x) + (float, y, y) + (float, z, z) + (float, roll, roll) + (float, pitch, pitch) + (float, yaw, yaw) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::tracking::ParticleXYRPY, pcl::tracking::_ParticleXYRPY) + + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::tracking::_ParticleXYRP, + (float, x, x) + (float, y, y) + (float, z, z) + (float, roll, roll) + (float, pitch, pitch) + (float, yaw, yaw) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::tracking::ParticleXYRP, pcl::tracking::_ParticleXYRP) + + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::tracking::_ParticleXYR, + (float, x, x) + (float, y, y) + (float, z, z) + (float, roll, roll) + (float, pitch, pitch) + (float, yaw, yaw) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::tracking::ParticleXYR, pcl::tracking::_ParticleXYR) + +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::tracking::_ParticleXYZR, + (float, x, x) + (float, y, y) + (float, z, z) + (float, roll, roll) + (float, pitch, pitch) + (float, yaw, yaw) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::tracking::ParticleXYZR, pcl::tracking::_ParticleXYZR) + +#ifdef BUILD_Maintainer +# if defined _MSC_VER +# pragma warning(pop) +# endif +#endif + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif diff --git a/pcl-1.7/pcl/visualization/area_picking_event.h b/pcl-1.7/pcl/visualization/area_picking_event.h new file mode 100644 index 0000000..dd29530 --- /dev/null +++ b/pcl-1.7/pcl/visualization/area_picking_event.h @@ -0,0 +1,77 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_VISUALIZATION_AREA_PICKING_EVENT_H_ +#define PCL_VISUALIZATION_AREA_PICKING_EVENT_H_ + +#include + +namespace pcl +{ + namespace visualization + { + /** /brief Class representing 3D area picking events. */ + class PCL_EXPORTS AreaPickingEvent + { + public: + AreaPickingEvent (int nb_points, const std::vector& indices) + : nb_points_ (nb_points) + , indices_ (indices) + {} + + /** \brief For situations where a whole are is selected, return the points indices. + * \param[out] indices indices of the points under the area selected by user. + * \return true, if the area selected by the user contains points, false otherwise + */ + inline bool + getPointsIndices (std::vector& indices) const + { + if (nb_points_ <= 0) + return (false); + indices = indices_; + return (true); + } + + private: + int nb_points_; + std::vector indices_; + }; + } //namespace visualization +} //namespace pcl + +#endif /* PCL_VISUALIZATION_AREA_PICKING_EVENT_H_ */ diff --git a/pcl-1.7/pcl/visualization/boost.h b/pcl-1.7/pcl/visualization/boost.h new file mode 100644 index 0000000..c0019a9 --- /dev/null +++ b/pcl-1.7/pcl/visualization/boost.h @@ -0,0 +1,69 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $ + * + */ + +#ifndef PCL_VISUALIZATION_BOOST_H_ +#define PCL_VISUALIZATION_BOOST_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +//https://bugreports.qt-project.org/browse/QTBUG-22829 +#ifndef Q_MOC_RUN +#include +#include +#define BOOST_PARAMETER_MAX_ARITY 7 +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#ifndef Q_MOC_RUN +#include +#endif +#include +#endif + +#endif // PCL_VISUALIZATION_BOOST_H_ diff --git a/pcl-1.7/pcl/visualization/cloud_viewer.h b/pcl-1.7/pcl/visualization/cloud_viewer.h new file mode 100644 index 0000000..b0b8d91 --- /dev/null +++ b/pcl-1.7/pcl/visualization/cloud_viewer.h @@ -0,0 +1,216 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ +#ifndef PCL_CLOUD_VIEWER_H_ +#define PCL_CLOUD_VIEWER_H_ + +#include //pcl vis + +#include + +namespace pcl +{ + namespace visualization + { + /** \brief Simple point cloud visualization class + * \author Ethan Rublee + * \ingroup visualization + */ + class PCL_EXPORTS CloudViewer : boost::noncopyable + { + public: + typedef pcl::PointCloud ColorACloud; + typedef pcl::PointCloud ColorCloud; + typedef pcl::PointCloud GrayCloud; + typedef pcl::PointCloud MonochromeCloud; + + /** \brief Construct a cloud viewer, with a window name. + * \param window_name This is displayed at the top of the window + */ + CloudViewer (const std::string& window_name); + + /** \brief Will quit the window, + * and release all resources held by the viewer. + * @return + */ + ~CloudViewer (); + + /** \brief Show a cloud, with an optional key for multiple clouds. + * \param[in] cloud RGB point cloud + * \param[in] cloudname a key for the point cloud, use the same name if you would like to overwrite the existing cloud. + */ + void + showCloud (const ColorCloud::ConstPtr &cloud, const std::string& cloudname = "cloud"); + + /** \brief Show a cloud, with an optional key for multiple clouds. + * \param[in] cloud RGB point cloud + * \param[in] cloudname a key for the point cloud, use the same name if you would like to overwrite the existing cloud. + */ + void + showCloud (const ColorACloud::ConstPtr &cloud, const std::string& cloudname = "cloud"); + + /** \brief Show a cloud, with an optional key for multiple clouds. + * \param[in] cloud XYZI point cloud + * \param[in] cloudname a key for the point cloud, use the same name if you would like to overwrite the existing cloud. + */ + void + showCloud (const GrayCloud::ConstPtr &cloud, const std::string& cloudname = "cloud"); + + + /** \brief Show a cloud, with an optional key for multiple clouds. + * \param[in] cloud XYZ point cloud + * \param[in] cloudname a key for the point cloud, use the same name if you would like to overwrite the existing cloud. + */ + void + showCloud (const MonochromeCloud::ConstPtr &cloud, const std::string& cloudname = "cloud"); + + /** \brief Check if the gui was quit, you should quit also + * \param millis_to_wait This will request to "spin" for the number of milliseconds, before exiting. + * \return true if the user signaled the gui to stop + */ + bool + wasStopped (int millis_to_wait = 1); + + /** Visualization callable function, may be used for running things on the UI thread. + */ + typedef boost::function1 VizCallable; + + /** \brief Run a callbable object on the UI thread. Will persist until removed + * @param x Use boost::ref(x) for a function object that you would like to not copy + * \param key The key for the callable -- use the same key to overwrite. + */ + void + runOnVisualizationThread (VizCallable x, const std::string& key = "callable"); + + /** \brief Run a callbable object on the UI thread. This will run once and be removed + * @param x Use boost::ref(x) for a function object that you would like to not copy + */ + void + runOnVisualizationThreadOnce (VizCallable x); + + /** \brief Remove a previously added callable object, NOP if it doesn't exist. + * @param key the key that was registered with the callable object. + */ + void + removeVisualizationCallable (const std::string& key = "callable"); + + /** \brief Register a callback function for keyboard events + * \param[in] callback the function that will be registered as a callback for a keyboard event + * \param[in] cookie user data that is passed to the callback + * \return connection object that allows to disconnect the callback function. + */ + inline boost::signals2::connection + registerKeyboardCallback (void (*callback) (const pcl::visualization::KeyboardEvent&, void*), void* cookie = NULL) + { + return (registerKeyboardCallback (boost::bind (callback, _1, cookie))); + } + + /** \brief Register a callback function for keyboard events + * \param[in] callback the member function that will be registered as a callback for a keyboard event + * \param[in] instance instance to the class that implements the callback function + * \param[in] cookie user data that is passed to the callback + * \return connection object that allows to disconnect the callback function. + */ + template inline boost::signals2::connection + registerKeyboardCallback (void (T::*callback) (const pcl::visualization::KeyboardEvent&, void*), T& instance, void* cookie = NULL) + { + return (registerKeyboardCallback (boost::bind (callback, boost::ref (instance), _1, cookie))); + } + + /** \brief Register a callback function for mouse events + * \param[in] callback the function that will be registered as a callback for a mouse event + * \param[in] cookie user data that is passed to the callback + * \return connection object that allows to disconnect the callback function. + */ + inline boost::signals2::connection + registerMouseCallback (void (*callback) (const pcl::visualization::MouseEvent&, void*), void* cookie = NULL) + { + return (registerMouseCallback (boost::bind (callback, _1, cookie))); + } + + /** \brief Register a callback function for mouse events + * \param[in] callback the member function that will be registered as a callback for a mouse event + * \param[in] instance instance to the class that implements the callback function + * \param[in] cookie user data that is passed to the callback + * \return connection object that allows to disconnect the callback function. + */ + template inline boost::signals2::connection + registerMouseCallback (void (T::*callback) (const pcl::visualization::MouseEvent&, void*), T& instance, void* cookie = NULL) + { + return (registerMouseCallback (boost::bind (callback, boost::ref (instance), _1, cookie))); + } + + + /** \brief Register a callback function for point picking events + * \param[in] callback the function that will be registered as a callback for a point picking event + * \param[in] cookie user data that is passed to the callback + * \return connection object that allows to disconnect the callback function. + */ + inline boost::signals2::connection + registerPointPickingCallback (void (*callback) (const pcl::visualization::PointPickingEvent&, void*), void* cookie = NULL) + { + return (registerPointPickingCallback (boost::bind (callback, _1, cookie))); + } + + /** \brief Register a callback function for point picking events + * \param[in] callback the member function that will be registered as a callback for a point picking event + * \param[in] instance instance to the class that implements the callback function + * \param[in] cookie user data that is passed to the callback + * \return connection object that allows to disconnect the callback function. + */ + template inline boost::signals2::connection + registerPointPickingCallback (void (T::*callback) (const pcl::visualization::PointPickingEvent&, void*), T& instance, void* cookie = NULL) + { + return (registerPointPickingCallback (boost::bind (callback, boost::ref (instance), _1, cookie))); + } + + private: + /** \brief Private implementation. */ + struct CloudViewer_impl; + std::auto_ptr impl_; + + boost::signals2::connection + registerMouseCallback (boost::function); + + boost::signals2::connection + registerKeyboardCallback (boost::function); + + boost::signals2::connection + registerPointPickingCallback (boost::function); + }; + } +} + +#endif /* CLOUD_VIEWER_H_ */ diff --git a/pcl-1.7/pcl/visualization/common/actor_map.h b/pcl-1.7/pcl/visualization/common/actor_map.h new file mode 100644 index 0000000..1a9b1a0 --- /dev/null +++ b/pcl-1.7/pcl/visualization/common/actor_map.h @@ -0,0 +1,110 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_PCL_VISUALIZER_ACTOR_MAP_H_ +#define PCL_PCL_VISUALIZER_ACTOR_MAP_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +template class vtkSmartPointer; +class vtkLODActor; +class vtkProp; + +namespace pcl +{ + namespace visualization + { + class PCL_EXPORTS CloudActor + { + typedef PointCloudGeometryHandler GeometryHandler; + typedef GeometryHandler::Ptr GeometryHandlerPtr; + typedef GeometryHandler::ConstPtr GeometryHandlerConstPtr; + + typedef PointCloudColorHandler ColorHandler; + typedef ColorHandler::Ptr ColorHandlerPtr; + typedef ColorHandler::ConstPtr ColorHandlerConstPtr; + + public: + CloudActor () : color_handler_index_ (0), geometry_handler_index_ (0) {} + + virtual ~CloudActor () + { + geometry_handlers.clear (); + color_handlers.clear (); + } + + /** \brief The actor holding the data to render. */ + vtkSmartPointer actor; + + /** \brief A vector of geometry handlers that can be used for rendering the data. */ + std::vector geometry_handlers; + + /** \brief A vector of color handlers that can be used for rendering the data. */ + std::vector color_handlers; + + /** \brief The active color handler. */ + int color_handler_index_; + + /** \brief The active geometry handler. */ + int geometry_handler_index_; + + /** \brief The viewpoint transformation matrix. */ + vtkSmartPointer viewpoint_transformation_; + + /** \brief Internal cell array. Used for optimizing updatePointCloud. */ + vtkSmartPointer cells; + }; + + typedef boost::unordered_map CloudActorMap; + typedef boost::shared_ptr CloudActorMapPtr; + + typedef boost::unordered_map > ShapeActorMap; + typedef boost::shared_ptr ShapeActorMapPtr; + + typedef boost::unordered_map > CoordinateActorMap; + typedef boost::shared_ptr CoordinateActorMapPtr; + } +} + +#endif diff --git a/pcl-1.7/pcl/visualization/common/common.h b/pcl-1.7/pcl/visualization/common/common.h new file mode 100644 index 0000000..5d19229 --- /dev/null +++ b/pcl-1.7/pcl/visualization/common/common.h @@ -0,0 +1,191 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_PCL_VISUALIZER_COMMON_H_ +#define PCL_PCL_VISUALIZER_COMMON_H_ + +#if defined __GNUC__ +#pragma GCC system_header +#endif + +#include +#include +#include + +namespace pcl +{ + struct RGB; + + namespace visualization + { + /** \brief Get (good) random values for R/G/B. + * \param[out] r the resultant R color value + * \param[out] g the resultant G color value + * \param[out] b the resultant B color value + * \param[in] min minimum value for the colors + * \param[in] max maximum value for the colors + */ + PCL_EXPORTS void + getRandomColors (double &r, double &g, double &b, double min = 0.2, double max = 2.8); + + /** \brief Get (good) random values for R/G/B. + * \param[out] rgb the resultant RGB color value + * \param[in] min minimum value for the colors + * \param[in] max maximum value for the colors + */ + PCL_EXPORTS void + getRandomColors (pcl::RGB &rgb, double min = 0.2, double max = 2.8); + + PCL_EXPORTS Eigen::Matrix4d + vtkToEigen (vtkMatrix4x4* vtk_matrix); + + PCL_EXPORTS Eigen::Vector2i + worldToView (const Eigen::Vector4d &world_pt, const Eigen::Matrix4d &view_projection_matrix, int width, int height); + + PCL_EXPORTS void + getViewFrustum (const Eigen::Matrix4d &view_projection_matrix, double planes[24]); + + enum FrustumCull + { + PCL_INSIDE_FRUSTUM, + PCL_INTERSECT_FRUSTUM, + PCL_OUTSIDE_FRUSTUM + }; + + PCL_EXPORTS int + cullFrustum (double planes[24], const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb); + + PCL_EXPORTS float + viewScreenArea (const Eigen::Vector3d &eye, const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, const Eigen::Matrix4d &view_projection_matrix, int width, int height); + + enum RenderingProperties + { + PCL_VISUALIZER_POINT_SIZE, + PCL_VISUALIZER_OPACITY, + PCL_VISUALIZER_LINE_WIDTH, + PCL_VISUALIZER_FONT_SIZE, + PCL_VISUALIZER_COLOR, + PCL_VISUALIZER_REPRESENTATION, + PCL_VISUALIZER_IMMEDIATE_RENDERING, + PCL_VISUALIZER_SHADING + }; + + enum RenderingRepresentationProperties + { + PCL_VISUALIZER_REPRESENTATION_POINTS, + PCL_VISUALIZER_REPRESENTATION_WIREFRAME, + PCL_VISUALIZER_REPRESENTATION_SURFACE + }; + + enum ShadingRepresentationProperties + { + PCL_VISUALIZER_SHADING_FLAT, + PCL_VISUALIZER_SHADING_GOURAUD, + PCL_VISUALIZER_SHADING_PHONG + }; + + ////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Camera class holds a set of camera parameters together with the window pos/size. */ + class PCL_EXPORTS Camera + { + public: + /** \brief Focal point or lookAt. + * \note The view direction can be obtained by (focal-pos).normalized () + */ + double focal[3]; + + /** \brief Position of the camera. */ + double pos[3]; + + /** \brief Up vector of the camera. + * \note Not to be confused with the view direction, bad naming here. */ + double view[3]; + + /** \brief Clipping planes depths. + * clip[0] is near clipping plane, and clip [1] is the far clipping plane + */ + double clip[2]; + + /** \brief Field of view angle in y direction (radians). */ + double fovy; + + // the following variables are the actual position and size of the window on the screen and NOT the viewport! + // except for the size, which is the same the viewport is assumed to be centered and same size as the window. + double window_size[2]; + double window_pos[2]; + + + /** \brief Computes View matrix for Camera (Based on gluLookAt) + * \param[out] view_mat the resultant matrix + */ + void + computeViewMatrix (Eigen::Matrix4d& view_mat) const; + + /** \brief Computes Projection Matrix for Camera + * \param[out] proj the resultant matrix + */ + void + computeProjectionMatrix (Eigen::Matrix4d& proj) const; + + /** \brief converts point to window coordiantes + * \param[in] pt xyz point to be converted + * \param[out] window_cord vector containing the pts' window X,Y, Z and 1 + * + * This function computes the projection and view matrix every time. + * It is very inefficient to use this for every point in the point cloud! + */ + template void + cvtWindowCoordinates (const PointT& pt, Eigen::Vector4d& window_cord) const; + + /** \brief converts point to window coordiantes + * \param[in] pt xyz point to be converted + * \param[out] window_cord vector containing the pts' window X,Y, Z and 1 + * \param[in] composite_mat composite transformation matrix (proj*view) + * + * Use this function to compute window coordinates with a precomputed + * transformation function. The typical composite matrix will be + * the projection matrix * the view matrix. However, additional + * matrices like a camera disortion matrix can also be added. + */ + template void + cvtWindowCoordinates (const PointT& pt, Eigen::Vector4d& window_cord, const Eigen::Matrix4d& composite_mat) const; + }; + } +} + +#include + +#endif diff --git a/pcl-1.7/pcl/visualization/common/float_image_utils.h b/pcl-1.7/pcl/visualization/common/float_image_utils.h new file mode 100644 index 0000000..2a89473 --- /dev/null +++ b/pcl-1.7/pcl/visualization/common/float_image_utils.h @@ -0,0 +1,103 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +#ifndef PCL_VISUALIZATION_FLOAT_IMAGE_UTILS_H_ +#define PCL_VISUALIZATION_FLOAT_IMAGE_UTILS_H_ + +#include + +#include +#include +#include + +namespace pcl +{ + namespace visualization + { + /** @b Provide some gerneral functionalities regarding 2d float arrays, e.g., for visualization purposes + * \author Bastian Steder + * \ingroup visualization + */ + class PCL_EXPORTS FloatImageUtils + { + public: + // =====STATIC METHODS===== + /** Get RGB color values for a given float in [0, 1] or special cases like -INFINITY(light green), INFINITY(light blue), NAN(light red) */ + static void + getColorForFloat (float value, unsigned char& r, unsigned char& g, unsigned char& b); + + /** Get RGB color values for a given float in [-PI, PI] or special cases like -INFINITY(light green), INFINITY(light blue), NAN(light red) + * The colors are black(-PI) -> blue(-PI/2) -> white(0) -> green(PI/2) -> black(PI) with accordant values in between */ + static void + getColorForAngle (float value, unsigned char& r, unsigned char& g, unsigned char& b); + + /** Get RGB color values for a given float in [0, PI] or special cases like -INFINITY(light green), INFINITY(light blue), NAN(light red) + * The colors are black(-PI/2) -> blue(-PI/4) -> white(0) -> green(PI/4) -> black(PI/2) with accordant values in between */ + static void + getColorForHalfAngle (float value, unsigned char& r, unsigned char& g, unsigned char& b); + + /** Use getColorForFloat for all elements of the given arrays, whereas the values are first normalized to [0,1], + * either using the given min/max values or based on the actual minimal and maximal values existing in the array. + * The output is a byte array of size 3*width*height containing the colors in RGB order. + * If gray_scale is true, the outcome will still be an RGB image, but all colors apart for the special colors of + * non-finite numbers, will be gray values */ + static unsigned char* + getVisualImage (const float* float_image, int width, int height, float min_value=-std::numeric_limits::infinity (), float max_value=std::numeric_limits::infinity (), bool gray_scale=false); + + /** Use getColorForFloat for all elements of the given arrays, whereas the values are normalized to [0,1] + * with the given min/max values. + * The output is a byte array of size 3*width*height containing the colors in RGB order. + * If gray_scale is true, the outcome will still be an RGB image, but all colors will be gray values. */ + static unsigned char* + getVisualImage (const unsigned short* float_image, int width, int height, + unsigned short min_value=0, + unsigned short max_value=std::numeric_limits::max (), + bool gray_scale=false); + + /** Use getColorForAngle for all elements of the given arrays. */ + static unsigned char* + getVisualAngleImage (const float* angle_image, int width, int height); + + /** Use getColorForHalfAngle for all elements of the given arrays. */ + static unsigned char* + getVisualHalfAngleImage (const float* angle_image, int width, int height); + }; + + } // namespace end +} + +#endif //#ifndef PCL_VISUALIZATION_FLOAT_IMAGE_UTILS_H_ + diff --git a/pcl-1.7/pcl/visualization/common/impl/common.hpp b/pcl-1.7/pcl/visualization/common/impl/common.hpp new file mode 100644 index 0000000..d98671f --- /dev/null +++ b/pcl-1.7/pcl/visualization/common/impl/common.hpp @@ -0,0 +1,79 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +namespace pcl +{ + namespace visualization + { + /** \brief Converts point to window coordinates + * \param[in] pt xyz point to be converted + * \param[out] window_cord vector containing the pts' window X,Y, Z and 1 + * \note This function computes the projection and view matrix every time. + * It is very inefficient to use this for every point in the point cloud! + */ + template void + Camera::cvtWindowCoordinates (const PointT& pt, Eigen::Vector4d& window_cord) const + { + Eigen::Matrix4d proj, view; + this->computeViewMatrix (view); + this->computeProjectionMatrix (proj); + this->cvtWindowCoordinates (pt, window_cord, proj*view); + return; + } + + + /** \brief converts point to window coordiantes + * \param[in] pt xyz point to be converted + * \param[out] window_cord vector containing the pts' window X,Y, Z and 1 + * \param[in] composite_mat composite transformation matrix (proj*view) + * + * \note Use this function to compute window coordinates with a pre-computed transformation function. + * The typical composite matrix will be the projection matrix * the view matrix. However, additional matrices like + * a camera distortion matrix can also be added. + */ + template void + Camera::cvtWindowCoordinates (const PointT& pt, Eigen::Vector4d& window_cord, const Eigen::Matrix4d& composite_mat) const + { + Eigen::Vector4d pte (pt.x, pt.y, pt.z, 1); + window_cord = composite_mat * pte; + window_cord = window_cord/window_cord (3); + window_cord[0] = (window_cord[0]+1.0) / 2.0*window_size[0]; + window_cord[1] = (window_cord[1]+1.0) / 2.0*window_size[1]; + window_cord[2] = (window_cord[2]+1.0) / 2.0; + } + } +} diff --git a/pcl-1.7/pcl/visualization/common/impl/shapes.hpp b/pcl-1.7/pcl/visualization/common/impl/shapes.hpp new file mode 100644 index 0000000..8622eab --- /dev/null +++ b/pcl-1.7/pcl/visualization/common/impl/shapes.hpp @@ -0,0 +1,109 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#pragma once +#include +#include +#include +#include + +//////////////////////////////////////////////////////////////////////////////////////////// +template vtkSmartPointer +pcl::visualization::createPolygon (const typename pcl::PointCloud::ConstPtr &cloud) +{ + vtkSmartPointer poly_grid; + if (cloud->points.empty ()) + return (poly_grid); + + vtkSmartPointer poly_points = vtkSmartPointer::New (); + vtkSmartPointer polygon = vtkSmartPointer::New (); + + poly_points->SetNumberOfPoints (cloud->points.size ()); + polygon->GetPointIds ()->SetNumberOfIds (cloud->points.size ()); + + size_t i; + for (i = 0; i < cloud->points.size (); ++i) + { + poly_points->SetPoint (i, cloud->points[i].x, cloud->points[i].y, cloud->points[i].z); + polygon->GetPointIds ()->SetId (i, i); + } + + allocVtkUnstructuredGrid (poly_grid); + poly_grid->Allocate (1, 1); + poly_grid->InsertNextCell (polygon->GetCellType (), polygon->GetPointIds ()); + poly_grid->SetPoints (poly_points); + + return (poly_grid); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template vtkSmartPointer +pcl::visualization::createPolygon (const pcl::PlanarPolygon &planar_polygon) +{ + vtkSmartPointer poly_grid; + if (planar_polygon.getContour ().empty ()) + return (poly_grid); + + vtkSmartPointer poly_points = vtkSmartPointer::New (); + vtkSmartPointer polygon = vtkSmartPointer::New (); + + poly_points->SetNumberOfPoints (planar_polygon.getContour ().size () + 1); + polygon->GetPointIds ()->SetNumberOfIds (planar_polygon.getContour ().size () + 1); + + size_t i; + for (i = 0; i < planar_polygon.getContour ().size (); ++i) + { + poly_points->SetPoint (i, planar_polygon.getContour ()[i].x, + planar_polygon.getContour ()[i].y, + planar_polygon.getContour ()[i].z); + polygon->GetPointIds ()->SetId (i, i); + } + + poly_points->SetPoint (i, planar_polygon.getContour ()[0].x, + planar_polygon.getContour ()[0].y, + planar_polygon.getContour ()[0].z); + polygon->GetPointIds ()->SetId (i, i); + + allocVtkUnstructuredGrid (poly_grid); + poly_grid->Allocate (1, 1); + poly_grid->InsertNextCell (polygon->GetCellType (), polygon->GetPointIds ()); + poly_grid->SetPoints (poly_points); + + return (poly_grid); +} + diff --git a/pcl-1.7/pcl/visualization/common/io.h b/pcl-1.7/pcl/visualization/common/io.h new file mode 100644 index 0000000..6b2d826 --- /dev/null +++ b/pcl-1.7/pcl/visualization/common/io.h @@ -0,0 +1,74 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_PCL_VISUALIZER_COMMON_IO_H_ +#define PCL_PCL_VISUALIZER_COMMON_IO_H_ + +#include +#include +#include + +class vtkPolyData; + +namespace pcl +{ + namespace visualization + { + /** \brief Obtain a list of corresponding indices, for a set of vtk points, + * from a pcl::PointCloud + * \param src the set of vtk points + * \param tgt the target pcl::PointCloud that we need to obtain indices from + * \param indices the resultant list of indices + * \ingroup visualization + */ + PCL_EXPORTS void + getCorrespondingPointCloud (vtkPolyData *src, const pcl::PointCloud &tgt, std::vector &indices); + + /** \brief Saves the vtk-formatted Point Cloud data into a set of files, based on whether + * the data comes from previously loaded PCD files. The PCD files are matched using the + * a list of names for the actors on screen. + * \param data the vtk data + * \param out_file the output file (extra indices will be appended to it) + * \param actors the list of actors present on screen + * \ingroup visualization + */ + PCL_EXPORTS bool + savePointData (vtkPolyData* data, const std::string &out_file, const boost::shared_ptr &actors); + } +} + +#endif diff --git a/pcl-1.7/pcl/visualization/common/ren_win_interact_map.h b/pcl-1.7/pcl/visualization/common/ren_win_interact_map.h new file mode 100644 index 0000000..f76046e --- /dev/null +++ b/pcl-1.7/pcl/visualization/common/ren_win_interact_map.h @@ -0,0 +1,86 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_PCL_VISUALIZER_REN_WIN_INTERACT_MAP_H_ +#define PCL_PCL_VISUALIZER_REN_WIN_INTERACT_MAP_H_ + +#include +#include + +template class vtkSmartPointer; +class vtkXYPlotActor; +class vtkRenderer; +class vtkRenderWindow; +class vtkRenderWindowInteractor; +class vtkInteractorStyleTrackballCamera; +class PCLVisualizerInteractor; + +namespace pcl +{ + namespace visualization + { + class RenWinInteract + { + public: + + RenWinInteract (); + + /** \brief The XY plot actor holding the actual data. */ + vtkSmartPointer xy_plot_; + + /** \brief The renderer used. */ + vtkSmartPointer ren_; + + /** \brief The render window. */ + vtkSmartPointer win_; + + /** \brief The render window interactor. */ + +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + vtkSmartPointer interactor_; +#else + vtkSmartPointer interactor_; +#endif + /** \brief The render window interactor style. */ + vtkSmartPointer style_; + }; + typedef std::map RenWinInteractMap; + } +} + +#endif diff --git a/pcl-1.7/pcl/visualization/common/shapes.h b/pcl-1.7/pcl/visualization/common/shapes.h new file mode 100644 index 0000000..ef36a0f --- /dev/null +++ b/pcl-1.7/pcl/visualization/common/shapes.h @@ -0,0 +1,295 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_PCL_VISUALIZER_SHAPES_H_ +#define PCL_PCL_VISUALIZER_SHAPES_H_ + +#include +#include +#include +#include + +template class vtkSmartPointer; +class vtkDataSet; +class vtkUnstructuredGrid; + +/** + * \file pcl/visualization/common/shapes.h + * Define methods or creating 3D shapes from parametric models + * \ingroup visualization + */ + +/*@{*/ +namespace pcl +{ + namespace visualization + { + /** \brief Create a 3d poly line from a set of points. + * \param[in] cloud the set of points used to create the 3d polyline + * \ingroup visualization + */ + template vtkSmartPointer inline + createPolygon (const typename pcl::PointCloud::ConstPtr &cloud); + + /** \brief Create a 3d poly line from a set of points on the boundary of a planar region. + * \param[in] planar_polygon the set of points used to create the 3d polyline + * \ingroup visualization + */ + template vtkSmartPointer inline + createPolygon (const pcl::PlanarPolygon &planar_polygon); + + /** \brief Create a line shape from two points + * \param[in] pt1 the first point on the line + * \param[in] pt2 the end point on the line + * \ingroup visualization + */ + PCL_EXPORTS vtkSmartPointer + createLine (const Eigen::Vector4f &pt1, const Eigen::Vector4f &pt2); + + /** \brief Create a sphere shape from a point and a radius + * \param[in] center the center of the sphere (as an Eigen Vector4f, with only the first 3 coordinates used) + * \param[in] radius the radius of the sphere + * \param[in] res (optional) the resolution used for rendering the model + * \ingroup visualization + */ + PCL_EXPORTS vtkSmartPointer + createSphere (const Eigen::Vector4f ¢er, double radius, int res = 10); + + /** \brief Create a cylinder shape from a set of model coefficients. + * \param[in] coefficients the model coefficients (point_on_axis, axis_direction, radius) + * \param[in] numsides (optional) the number of sides used for rendering the cylinder + * + * \code + * // The following are given (or computed using sample consensus techniques -- see SampleConsensusModelCylinder) + * // Eigen::Vector3f pt_on_axis, axis_direction; + * // float radius; + * + * pcl::ModelCoefficients cylinder_coeff; + * cylinder_coeff.values.resize (7); // We need 7 values + * cylinder_coeff.values[0] = pt_on_axis.x (); + * cylinder_coeff.values[1] = pt_on_axis.y (); + * cylinder_coeff.values[2] = pt_on_axis.z (); + * + * cylinder_coeff.values[3] = axis_direction.x (); + * cylinder_coeff.values[4] = axis_direction.y (); + * cylinder_coeff.values[5] = axis_direction.z (); + * + * cylinder_coeff.values[6] = radius; + * + * vtkSmartPointer data = pcl::visualization::createCylinder (cylinder_coeff, numsides); + * \endcode + * + * \ingroup visualization + */ + PCL_EXPORTS vtkSmartPointer + createCylinder (const pcl::ModelCoefficients &coefficients, int numsides = 30); + + /** \brief Create a sphere shape from a set of model coefficients. + * \param[in] coefficients the model coefficients (sphere center, radius) + * \param[in] res (optional) the resolution used for rendering the model + * + * \code + * // The following are given (or computed using sample consensus techniques -- see SampleConsensusModelSphere) + * // Eigen::Vector3f sphere_center; + * // float radius; + * + * pcl::ModelCoefficients sphere_coeff; + * sphere_coeff.values.resize (4); // We need 4 values + * sphere_coeff.values[0] = sphere_center.x (); + * sphere_coeff.values[1] = sphere_center.y (); + * sphere_coeff.values[2] = sphere_center.z (); + * + * sphere_coeff.values[3] = radius; + * + * vtkSmartPointer data = pcl::visualization::createSphere (sphere_coeff, resolution); + * \endcode + * + * \ingroup visualization + */ + PCL_EXPORTS vtkSmartPointer + createSphere (const pcl::ModelCoefficients &coefficients, int res = 10); + + /** \brief Create a line shape from a set of model coefficients. + * \param[in] coefficients the model coefficients (point_on_line, line_direction) + * + * \code + * // The following are given (or computed using sample consensus techniques -- see SampleConsensusModelLine) + * // Eigen::Vector3f point_on_line, line_direction; + * + * pcl::ModelCoefficients line_coeff; + * line_coeff.values.resize (6); // We need 6 values + * line_coeff.values[0] = point_on_line.x (); + * line_coeff.values[1] = point_on_line.y (); + * line_coeff.values[2] = point_on_line.z (); + * + * line_coeff.values[3] = line_direction.x (); + * line_coeff.values[4] = line_direction.y (); + * line_coeff.values[5] = line_direction.z (); + * + * vtkSmartPointer data = pcl::visualization::createLine (line_coeff); + * \endcode + * + * \ingroup visualization + */ + PCL_EXPORTS vtkSmartPointer + createLine (const pcl::ModelCoefficients &coefficients); + + /** \brief Create a planar shape from a set of model coefficients. + * \param[in] coefficients the model coefficients (a, b, c, d with ax+by+cz+d=0) + * + * \code + * // The following are given (or computed using sample consensus techniques -- see SampleConsensusModelPlane) + * // Eigen::Vector4f plane_parameters; + * + * pcl::ModelCoefficients plane_coeff; + * plane_coeff.values.resize (4); // We need 4 values + * plane_coeff.values[0] = plane_parameters.x (); + * plane_coeff.values[1] = plane_parameters.y (); + * plane_coeff.values[2] = plane_parameters.z (); + * plane_coeff.values[3] = plane_parameters.w (); + * + * vtkSmartPointer data = pcl::visualization::createPlane (plane_coeff); + * \endcode + * + * \ingroup visualization + */ + PCL_EXPORTS vtkSmartPointer + createPlane (const pcl::ModelCoefficients &coefficients); + + /** \brief Create a planar shape from a set of model coefficients. + * \param[in] coefficients the model coefficients (a, b, c, d with ax+by+cz+d=0) + * \param[in] x,y,z projection of this point on the plane is used to get the center of the plane. + * \ingroup visualization + */ + PCL_EXPORTS vtkSmartPointer + createPlane (const pcl::ModelCoefficients &coefficients, double x, double y, double z); + + /** \brief Create a 2d circle shape from a set of model coefficients. + * \param[in] coefficients the model coefficients (x, y, radius) + * \param[in] z (optional) specify a z value (default: 0) + * + * \code + * // The following are given (or computed using sample consensus techniques -- see SampleConsensusModelCircle2D) + * // float x, y, radius; + * + * pcl::ModelCoefficients circle_coeff; + * circle_coeff.values.resize (3); // We need 3 values + * circle_coeff.values[0] = x; + * circle_coeff.values[1] = y; + * circle_coeff.values[2] = radius; + * + * vtkSmartPointer data = pcl::visualization::create2DCircle (circle_coeff, z); + * \endcode + * + * \ingroup visualization + */ + PCL_EXPORTS vtkSmartPointer + create2DCircle (const pcl::ModelCoefficients &coefficients, double z = 0.0); + + /** \brief Create a cone shape from a set of model coefficients. + * \param[in] coefficients the cone coefficients (cone_apex, axis_direction, angle) + * + * \code + * // The following are given (or computed using sample consensus techniques -- see SampleConsensusModelCone) + * // Eigen::Vector3f cone_apex, axis_direction; + * // float angle; + * // Note: The height of the cone is set using the magnitude of the axis_direction vector. + * + * pcl::ModelCoefficients cone_coeff; + * plane_coeff.values.resize (7); // We need 7 values + * plane_coeff.values[0] = cone_apex.x (); + * plane_coeff.values[1] = cone_apex.y (); + * plane_coeff.values[2] = cone_apex.z (); + * plane_coeff.values[3] = axis_direction.x (); + * plane_coeff.values[4] = axis_direction.y (); + * plane_coeff.values[5] = axis_direction.z (); + * plane_coeff.values[6] = angle (); // degrees + * + * vtkSmartPointer data = pcl::visualization::createCone (cone_coeff); + * \endcode + * + * \ingroup visualization + */ + PCL_EXPORTS vtkSmartPointer + createCone (const pcl::ModelCoefficients &coefficients); + + /** \brief Creaet a cube shape from a set of model coefficients. + * \param[in] coefficients the cube coefficients (Tx, Ty, Tz, Qx, Qy, Qz, Qw, width, height, depth) + * \ingroup visualization + */ + PCL_EXPORTS vtkSmartPointer + createCube (const pcl::ModelCoefficients &coefficients); + + /** \brief Creaet a cube shape from a set of model coefficients. + * + * \param[in] translation a translation to apply to the cube from 0,0,0 + * \param[in] rotation a quaternion-based rotation to apply to the cube + * \param[in] width the cube's width + * \param[in] height the cube's height + * \param[in] depth the cube's depth + * \ingroup visualization + */ + PCL_EXPORTS vtkSmartPointer + createCube (const Eigen::Vector3f &translation, const Eigen::Quaternionf &rotation, + double width, double height, double depth); + + /** \brief Create a cube from a set of bounding points + * \param[in] x_min is the minimum x value of the box + * \param[in] x_max is the maximum x value of the box + * \param[in] y_min is the minimum y value of the box + * \param[in] y_max is the maximum y value of the box + * \param[in] z_min is the minimum z value of the box + * \param[in] z_max is the maximum z value of the box + */ + PCL_EXPORTS vtkSmartPointer + createCube (double x_min, double x_max, + double y_min, double y_max, + double z_min, double z_max); + + /** \brief Allocate a new unstructured grid smartpointer. For internal use only. + * \param[out] polydata the resultant unstructured grid. + */ + PCL_EXPORTS void + allocVtkUnstructuredGrid (vtkSmartPointer &polydata); + } +} +/*@}*/ + +#include + +#endif diff --git a/pcl-1.7/pcl/visualization/eigen.h b/pcl-1.7/pcl/visualization/eigen.h new file mode 100644 index 0000000..5408de4 --- /dev/null +++ b/pcl-1.7/pcl/visualization/eigen.h @@ -0,0 +1,50 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $ + * + */ + +#ifndef PCL_VISUALIZATION_EIGEN_H_ +#define PCL_VISUALIZATION_EIGEN_H_ + +#if defined __GNUC__ +# pragma GCC system_header +#endif + +#include +#include + +#endif // PCL_VISUALIZATION_EIGEN_H_ diff --git a/pcl-1.7/pcl/visualization/histogram_visualizer.h b/pcl-1.7/pcl/visualization/histogram_visualizer.h new file mode 100644 index 0000000..cbcba84 --- /dev/null +++ b/pcl-1.7/pcl/visualization/histogram_visualizer.h @@ -0,0 +1,269 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_PCL_HISTOGRAM_VISUALIZER_H_ +#define PCL_PCL_HISTOGRAM_VISUALIZER_H_ + +#include +#include +#include + +class vtkRenderWindowInteractor; + +namespace pcl +{ + namespace visualization + { + /** \brief PCL histogram visualizer main class. + * \author Radu Bogdan Rusu + * \ingroup visualization + */ + class PCL_EXPORTS PCLHistogramVisualizer + { + public: + /** \brief PCL histogram visualizer constructor. */ + PCLHistogramVisualizer (); + + virtual ~PCLHistogramVisualizer () {} + /** \brief Spin once method. Calls the interactor and updates the screen once. + * \param[in] time - How long (in ms) should the visualization loop be allowed to run. + */ +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + void + spinOnce (int time = 1, bool force_redraw = false); +#else + void + spinOnce (int time = 1); +#endif + /** \brief Spin method. Calls the interactor and runs an internal loop. */ + void + spin (); + + /** \brief Set the viewport's background color. + * \param[in] r the red component of the RGB color + * \param[in] g the green component of the RGB color + * \param[in] b the blue component of the RGB color + */ + void + setBackgroundColor (const double &r, const double &g, const double &b); + + /** \brief Add a histogram feature to screen as a separate window, from a cloud containing a single histogram. + * \param[in] cloud the PointCloud dataset containing the histogram + * \param[in] hsize the length of the histogram + * \param[in] id the point cloud object id (default: cloud) + * \param[in] win_width the width of the window + * \param[in] win_height the height of the window + */ + template bool + addFeatureHistogram (const pcl::PointCloud &cloud, + int hsize, + const std::string &id = "cloud", int win_width = 640, int win_height = 200); + + /** \brief Add a histogram feature to screen as a separate window from a cloud containing a single histogram. + * \param[in] cloud the PointCloud dataset containing the histogram + * \param[in] field_name the field name containing the histogram + * \param[in] id the point cloud object id (default: cloud) + * \param[in] win_width the width of the window + * \param[in] win_height the height of the window + */ + bool + addFeatureHistogram (const pcl::PCLPointCloud2 &cloud, + const std::string &field_name, + const std::string &id = "cloud", int win_width = 640, int win_height = 200); + + /** \brief Add a histogram feature to screen as a separate window. + * \param[in] cloud the PointCloud dataset containing the histogram + * \param[in] field_name the field name containing the histogram + * \param[in] index the point index to extract the histogram from + * \param[in] id the point cloud object id (default: cloud) + * \param[in] win_width the width of the window + * \param[in] win_height the height of the window + */ + template bool + addFeatureHistogram (const pcl::PointCloud &cloud, + const std::string &field_name, + const int index, + const std::string &id = "cloud", int win_width = 640, int win_height = 200); + + /** \brief Add a histogram feature to screen as a separate window. + * \param[in] cloud the PointCloud dataset containing the histogram + * \param[in] field_name the field name containing the histogram + * \param[in] index the point index to extract the histogram from + * \param[in] id the point cloud object id (default: cloud) + * \param[in] win_width the width of the window + * \param[in] win_height the height of the window + */ + bool + addFeatureHistogram (const pcl::PCLPointCloud2 &cloud, + const std::string &field_name, + const int index, + const std::string &id = "cloud", int win_width = 640, int win_height = 200); + + /** \brief Update a histogram feature that is already on screen, with a cloud containing a single histogram. + * \param[in] cloud the PointCloud dataset containing the histogram + * \param[in] hsize the length of the histogram + * \param[in] id the point cloud object id (default: cloud) + */ + template bool + updateFeatureHistogram (const pcl::PointCloud &cloud, int hsize, const std::string &id = "cloud"); + + + /** \brief Update a histogram feature that is already on screen, with a cloud containing a single histogram. + * \param[in] cloud the PointCloud dataset containing the histogram + * \param[in] field_name the field name containing the histogram + * \param[in] id the point cloud object id (default: cloud) + */ + bool + updateFeatureHistogram (const pcl::PCLPointCloud2 &cloud, + const std::string &field_name, + const std::string &id = "cloud"); + + + /** \brief Update a histogram feature that is already on screen, with a cloud containing a single histogram. + * \param[in] cloud the PointCloud dataset containing the histogram + * \param[in] field_name the field name containing the histogram + * \param[in] index the point index to extract the histogram from + * \param[in] id the point cloud object id (default: cloud) + */ + template bool + updateFeatureHistogram (const pcl::PointCloud &cloud, const std::string &field_name, + const int index, const std::string &id = "cloud"); + + + /** \brief Update a histogram feature that is already on screen, with a cloud containing a single histogram. + * \param[in] cloud the PointCloud dataset containing the histogram + * \param[in] field_name the field name containing the histogram + * \param[in] index the point index to extract the histogram from + * \param[in] id the point cloud object id (default: cloud) + */ + bool + updateFeatureHistogram (const pcl::PCLPointCloud2 &cloud, + const std::string &field_name, const int index, + const std::string &id = "cloud"); + + + /** \brief Set the Y range to minp-maxp for all histograms. + * \param[in] minp the minimum Y range + * \param[in] maxp the maximum Y range + */ + void + setGlobalYRange (float minp, float maxp); + + /** \brief Update all window positions on screen so that they fit. */ + void + updateWindowPositions (); +#if ((VTK_MAJOR_VERSION) == 5 && (VTK_MINOR_VERSION <= 4)) + /** \brief Returns true when the user tried to close the window */ + bool + wasStopped (); + + /** \brief Set the stopped flag back to false */ + void + resetStoppedFlag (); +#endif + protected: + + /** \brief Create a 2D actor from the given vtkDoubleArray histogram and add it to the screen. + * \param[in] xy_array the input vtkDoubleArray holding the histogram data + * \param[out] renwinint the resultant render window interactor holding the rendered object + * \param[in] id the point cloud object id + * \param[in] win_width the width of the window + * \param[in] win_height the height of the window + */ + void + createActor (const vtkSmartPointer &xy_array, + RenWinInteract &renwinint, + const std::string &id, const int win_width, const int win_height); + + /** \brief Remove the current 2d actor and create a new 2D actor from the given vtkDoubleArray histogram and add it to the screen. + * \param[in] xy_array the input vtkDoubleArray holding the histogram data + * \param[out] renwinupd the resultant render window interactor holding the rendered object + * \param[in] hsize Histogram size + */ + void + reCreateActor (const vtkSmartPointer &xy_array, + RenWinInteract* renwinupd, const int hsize); + + private: + /** \brief A map of all windows on screen (with their renderers and interactors). */ + RenWinInteractMap wins_; + + struct ExitMainLoopTimerCallback : public vtkCommand + { + static ExitMainLoopTimerCallback* New () + { + return (new ExitMainLoopTimerCallback); + } + virtual void + Execute (vtkObject*, unsigned long event_id, void* call_data); + + int right_timer_id; +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + PCLVisualizerInteractor *interact; +#else + vtkRenderWindowInteractor *interact; +#endif + }; + + struct ExitCallback : public vtkCommand + { + ExitCallback () : his () {} + + static ExitCallback* New () + { + return (new ExitCallback); + } + + virtual void + Execute (vtkObject*, unsigned long event_id, void*); + + PCLHistogramVisualizer *his; + }; + + /** \brief Callback object enabling us to leave the main loop, when a timer fires. */ + vtkSmartPointer exit_main_loop_timer_callback_; + vtkSmartPointer exit_callback_; + /** \brief Set to true when the histogram visualizer is ready to be terminated. */ + bool stopped_; + }; + } +} + +#include + +#endif diff --git a/pcl-1.7/pcl/visualization/image_viewer.h b/pcl-1.7/pcl/visualization/image_viewer.h new file mode 100644 index 0000000..21b060d --- /dev/null +++ b/pcl-1.7/pcl/visualization/image_viewer.h @@ -0,0 +1,1070 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_VISUALIZATION_IMAGE_VISUALIZER_H__ +#define PCL_VISUALIZATION_IMAGE_VISUALIZER_H__ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include + +class vtkImageSlice; +class vtkContextActor; +class vtkImageViewer; +class vtkImageFlip; + +namespace pcl +{ + namespace visualization + { + typedef Eigen::Array Vector3ub; + static const Vector3ub green_color (0, 255, 0); + static const Vector3ub red_color (255, 0, 0); + static const Vector3ub blue_color (0, 0, 255); + + /** \brief An image viewer interactor style, tailored for ImageViewer. + * \author Radu B. Rusu + * \ingroup visualization + */ + class PCL_EXPORTS ImageViewerInteractorStyle : public vtkInteractorStyleImage + { + public: + static ImageViewerInteractorStyle *New (); + ImageViewerInteractorStyle (); + + virtual void OnMouseWheelForward () {} + virtual void OnMouseWheelBackward () {} + virtual void OnMiddleButtonDown () {} + virtual void OnRightButtonDown () {} + virtual void OnLeftButtonDown (); + + virtual void + OnChar (); + + void + adjustCamera (vtkImageData *image, vtkRenderer *ren); + + void + adjustCamera (vtkRenderer *ren); + }; + + /** \brief ImageViewer is a class for 2D image visualization. + * + * Features include: + * - add and remove different layers with different opacity (transparency) values + * - add 2D geometric shapes (circles, boxes, etc) in separate layers + * - display RGB, monochrome, float, angle images + * + * Simple usage example: + * \code + * pcl::visualization::ImageViewer iv; + * iv.addCircle (10, 10, 5, 1.0, 0.0, 0.0, "circles", 1.0); // add a red, fully opaque circle with radius 5 pixels at (10,10) in layer "circles" + * iv.addFilledRectangle (10, 20, 10, 20, 0.0, 1.0, 0.0, "boxes", 0.5); // add a green, 50% transparent box at (10,10->20,20) in layer "boxes" + * iv.addRGBImage (cloud); // add a RGB image from a point cloud dataset in an "rgb_image" default layer + * iv.spin (); // press 'q' to exit + * iv.removeLayer ("circles"); // remove layer "circles" + * iv.spin (); // press 'q' to exit + * \endcode + * + * \author Radu B. Rusu, Suat Gedikli + * \ingroup visualization + */ + class PCL_EXPORTS ImageViewer + { + public: + typedef boost::shared_ptr Ptr; + + /** \brief Constructor. + * \param[in] window_title the title of the window + */ + ImageViewer (const std::string& window_title = ""); + + /** \brief Destructor. */ + virtual ~ImageViewer (); + +#if ((VTK_MAJOR_VERSION > 5) || ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 4))) + /** \brief Set up the interactor style. By default the interactor style is set to + * vtkInteractorStyleImage you can use this to set it to another type. + * \param[in] style user set interactor style. + */ + void + setInteractorStyle (vtkInteractorObserver *style) + { + interactor_->SetInteractorStyle (style); + } +#endif + /** \brief Show a monochrome 2D image on screen. + * \param[in] data the input data representing the image + * \param[in] width the width of the image + * \param[in] height the height of the image + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + showMonoImage (const unsigned char* data, unsigned width, unsigned height, + const std::string &layer_id = "mono_image", double opacity = 1.0); + + /** \brief Add a monochrome 2D image layer, but do not render it (use spin/spinOnce to update). + * \param[in] data the input data representing the image + * \param[in] width the width of the image + * \param[in] height the height of the image + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + addMonoImage (const unsigned char* data, unsigned width, unsigned height, + const std::string &layer_id = "mono_image", double opacity = 1.0); + + /** \brief Show a monochrome 2D image on screen. + * \param[in] cloud the input data representing the grayscale point cloud + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + inline void + showMonoImage (const pcl::PointCloud::ConstPtr &cloud, + const std::string &layer_id = "mono_image", double opacity = 1.0) + { + return (showMonoImage (*cloud, layer_id, opacity)); + } + + /** \brief Add a monochrome 2D image layer, but do not render it (use spin/spinOnce to update). + * \param[in] cloud the input data representing the grayscale point cloud + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + inline void + addMonoImage (const pcl::PointCloud::ConstPtr &cloud, + const std::string &layer_id = "mono_image", double opacity = 1.0) + { + return (addMonoImage (*cloud, layer_id, opacity)); + } + + /** \brief Show a monochrome 2D image on screen. + * \param[in] cloud the input data representing the grayscale point cloud + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + showMonoImage (const pcl::PointCloud &cloud, + const std::string &layer_id = "mono_image", double opacity = 1.0); + + /** \brief Add a monochrome 2D image layer, but do not render it (use spin/spinOnce to update). + * \param[in] cloud the input data representing the RGB point cloud + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + addMonoImage (const pcl::PointCloud &cloud, + const std::string &layer_id = "mono_image", double opacity = 1.0); + + /** \brief Show a monochrome 2D image on screen. + * \param[in] cloud the input data representing the grayscale point cloud + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + inline void + showMonoImage (const pcl::PointCloud::ConstPtr &cloud, + const std::string &layer_id = "mono_image", double opacity = 1.0) + { + return (showMonoImage (*cloud, layer_id, opacity)); + } + + /** \brief Add a monochrome 2D image layer, but do not render it (use spin/spinOnce to update). + * \param[in] cloud the input data representing the grayscale point cloud + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + inline void + addMonoImage (const pcl::PointCloud::ConstPtr &cloud, + const std::string &layer_id = "mono_image", double opacity = 1.0) + { + return (addMonoImage (*cloud, layer_id, opacity)); + } + + /** \brief Show a monochrome 2D image on screen. + * \param[in] cloud the input data representing the grayscale point cloud + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + showMonoImage (const pcl::PointCloud &cloud, + const std::string &layer_id = "mono_image", double opacity = 1.0); + + /** \brief Add a monochrome 2D image layer, but do not render it (use spin/spinOnce to update). + * \param[in] cloud the input data representing the RGB point cloud + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + addMonoImage (const pcl::PointCloud &cloud, + const std::string &layer_id = "mono_image", double opacity = 1.0); + + /** \brief Show a 2D RGB image on screen. + * \param[in] data the input data representing the image + * \param[in] width the width of the image + * \param[in] height the height of the image + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + showRGBImage (const unsigned char* data, unsigned width, unsigned height, + const std::string &layer_id = "rgb_image", double opacity = 1.0); + + /** \brief Add an RGB 2D image layer, but do not render it (use spin/spinOnce to update). + * \param[in] data the input data representing the image + * \param[in] width the width of the image + * \param[in] height the height of the image + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + addRGBImage (const unsigned char* data, unsigned width, unsigned height, + const std::string &layer_id = "rgb_image", double opacity = 1.0); + + /** \brief Show a 2D image on screen, obtained from the RGB channel of a point cloud. + * \param[in] cloud the input data representing the RGB point cloud + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + template inline void + showRGBImage (const typename pcl::PointCloud::ConstPtr &cloud, + const std::string &layer_id = "rgb_image", double opacity = 1.0) + { + return (showRGBImage (*cloud, layer_id, opacity)); + } + + /** \brief Add an RGB 2D image layer, but do not render it (use spin/spinOnce to update). + * \param[in] cloud the input data representing the RGB point cloud + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + template inline void + addRGBImage (const typename pcl::PointCloud::ConstPtr &cloud, + const std::string &layer_id = "rgb_image", double opacity = 1.0) + { + return (addRGBImage (*cloud, layer_id, opacity)); + } + + /** \brief Show a 2D image on screen, obtained from the RGB channel of a point cloud. + * \param[in] cloud the input data representing the RGB point cloud + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + template void + showRGBImage (const pcl::PointCloud &cloud, + const std::string &layer_id = "rgb_image", double opacity = 1.0); + + /** \brief Add an RGB 2D image layer, but do not render it (use spin/spinOnce to update). + * \param[in] cloud the input data representing the RGB point cloud + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + template void + addRGBImage (const pcl::PointCloud &cloud, + const std::string &layer_id = "rgb_image", double opacity = 1.0); + + /** \brief Show a 2D image (float) on screen. + * \param[in] data the input data representing the image in float format + * \param[in] width the width of the image + * \param[in] height the height of the image + * \param[in] min_value filter all values in the image to be larger than this minimum value + * \param[in] max_value filter all values in the image to be smaller than this maximum value + * \param[in] grayscale show data as grayscale (true) or not (false). Default: false + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + showFloatImage (const float* data, unsigned int width, unsigned int height, + float min_value = std::numeric_limits::min (), + float max_value = std::numeric_limits::max (), bool grayscale = false, + const std::string &layer_id = "float_image", double opacity = 1.0); + + /** \brief Add a float 2D image layer, but do not render it (use spin/spinOnce to update). + * \param[in] data the input data representing the image in float format + * \param[in] width the width of the image + * \param[in] height the height of the image + * \param[in] min_value filter all values in the image to be larger than this minimum value + * \param[in] max_value filter all values in the image to be smaller than this maximum value + * \param[in] grayscale show data as grayscale (true) or not (false). Default: false + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + addFloatImage (const float* data, unsigned int width, unsigned int height, + float min_value = std::numeric_limits::min (), + float max_value = std::numeric_limits::max (), bool grayscale = false, + const std::string &layer_id = "float_image", double opacity = 1.0); + + /** \brief Show a 2D image (unsigned short) on screen. + * \param[in] short_image the input data representing the image in unsigned short format + * \param[in] width the width of the image + * \param[in] height the height of the image + * \param[in] min_value filter all values in the image to be larger than this minimum value + * \param[in] max_value filter all values in the image to be smaller than this maximum value + * \param[in] grayscale show data as grayscale (true) or not (false). Default: false + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + showShortImage (const unsigned short* short_image, unsigned int width, unsigned int height, + unsigned short min_value = std::numeric_limits::min (), + unsigned short max_value = std::numeric_limits::max (), bool grayscale = false, + const std::string &layer_id = "short_image", double opacity = 1.0); + + /** \brief Add a short 2D image layer, but do not render it (use spin/spinOnce to update). + * \param[in] short_image the input data representing the image in unsigned short format + * \param[in] width the width of the image + * \param[in] height the height of the image + * \param[in] min_value filter all values in the image to be larger than this minimum value + * \param[in] max_value filter all values in the image to be smaller than this maximum value + * \param[in] grayscale show data as grayscale (true) or not (false). Default: false + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + addShortImage (const unsigned short* short_image, unsigned int width, unsigned int height, + unsigned short min_value = std::numeric_limits::min (), + unsigned short max_value = std::numeric_limits::max (), bool grayscale = false, + const std::string &layer_id = "short_image", double opacity = 1.0); + + /** \brief Show a 2D image on screen representing angle data. + * \param[in] data the input data representing the image + * \param[in] width the width of the image + * \param[in] height the height of the image + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + showAngleImage (const float* data, unsigned width, unsigned height, + const std::string &layer_id = "angle_image", double opacity = 1.0); + + /** \brief Add an angle 2D image layer, but do not render it (use spin/spinOnce to update). + * \param[in] data the input data representing the image + * \param[in] width the width of the image + * \param[in] height the height of the image + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + addAngleImage (const float* data, unsigned width, unsigned height, + const std::string &layer_id = "angle_image", double opacity = 1.0); + + /** \brief Show a 2D image on screen representing half angle data. + * \param[in] data the input data representing the image + * \param[in] width the width of the image + * \param[in] height the height of the image + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + showHalfAngleImage (const float* data, unsigned width, unsigned height, + const std::string &layer_id = "half_angle_image", double opacity = 1.0); + + /** \brief Add a half angle 2D image layer, but do not render it (use spin/spinOnce to update). + * \param[in] data the input data representing the image + * \param[in] width the width of the image + * \param[in] height the height of the image + * \param[in] layer_id the name of the layer (default: "image") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + addHalfAngleImage (const float* data, unsigned width, unsigned height, + const std::string &layer_id = "half_angle_image", double opacity = 1.0); + + /** \brief Sets the pixel at coordinates(u,v) to color while setting the neighborhood to another + * \param[in] u the u/x coordinate of the pixel + * \param[in] v the v/y coordinate of the pixel + * \param[in] fg_color the pixel color + * \param[in] bg_color the neighborhood color + * \param[in] radius the circle radius around the pixel + * \param[in] layer_id the name of the layer (default: "points") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + markPoint (size_t u, size_t v, Vector3ub fg_color, Vector3ub bg_color = red_color, double radius = 3.0, + const std::string &layer_id = "points", double opacity = 1.0); + + /** \brief Sets the pixel at coordinates(u,v) to color while setting the neighborhood to another + * \param[in] uv the u/x, v/y coordinate of the pixels to be marked + * \param[in] fg_color the pixel color + * \param[in] bg_color the neighborhood color + * \param[in] size edge of the square surrounding each pixel + * \param[in] layer_id the name of the layer (default: "markers") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + markPoints (const std::vector& uv, Vector3ub fg_color, Vector3ub bg_color = red_color, double size = 3.0, + const std::string &layer_id = "markers", double opacity = 1.0); + + /** \brief Sets the pixel at coordinates(u,v) to color while setting the neighborhood to another (float coordinates version). + * \param[in] uv the u/x, v/y coordinate of the pixels to be marked + * \param[in] fg_color the pixel color + * \param[in] bg_color the neighborhood color + * \param[in] size edge of the square surrounding each pixel + * \param[in] layer_id the name of the layer (default: "markers") + * \param[in] opacity the opacity of the layer (default: 1.0) + */ + void + markPoints (const std::vector& uv, Vector3ub fg_color, Vector3ub bg_color = red_color, double size = 3.0, + const std::string &layer_id = "markers", double opacity = 1.0); + + /** \brief Set the window title name + * \param[in] name the window title + */ + void + setWindowTitle (const std::string& name); + + /** \brief Spin method. Calls the interactor and runs an internal loop. */ + void + spin (); + + /** \brief Spin once method. Calls the interactor and updates the screen once. + * \param[in] time - How long (in ms) should the visualization loop be allowed to run. + * \param[in] force_redraw - if false it might return without doing anything if the + * interactor's framerate does not require a redraw yet. + */ + void + spinOnce (int time = 1, bool force_redraw = true); + + /** \brief Register a callback function for keyboard events + * \param[in] callback the function that will be registered as a callback for a keyboard event + * \param[in] cookie user data that is passed to the callback + * \return a connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerKeyboardCallback (void (*callback) (const pcl::visualization::KeyboardEvent&, void*), + void* cookie = NULL) + { + return (registerKeyboardCallback (boost::bind (callback, _1, cookie))); + } + + /** \brief Register a callback function for keyboard events + * \param[in] callback the member function that will be registered as a callback for a keyboard event + * \param[in] instance instance to the class that implements the callback function + * \param[in] cookie user data that is passed to the callback + * \return a connection object that allows to disconnect the callback function. + */ + template boost::signals2::connection + registerKeyboardCallback (void (T::*callback) (const pcl::visualization::KeyboardEvent&, void*), + T& instance, void* cookie = NULL) + { + return (registerKeyboardCallback (boost::bind (callback, boost::ref (instance), _1, cookie))); + } + + /** \brief Register a callback boost::function for keyboard events + * \param[in] cb the boost function that will be registered as a callback for a keyboard event + * \return a connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerKeyboardCallback (boost::function cb); + + /** \brief Register a callback boost::function for mouse events + * \param[in] callback the function that will be registered as a callback for a mouse event + * \param[in] cookie user data that is passed to the callback + * \return a connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerMouseCallback (void (*callback) (const pcl::visualization::MouseEvent&, void*), + void* cookie = NULL) + { + return (registerMouseCallback (boost::bind (callback, _1, cookie))); + } + + /** \brief Register a callback function for mouse events + * \param[in] callback the member function that will be registered as a callback for a mouse event + * \param[in] instance instance to the class that implements the callback function + * \param[in] cookie user data that is passed to the callback + * \return a connection object that allows to disconnect the callback function. + */ + template boost::signals2::connection + registerMouseCallback (void (T::*callback) (const pcl::visualization::MouseEvent&, void*), + T& instance, void* cookie = NULL) + { + return (registerMouseCallback (boost::bind (callback, boost::ref (instance), _1, cookie))); + } + + /** \brief Register a callback function for mouse events + * \param[in] cb the boost function that will be registered as a callback for a mouse event + * \return a connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerMouseCallback (boost::function cb); + + /** \brief Set the position in screen coordinates. + * \param[in] x where to move the window to (X) + * \param[in] y where to move the window to (Y) + */ + void + setPosition (int x, int y); + + /** \brief Set the window size in screen coordinates. + * \param[in] xw window size in horizontal (pixels) + * \param[in] yw window size in vertical (pixels) + */ + void + setSize (int xw, int yw); + + /** \brief Return the window size in pixels. */ + int* + getSize (); + + /** \brief Returns true when the user tried to close the window */ + bool + wasStopped () const { return (stopped_); } + + /** \brief Stop the interaction and close the visualizaton window. */ + void + close () + { + stopped_ = true; + // This tends to close the window... +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + interactor_->stopLoop (); +#else + interactor_->TerminateApp (); +#endif + } + + /** \brief Add a circle shape from a point and a radius + * \param[in] x the x coordinate of the circle center + * \param[in] y the y coordinate of the circle center + * \param[in] radius the radius of the circle + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + bool + addCircle (unsigned int x, unsigned int y, double radius, + const std::string &layer_id = "circles", double opacity = 1.0); + + /** \brief Add a circle shape from a point and a radius + * \param[in] x the x coordinate of the circle center + * \param[in] y the y coordinate of the circle center + * \param[in] radius the radius of the circle + * \param[in] r the red channel of the color that the sphere should be rendered with (0.0 -> 1.0) + * \param[in] g the green channel of the color that the sphere should be rendered with (0.0 -> 1.0) + * \param[in] b the blue channel of the color that the sphere should be rendered with (0.0 -> 1.0) + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + bool + addCircle (unsigned int x, unsigned int y, double radius, + double r, double g, double b, + const std::string &layer_id = "circles", double opacity = 1.0); + + /** \brief Add a 2D box and color its edges with a given color + * \param[in] min_pt the X,Y min coordinate + * \param[in] max_pt the X,Y max coordinate + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + bool + addRectangle (const pcl::PointXY &min_pt, const pcl::PointXY &max_pt, + const std::string &layer_id = "rectangles", double opacity = 1.0); + + /** \brief Add a 2D box and color its edges with a given color + * \param[in] min_pt the X,Y min coordinate + * \param[in] max_pt the X,Y max coordinate + * \param[in] r the red channel of the color that the box should be rendered with (0.0 -> 1.0) + * \param[in] g the green channel of the color that the box should be rendered with (0.0 -> 1.0) + * \param[in] b the blue channel of the color that the box should be rendered with (0.0 -> 1.0) + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + bool + addRectangle (const pcl::PointXY &min_pt, const pcl::PointXY &max_pt, + double r, double g, double b, + const std::string &layer_id = "rectangles", double opacity = 1.0); + + /** \brief Add a 2D box and color its edges with a given color + * \param[in] x_min the X min coordinate + * \param[in] x_max the X max coordinate + * \param[in] y_min the Y min coordinate + * \param[in] y_max the Y max coordinate + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + bool + addRectangle (unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max, + const std::string &layer_id = "rectangles", double opacity = 1.0); + + /** \brief Add a 2D box and color its edges with a given color + * \param[in] x_min the X min coordinate + * \param[in] x_max the X max coordinate + * \param[in] y_min the Y min coordinate + * \param[in] y_max the Y max coordinate + * \param[in] r the red channel of the color that the box should be rendered with (0.0 -> 1.0) + * \param[in] g the green channel of the color that the box should be rendered with (0.0 -> 1.0) + * \param[in] b the blue channel of the color that the box should be rendered with (0.0 -> 1.0) + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + bool + addRectangle (unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max, + double r, double g, double b, + const std::string &layer_id = "rectangles", double opacity = 1.0); + + /** \brief Add a 2D box and color its edges with a given color + * \param[in] image the organized point cloud dataset containing the image data + * \param[in] min_pt the X,Y min coordinate + * \param[in] max_pt the X,Y max coordinate + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + template bool + addRectangle (const typename pcl::PointCloud::ConstPtr &image, + const T &min_pt, const T &max_pt, + const std::string &layer_id = "rectangles", double opacity = 1.0); + + /** \brief Add a 2D box and color its edges with a given color + * \param[in] image the organized point cloud dataset containing the image data + * \param[in] min_pt the X,Y min coordinate + * \param[in] max_pt the X,Y max coordinate + * \param[in] r the red channel of the color that the box should be rendered with (0.0 -> 1.0) + * \param[in] g the green channel of the color that the box should be rendered with (0.0 -> 1.0) + * \param[in] b the blue channel of the color that the box should be rendered with (0.0 -> 1.0) + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + template bool + addRectangle (const typename pcl::PointCloud::ConstPtr &image, + const T &min_pt, const T &max_pt, + double r, double g, double b, + const std::string &layer_id = "rectangles", double opacity = 1.0); + + /** \brief Add a 2D box that contains a given image mask and color its edges + * \param[in] image the organized point cloud dataset containing the image data + * \param[in] mask the point data representing the mask that we want to draw + * \param[in] r the red channel of the color that the mask should be rendered with + * \param[in] g the green channel of the color that the mask should be rendered with + * \param[in] b the blue channel of the color that the mask should be rendered with + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + template bool + addRectangle (const typename pcl::PointCloud::ConstPtr &image, const pcl::PointCloud &mask, + double r, double g, double b, + const std::string &layer_id = "rectangles", double opacity = 1.0); + + /** \brief Add a 2D box that contains a given image mask and color its edges in red + * \param[in] image the organized point cloud dataset containing the image data + * \param[in] mask the point data representing the mask that we want to draw + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + template bool + addRectangle (const typename pcl::PointCloud::ConstPtr &image, const pcl::PointCloud &mask, + const std::string &layer_id = "image_mask", double opacity = 1.0); + + /** \brief Add a 2D box and fill it in with a given color + * \param[in] x_min the X min coordinate + * \param[in] x_max the X max coordinate + * \param[in] y_min the Y min coordinate + * \param[in] y_max the Y max coordinate + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 0.5) + */ + bool + addFilledRectangle (unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max, + const std::string &layer_id = "boxes", double opacity = 0.5); + + /** \brief Add a 2D box and fill it in with a given color + * \param[in] x_min the X min coordinate + * \param[in] x_max the X max coordinate + * \param[in] y_min the Y min coordinate + * \param[in] y_max the Y max coordinate + * \param[in] r the red channel of the color that the box should be rendered with (0.0 -> 1.0) + * \param[in] g the green channel of the color that the box should be rendered with (0.0 -> 1.0) + * \param[in] b the blue channel of the color that the box should be rendered with (0.0 -> 1.0) + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 0.5) + */ + bool + addFilledRectangle (unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max, + double r, double g, double b, + const std::string &layer_id = "boxes", double opacity = 0.5); + + /** \brief Add a 2D line with a given color + * \param[in] x_min the X min coordinate + * \param[in] y_min the Y min coordinate + * \param[in] x_max the X max coordinate + * \param[in] y_max the Y max coordinate + * \param[in] r the red channel of the color that the line should be rendered with (0.0 -> 1.0) + * \param[in] g the green channel of the color that the line should be rendered with (0.0 -> 1.0) + * \param[in] b the blue channel of the color that the line should be rendered with (0.0 -> 1.0) + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + bool + addLine (unsigned int x_min, unsigned int y_min, unsigned int x_max, unsigned int y_max, + double r, double g, double b, + const std::string &layer_id = "line", double opacity = 1.0); + + /** \brief Add a 2D line with a given color + * \param[in] x_min the X min coordinate + * \param[in] y_min the Y min coordinate + * \param[in] x_max the X max coordinate + * \param[in] y_max the Y max coordinate + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + bool + addLine (unsigned int x_min, unsigned int y_min, unsigned int x_max, unsigned int y_max, + const std::string &layer_id = "line", double opacity = 1.0); + + /** \brief Add a 2D text with a given color + * \param[in] x the X coordinate + * \param[in] y the Y coordinate + * \param[in] text the text string to be displayed + * \param[in] r the red channel of the color that the line should be rendered with (0.0 -> 1.0) + * \param[in] g the green channel of the color that the line should be rendered with (0.0 -> 1.0) + * \param[in] b the blue channel of the color that the line should be rendered with (0.0 -> 1.0) + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + bool + addText (unsigned int x, unsigned int y, const std::string& text, + double r, double g, double b, + const std::string &layer_id = "line", double opacity = 1.0); + + /** \brief Add a 2D text with a given color + * \param[in] x the X coordinate + * \param[in] y the Y coordinate + * \param[in] text the text string to be displayed + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + bool + addText (unsigned int x, unsigned int y, const std::string& text, + const std::string &layer_id = "line", double opacity = 1.0); + + /** \brief Add a generic 2D mask to an image + * \param[in] image the organized point cloud dataset containing the image data + * \param[in] mask the point data representing the mask that we want to draw + * \param[in] r the red channel of the color that the mask should be rendered with + * \param[in] g the green channel of the color that the mask should be rendered with + * \param[in] b the blue channel of the color that the mask should be rendered with + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 0.5) + */ + template bool + addMask (const typename pcl::PointCloud::ConstPtr &image, const pcl::PointCloud &mask, + double r, double g, double b, + const std::string &layer_id = "image_mask", double opacity = 0.5); + + /** \brief Add a generic 2D mask to an image (colored in red) + * \param[in] image the organized point cloud dataset containing the image data + * \param[in] mask the point data representing the mask that we want to draw + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 0.5) + */ + template bool + addMask (const typename pcl::PointCloud::ConstPtr &image, const pcl::PointCloud &mask, + const std::string &layer_id = "image_mask", double opacity = 0.5); + + /** \brief Add a generic 2D planar polygon to an image + * \param[in] image the organized point cloud dataset containing the image data + * \param[in] polygon the point data representing the polygon that we want to draw. + * A line will be drawn from each point to the next in the dataset. + * \param[in] r the red channel of the color that the polygon should be rendered with + * \param[in] g the green channel of the color that the polygon should be rendered with + * \param[in] b the blue channel of the color that the polygon should be rendered with + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + template bool + addPlanarPolygon (const typename pcl::PointCloud::ConstPtr &image, const pcl::PlanarPolygon &polygon, + double r, double g, double b, + const std::string &layer_id = "planar_polygon", double opacity = 1.0); + + /** \brief Add a generic 2D planar polygon to an image + * \param[in] image the organized point cloud dataset containing the image data + * \param[in] polygon the point data representing the polygon that we want to draw. + * A line will be drawn from each point to the next in the dataset. + * \param[in] layer_id the 2D layer ID where we want the extra information to be drawn. + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 1.0) + */ + template bool + addPlanarPolygon (const typename pcl::PointCloud::ConstPtr &image, const pcl::PlanarPolygon &polygon, + const std::string &layer_id = "planar_polygon", double opacity = 1.0); + + /** \brief Add a new 2D rendering layer to the viewer. + * \param[in] layer_id the name of the layer + * \param[in] width the width of the layer + * \param[in] height the height of the layer + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 0.5) + */ + bool + addLayer (const std::string &layer_id, int width, int height, double opacity = 0.5); + + /** \brief Remove a 2D layer given by its ID. + * \param[in] layer_id the name of the layer + */ + void + removeLayer (const std::string &layer_id); + + /** \brief Add the specified correspondences to the display. + * \param[in] source_img The source RGB image + * \param[in] target_img The target RGB image + * \param[in] correspondences The list of correspondences to display. + * \param[in] nth display only the Nth correspondence (e.g., skip the rest) + * \param[in] layer_id the layer id (default: "correspondences") + */ + template bool + showCorrespondences (const pcl::PointCloud &source_img, + const pcl::PointCloud &target_img, + const pcl::Correspondences &correspondences, + int nth = 1, + const std::string &layer_id = "correspondences"); + + protected: + /** \brief Trigger a render call. */ + void + render (); + + /** \brief Convert the Intensity information in a PointCloud to an unsigned char array + * \param[in] cloud the input cloud containing the grayscale intensity information + * \param[out] data a boost shared array of unsigned char type + * \note The method assumes that the data array has already been allocated and + * contains enough space to copy all the data from cloud! + */ + void + convertIntensityCloudToUChar (const pcl::PointCloud &cloud, + boost::shared_array data); + + /** \brief Convert the Intensity8u information in a PointCloud to an unsigned char array + * \param[in] cloud the input cloud containing the grayscale intensity information + * \param[out] data a boost shared array of unsigned char type + * \note The method assumes that the data array has already been allocated and + * contains enough space to copy all the data from cloud! + */ + void + convertIntensityCloud8uToUChar (const pcl::PointCloud &cloud, + boost::shared_array data); + + /** \brief Convert the RGB information in a PointCloud to an unsigned char array + * \param[in] cloud the input cloud containing the RGB information + * \param[out] data a boost shared array of unsigned char type + * \note The method assumes that the data array has already been allocated and + * contains enough space to copy all the data from cloud! + */ + template void + convertRGBCloudToUChar (const pcl::PointCloud &cloud, + boost::shared_array &data); + + /** \brief Set the stopped flag back to false */ + void + resetStoppedFlag () { stopped_ = false; } + + /** \brief Fire up a mouse event with a specified event ID + * \param[in] event_id the id of the event + */ + void + emitMouseEvent (unsigned long event_id); + + /** \brief Fire up a keyboard event with a specified event ID + * \param[in] event_id the id of the event + */ + void + emitKeyboardEvent (unsigned long event_id); + + // Callbacks used to register for vtk command + static void + MouseCallback (vtkObject*, unsigned long eid, void* clientdata, void *calldata); + static void + KeyboardCallback (vtkObject*, unsigned long eid, void* clientdata, void *calldata); + + protected: // types + struct ExitMainLoopTimerCallback : public vtkCommand + { + ExitMainLoopTimerCallback () : right_timer_id (), window () {} + + static ExitMainLoopTimerCallback* New () + { + return (new ExitMainLoopTimerCallback); + } + virtual void + Execute (vtkObject* vtkNotUsed (caller), unsigned long event_id, void* call_data) + { + if (event_id != vtkCommand::TimerEvent) + return; + int timer_id = *static_cast (call_data); + if (timer_id != right_timer_id) + return; +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + window->interactor_->stopLoop (); +#else + window->interactor_->TerminateApp (); +#endif + } + int right_timer_id; + ImageViewer* window; + }; + struct ExitCallback : public vtkCommand + { + ExitCallback () : window () {} + + static ExitCallback* New () + { + return (new ExitCallback); + } + virtual void + Execute (vtkObject*, unsigned long event_id, void*) + { + if (event_id != vtkCommand::ExitEvent) + return; + window->stopped_ = true; +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + window->interactor_->stopLoop (); +#else + window->interactor_->TerminateApp (); +#endif + } + ImageViewer* window; + }; + + private: + /** \brief Internal structure describing a layer. */ + struct Layer + { + Layer () : actor (), layer_name () {} + vtkSmartPointer actor; + std::string layer_name; + }; + + typedef std::vector LayerMap; + + /** \brief Add a new 2D rendering layer to the viewer. + * \param[in] layer_id the name of the layer + * \param[in] width the width of the layer + * \param[in] height the height of the layer + * \param[in] opacity the opacity of the layer: 0 for invisible, 1 for opaque. (default: 0.5) + * \param[in] fill_box set to true to fill in the image with one black box before starting + */ + LayerMap::iterator + createLayer (const std::string &layer_id, int width, int height, double opacity = 0.5, bool fill_box = true); + + boost::signals2::signal mouse_signal_; + boost::signals2::signal keyboard_signal_; + +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + vtkSmartPointer interactor_; +#else + vtkSmartPointer interactor_; +#endif + vtkSmartPointer mouse_command_; + vtkSmartPointer keyboard_command_; + + /** \brief Callback object enabling us to leave the main loop, when a timer fires. */ + vtkSmartPointer exit_main_loop_timer_callback_; + vtkSmartPointer exit_callback_; + + /** \brief The ImageViewer widget. */ + vtkSmartPointer image_viewer_; + + /** \brief The render window. */ + vtkSmartPointer win_; + + /** \brief The renderer. */ + vtkSmartPointer ren_; + +#if !((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10)) + /** \brief Global prop. This is the actual "actor". */ + vtkSmartPointer slice_; +#endif + /** \brief The interactor style. */ + vtkSmartPointer interactor_style_; + + /** \brief The data array representing the image. Used internally. */ + boost::shared_array data_; + + /** \brief The data array (representing the image) size. Used internally. */ + size_t data_size_; + + /** \brief Set to false if the interaction loop is running. */ + bool stopped_; + + /** \brief Global timer ID. Used in destructor only. */ + int timer_id_; + + // /** \brief Internal blender used to overlay 2D geometry over the image. */ + // vtkSmartPointer blend_; + + /** \brief Internal list with different 2D layers shapes. */ + LayerMap layer_map_; + + /** \brief Image reslice, used for flipping the image. */ + vtkSmartPointer algo_; + + /** \brief Internal data array. Used everytime add***Image is called. + * Cleared, everytime the render loop is executed. + */ + std::vector image_data_; + + struct LayerComparator + { + LayerComparator (const std::string &str) : str_ (str) {} + const std::string &str_; + + bool + operator () (const Layer &layer) + { + return (layer.layer_name == str_); + } + }; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + } +} + +#include + +#endif /* __IMAGE_VISUALIZER_H__ */ + diff --git a/pcl-1.7/pcl/visualization/impl/histogram_visualizer.hpp b/pcl-1.7/pcl/visualization/impl/histogram_visualizer.hpp new file mode 100644 index 0000000..939abdf --- /dev/null +++ b/pcl-1.7/pcl/visualization/impl/histogram_visualizer.hpp @@ -0,0 +1,218 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_PCL_HISTOGRAM_VISUALIZER_IMPL_H_ +#define PCL_PCL_HISTOGRAM_VISUALIZER_IMPL_H_ + +#include + +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLHistogramVisualizer::addFeatureHistogram ( + const pcl::PointCloud &cloud, int hsize, + const std::string &id, int win_width, int win_height) +{ + RenWinInteractMap::iterator am_it = wins_.find (id); + if (am_it != wins_.end ()) + { + PCL_WARN ("[addFeatureHistogram] A window with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + return (false); + } + + vtkSmartPointer xy_array = vtkSmartPointer::New (); + xy_array->SetNumberOfComponents (2); + xy_array->SetNumberOfTuples (hsize); + + // Parse the cloud data and store it in the array + double xy[2]; + for (int d = 0; d < hsize; ++d) + { + xy[0] = d; + xy[1] = cloud.points[0].histogram[d]; + xy_array->SetTuple (d, xy); + } + RenWinInteract renwinint; + createActor (xy_array, renwinint, id, win_width, win_height); + + // Save the pointer/ID pair to the global window map + wins_[id] = renwinint; +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + resetStoppedFlag (); +#endif + return (true); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLHistogramVisualizer::addFeatureHistogram ( + const pcl::PointCloud &cloud, + const std::string &field_name, + const int index, + const std::string &id, int win_width, int win_height) +{ + if (index < 0 || index >= cloud.points.size ()) + { + PCL_ERROR ("[addFeatureHistogram] Invalid point index (%d) given!\n", index); + return (false); + } + + // Get the fields present in this cloud + std::vector fields; + // Check if our field exists + int field_idx = pcl::getFieldIndex (cloud, field_name, fields); + if (field_idx == -1) + { + PCL_ERROR ("[addFeatureHistogram] The specified field <%s> does not exist!\n", field_name.c_str ()); + return (false); + } + + RenWinInteractMap::iterator am_it = wins_.find (id); + if (am_it != wins_.end ()) + { + PCL_WARN ("[addFeatureHistogram] A window with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + return (false); + } + + vtkSmartPointer xy_array = vtkSmartPointer::New (); + xy_array->SetNumberOfComponents (2); + xy_array->SetNumberOfTuples (fields[field_idx].count); + + // Parse the cloud data and store it in the array + double xy[2]; + for (uint32_t d = 0; d < fields[field_idx].count; ++d) + { + xy[0] = d; + //xy[1] = cloud.points[index].histogram[d]; + float data; + memcpy (&data, reinterpret_cast (&cloud.points[index]) + fields[field_idx].offset + d * sizeof (float), sizeof (float)); + xy[1] = data; + xy_array->SetTuple (d, xy); + } + RenWinInteract renwinint; + createActor (xy_array, renwinint, id, win_width, win_height); + + // Save the pointer/ID pair to the global window map + wins_[id] = renwinint; +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + resetStoppedFlag (); +#endif + return (true); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLHistogramVisualizer::updateFeatureHistogram ( + const pcl::PointCloud &cloud, int hsize, + const std::string &id) +{ + RenWinInteractMap::iterator am_it = wins_.find (id); + if (am_it == wins_.end ()) + { + PCL_WARN ("[updateFeatureHistogram] A window with id <%s> does not exists!.\n", id.c_str ()); + return (false); + } + RenWinInteract* renwinupd = &wins_[id]; + + vtkSmartPointer xy_array = vtkSmartPointer::New (); + xy_array->SetNumberOfComponents (2); + xy_array->SetNumberOfTuples (hsize); + + // Parse the cloud data and store it in the array + double xy[2]; + for (int d = 0; d < hsize; ++d) + { + xy[0] = d; + xy[1] = cloud.points[0].histogram[d]; + xy_array->SetTuple (d, xy); + } + reCreateActor (xy_array, renwinupd, hsize); + return (true); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLHistogramVisualizer::updateFeatureHistogram ( + const pcl::PointCloud &cloud, const std::string &field_name, const int index, + const std::string &id) +{ + if (index < 0 || index >= cloud.points.size ()) + { + PCL_ERROR ("[updateFeatureHistogram] Invalid point index (%d) given!\n", index); + return (false); + } + + // Get the fields present in this cloud + std::vector fields; + // Check if our field exists + int field_idx = pcl::getFieldIndex (cloud, field_name, fields); + if (field_idx == -1) + { + PCL_ERROR ("[updateFeatureHistogram] The specified field <%s> does not exist!\n", field_name.c_str ()); + return (false); + } + + RenWinInteractMap::iterator am_it = wins_.find (id); + if (am_it == wins_.end ()) + { + PCL_WARN ("[updateFeatureHistogram] A window with id <%s> does not exists!.\n", id.c_str ()); + return (false); + } + RenWinInteract* renwinupd = &wins_[id]; + + vtkSmartPointer xy_array = vtkSmartPointer::New (); + xy_array->SetNumberOfComponents (2); + xy_array->SetNumberOfTuples (fields[field_idx].count); + + // Parse the cloud data and store it in the array + double xy[2]; + for (uint32_t d = 0; d < fields[field_idx].count; ++d) + { + xy[0] = d; + //xy[1] = cloud.points[index].histogram[d]; + float data; + memcpy (&data, reinterpret_cast (&cloud.points[index]) + fields[field_idx].offset + d * sizeof (float), sizeof (float)); + xy[1] = data; + xy_array->SetTuple (d, xy); + } + + reCreateActor (xy_array, renwinupd, cloud.fields[field_idx].count - 1); + return (true); +} + +#endif + diff --git a/pcl-1.7/pcl/visualization/impl/image_viewer.hpp b/pcl-1.7/pcl/visualization/impl/image_viewer.hpp new file mode 100644 index 0000000..5f2ed77 --- /dev/null +++ b/pcl-1.7/pcl/visualization/impl/image_viewer.hpp @@ -0,0 +1,497 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_VISUALIZATION_IMAGE_VISUALIZER_HPP_ +#define PCL_VISUALIZATION_IMAGE_VISUALIZER_HPP_ + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::visualization::ImageViewer::convertRGBCloudToUChar ( + const pcl::PointCloud &cloud, + boost::shared_array &data) +{ + int j = 0; + for (size_t i = 0; i < cloud.points.size (); ++i) + { + data[j++] = cloud.points[i].r; + data[j++] = cloud.points[i].g; + data[j++] = cloud.points[i].b; + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::visualization::ImageViewer::addRGBImage (const pcl::PointCloud &cloud, + const std::string &layer_id, + double opacity) +{ + if (data_size_ < cloud.width * cloud.height) + { + data_size_ = cloud.width * cloud.height * 3; + data_.reset (new unsigned char[data_size_]); + } + + convertRGBCloudToUChar (cloud, data_); + + return (addRGBImage (data_.get (), cloud.width, cloud.height, layer_id, opacity)); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::visualization::ImageViewer::showRGBImage (const pcl::PointCloud &cloud, + const std::string &layer_id, + double opacity) +{ + addRGBImage (cloud, layer_id, opacity); + render (); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::ImageViewer::addMask ( + const typename pcl::PointCloud::ConstPtr &image, + const pcl::PointCloud &mask, + double r, double g, double b, + const std::string &layer_id, double opacity) +{ + // We assume that the data passed into image is organized, otherwise this doesn't make sense + if (!image->isOrganized ()) + return (false); + + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id)); + if (am_it == layer_map_.end ()) + { + PCL_DEBUG ("[pcl::visualization::ImageViewer::addMask] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ()); + am_it = createLayer (layer_id, getSize ()[0] - 1, getSize ()[1] - 1, opacity, true); + } + + // Construct a search object to get the camera parameters + pcl::search::OrganizedNeighbor search; + search.setInputCloud (image); + std::vector xy; + xy.reserve (mask.size () * 2); + const float image_height_f = static_cast (image->height); + for (size_t i = 0; i < mask.size (); ++i) + { + pcl::PointXY p_projected; + search.projectPoint (mask[i], p_projected); + + xy.push_back (p_projected.x); + #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10)) + xy.push_back (image_height_f - p_projected.y); + #else + xy.push_back (p_projected.y); + #endif + } + + vtkSmartPointer points = vtkSmartPointer::New (); + points->setColors (static_cast (r*255.0), + static_cast (g*255.0), + static_cast (b*255.0)); + points->setOpacity (opacity); + am_it->actor->GetScene ()->AddItem (points); + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::ImageViewer::addMask ( + const typename pcl::PointCloud::ConstPtr &image, + const pcl::PointCloud &mask, + const std::string &layer_id, double opacity) +{ + return (addMask (image, mask, 1.0, 0.0, 0.0, layer_id, opacity)); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::ImageViewer::addPlanarPolygon ( + const typename pcl::PointCloud::ConstPtr &image, + const pcl::PlanarPolygon &polygon, + double r, double g, double b, + const std::string &layer_id, double opacity) +{ + // We assume that the data passed into image is organized, otherwise this doesn't make sense + if (!image->isOrganized ()) + return (false); + + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id)); + if (am_it == layer_map_.end ()) + { + PCL_DEBUG ("[pcl::visualization::ImageViewer::addPlanarPolygon] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ()); + am_it = createLayer (layer_id, getSize ()[0] - 1, getSize ()[1] - 1, opacity, true); + } + + // Construct a search object to get the camera parameters and fill points + pcl::search::OrganizedNeighbor search; + search.setInputCloud (image); + const float image_height_f = static_cast (image->height); + std::vector xy; + xy.reserve ((polygon.getContour ().size () + 1) * 2); + for (size_t i = 0; i < polygon.getContour ().size (); ++i) + { + pcl::PointXY p; + search.projectPoint (polygon.getContour ()[i], p); + xy.push_back (p.x); + #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10)) + xy.push_back (image_height_f - p.y); + #else + xy.push_back (p.y); + #endif + } + + // Close the polygon + xy[xy.size () - 2] = xy[0]; + xy[xy.size () - 1] = xy[1]; + + vtkSmartPointer poly = vtkSmartPointer::New (); + poly->setColors (static_cast (r * 255.0), + static_cast (g * 255.0), + static_cast (b * 255.0)); + poly->set (xy); + am_it->actor->GetScene ()->AddItem (poly); + + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::ImageViewer::addPlanarPolygon ( + const typename pcl::PointCloud::ConstPtr &image, + const pcl::PlanarPolygon &polygon, + const std::string &layer_id, double opacity) +{ + return (addPlanarPolygon (image, polygon, 1.0, 0.0, 0.0, layer_id, opacity)); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::ImageViewer::addRectangle ( + const typename pcl::PointCloud::ConstPtr &image, + const T &min_pt, + const T &max_pt, + double r, double g, double b, + const std::string &layer_id, double opacity) +{ + // We assume that the data passed into image is organized, otherwise this doesn't make sense + if (!image->isOrganized ()) + return (false); + + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id)); + if (am_it == layer_map_.end ()) + { + PCL_DEBUG ("[pcl::visualization::ImageViewer::addRectangle] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ()); + am_it = createLayer (layer_id, getSize ()[0] - 1, getSize ()[1] - 1, opacity, true); + } + + // Construct a search object to get the camera parameters + pcl::search::OrganizedNeighbor search; + search.setInputCloud (image); + // Project the 8 corners + T p1, p2, p3, p4, p5, p6, p7, p8; + p1.x = min_pt.x; p1.y = min_pt.y; p1.z = min_pt.z; + p2.x = min_pt.x; p2.y = min_pt.y; p2.z = max_pt.z; + p3.x = min_pt.x; p3.y = max_pt.y; p3.z = min_pt.z; + p4.x = min_pt.x; p4.y = max_pt.y; p4.z = max_pt.z; + p5.x = max_pt.x; p5.y = min_pt.y; p5.z = min_pt.z; + p6.x = max_pt.x; p6.y = min_pt.y; p6.z = max_pt.z; + p7.x = max_pt.x; p7.y = max_pt.y; p7.z = min_pt.z; + p8.x = max_pt.x; p8.y = max_pt.y; p8.z = max_pt.z; + + std::vector pp_2d (8); + search.projectPoint (p1, pp_2d[0]); + search.projectPoint (p2, pp_2d[1]); + search.projectPoint (p3, pp_2d[2]); + search.projectPoint (p4, pp_2d[3]); + search.projectPoint (p5, pp_2d[4]); + search.projectPoint (p6, pp_2d[5]); + search.projectPoint (p7, pp_2d[6]); + search.projectPoint (p8, pp_2d[7]); + + pcl::PointXY min_pt_2d, max_pt_2d; + min_pt_2d.x = min_pt_2d.y = std::numeric_limits::max (); + max_pt_2d.x = max_pt_2d.y = -std::numeric_limits::max (); + // Search for the two extrema + for (size_t i = 0; i < pp_2d.size (); ++i) + { + if (pp_2d[i].x < min_pt_2d.x) min_pt_2d.x = pp_2d[i].x; + if (pp_2d[i].y < min_pt_2d.y) min_pt_2d.y = pp_2d[i].y; + if (pp_2d[i].x > max_pt_2d.x) max_pt_2d.x = pp_2d[i].x; + if (pp_2d[i].y > max_pt_2d.y) max_pt_2d.y = pp_2d[i].y; + } +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 7)) + min_pt_2d.y = float (image->height) - min_pt_2d.y; + max_pt_2d.y = float (image->height) - max_pt_2d.y; +#endif + + vtkSmartPointer rect = vtkSmartPointer::New (); + rect->setColors (static_cast (255.0 * r), + static_cast (255.0 * g), + static_cast (255.0 * b)); + rect->setOpacity (opacity); + rect->set (min_pt_2d.x, min_pt_2d.y, max_pt_2d.x, max_pt_2d.y); + am_it->actor->GetScene ()->AddItem (rect); + + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::ImageViewer::addRectangle ( + const typename pcl::PointCloud::ConstPtr &image, + const T &min_pt, + const T &max_pt, + const std::string &layer_id, double opacity) +{ + return (addRectangle (image, min_pt, max_pt, 0.0, 1.0, 0.0, layer_id, opacity)); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::ImageViewer::addRectangle ( + const typename pcl::PointCloud::ConstPtr &image, + const pcl::PointCloud &mask, + double r, double g, double b, + const std::string &layer_id, double opacity) +{ + // We assume that the data passed into image is organized, otherwise this doesn't make sense + if (!image->isOrganized ()) + return (false); + + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id)); + if (am_it == layer_map_.end ()) + { + PCL_DEBUG ("[pcl::visualization::ImageViewer::addRectangle] No layer with ID'=%s' found. Creating new one...\n", layer_id.c_str ()); + am_it = createLayer (layer_id, getSize ()[0] - 1, getSize ()[1] - 1, opacity, true); + } + + // Construct a search object to get the camera parameters + pcl::search::OrganizedNeighbor search; + search.setInputCloud (image); + std::vector pp_2d (mask.points.size ()); + for (size_t i = 0; i < mask.points.size (); ++i) + search.projectPoint (mask.points[i], pp_2d[i]); + + pcl::PointXY min_pt_2d, max_pt_2d; + min_pt_2d.x = min_pt_2d.y = std::numeric_limits::max (); + max_pt_2d.x = max_pt_2d.y = -std::numeric_limits::max (); + // Search for the two extrema + for (size_t i = 0; i < pp_2d.size (); ++i) + { + if (pp_2d[i].x < min_pt_2d.x) min_pt_2d.x = pp_2d[i].x; + if (pp_2d[i].y < min_pt_2d.y) min_pt_2d.y = pp_2d[i].y; + if (pp_2d[i].x > max_pt_2d.x) max_pt_2d.x = pp_2d[i].x; + if (pp_2d[i].y > max_pt_2d.y) max_pt_2d.y = pp_2d[i].y; + } +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 7)) + min_pt_2d.y = float (image->height) - min_pt_2d.y; + max_pt_2d.y = float (image->height) - max_pt_2d.y; +#endif + + vtkSmartPointer rect = vtkSmartPointer::New (); + rect->setColors (static_cast (255.0 * r), + static_cast (255.0 * g), + static_cast (255.0 * b)); + rect->setOpacity (opacity); + rect->set (min_pt_2d.x, min_pt_2d.y, max_pt_2d.x, max_pt_2d.y); + am_it->actor->GetScene ()->AddItem (rect); + + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::ImageViewer::addRectangle ( + const typename pcl::PointCloud::ConstPtr &image, + const pcl::PointCloud &mask, + const std::string &layer_id, double opacity) +{ + return (addRectangle (image, mask, 0.0, 1.0, 0.0, layer_id, opacity)); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::ImageViewer::showCorrespondences ( + const pcl::PointCloud &source_img, + const pcl::PointCloud &target_img, + const pcl::Correspondences &correspondences, + int nth, + const std::string &layer_id) +{ + if (correspondences.empty ()) + { + PCL_DEBUG ("[pcl::visualization::ImageViewer::addCorrespondences] An empty set of correspondences given! Nothing to display.\n"); + return (false); + } + + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + LayerMap::iterator am_it = std::find_if (layer_map_.begin (), layer_map_.end (), LayerComparator (layer_id)); + if (am_it == layer_map_.end ()) + { + PCL_DEBUG ("[pcl::visualization::ImageViewer::addCorrespondences] No layer with ID='%s' found. Creating new one...\n", layer_id.c_str ()); + am_it = createLayer (layer_id, source_img.width + target_img.width, std::max (source_img.height, target_img.height), 1.0, false); + } + + int src_size = source_img.width * source_img.height * 3; + int tgt_size = target_img.width * target_img.height * 3; + + // Set window size + setSize (source_img.width + target_img.width , std::max (source_img.height, target_img.height)); + + // Set data size + if (data_size_ < static_cast (src_size + tgt_size)) + { + data_size_ = src_size + tgt_size; + data_.reset (new unsigned char[data_size_]); + } + + // Copy data in VTK format + int j = 0; + for (size_t i = 0; i < std::max (source_img.height, target_img.height); ++i) + { + // Still need to copy the source? + if (i < source_img.height) + { + for (size_t k = 0; k < source_img.width; ++k) + { + data_[j++] = source_img[i * source_img.width + k].r; + data_[j++] = source_img[i * source_img.width + k].g; + data_[j++] = source_img[i * source_img.width + k].b; + } + } + else + { + memcpy (&data_[j], 0, source_img.width * 3); + j += source_img.width * 3; + } + + // Still need to copy the target? + if (i < source_img.height) + { + for (size_t k = 0; k < target_img.width; ++k) + { + data_[j++] = target_img[i * source_img.width + k].r; + data_[j++] = target_img[i * source_img.width + k].g; + data_[j++] = target_img[i * source_img.width + k].b; + } + } + else + { + memcpy (&data_[j], 0, target_img.width * 3); + j += target_img.width * 3; + } + } + + void* data = const_cast (reinterpret_cast (data_.get ())); + + vtkSmartPointer image = vtkSmartPointer::New (); + image->SetDimensions (source_img.width + target_img.width, std::max (source_img.height, target_img.height), 1); +#if VTK_MAJOR_VERSION < 6 + image->SetScalarTypeToUnsignedChar (); + image->SetNumberOfScalarComponents (3); + image->AllocateScalars (); +#else + image->AllocateScalars (VTK_UNSIGNED_CHAR, 3); +#endif + image->GetPointData ()->GetScalars ()->SetVoidArray (data, data_size_, 1); + vtkSmartPointer image_item = vtkSmartPointer::New (); +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 10)) + // Now create filter and set previously created transformation + algo_->SetInput (image); + algo_->Update (); + image_item->set (0, 0, algo_->GetOutput ()); +#else + image_item->set (0, 0, image); + interactor_style_->adjustCamera (image, ren_); +#endif + am_it->actor->GetScene ()->AddItem (image_item); + image_viewer_->SetSize (image->GetDimensions ()[0], image->GetDimensions ()[1]); + + // Draw lines between the best corresponding points + for (size_t i = 0; i < correspondences.size (); i += nth) + { + double r, g, b; + getRandomColors (r, g, b); + unsigned char u_r = static_cast (255.0 * r); + unsigned char u_g = static_cast (255.0 * g); + unsigned char u_b = static_cast (255.0 * b); + vtkSmartPointer query_circle = vtkSmartPointer::New (); + query_circle->setColors (u_r, u_g, u_b); + vtkSmartPointer match_circle = vtkSmartPointer::New (); + match_circle->setColors (u_r, u_g, u_b); + vtkSmartPointer line = vtkSmartPointer::New (); + line->setColors (u_r, u_g, u_b); + + float query_x = correspondences[i].index_query % source_img.width; + float match_x = correspondences[i].index_match % target_img.width + source_img.width; +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION > 10)) + float query_y = correspondences[i].index_query / source_img.width; + float match_y = correspondences[i].index_match / target_img.width; +#else + float query_y = getSize ()[1] - correspondences[i].index_query / source_img.width; + float match_y = getSize ()[1] - correspondences[i].index_match / target_img.width; +#endif + + query_circle->set (query_x, query_y, 3.0); + match_circle->set (match_x, match_y, 3.0); + line->set (query_x, query_y, match_x, match_y); + + am_it->actor->GetScene ()->AddItem (query_circle); + am_it->actor->GetScene ()->AddItem (match_circle); + am_it->actor->GetScene ()->AddItem (line); + } + + return (true); +} + +#endif // PCL_VISUALIZATION_IMAGE_VISUALIZER_HPP_ diff --git a/pcl-1.7/pcl/visualization/impl/pcl_plotter.hpp b/pcl-1.7/pcl/visualization/impl/pcl_plotter.hpp new file mode 100644 index 0000000..1d2d451 --- /dev/null +++ b/pcl-1.7/pcl/visualization/impl/pcl_plotter.hpp @@ -0,0 +1,102 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_VISUALUALIZATION_PCL_PLOTTER_IMPL_H_ +#define PCL_VISUALUALIZATION_PCL_PLOTTER_IMPL_H_ + +template bool +pcl::visualization::PCLPlotter::addFeatureHistogram ( + const pcl::PointCloud &cloud, int hsize, + const std::string &id, int win_width, int win_height) +{ + std::vector array_x(hsize), array_y(hsize); + + // Parse the cloud data and store it in the array + for (int i = 0; i < hsize; ++i) + { + array_x[i] = i; + array_y[i] = cloud.points[0].histogram[i]; + } + + this->addPlotData(array_x, array_y, id.c_str(), vtkChart::LINE); + setWindowSize (win_width, win_height); + return true; +} + + +template bool +pcl::visualization::PCLPlotter::addFeatureHistogram ( + const pcl::PointCloud &cloud, + const std::string &field_name, + const int index, + const std::string &id, int win_width, int win_height) +{ + if (index < 0 || index >= cloud.points.size ()) + { + PCL_ERROR ("[addFeatureHistogram] Invalid point index (%d) given!\n", index); + return (false); + } + + // Get the fields present in this cloud + std::vector fields; + // Check if our field exists + int field_idx = pcl::getFieldIndex (cloud, field_name, fields); + if (field_idx == -1) + { + PCL_ERROR ("[addFeatureHistogram] The specified field <%s> does not exist!\n", field_name.c_str ()); + return (false); + } + + int hsize = fields[field_idx].count; + std::vector array_x (hsize), array_y (hsize); + + for (int i = 0; i < hsize; ++i) + { + array_x[i] = i; + float data; + // TODO: replace float with the real data type + memcpy (&data, reinterpret_cast (&cloud.points[index]) + fields[field_idx].offset + i * sizeof (float), sizeof (float)); + array_y[i] = data; + } + + this->addPlotData(array_x, array_y, id.c_str(), vtkChart::LINE); + setWindowSize (win_width, win_height); + return (true); +} + +#endif /* PCL_VISUALUALIZATION_PCL_PLOTTER_IMPL_H_ */ + diff --git a/pcl-1.7/pcl/visualization/impl/pcl_visualizer.hpp b/pcl-1.7/pcl/visualization/impl/pcl_visualizer.hpp new file mode 100644 index 0000000..219e865 --- /dev/null +++ b/pcl-1.7/pcl/visualization/impl/pcl_visualizer.hpp @@ -0,0 +1,1862 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_PCL_VISUALIZER_IMPL_H_ +#define PCL_PCL_VISUALIZER_IMPL_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addPointCloud ( + const typename pcl::PointCloud::ConstPtr &cloud, + const std::string &id, int viewport) +{ + // Convert the PointCloud to VTK PolyData + PointCloudGeometryHandlerXYZ geometry_handler (cloud); + return (addPointCloud (cloud, geometry_handler, id, viewport)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addPointCloud ( + const typename pcl::PointCloud::ConstPtr &cloud, + const PointCloudGeometryHandler &geometry_handler, + const std::string &id, int viewport) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + CloudActorMap::iterator am_it = cloud_actor_map_->find (id); + + if (am_it != cloud_actor_map_->end ()) + { + PCL_WARN ("[addPointCloud] A PointCloud with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + return (false); + } + + //PointCloudColorHandlerRandom color_handler (cloud); + PointCloudColorHandlerCustom color_handler (cloud, 255, 255, 255); + return (fromHandlersToScreen (geometry_handler, color_handler, id, viewport, cloud->sensor_origin_, cloud->sensor_orientation_)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addPointCloud ( + const typename pcl::PointCloud::ConstPtr &cloud, + const GeometryHandlerConstPtr &geometry_handler, + const std::string &id, int viewport) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + CloudActorMap::iterator am_it = cloud_actor_map_->find (id); + + if (am_it != cloud_actor_map_->end ()) + { + // Here we're just pushing the handlers onto the queue. If needed, something fancier could + // be done such as checking if a specific handler already exists, etc. + am_it->second.geometry_handlers.push_back (geometry_handler); + return (true); + } + + //PointCloudColorHandlerRandom color_handler (cloud); + PointCloudColorHandlerCustom color_handler (cloud, 255, 255, 255); + return (fromHandlersToScreen (geometry_handler, color_handler, id, viewport, cloud->sensor_origin_, cloud->sensor_orientation_)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addPointCloud ( + const typename pcl::PointCloud::ConstPtr &cloud, + const PointCloudColorHandler &color_handler, + const std::string &id, int viewport) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + CloudActorMap::iterator am_it = cloud_actor_map_->find (id); + + if (am_it != cloud_actor_map_->end ()) + { + PCL_WARN ("[addPointCloud] A PointCloud with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + + // Here we're just pushing the handlers onto the queue. If needed, something fancier could + // be done such as checking if a specific handler already exists, etc. + //cloud_actor_map_[id].color_handlers.push_back (color_handler); + //style_->setCloudActorMap (boost::make_shared (cloud_actor_map_)); + return (false); + } + // Convert the PointCloud to VTK PolyData + PointCloudGeometryHandlerXYZ geometry_handler (cloud); + return (fromHandlersToScreen (geometry_handler, color_handler, id, viewport, cloud->sensor_origin_, cloud->sensor_orientation_)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addPointCloud ( + const typename pcl::PointCloud::ConstPtr &cloud, + const ColorHandlerConstPtr &color_handler, + const std::string &id, int viewport) +{ + // Check to see if this entry already exists (has it been already added to the visualizer?) + CloudActorMap::iterator am_it = cloud_actor_map_->find (id); + if (am_it != cloud_actor_map_->end ()) + { + // Here we're just pushing the handlers onto the queue. If needed, something fancier could + // be done such as checking if a specific handler already exists, etc. + am_it->second.color_handlers.push_back (color_handler); + return (true); + } + + PointCloudGeometryHandlerXYZ geometry_handler (cloud); + return (fromHandlersToScreen (geometry_handler, color_handler, id, viewport, cloud->sensor_origin_, cloud->sensor_orientation_)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addPointCloud ( + const typename pcl::PointCloud::ConstPtr &cloud, + const GeometryHandlerConstPtr &geometry_handler, + const ColorHandlerConstPtr &color_handler, + const std::string &id, int viewport) +{ + // Check to see if this entry already exists (has it been already added to the visualizer?) + CloudActorMap::iterator am_it = cloud_actor_map_->find (id); + if (am_it != cloud_actor_map_->end ()) + { + // Here we're just pushing the handlers onto the queue. If needed, something fancier could + // be done such as checking if a specific handler already exists, etc. + am_it->second.geometry_handlers.push_back (geometry_handler); + am_it->second.color_handlers.push_back (color_handler); + return (true); + } + return (fromHandlersToScreen (geometry_handler, color_handler, id, viewport, cloud->sensor_origin_, cloud->sensor_orientation_)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addPointCloud ( + const typename pcl::PointCloud::ConstPtr &cloud, + const PointCloudColorHandler &color_handler, + const PointCloudGeometryHandler &geometry_handler, + const std::string &id, int viewport) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + CloudActorMap::iterator am_it = cloud_actor_map_->find (id); + + if (am_it != cloud_actor_map_->end ()) + { + PCL_WARN ("[addPointCloud] A PointCloud with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + // Here we're just pushing the handlers onto the queue. If needed, something fancier could + // be done such as checking if a specific handler already exists, etc. + //cloud_actor_map_[id].geometry_handlers.push_back (geometry_handler); + //cloud_actor_map_[id].color_handlers.push_back (color_handler); + //style_->setCloudActorMap (boost::make_shared (cloud_actor_map_)); + return (false); + } + return (fromHandlersToScreen (geometry_handler, color_handler, id, viewport, cloud->sensor_origin_, cloud->sensor_orientation_)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::visualization::PCLVisualizer::convertPointCloudToVTKPolyData ( + const typename pcl::PointCloud::ConstPtr &cloud, + vtkSmartPointer &polydata, + vtkSmartPointer &initcells) +{ + vtkSmartPointer vertices; + if (!polydata) + { + allocVtkPolyData (polydata); + vertices = vtkSmartPointer::New (); + polydata->SetVerts (vertices); + } + + // Create the supporting structures + vertices = polydata->GetVerts (); + if (!vertices) + vertices = vtkSmartPointer::New (); + + vtkIdType nr_points = cloud->points.size (); + // Create the point set + vtkSmartPointer points = polydata->GetPoints (); + if (!points) + { + points = vtkSmartPointer::New (); + points->SetDataTypeToFloat (); + polydata->SetPoints (points); + } + points->SetNumberOfPoints (nr_points); + + // Get a pointer to the beginning of the data array + float *data = (static_cast (points->GetData ()))->GetPointer (0); + + // Set the points + if (cloud->is_dense) + { + for (vtkIdType i = 0; i < nr_points; ++i) + memcpy (&data[i * 3], &cloud->points[i].x, 12); // sizeof (float) * 3 + } + else + { + vtkIdType j = 0; // true point index + for (vtkIdType i = 0; i < nr_points; ++i) + { + // Check if the point is invalid + if (!pcl_isfinite (cloud->points[i].x) || + !pcl_isfinite (cloud->points[i].y) || + !pcl_isfinite (cloud->points[i].z)) + continue; + + memcpy (&data[j * 3], &cloud->points[i].x, 12); // sizeof (float) * 3 + j++; + } + nr_points = j; + points->SetNumberOfPoints (nr_points); + } + + vtkSmartPointer cells = vertices->GetData (); + updateCells (cells, initcells, nr_points); + + // Set the cells and the vertices + vertices->SetCells (nr_points, cells); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::visualization::PCLVisualizer::convertPointCloudToVTKPolyData ( + const pcl::visualization::PointCloudGeometryHandler &geometry_handler, + vtkSmartPointer &polydata, + vtkSmartPointer &initcells) +{ + vtkSmartPointer vertices; + if (!polydata) + { + allocVtkPolyData (polydata); + vertices = vtkSmartPointer::New (); + polydata->SetVerts (vertices); + } + + // Use the handler to obtain the geometry + vtkSmartPointer points; + geometry_handler.getGeometry (points); + polydata->SetPoints (points); + + vtkIdType nr_points = points->GetNumberOfPoints (); + + // Create the supporting structures + vertices = polydata->GetVerts (); + if (!vertices) + vertices = vtkSmartPointer::New (); + + vtkSmartPointer cells = vertices->GetData (); + updateCells (cells, initcells, nr_points); + // Set the cells and the vertices + vertices->SetCells (nr_points, cells); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addPolygon ( + const typename pcl::PointCloud::ConstPtr &cloud, + double r, double g, double b, const std::string &id, int viewport) +{ + vtkSmartPointer data = createPolygon (cloud); + if (!data) + return (false); + + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + ShapeActorMap::iterator am_it = shape_actor_map_->find (id); + if (am_it != shape_actor_map_->end ()) + { + vtkSmartPointer all_data = vtkSmartPointer::New (); + + // Add old data +#if VTK_MAJOR_VERSION < 6 + all_data->AddInput (reinterpret_cast ((vtkActor::SafeDownCast (am_it->second))->GetMapper ())->GetInput ()); +#else + all_data->AddInputData (reinterpret_cast ((vtkActor::SafeDownCast (am_it->second))->GetMapper ())->GetInput ()); +#endif + + // Add new data + vtkSmartPointer surface_filter = vtkSmartPointer::New (); +#if VTK_MAJOR_VERSION < 6 + surface_filter->AddInput (vtkUnstructuredGrid::SafeDownCast (data)); +#else + surface_filter->AddInputData (vtkUnstructuredGrid::SafeDownCast (data)); +#endif + vtkSmartPointer poly_data = surface_filter->GetOutput (); +#if VTK_MAJOR_VERSION < 6 + all_data->AddInput (poly_data); +#else + all_data->AddInputData (poly_data); +#endif + + // Create an Actor + vtkSmartPointer actor; + createActorFromVTKDataSet (all_data->GetOutput (), actor); + actor->GetProperty ()->SetRepresentationToWireframe (); + actor->GetProperty ()->SetColor (r, g, b); + actor->GetMapper ()->ScalarVisibilityOff (); + removeActorFromRenderer (am_it->second, viewport); + addActorToRenderer (actor, viewport); + + // Save the pointer/ID pair to the global actor map + (*shape_actor_map_)[id] = actor; + } + else + { + // Create an Actor + vtkSmartPointer actor; + createActorFromVTKDataSet (data, actor); + actor->GetProperty ()->SetRepresentationToWireframe (); + actor->GetProperty ()->SetColor (r, g, b); + actor->GetMapper ()->ScalarVisibilityOff (); + addActorToRenderer (actor, viewport); + + // Save the pointer/ID pair to the global actor map + (*shape_actor_map_)[id] = actor; + } + + return (true); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addPolygon ( + const pcl::PlanarPolygon &polygon, + double r, double g, double b, const std::string &id, int viewport) +{ + vtkSmartPointer data = createPolygon (polygon); + if (!data) + return (false); + + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + ShapeActorMap::iterator am_it = shape_actor_map_->find (id); + if (am_it != shape_actor_map_->end ()) + { + vtkSmartPointer all_data = vtkSmartPointer::New (); + + // Add old data +#if VTK_MAJOR_VERSION < 6 + all_data->AddInput (reinterpret_cast ((vtkActor::SafeDownCast (am_it->second))->GetMapper ())->GetInput ()); +#else + all_data->AddInputData (reinterpret_cast ((vtkActor::SafeDownCast (am_it->second))->GetMapper ())->GetInput ()); +#endif + + // Add new data + vtkSmartPointer surface_filter = vtkSmartPointer::New (); +#if VTK_MAJOR_VERSION < 6 + surface_filter->SetInput (vtkUnstructuredGrid::SafeDownCast (data)); +#else + surface_filter->SetInputData (vtkUnstructuredGrid::SafeDownCast (data)); +#endif + vtkSmartPointer poly_data = surface_filter->GetOutput (); +#if VTK_MAJOR_VERSION < 6 + all_data->AddInput (poly_data); +#else + all_data->AddInputData (poly_data); +#endif + + // Create an Actor + vtkSmartPointer actor; + createActorFromVTKDataSet (all_data->GetOutput (), actor); + actor->GetProperty ()->SetRepresentationToWireframe (); + actor->GetProperty ()->SetColor (r, g, b); + actor->GetMapper ()->ScalarVisibilityOn (); + actor->GetProperty ()->BackfaceCullingOff (); + removeActorFromRenderer (am_it->second, viewport); + addActorToRenderer (actor, viewport); + + // Save the pointer/ID pair to the global actor map + (*shape_actor_map_)[id] = actor; + } + else + { + // Create an Actor + vtkSmartPointer actor; + createActorFromVTKDataSet (data, actor); + actor->GetProperty ()->SetRepresentationToWireframe (); + actor->GetProperty ()->SetColor (r, g, b); + actor->GetMapper ()->ScalarVisibilityOn (); + actor->GetProperty ()->BackfaceCullingOff (); + addActorToRenderer (actor, viewport); + + // Save the pointer/ID pair to the global actor map + (*shape_actor_map_)[id] = actor; + } + return (true); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addPolygon ( + const typename pcl::PointCloud::ConstPtr &cloud, + const std::string &id, int viewport) +{ + return (!addPolygon (cloud, 0.5, 0.5, 0.5, id, viewport)); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addLine (const P1 &pt1, const P2 &pt2, double r, double g, double b, const std::string &id, int viewport) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + ShapeActorMap::iterator am_it = shape_actor_map_->find (id); + if (am_it != shape_actor_map_->end ()) + { + PCL_WARN ("[addLine] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + return (false); + } + + vtkSmartPointer data = createLine (pt1.getVector4fMap (), pt2.getVector4fMap ()); + + // Create an Actor + vtkSmartPointer actor; + createActorFromVTKDataSet (data, actor); + actor->GetProperty ()->SetRepresentationToWireframe (); + actor->GetProperty ()->SetColor (r, g, b); + actor->GetMapper ()->ScalarVisibilityOff (); + addActorToRenderer (actor, viewport); + + // Save the pointer/ID pair to the global actor map + (*shape_actor_map_)[id] = actor; + return (true); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b, const std::string &id, int viewport) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + ShapeActorMap::iterator am_it = shape_actor_map_->find (id); + if (am_it != shape_actor_map_->end ()) + { + PCL_WARN ("[addArrow] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + return (false); + } + + // Create an Actor + vtkSmartPointer leader = vtkSmartPointer::New (); + leader->GetPositionCoordinate ()->SetCoordinateSystemToWorld (); + leader->GetPositionCoordinate ()->SetValue (pt1.x, pt1.y, pt1.z); + leader->GetPosition2Coordinate ()->SetCoordinateSystemToWorld (); + leader->GetPosition2Coordinate ()->SetValue (pt2.x, pt2.y, pt2.z); + leader->SetArrowStyleToFilled (); + leader->AutoLabelOn (); + + leader->GetProperty ()->SetColor (r, g, b); + addActorToRenderer (leader, viewport); + + // Save the pointer/ID pair to the global actor map + (*shape_actor_map_)[id] = leader; + return (true); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b, bool display_length, const std::string &id, int viewport) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + ShapeActorMap::iterator am_it = shape_actor_map_->find (id); + if (am_it != shape_actor_map_->end ()) + { + PCL_WARN ("[addArrow] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + return (false); + } + + // Create an Actor + vtkSmartPointer leader = vtkSmartPointer::New (); + leader->GetPositionCoordinate ()->SetCoordinateSystemToWorld (); + leader->GetPositionCoordinate ()->SetValue (pt1.x, pt1.y, pt1.z); + leader->GetPosition2Coordinate ()->SetCoordinateSystemToWorld (); + leader->GetPosition2Coordinate ()->SetValue (pt2.x, pt2.y, pt2.z); + leader->SetArrowStyleToFilled (); + leader->SetArrowPlacementToPoint1 (); + if (display_length) + leader->AutoLabelOn (); + else + leader->AutoLabelOff (); + + leader->GetProperty ()->SetColor (r, g, b); + addActorToRenderer (leader, viewport); + + // Save the pointer/ID pair to the global actor map + (*shape_actor_map_)[id] = leader; + return (true); +} +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addArrow (const P1 &pt1, const P2 &pt2, + double r_line, double g_line, double b_line, + double r_text, double g_text, double b_text, + const std::string &id, int viewport) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + ShapeActorMap::iterator am_it = shape_actor_map_->find (id); + if (am_it != shape_actor_map_->end ()) + { + PCL_WARN ("[addArrow] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + return (false); + } + + // Create an Actor + vtkSmartPointer leader = vtkSmartPointer::New (); + leader->GetPositionCoordinate ()->SetCoordinateSystemToWorld (); + leader->GetPositionCoordinate ()->SetValue (pt1.x, pt1.y, pt1.z); + leader->GetPosition2Coordinate ()->SetCoordinateSystemToWorld (); + leader->GetPosition2Coordinate ()->SetValue (pt2.x, pt2.y, pt2.z); + leader->SetArrowStyleToFilled (); + leader->AutoLabelOn (); + + leader->GetLabelTextProperty()->SetColor(r_text, g_text, b_text); + + leader->GetProperty ()->SetColor (r_line, g_line, b_line); + addActorToRenderer (leader, viewport); + + // Save the pointer/ID pair to the global actor map + (*shape_actor_map_)[id] = leader; + return (true); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addLine (const P1 &pt1, const P2 &pt2, const std::string &id, int viewport) +{ + return (!addLine (pt1, pt2, 0.5, 0.5, 0.5, id, viewport)); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addSphere (const PointT ¢er, double radius, double r, double g, double b, const std::string &id, int viewport) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + ShapeActorMap::iterator am_it = shape_actor_map_->find (id); + if (am_it != shape_actor_map_->end ()) + { + PCL_WARN ("[addSphere] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + return (false); + } + + vtkSmartPointer data = vtkSmartPointer::New (); + data->SetRadius (radius); + data->SetCenter (double (center.x), double (center.y), double (center.z)); + data->SetPhiResolution (10); + data->SetThetaResolution (10); + data->LatLongTessellationOff (); + data->Update (); + + // Setup actor and mapper + vtkSmartPointer mapper = vtkSmartPointer::New (); + mapper->SetInputConnection (data->GetOutputPort ()); + + // Create an Actor + vtkSmartPointer actor = vtkSmartPointer::New (); + actor->SetMapper (mapper); + //createActorFromVTKDataSet (data, actor); + actor->GetProperty ()->SetRepresentationToSurface (); + actor->GetProperty ()->SetInterpolationToFlat (); + actor->GetProperty ()->SetColor (r, g, b); + actor->GetMapper ()->ImmediateModeRenderingOn (); + actor->GetMapper ()->StaticOn (); + actor->GetMapper ()->ScalarVisibilityOff (); + actor->GetMapper ()->Update (); + addActorToRenderer (actor, viewport); + + // Save the pointer/ID pair to the global actor map + (*shape_actor_map_)[id] = actor; + return (true); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addSphere (const PointT ¢er, double radius, const std::string &id, int viewport) +{ + return (addSphere (center, radius, 0.5, 0.5, 0.5, id, viewport)); +} + +//////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::updateSphere (const PointT ¢er, double radius, double r, double g, double b, const std::string &id) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + ShapeActorMap::iterator am_it = shape_actor_map_->find (id); + if (am_it == shape_actor_map_->end ()) + return (false); + + ////////////////////////////////////////////////////////////////////////// + // Get the actor pointer + vtkLODActor* actor = vtkLODActor::SafeDownCast (am_it->second); +#if VTK_MAJOR_VERSION < 6 + vtkAlgorithm *algo = actor->GetMapper ()->GetInput ()->GetProducerPort ()->GetProducer (); +#else + vtkAlgorithm *algo = actor->GetMapper ()->GetInputAlgorithm (); +#endif + vtkSphereSource *src = vtkSphereSource::SafeDownCast (algo); + + src->SetCenter (double (center.x), double (center.y), double (center.z)); + src->SetRadius (radius); + src->Update (); + actor->GetProperty ()->SetColor (r, g, b); + actor->Modified (); + + return (true); +} + +////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addText3D ( + const std::string &text, + const PointT& position, + double textScale, + double r, + double g, + double b, + const std::string &id, + int viewport) +{ + std::string tid; + if (id.empty ()) + tid = text; + else + tid = id; + + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + ShapeActorMap::iterator am_it = shape_actor_map_->find (tid); + if (am_it != shape_actor_map_->end ()) + { + pcl::console::print_warn (stderr, "[addText3d] A text with id <%s> already exists! Please choose a different id and retry.\n", tid.c_str ()); + return (false); + } + + vtkSmartPointer textSource = vtkSmartPointer::New (); + textSource->SetText (text.c_str()); + textSource->Update (); + + vtkSmartPointer textMapper = vtkSmartPointer::New (); + textMapper->SetInputConnection (textSource->GetOutputPort ()); + + // Since each follower may follow a different camera, we need different followers + rens_->InitTraversal (); + vtkRenderer* renderer = NULL; + int i = 1; + while ((renderer = rens_->GetNextItem ()) != NULL) + { + // Should we add the actor to all renderers or just to i-nth renderer? + if (viewport == 0 || viewport == i) + { + vtkSmartPointer textActor = vtkSmartPointer::New (); + textActor->SetMapper (textMapper); + textActor->SetPosition (position.x, position.y, position.z); + textActor->SetScale (textScale); + textActor->GetProperty ()->SetColor (r, g, b); + textActor->SetCamera (renderer->GetActiveCamera ()); + + renderer->AddActor (textActor); + renderer->Render (); + + // Save the pointer/ID pair to the global actor map. If we are saving multiple vtkFollowers + // for multiple viewport + std::string alternate_tid = tid; + alternate_tid.append(i, '*'); + + (*shape_actor_map_)[(viewport == 0) ? tid : alternate_tid] = textActor; + } + + ++i; + } + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addPointCloudNormals ( + const typename pcl::PointCloud::ConstPtr &cloud, + int level, float scale, const std::string &id, int viewport) +{ + return (addPointCloudNormals (cloud, cloud, level, scale, id, viewport)); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addPointCloudNormals ( + const typename pcl::PointCloud::ConstPtr &cloud, + const typename pcl::PointCloud::ConstPtr &normals, + int level, float scale, + const std::string &id, int viewport) +{ + if (normals->points.size () != cloud->points.size ()) + { + PCL_ERROR ("[addPointCloudNormals] The number of points differs from the number of normals!\n"); + return (false); + } + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + CloudActorMap::iterator am_it = cloud_actor_map_->find (id); + + if (am_it != cloud_actor_map_->end ()) + { + PCL_WARN ("[addPointCloudNormals] A PointCloud with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + return (false); + } + + vtkSmartPointer points = vtkSmartPointer::New(); + vtkSmartPointer lines = vtkSmartPointer::New(); + + points->SetDataTypeToFloat (); + vtkSmartPointer data = vtkSmartPointer::New (); + data->SetNumberOfComponents (3); + + + vtkIdType nr_normals = 0; + float* pts = 0; + + // If the cloud is organized, then distribute the normal step in both directions + if (cloud->isOrganized () && normals->isOrganized ()) + { + vtkIdType point_step = static_cast (sqrt (double (level))); + nr_normals = (static_cast ((cloud->width - 1)/ point_step) + 1) * + (static_cast ((cloud->height - 1) / point_step) + 1); + pts = new float[2 * nr_normals * 3]; + + vtkIdType cell_count = 0; + for (vtkIdType y = 0; y < normals->height; y += point_step) + for (vtkIdType x = 0; x < normals->width; x += point_step) + { + PointT p = (*cloud)(x, y); + p.x += (*normals)(x, y).normal[0] * scale; + p.y += (*normals)(x, y).normal[1] * scale; + p.z += (*normals)(x, y).normal[2] * scale; + + pts[2 * cell_count * 3 + 0] = (*cloud)(x, y).x; + pts[2 * cell_count * 3 + 1] = (*cloud)(x, y).y; + pts[2 * cell_count * 3 + 2] = (*cloud)(x, y).z; + pts[2 * cell_count * 3 + 3] = p.x; + pts[2 * cell_count * 3 + 4] = p.y; + pts[2 * cell_count * 3 + 5] = p.z; + + lines->InsertNextCell (2); + lines->InsertCellPoint (2 * cell_count); + lines->InsertCellPoint (2 * cell_count + 1); + cell_count ++; + } + } + else + { + nr_normals = (cloud->points.size () - 1) / level + 1 ; + pts = new float[2 * nr_normals * 3]; + + for (vtkIdType i = 0, j = 0; j < nr_normals; j++, i = j * level) + { + PointT p = cloud->points[i]; + p.x += normals->points[i].normal[0] * scale; + p.y += normals->points[i].normal[1] * scale; + p.z += normals->points[i].normal[2] * scale; + + pts[2 * j * 3 + 0] = cloud->points[i].x; + pts[2 * j * 3 + 1] = cloud->points[i].y; + pts[2 * j * 3 + 2] = cloud->points[i].z; + pts[2 * j * 3 + 3] = p.x; + pts[2 * j * 3 + 4] = p.y; + pts[2 * j * 3 + 5] = p.z; + + lines->InsertNextCell (2); + lines->InsertCellPoint (2 * j); + lines->InsertCellPoint (2 * j + 1); + } + } + + data->SetArray (&pts[0], 2 * nr_normals * 3, 0); + points->SetData (data); + + vtkSmartPointer polyData = vtkSmartPointer::New(); + polyData->SetPoints (points); + polyData->SetLines (lines); + + vtkSmartPointer mapper = vtkSmartPointer::New (); +#if VTK_MAJOR_VERSION < 6 + mapper->SetInput (polyData); +#else + mapper->SetInputData (polyData); +#endif + mapper->SetColorModeToMapScalars(); + mapper->SetScalarModeToUsePointData(); + + // create actor + vtkSmartPointer actor = vtkSmartPointer::New (); + actor->SetMapper (mapper); + + // Add it to all renderers + addActorToRenderer (actor, viewport); + + // Save the pointer/ID pair to the global actor map + (*cloud_actor_map_)[id].actor = actor; + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addPointCloudIntensityGradients ( + const typename pcl::PointCloud::ConstPtr &cloud, + const typename pcl::PointCloud::ConstPtr &gradients, + int level, double scale, + const std::string &id, int viewport) +{ + if (gradients->points.size () != cloud->points.size ()) + { + PCL_ERROR ("[addPointCloudGradients] The number of points differs from the number of gradients!\n"); + return (false); + } + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + CloudActorMap::iterator am_it = cloud_actor_map_->find (id); + + if (am_it != cloud_actor_map_->end ()) + { + PCL_WARN ("[addPointCloudGradients] A PointCloud with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + return (false); + } + + vtkSmartPointer points = vtkSmartPointer::New(); + vtkSmartPointer lines = vtkSmartPointer::New(); + + points->SetDataTypeToFloat (); + vtkSmartPointer data = vtkSmartPointer::New (); + data->SetNumberOfComponents (3); + + vtkIdType nr_gradients = (cloud->points.size () - 1) / level + 1 ; + float* pts = new float[2 * nr_gradients * 3]; + + for (vtkIdType i = 0, j = 0; j < nr_gradients; j++, i = j * level) + { + PointT p = cloud->points[i]; + p.x += gradients->points[i].gradient[0] * scale; + p.y += gradients->points[i].gradient[1] * scale; + p.z += gradients->points[i].gradient[2] * scale; + + pts[2 * j * 3 + 0] = cloud->points[i].x; + pts[2 * j * 3 + 1] = cloud->points[i].y; + pts[2 * j * 3 + 2] = cloud->points[i].z; + pts[2 * j * 3 + 3] = p.x; + pts[2 * j * 3 + 4] = p.y; + pts[2 * j * 3 + 5] = p.z; + + lines->InsertNextCell(2); + lines->InsertCellPoint(2*j); + lines->InsertCellPoint(2*j+1); + } + + data->SetArray (&pts[0], 2 * nr_gradients * 3, 0); + points->SetData (data); + + vtkSmartPointer polyData = vtkSmartPointer::New(); + polyData->SetPoints(points); + polyData->SetLines(lines); + + vtkSmartPointer mapper = vtkSmartPointer::New (); +#if VTK_MAJOR_VERSION < 6 + mapper->SetInput (polyData); +#else + mapper->SetInputData (polyData); +#endif + mapper->SetColorModeToMapScalars(); + mapper->SetScalarModeToUsePointData(); + + // create actor + vtkSmartPointer actor = vtkSmartPointer::New (); + actor->SetMapper (mapper); + + // Add it to all renderers + addActorToRenderer (actor, viewport); + + // Save the pointer/ID pair to the global actor map + (*cloud_actor_map_)[id].actor = actor; + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addCorrespondences ( + const typename pcl::PointCloud::ConstPtr &source_points, + const typename pcl::PointCloud::ConstPtr &target_points, + const std::vector &correspondences, + const std::string &id, + int viewport) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + ShapeActorMap::iterator am_it = shape_actor_map_->find (id); + if (am_it != shape_actor_map_->end ()) + { + PCL_WARN ("[addCorrespondences] A set of correspondences with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + return (false); + } + + int n_corr = int (correspondences.size ()); + vtkSmartPointer line_data = vtkSmartPointer::New (); + + // Prepare colors + vtkSmartPointer line_colors = vtkSmartPointer::New (); + line_colors->SetNumberOfComponents (3); + line_colors->SetName ("Colors"); + line_colors->SetNumberOfTuples (n_corr); + unsigned char* colors = line_colors->GetPointer (0); + memset (colors, 0, line_colors->GetNumberOfTuples () * line_colors->GetNumberOfComponents ()); + pcl::RGB rgb; + // Will use random colors or RED by default + rgb.r = 255; rgb.g = rgb.b = 0; + + // Prepare coordinates + vtkSmartPointer line_points = vtkSmartPointer::New (); + line_points->SetNumberOfPoints (2 * n_corr); + + vtkSmartPointer line_cells_id = vtkSmartPointer::New (); + line_cells_id->SetNumberOfComponents (3); + line_cells_id->SetNumberOfTuples (n_corr); + vtkIdType *line_cell_id = line_cells_id->GetPointer (0); + vtkSmartPointer line_cells = vtkSmartPointer::New (); + + vtkSmartPointer line_tcoords = vtkSmartPointer::New (); + line_tcoords->SetNumberOfComponents (1); + line_tcoords->SetNumberOfTuples (n_corr * 2); + line_tcoords->SetName ("Texture Coordinates"); + + double tc[3] = {0.0, 0.0, 0.0}; + + int j = 0, idx = 0; + // Draw lines between the best corresponding points + for (int i = 0; i < n_corr; ++i) + { + const PointT &p_src = source_points->points[i]; + const PointT &p_tgt = target_points->points[correspondences[i]]; + + int id1 = j * 2 + 0, id2 = j * 2 + 1; + // Set the points + line_points->SetPoint (id1, p_src.x, p_src.y, p_src.z); + line_points->SetPoint (id2, p_tgt.x, p_tgt.y, p_tgt.z); + // Set the cell ID + *line_cell_id++ = 2; + *line_cell_id++ = id1; + *line_cell_id++ = id2; + // Set the texture coords + tc[0] = 0.; line_tcoords->SetTuple (id1, tc); + tc[0] = 1.; line_tcoords->SetTuple (id2, tc); + + getRandomColors (rgb); + colors[idx+0] = rgb.r; + colors[idx+1] = rgb.g; + colors[idx+2] = rgb.b; + } + line_colors->SetNumberOfTuples (j); + line_cells_id->SetNumberOfTuples (j); + line_cells->SetCells (n_corr, line_cells_id); + line_points->SetNumberOfPoints (j*2); + line_tcoords->SetNumberOfTuples (j*2); + + // Fill in the lines + line_data->SetPoints (line_points); + line_data->SetLines (line_cells); + line_data->GetPointData ()->SetTCoords (line_tcoords); + line_data->GetCellData ()->SetScalars (line_colors); + + // Create an Actor + vtkSmartPointer actor; + createActorFromVTKDataSet (line_data, actor); + actor->GetProperty ()->SetRepresentationToWireframe (); + actor->GetProperty ()->SetOpacity (0.5); + addActorToRenderer (actor, viewport); + + // Save the pointer/ID pair to the global actor map + (*shape_actor_map_)[id] = actor; + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addCorrespondences ( + const typename pcl::PointCloud::ConstPtr &source_points, + const typename pcl::PointCloud::ConstPtr &target_points, + const pcl::Correspondences &correspondences, + int nth, + const std::string &id, + int viewport) +{ + if (correspondences.empty ()) + { + PCL_DEBUG ("[addCorrespondences] An empty set of correspondences given! Nothing to display.\n"); + return (false); + } + + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + ShapeActorMap::iterator am_it = shape_actor_map_->find (id); + if (am_it != shape_actor_map_->end ()) + { + PCL_WARN ("[addCorrespondences] A set of correspondences with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + return (false); + } + + int n_corr = int (correspondences.size () / nth + 1); + vtkSmartPointer line_data = vtkSmartPointer::New (); + + // Prepare colors + vtkSmartPointer line_colors = vtkSmartPointer::New (); + line_colors->SetNumberOfComponents (3); + line_colors->SetName ("Colors"); + line_colors->SetNumberOfTuples (n_corr); + unsigned char* colors = line_colors->GetPointer (0); + memset (colors, 0, line_colors->GetNumberOfTuples () * line_colors->GetNumberOfComponents ()); + pcl::RGB rgb; + // Will use random colors or RED by default + rgb.r = 255; rgb.g = rgb.b = 0; + + // Prepare coordinates + vtkSmartPointer line_points = vtkSmartPointer::New (); + line_points->SetNumberOfPoints (2 * n_corr); + + vtkSmartPointer line_cells_id = vtkSmartPointer::New (); + line_cells_id->SetNumberOfComponents (3); + line_cells_id->SetNumberOfTuples (n_corr); + vtkIdType *line_cell_id = line_cells_id->GetPointer (0); + vtkSmartPointer line_cells = vtkSmartPointer::New (); + + vtkSmartPointer line_tcoords = vtkSmartPointer::New (); + line_tcoords->SetNumberOfComponents (1); + line_tcoords->SetNumberOfTuples (n_corr * 2); + line_tcoords->SetName ("Texture Coordinates"); + + double tc[3] = {0.0, 0.0, 0.0}; + + int j = 0, idx = 0; + // Draw lines between the best corresponding points + for (size_t i = 0; i < correspondences.size (); i += nth, idx = j * 3, ++j) + { + const PointT &p_src = source_points->points[correspondences[i].index_query]; + const PointT &p_tgt = target_points->points[correspondences[i].index_match]; + + int id1 = j * 2 + 0, id2 = j * 2 + 1; + // Set the points + line_points->SetPoint (id1, p_src.x, p_src.y, p_src.z); + line_points->SetPoint (id2, p_tgt.x, p_tgt.y, p_tgt.z); + // Set the cell ID + *line_cell_id++ = 2; + *line_cell_id++ = id1; + *line_cell_id++ = id2; + // Set the texture coords + tc[0] = 0.; line_tcoords->SetTuple (id1, tc); + tc[0] = 1.; line_tcoords->SetTuple (id2, tc); + + getRandomColors (rgb); + colors[idx+0] = rgb.r; + colors[idx+1] = rgb.g; + colors[idx+2] = rgb.b; + } + line_colors->SetNumberOfTuples (j); + line_cells_id->SetNumberOfTuples (j); + line_cells->SetCells (n_corr, line_cells_id); + line_points->SetNumberOfPoints (j*2); + line_tcoords->SetNumberOfTuples (j*2); + + // Fill in the lines + line_data->SetPoints (line_points); + line_data->SetLines (line_cells); + line_data->GetPointData ()->SetTCoords (line_tcoords); + line_data->GetCellData ()->SetScalars (line_colors); + + // Create an Actor + vtkSmartPointer actor; + createActorFromVTKDataSet (line_data, actor); + actor->GetProperty ()->SetRepresentationToWireframe (); + actor->GetProperty ()->SetOpacity (0.5); + addActorToRenderer (actor, viewport); + + // Save the pointer/ID pair to the global actor map + (*shape_actor_map_)[id] = actor; + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::updateCorrespondences ( + const typename pcl::PointCloud::ConstPtr &source_points, + const typename pcl::PointCloud::ConstPtr &target_points, + const pcl::Correspondences &correspondences, + int nth, + const std::string &id) +{ + if (correspondences.empty ()) + { + PCL_DEBUG ("[updateCorrespondences] An empty set of correspondences given! Nothing to display.\n"); + return (false); + } + + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + ShapeActorMap::iterator am_it = shape_actor_map_->find (id); + if (am_it == shape_actor_map_->end ()) + return (false); + + vtkSmartPointer actor = vtkLODActor::SafeDownCast (am_it->second); + vtkSmartPointer line_data = reinterpret_cast(actor->GetMapper ())->GetInput (); + + int n_corr = int (correspondences.size () / nth + 1); + + // Prepare colors + vtkSmartPointer line_colors = vtkSmartPointer::New (); + line_colors->SetNumberOfComponents (3); + line_colors->SetName ("Colors"); + line_colors->SetNumberOfTuples (n_corr); + unsigned char* colors = line_colors->GetPointer (0); + memset (colors, 0, line_colors->GetNumberOfTuples () * line_colors->GetNumberOfComponents ()); + pcl::RGB rgb; + // Will use random colors or RED by default + rgb.r = 255.0; rgb.g = rgb.b = 0.0; + + // Prepare coordinates + vtkSmartPointer line_points = vtkSmartPointer::New (); + line_points->SetNumberOfPoints (2 * n_corr); + + vtkSmartPointer line_cells_id = vtkSmartPointer::New (); + line_cells_id->SetNumberOfComponents (3); + line_cells_id->SetNumberOfTuples (n_corr); + vtkIdType *line_cell_id = line_cells_id->GetPointer (0); + vtkSmartPointer line_cells = line_data->GetLines (); + + vtkSmartPointer line_tcoords = vtkSmartPointer::New (); + line_tcoords->SetNumberOfComponents (1); + line_tcoords->SetNumberOfTuples (n_corr * 2); + line_tcoords->SetName ("Texture Coordinates"); + + double tc[3] = {0.0, 0.0, 0.0}; + + int j = 0, idx = 0; + // Draw lines between the best corresponding points + for (size_t i = 0; i < correspondences.size (); i += nth, idx = j * 3, ++j) + { + const PointT &p_src = source_points->points[correspondences[i].index_query]; + const PointT &p_tgt = target_points->points[correspondences[i].index_match]; + + int id1 = j * 2 + 0, id2 = j * 2 + 1; + // Set the points + line_points->SetPoint (id1, p_src.x, p_src.y, p_src.z); + line_points->SetPoint (id2, p_tgt.x, p_tgt.y, p_tgt.z); + // Set the cell ID + *line_cell_id++ = 2; + *line_cell_id++ = id1; + *line_cell_id++ = id2; + // Set the texture coords + tc[0] = 0.; line_tcoords->SetTuple (id1, tc); + tc[0] = 1.; line_tcoords->SetTuple (id2, tc); + + getRandomColors (rgb); + colors[idx+0] = rgb.r; + colors[idx+1] = rgb.g; + colors[idx+2] = rgb.b; + } + line_colors->SetNumberOfTuples (j); + line_cells_id->SetNumberOfTuples (j); + line_cells->SetCells (n_corr, line_cells_id); + line_points->SetNumberOfPoints (j*2); + line_tcoords->SetNumberOfTuples (j*2); + + // Fill in the lines + line_data->SetPoints (line_points); + line_data->SetLines (line_cells); + line_data->GetPointData ()->SetTCoords (line_tcoords); + line_data->GetCellData ()->SetScalars (line_colors); + + // Update the mapper +#if VTK_MAJOR_VERSION < 6 + reinterpret_cast(actor->GetMapper ())->SetInput (line_data); +#else + reinterpret_cast (actor->GetMapper ())->SetInputData (line_data); +#endif + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::fromHandlersToScreen ( + const PointCloudGeometryHandler &geometry_handler, + const PointCloudColorHandler &color_handler, + const std::string &id, + int viewport, + const Eigen::Vector4f& sensor_origin, + const Eigen::Quaternion& sensor_orientation) +{ + if (!geometry_handler.isCapable ()) + { + PCL_WARN ("[fromHandlersToScreen] PointCloud <%s> requested with an invalid geometry handler (%s)!\n", id.c_str (), geometry_handler.getName ().c_str ()); + return (false); + } + + if (!color_handler.isCapable ()) + { + PCL_WARN ("[fromHandlersToScreen] PointCloud <%s> requested with an invalid color handler (%s)!\n", id.c_str (), color_handler.getName ().c_str ()); + return (false); + } + + vtkSmartPointer polydata; + vtkSmartPointer initcells; + // Convert the PointCloud to VTK PolyData + convertPointCloudToVTKPolyData (geometry_handler, polydata, initcells); + // use the given geometry handler + + // Get the colors from the handler + bool has_colors = false; + double minmax[2]; + vtkSmartPointer scalars; + if (color_handler.getColor (scalars)) + { + polydata->GetPointData ()->SetScalars (scalars); + scalars->GetRange (minmax); + has_colors = true; + } + + // Create an Actor + vtkSmartPointer actor; + createActorFromVTKDataSet (polydata, actor); + if (has_colors) + actor->GetMapper ()->SetScalarRange (minmax); + + // Add it to all renderers + addActorToRenderer (actor, viewport); + + // Save the pointer/ID pair to the global actor map + CloudActor& cloud_actor = (*cloud_actor_map_)[id]; + cloud_actor.actor = actor; + cloud_actor.cells = initcells; + + // Save the viewpoint transformation matrix to the global actor map + vtkSmartPointer transformation = vtkSmartPointer::New(); + convertToVtkMatrix (sensor_origin, sensor_orientation, transformation); + cloud_actor.viewpoint_transformation_ = transformation; + cloud_actor.actor->SetUserMatrix (transformation); + cloud_actor.actor->Modified (); + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::fromHandlersToScreen ( + const PointCloudGeometryHandler &geometry_handler, + const ColorHandlerConstPtr &color_handler, + const std::string &id, + int viewport, + const Eigen::Vector4f& sensor_origin, + const Eigen::Quaternion& sensor_orientation) +{ + if (!geometry_handler.isCapable ()) + { + PCL_WARN ("[fromHandlersToScreen] PointCloud <%s> requested with an invalid geometry handler (%s)!\n", id.c_str (), geometry_handler.getName ().c_str ()); + return (false); + } + + if (!color_handler->isCapable ()) + { + PCL_WARN ("[fromHandlersToScreen] PointCloud <%s> requested with an invalid color handler (%s)!\n", id.c_str (), color_handler->getName ().c_str ()); + return (false); + } + + vtkSmartPointer polydata; + vtkSmartPointer initcells; + // Convert the PointCloud to VTK PolyData + convertPointCloudToVTKPolyData (geometry_handler, polydata, initcells); + // use the given geometry handler + + // Get the colors from the handler + bool has_colors = false; + double minmax[2]; + vtkSmartPointer scalars; + if (color_handler->getColor (scalars)) + { + polydata->GetPointData ()->SetScalars (scalars); + scalars->GetRange (minmax); + has_colors = true; + } + + // Create an Actor + vtkSmartPointer actor; + createActorFromVTKDataSet (polydata, actor); + if (has_colors) + actor->GetMapper ()->SetScalarRange (minmax); + + // Add it to all renderers + addActorToRenderer (actor, viewport); + + // Save the pointer/ID pair to the global actor map + CloudActor& cloud_actor = (*cloud_actor_map_)[id]; + cloud_actor.actor = actor; + cloud_actor.cells = initcells; + cloud_actor.color_handlers.push_back (color_handler); + + // Save the viewpoint transformation matrix to the global actor map + vtkSmartPointer transformation = vtkSmartPointer::New(); + convertToVtkMatrix (sensor_origin, sensor_orientation, transformation); + cloud_actor.viewpoint_transformation_ = transformation; + cloud_actor.actor->SetUserMatrix (transformation); + cloud_actor.actor->Modified (); + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::fromHandlersToScreen ( + const GeometryHandlerConstPtr &geometry_handler, + const PointCloudColorHandler &color_handler, + const std::string &id, + int viewport, + const Eigen::Vector4f& sensor_origin, + const Eigen::Quaternion& sensor_orientation) +{ + if (!geometry_handler->isCapable ()) + { + PCL_WARN ("[fromHandlersToScreen] PointCloud <%s> requested with an invalid geometry handler (%s)!\n", id.c_str (), geometry_handler->getName ().c_str ()); + return (false); + } + + if (!color_handler.isCapable ()) + { + PCL_WARN ("[fromHandlersToScreen] PointCloud <%s> requested with an invalid color handler (%s)!\n", id.c_str (), color_handler.getName ().c_str ()); + return (false); + } + + vtkSmartPointer polydata; + vtkSmartPointer initcells; + // Convert the PointCloud to VTK PolyData + convertPointCloudToVTKPolyData (geometry_handler, polydata, initcells); + // use the given geometry handler + + // Get the colors from the handler + bool has_colors = false; + double minmax[2]; + vtkSmartPointer scalars; + if (color_handler.getColor (scalars)) + { + polydata->GetPointData ()->SetScalars (scalars); + scalars->GetRange (minmax); + has_colors = true; + } + + // Create an Actor + vtkSmartPointer actor; + createActorFromVTKDataSet (polydata, actor); + if (has_colors) + actor->GetMapper ()->SetScalarRange (minmax); + + // Add it to all renderers + addActorToRenderer (actor, viewport); + + // Save the pointer/ID pair to the global actor map + CloudActor& cloud_actor = (*cloud_actor_map_)[id]; + cloud_actor.actor = actor; + cloud_actor.cells = initcells; + cloud_actor.geometry_handlers.push_back (geometry_handler); + + // Save the viewpoint transformation matrix to the global actor map + vtkSmartPointer transformation = vtkSmartPointer::New (); + convertToVtkMatrix (sensor_origin, sensor_orientation, transformation); + cloud_actor.viewpoint_transformation_ = transformation; + cloud_actor.actor->SetUserMatrix (transformation); + cloud_actor.actor->Modified (); + + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::updatePointCloud (const typename pcl::PointCloud::ConstPtr &cloud, + const std::string &id) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + CloudActorMap::iterator am_it = cloud_actor_map_->find (id); + + if (am_it == cloud_actor_map_->end ()) + return (false); + + vtkSmartPointer polydata = reinterpret_cast(am_it->second.actor->GetMapper ())->GetInput (); + // Convert the PointCloud to VTK PolyData + convertPointCloudToVTKPolyData (cloud, polydata, am_it->second.cells); + + // Set scalars to blank, since there is no way we can update them here. + vtkSmartPointer scalars; + polydata->GetPointData ()->SetScalars (scalars); + double minmax[2]; + minmax[0] = std::numeric_limits::min (); + minmax[1] = std::numeric_limits::max (); + am_it->second.actor->GetMapper ()->ImmediateModeRenderingOff (); + am_it->second.actor->GetMapper ()->SetScalarRange (minmax); + + // Update the mapper +#if VTK_MAJOR_VERSION < 6 + reinterpret_cast(am_it->second.actor->GetMapper ())->SetInput (polydata); +#else + reinterpret_cast (am_it->second.actor->GetMapper ())->SetInputData (polydata); +#endif + return (true); +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::updatePointCloud (const typename pcl::PointCloud::ConstPtr &, + const PointCloudGeometryHandler &geometry_handler, + const std::string &id) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + CloudActorMap::iterator am_it = cloud_actor_map_->find (id); + + if (am_it == cloud_actor_map_->end ()) + return (false); + + vtkSmartPointer polydata = reinterpret_cast(am_it->second.actor->GetMapper ())->GetInput (); + if (!polydata) + return (false); + // Convert the PointCloud to VTK PolyData + convertPointCloudToVTKPolyData (geometry_handler, polydata, am_it->second.cells); + + // Set scalars to blank, since there is no way we can update them here. + vtkSmartPointer scalars; + polydata->GetPointData ()->SetScalars (scalars); + double minmax[2]; + minmax[0] = std::numeric_limits::min (); + minmax[1] = std::numeric_limits::max (); + am_it->second.actor->GetMapper ()->ImmediateModeRenderingOff (); + am_it->second.actor->GetMapper ()->SetScalarRange (minmax); + + // Update the mapper +#if VTK_MAJOR_VERSION < 6 + reinterpret_cast(am_it->second.actor->GetMapper ())->SetInput (polydata); +#else + reinterpret_cast (am_it->second.actor->GetMapper ())->SetInputData (polydata); +#endif + return (true); +} + + +///////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::updatePointCloud (const typename pcl::PointCloud::ConstPtr &cloud, + const PointCloudColorHandler &color_handler, + const std::string &id) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + CloudActorMap::iterator am_it = cloud_actor_map_->find (id); + + if (am_it == cloud_actor_map_->end ()) + return (false); + + // Get the current poly data + vtkSmartPointer polydata = reinterpret_cast(am_it->second.actor->GetMapper ())->GetInput (); + if (!polydata) + return (false); + vtkSmartPointer vertices = polydata->GetVerts (); + vtkSmartPointer points = polydata->GetPoints (); + // Copy the new point array in + vtkIdType nr_points = cloud->points.size (); + points->SetNumberOfPoints (nr_points); + + // Get a pointer to the beginning of the data array + float *data = (static_cast (points->GetData ()))->GetPointer (0); + + int pts = 0; + // If the dataset is dense (no NaNs) + if (cloud->is_dense) + { + for (vtkIdType i = 0; i < nr_points; ++i, pts += 3) + memcpy (&data[pts], &cloud->points[i].x, 12); // sizeof (float) * 3 + } + else + { + vtkIdType j = 0; // true point index + for (vtkIdType i = 0; i < nr_points; ++i) + { + // Check if the point is invalid + if (!isFinite (cloud->points[i])) + continue; + + memcpy (&data[pts], &cloud->points[i].x, 12); // sizeof (float) * 3 + pts += 3; + j++; + } + nr_points = j; + points->SetNumberOfPoints (nr_points); + } + + vtkSmartPointer cells = vertices->GetData (); + updateCells (cells, am_it->second.cells, nr_points); + + // Set the cells and the vertices + vertices->SetCells (nr_points, cells); + + // Get the colors from the handler + vtkSmartPointer scalars; + color_handler.getColor (scalars); + double minmax[2]; + scalars->GetRange (minmax); + // Update the data + polydata->GetPointData ()->SetScalars (scalars); + + am_it->second.actor->GetMapper ()->ImmediateModeRenderingOff (); + am_it->second.actor->GetMapper ()->SetScalarRange (minmax); + + // Update the mapper +#if VTK_MAJOR_VERSION < 6 + reinterpret_cast(am_it->second.actor->GetMapper ())->SetInput (polydata); +#else + reinterpret_cast (am_it->second.actor->GetMapper ())->SetInputData (polydata); +#endif + return (true); +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::addPolygonMesh ( + const typename pcl::PointCloud::ConstPtr &cloud, + const std::vector &vertices, + const std::string &id, + int viewport) +{ + if (vertices.empty () || cloud->points.empty ()) + return (false); + + CloudActorMap::iterator am_it = cloud_actor_map_->find (id); + if (am_it != cloud_actor_map_->end ()) + { + pcl::console::print_warn (stderr, + "[addPolygonMesh] A shape with id <%s> already exists! Please choose a different id and retry.\n", + id.c_str ()); + return (false); + } + + int rgb_idx = -1; + std::vector fields; + vtkSmartPointer colors; + rgb_idx = pcl::getFieldIndex (*cloud, "rgb", fields); + if (rgb_idx == -1) + rgb_idx = pcl::getFieldIndex (*cloud, "rgba", fields); + if (rgb_idx != -1) + { + colors = vtkSmartPointer::New (); + colors->SetNumberOfComponents (3); + colors->SetName ("Colors"); + + pcl::RGB rgb_data; + for (size_t i = 0; i < cloud->size (); ++i) + { + if (!isFinite (cloud->points[i])) + continue; + memcpy (&rgb_data, reinterpret_cast (&cloud->points[i]) + fields[rgb_idx].offset, sizeof (pcl::RGB)); + unsigned char color[3]; + color[0] = rgb_data.r; + color[1] = rgb_data.g; + color[2] = rgb_data.b; + colors->InsertNextTupleValue (color); + } + } + + // Create points from polyMesh.cloud + vtkSmartPointer points = vtkSmartPointer::New (); + vtkIdType nr_points = cloud->points.size (); + points->SetNumberOfPoints (nr_points); + vtkSmartPointer actor; + + // Get a pointer to the beginning of the data array + float *data = static_cast (points->GetData ())->GetPointer (0); + + int ptr = 0; + std::vector lookup; + // If the dataset is dense (no NaNs) + if (cloud->is_dense) + { + for (vtkIdType i = 0; i < nr_points; ++i, ptr += 3) + memcpy (&data[ptr], &cloud->points[i].x, sizeof (float) * 3); + } + else + { + lookup.resize (nr_points); + vtkIdType j = 0; // true point index + for (vtkIdType i = 0; i < nr_points; ++i) + { + // Check if the point is invalid + if (!isFinite (cloud->points[i])) + continue; + + lookup[i] = static_cast (j); + memcpy (&data[ptr], &cloud->points[i].x, sizeof (float) * 3); + j++; + ptr += 3; + } + nr_points = j; + points->SetNumberOfPoints (nr_points); + } + + // Get the maximum size of a polygon + int max_size_of_polygon = -1; + for (size_t i = 0; i < vertices.size (); ++i) + if (max_size_of_polygon < static_cast (vertices[i].vertices.size ())) + max_size_of_polygon = static_cast (vertices[i].vertices.size ()); + + if (vertices.size () > 1) + { + // Create polys from polyMesh.polygons + vtkSmartPointer cell_array = vtkSmartPointer::New (); + vtkIdType *cell = cell_array->WritePointer (vertices.size (), vertices.size () * (max_size_of_polygon + 1)); + int idx = 0; + if (lookup.size () > 0) + { + for (size_t i = 0; i < vertices.size (); ++i, ++idx) + { + size_t n_points = vertices[i].vertices.size (); + *cell++ = n_points; + //cell_array->InsertNextCell (n_points); + for (size_t j = 0; j < n_points; j++, ++idx) + *cell++ = lookup[vertices[i].vertices[j]]; + //cell_array->InsertCellPoint (lookup[vertices[i].vertices[j]]); + } + } + else + { + for (size_t i = 0; i < vertices.size (); ++i, ++idx) + { + size_t n_points = vertices[i].vertices.size (); + *cell++ = n_points; + //cell_array->InsertNextCell (n_points); + for (size_t j = 0; j < n_points; j++, ++idx) + *cell++ = vertices[i].vertices[j]; + //cell_array->InsertCellPoint (vertices[i].vertices[j]); + } + } + vtkSmartPointer polydata; + allocVtkPolyData (polydata); + cell_array->GetData ()->SetNumberOfValues (idx); + cell_array->Squeeze (); + polydata->SetPolys (cell_array); + polydata->SetPoints (points); + + if (colors) + polydata->GetPointData ()->SetScalars (colors); + + createActorFromVTKDataSet (polydata, actor, false); + } + else + { + vtkSmartPointer polygon = vtkSmartPointer::New (); + size_t n_points = vertices[0].vertices.size (); + polygon->GetPointIds ()->SetNumberOfIds (n_points - 1); + + if (lookup.size () > 0) + { + for (size_t j = 0; j < (n_points - 1); ++j) + polygon->GetPointIds ()->SetId (j, lookup[vertices[0].vertices[j]]); + } + else + { + for (size_t j = 0; j < (n_points - 1); ++j) + polygon->GetPointIds ()->SetId (j, vertices[0].vertices[j]); + } + vtkSmartPointer poly_grid; + allocVtkUnstructuredGrid (poly_grid); + poly_grid->Allocate (1, 1); + poly_grid->InsertNextCell (polygon->GetCellType (), polygon->GetPointIds ()); + poly_grid->SetPoints (points); + if (colors) + poly_grid->GetPointData ()->SetScalars (colors); + + createActorFromVTKDataSet (poly_grid, actor, false); + } + addActorToRenderer (actor, viewport); + actor->GetProperty ()->SetRepresentationToSurface (); + // Backface culling renders the visualization slower, but guarantees that we see all triangles + actor->GetProperty ()->BackfaceCullingOff (); + actor->GetProperty ()->SetInterpolationToFlat (); + actor->GetProperty ()->EdgeVisibilityOff (); + actor->GetProperty ()->ShadingOff (); + + // Save the pointer/ID pair to the global actor map + (*cloud_actor_map_)[id].actor = actor; + + // Save the viewpoint transformation matrix to the global actor map + vtkSmartPointer transformation = vtkSmartPointer::New(); + convertToVtkMatrix (cloud->sensor_origin_, cloud->sensor_orientation_, transformation); + (*cloud_actor_map_)[id].viewpoint_transformation_ = transformation; + + return (true); +} + +///////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PCLVisualizer::updatePolygonMesh ( + const typename pcl::PointCloud::ConstPtr &cloud, + const std::vector &verts, + const std::string &id) +{ + if (verts.empty ()) + { + pcl::console::print_error ("[addPolygonMesh] No vertices given!\n"); + return (false); + } + + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + CloudActorMap::iterator am_it = cloud_actor_map_->find (id); + if (am_it == cloud_actor_map_->end ()) + return (false); + + // Get the current poly data + vtkSmartPointer polydata = static_cast(am_it->second.actor->GetMapper ())->GetInput (); + if (!polydata) + return (false); + vtkSmartPointer cells = polydata->GetStrips (); + if (!cells) + return (false); + vtkSmartPointer points = polydata->GetPoints (); + // Copy the new point array in + vtkIdType nr_points = cloud->points.size (); + points->SetNumberOfPoints (nr_points); + + // Get a pointer to the beginning of the data array + float *data = (static_cast (points->GetData ()))->GetPointer (0); + + int ptr = 0; + std::vector lookup; + // If the dataset is dense (no NaNs) + if (cloud->is_dense) + { + for (vtkIdType i = 0; i < nr_points; ++i, ptr += 3) + memcpy (&data[ptr], &cloud->points[i].x, sizeof (float) * 3); + } + else + { + lookup.resize (nr_points); + vtkIdType j = 0; // true point index + for (vtkIdType i = 0; i < nr_points; ++i) + { + // Check if the point is invalid + if (!isFinite (cloud->points[i])) + continue; + + lookup [i] = static_cast (j); + memcpy (&data[ptr], &cloud->points[i].x, sizeof (float) * 3); + j++; + ptr += 3; + } + nr_points = j; + points->SetNumberOfPoints (nr_points); + } + + // Update colors + vtkUnsignedCharArray* colors = vtkUnsignedCharArray::SafeDownCast (polydata->GetPointData ()->GetScalars ()); + int rgb_idx = -1; + std::vector fields; + rgb_idx = pcl::getFieldIndex (*cloud, "rgb", fields); + if (rgb_idx == -1) + rgb_idx = pcl::getFieldIndex (*cloud, "rgba", fields); + if (rgb_idx != -1 && colors) + { + pcl::RGB rgb_data; + int j = 0; + for (size_t i = 0; i < cloud->size (); ++i) + { + if (!isFinite (cloud->points[i])) + continue; + memcpy (&rgb_data, + reinterpret_cast (&cloud->points[i]) + fields[rgb_idx].offset, + sizeof (pcl::RGB)); + unsigned char color[3]; + color[0] = rgb_data.r; + color[1] = rgb_data.g; + color[2] = rgb_data.b; + colors->SetTupleValue (j++, color); + } + } + + // Get the maximum size of a polygon + int max_size_of_polygon = -1; + for (size_t i = 0; i < verts.size (); ++i) + if (max_size_of_polygon < static_cast (verts[i].vertices.size ())) + max_size_of_polygon = static_cast (verts[i].vertices.size ()); + + // Update the cells + cells = vtkSmartPointer::New (); + vtkIdType *cell = cells->WritePointer (verts.size (), verts.size () * (max_size_of_polygon + 1)); + int idx = 0; + if (lookup.size () > 0) + { + for (size_t i = 0; i < verts.size (); ++i, ++idx) + { + size_t n_points = verts[i].vertices.size (); + *cell++ = n_points; + for (size_t j = 0; j < n_points; j++, cell++, ++idx) + *cell = lookup[verts[i].vertices[j]]; + } + } + else + { + for (size_t i = 0; i < verts.size (); ++i, ++idx) + { + size_t n_points = verts[i].vertices.size (); + *cell++ = n_points; + for (size_t j = 0; j < n_points; j++, cell++, ++idx) + *cell = verts[i].vertices[j]; + } + } + cells->GetData ()->SetNumberOfValues (idx); + cells->Squeeze (); + // Set the the vertices + polydata->SetPolys (cells); + + return (true); +} + +#endif diff --git a/pcl-1.7/pcl/visualization/impl/point_cloud_color_handlers.hpp b/pcl-1.7/pcl/visualization/impl/point_cloud_color_handlers.hpp new file mode 100644 index 0000000..2584f5c --- /dev/null +++ b/pcl-1.7/pcl/visualization/impl/point_cloud_color_handlers.hpp @@ -0,0 +1,494 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_POINT_CLOUD_COLOR_HANDLERS_IMPL_HPP_ +#define PCL_POINT_CLOUD_COLOR_HANDLERS_IMPL_HPP_ + +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PointCloudColorHandlerCustom::getColor (vtkSmartPointer &scalars) const +{ + if (!capable_ || !cloud_) + return (false); + + if (!scalars) + scalars = vtkSmartPointer::New (); + scalars->SetNumberOfComponents (3); + + vtkIdType nr_points = cloud_->points.size (); + reinterpret_cast(&(*scalars))->SetNumberOfTuples (nr_points); + + // Get a random color + unsigned char* colors = new unsigned char[nr_points * 3]; + + // Color every point + for (vtkIdType cp = 0; cp < nr_points; ++cp) + { + colors[cp * 3 + 0] = static_cast (r_); + colors[cp * 3 + 1] = static_cast (g_); + colors[cp * 3 + 2] = static_cast (b_); + } + reinterpret_cast(&(*scalars))->SetArray (colors, 3 * nr_points, 0); + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PointCloudColorHandlerRandom::getColor (vtkSmartPointer &scalars) const +{ + if (!capable_ || !cloud_) + return (false); + + if (!scalars) + scalars = vtkSmartPointer::New (); + scalars->SetNumberOfComponents (3); + + vtkIdType nr_points = cloud_->points.size (); + reinterpret_cast(&(*scalars))->SetNumberOfTuples (nr_points); + + // Get a random color + unsigned char* colors = new unsigned char[nr_points * 3]; + double r, g, b; + pcl::visualization::getRandomColors (r, g, b); + + int r_ = static_cast (pcl_lrint (r * 255.0)), + g_ = static_cast (pcl_lrint (g * 255.0)), + b_ = static_cast (pcl_lrint (b * 255.0)); + + // Color every point + for (vtkIdType cp = 0; cp < nr_points; ++cp) + { + colors[cp * 3 + 0] = static_cast (r_); + colors[cp * 3 + 1] = static_cast (g_); + colors[cp * 3 + 2] = static_cast (b_); + } + reinterpret_cast(&(*scalars))->SetArray (colors, 3 * nr_points, 0); + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::visualization::PointCloudColorHandlerRGBField::setInputCloud ( + const PointCloudConstPtr &cloud) +{ + PointCloudColorHandler::setInputCloud (cloud); + // Handle the 24-bit packed RGB values + field_idx_ = pcl::getFieldIndex (*cloud, "rgb", fields_); + if (field_idx_ != -1) + { + capable_ = true; + return; + } + else + { + field_idx_ = pcl::getFieldIndex (*cloud, "rgba", fields_); + if (field_idx_ != -1) + capable_ = true; + else + capable_ = false; + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PointCloudColorHandlerRGBField::getColor (vtkSmartPointer &scalars) const +{ + if (!capable_ || !cloud_) + return (false); + + if (!scalars) + scalars = vtkSmartPointer::New (); + scalars->SetNumberOfComponents (3); + + vtkIdType nr_points = cloud_->points.size (); + reinterpret_cast(&(*scalars))->SetNumberOfTuples (nr_points); + unsigned char* colors = reinterpret_cast(&(*scalars))->GetPointer (0); + + int j = 0; + // If XYZ present, check if the points are invalid + int x_idx = -1; + for (size_t d = 0; d < fields_.size (); ++d) + if (fields_[d].name == "x") + x_idx = static_cast (d); + + if (x_idx != -1) + { + // Color every point + for (vtkIdType cp = 0; cp < nr_points; ++cp) + { + // Copy the value at the specified field + if (!pcl_isfinite (cloud_->points[cp].x) || + !pcl_isfinite (cloud_->points[cp].y) || + !pcl_isfinite (cloud_->points[cp].z)) + continue; + + colors[j ] = cloud_->points[cp].r; + colors[j + 1] = cloud_->points[cp].g; + colors[j + 2] = cloud_->points[cp].b; + j += 3; + } + } + else + { + // Color every point + for (vtkIdType cp = 0; cp < nr_points; ++cp) + { + int idx = static_cast (cp) * 3; + colors[idx ] = cloud_->points[cp].r; + colors[idx + 1] = cloud_->points[cp].g; + colors[idx + 2] = cloud_->points[cp].b; + } + } + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::visualization::PointCloudColorHandlerHSVField::PointCloudColorHandlerHSVField (const PointCloudConstPtr &cloud) : + pcl::visualization::PointCloudColorHandler::PointCloudColorHandler (cloud) +{ + // Check for the presence of the "H" field + field_idx_ = pcl::getFieldIndex (*cloud, "h", fields_); + if (field_idx_ == -1) + { + capable_ = false; + return; + } + + // Check for the presence of the "S" field + s_field_idx_ = pcl::getFieldIndex (*cloud, "s", fields_); + if (s_field_idx_ == -1) + { + capable_ = false; + return; + } + + // Check for the presence of the "V" field + v_field_idx_ = pcl::getFieldIndex (*cloud, "v", fields_); + if (v_field_idx_ == -1) + { + capable_ = false; + return; + } + capable_ = true; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PointCloudColorHandlerHSVField::getColor (vtkSmartPointer &scalars) const +{ + if (!capable_ || !cloud_) + return (false); + + if (!scalars) + scalars = vtkSmartPointer::New (); + scalars->SetNumberOfComponents (3); + + vtkIdType nr_points = cloud_->points.size (); + reinterpret_cast(&(*scalars))->SetNumberOfTuples (nr_points); + unsigned char* colors = reinterpret_cast(&(*scalars))->GetPointer (0); + + int idx = 0; + // If XYZ present, check if the points are invalid + int x_idx = -1; + + for (size_t d = 0; d < fields_.size (); ++d) + if (fields_[d].name == "x") + x_idx = static_cast (d); + + if (x_idx != -1) + { + // Color every point + for (vtkIdType cp = 0; cp < nr_points; ++cp) + { + // Copy the value at the specified field + if (!pcl_isfinite (cloud_->points[cp].x) || + !pcl_isfinite (cloud_->points[cp].y) || + !pcl_isfinite (cloud_->points[cp].z)) + continue; + + ///@todo do this with the point_types_conversion in common, first template it! + + float h = cloud_->points[cp].h; + float v = cloud_->points[cp].v; + float s = cloud_->points[cp].s; + + // Fill color data with HSV here: + // restrict the hue value to [0,360[ + h = h < 0.0f ? h - (((int)h)/360 - 1)*360 : h - (((int)h)/360)*360; + + // restrict s and v to [0,1] + if (s > 1.0f) s = 1.0f; + if (s < 0.0f) s = 0.0f; + if (v > 1.0f) v = 1.0f; + if (v < 0.0f) v = 0.0f; + + if (s == 0.0f) + { + colors[idx] = colors[idx+1] = colors[idx+2] = v*255; + } + else + { + // calculate p, q, t from HSV-values + float a = h / 60; + int i = floor (a); + float f = a - i; + float p = v * (1 - s); + float q = v * (1 - s * f); + float t = v * (1 - s * (1 - f)); + + switch (i) + { + case 0: + colors[idx] = v*255; colors[idx+1] = t*255; colors[idx+2] = p*255; break; + case 1: + colors[idx] = q*255; colors[idx+1] = v*255; colors[idx+2] = p*255; break; + case 2: + colors[idx] = p*255; colors[idx+1] = v*255; colors[idx+2] = t*255; break; + case 3: + colors[idx] = p*255; colors[idx+1] = q*255; colors[idx+2] = v*255; break; + case 4: + colors[idx] = t*255; colors[idx+1] = p*255; colors[idx+2] = v*255; break; + case 5: + colors[idx] = v*255; colors[idx+1] = p*255; colors[idx+2] = q*255; break; + } + } + idx +=3; + } + } + else + { + // Color every point + for (vtkIdType cp = 0; cp < nr_points; ++cp) + { + float h = cloud_->points[cp].h; + float v = cloud_->points[cp].v; + float s = cloud_->points[cp].s; + + // Fill color data with HSV here: + // restrict the hue value to [0,360[ + h = h < 0.0f ? h - (((int)h)/360 - 1)*360 : h - (((int)h)/360)*360; + + // restrict s and v to [0,1] + if (s > 1.0f) s = 1.0f; + if (s < 0.0f) s = 0.0f; + if (v > 1.0f) v = 1.0f; + if (v < 0.0f) v = 0.0f; + + if (s == 0.0f) + { + colors[idx] = colors[idx+1] = colors[idx+2] = v*255; + } + else + { + // calculate p, q, t from HSV-values + float a = h / 60; + int i = floor (a); + float f = a - i; + float p = v * (1 - s); + float q = v * (1 - s * f); + float t = v * (1 - s * (1 - f)); + + switch (i) + { + case 0: + colors[idx] = v*255; colors[idx+1] = t*255; colors[idx+2] = p*255; break; + case 1: + colors[idx] = q*255; colors[idx+1] = v*255; colors[idx+2] = p*255; break; + case 2: + colors[idx] = p*255; colors[idx+1] = v*255; colors[idx+2] = t*255; break; + case 3: + colors[idx] = p*255; colors[idx+1] = q*255; colors[idx+2] = v*255; break; + case 4: + colors[idx] = t*255; colors[idx+1] = p*255; colors[idx+2] = v*255; break; + case 5: + colors[idx] = v*255; colors[idx+1] = p*255; colors[idx+2] = q*255; break; + } + } + idx +=3; + } + } + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::visualization::PointCloudColorHandlerGenericField::setInputCloud ( + const PointCloudConstPtr &cloud) +{ + PointCloudColorHandler::setInputCloud (cloud); + field_idx_ = pcl::getFieldIndex (*cloud, field_name_, fields_); + if (field_idx_ != -1) + capable_ = true; + else + capable_ = false; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PointCloudColorHandlerGenericField::getColor (vtkSmartPointer &scalars) const +{ + if (!capable_ || !cloud_) + return (false); + + if (!scalars) + scalars = vtkSmartPointer::New (); + scalars->SetNumberOfComponents (1); + + vtkIdType nr_points = cloud_->points.size (); + reinterpret_cast(&(*scalars))->SetNumberOfTuples (nr_points); + + typedef typename pcl::traits::fieldList::type FieldList; + + float* colors = new float[nr_points]; + float field_data; + + int j = 0; + // If XYZ present, check if the points are invalid + int x_idx = -1; + for (size_t d = 0; d < fields_.size (); ++d) + if (fields_[d].name == "x") + x_idx = static_cast (d); + + if (x_idx != -1) + { + // Color every point + for (vtkIdType cp = 0; cp < nr_points; ++cp) + { + // Copy the value at the specified field + if (!pcl_isfinite (cloud_->points[cp].x) || !pcl_isfinite (cloud_->points[cp].y) || !pcl_isfinite (cloud_->points[cp].z)) + continue; + + const uint8_t* pt_data = reinterpret_cast (&cloud_->points[cp]); + memcpy (&field_data, pt_data + fields_[field_idx_].offset, pcl::getFieldSize (fields_[field_idx_].datatype)); + + colors[j] = field_data; + j++; + } + } + else + { + // Color every point + for (vtkIdType cp = 0; cp < nr_points; ++cp) + { + const uint8_t* pt_data = reinterpret_cast (&cloud_->points[cp]); + memcpy (&field_data, pt_data + fields_[field_idx_].offset, pcl::getFieldSize (fields_[field_idx_].datatype)); + + if (!pcl_isfinite (field_data)) + continue; + + colors[j] = field_data; + j++; + } + } + reinterpret_cast(&(*scalars))->SetArray (colors, j, 0); + return (true); +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::visualization::PointCloudColorHandlerRGBAField::setInputCloud ( + const PointCloudConstPtr &cloud) +{ + PointCloudColorHandler::setInputCloud (cloud); + // Handle the 24-bit packed RGBA values + field_idx_ = pcl::getFieldIndex (*cloud, "rgba", fields_); + if (field_idx_ != -1) + capable_ = true; + else + capable_ = false; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template bool +pcl::visualization::PointCloudColorHandlerRGBAField::getColor (vtkSmartPointer &scalars) const +{ + if (!capable_ || !cloud_) + return (false); + + if (!scalars) + scalars = vtkSmartPointer::New (); + scalars->SetNumberOfComponents (4); + + vtkIdType nr_points = cloud_->points.size (); + reinterpret_cast(&(*scalars))->SetNumberOfTuples (nr_points); + unsigned char* colors = reinterpret_cast(&(*scalars))->GetPointer (0); + + int j = 0; + // If XYZ present, check if the points are invalid + int x_idx = -1; + for (size_t d = 0; d < fields_.size (); ++d) + if (fields_[d].name == "x") + x_idx = static_cast (d); + + if (x_idx != -1) + { + // Color every point + for (vtkIdType cp = 0; cp < nr_points; ++cp) + { + // Copy the value at the specified field + if (!pcl_isfinite (cloud_->points[cp].x) || + !pcl_isfinite (cloud_->points[cp].y) || + !pcl_isfinite (cloud_->points[cp].z)) + continue; + + colors[j ] = cloud_->points[cp].r; + colors[j + 1] = cloud_->points[cp].g; + colors[j + 2] = cloud_->points[cp].b; + colors[j + 3] = cloud_->points[cp].a; + j += 4; + } + } + else + { + // Color every point + for (vtkIdType cp = 0; cp < nr_points; ++cp) + { + int idx = static_cast (cp) * 4; + colors[idx ] = cloud_->points[cp].r; + colors[idx + 1] = cloud_->points[cp].g; + colors[idx + 2] = cloud_->points[cp].b; + colors[idx + 3] = cloud_->points[cp].a; + } + } + return (true); +} + +#endif // PCL_POINT_CLOUD_COLOR_HANDLERS_IMPL_HPP_ + diff --git a/pcl-1.7/pcl/visualization/impl/point_cloud_geometry_handlers.hpp b/pcl-1.7/pcl/visualization/impl/point_cloud_geometry_handlers.hpp new file mode 100644 index 0000000..11051b9 --- /dev/null +++ b/pcl-1.7/pcl/visualization/impl/point_cloud_geometry_handlers.hpp @@ -0,0 +1,157 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: point_cloud_handlers.hpp 7678 2012-10-22 20:54:04Z rusu $ + * + */ +#ifndef PCL_POINT_CLOUD_GEOMETRY_HANDLERS_IMPL_HPP_ +#define PCL_POINT_CLOUD_GEOMETRY_HANDLERS_IMPL_HPP_ + +#include + +/////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::visualization::PointCloudGeometryHandlerXYZ::PointCloudGeometryHandlerXYZ (const PointCloudConstPtr &cloud) + : pcl::visualization::PointCloudGeometryHandler::PointCloudGeometryHandler (cloud) +{ + field_x_idx_ = pcl::getFieldIndex (*cloud, "x", fields_); + if (field_x_idx_ == -1) + return; + field_y_idx_ = pcl::getFieldIndex (*cloud, "y", fields_); + if (field_y_idx_ == -1) + return; + field_z_idx_ = pcl::getFieldIndex (*cloud, "z", fields_); + if (field_z_idx_ == -1) + return; + capable_ = true; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::visualization::PointCloudGeometryHandlerXYZ::getGeometry (vtkSmartPointer &points) const +{ + if (!capable_) + return; + + if (!points) + points = vtkSmartPointer::New (); + points->SetDataTypeToFloat (); + + vtkSmartPointer data = vtkSmartPointer::New (); + data->SetNumberOfComponents (3); + vtkIdType nr_points = cloud_->points.size (); + + // Add all points + vtkIdType j = 0; // true point index + float* pts = static_cast (malloc (nr_points * 3 * sizeof (float))); + + // If the dataset has no invalid values, just copy all of them + if (cloud_->is_dense) + { + for (vtkIdType i = 0; i < nr_points; ++i) + { + pts[i * 3 + 0] = cloud_->points[i].x; + pts[i * 3 + 1] = cloud_->points[i].y; + pts[i * 3 + 2] = cloud_->points[i].z; + } + data->SetArray (&pts[0], nr_points * 3, 0); + points->SetData (data); + } + // Need to check for NaNs, Infs, ec + else + { + for (vtkIdType i = 0; i < nr_points; ++i) + { + // Check if the point is invalid + if (!pcl_isfinite (cloud_->points[i].x) || !pcl_isfinite (cloud_->points[i].y) || !pcl_isfinite (cloud_->points[i].z)) + continue; + + pts[j * 3 + 0] = cloud_->points[i].x; + pts[j * 3 + 1] = cloud_->points[i].y; + pts[j * 3 + 2] = cloud_->points[i].z; + // Set j and increment + j++; + } + data->SetArray (&pts[0], j * 3, 0); + points->SetData (data); + } +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template +pcl::visualization::PointCloudGeometryHandlerSurfaceNormal::PointCloudGeometryHandlerSurfaceNormal (const PointCloudConstPtr &cloud) + : pcl::visualization::PointCloudGeometryHandler::PointCloudGeometryHandler (cloud) +{ + field_x_idx_ = pcl::getFieldIndex (*cloud, "normal_x", fields_); + if (field_x_idx_ == -1) + return; + field_y_idx_ = pcl::getFieldIndex (*cloud, "normal_y", fields_); + if (field_y_idx_ == -1) + return; + field_z_idx_ = pcl::getFieldIndex (*cloud, "normal_z", fields_); + if (field_z_idx_ == -1) + return; + capable_ = true; +} + +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::visualization::PointCloudGeometryHandlerSurfaceNormal::getGeometry (vtkSmartPointer &points) const +{ + if (!capable_) + return; + + if (!points) + points = vtkSmartPointer::New (); + points->SetDataTypeToFloat (); + points->SetNumberOfPoints (cloud_->points.size ()); + + // Add all points + double p[3]; + for (vtkIdType i = 0; i < static_cast (cloud_->points.size ()); ++i) + { + p[0] = cloud_->points[i].normal[0]; + p[1] = cloud_->points[i].normal[1]; + p[2] = cloud_->points[i].normal[2]; + + points->SetPoint (i, p); + } +} + +#define PCL_INSTANTIATE_PointCloudGeometryHandlerXYZ(T) template class PCL_EXPORTS pcl::visualization::PointCloudGeometryHandlerXYZ; +#define PCL_INSTANTIATE_PointCloudGeometryHandlerSurfaceNormal(T) template class PCL_EXPORTS pcl::visualization::PointCloudGeometryHandlerSurfaceNormal; + +#endif // PCL_POINT_CLOUD_GEOMETRY_HANDLERS_IMPL_HPP_ + diff --git a/pcl-1.7/pcl/visualization/impl/point_cloud_handlers.hpp b/pcl-1.7/pcl/visualization/impl/point_cloud_handlers.hpp new file mode 100644 index 0000000..f4f013c --- /dev/null +++ b/pcl-1.7/pcl/visualization/impl/point_cloud_handlers.hpp @@ -0,0 +1,44 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_POINT_CLOUD_HANDLERS_IMPL_HPP_ +#define PCL_POINT_CLOUD_HANDLERS_IMPL_HPP_ + +#include +#include + +#endif // PCL_POINT_CLOUD_HANDLERS_IMPL_HPP_ diff --git a/pcl-1.7/pcl/visualization/impl/registration_visualizer.hpp b/pcl-1.7/pcl/visualization/impl/registration_visualizer.hpp new file mode 100644 index 0000000..2961fd7 --- /dev/null +++ b/pcl-1.7/pcl/visualization/impl/registration_visualizer.hpp @@ -0,0 +1,212 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegistrationVisualizer::startDisplay () +{ + // Create and start the rendering thread. This will open the display window. + viewer_thread_ = boost::thread (&pcl::RegistrationVisualizer::runDisplay, this); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegistrationVisualizer::stopDisplay () +{ + // Stop the rendering thread. This will kill the display window. + viewer_thread_.~thread (); +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegistrationVisualizer::runDisplay () +{ + // Open 3D viewer + viewer_ + = boost::shared_ptr (new pcl::visualization::PCLVisualizer ("3D Viewer")); + viewer_->initCameraParameters (); + + // Create the handlers for the three point clouds buffers: cloud_source_, cloud_target_ and cloud_intermediate_ + pcl::visualization::PointCloudColorHandlerCustom cloud_source_handler_ (cloud_source_.makeShared (), + 255, 0, 0); + pcl::visualization::PointCloudColorHandlerCustom cloud_target_handler_ (cloud_target_.makeShared (), + 0, 0, 255); + pcl::visualization::PointCloudColorHandlerCustom cloud_intermediate_handler_ (cloud_intermediate_.makeShared (), + 255, 255, 0); + + // Create the view port for displaying initial source and target point clouds + int v1 (0); + viewer_->createViewPort (0.0, 0.0, 0.5, 1.0, v1); + viewer_->setBackgroundColor (0, 0, 0, v1); + viewer_->addText ("Initial position of source and target point clouds", 10, 50, "title v1", v1); + viewer_->addText ("Blue -> target", 10, 30, 0.0, 0.0, 1.0, "legend target v1", v1); + viewer_->addText ("Red -> source", 10, 10, 1.0, 0.0, 0.0, "legend source v1", v1); + // + viewer_->addPointCloud (cloud_source_.makeShared (), cloud_source_handler_, "cloud source v1", v1); + viewer_->addPointCloud (cloud_target_.makeShared (), cloud_target_handler_, "cloud target v1", v1); + + // Create the view port for displaying the registration process of source to target point cloud + int v2 (0); + viewer_->createViewPort (0.5, 0.0, 1.0, 1.0, v2); + viewer_->setBackgroundColor (0.1, 0.1, 0.1, v2); + std::string registration_port_title_ = "Registration using "+registration_method_name_; + viewer_->addText (registration_port_title_, 10, 90, "title v2", v2); + + viewer_->addText ("Yellow -> intermediate", 10, 50, 1.0, 1.0, 0.0, "legend intermediate v2", v2); + viewer_->addText ("Blue -> target", 10, 30, 0.0, 0.0, 1.0, "legend target v2", v2); + viewer_->addText ("Red -> source", 10, 10, 1.0, 0.0, 0.0, "legend source v2", v1); + +// viewer_->addPointCloud (cloud_source_.makeShared (), cloud_source_handler_, "cloud source v2", v2); + viewer_->addPointCloud (cloud_target_.makeShared (), cloud_target_handler_, "cloud target v2", v2); + viewer_->addPointCloud (cloud_intermediate_.makeShared (), cloud_intermediate_handler_, + "cloud intermediate v2", v2); + + // Used to remove all old correspondences + size_t correspondeces_old_size = 0; + + // Add coordinate system to both ports + viewer_->addCoordinateSystem (1.0, "global"); + + // The root name of correspondence lines + std::string line_root_ = "line"; + + // Visualization loop + while (!viewer_->wasStopped ()) + { + // Lock access to visualizer buffers + visualizer_updating_mutex_.lock (); + + // Updating intermediate point cloud + // Remove old point cloud + viewer_->removePointCloud ("cloud intermediate v2", v2); + + // Add the new point cloud + viewer_->addPointCloud (cloud_intermediate_.makeShared (), cloud_intermediate_handler_, + "cloud intermediate v2", v2); + + // Updating the correspondece lines + + std::string line_name_; + // Remove the old correspondeces + for (size_t correspondence_id = 0; correspondence_id < correspondeces_old_size; ++correspondence_id) + { + // Generate the line name + line_name_ = getIndexedName (line_root_, correspondence_id); + + // Remove the current line according to it's name + viewer_->removeShape (line_name_, v2); + } + + // Display the new correspondences lines + size_t correspondences_new_size = cloud_intermediate_indices_.size (); + + + std::stringstream stream_; + stream_ << "Random -> correspondences " << correspondences_new_size; + viewer_->removeShape ("correspondences_size", 0); + viewer_->addText (stream_.str(), 10, 70, 0.0, 1.0, 0.0, "correspondences_size", v2); + + // Display entire set of correspondece lines if no maximum displayed correspondences is set + if( ( 0 < maximum_displayed_correspondences_ ) && + (maximum_displayed_correspondences_ < correspondences_new_size) ) + correspondences_new_size = maximum_displayed_correspondences_; + + // Actualize correspondeces_old_size + correspondeces_old_size = correspondences_new_size; + + // Update new correspondence lines + for (size_t correspondence_id = 0; correspondence_id < correspondences_new_size; ++correspondence_id) + { + // Generate random color for current correspondence line + double random_red = 255 * rand () / (RAND_MAX + 1.0); + double random_green = 255 * rand () / (RAND_MAX + 1.0); + double random_blue = 255 * rand () / (RAND_MAX + 1.0); + + // Generate the name for current line + line_name_ = getIndexedName (line_root_, correspondence_id); + + // Add the new correspondence line. + viewer_->addLine (cloud_intermediate_[cloud_intermediate_indices_[correspondence_id]], + cloud_target_[cloud_target_indices_[correspondence_id]], + random_red, random_green, random_blue, + line_name_, v2); + } + + // Unlock access to visualizer buffers + visualizer_updating_mutex_.unlock (); + + // Render visualizer updated buffers + viewer_->spinOnce (100); + boost::this_thread::sleep (boost::posix_time::microseconds (100000)); + + } +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::RegistrationVisualizer::updateIntermediateCloud ( + const pcl::PointCloud &cloud_src, + const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, + const std::vector &indices_tgt) +{ + // Lock local buffers + visualizer_updating_mutex_.lock (); + + // Update source and target point clouds if this is the first callback + // Here we are sure that source and target point clouds are initialized + if (!first_update_flag_) + { + first_update_flag_ = true; + + this->cloud_source_ = cloud_src; + this->cloud_target_ = cloud_tgt; + + this->cloud_intermediate_ = cloud_src; + } + + // Copy the intermediate point cloud and it's associates indices + cloud_intermediate_ = cloud_src; + cloud_intermediate_indices_ = indices_src; + + // Copy the intermediate indices associate to the target point cloud + cloud_target_indices_ = indices_tgt; + + // Unlock local buffers + visualizer_updating_mutex_.unlock (); +} diff --git a/pcl-1.7/pcl/visualization/interactor.h b/pcl-1.7/pcl/visualization/interactor.h new file mode 100644 index 0000000..64a4952 --- /dev/null +++ b/pcl-1.7/pcl/visualization/interactor.h @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id: interactor.h 2050 2011-08-12 15:26:19Z bouffa $ + * + */ +#ifndef PCL_PCL_VISUALIZER_INTERACTOR_H_ +#define PCL_PCL_VISUALIZER_INTERACTOR_H_ + +#include + +#include +#include +#ifdef _WIN32 +# include +#else +#include +#if (VTK_MAJOR_VERSION <= 5 && defined VTK_USE_COCOA) || defined __APPLE__ +# include +#elif VTK_MAJOR_VERSION <= 5 && defined VTK_USE_CARBON +# include +#else +// Stupid X.h defines Complex, Bool, Success globally (!) +# include +# undef Complex +# undef Bool +# undef Success +# undef Status +#endif +#endif + +namespace pcl +{ + namespace visualization + { + /** \brief The PCLVisualizer interactor */ +#ifdef _WIN32 + class PCL_EXPORTS PCLVisualizerInteractor : public vtkWin32RenderWindowInteractor +#elif (VTK_MAJOR_VERSION <= 5 && defined VTK_USE_COCOA) || defined __APPLE__ + class PCLVisualizerInteractor : public vtkCocoaRenderWindowInteractor +#elif VTK_MAJOR_VERSION <= 5 && defined VTK_USE_CARBON + class PCLVisualizerInteractor : public vtkCarbonRenderWindowInteractor +#else + class PCLVisualizerInteractor : public vtkXRenderWindowInteractor +#endif + { + public: + static PCLVisualizerInteractor *New (); + +// void TerminateApp (void); // do nothing -> disable exit(0) on keys 'q', 'Q' or Esc + void stopLoop (); + + bool stopped; + int timer_id_; + +#if defined (_WIN32) && ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + int BreakLoopFlag; // if true quit the GetMessage loop + + virtual void + Start (); // Redefine the vtkWin32RenderWindowInteractor::Start method... + + vtkGetMacro (BreakLoopFlag, int); + + void + SetBreakLoopFlag (int); // Change the value of BreakLoopFlag + + void + BreakLoopFlagOff (); // set BreakLoopFlag to 0 + + void + BreakLoopFlagOn (); // set BreakLoopFlag to 1 (quit) +#endif + }; + } +} + +#endif diff --git a/pcl-1.7/pcl/visualization/interactor_style.h b/pcl-1.7/pcl/visualization/interactor_style.h new file mode 100644 index 0000000..c89bb2d --- /dev/null +++ b/pcl-1.7/pcl/visualization/interactor_style.h @@ -0,0 +1,416 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_PCL_VISUALIZER_INTERACTOR_STYLE_H_ +#define PCL_PCL_VISUALIZER_INTERACTOR_STYLE_H_ + +#include +#include +#include +#include +#include +#include +#include +#ifndef Q_MOC_RUN +#include +#endif +#include + +class vtkRendererCollection; +class vtkLegendScaleActor; +class vtkScalarBarActor; +class vtkPNGWriter; +class vtkWindowToImageFilter; +class vtkPointPicker; + +namespace pcl +{ + namespace visualization + { + + /** \brief A list of potential keyboard modifiers for \ref pcl::visualization::PCLVisualizerInteractorStyle::PCLVisualizerInteractorStyle() + * Defaults to Alt. + */ + enum InteractorKeyboardModifier + { + INTERACTOR_KB_MOD_ALT, + INTERACTOR_KB_MOD_CTRL, + INTERACTOR_KB_MOD_SHIFT + }; + + /** \brief PCLVisualizerInteractorStyle defines an unique, custom VTK + * based interactory style for PCL Visualizer applications. Besides + * defining the rendering style, we also create a list of custom actions + * that are triggered on different keys being pressed: + * + * - p, P : switch to a point-based representation + * - w, W : switch to a wireframe-based representation (where available) + * - s, S : switch to a surface-based representation (where available) + * - j, J : take a .PNG snapshot of the current window view + * - c, C : display current camera/window parameters + * - f, F : fly to point mode + * - e, E : exit the interactor\ + * - q, Q : stop and call VTK's TerminateApp + * - + / - : increment/decrement overall point size + * - g, G : display scale grid (on/off) + * - u, U : display lookup table (on/off) + * - r, R [+ ALT] : reset camera [to viewpoint = {0, 0, 0} -> center_{x, y, z}] + * - CTRL + s, S : save camera parameters + * - CTRL + r, R : restore camera parameters + * - ALT + s, S : turn stereo mode on/off + * - ALT + f, F : switch between maximized window mode and original size + * - l, L : list all available geometric and color handlers for the current actor map + * - ALT + 0..9 [+ CTRL] : switch between different geometric handlers (where available) + * - 0..9 [+ CTRL] : switch between different color handlers (where available) + * - + * - SHIFT + left click : select a point + * - x, X : toggle rubber band selection mode for left mouse button + * + * \author Radu B. Rusu + * \ingroup visualization + */ + class PCL_EXPORTS PCLVisualizerInteractorStyle : public vtkInteractorStyleRubberBandPick + { + typedef boost::shared_ptr CloudActorMapPtr; + + public: + static PCLVisualizerInteractorStyle *New (); + + /** \brief Empty constructor. */ + PCLVisualizerInteractorStyle () : + init_ (), rens_ (), actors_ (), win_height_ (), win_width_ (), win_pos_x_ (), win_pos_y_ (), + max_win_height_ (), max_win_width_ (), grid_enabled_ (), grid_actor_ (), lut_enabled_ (), + lut_actor_ (), snapshot_writer_ (), wif_ (), mouse_signal_ (), keyboard_signal_ (), + point_picking_signal_ (), area_picking_signal_ (), stereo_anaglyph_mask_default_ (), + mouse_callback_ (), modifier_ (), camera_file_ (), camera_ (), camera_saved_ (), win_ () + {} + + /** \brief Empty destructor */ + virtual ~PCLVisualizerInteractorStyle () {} + + // this macro defines Superclass, the isA functionality and the safe downcast method + vtkTypeMacro (PCLVisualizerInteractorStyle, vtkInteractorStyleRubberBandPick); + + /** \brief Initialization routine. Must be called before anything else. */ + virtual void + Initialize (); + + /** \brief Pass a pointer to the actor map + * \param[in] actors the actor map that will be used with this style + */ + inline void + setCloudActorMap (const CloudActorMapPtr &actors) { actors_ = actors; } + + /** \brief Get the cloud actor map pointer. */ + inline CloudActorMapPtr + getCloudActorMap () { return (actors_); } + + /** \brief Pass a set of renderers to the interactor style. + * \param[in] rens the vtkRendererCollection to use + */ + void + setRendererCollection (vtkSmartPointer &rens) { rens_ = rens; } + + /** \brief Pass a pointer to the actor map + * \param[in] use_vbos + */ + inline void + setUseVbos (const bool use_vbos) { use_vbos_ = use_vbos; } + + /** \brief Register a callback function for mouse events + * \param[in] cb a boost function that will be registered as a callback for a mouse event + * \return a connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerMouseCallback (boost::function cb); + + /** \brief Register a callback boost::function for keyboard events + * \param[in] cb a boost function that will be registered as a callback for a keyboard event + * \return a connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerKeyboardCallback (boost::function cb); + + /** \brief Register a callback function for point picking events + * \param[in] cb a boost function that will be registered as a callback for a point picking event + * \return a connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerPointPickingCallback (boost::function cb); + + /** \brief Register a callback function for area picking events + * \param[in] cb a boost function that will be registered as a callback for a area picking event + * \return a connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerAreaPickingCallback (boost::function cb); + + /** \brief Save the current rendered image to disk, as a PNG screenshot. + * \param[in] file the name of the PNG file + */ + void + saveScreenshot (const std::string &file); + + /** \brief Save the camera parameters to disk, as a .cam file. + * \param[in] file the name of the .cam file + */ + bool + saveCameraParameters (const std::string &file); + + /** \brief Get camera parameters and save them to a \ref pcl::visualization::Camera. + * \param[out] camera the name of the \ref pcl::visualization::Camera + */ + void + getCameraParameters (Camera &camera); + + /** \brief Load camera parameters from a camera parameter file. + * \param[in] file the name of the camera parameter file + */ + bool + loadCameraParameters (const std::string &file); + + /** \brief Set the camera parameters via an intrinsics and and extrinsics matrix + * \note This assumes that the pixels are square and that the center of the image is at the center of the sensor. + * \param[in] intrinsics the intrinsics that will be used to compute the VTK camera parameters + * \param[in] extrinsics the extrinsics that will be used to compute the VTK camera parameters + * \param[in] viewport the viewport to modify camera of (0 modifies all cameras) + */ + void + setCameraParameters (const Eigen::Matrix3f &intrinsics, const Eigen::Matrix4f &extrinsics, int viewport = 0); + + /** \brief Set the camera parameters by given a full camera data structure. + * \param[in] camera camera structure containing all the camera parameters. + * \param[in] viewport the viewport to modify camera of (0 modifies all cameras) + */ + void + setCameraParameters (const Camera &camera, int viewport = 0); + + /** \brief Set camera file for camera parameter saving/restoring. + * \param[in] file the name of the camera parameter file + */ + void + setCameraFile (const std::string file) + { + camera_file_ = file; + } + + /** \brief Get camera file for camera parameter saving/restoring. */ + std::string + getCameraFile () const + { + return (camera_file_); + } + + /** \brief Change the default keyboard modified from ALT to a different special key. + * Allowed values are: + * - INTERACTOR_KB_MOD_ALT + * - INTERACTOR_KB_MOD_CTRL + * - INTERACTOR_KB_MOD_SHIFT + * \param[in] modifier the new keyboard modifier + */ + inline void + setKeyboardModifier (const InteractorKeyboardModifier &modifier) + { + modifier_ = modifier; + } + + protected: + /** \brief Set to true after initialization is complete. */ + bool init_; + + /** \brief Collection of vtkRenderers stored internally. */ + vtkSmartPointer rens_; + + /** \brief Actor map stored internally. */ + CloudActorMapPtr actors_; + + /** \brief The current window width/height. */ + int win_height_, win_width_; + + /** \brief The current window position x/y. */ + int win_pos_x_, win_pos_y_; + + /** \brief The maximum resizeable window width/height. */ + int max_win_height_, max_win_width_; + + /** \brief The maximum resizeable window width/height. */ + bool use_vbos_; + + /** \brief Set to true if the grid actor is enabled. */ + bool grid_enabled_; + /** \brief Actor for 2D grid on screen. */ + vtkSmartPointer grid_actor_; + + /** \brief Set to true if the LUT actor is enabled. */ + bool lut_enabled_; + /** \brief Actor for 2D lookup table on screen. */ + vtkSmartPointer lut_actor_; + + /** \brief A PNG writer for screenshot captures. */ + vtkSmartPointer snapshot_writer_; + /** \brief Internal window to image filter. Needed by \a snapshot_writer_. */ + vtkSmartPointer wif_; + /** \brief Stores the point picker when switching to an area picker. */ + vtkSmartPointer point_picker_; + + boost::signals2::signal mouse_signal_; + boost::signals2::signal keyboard_signal_; + boost::signals2::signal point_picking_signal_; + boost::signals2::signal area_picking_signal_; + + /** \brief Interactor style internal method. Gets called whenever a key is pressed. */ + virtual void + OnChar (); + + // Keyboard events + virtual void + OnKeyDown (); + virtual void + OnKeyUp (); + + // mouse button events + virtual void + OnMouseMove (); + virtual void + OnLeftButtonDown (); + virtual void + OnLeftButtonUp (); + virtual void + OnMiddleButtonDown (); + virtual void + OnMiddleButtonUp (); + virtual void + OnRightButtonDown (); + virtual void + OnRightButtonUp (); + virtual void + OnMouseWheelForward (); + virtual void + OnMouseWheelBackward (); + + // mouse move event + /** \brief Interactor style internal method. Gets called periodically if a timer is set. */ + virtual void + OnTimer (); + + /** \brief Interactor style internal method. Zoom in. */ + void + zoomIn (); + + /** \brief Interactor style internal method. Zoom out. */ + void + zoomOut (); + + /** \brief Get camera parameters from a string vector. + * \param[in] camera A string vector: + * Clipping Range, Focal Point, Position, ViewUp, Distance, Field of View Y, Window Size, Window Pos. + * Values in each string are seperated by a ',' + */ + bool + getCameraParameters (const std::vector &camera); + + /** \brief Set render window. */ + void + setRenderWindow (const vtkSmartPointer &win) + { + win_ = win; + } + + /** \brief True if we're using red-blue colors for anaglyphic stereo, false if magenta-green. */ + bool stereo_anaglyph_mask_default_; + + /** \brief A VTK Mouse Callback object, used for point picking. */ + vtkSmartPointer mouse_callback_; + + /** \brief The keyboard modifier to use. Default: Alt. */ + InteractorKeyboardModifier modifier_; + + /** \brief Camera file for camera parameter saving/restoring. */ + std::string camera_file_; + /** \brief A \ref pcl::visualization::Camera for camera parameter saving/restoring. */ + Camera camera_; + /** \brief A \ref pcl::visualization::Camera is saved or not. */ + bool camera_saved_; + /** \brief The render window. + * Only used when interactor maybe not available + */ + vtkSmartPointer win_; + + friend class PointPickingCallback; + friend class PCLVisualizer; + }; + + /** \brief PCL histogram visualizer interactory style class. + * \author Radu B. Rusu + */ + class PCLHistogramVisualizerInteractorStyle : public vtkInteractorStyleTrackballCamera + { + public: + static PCLHistogramVisualizerInteractorStyle *New (); + + /** \brief Empty constructor. */ + PCLHistogramVisualizerInteractorStyle () : wins_ (), init_ (false) {} + + /** \brief Initialization routine. Must be called before anything else. */ + void + Initialize (); + + /** \brief Pass a map of render/window/interactors to the interactor style. + * \param[in] wins the RenWinInteract map to use + */ + void + setRenWinInteractMap (const RenWinInteractMap &wins) { wins_ = wins; } + + private: + /** \brief A map of all windows on screen (with their renderers and interactors). */ + RenWinInteractMap wins_; + + /** \brief Set to true after initialization is complete. */ + bool init_; + + /** \brief Interactor style internal method. Gets called whenever a key is pressed. */ + void OnKeyDown (); + + /** \brief Interactor style internal method. Gets called periodically if a timer is set. */ + void OnTimer (); + }; + } +} + +#endif diff --git a/pcl-1.7/pcl/visualization/keyboard_event.h b/pcl-1.7/pcl/visualization/keyboard_event.h new file mode 100644 index 0000000..00ff6c0 --- /dev/null +++ b/pcl-1.7/pcl/visualization/keyboard_event.h @@ -0,0 +1,182 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_VISUALIZATION_KEYBOARD_EVENT_H_ +#define PCL_VISUALIZATION_KEYBOARD_EVENT_H_ + +#include + +namespace pcl +{ + namespace visualization + { + /** /brief Class representing key hit/release events */ + class KeyboardEvent + { + public: + /** \brief bit patter for the ALT key*/ + static const unsigned int Alt = 1; + /** \brief bit patter for the Control key*/ + static const unsigned int Ctrl = 2; + /** \brief bit patter for the Shift key*/ + static const unsigned int Shift = 4; + + /** \brief Constructor + * \param[in] action true for key was pressed, false for released + * \param[in] key_sym the key-name that caused the action + * \param[in] key the key code that caused the action + * \param[in] alt whether the alt key was pressed at the time where this event was triggered + * \param[in] ctrl whether the ctrl was pressed at the time where this event was triggered + * \param[in] shift whether the shift was pressed at the time where this event was triggered + */ + inline KeyboardEvent (bool action, const std::string& key_sym, unsigned char key, + bool alt, bool ctrl, bool shift); + + /** + * \return whether the alt key was pressed at the time where this event was triggered + */ + inline bool + isAltPressed () const; + + /** + * \return whether the ctrl was pressed at the time where this event was triggered + */ + inline bool + isCtrlPressed () const; + + /** + * \return whether the shift was pressed at the time where this event was triggered + */ + inline bool + isShiftPressed () const; + + /** + * \return the ASCII Code of the key that caused the event. If 0, then it was a special key, like ALT, F1, F2,... PgUp etc. Then the name of the key is in the keysym field. + */ + inline unsigned char + getKeyCode () const; + + /** + * \return name of the key that caused the event + */ + inline const std::string& + getKeySym () const; + + /** + * \return true if a key-press caused the event, false otherwise + */ + inline bool + keyDown () const; + + /** + * \return true if a key-release caused the event, false otherwise + */ + inline bool + keyUp () const; + + protected: + + bool action_; + unsigned int modifiers_; + unsigned char key_code_; + std::string key_sym_; + }; + + KeyboardEvent::KeyboardEvent (bool action, const std::string& key_sym, unsigned char key, + bool alt, bool ctrl, bool shift) + : action_ (action) + , modifiers_ (0) + , key_code_(key) + , key_sym_ (key_sym) + { + if (alt) + modifiers_ = Alt; + + if (ctrl) + modifiers_ |= Ctrl; + + if (shift) + modifiers_ |= Shift; + } + + bool + KeyboardEvent::isAltPressed () const + { + return (modifiers_ & Alt) != 0; + } + + bool + KeyboardEvent::isCtrlPressed () const + { + return (modifiers_ & Ctrl) != 0; + } + + bool + KeyboardEvent::isShiftPressed () const + { + return (modifiers_ & Shift) != 0; + } + + unsigned char + KeyboardEvent::getKeyCode () const + { + return (key_code_); + } + + const std::string& + KeyboardEvent::getKeySym () const + { + return (key_sym_); + } + + bool + KeyboardEvent::keyDown () const + { + return (action_); + } + + bool + KeyboardEvent::keyUp () const + { + return (!action_); + } + } // namespace visualization +} // namespace pcl + +#endif /* PCL_VISUALIZATION_KEYBOARD_EVENT_H_ */ + diff --git a/pcl-1.7/pcl/visualization/mouse_event.h b/pcl-1.7/pcl/visualization/mouse_event.h new file mode 100644 index 0000000..b4184dc --- /dev/null +++ b/pcl-1.7/pcl/visualization/mouse_event.h @@ -0,0 +1,213 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_VISUALIZATION_MOUSE_EVENT_H_ +#define PCL_VISUALIZATION_MOUSE_EVENT_H_ + +#include + +namespace pcl +{ + namespace visualization + { + class MouseEvent + { + public: + typedef enum + { + MouseMove = 1, + MouseButtonPress, + MouseButtonRelease, + MouseScrollDown, + MouseScrollUp, + MouseDblClick + } Type; + + typedef enum + { + NoButton = 0, + LeftButton, + MiddleButton, + RightButton, + VScroll /*other buttons, scroll wheels etc. may follow*/ + } MouseButton; + + /** Constructor. + * \param[in] type event type + * \param[in] button The Button that causes the event + * \param[in] x x position of mouse pointer at that time where event got fired + * \param[in] y y position of mouse pointer at that time where event got fired + * \param[in] alt whether the ALT key was pressed at that time where event got fired + * \param[in] ctrl whether the CTRL key was pressed at that time where event got fired + * \param[in] shift whether the Shift key was pressed at that time where event got fired + * \param[in] selection_mode whether we are in selection mode + */ + inline MouseEvent (const Type& type, const MouseButton& button, + unsigned int x, unsigned int y, + bool alt, bool ctrl, bool shift, + bool selection_mode = false); + + /** + * \return type of mouse event + */ + inline const Type& + getType () const; + + /** + * \brief Sets the mouse event type + */ + inline void + setType (const Type& type); + + /** + * \return the Button that caused the action + */ + inline const MouseButton& + getButton () const; + + /** \brief Set the button that caused the event */ + inline void + setButton (const MouseButton& button); + + /** + * \return the x position of the mouse pointer at that time where the event got fired + */ + inline unsigned int + getX () const; + + /** + * \return the y position of the mouse pointer at that time where the event got fired + */ + inline unsigned int + getY () const; + + /** + * \return returns the keyboard modifiers state at that time where the event got fired + */ + inline unsigned int + getKeyboardModifiers () const; + + /** + * \return selection mode status + */ + inline bool + getSelectionMode () const; + + protected: + Type type_; + MouseButton button_; + unsigned int pointer_x_; + unsigned int pointer_y_; + unsigned int key_state_; + bool selection_mode_; + }; + + MouseEvent::MouseEvent (const Type& type, const MouseButton& button, + unsigned x, unsigned y, + bool alt, bool ctrl, bool shift, + bool selection_mode) + : type_ (type) + , button_ (button) + , pointer_x_ (x) + , pointer_y_ (y) + , key_state_ (0) + , selection_mode_ (selection_mode) + { + if (alt) + key_state_ = KeyboardEvent::Alt; + + if (ctrl) + key_state_ |= KeyboardEvent::Ctrl; + + if (shift) + key_state_ |= KeyboardEvent::Shift; + } + + const MouseEvent::Type& + MouseEvent::getType () const + { + return (type_); + } + + void + MouseEvent::setType (const Type& type) + { + type_ = type; + } + + const MouseEvent::MouseButton& + MouseEvent::getButton () const + { + return (button_); + } + + void + MouseEvent::setButton (const MouseButton& button) + { + button_ = button; + } + + unsigned int + MouseEvent::getX () const + { + return (pointer_x_); + } + + unsigned int + MouseEvent::getY () const + { + return (pointer_y_); + } + + unsigned int + MouseEvent::getKeyboardModifiers () const + { + return (key_state_); + } + + bool + MouseEvent::getSelectionMode () const + { + return (selection_mode_); + } + + } //namespace visualization +} //namespace pcl + +#endif /* PCL_VISUALIZATION_MOUSE_EVENT_H_ */ + diff --git a/pcl-1.7/pcl/visualization/pcl_painter2D.h b/pcl-1.7/pcl/visualization/pcl_painter2D.h new file mode 100644 index 0000000..d7cf85a --- /dev/null +++ b/pcl-1.7/pcl/visualization/pcl_painter2D.h @@ -0,0 +1,471 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#ifndef PCL_VISUALUALIZATION_PCL_PAINTER2D_H_ +#define PCL_VISUALUALIZATION_PCL_PAINTER2D_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "vtkCommand.h" + +namespace pcl +{ + namespace visualization + { + + /** \brief Abstract class for storing figure information. All the derived class uses the same method draw() to invoke different drawing function of vtkContext2D + * \author Kripasindhu Sarkar + * \ingroup visualization + */ + struct Figure2D + { + std::vector info_; //information stored in a general form for every object + vtkPen *pen_; //the corresponding pen and brush for the figure + vtkBrush *brush_; + vtkTransform2D *transform_; + + Figure2D (std::vector info, vtkPen *p, vtkBrush * b, vtkTransform2D *t) + { + this->pen_ = vtkPen::New (); + this->brush_ = vtkBrush::New (); + this->transform_ = vtkTransform2D::New(); + + this->pen_->DeepCopy (p); + this->brush_->DeepCopy (b); + this->transform_->SetMatrix (t->GetMatrix()); + this->info_ = info; //note: it copies :-) + } + + Figure2D (vtkPen *p, vtkBrush * b, vtkTransform2D *t) + { + this->pen_ = vtkPen::New (); + this->brush_ = vtkBrush::New (); + this->transform_ = vtkTransform2D::New(); + + this->pen_->DeepCopy (p); + this->brush_->DeepCopy (b); + this->transform_->SetMatrix (t->GetMatrix()); + } + + void applyInternals (vtkContext2D *painter) + { + painter->ApplyPen (pen_); + painter->ApplyBrush (brush_); + painter->GetDevice ()->SetMatrix (transform_->GetMatrix()); + } + + virtual void draw (vtkContext2D *) {} + }; + + /** \brief Class for PolyLine + */ + struct FPolyLine2D : public Figure2D + { + + FPolyLine2D (std::vector info, vtkPen *p, vtkBrush * b, vtkTransform2D *t) : Figure2D (info, p, b, t){} + + void draw (vtkContext2D * painter) + { + applyInternals(painter); + painter->DrawPoly (&info_[0], static_cast (info_.size ()) / 2); + } + }; + + /** \brief Class for storing Points + */ + struct FPoints2D : public Figure2D + { + + FPoints2D (std::vector info, vtkPen *p, vtkBrush * b, vtkTransform2D *t) : Figure2D (info, p, b, t) {} + + void draw (vtkContext2D * painter) + { + applyInternals(painter); + painter->DrawPoints (&info_[0], static_cast (info_.size ()) / 2); + } + }; + + /** \brief Class for storing Quads + */ + struct FQuad2D : public Figure2D + { + + FQuad2D (std::vector info, vtkPen *p, vtkBrush * b, vtkTransform2D *t) : Figure2D (info, p, b, t) {} + + void draw (vtkContext2D * painter) + { + applyInternals(painter); + painter->DrawQuad (&info_[0]); + } + }; + + /** \brief Class for Polygon + */ + struct FPolygon2D : public Figure2D + { + + FPolygon2D (std::vector info, vtkPen *p, vtkBrush * b, vtkTransform2D *t) : Figure2D (info, p, b, t){} + + void draw (vtkContext2D * painter) + { + applyInternals(painter); + painter->DrawPolygon (&info_[0], static_cast (info_.size ()) / 2); + } + }; + + /** \brief Class for storing EllipticArc; every ellipse , circle are covered by this + */ + struct FEllipticArc2D : public Figure2D + { + + FEllipticArc2D (std::vector info, vtkPen *p, vtkBrush * b, vtkTransform2D *t) : Figure2D (info, p, b, t) {} + + FEllipticArc2D (float x, float y, float rx, float ry, float sa, float ea, vtkPen *p, vtkBrush * b, vtkTransform2D *t) : Figure2D (p, b, t) + { + info_.resize (6); + info_[0] = x; + info_[1] = y; + info_[2] = rx; + info_[3] = ry; + info_[4] = sa; + info_[5] = ea; + } + + void draw (vtkContext2D * painter) + { + applyInternals(painter); + painter->DrawEllipticArc (info_[0], info_[1], info_[2], info_[3], info_[4], info_[5]); + } + }; + + + ////////////////////////////////////The Main Painter Class begins here////////////////////////////////////// + /** \brief PCL Painter2D main class. Class for drawing 2D figures + * \author Kripasindhu Sarkar + * \ingroup visualization + */ + class PCL_EXPORTS PCLPainter2D: public vtkContextItem + { + public: + + //static PCLPainter2D *New(); + + /** \brief Constructor of the class + */ + PCLPainter2D (char const * name = "PCLPainter2D"); + vtkTypeMacro (PCLPainter2D, vtkContextItem); + + /** \brief Paint event for the chart, called whenever the chart needs to be drawn + * \param[in] painter Name of the window + */ + virtual bool + Paint (vtkContext2D *painter); + + /** \brief Draw a line between the specified points. + * \param[in] x1 X coordinate of the starting point of the line + * \param[in] y1 Y coordinate of the starting point of the line + * \param[in] x2 X coordinate of the ending point of the line + * \param[in] y2 Y coordinate of the ending point of the line + */ + void + addLine (float x1, float y1, float x2, float y2); + + /** \brief Draw line(s) between the specified points + * \param[in] p a vector of size 2*n and the points are packed x1, y1, x2, y2 etc. + */ + void + addLine (std::vector p); + + + /** \brief Draw specified point(s). + * \param[in] x X coordinate of the point + * \param[in] y Y coordinate of the point + */ + void + addPoint (float x, float y); + /** \brief Draw specified point(s). + * \param[in] points a vector of size 2*n and the points are packed x1, y1, x2, y2 etc. + */ + + void + addPoints (std::vector points); + + + /** \brief Draw a rectangle based on the given points + * \param[in] x X coordinate of the origin + * \param[in] y Y coordinate of the origin + * \param[in] width width of the rectangle + * \param[in] height height of the rectangle + */ + void + addRect (float x, float y, float width, float height); + + /** \brief Draw a quadrilateral based on the given points + * \param[in] p a vector of size 8 and the points are packed x1, y1, x2, y2, x3, y3 and x4, y4. + */ + void + addQuad (std::vector p); + + /** \brief Draw a polygon between the specified points + * \param[in] p a vector of size 2*n and the points are packed x1, y1, x2, y2 etc. + */ + void + addPolygon (std::vector p); + + + /** \brief Draw an ellipse based on the inputs + * \param[in] x X coordinate of the origin + * \param[in] y Y coordinate of the origin + * \param[in] rx X radius of the ellipse + * \param[in] ry Y radius of the ellipse + */ + void + addEllipse (float x, float y, float rx, float ry); + + /** \brief Draw a circle based on the inputs + * \param[in] x X coordinate of the origin + * \param[in] y Y coordinate of the origin + * \param[in] r radius of the circle + */ + void + addCircle (float x, float y, float r); + + /** \brief Draw an elliptic arc based on the inputs + * \param[in] x X coordinate of the origin + * \param[in] y Y coordinate of the origin + * \param[in] rx X radius of the ellipse + * \param[in] ry Y radius of the ellipse + * \param[in] start_angle the starting angle of the arc expressed in degrees + * \param[in] end_angle the ending angle of the arc expressed in degrees + */ + void + addEllipticArc (float x, float y, float rx, float ry, float start_angle, float end_angle); + + /** \brief Draw an arc based on the inputs + * \param[in] x X coordinate of the origin + * \param[in] y Y coordinate of the origin + * \param[in] r radius of the circle + * \param[in] start_angle the starting angle of the arc expressed in degrees + * \param[in] end_angle the ending angle of the arc expressed in degrees + */ + void + addArc (float x, float y, float r, float start_angle, float end_angle); + + + /** \brief Create a translation matrix and concatenate it with the current transformation. + * \param[in] x translation along X axis + * \param[in] y translation along Y axis + */ + void + translatePen (double x, double y); + + /** \brief Create a rotation matrix and concatenate it with the current transformation. + * \param[in] angle angle in degrees + */ + void + rotatePen(double angle); + + /** \brief Create a scale matrix and concatenate it with the current transformation. + * \param[in] x translation along X axis + * \param[in] y translation along Y axis + */ + void + scalePen(double x, double y); + + /** \brief Create a translation matrix and concatenate it with the current transformation. + * \param[in] matrix the transformation matrix + */ + void + setTransform(vtkMatrix3x3 *matrix); + + /** \brief Returns the current transformation matrix. + */ + vtkMatrix3x3 * + getTransform(); + + /** \brief Clears all the transformation applied. Sets the transformation matrix to Identity + */ + void + clearTransform(); + + /** \brief remove all the figures from the window + */ + void + clearFigures(); + + /** \brief set/get methods for current working vtkPen + */ + void setPenColor (unsigned char r, unsigned char g, unsigned char b, unsigned char a); + void setPenWidth (float w); + void setPenType (int type); + + /** \brief set/get methods for current working vtkPen + */ + unsigned char* getPenColor (); + float getPenWidth (); + int getPenType (); + void setPen (vtkPen *pen); + vtkPen* getPen (); + + /** \brief set/get methods for current working vtkBrush + */ + void setBrush (vtkBrush *brush); + vtkBrush* getBrush (); + void setBrushColor (unsigned char r, unsigned char g, unsigned char b, unsigned char a); + unsigned char* getBrushColor (); + + /** \brief set/get method for the viewport's background color. + * \param[in] r the red component of the RGB color + * \param[in] g the green component of the RGB color + * \param[in] b the blue component of the RGB color + */ + void + setBackgroundColor (const double r, const double g, const double b); + + /** \brief set/get method for the viewport's background color. + * \param [in] color the array containing the 3 component of the RGB color + */ + void + setBackgroundColor (const double color[3]); + + /** \brief set/get method for the viewport's background color. + * \return [out] color the array containing the 3 component of the RGB color + */ + double * + getBackgroundColor (); + + + /** \brief set/get method for the window size. + * \param[in] w the width of the window + * \param[in] h the height of the window + */ + void + setWindowSize (int w, int h); + + /** \brief set/get method for the window size. + * \return[in] array containing the width and height of the window + */ + int * + getWindowSize (); + + /** \brief displays all the figures added in a window. + */ + void display (); + + /** \brief spins (runs the event loop) the interactor for spin_time amount of time. The name is confusing and will be probably obsolete in the future release with a single overloaded spin()/display() function. + * \param[in] spin_time - How long (in ms) should the visualization loop be allowed to run. + */ + void spinOnce ( const int spin_time = 0 ); + + /** \brief spins (runs the event loop) the interactor indefinitely. Same as display() - added to retain the similarity between other existing visualization classes + */ + void spin (); + + private: + //std::map< int, std::vector< std::vector > > figures_; //FIG_TYPE -> vector + + //All the figures drawn till now gets stored here + std::vector figures_; + + //state variables of the class + vtkPen *current_pen_; + vtkBrush *current_brush_; + vtkTransform2D *current_transform_; + int win_width_, win_height_; + double bkg_color_[3]; + + vtkContextView *view_; + + //####event callback class#### + struct ExitMainLoopTimerCallback : public vtkCommand + { + static ExitMainLoopTimerCallback* New () + { + return (new ExitMainLoopTimerCallback); + } + virtual void + Execute (vtkObject* vtkNotUsed (caller), unsigned long event_id, void* call_data) + { + if (event_id != vtkCommand::TimerEvent) + return; + int timer_id = *(reinterpret_cast (call_data)); + + if (timer_id != right_timer_id) + return; + + // Stop vtk loop and send notification to app to wake it up +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + interactor->stopLoop (); +#else + interactor->TerminateApp (); +#endif + } + int right_timer_id; +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + PCLVisualizerInteractor *interactor; +#else + vtkRenderWindowInteractor *interactor; +#endif + }; + + /** \brief Callback object enabling us to leave the main loop, when a timer fires. */ + vtkSmartPointer exit_loop_timer_; + }; + + } +} + +#endif /* PCL_VISUALUALIZATION_PCL_PAINTER2D_H_ */ + diff --git a/pcl-1.7/pcl/visualization/pcl_plotter.h b/pcl-1.7/pcl/visualization/pcl_plotter.h new file mode 100644 index 0000000..6b966eb --- /dev/null +++ b/pcl-1.7/pcl/visualization/pcl_plotter.h @@ -0,0 +1,478 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_VISUALUALIZATION_PCL_PLOTTER_H_ +#define PCL_VISUALUALIZATION_PCL_PLOTTER_H_ + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +class PCLVisualizerInteractor; +class vtkRenderWindow; +class vtkRenderWindowInteractor; +class vtkContextView; +class vtkChartXY; +class vtkColorSeries; + +#include +#include +#include + +namespace pcl +{ + namespace visualization + { + /** \brief PCL Plotter main class. Given point correspondences this class + * can be used to plot the data one against the other and display it on the + * screen. It also has methods for providing plot for important functions + * like histogram etc. Important functions of PCLHistogramVisualizer are + * redefined here so that this single class can take responsibility of all + * plotting related functionalities. + * + * \author Kripasindhu Sarkar + * \ingroup visualization + */ + class PCL_EXPORTS PCLPlotter + { + public: + + /**\brief A representation of polynomial function. i'th element of the vector denotes the coefficient of x^i of the polynomial in variable x. + */ + typedef std::vector PolynomialFunction; + + /**\brief A representation of rational function, defined as the ratio of two polynomial functions. pair::first denotes the numerator and pair::second denotes the denominator of the Rational function. + */ + typedef std::pair RationalFunction; + + /** \brief PCL Plotter constructor. + * \param[in] name Name of the window + */ + PCLPlotter (char const * name = "PCL Plotter"); + + /** \brief Destructor. */ + ~PCLPlotter(); + + /** \brief Adds a plot with correspondences in the arrays arrayX and arrayY + * \param[in] array_X X coordinates of point correspondence array + * \param[in] array_Y Y coordinates of point correspondence array + * \param[in] size length of the array arrayX and arrayY + * \param[in] name name of the plot which appears in the legend when toggled on + * \param[in] type type of the graph plotted. vtkChart::LINE for line plot, vtkChart::BAR for bar plot, and vtkChart::POINTS for a scattered point plot + * \param[in] color a character array of 4 fields denoting the R,G,B and A component of the color of the plot ranging from 0 to 255. If this argument is not passed (or NULL is passed) the plot is colored based on a color scheme + */ + void + addPlotData (double const *array_X, + double const *array_Y, + unsigned long size, + char const * name = "Y Axis", + int type = vtkChart::LINE , + char const *color=NULL); + + /** \brief Adds a plot with correspondences in vectors arrayX and arrayY. This is the vector version of the addPlotData function. + * \param[in] array_x X coordinates of point correspondence array + * \param[in] array_y Y coordinates of point correspondence array + * \param[in] name name of the plot which appears in the legend when toggled on + * \param[in] type type of the graph plotted. vtkChart::LINE for line plot, vtkChart::BAR for bar plot, and vtkChart::POINTS for a scattered point plot + * \param[in] color a character array of 4 fields denoting the R,G,B and A component of the color of the plot ranging from 0 to 255. If this argument is not passed (or NULL is passed) the plot is colored based on a color scheme + */ + void + addPlotData (std::vector const &array_x, + std::vectorconst &array_y, + char const * name = "Y Axis", + int type = vtkChart::LINE, + std::vector const &color = std::vector ()); + + /** \brief Adds a plot with correspondences in vector of pairs. The the first and second field of the pairs of the vector forms the correspondence. + * \param plot_data + * \param[in] name name of the plot which appears in the legend when toggled on + * \param[in] type type of the graph plotted. vtkChart::LINE for line plot, vtkChart::BAR for bar plot, and vtkChart::POINTS for a scattered point plot + * \param[in] color a character array of 4 fields denoting the R,G,B and A component of the color of the plot ranging from 0 to 255. If this argument is not passed (or NULL is passed) the plot is colored based on a color scheme + */ + void + addPlotData (std::vector > const &plot_data, + char const * name = "Y Axis", + int type = vtkChart::LINE, + std::vector const &color = std::vector()); + + /** \brief Adds a plot based on the given polynomial function and the range in X axis. + * \param[in] p_function A polynomial function which is represented by a vector which stores the coefficients. See description on the typedef. + * \param[in] x_min the left boundary of the range for displaying the plot + * \param[in] x_max the right boundary of the range for displaying the plot + * \param[in] name name of the plot which appears in the legend when toggled on + * \param[in] num_points Number of points plotted to show the graph. More this number, more is the resolution. + * \param[in] type type of the graph plotted. vtkChart::LINE for line plot, vtkChart::BAR for bar plot, and vtkChart::POINTS for a scattered point plot + * \param[in] color a character array of 4 fields denoting the R,G,B and A component of the color of the plot ranging from 0 to 255. If this argument is not passed (or NULL is passed) the plot is colored based on a color scheme + */ + void + addPlotData (PolynomialFunction const & p_function, + double x_min, double x_max, + char const *name = "Y Axis", + int num_points = 100, + int type = vtkChart::LINE, + std::vector const &color = std::vector()); + + /** \brief Adds a plot based on the given rational function and the range in X axis. + * \param[in] r_function A rational function which is represented by the ratio of two polynomial functions. See description on the typedef for more details. + * \param[in] x_min the left boundary of the range for displaying the plot + * \param[in] x_max the right boundary of the range for displaying the plot + * \param[in] name name of the plot which appears in the legend when toggled on + * \param[in] num_points Number of points plotted to show the graph. More this number, more is the resolution. + * \param[in] type type of the graph plotted. vtkChart::LINE for line plot, vtkChart::BAR for bar plot, and vtkChart::POINTS for a scattered point plot + * \param[in] color a character array of 4 fields denoting the R,G,B and A component of the color of the plot ranging from 0 to 255. If this argument is not passed (or NULL is passed) the plot is colored based on a color scheme + */ + void + addPlotData (RationalFunction const & r_function, + double x_min, double x_max, + char const *name = "Y Axis", + int num_points = 100, + int type = vtkChart::LINE, + std::vector const &color = std::vector()); + + /** \brief Adds a plot based on a user defined callback function representing the function to plot + * \param[in] function a user defined callback function representing the relation y = function(x) + * \param[in] x_min the left boundary of the range for displaying the plot + * \param[in] x_max the right boundary of the range for displaying the plot + * \param[in] name name of the plot which appears in the legend when toggled on + * \param[in] num_points Number of points plotted to show the graph. More this number, more is the resolution. + * \param[in] type type of the graph plotted. vtkChart::LINE for line plot, vtkChart::BAR for bar plot, and vtkChart::POINTS for a scattered point plot + * \param[in] color a character array of 4 fields denoting the R,G,B and A component of the color of the plot ranging from 0 to 255. If this argument is not passed (or NULL is passed) the plot is colored based on a color scheme + */ + void + addPlotData (double (*function)(double), + double x_min, double x_max, + char const *name = "Y Axis", + int num_points = 100, + int type = vtkChart::LINE, + std::vector const &color = std::vector()); + + /** \brief Adds a plot based on a space/tab delimited table provided in a file + * \param[in] filename name of the file containing the table. 1st column represents the values of X-Axis. Rest of the columns represent the corresponding values in Y-Axes. First row of the file is concidered for naming/labling of the plot. The plot-names should not contain any space in between. + * \param[in] type type of the graph plotted. vtkChart::LINE for line plot, vtkChart::BAR for bar plot, and vtkChart::POINTS for a scattered point plot + */ + void + addPlotData (char const * filename, + int type = vtkChart::LINE); + + /** \brief Bins the elements in vector data into nbins equally spaced containers and plots the resulted histogram + * \param[in] data the raw data + * \param[in] nbins the number of bins for the histogram + * \param[in] name name of this histogram which will appear on legends if toggled on + * \param[in] color a character array of 4 fields denoting the R,G,B and A component of the color of the plot ranging from 0 to 255. If this argument is not passed (or an empty vector is passed) the histogram is colored based on the current color scheme + */ + void + addHistogramData (std::vector const & data, + int const nbins = 10, + char const * name = "Histogram", + std::vector const &color = std::vector()); + + //##PCLHistogramVisulizer methods## + /** \brief Add a histogram feature to screen as a separate window, from a cloud containing a single histogram. + * \param[in] cloud the PointCloud dataset containing the histogram + * \param[in] hsize the length of the histogram + * \param[in] id the point cloud object id (default: cloud) + * \param[in] win_width the width of the window + * \param[in] win_height the height of the window + */ + template bool + addFeatureHistogram (const pcl::PointCloud &cloud, + int hsize, + const std::string &id = "cloud", int win_width = 640, int win_height = 200); + + /** \brief Add a histogram feature to screen as a separate window from a cloud containing a single histogram. + * \param[in] cloud the PointCloud dataset containing the histogram + * \param[in] field_name the field name containing the histogram + * \param[in] id the point cloud object id (default: cloud) + * \param[in] win_width the width of the window + * \param[in] win_height the height of the window + */ + bool + addFeatureHistogram (const pcl::PCLPointCloud2 &cloud, + const std::string &field_name, + const std::string &id = "cloud", int win_width = 640, int win_height = 200); + + /** \brief Add a histogram feature to screen as a separate window. + * \param[in] cloud the PointCloud dataset containing the histogram + * \param[in] field_name the field name containing the histogram + * \param[in] index the point index to extract the histogram from + * \param[in] id the point cloud object id (default: cloud) + * \param[in] win_width the width of the window + * \param[in] win_height the height of the window + */ + template bool + addFeatureHistogram (const pcl::PointCloud &cloud, + const std::string &field_name, + const int index, + const std::string &id = "cloud", int win_width = 640, int win_height = 200); + + /** \brief Add a histogram feature to screen as a separate window. + * \param[in] cloud the PointCloud dataset containing the histogram + * \param[in] field_name the field name containing the histogram + * \param[in] index the point index to extract the histogram from + * \param[in] id the point cloud object id (default: cloud) + * \param[in] win_width the width of the window + * \param[in] win_height the height of the window + */ + bool + addFeatureHistogram (const pcl::PCLPointCloud2 &cloud, + const std::string &field_name, + const int index, + const std::string &id = "cloud", int win_width = 640, int win_height = 200); + + /** \brief Draws all the plots added by addPlotData() or addHistogramData() till now */ + void + plot (); + + /** \brief Spins (runs the event loop) the interactor for spin_time amount of time. The name is confusing and will be probably obsolete in the future release with a single overloaded spin()/display() function. + * \param[in] spin_time - How long (in ms) should the visualization loop be allowed to run. + */ + void + spinOnce (const int spin_time = 1); + + /** \brief Spins (runs the event loop) the interactor indefinitely. Same as plot() - added to retain the similarity between other existing visualization classes. */ + void + spin (); + + /** \brief Remove all plots from the window. */ + void + clearPlots(); + + /** \brief Set method for the color scheme of the plot. The plots gets autocolored differently based on the color scheme. + * \param[in] scheme the color scheme. Possible values are vtkColorSeries::SPECTRUM, vtkColorSeries::WARM, vtkColorSeries::COOL, vtkColorSeries::BLUES, vtkColorSeries::WILD_FLOWER, vtkColorSeries::CITRUS + */ + void + setColorScheme (int scheme); + + /** \brief get the currently used color scheme + * \return[out] the currently used color scheme. Values include WARM, COOL, BLUES, WILD_FLOWER, CITRUS, CUSTOM + */ + int + getColorScheme (); + + /** \brief set/get method for the viewport's background color. + * \param[in] r the red component of the RGB color + * \param[in] g the green component of the RGB color + * \param[in] b the blue component of the RGB color + */ + void + setBackgroundColor (const double r, const double g, const double b); + + /** \brief set/get method for the viewport's background color. + * \param [in] color the array containing the 3 component of the RGB color + */ + void + setBackgroundColor (const double color[3]); + + /** \brief set/get method for the viewport's background color. + * \return [out] color the array containing the 3 component of the RGB color + */ + double * + getBackgroundColor (); + + /** \brief Set logical range of the X-Axis in plot coordinates + * \param[in] min the left boundary of the range + * \param[in] max the right boundary of the range + */ + void + setXRange (double min, double max); + + /** \brief Set logical range of the Y-Axis in plot coordinates + * \param[in] min the left boundary of the range + * \param[in] max the right boundary of the range + */ + void + setYRange (double min, double max); + + /** \brief Set the main title of the plot + * \param[in] title the title to set + */ + void + setTitle (const char *title); + + /** \brief Set the title of the X-Axis + * \param[in] title the title to set + */ + void + setXTitle (const char *title); + + /** \brief Set the title of the Y-Axis + * \param[in] title the title to set + */ + void + setYTitle (const char *title); + + /** \brief Shows the legend of the graph + * \param[in] flag pass flag = true for the display of the legend of the graph + */ + void + setShowLegend (bool flag); + + /** \brief set/get method for the window size. + * \param[in] w the width of the window + * \param[in] h the height of the window + */ + void + setWindowSize (int w, int h); + + /** \brief Set the position in screen coordinates. + * \param[in] x where to move the window to (X) + * \param[in] y where to move the window to (Y) + */ + void + setWindowPosition (int x, int y); + + /** \brief Set the visualizer window name. + * \param[in] name the name of the window + */ + void + setWindowName (const std::string &name); + + /** \brief set/get method for the window size. + * \return[in] array containing the width and height of the window + */ + int* + getWindowSize (); + + /** \brief Return a pointer to the underlying VTK RenderWindow used. */ + vtkSmartPointer + getRenderWindow (); + + /** \brief Set the view's interactor. */ + void + setViewInteractor (vtkSmartPointer interactor); + + /** \brief Initialize and Start the view's interactor. */ + void + startInteractor (); + + /** \brief Render the vtkWindow once. */ + void renderOnce(); + + /** \brief Returns true when the user tried to close the window */ + bool + wasStopped () const; + + /** \brief Stop the interaction and close the visualizaton window. */ + void + close (); + + private: + vtkSmartPointer view_; + vtkSmartPointer chart_; + vtkSmartPointer color_series_; //for automatic coloring + + //extra state variables + int current_plot_; //stores the id of the current (most recent) plot, used in automatic coloring and other state change schemes + int win_width_, win_height_; + int win_x_, win_y_; //window position according to screen coordinate + double bkg_color_[3]; + std::string win_name_; + + //####event callback class#### + struct ExitMainLoopTimerCallback : public vtkCommand + { + static ExitMainLoopTimerCallback* New () + { + return (new ExitMainLoopTimerCallback); + } + virtual void + Execute (vtkObject*, unsigned long event_id, void* call_data); + + int right_timer_id; +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + PCLVisualizerInteractor *interactor; +#else + vtkRenderWindowInteractor *interactor; +#endif + }; + + struct ExitCallback : public vtkCommand + { + static ExitCallback* New () + { + return new ExitCallback; + } + virtual void + Execute (vtkObject*, unsigned long event_id, void*); + + PCLPlotter *plotter; + }; + + /** \brief Set to false if the interaction loop is running. */ + bool stopped_; + + /** \brief Callback object enabling us to leave the main loop, when a timer fires. */ + vtkSmartPointer exit_loop_timer_; + vtkSmartPointer exit_callback_; + + ////////////////////////////////////IMPORTANT PRIVATE COMPUTING FUNCTIONS//////////////////////////////////////////////////// + /** \brief computes the value of the polynomial function at val + * \param[in] p_function polynomial function + * \param[in] value the value at which the function is to be computed + */ + double + compute (PolynomialFunction const & p_function, double val); + + /** \brief computes the value of the rational function at val + * \param[in] r_function the rational function + * \param[in] value the value at which the function is to be computed + */ + double + compute (RationalFunction const & r_function, double val); + + /** \brief bins the elements in vector data into nbins equally spaced containers and returns the histogram form, ie, computes the histogram for 'data' + * \param[in] data data who's frequency distribution is to be found + * \param[in] nbins number of bins for the histogram + * \param[out] histogram vector of pairs containing the histogram. The first field of the pair represent the middle value of the corresponding bin. The second field denotes the frequency of data in that bin. + */ + void + computeHistogram (std::vector const & data, int const nbins, std::vector > &histogram); + }; + } +} + +#include + +#endif /* PCL_VISUALUALIZATION_PCL_PLOTTER_H_ */ + diff --git a/pcl-1.7/pcl/visualization/pcl_visualizer.h b/pcl-1.7/pcl/visualization/pcl_visualizer.h new file mode 100644 index 0000000..18ba43a --- /dev/null +++ b/pcl-1.7/pcl/visualization/pcl_visualizer.h @@ -0,0 +1,2156 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_PCL_VISUALIZER_H_ +#define PCL_PCL_VISUALIZER_H_ + +// PCL includes +#include +#include +#include +#include +// +#include +#include +#include +#include +#include +#include +#include +#include + +// VTK includes +class vtkPolyData; +class vtkTextActor; +class vtkRenderWindow; +class vtkOrientationMarkerWidget; +class vtkAppendPolyData; +class vtkRenderWindow; +class vtkRenderWindowInteractor; +class vtkTransform; +class vtkInteractorStyle; +class vtkLODActor; +class vtkProp; +class vtkActor; +class vtkDataSet; +class vtkUnstructuredGrid; + +namespace pcl +{ + template class PointCloud; + template class PlanarPolygon; + + namespace visualization + { + /** \brief PCL Visualizer main class. + * \author Radu B. Rusu + * \ingroup visualization + * \note This class can NOT be used across multiple threads. Only call functions of objects of this class + * from the same thread that they were created in! Some methods, e.g. addPointCloud, will crash if called + * from other threads. + */ + class PCL_EXPORTS PCLVisualizer + { + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + + typedef PointCloudGeometryHandler GeometryHandler; + typedef GeometryHandler::Ptr GeometryHandlerPtr; + typedef GeometryHandler::ConstPtr GeometryHandlerConstPtr; + + typedef PointCloudColorHandler ColorHandler; + typedef ColorHandler::Ptr ColorHandlerPtr; + typedef ColorHandler::ConstPtr ColorHandlerConstPtr; + + /** \brief PCL Visualizer constructor. + * \param[in] name the window name (empty by default) + * \param[in] create_interactor if true (default), create an interactor, false otherwise + */ + PCLVisualizer (const std::string &name = "", const bool create_interactor = true); + + /** \brief PCL Visualizer constructor. + * \param[in] argc + * \param[in] argv + * \param[in] name the window name (empty by default) + * \param[in] style interactor style (defaults to PCLVisualizerInteractorStyle) + * \param[in] create_interactor if true (default), create an interactor, false otherwise + */ + PCLVisualizer (int &argc, char **argv, const std::string &name = "", + PCLVisualizerInteractorStyle* style = PCLVisualizerInteractorStyle::New (), const bool create_interactor = true); + + /** \brief PCL Visualizer destructor. */ + virtual ~PCLVisualizer (); + + /** \brief Enables/Disabled the underlying window mode to full screen. + * \note This might or might not work, depending on your window manager. + * See the VTK documentation for additional details. + * \param[in] mode true for full screen, false otherwise + */ + void + setFullScreen (bool mode); + + /** \brief Set the visualizer window name. + * \param[in] name the name of the window + */ + void + setWindowName (const std::string &name); + + /** \brief Enables or disable the underlying window borders. + * \note This might or might not work, depending on your window manager. + * See the VTK documentation for additional details. + * \param[in] mode true for borders, false otherwise + */ + void + setWindowBorders (bool mode); + + /** \brief Register a callback boost::function for keyboard events + * \param[in] cb a boost function that will be registered as a callback for a keyboard event + * \return a connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerKeyboardCallback (boost::function cb); + + /** \brief Register a callback function for keyboard events + * \param[in] callback the function that will be registered as a callback for a keyboard event + * \param[in] cookie user data that is passed to the callback + * \return a connection object that allows to disconnect the callback function. + */ + inline boost::signals2::connection + registerKeyboardCallback (void (*callback) (const pcl::visualization::KeyboardEvent&, void*), void* cookie = NULL) + { + return (registerKeyboardCallback (boost::bind (callback, _1, cookie))); + } + + /** \brief Register a callback function for keyboard events + * \param[in] callback the member function that will be registered as a callback for a keyboard event + * \param[in] instance instance to the class that implements the callback function + * \param[in] cookie user data that is passed to the callback + * \return a connection object that allows to disconnect the callback function. + */ + template inline boost::signals2::connection + registerKeyboardCallback (void (T::*callback) (const pcl::visualization::KeyboardEvent&, void*), T& instance, void* cookie = NULL) + { + return (registerKeyboardCallback (boost::bind (callback, boost::ref (instance), _1, cookie))); + } + + /** \brief Register a callback function for mouse events + * \param[in] cb a boost function that will be registered as a callback for a mouse event + * \return a connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerMouseCallback (boost::function cb); + + /** \brief Register a callback function for mouse events + * \param[in] callback the function that will be registered as a callback for a mouse event + * \param[in] cookie user data that is passed to the callback + * \return a connection object that allows to disconnect the callback function. + */ + inline boost::signals2::connection + registerMouseCallback (void (*callback) (const pcl::visualization::MouseEvent&, void*), void* cookie = NULL) + { + return (registerMouseCallback (boost::bind (callback, _1, cookie))); + } + + /** \brief Register a callback function for mouse events + * \param[in] callback the member function that will be registered as a callback for a mouse event + * \param[in] instance instance to the class that implements the callback function + * \param[in] cookie user data that is passed to the callback + * \return a connection object that allows to disconnect the callback function. + */ + template inline boost::signals2::connection + registerMouseCallback (void (T::*callback) (const pcl::visualization::MouseEvent&, void*), T& instance, void* cookie = NULL) + { + return (registerMouseCallback (boost::bind (callback, boost::ref (instance), _1, cookie))); + } + + /** \brief Register a callback function for point picking events + * \param[in] cb a boost function that will be registered as a callback for a point picking event + * \return a connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerPointPickingCallback (boost::function cb); + + /** \brief Register a callback function for point picking events + * \param[in] callback the function that will be registered as a callback for a point picking event + * \param[in] cookie user data that is passed to the callback + * \return a connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerPointPickingCallback (void (*callback) (const pcl::visualization::PointPickingEvent&, void*), void* cookie = NULL); + + /** \brief Register a callback function for point picking events + * \param[in] callback the member function that will be registered as a callback for a point picking event + * \param[in] instance instance to the class that implements the callback function + * \param[in] cookie user data that is passed to the callback + * \return a connection object that allows to disconnect the callback function. + */ + template inline boost::signals2::connection + registerPointPickingCallback (void (T::*callback) (const pcl::visualization::PointPickingEvent&, void*), T& instance, void* cookie = NULL) + { + return (registerPointPickingCallback (boost::bind (callback, boost::ref (instance), _1, cookie))); + } + + /** \brief Register a callback function for area picking events + * \param[in] cb a boost function that will be registered as a callback for an area picking event + * \return a connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerAreaPickingCallback (boost::function cb); + + /** \brief Register a callback function for area picking events + * \param[in] callback the function that will be registered as a callback for an area picking event + * \param[in] cookie user data that is passed to the callback + * \return a connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerAreaPickingCallback (void (*callback) (const pcl::visualization::AreaPickingEvent&, void*), void* cookie = NULL); + + /** \brief Register a callback function for area picking events + * \param[in] callback the member function that will be registered as a callback for an area picking event + * \param[in] instance instance to the class that implements the callback function + * \param[in] cookie user data that is passed to the callback + * \return a connection object that allows to disconnect the callback function. + */ + template inline boost::signals2::connection + registerAreaPickingCallback (void (T::*callback) (const pcl::visualization::AreaPickingEvent&, void*), T& instance, void* cookie = NULL) + { + return (registerAreaPickingCallback (boost::bind (callback, boost::ref (instance), _1, cookie))); + } + + /** \brief Spin method. Calls the interactor and runs an internal loop. */ + void + spin (); + + /** \brief Spin once method. Calls the interactor and updates the screen once. + * \param[in] time - How long (in ms) should the visualization loop be allowed to run. + * \param[in] force_redraw - if false it might return without doing anything if the + * interactor's framerate does not require a redraw yet. + */ + void + spinOnce (int time = 1, bool force_redraw = false); + + /** \brief Adds a widget which shows an interactive axes display for orientation + * \param[in] interactor - Pointer to the vtk interactor object used by the PCLVisualizer window + */ + void + addOrientationMarkerWidgetAxes (vtkRenderWindowInteractor* interactor); + + /** \brief Disables the Orientatation Marker Widget so it is removed from the renderer */ + void + removeOrientationMarkerWidgetAxes (); + + /** \brief Adds 3D axes describing a coordinate system to screen at 0,0,0. + * \param[in] scale the scale of the axes (default: 1) + * \param[in] viewport the view port where the 3D axes should be added (default: all) + */ + PCL_DEPRECATED ( + "addCoordinateSystem (scale, viewport) is deprecated, please use function " + "addCoordinateSystem (scale, id, viewport) with id a unique string identifier.") + void + addCoordinateSystem (double scale, int viewport); + + /** \brief Adds 3D axes describing a coordinate system to screen at 0,0,0. + * \param[in] scale the scale of the axes (default: 1) + * \param[in] id the coordinate system object id (default: reference) + * \param[in] viewport the view port where the 3D axes should be added (default: all) + */ + void + addCoordinateSystem (double scale = 1.0, const std::string& id = "reference", int viewport = 0); + + /** \brief Adds 3D axes describing a coordinate system to screen at x, y, z + * \param[in] scale the scale of the axes (default: 1) + * \param[in] x the X position of the axes + * \param[in] y the Y position of the axes + * \param[in] z the Z position of the axes + * \param[in] viewport the view port where the 3D axes should be added (default: all) + */ + PCL_DEPRECATED ( + "addCoordinateSystem (scale, x, y, z, viewport) is deprecated, please use function " + "addCoordinateSystem (scale, x, y, z, id, viewport) with id a unique string identifier.") + void + addCoordinateSystem (double scale, float x, float y, float z, int viewport); + + /** \brief Adds 3D axes describing a coordinate system to screen at x, y, z + * \param[in] scale the scale of the axes (default: 1) + * \param[in] x the X position of the axes + * \param[in] y the Y position of the axes + * \param[in] z the Z position of the axes + * \param[in] id the coordinate system object id (default: reference) + * \param[in] viewport the view port where the 3D axes should be added (default: all) + */ + void + addCoordinateSystem (double scale, float x, float y, float z, const std::string &id = "reference", int viewport = 0); + + /** \brief Adds 3D axes describing a coordinate system to screen at x, y, z, Roll,Pitch,Yaw + * + * \param[in] scale the scale of the axes (default: 1) + * \param[in] t transformation matrix + * \param[in] viewport the view port where the 3D axes should be added (default: all) + */ + PCL_DEPRECATED ( + "addCoordinateSystem (scale, t, viewport) is deprecated, please use function " + "addCoordinateSystem (scale, t, id, viewport) with id a unique string identifier.") + void + addCoordinateSystem (double scale, const Eigen::Affine3f& t, int viewport); + + /** \brief Adds 3D axes describing a coordinate system to screen at x, y, z, Roll,Pitch,Yaw + * + * \param[in] scale the scale of the axes (default: 1) + * \param[in] t transformation matrix + * \param[in] id the coordinate system object id (default: reference) + * \param[in] viewport the view port where the 3D axes should be added (default: all) + * + * RPY Angles + * Rotate the reference frame by the angle roll about axis x + * Rotate the reference frame by the angle pitch about axis y + * Rotate the reference frame by the angle yaw about axis z + * + * Description: + * Sets the orientation of the Prop3D. Orientation is specified as + * X,Y and Z rotations in that order, but they are performed as + * RotateZ, RotateX, and finally RotateY. + * + * All axies use right hand rule. x=red axis, y=green axis, z=blue axis + * z direction is point into the screen. + * \code + * z + * \ + * \ + * \ + * -----------> x + * | + * | + * | + * | + * | + * | + * y + * \endcode + */ + + void + addCoordinateSystem (double scale, const Eigen::Affine3f& t, const std::string &id = "reference", int viewport = 0); + + /** \brief Removes a previously added 3D axes (coordinate system) + * \param[in] viewport view port where the 3D axes should be removed from (default: all) + */ + PCL_DEPRECATED ( + "removeCoordinateSystem (viewport) is deprecated, please use function " + "addCoordinateSystem (id, viewport) with id a unique string identifier.") + bool + removeCoordinateSystem (int viewport); + + /** \brief Removes a previously added 3D axes (coordinate system) + * \param[in] id the coordinate system object id (default: reference) + * \param[in] viewport view port where the 3D axes should be removed from (default: all) + */ + bool + removeCoordinateSystem (const std::string &id = "reference", int viewport = 0); + + /** \brief Removes a Point Cloud from screen, based on a given ID. + * \param[in] id the point cloud object id (i.e., given on \a addPointCloud) + * \param[in] viewport view port from where the Point Cloud should be removed (default: all) + * \return true if the point cloud is successfully removed and false if the point cloud is + * not actually displayed + */ + bool + removePointCloud (const std::string &id = "cloud", int viewport = 0); + + /** \brief Removes a PolygonMesh from screen, based on a given ID. + * \param[in] id the polygon object id (i.e., given on \a addPolygonMesh) + * \param[in] viewport view port from where the PolygonMesh should be removed (default: all) + */ + inline bool + removePolygonMesh (const std::string &id = "polygon", int viewport = 0) + { + // Polygon Meshes are represented internally as point clouds with special cell array structures since 1.4 + return (removePointCloud (id, viewport)); + } + + /** \brief Removes an added shape from screen (line, polygon, etc.), based on a given ID + * \note This methods also removes PolygonMesh objects and PointClouds, if they match the ID + * \param[in] id the shape object id (i.e., given on \a addLine etc.) + * \param[in] viewport view port from where the Point Cloud should be removed (default: all) + */ + bool + removeShape (const std::string &id = "cloud", int viewport = 0); + + /** \brief Removes an added 3D text from the scene, based on a given ID + * \param[in] id the 3D text id (i.e., given on \a addText3D etc.) + * \param[in] viewport view port from where the 3D text should be removed (default: all) + */ + bool + removeText3D (const std::string &id = "cloud", int viewport = 0); + + /** \brief Remove all point cloud data on screen from the given viewport. + * \param[in] viewport view port from where the clouds should be removed (default: all) + */ + bool + removeAllPointClouds (int viewport = 0); + + /** \brief Remove all 3D shape data on screen from the given viewport. + * \param[in] viewport view port from where the shapes should be removed (default: all) + */ + bool + removeAllShapes (int viewport = 0); + + /** \brief Set the viewport's background color. + * \param[in] r the red component of the RGB color + * \param[in] g the green component of the RGB color + * \param[in] b the blue component of the RGB color + * \param[in] viewport the view port (default: all) + */ + void + setBackgroundColor (const double &r, const double &g, const double &b, int viewport = 0); + + /** \brief Add a text to screen + * \param[in] text the text to add + * \param[in] xpos the X position on screen where the text should be added + * \param[in] ypos the Y position on screen where the text should be added + * \param[in] id the text object id (default: equal to the "text" parameter) + * \param[in] viewport the view port (default: all) + */ + bool + addText (const std::string &text, + int xpos, int ypos, + const std::string &id = "", int viewport = 0); + + /** \brief Add a text to screen + * \param[in] text the text to add + * \param[in] xpos the X position on screen where the text should be added + * \param[in] ypos the Y position on screen where the text should be added + * \param[in] r the red color value + * \param[in] g the green color value + * \param[in] b the blue color vlaue + * \param[in] id the text object id (default: equal to the "text" parameter) + * \param[in] viewport the view port (default: all) + */ + bool + addText (const std::string &text, int xpos, int ypos, double r, double g, double b, + const std::string &id = "", int viewport = 0); + + /** \brief Add a text to screen + * \param[in] text the text to add + * \param[in] xpos the X position on screen where the text should be added + * \param[in] ypos the Y position on screen where the text should be added + * \param[in] fontsize the fontsize of the text + * \param[in] r the red color value + * \param[in] g the green color value + * \param[in] b the blue color vlaue + * \param[in] id the text object id (default: equal to the "text" parameter) + * \param[in] viewport the view port (default: all) + */ + bool + addText (const std::string &text, int xpos, int ypos, int fontsize, double r, double g, double b, + const std::string &id = "", int viewport = 0); + + + /** \brief Update a text to screen + * \param[in] text the text to update + * \param[in] xpos the new X position on screen + * \param[in] ypos the new Y position on screen + * \param[in] id the text object id (default: equal to the "text" parameter) + */ + bool + updateText (const std::string &text, + int xpos, int ypos, + const std::string &id = ""); + + /** \brief Update a text to screen + * \param[in] text the text to update + * \param[in] xpos the new X position on screen + * \param[in] ypos the new Y position on screen + * \param[in] r the red color value + * \param[in] g the green color value + * \param[in] b the blue color vlaue + * \param[in] id the text object id (default: equal to the "text" parameter) + */ + bool + updateText (const std::string &text, + int xpos, int ypos, double r, double g, double b, + const std::string &id = ""); + + /** \brief Update a text to screen + * \param[in] text the text to update + * \param[in] xpos the new X position on screen + * \param[in] ypos the new Y position on screen + * \param[in] fontsize the fontsize of the text + * \param[in] r the red color value + * \param[in] g the green color value + * \param[in] b the blue color vlaue + * \param[in] id the text object id (default: equal to the "text" parameter) + */ + bool + updateText (const std::string &text, + int xpos, int ypos, int fontsize, double r, double g, double b, + const std::string &id = ""); + + /** \brief Set the pose of an existing shape. + * + * Returns false if the shape doesn't exist, true if the pose was successfully + * updated. + * + * \param[in] id the shape or cloud object id (i.e., given on \a addLine etc.) + * \param[in] pose the new pose + * \return false if no shape or cloud with the specified ID was found + */ + bool + updateShapePose (const std::string &id, const Eigen::Affine3f& pose); + + /** \brief Set the pose of an existing coordinate system. + * + * Returns false if the coordinate system doesn't exist, true if the pose was successfully + * updated. + * + * \param[in] id the point cloud object id (i.e., given on \a addCoordinateSystem etc.) + * \param[in] pose the new pose + * \return false if no coordinate system with the specified ID was found + */ + bool + updateCoordinateSystemPose (const std::string &id, const Eigen::Affine3f& pose); + + /** \brief Set the pose of an existing point cloud. + * + * Returns false if the point cloud doesn't exist, true if the pose was successfully + * updated. + * + * \param[in] id the point cloud object id (i.e., given on \a addPointCloud etc.) + * \param[in] pose the new pose + * \return false if no point cloud with the specified ID was found + */ + bool + updatePointCloudPose (const std::string &id, const Eigen::Affine3f& pose); + + /** \brief Add a 3d text to the scene + * \param[in] text the text to add + * \param[in] position the world position where the text should be added + * \param[in] textScale the scale of the text to render + * \param[in] r the red color value + * \param[in] g the green color value + * \param[in] b the blue color value + * \param[in] id the text object id (default: equal to the "text" parameter) + * \param[in] viewport the view port (default: all) + */ + template bool + addText3D (const std::string &text, + const PointT &position, + double textScale = 1.0, + double r = 1.0, double g = 1.0, double b = 1.0, + const std::string &id = "", int viewport = 0); + + /** \brief Add the estimated surface normals of a Point Cloud to screen. + * \param[in] cloud the input point cloud dataset containing XYZ data and normals + * \param[in] level display only every level'th point (default: 100) + * \param[in] scale the normal arrow scale (default: 0.02m) + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + template bool + addPointCloudNormals (const typename pcl::PointCloud::ConstPtr &cloud, + int level = 100, float scale = 0.02f, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Add the estimated surface normals of a Point Cloud to screen. + * \param[in] cloud the input point cloud dataset containing the XYZ data + * \param[in] normals the input point cloud dataset containing the normal data + * \param[in] level display only every level'th point (default: 100) + * \param[in] scale the normal arrow scale (default: 0.02m) + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + template bool + addPointCloudNormals (const typename pcl::PointCloud::ConstPtr &cloud, + const typename pcl::PointCloud::ConstPtr &normals, + int level = 100, float scale = 0.02f, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Add the estimated principal curvatures of a Point Cloud to screen. + * \param[in] cloud the input point cloud dataset containing the XYZ data + * \param[in] normals the input point cloud dataset containing the normal data + * \param[in] pcs the input point cloud dataset containing the principal curvatures data + * \param[in] level display only every level'th point. Default: 100 + * \param[in] scale the normal arrow scale. Default: 1.0 + * \param[in] id the point cloud object id. Default: "cloud" + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + bool + addPointCloudPrincipalCurvatures ( + const pcl::PointCloud::ConstPtr &cloud, + const pcl::PointCloud::ConstPtr &normals, + const pcl::PointCloud::ConstPtr &pcs, + int level = 100, float scale = 1.0f, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Add the estimated surface intensity gradients of a Point Cloud to screen. + * \param[in] cloud the input point cloud dataset containing the XYZ data + * \param[in] gradients the input point cloud dataset containing the intensity gradient data + * \param[in] level display only every level'th point (default: 100) + * \param[in] scale the intensity gradient arrow scale (default: 1e-6m) + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + template bool + addPointCloudIntensityGradients (const typename pcl::PointCloud::ConstPtr &cloud, + const typename pcl::PointCloud::ConstPtr &gradients, + int level = 100, double scale = 1e-6, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Add a Point Cloud (templated) to screen. + * \param[in] cloud the input point cloud dataset + * \param[in] id the point cloud object id (default: cloud) + * \param viewport the view port where the Point Cloud should be added (default: all) + */ + template bool + addPointCloud (const typename pcl::PointCloud::ConstPtr &cloud, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Updates the XYZ data for an existing cloud object id on screen. + * \param[in] cloud the input point cloud dataset + * \param[in] id the point cloud object id to update (default: cloud) + * \return false if no cloud with the specified ID was found + */ + template bool + updatePointCloud (const typename pcl::PointCloud::ConstPtr &cloud, + const std::string &id = "cloud"); + + /** \brief Updates the XYZ data for an existing cloud object id on screen. + * \param[in] cloud the input point cloud dataset + * \param[in] geometry_handler the geometry handler to use + * \param[in] id the point cloud object id to update (default: cloud) + * \return false if no cloud with the specified ID was found + */ + template bool + updatePointCloud (const typename pcl::PointCloud::ConstPtr &cloud, + const PointCloudGeometryHandler &geometry_handler, + const std::string &id = "cloud"); + + /** \brief Updates the XYZ data for an existing cloud object id on screen. + * \param[in] cloud the input point cloud dataset + * \param[in] color_handler the color handler to use + * \param[in] id the point cloud object id to update (default: cloud) + * \return false if no cloud with the specified ID was found + */ + template bool + updatePointCloud (const typename pcl::PointCloud::ConstPtr &cloud, + const PointCloudColorHandler &color_handler, + const std::string &id = "cloud"); + + /** \brief Add a Point Cloud (templated) to screen. + * \param[in] cloud the input point cloud dataset + * \param[in] geometry_handler use a geometry handler object to extract the XYZ data + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + template bool + addPointCloud (const typename pcl::PointCloud::ConstPtr &cloud, + const PointCloudGeometryHandler &geometry_handler, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Add a Point Cloud (templated) to screen. + * + * Because the geometry handler is given as a pointer, it will be pushed back to the list of available + * handlers, rather than replacing the current active geometric handler. This makes it possible to + * switch between different geometric handlers 'on-the-fly' at runtime, from the PCLVisualizer + * interactor interface (using Alt+0..9). + * + * \param[in] cloud the input point cloud dataset + * \param[in] geometry_handler use a geometry handler object to extract the XYZ data + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + template bool + addPointCloud (const typename pcl::PointCloud::ConstPtr &cloud, + const GeometryHandlerConstPtr &geometry_handler, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Add a Point Cloud (templated) to screen. + * \param[in] cloud the input point cloud dataset + * \param[in] color_handler a specific PointCloud visualizer handler for colors + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + template bool + addPointCloud (const typename pcl::PointCloud::ConstPtr &cloud, + const PointCloudColorHandler &color_handler, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Add a Point Cloud (templated) to screen. + * + * Because the color handler is given as a pointer, it will be pushed back to the list of available + * handlers, rather than replacing the current active color handler. This makes it possible to + * switch between different color handlers 'on-the-fly' at runtime, from the PCLVisualizer + * interactor interface (using 0..9). + * + * \param[in] cloud the input point cloud dataset + * \param[in] color_handler a specific PointCloud visualizer handler for colors + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + template bool + addPointCloud (const typename pcl::PointCloud::ConstPtr &cloud, + const ColorHandlerConstPtr &color_handler, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Add a Point Cloud (templated) to screen. + * + * Because the geometry/color handler is given as a pointer, it will be pushed back to the list of + * available handlers, rather than replacing the current active handler. This makes it possible to + * switch between different handlers 'on-the-fly' at runtime, from the PCLVisualizer interactor + * interface (using [Alt+]0..9). + * + * \param[in] cloud the input point cloud dataset + * \param[in] geometry_handler a specific PointCloud visualizer handler for geometry + * \param[in] color_handler a specific PointCloud visualizer handler for colors + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + template bool + addPointCloud (const typename pcl::PointCloud::ConstPtr &cloud, + const GeometryHandlerConstPtr &geometry_handler, + const ColorHandlerConstPtr &color_handler, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Add a binary blob Point Cloud to screen. + * + * Because the geometry/color handler is given as a pointer, it will be pushed back to the list of + * available handlers, rather than replacing the current active handler. This makes it possible to + * switch between different handlers 'on-the-fly' at runtime, from the PCLVisualizer interactor + * interface (using [Alt+]0..9). + * + * \param[in] cloud the input point cloud dataset + * \param[in] geometry_handler a specific PointCloud visualizer handler for geometry + * \param[in] color_handler a specific PointCloud visualizer handler for colors + * \param[in] sensor_origin the origin of the cloud data in global coordinates (defaults to 0,0,0) + * \param[in] sensor_orientation the orientation of the cloud data in global coordinates (defaults to 1,0,0,0) + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + bool + addPointCloud (const pcl::PCLPointCloud2::ConstPtr &cloud, + const GeometryHandlerConstPtr &geometry_handler, + const ColorHandlerConstPtr &color_handler, + const Eigen::Vector4f& sensor_origin, + const Eigen::Quaternion& sensor_orientation, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Add a binary blob Point Cloud to screen. + * + * Because the geometry/color handler is given as a pointer, it will be pushed back to the list of + * available handlers, rather than replacing the current active handler. This makes it possible to + * switch between different handlers 'on-the-fly' at runtime, from the PCLVisualizer interactor + * interface (using [Alt+]0..9). + * + * \param[in] cloud the input point cloud dataset + * \param[in] geometry_handler a specific PointCloud visualizer handler for geometry + * \param[in] sensor_origin the origin of the cloud data in global coordinates (defaults to 0,0,0) + * \param[in] sensor_orientation the orientation of the cloud data in global coordinates (defaults to 1,0,0,0) + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + bool + addPointCloud (const pcl::PCLPointCloud2::ConstPtr &cloud, + const GeometryHandlerConstPtr &geometry_handler, + const Eigen::Vector4f& sensor_origin, + const Eigen::Quaternion& sensor_orientation, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Add a binary blob Point Cloud to screen. + * + * Because the geometry/color handler is given as a pointer, it will be pushed back to the list of + * available handlers, rather than replacing the current active handler. This makes it possible to + * switch between different handlers 'on-the-fly' at runtime, from the PCLVisualizer interactor + * interface (using [Alt+]0..9). + * + * \param[in] cloud the input point cloud dataset + * \param[in] color_handler a specific PointCloud visualizer handler for colors + * \param[in] sensor_origin the origin of the cloud data in global coordinates (defaults to 0,0,0) + * \param[in] sensor_orientation the orientation of the cloud data in global coordinates (defaults to 1,0,0,0) + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + bool + addPointCloud (const pcl::PCLPointCloud2::ConstPtr &cloud, + const ColorHandlerConstPtr &color_handler, + const Eigen::Vector4f& sensor_origin, + const Eigen::Quaternion& sensor_orientation, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Add a Point Cloud (templated) to screen. + * \param[in] cloud the input point cloud dataset + * \param[in] color_handler a specific PointCloud visualizer handler for colors + * \param[in] geometry_handler use a geometry handler object to extract the XYZ data + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + template bool + addPointCloud (const typename pcl::PointCloud::ConstPtr &cloud, + const PointCloudColorHandler &color_handler, + const PointCloudGeometryHandler &geometry_handler, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Add a PointXYZ Point Cloud to screen. + * \param[in] cloud the input point cloud dataset + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + inline bool + addPointCloud (const pcl::PointCloud::ConstPtr &cloud, + const std::string &id = "cloud", int viewport = 0) + { + return (addPointCloud (cloud, id, viewport)); + } + + + /** \brief Add a PointXYZRGB Point Cloud to screen. + * \param[in] cloud the input point cloud dataset + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + inline bool + addPointCloud (const pcl::PointCloud::ConstPtr &cloud, + const std::string &id = "cloud", int viewport = 0) + { + pcl::visualization::PointCloudColorHandlerRGBField color_handler (cloud); + return (addPointCloud (cloud, color_handler, id, viewport)); + } + + /** \brief Add a PointXYZRGBA Point Cloud to screen. + * \param[in] cloud the input point cloud dataset + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud should be added (default: all) + */ + inline bool + addPointCloud (const pcl::PointCloud::ConstPtr &cloud, + const std::string &id = "cloud", int viewport = 0) + { + pcl::visualization::PointCloudColorHandlerRGBField color_handler (cloud); + return (addPointCloud (cloud, color_handler, id, viewport)); + } + + /** \brief Updates the XYZ data for an existing cloud object id on screen. + * \param[in] cloud the input point cloud dataset + * \param[in] id the point cloud object id to update (default: cloud) + * \return false if no cloud with the specified ID was found + */ + inline bool + updatePointCloud (const pcl::PointCloud::ConstPtr &cloud, + const std::string &id = "cloud") + { + return (updatePointCloud (cloud, id)); + } + + /** \brief Updates the XYZRGB data for an existing cloud object id on screen. + * \param[in] cloud the input point cloud dataset + * \param[in] id the point cloud object id to update (default: cloud) + * \return false if no cloud with the specified ID was found + */ + inline bool + updatePointCloud (const pcl::PointCloud::ConstPtr &cloud, + const std::string &id = "cloud") + { + pcl::visualization::PointCloudColorHandlerRGBField color_handler (cloud); + return (updatePointCloud (cloud, color_handler, id)); + } + + /** \brief Updates the XYZRGBA data for an existing cloud object id on screen. + * \param[in] cloud the input point cloud dataset + * \param[in] id the point cloud object id to update (default: cloud) + * \return false if no cloud with the specified ID was found + */ + inline bool + updatePointCloud (const pcl::PointCloud::ConstPtr &cloud, + const std::string &id = "cloud") + { + pcl::visualization::PointCloudColorHandlerRGBField color_handler (cloud); + return (updatePointCloud (cloud, color_handler, id)); + } + + /** \brief Add a PolygonMesh object to screen + * \param[in] polymesh the polygonal mesh + * \param[in] id the polygon object id (default: "polygon") + * \param[in] viewport the view port where the PolygonMesh should be added (default: all) + */ + bool + addPolygonMesh (const pcl::PolygonMesh &polymesh, + const std::string &id = "polygon", + int viewport = 0); + + /** \brief Add a PolygonMesh object to screen + * \param[in] cloud the polygonal mesh point cloud + * \param[in] vertices the polygonal mesh vertices + * \param[in] id the polygon object id (default: "polygon") + * \param[in] viewport the view port where the PolygonMesh should be added (default: all) + */ + template bool + addPolygonMesh (const typename pcl::PointCloud::ConstPtr &cloud, + const std::vector &vertices, + const std::string &id = "polygon", + int viewport = 0); + + /** \brief Update a PolygonMesh object on screen + * \param[in] cloud the polygonal mesh point cloud + * \param[in] vertices the polygonal mesh vertices + * \param[in] id the polygon object id (default: "polygon") + * \return false if no polygonmesh with the specified ID was found + */ + template bool + updatePolygonMesh (const typename pcl::PointCloud::ConstPtr &cloud, + const std::vector &vertices, + const std::string &id = "polygon"); + + /** \brief Update a PolygonMesh object on screen + * \param[in] polymesh the polygonal mesh + * \param[in] id the polygon object id (default: "polygon") + * \return false if no polygonmesh with the specified ID was found + */ + bool + updatePolygonMesh (const pcl::PolygonMesh &polymesh, + const std::string &id = "polygon"); + + /** \brief Add a Polygonline from a polygonMesh object to screen + * \param[in] polymesh the polygonal mesh from where the polylines will be extracted + * \param[in] id the polygon object id (default: "polygon") + * \param[in] viewport the view port where the PolygonMesh should be added (default: all) + */ + bool + addPolylineFromPolygonMesh (const pcl::PolygonMesh &polymesh, + const std::string &id = "polyline", + int viewport = 0); + + /** \brief Add the specified correspondences to the display. + * \param[in] source_points The source points + * \param[in] target_points The target points + * \param[in] correspondences The mapping from source points to target points. Each element must be an index into target_points + * \param[in] id the polygon object id (default: "correspondences") + * \param[in] viewport the view port where the correspondences should be added (default: all) + */ + template bool + addCorrespondences (const typename pcl::PointCloud::ConstPtr &source_points, + const typename pcl::PointCloud::ConstPtr &target_points, + const std::vector & correspondences, + const std::string &id = "correspondences", + int viewport = 0); + + /** \brief Add a TextureMesh object to screen + * \param[in] polymesh the textured polygonal mesh + * \param[in] id the texture mesh object id (default: "texture") + * \param[in] viewport the view port where the TextureMesh should be added (default: all) + */ + bool + addTextureMesh (const pcl::TextureMesh &polymesh, + const std::string &id = "texture", + int viewport = 0); + + /** \brief Add the specified correspondences to the display. + * \param[in] source_points The source points + * \param[in] target_points The target points + * \param[in] correspondences The mapping from source points to target points. Each element must be an index into target_points + * \param[in] nth display only the Nth correspondence (e.g., skip the rest) + * \param[in] id the polygon object id (default: "correspondences") + * \param[in] viewport the view port where the correspondences should be added (default: all) + */ + template bool + addCorrespondences (const typename pcl::PointCloud::ConstPtr &source_points, + const typename pcl::PointCloud::ConstPtr &target_points, + const pcl::Correspondences &correspondences, + int nth, + const std::string &id = "correspondences", + int viewport = 0); + + /** \brief Add the specified correspondences to the display. + * \param[in] source_points The source points + * \param[in] target_points The target points + * \param[in] correspondences The mapping from source points to target points. Each element must be an index into target_points + * \param[in] id the polygon object id (default: "correspondences") + * \param[in] viewport the view port where the correspondences should be added (default: all) + */ + template bool + addCorrespondences (const typename pcl::PointCloud::ConstPtr &source_points, + const typename pcl::PointCloud::ConstPtr &target_points, + const pcl::Correspondences &correspondences, + const std::string &id = "correspondences", + int viewport = 0) + { + // If Nth not given, display all correspondences + return (addCorrespondences (source_points, target_points, + correspondences, 1, id, viewport)); + } + + /** \brief Update the specified correspondences to the display. + * \param[in] source_points The source points + * \param[in] target_points The target points + * \param[in] correspondences The mapping from source points to target points. Each element must be an index into target_points + * \param[in] nth display only the Nth correspondence (e.g., skip the rest) + * \param[in] id the polygon object id (default: "correspondences") + */ + template bool + updateCorrespondences ( + const typename pcl::PointCloud::ConstPtr &source_points, + const typename pcl::PointCloud::ConstPtr &target_points, + const pcl::Correspondences &correspondences, + int nth, + const std::string &id = "correspondences"); + + /** \brief Remove the specified correspondences from the display. + * \param[in] id the polygon correspondences object id (i.e., given on \ref addCorrespondences) + * \param[in] viewport view port from where the correspondences should be removed (default: all) + */ + void + removeCorrespondences (const std::string &id = "correspondences", int viewport = 0); + + /** \brief Get the color handler index of a rendered PointCloud based on its ID + * \param[in] id the point cloud object id + */ + int + getColorHandlerIndex (const std::string &id); + + /** \brief Get the geometry handler index of a rendered PointCloud based on its ID + * \param[in] id the point cloud object id + */ + int + getGeometryHandlerIndex (const std::string &id); + + /** \brief Update/set the color index of a renderered PointCloud based on its ID + * \param[in] id the point cloud object id + * \param[in] index the color handler index to use + */ + bool + updateColorHandlerIndex (const std::string &id, int index); + + /** \brief Set the rendering properties of a PointCloud (3x values - e.g., RGB) + * \param[in] property the property type + * \param[in] val1 the first value to be set + * \param[in] val2 the second value to be set + * \param[in] val3 the third value to be set + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud's rendering properties should be modified (default: all) + */ + bool + setPointCloudRenderingProperties (int property, double val1, double val2, double val3, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Set the rendering properties of a PointCloud + * \param[in] property the property type + * \param[in] value the value to be set + * \param[in] id the point cloud object id (default: cloud) + * \param[in] viewport the view port where the Point Cloud's rendering properties should be modified (default: all) + */ + bool + setPointCloudRenderingProperties (int property, double value, + const std::string &id = "cloud", int viewport = 0); + + /** \brief Get the rendering properties of a PointCloud + * \param[in] property the property type + * \param[in] value the resultant property value + * \param[in] id the point cloud object id (default: cloud) + */ + bool + getPointCloudRenderingProperties (int property, double &value, + const std::string &id = "cloud"); + + /** \brief Set whether the point cloud is selected or not + * \param[in] selected whether the cloud is selected or not (true = selected) + * \param[in] id the point cloud object id (default: cloud) + */ + bool + setPointCloudSelected (const bool selected, const std::string &id = "cloud" ); + + /** \brief Set the rendering properties of a shape + * \param[in] property the property type + * \param[in] value the value to be set + * \param[in] id the shape object id + * \param[in] viewport the view port where the shape's properties should be modified (default: all) + */ + bool + setShapeRenderingProperties (int property, double value, + const std::string &id, int viewport = 0); + + /** \brief Set the rendering properties of a shape (3x values - e.g., RGB) + * \param[in] property the property type + * \param[in] val1 the first value to be set + * \param[in] val2 the second value to be set + * \param[in] val3 the third value to be set + * \param[in] id the shape object id + * \param[in] viewport the view port where the shape's properties should be modified (default: all) + */ + bool + setShapeRenderingProperties (int property, double val1, double val2, double val3, + const std::string &id, int viewport = 0); + + /** \brief Returns true when the user tried to close the window */ + bool + wasStopped () const; + + /** \brief Set the stopped flag back to false */ + void + resetStoppedFlag (); + + /** \brief Stop the interaction and close the visualizaton window. */ + void + close (); + + /** \brief Create a new viewport from [xmin,ymin] -> [xmax,ymax]. + * \param[in] xmin the minimum X coordinate for the viewport (0.0 <= 1.0) + * \param[in] ymin the minimum Y coordinate for the viewport (0.0 <= 1.0) + * \param[in] xmax the maximum X coordinate for the viewport (0.0 <= 1.0) + * \param[in] ymax the maximum Y coordinate for the viewport (0.0 <= 1.0) + * \param[in] viewport the id of the new viewport + * + * \note If no renderer for the current window exists, one will be created, and + * the viewport will be set to 0 ('all'). In case one or multiple renderers do + * exist, the viewport ID will be set to the total number of renderers - 1. + */ + void + createViewPort (double xmin, double ymin, double xmax, double ymax, int &viewport); + + /** \brief Create a new separate camera for the given viewport. + * \param[in] viewport the viewport to create a new camera for. + */ + void + createViewPortCamera (const int viewport); + + /** \brief Add a polygon (polyline) that represents the input point cloud (connects all + * points in order) + * \param[in] cloud the point cloud dataset representing the polygon + * \param[in] r the red channel of the color that the polygon should be rendered with + * \param[in] g the green channel of the color that the polygon should be rendered with + * \param[in] b the blue channel of the color that the polygon should be rendered with + * \param[in] id (optional) the polygon id/name (default: "polygon") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + template bool + addPolygon (const typename pcl::PointCloud::ConstPtr &cloud, + double r, double g, double b, + const std::string &id = "polygon", int viewport = 0); + + /** \brief Add a polygon (polyline) that represents the input point cloud (connects all + * points in order) + * \param[in] cloud the point cloud dataset representing the polygon + * \param[in] id the polygon id/name (default: "polygon") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + template bool + addPolygon (const typename pcl::PointCloud::ConstPtr &cloud, + const std::string &id = "polygon", + int viewport = 0); + + /** \brief Add a planar polygon that represents the input point cloud (connects all points in order) + * \param[in] polygon the polygon to draw + * \param[in] r the red channel of the color that the polygon should be rendered with + * \param[in] g the green channel of the color that the polygon should be rendered with + * \param[in] b the blue channel of the color that the polygon should be rendered with + * \param[in] id the polygon id/name (default: "polygon") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + template bool + addPolygon (const pcl::PlanarPolygon &polygon, + double r, double g, double b, + const std::string &id = "polygon", + int viewport = 0); + + /** \brief Add a line segment from two points + * \param[in] pt1 the first (start) point on the line + * \param[in] pt2 the second (end) point on the line + * \param[in] id the line id/name (default: "line") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + template bool + addLine (const P1 &pt1, const P2 &pt2, const std::string &id = "line", + int viewport = 0); + + /** \brief Add a line segment from two points + * \param[in] pt1 the first (start) point on the line + * \param[in] pt2 the second (end) point on the line + * \param[in] r the red channel of the color that the line should be rendered with + * \param[in] g the green channel of the color that the line should be rendered with + * \param[in] b the blue channel of the color that the line should be rendered with + * \param[in] id the line id/name (default: "line") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + template bool + addLine (const P1 &pt1, const P2 &pt2, double r, double g, double b, + const std::string &id = "line", int viewport = 0); + + /** \brief Add a line arrow segment between two points, and display the distance between them + * + * Arrow heads are attached to both end points of the arrow. + * + * \param[in] pt1 the first (start) point on the line + * \param[in] pt2 the second (end) point on the line + * \param[in] r the red channel of the color that the line should be rendered with + * \param[in] g the green channel of the color that the line should be rendered with + * \param[in] b the blue channel of the color that the line should be rendered with + * \param[in] id the arrow id/name (default: "arrow") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + template bool + addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b, + const std::string &id = "arrow", int viewport = 0); + + /** \brief Add a line arrow segment between two points, and (optianally) display the distance between them + * + * Arrow head is attached on the **start** point (\c pt1) of the arrow. + * + * \param[in] pt1 the first (start) point on the line + * \param[in] pt2 the second (end) point on the line + * \param[in] r the red channel of the color that the line should be rendered with + * \param[in] g the green channel of the color that the line should be rendered with + * \param[in] b the blue channel of the color that the line should be rendered with + * \param[in] display_length true if the length should be displayed on the arrow as text + * \param[in] id the line id/name (default: "arrow") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + template bool + addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b, bool display_length, + const std::string &id = "arrow", int viewport = 0); + + /** \brief Add a line arrow segment between two points, and display the distance between them in a given color + * + * Arrow heads are attached to both end points of the arrow. + * + * \param[in] pt1 the first (start) point on the line + * \param[in] pt2 the second (end) point on the line + * \param[in] r_line the red channel of the color that the line should be rendered with + * \param[in] g_line the green channel of the color that the line should be rendered with + * \param[in] b_line the blue channel of the color that the line should be rendered with + * \param[in] r_text the red channel of the color that the text should be rendered with + * \param[in] g_text the green channel of the color that the text should be rendered with + * \param[in] b_text the blue channel of the color that the text should be rendered with + * \param[in] id the line id/name (default: "arrow") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + template bool + addArrow (const P1 &pt1, const P2 &pt2, + double r_line, double g_line, double b_line, + double r_text, double g_text, double b_text, + const std::string &id = "arrow", int viewport = 0); + + + /** \brief Add a sphere shape from a point and a radius + * \param[in] center the center of the sphere + * \param[in] radius the radius of the sphere + * \param[in] id the sphere id/name (default: "sphere") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + template bool + addSphere (const PointT ¢er, double radius, const std::string &id = "sphere", + int viewport = 0); + + /** \brief Add a sphere shape from a point and a radius + * \param[in] center the center of the sphere + * \param[in] radius the radius of the sphere + * \param[in] r the red channel of the color that the sphere should be rendered with + * \param[in] g the green channel of the color that the sphere should be rendered with + * \param[in] b the blue channel of the color that the sphere should be rendered with + * \param[in] id the sphere id/name (default: "sphere") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + template bool + addSphere (const PointT ¢er, double radius, double r, double g, double b, + const std::string &id = "sphere", int viewport = 0); + + /** \brief Update an existing sphere shape from a point and a radius + * \param[in] center the center of the sphere + * \param[in] radius the radius of the sphere + * \param[in] r the red channel of the color that the sphere should be rendered with + * \param[in] g the green channel of the color that the sphere should be rendered with + * \param[in] b the blue channel of the color that the sphere should be rendered with + * \param[in] id the sphere id/name (default: "sphere") + */ + template bool + updateSphere (const PointT ¢er, double radius, double r, double g, double b, + const std::string &id = "sphere"); + + /** \brief Add a vtkPolydata as a mesh + * \param[in] polydata vtkPolyData + * \param[in] id the model id/name (default: "PolyData") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + bool + addModelFromPolyData (vtkSmartPointer polydata, + const std::string & id = "PolyData", + int viewport = 0); + + /** \brief Add a vtkPolydata as a mesh + * \param[in] polydata vtkPolyData + * \param[in] transform transformation to apply + * \param[in] id the model id/name (default: "PolyData") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + bool + addModelFromPolyData (vtkSmartPointer polydata, + vtkSmartPointer transform, + const std::string &id = "PolyData", + int viewport = 0); + + /** \brief Add a PLYmodel as a mesh + * \param[in] filename of the ply file + * \param[in] id the model id/name (default: "PLYModel") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + bool + addModelFromPLYFile (const std::string &filename, + const std::string &id = "PLYModel", + int viewport = 0); + + /** \brief Add a PLYmodel as a mesh and applies given transformation + * \param[in] filename of the ply file + * \param[in] transform transformation to apply + * \param[in] id the model id/name (default: "PLYModel") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + bool + addModelFromPLYFile (const std::string &filename, + vtkSmartPointer transform, + const std::string &id = "PLYModel", + int viewport = 0); + + /** \brief Add a cylinder from a set of given model coefficients + * \param[in] coefficients the model coefficients (point_on_axis, axis_direction, radius) + * \param[in] id the cylinder id/name (default: "cylinder") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + * + * \code + * // The following are given (or computed using sample consensus techniques) + * // See SampleConsensusModelCylinder for more information. + * // Eigen::Vector3f pt_on_axis, axis_direction; + * // float radius; + * + * pcl::ModelCoefficients cylinder_coeff; + * cylinder_coeff.values.resize (7); // We need 7 values + * cylinder_coeff.values[0] = pt_on_axis.x (); + * cylinder_coeff.values[1] = pt_on_axis.y (); + * cylinder_coeff.values[2] = pt_on_axis.z (); + * + * cylinder_coeff.values[3] = axis_direction.x (); + * cylinder_coeff.values[4] = axis_direction.y (); + * cylinder_coeff.values[5] = axis_direction.z (); + * + * cylinder_coeff.values[6] = radius; + * + * addCylinder (cylinder_coeff); + * \endcode + */ + bool + addCylinder (const pcl::ModelCoefficients &coefficients, + const std::string &id = "cylinder", + int viewport = 0); + + /** \brief Add a sphere from a set of given model coefficients + * \param[in] coefficients the model coefficients (sphere center, radius) + * \param[in] id the sphere id/name (default: "sphere") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + * + * \code + * // The following are given (or computed using sample consensus techniques) + * // See SampleConsensusModelSphere for more information + * // Eigen::Vector3f sphere_center; + * // float radius; + * + * pcl::ModelCoefficients sphere_coeff; + * sphere_coeff.values.resize (4); // We need 4 values + * sphere_coeff.values[0] = sphere_center.x (); + * sphere_coeff.values[1] = sphere_center.y (); + * sphere_coeff.values[2] = sphere_center.z (); + * + * sphere_coeff.values[3] = radius; + * + * addSphere (sphere_coeff); + * \endcode + */ + bool + addSphere (const pcl::ModelCoefficients &coefficients, + const std::string &id = "sphere", + int viewport = 0); + + /** \brief Add a line from a set of given model coefficients + * \param[in] coefficients the model coefficients (point_on_line, direction) + * \param[in] id the line id/name (default: "line") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + * + * \code + * // The following are given (or computed using sample consensus techniques) + * // See SampleConsensusModelLine for more information + * // Eigen::Vector3f point_on_line, line_direction; + * + * pcl::ModelCoefficients line_coeff; + * line_coeff.values.resize (6); // We need 6 values + * line_coeff.values[0] = point_on_line.x (); + * line_coeff.values[1] = point_on_line.y (); + * line_coeff.values[2] = point_on_line.z (); + * + * line_coeff.values[3] = line_direction.x (); + * line_coeff.values[4] = line_direction.y (); + * line_coeff.values[5] = line_direction.z (); + * + * addLine (line_coeff); + * \endcode + */ + bool + addLine (const pcl::ModelCoefficients &coefficients, + const std::string &id = "line", + int viewport = 0); + + /** \brief Add a plane from a set of given model coefficients + * \param[in] coefficients the model coefficients (a, b, c, d with ax+by+cz+d=0) + * \param[in] id the plane id/name (default: "plane") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + * + * \code + * // The following are given (or computed using sample consensus techniques) + * // See SampleConsensusModelPlane for more information + * // Eigen::Vector4f plane_parameters; + * + * pcl::ModelCoefficients plane_coeff; + * plane_coeff.values.resize (4); // We need 4 values + * plane_coeff.values[0] = plane_parameters.x (); + * plane_coeff.values[1] = plane_parameters.y (); + * plane_coeff.values[2] = plane_parameters.z (); + * plane_coeff.values[3] = plane_parameters.w (); + * + * addPlane (plane_coeff); + * \endcode + */ + bool + addPlane (const pcl::ModelCoefficients &coefficients, + const std::string &id = "plane", + int viewport = 0); + + bool + addPlane (const pcl::ModelCoefficients &coefficients, double x, double y, double z, + const std::string &id = "plane", + int viewport = 0); + /** \brief Add a circle from a set of given model coefficients + * \param[in] coefficients the model coefficients (x, y, radius) + * \param[in] id the circle id/name (default: "circle") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + * + * \code + * // The following are given (or computed using sample consensus techniques) + * // See SampleConsensusModelCircle2D for more information + * // float x, y, radius; + * + * pcl::ModelCoefficients circle_coeff; + * circle_coeff.values.resize (3); // We need 3 values + * circle_coeff.values[0] = x; + * circle_coeff.values[1] = y; + * circle_coeff.values[2] = radius; + * + * vtkSmartPointer data = pcl::visualization::create2DCircle (circle_coeff, z); + * \endcode + */ + bool + addCircle (const pcl::ModelCoefficients &coefficients, + const std::string &id = "circle", + int viewport = 0); + + /** \brief Add a cone from a set of given model coefficients + * \param[in] coefficients the model coefficients (point_on_axis, axis_direction, radiu) + * \param[in] id the cone id/name (default: "cone") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + bool + addCone (const pcl::ModelCoefficients &coefficients, + const std::string &id = "cone", + int viewport = 0); + + /** \brief Add a cube from a set of given model coefficients + * \param[in] coefficients the model coefficients (Tx, Ty, Tz, Qx, Qy, Qz, Qw, width, height, depth) + * \param[in] id the cube id/name (default: "cube") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + bool + addCube (const pcl::ModelCoefficients &coefficients, + const std::string &id = "cube", + int viewport = 0); + + /** \brief Add a cube from a set of given model coefficients + * \param[in] translation a translation to apply to the cube from 0,0,0 + * \param[in] rotation a quaternion-based rotation to apply to the cube + * \param[in] width the cube's width + * \param[in] height the cube's height + * \param[in] depth the cube's depth + * \param[in] id the cube id/name (default: "cube") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + bool + addCube (const Eigen::Vector3f &translation, const Eigen::Quaternionf &rotation, + double width, double height, double depth, + const std::string &id = "cube", + int viewport = 0); + + /** \brief Add a cube + * \param[in] x_min the min X coordinate + * \param[in] x_max the max X coordinate + * \param[in] y_min the min Y coordinate + * \param[in] y_max the max Y coordinate + * \param[in] z_min the min Z coordinate + * \param[in] z_max the max Z coordinate + * \param[in] r how much red (0.0 -> 1.0) + * \param[in] g how much green (0.0 -> 1.0) + * \param[in] b how much blue (0.0 -> 1.0) + * \param[in] id the cube id/name (default: "cube") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + bool + addCube (float x_min, float x_max, float y_min, float y_max, float z_min, float z_max, + double r = 1.0, double g = 1.0, double b = 1.0, const std::string &id = "cube", int viewport = 0); + + /** \brief Changes the visual representation for all actors to surface representation. */ + void + setRepresentationToSurfaceForAllActors (); + + /** \brief Changes the visual representation for all actors to points representation. */ + void + setRepresentationToPointsForAllActors (); + + /** \brief Changes the visual representation for all actors to wireframe representation. */ + void + setRepresentationToWireframeForAllActors (); + + /** \brief Sets whether the 2D overlay text showing the framerate of the window is displayed or not. + * \param[in] show_fps determines whether the fps text will be shown or not. + */ + void + setShowFPS (bool show_fps); + + /** \brief Renders a virtual scene as seen from the camera viewpoint and returns the rendered point cloud. + * ATT: This method will only render the scene if only on viewport exists. Otherwise, returns an empty + * point cloud and exits immediately. + * \param[in] xres is the size of the window (X) used to render the scene + * \param[in] yres is the size of the window (Y) used to render the scene + * \param[in] cloud is the rendered point cloud + */ + void + renderView (int xres, int yres, pcl::PointCloud::Ptr & cloud); + + /** \brief The purpose of this method is to render a CAD model added to the visualizer from different viewpoints + * in order to simulate partial views of model. The viewpoint locations are the vertices of a tesselated sphere + * build from an icosaheadron. The tesselation paremeter controls how many times the triangles of the original + * icosahedron are divided to approximate the sphere and thus the number of partial view generated for a model, + * with a tesselation_level of 0, 12 views are generated if use_vertices=true and 20 views if use_vertices=false + * + * \param[in] xres the size of the window (X) used to render the partial view of the object + * \param[in] yres the size of the window (Y) used to render the partial view of the object + * \param[in] cloud is a vector of pointcloud with XYZ information that represent the model as seen from the respective viewpoints. + * \param[out] poses represent the transformation from object coordinates to camera coordinates for the respective viewpoint. + * \param[out] enthropies are values between 0 and 1 representing which percentage of the model is seen from the respective viewpoint. + * \param[in] tesselation_level represents the number of subdivisions applied to the triangles of original icosahedron. + * \param[in] view_angle field of view of the virtual camera. Default: 45 + * \param[in] radius_sphere the tesselated sphere radius. Default: 1 + * \param[in] use_vertices if true, use the vertices of tesselated icosahedron (12,42,...) or if false, use the faces of tesselated + * icosahedron (20,80,...). Default: true + */ + void + renderViewTesselatedSphere ( + int xres, int yres, + pcl::PointCloud::CloudVectorType & cloud, + std::vector > & poses, std::vector & enthropies, int tesselation_level, + float view_angle = 45, float radius_sphere = 1, bool use_vertices = true); + + + /** \brief Initialize camera parameters with some default values. */ + void + initCameraParameters (); + + /** \brief Search for camera parameters at the command line and set them internally. + * \param[in] argc + * \param[in] argv + */ + bool + getCameraParameters (int argc, char **argv); + + /** \brief Load camera parameters from a camera parameters file. + * \param[in] file the name of the camera parameters file + */ + bool + loadCameraParameters (const std::string &file); + + /** \brief Checks whether the camera parameters were manually loaded. + * \return True if valid "-cam" option is available in command line. + * \sa cameraFileLoaded () + */ + bool + cameraParamsSet () const; + + /** \brief Checks whether a camera file were automatically loaded. + * \return True if a valid camera file is automatically loaded. + * \note The camera file is saved by pressing "ctrl + s" during last run of the program + * and restored automatically when the program runs this time. + * \sa cameraParamsSet () + */ + bool + cameraFileLoaded () const; + + /** \brief Get camera file for camera parameter saving/restoring. + * \note This will be valid only when valid "-cam" option were available in command line + * or a saved camera file were automatically loaded. + * \sa cameraParamsSet (), cameraFileLoaded () + */ + std::string + getCameraFile () const; + + /** \brief Update camera parameters and render. */ + void + updateCamera (); + + /** \brief Reset camera parameters and render. */ + void + resetCamera (); + + /** \brief Reset the camera direction from {0, 0, 0} to the center_{x, y, z} of a given dataset. + * \param[in] id the point cloud object id (default: cloud) + */ + void + resetCameraViewpoint (const std::string &id = "cloud"); + + /** \brief Set the camera pose given by position, viewpoint and up vector + * \param[in] pos_x the x coordinate of the camera location + * \param[in] pos_y the y coordinate of the camera location + * \param[in] pos_z the z coordinate of the camera location + * \param[in] view_x the x component of the view point of the camera + * \param[in] view_y the y component of the view point of the camera + * \param[in] view_z the z component of the view point of the camera + * \param[in] up_x the x component of the view up direction of the camera + * \param[in] up_y the y component of the view up direction of the camera + * \param[in] up_z the y component of the view up direction of the camera + * \param[in] viewport the viewport to modify camera of (0 modifies all cameras) + */ + void + setCameraPosition (double pos_x, double pos_y, double pos_z, + double view_x, double view_y, double view_z, + double up_x, double up_y, double up_z, int viewport = 0); + + /** \brief Set the camera location and viewup according to the given arguments + * \param[in] pos_x the x coordinate of the camera location + * \param[in] pos_y the y coordinate of the camera location + * \param[in] pos_z the z coordinate of the camera location + * \param[in] up_x the x component of the view up direction of the camera + * \param[in] up_y the y component of the view up direction of the camera + * \param[in] up_z the z component of the view up direction of the camera + * \param[in] viewport the viewport to modify camera of (0 modifies all cameras) + */ + void + setCameraPosition (double pos_x, double pos_y, double pos_z, + double up_x, double up_y, double up_z, int viewport = 0); + + /** \brief Set the camera parameters via an intrinsics and and extrinsics matrix + * \note This assumes that the pixels are square and that the center of the image is at the center of the sensor. + * \param[in] intrinsics the intrinsics that will be used to compute the VTK camera parameters + * \param[in] extrinsics the extrinsics that will be used to compute the VTK camera parameters + * \param[in] viewport the viewport to modify camera of (0 modifies all cameras) + */ + void + setCameraParameters (const Eigen::Matrix3f &intrinsics, const Eigen::Matrix4f &extrinsics, int viewport = 0); + + /** \brief Set the camera parameters by given a full camera data structure. + * \param[in] camera camera structure containing all the camera parameters. + * \param[in] viewport the viewport to modify camera of (0 modifies all cameras) + */ + void + setCameraParameters (const Camera &camera, int viewport = 0); + + /** \brief Set the camera clipping distances. + * \param[in] near the near clipping distance (no objects closer than this to the camera will be drawn) + * \param[in] far the far clipping distance (no objects further away than this to the camera will be drawn) + * \param[in] viewport the viewport to modify camera of (0 modifies all cameras) + */ + void + setCameraClipDistances (double near, double far, int viewport = 0); + + /** \brief Set the camera vertical field of view. + * \param[in] fovy vertical field of view in radians + * \param[in] viewport the viewport to modify camera of (0 modifies all cameras) + */ + void + setCameraFieldOfView (double fovy, int viewport = 0); + + /** \brief Get the current camera parameters. */ + void + getCameras (std::vector& cameras); + + + /** \brief Get the current viewing pose. */ + Eigen::Affine3f + getViewerPose (int viewport = 0); + + /** \brief Save the current rendered image to disk, as a PNG screenshot. + * \param[in] file the name of the PNG file + */ + void + saveScreenshot (const std::string &file); + + /** \brief Save the camera parameters to disk, as a .cam file. + * \param[in] file the name of the .cam file + */ + void + saveCameraParameters (const std::string &file); + + /** \brief Get camera parameters and save them to a pcl::visualization::Camera. + * \param[out] camera the name of the pcl::visualization::Camera + */ + void + getCameraParameters (Camera &camera); + + /** \brief Return a pointer to the underlying VTK Render Window used. */ + vtkSmartPointer + getRenderWindow () + { + return (win_); + } + + /** \brief Return a pointer to the underlying VTK Renderer Collection. */ + vtkSmartPointer + getRendererCollection () + { + return (rens_); + } + + /** \brief Return a pointer to the CloudActorMap this visualizer uses. */ + CloudActorMapPtr + getCloudActorMap () + { + return (cloud_actor_map_); + } + + /** \brief Return a pointer to the ShapeActorMap this visualizer uses. */ + ShapeActorMapPtr + getShapeActorMap () + { + return (shape_actor_map_); + } + + /** \brief Set the position in screen coordinates. + * \param[in] x where to move the window to (X) + * \param[in] y where to move the window to (Y) + */ + void + setPosition (int x, int y); + + /** \brief Set the window size in screen coordinates. + * \param[in] xw window size in horizontal (pixels) + * \param[in] yw window size in vertical (pixels) + */ + void + setSize (int xw, int yw); + + /** \brief Use Vertex Buffer Objects renderers. + * \param[in] use_vbos set to true to use VBOs + */ + void + setUseVbos (bool use_vbos); + + /** \brief Create the internal Interactor object. */ + void + createInteractor (); + + /** \brief Set up our unique PCL interactor style for a given vtkRenderWindowInteractor object + * attached to a given vtkRenderWindow + * \param[in,out] iren the vtkRenderWindowInteractor object to set up + * \param[in,out] win a vtkRenderWindow object that the interactor is attached to + */ + void + setupInteractor (vtkRenderWindowInteractor *iren, + vtkRenderWindow *win); + + /** \brief Set up PCLVisualizer with custom interactor style for a given vtkRenderWindowInteractor object + * attached to a given vtkRenderWindow + * \param[in,out] iren the vtkRenderWindowInteractor object to set up + * \param[in,out] win a vtkRenderWindow object that the interactor is attached to + * \param[in,out] style a vtkInteractorStyle object + */ + void + setupInteractor (vtkRenderWindowInteractor *iren, + vtkRenderWindow *win, + vtkInteractorStyle *style); + + /** \brief Get a pointer to the current interactor style used. */ + inline vtkSmartPointer + getInteractorStyle () + { + return (style_); + } + protected: + /** \brief The render window interactor. */ +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + vtkSmartPointer interactor_; +#else + vtkSmartPointer interactor_; +#endif + private: + struct ExitMainLoopTimerCallback : public vtkCommand + { + static ExitMainLoopTimerCallback* New () + { + return (new ExitMainLoopTimerCallback); + } + virtual void + Execute (vtkObject*, unsigned long event_id, void*); + + int right_timer_id; + PCLVisualizer* pcl_visualizer; + }; + + struct ExitCallback : public vtkCommand + { + static ExitCallback* New () + { + return (new ExitCallback); + } + virtual void + Execute (vtkObject*, unsigned long event_id, void*); + + PCLVisualizer* pcl_visualizer; + }; + + ////////////////////////////////////////////////////////////////////////////////////////////// + struct FPSCallback : public vtkCommand + { + static FPSCallback *New () { return (new FPSCallback); } + + FPSCallback () : actor (), pcl_visualizer (), decimated () {} + FPSCallback (const FPSCallback& src) : vtkCommand (), actor (src.actor), pcl_visualizer (src.pcl_visualizer), decimated (src.decimated) {} + FPSCallback& operator = (const FPSCallback& src) { actor = src.actor; pcl_visualizer = src.pcl_visualizer; decimated = src.decimated; return (*this); } + + virtual void + Execute (vtkObject*, unsigned long event_id, void*); + + vtkTextActor *actor; + PCLVisualizer* pcl_visualizer; + bool decimated; + }; + + /** \brief The FPSCallback object for the current visualizer. */ + vtkSmartPointer update_fps_; + +#if !((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) + /** \brief Set to false if the interaction loop is running. */ + bool stopped_; + + /** \brief Global timer ID. Used in destructor only. */ + int timer_id_; +#endif + /** \brief Callback object enabling us to leave the main loop, when a timer fires. */ + vtkSmartPointer exit_main_loop_timer_callback_; + vtkSmartPointer exit_callback_; + + /** \brief The collection of renderers used. */ + vtkSmartPointer rens_; + + /** \brief The render window. */ + vtkSmartPointer win_; + + /** \brief The render window interactor style. */ + vtkSmartPointer style_; + + /** \brief Internal list with actor pointers and name IDs for point clouds. */ + CloudActorMapPtr cloud_actor_map_; + + /** \brief Internal list with actor pointers and name IDs for shapes. */ + ShapeActorMapPtr shape_actor_map_; + + /** \brief Internal list with actor pointers and viewpoint for coordinates. */ + CoordinateActorMapPtr coordinate_actor_map_; + + /** \brief Internal pointer to widget which contains a set of axes */ + vtkSmartPointer axes_widget_; + + /** \brief Boolean that holds whether or not the camera parameters were manually initialized */ + bool camera_set_; + + /** \brief Boolean that holds whether or not a camera file were automatically loaded */ + bool camera_file_loaded_; + + /** \brief Boolean that holds whether or not to use the vtkVertexBufferObjectMapper*/ + bool use_vbos_; + + /** \brief Internal method. Removes a vtk actor from the screen. + * \param[in] actor a pointer to the vtk actor object + * \param[in] viewport the view port where the actor should be removed from (default: all) + */ + bool + removeActorFromRenderer (const vtkSmartPointer &actor, + int viewport = 0); + + /** \brief Internal method. Removes a vtk actor from the screen. + * \param[in] actor a pointer to the vtk actor object + * \param[in] viewport the view port where the actor should be removed from (default: all) + */ + bool + removeActorFromRenderer (const vtkSmartPointer &actor, + int viewport = 0); + + /** \brief Internal method. Adds a vtk actor to screen. + * \param[in] actor a pointer to the vtk actor object + * \param[in] viewport port where the actor should be added to (default: 0/all) + * + * \note If viewport is set to 0, the actor will be added to all existing + * renders. To select a specific viewport use an integer between 1 and N. + */ + void + addActorToRenderer (const vtkSmartPointer &actor, + int viewport = 0); + + /** \brief Internal method. Adds a vtk actor to screen. + * \param[in] actor a pointer to the vtk actor object + * \param[in] viewport the view port where the actor should be added to (default: all) + */ + bool + removeActorFromRenderer (const vtkSmartPointer &actor, + int viewport = 0); + + /** \brief Internal method. Creates a vtk actor from a vtk polydata object. + * \param[in] data the vtk polydata object to create an actor for + * \param[out] actor the resultant vtk actor object + * \param[in] use_scalars set scalar properties to the mapper if it exists in the data. Default: true. + */ + void + createActorFromVTKDataSet (const vtkSmartPointer &data, + vtkSmartPointer &actor, + bool use_scalars = true); + + /** \brief Internal method. Creates a vtk actor from a vtk polydata object. + * \param[in] data the vtk polydata object to create an actor for + * \param[out] actor the resultant vtk actor object + * \param[in] use_scalars set scalar properties to the mapper if it exists in the data. Default: true. + */ + void + createActorFromVTKDataSet (const vtkSmartPointer &data, + vtkSmartPointer &actor, + bool use_scalars = true); + + /** \brief Converts a PCL templated PointCloud object to a vtk polydata object. + * \param[in] cloud the input PCL PointCloud dataset + * \param[out] polydata the resultant polydata containing the cloud + * \param[out] initcells a list of cell indices used for the conversion. This can be set once and then passed + * around to speed up the conversion. + */ + template void + convertPointCloudToVTKPolyData (const typename pcl::PointCloud::ConstPtr &cloud, + vtkSmartPointer &polydata, + vtkSmartPointer &initcells); + + /** \brief Converts a PCL templated PointCloud object to a vtk polydata object. + * \param[in] geometry_handler the geometry handler object used to extract the XYZ data + * \param[out] polydata the resultant polydata containing the cloud + * \param[out] initcells a list of cell indices used for the conversion. This can be set once and then passed + * around to speed up the conversion. + */ + template void + convertPointCloudToVTKPolyData (const PointCloudGeometryHandler &geometry_handler, + vtkSmartPointer &polydata, + vtkSmartPointer &initcells); + + /** \brief Converts a PCL templated PointCloud object to a vtk polydata object. + * \param[in] geometry_handler the geometry handler object used to extract the XYZ data + * \param[out] polydata the resultant polydata containing the cloud + * \param[out] initcells a list of cell indices used for the conversion. This can be set once and then passed + * around to speed up the conversion. + */ + void + convertPointCloudToVTKPolyData (const GeometryHandlerConstPtr &geometry_handler, + vtkSmartPointer &polydata, + vtkSmartPointer &initcells); + + /** \brief Updates a set of cells (vtkIdTypeArray) if the number of points in a cloud changes + * \param[out] cells the vtkIdTypeArray object (set of cells) to update + * \param[out] initcells a previously saved set of cells. If the number of points in the current cloud is + * higher than the number of cells in \a cells, and initcells contains enough data, then a copy from it + * will be made instead of regenerating the entire array. + * \param[in] nr_points the number of points in the new cloud. This dictates how many cells we need to + * generate + */ + void + updateCells (vtkSmartPointer &cells, + vtkSmartPointer &initcells, + vtkIdType nr_points); + + /** \brief Internal function which converts the information present in the geometric + * and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds + * all the required information to the internal cloud_actor_map_ object. + * \param[in] geometry_handler the geometric handler that contains the XYZ data + * \param[in] color_handler the color handler that contains the "RGB" (scalar) data + * \param[in] id the point cloud object id + * \param[in] viewport the view port where the Point Cloud should be added + * \param[in] sensor_origin the origin of the cloud data in global coordinates (defaults to 0,0,0) + * \param[in] sensor_orientation the orientation of the cloud data in global coordinates (defaults to 1,0,0,0) + */ + template bool + fromHandlersToScreen (const PointCloudGeometryHandler &geometry_handler, + const PointCloudColorHandler &color_handler, + const std::string &id, + int viewport, + const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0), + const Eigen::Quaternion& sensor_orientation = Eigen::Quaternion (1, 0, 0 ,0)); + + /** \brief Internal function which converts the information present in the geometric + * and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds + * all the required information to the internal cloud_actor_map_ object. + * \param[in] geometry_handler the geometric handler that contains the XYZ data + * \param[in] color_handler the color handler that contains the "RGB" (scalar) data + * \param[in] id the point cloud object id + * \param[in] viewport the view port where the Point Cloud should be added + * \param[in] sensor_origin the origin of the cloud data in global coordinates (defaults to 0,0,0) + * \param[in] sensor_orientation the orientation of the cloud data in global coordinates (defaults to 1,0,0,0) + */ + template bool + fromHandlersToScreen (const PointCloudGeometryHandler &geometry_handler, + const ColorHandlerConstPtr &color_handler, + const std::string &id, + int viewport, + const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0), + const Eigen::Quaternion& sensor_orientation = Eigen::Quaternion (1, 0, 0 ,0)); + + /** \brief Internal function which converts the information present in the geometric + * and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds + * all the required information to the internal cloud_actor_map_ object. + * \param[in] geometry_handler the geometric handler that contains the XYZ data + * \param[in] color_handler the color handler that contains the "RGB" (scalar) data + * \param[in] id the point cloud object id + * \param[in] viewport the view port where the Point Cloud should be added + * \param[in] sensor_origin the origin of the cloud data in global coordinates (defaults to 0,0,0) + * \param[in] sensor_orientation the orientation of the cloud data in global coordinates (defaults to 1,0,0,0) + */ + bool + fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler, + const ColorHandlerConstPtr &color_handler, + const std::string &id, + int viewport, + const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0), + const Eigen::Quaternion& sensor_orientation = Eigen::Quaternion (1, 0, 0 ,0)); + + /** \brief Internal function which converts the information present in the geometric + * and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds + * all the required information to the internal cloud_actor_map_ object. + * \param[in] geometry_handler the geometric handler that contains the XYZ data + * \param[in] color_handler the color handler that contains the "RGB" (scalar) data + * \param[in] id the point cloud object id + * \param[in] viewport the view port where the Point Cloud should be added + * \param[in] sensor_origin the origin of the cloud data in global coordinates (defaults to 0,0,0) + * \param[in] sensor_orientation the orientation of the cloud data in global coordinates (defaults to 1,0,0,0) + */ + template bool + fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler, + const PointCloudColorHandler &color_handler, + const std::string &id, + int viewport, + const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0), + const Eigen::Quaternion& sensor_orientation = Eigen::Quaternion (1, 0, 0 ,0)); + + /** \brief Allocate a new polydata smartpointer. Internal + * \param[out] polydata the resultant poly data + */ + void + allocVtkPolyData (vtkSmartPointer &polydata); + + /** \brief Allocate a new polydata smartpointer. Internal + * \param[out] polydata the resultant poly data + */ + void + allocVtkPolyData (vtkSmartPointer &polydata); + + /** \brief Allocate a new unstructured grid smartpointer. Internal + * \param[out] polydata the resultant poly data + */ + void + allocVtkUnstructuredGrid (vtkSmartPointer &polydata); + + /** \brief Transform the point cloud viewpoint to a transformation matrix + * \param[in] origin the camera origin + * \param[in] orientation the camera orientation + * \param[out] transformation the camera transformation matrix + */ + void + getTransformationMatrix (const Eigen::Vector4f &origin, + const Eigen::Quaternion &orientation, + Eigen::Matrix4f &transformation); + + /** \brief Fills a vtkTexture structure from pcl::TexMaterial. + * \param[in] tex_mat texture material in PCL format + * \param[out] vtk_tex texture material in VTK format + * \return 0 on success and -1 else. + * \note for now only image based textures are supported, image file must be in + * tex_file attribute of \a tex_mat. + */ + int + textureFromTexMaterial (const pcl::TexMaterial& tex_mat, + vtkTexture* vtk_tex) const; + + /** \brief Get camera file for camera parameter saving/restoring from command line. + * Camera filename is calculated using sha1 value of all pathes of input .pcd files + * \return empty string if failed. + */ + std::string + getUniqueCameraFile (int argc, char **argv); + + //There's no reason these conversion functions shouldn't be public and static so others can use them. + public: + /** \brief Convert Eigen::Matrix4f to vtkMatrix4x4 + * \param[in] m the input Eigen matrix + * \param[out] vtk_matrix the resultant VTK matrix + */ + static void + convertToVtkMatrix (const Eigen::Matrix4f &m, + vtkSmartPointer &vtk_matrix); + + /** \brief Convert origin and orientation to vtkMatrix4x4 + * \param[in] origin the point cloud origin + * \param[in] orientation the point cloud orientation + * \param[out] vtk_matrix the resultant VTK 4x4 matrix + */ + static void + convertToVtkMatrix (const Eigen::Vector4f &origin, + const Eigen::Quaternion &orientation, + vtkSmartPointer &vtk_matrix); + + /** \brief Convert vtkMatrix4x4 to an Eigen4f + * \param[in] vtk_matrix the original VTK 4x4 matrix + * \param[out] m the resultant Eigen 4x4 matrix + */ + static void + convertToEigenMatrix (const vtkSmartPointer &vtk_matrix, + Eigen::Matrix4f &m); + + }; + } +} + +#include + +#endif + diff --git a/pcl-1.7/pcl/visualization/point_cloud_color_handlers.h b/pcl-1.7/pcl/visualization/point_cloud_color_handlers.h new file mode 100644 index 0000000..ee56e4b --- /dev/null +++ b/pcl-1.7/pcl/visualization/point_cloud_color_handlers.h @@ -0,0 +1,833 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_POINT_CLOUD_COLOR_HANDLERS_H_ +#define PCL_POINT_CLOUD_COLOR_HANDLERS_H_ + +#if defined __GNUC__ +#pragma GCC system_header +#endif + +// PCL includes +#include +#include +#include +// VTK includes +#include +#include +#include +#include + +namespace pcl +{ + namespace visualization + { + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Base Handler class for PointCloud colors. + * \author Radu B. Rusu + * \ingroup visualization + */ + template + class PointCloudColorHandler + { + public: + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudColorHandler () : + cloud_ (), capable_ (false), field_idx_ (-1), fields_ () + {} + + /** \brief Constructor. */ + PointCloudColorHandler (const PointCloudConstPtr &cloud) : + cloud_ (cloud), capable_ (false), field_idx_ (-1), fields_ () + {} + + /** \brief Destructor. */ + virtual ~PointCloudColorHandler () {} + + /** \brief Check if this handler is capable of handling the input data or not. */ + inline bool + isCapable () const { return (capable_); } + + /** \brief Abstract getName method. */ + virtual std::string + getName () const = 0; + + /** \brief Abstract getFieldName method. */ + virtual std::string + getFieldName () const = 0; + + /** \brief Obtain the actual color for the input dataset as vtk scalars. + * \param[out] scalars the output scalars containing the color for the dataset + * \return true if the operation was successful (the handler is capable and + * the input cloud was given as a valid pointer), false otherwise + */ + virtual bool + getColor (vtkSmartPointer &scalars) const = 0; + + /** \brief Set the input cloud to be used. + * \param[in] cloud the input cloud to be used by the handler + */ + virtual void + setInputCloud (const PointCloudConstPtr &cloud) + { + cloud_ = cloud; + } + + protected: + /** \brief A pointer to the input dataset. */ + PointCloudConstPtr cloud_; + + /** \brief True if this handler is capable of handling the input data, false + * otherwise. + */ + bool capable_; + + /** \brief The index of the field holding the data that represents the color. */ + int field_idx_; + + /** \brief The list of fields available for this PointCloud. */ + std::vector fields_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Handler for random PointCloud colors (i.e., R, G, B will be randomly chosen) + * \author Radu B. Rusu + * \ingroup visualization + */ + template + class PointCloudColorHandlerRandom : public PointCloudColorHandler + { + typedef typename PointCloudColorHandler::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudColorHandlerRandom () : + PointCloudColorHandler () + { + capable_ = true; + } + + /** \brief Constructor. */ + PointCloudColorHandlerRandom (const PointCloudConstPtr &cloud) : + PointCloudColorHandler (cloud) + { + capable_ = true; + } + + /** \brief Abstract getName method. */ + virtual std::string + getName () const { return ("PointCloudColorHandlerRandom"); } + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return ("[random]"); } + + /** \brief Obtain the actual color for the input dataset as vtk scalars. + * \param[out] scalars the output scalars containing the color for the dataset + * \return true if the operation was successful (the handler is capable and + * the input cloud was given as a valid pointer), false otherwise + */ + virtual bool + getColor (vtkSmartPointer &scalars) const; + + protected: + // Members derived from the base class + using PointCloudColorHandler::cloud_; + using PointCloudColorHandler::capable_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Handler for predefined user colors. The color at each point will be drawn + * as the use given R, G, B values. + * \author Radu B. Rusu + * \ingroup visualization + */ + template + class PointCloudColorHandlerCustom : public PointCloudColorHandler + { + typedef typename PointCloudColorHandler::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudColorHandlerCustom (double r, double g, double b) + : PointCloudColorHandler () + , r_ (r) + , g_ (g) + , b_ (b) + { + capable_ = true; + } + + /** \brief Constructor. */ + PointCloudColorHandlerCustom (const PointCloudConstPtr &cloud, + double r, double g, double b) + : PointCloudColorHandler (cloud) + , r_ (r) + , g_ (g) + , b_ (b) + { + capable_ = true; + } + + /** \brief Destructor. */ + virtual ~PointCloudColorHandlerCustom () {}; + + /** \brief Abstract getName method. */ + virtual std::string + getName () const { return ("PointCloudColorHandlerCustom"); } + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return (""); } + + /** \brief Obtain the actual color for the input dataset as vtk scalars. + * \param[out] scalars the output scalars containing the color for the dataset + * \return true if the operation was successful (the handler is capable and + * the input cloud was given as a valid pointer), false otherwise + */ + virtual bool + getColor (vtkSmartPointer &scalars) const; + + protected: + // Members derived from the base class + using PointCloudColorHandler::cloud_; + using PointCloudColorHandler::capable_; + + /** \brief Internal R, G, B holding the values given by the user. */ + double r_, g_, b_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief RGB handler class for colors. Uses the data present in the "rgb" or "rgba" + * fields as the color at each point. + * \author Radu B. Rusu + * \ingroup visualization + */ + template + class PointCloudColorHandlerRGBField : public PointCloudColorHandler + { + typedef typename PointCloudColorHandler::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudColorHandlerRGBField () + { + capable_ = false; + } + + /** \brief Constructor. */ + PointCloudColorHandlerRGBField (const PointCloudConstPtr &cloud) + : PointCloudColorHandler (cloud) + { + setInputCloud (cloud); + } + + /** \brief Destructor. */ + virtual ~PointCloudColorHandlerRGBField () {} + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return ("rgb"); } + + /** \brief Obtain the actual color for the input dataset as vtk scalars. + * \param[out] scalars the output scalars containing the color for the dataset + * \return true if the operation was successful (the handler is capable and + * the input cloud was given as a valid pointer), false otherwise + */ + virtual bool + getColor (vtkSmartPointer &scalars) const; + + /** \brief Set the input cloud to be used. + * \param[in] cloud the input cloud to be used by the handler + */ + virtual void + setInputCloud (const PointCloudConstPtr &cloud); + + protected: + /** \brief Class getName method. */ + virtual std::string + getName () const { return ("PointCloudColorHandlerRGBField"); } + + private: + // Members derived from the base class + using PointCloudColorHandler::cloud_; + using PointCloudColorHandler::capable_; + using PointCloudColorHandler::field_idx_; + using PointCloudColorHandler::fields_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief HSV handler class for colors. Uses the data present in the "h", "s", "v" + * fields as the color at each point. + * \ingroup visualization + */ + template + class PointCloudColorHandlerHSVField : public PointCloudColorHandler + { + typedef typename PointCloudColorHandler::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudColorHandlerHSVField (const PointCloudConstPtr &cloud); + + /** \brief Empty destructor */ + virtual ~PointCloudColorHandlerHSVField () {} + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return ("hsv"); } + + /** \brief Obtain the actual color for the input dataset as vtk scalars. + * \param[out] scalars the output scalars containing the color for the dataset + * \return true if the operation was successful (the handler is capable and + * the input cloud was given as a valid pointer), false otherwise + */ + virtual bool + getColor (vtkSmartPointer &scalars) const; + + protected: + /** \brief Class getName method. */ + virtual std::string + getName () const { return ("PointCloudColorHandlerHSVField"); } + + /** \brief The field index for "S". */ + int s_field_idx_; + + /** \brief The field index for "V". */ + int v_field_idx_; + private: + // Members derived from the base class + using PointCloudColorHandler::cloud_; + using PointCloudColorHandler::capable_; + using PointCloudColorHandler::field_idx_; + using PointCloudColorHandler::fields_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Generic field handler class for colors. Uses an user given field to extract + * 1D data and display the color at each point using a min-max lookup table. + * \author Radu B. Rusu + * \ingroup visualization + */ + template + class PointCloudColorHandlerGenericField : public PointCloudColorHandler + { + typedef typename PointCloudColorHandler::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudColorHandlerGenericField (const std::string &field_name) + : field_name_ (field_name) + { + capable_ = false; + } + + /** \brief Constructor. */ + PointCloudColorHandlerGenericField (const PointCloudConstPtr &cloud, + const std::string &field_name) + : PointCloudColorHandler (cloud) + , field_name_ (field_name) + { + setInputCloud (cloud); + } + + /** \brief Destructor. */ + virtual ~PointCloudColorHandlerGenericField () {} + + /** \brief Get the name of the field used. */ + virtual std::string getFieldName () const { return (field_name_); } + + /** \brief Obtain the actual color for the input dataset as vtk scalars. + * \param[out] scalars the output scalars containing the color for the dataset + * \return true if the operation was successful (the handler is capable and + * the input cloud was given as a valid pointer), false otherwise + */ + virtual bool + getColor (vtkSmartPointer &scalars) const; + + /** \brief Set the input cloud to be used. + * \param[in] cloud the input cloud to be used by the handler + */ + virtual void + setInputCloud (const PointCloudConstPtr &cloud); + + protected: + /** \brief Class getName method. */ + virtual std::string + getName () const { return ("PointCloudColorHandlerGenericField"); } + + private: + using PointCloudColorHandler::cloud_; + using PointCloudColorHandler::capable_; + using PointCloudColorHandler::field_idx_; + using PointCloudColorHandler::fields_; + + /** \brief Name of the field used to create the color handler. */ + std::string field_name_; + }; + + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief RGBA handler class for colors. Uses the data present in the "rgba" field as + * the color at each point. Transparency is handled. + * \author Nizar Sallem + * \ingroup visualization + */ + template + class PointCloudColorHandlerRGBAField : public PointCloudColorHandler + { + typedef typename PointCloudColorHandler::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudColorHandlerRGBAField () + { + capable_ = false; + } + + /** \brief Constructor. */ + PointCloudColorHandlerRGBAField (const PointCloudConstPtr &cloud) + : PointCloudColorHandler (cloud) + { + setInputCloud (cloud); + } + + /** \brief Destructor. */ + virtual ~PointCloudColorHandlerRGBAField () {} + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return ("rgba"); } + + /** \brief Obtain the actual color for the input dataset as vtk scalars. + * \param[out] scalars the output scalars containing the color for the dataset + * \return true if the operation was successful (the handler is capable and + * the input cloud was given as a valid pointer), false otherwise + */ + virtual bool + getColor (vtkSmartPointer &scalars) const; + + /** \brief Set the input cloud to be used. + * \param[in] cloud the input cloud to be used by the handler + */ + virtual void + setInputCloud (const PointCloudConstPtr &cloud); + + protected: + /** \brief Class getName method. */ + virtual std::string + getName () const { return ("PointCloudColorHandlerRGBAField"); } + + // Members derived from the base class + using PointCloudColorHandler::cloud_; + using PointCloudColorHandler::capable_; + using PointCloudColorHandler::field_idx_; + using PointCloudColorHandler::fields_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Base Handler class for PointCloud colors. + * \author Radu B. Rusu + * \ingroup visualization + */ + template <> + class PCL_EXPORTS PointCloudColorHandler + { + public: + typedef pcl::PCLPointCloud2 PointCloud; + typedef PointCloud::Ptr PointCloudPtr; + typedef PointCloud::ConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudColorHandler (const PointCloudConstPtr &cloud) : + cloud_ (cloud), capable_ (false), field_idx_ () + {} + + /** \brief Destructor. */ + virtual ~PointCloudColorHandler () {} + + /** \brief Return whether this handler is capable of handling the input data or not. */ + inline bool + isCapable () const { return (capable_); } + + /** \brief Abstract getName method. */ + virtual std::string + getName () const = 0; + + /** \brief Abstract getFieldName method. */ + virtual std::string + getFieldName () const = 0; + + /** \brief Obtain the actual color for the input dataset as vtk scalars. + * \param[out] scalars the output scalars containing the color for the dataset + * \return true if the operation was successful (the handler is capable and + * the input cloud was given as a valid pointer), false otherwise + */ + virtual bool + getColor (vtkSmartPointer &scalars) const = 0; + + /** \brief Set the input cloud to be used. + * \param[in] cloud the input cloud to be used by the handler + */ + void + setInputCloud (const PointCloudConstPtr &cloud) + { + cloud_ = cloud; + } + + protected: + /** \brief A pointer to the input dataset. */ + PointCloudConstPtr cloud_; + + /** \brief True if this handler is capable of handling the input data, false + * otherwise. + */ + bool capable_; + + /** \brief The index of the field holding the data that represents the color. */ + int field_idx_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Handler for random PointCloud colors (i.e., R, G, B will be randomly chosen) + * \author Radu B. Rusu + * \ingroup visualization + */ + template <> + class PCL_EXPORTS PointCloudColorHandlerRandom : public PointCloudColorHandler + { + typedef PointCloudColorHandler::PointCloud PointCloud; + typedef PointCloud::Ptr PointCloudPtr; + typedef PointCloud::ConstPtr PointCloudConstPtr; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudColorHandlerRandom (const PointCloudConstPtr &cloud) : + PointCloudColorHandler (cloud) + { + capable_ = true; + } + + /** \brief Empty destructor */ + virtual ~PointCloudColorHandlerRandom () {} + + /** \brief Get the name of the class. */ + virtual std::string + getName () const { return ("PointCloudColorHandlerRandom"); } + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return ("[random]"); } + + /** \brief Obtain the actual color for the input dataset as vtk scalars. + * \param[out] scalars the output scalars containing the color for the dataset + * \return true if the operation was successful (the handler is capable and + * the input cloud was given as a valid pointer), false otherwise + */ + virtual bool + getColor (vtkSmartPointer &scalars) const; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Handler for predefined user colors. The color at each point will be drawn + * as the use given R, G, B values. + * \author Radu B. Rusu + * \ingroup visualization + */ + template <> + class PCL_EXPORTS PointCloudColorHandlerCustom : public PointCloudColorHandler + { + typedef PointCloudColorHandler::PointCloud PointCloud; + typedef PointCloud::Ptr PointCloudPtr; + typedef PointCloud::ConstPtr PointCloudConstPtr; + + public: + /** \brief Constructor. */ + PointCloudColorHandlerCustom (const PointCloudConstPtr &cloud, + double r, double g, double b) : + PointCloudColorHandler (cloud), + r_ (r), g_ (g), b_ (b) + { + capable_ = true; + } + + /** \brief Empty destructor */ + virtual ~PointCloudColorHandlerCustom () {} + + /** \brief Get the name of the class. */ + virtual std::string + getName () const { return ("PointCloudColorHandlerCustom"); } + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return (""); } + + /** \brief Obtain the actual color for the input dataset as vtk scalars. + * \param[out] scalars the output scalars containing the color for the dataset + * \return true if the operation was successful (the handler is capable and + * the input cloud was given as a valid pointer), false otherwise + */ + virtual bool + getColor (vtkSmartPointer &scalars) const; + + protected: + /** \brief Internal R, G, B holding the values given by the user. */ + double r_, g_, b_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief RGB handler class for colors. Uses the data present in the "rgb" or "rgba" + * fields as the color at each point. + * \author Radu B. Rusu + * \ingroup visualization + */ + template <> + class PCL_EXPORTS PointCloudColorHandlerRGBField : public PointCloudColorHandler + { + typedef PointCloudColorHandler::PointCloud PointCloud; + typedef PointCloud::Ptr PointCloudPtr; + typedef PointCloud::ConstPtr PointCloudConstPtr; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudColorHandlerRGBField (const PointCloudConstPtr &cloud); + + /** \brief Empty destructor */ + virtual ~PointCloudColorHandlerRGBField () {} + + /** \brief Obtain the actual color for the input dataset as vtk scalars. + * \param[out] scalars the output scalars containing the color for the dataset + * \return true if the operation was successful (the handler is capable and + * the input cloud was given as a valid pointer), false otherwise + */ + virtual bool + getColor (vtkSmartPointer &scalars) const; + + protected: + /** \brief Get the name of the class. */ + virtual std::string + getName () const { return ("PointCloudColorHandlerRGBField"); } + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return ("rgb"); } + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief HSV handler class for colors. Uses the data present in the "h", "s", "v" + * fields as the color at each point. + * \ingroup visualization + */ + template <> + class PCL_EXPORTS PointCloudColorHandlerHSVField : public PointCloudColorHandler + { + typedef PointCloudColorHandler::PointCloud PointCloud; + typedef PointCloud::Ptr PointCloudPtr; + typedef PointCloud::ConstPtr PointCloudConstPtr; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudColorHandlerHSVField (const PointCloudConstPtr &cloud); + + /** \brief Empty destructor */ + virtual ~PointCloudColorHandlerHSVField () {} + + /** \brief Obtain the actual color for the input dataset as vtk scalars. + * \param[out] scalars the output scalars containing the color for the dataset + * \return true if the operation was successful (the handler is capable and + * the input cloud was given as a valid pointer), false otherwise + */ + virtual bool + getColor (vtkSmartPointer &scalars) const; + + protected: + /** \brief Get the name of the class. */ + virtual std::string + getName () const { return ("PointCloudColorHandlerHSVField"); } + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return ("hsv"); } + + /** \brief The field index for "S". */ + int s_field_idx_; + + /** \brief The field index for "V". */ + int v_field_idx_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Generic field handler class for colors. Uses an user given field to extract + * 1D data and display the color at each point using a min-max lookup table. + * \author Radu B. Rusu + * \ingroup visualization + */ + template <> + class PCL_EXPORTS PointCloudColorHandlerGenericField : public PointCloudColorHandler + { + typedef PointCloudColorHandler::PointCloud PointCloud; + typedef PointCloud::Ptr PointCloudPtr; + typedef PointCloud::ConstPtr PointCloudConstPtr; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudColorHandlerGenericField (const PointCloudConstPtr &cloud, + const std::string &field_name); + + /** \brief Empty destructor */ + virtual ~PointCloudColorHandlerGenericField () {} + + /** \brief Obtain the actual color for the input dataset as vtk scalars. + * \param[out] scalars the output scalars containing the color for the dataset + * \return true if the operation was successful (the handler is capable and + * the input cloud was given as a valid pointer), false otherwise + */ + virtual bool + getColor (vtkSmartPointer &scalars) const; + + protected: + /** \brief Get the name of the class. */ + virtual std::string + getName () const { return ("PointCloudColorHandlerGenericField"); } + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return (field_name_); } + + private: + /** \brief Name of the field used to create the color handler. */ + std::string field_name_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief RGBA handler class for colors. Uses the data present in the "rgba" field as + * the color at each point. Transparency is handled. + * \author Nizar Sallem + * \ingroup visualization + */ + template <> + class PCL_EXPORTS PointCloudColorHandlerRGBAField : public PointCloudColorHandler + { + typedef PointCloudColorHandler::PointCloud PointCloud; + typedef PointCloud::Ptr PointCloudPtr; + typedef PointCloud::ConstPtr PointCloudConstPtr; + + public: + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudColorHandlerRGBAField (const PointCloudConstPtr &cloud); + + /** \brief Empty destructor */ + virtual ~PointCloudColorHandlerRGBAField () {} + + /** \brief Obtain the actual color for the input dataset as vtk scalars. + * \param[out] scalars the output scalars containing the color for the dataset + * \return true if the operation was successful (the handler is capable and + * the input cloud was given as a valid pointer), false otherwise + */ + virtual bool + getColor (vtkSmartPointer &scalars) const; + + protected: + /** \brief Get the name of the class. */ + virtual std::string + getName () const { return ("PointCloudColorHandlerRGBAField"); } + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return ("rgba"); } + }; + } +} + +#include + +#endif // PCL_POINT_CLOUD_COLOR_HANDLERS_H_ + diff --git a/pcl-1.7/pcl/visualization/point_cloud_geometry_handlers.h b/pcl-1.7/pcl/visualization/point_cloud_geometry_handlers.h new file mode 100644 index 0000000..c4a4de4 --- /dev/null +++ b/pcl-1.7/pcl/visualization/point_cloud_geometry_handlers.h @@ -0,0 +1,501 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_POINT_CLOUD_GEOMETRY_HANDLERS_H_ +#define PCL_POINT_CLOUD_GEOMETRY_HANDLERS_H_ + +#if defined __GNUC__ +#pragma GCC system_header +#endif + +// PCL includes +#include +#include +// VTK includes +#include +#include +#include + +namespace pcl +{ + namespace visualization + { + /** \brief Base handler class for PointCloud geometry. + * \author Radu B. Rusu + * \ingroup visualization + */ + template + class PointCloudGeometryHandler + { + public: + typedef pcl::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename boost::shared_ptr > Ptr; + typedef typename boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudGeometryHandler (const PointCloudConstPtr &cloud) : + cloud_ (cloud), capable_ (false), + field_x_idx_ (-1), field_y_idx_ (-1), field_z_idx_ (-1), + fields_ () + {} + + /** \brief Destructor. */ + virtual ~PointCloudGeometryHandler () {} + + /** \brief Abstract getName method. + * \return the name of the class/object. + */ + virtual std::string + getName () const = 0; + + /** \brief Abstract getFieldName method. */ + virtual std::string + getFieldName () const = 0; + + /** \brief Checl if this handler is capable of handling the input data or not. */ + inline bool + isCapable () const { return (capable_); } + + /** \brief Obtain the actual point geometry for the input dataset in VTK format. + * \param[out] points the resultant geometry + */ + virtual void + getGeometry (vtkSmartPointer &points) const = 0; + + /** \brief Set the input cloud to be used. + * \param[in] cloud the input cloud to be used by the handler + */ + void + setInputCloud (const PointCloudConstPtr &cloud) + { + cloud_ = cloud; + } + + protected: + /** \brief A pointer to the input dataset. */ + PointCloudConstPtr cloud_; + + /** \brief True if this handler is capable of handling the input data, false + * otherwise. + */ + bool capable_; + + /** \brief The index of the field holding the X data. */ + int field_x_idx_; + + /** \brief The index of the field holding the Y data. */ + int field_y_idx_; + + /** \brief The index of the field holding the Z data. */ + int field_z_idx_; + + /** \brief The list of fields available for this PointCloud. */ + std::vector fields_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief XYZ handler class for PointCloud geometry. Given an input dataset, all XYZ + * data present in fields "x", "y", and "z" is extracted and displayed on screen. + * \author Radu B. Rusu + * \ingroup visualization + */ + template + class PointCloudGeometryHandlerXYZ : public PointCloudGeometryHandler + { + public: + typedef typename PointCloudGeometryHandler::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename boost::shared_ptr > Ptr; + typedef typename boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudGeometryHandlerXYZ (const PointCloudConstPtr &cloud); + + /** \brief Destructor. */ + virtual ~PointCloudGeometryHandlerXYZ () {}; + + /** \brief Class getName method. */ + virtual std::string + getName () const { return ("PointCloudGeometryHandlerXYZ"); } + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return ("xyz"); } + + /** \brief Obtain the actual point geometry for the input dataset in VTK format. + * \param[out] points the resultant geometry + */ + virtual void + getGeometry (vtkSmartPointer &points) const; + + private: + // Members derived from the base class + using PointCloudGeometryHandler::cloud_; + using PointCloudGeometryHandler::capable_; + using PointCloudGeometryHandler::field_x_idx_; + using PointCloudGeometryHandler::field_y_idx_; + using PointCloudGeometryHandler::field_z_idx_; + using PointCloudGeometryHandler::fields_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Surface normal handler class for PointCloud geometry. Given an input + * dataset, all data present in fields "normal_x", "normal_y", and "normal_z" is + * extracted and dislayed on screen as XYZ data. + * \author Radu B. Rusu + * \ingroup visualization + */ + template + class PointCloudGeometryHandlerSurfaceNormal : public PointCloudGeometryHandler + { + public: + typedef typename PointCloudGeometryHandler::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename boost::shared_ptr > Ptr; + typedef typename boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudGeometryHandlerSurfaceNormal (const PointCloudConstPtr &cloud); + + /** \brief Class getName method. */ + virtual std::string + getName () const { return ("PointCloudGeometryHandlerSurfaceNormal"); } + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return ("normal_xyz"); } + + /** \brief Obtain the actual point geometry for the input dataset in VTK format. + * \param[out] points the resultant geometry + */ + virtual void + getGeometry (vtkSmartPointer &points) const; + + private: + // Members derived from the base class + using PointCloudGeometryHandler::cloud_; + using PointCloudGeometryHandler::capable_; + using PointCloudGeometryHandler::field_x_idx_; + using PointCloudGeometryHandler::field_y_idx_; + using PointCloudGeometryHandler::field_z_idx_; + using PointCloudGeometryHandler::fields_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Custom handler class for PointCloud geometry. Given an input dataset and + * three user defined fields, all data present in them is extracted and displayed on + * screen as XYZ data. + * \author Radu B. Rusu + * \ingroup visualization + */ + template + class PointCloudGeometryHandlerCustom : public PointCloudGeometryHandler + { + public: + typedef typename PointCloudGeometryHandler::PointCloud PointCloud; + typedef typename PointCloud::Ptr PointCloudPtr; + typedef typename PointCloud::ConstPtr PointCloudConstPtr; + + typedef typename boost::shared_ptr > Ptr; + typedef typename boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudGeometryHandlerCustom (const PointCloudConstPtr &cloud, + const std::string &x_field_name, + const std::string &y_field_name, + const std::string &z_field_name) + { + field_x_idx_ = pcl::getFieldIndex (*cloud, x_field_name, fields_); + if (field_x_idx_ == -1) + return; + field_y_idx_ = pcl::getFieldIndex (*cloud, y_field_name, fields_); + if (field_y_idx_ == -1) + return; + field_z_idx_ = pcl::getFieldIndex (*cloud, z_field_name, fields_); + if (field_z_idx_ == -1) + return; + field_name_ = x_field_name + y_field_name + z_field_name; + capable_ = true; + } + + /** \brief Class getName method. */ + virtual std::string + getName () const { return ("PointCloudGeometryHandlerCustom"); } + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return (field_name_); } + + /** \brief Obtain the actual point geometry for the input dataset in VTK format. + * \param[out] points the resultant geometry + */ + virtual void + getGeometry (vtkSmartPointer &points) const + { + if (!capable_) + return; + + if (!points) + points = vtkSmartPointer::New (); + points->SetDataTypeToFloat (); + points->SetNumberOfPoints (cloud_->points.size ()); + + float data; + // Add all points + double p[3]; + for (vtkIdType i = 0; i < static_cast (cloud_->points.size ()); ++i) + { + // Copy the value at the specified field + const uint8_t* pt_data = reinterpret_cast (&cloud_->points[i]); + memcpy (&data, pt_data + fields_[field_x_idx_].offset, sizeof (float)); + p[0] = data; + + memcpy (&data, pt_data + fields_[field_y_idx_].offset, sizeof (float)); + p[1] = data; + + memcpy (&data, pt_data + fields_[field_z_idx_].offset, sizeof (float)); + p[2] = data; + + points->SetPoint (i, p); + } + } + + private: + // Members derived from the base class + using PointCloudGeometryHandler::cloud_; + using PointCloudGeometryHandler::capable_; + using PointCloudGeometryHandler::field_x_idx_; + using PointCloudGeometryHandler::field_y_idx_; + using PointCloudGeometryHandler::field_z_idx_; + using PointCloudGeometryHandler::fields_; + + /** \brief Name of the field used to create the geometry handler. */ + std::string field_name_; + }; + + /////////////////////////////////////////////////////////////////////////////////////// + /** \brief Base handler class for PointCloud geometry. + * \author Radu B. Rusu + * \ingroup visualization + */ + template <> + class PCL_EXPORTS PointCloudGeometryHandler + { + public: + typedef pcl::PCLPointCloud2 PointCloud; + typedef PointCloud::Ptr PointCloudPtr; + typedef PointCloud::ConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudGeometryHandler (const PointCloudConstPtr &cloud, const Eigen::Vector4f & = Eigen::Vector4f::Zero ()) + : cloud_ (cloud) + , capable_ (false) + , field_x_idx_ (-1) + , field_y_idx_ (-1) + , field_z_idx_ (-1) + , fields_ (cloud_->fields) + { + } + + /** \brief Destructor. */ + virtual ~PointCloudGeometryHandler () {} + + /** \brief Abstract getName method. */ + virtual std::string + getName () const = 0; + + /** \brief Abstract getFieldName method. */ + virtual std::string + getFieldName () const = 0; + + /** \brief Check if this handler is capable of handling the input data or not. */ + inline bool + isCapable () const { return (capable_); } + + /** \brief Obtain the actual point geometry for the input dataset in VTK format. + * \param[out] points the resultant geometry + */ + virtual void + getGeometry (vtkSmartPointer &points) const; + + /** \brief Set the input cloud to be used. + * \param[in] cloud the input cloud to be used by the handler + */ + void + setInputCloud (const PointCloudConstPtr &cloud) + { + cloud_ = cloud; + } + + protected: + /** \brief A pointer to the input dataset. */ + PointCloudConstPtr cloud_; + + /** \brief True if this handler is capable of handling the input data, false + * otherwise. + */ + bool capable_; + + /** \brief The index of the field holding the X data. */ + int field_x_idx_; + + /** \brief The index of the field holding the Y data. */ + int field_y_idx_; + + /** \brief The index of the field holding the Z data. */ + int field_z_idx_; + + /** \brief The list of fields available for this PointCloud. */ + std::vector fields_; + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief XYZ handler class for PointCloud geometry. Given an input dataset, all XYZ + * data present in fields "x", "y", and "z" is extracted and displayed on screen. + * \author Radu B. Rusu + * \ingroup visualization + */ + template <> + class PCL_EXPORTS PointCloudGeometryHandlerXYZ : public PointCloudGeometryHandler + { + public: + typedef PointCloudGeometryHandler::PointCloud PointCloud; + typedef PointCloud::Ptr PointCloudPtr; + typedef PointCloud::ConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudGeometryHandlerXYZ (const PointCloudConstPtr &cloud); + + /** \brief Destructor. */ + virtual ~PointCloudGeometryHandlerXYZ () {} + + /** \brief Class getName method. */ + virtual std::string + getName () const { return ("PointCloudGeometryHandlerXYZ"); } + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return ("xyz"); } + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Surface normal handler class for PointCloud geometry. Given an input + * dataset, all data present in fields "normal_x", "normal_y", and "normal_z" is + * extracted and dislayed on screen as XYZ data. + * \author Radu B. Rusu + * \ingroup visualization + */ + template <> + class PCL_EXPORTS PointCloudGeometryHandlerSurfaceNormal : public PointCloudGeometryHandler + { + public: + typedef PointCloudGeometryHandler::PointCloud PointCloud; + typedef PointCloud::Ptr PointCloudPtr; + typedef PointCloud::ConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr > Ptr; + typedef boost::shared_ptr > ConstPtr; + + /** \brief Constructor. */ + PointCloudGeometryHandlerSurfaceNormal (const PointCloudConstPtr &cloud); + + /** \brief Class getName method. */ + virtual std::string + getName () const { return ("PointCloudGeometryHandlerSurfaceNormal"); } + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return ("normal_xyz"); } + }; + + ////////////////////////////////////////////////////////////////////////////////////// + /** \brief Custom handler class for PointCloud geometry. Given an input dataset and + * three user defined fields, all data present in them is extracted and displayed on + * screen as XYZ data. + * \author Radu B. Rusu + * \ingroup visualization + */ + template <> + class PCL_EXPORTS PointCloudGeometryHandlerCustom : public PointCloudGeometryHandler + { + public: + typedef PointCloudGeometryHandler::PointCloud PointCloud; + typedef PointCloud::Ptr PointCloudPtr; + typedef PointCloud::ConstPtr PointCloudConstPtr; + + /** \brief Constructor. */ + PointCloudGeometryHandlerCustom (const PointCloudConstPtr &cloud, + const std::string &x_field_name, + const std::string &y_field_name, + const std::string &z_field_name); + + /** \brief Destructor. */ + virtual ~PointCloudGeometryHandlerCustom () {} + + /** \brief Class getName method. */ + virtual std::string + getName () const { return ("PointCloudGeometryHandlerCustom"); } + + /** \brief Get the name of the field used. */ + virtual std::string + getFieldName () const { return (field_name_); } + + private: + /** \brief Name of the field used to create the geometry handler. */ + std::string field_name_; + }; + } +} + +#ifdef PCL_NO_PRECOMPILE +#include +#endif + +#endif // PCL_POINT_CLOUD_GEOMETRY_HANDLERS_H_ + diff --git a/pcl-1.7/pcl/visualization/point_cloud_handlers.h b/pcl-1.7/pcl/visualization/point_cloud_handlers.h new file mode 100644 index 0000000..ec42da5 --- /dev/null +++ b/pcl-1.7/pcl/visualization/point_cloud_handlers.h @@ -0,0 +1,44 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_POINT_CLOUD_HANDLERS_H_ +#define PCL_POINT_CLOUD_HANDLERS_H_ + +#include +#include + +#endif diff --git a/pcl-1.7/pcl/visualization/point_picking_event.h b/pcl-1.7/pcl/visualization/point_picking_event.h new file mode 100644 index 0000000..6c03df9 --- /dev/null +++ b/pcl-1.7/pcl/visualization/point_picking_event.h @@ -0,0 +1,167 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_VISUALIZATION_POINT_PICKING_EVENT_H_ +#define PCL_VISUALIZATION_POINT_PICKING_EVENT_H_ + +#include +#include + +#include +class vtkRenderWindowInteractor; + +namespace pcl +{ + namespace visualization + { + class PCL_EXPORTS PointPickingCallback : public vtkCommand + { + public: + static PointPickingCallback *New () + { + return (new PointPickingCallback); + } + + PointPickingCallback () : x_ (0), y_ (0), z_ (0), idx_ (-1), pick_first_ (false) {} + + /** \brief Empty destructor */ + virtual ~PointPickingCallback () {} + + virtual void + Execute (vtkObject *caller, unsigned long eventid, void*); + + int + performSinglePick (vtkRenderWindowInteractor *iren); + + int + performSinglePick (vtkRenderWindowInteractor *iren, float &x, float &y, float &z); + + int + performAreaPick (vtkRenderWindowInteractor *iren, std::vector &indices); + + private: + float x_, y_, z_; + int idx_; + bool pick_first_; + }; + + /** /brief Class representing 3D point picking events. */ + class PCL_EXPORTS PointPickingEvent + { + public: + PointPickingEvent (int idx) : idx_ (idx), idx2_ (-1), x_ (), y_ (), z_ (), x2_ (), y2_ (), z2_ () {} + PointPickingEvent (int idx, float x, float y, float z) : idx_ (idx), idx2_ (-1), x_ (x), y_ (y), z_ (z), x2_ (), y2_ (), z2_ () {} + + PointPickingEvent (int idx1, int idx2, float x1, float y1, float z1, float x2, float y2, float z2) : + idx_ (idx1), idx2_ (idx2), x_ (x1), y_ (y1), z_ (z1), x2_ (x2), y2_ (y2), z2_ (z2) + {} + + /** \brief Obtain the ID of a point that the user just clicked on. + * \warning If the cloud contains NaNs the index returned by this function will not correspond to the + * original indices. To get the correct index either sanitize the input cloud to remove NaNs or use the + * PointPickingEvent::getPoint function to get the x,y,z of the picked point and then search the original + * cloud for the correct index. An example of how to do this can be found in the pp_callback function in + * visualization/tools/pcd_viewer.cpp + */ + inline int + getPointIndex () const + { + return (idx_); + } + + /** \brief Obtain the XYZ point coordinates of a point that the user just clicked on. + * \param[out] x the x coordinate of the point that got selected by the user + * \param[out] y the y coordinate of the point that got selected by the user + * \param[out] z the z coordinate of the point that got selected by the user + */ + inline void + getPoint (float &x, float &y, float &z) const + { + x = x_; y = y_; z = z_; + } + + /** \brief For situations when multiple points are selected in a sequence, return the point coordinates. + * \param[out] x1 the x coordinate of the first point that got selected by the user + * \param[out] y1 the y coordinate of the first point that got selected by the user + * \param[out] z1 the z coordinate of the firts point that got selected by the user + * \param[out] x2 the x coordinate of the second point that got selected by the user + * \param[out] y2 the y coordinate of the second point that got selected by the user + * \param[out] z2 the z coordinate of the second point that got selected by the user + * \return true, if two points are available and have been clicked by the user, false otherwise + */ + inline bool + getPoints (float &x1, float &y1, float &z1, float &x2, float &y2, float &z2) const + { + if (idx2_ == -1) + return (false); + x1 = x_; y1 = y_; z1 = z_; + x2 = x2_; y2 = y2_; z2 = z2_; + return (true); + } + + /** \brief For situations where multiple points are selected in a sequence, return the points indices. + * \param[out] index_1 index of the first point selected by user + * \param[out] index_2 index of the second point selected by user + * \return true, if two points are available and have been clicked by the user, false otherwise + * \warning If the cloud contains NaNs the index returned by this function will not correspond to the + * original indices. To get the correct index either sanitize the input cloud to remove NaNs or use the + * PointPickingEvent::getPoint function to get the x,y,z of the picked point and then search the original + * cloud for the correct index. An example of how to do this can be found in the pp_callback function in + * visualization/tools/pcd_viewer.cpp + */ + inline bool + getPointIndices (int &index_1, int &index_2) const + { + if (idx2_ == -1) + return (false); + index_1 = idx_; + index_2 = idx2_; + return (true); + } + + private: + int idx_, idx2_; + + float x_, y_, z_; + float x2_, y2_, z2_; + }; + } //namespace visualization +} //namespace pcl + +#endif /* PCL_VISUALIZATION_POINT_PICKING_EVENT_H_ */ + diff --git a/pcl-1.7/pcl/visualization/range_image_visualizer.h b/pcl-1.7/pcl/visualization/range_image_visualizer.h new file mode 100644 index 0000000..dc5305f --- /dev/null +++ b/pcl-1.7/pcl/visualization/range_image_visualizer.h @@ -0,0 +1,117 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + */ + +#include + +#ifndef PCL_VISUALIZATION_RANGE_IMAGE_VISUALIZER_H_ +#define PCL_VISUALIZATION_RANGE_IMAGE_VISUALIZER_H_ + +// PCL includes +#include +#include + +namespace pcl +{ + namespace visualization + { + /** \brief Range image visualizer class. + * \author Bastian Steder + * \ingroup visualization + */ + class PCL_EXPORTS RangeImageVisualizer : public ImageViewer + { + public: + // =====CONSTRUCTOR & DESTRUCTOR===== + //! Constructor + RangeImageVisualizer (const std::string& name="Range Image"); + //! Destructor + ~RangeImageVisualizer (); + + // =====PUBLIC STATIC METHODS===== + /** Get a widget visualizing the given range image. + * You are responsible for deleting it after usage! */ + static RangeImageVisualizer* getRangeImageWidget (const pcl::RangeImage& range_image, float min_value, + float max_value, bool grayscale, const std::string& name="Range image"); + + /** Visualize the given range image and the detected borders in it. + * Borders on the obstacles are marked green, borders on the background are marked bright blue. */ + void visualizeBorders (const pcl::RangeImage& range_image, float min_value, float max_value, bool grayscale, + const pcl::PointCloud& border_descriptions); + + /** Same as above, but returning a new widget. You are responsible for deleting it after usage! */ + static RangeImageVisualizer* getRangeImageBordersWidget (const pcl::RangeImage& range_image, float min_value, + float max_value, bool grayscale, const pcl::PointCloud& border_descriptions, + const std::string& name="Range image with borders"); + + /** Get a widget visualizing the given angle image (assuming values in (-PI, PI]). + * -PI and PI will return the same color + * You are responsible for deleting it after usage! */ + static RangeImageVisualizer* getAnglesWidget (const pcl::RangeImage& range_image, float* angles_image, const std::string& name); + + /** Get a widget visualizing the given angle image (assuming values in (-PI/2, PI/2]). + * -PI/2 and PI/2 will return the same color + * You are responsible for deleting it after usage! */ + static RangeImageVisualizer* getHalfAnglesWidget (const pcl::RangeImage& range_image, float* angles_image, const std::string& name); + + + /** Get a widget visualizing the interest values and extracted interest points. + * The interest points will be marked green. + * You are responsible for deleting it after usage! */ + static RangeImageVisualizer* getInterestPointsWidget (const pcl::RangeImage& range_image, const float* interest_image, float min_value, float max_value, + const pcl::PointCloud& interest_points, const std::string& name); + + // =====PUBLIC METHODS===== + //! Visualize a range image + /* void */ + /* setRangeImage (const pcl::RangeImage& range_image, */ + /* float min_value = -std::numeric_limits::infinity (), */ + /* float max_value = std::numeric_limits::infinity (), */ + /* bool grayscale = false); */ + + void + showRangeImage (const pcl::RangeImage& range_image, + float min_value = -std::numeric_limits::infinity (), + float max_value = std::numeric_limits::infinity (), + bool grayscale = false); + + protected: + // =====PROTECTED MEMBER VARIABLES===== + std::string name_; + }; + } +} + +#endif //#define PCL_VISUALIZATION_RANGE_IMAGE_VISUALIZER_H_ diff --git a/pcl-1.7/pcl/visualization/registration_visualizer.h b/pcl-1.7/pcl/visualization/registration_visualizer.h new file mode 100644 index 0000000..72930a1 --- /dev/null +++ b/pcl-1.7/pcl/visualization/registration_visualizer.h @@ -0,0 +1,210 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_REGISTRATION_VISUALIZER_H_ +#define PCL_REGISTRATION_VISUALIZER_H_ + +// PCL +#include +#include + +namespace pcl +{ + /** \brief @b RegistrationVisualizer represents the base class for rendering + * the intermediate positions ocupied by the source point cloud during it's registration + * to the target point cloud. A registration algorithm is considered as input and + * it's covergence is rendered. + * \author Gheorghe Lisca + * \ingroup visualization + */ + template + class RegistrationVisualizer + { + + public: + /** \brief Empty constructor. */ + RegistrationVisualizer () : + viewer_ (), + viewer_thread_ (), + registration_method_name_ (), + update_visualizer_ (), + first_update_flag_ (), + cloud_source_ (), + cloud_target_ (), + visualizer_updating_mutex_ (), + cloud_intermediate_ (), + cloud_intermediate_indices_ (), + cloud_target_indices_ (), + maximum_displayed_correspondences_ (0) + {} + + /** \brief Set the registration algorithm whose intermediate steps will be rendered. + * The method creates the local callback function pcl::RegistrationVisualizer::update_visualizer_ and + * binds it to the local biffers update function pcl::RegistrationVisualizer::updateIntermediateCloud(). + * The local callback function pcl::RegistrationVisualizer::update_visualizer_ is then linked to + * the pcl::Registration::update_visualizer_ callback function. + * \param registration represents the registration method whose intermediate steps will be rendered. + */ + bool + setRegistration (pcl::Registration ®istration) + { + // Update the name of the registration method to be desplayed + registration_method_name_ = registration.getClassName(); + + // Create the local callback function and bind it to the local function resposable for updating + // the local buffers + update_visualizer_ = boost::bind (&RegistrationVisualizer::updateIntermediateCloud, + this, _1, _2, _3, _4); + + // Register the local callback function to the registration algorithm callback function + registration.registerVisualizationCallback (this->update_visualizer_); + + // Flag that no visualizer update was done. It indicates to visualizer update function to copy + // the registration input source and the target point clouds in the next call. + visualizer_updating_mutex_.lock (); + + first_update_flag_ = false; + + visualizer_updating_mutex_.unlock (); + + return true; + } + + /** \brief Start the viewer thread + */ + void + startDisplay (); + + /** \brief Stop the viewer thread + */ + void + stopDisplay (); + + /** \brief Updates visualizer local buffers cloud_intermediate, cloud_intermediate_indices, cloud_target_indices with + * the newest registration intermediate results. + * \param cloud_src represents the initial source point cloud + * \param indices_src represents the incices of the intermediate source points used for the estimation of rigid transformation + * \param cloud_tgt represents the target point cloud + * \param indices_tgt represents the incices of the target points used for the estimation of rigid transformation + */ + void + updateIntermediateCloud (const pcl::PointCloud &cloud_src, const std::vector &indices_src, + const pcl::PointCloud &cloud_tgt, const std::vector &indices_tgt); + + /** \brief Set maximum number of corresponcence lines whch will be rendered. */ + inline void + setMaximumDisplayedCorrespondences (const int maximum_displayed_correspondences) + { + // This method is usualy called form other thread than visualizer thread + // therefore same visualizer_updating_mutex_ will be used + + // Lock maximum_displayed_correspondences_ + visualizer_updating_mutex_.lock (); + + // Update maximum_displayed_correspondences_ + maximum_displayed_correspondences_ = maximum_displayed_correspondences; + + // Unlock maximum_displayed_correspondences_ + visualizer_updating_mutex_.unlock(); + } + + /** \brief Return maximum number of corresponcence lines which are rendered. */ + inline size_t + getMaximumDisplayedCorrespondences() + { + return maximum_displayed_correspondences_; + } + + private: + /** \brief Initialize and run the visualization loop. This function will be runned in the internal thread viewer_thread_ */ + void + runDisplay (); + + /** \brief Return the string obtained by concatenating a root_name and an id */ + inline std::string + getIndexedName (std::string &root_name, size_t &id) + { + std::stringstream id_stream_; + id_stream_ << id; + std::string indexed_name_ = root_name + id_stream_.str (); + return indexed_name_; + } + + /** \brief The registration viewer. */ + boost::shared_ptr viewer_; + + /** \brief The thread running the runDisplay() function. */ + boost::thread viewer_thread_; + + /** \brief The name of the registration method whose intermediate results are rendered. */ + std::string registration_method_name_; + + /** \brief Callback function linked to pcl::Registration::update_visualizer_ */ + boost::function &cloud_src, const std::vector &indices_src, const pcl::PointCloud< + PointTarget> &cloud_tgt, const std::vector &indices_tgt)> update_visualizer_; + + /** \brief Updates source and target point clouds only for the first update call. */ + bool first_update_flag_; + + /** \brief The local buffer for source point cloud. */ + pcl::PointCloud cloud_source_; + + /** \brief The local buffer for target point cloud. */ + pcl::PointCloud cloud_target_; + + /** \brief The mutex used for the sincronization of updating and rendering of the local buffers. */ + boost::mutex visualizer_updating_mutex_; + + /** \brief The local buffer for intermediate point cloud obtained during registration process. */ + pcl::PointCloud cloud_intermediate_; + + /** \brief The indices of intermediate points used for computation of rigid transformation. */ + std::vector cloud_intermediate_indices_; + + /** \brief The indices of target points used for computation of rigid transformation. */ + std::vector cloud_target_indices_; + + /** \brief The maximum number of displayed correspondences. */ + size_t maximum_displayed_correspondences_; + + }; +} + +#include + +#endif //#ifndef PCL_REGISTRATION_VISUALIZER_H_ diff --git a/pcl-1.7/pcl/visualization/simple_buffer_visualizer.h b/pcl-1.7/pcl/visualization/simple_buffer_visualizer.h new file mode 100644 index 0000000..75521c7 --- /dev/null +++ b/pcl-1.7/pcl/visualization/simple_buffer_visualizer.h @@ -0,0 +1,228 @@ +#ifndef PCL_VISUALIZATION_SIMPLE_BUFF_H +#define PCL_VISUALIZATION_SIMPLE_BUFF_H + +#include + +//#include + + +namespace pcl +{ + namespace visualization + { + /** \brief PCL simple buffer visualizer main class. + * \note The idea is to offer a simple visualizer that stores and display the last X values as a curve. + * \note The class is based on PCLHistogramVisualizer and pcl::VFHSignature308 for display. + * \note Therefore, the number of values is limited to [2-308]. + * \author Raphael Favier + * \ingroup visualization + */ + class PCL_EXPORTS PCLSimpleBufferVisualizer + { + public: + /** \brief PCL simple buffer visualizer visualizer default constructor. */ + PCLSimpleBufferVisualizer () + { + histo_ = new PCLHistogramVisualizer (); + nb_values_ = 308; + + // init values buffer + initValuesAndVisualization(); + } + + /** \brief PCL simple buffer visualizer visualizer constructor. + * \param[in] nb_values the number of values stored in the buffer [2 - 308] + */ + PCLSimpleBufferVisualizer (const int nb_values) + { + histo_ = new PCLHistogramVisualizer (); + nb_values_ = nb_values; + + if(nb_values_ > 308) + { + PCL_WARN("Maximum number of values can only be 308 (%d given). Setting back to 308. \n"); + nb_values_ = 308; + } + + if(nb_values_ <= 1) + { + PCL_WARN("Number of values must be at least 2 (%d given). Setting it to default (308). \n"); + nb_values_ = 308; + } + + // init values buffer + initValuesAndVisualization(); + } + + /** \brief force display of values. + * \param[in] time - How long (in ms) should the visualization loop be allowed to run + */ + void + displayValues (const int time = 1) + { + // load values into cloud + updateValuesToDisplay(); + + // check if we need to automatically handle the backgroud color + if(control_background_color_) + { + if(values_.back() < lowest_threshold_) + { + histo_->setBackgroundColor(255.0, 140.0, 0.0); + } + else + { + histo_->setBackgroundColor(255.0, 255.0, 255.0); + } + } + + // add cloud to the visualizer + histo_->updateFeatureHistogram(cloud_, nb_values_); + + // check if we need to handle the Y scale ourselves + if (handle_y_scale_) + { + histo_->setGlobalYRange(min_, max_); + } + + // spin once + spinOnce(time); + } + + /** \brief add a new value at the end of the buffer. + * \param[in] val the float value to add. + */ + void + addValue (const float val) + { + // remove front value + values_.pop_front(); + + // push new value in the back + values_.push_back(val); + + // udapte min_ and max_ values + if (val > max_) + max_ = val; + + if (val < min_) + min_ = val; + } + + /** \brief spinOnce method. + * \param[in] time - How long (in ms) should the visualization loop be allowed to run + */ + void + spinOnce (const int time = 1) + { + histo_->spinOnce(time); + } + + /** \brief spin method. */ + void + spin () + { + histo_->spin(); + } + + /** \brief set background color handling mode. + * \note The point here is to change the background to orange when the latest value is under a threshold. + * \param[in] value if true, automatic mode is enabled. Else, background will be white + * \param[in] threshold value that triggers the background to turn orange if the latest value is lower + * \note This functionality does not work yet at time of commit (see http://dev.pointclouds.org/issues/829) + */ + void + setAutomaticBackgroundColorControl (const bool value = true, const float threshold = 0.0f) + { + control_background_color_ = value; + + // if the user sets it back to false, we make sure to reset the bckgrd color to white + if(value == false) + histo_->setBackgroundColor(255.0, 255.0, 255.0); + + lowest_threshold_ = threshold; + } + + /** \brief set Y scale policy. + * \note If set to true, the minimal and maximal Y values are kept forever. + * \note If set to false, the Y scale is automatically adjusted to the current values (default). + * \param[in] value boolean that enable or disable this policy + */ + void + setManuallyManageYScale (const bool value = false) + { + handle_y_scale_ = value; + } + + private: + /** \brief initialize ther buffer that stores the values to zero. + * \note The size is set by private member nb_values_ which is in the range [2-308]. + */ + void + initValuesAndVisualization () + { + cloud_.points.resize(1); + + PCL_WARN("Setting buffer size to %d entries.\n", nb_values_); + values_.resize(nb_values_); + + // add the cloud to the histogram viewer + histo_->addFeatureHistogram(cloud_, nb_values_); + + // init GUI-related variables + initGUIValues(); + } + + /** \brief pushes the values contained inside the buffer to the cloud used for visualization. */ + void + updateValuesToDisplay () + { + for(int i = 0 ; i < nb_values_ ; ++i) + { + cloud_.points[0].histogram[i] = values_[i]; + } + } + + /** \brief initialize private variables linked to the GUI */ + void + initGUIValues () + { + control_background_color_ = false; + lowest_threshold_ = 0.0f; + + handle_y_scale_ = false; + + min_ = -1.0f; // numeric_limits::max( ); + max_ = 1.0f; // numeric_limits::min( ); + } + + /** \brief visualizer object */ + PCLHistogramVisualizer *histo_; + + /** \brief cloud used for visualization */ + PointCloud cloud_; + + /** \brief buffer of values */ + std::deque values_; + + /** \brief number of values stored in the buffer + * \note ([2-308]) + */ + int nb_values_; + + /** \brief boolean used to know if we need to change the backgroud color in case of low values. */ + bool control_background_color_; + + /** \brief threshold to turn the background orange if latest value is lower. */ + float lowest_threshold_; + + /** \brief boolean used to know if we need to change the backgroud color in case of low values. True means we do it ourselves. */ + bool handle_y_scale_; + + /** \brief float tracking the minimal and maximal values ever observed. */ + float min_, max_; + }; + } +} + +#endif // PCL_VISUALIZATION_SIMPLE_BUFF_H diff --git a/pcl-1.7/pcl/visualization/vtk.h b/pcl-1.7/pcl/visualization/vtk.h new file mode 100644 index 0000000..e390e9c --- /dev/null +++ b/pcl-1.7/pcl/visualization/vtk.h @@ -0,0 +1,187 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ +#ifndef PCL_PCL_VISUALIZER_VTK_H_ +#define PCL_PCL_VISUALIZER_VTK_H_ + +#if defined __GNUC__ +#pragma GCC system_header +#ifdef __DEPRECATED +#undef __DEPRECATED +#define __DEPRECATED_DISABLED__ +#endif +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION >= 10)) +#include +#include +#include +#endif +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) +# include +#else +# include +# include +# include +# include +# include +# include +# include +# include +#endif +#include + +#if VTK_MAJOR_VERSION==6 || (VTK_MAJOR_VERSION==5 && VTK_MINOR_VERSION>4) +#include +#else +#include +#endif + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#if defined __GNUC__ && defined __DEPRECATED_DISABLED__ +#define __DEPRECATED +#undef __DEPRECATED_DISABLED__ +#endif + +#endif // PCL_PCL_VISUALIZER_VTK_H_ + diff --git a/pcl-1.7/pcl/visualization/vtk/pcl_context_item.h b/pcl-1.7/pcl/visualization/vtk/pcl_context_item.h new file mode 100644 index 0000000..9078fc5 --- /dev/null +++ b/pcl-1.7/pcl/visualization/vtk/pcl_context_item.h @@ -0,0 +1,175 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_VISUALIZATION_PCL_CONTEXT_ITEM_H_ +#define PCL_VISUALIZATION_PCL_CONTEXT_ITEM_H_ + +#include +#include +#include + +template class vtkSmartPointer; +class vtkImageData; +class vtkContext2D; + +namespace pcl +{ + namespace visualization + { + /** Struct PCLContextItem represents our own custom version of vtkContextItem, used by + * the ImageViewer class. + * + * \author Nizar Sallem + */ + struct PCL_EXPORTS PCLContextItem : public vtkContextItem + { + vtkTypeMacro (PCLContextItem, vtkContextItem); + static PCLContextItem *New(); + virtual bool Paint (vtkContext2D *) { return (false); }; + void setColors (unsigned char r, unsigned char g, unsigned char b); + void setColors (unsigned char rgb[3]) { memcpy (colors, rgb, 3 * sizeof (unsigned char)); } + void setOpacity (double opacity) { SetOpacity (opacity); }; + unsigned char colors[3]; + double opacity; + std::vector params; + }; + + /** Struct PCLContextImageItem a specification of vtkContextItem, used to add an image to the + * scene in the ImageViewer class. + * + * \author Nizar Sallem + */ + struct PCL_EXPORTS PCLContextImageItem : public vtkContextItem + { + vtkTypeMacro (PCLContextImageItem, vtkContextItem); + PCLContextImageItem (); + + static PCLContextImageItem *New (); + virtual bool Paint (vtkContext2D *painter); + void set (float _x, float _y, vtkImageData *_image); + vtkSmartPointer image; + float x, y; + }; + + namespace context_items + { + struct PCL_EXPORTS Point : public PCLContextItem + { + vtkTypeMacro (Point, PCLContextItem); + static Point *New(); + virtual bool Paint (vtkContext2D *painter); + virtual void set (float _x, float _y); + }; + + struct PCL_EXPORTS Line : public PCLContextItem + { + vtkTypeMacro (Line, PCLContextItem); + static Line *New(); + virtual bool Paint (vtkContext2D *painter); + virtual void set (float _x_1, float _y_1, float _x_2, float _y_2); + }; + + struct PCL_EXPORTS Circle : public PCLContextItem + { + vtkTypeMacro (Circle, PCLContextItem); + static Circle *New(); + virtual bool Paint (vtkContext2D *painter); + virtual void set (float _x, float _y, float _r); + }; + + struct PCL_EXPORTS Disk : public Circle + { + vtkTypeMacro (Disk, Circle); + static Disk *New(); + virtual bool Paint (vtkContext2D *painter); + }; + + struct PCL_EXPORTS Rectangle : public PCLContextItem + { + vtkTypeMacro (Rectangle, Point); + static Rectangle *New(); + virtual bool Paint (vtkContext2D *painter); + virtual void set (float _x, float _y, float _w, float _h); + }; + + struct PCL_EXPORTS FilledRectangle : public Rectangle + { + vtkTypeMacro (FilledRectangle, Rectangle); + static FilledRectangle *New(); + virtual bool Paint (vtkContext2D *painter); + }; + + struct PCL_EXPORTS Points : public PCLContextItem + { + vtkTypeMacro (Points, PCLContextItem); + static Points *New(); + virtual bool Paint (vtkContext2D *painter); + void set (const std::vector& _xy) { params = _xy; } + }; + + struct PCL_EXPORTS Polygon : public Points + { + vtkTypeMacro (Polygon, Points); + static Polygon *New(); + virtual bool Paint (vtkContext2D *painter); + }; + + struct PCL_EXPORTS Text : public PCLContextItem + { + vtkTypeMacro (Text, PCLContextItem); + static Text *New (); + virtual bool Paint (vtkContext2D *painter); + virtual void set (float x, float y, const std::string& _text); + std::string text; + }; + + struct PCL_EXPORTS Markers : public Points + { + vtkTypeMacro (Markers, Points); + static Markers *New (); + virtual bool Paint (vtkContext2D *painter); + void setSize (float _size) { size = _size; } + void setPointColors (unsigned char r, unsigned char g, unsigned char b); + void setPointColors (unsigned char rgb[3]); + float size; + unsigned char point_colors[3]; + }; + } + } +} + +#endif diff --git a/pcl-1.7/pcl/visualization/vtk/pcl_image_canvas_source_2d.h b/pcl-1.7/pcl/visualization/vtk/pcl_image_canvas_source_2d.h new file mode 100644 index 0000000..3f79012 --- /dev/null +++ b/pcl-1.7/pcl/visualization/vtk/pcl_image_canvas_source_2d.h @@ -0,0 +1,62 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_VTK_IMAGE_CANVAS_SOURCE_2D_H_ +#define PCL_VTK_IMAGE_CANVAS_SOURCE_2D_H_ + +#include +#include + +namespace pcl +{ + namespace visualization + { + /** \brief PCLImageCanvasSource2D represents our own custom version of + * vtkImageCanvasSource2D, used by the ImageViewer class. + */ + class PCL_EXPORTS PCLImageCanvasSource2D : public vtkImageCanvasSource2D + { + public: + static PCLImageCanvasSource2D *New (); + + void + DrawImage (vtkImageData* image); + }; + } +} + +#endif // PCL_VTK_IMAGE_CANVAS_SOURCE_2D_H_ diff --git a/pcl-1.7/pcl/visualization/vtk/vtkRenderWindowInteractorFix.h b/pcl-1.7/pcl/visualization/vtk/vtkRenderWindowInteractorFix.h new file mode 100644 index 0000000..a2bf54b --- /dev/null +++ b/pcl-1.7/pcl/visualization/vtk/vtkRenderWindowInteractorFix.h @@ -0,0 +1,45 @@ + /* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ +#ifndef PCL_VISUALIZATION_VTK_RENDER_WINDOW_FIX_H_ +#define PCL_VISUALIZATION_VTK_RENDER_WINDOW_FIX_H_ + +#include + +vtkRenderWindowInteractor* vtkRenderWindowInteractorFixNew (); + +#endif // PCL_VISUALIZATION_VTK_RENDER_WINDOW_FIX_H_ + diff --git a/pcl-1.7/pcl/visualization/vtk/vtkVertexBufferObject.h b/pcl-1.7/pcl/visualization/vtk/vtkVertexBufferObject.h new file mode 100644 index 0000000..a124e0a --- /dev/null +++ b/pcl-1.7/pcl/visualization/vtk/vtkVertexBufferObject.h @@ -0,0 +1,219 @@ + /*========================================================================= + + Program: Visualization Toolkit + Module: vtkPixelBufferObject.h + + Copyright (c) Ken Martin, Will Schroeder, Bill Lorensen + All rights reserved. + See Copyright.txt or http://www.kitware.com/Copyright.htm for details. + + This software is distributed WITHOUT ANY WARRANTY; without even + the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR + PURPOSE. See the above copyright notice for more information. + +=========================================================================*/ +// .NAME vtkVertexBufferObject - abstracts an OpenGL vertex buffer object. +// .SECTION Description +// Provides low-level access to GPU memory. Used to pass raw data to GPU. +// The data is uploaded into a vertex buffer. +// .SECTION See Also +// OpenGL Vertex Buffer Object Extension Spec (ARB_vertex_buffer_object): +// http://www.opengl.org/registry/specs/ARB/vertex_buffer_object.txt +// .SECTION Caveats +// Since most GPUs don't support double format all double data is converted to +// float and then uploaded. +// DON'T PLAY WITH IT YET. + +#ifndef __vtkVertexBufferObject_h +#define __vtkVertexBufferObject_h + +#include + +#include "vtkObject.h" +#include "vtkWeakPointer.h" + +#include "vtkgl.h" // Needed for gl data types exposed in API +#include + +class vtkCellArray; +class vtkDataArray; +class vtkObject; +class vtkPoints; +class vtkUnsignedCharArray; +class vtkOpenGLExtensionManager; +class vtkRenderWindow; + +class PCL_EXPORTS vtkVertexBufferObject : public vtkObject +{ +public: + + static vtkVertexBufferObject* New(); + vtkTypeMacro(vtkVertexBufferObject, vtkObject); + void PrintSelf(ostream& os, vtkIndent indent); + + // Description: + // Get/Set the context. Context must be a vtkOpenGLRenderWindow. + // This does not increase the reference count of the + // context to avoid reference loops. + // SetContext() may raise an error is the OpenGL context does not support the + // required OpenGL extensions. + void SetContext(vtkRenderWindow* context); + vtkRenderWindow* GetContext(); + + //BTX + // Usage values. + enum + { + StreamDraw=0, + StreamRead, + StreamCopy, + StaticDraw, + StaticRead, + StaticCopy, + DynamicDraw, + DynamicRead, + DynamicCopy, + NumberOfUsages + }; + //ETX + + // Description: + // Usage is a performance hint. + // Valid values are: + // - StreamDraw specified once by A, used few times S + // - StreamRead specified once by R, queried a few times by A + // - StreamCopy specified once by R, used a few times S + // - StaticDraw specified once by A, used many times S + // - StaticRead specificed once by R, queried many times by A + // - StaticCopy specified once by R, used many times S + // - DynamicDraw respecified repeatedly by A, used many times S + // - DynamicRead respecified repeatedly by R, queried many times by A + // - DynamicCopy respecified repeatedly by R, used many times S + // A: the application + // S: as the source for GL drawing and image specification commands. + // R: reading data from the GL + // Initial value is StaticDraw, as in OpenGL spec. + vtkGetMacro(Usage, int); + vtkSetMacro(Usage, int); + + int GetAttributeIndex(); + void SetUserDefinedAttribute(int index, bool normalized=false, int stride=0); + void ResetUserDefinedAttribute(); + + void SetAttributeNormalized(bool normalized); + + // Description: + // Set point data + bool Upload(vtkPoints *points); + + // Description: + // Set indice data + bool Upload(vtkCellArray *verts); + + // Description: + // Set indice data + bool Upload(unsigned int *indices, unsigned int count); + + // Description: + // Set color data + bool Upload(vtkUnsignedCharArray *colors); + + // Description: + // Set color data + bool Upload(vtkDataArray *array); + bool Upload(vtkDataArray *array, int attributeType, int arrayType); + bool UploadNormals(vtkDataArray *normals); + bool UploadColors(vtkDataArray *colors); + + + // Description: + // Get the size of the data loaded into the GPU. Size is in the number of + // elements of the uploaded Type. + vtkGetMacro(Size, unsigned int); + + // Description: + // Get the size of the data loaded into the GPU. Size is in the number of + // elements of the uploaded Type. + vtkGetMacro(Count, unsigned int); + + // Description: + // Get the openGL buffer handle. + vtkGetMacro(Handle, unsigned int); + + // Description: + // Inactivate the buffer. + void UnBind(); + + // Description: + // Make the buffer active. + void Bind(); + + // Description: + // Allocate the memory. size is in number of bytes. type is a VTK type. +// void Allocate(unsigned int size, int type); + +//BTX + + // Description: + // Release the memory allocated without destroying the PBO handle. + void ReleaseMemory(); + + // Description: + // Returns if the context supports the required extensions. + static bool IsSupported(vtkRenderWindow* renWin); + +//ETX +//BTX +protected: + vtkVertexBufferObject(); + ~vtkVertexBufferObject(); + + // Description: + // Loads all required OpenGL extensions. Must be called every time a new + // context is set. + bool LoadRequiredExtensions(vtkOpenGLExtensionManager* mgr); + + // Description: + // Create the pixel buffer object. + void CreateBuffer(); + + // Description: + // Destroys the pixel buffer object. + void DestroyBuffer(); + + // Description: + // Uploads data to buffer object + bool Upload(GLvoid* data); + + // Description: + // Get the openGL buffer handle. + vtkGetMacro(ArrayType, unsigned int); + + int Usage; + unsigned int Size; + unsigned int Count; + unsigned int Handle; + unsigned int ArrayType; + unsigned int BufferTarget; + + int AttributeIndex; + int AttributeSize; + int AttributeType; + int AttributeNormalized; + int AttributeStride; + + vtkWeakPointer Context; + + +private: + vtkVertexBufferObject(const vtkVertexBufferObject&); // Not implemented. + void operator=(const vtkVertexBufferObject&); // Not implemented. + + // Helper to get data type sizes when passing to opengl + int GetDataTypeSize(int type); + //ETX +}; + +#endif + + diff --git a/pcl-1.7/pcl/visualization/vtk/vtkVertexBufferObjectMapper.h b/pcl-1.7/pcl/visualization/vtk/vtkVertexBufferObjectMapper.h new file mode 100644 index 0000000..e96ad63 --- /dev/null +++ b/pcl-1.7/pcl/visualization/vtk/vtkVertexBufferObjectMapper.h @@ -0,0 +1,137 @@ +/*========================================================================= + + Program: Visualization Toolkit + Module: vtkVertexBufferObjectMapper.h + + Copyright (c) Ken Martin, Will Schroeder, Bill Lorensen + All rights reserved. + See Copyright.txt or http://www.kitware.com/Copyright.htm for details. + + This software is distributed WITHOUT ANY WARRANTY; without even + the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR + PURPOSE. See the above copyright notice for more information. + +=========================================================================*/ +// .NAME vtkVertexBufferObjectMapper - map vtkPolyData to graphics primitives +// .SECTION Description +// vtkVertexBufferObjectMapper is a class that maps polygonal data (i.e., vtkPolyData) +// to graphics primitives. vtkVertexBufferObjectMapper serves as a superclass for +// device-specific poly data mappers, that actually do the mapping to the +// rendering/graphics hardware/software. + +#ifndef __vtkVertexBufferObjectMapper_h +#define __vtkVertexBufferObjectMapper_h + +#include + +#include "vtkMapper.h" +#include "vtkSmartPointer.h" + +class vtkOpenGLRenderWindow; +class vtkPolyData; +class vtkRenderer; +class vtkRenderWindow; +class vtkShader2; +class vtkShaderProgram2; +class vtkVertexBufferObject; + +class PCL_EXPORTS vtkVertexBufferObjectMapper : public vtkMapper +{ +public: + static vtkVertexBufferObjectMapper *New(); + vtkTypeMacro(vtkVertexBufferObjectMapper, vtkMapper); +// void PrintSelf(ostream& os, vtkIndent indent); + + // Description: + // Implemented by sub classes. Actual rendering is done here. +// virtual void RenderPiece(vtkRenderer *ren, vtkActor *act); + + // Description: + // This calls RenderPiece (in a for loop is streaming is necessary). + virtual void Render(vtkRenderer *ren, vtkActor *act); + + // Description: + // Specify the input data to map. + //void SetInputData(vtkPolyData *in); + void SetInput(vtkPolyData *input); + void SetInput(vtkDataSet *input); + vtkPolyData *GetInput(); + + void SetProgram(vtkSmartPointer program) + { + this->program = program; + } + + // Description: + // Update that sets the update piece first. + void Update(); + + // Description: + // Return bounding box (array of six doubles) of data expressed as + // (xmin,xmax, ymin,ymax, zmin,zmax). + virtual double *GetBounds(); + virtual void GetBounds(double bounds[6]) + {this->Superclass::GetBounds(bounds);}; + + // Description: + // Make a shallow copy of this mapper. +// void ShallowCopy(vtkAbstractMapper *m); + + // Description: + // Select a data array from the point/cell data + // and map it to a generic vertex attribute. + // vertexAttributeName is the name of the vertex attribute. + // dataArrayName is the name of the data array. + // fieldAssociation indicates when the data array is a point data array or + // cell data array (vtkDataObject::FIELD_ASSOCIATION_POINTS or + // (vtkDataObject::FIELD_ASSOCIATION_CELLS). + // componentno indicates which component from the data array must be passed as + // the attribute. If -1, then all components are passed. +// virtual void MapDataArrayToVertexAttribute( +// const char* vertexAttributeName, +// const char* dataArrayName, int fieldAssociation, int componentno=-1); +// +// virtual void MapDataArrayToMultiTextureAttribute( +// int unit, +// const char* dataArrayName, int fieldAssociation, int componentno=-1); + + // Description: + // Remove a vertex attribute mapping. +// virtual void RemoveVertexAttributeMapping(const char* vertexAttributeName); +// +// // Description: +// // Remove all vertex attributes. +// virtual void RemoveAllVertexAttributeMappings(); + +protected: + vtkVertexBufferObjectMapper(); + ~vtkVertexBufferObjectMapper() {}; + + // Description: + // Called in GetBounds(). When this method is called, the consider the input + // to be updated depending on whether this->Static is set or not. This method + // simply obtains the bounds from the data-object and returns it. + virtual void ComputeBounds(); + + vtkVertexBufferObject *vertexVbo; + vtkVertexBufferObject *indiceVbo; + vtkVertexBufferObject *colorVbo; + vtkVertexBufferObject *normalVbo; +// vtkVertexBufferObject *normalIndiceVbo; + + vtkSmartPointer program; + + virtual int FillInputPortInformation(int, vtkInformation*); + + void createShaders(vtkOpenGLRenderWindow* win); + void createVBOs(vtkRenderWindow* win); + + bool initialized; + bool shadersInitialized; + +private: + vtkVertexBufferObjectMapper(const vtkVertexBufferObjectMapper&); // Not implemented. + void operator=(const vtkVertexBufferObjectMapper&); // Not implemented. +}; + +#endif diff --git a/pcl-1.7/pcl/visualization/window.h b/pcl-1.7/pcl/visualization/window.h new file mode 100644 index 0000000..c434343 --- /dev/null +++ b/pcl-1.7/pcl/visualization/window.h @@ -0,0 +1,233 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2012, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +#ifndef PCL_VISUALIZER_WINDOW_H__ +#define PCL_VISUALIZER_WINDOW_H__ + +#include +#include + +#include + +template class vtkSmartPointer; +class vtkObject; +class vtkRenderWindow; +class vtkRenderWindowInteractor; +class vtkCallbackCommand; +class vtkRendererCollection; +class PCLVisualizerInteractorStyle; + +namespace pcl +{ + namespace visualization + { + class MouseEvent; + class KeyboardEvent; + + class PCL_EXPORTS Window + { + public: + Window (const std::string& window_name = ""); + Window (const Window &src); + Window& operator = (const Window &src); + + virtual ~Window (); + + /** \brief Spin method. Calls the interactor and runs an internal loop. */ + void + spin (); + + /** \brief Spin once method. Calls the interactor and updates the screen once. + * \param time - How long (in ms) should the visualization loop be allowed to run. + * \param force_redraw - if false it might return without doing anything if the + * interactor's framerate does not require a redraw yet. + */ + void + spinOnce (int time = 1, bool force_redraw = false); + + /** \brief Returns true when the user tried to close the window */ + bool + wasStopped () const { return (stopped_); } + + /** + * @brief registering a callback function for keyboard events + * @param callback the function that will be registered as a callback for a keyboard event + * @param cookie user data that is passed to the callback + * @return connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerKeyboardCallback (void (*callback) (const pcl::visualization::KeyboardEvent&, void*), + void* cookie = NULL) + { + return registerKeyboardCallback (boost::bind (callback, _1, cookie)); + } + + /** + * @brief registering a callback function for keyboard events + * @param callback the member function that will be registered as a callback for a keyboard event + * @param instance instance to the class that implements the callback function + * @param cookie user data that is passed to the callback + * @return connection object that allows to disconnect the callback function. + */ + template boost::signals2::connection + registerKeyboardCallback (void (T::*callback) (const pcl::visualization::KeyboardEvent&, void*), + T& instance, void* cookie = NULL) + { + return registerKeyboardCallback (boost::bind (callback, boost::ref (instance), _1, cookie)); + } + + /** + * @brief + * @param callback the function that will be registered as a callback for a mouse event + * @param cookie user data that is passed to the callback + * @return connection object that allows to disconnect the callback function. + */ + boost::signals2::connection + registerMouseCallback (void (*callback) (const pcl::visualization::MouseEvent&, void*), + void* cookie = NULL) + { + return registerMouseCallback (boost::bind (callback, _1, cookie)); + } + + /** + * @brief registering a callback function for mouse events + * @param callback the member function that will be registered as a callback for a mouse event + * @param instance instance to the class that implements the callback function + * @param cookie user data that is passed to the callback + * @return connection object that allows to disconnect the callback function. + */ + template boost::signals2::connection + registerMouseCallback (void (T::*callback) (const pcl::visualization::MouseEvent&, void*), + T& instance, void* cookie = NULL) + { + return registerMouseCallback (boost::bind (callback, boost::ref (instance), _1, cookie)); + } + + protected: // methods + + /** \brief Set the stopped flag back to false */ + void + resetStoppedFlag () { stopped_ = false; } + + /** + * @brief registering a callback function for mouse events + * @return connection object that allows to disconnect the callback function. + */ + // param the boost function that will be registered as a callback for a mouse event + boost::signals2::connection + registerMouseCallback (boost::function ); + + /** + * @brief registering a callback boost::function for keyboard events + * @return connection object that allows to disconnect the callback function. + */ + // param the boost function that will be registered as a callback for a keyboard event + boost::signals2::connection + registerKeyboardCallback (boost::function ); + + void + emitMouseEvent (unsigned long event_id); + + void + emitKeyboardEvent (unsigned long event_id); + + // Callbacks used to register for vtk command + static void + MouseCallback (vtkObject*, unsigned long eid, void* clientdata, void *calldata); + static void + KeyboardCallback (vtkObject*, unsigned long eid, void* clientdata, void *calldata); + + protected: // types + struct ExitMainLoopTimerCallback : public vtkCommand + { + static ExitMainLoopTimerCallback* New () + { + return (new ExitMainLoopTimerCallback); + } + + ExitMainLoopTimerCallback (); + ExitMainLoopTimerCallback (const ExitMainLoopTimerCallback& src); + ExitMainLoopTimerCallback& operator = (const ExitMainLoopTimerCallback& src); + + virtual void + Execute (vtkObject*, unsigned long event_id, void* call_data); + + int right_timer_id; + Window* window; + }; + + struct ExitCallback : public vtkCommand + { + static ExitCallback* New () + { + return (new ExitCallback); + } + + ExitCallback (); + ExitCallback (const ExitCallback &src); + ExitCallback& operator = (const ExitCallback &src); + + virtual void + Execute (vtkObject*, unsigned long event_id, void*); + + Window* window; + }; + + bool stopped_; + int timer_id_; + + protected: // member fields + boost::signals2::signal mouse_signal_; + boost::signals2::signal keyboard_signal_; + + vtkSmartPointer win_; + vtkSmartPointer interactor_; + vtkCallbackCommand* mouse_command_; + vtkCallbackCommand* keyboard_command_; + /** \brief The render window interactor style. */ + vtkSmartPointer style_; + /** \brief The collection of renderers used. */ + vtkSmartPointer rens_; + vtkSmartPointer exit_main_loop_timer_callback_; + vtkSmartPointer exit_callback_; + }; + } +} + +#endif /* __WINDOW_H__ */ + diff --git a/utils/sample/000000.bin b/sample_data/000000.bin old mode 100755 new mode 100644 similarity index 100% rename from utils/sample/000000.bin rename to sample_data/000000.bin diff --git a/utils/sample/000001.bin b/sample_data/000001.bin old mode 100755 new mode 100644 similarity index 100% rename from utils/sample/000001.bin rename to sample_data/000001.bin diff --git a/sample_data/000002.bin b/sample_data/000002.bin new file mode 100644 index 0000000..c821667 Binary files /dev/null and b/sample_data/000002.bin differ diff --git a/sample_data/000003.bin b/sample_data/000003.bin new file mode 100644 index 0000000..3584c39 Binary files /dev/null and b/sample_data/000003.bin differ diff --git a/sample_data/000004.bin b/sample_data/000004.bin new file mode 100644 index 0000000..07bdf36 Binary files /dev/null and b/sample_data/000004.bin differ diff --git a/sample_data/000005.bin b/sample_data/000005.bin new file mode 100644 index 0000000..d91b6c9 Binary files /dev/null and b/sample_data/000005.bin differ diff --git a/src/modules.cpp b/src/modules.cpp new file mode 100644 index 0000000..95a791f --- /dev/null +++ b/src/modules.cpp @@ -0,0 +1,458 @@ +#include "typedefs.h" +#include "modules.h" +#include "utils.h" + +/**** + + ****/ +void filter(FeatureCloud &cloud) +{ + const PointCloud::Ptr filtered(new PointCloud); + int num = (cloud.getPointCloud())->size(); + pcl::StatisticalOutlierRemoval sor; + sor.setInputCloud(cloud.getPointCloud()); + sor.setMeanK(50); + sor.setStddevMulThresh(1.0); + sor.filter(*filtered); + cloud.setInputCloud(filtered); + + std::cout << "Outlier Filtering:" << std::endl; + std::cout << (num - filtered->size()) << " Points Are Filtered: " \ + << num << "->" << filtered->size() << std::endl << std::endl; +} + +/**** + + ****/ +void downSample(FeatureCloud &cloud, float gridsize) +{ + const PointCloud::Ptr filtered(new PointCloud); + pcl::VoxelGrid grid; + grid.setLeafSize(gridsize, gridsize, gridsize); + + std::cout << "Before Downsampling:" << \ + (cloud.getPointCloud())->size() << std::endl; + + grid.setInputCloud(cloud.getPointCloud()); + grid.filter(*filtered); + cloud.setInputCloud(filtered); + + std::cout << "After Downsampling: " << filtered->size() << std::endl; +} + +/**** + + ****/ +void keyPointsNARF(FeatureCloud &cloud) +{ + float angular_resolution = 0.5f; + float support_size = 0.2f; + + const PointCloud::Ptr keyPoints_NARF(new PointCloud); + + PointCloud &point_cloud = *cloud.getPointCloud(); + pcl::PointCloud far_ranges; + pcl::RangeImage::CoordinateFrame coordinate_frame = \ + pcl::RangeImage::CAMERA_FRAME; + Eigen::Affine3f scene_sensor_pose (Eigen::Affine3f::Identity ()); + + angular_resolution = pcl::deg2rad (angular_resolution); + scene_sensor_pose = Eigen::Affine3f (\ + Eigen::Translation3f (point_cloud.sensor_origin_[0], \ + point_cloud.sensor_origin_[1], \ + point_cloud.sensor_origin_[2])) * \ + Eigen::Affine3f (point_cloud.sensor_orientation_); + + // -----Create RangeImage from the PointCloud----- + float noise_level = 0.0; + float min_range = 0.0f; + int border_size = 1; + boost::shared_ptr range_image_ptr (new pcl::RangeImage); + + pcl::RangeImage& range_image = *range_image_ptr; + range_image.createFromPointCloud (point_cloud, angular_resolution, \ + pcl::deg2rad (360.0f), pcl::deg2rad (180.0f), \ + scene_sensor_pose, coordinate_frame, noise_level, min_range, border_size); + + range_image.integrateFarRanges (far_ranges); + + // -------------------------------- + // -----Extract NARF keypoints----- + // -------------------------------- + pcl::RangeImageBorderExtractor range_image_border_extractor; + pcl::NarfKeypoint narf_keypoint_detector (&range_image_border_extractor); + narf_keypoint_detector.setRangeImage (&range_image); + narf_keypoint_detector.getParameters ().support_size = support_size; + + pcl::PointCloud keypoint_indices; + narf_keypoint_detector.compute (keypoint_indices); + + PointCloud &keypoints = *keyPoints_NARF; + keypoints.points.resize (keypoint_indices.points.size ()); + + for (size_t i=0; i sift; + pcl::PointCloud result; + + pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); + sift.setSearchMethod(tree); + sift.setScales(min_scale, n_octaves, n_scales_per_octave); + sift.setMinimumContrast(min_contrast); + + sift.setInputCloud(cloud.getPointCloud()); + sift.compute(result); + copyPointCloud(result, *keyPoints_SIFT); + + cloud.setKeyPoints(keyPoints_SIFT); + + std::cout << result.points.size() << \ + " SIFT Key Points Are Detected." << std::endl << std::endl; +} + +/**** + + ****/ +void keyPointsHARRIS(FeatureCloud &cloud) +{ + const PointCloud::Ptr cloud_src = cloud.getPointCloud(); + const PointCloud::Ptr keyPoints_Harris_ptr(new PointCloud); + pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud); + pcl::HarrisKeypoint3D harris; + + harris.setInputCloud(cloud_src); + + // Filter only + harris.setRadius(0.35f);//0.5 + harris.setThreshold(0.01f);//0.02 + harris.setNonMaxSupression(true); + harris.setRefine(true); + + cloud_out->height = 1; + cloud_out->width = 100; + cloud_out->resize(cloud_out->height * cloud_src->width); + cloud_out->clear(); + harris.compute(*cloud_out); + int size = cloud_out->size(); + + keyPoints_Harris_ptr->height = 1; + keyPoints_Harris_ptr->width = 100; + keyPoints_Harris_ptr->resize(cloud_out->height*cloud_src->width); + keyPoints_Harris_ptr->clear(); + + pcl::PointXYZ point; + for (int i = 0; iat(i).x; + point.y = cloud_out->at(i).y; + point.z = cloud_out->at(i).z; + keyPoints_Harris_ptr->push_back(point); + } + + cloud.setKeyPoints(keyPoints_Harris_ptr); + + std::cout << keyPoints_Harris_ptr->size() << \ + " HARRIS Key Points Are Detected." << std::endl << std::endl; +} + +/**** + + ****/ +void constructPointNormal(FeatureCloud &source_cloud, FeatureCloud &target_cloud) +{ + PointCloudNormal::Ptr pointNormal_src (new PointCloudNormal); + PointCloudNormal::Ptr pointNormal_tgt (new PointCloudNormal); + + // NOTICE: we need the transformed point cloud here. + PointCloud::Ptr src_cloud = source_cloud.getTransformedCloud (); + SurfaceNormals::Ptr src_normal = source_cloud.getSurfaceNormals (); + + for(size_t i = 0; i < src_cloud->points.size(); ++i) + { + PointNormal pt_normal; + + pt_normal.x = src_cloud->points[i].x; + pt_normal.y = src_cloud->points[i].y; + pt_normal.z = src_cloud->points[i].z; + + pt_normal.normal_x = src_normal->points[i].normal_x; + pt_normal.normal_y = src_normal->points[i].normal_y; + pt_normal.normal_z = src_normal->points[i].normal_z; + + pointNormal_src->push_back(pt_normal); + } + source_cloud.setPointCloudNormal(pointNormal_src); + + // tgt + PointCloud::Ptr tgt_cloud = target_cloud.getPointCloud (); + SurfaceNormals::Ptr tgt_normal = target_cloud.getSurfaceNormals (); + + for(size_t i = 0; i < tgt_cloud->points.size(); ++i) + { + PointNormal pt_normal; + + pt_normal.x = tgt_cloud->points[i].x; + pt_normal.y = tgt_cloud->points[i].y; + pt_normal.z = tgt_cloud->points[i].z; + + pt_normal.normal_x = tgt_normal->points[i].normal_x; + pt_normal.normal_y = tgt_normal->points[i].normal_y; + pt_normal.normal_z = tgt_normal->points[i].normal_z; + + pointNormal_tgt->push_back(pt_normal); + } + target_cloud.setPointCloudNormal(pointNormal_tgt); +} + +/**** + + ****/ +void computeSurfaceNormals (FeatureCloud &cloud, std::vector &LF_points_counter, \ + std::vector &LF_operations_counter) +{ + SurfaceNormals::Ptr normals_ (new SurfaceNormals); + + pcl::NormalEstimation norm_est; + + norm_est.setInputCloud (cloud.getPointCloud()); + // norm_est.setIndices(cloud.getKeyPoint_indices()); + + pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); + norm_est.setSearchMethod(tree); + norm_est.setRadiusSearch(g_NORMAL_SEARCH_RADIUS); + + norm_est.setUseCustomizedKDTree(g_NORMAL_USE_CUSTOMIZED_KDTREE); + norm_est.setMaxLeafSize(g_NORMAL_MAX_LEAF_SIZE); + norm_est.setApproxRadiusPara(g_APPROX_RADIUS_SEARCH_PARA); + + norm_est.setSaveApproxData(g_SAVE_APPROX_DATA); + + norm_est.compute (*normals_); + + cloud.setSurfaceNormals(normals_); + removeNANFromNormal(cloud); + + // record leader and follower points number + LF_points_counter.push_back(norm_est.getApproxLeadersNum()); + LF_points_counter.push_back(norm_est.getApproxFollowersNum()); + LF_points_counter.push_back(norm_est.getApproxLeadersNum() + norm_est.getApproxFollowersNum()); + LF_operations_counter.push_back(norm_est.getApproxRadiusOpsNum()); +} + +/**** + + ****/ +void computeFeatures_FPFH (FeatureCloud &cloud, float R) +{ + FPFH_Features::Ptr fpfh_features_ (new FPFH_Features); + FPFH_Features::Ptr nanremoved_(new FPFH_Features); + + pcl::FPFHEstimation fpfh_est; + fpfh_est.setSearchSurface (cloud.getPointCloud()); + fpfh_est.setInputNormals (cloud.getSurfaceNormals()); + fpfh_est.setInputCloud (cloud.getKeyPoints()); + + pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); + + fpfh_est.setSearchMethod(tree); + fpfh_est.setRadiusSearch(R); + + fpfh_est.compute (*fpfh_features_); + + removeNANFromFPFH(fpfh_features_, nanremoved_, cloud); + + cloud.setFeatures_FPFH(nanremoved_); +} + +/**** + + ****/ + void computeFeatures_SHOT (FeatureCloud &cloud, float R) + { + SHOT_Features::Ptr shot_features_(new SHOT_Features); + SHOT_Features::Ptr nanremoved_(new SHOT_Features); + pcl::SHOTEstimation shot_est; + shot_est.setSearchSurface(cloud.getPointCloud()); + shot_est.setInputNormals(cloud.getSurfaceNormals()); + shot_est.setInputCloud(cloud.getKeyPoints()); + pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); + + shot_est.setSearchMethod(tree); + shot_est.setRadiusSearch(R); //0.5 + + shot_est.compute(*shot_features_); + + removeNANFromDescriptor(shot_features_, nanremoved_, cloud); + + cloud.setFeatures_SHOT(nanremoved_); +} + +void estimateCorrespondence(FeatureCloud &source_cloud, FeatureCloud &target_cloud, \ + pcl::Correspondences &all_corres) +{ + if (g_FEATURE_MODULE == "FPFH") + { + pcl::registration::CorrespondenceEstimation est; + est.setInputSource (source_cloud.getFeatures_FPFH()); + est.setInputTarget (target_cloud.getFeatures_FPFH()); + + if(g_CORR_EST_USE_RECIPROCAL_SEARCH) + est.determineReciprocalCorrespondences (all_corres); + } + + if (g_FEATURE_MODULE == "SHOT") + { + pcl::registration::CorrespondenceEstimation est; + est.setInputSource (source_cloud.getFeatures_SHOT()); + est.setInputTarget (target_cloud.getFeatures_SHOT()); + + if(g_CORR_EST_USE_RECIPROCAL_SEARCH) + est.determineReciprocalCorrespondences (all_corres); + } +} + +/**** + + ****/ +void rejectCorrespondences(FeatureCloud &source_cloud, \ + FeatureCloud &target_cloud, pcl::Correspondences &correspondences, \ + pcl::Correspondences &inliers, Result *result) +{ + + pcl::registration::CorrespondenceRejectorSampleConsensus sac; + sac.setInputSource(source_cloud.getKeyPoints ()); + sac.setInputTarget(target_cloud.getKeyPoints ()); + + // sac.setInputSource(source_cloud.getPointCloud ()); + // sac.setInputTarget(target_cloud.getPointCloud ()); + + // Set the threshold for rejection iteration + sac.setInlierThreshold(g_RANSAC_THRESHOLD); + sac.setMaximumIterations(g_RANSAC_MAX_ITERATION); + sac.getRemainingCorrespondences(correspondences, inliers); + + Eigen::Matrix4f transformation = sac.getBestTransformation(); + + result->final_transformation = transformation; + + printMatrix("RANSAC", transformation); + + PointCloud::Ptr transformed_cloud (new PointCloud); + + pcl::transformPointCloud (*(source_cloud.getPointCloud ()), \ + *transformed_cloud, transformation); + source_cloud.setTransformedCloud(transformed_cloud); + + std::cout << "Correspondences Rejection:" << std::endl; + std::cout << (correspondences.size() - inliers.size()) << \ + " Correspondences Are Rejected: " << correspondences.size() << "->" << \ + inliers.size() << std::endl << std::endl; +} + +/**** + + ****/ +void iterativeClosestPoints(FeatureCloud &source_cloud, FeatureCloud &target_cloud,\ + Result *result, pcl::Correspondences &inliers, std::vector &LF_points_counter, std::vector &LF_operations_counter) +{ + PointCloudNormal Final; + + PointCloudNormal::Ptr pointNormal_src = source_cloud.getPointCloudNormal(); + PointCloudNormal::Ptr pointNormal_tgt = target_cloud.getPointCloudNormal(); + + pcl::registration::CorrespondenceRejector::Ptr ransac_rej \ + (new pcl::registration::CorrespondenceRejectorSampleConsensus ()); + + if(g_ICP_SOLVER == "SVD") + { + std::cout << "SVD Solver for ICP Is Running!" << std::endl; + pcl::IterativeClosestPoint icp; + + if (g_ICP_USE_RECIPROCAL_SEARCH) + icp.setUseReciprocalCorrespondences(true); + if (g_ICP_USE_RANSAC) + { + icp.setRANSACOutlierRejectionThreshold (g_ICP_RANSAC_OUTLIER_REJECTION_THRESHOLD); + icp.addCorrespondenceRejector(ransac_rej); + } + + icp.setInputSource(pointNormal_src); + icp.setInputTarget(pointNormal_tgt); + + icp.setUseCustomizedKDTree(g_ICP_USE_CUSTOMIZED_KDTREE); + icp.setMaxLeafSize(g_ICP_MAX_LEAF_SIZE); + icp.setApproxNNPara(g_APPROX_NEAREST_SEARCH_PARA); + + icp.setMaximumIterations (g_ICP_MAX_ITERATION); + icp.setTransformationEpsilon (g_ICP_TRANSFORMATION_EPSILON); + icp.setMaxCorrespondenceDistance (g_ICP_MAX_CORRESPONDENCE_DISTANCE); + icp.setEuclideanFitnessEpsilon (g_ICP_EUCLIDEAN_FITNESS_EPSILON); + + icp.setSaveApproxData(g_SAVE_APPROX_DATA); + + icp.align(Final); + + result->final_transformation = icp.getFinalTransformation(); + // result->fitness_score = icp.getFitnessScore(); + + std::cout << "ICP Iteration Number: " << icp.getIterNumber() << std::endl; + + LF_points_counter.push_back(icp.getApproxLeadersNum()); + LF_points_counter.push_back(icp.getApproxFollowersNum()); + LF_points_counter.push_back(icp.getApproxLeadersNum() + icp.getApproxFollowersNum()); + LF_operations_counter.push_back(icp.getApproxNNOpsNum()); + + } + if (g_ICP_SOLVER == "LM") + { + std::cout << "LM Solver for ICP Is Running!" << std::endl; + pcl::IterativeClosestPointNonLinear icp_lm; + + if (g_ICP_USE_RECIPROCAL_SEARCH) + icp_lm.setUseReciprocalCorrespondences(true); + if (g_ICP_USE_RANSAC) + { + icp_lm.setRANSACOutlierRejectionThreshold (g_ICP_RANSAC_OUTLIER_REJECTION_THRESHOLD); + // add ransac rejector + icp_lm.addCorrespondenceRejector(ransac_rej); + } + + icp_lm.setInputSource(pointNormal_src); + icp_lm.setInputTarget(pointNormal_tgt); + + icp_lm.setMaximumIterations(g_ICP_MAX_ITERATION); + icp_lm.setTransformationEpsilon(g_ICP_TRANSFORMATION_EPSILON); + icp_lm.setMaxCorrespondenceDistance(g_ICP_MAX_CORRESPONDENCE_DISTANCE); + icp_lm.setEuclideanFitnessEpsilon (g_ICP_EUCLIDEAN_FITNESS_EPSILON); + + icp_lm.align(Final); + + result->final_transformation = icp_lm.getFinalTransformation(); + // result->fitness_score = icp_lm.getFitnessScore(); + } +} diff --git a/src/pc-registration.cpp b/src/pc-registration.cpp deleted file mode 100755 index 2cb785c..0000000 --- a/src/pc-registration.cpp +++ /dev/null @@ -1,416 +0,0 @@ -#include "typedefs.h" -#include "utils.h" - -int main(int argc, char **argv) -{ - std::vector arguments(argv, argv + argc); - - // int normal_K = std::stoi(arguments[1]); - // int FPFH_K = std::stoi(arguments[2]); - float normal_R = std::stof(arguments[1]); - float descriptor_R = std::stof(arguments[2]); - float ransac_threshold = std::stof(arguments[3]); - float icp_transEps = std::stof(arguments[4]); - float icp_corresDist = std::stof(arguments[5]); - float icp_EuclFitEps = std::stof(arguments[6]); - float icp_outlThresh = std::stof(arguments[7]); - const char * out_file2 = argv[8]; - const char * stage_time_file = argv[9]; - const char * dataset_dir = argv[10]; - const char * ransac_delta_file = argv[11]; - const char * icp_delta_file = argv[12]; - const char * kdtree_time_file = argv[22]; - - int use_keypoints = std::stoi(arguments[13]); - // 1: keypoints, 0: all points - - std::string kernel_keyPoints = argv[14]; - std::string kernel_descriptors = argv[15]; - std::string kernel_corrEst = argv[16]; - std::string kernel_corrRej = argv[17]; - std::string corrEst_flag_reciprocal = argv[18]; - std::string icp_solver = argv[19]; - std::string icp_flag_ransac = argv[20]; - std::string icp_flag_reciprocal = argv[21]; -/* - std::cout << "normal_R: " << normal_R << std::endl; - std::cout << "descriptor_R: " << descriptor_R << std::endl; - std::cout << "ransac_threshold: " << ransac_threshold << std::endl; - std::cout << "icp_transEps: " << icp_transEps << std::endl; - std::cout << "icp_corresDist: " << icp_corresDist << std::endl; - std::cout << "icp_EuclFitEps: " << icp_EuclFitEps << std::endl; - std::cout << "icp_outlThresh: " << icp_outlThresh << std::endl; - std::cout << "kernel_keyPoints: " << kernel_keyPoints << std::endl; - std::cout << "kernel_descriptors: " << kernel_descriptors << std::endl; - std::cout << "corrEst_flag_reciprocal: " << corrEst_flag_reciprocal << std::endl; - std::cout << "icp_solver: " << icp_solver << std::endl; - std::cout << "icp_flag_ransac: " << icp_flag_ransac << std::endl; - std::cout << "icp_flag_reciprocal: " << icp_flag_reciprocal << std::endl; - std::cout << std::endl; - std::cout << "result files:" << std::endl; - std::cout << out_file2 << std::endl; - std::cout << ransac_delta_file << std::endl; - std::cout << icp_delta_file << std::endl; - std::cout << stage_time_file << std::endl; - std::cout << kdtree_time_file << std::endl; - std::cout << std::endl; -*/ - - std::vector path2bins; - std::queue clouds; - - std::vector single_stage_time; - std::vector stage_kdtree_time; - - struct timespec start, finish; - double elapsed_secs; - - float nn_time, bd_time; - nn_time = 0.0; - bd_time = 0.0; - - Eigen::Matrix4f final_result_kitti = Eigen::Matrix4f::Identity(); - - int index_start = 0; - - // Start loading frame 0 - FeatureCloud cloud_; - listdir(dataset_dir, path2bins); - // the path2bins contains frames (.bin) in a sorted order. - load_bin(path2bins[index_start], cloud_); - clouds.push(cloud_); - - PointCloud::Ptr cloud_ptr = (clouds.front()).getPointCloud(); - PointCloud::Ptr keyPoints_ptr(new PointCloud); - PointCloud::Ptr keyPoints_cal_ptr(new PointCloud); - pcl::PointIndices::Ptr indices_ptr (new pcl::PointIndices); - - filter(cloud_ptr, cloud_ptr, nn_time, bd_time); - // downSample(cloud_ptr, cloud_ptr, 0.1); - - // Normal Calculation - computeSurfaceNormals (clouds.front(), normal_R, nn_time, bd_time); - pointsNumberCheck (clouds.front()); // remove NAN - - // Keypoints Detection - detectKeyPoints(kernel_keyPoints, cloud_ptr, keyPoints_cal_ptr); - - // Calculate the indices of keypoints - getIndices(cloud_ptr, keyPoints_cal_ptr, keyPoints_ptr, indices_ptr); - (clouds.front()).setKeyPoints(keyPoints_ptr); - (clouds.front()).setKeyPoint_indices(indices_ptr); - - // Feature Descriptor Calculation - describeFeatures(kernel_descriptors, clouds.front(), descriptor_R, nn_time, bd_time); - - std::ofstream myfile_kitti; - myfile_kitti.open (out_file2, std::fstream::app); - std::cout << "writing to " << out_file2 << std::endl; - - // write the matrix into the pose file. - for(int i = 0; i < 3; i ++) - { - for(int j = 0; j < 4; j ++) - { - myfile_kitti << ("%lf", final_result_kitti(i,j)); - if (j != 4) - myfile_kitti << " "; - } - } - myfile_kitti << "\n"; - myfile_kitti.close(); - - for (int n=(index_start + 1); n < path2bins.size(); n++) - { - - nn_time = 0.0; - bd_time = 0.0; - - FeatureCloud cloud_; - - clock_gettime(CLOCK_MONOTONIC, &start); - - load_bin(path2bins[n], cloud_); - - clock_gettime(CLOCK_MONOTONIC, &finish); - elapsed_secs = (finish.tv_sec - start.tv_sec); - elapsed_secs += (finish.tv_nsec - start.tv_nsec) / 1000000000.0; - - clouds.push(cloud_); - if (!(n == (index_start + 1))) - clouds.pop(); - - PCL_ERROR("T loading: %f\n\n", elapsed_secs); - single_stage_time.push_back(elapsed_secs); - //0: loading time - - PointCloud::Ptr cloud_ptr = (clouds.back()).getPointCloud(); - PointCloud::Ptr keyPoints_cal_ptr(new PointCloud); - PointCloud::Ptr keyPoints_ptr(new PointCloud); - pcl::PointIndices::Ptr indices_ (new pcl::PointIndices); - - clock_gettime(CLOCK_MONOTONIC, &start); - - filter(cloud_ptr, cloud_ptr, nn_time, bd_time); - - clock_gettime(CLOCK_MONOTONIC, &finish); - elapsed_secs = (finish.tv_sec - start.tv_sec); - elapsed_secs += (finish.tv_nsec - start.tv_nsec) / 1000000000.0; - - PCL_ERROR("T Filter: %f\n\n", elapsed_secs); - PCL_ERROR("Search: %f\n", nn_time); - PCL_ERROR("Build: %f\n", bd_time); - stage_kdtree_time.push_back(nn_time); - stage_kdtree_time.push_back(bd_time); - single_stage_time.push_back(elapsed_secs); - // 1: filter time - nn_time = 0.0; - bd_time = 0.0; - std::cout << std::endl; - - // Normal - clock_gettime(CLOCK_MONOTONIC, &start); - - computeSurfaceNormals (clouds.back(), normal_R, nn_time, bd_time); - - clock_gettime(CLOCK_MONOTONIC, &finish); - elapsed_secs = (finish.tv_sec - start.tv_sec); - elapsed_secs += (finish.tv_nsec - start.tv_nsec) / 1000000000.0; - - PCL_ERROR("T Normal: %f\n\n", elapsed_secs); - PCL_ERROR("Search: %f\n", nn_time); - PCL_ERROR("Build: %f\n", bd_time); - stage_kdtree_time.push_back(nn_time); - stage_kdtree_time.push_back(bd_time); - single_stage_time.push_back(elapsed_secs); - // 2: Normal calc time - nn_time = 0.0; - bd_time = 0.0; - std::cout << std::endl; - - pointsNumberCheck (clouds.back()); - - // Keypoints Detection - clock_gettime(CLOCK_MONOTONIC, &start); - - detectKeyPoints(kernel_keyPoints, cloud_ptr, keyPoints_cal_ptr); - - clock_gettime(CLOCK_MONOTONIC, &finish); - elapsed_secs = (finish.tv_sec - start.tv_sec); - elapsed_secs += (finish.tv_nsec - start.tv_nsec) / 1000000000.0; - PCL_ERROR("T Keypoint Detection: %f\n\n", elapsed_secs); - single_stage_time.push_back(elapsed_secs); - // #: Keypoint detection time - - getIndices(cloud_ptr, keyPoints_cal_ptr, keyPoints_ptr, indices_); - (clouds.back()).setKeyPoints(keyPoints_ptr); - (clouds.back()).setKeyPoint_indices(indices_); - - // Feature Descriptor - clock_gettime(CLOCK_MONOTONIC, &start); - - describeFeatures(kernel_descriptors, clouds.back(), descriptor_R, \ - nn_time, bd_time); - - clock_gettime(CLOCK_MONOTONIC, &finish); - elapsed_secs = (finish.tv_sec - start.tv_sec); - elapsed_secs += (finish.tv_nsec - start.tv_nsec) / 1000000000.0; - PCL_ERROR("T Feature Descriptor: %f\n", elapsed_secs); - PCL_ERROR("Search: %f\n", nn_time); - PCL_ERROR("Build: %f\n", bd_time); - stage_kdtree_time.push_back(nn_time); - stage_kdtree_time.push_back(bd_time); - single_stage_time.push_back(elapsed_secs); - // 4: Feature Descriptor Calc time - nn_time = 0.0; - bd_time = 0.0; - std::cout << std::endl; - - // Correspondence Estimation - Correspondences all_correspondences; - Correspondences inliers; - - clock_gettime(CLOCK_MONOTONIC, &start); - - // (back, front): (source, target) - correspondence_estimation(kernel_descriptors, corrEst_flag_reciprocal,\ - (clouds.back()), (clouds.front()), all_correspondences, nn_time, bd_time); - - clock_gettime(CLOCK_MONOTONIC, &finish); - elapsed_secs = (finish.tv_sec - start.tv_sec); - elapsed_secs += (finish.tv_nsec - start.tv_nsec) / 1000000000.0; - PCL_ERROR("T Correspondence Est: %f\n", elapsed_secs); - PCL_ERROR("Search: %f\n", nn_time); - PCL_ERROR("Build: %f\n", bd_time); - stage_kdtree_time.push_back(nn_time); - stage_kdtree_time.push_back(bd_time); - single_stage_time.push_back(elapsed_secs); - // 5: Correspondence Est time - nn_time = 0.0; - bd_time = 0.0; - std::cout << std::endl; - - // Corres Rejection - Result* init_result_ptr, init_result; - init_result_ptr = &init_result; - - clock_gettime(CLOCK_MONOTONIC, &start); - correspondences_rejection((clouds.back()), (clouds.front()), \ - all_correspondences, inliers, init_result_ptr, 1000, \ - ransac_threshold, use_keypoints); // (source, target) - - clock_gettime(CLOCK_MONOTONIC, &finish); - elapsed_secs = (finish.tv_sec - start.tv_sec); - elapsed_secs += (finish.tv_nsec - start.tv_nsec) / 1000000000.0; - - PCL_ERROR("T Coores Rej: %f\n\n", elapsed_secs); - single_stage_time.push_back(elapsed_secs); - // 6: Corres Rej time - - /* Constructing PointNormal type */ - // Here the time consumption is not counted - construct_PointNormal(clouds.back(), clouds.front(), use_keypoints); - - // ICP - Result* icp_result_ptr, icp_result; - icp_result_ptr = &icp_result; - - clock_gettime(CLOCK_MONOTONIC, &start); - - iterative_closest_points(icp_solver, icp_flag_reciprocal, icp_flag_ransac, (clouds.back()), (clouds.front()), \ - icp_result_ptr, icp_transEps, icp_corresDist, \ - icp_EuclFitEps, icp_outlThresh, use_keypoints, inliers, \ - nn_time, bd_time); - - clock_gettime(CLOCK_MONOTONIC, &finish); - elapsed_secs = (finish.tv_sec - start.tv_sec); - elapsed_secs += (finish.tv_nsec - start.tv_nsec) / 1000000000.0; - PCL_ERROR("T ICP: %f\n\n", elapsed_secs); - PCL_ERROR("Search: %f\n", nn_time); - PCL_ERROR("Build: %f\n", bd_time); - stage_kdtree_time.push_back(nn_time); - stage_kdtree_time.push_back(bd_time); - single_stage_time.push_back(elapsed_secs); - // 7: ICP time - nn_time = 0.0; - bd_time = 0.0; - std::cout << std::endl; - - /* Dump the results / profiling data */ - - Eigen::Matrix4f final_result = icp_result_ptr->final_transformation * \ - init_result_ptr->final_transformation; - - final_result_kitti = final_result_kitti * final_result; - - // save stage time records - std::ofstream timefile; - timefile.open (stage_time_file, std::fstream::app); - - for(int i = 0; i < single_stage_time.size(); i ++) - { - timefile << ("%lf", single_stage_time[i]); - if (i != 7) - timefile << " "; - } - timefile << "\n"; - timefile.close(); - single_stage_time.clear(); - - // kdtree time (stages) - std::ofstream kdtree_time; - kdtree_time.open(kdtree_time_file, std::fstream::app); - for(int i = 0; i < stage_kdtree_time.size(); i ++) - { - kdtree_time << ("%lf", stage_kdtree_time[i]); - kdtree_time << " "; - } - kdtree_time << "\n"; - kdtree_time.close(); - stage_kdtree_time.clear(); - - // Results - std::cout << "ICP:" << std::endl; - for(int i = 0; i < 3; i ++) - { - for(int j = 0; j < 4; j ++) - { - std::cout << ("%lf", icp_result_ptr->final_transformation(i,j)); - if (j != 4) - std::cout << " "; - } - std::cout << std::endl; - } - std::cout << std::endl; - - std::cout << "Final:" << std::endl; - for(int i = 0; i < 3; i ++) - { - for(int j = 0; j < 4; j ++) - { - std::cout << ("%lf", final_result(i,j)); - if (j != 4) - std::cout << " "; - } - std::cout << std::endl; - } - std::cout << std::endl; - - /* ransac delta */ - std::ofstream myfile_ransac; - myfile_ransac.open (ransac_delta_file, std::fstream::app); - - std::cout << "writing to " << ransac_delta_file << std::endl; - - for(int i = 0; i < 3; i ++) - { - for(int j = 0; j < 4; j ++) - { - myfile_ransac << ("%lf", init_result_ptr->final_transformation(i,j)); - if (j != 4) - myfile_ransac << " "; - } - } - myfile_ransac << "\n"; - myfile_ransac.close(); - - /* ransac delta */ - std::ofstream myfile_icp; - myfile_icp.open (icp_delta_file, std::fstream::app); - std::cout << "writing to " << icp_delta_file << std::endl; - - for(int i = 0; i < 3; i ++) - { - for(int j = 0; j < 4; j ++) - { - myfile_icp << ("%lf", icp_result_ptr->final_transformation(i,j)); - if (j != 4) - myfile_icp << " "; - } - } - myfile_icp << "\n"; - myfile_icp.close(); - - - /* Accumulated result*/ - std::ofstream myfile_kitti; - myfile_kitti.open (out_file2, std::fstream::app); - std::cout << "writing to " << out_file2 << std::endl; - - // write the matrix into the pose file. - for(int i = 0; i < 3; i ++) - { - for(int j = 0; j < 4; j ++) - { - myfile_kitti << ("%lf", final_result_kitti(i,j)); - if (j != 4) - myfile_kitti << " "; - } - } - - myfile_kitti << "\n"; - myfile_kitti.close(); - - } - return 0; -} \ No newline at end of file diff --git a/src/pc_pipeline.cpp b/src/pc_pipeline.cpp new file mode 100755 index 0000000..f03f3ba --- /dev/null +++ b/src/pc_pipeline.cpp @@ -0,0 +1,122 @@ +#include "typedefs.h" +#include "utils.h" +#include "modules.h" + + +int main(int argc, char **argv) +{ + std::string file_name = "config.txt"; + + readConfigFile(file_name); + makeResultFolder(g_RESULT_DIR); + + // ---------------------------------------------------------generate file's datapath + std::string file_final_pose_matrix = g_RESULT_DIR + "pose_result_kitti.txt"; + std::string file_Ransac_delta_matrix = g_RESULT_DIR + "ransac_delta.txt"; + std::string file_ICP_delta_matrix = g_RESULT_DIR + "icp_delta.txt"; + std::string file_approx_ops_counter = g_RESULT_DIR + "approx_search_ops.txt"; + std::string file_approx_lf_counter = g_RESULT_DIR + "leader_follower_num.txt"; + + // ---------------------------------------------------------define variables + int index_start = 0; + std::queue clouds; + std::vector path2bins; + std::vector approx_lf_counter; + std::vector approx_ops_counter; + + // initialized identity matrix + Eigen::Matrix4f final_result_kitti = Eigen::Matrix4f::Identity(); + // matrix + std::ofstream stream_icp_matrix; + std::ofstream stream_ransac_matrix; + std::ofstream stream_final_pose_matrix; + // vector + std::ofstream stream_approx_lf; + std::ofstream stream_approx_ops; + + // generate data loading path at path2bins + listDir(g_DATASET_DIR, path2bins); + // Initial matrix for KITTI pose result + writeMatrix(stream_final_pose_matrix, file_final_pose_matrix, final_result_kitti); + + for (int n = index_start; n < path2bins.size(); n++) + { + FeatureCloud cloud_; + + // --------------Stage1: Loading Frame-------------- + loadBINFile(path2bins[n], cloud_); + // loadTXTFile(path2bins[n], cloud_); + + if (!(n == index_start) && !(n == (index_start + 1))) + clouds.pop(); + clouds.push(cloud_); + + // --------------Stage2: Preprocessing-------------- + filter(clouds.back()); + // downSample(clouds.back(), 0.1); + + // --------------Stage3: Normal Calculation-------------- + computeSurfaceNormals (clouds.back(), approx_lf_counter, approx_ops_counter); + + // --------------Stage4: Key Points Detection-------------- + detectKeyPoints(clouds.back()); + + // --------------Stage5: Feature Description-------------- + describeFeatures(clouds.back()); + + + if (n == index_start) // continue to load 2nd frame + { + approx_lf_counter.clear(); + approx_ops_counter.clear(); + continue; + } + + // -------------Stage6: Correspondence Estimation-------------- + Correspondences all_correspondences; + Correspondences inliers; + + estimateCorrespondence((clouds.back()), (clouds.front()), all_correspondences); // (source, target) + + // ------------Stage7: Corresponence Rejection-------------- + Result* init_result_ptr, init_result; + init_result_ptr = &init_result; + + rejectCorrespondences((clouds.back()), (clouds.front()), \ + all_correspondences, inliers, init_result_ptr); // (source, target) + + /** Constructing PointNormal **/ + constructPointNormal(clouds.back(), clouds.front()); + + // -----------Stage8: Pose Estimation (ICP)-------------- + Result* icp_result_ptr, icp_result; + icp_result_ptr = &icp_result; + + iterativeClosestPoints((clouds.back()), (clouds.front()), icp_result_ptr,\ + inliers, approx_lf_counter, approx_ops_counter); + + Eigen::Matrix4f final_result = icp_result_ptr->final_transformation * init_result_ptr->final_transformation; + final_result_kitti = final_result_kitti * final_result; + + + // ---------------------------------------------------------Stage9: Record Results + printMatrix("ICP", icp_result_ptr->final_transformation); + printMatrix("Final Pose", final_result_kitti); + + // Leader follower points counter + writeVector(stream_approx_lf, file_approx_lf_counter, approx_lf_counter); + + // Leader follower operations counter + writeVector(stream_approx_ops, file_approx_ops_counter, approx_ops_counter); + + /* Ransac delta */ + writeMatrix(stream_ransac_matrix, file_Ransac_delta_matrix, init_result_ptr->final_transformation); + + /* ICP delta */ + writeMatrix(stream_icp_matrix, file_ICP_delta_matrix, icp_result_ptr->final_transformation); + + /* Accumulated result*/ + writeMatrix(stream_final_pose_matrix, file_final_pose_matrix, final_result_kitti); + } + return 0; +} diff --git a/src/read_config.cpp b/src/read_config.cpp new file mode 100644 index 0000000..38ded8d --- /dev/null +++ b/src/read_config.cpp @@ -0,0 +1,51 @@ +#include "read_config.h" + +Config::Config(std::string filename, std::string delimiter, std::string comment) \ + :m_Delimiter(delimiter), m_Comment(comment) +{ + std::ifstream in (filename.c_str()); + + if (!in) + throw File_Not_Found(filename); + + in >> (*this); +} + +// remove leading and trailing white space +void Config::Trim(std::string &inout_s) +{ + const char white_space[] = "\n\t\v\r\f"; + inout_s.erase(0, inout_s.find_first_not_of(white_space)); + inout_s.erase(inout_s.find_last_not_of(white_space) + 1U); +} + +std::istream &operator>>(std::istream &is, Config &cf) +{ + typedef std::string::size_type pos; + const std::string &delim = cf.m_Delimiter; + const std::string &comm = cf.m_Comment; + const pos skip = delim.length(); + + std::string line; + + while (std::getline(is, line)) + { + // ignore comments + line = line.substr(0, line.find(comm)); + + pos delimPos = line.find(delim); + // find a delimiter before termination of string + if (delimPos < std::string::npos) + { + // extract key + std::string key = line.substr(0, delimPos); + line.replace(0, delimPos + skip, ""); + + Config::Trim(key); + Config::Trim(line); + + cf.m_Contents[key] = line; + } + } + return is; +} \ No newline at end of file diff --git a/src/utils.cpp b/src/utils.cpp index 10631d4..df91680 100755 --- a/src/utils.cpp +++ b/src/utils.cpp @@ -1,333 +1,158 @@ #include "typedefs.h" #include "utils.h" +#include "modules.h" +#include "read_config.h" -void filter(const PointCloud::Ptr cloud_src, \ - const PointCloud::Ptr filtered, float &nn_time, float &bd_time) -{ - int num = cloud_src->size(); - pcl::StatisticalOutlierRemoval sor; - sor.setInputCloud(cloud_src); - sor.setMeanK(50); - sor.setStddevMulThresh(1.0); - sor.filter(*filtered); - - // sor.getNnTime(nn_time); - // sor.getBuildTime(bd_time); - // std::cout << "Outlier Filtering:" << std::endl; - // std::cout << (num - filtered->size()) << " Points Are Filtered: " \ - // << num << "->" << filtered->size() << std::endl << std::endl; -} +/** global variable definition**/ +std::string g_DATASET_DIR; // Dataset directory +std::string g_RESULT_DIR; // Result directory -void downSample(const PointCloud::Ptr cloud_src, \ - const PointCloud::Ptr filtered, float gridsize) -{ - pcl::VoxelGrid grid; //VoxelGrid - grid.setLeafSize(gridsize, gridsize, gridsize); - std::cout << "Before Downsampling:" << cloud_src->size() << std::endl; - grid.setInputCloud(cloud_src); - grid.filter(*filtered); - std::cout << "After Downsampling: " << filtered->size() << std::endl; -} +// Normal Estimation Parameters +float g_NORMAL_SEARCH_RADIUS; +bool g_NORMAL_USE_CUSTOMIZED_KDTREE; +int g_NORMAL_MAX_LEAF_SIZE; -void detectKeyPoints(std::string kernel_keyPoints, const PointCloud::Ptr cloud_ptr, const PointCloud::Ptr keyPoints_cal_ptr) -{ - if (kernel_keyPoints == "NARF") - { - std::cout << "NARF Keypoints Are Being Detected!" << std::endl; - keyPointsNARF(cloud_ptr, keyPoints_cal_ptr); - } - if (kernel_keyPoints == "SIFT") - { - std::cout << "SIFT Keypoints Are Being Detected!" << std::endl; - keyPointsSIFT(cloud_ptr, keyPoints_cal_ptr); - } - if (kernel_keyPoints == "HARRIS") - { - std::cout << "HARRIS Keypoints Are Being Detected!" << std::endl; - keyPointsHARRIS(cloud_ptr, keyPoints_cal_ptr); - } -/* if (kernel_keyPoints == "LOAM") - { - std::cout << "LOAM Keypoints Are Being Detected!" << std::endl; - keyPointsLOAM(cloud_ptr, keyPoints_cal_ptr); - }*/ -} +// Key Point Detection Parameters +std::string g_KEYPOINTS_MODULE; -void describeFeatures(std::string kernel_descriptors, FeatureCloud &cloud, float R, \ - float &nn_time, float &bd_time) -{ - if (kernel_descriptors == "FPFH") - { - std::cout << "FPFH Descriptors Are Being Detected!" << std::endl; - computeFeatures_FPFH (cloud, R, nn_time, bd_time); - } - if (kernel_descriptors == "VFH") - { - std::cout << "VFH Descriptors Are Being Detected!" << std::endl; - computeFeatures_VFH (cloud, R); - } - if (kernel_descriptors == "SpinImage") - { - std::cout << "SpinImage Descriptors Are Being Detected!" << std::endl; - computeFeatures_SpinImage (cloud, R); - } - if (kernel_descriptors == "3DSC") - { - std::cout << "3DSC Descriptors Are Being Detected!" << std::endl; - computeFeatures_3DSC (cloud, R, nn_time, bd_time); - } - // if (kernel_descriptors == "USC") - // { - // std::cout << "USC Descriptors Are Being Detected!" << std::endl; - // computeFeatures_USC (cloud, R); - // } - if (kernel_descriptors == "SHOT") - { - std::cout << "SHOT Descriptors Are Being Detected!" << std::endl; - computeFeatures_SHOT (cloud, R, nn_time, bd_time); - } - // if (kernel_descriptors == "RSD") - // { - // std::cout << "RSD Descriptors Are Being Detected!" << std::endl; - // computeFeatures_RSD (cloud, R); - // } -} +// Feature Description Parameters +float g_FEATURE_SEARCH_RADIUS; +std::string g_FEATURE_MODULE; -void pointsNumberCheck(FeatureCloud &cloud) -{ - PointCloud::Ptr nanremoved_(new PointCloud); - PointCloud::Ptr cloud_ = cloud.getPointCloud(); - SurfaceNormals::Ptr normals_ = cloud.getSurfaceNormals(); - std::vector index; +// Correspondence Estimation Parameters +bool g_CORR_EST_USE_RECIPROCAL_SEARCH; - int num_point = cloud_->size(); - int num_normal = normals_->size(); +// Correspondence Rejection Parameters +float g_RANSAC_THRESHOLD; +int g_RANSAC_MAX_ITERATION; - pcl::removeNaNNormalsFromPointCloud(*normals_, *normals_, index); - pcl::copyPointCloud(*cloud_, index, *nanremoved_); - cloud.setInputCloud(nanremoved_); +// ICP Parameters +std::string g_ICP_SOLVER; +int g_ICP_MAX_ITERATION; +bool g_ICP_USE_RANSAC; +bool g_ICP_USE_RECIPROCAL_SEARCH; - // std::cout << "Remove NAN From Normals:" << std::endl; - // std::cout << (num_normal - normals_->size()) << " Normals Are Removed: " \ - // << num_normal << "->" << normals_->size() << std::endl; - // std::cout << (num_point - nanremoved_->size()) << " Points Are Removed: " \ - // << num_point << "->" << nanremoved_->size() << std::endl << std::endl; +float g_ICP_TRANSFORMATION_EPSILON; +float g_ICP_MAX_CORRESPONDENCE_DISTANCE; +float g_ICP_EUCLIDEAN_FITNESS_EPSILON; +float g_ICP_RANSAC_OUTLIER_REJECTION_THRESHOLD; -} +bool g_ICP_USE_CUSTOMIZED_KDTREE; +int g_ICP_MAX_LEAF_SIZE; -void removeNANFromFPFH(FPFH_Features::Ptr feature_descriptor, FPFH_Features::Ptr nanremoved, FeatureCloud &cloud) +float g_APPROX_RADIUS_SEARCH_PARA; +float g_APPROX_NEAREST_SEARCH_PARA; + +bool g_SAVE_APPROX_DATA; + +void readConfigFile(std::string file_name) { - PointCloud::Ptr keyPoints_nanremoved_ptr(new PointCloud); - pcl::PointIndices::Ptr indices_nanremoved_ptr (new pcl::PointIndices); + Config config_file(file_name); - for (int i=0; ipoints.size();i++) - { - float p = feature_descriptor->points[i].histogram[0]; - if (p != p) - { - continue; - } - else - { - nanremoved->push_back(feature_descriptor->points[i]); - keyPoints_nanremoved_ptr->push_back(cloud.getKeyPoints()->points[i]); - indices_nanremoved_ptr->indices.push_back((cloud.getKeyPoint_indices())->indices[i]); - } - } - if(feature_descriptor->points.size() != nanremoved->points.size()) - { - cloud.setKeyPoints(keyPoints_nanremoved_ptr); - cloud.setKeyPoint_indices(indices_nanremoved_ptr); - } + // File Directory Parameters + g_DATASET_DIR = config_file.Read("Dataset_Directory", g_DATASET_DIR); + g_RESULT_DIR = config_file.Read("Result_Directory", g_RESULT_DIR); - // std::cout << "Remove NAN From Feature Descriptors:" << std::endl; - // std::cout << (feature_descriptor->points.size() - nanremoved->points.size()) << " Feature Descriptors Are Removed: " \ - // << feature_descriptor->points.size() << "->" << nanremoved->points.size() << std::endl << std::endl; -} + // Normal Estimation Parameters + g_NORMAL_SEARCH_RADIUS = config_file.Read("Normal_Search_Radius", g_NORMAL_SEARCH_RADIUS); + g_NORMAL_USE_CUSTOMIZED_KDTREE = config_file.Read("Normal_Use_Customized_KDTree", g_NORMAL_USE_CUSTOMIZED_KDTREE); + g_NORMAL_MAX_LEAF_SIZE = config_file.Read("Normal_Max_Leaf_Size", g_NORMAL_MAX_LEAF_SIZE); -// Narf Key Point Detection -void keyPointsNARF(const PointCloud::Ptr cloud_src, \ - const PointCloud::Ptr keyPoints_NARF) -{ - //Parameters - float angular_resolution = 0.5f; - float support_size = 0.2f; - - PointCloud& point_cloud = *cloud_src; - pcl::PointCloud far_ranges; - pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME; - Eigen::Affine3f scene_sensor_pose (Eigen::Affine3f::Identity ()); - - angular_resolution = pcl::deg2rad (angular_resolution); - scene_sensor_pose = Eigen::Affine3f (Eigen::Translation3f (point_cloud.sensor_origin_[0], - point_cloud.sensor_origin_[1], - point_cloud.sensor_origin_[2])) * - Eigen::Affine3f (point_cloud.sensor_orientation_); - - // -----Create RangeImage from the PointCloud----- - float noise_level = 0.0; - float min_range = 0.0f; - int border_size = 1; - boost::shared_ptr range_image_ptr (new pcl::RangeImage); - - pcl::RangeImage& range_image = *range_image_ptr; - range_image.createFromPointCloud (point_cloud, angular_resolution, \ - pcl::deg2rad (360.0f), pcl::deg2rad (180.0f), \ - scene_sensor_pose, coordinate_frame, noise_level, min_range, border_size); - - range_image.integrateFarRanges (far_ranges); - - // -------------------------------- - // -----Extract NARF keypoints----- - // -------------------------------- - pcl::RangeImageBorderExtractor range_image_border_extractor; - pcl::NarfKeypoint narf_keypoint_detector (&range_image_border_extractor); - narf_keypoint_detector.setRangeImage (&range_image); - narf_keypoint_detector.getParameters ().support_size = support_size; - //narf_keypoint_detector.getParameters ().add_points_on_straight_edges = true; - //narf_keypoint_detector.getParameters ().distance_for_additional_points = 0.5; - - pcl::PointCloud keypoint_indices; - narf_keypoint_detector.compute (keypoint_indices); - - PointCloud& keypoints = *keyPoints_NARF; - keypoints.points.resize (keypoint_indices.points.size ()); - for (size_t i=0; i sift; - pcl::PointCloud result; - - pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); - sift.setSearchMethod(tree); - sift.setScales(min_scale, n_octaves, n_scales_per_octave); - sift.setMinimumContrast(min_contrast); - - sift.setInputCloud(cloud_src); - sift.compute(result); - copyPointCloud(result, *keyPoints_SIFT); - - // std::cout << result.points.size() << " SIFT Key Points Are Detected." << std::endl << std::endl; -} + // Key Point Detection Parameters + g_KEYPOINTS_MODULE = config_file.Read("Key_Point_Detection_Module", g_KEYPOINTS_MODULE); -void keyPointsHARRIS(const PointCloud::Ptr cloud_src, const PointCloud::Ptr keyPoints_Harris) -{ - pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud); - pcl::HarrisKeypoint3D harris; - - harris.setInputCloud(cloud_src); - - // Filter only - harris.setRadius(0.35f);//0.5 - harris.setThreshold(0.01f);//0.02 - harris.setNonMaxSupression(true); - harris.setRefine(true); - - cloud_out->height = 1; - cloud_out->width = 100; - cloud_out->resize(cloud_out->height*cloud_src->width); - cloud_out->clear(); - harris.compute(*cloud_out); - int size = cloud_out->size(); - - keyPoints_Harris->height = 1; - keyPoints_Harris->width = 100; - keyPoints_Harris->resize(cloud_out->height*cloud_src->width); - keyPoints_Harris->clear(); - - pcl::PointXYZ point; - for (int i = 0; iat(i).x; - point.y = cloud_out->at(i).y; - point.z = cloud_out->at(i).z; - keyPoints_Harris->push_back(point); - } - // std::cout << keyPoints_Harris->size() << " HARRIS Key Points Are Detected." << std::endl << std::endl; -} + // Feature Description Parameters + g_FEATURE_SEARCH_RADIUS = config_file.Read("Feature_Search_Radius", g_FEATURE_SEARCH_RADIUS); + g_FEATURE_MODULE = config_file.Read("Feature_Module", g_FEATURE_MODULE); -// only used for parameters finetune -void keyPointsSIFTtest(const PointCloud::Ptr cloud_src, const PointCloud::Ptr keyPoints_SIFT, float min_scale, int n_octaves, int n_scales_per_octave, float min_contrast) -{ -/* const float min_scale = 0.1f; //the standard deviation of the smallest scale in the scale space //0.005 - const int n_octaves = 6; //the number of octaves (i.e. doublings of scale) to compute //6 - const int n_scales_per_octave = 4;//the number of scales to compute within each octave //4 - const float min_contrast = 0.1f;//the minimum contrast required for detection //0.005*/ + // Correspondence Estimation Parameters + g_CORR_EST_USE_RECIPROCAL_SEARCH = config_file.Read("Corr_Est_Use_Reciprocal_Search", g_CORR_EST_USE_RECIPROCAL_SEARCH); - std::cout << "min_scale: " << min_scale << std::endl; - std::cout << "n_octaves: " << n_octaves << std::endl; - std::cout << "n_scales_per_octave: " << n_scales_per_octave << std::endl; - std::cout << "min_contrast: " << min_contrast << std::endl; + // Correspondence Rejection Parameters + g_RANSAC_THRESHOLD = config_file.Read("Ransac_Threshold", g_RANSAC_THRESHOLD); + g_RANSAC_MAX_ITERATION = config_file.Read("Ransac_Max_Iteration", g_RANSAC_MAX_ITERATION); + // ICP Parameters + g_ICP_SOLVER = config_file.Read("ICP_Solver", g_ICP_SOLVER); + g_ICP_MAX_ITERATION = config_file.Read("ICP_Max_Iteration", g_ICP_MAX_ITERATION); + g_ICP_USE_RANSAC = config_file.Read("ICP_Use_Ransac", g_ICP_USE_RANSAC); + g_ICP_USE_RECIPROCAL_SEARCH = config_file.Read("ICP_Use_Reciprocal_Search", g_ICP_USE_RECIPROCAL_SEARCH); + + g_ICP_TRANSFORMATION_EPSILON = config_file.Read("ICP_Transformation_Epsilon", g_ICP_TRANSFORMATION_EPSILON); + g_ICP_MAX_CORRESPONDENCE_DISTANCE = config_file.Read("ICP_Max_Correspondence_Distance", g_ICP_MAX_CORRESPONDENCE_DISTANCE); + g_ICP_EUCLIDEAN_FITNESS_EPSILON = config_file.Read("ICP_Euclidean_Fitness_Epsilon", g_ICP_EUCLIDEAN_FITNESS_EPSILON); + g_ICP_RANSAC_OUTLIER_REJECTION_THRESHOLD = config_file.Read("ICP_Ransac_Outlier_Rejection_Threshold", g_ICP_RANSAC_OUTLIER_REJECTION_THRESHOLD); - // Estimate the sift interest points using z values from xyz as the Intensity variants - pcl::SIFTKeypoint sift; - pcl::PointCloud result; + g_ICP_USE_CUSTOMIZED_KDTREE = config_file.Read("ICP_Use_Customized_KDTree", g_ICP_USE_CUSTOMIZED_KDTREE); + g_ICP_MAX_LEAF_SIZE = config_file.Read("ICP_Max_Leaf_Size", g_ICP_MAX_LEAF_SIZE); - pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); - sift.setSearchMethod(tree); - sift.setScales(min_scale, n_octaves, n_scales_per_octave); - sift.setMinimumContrast(min_contrast); + // Approximation Search Parameters + g_APPROX_RADIUS_SEARCH_PARA = config_file.Read("Approx_Radius_Search_Para", g_APPROX_RADIUS_SEARCH_PARA); + g_APPROX_NEAREST_SEARCH_PARA = config_file.Read("Approx_Nearest_Search_Para", g_APPROX_NEAREST_SEARCH_PARA); - sift.setInputCloud(cloud_src); - sift.compute(result); - copyPointCloud(result, *keyPoints_SIFT); + g_SAVE_APPROX_DATA = config_file.Read("Save_Approx_Data", g_SAVE_APPROX_DATA); - std::cout << result.points.size() << " SIFT Key Points Are Detected." << std::endl << std::endl; + std::cout << std::endl << "Reading Config Successfully!" << std::endl; } -// only used for parameters finetune -void keyPointsHARRIStest(const PointCloud::Ptr cloud_src, const PointCloud::Ptr keyPoints_Harris, float radius, float threshold) +void makeResultFolder(std::string &g_result_dir) { - pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud); - pcl::HarrisKeypoint3D harris; - - harris.setInputCloud(cloud_src); - - // Filter only - harris.setRadius(radius);//0.5 - harris.setThreshold(threshold);//0.02 - harris.setNonMaxSupression(true); - harris.setRefine(true); - - cloud_out->height = 1; - cloud_out->width = 100; - cloud_out->resize(cloud_out->height*cloud_src->width); - cloud_out->clear(); - harris.compute(*cloud_out); - int size = cloud_out->size(); - - keyPoints_Harris->height = 1; - keyPoints_Harris->width = 100; - keyPoints_Harris->resize(cloud_out->height*cloud_src->width); - keyPoints_Harris->clear(); - - pcl::PointXYZ point; - for (int i = 0; iat(i).x; - point.y = cloud_out->at(i).y; - point.z = cloud_out->at(i).z; - keyPoints_Harris->push_back(point); - } - std::cout << keyPoints_Harris->size() << " HARRIS Key Points Are Detected." << std::endl << std::endl; + DIR *dirp; + struct dirent *directory; + + int last_file_id = 0; + std::string cmd; + std::vector file_name; + + cmd = "mkdir -p " + g_result_dir; + system(cmd.c_str()); + + dirp = opendir(g_result_dir.c_str()); + if (dirp) + { + while ((directory = readdir(dirp)) != NULL) + { + file_name.push_back(directory->d_name); + } + + closedir(dirp); + + if (file_name.size() == 2) + { + cmd = "mkdir " + g_result_dir+ "result_1"; + } + else + { + for (int i = 0; i < file_name.size(); i++) + { + if (file_name[i].find("result") != std::string::npos) + { + int split_index = file_name[i].find("_"); + int cur_file_id = std::stoi(file_name[i].substr(split_index + 1)); + if (last_file_id < cur_file_id) + last_file_id = cur_file_id; + } + + } + cmd = "mkdir " + g_result_dir + "result_" + std::to_string(last_file_id + 1); + } + + g_result_dir = g_result_dir + "result_" + std::to_string(last_file_id + 1) + "/"; + + if (!system(cmd.c_str())) + std::cout << "Making New Directory Successfully!" << std::endl; + else + { + std::cout << "Making New Result Directory Failed!" << std::endl; + exit(-1); + } + } + else { + std::cout << errno << std::endl; + } } -// utils -bool string_sort (std::string i,std::string j) +bool sortString (std::string i,std::string j) { // the part before '.bin' std::string foo_i = i.substr(0,i.length()-4); @@ -335,7 +160,7 @@ bool string_sort (std::string i,std::string j) return (foo_i &files) +void listDir(std::string path_dir, std::vector &files) { DIR* dirp = opendir(path_dir.c_str()); @@ -352,26 +177,26 @@ void listdir(std::string path_dir, std::vector &files) std::string str_d_name(dp->d_name); if (str_d_name == ".") - continue; + continue; if (str_d_name == "..") - continue; + continue; file_num += 1; if (*(path_dir.end() - 1) == '/') - files.push_back(path_dir + str_d_name); + files.push_back(path_dir + str_d_name); else - files.push_back(path_dir + '/' + str_d_name); + files.push_back(path_dir + '/' + str_d_name); } closedir(dirp); std::cout << "total number of frames: " << file_num << std::endl << std::endl; // sort - std::sort (files.begin(), files.end(), string_sort); + std::sort (files.begin(), files.end(), sortString); } -void load_bin(std::string infile, FeatureCloud &cloud) +void loadBINFile(std::string infile, FeatureCloud &cloud) { - std::cout << std::endl; + std::cout << std::endl; std::cout << "Loading " << infile << std::endl; std::fstream input(infile.c_str(), std::ios::in | std::ios::binary); @@ -403,522 +228,193 @@ void load_bin(std::string infile, FeatureCloud &cloud) cloud.setInputCloud(points); input.close(); - std::cout << "Number Of Points Loaded: " << points->points.size() << std::endl << std::endl; -} - -// Compute the surface normals -void computeSurfaceNormals (FeatureCloud &cloud, float R, \ - float &nn_time, float &bd_time) -{ - SurfaceNormals::Ptr normals_ (new SurfaceNormals); - - pcl::NormalEstimation norm_est; - - norm_est.setInputCloud (cloud.getPointCloud()); - // norm_est.setIndices(cloud.getKeyPoint_indices()); - - pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); - norm_est.setSearchMethod(tree); - norm_est.setRadiusSearch(R); - // norm_est.setKSearch(35); - // norm_est.setKSearch(K); - norm_est.compute (*normals_); - // norm_est.getNnTime(nn_time); - // norm_est.getBuildTime(bd_time); - - cloud.setSurfaceNormals(normals_); - // std::cout << "Normals:" << *normals_ << std::endl; + std::cout << "Number Of Points Loaded: " << points->points.size() << std::endl << std::endl; } -void computeFeatures_FPFH (FeatureCloud &cloud, float R, float &nn_time, float &bd_time) +void loadTXTFile(std::string infile, FeatureCloud &cloud) { - FPFH_Features::Ptr fpfh_features_ (new FPFH_Features); - FPFH_Features::Ptr nanremoved_(new FPFH_Features); - - pcl::FPFHEstimation fpfh_est; - fpfh_est.setSearchSurface (cloud.getPointCloud()); - fpfh_est.setInputNormals (cloud.getSurfaceNormals()); - fpfh_est.setInputCloud (cloud.getKeyPoints()); - - pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); + std::cout << "Loading " << infile << std::endl; - fpfh_est.setSearchMethod(tree); - fpfh_est.setRadiusSearch(R); + std::ifstream file(infile.c_str()); + std::string str; - fpfh_est.compute (*fpfh_features_); - - // fpfh_est.getNnTime(nn_time); - // fpfh_est.getBuildTime(bd_time); - - removeNANFromFPFH(fpfh_features_, nanremoved_, cloud); - - // for future optimization - //removeNANFromDescriptor(fpfh_features_, nanremoved_, cloud); - - cloud.setFeatures_FPFH(nanremoved_); -} - -void computeFeatures_VFH (FeatureCloud &cloud, float R) -{ - VFH_Features::Ptr vfh_features_(new VFH_Features); - pcl::VFHEstimation vfh_est; - vfh_est.setSearchSurface(cloud.getPointCloud()); - vfh_est.setInputNormals(cloud.getSurfaceNormals()); - vfh_est.setInputCloud(cloud.getKeyPoints()); + PointCloud::Ptr points (new PointCloud); + std::vector raw_data; - pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); - - vfh_est.setSearchMethod(tree); - vfh_est.setRadiusSearch(R); - - vfh_est.compute(*vfh_features_); - cloud.setFeatures_VFH(vfh_features_); - - //std::cout << "output points.size (): " << vfh_features_->points.size() << std::endl; -} - -void computeFeatures_SpinImage (FeatureCloud &cloud, float R) -{ - SpinImage_Features::Ptr spinImage_features_(new SpinImage_Features); - pcl::SpinImageEstimation> spinimage_est; - spinimage_est.setSearchSurface(cloud.getPointCloud()); - spinimage_est.setInputNormals(cloud.getSurfaceNormals()); - spinimage_est.setInputCloud(cloud.getKeyPoints()); + while (std::getline(file, str)) + raw_data.push_back(str); + std:: cout << "Size: " << raw_data.size() << std::endl; + for (int i = 0; i < raw_data.size(); i++) + { + PointT point; - pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); + std::stringstream raw_ss(raw_data[i]); - spinimage_est.setSearchMethod(tree); - spinimage_est.setRadiusSearch(R); + int j = 0; + while (raw_ss.good()) + { + std::string substr; + std::getline(raw_ss, substr, ','); + float value_ = std::stof(substr); + if (j % 3 == 0) point.x = value_; + if (j % 3 == 1) point.y = value_; + if (j % 3 == 2) point.z = value_; + j += 1; + } - spinimage_est.compute(*spinImage_features_); - cloud.setFeatures_SpinImage(spinImage_features_); + points->push_back(point); + } - // std::cout << "output points.size (): " << spinImage_features_->points.size() << std::endl; + cloud.setInputCloud(points); + std::cout << "Number Of Points Loaded: " << points->points.size() << std::endl << std::endl; } -void computeFeatures_3DSC (FeatureCloud &cloud, float R, float &nn_time, float &bd_time) +void getIndices(FeatureCloud &cloud) { - threeDSC_Features::Ptr threedsc_features_(new threeDSC_Features); - threeDSC_Features::Ptr nanremoved_(new threeDSC_Features); - pcl::ShapeContext3DEstimation threedsc_est; - threedsc_est.setSearchSurface(cloud.getPointCloud()); - threedsc_est.setInputNormals(cloud.getSurfaceNormals()); - threedsc_est.setInputCloud(cloud.getKeyPoints()); - - pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); - - threedsc_est.setSearchMethod(tree); - threedsc_est.setRadiusSearch(R); - - // The minimal radius value for the search sphere, to avoid being too sensitive - // in bins close to the center of the sphere. - threedsc_est.setMinimalRadius(0.4); - // Radius used to compute the local point density for the neighbors - // (the density is the number of points within that radius). - threedsc_est.setPointDensityRadius(0.45); - - - threedsc_est.compute(*threedsc_features_); - - // threedsc_est.getNnTime(nn_time); - // threedsc_est.getBuildTime(bd_time); + const PointCloud::Ptr cloudin_ptr = cloud.getPointCloud(); + const PointCloud::Ptr keypoints_cal_ptr = cloud.getKeyPoints(); + const PointCloud::Ptr keypoints_real_ptr (new PointCloud); + pcl::PointIndices::Ptr indices_ptr (new pcl::PointIndices); + + pcl::KdTreeFLANN kdtree; + kdtree.setInputCloud(cloudin_ptr); + std::vectorpointNKNSquareDistance; + std::vector pointIdxNKNSearch; + + int indice = 0; + for (size_t i =0; i < keypoints_cal_ptr->size();i++) + { + kdtree.nearestKSearch(keypoints_cal_ptr->points[i],1,pointIdxNKNSearch,pointNKNSquareDistance); - removeNANFromDescriptor(threedsc_features_, nanremoved_, cloud); + indice = pointIdxNKNSearch[0]; + indices_ptr->indices.push_back(indice); + keypoints_real_ptr->points.push_back(cloudin_ptr->points[indice]); + } - cloud.setFeatures_3DSC(nanremoved_); + cloud.setKeyPoints(keypoints_real_ptr); + cloud.setKeyPoint_indices(indices_ptr); } -// void computeFeatures_USC (FeatureCloud &cloud, float R) -// { -// USC_Features::Ptr usc_features_(new USC_Features); -// USC_Features::Ptr nanremoved_(new USC_Features); -// pcl::UniqueShapeContext usc_est; -// usc_est.setSearchSurface(cloud.getPointCloud()); -// //usc_est.setInputNormals(cloud.getSurfaceNormals()); -// usc_est.setInputCloud(cloud.getKeyPoints()); - -// pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); - -// usc_est.setSearchMethod(tree); -// usc_est.setRadiusSearch(R); - -// // The minimal radius value for the search sphere, to avoid being too sensitive -// // in bins close to the center of the sphere. -// usc_est.setMinimalRadius(0.4); -// // Radius used to compute the local point density for the neighbors -// // (the density is the number of points within that radius). -// usc_est.setPointDensityRadius(0.45); -// // Set the radius to compute the Local Reference Frame. -// usc_est.setLocalRadius(0.4); - -// usc_est.compute(*usc_features_); - -// removeNANFromDescriptor(usc_features_, nanremoved_, cloud); - -// cloud.setFeatures_USC(nanremoved_); -// } - - -void computeFeatures_SHOT (FeatureCloud &cloud, float R, float &nn_time, float &bd_time) +void writeMatrix(std::ofstream &stream_name, std::string file_name, Eigen::Matrix4f &stream_data) { - SHOT_Features::Ptr shot_features_(new SHOT_Features); - SHOT_Features::Ptr nanremoved_(new SHOT_Features); - pcl::SHOTEstimation shot_est; - shot_est.setSearchSurface(cloud.getPointCloud()); - shot_est.setInputNormals(cloud.getSurfaceNormals()); - shot_est.setInputCloud(cloud.getKeyPoints()); + stream_name.open (file_name, std::fstream::app); - pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); - - shot_est.setSearchMethod(tree); - shot_est.setRadiusSearch(R); //0.5 - - shot_est.compute(*shot_features_); - - // shot_est.getNnTime(nn_time); - // shot_est.getBuildTime(bd_time); - - //removeNANFromSHOT(shot_features_, nanremoved_, cloud); - - //for future optimization - removeNANFromDescriptor(shot_features_, nanremoved_, cloud); - - cloud.setFeatures_SHOT(nanremoved_); + for(int i = 0; i < 3; i ++) + { + for(int j = 0; j < 4; j ++) + { + stream_name << ("%lf", stream_data(i,j)); + if (j != 4) + stream_name << " "; + } + } + stream_name << "\n"; + stream_name.close(); } -// strange output, only 2 dimensions. -// void computeFeatures_RSD (FeatureCloud &cloud, float R) -// { -// RSD_Features::Ptr rsd_features_(new RSD_Features); -// pcl::RSDEstimation rsd_est; -// rsd_est.setSearchSurface(cloud.getPointCloud()); -// rsd_est.setInputNormals(cloud.getSurfaceNormals()); -// rsd_est.setInputCloud(cloud.getKeyPoints()); - -// pcl::search::KdTree::Ptr tree(new pcl::search::KdTree()); - -// rsd_est.setSearchMethod(tree); -// rsd_est.setRadiusSearch(R); - -// rsd_est.compute(*rsd_features_); -// rsd_est.setSaveHistograms(true); -// // Plane radius. Any radius larger than this is considered infinite (a plane). -// rsd_est.setPlaneRadius(1.0); - -// cloud.setFeatures_RSD(rsd_features_); - -// std::cout << "output points.size (): " << rsd_features_->points.size() << std::endl; - -// ofstream RSDSignature; -// RSDSignature.open("RSDSignature.txt"); -// for (int i = 0; i < rsd_features_->points.size(); i++) -// { -// RSD_FeatureT descriptor = rsd_features_->points[i]; -// //std::cout << descriptor << std::endl; -// RSDSignature << descriptor << endl; -// //std::cout << rsd_est.getHistograms() << std::endl; -// } -// RSDSignature.close(); -// } - - -// Initialize the PointCloudNormal type -void construct_PointNormal(FeatureCloud &source_cloud, FeatureCloud &target_cloud, \ - int use_keypoints) +void printMatrix(std::string matrix_name, Eigen::Matrix4f &matrix) { - // src - PointCloudNormal::Ptr pointNormal_src (new PointCloudNormal); - PointCloudNormal::Ptr pointNormal_tgt (new PointCloudNormal); - - if (use_keypoints == 1){ - // to-do - } - else{ - // src - PointCloud::Ptr src_cloud = source_cloud.getTransformedCloud (); - SurfaceNormals::Ptr src_normal = source_cloud.getSurfaceNormals (); - - for(size_t i = 0; i < src_cloud->points.size(); ++i) - { - PointNormal pt_normal; - - pt_normal.x = src_cloud->points[i].x; - pt_normal.y = src_cloud->points[i].y; - pt_normal.z = src_cloud->points[i].z; - - pt_normal.normal_x = src_normal->points[i].normal_x; - pt_normal.normal_y = src_normal->points[i].normal_y; - pt_normal.normal_z = src_normal->points[i].normal_z; - - pointNormal_src->push_back(pt_normal); - } - source_cloud.setPointCloudNormal(pointNormal_src); - - // tgt - PointCloud::Ptr tgt_cloud = target_cloud.getPointCloud (); - SurfaceNormals::Ptr tgt_normal = target_cloud.getSurfaceNormals (); - - for(size_t i = 0; i < tgt_cloud->points.size(); ++i) + std::cout << matrix_name << ": " << std::endl; + for(int i = 0; i < 3; i ++) + { + for(int j = 0; j < 4; j ++) { - PointNormal pt_normal; - - pt_normal.x = tgt_cloud->points[i].x; - pt_normal.y = tgt_cloud->points[i].y; - pt_normal.z = tgt_cloud->points[i].z; - - pt_normal.normal_x = tgt_normal->points[i].normal_x; - pt_normal.normal_y = tgt_normal->points[i].normal_y; - pt_normal.normal_z = tgt_normal->points[i].normal_z; - - pointNormal_tgt->push_back(pt_normal); + std::cout << ("%lf", matrix(i,j)); + if (j != 4) + std::cout << " "; } - target_cloud.setPointCloudNormal(pointNormal_tgt); + std::cout << std::endl; } + std::cout << std::endl; } -void getIndices (PointCloud::Ptr cloudin, PointCloud::Ptr keypoints_cal, \ - PointCloud::Ptr keypoints_real, pcl::PointIndices::Ptr indices) +void detectKeyPoints(FeatureCloud &cloud) { - pcl::KdTreeFLANN kdtree; - kdtree.setInputCloud(cloudin); - std::vectorpointNKNSquareDistance; - std::vector pointIdxNKNSearch; - - int indice = 0; - for (size_t i =0; i < keypoints_cal->size();i++) - { - kdtree.nearestKSearch(keypoints_cal->points[i],1,pointIdxNKNSearch,pointNKNSquareDistance); - - indice = pointIdxNKNSearch[0]; - indices->indices.push_back(indice); - keypoints_real->points.push_back(cloudin->points[indice]); - } -} - -void correspondence_estimation(std::string kernel_descriptors, std::string flag_reciprocal, \ - FeatureCloud &source_cloud, FeatureCloud &target_cloud,\ - pcl::Correspondences &all_corres, float &nn_time, float &bd_time) -{ - if (kernel_descriptors == "FPFH") - { - pcl::registration::CorrespondenceEstimation est; - est.setInputSource (source_cloud.getFeatures_FPFH()); - est.setInputTarget (target_cloud.getFeatures_FPFH()); - if(flag_reciprocal == "True") - est.determineReciprocalCorrespondences (all_corres); - // est.getBuildTime(bd_time); - // est.getNnTime(nn_time); - } - if (kernel_descriptors == "VFH") + if (g_KEYPOINTS_MODULE == "NARF") { - pcl::registration::CorrespondenceEstimation est; - est.setInputSource (source_cloud.getFeatures_VFH()); - est.setInputTarget (target_cloud.getFeatures_VFH()); - if(flag_reciprocal == "True") - est.determineReciprocalCorrespondences (all_corres); - // est.getBuildTime(bd_time); - // est.getNnTime(nn_time); + std::cout << "NARF Keypoints Are Being Detected!" << std::endl; + keyPointsNARF(cloud); } -/* if (kernel_descriptors == "SpinImage") - { - pcl::registration::CorrespondenceEstimation est; - est.setInputSource (source_cloud.getFeatures_SpinImage()); - est.setInputTarget (target_cloud.getFeatures_SpinImage()); - if(flag_reciprocal == "True") - est.determineReciprocalCorrespondences (all_corres); - }*/ - if (kernel_descriptors == "3DSC") + + if (g_KEYPOINTS_MODULE == "SIFT") { - pcl::registration::CorrespondenceEstimation est; - est.setInputSource (source_cloud.getFeatures_3DSC()); - est.setInputTarget (target_cloud.getFeatures_3DSC()); - if(flag_reciprocal == "True") - est.determineReciprocalCorrespondences (all_corres); - // est.getBuildTime(bd_time); - // est.getNnTime(nn_time); + std::cout << "SIFT Keypoints Are Being Detected!" << std::endl; + keyPointsSIFT(cloud); } - // if (kernel_descriptors == "USC") - // { - // pcl::registration::CorrespondenceEstimation est; - // est.setInputSource (source_cloud.getFeatures_USC()); - // est.setInputTarget (target_cloud.getFeatures_USC()); - // if(flag_reciprocal == "True") - // est.determineReciprocalCorrespondences (all_corres); - // } - if (kernel_descriptors == "SHOT") + + if (g_KEYPOINTS_MODULE == "HARRIS") { - pcl::registration::CorrespondenceEstimation est; - est.setInputSource (source_cloud.getFeatures_SHOT()); - est.setInputTarget (target_cloud.getFeatures_SHOT()); + std::cout << "HARRIS Keypoints Are Being Detected!" << std::endl; + keyPointsHARRIS(cloud); + } - if(flag_reciprocal == "True") - est.determineReciprocalCorrespondences (all_corres); - - // est.getBuildTime(bd_time); - // est.getNnTime(nn_time); - } - // if (kernel_descriptors == "RSD") - // { - // pcl::registration::CorrespondenceEstimation est; - // est.setInputSource (source_cloud.getFeatures_RSD()); - // est.setInputTarget (target_cloud.getFeatures_RSD()); - // if(flag_reciprocal == "True") - // est.determineReciprocalCorrespondences (all_corres); - // } + getIndices(cloud); } - -// previous XYZ based rejection -void correspondences_rejection(FeatureCloud &source_cloud, FeatureCloud &target_cloud,\ - pcl::Correspondences &correspondences, pcl::Correspondences &inliers, \ - Result *result, int N, float threshold, int use_keypoints) +void describeFeatures(FeatureCloud &cloud) { - - pcl::registration::CorrespondenceRejectorSampleConsensus sac; - sac.setInputSource(source_cloud.getKeyPoints ()); - sac.setInputTarget(target_cloud.getKeyPoints ()); - - // sac.setInputSource(source_cloud.getPointCloud ()); - // sac.setInputTarget(target_cloud.getPointCloud ()); - - // Set the threshold for rejection iteration - sac.setInlierThreshold(threshold); - sac.setMaximumIterations(N); - sac.getRemainingCorrespondences(correspondences, inliers); - - Eigen::Matrix4f transformation = sac.getBestTransformation(); - - result->final_transformation = transformation; - - // std::cout << "RANSAC:" << std::endl; - // for(int i = 0; i < 3; i ++) - // { - // for(int j = 0; j < 4; j ++) - // { - // std::cout << ("%lf", transformation(i,j)); - // if (j != 4) - // std::cout << " "; - // } - // std::cout << std::endl; - // } - - PointCloud::Ptr transformed_cloud (new PointCloud); - - if (use_keypoints == 1) + if (g_FEATURE_MODULE == "FPFH") { - pcl::transformPointCloud (*(source_cloud.getKeyPoints ()), *transformed_cloud, transformation); + std::cout << "FPFH Descriptors Are Being Detected!" << std::endl; + computeFeatures_FPFH (cloud, g_FEATURE_SEARCH_RADIUS); } - else + + if (g_FEATURE_MODULE == "SHOT") { - pcl::transformPointCloud (*(source_cloud.getPointCloud ()), *transformed_cloud, transformation); + std::cout << "SHOT Descriptors Are Being Detected!" << std::endl; + computeFeatures_SHOT (cloud, g_FEATURE_SEARCH_RADIUS); } - source_cloud.setTransformedCloud(transformed_cloud); - - // std::cout << "Correspondences Rejection:" << std::endl; - // std::cout << (correspondences.size() - inliers.size()) << " Correspondences Are Rejected: " \ - // << correspondences.size() << "->" << inliers.size() << std::endl << std::endl; } -void iterative_closest_points(std::string solver, std::string flag_reciprocal, \ - std::string flag_ransac, FeatureCloud &source_cloud, FeatureCloud &target_cloud,\ - Result *result, float transEps, float corresDist, float EuclFitEps, float outlThresh, \ - int use_keypoint, pcl::Correspondences &inliers, float &nn_time, float &bd_time) +void removeNANFromNormal(FeatureCloud &cloud) { - PointCloudNormal Final; - - PointCloudNormal::Ptr pointNormal_src = source_cloud.getPointCloudNormal(); - PointCloudNormal::Ptr pointNormal_tgt = target_cloud.getPointCloudNormal(); - - pcl::registration::CorrespondenceRejector::Ptr ransac_rej \ - (new pcl::registration::CorrespondenceRejectorSampleConsensus ()); - - if(solver == "SVD") - { - std::cout << "SVD Solver for ICP Is Running!" << std::endl; - pcl::IterativeClosestPoint icp; - - if (flag_reciprocal == "True") - icp.setUseReciprocalCorrespondences(true); - if (flag_ransac == "True") - { - icp.setRANSACOutlierRejectionThreshold (outlThresh); - // add ransac rejector - icp.addCorrespondenceRejector(ransac_rej); - } - - icp.setInputSource(pointNormal_src); - icp.setInputTarget(pointNormal_tgt); - - icp.setMaximumIterations (15); - icp.setTransformationEpsilon (transEps); - icp.setMaxCorrespondenceDistance (corresDist); - icp.setEuclideanFitnessEpsilon (EuclFitEps); - - icp.align(Final); - - result->final_transformation = icp.getFinalTransformation(); - result->fitness_score = icp.getFitnessScore(); - - // icp.getNnTime_icp(nn_time); - // icp.getBuildTime_icp(bd_time); - - } - if (solver == "LM") - { - std::cout << "LM Solver for ICP Is Running!" << std::endl; - pcl::IterativeClosestPointNonLinear icp_lm; - - if (flag_reciprocal == "True") - icp_lm.setUseReciprocalCorrespondences(true); - if (flag_ransac == "True") - { - icp_lm.setRANSACOutlierRejectionThreshold (outlThresh); - // add ransac rejector - icp_lm.addCorrespondenceRejector(ransac_rej); - } - - icp_lm.setInputSource(pointNormal_src); - icp_lm.setInputTarget(pointNormal_tgt); - - icp_lm.setMaximumIterations(15); - icp_lm.setTransformationEpsilon(transEps); - icp_lm.setMaxCorrespondenceDistance(corresDist); - icp_lm.setEuclideanFitnessEpsilon (EuclFitEps); + PointCloud::Ptr nanremoved_(new PointCloud); + PointCloud::Ptr cloud_ = cloud.getPointCloud(); + SurfaceNormals::Ptr normals_ = cloud.getSurfaceNormals(); + std::vector index; - icp_lm.align(Final); + int num_point = cloud_->size(); + int num_normal = normals_->size(); - result->final_transformation = icp_lm.getFinalTransformation(); - result->fitness_score = icp_lm.getFitnessScore(); + pcl::removeNaNNormalsFromPointCloud(*normals_, *normals_, index); + pcl::copyPointCloud(*cloud_, index, *nanremoved_); + cloud.setInputCloud(nanremoved_); - // icp_lm.getNnTime_icp(nn_time); - // icp_lm.getBuildTime_icp(bd_time); + std::cout << "Remove NAN From Normals:" << std::endl; + std::cout << (num_normal - normals_->size()) << " Normals Are Removed: " \ + << num_normal << "->" << normals_->size() << std::endl; + std::cout << (num_point - nanremoved_->size()) << " Points Are Removed: " \ + << num_point << "->" << nanremoved_->size() << std::endl << std::endl; - } } -void keyPoint_dist(FeatureCloud &source_cloud, FeatureCloud &target_cloud) +void removeNANFromFPFH(FPFH_Features::Ptr feature_descriptor, FPFH_Features::Ptr nanremoved, FeatureCloud &cloud) { - pcl::KdTreeFLANN kdtree; - kdtree.setInputCloud(target_cloud.getKeyPoints()); + PointCloud::Ptr keyPoints_nanremoved_ptr(new PointCloud); + pcl::PointIndices::Ptr indices_nanremoved_ptr (new pcl::PointIndices); - PointCloud::Ptr keypoints_cal = source_cloud.getKeyPoints(); - - std::vectorpointNKNSquareDistance; - std::vector pointIdxNKNSearch; - - int indice = 0; + for (int i=0; ipoints.size();i++) + { + float p = feature_descriptor->points[i].histogram[0]; + if (p != p) + { + continue; + } + else + { + nanremoved->push_back(feature_descriptor->points[i]); + keyPoints_nanremoved_ptr->push_back(cloud.getKeyPoints()->points[i]); + indices_nanremoved_ptr->indices.push_back((cloud.getKeyPoint_indices())->indices[i]); + } + } + if(feature_descriptor->points.size() != nanremoved->points.size()) + { + cloud.setKeyPoints(keyPoints_nanremoved_ptr); + cloud.setKeyPoint_indices(indices_nanremoved_ptr); + } - for (size_t i =0; i < keypoints_cal->size();i++) - { - kdtree.nearestKSearch(keypoints_cal->points[i],1,pointIdxNKNSearch,pointNKNSquareDistance); - - std::cout << "Distances:"<indices.push_back(indice); - // keypoints_real->points.push_back(cloudin->points[indice]); - } + std::cout << "Remove NAN From Feature Descriptors:" << std::endl; + std::cout << (feature_descriptor->points.size() - nanremoved->points.size()) << " Feature Descriptors Are Removed: " \ + << feature_descriptor->points.size() << "->" << nanremoved->points.size() << std::endl << std::endl; } diff --git a/tools/Ground-Truth/dataset/poses/00.txt b/tools/Ground-Truth/dataset/poses/00.txt new file mode 100644 index 0000000..e2e8661 --- /dev/null +++ b/tools/Ground-Truth/dataset/poses/00.txt @@ -0,0 +1,4541 @@ +1.000000e+00 9.043680e-12 2.326809e-11 5.551115e-17 9.043683e-12 1.000000e+00 2.392370e-10 3.330669e-16 2.326810e-11 2.392370e-10 9.999999e-01 -4.440892e-16 +9.999978e-01 5.272628e-04 -2.066935e-03 -4.690294e-02 -5.296506e-04 9.999992e-01 -1.154865e-03 -2.839928e-02 2.066324e-03 1.155958e-03 9.999971e-01 8.586941e-01 +9.999910e-01 1.048972e-03 -4.131348e-03 -9.374345e-02 -1.058514e-03 9.999968e-01 -2.308104e-03 -5.676064e-02 4.128913e-03 2.312456e-03 9.999887e-01 1.716275e+00 +9.999796e-01 1.566466e-03 -6.198571e-03 -1.406429e-01 -1.587952e-03 9.999927e-01 -3.462706e-03 -8.515762e-02 6.193102e-03 3.472479e-03 9.999747e-01 2.574964e+00 +9.999637e-01 2.078471e-03 -8.263498e-03 -1.874858e-01 -2.116664e-03 9.999871e-01 -4.615826e-03 -1.135202e-01 8.253797e-03 4.633149e-03 9.999551e-01 3.432648e+00 +9.999433e-01 2.586172e-03 -1.033094e-02 -2.343818e-01 -2.645881e-03 9.999798e-01 -5.770163e-03 -1.419150e-01 1.031581e-02 5.797170e-03 9.999299e-01 4.291335e+00 +9.999184e-01 3.088363e-03 -1.239599e-02 -2.812195e-01 -3.174350e-03 9.999710e-01 -6.922975e-03 -1.702743e-01 1.237425e-02 6.961759e-03 9.998991e-01 5.148987e+00 +9.998890e-01 3.586305e-03 -1.446384e-02 -3.281178e-01 -3.703403e-03 9.999605e-01 -8.077186e-03 -1.986703e-01 1.443430e-02 8.129853e-03 9.998627e-01 6.007777e+00 +9.998551e-01 4.078705e-03 -1.652913e-02 -3.749547e-01 -4.231669e-03 9.999484e-01 -9.229794e-03 -2.270290e-01 1.649063e-02 9.298401e-03 9.998207e-01 6.865477e+00 +9.998167e-01 4.566671e-03 -1.859652e-02 -4.218367e-01 -4.760342e-03 9.999347e-01 -1.038342e-02 -2.554151e-01 1.854788e-02 1.047004e-02 9.997731e-01 7.724036e+00 +9.997738e-01 5.049868e-03 -2.066463e-02 -4.687329e-01 -5.289072e-03 9.999194e-01 -1.153730e-02 -2.838096e-01 2.060470e-02 1.164399e-02 9.997198e-01 8.582886e+00 +9.997264e-01 5.527315e-03 -2.272922e-02 -5.155474e-01 -5.816781e-03 9.999025e-01 -1.268908e-02 -3.121547e-01 2.265686e-02 1.281782e-02 9.996611e-01 9.440275e+00 +9.996745e-01 6.000540e-03 -2.479692e-02 -5.624310e-01 -6.345160e-03 9.998840e-01 -1.384246e-02 -3.405416e-01 2.471098e-02 1.399530e-02 9.995966e-01 1.029896e+01 +9.996182e-01 6.468772e-03 -2.686440e-02 -6.093087e-01 -6.873365e-03 9.998639e-01 -1.499561e-02 -3.689250e-01 2.676374e-02 1.517453e-02 9.995266e-01 1.115757e+01 +9.995562e-01 7.058450e-03 -2.894213e-02 -6.562052e-01 -7.530449e-03 9.998399e-01 -1.623192e-02 -3.973964e-01 2.882292e-02 1.644266e-02 9.994492e-01 1.201541e+01 +9.995095e-01 5.595311e-03 -3.081450e-02 -7.018788e-01 -6.093682e-03 9.998517e-01 -1.610315e-02 -4.239119e-01 3.071983e-02 1.628303e-02 9.993953e-01 1.286965e+01 +9.994226e-01 7.842768e-03 -3.306167e-02 -7.498241e-01 -8.456089e-03 9.997940e-01 -1.845198e-02 -4.540039e-01 3.291014e-02 1.872089e-02 9.992829e-01 1.373146e+01 +9.993587e-01 8.704386e-03 -3.473400e-02 -7.992511e-01 -9.439421e-03 9.997338e-01 -2.105422e-02 -4.840770e-01 3.454149e-02 2.136859e-02 9.991747e-01 1.460026e+01 +9.992482e-01 1.235688e-02 -3.674849e-02 -8.546642e-01 -1.320676e-02 9.996488e-01 -2.297477e-02 -5.155070e-01 3.645169e-02 2.344282e-02 9.990604e-01 1.547957e+01 +9.991826e-01 1.352279e-02 -3.809783e-02 -9.072868e-01 -1.439161e-02 9.996404e-01 -2.262373e-02 -5.464705e-01 3.777819e-02 2.315352e-02 9.990178e-01 1.636940e+01 +9.991241e-01 1.328777e-02 -3.967996e-02 -9.609163e-01 -1.412604e-02 9.996813e-01 -2.092052e-02 -5.783595e-01 3.938933e-02 2.146271e-02 9.989934e-01 1.726896e+01 +9.990604e-01 1.351433e-02 -4.118029e-02 -1.011589e+00 -1.432436e-02 9.997084e-01 -1.943894e-02 -6.092403e-01 4.090558e-02 2.001055e-02 9.989626e-01 1.817318e+01 +9.990174e-01 1.304822e-02 -4.235654e-02 -1.066256e+00 -1.386115e-02 9.997242e-01 -1.895579e-02 -6.387363e-01 4.209752e-02 1.952427e-02 9.989227e-01 1.908411e+01 +9.989383e-01 1.325999e-02 -4.411963e-02 -1.118651e+00 -1.413494e-02 9.997084e-01 -1.957870e-02 -6.686219e-01 4.384715e-02 2.018154e-02 9.988343e-01 1.999722e+01 +9.989120e-01 1.152857e-02 -4.518863e-02 -1.171840e+00 -1.247777e-02 9.997062e-01 -2.077977e-02 -6.990778e-01 4.493579e-02 2.132101e-02 9.987623e-01 2.091368e+01 +9.988800e-01 1.128892e-02 -4.595003e-02 -1.224279e+00 -1.218132e-02 9.997417e-01 -1.918760e-02 -7.287421e-01 4.572155e-02 1.972584e-02 9.987594e-01 2.184042e+01 +9.988593e-01 1.299421e-02 -4.594914e-02 -1.280807e+00 -1.370812e-02 9.997896e-01 -1.525610e-02 -7.604717e-01 4.574123e-02 1.586857e-02 9.988272e-01 2.277432e+01 +9.988876e-01 1.379030e-02 -4.509495e-02 -1.334841e+00 -1.432558e-02 9.998304e-01 -1.156850e-02 -7.929673e-01 4.492776e-02 1.220164e-02 9.989157e-01 2.370953e+01 +9.989649e-01 1.285173e-02 -4.363580e-02 -1.385747e+00 -1.325687e-02 9.998715e-01 -9.007757e-03 -8.209244e-01 4.351442e-02 9.576906e-03 9.990068e-01 2.465175e+01 +9.990298e-01 1.265253e-02 -4.218321e-02 -1.436633e+00 -1.299403e-02 9.998849e-01 -7.831284e-03 -8.456208e-01 4.207926e-02 8.371815e-03 9.990791e-01 2.559694e+01 +9.990746e-01 1.289592e-02 -4.103309e-02 -1.487044e+00 -1.333334e-02 9.998570e-01 -1.040438e-02 -8.702127e-01 4.089305e-02 1.094186e-02 9.991036e-01 2.654471e+01 +9.990967e-01 1.391010e-02 -4.015465e-02 -1.538025e+00 -1.454998e-02 9.997711e-01 -1.568743e-02 -8.971121e-01 3.992724e-02 1.625751e-02 9.990703e-01 2.749627e+01 +9.991533e-01 1.320645e-02 -3.896502e-02 -1.586551e+00 -1.396325e-02 9.997178e-01 -1.921474e-02 -9.254151e-01 3.870026e-02 1.974255e-02 9.990558e-01 2.845466e+01 +9.992105e-01 1.079096e-02 -3.823584e-02 -1.633363e+00 -1.148611e-02 9.997718e-01 -1.800793e-02 -9.555630e-01 3.803279e-02 1.843289e-02 9.991064e-01 2.942293e+01 +9.992215e-01 9.086312e-03 -3.839229e-02 -1.680971e+00 -9.596057e-03 9.998679e-01 -1.311391e-02 -9.838377e-01 3.826806e-02 1.347211e-02 9.991766e-01 3.039839e+01 +9.992105e-01 5.838117e-03 -3.929763e-02 -1.728893e+00 -6.198498e-03 9.999398e-01 -9.054940e-03 -1.011772e+00 3.924239e-02 9.291377e-03 9.991865e-01 3.137765e+01 +9.991830e-01 -1.840283e-03 -4.037463e-02 -1.768976e+00 1.460769e-03 9.999545e-01 -9.427292e-03 -1.036363e+00 4.039014e-02 9.360611e-03 9.991401e-01 3.235714e+01 +9.991063e-01 -4.894794e-03 -4.198475e-02 -1.815834e+00 4.337365e-03 9.999014e-01 -1.335777e-02 -1.059789e+00 4.204599e-02 1.316373e-02 9.990289e-01 3.333631e+01 +9.990442e-01 -4.076714e-03 -4.352240e-02 -1.870663e+00 3.306848e-03 9.998370e-01 -1.774634e-02 -1.088016e+00 4.358766e-02 1.758545e-02 9.988948e-01 3.432021e+01 +9.989620e-01 -3.501086e-03 -4.541814e-02 -1.929780e+00 2.639355e-03 9.998156e-01 -1.901940e-02 -1.129880e+00 4.547635e-02 1.887978e-02 9.987869e-01 3.533097e+01 +9.989126e-01 -3.564847e-03 -4.648700e-02 -1.993748e+00 2.782576e-03 9.998536e-01 -1.688161e-02 -1.194548e+00 4.654037e-02 1.673390e-02 9.987762e-01 3.638751e+01 +9.988708e-01 -2.386257e-04 -4.750925e-02 -2.061112e+00 -4.151975e-04 9.999053e-01 -1.375168e-02 -1.249881e+00 4.750803e-02 1.375587e-02 9.987761e-01 3.742850e+01 +9.988085e-01 2.160348e-06 -4.880145e-02 -2.126953e+00 -6.257569e-04 9.999183e-01 -1.276297e-02 -1.305052e+00 4.879743e-02 1.277830e-02 9.987269e-01 3.847151e+01 +9.987592e-01 8.809214e-04 -4.979299e-02 -2.190967e+00 -1.403287e-03 9.999443e-01 -1.045676e-02 -1.349142e+00 4.978101e-02 1.051366e-02 9.987048e-01 3.950365e+01 +9.987569e-01 4.894213e-04 -4.984526e-02 -2.256115e+00 -8.210333e-04 9.999776e-01 -6.632571e-03 -1.393047e+00 4.984090e-02 6.665250e-03 9.987349e-01 4.053855e+01 +9.987132e-01 6.466500e-03 -5.030151e-02 -2.329940e+00 -6.722014e-03 9.999653e-01 -4.912121e-03 -1.426813e+00 5.026800e-02 5.243927e-03 9.987219e-01 4.156111e+01 +9.987143e-01 6.952179e-03 -5.021498e-02 -2.399728e+00 -7.192513e-03 9.999635e-01 -4.606971e-03 -1.460731e+00 5.018112e-02 4.962219e-03 9.987278e-01 4.258303e+01 +9.987083e-01 6.676282e-03 -5.037160e-02 -2.465214e+00 -7.006772e-03 9.999550e-01 -6.387280e-03 -1.489501e+00 5.032669e-02 6.731971e-03 9.987101e-01 4.359302e+01 +9.987013e-01 8.983148e-03 -5.015069e-02 -2.535885e+00 -9.456170e-03 9.999129e-01 -9.202712e-03 -1.522850e+00 5.006365e-02 9.664992e-03 9.986992e-01 4.459790e+01 +9.986535e-01 8.808468e-03 -5.112439e-02 -2.600016e+00 -9.296065e-03 9.999135e-01 -9.307503e-03 -1.559885e+00 5.103798e-02 9.770225e-03 9.986489e-01 4.559882e+01 +9.986012e-01 6.863746e-03 -5.242779e-02 -2.661881e+00 -7.280160e-03 9.999434e-01 -7.755765e-03 -1.593756e+00 5.237159e-02 8.126598e-03 9.985945e-01 4.659803e+01 +9.985540e-01 7.061951e-03 -5.329345e-02 -2.728914e+00 -7.431486e-03 9.999497e-01 -6.738977e-03 -1.629817e+00 5.324317e-02 7.125281e-03 9.985561e-01 4.759275e+01 +9.985154e-01 9.830435e-03 -5.357609e-02 -2.800794e+00 -1.032218e-02 9.999070e-01 -8.909522e-03 -1.664529e+00 5.348352e-02 9.449317e-03 9.985240e-01 4.857856e+01 +9.984686e-01 1.023790e-02 -5.436634e-02 -2.871336e+00 -1.103255e-02 9.998363e-01 -1.433651e-02 -1.697621e+00 5.421067e-02 1.491435e-02 9.984181e-01 4.955600e+01 +9.984385e-01 1.064895e-02 -5.483888e-02 -2.937935e+00 -1.149460e-02 9.998195e-01 -1.512829e-02 -1.729013e+00 5.466788e-02 1.573501e-02 9.983805e-01 5.053773e+01 +9.984274e-01 1.026893e-02 -5.511221e-02 -3.002463e+00 -1.093885e-02 9.998697e-01 -1.186763e-02 -1.766742e+00 5.498316e-02 1.245183e-02 9.984096e-01 5.151845e+01 +9.984356e-01 7.566176e-03 -5.540070e-02 -3.065844e+00 -8.064009e-03 9.999290e-01 -8.767995e-03 -1.798994e+00 5.533043e-02 9.201029e-03 9.984256e-01 5.249501e+01 +9.984285e-01 6.348755e-03 -5.568046e-02 -3.130185e+00 -6.799312e-03 9.999456e-01 -7.906116e-03 -1.830051e+00 5.562724e-02 8.272279e-03 9.984173e-01 5.346498e+01 +9.984326e-01 3.282949e-03 -5.587138e-02 -3.191520e+00 -3.779690e-03 9.999542e-01 -8.787440e-03 -1.858398e+00 5.583997e-02 8.984842e-03 9.983992e-01 5.442804e+01 +9.984068e-01 -1.460363e-04 -5.642638e-02 -3.248811e+00 -4.508913e-04 9.999441e-01 -1.056600e-02 -1.886487e+00 5.642476e-02 1.057461e-02 9.983508e-01 5.539178e+01 +9.983367e-01 -1.591214e-03 -5.763218e-02 -3.310922e+00 1.036802e-03 9.999529e-01 -9.648457e-03 -1.913841e+00 5.764481e-02 9.572654e-03 9.982912e-01 5.635039e+01 +9.982641e-01 -4.382863e-03 -5.873397e-02 -3.371514e+00 4.075329e-03 9.999773e-01 -5.354817e-03 -1.938229e+00 5.875611e-02 5.106161e-03 9.982593e-01 5.731251e+01 +9.982268e-01 -5.964740e-03 -5.922694e-02 -3.438994e+00 5.986946e-03 9.999820e-01 1.974663e-04 -1.956763e+00 5.922470e-02 -5.517038e-04 9.982445e-01 5.827400e+01 +9.982022e-01 -4.407760e-03 -5.977459e-02 -3.511313e+00 4.547914e-03 9.999872e-01 2.208854e-03 -1.975962e+00 5.976408e-02 -2.476732e-03 9.982094e-01 5.922540e+01 +9.981161e-01 -2.919496e-03 -6.128511e-02 -3.579193e+00 2.920554e-03 9.999957e-01 -7.231076e-05 -1.998111e+00 6.128506e-02 -1.068112e-04 9.981202e-01 6.016633e+01 +9.980242e-01 -1.762043e-03 -6.280674e-02 -3.641784e+00 1.227247e-03 9.999627e-01 -8.552514e-03 -2.021539e+00 6.281946e-02 8.458535e-03 9.979890e-01 6.109125e+01 +9.979547e-01 -9.592105e-04 -6.391830e-02 -3.703384e+00 5.024105e-05 9.998989e-01 -1.422089e-02 -2.049159e+00 6.392547e-02 1.418860e-02 9.978538e-01 6.200632e+01 +9.978643e-01 4.204986e-03 -6.518610e-02 -3.776035e+00 -5.092497e-03 9.998965e-01 -1.345487e-02 -2.078109e+00 6.512277e-02 1.375809e-02 9.977824e-01 6.291678e+01 +9.977905e-01 7.492613e-03 -6.601519e-02 -3.843940e+00 -8.206300e-03 9.999107e-01 -1.054641e-02 -2.112094e+00 6.593028e-02 1.106485e-02 9.977628e-01 6.381519e+01 +9.976764e-01 1.025448e-02 -6.735521e-02 -3.912602e+00 -1.087073e-02 9.999023e-01 -8.789172e-03 -2.145353e+00 6.725849e-02 9.500949e-03 9.976903e-01 6.469786e+01 +9.975909e-01 1.034502e-02 -6.859620e-02 -3.978228e+00 -1.103350e-02 9.998924e-01 -9.665437e-03 -2.173835e+00 6.848883e-02 1.039901e-02 9.975976e-01 6.556672e+01 +9.974616e-01 1.183547e-02 -7.021661e-02 -4.046625e+00 -1.248174e-02 9.998836e-01 -8.772233e-03 -2.201409e+00 7.010461e-02 9.626390e-03 9.974931e-01 6.642163e+01 +9.973396e-01 1.318380e-02 -7.169363e-02 -4.114442e+00 -1.380046e-02 9.998718e-01 -8.112825e-03 -2.230822e+00 7.157748e-02 9.080646e-03 9.973937e-01 6.726455e+01 +9.972258e-01 1.296774e-02 -7.329823e-02 -4.179994e+00 -1.352350e-02 9.998834e-01 -7.090915e-03 -2.258366e+00 7.319772e-02 8.062491e-03 9.972848e-01 6.809328e+01 +9.971241e-01 1.256612e-02 -7.473754e-02 -4.244856e+00 -1.307757e-02 9.998942e-01 -6.357728e-03 -2.283310e+00 7.464974e-02 7.316829e-03 9.971829e-01 6.890994e+01 +9.969894e-01 1.489953e-02 -7.609372e-02 -4.313021e+00 -1.525772e-02 9.998751e-01 -4.127928e-03 -2.307845e+00 7.602271e-02 5.276517e-03 9.970921e-01 6.971424e+01 +9.968772e-01 1.677181e-02 -7.716622e-02 -4.381935e+00 -1.677976e-02 9.998590e-01 5.454462e-04 -2.329476e+00 7.716449e-02 7.510882e-04 9.970180e-01 7.050799e+01 +9.966886e-01 1.928865e-02 -7.899331e-02 -4.445510e+00 -1.916694e-02 9.998136e-01 2.298764e-03 -2.355391e+00 7.902292e-02 -7.770902e-04 9.968724e-01 7.128437e+01 +9.964961e-01 2.232345e-02 -8.060564e-02 -4.514875e+00 -2.246983e-02 9.997471e-01 -9.091952e-04 -2.382091e+00 8.056495e-02 2.717205e-03 9.967456e-01 7.203735e+01 +9.963707e-01 2.284027e-02 -8.199948e-02 -4.580210e+00 -2.361073e-02 9.996856e-01 -8.438421e-03 -2.409731e+00 8.178096e-02 1.034386e-02 9.965966e-01 7.276791e+01 +9.962563e-01 2.164989e-02 -8.369451e-02 -4.644343e+00 -2.291184e-02 9.996374e-01 -1.414702e-02 -2.432982e+00 8.335788e-02 1.601165e-02 9.963910e-01 7.348065e+01 +9.962035e-01 2.236698e-02 -8.413330e-02 -4.709494e+00 -2.381956e-02 9.995833e-01 -1.630112e-02 -2.459523e+00 8.373364e-02 1.824325e-02 9.963211e-01 7.417539e+01 +9.960873e-01 2.480834e-02 -8.482128e-02 -4.775730e+00 -2.599143e-02 9.995793e-01 -1.287207e-02 -2.490277e+00 8.446625e-02 1.502633e-02 9.963130e-01 7.485147e+01 +9.959529e-01 2.606958e-02 -8.601342e-02 -4.837515e+00 -2.697536e-02 9.995920e-01 -9.385091e-03 -2.525955e+00 8.573366e-02 1.166735e-02 9.962497e-01 7.550744e+01 +9.959075e-01 2.291063e-02 -8.742661e-02 -4.891889e+00 -2.409575e-02 9.996312e-01 -1.252425e-02 -2.556654e+00 8.710742e-02 1.457961e-02 9.960922e-01 7.613828e+01 +9.960426e-01 1.503549e-02 -8.759638e-02 -4.937677e+00 -1.662384e-02 9.997098e-01 -1.743140e-02 -2.585469e+00 8.730887e-02 1.881860e-02 9.960035e-01 7.675010e+01 +9.961635e-01 1.044107e-02 -8.688679e-02 -4.985837e+00 -1.249941e-02 9.996532e-01 -2.317957e-02 -2.616742e+00 8.661463e-02 2.417667e-02 9.959484e-01 7.734409e+01 +9.963973e-01 1.211154e-02 -8.393973e-02 -5.039038e+00 -1.414999e-02 9.996182e-01 -2.373245e-02 -2.646048e+00 8.362024e-02 2.483469e-02 9.961881e-01 7.792534e+01 +9.966394e-01 1.770654e-02 -7.997749e-02 -5.092732e+00 -1.941041e-02 9.995998e-01 -2.057726e-02 -2.675699e+00 7.958113e-02 2.206050e-02 9.965842e-01 7.849464e+01 +9.970121e-01 1.664848e-02 -7.543122e-02 -5.133801e+00 -1.801913e-02 9.996840e-01 -1.752686e-02 -2.701840e+00 7.511558e-02 1.883369e-02 9.969969e-01 7.904953e+01 +9.974633e-01 1.217037e-02 -7.013516e-02 -5.159772e+00 -1.315774e-02 9.998205e-01 -1.363335e-02 -2.729207e+00 6.995665e-02 1.452158e-02 9.974443e-01 7.959230e+01 +9.980240e-01 7.887781e-03 -6.233726e-02 -5.183357e+00 -8.483336e-03 9.999208e-01 -9.294846e-03 -2.756800e+00 6.225900e-02 9.805306e-03 9.980118e-01 8.012304e+01 +9.985955e-01 1.068615e-02 -5.189267e-02 -5.208269e+00 -1.122407e-02 9.998861e-01 -1.008572e-02 -2.780022e+00 5.177898e-02 1.065400e-02 9.986017e-01 8.063455e+01 +9.991827e-01 1.624761e-02 -3.701415e-02 -5.235209e+00 -1.664974e-02 9.998054e-01 -1.058172e-02 -2.801727e+00 3.683502e-02 1.118935e-02 9.992587e-01 8.113538e+01 +9.995878e-01 2.136933e-02 -1.917552e-02 -5.248892e+00 -2.156744e-02 9.997155e-01 -1.018473e-02 -2.822088e+00 1.895242e-02 1.059410e-02 9.997642e-01 8.162286e+01 +9.997985e-01 1.993349e-02 2.394767e-03 -5.236828e+00 -1.990872e-02 9.997522e-01 -9.958356e-03 -2.839863e+00 -2.592678e-03 9.908671e-03 9.999475e-01 8.209701e+01 +9.994836e-01 1.619025e-02 2.775764e-02 -5.207469e+00 -1.594000e-02 9.998305e-01 -9.213406e-03 -2.859306e+00 -2.790210e-02 8.766190e-03 9.995722e-01 8.255594e+01 +9.982814e-01 1.472502e-02 5.672377e-02 -5.163543e+00 -1.430176e-02 9.998668e-01 -7.860647e-03 -2.878004e+00 -5.683196e-02 7.035887e-03 9.983589e-01 8.300846e+01 +9.959138e-01 1.420072e-02 8.918593e-02 -5.105620e+00 -1.367050e-02 9.998851e-01 -6.553178e-03 -2.895751e+00 -8.926873e-02 5.307184e-03 9.959934e-01 8.345454e+01 +9.920007e-01 1.389449e-02 1.254661e-01 -5.029560e+00 -1.324753e-02 9.998943e-01 -5.989348e-03 -2.911918e+00 -1.255360e-01 4.279320e-03 9.920798e-01 8.388530e+01 +9.859899e-01 1.389745e-02 1.662252e-01 -4.934649e+00 -1.302694e-02 9.998951e-01 -6.326123e-03 -2.926167e+00 -1.662957e-01 4.072087e-03 9.860675e-01 8.431338e+01 +9.775146e-01 1.346779e-02 2.104374e-01 -4.817297e+00 -1.236226e-02 9.999020e-01 -6.568159e-03 -2.942364e+00 -2.105053e-01 3.818988e-03 9.775852e-01 8.472869e+01 +9.660755e-01 1.536344e-02 2.578024e-01 -4.680938e+00 -1.364848e-02 9.998712e-01 -8.440597e-03 -2.961855e+00 -2.578989e-01 4.635642e-03 9.661607e-01 8.511820e+01 +9.507397e-01 1.607587e-02 3.095733e-01 -4.519193e+00 -1.319900e-02 9.998480e-01 -1.138540e-02 -2.980545e+00 -3.097093e-01 6.738488e-03 9.508074e-01 8.550171e+01 +9.313823e-01 1.599263e-02 3.636913e-01 -4.336344e+00 -1.189395e-02 9.998380e-01 -1.350660e-02 -2.995233e+00 -3.638483e-01 8.254080e-03 9.314216e-01 8.585373e+01 +9.076306e-01 1.642664e-02 4.194484e-01 -4.130089e+00 -1.094447e-02 9.998204e-01 -1.547307e-02 -3.006846e+00 -4.196272e-01 9.453184e-03 9.076472e-01 8.620001e+01 +8.794214e-01 1.652575e-02 4.757573e-01 -3.903866e+00 -9.195858e-03 9.998005e-01 -1.773051e-02 -3.018353e+00 -4.759554e-01 1.121759e-02 8.793978e-01 8.652588e+01 +8.470020e-01 1.463490e-02 5.313884e-01 -3.656380e+00 -4.922887e-03 9.997940e-01 -1.968841e-02 -3.030941e+00 -5.315670e-01 1.406015e-02 8.468995e-01 8.681210e+01 +8.111527e-01 1.400217e-02 5.846668e-01 -3.393066e+00 -2.514888e-03 9.997876e-01 -2.045480e-02 -3.048142e+00 -5.848290e-01 1.512159e-02 8.110156e-01 8.709558e+01 +7.722941e-01 1.213857e-02 6.351492e-01 -3.115393e+00 -7.665609e-05 9.998192e-01 -1.901471e-02 -3.063358e+00 -6.352652e-01 1.463625e-02 7.721553e-01 8.734503e+01 +7.306835e-01 1.139090e-02 6.826214e-01 -2.817803e+00 -2.276654e-04 9.998648e-01 -1.644104e-02 -3.074584e+00 -6.827163e-01 1.185778e-02 7.305872e-01 8.759401e+01 +6.869081e-01 1.002390e-02 7.266752e-01 -2.508137e+00 1.642222e-03 9.998809e-01 -1.534491e-02 -3.084460e+00 -7.267424e-01 1.173390e-02 6.868098e-01 8.782010e+01 +6.415606e-01 8.605910e-03 7.670241e-01 -2.182602e+00 5.801600e-03 9.998540e-01 -1.607086e-02 -3.093149e+00 -7.670504e-01 1.476039e-02 6.414170e-01 8.800813e+01 +5.961032e-01 5.416591e-03 8.028896e-01 -1.847638e+00 1.299442e-02 9.997812e-01 -1.639257e-02 -3.103538e+00 -8.028026e-01 2.020475e-02 5.959023e-01 8.818799e+01 +5.506435e-01 6.831839e-03 8.347126e-01 -1.511055e+00 1.267694e-02 9.997827e-01 -1.654562e-02 -3.116572e+00 -8.346443e-01 1.969233e-02 5.504372e-01 8.834349e+01 +5.045001e-01 9.750747e-03 8.633566e-01 -1.165582e+00 8.934955e-03 9.998237e-01 -1.651313e-02 -3.127427e+00 -8.633654e-01 1.604492e-02 5.043240e-01 8.850204e+01 +4.602983e-01 1.148164e-02 8.876901e-01 -8.110714e-01 8.704640e-03 9.998099e-01 -1.744550e-02 -3.138031e+00 -8.877216e-01 1.575715e-02 4.601108e-01 8.864159e+01 +4.188673e-01 9.627242e-03 9.079964e-01 -4.500223e-01 1.561927e-02 9.997194e-01 -1.780508e-02 -3.146259e+00 -9.079131e-01 2.164020e-02 4.185994e-01 8.874795e+01 +3.806252e-01 1.378826e-03 9.247284e-01 -7.268361e-02 3.173796e-02 9.993902e-01 -1.455374e-02 -3.150458e+00 -9.241845e-01 3.488851e-02 3.803494e-01 8.883995e+01 +3.461082e-01 -2.337058e-03 9.381917e-01 3.020916e-01 3.764494e-02 9.992261e-01 -1.139850e-02 -3.156586e+00 -9.374390e-01 3.926327e-02 3.459283e-01 8.893047e+01 +3.138409e-01 1.002432e-03 9.494751e-01 6.763450e-01 3.611653e-02 9.992631e-01 -1.299301e-02 -3.166835e+00 -9.487884e-01 3.836947e-02 3.135734e-01 8.902315e+01 +2.833112e-01 8.752363e-03 9.589881e-01 1.050891e+00 2.492263e-02 9.995534e-01 -1.648542e-02 -3.185174e+00 -9.587041e-01 2.857100e-02 2.829665e-01 8.912503e+01 +2.551133e-01 1.327093e-02 9.668201e-01 1.434583e+00 1.946154e-02 9.996327e-01 -1.885662e-02 -3.205997e+00 -9.667153e-01 2.362638e-02 2.547613e-01 8.921056e+01 +2.298762e-01 1.514276e-02 9.731021e-01 1.832910e+00 2.080734e-02 9.995739e-01 -2.047003e-02 -3.222114e+00 -9.729974e-01 2.495324e-02 2.294632e-01 8.927715e+01 +2.067350e-01 1.580712e-02 9.782693e-01 2.240743e+00 2.747050e-02 9.993815e-01 -2.195352e-02 -3.234217e+00 -9.780112e-01 3.141210e-02 2.061729e-01 8.932950e+01 +1.870149e-01 2.174817e-02 9.821163e-01 2.662750e+00 3.631700e-02 9.989184e-01 -2.903574e-02 -3.232193e+00 -9.816855e-01 4.109762e-02 1.860228e-01 8.937210e+01 +1.677054e-01 2.973015e-02 9.853888e-01 3.089762e+00 3.891920e-02 9.985663e-01 -3.675147e-02 -3.233114e+00 -9.850686e-01 4.451395e-02 1.663079e-01 8.941899e+01 +1.501195e-01 3.105637e-02 9.881800e-01 3.536770e+00 3.662397e-02 9.986458e-01 -3.694904e-02 -3.247013e+00 -9.879892e-01 4.173784e-02 1.487788e-01 8.947222e+01 +1.346625e-01 2.612444e-02 9.905471e-01 4.002128e+00 3.409387e-02 9.989383e-01 -3.098074e-02 -3.269703e+00 -9.903048e-01 3.794352e-02 1.336289e-01 8.952059e+01 +1.200339e-01 2.244059e-02 9.925162e-01 4.475771e+00 3.438479e-02 9.990507e-01 -2.674681e-02 -3.292077e+00 -9.921741e-01 3.733797e-02 1.191484e-01 8.955606e+01 +1.066450e-01 2.015680e-02 9.940929e-01 4.962461e+00 3.689254e-02 9.990258e-01 -2.421462e-02 -3.311658e+00 -9.936124e-01 3.925697e-02 1.057975e-01 8.958341e+01 +9.481660e-02 1.910255e-02 9.953115e-01 5.460049e+00 4.091002e-02 9.988965e-01 -2.306858e-02 -3.327578e+00 -9.946538e-01 4.290548e-02 9.393048e-02 8.960332e+01 +8.451437e-02 1.970806e-02 9.962274e-01 5.974572e+00 4.433756e-02 9.987397e-01 -2.351912e-02 -3.344693e+00 -9.954353e-01 4.615798e-02 8.353405e-02 8.962101e+01 +7.611140e-02 2.033196e-02 9.968920e-01 6.504623e+00 4.662512e-02 9.986258e-01 -2.392709e-02 -3.362740e+00 -9.960086e-01 4.830132e-02 7.505883e-02 8.963826e+01 +7.011217e-02 2.055161e-02 9.973274e-01 7.050381e+00 4.845902e-02 9.985372e-01 -2.398322e-02 -3.379767e+00 -9.963613e-01 5.001101e-02 6.901370e-02 8.965473e+01 +6.433620e-02 2.169879e-02 9.976924e-01 7.614093e+00 4.999818e-02 9.984379e-01 -2.493915e-02 -3.394968e+00 -9.966749e-01 5.148728e-02 6.315079e-02 8.967153e+01 +5.805224e-02 2.266708e-02 9.980562e-01 8.197957e+00 5.045707e-02 9.983978e-01 -2.560970e-02 -3.409306e+00 -9.970376e-01 5.184568e-02 5.681551e-02 8.968785e+01 +5.340714e-02 2.263529e-02 9.983163e-01 8.800912e+00 5.292689e-02 9.982736e-01 -2.546577e-02 -3.426200e+00 -9.971692e-01 5.419782e-02 5.211692e-02 8.970167e+01 +4.996154e-02 2.243890e-02 9.984991e-01 9.420230e+00 5.465687e-02 9.981880e-01 -2.516676e-02 -3.442284e+00 -9.972544e-01 5.583219e-02 4.864457e-02 8.970786e+01 +4.649404e-02 2.206005e-02 9.986750e-01 1.005978e+01 5.576839e-02 9.981395e-01 -2.464457e-02 -3.460292e+00 -9.973606e-01 5.684031e-02 4.517728e-02 8.971666e+01 +4.330615e-02 2.144658e-02 9.988317e-01 1.071458e+01 5.731411e-02 9.980697e-01 -2.391518e-02 -3.477648e+00 -9.974165e-01 5.828281e-02 4.199336e-02 8.971954e+01 +4.207275e-02 2.108560e-02 9.988921e-01 1.138837e+01 6.197780e-02 9.977967e-01 -2.367295e-02 -3.495197e+00 -9.971903e-01 6.290510e-02 4.067321e-02 8.972145e+01 +4.227179e-02 2.071974e-02 9.988913e-01 1.207462e+01 6.595748e-02 9.975460e-01 -2.348308e-02 -3.511618e+00 -9.969266e-01 6.687701e-02 4.080144e-02 8.972018e+01 +4.410340e-02 2.054931e-02 9.988156e-01 1.278190e+01 6.780199e-02 9.974216e-01 -2.351448e-02 -3.529809e+00 -9.967235e-01 6.875874e-02 4.259640e-02 8.972729e+01 +4.733313e-02 2.077681e-02 9.986631e-01 1.350501e+01 7.020740e-02 9.972418e-01 -2.407483e-02 -3.549541e+00 -9.964088e-01 7.125306e-02 4.574389e-02 8.973868e+01 +5.107260e-02 2.062413e-02 9.984820e-01 1.424395e+01 7.097170e-02 9.971840e-01 -2.422755e-02 -3.570045e+00 -9.961699e-01 7.210131e-02 4.946505e-02 8.975239e+01 +5.485120e-02 1.873660e-02 9.983188e-01 1.500260e+01 7.237751e-02 9.971191e-01 -2.269077e-02 -3.595307e+00 -9.958678e-01 7.350043e-02 5.333707e-02 8.977631e+01 +5.870203e-02 1.722669e-02 9.981269e-01 1.577368e+01 7.228987e-02 9.971527e-01 -2.146141e-02 -3.621398e+00 -9.956546e-01 7.341427e-02 5.728957e-02 8.980526e+01 +6.263966e-02 1.506436e-02 9.979225e-01 1.656055e+01 6.951846e-02 9.973916e-01 -1.942003e-02 -3.645849e+00 -9.956121e-01 7.059048e-02 6.142902e-02 8.984339e+01 +6.659830e-02 1.396403e-02 9.976822e-01 1.735473e+01 6.848000e-02 9.974803e-01 -1.853246e-02 -3.669719e+00 -9.954271e-01 6.955549e-02 6.547424e-02 8.988363e+01 +7.057071e-02 1.479215e-02 9.973971e-01 1.815651e+01 6.595721e-02 9.976326e-01 -1.946245e-02 -3.696455e+00 -9.953237e-01 6.715900e-02 6.942799e-02 8.992948e+01 +7.390613e-02 1.816167e-02 9.970998e-01 1.895996e+01 6.387777e-02 9.976948e-01 -2.290720e-02 -3.726996e+00 -9.952173e-01 6.538548e-02 7.257563e-02 8.997884e+01 +7.513596e-02 2.442768e-02 9.968741e-01 1.976819e+01 5.827767e-02 9.978836e-01 -2.884490e-02 -3.758629e+00 -9.954688e-01 6.026278e-02 7.355335e-02 9.003338e+01 +7.474794e-02 2.749119e-02 9.968235e-01 2.058193e+01 5.566893e-02 9.979460e-01 -3.169656e-02 -3.789412e+00 -9.956473e-01 5.786133e-02 7.306400e-02 9.008278e+01 +7.476584e-02 2.757564e-02 9.968198e-01 2.139947e+01 5.324229e-02 9.980814e-01 -3.160395e-02 -3.828201e+00 -9.957787e-01 5.543585e-02 7.315419e-02 9.013241e+01 +7.451993e-02 2.494887e-02 9.969074e-01 2.221735e+01 5.043155e-02 9.983135e-01 -2.875388e-02 -3.869642e+00 -9.959434e-01 5.241831e-02 7.313604e-02 9.018269e+01 +7.437195e-02 2.433854e-02 9.969336e-01 2.303432e+01 5.132069e-02 9.982840e-01 -2.820007e-02 -3.908789e+00 -9.959091e-01 5.326060e-02 7.299525e-02 9.022769e+01 +7.447614e-02 2.322760e-02 9.969523e-01 2.385148e+01 4.903232e-02 9.984342e-01 -2.692503e-02 -3.948711e+00 -9.960166e-01 5.088814e-02 7.322062e-02 9.027374e+01 +7.410208e-02 2.327013e-02 9.969792e-01 2.466660e+01 4.734121e-02 9.985185e-01 -2.682478e-02 -3.991884e+00 -9.961263e-01 4.918596e-02 7.289066e-02 9.031732e+01 +7.412396e-02 2.412341e-02 9.969572e-01 2.547837e+01 4.481095e-02 9.986170e-01 -2.749528e-02 -4.031552e+00 -9.962417e-01 4.671265e-02 7.294045e-02 9.036500e+01 +7.273598e-02 2.538877e-02 9.970281e-01 2.628880e+01 4.182689e-02 9.987188e-01 -2.848322e-02 -4.070675e+00 -9.964737e-01 4.377433e-02 7.158085e-02 9.041153e+01 +6.992106e-02 2.548140e-02 9.972271e-01 2.710009e+01 3.897825e-02 9.988405e-01 -2.825561e-02 -4.110043e+00 -9.967907e-01 4.084581e-02 6.884676e-02 9.045782e+01 +6.591466e-02 2.417630e-02 9.975324e-01 2.790992e+01 3.637502e-02 9.989837e-01 -2.661506e-02 -4.149285e+00 -9.971620e-01 3.803957e-02 6.496825e-02 9.049922e+01 +6.089788e-02 2.167742e-02 9.979086e-01 2.872180e+01 3.431028e-02 9.991278e-01 -2.379771e-02 -4.189372e+00 -9.975541e-01 3.568775e-02 6.010101e-02 9.053737e+01 +5.454557e-02 1.931204e-02 9.983245e-01 2.953344e+01 3.223633e-02 9.992577e-01 -2.109140e-02 -4.227712e+00 -9.979907e-01 3.333275e-02 5.388253e-02 9.056802e+01 +4.700058e-02 1.930296e-02 9.987084e-01 3.034032e+01 3.172229e-02 9.992801e-01 -2.080691e-02 -4.264420e+00 -9.983910e-01 3.265924e-02 4.635441e-02 9.058889e+01 +3.816210e-02 2.033872e-02 9.990646e-01 3.114204e+01 3.120822e-02 9.992809e-01 -2.153522e-02 -4.298961e+00 -9.987841e-01 3.200084e-02 3.749992e-02 9.060259e+01 +2.806847e-02 2.112184e-02 9.993829e-01 3.194324e+01 3.180308e-02 9.992517e-01 -2.201229e-02 -4.332533e+00 -9.990999e-01 3.240129e-02 2.737573e-02 9.060409e+01 +1.781185e-02 2.023573e-02 9.996366e-01 3.274069e+01 3.296529e-02 9.992397e-01 -2.081509e-02 -4.366800e+00 -9.992977e-01 3.332406e-02 1.713123e-02 9.059833e+01 +6.968081e-03 1.874427e-02 9.998001e-01 3.353267e+01 3.197931e-02 9.993087e-01 -1.895795e-02 -4.400925e+00 -9.994642e-01 3.210501e-02 6.363835e-03 9.058651e+01 +-4.213761e-03 1.806636e-02 9.998279e-01 3.432424e+01 3.337770e-02 9.992822e-01 -1.791584e-02 -4.430514e+00 -9.994339e-01 3.329646e-02 -4.813748e-03 9.056241e+01 +-1.536171e-02 1.808549e-02 9.997185e-01 3.511039e+01 3.379189e-02 9.992746e-01 -1.755822e-02 -4.460151e+00 -9.993108e-01 3.351264e-02 -1.596171e-02 9.052962e+01 +-2.648072e-02 1.872506e-02 9.994740e-01 3.588915e+01 3.400306e-02 9.992628e-01 -1.782022e-02 -4.490465e+00 -9.990708e-01 3.351327e-02 -2.709790e-02 9.049003e+01 +-3.725612e-02 1.985515e-02 9.991085e-01 3.666363e+01 3.374649e-02 9.992573e-01 -1.859973e-02 -4.519810e+00 -9.987357e-01 3.302344e-02 -3.789849e-02 9.044253e+01 +-4.758921e-02 2.088992e-02 9.986486e-01 3.743083e+01 3.458039e-02 9.992164e-01 -1.925393e-02 -4.548257e+00 -9.982682e-01 3.361737e-02 -4.827430e-02 9.038673e+01 +-5.718399e-02 2.164931e-02 9.981289e-01 3.818958e+01 3.548667e-02 9.991771e-01 -1.963898e-02 -4.577147e+00 -9.977327e-01 3.429723e-02 -5.790519e-02 9.032361e+01 +-6.683215e-02 2.208670e-02 9.975198e-01 3.894049e+01 3.617941e-02 9.991511e-01 -1.969887e-02 -4.607065e+00 -9.971080e-01 3.477315e-02 -6.757450e-02 9.025165e+01 +-7.637784e-02 2.219893e-02 9.968318e-01 3.968363e+01 3.679438e-02 9.991339e-01 -1.943100e-02 -4.635152e+00 -9.963998e-01 3.519370e-02 -7.712847e-02 9.017629e+01 +-8.502155e-02 2.197809e-02 9.961367e-01 4.041876e+01 3.826025e-02 9.990913e-01 -1.877773e-02 -4.664020e+00 -9.956442e-01 3.651592e-02 -8.578518e-02 9.009176e+01 +-9.242347e-02 2.068885e-02 9.955049e-01 4.114574e+01 3.988263e-02 9.990587e-01 -1.705998e-02 -4.692210e+00 -9.949207e-01 3.812660e-02 -9.316159e-02 9.000290e+01 +-9.778459e-02 1.924550e-02 9.950215e-01 4.186324e+01 4.272773e-02 9.989723e-01 -1.512291e-02 -4.721760e+00 -9.942899e-01 4.103621e-02 -9.850640e-02 8.991031e+01 +-1.017231e-01 1.749021e-02 9.946590e-01 4.257483e+01 4.579707e-02 9.988677e-01 -1.288059e-02 -4.746579e+00 -9.937580e-01 4.424220e-02 -1.024090e-01 8.981611e+01 +-1.045887e-01 1.626385e-02 9.943826e-01 4.327463e+01 4.754502e-02 9.988048e-01 -1.133542e-02 -4.770015e+00 -9.933784e-01 4.609237e-02 -1.052369e-01 8.972399e+01 +-1.064238e-01 1.554435e-02 9.941994e-01 4.395946e+01 4.803206e-02 9.987908e-01 -1.047457e-02 -4.793116e+00 -9.931600e-01 4.663869e-02 -1.070417e-01 8.963442e+01 +-1.074152e-01 1.566224e-02 9.940909e-01 4.463116e+01 4.845889e-02 9.987700e-01 -1.049981e-02 -4.815263e+00 -9.930325e-01 4.704469e-02 -1.080420e-01 8.954649e+01 +-1.066568e-01 1.685791e-02 9.941530e-01 4.528497e+01 4.949480e-02 9.987067e-01 -1.162513e-02 -4.837060e+00 -9.930632e-01 4.796549e-02 -1.073532e-01 8.946022e+01 +-1.039437e-01 1.811139e-02 9.944183e-01 4.592280e+01 5.064114e-02 9.986336e-01 -1.289480e-02 -4.858683e+00 -9.932931e-01 4.901813e-02 -1.047188e-01 8.937856e+01 +-9.900439e-02 1.888729e-02 9.949078e-01 4.654259e+01 5.067771e-02 9.986181e-01 -1.391474e-02 -4.880596e+00 -9.937957e-01 4.904201e-02 -9.982473e-02 8.930650e+01 +-9.158105e-02 1.937642e-02 9.956091e-01 4.714397e+01 4.996096e-02 9.986409e-01 -1.483978e-02 -4.902936e+00 -9.945435e-01 4.838254e-02 -9.242464e-02 8.924451e+01 +-8.067749e-02 1.959419e-02 9.965477e-01 4.772631e+01 4.891325e-02 9.986800e-01 -1.567626e-02 -4.926346e+00 -9.955393e-01 4.747965e-02 -8.152941e-02 8.919325e+01 +-6.719239e-02 1.967589e-02 9.975460e-01 4.828879e+01 4.841075e-02 9.986922e-01 -1.643767e-02 -4.950044e+00 -9.965648e-01 4.718745e-02 -6.805703e-02 8.915280e+01 +-5.072110e-02 2.086047e-02 9.984950e-01 4.883147e+01 4.714178e-02 9.987174e-01 -1.847044e-02 -4.973119e+00 -9.975996e-01 4.613398e-02 -5.163944e-02 8.912695e+01 +-3.001449e-02 2.349433e-02 9.992733e-01 4.936647e+01 4.565938e-02 9.987123e-01 -2.210970e-02 -5.001409e+00 -9.985060e-01 4.496258e-02 -3.104857e-02 8.912113e+01 +-6.012730e-03 2.652506e-02 9.996301e-01 4.989376e+01 4.359308e-02 9.987047e-01 -2.623831e-02 -5.029978e+00 -9.990312e-01 4.341918e-02 -7.161249e-03 8.913018e+01 +2.161174e-02 2.824599e-02 9.993674e-01 5.041670e+01 4.145875e-02 9.987156e-01 -2.912415e-02 -5.056479e+00 -9.989064e-01 4.206193e-02 2.041294e-02 8.914842e+01 +5.426707e-02 2.797547e-02 9.981345e-01 5.093941e+01 3.943816e-02 9.987674e-01 -3.013741e-02 -5.083698e+00 -9.977473e-01 4.100004e-02 5.309688e-02 8.919154e+01 +9.163408e-02 2.556617e-02 9.954645e-01 5.145679e+01 3.803664e-02 9.988509e-01 -2.915448e-02 -5.111122e+00 -9.950660e-01 4.053566e-02 9.055633e-02 8.925586e+01 +1.328286e-01 2.208643e-02 9.908929e-01 5.196384e+01 3.578779e-02 9.989928e-01 -2.706431e-02 -5.139956e+00 -9.904927e-01 3.905678e-02 1.319044e-01 8.933556e+01 +1.770684e-01 1.742295e-02 9.840444e-01 5.246407e+01 3.263936e-02 9.991893e-01 -2.356422e-02 -5.168307e+00 -9.836571e-01 3.629105e-02 1.763561e-01 8.945093e+01 +2.245365e-01 1.412619e-02 9.743633e-01 5.295984e+01 2.803140e-02 9.993875e-01 -2.094867e-02 -5.197886e+00 -9.740624e-01 3.201650e-02 2.240030e-01 8.959271e+01 +2.747903e-01 1.261810e-02 9.614214e-01 5.343056e+01 2.372844e-02 9.995203e-01 -1.990011e-02 -5.228395e+00 -9.612113e-01 2.828138e-02 2.743591e-01 8.975037e+01 +3.285181e-01 1.239074e-02 9.444164e-01 5.388945e+01 2.179716e-02 9.995481e-01 -2.069628e-02 -5.254058e+00 -9.442461e-01 2.738469e-02 3.280996e-01 8.994526e+01 +3.855813e-01 1.285007e-02 9.225844e-01 5.433154e+01 2.342307e-02 9.994444e-01 -2.370995e-02 -5.281038e+00 -9.223765e-01 3.075187e-02 3.850661e-01 9.016419e+01 +4.443980e-01 1.583459e-02 8.956895e-01 5.473889e+01 2.326734e-02 9.993024e-01 -2.921047e-02 -5.307765e+00 -8.955272e-01 3.382138e-02 4.437196e-01 9.038860e+01 +5.031692e-01 1.924202e-02 8.639737e-01 5.513319e+01 2.368969e-02 9.990692e-01 -3.604743e-02 -5.336870e+00 -8.638631e-01 3.860521e-02 5.022450e-01 9.066097e+01 +5.605451e-01 2.352431e-02 8.277897e-01 5.549149e+01 1.882847e-02 9.989760e-01 -4.113899e-02 -5.362113e+00 -8.279098e-01 3.864626e-02 5.595281e-01 9.094160e+01 +6.156356e-01 2.682680e-02 7.875742e-01 5.583593e+01 1.377101e-02 9.989015e-01 -4.478976e-02 -5.389737e+00 -7.879106e-01 3.841985e-02 6.145899e-01 9.127112e+01 +6.681238e-01 2.787792e-02 7.435277e-01 5.615845e+01 1.109601e-02 9.988134e-01 -4.742037e-02 -5.418165e+00 -7.439674e-01 3.993286e-02 6.670216e-01 9.162030e+01 +7.170289e-01 2.626286e-02 6.965485e-01 5.644855e+01 9.622649e-03 9.988218e-01 -4.756544e-02 -5.448053e+00 -6.969770e-01 4.080842e-02 7.159313e-01 9.196615e+01 +7.622181e-01 2.264837e-02 6.469240e-01 5.672244e+01 6.903411e-03 9.990465e-01 -4.310967e-02 -5.479109e+00 -6.472835e-01 3.732494e-02 7.613349e-01 9.235602e+01 +8.038727e-01 1.798655e-02 5.945294e-01 5.696793e+01 4.662333e-03 9.993214e-01 -3.653692e-02 -5.510534e+00 -5.947831e-01 3.214292e-02 8.032433e-01 9.276492e+01 +8.408561e-01 1.529420e-02 5.410427e-01 5.717528e+01 1.699980e-03 9.995211e-01 -3.089649e-02 -5.539453e+00 -5.412561e-01 2.689926e-02 8.404274e-01 9.317127e+01 +8.725465e-01 1.221869e-02 4.883783e-01 5.737005e+01 -4.511298e-04 9.997069e-01 -2.420557e-02 -5.564449e+00 -4.885309e-01 2.090016e-02 8.722962e-01 9.361062e+01 +8.986353e-01 1.248378e-02 4.385189e-01 5.753992e+01 -4.757360e-03 9.998135e-01 -1.871374e-02 -5.590987e+00 -4.386707e-01 1.473063e-02 8.985271e-01 9.406120e+01 +9.196509e-01 1.403544e-02 3.924860e-01 5.768438e+01 -8.629860e-03 9.998421e-01 -1.553372e-02 -5.612666e+00 -3.926420e-01 1.089850e-02 9.196268e-01 9.450798e+01 +9.354383e-01 2.009299e-02 3.529185e-01 5.781242e+01 -1.677232e-02 9.997816e-01 -1.246502e-02 -5.628018e+00 -3.530919e-01 5.740989e-03 9.355710e-01 9.498160e+01 +9.478455e-01 2.467478e-02 3.177737e-01 5.792720e+01 -2.141611e-02 9.996761e-01 -1.374446e-02 -5.638494e+00 -3.180099e-01 6.222142e-03 9.480669e-01 9.544688e+01 +9.575689e-01 2.703186e-02 2.869340e-01 5.804176e+01 -2.398075e-02 9.996123e-01 -1.414319e-02 -5.648502e+00 -2.872051e-01 6.662179e-03 9.578459e-01 9.592488e+01 +9.641795e-01 2.129999e-02 2.643943e-01 5.816224e+01 -1.820981e-02 9.997343e-01 -1.413344e-02 -5.661977e+00 -2.646251e-01 8.812601e-03 9.643110e-01 9.640217e+01 +9.684686e-01 1.824212e-02 2.484671e-01 5.827731e+01 -1.542480e-02 9.997928e-01 -1.328105e-02 -5.680139e+00 -2.486579e-01 9.029716e-03 9.685492e-01 9.688437e+01 +9.715089e-01 2.227795e-02 2.359539e-01 5.838327e+01 -1.962485e-02 9.997151e-01 -1.358695e-02 -5.692607e+00 -2.361893e-01 8.569285e-03 9.716692e-01 9.738035e+01 +9.736636e-01 2.774803e-02 2.262947e-01 5.848694e+01 -2.542298e-02 9.995898e-01 -1.318291e-02 -5.698710e+00 -2.265677e-01 7.082631e-03 9.739696e-01 9.788806e+01 +9.747832e-01 3.487426e-02 2.204121e-01 5.858946e+01 -3.249051e-02 9.993678e-01 -1.443214e-02 -5.712881e+00 -2.207760e-01 6.906903e-03 9.753000e-01 9.840345e+01 +9.751968e-01 4.130161e-02 2.174521e-01 5.869673e+01 -3.824103e-02 9.991016e-01 -1.826602e-02 -5.732310e+00 -2.180111e-01 9.497371e-03 9.759000e-01 9.892830e+01 +9.753059e-01 4.290914e-02 2.166502e-01 5.881399e+01 -3.946071e-02 9.990165e-01 -2.022010e-02 -5.756138e+00 -2.173047e-01 1.117161e-02 9.760398e-01 9.946087e+01 +9.748460e-01 4.206880e-02 2.188736e-01 5.894036e+01 -3.790111e-02 9.990119e-01 -2.320746e-02 -5.778487e+00 -2.196337e-01 1.432814e-02 9.754771e-01 1.000024e+02 +9.740428e-01 4.025106e-02 2.227568e-01 5.907451e+01 -3.435475e-02 9.989508e-01 -3.028340e-02 -5.797891e+00 -2.237420e-01 2.184457e-02 9.744035e-01 1.005505e+02 +9.731349e-01 4.014621e-02 2.267087e-01 5.920976e+01 -3.294070e-02 9.988274e-01 -3.547901e-02 -5.818562e+00 -2.278672e-01 2.705792e-02 9.733161e-01 1.011106e+02 +9.718871e-01 4.493798e-02 2.311193e-01 5.934323e+01 -3.793231e-02 9.986787e-01 -3.466905e-02 -5.844770e+00 -2.323718e-01 2.492751e-02 9.723075e-01 1.016926e+02 +9.703452e-01 4.844800e-02 2.368188e-01 5.947979e+01 -4.230693e-02 9.986252e-01 -3.094804e-02 -5.872668e+00 -2.379925e-01 2.001121e-02 9.710608e-01 1.022853e+02 +9.692780e-01 4.541030e-02 2.417398e-01 5.963546e+01 -4.019101e-02 9.988410e-01 -2.648059e-02 -5.900971e+00 -2.426622e-01 1.595128e-02 9.699797e-01 1.028883e+02 +9.685083e-01 4.085678e-02 2.456065e-01 5.979880e+01 -3.690930e-02 9.991051e-01 -2.065604e-02 -5.928075e+00 -2.462306e-01 1.094038e-02 9.691495e-01 1.034998e+02 +9.677060e-01 3.817011e-02 2.491753e-01 5.996454e+01 -3.530703e-02 9.992492e-01 -1.595117e-02 -5.953554e+00 -2.495970e-01 6.638405e-03 9.683270e-01 1.041244e+02 +9.670771e-01 3.374565e-02 2.522366e-01 6.013424e+01 -3.096203e-02 9.994080e-01 -1.499784e-02 -5.975190e+00 -2.525933e-01 6.694307e-03 9.675493e-01 1.047544e+02 +9.670770e-01 3.012062e-02 2.526952e-01 6.030914e+01 -2.652167e-02 9.994926e-01 -1.763722e-02 -5.998250e+00 -2.530982e-01 1.035465e-02 9.673851e-01 1.053923e+02 +9.672372e-01 2.935759e-02 2.521715e-01 6.048079e+01 -2.413441e-02 9.994258e-01 -2.378160e-02 -6.023068e+00 -2.527249e-01 1.691644e-02 9.673902e-01 1.060354e+02 +9.674264e-01 3.108975e-02 2.512362e-01 6.064973e+01 -2.389677e-02 9.992139e-01 -3.163137e-02 -6.049018e+00 -2.520221e-01 2.459729e-02 9.674088e-01 1.066923e+02 +9.679171e-01 3.485791e-02 2.488402e-01 6.081912e+01 -2.666631e-02 9.989881e-01 -3.621546e-02 -6.075562e+00 -2.498508e-01 2.841791e-02 9.678672e-01 1.073637e+02 +9.685648e-01 3.339321e-02 2.465099e-01 6.099510e+01 -2.633527e-02 9.991449e-01 -3.187395e-02 -6.103151e+00 -2.473634e-01 2.438008e-02 9.686159e-01 1.080547e+02 +9.690741e-01 2.877873e-02 2.450863e-01 6.117722e+01 -2.348928e-02 9.994243e-01 -2.447838e-02 -6.135437e+00 -2.456496e-01 1.796446e-02 9.691922e-01 1.087607e+02 +9.696494e-01 2.911215e-02 2.427603e-01 6.135508e+01 -2.561797e-02 9.995179e-01 -1.753858e-02 -6.168814e+00 -2.431539e-01 1.078724e-02 9.699277e-01 1.094778e+02 +9.700047e-01 3.237650e-02 2.409204e-01 6.152759e+01 -2.883405e-02 9.994182e-01 -1.821556e-02 -6.198021e+00 -2.413700e-01 1.072247e-02 9.703739e-01 1.102002e+02 +9.702632e-01 3.845449e-02 2.389783e-01 6.169627e+01 -3.397645e-02 9.991618e-01 -2.283122e-02 -6.225332e+00 -2.396559e-01 1.403265e-02 9.707564e-01 1.109295e+02 +9.711702e-01 3.945438e-02 2.350997e-01 6.187414e+01 -3.375909e-02 9.990320e-01 -2.820239e-02 -6.252301e+00 -2.359848e-01 1.945256e-02 9.715620e-01 1.116692e+02 +9.721966e-01 3.867136e-02 2.309511e-01 6.205312e+01 -3.231967e-02 9.989897e-01 -3.122404e-02 -6.282018e+00 -2.319252e-01 2.289163e-02 9.724642e-01 1.124214e+02 +9.731405e-01 3.672904e-02 2.272633e-01 6.223417e+01 -3.078898e-02 9.990867e-01 -2.962862e-02 -6.315240e+00 -2.281439e-01 2.183560e-02 9.733825e-01 1.131891e+02 +9.741028e-01 3.235463e-02 2.237790e-01 6.241758e+01 -2.673172e-02 9.992473e-01 -2.811183e-02 -6.351409e+00 -2.245201e-01 2.140181e-02 9.742344e-01 1.139649e+02 +9.745476e-01 3.082445e-02 2.220517e-01 6.260024e+01 -2.588369e-02 9.993491e-01 -2.512708e-02 -6.387404e+00 -2.226817e-01 1.874001e-02 9.747110e-01 1.147551e+02 +9.749759e-01 2.776787e-02 2.205697e-01 6.278483e+01 -2.339025e-02 9.994746e-01 -2.243445e-02 -6.419328e+00 -2.210768e-01 1.671386e-02 9.751131e-01 1.155643e+02 +9.752499e-01 2.247719e-02 2.199602e-01 6.297372e+01 -1.826607e-02 9.996092e-01 -2.116033e-02 -6.450506e+00 -2.203499e-01 1.661880e-02 9.752793e-01 1.163732e+02 +9.753752e-01 2.305642e-02 2.193439e-01 6.315739e+01 -1.920219e-02 9.996217e-01 -1.968763e-02 -6.483943e+00 -2.197148e-01 1.499094e-02 9.754489e-01 1.171926e+02 +9.751303e-01 2.794458e-02 2.198640e-01 6.333463e+01 -2.375350e-02 9.994826e-01 -2.168323e-02 -6.517585e+00 -2.203562e-01 1.592143e-02 9.752895e-01 1.180121e+02 +9.748174e-01 3.407297e-02 2.203864e-01 6.351246e+01 -2.930179e-02 9.992608e-01 -2.488311e-02 -6.551031e+00 -2.210713e-01 1.779877e-02 9.750952e-01 1.188364e+02 +9.743646e-01 4.180173e-02 2.210574e-01 6.369130e+01 -3.686288e-02 9.989709e-01 -2.642226e-02 -6.583319e+00 -2.219344e-01 1.759609e-02 9.749028e-01 1.196659e+02 +9.734172e-01 4.884577e-02 2.237701e-01 6.387033e+01 -4.420333e-02 9.986916e-01 -2.571202e-02 -6.619743e+00 -2.247332e-01 1.513714e-02 9.743027e-01 1.205026e+02 +9.724994e-01 5.172831e-02 2.270885e-01 6.405736e+01 -4.772120e-02 9.985934e-01 -2.310429e-02 -6.658079e+00 -2.279642e-01 1.163197e-02 9.736000e-01 1.213427e+02 +9.719058e-01 5.218735e-02 2.295117e-01 6.425325e+01 -4.802517e-02 9.985652e-01 -2.368740e-02 -6.695256e+00 -2.304186e-01 1.199958e-02 9.730176e-01 1.221809e+02 +9.714761e-01 5.201240e-02 2.313632e-01 6.444981e+01 -4.701719e-02 9.985276e-01 -2.705593e-02 -6.728166e+00 -2.324297e-01 1.540614e-02 9.724911e-01 1.230215e+02 +9.716103e-01 4.466236e-02 2.323333e-01 6.465586e+01 -3.970179e-02 9.988736e-01 -2.598590e-02 -6.752867e+00 -2.332322e-01 1.602412e-02 9.722890e-01 1.238767e+02 +9.718221e-01 3.802642e-02 2.326284e-01 6.486450e+01 -3.279916e-02 9.991159e-01 -2.629888e-02 -6.784235e+00 -2.334227e-01 1.792781e-02 9.722100e-01 1.247241e+02 +9.715160e-01 3.673359e-02 2.341097e-01 6.506629e+01 -3.144821e-02 9.991600e-01 -2.627103e-02 -6.818192e+00 -2.348781e-01 1.816039e-02 9.718551e-01 1.255712e+02 +9.711204e-01 4.003934e-02 2.352064e-01 6.526209e+01 -3.523136e-02 9.990761e-01 -2.461010e-02 -6.849345e+00 -2.359744e-01 1.561273e-02 9.716338e-01 1.264226e+02 +9.707950e-01 4.129353e-02 2.363301e-01 6.545904e+01 -3.782412e-02 9.991000e-01 -1.919733e-02 -6.878751e+00 -2.369101e-01 9.697688e-03 9.714831e-01 1.272746e+02 +9.703421e-01 4.468201e-02 2.375705e-01 6.565809e+01 -4.268596e-02 9.989967e-01 -1.354208e-02 -6.913045e+00 -2.379372e-01 2.999522e-03 9.712758e-01 1.281205e+02 +9.701141e-01 4.431270e-02 2.385687e-01 6.586477e+01 -4.089052e-02 9.989776e-01 -1.927718e-02 -6.955017e+00 -2.391791e-01 8.945864e-03 9.709342e-01 1.289410e+02 +9.702979e-01 4.107535e-02 2.384005e-01 6.608066e+01 -3.412526e-02 9.988656e-01 -3.320919e-02 -7.000709e+00 -2.394942e-01 2.408732e-02 9.705989e-01 1.297485e+02 +9.706399e-01 3.734387e-02 2.376208e-01 6.629836e+01 -2.778327e-02 9.986688e-01 -4.345839e-02 -7.046839e+00 -2.389273e-01 3.558056e-02 9.703853e-01 1.305573e+02 +9.708707e-01 3.562799e-02 2.369405e-01 6.651051e+01 -2.737139e-02 9.989010e-01 -3.804652e-02 -7.092137e+00 -2.380356e-01 3.045286e-02 9.707789e-01 1.313828e+02 +9.711965e-01 2.941011e-02 2.364583e-01 6.672265e+01 -2.649658e-02 9.995289e-01 -1.549055e-02 -7.134533e+00 -2.368024e-01 8.779029e-03 9.715181e-01 1.322254e+02 +9.714734e-01 2.591697e-02 2.357283e-01 6.693208e+01 -2.747143e-02 9.996171e-01 3.311926e-03 -7.177765e+00 -2.355522e-01 -9.693239e-03 9.718133e-01 1.330601e+02 +9.715736e-01 2.883383e-02 2.349753e-01 6.713546e+01 -2.883399e-02 9.995783e-01 -3.435808e-03 -7.203471e+00 -2.349753e-01 -3.437134e-03 9.719952e-01 1.338675e+02 +9.716942e-01 3.680518e-02 2.333577e-01 6.733397e+01 -3.320560e-02 9.992614e-01 -1.933645e-02 -7.221705e+00 -2.338970e-01 1.104033e-02 9.721986e-01 1.346626e+02 +9.719789e-01 3.798216e-02 2.319793e-01 6.753946e+01 -3.220590e-02 9.990709e-01 -2.863797e-02 -7.240417e+00 -2.328515e-01 2.036440e-02 9.722990e-01 1.354599e+02 +9.725903e-01 3.392131e-02 2.300382e-01 6.774822e+01 -2.784568e-02 9.991736e-01 -2.960745e-02 -7.275568e+00 -2.308524e-01 2.239035e-02 9.727311e-01 1.362625e+02 +9.732069e-01 3.360055e-02 2.274630e-01 6.793990e+01 -2.840108e-02 9.992559e-01 -2.609403e-02 -7.307651e+00 -2.281706e-01 1.893469e-02 9.734370e-01 1.370723e+02 +9.740244e-01 3.316910e-02 2.240007e-01 6.812659e+01 -2.766976e-02 9.992347e-01 -2.764591e-02 -7.329594e+00 -2.247463e-01 2.072974e-02 9.741967e-01 1.378726e+02 +9.751147e-01 3.373626e-02 2.191191e-01 6.831148e+01 -2.785670e-02 9.991656e-01 -2.986795e-02 -7.347445e+00 -2.199439e-01 2.302074e-02 9.752408e-01 1.386688e+02 +9.756333e-01 3.839790e-02 2.160215e-01 6.848738e+01 -3.300030e-02 9.990478e-01 -2.853953e-02 -7.375994e+00 -2.169116e-01 2.071534e-02 9.759714e-01 1.394818e+02 +9.758225e-01 4.488478e-02 2.139062e-01 6.865535e+01 -3.922057e-02 9.987603e-01 -3.065279e-02 -7.400654e+00 -2.150169e-01 2.152215e-02 9.763731e-01 1.402662e+02 +9.761098e-01 4.665322e-02 2.122104e-01 6.883080e+01 -4.167268e-02 9.987421e-01 -2.788476e-02 -7.431426e+00 -2.132444e-01 1.837520e-02 9.768260e-01 1.410669e+02 +9.764697e-01 4.461131e-02 2.109903e-01 6.901055e+01 -4.067802e-02 9.989087e-01 -2.294787e-02 -7.461305e+00 -2.117838e-01 1.382523e-02 9.772187e-01 1.418662e+02 +9.767943e-01 4.343929e-02 2.097286e-01 6.918789e+01 -3.956073e-02 9.989603e-01 -2.265516e-02 -7.492154e+00 -2.104946e-01 1.383241e-02 9.774971e-01 1.426598e+02 +9.774640e-01 4.156360e-02 2.069702e-01 6.935983e+01 -3.690635e-02 9.989722e-01 -2.631422e-02 -7.522327e+00 -2.078512e-01 1.808269e-02 9.779932e-01 1.434510e+02 +9.785757e-01 3.715735e-02 2.025067e-01 6.953255e+01 -3.191867e-02 9.990675e-01 -2.907493e-02 -7.548491e+00 -2.033982e-01 2.198827e-02 9.788491e-01 1.442346e+02 +9.800402e-01 3.397379e-02 1.958750e-01 6.969416e+01 -2.847149e-02 9.991187e-01 -3.083931e-02 -7.579826e+00 -1.967501e-01 2.464691e-02 9.801438e-01 1.450284e+02 +9.813433e-01 3.290257e-02 1.894277e-01 6.984462e+01 -2.849114e-02 9.992567e-01 -2.596524e-02 -7.612956e+00 -1.901412e-01 2.008380e-02 9.815513e-01 1.458298e+02 +9.825216e-01 3.087594e-02 1.835705e-01 6.999277e+01 -2.824613e-02 9.994577e-01 -1.692414e-02 -7.645990e+00 -1.839935e-01 1.144318e-02 9.828608e-01 1.466342e+02 +9.833609e-01 2.646368e-02 1.797248e-01 7.013150e+01 -2.542474e-02 9.996440e-01 -8.082177e-03 -7.668862e+00 -1.798747e-01 3.378240e-03 9.836837e-01 1.474395e+02 +9.838322e-01 3.363794e-02 1.759058e-01 7.025738e+01 -3.351540e-02 9.994314e-01 -3.668401e-03 -7.690397e+00 -1.759292e-01 -2.286463e-03 9.844001e-01 1.482407e+02 +9.845163e-01 3.687818e-02 1.713701e-01 7.037981e+01 -3.585879e-02 9.993159e-01 -9.041220e-03 -7.712080e+00 -1.715862e-01 2.756104e-03 9.851652e-01 1.490330e+02 +9.857542e-01 3.716732e-02 1.640347e-01 7.050797e+01 -3.448744e-02 9.992215e-01 -1.915602e-02 -7.732710e+00 -1.646189e-01 1.322599e-02 9.862685e-01 1.498199e+02 +9.869512e-01 3.436872e-02 1.573096e-01 7.063407e+01 -3.068028e-02 9.991958e-01 -2.581629e-02 -7.751909e+00 -1.580703e-01 2.065311e-02 9.872118e-01 1.506153e+02 +9.880243e-01 3.297858e-02 1.507330e-01 7.075332e+01 -2.956337e-02 9.992541e-01 -2.484300e-02 -7.779012e+00 -1.514399e-01 2.008931e-02 9.882622e-01 1.514220e+02 +9.888875e-01 3.991791e-02 1.432067e-01 7.085703e+01 -3.731589e-02 9.990868e-01 -2.081080e-02 -7.812429e+00 -1.439066e-01 1.523565e-02 9.894739e-01 1.522370e+02 +9.897183e-01 4.586975e-02 1.354761e-01 7.095263e+01 -4.336929e-02 9.988309e-01 -2.135247e-02 -7.841404e+00 -1.362971e-01 1.525743e-02 9.905505e-01 1.530488e+02 +9.909259e-01 4.849401e-02 1.253563e-01 7.105219e+01 -4.546236e-02 9.986028e-01 -2.693473e-02 -7.868414e+00 -1.264873e-01 2.099133e-02 9.917460e-01 1.538549e+02 +9.920486e-01 4.708364e-02 1.167168e-01 7.114828e+01 -4.394991e-02 9.986045e-01 -2.928025e-02 -7.891249e+00 -1.179326e-01 2.391773e-02 9.927335e-01 1.546649e+02 +9.929566e-01 4.708196e-02 1.087220e-01 7.123668e+01 -4.431524e-02 9.986327e-01 -2.772649e-02 -7.916918e+00 -1.098787e-01 2.271316e-02 9.936854e-01 1.554826e+02 +9.935935e-01 5.028742e-02 1.012092e-01 7.130611e+01 -4.847236e-02 9.986179e-01 -2.031541e-02 -7.939937e+00 -1.020909e-01 1.527941e-02 9.946577e-01 1.563078e+02 +9.941880e-01 5.348146e-02 9.343488e-02 7.136837e+01 -5.238072e-02 9.985263e-01 -1.419561e-02 -7.966304e+00 -9.405638e-02 9.218918e-03 9.955241e-01 1.571360e+02 +9.949035e-01 5.253998e-02 8.606248e-02 7.143075e+01 -5.185407e-02 9.986027e-01 -1.018773e-02 -7.990297e+00 -8.647748e-02 5.673120e-03 9.962376e-01 1.579586e+02 +9.954223e-01 5.249755e-02 7.986537e-02 7.149070e+01 -5.197701e-02 9.986114e-01 -8.584225e-03 -8.012612e+00 -8.020511e-02 4.393765e-03 9.967686e-01 1.587800e+02 +9.958028e-01 5.184121e-02 7.542759e-02 7.154565e+01 -5.127576e-02 9.986401e-01 -9.415322e-03 -8.036337e+00 -7.581312e-02 5.508196e-03 9.971068e-01 1.596018e+02 +9.958975e-01 5.644942e-02 7.072225e-02 7.159206e+01 -5.546812e-02 9.983360e-01 -1.576487e-02 -8.062682e+00 -7.149448e-02 1.177736e-02 9.973714e-01 1.604205e+02 +9.957357e-01 6.336806e-02 6.704397e-02 7.162754e+01 -6.207913e-02 9.978473e-01 -2.113905e-02 -8.085177e+00 -6.823918e-02 1.688687e-02 9.975260e-01 1.612383e+02 +9.958600e-01 6.437660e-02 6.417679e-02 7.166501e+01 -6.289692e-02 9.977114e-01 -2.481823e-02 -8.105358e+00 -6.562762e-02 2.067896e-02 9.976298e-01 1.620549e+02 +9.959250e-01 6.612540e-02 6.132616e-02 7.170556e+01 -6.512064e-02 9.977106e-01 -1.824263e-02 -8.124046e+00 -6.239206e-02 1.417469e-02 9.979510e-01 1.628891e+02 +9.958828e-01 6.825485e-02 5.965502e-02 7.173958e+01 -6.785743e-02 9.976574e-01 -8.664995e-03 -8.140372e+00 -6.010669e-02 4.581283e-03 9.981814e-01 1.637286e+02 +9.960001e-01 6.906583e-02 5.669062e-02 7.177540e+01 -6.916226e-02 9.976054e-01 -2.616200e-04 -8.158203e+00 -5.657294e-02 -3.660277e-03 9.983917e-01 1.645638e+02 +9.964269e-01 6.676599e-02 5.172834e-02 7.181125e+01 -6.671062e-02 9.977684e-01 -2.798170e-03 -8.173449e+00 -5.179972e-02 -6.626575e-04 9.986572e-01 1.653868e+02 +9.973506e-01 5.623046e-02 4.615245e-02 7.185566e+01 -5.577477e-02 9.983816e-01 -1.110362e-02 -8.188372e+00 -4.670211e-02 8.500062e-03 9.988726e-01 1.662010e+02 +9.979389e-01 5.110589e-02 3.881003e-02 7.188912e+01 -5.043294e-02 9.985629e-01 -1.812578e-02 -8.197125e+00 -3.968059e-02 1.613112e-02 9.990821e-01 1.670187e+02 +9.979639e-01 5.517487e-02 3.199794e-02 7.190149e+01 -5.468822e-02 9.983770e-01 -1.589030e-02 -8.209715e+00 -3.282275e-02 1.410803e-02 9.993616e-01 1.678465e+02 +9.982641e-01 5.341943e-02 2.480255e-02 7.191447e+01 -5.316930e-02 9.985288e-01 -1.063788e-02 -8.225974e+00 -2.533433e-02 9.300678e-03 9.996357e-01 1.686811e+02 +9.986378e-01 4.912776e-02 1.758187e-02 7.193066e+01 -4.903568e-02 9.987811e-01 -5.630728e-03 -8.240659e+00 -1.783706e-02 4.760919e-03 9.998295e-01 1.695173e+02 +9.990975e-01 4.078690e-02 1.185966e-02 7.194420e+01 -4.075076e-02 9.991640e-01 -3.273653e-03 -8.251269e+00 -1.198327e-02 2.787409e-03 9.999243e-01 1.703582e+02 +9.993260e-01 3.624932e-02 5.790517e-03 7.195036e+01 -3.623788e-02 9.993410e-01 -2.069112e-03 -8.265898e+00 -5.861705e-03 1.857882e-03 9.999810e-01 1.712012e+02 +9.994607e-01 3.283240e-02 -5.780755e-04 7.194712e+01 -3.283589e-02 9.994309e-01 -7.716679e-03 -8.281895e+00 3.243895e-04 7.731499e-03 9.999700e-01 1.720379e+02 +9.996479e-01 2.528590e-02 -8.050398e-03 7.194423e+01 -2.542603e-02 9.995181e-01 -1.780696e-02 -8.295895e+00 7.596253e-03 1.800538e-02 9.998090e-01 1.728670e+02 +9.997990e-01 1.295244e-02 -1.530398e-02 7.194610e+01 -1.333594e-02 9.995928e-01 -2.522779e-02 -8.314995e+00 1.497098e-02 2.542681e-02 9.995645e-01 1.736993e+02 +9.996436e-01 1.605209e-02 -2.133065e-02 7.192242e+01 -1.640104e-02 9.997328e-01 -1.628577e-02 -8.332767e+00 2.106353e-02 1.662980e-02 9.996398e-01 1.745517e+02 +9.993113e-01 2.637007e-02 -2.610724e-02 7.188077e+01 -2.645667e-02 9.996455e-01 -2.976997e-03 -8.350218e+00 2.601948e-02 3.665657e-03 9.996547e-01 1.754112e+02 +9.990013e-01 3.251977e-02 -3.064244e-02 7.183806e+01 -3.236068e-02 9.994601e-01 5.673991e-03 -8.369208e+00 3.081041e-02 -4.676713e-03 9.995143e-01 1.762661e+02 +9.988864e-01 3.211212e-02 -3.456697e-02 7.180048e+01 -3.201024e-02 9.994814e-01 3.496713e-03 -8.380943e+00 3.466132e-02 -2.386321e-03 9.993962e-01 1.771104e+02 +9.987805e-01 3.298445e-02 -3.673766e-02 7.175930e+01 -3.325968e-02 9.994229e-01 -6.905757e-03 -8.392488e+00 3.648868e-02 8.119217e-03 9.993010e-01 1.779477e+02 +9.982576e-01 4.360448e-02 -3.975662e-02 7.170504e+01 -4.429609e-02 9.988791e-01 -1.668374e-02 -8.408732e+00 3.898457e-02 1.841573e-02 9.990700e-01 1.787853e+02 +9.981639e-01 4.382976e-02 -4.180851e-02 7.166001e+01 -4.470847e-02 9.987934e-01 -2.031881e-02 -8.427651e+00 4.086750e-02 2.215070e-02 9.989190e-01 1.796316e+02 +9.983190e-01 3.709972e-02 -4.452873e-02 7.162938e+01 -3.785446e-02 9.991515e-01 -1.622741e-02 -8.451315e+00 4.388891e-02 1.788574e-02 9.988762e-01 1.804893e+02 +9.982984e-01 3.770733e-02 -4.448140e-02 7.158675e+01 -3.805675e-02 9.992508e-01 -7.034446e-03 -8.471918e+00 4.418282e-02 8.715292e-03 9.989854e-01 1.813511e+02 +9.982447e-01 3.981282e-02 -4.384633e-02 7.153819e+01 -3.987331e-02 9.992046e-01 -5.053899e-04 -8.495182e+00 4.379133e-02 2.252801e-03 9.990381e-01 1.822141e+02 +9.982172e-01 3.836984e-02 -4.571952e-02 7.149582e+01 -3.851832e-02 9.992551e-01 -2.370550e-03 -8.518990e+00 4.559450e-02 4.127362e-03 9.989514e-01 1.830694e+02 +9.981548e-01 3.713477e-02 -4.804330e-02 7.145164e+01 -3.766269e-02 9.992391e-01 -1.012985e-02 -8.543212e+00 4.763058e-02 1.192060e-02 9.987938e-01 1.839180e+02 +9.983567e-01 2.690662e-02 -5.059681e-02 7.141963e+01 -2.803423e-02 9.993712e-01 -2.171003e-02 -8.567846e+00 4.998085e-02 2.309279e-02 9.984831e-01 1.847628e+02 +9.984731e-01 1.547705e-02 -5.302878e-02 7.138986e+01 -1.690010e-02 9.995061e-01 -2.649288e-02 -8.596086e+00 5.259256e-02 2.734862e-02 9.982414e-01 1.856110e+02 +9.983890e-01 1.720848e-02 -5.406808e-02 7.134131e+01 -1.842183e-02 9.995877e-01 -2.202345e-02 -8.625507e+00 5.366680e-02 2.298400e-02 9.982943e-01 1.864714e+02 +9.982214e-01 2.292478e-02 -5.503216e-02 7.128399e+01 -2.362423e-02 9.996477e-01 -1.209310e-02 -8.659180e+00 5.473554e-02 1.337168e-02 9.984113e-01 1.873332e+02 +9.980787e-01 2.529689e-02 -5.656048e-02 7.122920e+01 -2.571834e-02 9.996465e-01 -6.735662e-03 -8.688115e+00 5.637009e-02 8.177361e-03 9.983764e-01 1.881818e+02 +9.980717e-01 2.293392e-02 -5.768076e-02 7.118264e+01 -2.358163e-02 9.996660e-01 -1.057360e-02 -8.712856e+00 5.741900e-02 1.191341e-02 9.982790e-01 1.890202e+02 +9.980532e-01 2.327322e-02 -5.786424e-02 7.113685e+01 -2.430321e-02 9.995573e-01 -1.716040e-02 -8.736466e+00 5.743924e-02 1.853328e-02 9.981769e-01 1.898562e+02 +9.978588e-01 3.003041e-02 -5.810388e-02 7.107577e+01 -3.115242e-02 9.993434e-01 -1.850161e-02 -8.761375e+00 5.751011e-02 2.027207e-02 9.981390e-01 1.906947e+02 +9.977393e-01 3.329039e-02 -5.837976e-02 7.101964e+01 -3.417387e-02 9.993150e-01 -1.420047e-02 -8.788561e+00 5.786702e-02 1.616343e-02 9.981934e-01 1.915357e+02 +9.975674e-01 3.693481e-02 -5.912010e-02 7.096425e+01 -3.766129e-02 9.992275e-01 -1.122112e-02 -8.816710e+00 5.865998e-02 1.342036e-02 9.981878e-01 1.923732e+02 +9.974328e-01 4.009581e-02 -5.933112e-02 7.090819e+01 -4.066337e-02 9.991377e-01 -8.389275e-03 -8.838886e+00 5.894358e-02 1.078034e-02 9.982030e-01 1.932083e+02 +9.972334e-01 4.411351e-02 -5.982968e-02 7.084733e+01 -4.469685e-02 9.989649e-01 -8.446293e-03 -8.861377e+00 5.939515e-02 1.109712e-02 9.981728e-01 1.940400e+02 +9.972752e-01 4.218303e-02 -6.052129e-02 7.079115e+01 -4.291190e-02 9.990205e-01 -1.079394e-02 -8.884907e+00 6.000668e-02 1.336161e-02 9.981085e-01 1.948635e+02 +9.971203e-01 4.409215e-02 -6.170116e-02 7.073224e+01 -4.521326e-02 9.988345e-01 -1.689265e-02 -8.906076e+00 6.088441e-02 1.963371e-02 9.979516e-01 1.956763e+02 +9.969926e-01 4.514267e-02 -6.299117e-02 7.067083e+01 -4.633030e-02 9.987725e-01 -1.752171e-02 -8.923746e+00 6.212287e-02 2.038741e-02 9.978602e-01 1.964897e+02 +9.971780e-01 4.511427e-02 -6.000663e-02 7.062911e+01 -4.628586e-02 9.987610e-01 -1.827907e-02 -8.938874e+00 5.910763e-02 2.100494e-02 9.980305e-01 1.971957e+02 +9.973545e-01 4.508963e-02 -5.701710e-02 7.058733e+01 -4.624100e-02 9.987489e-01 -1.903726e-02 -8.954024e+00 5.608737e-02 2.162342e-02 9.981916e-01 1.979026e+02 +9.975218e-01 4.506880e-02 -5.402910e-02 7.054557e+01 -4.619582e-02 9.987362e-01 -1.979462e-02 -8.969162e+00 5.306869e-02 2.224148e-02 9.983431e-01 1.986091e+02 +9.976800e-01 4.505178e-02 -5.104010e-02 7.050380e+01 -4.615029e-02 9.987230e-01 -2.055182e-02 -8.984301e+00 5.004903e-02 2.285965e-02 9.984851e-01 1.993157e+02 +9.978290e-01 4.503855e-02 -4.805043e-02 7.046202e+01 -4.610441e-02 9.987093e-01 -2.130877e-02 -8.999441e+00 4.702870e-02 2.347784e-02 9.986175e-01 2.000222e+02 +9.979689e-01 4.502913e-02 -4.506211e-02 7.042027e+01 -4.605821e-02 9.986950e-01 -2.206497e-02 -9.014570e+00 4.400973e-02 2.409563e-02 9.987404e-01 2.007284e+02 +9.980995e-01 4.502350e-02 -4.207462e-02 7.037852e+01 -4.601169e-02 9.986802e-01 -2.282056e-02 -9.029691e+00 4.099163e-02 2.471311e-02 9.988538e-01 2.014342e+02 +9.982214e-01 4.502167e-02 -3.907941e-02 7.033667e+01 -4.596471e-02 9.986648e-01 -2.357770e-02 -9.044849e+00 3.796572e-02 2.533204e-02 9.989578e-01 2.021417e+02 +9.983338e-01 4.502363e-02 -3.609049e-02 7.029491e+01 -4.591749e-02 9.986488e-01 -2.433286e-02 -9.059972e+00 3.494617e-02 2.594950e-02 9.990522e-01 2.028477e+02 +9.984373e-01 4.502940e-02 -3.309705e-02 7.025308e+01 -4.586987e-02 9.986323e-01 -2.508878e-02 -9.075116e+00 3.192205e-02 2.656773e-02 9.991371e-01 2.035546e+02 +9.985315e-01 4.503897e-02 -3.010522e-02 7.021128e+01 -4.582193e-02 9.986152e-01 -2.584392e-02 -9.090248e+00 2.889955e-02 2.718544e-02 9.992125e-01 2.042610e+02 +9.986166e-01 4.505231e-02 -2.711672e-02 7.016952e+01 -4.577371e-02 9.985977e-01 -2.659784e-02 -9.105362e+00 2.588040e-02 2.780227e-02 9.992783e-01 2.049666e+02 +9.986926e-01 4.506947e-02 -2.412324e-02 7.012768e+01 -4.572507e-02 9.985795e-01 -2.735266e-02 -9.120498e+00 2.285620e-02 2.841993e-02 9.993347e-01 2.056732e+02 +9.987594e-01 4.509040e-02 -2.113323e-02 7.008590e+01 -4.567615e-02 9.985608e-01 -2.810624e-02 -9.135614e+00 1.983549e-02 2.903665e-02 9.993815e-01 2.063790e+02 +9.988171e-01 4.511514e-02 -1.813963e-02 7.004406e+01 -4.562684e-02 9.985415e-01 -2.886037e-02 -9.150747e+00 1.681113e-02 2.965389e-02 9.994188e-01 2.070856e+02 +9.988567e-01 4.517153e-02 -1.565232e-02 6.999905e+01 -4.562219e-02 9.985159e-01 -2.974193e-02 -9.165290e+00 1.428560e-02 3.042201e-02 9.994350e-01 2.077971e+02 +9.989610e-01 4.486150e-02 -8.029166e-03 6.998606e+01 -4.507788e-02 9.985573e-01 -2.917563e-02 -9.185709e+00 6.708720e-03 2.950725e-02 9.995420e-01 2.084453e+02 +9.991350e-01 4.154088e-02 -1.912342e-03 6.998306e+01 -4.157468e-02 9.988516e-01 -2.381015e-02 -9.208113e+00 9.210518e-04 2.386905e-02 9.997146e-01 2.090931e+02 +9.994026e-01 3.430069e-02 4.241041e-03 6.999464e+01 -3.422306e-02 9.992663e-01 -1.719175e-02 -9.235771e+00 -4.827618e-03 1.703633e-02 9.998432e-01 2.097400e+02 +9.995600e-01 2.799323e-02 9.815266e-03 7.000778e+01 -2.783387e-02 9.994843e-01 -1.601343e-02 -9.261371e+00 -1.025847e-02 1.573319e-02 9.998235e-01 2.103757e+02 +9.995027e-01 2.847329e-02 1.355659e-02 7.001564e+01 -2.827301e-02 9.994915e-01 -1.474345e-02 -9.283511e+00 -1.396949e-02 1.435283e-02 9.997993e-01 2.110139e+02 +9.993972e-01 3.154472e-02 1.450058e-02 7.001951e+01 -3.133748e-02 9.994065e-01 -1.430386e-02 -9.302230e+00 -1.494319e-02 1.384082e-02 9.997925e-01 2.116498e+02 +9.993906e-01 3.173357e-02 1.454168e-02 7.002608e+01 -3.154475e-02 9.994173e-01 -1.303544e-02 -9.317034e+00 -1.494687e-02 1.256878e-02 9.998092e-01 2.122959e+02 +9.993983e-01 3.193726e-02 1.353550e-02 7.003039e+01 -3.180250e-02 9.994435e-01 -1.005720e-02 -9.333416e+00 -1.384917e-02 9.620679e-03 9.998578e-01 2.129445e+02 +9.993448e-01 3.345592e-02 1.380943e-02 7.003031e+01 -3.335812e-02 9.994171e-01 -7.253049e-03 -9.346935e+00 -1.404404e-02 6.787639e-03 9.998783e-01 2.136019e+02 +9.990170e-01 4.213031e-02 1.378874e-02 7.001762e+01 -4.197964e-02 9.990574e-01 -1.103998e-02 -9.361494e+00 -1.424087e-02 1.045028e-02 9.998439e-01 2.142524e+02 +9.988099e-01 4.710767e-02 1.263911e-02 7.000789e+01 -4.684375e-02 9.986934e-01 -2.042305e-02 -9.378064e+00 -1.358467e-02 1.980668e-02 9.997115e-01 2.149028e+02 +9.989009e-01 4.575401e-02 1.018246e-02 7.000644e+01 -4.544509e-02 9.985532e-01 -2.874302e-02 -9.397152e+00 -1.148284e-02 2.824868e-02 9.995349e-01 2.155565e+02 +9.992198e-01 3.894455e-02 6.569220e-03 7.001323e+01 -3.869261e-02 9.986417e-01 -3.489495e-02 -9.415421e+00 -7.919264e-03 3.461354e-02 9.993693e-01 2.162172e+02 +9.991864e-01 4.023503e-02 2.775105e-03 7.000612e+01 -4.014078e-02 9.987944e-01 -2.825507e-02 -9.429329e+00 -3.908602e-03 2.812068e-02 9.995968e-01 2.168933e+02 +9.988357e-01 4.823388e-02 -8.642295e-04 6.998281e+01 -4.824156e-02 9.987046e-01 -1.617815e-02 -9.452115e+00 8.277524e-05 1.620100e-02 9.998687e-01 2.175788e+02 +9.989962e-01 4.456999e-02 -4.497923e-03 6.997211e+01 -4.457970e-02 9.990036e-01 -2.080989e-03 -9.473975e+00 4.400691e-03 2.279416e-03 9.999877e-01 2.182707e+02 +9.992283e-01 3.837875e-02 -8.362817e-03 6.996763e+01 -3.830045e-02 9.992227e-01 9.330271e-03 -9.487565e+00 8.714400e-03 -9.002769e-03 9.999214e-01 2.189643e+02 +9.993067e-01 3.538900e-02 -1.156541e-02 6.995651e+01 -3.531205e-02 9.993532e-01 6.791368e-03 -9.495411e+00 1.179826e-02 -6.378259e-03 9.999100e-01 2.196463e+02 +9.990883e-01 4.036912e-02 -1.389429e-02 6.993436e+01 -4.034287e-02 9.991835e-01 2.164684e-03 -9.510323e+00 1.397033e-02 -1.602174e-03 9.999011e-01 2.203174e+02 +9.990959e-01 3.833680e-02 -1.837810e-02 6.994019e+01 -3.847501e-02 9.992334e-01 -7.226487e-03 -9.540496e+00 1.808697e-02 7.927050e-03 9.998049e-01 2.209704e+02 +9.993118e-01 3.052516e-02 -2.107665e-02 6.996054e+01 -3.081390e-02 9.994338e-01 -1.351338e-02 -9.567751e+00 2.065221e-02 1.415353e-02 9.996865e-01 2.216247e+02 +9.995047e-01 2.253595e-02 -2.196621e-02 6.997285e+01 -2.273633e-02 9.997017e-01 -8.915106e-03 -9.591872e+00 2.175874e-02 9.410120e-03 9.997189e-01 2.223055e+02 +9.996015e-01 1.534279e-02 -2.369614e-02 6.998119e+01 -1.543214e-02 9.998744e-01 -3.592590e-03 -9.615886e+00 2.363804e-02 3.956841e-03 9.997127e-01 2.229918e+02 +9.996094e-01 1.212864e-02 -2.518004e-02 6.998430e+01 -1.213886e-02 9.999263e-01 -2.531299e-04 -9.650603e+00 2.517511e-02 5.586885e-04 9.996828e-01 2.236723e+02 +9.996062e-01 9.568085e-03 -2.638256e-02 6.998163e+01 -9.648184e-03 9.999492e-01 -2.910422e-03 -9.683750e+00 2.635337e-02 3.163819e-03 9.996476e-01 2.243537e+02 +9.996142e-01 3.849148e-03 -2.751025e-02 6.998542e+01 -4.102379e-03 9.999497e-01 -9.154463e-03 -9.716608e+00 2.747363e-02 9.263787e-03 9.995795e-01 2.250278e+02 +9.995754e-01 -4.678655e-03 -2.876161e-02 6.998607e+01 4.383364e-03 9.999371e-01 -1.032134e-02 -9.742245e+00 2.880809e-02 1.019089e-02 9.995330e-01 2.257134e+02 +9.995281e-01 -7.405982e-03 -2.981397e-02 6.998187e+01 7.180519e-03 9.999448e-01 -7.662325e-03 -9.771343e+00 2.986907e-02 7.444628e-03 9.995260e-01 2.263991e+02 +9.995051e-01 -8.326333e-03 -3.033594e-02 6.996949e+01 8.243860e-03 9.999620e-01 -2.842732e-03 -9.792795e+00 3.035846e-02 2.591240e-03 9.995357e-01 2.270898e+02 +9.994670e-01 -8.991090e-03 -3.138530e-02 6.996118e+01 8.999502e-03 9.999595e-01 1.267407e-04 -9.818999e+00 3.138288e-02 -4.091245e-04 9.995073e-01 2.277732e+02 +9.994428e-01 -1.020901e-02 -3.178101e-02 6.994919e+01 1.015480e-02 9.999467e-01 -1.866652e-03 -9.840708e+00 3.179837e-02 1.542882e-03 9.994931e-01 2.284545e+02 +9.994092e-01 -1.323742e-02 -3.171797e-02 6.993862e+01 1.297005e-02 9.998787e-01 -8.620756e-03 -9.863524e+00 3.182824e-02 8.204279e-03 9.994596e-01 2.291258e+02 +9.993800e-01 -1.491247e-02 -3.189520e-02 6.992429e+01 1.432713e-02 9.997261e-01 -1.850238e-02 -9.884742e+00 3.216238e-02 1.803394e-02 9.993199e-01 2.297927e+02 +9.993829e-01 -1.412937e-02 -3.216079e-02 6.990717e+01 1.335457e-02 9.996184e-01 -2.417986e-02 -9.909781e+00 3.249016e-02 2.373544e-02 9.991901e-01 2.304543e+02 +9.994430e-01 -1.049593e-02 -3.167951e-02 6.988635e+01 9.741052e-03 9.996671e-01 -2.388948e-02 -9.937611e+00 3.191970e-02 2.356758e-02 9.992125e-01 2.311122e+02 +9.994183e-01 -1.238982e-02 -3.177627e-02 6.987145e+01 1.184129e-02 9.997786e-01 -1.739299e-02 -9.964503e+00 3.198473e-02 1.700660e-02 9.993436e-01 2.317690e+02 +9.993685e-01 -1.429766e-02 -3.252990e-02 6.985983e+01 1.401429e-02 9.998620e-01 -8.922511e-03 -9.992889e+00 3.265298e-02 8.460992e-03 9.994309e-01 2.324182e+02 +9.993512e-01 -1.492646e-02 -3.277765e-02 6.984446e+01 1.479210e-02 9.998812e-01 -4.337658e-03 -1.001409e+01 3.283849e-02 3.849993e-03 9.994532e-01 2.330405e+02 +9.993530e-01 -1.359056e-02 -3.329980e-02 6.982710e+01 1.357282e-02 9.999076e-01 -7.585932e-04 -1.003357e+01 3.330703e-02 3.061307e-04 9.994451e-01 2.336500e+02 +9.992501e-01 -1.502281e-02 -3.568876e-02 6.981020e+01 1.510574e-02 9.998838e-01 2.054942e-03 -1.004766e+01 3.565374e-02 -2.592505e-03 9.993608e-01 2.342476e+02 +9.989381e-01 -2.157956e-02 -4.070775e-02 6.980096e+01 2.168150e-02 9.997628e-01 2.064218e-03 -1.005898e+01 4.065355e-02 -2.944630e-03 9.991689e-01 2.348182e+02 +9.984666e-01 -2.652601e-02 -4.858840e-02 6.978279e+01 2.653046e-02 9.996478e-01 -5.535584e-04 -1.006888e+01 4.858597e-02 -7.363619e-04 9.988187e-01 2.353659e+02 +9.978259e-01 -2.916094e-02 -5.910287e-02 6.975496e+01 2.896311e-02 9.995716e-01 -4.201377e-03 -1.007841e+01 5.920007e-02 2.480440e-03 9.982430e-01 2.358968e+02 +9.968748e-01 -2.993489e-02 -7.310717e-02 6.971456e+01 2.942164e-02 9.995343e-01 -8.087593e-03 -1.008536e+01 7.331523e-02 5.911384e-03 9.972912e-01 2.364174e+02 +9.953043e-01 -3.131877e-02 -9.158957e-02 6.966405e+01 3.043549e-02 9.994759e-01 -1.102519e-02 -1.008899e+01 9.188686e-02 8.185844e-03 9.957358e-01 2.369317e+02 +9.929139e-01 -3.522832e-02 -1.134947e-01 6.960296e+01 3.427210e-02 9.993588e-01 -1.036600e-02 -1.009296e+01 1.137871e-01 6.402846e-03 9.934845e-01 2.374372e+02 +9.899005e-01 -3.275755e-02 -1.379279e-01 6.952087e+01 3.196483e-02 9.994573e-01 -7.959044e-03 -1.009963e+01 1.381138e-01 3.469819e-03 9.904102e-01 2.379427e+02 +9.856528e-01 -3.228651e-02 -1.656692e-01 6.942542e+01 3.177041e-02 9.994785e-01 -5.765007e-03 -1.010590e+01 1.657689e-01 4.189171e-04 9.861645e-01 2.384416e+02 +9.797313e-01 -3.394986e-02 -1.974186e-01 6.931500e+01 3.353493e-02 9.994227e-01 -5.445507e-03 -1.011569e+01 1.974895e-01 -1.285283e-03 9.803041e-01 2.389201e+02 +9.719757e-01 -3.229428e-02 -2.328528e-01 6.918511e+01 3.113808e-02 9.994777e-01 -8.640477e-03 -1.012556e+01 2.330102e-01 1.147745e-03 9.724735e-01 2.393949e+02 +9.619720e-01 -2.748637e-02 -2.717618e-01 6.902217e+01 2.486868e-02 9.996052e-01 -1.307228e-02 -1.013488e+01 2.720138e-01 5.816810e-03 9.622757e-01 2.398316e+02 +9.491560e-01 -2.367706e-02 -3.139146e-01 6.884642e+01 1.943740e-02 9.996728e-01 -1.662934e-02 -1.014043e+01 3.142056e-01 9.682159e-03 9.493055e-01 2.402766e+02 +9.334436e-01 -1.890486e-02 -3.582258e-01 6.864775e+01 1.334384e-02 9.997491e-01 -1.798977e-02 -1.014643e+01 3.584760e-01 1.201233e-02 9.334616e-01 2.407091e+02 +9.147510e-01 -8.804964e-03 -4.039222e-01 6.841495e+01 1.345196e-03 9.998233e-01 -1.874838e-02 -1.015095e+01 4.040159e-01 1.660675e-02 9.146011e-01 2.410925e+02 +8.926575e-01 4.783842e-03 -4.507104e-01 6.816609e+01 -1.452077e-02 9.997298e-01 -1.814807e-02 -1.016774e+01 4.505018e-01 2.274467e-02 8.924857e-01 2.414794e+02 +8.668268e-01 1.766589e-02 -4.982963e-01 6.789906e+01 -2.937527e-02 9.994456e-01 -1.566773e-02 -1.018148e+01 4.977433e-01 2.821880e-02 8.668652e-01 2.418486e+02 +8.370897e-01 2.722037e-02 -5.463881e-01 6.760937e+01 -4.034109e-02 9.991135e-01 -1.202968e-02 -1.018159e+01 5.455762e-01 3.211181e-02 8.374457e-01 2.421616e+02 +8.037197e-01 3.418704e-02 -5.940252e-01 6.731827e+01 -4.804963e-02 9.988166e-01 -7.528043e-03 -1.018322e+01 5.930648e-01 3.459312e-02 8.044112e-01 2.424928e+02 +7.676768e-01 4.234926e-02 -6.394364e-01 6.700890e+01 -5.366195e-02 9.985577e-01 1.709552e-03 -1.018416e+01 6.385865e-01 3.300102e-02 7.688420e-01 2.428099e+02 +7.298087e-01 5.429701e-02 -6.814919e-01 6.667291e+01 -5.888986e-02 9.981288e-01 1.645961e-02 -1.017111e+01 6.811104e-01 2.812060e-02 7.316405e-01 2.430702e+02 +6.901781e-01 6.672397e-02 -7.205569e-01 6.633224e+01 -6.457326e-02 9.974463e-01 3.051326e-02 -1.016386e+01 7.207527e-01 2.546912e-02 6.927241e-01 2.433442e+02 +6.485969e-01 7.637250e-02 -7.572908e-01 6.598247e+01 -6.981509e-02 9.967283e-01 4.072516e-02 -1.015157e+01 7.579234e-01 2.645611e-02 6.518068e-01 2.435912e+02 +6.054692e-01 8.074954e-02 -7.917618e-01 6.562105e+01 -7.027296e-02 9.963781e-01 4.787927e-02 -1.013305e+01 7.927602e-01 2.665002e-02 6.089506e-01 2.437845e+02 +5.598590e-01 8.423029e-02 -8.242956e-01 6.526011e+01 -7.033104e-02 9.960603e-01 5.401338e-02 -1.011788e+01 8.255976e-01 2.773368e-02 5.635773e-01 2.439919e+02 +5.123307e-01 8.230045e-02 -8.548356e-01 6.489784e+01 -6.435976e-02 9.962777e-01 5.734510e-02 -1.009595e+01 8.563732e-01 2.563736e-02 5.157205e-01 2.441844e+02 +4.625216e-01 7.638311e-02 -8.833116e-01 6.452042e+01 -5.635113e-02 9.968002e-01 5.669019e-02 -1.007158e+01 8.848154e-01 2.355517e-02 4.653459e-01 2.443200e+02 +4.108591e-01 6.909842e-02 -9.090766e-01 6.414030e+01 -4.771502e-02 9.973869e-01 5.424594e-02 -1.004135e+01 9.104494e-01 2.108918e-02 4.130824e-01 2.444743e+02 +3.578203e-01 6.312724e-02 -9.316543e-01 6.373047e+01 -4.313740e-02 9.977646e-01 5.103900e-02 -1.001139e+01 9.327935e-01 2.192636e-02 3.597435e-01 2.445719e+02 +3.070666e-01 6.126535e-02 -9.497140e-01 6.330850e+01 -4.192552e-02 9.978277e-01 5.081356e-02 -9.982249e+00 9.507640e-01 2.421411e-02 3.089682e-01 2.446831e+02 +2.583650e-01 6.223652e-02 -9.640406e-01 6.286751e+01 -4.237868e-02 9.976921e-01 5.305142e-02 -9.956809e+00 9.651173e-01 2.714814e-02 2.604062e-01 2.447727e+02 +2.119977e-01 6.361948e-02 -9.751972e-01 6.240525e+01 -4.089409e-02 9.975822e-01 5.618988e-02 -9.929802e+00 9.764141e-01 2.796767e-02 2.140868e-01 2.448251e+02 +1.692436e-01 6.258446e-02 -9.835852e-01 6.193966e+01 -3.816279e-02 9.976495e-01 5.691277e-02 -9.901649e+00 9.848351e-01 2.790424e-02 1.712342e-01 2.448844e+02 +1.290802e-01 6.165050e-02 -9.897159e-01 6.145894e+01 -3.658882e-02 9.976820e-01 5.737475e-02 -9.873647e+00 9.909589e-01 2.880659e-02 1.310367e-01 2.449260e+02 +9.339541e-02 6.112447e-02 -9.937511e-01 6.096195e+01 -3.577600e-02 9.976751e-01 5.800353e-02 -9.844318e+00 9.949861e-01 3.013517e-02 9.536506e-02 2.449414e+02 +6.403760e-02 5.829931e-02 -9.962432e-01 6.046150e+01 -3.642959e-02 9.977633e-01 5.604662e-02 -9.811810e+00 9.972823e-01 3.270364e-02 6.601818e-02 2.449539e+02 +3.857869e-02 5.591526e-02 -9.976899e-01 5.994742e+01 -3.609550e-02 9.978595e-01 5.452904e-02 -9.779054e+00 9.986034e-01 3.390845e-02 4.051440e-02 2.449520e+02 +1.584437e-02 5.443454e-02 -9.983917e-01 5.942184e+01 -3.716079e-02 9.978592e-01 5.381578e-02 -9.749152e+00 9.991836e-01 3.624835e-02 1.783327e-02 2.449457e+02 +-3.072926e-03 5.313575e-02 -9.985826e-01 5.888559e+01 -3.932738e-02 9.978083e-01 5.321559e-02 -9.720660e+00 9.992216e-01 3.943516e-02 -9.765028e-04 2.449283e+02 +-1.815342e-02 5.229163e-02 -9.984669e-01 5.833537e+01 -4.212530e-02 9.977046e-01 5.301761e-02 -9.691560e+00 9.989474e-01 4.302316e-02 -1.590895e-02 2.449021e+02 +-2.862872e-02 5.060338e-02 -9.983084e-01 5.777118e+01 -4.374597e-02 9.976975e-01 5.182693e-02 -9.660943e+00 9.986324e-01 4.515570e-02 -2.634911e-02 2.448764e+02 +-3.531846e-02 4.863119e-02 -9.981922e-01 5.719241e+01 -4.399184e-02 9.977715e-01 5.016724e-02 -9.629490e+00 9.984074e-01 4.568413e-02 -3.310038e-02 2.448503e+02 +-3.900133e-02 4.809847e-02 -9.980809e-01 5.659598e+01 -4.432450e-02 9.977744e-01 4.981575e-02 -9.598446e+00 9.982556e-01 4.618231e-02 -3.678258e-02 2.448240e+02 +-4.089244e-02 4.857652e-02 -9.979821e-01 5.598115e+01 -4.394532e-02 9.977635e-01 5.036655e-02 -9.567377e+00 9.981966e-01 4.591625e-02 -3.866627e-02 2.447978e+02 +-4.214587e-02 4.899243e-02 -9.979096e-01 5.534817e+01 -4.363390e-02 9.977538e-01 5.082763e-02 -9.534743e+00 9.981582e-01 4.568486e-02 -3.991346e-02 2.447709e+02 +-4.211898e-02 4.942055e-02 -9.978896e-01 5.469404e+01 -4.335224e-02 9.977448e-01 5.124320e-02 -9.501856e+00 9.981716e-01 4.541906e-02 -3.988150e-02 2.447438e+02 +-4.129111e-02 4.970212e-02 -9.979102e-01 5.402129e+01 -4.265036e-02 9.977639e-01 5.145961e-02 -9.467967e+00 9.982364e-01 4.468605e-02 -3.907896e-02 2.447179e+02 +-4.120315e-02 4.791619e-02 -9.980012e-01 5.333773e+01 -4.132406e-02 9.979130e-01 4.961806e-02 -9.428068e+00 9.982958e-01 4.328588e-02 -3.913707e-02 2.446758e+02 +-4.156077e-02 4.509514e-02 -9.981178e-01 5.265042e+01 -3.886575e-02 9.981518e-01 4.671503e-02 -9.376197e+00 9.983797e-01 4.073411e-02 -3.973130e-02 2.446048e+02 +-4.172997e-02 4.367408e-02 -9.981740e-01 5.194411e+01 -3.799230e-02 9.982522e-01 4.526583e-02 -9.321575e+00 9.984063e-01 3.981186e-02 -3.999775e-02 2.445279e+02 +-4.177101e-02 4.275942e-02 -9.982118e-01 5.120668e+01 -3.860585e-02 9.982686e-01 4.437736e-02 -9.271451e+00 9.983810e-01 4.039050e-02 -4.004792e-02 2.444614e+02 +-4.144332e-02 4.258583e-02 -9.982329e-01 5.045197e+01 -3.928489e-02 9.982492e-01 4.421751e-02 -9.222874e+00 9.983682e-01 4.104799e-02 -3.969778e-02 2.443907e+02 +-4.068132e-02 4.334719e-02 -9.982315e-01 4.966726e+01 -3.774082e-02 9.982789e-01 4.488733e-02 -9.176746e+00 9.984591e-01 3.950015e-02 -3.897534e-02 2.443343e+02 +-3.976130e-02 4.369248e-02 -9.982535e-01 4.886814e+01 -3.523235e-02 9.983609e-01 4.510052e-02 -9.139656e+00 9.985878e-01 3.696407e-02 -3.815674e-02 2.442845e+02 +-3.861235e-02 4.372656e-02 -9.982971e-01 4.805807e+01 -3.236090e-02 9.984633e-01 4.498551e-02 -9.108985e+00 9.987301e-01 3.404279e-02 -3.713799e-02 2.442350e+02 +-3.772664e-02 4.382670e-02 -9.983266e-01 4.722454e+01 -3.113691e-02 9.985011e-01 4.501103e-02 -9.074933e+00 9.988028e-01 3.278292e-02 -3.630546e-02 2.441891e+02 +-3.715853e-02 4.606859e-02 -9.982470e-01 4.638186e+01 -3.041643e-02 9.984218e-01 4.720889e-02 -9.039820e+00 9.988463e-01 3.211732e-02 -3.569864e-02 2.441410e+02 +-3.668499e-02 5.022321e-02 -9.980641e-01 4.551505e+01 -2.858509e-02 9.982749e-01 5.128451e-02 -9.002662e+00 9.989179e-01 3.041113e-02 -3.518607e-02 2.441009e+02 +-3.616752e-02 5.496909e-02 -9.978328e-01 4.465008e+01 -2.748700e-02 9.980536e-01 5.597756e-02 -8.966351e+00 9.989676e-01 2.945200e-02 -3.458619e-02 2.440565e+02 +-3.588490e-02 5.657377e-02 -9.977533e-01 4.378198e+01 -2.660232e-02 9.979885e-01 5.754389e-02 -8.926032e+00 9.990018e-01 2.860751e-02 -3.430772e-02 2.440160e+02 +-3.699745e-02 5.340815e-02 -9.978872e-01 4.292179e+01 -2.705227e-02 9.981513e-01 5.442528e-02 -8.888812e+00 9.989491e-01 2.900871e-02 -3.548424e-02 2.439692e+02 +-3.848837e-02 4.919261e-02 -9.980475e-01 4.206014e+01 -2.626256e-02 9.983927e-01 5.022242e-02 -8.851693e+00 9.989138e-01 2.814427e-02 -3.713458e-02 2.439267e+02 +-4.063027e-02 4.763625e-02 -9.980381e-01 4.119342e+01 -2.332629e-02 9.985454e-01 4.861009e-02 -8.814679e+00 9.989019e-01 2.525557e-02 -3.945999e-02 2.438841e+02 +-4.328305e-02 5.235258e-02 -9.976903e-01 4.031659e+01 -2.093080e-02 9.983594e-01 5.329574e-02 -8.777811e+00 9.988435e-01 2.318926e-02 -4.211626e-02 2.438403e+02 +-4.653298e-02 5.881119e-02 -9.971840e-01 3.944834e+01 -1.901639e-02 9.980323e-01 5.974862e-02 -8.740525e+00 9.987357e-01 2.174312e-02 -4.532304e-02 2.437937e+02 +-4.962930e-02 6.362340e-02 -9.967392e-01 3.857904e+01 -1.729574e-02 9.977646e-01 6.455004e-02 -8.699355e+00 9.986179e-01 2.044292e-02 -4.841794e-02 2.437424e+02 +-5.168669e-02 6.301279e-02 -9.966734e-01 3.770694e+01 -1.463460e-02 9.978524e-01 6.384628e-02 -8.641674e+00 9.985561e-01 1.788592e-02 -5.065352e-02 2.437224e+02 +-5.359497e-02 6.149026e-02 -9.966677e-01 3.683197e+01 -1.382364e-02 9.979609e-01 6.231341e-02 -8.584315e+00 9.984670e-01 1.711726e-02 -5.263566e-02 2.437018e+02 +-5.595537e-02 5.846574e-02 -9.967200e-01 3.596532e+01 -1.594662e-02 9.981043e-01 5.944219e-02 -8.533757e+00 9.983059e-01 1.922043e-02 -5.491696e-02 2.436638e+02 +-5.780494e-02 5.654442e-02 -9.967253e-01 3.509489e+01 -1.698818e-02 9.981944e-01 5.761300e-02 -8.481095e+00 9.981833e-01 2.026286e-02 -5.673998e-02 2.436298e+02 +-5.928177e-02 5.599217e-02 -9.966698e-01 3.422783e+01 -1.645021e-02 9.982353e-01 5.705859e-02 -8.428708e+00 9.981057e-01 1.977796e-02 -5.825607e-02 2.435838e+02 +-6.055939e-02 5.494748e-02 -9.966511e-01 3.334194e+01 -2.093509e-02 9.981941e-01 5.630464e-02 -8.373309e+00 9.979450e-01 2.427476e-02 -5.929969e-02 2.435406e+02 +-6.131504e-02 5.187698e-02 -9.967694e-01 3.247295e+01 -2.518677e-02 9.982500e-01 5.350338e-02 -8.324969e+00 9.978006e-01 2.838596e-02 -5.990112e-02 2.434890e+02 +-6.184715e-02 4.853574e-02 -9.969048e-01 3.159247e+01 -2.759989e-02 9.983518e-01 5.031847e-02 -8.284474e+00 9.977039e-01 3.062651e-02 -6.040563e-02 2.434415e+02 +-6.115626e-02 4.728597e-02 -9.970075e-01 3.071981e+01 -2.926830e-02 9.983627e-01 4.914556e-02 -8.245801e+00 9.976989e-01 3.218627e-02 -5.967215e-02 2.433929e+02 +-5.931853e-02 4.758689e-02 -9.971042e-01 2.985195e+01 -3.021690e-02 9.983198e-01 4.944254e-02 -8.214500e+00 9.977816e-01 3.306226e-02 -5.778093e-02 2.433482e+02 +-5.738838e-02 4.803069e-02 -9.971959e-01 2.898709e+01 -2.947892e-02 9.983250e-01 4.978158e-02 -8.189127e+00 9.979166e-01 3.225314e-02 -5.587635e-02 2.433150e+02 +-5.529084e-02 4.884164e-02 -9.972750e-01 2.812453e+01 -2.810314e-02 9.983310e-01 5.045146e-02 -8.151992e+00 9.980747e-01 3.081606e-02 -5.382595e-02 2.432849e+02 +-5.309253e-02 4.992647e-02 -9.973408e-01 2.726420e+01 -2.598840e-02 9.983420e-01 5.136007e-02 -8.118056e+00 9.982513e-01 2.864613e-02 -5.170699e-02 2.432585e+02 +-5.123993e-02 5.223599e-02 -9.973194e-01 2.641452e+01 -2.135718e-02 9.983455e-01 5.338702e-02 -8.084825e+00 9.984579e-01 2.403548e-02 -5.003954e-02 2.432298e+02 +-4.922633e-02 5.241439e-02 -9.974114e-01 2.556309e+01 -1.550442e-02 9.984616e-01 5.323480e-02 -8.045766e+00 9.986673e-01 1.808484e-02 -4.833795e-02 2.432081e+02 +-4.730535e-02 5.068884e-02 -9.975936e-01 2.472405e+01 -1.582281e-02 9.985483e-01 5.148767e-02 -8.010156e+00 9.987551e-01 1.822038e-02 -4.643463e-02 2.431749e+02 +-4.553925e-02 5.028750e-02 -9.976960e-01 2.388069e+01 -1.697085e-02 9.985491e-01 5.110513e-02 -7.985757e+00 9.988183e-01 1.925904e-02 -4.461975e-02 2.431391e+02 +-4.473834e-02 4.976063e-02 -9.977587e-01 2.304725e+01 -1.250247e-02 9.986526e-01 5.036582e-02 -7.958451e+00 9.989205e-01 1.472774e-02 -4.405593e-02 2.431145e+02 +-4.473087e-02 5.407644e-02 -9.975344e-01 2.221039e+01 -1.015789e-02 9.984576e-01 5.458199e-02 -7.933477e+00 9.989474e-01 1.257435e-02 -4.411257e-02 2.430910e+02 +-4.526291e-02 5.848194e-02 -9.972618e-01 2.138123e+01 -1.198970e-02 9.981812e-01 5.908004e-02 -7.910159e+00 9.989031e-01 1.463101e-02 -4.447940e-02 2.430551e+02 +-4.690140e-02 6.052890e-02 -9.970640e-01 2.055536e+01 -1.360045e-02 9.980312e-01 6.122739e-02 -7.887252e+00 9.988069e-01 1.643217e-02 -4.598583e-02 2.430172e+02 +-4.940591e-02 5.985638e-02 -9.969836e-01 1.973633e+01 -1.492180e-02 9.980469e-01 6.065968e-02 -7.865476e+00 9.986673e-01 1.787374e-02 -4.841625e-02 2.429795e+02 +-5.227617e-02 5.631150e-02 -9.970438e-01 1.892549e+01 -1.560376e-02 9.982409e-01 5.719725e-02 -7.844050e+00 9.985107e-01 1.854769e-02 -5.130554e-02 2.429405e+02 +-5.591956e-02 5.302971e-02 -9.970260e-01 1.811645e+01 -1.638986e-02 9.984052e-01 5.402233e-02 -7.824628e+00 9.983007e-01 1.936203e-02 -5.496123e-02 2.428980e+02 +-6.045013e-02 5.112020e-02 -9.968614e-01 1.731107e+01 -1.704110e-02 9.984893e-01 5.223708e-02 -7.802514e+00 9.980257e-01 2.014535e-02 -5.948766e-02 2.428504e+02 +-6.554325e-02 5.080544e-02 -9.965555e-01 1.650231e+01 -1.848901e-02 9.984697e-01 5.211905e-02 -7.778565e+00 9.976784e-01 2.184138e-02 -6.450360e-02 2.427995e+02 +-7.047798e-02 5.090720e-02 -9.962135e-01 1.570147e+01 -2.042675e-02 9.984138e-01 5.246475e-02 -7.748232e+00 9.973041e-01 2.404701e-02 -6.932632e-02 2.427426e+02 +-7.512578e-02 5.232973e-02 -9.958001e-01 1.490179e+01 -2.230864e-02 9.982839e-01 5.414330e-02 -7.723120e+00 9.969244e-01 2.628250e-02 -7.382945e-02 2.426828e+02 +-7.951903e-02 5.522067e-02 -9.953027e-01 1.410837e+01 -2.472708e-02 9.980479e-01 5.734854e-02 -7.697842e+00 9.965266e-01 2.917123e-02 -7.799836e-02 2.426121e+02 +-8.371244e-02 5.651182e-02 -9.948863e-01 1.332260e+01 -2.894793e-02 9.978314e-01 5.911488e-02 -7.672823e+00 9.960694e-01 3.374855e-02 -8.189499e-02 2.425362e+02 +-8.689516e-02 5.609011e-02 -9.946372e-01 1.254200e+01 -3.297897e-02 9.977045e-01 5.914426e-02 -7.650837e+00 9.956714e-01 3.794146e-02 -8.484590e-02 2.424553e+02 +-8.907174e-02 5.483452e-02 -9.945147e-01 1.177083e+01 -3.726923e-02 9.976007e-01 5.834262e-02 -7.627257e+00 9.953277e-01 4.226147e-02 -8.681438e-02 2.423767e+02 +-9.067270e-02 5.368439e-02 -9.944328e-01 1.100912e+01 -4.247981e-02 9.974286e-01 5.771946e-02 -7.604613e+00 9.949743e-01 4.747689e-02 -8.815904e-02 2.422959e+02 +-9.164312e-02 5.389024e-02 -9.943327e-01 1.025808e+01 -4.632776e-02 9.972226e-01 5.831670e-02 -7.581080e+00 9.947136e-01 5.140952e-02 -8.889196e-02 2.422181e+02 +-9.246109e-02 5.457420e-02 -9.942196e-01 9.515117e+00 -4.877149e-02 9.970501e-01 5.926526e-02 -7.565821e+00 9.945211e-01 5.396930e-02 -8.952667e-02 2.421430e+02 +-9.280224e-02 5.437444e-02 -9.941988e-01 8.787789e+00 -5.120081e-02 9.969261e-01 5.930289e-02 -7.550347e+00 9.943672e-01 5.640722e-02 -8.973295e-02 2.420695e+02 +-9.259478e-02 5.442722e-02 -9.942152e-01 8.077281e+00 -5.444942e-02 9.967340e-01 5.963619e-02 -7.534341e+00 9.942140e-01 5.965644e-02 -8.932884e-02 2.419973e+02 +-9.220125e-02 5.416512e-02 -9.942661e-01 7.381882e+00 -5.695575e-02 9.965977e-01 5.957383e-02 -7.513435e+00 9.941101e-01 6.212195e-02 -8.880253e-02 2.419290e+02 +-9.102842e-02 5.504401e-02 -9.943259e-01 6.700094e+00 -5.837182e-02 9.964596e-01 6.050595e-02 -7.496876e+00 9.941360e-01 6.354836e-02 -8.749312e-02 2.418648e+02 +-8.861615e-02 5.621136e-02 -9.944785e-01 6.032146e+00 -5.918043e-02 9.963455e-01 6.159036e-02 -7.478381e+00 9.943062e-01 6.431156e-02 -8.496568e-02 2.418054e+02 +-8.579543e-02 5.681460e-02 -9.946916e-01 5.376557e+00 -6.044080e-02 9.962371e-01 6.211611e-02 -7.462505e+00 9.944777e-01 6.544923e-02 -8.203867e-02 2.417488e+02 +-8.303764e-02 5.576182e-02 -9.949851e-01 4.739786e+00 -6.223855e-02 9.961940e-01 6.102377e-02 -7.443521e+00 9.946009e-01 6.699370e-02 -7.925105e-02 2.416958e+02 +-8.006015e-02 5.455034e-02 -9.952963e-01 4.114420e+00 -6.244703e-02 9.962655e-01 5.962662e-02 -7.425036e+00 9.948320e-01 6.692700e-02 -7.635465e-02 2.416471e+02 +-7.729197e-02 5.380904e-02 -9.955554e-01 3.505020e+00 -6.059704e-02 9.964429e-01 5.856159e-02 -7.403702e+00 9.951652e-01 6.485405e-02 -7.375637e-02 2.416056e+02 +-7.423508e-02 5.345577e-02 -9.958071e-01 2.907815e+00 -5.842191e-02 9.966141e-01 5.785432e-02 -7.383011e+00 9.955280e-01 6.247177e-02 -7.086074e-02 2.415665e+02 +-7.093472e-02 5.380028e-02 -9.960290e-01 2.325909e+00 -5.873410e-02 9.965865e-01 5.801330e-02 -7.363850e+00 9.957502e-01 6.261601e-02 -6.753267e-02 2.415237e+02 +-6.703682e-02 5.524507e-02 -9.962199e-01 1.760074e+00 -5.951483e-02 9.964666e-01 5.926359e-02 -7.344447e+00 9.959739e-01 6.326270e-02 -6.351205e-02 2.414841e+02 +-6.305890e-02 5.531940e-02 -9.964755e-01 1.213038e+00 -6.050102e-02 9.964143e-01 5.914463e-02 -7.327049e+00 9.961742e-01 6.401737e-02 -5.948591e-02 2.414491e+02 +-5.858339e-02 5.501398e-02 -9.967655e-01 6.848531e-01 -6.033977e-02 9.964596e-01 5.854349e-02 -7.310814e+00 9.964572e-01 6.357427e-02 -5.505645e-02 2.414221e+02 +-5.412180e-02 5.544775e-02 -9.969937e-01 1.703349e-01 -5.914283e-02 9.965261e-01 5.863232e-02 -7.299518e+00 9.967813e-01 6.213830e-02 -5.065445e-02 2.413995e+02 +-4.981643e-02 5.630950e-02 -9.971698e-01 -3.247848e-01 -5.872758e-02 9.965167e-01 5.920653e-02 -7.285113e+00 9.970302e-01 6.151082e-02 -4.633599e-02 2.413788e+02 +-4.550638e-02 5.687983e-02 -9.973434e-01 -8.046972e-01 -5.675787e-02 9.966177e-01 5.942817e-02 -7.270660e+00 9.973503e-01 5.931145e-02 -4.212408e-02 2.413618e+02 +-4.120044e-02 5.798503e-02 -9.974670e-01 -1.267287e+00 -5.680532e-02 9.965639e-01 6.027889e-02 -7.253762e+00 9.975348e-01 5.914494e-02 -3.776501e-02 2.413461e+02 +-3.610771e-02 5.992338e-02 -9.975497e-01 -1.717128e+00 -5.736686e-02 9.964303e-01 6.193262e-02 -7.238023e+00 9.977000e-01 5.946254e-02 -3.254120e-02 2.413305e+02 +-3.140207e-02 6.112176e-02 -9.976363e-01 -2.147061e+00 -5.786746e-02 9.963430e-01 6.286400e-02 -7.227306e+00 9.978302e-01 5.970473e-02 -2.775027e-02 2.413224e+02 +-2.624658e-02 6.176553e-02 -9.977456e-01 -2.559693e+00 -5.693015e-02 9.963771e-01 6.317843e-02 -7.217072e+00 9.980331e-01 5.846002e-02 -2.263517e-02 2.413183e+02 +-2.046943e-02 6.252511e-02 -9.978335e-01 -2.957329e+00 -5.622369e-02 9.963912e-01 6.358811e-02 -7.203941e+00 9.982083e-01 5.740349e-02 -1.688017e-02 2.413176e+02 +-1.446951e-02 6.200308e-02 -9.979711e-01 -3.335045e+00 -5.472316e-02 9.965306e-01 6.270702e-02 -7.191538e+00 9.983967e-01 5.551947e-02 -1.102630e-02 2.413211e+02 +-8.663444e-03 6.079635e-02 -9.981126e-01 -3.693693e+00 -5.283777e-02 9.967278e-01 6.117064e-02 -7.183816e+00 9.985655e-01 5.326799e-02 -5.422752e-03 2.413290e+02 +-2.829753e-03 6.025885e-02 -9.981788e-01 -4.038108e+00 -5.192025e-02 9.968276e-01 6.032448e-02 -7.172216e+00 9.986472e-01 5.199639e-02 3.078767e-04 2.413375e+02 +2.518108e-03 5.938084e-02 -9.982323e-01 -4.362696e+00 -5.116412e-02 9.969356e-01 5.917465e-02 -7.164628e+00 9.986870e-01 5.092466e-02 5.548558e-03 2.413477e+02 +7.348508e-03 5.940952e-02 -9.982067e-01 -4.663567e+00 -5.110519e-02 9.969514e-01 5.895860e-02 -7.156169e+00 9.986662e-01 5.058028e-02 1.036224e-02 2.413569e+02 +1.185470e-02 6.001610e-02 -9.981270e-01 -4.943153e+00 -5.106244e-02 9.969311e-01 5.933774e-02 -7.153234e+00 9.986251e-01 5.026337e-02 1.488288e-02 2.413655e+02 +1.591373e-02 5.996155e-02 -9.980739e-01 -5.195608e+00 -5.100457e-02 9.969493e-01 5.908076e-02 -7.148566e+00 9.985716e-01 4.996612e-02 1.892349e-02 2.413751e+02 +1.967919e-02 5.830293e-02 -9.981050e-01 -5.423479e+00 -4.946181e-02 9.971327e-01 5.727093e-02 -7.145945e+00 9.985821e-01 4.824103e-02 2.250653e-02 2.413865e+02 +2.295032e-02 5.335208e-02 -9.983120e-01 -5.617740e+00 -4.762497e-02 9.974996e-01 5.221382e-02 -7.146376e+00 9.986016e-01 4.634625e-02 2.543382e-02 2.413993e+02 +2.570316e-02 4.958938e-02 -9.984389e-01 -5.787975e+00 -4.611513e-02 9.977644e-01 4.836873e-02 -7.145318e+00 9.986054e-01 4.479991e-02 2.793251e-02 2.414110e+02 +2.777035e-02 4.973839e-02 -9.983762e-01 -5.935611e+00 -4.596377e-02 9.977684e-01 4.842962e-02 -7.141520e+00 9.985570e-01 4.454422e-02 2.999454e-02 2.414211e+02 +2.924553e-02 5.138035e-02 -9.982509e-01 -6.055183e+00 -4.628213e-02 9.976765e-01 4.999488e-02 -7.140534e+00 9.985002e-01 4.473904e-02 3.155556e-02 2.414288e+02 +3.014480e-02 5.060538e-02 -9.982637e-01 -6.148943e+00 -4.636141e-02 9.977135e-01 4.917751e-02 -7.141362e+00 9.984697e-01 4.479846e-02 3.242200e-02 2.414357e+02 +3.082369e-02 4.809906e-02 -9.983669e-01 -6.224444e+00 -4.597130e-02 9.978526e-01 4.665497e-02 -7.140925e+00 9.984671e-01 4.445814e-02 3.296867e-02 2.414423e+02 +3.139705e-02 4.642569e-02 -9.984282e-01 -6.292219e+00 -4.561437e-02 9.979464e-01 4.496889e-02 -7.144182e+00 9.984656e-01 4.413078e-02 3.345025e-02 2.414481e+02 +3.143924e-02 4.563628e-02 -9.984633e-01 -6.347609e+00 -4.544415e-02 9.979893e-01 4.418369e-02 -7.147305e+00 9.984720e-01 4.398521e-02 3.344992e-02 2.414535e+02 +3.145683e-02 4.593749e-02 -9.984489e-01 -6.391909e+00 -4.562791e-02 9.979678e-01 4.447782e-02 -7.151484e+00 9.984631e-01 4.415801e-02 3.348893e-02 2.414576e+02 +3.162515e-02 4.589291e-02 -9.984457e-01 -6.421901e+00 -4.583707e-02 9.979609e-01 4.441877e-02 -7.154462e+00 9.984482e-01 4.436107e-02 3.366426e-02 2.414586e+02 +3.170023e-02 4.558599e-02 -9.984573e-01 -6.441034e+00 -4.586583e-02 9.979733e-01 4.410770e-02 -7.157278e+00 9.984445e-01 4.439685e-02 3.372682e-02 2.414574e+02 +3.177846e-02 4.565542e-02 -9.984517e-01 -6.448340e+00 -4.594093e-02 9.979671e-01 4.417107e-02 -7.158324e+00 9.984385e-01 4.446610e-02 3.381131e-02 2.414564e+02 +3.185787e-02 4.526446e-02 -9.984670e-01 -6.445881e+00 -4.603004e-02 9.979805e-01 4.377375e-02 -7.158426e+00 9.984319e-01 4.456493e-02 3.387705e-02 2.414562e+02 +3.185098e-02 4.399996e-02 -9.985237e-01 -6.441440e+00 -4.631928e-02 9.980221e-01 4.250037e-02 -7.159400e+00 9.984187e-01 4.489721e-02 3.382603e-02 2.414561e+02 +3.195735e-02 4.223728e-02 -9.985964e-01 -6.441119e+00 -4.659687e-02 9.980833e-01 4.072438e-02 -7.161211e+00 9.984024e-01 4.523002e-02 3.386422e-02 2.414563e+02 +3.185990e-02 4.174043e-02 -9.986204e-01 -6.441162e+00 -4.668088e-02 9.980994e-01 4.022936e-02 -7.161957e+00 9.984016e-01 4.533477e-02 3.374783e-02 2.414591e+02 +3.178882e-02 4.223003e-02 -9.986021e-01 -6.439927e+00 -4.638389e-02 9.980929e-01 4.073195e-02 -7.160925e+00 9.984177e-01 4.502423e-02 3.368698e-02 2.414626e+02 +3.170929e-02 4.185072e-02 -9.986206e-01 -6.435729e+00 -4.602516e-02 9.981243e-01 4.036849e-02 -7.162727e+00 9.984368e-01 4.468161e-02 3.357600e-02 2.414683e+02 +3.147722e-02 4.154018e-02 -9.986409e-01 -6.435232e+00 -4.613712e-02 9.981313e-01 4.006475e-02 -7.164249e+00 9.984390e-01 4.481329e-02 3.333494e-02 2.414733e+02 +3.114961e-02 4.115968e-02 -9.986669e-01 -6.440440e+00 -4.610469e-02 9.981474e-01 3.970021e-02 -7.166143e+00 9.984508e-01 4.480658e-02 3.298955e-02 2.414828e+02 +3.108701e-02 4.056081e-02 -9.986934e-01 -6.449325e+00 -4.603399e-02 9.981741e-01 3.910680e-02 -7.162294e+00 9.984560e-01 4.475812e-02 3.289742e-02 2.414880e+02 +3.105899e-02 4.042378e-02 -9.986998e-01 -6.462353e+00 -4.593484e-02 9.981838e-01 3.897436e-02 -7.157896e+00 9.984614e-01 4.466461e-02 3.285944e-02 2.414935e+02 +3.098859e-02 4.053219e-02 -9.986976e-01 -6.480607e+00 -4.600033e-02 9.981765e-01 3.908370e-02 -7.153230e+00 9.984606e-01 4.472926e-02 3.279657e-02 2.414981e+02 +3.108834e-02 4.037203e-02 -9.987010e-01 -6.502415e+00 -4.593963e-02 9.981857e-01 3.892116e-02 -7.152502e+00 9.984603e-01 4.466995e-02 3.288661e-02 2.415018e+02 +3.114357e-02 4.018303e-02 -9.987069e-01 -6.528339e+00 -4.592933e-02 9.981936e-01 3.873013e-02 -7.151255e+00 9.984591e-01 4.466374e-02 3.293289e-02 2.415060e+02 +3.118041e-02 3.939027e-02 -9.987373e-01 -6.560264e+00 -4.592693e-02 9.982242e-01 3.793621e-02 -7.150510e+00 9.984580e-01 4.468607e-02 3.293411e-02 2.415077e+02 +3.151021e-02 3.709605e-02 -9.988148e-01 -6.603855e+00 -4.590655e-02 9.983101e-01 3.562907e-02 -7.149296e+00 9.984486e-01 4.472946e-02 3.315991e-02 2.415090e+02 +3.214448e-02 3.434114e-02 -9.988931e-01 -6.662736e+00 -4.586604e-02 9.984074e-01 3.284847e-02 -7.149164e+00 9.984302e-01 4.475937e-02 3.366837e-02 2.415123e+02 +3.337074e-02 3.224510e-02 -9.989228e-01 -6.742488e+00 -4.570207e-02 9.984831e-01 3.070416e-02 -7.147470e+00 9.983975e-01 4.462822e-02 3.479378e-02 2.415161e+02 +3.551186e-02 3.107362e-02 -9.988861e-01 -6.841205e+00 -4.549815e-02 9.985304e-01 2.944504e-02 -7.146762e+00 9.983330e-01 4.440181e-02 3.687346e-02 2.415229e+02 +3.904896e-02 3.013454e-02 -9.987828e-01 -6.960563e+00 -4.542079e-02 9.985655e-01 2.835220e-02 -7.146072e+00 9.982044e-01 4.425838e-02 4.036168e-02 2.415303e+02 +4.439619e-02 2.837773e-02 -9.986109e-01 -7.099251e+00 -4.503181e-02 9.986373e-01 2.637646e-02 -7.145097e+00 9.979985e-01 4.379824e-02 4.561359e-02 2.415417e+02 +5.169972e-02 2.698510e-02 -9.982981e-01 -7.256774e+00 -4.495861e-02 9.986842e-01 2.466724e-02 -7.142968e+00 9.976501e-01 4.360680e-02 5.284491e-02 2.415560e+02 +6.120976e-02 2.643534e-02 -9.977748e-01 -7.433982e+00 -4.555554e-02 9.986814e-01 2.366471e-02 -7.138124e+00 9.970847e-01 4.400565e-02 6.233333e-02 2.415750e+02 +7.270826e-02 2.614764e-02 -9.970105e-01 -7.627305e+00 -4.679329e-02 9.986448e-01 2.277805e-02 -7.130703e+00 9.962549e-01 4.499724e-02 7.383326e-02 2.415979e+02 +8.656549e-02 2.535974e-02 -9.959234e-01 -7.834980e+00 -4.844174e-02 9.986006e-01 2.121737e-02 -7.122577e+00 9.950677e-01 4.640756e-02 8.767281e-02 2.416234e+02 +1.026980e-01 2.596047e-02 -9.943738e-01 -8.055734e+00 -4.900017e-02 9.985778e-01 2.100954e-02 -7.117187e+00 9.935049e-01 4.656684e-02 1.038240e-01 2.416612e+02 +1.216410e-01 3.071668e-02 -9.920988e-01 -8.293171e+00 -4.812427e-02 9.985280e-01 2.501525e-02 -7.114535e+00 9.914068e-01 4.470115e-02 1.229401e-01 2.417050e+02 +1.441195e-01 3.574823e-02 -9.889144e-01 -8.540863e+00 -4.914636e-02 9.983726e-01 2.892780e-02 -7.111017e+00 9.883391e-01 4.443248e-02 1.456418e-01 2.417596e+02 +1.676810e-01 3.643599e-02 -9.851678e-01 -8.793327e+00 -5.046545e-02 9.983238e-01 2.833307e-02 -7.102833e+00 9.845487e-01 4.496602e-02 1.692387e-01 2.418206e+02 +1.937520e-01 3.543131e-02 -9.804106e-01 -9.050632e+00 -4.849689e-02 9.984717e-01 2.649992e-02 -7.098001e+00 9.798511e-01 4.241244e-02 1.951742e-01 2.418908e+02 +2.236658e-01 3.505221e-02 -9.740354e-01 -9.316724e+00 -4.638919e-02 9.986034e-01 2.528408e-02 -7.092475e+00 9.735613e-01 3.952952e-02 2.249795e-01 2.419850e+02 +2.566230e-01 3.490910e-02 -9.658810e-01 -9.588231e+00 -4.294145e-02 9.987725e-01 2.468885e-02 -7.088248e+00 9.655571e-01 3.514060e-02 2.578070e-01 2.420972e+02 +2.919401e-01 3.517341e-02 -9.557897e-01 -9.863606e+00 -3.836837e-02 9.989498e-01 2.504234e-02 -7.085354e+00 9.556667e-01 2.936123e-02 2.929830e-01 2.422077e+02 +3.313972e-01 3.834766e-02 -9.427117e-01 -1.014807e+01 -3.663018e-02 9.989433e-01 2.775822e-02 -7.081455e+00 9.427800e-01 2.533270e-02 3.324517e-01 2.423512e+02 +3.732099e-01 4.373391e-02 -9.267156e-01 -1.043713e+01 -3.828661e-02 9.987634e-01 3.171512e-02 -7.076031e+00 9.269565e-01 2.364440e-02 3.744228e-01 2.424854e+02 +4.172784e-01 4.806950e-02 -9.075066e-01 -1.072766e+01 -4.334647e-02 9.985163e-01 3.295915e-02 -7.069560e+00 9.077443e-01 2.558407e-02 4.187429e-01 2.426616e+02 +4.633272e-01 5.101507e-02 -8.847177e-01 -1.101459e+01 -4.799635e-02 9.983209e-01 3.243002e-02 -7.064329e+00 8.848866e-01 2.743751e-02 4.649977e-01 2.428586e+02 +5.098119e-01 5.221632e-02 -8.586998e-01 -1.129588e+01 -4.801255e-02 9.983275e-01 3.220174e-02 -7.059169e+00 8.589451e-01 2.481153e-02 5.114662e-01 2.430471e+02 +5.569376e-01 5.164291e-02 -8.289473e-01 -1.156617e+01 -4.545139e-02 9.984645e-01 3.166671e-02 -7.058609e+00 8.293098e-01 2.004042e-02 5.584296e-01 2.432941e+02 +6.044473e-01 4.887129e-02 -7.951447e-01 -1.182781e+01 -4.278162e-02 9.986675e-01 2.885883e-02 -7.059708e+00 7.954955e-01 1.657394e-02 6.057327e-01 2.435650e+02 +6.510547e-01 4.512475e-02 -7.576884e-01 -1.207917e+01 -4.234910e-02 9.988358e-01 2.309742e-02 -7.054224e+00 7.578485e-01 1.704974e-02 6.522077e-01 2.438100e+02 +6.971811e-01 3.975702e-02 -7.157918e-01 -1.231767e+01 -4.205941e-02 9.990095e-01 1.452185e-02 -7.048075e+00 7.156602e-01 1.998142e-02 6.981627e-01 2.441218e+02 +7.418464e-01 3.796311e-02 -6.694944e-01 -1.254841e+01 -4.460439e-02 9.989786e-01 7.221468e-03 -7.040201e+00 6.690847e-01 2.450517e-02 7.427819e-01 2.444066e+02 +7.845385e-01 3.766814e-02 -6.189350e-01 -1.276645e+01 -4.577573e-02 9.989479e-01 2.772012e-03 -7.039227e+00 6.183882e-01 2.615745e-02 7.854373e-01 2.447706e+02 +8.233369e-01 3.776799e-02 -5.662950e-01 -1.296987e+01 -4.441218e-02 9.990112e-01 2.056290e-03 -7.041870e+00 5.658127e-01 2.345738e-02 8.242000e-01 2.451641e+02 +8.573750e-01 3.416242e-02 -5.135573e-01 -1.315225e+01 -3.927378e-02 9.992281e-01 9.029155e-04 -7.045521e+00 5.131917e-01 1.939520e-02 8.580548e-01 2.455349e+02 +8.871323e-01 3.008649e-02 -4.605336e-01 -1.331828e+01 -3.384144e-02 9.994272e-01 1.029760e-04 -7.056461e+00 4.602728e-01 1.549377e-02 8.876422e-01 2.459798e+02 +9.126407e-01 2.660723e-02 -4.078960e-01 -1.346958e+01 -2.995712e-02 9.995495e-01 -1.826035e-03 -7.066833e+00 4.076636e-01 1.388590e-02 9.130265e-01 2.464412e+02 +9.337846e-01 2.360728e-02 -3.570561e-01 -1.360271e+01 -2.720910e-02 9.996169e-01 -5.066996e-03 -7.074069e+00 3.567997e-01 1.444666e-02 9.340691e-01 2.468869e+02 +9.507319e-01 2.143287e-02 -3.092726e-01 -1.372235e+01 -2.617588e-02 9.995947e-01 -1.119420e-02 -7.081737e+00 3.089073e-01 1.873816e-02 9.509075e-01 2.473819e+02 +9.645302e-01 2.088140e-02 -2.631455e-01 -1.382811e+01 -2.573414e-02 9.995561e-01 -1.500775e-02 -7.091706e+00 2.627153e-01 2.124725e-02 9.646394e-01 2.478773e+02 +9.750521e-01 2.050081e-02 -2.210276e-01 -1.391896e+01 -2.448105e-02 9.995834e-01 -1.528326e-02 -7.107983e+00 2.206222e-01 2.031296e-02 9.751477e-01 2.484226e+02 +9.827972e-01 2.010763e-02 -1.835902e-01 -1.399361e+01 -2.322719e-02 9.996198e-01 -1.485716e-02 -7.126064e+00 1.832216e-01 1.886586e-02 9.828905e-01 2.489891e+02 +9.883304e-01 1.935405e-02 -1.510909e-01 -1.405752e+01 -2.179091e-02 9.996575e-01 -1.448928e-02 -7.143097e+00 1.507587e-01 1.761260e-02 9.884136e-01 2.495580e+02 +9.921809e-01 1.665338e-02 -1.236926e-01 -1.410353e+01 -1.858093e-02 9.997230e-01 -1.444609e-02 -7.161301e+00 1.234178e-01 1.663145e-02 9.922154e-01 2.501686e+02 +9.946502e-01 1.350806e-02 -1.024142e-01 -1.414237e+01 -1.510162e-02 9.997764e-01 -1.480062e-02 -7.177194e+00 1.021914e-01 1.626806e-02 9.946317e-01 2.507760e+02 +9.962842e-01 1.150535e-02 -8.535498e-02 -1.417621e+01 -1.278396e-02 9.998139e-01 -1.444852e-02 -7.194110e+00 8.517285e-02 1.548601e-02 9.962458e-01 2.514059e+02 +9.973124e-01 1.063516e-02 -7.249081e-02 -1.421087e+01 -1.169431e-02 9.998307e-01 -1.420202e-02 -7.211060e+00 7.232750e-02 1.501158e-02 9.972679e-01 2.520577e+02 +9.979777e-01 1.000854e-02 -6.277310e-02 -1.424036e+01 -1.096630e-02 9.998284e-01 -1.493162e-02 -7.227459e+00 6.261288e-02 1.558981e-02 9.979161e-01 2.527243e+02 +9.984713e-01 9.784261e-03 -5.440052e-02 -1.426469e+01 -1.067759e-02 9.998125e-01 -1.615498e-02 -7.244408e+00 5.423225e-02 1.671115e-02 9.983884e-01 2.534050e+02 +9.988298e-01 8.648028e-03 -4.758561e-02 -1.428735e+01 -9.487898e-03 9.998027e-01 -1.745218e-02 -7.262488e+00 4.742529e-02 1.788324e-02 9.987146e-01 2.541031e+02 +9.990223e-01 8.114487e-03 -4.345983e-02 -1.430712e+01 -8.919116e-03 9.997918e-01 -1.835252e-02 -7.282421e+00 4.330186e-02 1.872219e-02 9.988865e-01 2.548169e+02 +9.991434e-01 7.492461e-03 -4.070019e-02 -1.432889e+01 -8.231782e-03 9.998036e-01 -1.802794e-02 -7.302451e+00 4.055712e-02 1.834752e-02 9.990087e-01 2.555442e+02 +9.992270e-01 7.280994e-03 -3.863134e-02 -1.434971e+01 -7.940312e-03 9.998249e-01 -1.694101e-02 -7.323118e+00 3.850122e-02 1.723466e-02 9.991099e-01 2.562902e+02 +9.992676e-01 7.770527e-03 -3.746952e-02 -1.437576e+01 -8.333282e-03 9.998544e-01 -1.488628e-02 -7.341575e+00 3.734839e-02 1.518762e-02 9.991868e-01 2.570548e+02 +9.992972e-01 7.176542e-03 -3.679222e-02 -1.439965e+01 -7.624023e-03 9.998985e-01 -1.203652e-02 -7.358411e+00 3.670210e-02 1.230856e-02 9.992504e-01 2.578376e+02 +9.992876e-01 6.676240e-03 -3.714609e-02 -1.442260e+01 -7.101514e-03 9.999106e-01 -1.132853e-02 -7.372660e+00 3.706713e-02 1.158425e-02 9.992456e-01 2.586323e+02 +9.992276e-01 5.891745e-03 -3.885420e-02 -1.444732e+01 -6.384081e-03 9.999007e-01 -1.255948e-02 -7.385382e+00 3.877635e-02 1.279783e-02 9.991659e-01 2.594409e+02 +9.991628e-01 4.458685e-03 -4.066817e-02 -1.447138e+01 -5.111776e-03 9.998594e-01 -1.596920e-02 -7.396035e+00 4.059125e-02 1.616371e-02 9.990450e-01 2.602632e+02 +9.990942e-01 6.010951e-03 -4.212781e-02 -1.449886e+01 -6.936102e-03 9.997372e-01 -2.184894e-02 -7.409775e+00 4.198540e-02 2.212134e-02 9.988732e-01 2.610941e+02 +9.990658e-01 8.135047e-03 -4.244319e-02 -1.452874e+01 -9.250828e-03 9.996150e-01 -2.615897e-02 -7.427194e+00 4.221405e-02 2.652717e-02 9.987563e-01 2.619434e+02 +9.990430e-01 1.004219e-02 -4.257084e-02 -1.456159e+01 -1.116962e-02 9.995909e-01 -2.632906e-02 -7.448031e+00 4.228902e-02 2.677936e-02 9.987464e-01 2.628078e+02 +9.990513e-01 1.056088e-02 -4.224966e-02 -1.459164e+01 -1.140066e-02 9.997412e-01 -1.968541e-02 -7.468860e+00 4.203083e-02 2.014841e-02 9.989131e-01 2.636919e+02 +9.990818e-01 1.032153e-02 -4.158202e-02 -1.462306e+01 -1.071466e-02 9.998999e-01 -9.242434e-03 -7.489532e+00 4.148246e-02 9.679484e-03 9.990923e-01 2.645856e+02 +9.991022e-01 8.576964e-03 -4.148808e-02 -1.465282e+01 -8.756423e-03 9.999530e-01 -4.145755e-03 -7.507641e+00 4.145058e-02 4.505320e-03 9.991303e-01 2.654917e+02 +9.991063e-01 4.707581e-03 -4.200629e-02 -1.468155e+01 -4.957871e-03 9.999705e-01 -5.856188e-03 -7.522891e+00 4.197748e-02 6.059215e-03 9.991001e-01 2.664038e+02 +9.990583e-01 1.247512e-03 -4.337041e-02 -1.470869e+01 -1.804954e-03 9.999162e-01 -1.281627e-02 -7.535572e+00 4.335078e-02 1.288249e-02 9.989768e-01 2.673230e+02 +9.990023e-01 -1.132359e-03 -4.464555e-02 -1.473976e+01 2.148140e-04 9.997888e-01 -2.055121e-02 -7.552162e+00 4.465939e-02 2.052111e-02 9.987914e-01 2.682544e+02 +9.989420e-01 -1.462056e-03 -4.596511e-02 -1.477556e+01 3.091421e-04 9.996854e-01 -2.507948e-02 -7.575616e+00 4.598732e-02 2.503874e-02 9.986281e-01 2.691985e+02 +9.989125e-01 -1.191959e-03 -4.660990e-02 -1.481424e+01 -2.887654e-05 9.996571e-01 -2.618319e-02 -7.605036e+00 4.662513e-02 2.615605e-02 9.985699e-01 2.701618e+02 +9.988735e-01 1.364250e-03 -4.743263e-02 -1.485834e+01 -2.523230e-03 9.996995e-01 -2.438295e-02 -7.636316e+00 4.738511e-02 2.447516e-02 9.985767e-01 2.711348e+02 +9.988723e-01 2.905000e-03 -4.738863e-02 -1.490154e+01 -3.788932e-03 9.998203e-01 -1.857367e-02 -7.666176e+00 4.732616e-02 1.873227e-02 9.987038e-01 2.721219e+02 +9.988801e-01 4.315237e-03 -4.711669e-02 -1.494400e+01 -4.830234e-03 9.999298e-01 -1.082186e-02 -7.692098e+00 4.706668e-02 1.103732e-02 9.988307e-01 2.731257e+02 +9.989308e-01 4.024903e-03 -4.605644e-02 -1.497353e+01 -4.345222e-03 9.999670e-01 -6.856915e-03 -7.717050e+00 4.602732e-02 7.049708e-03 9.989152e-01 2.741347e+02 +9.989498e-01 2.119031e-03 -4.577001e-02 -1.500587e+01 -2.515547e-03 9.999598e-01 -8.607377e-03 -7.737837e+00 4.574993e-02 8.713473e-03 9.989149e-01 2.751423e+02 +9.989640e-01 3.271503e-04 -4.550810e-02 -1.503534e+01 -9.187433e-04 9.999153e-01 -1.297942e-02 -7.761510e+00 4.550000e-02 1.300778e-02 9.988796e-01 2.761557e+02 +9.989413e-01 -6.527915e-04 -4.599968e-02 -1.506955e+01 -1.360693e-04 9.998530e-01 -1.714405e-02 -7.787226e+00 4.600411e-02 1.713216e-02 9.987943e-01 2.771757e+02 +9.989253e-01 -2.385309e-03 -4.628885e-02 -1.510295e+01 1.525131e-03 9.998256e-01 -1.860927e-02 -7.816972e+00 4.632517e-02 1.851867e-02 9.987547e-01 2.782078e+02 +9.988876e-01 -2.298772e-03 -4.709969e-02 -1.514094e+01 1.432700e-03 9.998294e-01 -1.841358e-02 -7.847445e+00 4.713399e-02 1.832561e-02 9.987204e-01 2.792453e+02 +9.988294e-01 -3.910977e-03 -4.821364e-02 -1.517521e+01 3.173488e-03 9.998769e-01 -1.536335e-02 -7.874001e+00 4.826778e-02 1.519236e-02 9.987188e-01 2.802936e+02 +9.987399e-01 -3.697907e-03 -5.005105e-02 -1.521559e+01 3.108383e-03 9.999249e-01 -1.185118e-02 -7.902476e+00 5.009111e-02 1.168066e-02 9.986763e-01 2.813463e+02 +9.986454e-01 -4.742608e-03 -5.181604e-02 -1.525743e+01 4.087801e-03 9.999105e-01 -1.273583e-02 -7.930494e+00 5.187180e-02 1.250676e-02 9.985754e-01 2.823977e+02 +9.985229e-01 -7.975316e-03 -5.374395e-02 -1.529723e+01 6.955752e-03 9.997928e-01 -1.913121e-02 -7.955939e+00 5.388539e-02 1.872912e-02 9.983714e-01 2.834464e+02 +9.984444e-01 -7.380052e-03 -5.526746e-02 -1.534119e+01 6.075483e-03 9.996998e-01 -2.373559e-02 -7.990759e+00 5.542604e-02 2.336289e-02 9.981894e-01 2.844978e+02 +9.983812e-01 -6.912109e-03 -5.645685e-02 -1.538588e+01 5.516813e-03 9.996764e-01 -2.483296e-02 -8.031229e+00 5.661022e-02 2.448129e-02 9.980961e-01 2.855557e+02 +9.983049e-01 -5.105044e-03 -5.797659e-02 -1.543659e+01 3.769235e-03 9.997254e-01 -2.312653e-02 -8.069890e+00 5.807873e-02 2.286880e-02 9.980500e-01 2.866196e+02 +9.982427e-01 -3.686731e-03 -5.914424e-02 -1.548438e+01 2.558879e-03 9.998136e-01 -1.913395e-02 -8.105104e+00 5.920376e-02 1.894898e-02 9.980660e-01 2.876852e+02 +9.981689e-01 -1.610070e-03 -6.046705e-02 -1.553562e+01 7.429468e-04 9.998966e-01 -1.436018e-02 -8.139637e+00 6.048392e-02 1.428896e-02 9.980668e-01 2.887506e+02 +9.981017e-01 4.768442e-05 -6.158783e-02 -1.558579e+01 -7.090934e-04 9.999423e-01 -1.071747e-02 -8.171223e+00 6.158377e-02 1.074079e-02 9.980441e-01 2.898109e+02 +9.980578e-01 2.519387e-03 -6.224415e-02 -1.563834e+01 -3.131490e-03 9.999477e-01 -9.738314e-03 -8.199249e+00 6.221636e-02 9.914316e-03 9.980134e-01 2.908664e+02 +9.980532e-01 2.632571e-03 -6.231318e-02 -1.568736e+01 -3.297814e-03 9.999386e-01 -1.057536e-02 -8.224551e+00 6.228152e-02 1.076027e-02 9.980006e-01 2.919147e+02 +9.980760e-01 1.323292e-03 -6.198871e-02 -1.573624e+01 -2.109184e-03 9.999182e-01 -1.261426e-02 -8.251678e+00 6.196694e-02 1.272074e-02 9.979971e-01 2.929596e+02 +9.980770e-01 1.955753e-03 -6.195659e-02 -1.578736e+01 -2.953217e-03 9.998674e-01 -1.601192e-02 -8.281877e+00 6.191706e-02 1.616410e-02 9.979503e-01 2.939980e+02 +9.980657e-01 3.718679e-04 -6.216768e-02 -1.583486e+01 -1.613933e-03 9.998000e-01 -1.993026e-02 -8.313716e+00 6.214783e-02 1.999204e-02 9.978667e-01 2.950365e+02 +9.980551e-01 6.113599e-04 -6.233626e-02 -1.588531e+01 -1.963118e-03 9.997642e-01 -2.162600e-02 -8.348776e+00 6.230834e-02 2.170631e-02 9.978208e-01 2.960719e+02 +9.980904e-01 1.530942e-03 -6.175197e-02 -1.593564e+01 -2.765562e-03 9.997979e-01 -1.991270e-02 -8.385496e+00 6.170900e-02 2.004545e-02 9.978928e-01 2.971070e+02 +9.981177e-01 3.726375e-03 -6.121435e-02 -1.599106e+01 -4.769569e-03 9.998457e-01 -1.690439e-02 -8.423964e+00 6.114191e-02 1.716453e-02 9.979814e-01 2.981391e+02 +9.981435e-01 5.930896e-03 -6.061700e-02 -1.604697e+01 -6.860732e-03 9.998618e-01 -1.514292e-02 -8.461541e+00 6.051880e-02 1.553068e-02 9.980462e-01 2.991656e+02 +9.981552e-01 7.384158e-03 -6.026477e-02 -1.610293e+01 -8.263692e-03 9.998627e-01 -1.435831e-02 -8.494666e+00 6.015047e-02 1.482983e-02 9.980791e-01 3.001912e+02 +9.981795e-01 9.191397e-03 -5.961014e-02 -1.616193e+01 -9.862368e-03 9.998912e-01 -1.097155e-02 -8.522851e+00 5.950280e-02 1.153948e-02 9.981614e-01 3.012168e+02 +9.982047e-01 1.162900e-02 -5.875564e-02 -1.621966e+01 -1.199174e-02 9.999111e-01 -5.824913e-03 -8.545531e+00 5.868267e-02 6.519037e-03 9.982553e-01 3.022463e+02 +9.982063e-01 1.422968e-02 -5.815372e-02 -1.627711e+01 -1.454371e-02 9.998818e-01 -4.980213e-03 -8.564683e+00 5.807598e-02 5.817050e-03 9.982952e-01 3.032743e+02 +9.981850e-01 1.709697e-02 -5.774464e-02 -1.633433e+01 -1.771294e-02 9.997913e-01 -1.017203e-02 -8.585233e+00 5.755868e-02 1.117639e-02 9.982795e-01 3.042939e+02 +9.981657e-01 1.886348e-02 -5.752832e-02 -1.638971e+01 -1.977332e-02 9.996876e-01 -1.528736e-02 -8.606509e+00 5.722198e-02 1.639684e-02 9.982268e-01 3.053141e+02 +9.981468e-01 2.150165e-02 -5.692666e-02 -1.644631e+01 -2.253866e-02 9.995904e-01 -1.763756e-02 -8.631852e+00 5.652410e-02 1.888792e-02 9.982225e-01 3.063356e+02 +9.981021e-01 2.478627e-02 -5.637325e-02 -1.650343e+01 -2.584925e-02 9.995000e-01 -1.820552e-02 -8.662702e+00 5.589382e-02 1.962817e-02 9.982437e-01 3.073565e+02 +9.980666e-01 2.695554e-02 -5.600554e-02 -1.655969e+01 -2.811222e-02 9.994053e-01 -1.996868e-02 -8.692187e+00 5.543396e-02 2.150450e-02 9.982307e-01 3.083783e+02 +9.980493e-01 2.768966e-02 -5.595444e-02 -1.661304e+01 -2.878223e-02 9.994086e-01 -1.881517e-02 -8.722646e+00 5.540036e-02 2.038896e-02 9.982560e-01 3.093998e+02 +9.980319e-01 2.817050e-02 -5.602515e-02 -1.666632e+01 -2.913385e-02 9.994401e-01 -1.645301e-02 -8.754727e+00 5.553029e-02 1.805286e-02 9.982937e-01 3.104297e+02 +9.980327e-01 2.744582e-02 -5.637045e-02 -1.670935e+01 -2.830643e-02 9.994937e-01 -1.452562e-02 -8.785016e+00 5.594324e-02 1.609268e-02 9.983042e-01 3.114589e+02 +9.980200e-01 2.710993e-02 -5.675649e-02 -1.675029e+01 -2.793765e-02 9.995138e-01 -1.384130e-02 -8.813019e+00 5.635366e-02 1.539954e-02 9.982920e-01 3.124903e+02 +9.980008e-01 2.806362e-02 -5.663033e-02 -1.679627e+01 -2.890272e-02 9.994834e-01 -1.405281e-02 -8.839964e+00 5.620670e-02 1.566148e-02 9.982963e-01 3.135254e+02 +9.980613e-01 2.765939e-02 -5.575568e-02 -1.683930e+01 -2.849716e-02 9.994917e-01 -1.428705e-02 -8.867010e+00 5.533217e-02 1.584823e-02 9.983422e-01 3.145633e+02 +9.981009e-01 2.783125e-02 -5.495629e-02 -1.688389e+01 -2.864324e-02 9.994910e-01 -1.404317e-02 -8.894774e+00 5.453748e-02 1.559063e-02 9.983899e-01 3.156082e+02 +9.981614e-01 2.695400e-02 -5.428964e-02 -1.692691e+01 -2.777838e-02 9.995091e-01 -1.448769e-02 -8.922586e+00 5.387248e-02 1.596913e-02 9.984201e-01 3.166562e+02 +9.981692e-01 2.755228e-02 -5.384389e-02 -1.697227e+01 -2.838637e-02 9.994876e-01 -1.478765e-02 -8.954986e+00 5.340886e-02 1.628901e-02 9.984398e-01 3.177092e+02 +9.981900e-01 2.806323e-02 -5.319097e-02 -1.702224e+01 -2.881130e-02 9.994957e-01 -1.334943e-02 -8.983779e+00 5.278951e-02 1.485776e-02 9.984951e-01 3.187691e+02 +9.982522e-01 2.697717e-02 -5.258238e-02 -1.706905e+01 -2.776246e-02 9.995128e-01 -1.426161e-02 -9.017426e+00 5.217202e-02 1.569650e-02 9.985147e-01 3.198317e+02 +9.982316e-01 2.808579e-02 -5.239269e-02 -1.711840e+01 -2.911760e-02 9.993947e-01 -1.903520e-02 -9.048416e+00 5.182636e-02 2.052708e-02 9.984451e-01 3.208931e+02 +9.982310e-01 2.804119e-02 -5.242845e-02 -1.717214e+01 -2.926733e-02 9.993123e-01 -2.276701e-02 -9.084710e+00 5.175398e-02 2.426117e-02 9.983651e-01 3.219660e+02 +9.982750e-01 2.633589e-02 -5.247431e-02 -1.722368e+01 -2.739219e-02 9.994343e-01 -1.951331e-02 -9.122043e+00 5.193072e-02 2.091703e-02 9.984316e-01 3.230455e+02 +9.982835e-01 2.685334e-02 -5.204802e-02 -1.728170e+01 -2.763333e-02 9.995155e-01 -1.432442e-02 -9.164148e+00 5.163814e-02 1.573809e-02 9.985418e-01 3.241272e+02 +9.982801e-01 2.795495e-02 -5.153154e-02 -1.733875e+01 -2.858648e-02 9.995245e-01 -1.155910e-02 -9.202510e+00 5.118389e-02 1.301232e-02 9.986044e-01 3.252114e+02 +9.983401e-01 2.681858e-02 -5.096930e-02 -1.739586e+01 -2.734100e-02 9.995802e-01 -9.579940e-03 -9.238189e+00 5.069098e-02 1.095759e-02 9.986542e-01 3.262940e+02 +9.983392e-01 2.756337e-02 -5.058741e-02 -1.745438e+01 -2.798429e-02 9.995792e-01 -7.631242e-03 -9.272285e+00 5.035578e-02 9.034220e-03 9.986904e-01 3.273754e+02 +9.984003e-01 2.571505e-02 -5.035630e-02 -1.750894e+01 -2.610599e-02 9.996338e-01 -7.121138e-03 -9.305503e+00 5.015474e-02 8.424346e-03 9.987059e-01 3.284521e+02 +9.984555e-01 2.281474e-02 -5.065657e-02 -1.756163e+01 -2.329993e-02 9.996879e-01 -9.008098e-03 -9.339167e+00 5.043524e-02 1.017448e-02 9.986755e-01 3.295244e+02 +9.984733e-01 2.147258e-02 -5.089227e-02 -1.761419e+01 -2.210281e-02 9.996854e-01 -1.185325e-02 -9.373015e+00 5.062174e-02 1.296001e-02 9.986338e-01 3.305939e+02 +9.984995e-01 1.930106e-02 -5.124836e-02 -1.766713e+01 -2.003001e-02 9.997048e-01 -1.374839e-02 -9.408480e+00 5.096787e-02 1.475426e-02 9.985912e-01 3.316621e+02 +9.985037e-01 1.822851e-02 -5.155769e-02 -1.771901e+01 -1.887459e-02 9.997490e-01 -1.207225e-02 -9.442686e+00 5.132469e-02 1.302731e-02 9.985970e-01 3.327313e+02 +9.985493e-01 1.574748e-02 -5.149140e-02 -1.777586e+01 -1.624307e-02 9.998255e-01 -9.220505e-03 -9.476537e+00 5.133721e-02 1.004351e-02 9.986308e-01 3.338025e+02 +9.985773e-01 1.325286e-02 -5.165107e-02 -1.783594e+01 -1.356460e-02 9.998918e-01 -5.689473e-03 -9.508603e+00 5.157007e-02 6.382004e-03 9.986489e-01 3.348728e+02 +9.985967e-01 1.064236e-02 -5.187940e-02 -1.790043e+01 -1.084865e-02 9.999343e-01 -3.696252e-03 -9.541916e+00 5.183665e-02 4.253886e-03 9.986465e-01 3.359393e+02 +9.986036e-01 7.811883e-03 -5.224871e-02 -1.795961e+01 -8.174264e-03 9.999439e-01 -6.725582e-03 -9.572257e+00 5.219324e-02 7.143284e-03 9.986114e-01 3.369952e+02 +9.986097e-01 4.252037e-03 -5.254244e-02 -1.801787e+01 -4.852603e-03 9.999243e-01 -1.130783e-02 -9.602235e+00 5.249038e-02 1.154708e-02 9.985546e-01 3.380469e+02 +9.985969e-01 2.612049e-03 -5.289080e-02 -1.807196e+01 -3.293556e-03 9.999126e-01 -1.280210e-02 -9.634547e+00 5.285274e-02 1.295833e-02 9.985182e-01 3.390980e+02 +9.985694e-01 1.754677e-03 -5.344295e-02 -1.812844e+01 -2.379828e-03 9.999294e-01 -1.163614e-02 -9.671642e+00 5.341876e-02 1.174668e-02 9.985030e-01 3.401343e+02 +9.985231e-01 -5.164091e-05 -5.432863e-02 -1.818459e+01 -4.450667e-04 9.999582e-01 -9.130511e-03 -9.708592e+00 5.432683e-02 9.141205e-03 9.984813e-01 3.411635e+02 +9.984600e-01 -1.904697e-03 -5.544415e-02 -1.823973e+01 1.540662e-03 9.999770e-01 -6.607799e-03 -9.742058e+00 5.545545e-02 6.512202e-03 9.984399e-01 3.421813e+02 +9.984080e-01 -3.499733e-03 -5.629613e-02 -1.829564e+01 3.306891e-03 9.999883e-01 -3.518292e-03 -9.773282e+00 5.630778e-02 3.326525e-03 9.984079e-01 3.431919e+02 +9.983343e-01 -5.552358e-03 -5.742732e-02 -1.834619e+01 5.432087e-03 9.999827e-01 -2.250220e-03 -9.800677e+00 5.743882e-02 1.934522e-03 9.983471e-01 3.441923e+02 +9.982580e-01 -7.305779e-03 -5.854621e-02 -1.839821e+01 7.121750e-03 9.999690e-01 -3.351354e-03 -9.829370e+00 5.856887e-02 2.928565e-03 9.982790e-01 3.451844e+02 +9.981817e-01 -9.071191e-03 -5.959162e-02 -1.845308e+01 8.779304e-03 9.999481e-01 -5.158145e-03 -9.855773e+00 5.963532e-02 4.625593e-03 9.982095e-01 3.461690e+02 +9.981170e-01 -9.075693e-03 -6.066500e-02 -1.851181e+01 8.679338e-03 9.999392e-01 -6.793847e-03 -9.882062e+00 6.072297e-02 6.254521e-03 9.981350e-01 3.471442e+02 +9.980733e-01 -7.636205e-03 -6.157438e-02 -1.857248e+01 7.199344e-03 9.999473e-01 -7.313618e-03 -9.908893e+00 6.162698e-02 6.856232e-03 9.980756e-01 3.481059e+02 +9.980269e-01 -7.307747e-03 -6.236224e-02 -1.863261e+01 6.856186e-03 9.999487e-01 -7.451883e-03 -9.935871e+00 6.241350e-02 7.009612e-03 9.980257e-01 3.490562e+02 +9.979955e-01 -6.581295e-03 -6.294219e-02 -1.869263e+01 6.201206e-03 9.999613e-01 -6.232169e-03 -9.964349e+00 6.298076e-02 5.829359e-03 9.979977e-01 3.499968e+02 +9.979777e-01 -4.895669e-03 -6.337752e-02 -1.875506e+01 4.584373e-03 9.999767e-01 -5.056268e-03 -9.993081e+00 6.340079e-02 4.755496e-03 9.979768e-01 3.509250e+02 +9.979606e-01 -2.742424e-03 -6.377420e-02 -1.881771e+01 2.345222e-03 9.999774e-01 -6.302295e-03 -1.002007e+01 6.379004e-02 6.139877e-03 9.979444e-01 3.518411e+02 +9.979539e-01 -2.004775e-03 -6.390638e-02 -1.887668e+01 1.486504e-03 9.999656e-01 -8.156372e-03 -1.004361e+01 6.392053e-02 8.044686e-03 9.979225e-01 3.527376e+02 +9.979927e-01 -2.650640e-03 -6.327444e-02 -1.893231e+01 2.054009e-03 9.999528e-01 -9.492455e-03 -1.006499e+01 6.329661e-02 9.343433e-03 9.979510e-01 3.536193e+02 +9.980688e-01 -2.200870e-03 -6.208002e-02 -1.898645e+01 1.649294e-03 9.999587e-01 -8.934767e-03 -1.009002e+01 6.209712e-02 8.815123e-03 9.980311e-01 3.544884e+02 +9.981740e-01 -1.421829e-03 -6.038857e-02 -1.903898e+01 9.237563e-04 9.999653e-01 -8.274912e-03 -1.011649e+01 6.039824e-02 8.204016e-03 9.981406e-01 3.553388e+02 +9.982707e-01 -2.958885e-03 -5.871090e-02 -1.908444e+01 2.558607e-03 9.999730e-01 -6.891801e-03 -1.014361e+01 5.872970e-02 6.729665e-03 9.982512e-01 3.561720e+02 +9.983501e-01 -5.015791e-03 -5.720178e-02 -1.912487e+01 4.652761e-03 9.999682e-01 -6.477911e-03 -1.017245e+01 5.723245e-02 6.201076e-03 9.983416e-01 3.569824e+02 +9.984377e-01 -5.386841e-03 -5.561598e-02 -1.916170e+01 5.084692e-03 9.999715e-01 -5.572844e-03 -1.020380e+01 5.564442e-02 5.281347e-03 9.984366e-01 3.577702e+02 +9.985141e-01 -7.980842e-03 -5.390679e-02 -1.919084e+01 7.796447e-03 9.999630e-01 -3.630072e-03 -1.023706e+01 5.393376e-02 3.204396e-03 9.985393e-01 3.585447e+02 +9.985803e-01 -9.202805e-03 -5.246779e-02 -1.922093e+01 9.115056e-03 9.999566e-01 -1.911510e-03 -1.026248e+01 5.248311e-02 1.430549e-03 9.986207e-01 3.592895e+02 +9.986795e-01 -7.186209e-03 -5.087034e-02 -1.925385e+01 7.179260e-03 9.999742e-01 -3.193450e-04 -1.028902e+01 5.087132e-02 -4.628740e-05 9.987052e-01 3.600121e+02 +9.987562e-01 -7.251884e-03 -4.933017e-02 -1.928152e+01 7.257127e-03 9.999736e-01 -7.282749e-05 -1.031346e+01 4.932939e-02 -2.852576e-04 9.987825e-01 3.607091e+02 +9.988048e-01 -7.620574e-03 -4.828057e-02 -1.931045e+01 7.470628e-03 9.999667e-01 -3.285431e-03 -1.034004e+01 4.830399e-02 2.920818e-03 9.988284e-01 3.613777e+02 +9.988640e-01 -7.962988e-03 -4.698197e-02 -1.933791e+01 7.556177e-03 9.999324e-01 -8.830138e-03 -1.036798e+01 4.704911e-02 8.465103e-03 9.988567e-01 3.620224e+02 +9.989318e-01 -7.630449e-03 -4.557471e-02 -1.936488e+01 7.101791e-03 9.999057e-01 -1.175049e-02 -1.039159e+01 4.566007e-02 1.141427e-02 9.988918e-01 3.626482e+02 +9.989751e-01 -7.181600e-03 -4.469035e-02 -1.939005e+01 6.700128e-03 9.999180e-01 -1.091400e-02 -1.041291e+01 4.476506e-02 1.060338e-02 9.989412e-01 3.632540e+02 +9.989926e-01 -7.481992e-03 -4.424791e-02 -1.941263e+01 7.100457e-03 9.999363e-01 -8.773571e-03 -1.043387e+01 4.431073e-02 8.450552e-03 9.989820e-01 3.638417e+02 +9.989841e-01 -7.408061e-03 -4.445172e-02 -1.943538e+01 7.196113e-03 9.999620e-01 -4.926187e-03 -1.046051e+01 4.448652e-02 4.601302e-03 9.989993e-01 3.644048e+02 +9.989025e-01 -7.148054e-03 -4.629010e-02 -1.945834e+01 7.005405e-03 9.999702e-01 -3.243141e-03 -1.048547e+01 4.631190e-02 2.915301e-03 9.989227e-01 3.649459e+02 +9.987303e-01 -5.839828e-03 -5.003797e-02 -1.948219e+01 5.561817e-03 9.999683e-01 -5.693446e-03 -1.050845e+01 5.006963e-02 5.407914e-03 9.987310e-01 3.654565e+02 +9.984418e-01 -4.930242e-03 -5.558556e-02 -1.951293e+01 4.420359e-03 9.999470e-01 -9.292167e-03 -1.052766e+01 5.562842e-02 9.031979e-03 9.984106e-01 3.659466e+02 +9.979648e-01 -4.067365e-03 -6.363771e-02 -1.955244e+01 3.304268e-03 9.999214e-01 -1.209194e-02 -1.054957e+01 6.368189e-02 1.185705e-02 9.978998e-01 3.664174e+02 +9.971397e-01 -4.126093e-03 -7.546833e-02 -1.959573e+01 3.147394e-03 9.999094e-01 -1.308269e-02 -1.057038e+01 7.551548e-02 1.280774e-02 9.970623e-01 3.668759e+02 +9.958645e-01 -3.743720e-03 -9.077401e-02 -1.964989e+01 2.475095e-03 9.998977e-01 -1.408419e-02 -1.059195e+01 9.081745e-02 1.380127e-02 9.957719e-01 3.673221e+02 +9.940304e-01 -1.950481e-03 -1.090860e-01 -1.971691e+01 3.369825e-04 9.998903e-01 -1.480755e-02 -1.061419e+01 1.091029e-01 1.468239e-02 9.939220e-01 3.677556e+02 +9.914550e-01 1.298631e-03 -1.304433e-01 -1.979756e+01 -3.145821e-03 9.998976e-01 -1.395580e-02 -1.063599e+01 1.304118e-01 1.424690e-02 9.913575e-01 3.681930e+02 +9.878196e-01 4.390917e-03 -1.555418e-01 -1.989223e+01 -6.258518e-03 9.999140e-01 -1.151939e-02 -1.065635e+01 1.554778e-01 1.235253e-02 9.877621e-01 3.686282e+02 +9.827850e-01 4.520839e-03 -1.846978e-01 -1.999201e+01 -5.948586e-03 9.999565e-01 -7.176795e-03 -1.067197e+01 1.846573e-01 8.151937e-03 9.827691e-01 3.690442e+02 +9.758239e-01 3.941942e-03 -2.185231e-01 -2.011145e+01 -5.177860e-03 9.999737e-01 -5.083399e-03 -1.069258e+01 2.184973e-01 6.091984e-03 9.758185e-01 3.694708e+02 +9.663979e-01 4.343598e-03 -2.570142e-01 -2.025209e+01 -5.620668e-03 9.999752e-01 -4.234440e-03 -1.071488e+01 2.569895e-01 5.536746e-03 9.663983e-01 3.698915e+02 +9.543646e-01 7.912236e-03 -2.985393e-01 -2.041310e+01 -8.955059e-03 9.999576e-01 -2.125312e-03 -1.073262e+01 2.985098e-01 4.701761e-03 9.543949e-01 3.702672e+02 +9.398804e-01 1.262340e-02 -3.412706e-01 -2.059635e+01 -1.277685e-02 9.999167e-01 1.798107e-03 -1.074732e+01 3.412649e-01 2.670359e-03 9.399633e-01 3.706619e+02 +9.228212e-01 1.690747e-02 -3.848573e-01 -2.079175e+01 -1.539227e-02 9.998569e-01 7.017531e-03 -1.075976e+01 3.849209e-01 -5.520978e-04 9.229493e-01 3.710542e+02 +9.027482e-01 1.751854e-02 -4.298126e-01 -2.099448e+01 -1.391458e-02 9.998367e-01 1.152669e-02 -1.076923e+01 4.299443e-01 -4.425029e-03 9.028445e-01 3.713905e+02 +8.796044e-01 2.149342e-02 -4.752202e-01 -2.122593e+01 -1.553767e-02 9.997438e-01 1.645744e-02 -1.077923e+01 4.754522e-01 -7.092220e-03 8.797129e-01 3.717584e+02 +8.523648e-01 2.856964e-02 -5.221668e-01 -2.148733e+01 -2.085011e-02 9.995692e-01 2.065516e-02 -1.079175e+01 5.225319e-01 -6.718489e-03 8.525932e-01 3.721192e+02 +8.212983e-01 3.651026e-02 -5.693296e-01 -2.176792e+01 -2.673728e-02 9.993168e-01 2.551430e-02 -1.078903e+01 5.698721e-01 -5.732523e-03 8.217133e-01 3.724120e+02 +7.867686e-01 4.160532e-02 -6.158443e-01 -2.207385e+01 -2.766828e-02 9.991000e-01 3.214992e-02 -1.078485e+01 6.166277e-01 -8.255185e-03 7.872116e-01 3.727666e+02 +7.486532e-01 4.278519e-02 -6.615799e-01 -2.240006e+01 -2.352688e-02 9.990014e-01 3.798332e-02 -1.077442e+01 6.625443e-01 -1.287142e-02 7.489121e-01 3.731138e+02 +7.068168e-01 4.118838e-02 -7.061965e-01 -2.274041e+01 -1.666484e-02 9.989959e-01 4.158621e-02 -1.076969e+01 7.072003e-01 -1.762518e-02 7.067935e-01 3.733813e+02 +6.614981e-01 4.179807e-02 -7.487811e-01 -2.311657e+01 -9.999883e-03 9.988484e-01 4.692298e-02 -1.076253e+01 7.498801e-01 -2.355173e-02 6.611543e-01 3.736999e+02 +6.128729e-01 4.327422e-02 -7.889957e-01 -2.351416e+01 -4.725865e-03 9.986821e-01 5.110401e-02 -1.074819e+01 7.901674e-01 -2.759156e-02 6.122696e-01 3.739226e+02 +5.598859e-01 3.951947e-02 -8.276267e-01 -2.393140e+01 3.706369e-03 9.987324e-01 5.019718e-02 -1.072974e+01 8.285614e-01 -3.117217e-02 5.590297e-01 3.741995e+02 +5.031833e-01 3.489118e-02 -8.634751e-01 -2.437041e+01 1.238171e-02 9.987909e-01 4.757436e-02 -1.071168e+01 8.640910e-01 -3.462991e-02 5.021429e-01 3.744566e+02 +4.432234e-01 3.354891e-02 -8.957832e-01 -2.482872e+01 1.370107e-02 9.989291e-01 4.419107e-02 -1.070388e+01 8.963065e-01 -3.185969e-02 4.422890e-01 3.745891e+02 +3.802574e-01 3.290759e-02 -9.242951e-01 -2.531190e+01 1.358916e-02 9.990601e-01 4.116007e-02 -1.069490e+01 9.247808e-01 -2.821181e-02 3.794528e-01 3.747754e+02 +3.156375e-01 2.922396e-02 -9.484297e-01 -2.580661e+01 1.738300e-02 9.991798e-01 3.657279e-02 -1.068257e+01 9.487206e-01 -2.803029e-02 3.148706e-01 3.749355e+02 +2.501886e-01 2.461508e-02 -9.678842e-01 -2.631378e+01 3.032354e-02 9.989871e-01 3.324443e-02 -1.066974e+01 9.677221e-01 -3.766704e-02 2.491887e-01 3.749978e+02 +1.858934e-01 2.908500e-02 -9.821394e-01 -2.684913e+01 3.368512e-02 9.987856e-01 3.595368e-02 -1.065755e+01 9.819923e-01 -3.976702e-02 1.846879e-01 3.751027e+02 +1.257519e-01 3.922354e-02 -9.912860e-01 -2.740599e+01 2.738880e-02 9.986999e-01 4.299137e-02 -1.064986e+01 9.916835e-01 -3.255637e-02 1.245141e-01 3.751528e+02 +7.102653e-02 4.827880e-02 -9.963054e-01 -2.796897e+01 1.710392e-02 9.986222e-01 4.961041e-02 -1.063684e+01 9.973277e-01 -2.056437e-02 7.010291e-02 3.751080e+02 +2.305901e-02 5.233677e-02 -9.983633e-01 -2.854132e+01 7.376844e-03 9.985926e-01 5.251919e-02 -1.062462e+01 9.997068e-01 -8.575804e-03 2.264047e-02 3.750885e+02 +-1.792318e-02 5.391266e-02 -9.983848e-01 -2.912195e+01 2.374449e-03 9.985446e-01 5.387868e-02 -1.060557e+01 9.998365e-01 -1.404931e-03 -1.802511e-02 3.750327e+02 +-4.827881e-02 5.930858e-02 -9.970716e-01 -2.972223e+01 -5.899366e-04 9.982337e-01 5.940629e-02 -1.058472e+01 9.988337e-01 3.456278e-03 -4.815854e-02 3.749866e+02 +-7.000877e-02 6.580012e-02 -9.953739e-01 -3.033161e+01 -1.597988e-03 9.978134e-01 6.607380e-02 -1.056036e+01 9.975451e-01 6.216345e-03 -6.975054e-02 3.749304e+02 +-8.720875e-02 6.846012e-02 -9.938349e-01 -3.094654e+01 -3.293942e-03 9.976106e-01 6.900926e-02 -1.053899e+01 9.961846e-01 9.291849e-03 -8.677486e-02 3.748624e+02 +-9.738643e-02 6.444002e-02 -9.931583e-01 -3.156150e+01 -8.522140e-03 9.978111e-01 6.557758e-02 -1.051891e+01 9.952101e-01 1.485020e-02 -9.662409e-02 3.747889e+02 +-1.031194e-01 5.304976e-02 -9.932533e-01 -3.217858e+01 -1.235733e-02 9.984313e-01 5.460926e-02 -1.049498e+01 9.945922e-01 1.790524e-02 -1.023021e-01 3.747144e+02 +-1.059933e-01 4.028742e-02 -9.935504e-01 -3.280730e+01 -1.301408e-02 9.990371e-01 4.189827e-02 -1.046742e+01 9.942816e-01 1.737108e-02 -1.053669e-01 3.746461e+02 +-1.059440e-01 3.481156e-02 -9.937626e-01 -3.345603e+01 -9.943746e-03 9.992999e-01 3.606564e-02 -1.044538e+01 9.943223e-01 1.370266e-02 -1.055237e-01 3.745824e+02 +-1.044871e-01 3.834089e-02 -9.937869e-01 -3.412460e+01 -6.761890e-03 9.992061e-01 3.926092e-02 -1.043010e+01 9.945032e-01 1.082214e-02 -1.041449e-01 3.745193e+02 +-1.034141e-01 4.456558e-02 -9.936395e-01 -3.480652e+01 -4.516770e-03 9.989644e-01 4.527450e-02 -1.041950e+01 9.946281e-01 9.170066e-03 -1.031057e-01 3.744543e+02 +-1.026641e-01 4.646491e-02 -9.936303e-01 -3.549402e+01 -5.460093e-03 9.988670e-01 4.727396e-02 -1.040427e+01 9.947011e-01 1.027865e-02 -1.022941e-01 3.743853e+02 +-1.017117e-01 4.631928e-02 -9.937350e-01 -3.619251e+01 -8.073540e-03 9.988441e-01 4.738378e-02 -1.038614e+01 9.947811e-01 1.284245e-02 -1.012201e-01 3.743120e+02 +-1.005378e-01 4.528225e-02 -9.939023e-01 -3.690223e+01 -1.181186e-02 9.988390e-01 4.670200e-02 -1.036462e+01 9.948631e-01 1.643515e-02 -9.988617e-02 3.742372e+02 +-9.752465e-02 4.322706e-02 -9.942939e-01 -3.762426e+01 -1.683617e-02 9.988416e-01 4.507614e-02 -1.034508e+01 9.950907e-01 2.113614e-02 -9.668390e-02 3.741631e+02 +-9.296835e-02 4.170676e-02 -9.947952e-01 -3.836035e+01 -1.995138e-02 9.988436e-01 4.374105e-02 -1.032578e+01 9.954691e-01 2.391407e-02 -9.202874e-02 3.740890e+02 +-8.863652e-02 4.189795e-02 -9.951825e-01 -3.911122e+01 -2.284854e-02 9.987665e-01 4.408387e-02 -1.030501e+01 9.958019e-01 2.664590e-02 -8.756987e-02 3.740170e+02 +-8.436246e-02 4.444280e-02 -9.954436e-01 -3.988459e+01 -2.433195e-02 9.986150e-01 4.664650e-02 -1.028617e+01 9.961380e-01 2.815629e-02 -8.316424e-02 3.739571e+02 +-8.018097e-02 4.803644e-02 -9.956222e-01 -4.067409e+01 -2.744073e-02 9.983531e-01 5.037811e-02 -1.026296e+01 9.964025e-01 3.135997e-02 -7.873076e-02 3.738909e+02 +-7.676122e-02 5.010214e-02 -9.957899e-01 -4.147522e+01 -2.919341e-02 9.981955e-01 5.247358e-02 -1.024075e+01 9.966220e-01 3.309844e-02 -7.516005e-02 3.738277e+02 +-7.383626e-02 4.858678e-02 -9.960861e-01 -4.229422e+01 -2.994891e-02 9.982539e-01 5.091253e-02 -1.020926e+01 9.968205e-01 3.359089e-02 -7.225221e-02 3.737678e+02 +-7.058995e-02 4.572886e-02 -9.964567e-01 -4.312535e+01 -2.838747e-02 9.984519e-01 4.783143e-02 -1.017746e+01 9.971014e-01 3.166331e-02 -6.918254e-02 3.737174e+02 +-6.697657e-02 4.619894e-02 -9.966844e-01 -4.397811e+01 -2.602609e-02 9.985066e-01 4.803235e-02 -1.014326e+01 9.974150e-01 2.915684e-02 -6.567417e-02 3.736686e+02 +-6.389866e-02 5.055652e-02 -9.966750e-01 -4.485127e+01 -2.613449e-02 9.982886e-01 5.231391e-02 -1.010567e+01 9.976141e-01 2.939038e-02 -6.246804e-02 3.736186e+02 +-6.060847e-02 5.610264e-02 -9.965837e-01 -4.573389e+01 -2.551888e-02 9.980057e-01 5.773466e-02 -1.007084e+01 9.978353e-01 2.893091e-02 -5.905592e-02 3.735706e+02 +-5.771309e-02 6.146979e-02 -9.964390e-01 -4.662626e+01 -2.393362e-02 9.977305e-01 6.293570e-02 -1.002954e+01 9.980462e-01 2.748061e-02 -5.611092e-02 3.735291e+02 +-5.477673e-02 6.289815e-02 -9.965156e-01 -4.752284e+01 -2.269734e-02 9.976776e-01 6.421914e-02 -9.991003e+00 9.982406e-01 2.613597e-02 -5.322189e-02 3.734909e+02 +-5.204313e-02 6.247196e-02 -9.966889e-01 -4.842205e+01 -2.477983e-02 9.976533e-01 6.382632e-02 -9.953142e+00 9.983373e-01 2.801951e-02 -5.037295e-02 3.734503e+02 +-5.006292e-02 5.792578e-02 -9.970649e-01 -4.932645e+01 -2.674703e-02 9.978808e-01 5.931617e-02 -9.914375e+00 9.983878e-01 2.963806e-02 -4.840749e-02 3.734089e+02 +-4.895235e-02 5.440657e-02 -9.973182e-01 -5.023736e+01 -2.614553e-02 9.981033e-01 5.573273e-02 -9.876888e+00 9.984588e-01 2.880366e-02 -4.743702e-02 3.733720e+02 +-4.844080e-02 5.342693e-02 -9.973962e-01 -5.115358e+01 -2.516498e-02 9.981861e-01 5.469145e-02 -9.841602e+00 9.985090e-01 2.774875e-02 -4.700845e-02 3.733369e+02 +-4.862114e-02 5.432673e-02 -9.973388e-01 -5.207555e+01 -2.479428e-02 9.981463e-01 5.557947e-02 -9.806627e+00 9.985095e-01 2.743063e-02 -4.718402e-02 3.732968e+02 +-4.949872e-02 5.540540e-02 -9.972363e-01 -5.300011e+01 -2.392873e-02 9.981078e-01 5.664156e-02 -9.773933e+00 9.984875e-01 2.666628e-02 -4.807927e-02 3.732575e+02 +-5.049479e-02 5.646806e-02 -9.971267e-01 -5.391919e+01 -2.318753e-02 9.980649e-01 5.769543e-02 -9.738669e+00 9.984551e-01 2.603423e-02 -4.908772e-02 3.732173e+02 +-5.177777e-02 5.708943e-02 -9.970255e-01 -5.483668e+01 -2.481405e-02 9.979829e-01 5.843291e-02 -9.701954e+00 9.983503e-01 2.776577e-02 -5.025671e-02 3.731742e+02 +-5.312263e-02 5.794277e-02 -9.969056e-01 -5.575461e+01 -2.731211e-02 9.978573e-01 5.945350e-02 -9.666145e+00 9.982144e-01 3.038592e-02 -5.142626e-02 3.731277e+02 +-5.424670e-02 5.810904e-02 -9.968353e-01 -5.666814e+01 -2.844995e-02 9.978100e-01 5.971408e-02 -9.629948e+00 9.981221e-01 3.159921e-02 -5.247469e-02 3.730824e+02 +-5.504347e-02 5.865725e-02 -9.967596e-01 -5.758298e+01 -2.781843e-02 9.977953e-01 6.025441e-02 -9.595395e+00 9.980963e-01 3.104490e-02 -5.329036e-02 3.730404e+02 +-5.634955e-02 5.780837e-02 -9.967362e-01 -5.848949e+01 -2.953307e-02 9.977890e-01 5.953906e-02 -9.561552e+00 9.979742e-01 3.279167e-02 -5.451770e-02 3.729954e+02 +-5.783411e-02 5.596459e-02 -9.967564e-01 -5.939958e+01 -2.987117e-02 9.978834e-01 5.776108e-02 -9.525374e+00 9.978792e-01 3.311484e-02 -5.603997e-02 3.729496e+02 +-6.063863e-02 5.432452e-02 -9.966804e-01 -6.030854e+01 -2.818048e-02 9.980267e-01 5.611242e-02 -9.487650e+00 9.977619e-01 3.148951e-02 -5.898807e-02 3.729050e+02 +-6.411494e-02 5.616216e-02 -9.963610e-01 -6.121711e+01 -2.896349e-02 9.978898e-01 5.811213e-02 -9.447759e+00 9.975221e-01 3.258395e-02 -6.235299e-02 3.728540e+02 +-6.804216e-02 6.096702e-02 -9.958179e-01 -6.212827e+01 -2.986373e-02 9.975594e-01 6.311418e-02 -9.413426e+00 9.972353e-01 3.403326e-02 -6.605539e-02 3.727971e+02 +-7.190997e-02 6.371124e-02 -9.953742e-01 -6.303109e+01 -3.129255e-02 9.973224e-01 6.609665e-02 -9.379269e+00 9.969201e-01 3.590080e-02 -6.972373e-02 3.727365e+02 +-7.535459e-02 6.172806e-02 -9.952444e-01 -6.393282e+01 -3.609309e-02 9.972592e-01 6.458581e-02 -9.341901e+00 9.965033e-01 4.078828e-02 -7.292010e-02 3.726685e+02 +-7.801495e-02 5.909321e-02 -9.951993e-01 -6.482727e+01 -3.865197e-02 9.973119e-01 6.224864e-02 -9.302409e+00 9.962026e-01 4.332273e-02 -7.552116e-02 3.725998e+02 +-8.045080e-02 5.580634e-02 -9.951951e-01 -6.572199e+01 -3.927851e-02 9.974784e-01 5.910963e-02 -9.267669e+00 9.959843e-01 4.384519e-02 -7.805594e-02 3.725323e+02 +-8.191513e-02 5.392768e-02 -9.951793e-01 -6.661519e+01 -3.649405e-02 9.977030e-01 5.706835e-02 -9.234586e+00 9.959709e-01 4.099288e-02 -7.975893e-02 3.724709e+02 +-8.305142e-02 5.333808e-02 -9.951169e-01 -6.750920e+01 -3.622612e-02 9.977450e-01 5.650235e-02 -9.200919e+00 9.958866e-01 4.074182e-02 -8.093191e-02 3.724021e+02 +-8.347450e-02 5.660145e-02 -9.949012e-01 -6.840522e+01 -3.856950e-02 9.974540e-01 5.998277e-02 -9.171513e+00 9.957632e-01 4.337987e-02 -8.107888e-02 3.723333e+02 +-8.310290e-02 5.896421e-02 -9.947950e-01 -6.930001e+01 -3.638643e-02 9.974028e-01 6.215843e-02 -9.143158e+00 9.958764e-01 4.136258e-02 -8.074156e-02 3.722717e+02 +-8.177674e-02 5.531960e-02 -9.951142e-01 -7.018617e+01 -3.767985e-02 9.975729e-01 5.855276e-02 -9.112672e+00 9.959381e-01 4.228401e-02 -7.949382e-02 3.722087e+02 +-7.855670e-02 5.236842e-02 -9.955332e-01 -7.107138e+01 -3.926376e-02 9.976819e-01 5.557973e-02 -9.081827e+00 9.961361e-01 4.345453e-02 -7.631841e-02 3.721463e+02 +-7.545427e-02 5.287978e-02 -9.957462e-01 -7.195849e+01 -4.253972e-02 9.975130e-01 5.619713e-02 -9.051563e+00 9.962414e-01 4.659907e-02 -7.301712e-02 3.720834e+02 +-7.106780e-02 5.549648e-02 -9.959265e-01 -7.284534e+01 -4.331506e-02 9.973375e-01 5.866602e-02 -9.021905e+00 9.965305e-01 4.730788e-02 -6.847474e-02 3.720284e+02 +-6.643211e-02 5.727894e-02 -9.961455e-01 -7.373148e+01 -4.448647e-02 9.971881e-01 6.030567e-02 -8.989193e+00 9.967987e-01 4.832122e-02 -6.369717e-02 3.719759e+02 +-6.115884e-02 5.825840e-02 -9.964264e-01 -7.461312e+01 -4.498354e-02 9.971199e-01 6.105996e-02 -8.955145e+00 9.971138e-01 4.855714e-02 -5.836203e-02 3.719277e+02 +-5.591674e-02 5.938125e-02 -9.966681e-01 -7.549532e+01 -4.501014e-02 9.970650e-01 6.193015e-02 -8.920653e+00 9.974203e-01 4.832310e-02 -5.307987e-02 3.718861e+02 +-5.081605e-02 5.971275e-02 -9.969213e-01 -7.636962e+01 -4.454360e-02 9.970821e-01 6.199291e-02 -8.885715e+00 9.977141e-01 4.755670e-02 -4.800796e-02 3.718493e+02 +-4.531908e-02 5.881432e-02 -9.972397e-01 -7.724379e+01 -4.366453e-02 9.971947e-01 6.079599e-02 -8.853528e+00 9.980178e-01 4.629922e-02 -4.262384e-02 3.718176e+02 +-4.023740e-02 5.691804e-02 -9.975677e-01 -7.811605e+01 -4.420633e-02 9.972972e-01 5.868570e-02 -8.821990e+00 9.982117e-01 4.646016e-02 -3.761251e-02 3.717873e+02 +-3.499781e-02 5.499364e-02 -9.978732e-01 -7.898474e+01 -4.491381e-02 9.973894e-01 5.654222e-02 -8.793073e+00 9.983776e-01 4.679714e-02 -3.243647e-02 3.717602e+02 +-2.986458e-02 5.393778e-02 -9.980976e-01 -7.984974e+01 -4.541275e-02 9.974386e-01 5.526099e-02 -8.767265e+00 9.985218e-01 4.697670e-02 -2.733862e-02 3.717354e+02 +-2.462415e-02 5.467083e-02 -9.982008e-01 -8.071785e+01 -4.546706e-02 9.974090e-01 5.574908e-02 -8.739272e+00 9.986623e-01 4.675803e-02 -2.207463e-02 3.717185e+02 +-1.968438e-02 5.569423e-02 -9.982538e-01 -8.158408e+01 -4.569083e-02 9.973540e-01 5.654500e-02 -8.709843e+00 9.987616e-01 4.672410e-02 -1.708758e-02 3.717068e+02 +-1.502749e-02 5.761819e-02 -9.982256e-01 -8.244873e+01 -4.662108e-02 9.972121e-01 5.826154e-02 -8.680237e+00 9.987996e-01 4.741388e-02 -1.229937e-02 3.716974e+02 +-1.072362e-02 6.007042e-02 -9.981366e-01 -8.331178e+01 -4.623057e-02 9.970967e-01 6.050454e-02 -8.648349e+00 9.988732e-01 4.679325e-02 -7.915395e-03 3.716948e+02 +-7.057561e-03 6.168402e-02 -9.980708e-01 -8.416878e+01 -4.410449e-02 9.971051e-01 6.193622e-02 -8.617964e+00 9.990020e-01 4.445652e-02 -4.316589e-03 3.716980e+02 +-4.087821e-03 6.197835e-02 -9.980692e-01 -8.501559e+01 -4.162482e-02 9.972019e-01 6.209499e-02 -8.589614e+00 9.991249e-01 4.179828e-02 -1.496546e-03 3.717041e+02 +-1.760038e-03 6.103921e-02 -9.981338e-01 -8.584271e+01 -3.964425e-02 9.973464e-01 6.106097e-02 -8.562016e+00 9.992123e-01 3.967774e-02 6.644851e-04 3.717099e+02 +-3.183940e-04 5.851355e-02 -9.982866e-01 -8.665213e+01 -3.639312e-02 9.976246e-01 5.848637e-02 -8.534700e+00 9.993375e-01 3.634938e-02 1.811852e-03 3.717181e+02 +7.352782e-04 5.793684e-02 -9.983200e-01 -8.744548e+01 -3.345229e-02 9.977629e-01 5.787988e-02 -8.511473e+00 9.994400e-01 3.335353e-02 2.671752e-03 3.717253e+02 +1.306633e-03 5.803989e-02 -9.983134e-01 -8.821569e+01 -3.165525e-02 9.978163e-01 5.796957e-02 -8.488287e+00 9.994980e-01 3.152611e-02 3.141046e-03 3.717341e+02 +1.243637e-03 5.583075e-02 -9.984395e-01 -8.896671e+01 -2.876484e-02 9.980291e-01 5.577198e-02 -8.468100e+00 9.995854e-01 2.865059e-02 2.847147e-03 3.717420e+02 +3.983406e-04 5.534356e-02 -9.984673e-01 -8.969543e+01 -2.694129e-02 9.981055e-01 5.531277e-02 -8.448239e+00 9.996369e-01 2.687796e-02 1.888611e-03 3.717483e+02 +-1.761077e-03 5.446575e-02 -9.985141e-01 -9.040266e+01 -2.387835e-02 9.982286e-01 5.449230e-02 -8.426609e+00 9.997133e-01 2.393883e-02 -4.574064e-04 3.717553e+02 +-4.984478e-03 5.643605e-02 -9.983938e-01 -9.108715e+01 -2.194172e-02 9.981596e-01 5.653236e-02 -8.410589e+00 9.997468e-01 2.218826e-02 -3.737002e-03 3.717554e+02 +-9.015765e-03 5.941652e-02 -9.981926e-01 -9.174421e+01 -1.923550e-02 9.980381e-01 5.958107e-02 -8.396913e+00 9.997743e-01 1.973790e-02 -7.855171e-03 3.717538e+02 +-1.417810e-02 6.033010e-02 -9.980778e-01 -9.237686e+01 -1.802747e-02 9.980004e-01 6.058152e-02 -8.377804e+00 9.997369e-01 1.885175e-02 -1.306215e-02 3.717472e+02 +-2.005889e-02 6.023929e-02 -9.979824e-01 -9.299091e+01 -1.575382e-02 9.980402e-01 6.055943e-02 -8.359815e+00 9.996746e-01 1.693679e-02 -1.907058e-02 3.717379e+02 +-2.649183e-02 5.783823e-02 -9.979744e-01 -9.358457e+01 -1.469932e-02 9.981943e-01 5.824119e-02 -8.343593e+00 9.995409e-01 1.621246e-02 -2.559381e-02 3.717213e+02 +-3.357685e-02 5.543715e-02 -9.978975e-01 -9.418117e+01 -1.368763e-02 9.983413e-01 5.592237e-02 -8.327124e+00 9.993424e-01 1.553655e-02 -3.276235e-02 3.717000e+02 +-4.160326e-02 5.552193e-02 -9.975904e-01 -9.477460e+01 -1.405422e-02 9.983235e-01 5.614886e-02 -8.309292e+00 9.990353e-01 1.635634e-02 -4.075319e-02 3.716732e+02 +-4.893424e-02 5.683927e-02 -9.971834e-01 -9.536688e+01 -1.275195e-02 9.982625e-01 5.752656e-02 -8.292758e+00 9.987206e-01 1.553106e-02 -4.812440e-02 3.716455e+02 +-5.632171e-02 5.739264e-02 -9.967618e-01 -9.595417e+01 -1.322561e-02 9.982159e-01 5.822369e-02 -8.278958e+00 9.983250e-01 1.646204e-02 -5.546217e-02 3.716101e+02 +-6.340252e-02 5.498277e-02 -9.964723e-01 -9.653780e+01 -1.385944e-02 9.983364e-01 5.596747e-02 -8.263858e+00 9.978918e-01 1.735902e-02 -6.253500e-02 3.715706e+02 +-7.036542e-02 5.106428e-02 -9.962134e-01 -9.711600e+01 -1.516960e-02 9.985186e-01 5.225392e-02 -8.247622e+00 9.974059e-01 1.878903e-02 -6.948655e-02 3.715277e+02 +-7.669274e-02 4.779096e-02 -9.959088e-01 -9.769290e+01 -1.476679e-02 9.986866e-01 4.906143e-02 -8.229449e+00 9.969454e-01 1.846903e-02 -7.588628e-02 3.714840e+02 +-8.328609e-02 4.514690e-02 -9.955025e-01 -9.826993e+01 -1.430732e-02 9.988161e-01 4.649417e-02 -8.213451e+00 9.964229e-01 1.811529e-02 -8.254155e-02 3.714388e+02 +-8.895906e-02 4.273338e-02 -9.951182e-01 -9.884636e+01 -1.434183e-02 9.989207e-01 4.417877e-02 -8.199034e+00 9.959320e-01 1.820192e-02 -8.825016e-02 3.713890e+02 +-9.452557e-02 4.149222e-02 -9.946574e-01 -9.942884e+01 -1.634106e-02 9.989318e-01 4.322348e-02 -8.186657e+00 9.953883e-01 2.033949e-02 -9.374656e-02 3.713324e+02 +-9.922676e-02 4.069118e-02 -9.942325e-01 -1.000168e+02 -1.818838e-02 9.989224e-01 4.269838e-02 -8.171096e+00 9.948986e-01 2.232030e-02 -9.837972e-02 3.712717e+02 +-1.040151e-01 3.997827e-02 -9.937719e-01 -1.006101e+02 -1.775479e-02 9.989579e-01 4.204524e-02 -8.156426e+00 9.944172e-01 2.201755e-02 -1.031969e-01 3.712114e+02 +-1.084053e-01 4.003776e-02 -9.933002e-01 -1.012124e+02 -1.644231e-02 9.989797e-01 4.206116e-02 -8.141451e+00 9.939708e-01 2.089180e-02 -1.076364e-01 3.711501e+02 +-1.121510e-01 3.932628e-02 -9.929127e-01 -1.018198e+02 -1.767161e-02 9.989796e-01 4.156262e-02 -8.127155e+00 9.935340e-01 2.220765e-02 -1.113416e-01 3.710817e+02 +-1.155328e-01 3.695243e-02 -9.926161e-01 -1.024309e+02 -2.230033e-02 9.989594e-01 3.978416e-02 -8.112895e+00 9.930533e-01 2.673204e-02 -1.145885e-01 3.710055e+02 +-1.178769e-01 3.551224e-02 -9.923931e-01 -1.030491e+02 -2.583621e-02 9.989124e-01 3.881438e-02 -8.096046e+00 9.926920e-01 3.021499e-02 -1.168311e-01 3.709299e+02 +-1.193593e-01 3.462679e-02 -9.922472e-01 -1.036768e+02 -2.589438e-02 9.989431e-01 3.797535e-02 -8.078290e+00 9.925134e-01 3.022633e-02 -1.183365e-01 3.708586e+02 +-1.199653e-01 3.437181e-02 -9.921829e-01 -1.043134e+02 -2.424181e-02 9.990011e-01 3.753911e-02 -8.060977e+00 9.924820e-01 2.855570e-02 -1.190122e-01 3.707887e+02 +-1.201938e-01 3.558811e-02 -9.921124e-01 -1.049637e+02 -2.512899e-02 9.989280e-01 3.887696e-02 -8.042390e+00 9.924323e-01 2.960355e-02 -1.191706e-01 3.707129e+02 +-1.195223e-01 3.957517e-02 -9.920425e-01 -1.056283e+02 -2.525610e-02 9.987607e-01 4.288607e-02 -8.019412e+00 9.925102e-01 3.018096e-02 -1.183746e-01 3.706343e+02 +-1.193852e-01 4.476975e-02 -9.918381e-01 -1.063014e+02 -2.834621e-02 9.984219e-01 4.847890e-02 -7.995103e+00 9.924432e-01 3.390251e-02 -1.179277e-01 3.705532e+02 +-1.182758e-01 5.654201e-02 -9.913697e-01 -1.069999e+02 -2.965854e-02 9.977309e-01 6.044325e-02 -7.961767e+00 9.925377e-01 3.655155e-02 -1.163305e-01 3.704698e+02 +-1.165393e-01 6.727038e-02 -9.909053e-01 -1.077095e+02 -3.336337e-02 9.968753e-01 7.159951e-02 -7.927113e+00 9.926255e-01 4.140410e-02 -1.139308e-01 3.703837e+02 +-1.137649e-01 7.017563e-02 -9.910262e-01 -1.084259e+02 -3.556553e-02 9.965753e-01 7.465132e-02 -7.892215e+00 9.928709e-01 4.373906e-02 -1.108794e-01 3.702999e+02 +-1.107229e-01 6.308715e-02 -9.918470e-01 -1.091474e+02 -3.977229e-02 9.969025e-01 6.784863e-02 -7.863187e+00 9.930551e-01 4.696042e-02 -1.078708e-01 3.702185e+02 +-1.064261e-01 4.665078e-02 -9.932257e-01 -1.098735e+02 -4.240981e-02 9.977768e-01 5.140885e-02 -7.822793e+00 9.934157e-01 4.759375e-02 -1.042111e-01 3.701404e+02 +-1.024481e-01 3.848327e-02 -9.939937e-01 -1.106253e+02 -4.362888e-02 9.981160e-01 4.313958e-02 -7.775619e+00 9.937811e-01 4.778640e-02 -1.005761e-01 3.700636e+02 +-9.832008e-02 5.068146e-02 -9.938635e-01 -1.114139e+02 -4.315178e-02 9.975458e-01 5.513813e-02 -7.727221e+00 9.942188e-01 4.830816e-02 -9.589178e-02 3.699905e+02 +-9.406416e-02 7.002775e-02 -9.931003e-01 -1.122248e+02 -4.478078e-02 9.962159e-01 7.448898e-02 -7.690621e+00 9.945585e-01 5.147854e-02 -9.057230e-02 3.699157e+02 +-9.014759e-02 7.570782e-02 -9.930467e-01 -1.130391e+02 -4.360401e-02 9.958503e-01 7.987989e-02 -7.648582e+00 9.949734e-01 5.050180e-02 -8.647234e-02 3.698495e+02 +-8.662695e-02 6.646987e-02 -9.940209e-01 -1.138504e+02 -4.123745e-02 9.966773e-01 7.024128e-02 -7.597550e+00 9.953869e-01 4.707567e-02 -8.359806e-02 3.697875e+02 +-8.284837e-02 4.926372e-02 -9.953438e-01 -1.146710e+02 -4.247035e-02 9.976954e-01 5.291518e-02 -7.551143e+00 9.956567e-01 4.665653e-02 -8.056519e-02 3.697225e+02 +-7.889538e-02 3.753908e-02 -9.961759e-01 -1.155125e+02 -4.473820e-02 9.981506e-01 4.115669e-02 -7.506696e+00 9.958785e-01 4.781418e-02 -7.707004e-02 3.696572e+02 +-7.491892e-02 4.034314e-02 -9.963732e-01 -1.163815e+02 -5.025876e-02 9.977586e-01 4.417828e-02 -7.470759e+00 9.959223e-01 5.338627e-02 -7.272340e-02 3.695879e+02 +-6.962103e-02 5.160105e-02 -9.962381e-01 -1.172754e+02 -5.722763e-02 9.968100e-01 5.562998e-02 -7.432281e+00 9.959306e-01 6.088536e-02 -6.644593e-02 3.695175e+02 +-6.336864e-02 5.643060e-02 -9.963935e-01 -1.181783e+02 -6.201470e-02 9.962480e-01 6.036638e-02 -7.392513e+00 9.960615e-01 6.561638e-02 -5.963135e-02 3.694551e+02 +-5.637116e-02 4.730667e-02 -9.972885e-01 -1.190790e+02 -6.461708e-02 9.966098e-01 5.092693e-02 -7.352691e+00 9.963166e-01 6.731268e-02 -5.312322e-02 3.694020e+02 +-4.872278e-02 3.298185e-02 -9.982677e-01 -1.199904e+02 -6.185812e-02 9.974364e-01 3.597353e-02 -7.316884e+00 9.968950e-01 6.350368e-02 -4.655768e-02 3.693637e+02 +-4.161567e-02 2.354608e-02 -9.988562e-01 -1.209176e+02 -5.483414e-02 9.981617e-01 2.581429e-02 -7.287875e+00 9.976278e-01 5.584570e-02 -4.024803e-02 3.693375e+02 +-3.450527e-02 2.873525e-02 -9.989914e-01 -1.218705e+02 -5.062995e-02 9.982528e-01 3.046278e-02 -7.268012e+00 9.981212e-01 5.163000e-02 -3.299012e-02 3.693124e+02 +-2.733270e-02 4.100511e-02 -9.987850e-01 -1.228443e+02 -4.785905e-02 9.979588e-01 4.228091e-02 -7.242979e+00 9.984800e-01 4.895655e-02 -2.531444e-02 3.692910e+02 +-2.097537e-02 5.238267e-02 -9.984068e-01 -1.238220e+02 -4.573789e-02 9.975306e-01 5.329761e-02 -7.210357e+00 9.987332e-01 4.678296e-02 -1.852770e-02 3.692685e+02 +-1.558509e-02 5.377397e-02 -9.984315e-01 -1.247980e+02 -4.462857e-02 9.975202e-01 5.442153e-02 -7.171402e+00 9.988820e-01 4.540673e-02 -1.314659e-02 3.692510e+02 +-1.189366e-02 4.843143e-02 -9.987557e-01 -1.257739e+02 -4.266151e-02 9.978923e-01 4.889761e-02 -7.129720e+00 9.990187e-01 4.318999e-02 -9.802436e-03 3.692360e+02 +-9.853041e-03 4.559385e-02 -9.989115e-01 -1.267573e+02 -4.165551e-02 9.980741e-01 4.596652e-02 -7.094259e+00 9.990834e-01 4.206307e-02 -7.934831e-03 3.692286e+02 +-9.012415e-03 4.558744e-02 -9.989197e-01 -1.277492e+02 -3.952559e-02 9.981633e-01 4.590953e-02 -7.067306e+00 9.991779e-01 3.989664e-02 -7.193992e-03 3.692220e+02 +-8.681528e-03 4.748294e-02 -9.988344e-01 -1.287442e+02 -3.689769e-02 9.981765e-01 4.777238e-02 -7.039616e+00 9.992813e-01 3.726941e-02 -6.913688e-03 3.692162e+02 +-9.113077e-03 4.856194e-02 -9.987786e-01 -1.297392e+02 -3.710233e-02 9.981159e-01 4.886826e-02 -7.010053e+00 9.992699e-01 3.750236e-02 -7.294146e-03 3.692059e+02 +-1.110359e-02 5.159610e-02 -9.986063e-01 -1.307381e+02 -3.844600e-02 9.979074e-01 5.198749e-02 -6.978782e+00 9.991989e-01 3.896967e-02 -9.096690e-03 3.691913e+02 +-1.384410e-02 5.578262e-02 -9.983470e-01 -1.317386e+02 -3.814968e-02 9.976862e-01 5.627473e-02 -6.944658e+00 9.991761e-01 3.886569e-02 -1.168398e-02 3.691754e+02 +-1.717664e-02 5.655699e-02 -9.982516e-01 -1.327370e+02 -3.856448e-02 9.976185e-01 5.718470e-02 -6.909152e+00 9.991084e-01 3.947929e-02 -1.495465e-02 3.691613e+02 +-2.014464e-02 4.928275e-02 -9.985817e-01 -1.337249e+02 -3.541369e-02 9.981224e-01 4.997450e-02 -6.873000e+00 9.991696e-01 3.637018e-02 -1.836153e-02 3.691510e+02 +-2.332779e-02 4.079338e-02 -9.988953e-01 -1.347107e+02 -3.070672e-02 9.986665e-01 4.150116e-02 -6.836596e+00 9.992561e-01 3.164093e-02 -2.204405e-02 3.691420e+02 +-2.659783e-02 3.897954e-02 -9.988860e-01 -1.356995e+02 -2.505098e-02 9.988996e-01 3.964713e-02 -6.801852e+00 9.993322e-01 2.607760e-02 -2.559208e-02 3.691313e+02 +-2.996479e-02 4.514121e-02 -9.985311e-01 -1.366932e+02 -2.204334e-02 9.987069e-01 4.581066e-02 -6.767486e+00 9.993078e-01 2.338366e-02 -2.893098e-02 3.691167e+02 +-3.287829e-02 5.156356e-02 -9.981284e-01 -1.376860e+02 -2.158186e-02 9.983988e-01 5.228844e-02 -6.733132e+00 9.992263e-01 2.326062e-02 -3.171280e-02 3.690914e+02 +-3.520728e-02 5.307285e-02 -9.979698e-01 -1.386679e+02 -2.262992e-02 9.982905e-01 5.388827e-02 -6.697390e+00 9.991237e-01 2.448124e-02 -3.394606e-02 3.690630e+02 +-3.748825e-02 5.000773e-02 -9.980450e-01 -1.396402e+02 -2.654743e-02 9.983447e-01 5.101992e-02 -6.665761e+00 9.989443e-01 2.840818e-02 -3.609862e-02 3.690262e+02 +-3.983027e-02 4.611387e-02 -9.981418e-01 -1.406078e+02 -3.099335e-02 9.983968e-01 4.736243e-02 -6.632860e+00 9.987256e-01 3.282222e-02 -3.833719e-02 3.689840e+02 +-4.207209e-02 4.314398e-02 -9.981826e-01 -1.415778e+02 -3.267945e-02 9.984732e-01 4.453395e-02 -6.602139e+00 9.985799e-01 3.449370e-02 -4.059793e-02 3.689429e+02 +-4.405978e-02 4.245006e-02 -9.981266e-01 -1.425454e+02 -3.173202e-02 9.985332e-01 4.386809e-02 -6.575320e+00 9.985248e-01 3.360539e-02 -4.264813e-02 3.689094e+02 +-4.589568e-02 4.412076e-02 -9.979714e-01 -1.435151e+02 -2.994613e-02 9.985144e-01 4.552197e-02 -6.547679e+00 9.984972e-01 3.197465e-02 -4.450625e-02 3.688734e+02 +-4.807395e-02 5.004634e-02 -9.975893e-01 -1.444860e+02 -2.626054e-02 9.983354e-01 5.134928e-02 -6.517102e+00 9.984985e-01 2.866580e-02 -4.667968e-02 3.688390e+02 +-5.114879e-02 5.688625e-02 -9.970696e-01 -1.454529e+02 -2.457189e-02 9.980025e-01 5.820000e-02 -6.483563e+00 9.983887e-01 2.747675e-02 -4.964881e-02 3.688004e+02 +-5.415381e-02 6.143589e-02 -9.966409e-01 -1.464204e+02 -2.202613e-02 9.977891e-01 6.270350e-02 -6.445217e+00 9.982896e-01 2.534778e-02 -5.268089e-02 3.687580e+02 +-5.766881e-02 6.033428e-02 -9.965110e-01 -1.473774e+02 -2.382930e-02 9.978045e-01 6.179163e-02 -6.403585e+00 9.980513e-01 2.730961e-02 -5.610447e-02 3.687095e+02 +-6.084897e-02 5.239532e-02 -9.967709e-01 -1.483260e+02 -2.566450e-02 9.982090e-01 5.403764e-02 -6.362759e+00 9.978169e-01 2.886976e-02 -5.939529e-02 3.686537e+02 +-6.368640e-02 4.699773e-02 -9.968627e-01 -1.492752e+02 -2.801701e-02 9.984126e-01 4.886073e-02 -6.321440e+00 9.975766e-01 3.104087e-02 -6.226857e-02 3.685981e+02 +-6.568723e-02 4.667322e-02 -9.967481e-01 -1.502278e+02 -2.595952e-02 9.984874e-01 4.846545e-02 -6.288175e+00 9.975025e-01 2.905866e-02 -6.437626e-02 3.685407e+02 +-6.725695e-02 5.207556e-02 -9.963758e-01 -1.511845e+02 -2.506258e-02 9.982337e-01 5.386443e-02 -6.256123e+00 9.974208e-01 2.859450e-02 -6.583300e-02 3.684837e+02 +-6.868069e-02 5.697110e-02 -9.960107e-01 -1.521373e+02 -2.330961e-02 9.980039e-01 5.869246e-02 -6.219180e+00 9.973663e-01 2.724766e-02 -6.721561e-02 3.684250e+02 +-6.992206e-02 5.926050e-02 -9.957907e-01 -1.530839e+02 -2.060872e-02 9.979350e-01 6.083522e-02 -6.175756e+00 9.973395e-01 2.477569e-02 -6.855638e-02 3.683679e+02 +-7.063564e-02 6.136347e-02 -9.956130e-01 -1.540295e+02 -2.036505e-02 9.978093e-01 6.294368e-02 -6.138328e+00 9.972942e-01 2.472177e-02 -6.923122e-02 3.683067e+02 +-7.063519e-02 6.221153e-02 -9.955604e-01 -1.549685e+02 -2.085577e-02 9.977430e-01 6.382765e-02 -6.101396e+00 9.972841e-01 2.527165e-02 -6.917830e-02 3.682417e+02 +-7.031087e-02 6.142404e-02 -9.956322e-01 -1.559016e+02 -2.337090e-02 9.977269e-01 6.320372e-02 -6.064642e+00 9.972513e-01 2.771273e-02 -6.871551e-02 3.681752e+02 +-6.951060e-02 5.965373e-02 -9.957960e-01 -1.568340e+02 -2.697629e-02 9.977330e-01 6.165283e-02 -6.028879e+00 9.972164e-01 3.114841e-02 -6.774378e-02 3.681108e+02 +-6.847529e-02 5.766241e-02 -9.959851e-01 -1.577614e+02 -3.023284e-02 9.977498e-01 5.984314e-02 -5.992298e+00 9.971946e-01 3.420923e-02 -6.657790e-02 3.680449e+02 +-6.703008e-02 5.437833e-02 -9.962680e-01 -1.586835e+02 -2.993901e-02 9.979545e-01 5.648472e-02 -5.959485e+00 9.973016e-01 3.361345e-02 -6.526493e-02 3.679845e+02 +-6.581856e-02 5.169557e-02 -9.964916e-01 -1.596016e+02 -2.817943e-02 9.981624e-01 5.364351e-02 -5.927697e+00 9.974336e-01 3.161130e-02 -6.424086e-02 3.679298e+02 +-6.419495e-02 5.018196e-02 -9.966749e-01 -1.605196e+02 -2.768902e-02 9.982608e-01 5.204525e-02 -5.894364e+00 9.975531e-01 3.093799e-02 -6.269380e-02 3.678737e+02 +-6.303622e-02 5.440678e-02 -9.965272e-01 -1.614371e+02 -2.687190e-02 9.980584e-01 5.619020e-02 -5.861145e+00 9.976494e-01 3.032059e-02 -6.145181e-02 3.678205e+02 +-6.215397e-02 6.171511e-02 -9.961567e-01 -1.623529e+02 -2.501014e-02 9.976767e-01 6.336976e-02 -5.826577e+00 9.977531e-01 2.885270e-02 -6.046606e-02 3.677697e+02 +-6.113681e-02 6.506562e-02 -9.960064e-01 -1.632549e+02 -2.335634e-02 9.975065e-01 6.659728e-02 -5.789504e+00 9.978560e-01 2.733461e-02 -5.946467e-02 3.677206e+02 +-5.982877e-02 6.497859e-02 -9.960915e-01 -1.641449e+02 -2.391060e-02 9.974994e-01 6.650660e-02 -5.750163e+00 9.979222e-01 2.779616e-02 -5.812548e-02 3.676707e+02 +-5.841149e-02 6.273405e-02 -9.963195e-01 -1.650253e+02 -2.311541e-02 9.976709e-01 6.417435e-02 -5.709019e+00 9.980249e-01 2.677885e-02 -5.682532e-02 3.676228e+02 +-5.732252e-02 6.022540e-02 -9.965375e-01 -1.658914e+02 -2.352658e-02 9.978201e-01 6.165621e-02 -5.666980e+00 9.980784e-01 2.697941e-02 -5.578066e-02 3.675742e+02 +-5.642917e-02 6.061396e-02 -9.965650e-01 -1.667434e+02 -2.484652e-02 9.977610e-01 6.209362e-02 -5.627809e+00 9.980973e-01 2.826506e-02 -5.479678e-02 3.675248e+02 +-5.589303e-02 6.415437e-02 -9.963735e-01 -1.675871e+02 -2.637749e-02 9.974903e-01 6.570597e-02 -5.591398e+00 9.980882e-01 2.995434e-02 -5.406053e-02 3.674736e+02 +-5.526132e-02 6.704275e-02 -9.962186e-01 -1.684147e+02 -2.552006e-02 9.973224e-01 6.853267e-02 -5.560208e+00 9.981457e-01 2.921076e-02 -5.340241e-02 3.674265e+02 +-5.464152e-02 6.385069e-02 -9.964625e-01 -1.692138e+02 -2.113899e-02 9.976557e-01 6.508633e-02 -5.530577e+00 9.982822e-01 2.462063e-02 -5.316368e-02 3.673848e+02 +-5.403882e-02 5.696162e-02 -9.969129e-01 -1.699897e+02 -1.773033e-02 9.981595e-01 5.799395e-02 -5.497707e+00 9.983814e-01 2.080952e-02 -5.292941e-02 3.673471e+02 +-5.403008e-02 5.219054e-02 -9.971745e-01 -1.707472e+02 -1.663346e-02 9.984475e-01 5.315843e-02 -5.465282e+00 9.984007e-01 1.945861e-02 -5.307809e-02 3.673055e+02 +-5.437363e-02 5.665159e-02 -9.969123e-01 -1.714949e+02 -1.285263e-02 9.982668e-01 5.742959e-02 -5.436150e+00 9.984379e-01 1.593560e-02 -5.355126e-02 3.672694e+02 +-5.520551e-02 6.563741e-02 -9.963153e-01 -1.722298e+02 -7.400959e-03 9.977826e-01 6.614417e-02 -5.408734e+00 9.984475e-01 1.102522e-02 -5.459732e-02 3.672374e+02 +-5.703222e-02 6.879741e-02 -9.959991e-01 -1.729313e+02 -7.073998e-03 9.975700e-01 6.931099e-02 -5.384605e+00 9.983472e-01 1.099866e-02 -5.640695e-02 3.672013e+02 +-5.856718e-02 6.543314e-02 -9.961368e-01 -1.736069e+02 -7.827707e-03 9.977888e-01 6.600189e-02 -5.362451e+00 9.982527e-01 1.166301e-02 -5.792548e-02 3.671608e+02 +-6.189470e-02 5.660624e-02 -9.964762e-01 -1.742550e+02 -1.023150e-02 9.983019e-01 5.734548e-02 -5.340548e+00 9.980302e-01 1.374483e-02 -6.121043e-02 3.671185e+02 +-6.447237e-02 5.006024e-02 -9.966631e-01 -1.748867e+02 -1.120022e-02 9.986417e-01 5.088415e-02 -5.317998e+00 9.978566e-01 1.444347e-02 -6.382411e-02 3.670760e+02 +-6.737246e-02 4.833993e-02 -9.965562e-01 -1.755043e+02 -1.532907e-02 9.986575e-01 4.947819e-02 -5.294660e+00 9.976101e-01 1.860975e-02 -6.654101e-02 3.670285e+02 +-7.134877e-02 5.066223e-02 -9.961640e-01 -1.761135e+02 -1.799863e-02 9.984812e-01 5.206922e-02 -5.277180e+00 9.972890e-01 2.164466e-02 -7.032855e-02 3.669763e+02 +-7.668700e-02 5.522832e-02 -9.955245e-01 -1.767064e+02 -1.945003e-02 9.981918e-01 5.687457e-02 -5.259521e+00 9.968654e-01 2.372452e-02 -7.547414e-02 3.669279e+02 +-8.250596e-02 5.802894e-02 -9.948997e-01 -1.772879e+02 -1.898789e-02 9.980306e-01 5.978621e-02 -5.242102e+00 9.964096e-01 2.382377e-02 -8.124162e-02 3.668763e+02 +-9.101204e-02 5.891668e-02 -9.941055e-01 -1.778516e+02 -1.791488e-02 9.979900e-01 6.078705e-02 -5.224067e+00 9.956886e-01 2.334164e-02 -8.977361e-02 3.668251e+02 +-1.032542e-01 5.832202e-02 -9.929437e-01 -1.784058e+02 -1.554857e-02 9.980628e-01 6.023958e-02 -5.200726e+00 9.945334e-01 2.165884e-02 -1.021474e-01 3.667708e+02 +-1.191298e-01 5.720440e-02 -9.912294e-01 -1.789483e+02 -1.247272e-02 9.981739e-01 5.910420e-02 -5.178101e+00 9.928003e-01 1.940440e-02 -1.181988e-01 3.667006e+02 +-1.395858e-01 5.562312e-02 -9.886465e-01 -1.794822e+02 -1.038177e-02 9.982839e-01 5.763114e-02 -5.157679e+00 9.901555e-01 1.830839e-02 -1.387688e-01 3.666191e+02 +-1.649366e-01 5.493020e-02 -9.847734e-01 -1.800128e+02 -8.198430e-03 9.983371e-01 5.705992e-02 -5.137863e+00 9.862700e-01 1.748487e-02 -1.642120e-01 3.665239e+02 +-1.947555e-01 5.420350e-02 -9.793530e-01 -1.805245e+02 -7.047529e-03 9.983688e-01 5.665745e-02 -5.114952e+00 9.808265e-01 1.793637e-02 -1.940558e-01 3.663922e+02 +-2.293444e-01 5.458947e-02 -9.718134e-01 -1.810410e+02 -6.346743e-03 9.983209e-01 5.757630e-02 -5.091005e+00 9.733246e-01 1.937265e-02 -2.286128e-01 3.662572e+02 +-2.684077e-01 5.532174e-02 -9.617156e-01 -1.815484e+02 -3.612893e-03 9.982847e-01 5.843369e-02 -5.065694e+00 9.632986e-01 1.915863e-02 -2.677474e-01 3.661069e+02 +-3.116168e-01 5.559536e-02 -9.485801e-01 -1.820234e+02 -5.501312e-04 9.982762e-01 5.868874e-02 -5.042477e+00 9.502077e-01 1.881024e-02 -3.110490e-01 3.658942e+02 +-3.588189e-01 5.633877e-02 -9.317054e-01 -1.825069e+02 3.899528e-03 9.982585e-01 5.886136e-02 -5.016582e+00 9.333990e-01 1.748736e-02 -3.584137e-01 3.657009e+02 +-4.082375e-01 5.754307e-02 -9.110604e-01 -1.829767e+02 7.050410e-03 9.981803e-01 5.988641e-02 -4.990208e+00 9.128485e-01 1.802453e-02 -4.079003e-01 3.654859e+02 +-4.584834e-01 5.859806e-02 -8.867690e-01 -1.833992e+02 1.089550e-02 9.981194e-01 6.032289e-02 -4.960498e+00 8.886361e-01 1.799525e-02 -4.582596e-01 3.651915e+02 +-5.086892e-01 5.913891e-02 -8.589167e-01 -1.838309e+02 1.347660e-02 9.980627e-01 6.073807e-02 -4.931494e+00 8.608447e-01 1.932152e-02 -5.085007e-01 3.649227e+02 +-5.589647e-01 5.968910e-02 -8.270404e-01 -1.842427e+02 1.409014e-02 9.979454e-01 6.250068e-02 -4.906417e+00 8.290717e-01 2.328256e-02 -5.586572e-01 3.646328e+02 +-6.098841e-01 5.953893e-02 -7.902510e-01 -1.845960e+02 1.470181e-02 9.978522e-01 6.383373e-02 -4.880452e+00 7.923542e-01 2.731306e-02 -6.094495e-01 3.642445e+02 +-6.603689e-01 6.003445e-02 -7.485378e-01 -1.849679e+02 1.597157e-02 9.976966e-01 6.592728e-02 -4.856770e+00 7.507714e-01 3.158101e-02 -6.598066e-01 3.639019e+02 +-7.092737e-01 5.937761e-02 -7.024280e-01 -1.853180e+02 1.844311e-02 9.976682e-01 6.571199e-02 -4.831999e+00 7.046919e-01 3.365283e-02 -7.087149e-01 3.635380e+02 +-7.555738e-01 5.943099e-02 -6.523621e-01 -1.856000e+02 2.222471e-02 9.976283e-01 6.514427e-02 -4.805931e+00 6.546864e-01 3.472274e-02 -7.551026e-01 3.630652e+02 +-7.988709e-01 5.907796e-02 -5.985943e-01 -1.859006e+02 2.394102e-02 9.974994e-01 6.649655e-02 -4.775507e+00 6.010259e-01 3.879120e-02 -7.982876e-01 3.626453e+02 +-8.383895e-01 5.550605e-02 -5.422381e-01 -1.861231e+02 2.322727e-02 9.975360e-01 6.619933e-02 -4.744508e+00 5.445765e-01 4.290610e-02 -8.376129e-01 3.621165e+02 +-8.738963e-01 5.274897e-02 -4.832420e-01 -1.863646e+02 2.341367e-02 9.975088e-01 6.654318e-02 -4.713220e+00 4.855482e-01 4.683737e-02 -8.729543e-01 3.616515e+02 +-9.051966e-01 5.198891e-02 -4.218014e-01 -1.865757e+02 2.608472e-02 9.974148e-01 6.695741e-02 -4.687420e+00 4.241919e-01 4.960704e-02 -9.042125e-01 3.611633e+02 +-9.315783e-01 5.654804e-02 -3.591160e-01 -1.867261e+02 3.403483e-02 9.970558e-01 6.871169e-02 -4.654975e+00 3.619442e-01 5.178787e-02 -9.307601e-01 3.605806e+02 +-9.527563e-01 5.901103e-02 -2.979483e-01 -1.868836e+02 4.017523e-02 9.968103e-01 6.895698e-02 -4.625626e+00 3.010671e-01 5.372905e-02 -9.520881e-01 3.600514e+02 +-9.686751e-01 5.929647e-02 -2.411486e-01 -1.869996e+02 4.422759e-02 9.967431e-01 6.743229e-02 -4.592235e+00 2.443617e-01 5.465455e-02 -9.681426e-01 3.594979e+02 +-9.804789e-01 5.597044e-02 -1.884899e-01 -1.870639e+02 4.447969e-02 9.969160e-01 6.465307e-02 -4.560700e+00 1.915272e-01 5.500699e-02 -9.799446e-01 3.588838e+02 +-9.884014e-01 5.102838e-02 -1.430345e-01 -1.871247e+02 4.242581e-02 9.971388e-01 6.256298e-02 -4.531234e+00 1.458178e-01 5.576897e-02 -9.877383e-01 3.582971e+02 +-9.934441e-01 4.535166e-02 -1.049386e-01 -1.871523e+02 3.916460e-02 9.974124e-01 6.028746e-02 -4.505623e+00 1.074011e-01 5.578233e-02 -9.926496e-01 3.576756e+02 +-9.963187e-01 4.145223e-02 -7.503889e-02 -1.871797e+02 3.689873e-02 9.974504e-01 6.108384e-02 -4.473612e+00 7.737963e-02 5.809012e-02 -9.953079e-01 3.570554e+02 +-9.977972e-01 4.047053e-02 -5.256361e-02 -1.871955e+02 3.712769e-02 9.973172e-01 6.308685e-02 -4.440880e+00 5.497574e-02 6.099631e-02 -9.966228e-01 3.564193e+02 +-9.985377e-01 4.133062e-02 -3.484636e-02 -1.872060e+02 3.914782e-02 9.973604e-01 6.115309e-02 -4.412544e+00 3.728188e-02 5.969950e-02 -9.975199e-01 3.557735e+02 +-9.989044e-01 4.266642e-02 -1.922528e-02 -1.872126e+02 4.153044e-02 9.975639e-01 5.604879e-02 -4.393112e+00 2.156984e-02 5.518894e-02 -9.982429e-01 3.551263e+02 +-9.989320e-01 4.597104e-02 -4.651654e-03 -1.872097e+02 4.569286e-02 9.977830e-01 4.838651e-02 -4.369286e+00 6.865720e-03 4.812228e-02 -9.988178e-01 3.544658e+02 +-9.986796e-01 5.038595e-02 1.001768e-02 -1.871974e+02 5.074252e-02 9.979394e-01 3.926943e-02 -4.339156e+00 -8.018405e-03 3.972589e-02 -9.991784e-01 3.538009e+02 +-9.984338e-01 4.978318e-02 2.552710e-02 -1.871702e+02 5.064785e-02 9.981231e-01 3.442465e-02 -4.316768e+00 -2.376542e-02 3.566362e-02 -9.990812e-01 3.531204e+02 +-9.981428e-01 4.624168e-02 3.965786e-02 -1.871252e+02 4.763379e-02 9.982547e-01 3.490667e-02 -4.298690e+00 -3.797450e-02 3.673089e-02 -9.986034e-01 3.524225e+02 +-9.976692e-01 4.479935e-02 5.147053e-02 -1.870783e+02 4.668419e-02 9.982600e-01 3.601980e-02 -4.279837e+00 -4.976731e-02 3.833870e-02 -9.980247e-01 3.517129e+02 +-9.970587e-01 4.622445e-02 6.113338e-02 -1.870304e+02 4.839278e-02 9.982332e-01 3.447629e-02 -4.261203e+00 -5.943172e-02 3.733329e-02 -9.975340e-01 3.509938e+02 +-9.967822e-01 4.408104e-02 6.694989e-02 -1.869710e+02 4.644513e-02 9.983361e-01 3.417423e-02 -4.242069e+00 -6.533205e-02 3.717375e-02 -9.971709e-01 3.502608e+02 +-9.966352e-01 3.992878e-02 7.158207e-02 -1.869043e+02 4.247851e-02 9.985030e-01 3.445780e-02 -4.221325e+00 -7.009905e-02 3.738255e-02 -9.968393e-01 3.495157e+02 +-9.964330e-01 3.752733e-02 7.558415e-02 -1.868369e+02 4.014029e-02 9.986372e-01 3.335233e-02 -4.199482e+00 -7.422952e-02 3.626733e-02 -9.965814e-01 3.487591e+02 +-9.961127e-01 3.731923e-02 7.979282e-02 -1.867699e+02 4.016267e-02 9.986031e-01 3.433169e-02 -4.177337e+00 -7.840013e-02 3.740292e-02 -9.962200e-01 3.479857e+02 +-9.956153e-01 3.861368e-02 8.520150e-02 -1.867002e+02 4.172390e-02 9.985149e-01 3.502987e-02 -4.153622e+00 -8.372233e-02 3.843120e-02 -9.957477e-01 3.471995e+02 +-9.952306e-01 3.680483e-02 9.034170e-02 -1.866213e+02 4.045359e-02 9.984241e-01 3.889460e-02 -4.129835e+00 -8.876782e-02 4.236373e-02 -9.951510e-01 3.463977e+02 +-9.949026e-01 3.255063e-02 9.544259e-02 -1.865329e+02 3.657758e-02 9.984996e-01 4.075038e-02 -4.104362e+00 -9.397293e-02 4.403371e-02 -9.946004e-01 3.455850e+02 +-9.944347e-01 3.108847e-02 1.006637e-01 -1.864415e+02 3.538405e-02 9.985253e-01 4.117163e-02 -4.077090e+00 -9.923532e-02 4.450438e-02 -9.940682e-01 3.447617e+02 +-9.940038e-01 2.946047e-02 1.053025e-01 -1.863430e+02 3.383768e-02 9.986255e-01 4.002556e-02 -4.043981e+00 -1.039786e-01 4.334874e-02 -9.936344e-01 3.439351e+02 +-9.937319e-01 2.822859e-02 1.081676e-01 -1.862422e+02 3.232519e-02 9.988177e-01 3.630788e-02 -4.015366e+00 -1.070148e-01 3.957683e-02 -9.934694e-01 3.430956e+02 +-9.936779e-01 2.574361e-02 1.092779e-01 -1.861381e+02 2.941187e-02 9.990521e-01 3.208984e-02 -3.987286e+00 -1.083482e-01 3.510103e-02 -9.934931e-01 3.422456e+02 +-9.937461e-01 2.418959e-02 1.090119e-01 -1.860360e+02 2.752673e-02 9.991941e-01 2.921214e-02 -3.960565e+00 -1.082174e-01 3.203018e-02 -9.936111e-01 3.413784e+02 +-9.938599e-01 2.444263e-02 1.079124e-01 -1.859369e+02 2.790306e-02 9.991399e-01 3.067411e-02 -3.936593e+00 -1.070698e-01 3.349685e-02 -9.936870e-01 3.404954e+02 +-9.940648e-01 2.269373e-02 1.063967e-01 -1.858362e+02 2.646425e-02 9.990659e-01 3.416118e-02 -3.912968e+00 -1.055221e-01 3.677413e-02 -9.937367e-01 3.396007e+02 +-9.944083e-01 1.963580e-02 1.037621e-01 -1.857407e+02 2.343103e-02 9.990955e-01 3.548468e-02 -3.893331e+00 -1.029715e-01 3.771751e-02 -9.939689e-01 3.386963e+02 +-9.946803e-01 1.831302e-02 1.013701e-01 -1.856499e+02 2.202904e-02 9.991211e-01 3.566057e-02 -3.868950e+00 -1.006280e-01 3.770394e-02 -9.942094e-01 3.377892e+02 +-9.949748e-01 1.651522e-02 9.875441e-02 -1.855588e+02 2.023026e-02 9.991202e-01 3.673653e-02 -3.843310e+00 -9.806081e-02 3.854974e-02 -9.944334e-01 3.368700e+02 +-9.953039e-01 1.463971e-02 9.568600e-02 -1.854699e+02 1.839618e-02 9.990894e-01 3.849465e-02 -3.819756e+00 -9.503532e-02 4.007413e-02 -9.946669e-01 3.359488e+02 +-9.955645e-01 1.365560e-02 9.308602e-02 -1.853826e+02 1.756023e-02 9.989942e-01 4.125710e-02 -3.795030e+00 -9.242900e-02 4.270871e-02 -9.948029e-01 3.350194e+02 +-9.957762e-01 1.331149e-02 9.084416e-02 -1.853002e+02 1.752134e-02 9.988014e-01 4.570230e-02 -3.764975e+00 -9.012691e-02 4.710096e-02 -9.948158e-01 3.340884e+02 +-9.959957e-01 1.275509e-02 8.848706e-02 -1.852184e+02 1.745002e-02 9.984690e-01 5.248873e-02 -3.733635e+00 -8.768208e-02 5.382264e-02 -9.946934e-01 3.331545e+02 +-9.961830e-01 1.186678e-02 8.647927e-02 -1.851342e+02 1.690448e-02 9.981876e-01 5.775568e-02 -3.698286e+00 -8.563715e-02 5.899710e-02 -9.945781e-01 3.322208e+02 +-9.963830e-01 1.025930e-02 8.435512e-02 -1.850534e+02 1.504292e-02 9.983023e-01 5.626942e-02 -3.662061e+00 -8.363462e-02 5.733483e-02 -9.948456e-01 3.312957e+02 +-9.966026e-01 7.861370e-03 8.198488e-02 -1.849741e+02 1.215374e-02 9.985737e-01 5.198858e-02 -3.627279e+00 -8.145924e-02 5.280837e-02 -9.952766e-01 3.303728e+02 +-9.967791e-01 8.640203e-03 7.972968e-02 -1.848995e+02 1.269010e-02 9.986470e-01 5.042916e-02 -3.589469e+00 -7.918608e-02 5.127850e-02 -9.955400e-01 3.294393e+02 +-9.969232e-01 7.588653e-03 7.801657e-02 -1.848257e+02 1.161914e-02 9.986137e-01 5.133846e-02 -3.554183e+00 -7.751882e-02 5.208698e-02 -9.956293e-01 3.285131e+02 +-9.970723e-01 8.984319e-03 7.593565e-02 -1.847565e+02 1.295678e-02 9.985639e-01 5.198373e-02 -3.522351e+00 -7.535955e-02 5.281540e-02 -9.957567e-01 3.275735e+02 +-9.971547e-01 1.145367e-02 7.450714e-02 -1.846927e+02 1.516954e-02 9.986589e-01 4.949952e-02 -3.489816e+00 -7.384026e-02 5.048891e-02 -9.959912e-01 3.266419e+02 +-9.972948e-01 1.091640e-02 7.269077e-02 -1.846267e+02 1.448511e-02 9.987060e-01 4.874956e-02 -3.457730e+00 -7.206453e-02 4.967061e-02 -9.961623e-01 3.257067e+02 +-9.974790e-01 7.041210e-03 7.061300e-02 -1.845562e+02 1.050092e-02 9.987561e-01 4.874441e-02 -3.428208e+00 -7.018194e-02 4.936302e-02 -9.963120e-01 3.247739e+02 +-9.976280e-01 2.278638e-03 6.879934e-02 -1.844861e+02 5.514911e-03 9.988850e-01 4.688597e-02 -3.397748e+00 -6.861579e-02 4.715416e-02 -9.965281e-01 3.238350e+02 +-9.977938e-01 -1.132186e-03 6.638078e-02 -1.844181e+02 1.922755e-03 9.989424e-01 4.593939e-02 -3.364575e+00 -6.636259e-02 4.596566e-02 -9.967362e-01 3.228956e+02 +-9.979300e-01 -5.032110e-03 6.411358e-02 -1.843480e+02 -1.961670e-03 9.988519e-01 4.786373e-02 -3.332388e+00 -6.428083e-02 4.763887e-02 -9.967941e-01 3.219491e+02 +-9.980669e-01 -9.151789e-03 6.147257e-02 -1.842803e+02 -6.068217e-03 9.987226e-01 5.016228e-02 -3.300810e+00 -6.185312e-02 4.969227e-02 -9.968474e-01 3.210006e+02 +-9.981980e-01 -9.592838e-03 5.923543e-02 -1.842193e+02 -6.496391e-03 9.986131e-01 5.224648e-02 -3.265983e+00 -5.965446e-02 5.176750e-02 -9.968758e-01 3.200498e+02 +-9.983672e-01 -3.834383e-03 5.699468e-02 -1.841701e+02 -8.478517e-04 9.986294e-01 5.233211e-02 -3.231575e+00 -5.711722e-02 5.219833e-02 -9.970019e-01 3.190934e+02 +-9.984642e-01 3.865386e-03 5.526660e-02 -1.841277e+02 6.588943e-03 9.987680e-01 4.918324e-02 -3.199115e+00 -5.500840e-02 4.947185e-02 -9.972595e-01 3.181419e+02 +-9.985477e-01 5.238518e-03 5.361970e-02 -1.840779e+02 7.690445e-03 9.989290e-01 4.562427e-02 -3.164447e+00 -5.332327e-02 4.597036e-02 -9.975185e-01 3.171871e+02 +-9.986099e-01 3.144079e-03 5.261652e-02 -1.840244e+02 5.787295e-03 9.987245e-01 5.015863e-02 -3.127592e+00 -5.239170e-02 5.039341e-02 -9.973543e-01 3.162249e+02 +-9.986151e-01 3.929795e-03 5.246509e-02 -1.839789e+02 7.010536e-03 9.982531e-01 5.866544e-02 -3.092866e+00 -5.214289e-02 5.895199e-02 -9.968980e-01 3.152600e+02 +-9.986216e-01 5.750679e-03 5.217223e-02 -1.839332e+02 8.951732e-03 9.980773e-01 6.133073e-02 -3.055122e+00 -5.171923e-02 6.171321e-02 -9.967530e-01 3.143008e+02 +-9.986156e-01 1.170781e-04 5.260237e-02 -1.838728e+02 3.117758e-03 9.983712e-01 5.696598e-02 -3.008214e+00 -5.251002e-02 5.705110e-02 -9.969893e-01 3.133504e+02 +-9.985475e-01 -4.907340e-03 5.365609e-02 -1.838124e+02 -2.275125e-03 9.987958e-01 4.900845e-02 -2.968608e+00 -5.383197e-02 4.881518e-02 -9.973560e-01 3.124073e+02 +-9.984639e-01 -1.452966e-03 5.538791e-02 -1.837616e+02 9.891994e-04 9.990293e-01 4.403898e-02 -2.932355e+00 -5.539813e-02 4.402611e-02 -9.974932e-01 3.114602e+02 +-9.983835e-01 -6.416411e-04 5.683359e-02 -1.837100e+02 1.790703e-03 9.990848e-01 4.273624e-02 -2.900357e+00 -5.680899e-02 4.276892e-02 -9.974685e-01 3.105136e+02 +-9.983398e-01 -1.109504e-03 5.758920e-02 -1.836542e+02 1.462512e-03 9.990038e-01 4.459994e-02 -2.868230e+00 -5.758132e-02 4.461011e-02 -9.973436e-01 3.095622e+02 +-9.983209e-01 -4.420059e-04 5.792403e-02 -1.836018e+02 2.269527e-03 9.989046e-01 4.673759e-02 -2.838860e+00 -5.788123e-02 4.679056e-02 -9.972263e-01 3.086162e+02 +-9.983784e-01 -2.405604e-04 5.692603e-02 -1.835521e+02 2.406885e-03 9.989185e-01 4.643348e-02 -2.809138e+00 -5.687563e-02 4.649519e-02 -9.972980e-01 3.076738e+02 +-9.985080e-01 -1.651476e-03 5.458224e-02 -1.835027e+02 8.158484e-04 9.989798e-01 4.515048e-02 -2.779480e+00 -5.460112e-02 4.512763e-02 -9.974879e-01 3.067371e+02 +-9.986559e-01 -1.211054e-03 5.181624e-02 -1.834581e+02 1.108385e-03 9.989993e-01 4.471047e-02 -2.749605e+00 -5.181854e-02 4.470780e-02 -9.976552e-01 3.057949e+02 +-9.987961e-01 6.824660e-05 4.905484e-02 -1.834195e+02 2.375459e-03 9.988932e-01 4.697639e-02 -2.718396e+00 -4.899734e-02 4.703636e-02 -9.976907e-01 3.048598e+02 +-9.989324e-01 4.791895e-05 4.619650e-02 -1.833786e+02 2.259040e-03 9.988538e-01 4.781219e-02 -2.689800e+00 -4.614125e-02 4.786550e-02 -9.977874e-01 3.039271e+02 +-9.990585e-01 -1.822606e-03 4.334551e-02 -1.833431e+02 8.849913e-05 9.990294e-01 4.404711e-02 -2.662548e+00 -4.338372e-02 4.400947e-02 -9.980886e-01 3.030002e+02 +-9.991392e-01 1.987768e-03 4.143727e-02 -1.833166e+02 3.641517e-03 9.991981e-01 3.987230e-02 -2.628647e+00 -4.132478e-02 3.998886e-02 -9.983452e-01 3.020756e+02 +-9.991699e-01 2.507305e-03 4.066007e-02 -1.832895e+02 4.265357e-03 9.990569e-01 4.320867e-02 -2.597211e+00 -4.051338e-02 4.334622e-02 -9.982383e-01 3.011445e+02 +-9.991948e-01 1.178021e-03 4.010582e-02 -1.832613e+02 3.098074e-03 9.988499e-01 4.784604e-02 -2.570727e+00 -4.000333e-02 4.793176e-02 -9.980492e-01 3.002119e+02 +-9.991897e-01 3.534238e-03 4.009399e-02 -1.832372e+02 5.529962e-03 9.987451e-01 4.977476e-02 -2.538212e+00 -3.986776e-02 4.995613e-02 -9.979553e-01 2.992862e+02 +-9.991814e-01 4.771053e-03 4.017210e-02 -1.832087e+02 6.585816e-03 9.989579e-01 4.516405e-02 -2.505074e+00 -3.991475e-02 4.539163e-02 -9.981715e-01 2.983688e+02 +-9.991223e-01 6.492765e-03 4.138362e-02 -1.831788e+02 8.218533e-03 9.990977e-01 4.166875e-02 -2.471370e+00 -4.107573e-02 4.197228e-02 -9.982740e-01 2.974500e+02 +-9.989448e-01 1.137894e-02 4.449668e-02 -1.831531e+02 1.319183e-02 9.990858e-01 4.066278e-02 -2.438103e+00 -4.399330e-02 4.120686e-02 -9.981816e-01 2.965249e+02 +-9.987075e-01 1.498792e-02 4.856636e-02 -1.831228e+02 1.709077e-02 9.989212e-01 4.317644e-02 -2.411142e+00 -4.786685e-02 4.395066e-02 -9.978863e-01 2.956017e+02 +-9.984145e-01 1.939432e-02 5.284353e-02 -1.830905e+02 2.167306e-02 9.988444e-01 4.289606e-02 -2.384435e+00 -5.195052e-02 4.397332e-02 -9.976810e-01 2.946849e+02 +-9.982328e-01 1.602972e-02 5.722203e-02 -1.830403e+02 1.835986e-02 9.990136e-01 4.043021e-02 -2.355767e+00 -5.651750e-02 4.140934e-02 -9.975424e-01 2.937625e+02 +-9.981255e-01 1.022608e-02 6.034023e-02 -1.829820e+02 1.252178e-02 9.992072e-01 3.779125e-02 -2.328667e+00 -5.990593e-02 3.847597e-02 -9.974622e-01 2.928436e+02 +-9.980013e-01 9.706870e-03 6.244442e-02 -1.829273e+02 1.234232e-02 9.990431e-01 4.195821e-02 -2.297451e+00 -6.197738e-02 4.264505e-02 -9.971660e-01 2.919083e+02 +-9.979644e-01 9.687798e-03 6.303416e-02 -1.828746e+02 1.264318e-02 9.988310e-01 4.665659e-02 -2.267893e+00 -6.250846e-02 4.735856e-02 -9.969201e-01 2.909730e+02 +-9.979881e-01 6.695272e-03 6.304701e-02 -1.828171e+02 9.879059e-03 9.986841e-01 5.032295e-02 -2.238052e+00 -6.262712e-02 5.084454e-02 -9.967410e-01 2.900341e+02 +-9.978840e-01 9.969184e-03 6.425098e-02 -1.827666e+02 1.291541e-02 9.988761e-01 4.560386e-02 -2.207091e+00 -6.372413e-02 4.633718e-02 -9.968912e-01 2.890992e+02 +-9.977281e-01 1.711478e-02 6.516030e-02 -1.827218e+02 1.952573e-02 9.991412e-01 3.654488e-02 -2.176152e+00 -6.447888e-02 3.773415e-02 -9.972053e-01 2.881653e+02 +-9.976307e-01 2.047487e-02 6.567957e-02 -1.826726e+02 2.266837e-02 9.992039e-01 3.282720e-02 -2.147003e+00 -6.495515e-02 3.423827e-02 -9.973006e-01 2.872220e+02 +-9.977185e-01 1.804456e-02 6.505557e-02 -1.826138e+02 2.053092e-02 9.990761e-01 3.775513e-02 -2.123569e+00 -6.431419e-02 3.900463e-02 -9.971671e-01 2.862673e+02 +-9.977665e-01 1.524609e-02 6.503609e-02 -1.825528e+02 1.824805e-02 9.987832e-01 4.581673e-02 -2.097813e+00 -6.425842e-02 4.690117e-02 -9.968305e-01 2.853066e+02 +-9.978139e-01 1.408128e-02 6.457023e-02 -1.824948e+02 1.728231e-02 9.986351e-01 4.928680e-02 -2.065947e+00 -6.378808e-02 5.029496e-02 -9.966952e-01 2.843463e+02 +-9.978981e-01 1.599587e-02 6.279830e-02 -1.824419e+02 1.910188e-02 9.986075e-01 4.917532e-02 -2.031942e+00 -6.192424e-02 5.027151e-02 -9.968140e-01 2.833856e+02 +-9.980483e-01 1.745674e-02 5.995739e-02 -1.823929e+02 2.020818e-02 9.987556e-01 4.559427e-02 -1.996433e+00 -5.908685e-02 4.671691e-02 -9.971590e-01 2.824284e+02 +-9.981824e-01 1.969323e-02 5.695762e-02 -1.823488e+02 2.215084e-02 9.988362e-01 4.284340e-02 -1.963862e+00 -5.604760e-02 4.402717e-02 -9.974568e-01 2.814646e+02 +-9.983191e-01 2.046627e-02 5.422425e-02 -1.823004e+02 2.290008e-02 9.987402e-01 4.464966e-02 -1.925579e+00 -5.324213e-02 4.581634e-02 -9.975300e-01 2.804906e+02 +-9.984121e-01 2.325060e-02 5.130993e-02 -1.822509e+02 2.584629e-02 9.983886e-01 5.051854e-02 -1.885551e+00 -5.005266e-02 5.176449e-02 -9.974042e-01 2.795142e+02 +-9.985371e-01 2.295253e-02 4.895808e-02 -1.822003e+02 2.564514e-02 9.981515e-01 5.509824e-02 -1.841502e+00 -4.760293e-02 5.627316e-02 -9.972799e-01 2.785289e+02 +-9.986328e-01 2.259906e-02 4.713739e-02 -1.821499e+02 2.510700e-02 9.982623e-01 5.330939e-02 -1.800893e+00 -4.585073e-02 5.441997e-02 -9.974648e-01 2.775570e+02 +-9.986745e-01 2.006255e-02 4.740023e-02 -1.820977e+02 2.248367e-02 9.984399e-01 5.110954e-02 -1.766355e+00 -4.630089e-02 5.210752e-02 -9.975675e-01 2.765833e+02 +-9.985658e-01 2.323133e-02 4.823540e-02 -1.820509e+02 2.559945e-02 9.984671e-01 4.907194e-02 -1.732915e+00 -4.702145e-02 5.023636e-02 -9.976298e-01 2.756086e+02 +-9.984366e-01 2.448874e-02 5.024697e-02 -1.820014e+02 2.703532e-02 9.983508e-01 5.064366e-02 -1.699389e+00 -4.892389e-02 5.192291e-02 -9.974519e-01 2.746278e+02 +-9.983341e-01 2.274934e-02 5.302463e-02 -1.819452e+02 2.543443e-02 9.983988e-01 5.052612e-02 -1.664500e+00 -5.179029e-02 5.179059e-02 -9.973141e-01 2.736526e+02 +-9.981534e-01 2.108874e-02 5.696630e-02 -1.818851e+02 2.419256e-02 9.982284e-01 5.435660e-02 -1.628436e+00 -5.571907e-02 5.563438e-02 -9.968952e-01 2.726701e+02 +-9.979778e-01 2.079746e-02 6.006579e-02 -1.818235e+02 2.421887e-02 9.980914e-01 5.680632e-02 -1.591806e+00 -5.876972e-02 5.814616e-02 -9.965767e-01 2.716890e+02 +-9.979101e-01 2.042248e-02 6.130634e-02 -1.817618e+02 2.383613e-02 9.981754e-01 5.547675e-02 -1.554957e+00 -6.006151e-02 5.682210e-02 -9.965760e-01 2.707124e+02 +-9.978628e-01 2.091333e-02 6.190728e-02 -1.816986e+02 2.393974e-02 9.985336e-01 4.855490e-02 -1.518421e+00 -6.080105e-02 4.993317e-02 -9.969001e-01 2.697430e+02 +-9.977658e-01 2.223882e-02 6.299947e-02 -1.816385e+02 2.495187e-02 9.987801e-01 4.261014e-02 -1.484133e+00 -6.197501e-02 4.408688e-02 -9.971035e-01 2.687678e+02 +-9.976767e-01 1.912250e-02 6.538792e-02 -1.815688e+02 2.190007e-02 9.988763e-01 4.202873e-02 -1.450150e+00 -6.451075e-02 4.336308e-02 -9.969744e-01 2.677765e+02 +-9.975603e-01 1.997411e-02 6.689226e-02 -1.815024e+02 2.313895e-02 9.986326e-01 4.687673e-02 -1.413471e+00 -6.586447e-02 4.831017e-02 -9.966584e-01 2.667855e+02 +-9.975459e-01 1.325752e-02 6.874939e-02 -1.814246e+02 1.694154e-02 9.984357e-01 5.328300e-02 -1.374923e+00 -6.793544e-02 5.431695e-02 -9.962100e-01 2.657878e+02 +-9.974531e-01 1.020604e-02 7.059136e-02 -1.813532e+02 1.391147e-02 9.985397e-01 5.220025e-02 -1.335469e+00 -6.995551e-02 5.304933e-02 -9.961385e-01 2.648055e+02 +-9.972573e-01 1.346563e-02 7.277754e-02 -1.812862e+02 1.681368e-02 9.988188e-01 4.558866e-02 -1.295565e+00 -7.207769e-02 4.668728e-02 -9.963057e-01 2.638162e+02 +-9.970797e-01 1.637935e-02 7.459169e-02 -1.812198e+02 1.886034e-02 9.992879e-01 3.267880e-02 -1.264596e+00 -7.400331e-02 3.399018e-02 -9.966785e-01 2.628382e+02 +-9.968337e-01 2.031560e-02 7.687648e-02 -1.811524e+02 2.203389e-02 9.995245e-01 2.156928e-02 -1.242004e+00 -7.640173e-02 2.319487e-02 -9.968072e-01 2.618529e+02 +-9.965898e-01 2.407933e-02 7.892418e-02 -1.810843e+02 2.585502e-02 9.994333e-01 2.155424e-02 -1.224198e+00 -7.836044e-02 2.352132e-02 -9.966475e-01 2.608590e+02 +-9.964449e-01 2.442469e-02 8.062938e-02 -1.810093e+02 2.715063e-02 9.990902e-01 3.288650e-02 -1.208518e+00 -7.975278e-02 3.495872e-02 -9.962014e-01 2.598449e+02 +-9.964428e-01 2.200869e-02 8.134822e-02 -1.809292e+02 2.572248e-02 9.986607e-01 4.489033e-02 -1.182226e+00 -8.025129e-02 4.682311e-02 -9.956743e-01 2.588320e+02 +-9.964881e-01 2.050220e-02 8.118572e-02 -1.808483e+02 2.480883e-02 9.983180e-01 5.239820e-02 -1.149494e+00 -7.997489e-02 5.422829e-02 -9.953207e-01 2.578248e+02 +-9.965790e-01 1.950259e-02 8.031188e-02 -1.807704e+02 2.375694e-02 9.983455e-01 5.236253e-02 -1.114211e+00 -7.915779e-02 5.409136e-02 -9.953934e-01 2.568280e+02 +-9.966840e-01 2.019145e-02 7.882554e-02 -1.806952e+02 2.394794e-02 9.986075e-01 4.700483e-02 -1.078985e+00 -7.776668e-02 4.873666e-02 -9.957796e-01 2.558384e+02 +-9.967383e-01 2.420343e-02 7.698721e-02 -1.806275e+02 2.749534e-02 9.987396e-01 4.199042e-02 -1.046652e+00 -7.587386e-02 4.397024e-02 -9.961474e-01 2.548491e+02 +-9.968376e-01 2.579074e-02 7.516397e-02 -1.805610e+02 2.887392e-02 9.987733e-01 4.022523e-02 -1.019212e+00 -7.403432e-02 4.226829e-02 -9.963595e-01 2.538604e+02 +-9.968944e-01 2.916869e-02 7.314901e-02 -1.804967e+02 3.187311e-02 9.988405e-01 3.608033e-02 -9.941325e-01 -7.201177e-02 3.829976e-02 -9.966681e-01 2.528750e+02 +-9.969335e-01 3.201212e-02 7.140657e-02 -1.804354e+02 3.461487e-02 9.987695e-01 3.551471e-02 -9.705894e-01 -7.018180e-02 3.787753e-02 -9.968148e-01 2.518909e+02 +-9.970181e-01 3.281358e-02 6.984412e-02 -1.803727e+02 3.555275e-02 9.986319e-01 3.834310e-02 -9.466300e-01 -6.849039e-02 4.071191e-02 -9.968207e-01 2.509082e+02 +-9.971064e-01 3.318144e-02 6.839496e-02 -1.803120e+02 3.615929e-02 9.984303e-01 4.277060e-02 -9.223052e-01 -6.686841e-02 4.511994e-02 -9.967410e-01 2.499236e+02 +-9.972231e-01 3.274316e-02 6.688805e-02 -1.802514e+02 3.571254e-02 9.984066e-01 4.369057e-02 -8.975132e-01 -6.535090e-02 4.595798e-02 -9.968034e-01 2.489474e+02 +-9.973897e-01 3.130770e-02 6.506686e-02 -1.801910e+02 3.410880e-02 9.985186e-01 4.239394e-02 -8.712488e-01 -6.364321e-02 4.450262e-02 -9.969799e-01 2.479795e+02 +-9.975282e-01 2.965914e-02 6.370145e-02 -1.801307e+02 3.230687e-02 9.986390e-01 4.094469e-02 -8.440752e-01 -6.240037e-02 4.290147e-02 -9.971287e-01 2.470169e+02 +-9.975574e-01 3.098137e-02 6.260632e-02 -1.800771e+02 3.364212e-02 9.985552e-01 4.190194e-02 -8.176461e-01 -6.121768e-02 4.390579e-02 -9.971582e-01 2.460599e+02 +-9.975910e-01 3.167595e-02 6.171639e-02 -1.800256e+02 3.445330e-02 9.984164e-01 4.446943e-02 -7.912622e-01 -6.021004e-02 4.648863e-02 -9.971025e-01 2.451048e+02 +-9.976438e-01 3.208050e-02 6.064431e-02 -1.799748e+02 3.493899e-02 9.982988e-01 4.667761e-02 -7.643523e-01 -5.904369e-02 4.868647e-02 -9.970674e-01 2.441585e+02 +-9.974256e-01 3.864042e-02 6.040897e-02 -1.799320e+02 4.171567e-02 9.978523e-01 5.050289e-02 -7.331120e-01 -5.832777e-02 5.289286e-02 -9.968952e-01 2.432222e+02 +-9.972350e-01 4.269384e-02 6.082441e-02 -1.798900e+02 4.596165e-02 9.975160e-01 5.337918e-02 -7.015608e-01 -5.839436e-02 5.602717e-02 -9.967201e-01 2.423011e+02 +-9.972952e-01 4.122611e-02 6.085018e-02 -1.798396e+02 4.436305e-02 9.977060e-01 5.113395e-02 -6.755522e-01 -5.860253e-02 5.369514e-02 -9.968362e-01 2.413981e+02 +-9.969309e-01 4.944306e-02 6.069838e-02 -1.798009e+02 5.235558e-02 9.975044e-01 4.736878e-02 -6.438624e-01 -5.820484e-02 5.040129e-02 -9.970315e-01 2.405085e+02 +-9.965951e-01 5.564877e-02 6.084034e-02 -1.797651e+02 5.848959e-02 9.972298e-01 4.595323e-02 -6.101037e-01 -5.811456e-02 4.935528e-02 -9.970891e-01 2.396292e+02 +-9.971871e-01 4.473263e-02 6.014123e-02 -1.797063e+02 4.744974e-02 9.978803e-01 4.453591e-02 -5.888265e-01 -5.802153e-02 4.726431e-02 -9.971958e-01 2.387631e+02 +-9.977473e-01 3.403087e-02 5.781342e-02 -1.796450e+02 3.633938e-02 9.985641e-01 3.935922e-02 -5.708078e-01 -5.639097e-02 4.137145e-02 -9.975512e-01 2.379148e+02 +-9.978335e-01 3.599311e-02 5.507191e-02 -1.796034e+02 3.780243e-02 9.987672e-01 3.217209e-02 -5.482957e-01 -5.384604e-02 3.418423e-02 -9.979639e-01 2.370777e+02 +-9.981272e-01 3.504328e-02 5.014095e-02 -1.795652e+02 3.686669e-02 9.986746e-01 3.591484e-02 -5.273764e-01 -4.881591e-02 3.769611e-02 -9.980961e-01 2.362422e+02 +-9.985646e-01 2.791231e-02 4.571292e-02 -1.795221e+02 2.986320e-02 9.986473e-01 4.256490e-02 -5.092179e-01 -4.446299e-02 4.386893e-02 -9.980473e-01 2.354177e+02 +-9.988258e-01 2.471756e-02 4.166671e-02 -1.794866e+02 2.663554e-02 9.985806e-01 4.612259e-02 -4.890252e-01 -4.046753e-02 4.717824e-02 -9.980664e-01 2.346106e+02 +-9.989512e-01 2.466021e-02 3.858079e-02 -1.794618e+02 2.647848e-02 9.985273e-01 4.735008e-02 -4.651856e-01 -3.735630e-02 4.832197e-02 -9.981329e-01 2.338196e+02 +-9.990130e-01 2.674164e-02 3.546875e-02 -1.794435e+02 2.841845e-02 9.984599e-01 4.764572e-02 -4.403554e-01 -3.414000e-02 4.860665e-02 -9.982343e-01 2.330489e+02 +-9.991033e-01 2.761392e-02 3.209627e-02 -1.794262e+02 2.914539e-02 9.984090e-01 4.826883e-02 -4.184439e-01 -3.071231e-02 4.916100e-02 -9.983185e-01 2.322935e+02 +-9.992291e-01 2.688436e-02 2.861148e-02 -1.794100e+02 2.826954e-02 9.983906e-01 4.916359e-02 -3.961760e-01 -2.724370e-02 4.993451e-02 -9.983808e-01 2.315589e+02 +-9.993375e-01 2.635335e-02 2.510282e-02 -1.793952e+02 2.756980e-02 9.983978e-01 4.941269e-02 -3.719122e-01 -2.376041e-02 5.007202e-02 -9.984629e-01 2.308454e+02 +-9.993958e-01 2.688265e-02 2.203485e-02 -1.793848e+02 2.794833e-02 9.983793e-01 4.957379e-02 -3.491587e-01 -2.066646e-02 5.015966e-02 -9.985273e-01 2.301530e+02 +-9.993643e-01 2.925682e-02 2.037680e-02 -1.793801e+02 3.024438e-02 9.982926e-01 4.997207e-02 -3.282832e-01 -1.887999e-02 5.055657e-02 -9.985427e-01 2.294817e+02 +-9.992959e-01 3.197517e-02 1.963204e-02 -1.793770e+02 3.292250e-02 9.982067e-01 4.999374e-02 -3.078274e-01 -1.799827e-02 5.060487e-02 -9.985565e-01 2.288304e+02 +-9.992307e-01 3.397066e-02 1.959563e-02 -1.793729e+02 3.488981e-02 9.982066e-01 4.864478e-02 -2.870117e-01 -1.790799e-02 4.929104e-02 -9.986238e-01 2.282030e+02 +-9.991488e-01 3.566889e-02 2.072602e-02 -1.793672e+02 3.662980e-02 9.981756e-01 4.799675e-02 -2.672289e-01 -1.897621e-02 4.871507e-02 -9.986324e-01 2.275967e+02 +-9.989674e-01 3.886522e-02 2.352914e-02 -1.793616e+02 3.994257e-02 9.980868e-01 4.719477e-02 -2.485969e-01 -2.164988e-02 4.808585e-02 -9.986085e-01 2.270094e+02 +-9.987144e-01 4.201232e-02 2.836476e-02 -1.793532e+02 4.329230e-02 9.979969e-01 4.612985e-02 -2.315390e-01 -2.636991e-02 4.729852e-02 -9.985326e-01 2.264456e+02 +-9.984593e-01 4.302391e-02 3.504259e-02 -1.793378e+02 4.461946e-02 9.979398e-01 4.609908e-02 -2.153403e-01 -3.298703e-02 4.759163e-02 -9.983220e-01 2.259028e+02 +-9.981595e-01 4.234893e-02 4.340903e-02 -1.793138e+02 4.436803e-02 9.979252e-01 4.665590e-02 -1.992051e-01 -4.134314e-02 4.849600e-02 -9.979673e-01 2.253829e+02 +-9.976709e-01 4.184389e-02 5.386990e-02 -1.792845e+02 4.436900e-02 9.979294e-01 4.656399e-02 -1.833889e-01 -5.180994e-02 4.884568e-02 -9.974616e-01 2.248897e+02 +-9.967960e-01 4.297559e-02 6.745994e-02 -1.792524e+02 4.612492e-02 9.978832e-01 4.584198e-02 -1.699047e-01 -6.534705e-02 4.880668e-02 -9.966682e-01 2.244216e+02 +-9.953559e-01 4.628344e-02 8.440667e-02 -1.792118e+02 5.008996e-02 9.977947e-01 4.355054e-02 -1.577349e-01 -8.220486e-02 4.757621e-02 -9.954792e-01 2.239655e+02 +-9.932889e-01 4.737817e-02 1.055105e-01 -1.791595e+02 5.186348e-02 9.978456e-01 4.017896e-02 -1.468091e-01 -1.033796e-01 4.538145e-02 -9.936061e-01 2.235204e+02 +-9.902613e-01 4.679603e-02 1.311212e-01 -1.790907e+02 5.215381e-02 9.979261e-01 3.772771e-02 -1.355985e-01 -1.290837e-01 4.419875e-02 -9.906481e-01 2.230843e+02 +-9.857494e-01 4.560044e-02 1.619224e-01 -1.789955e+02 5.209185e-02 9.979906e-01 3.607087e-02 -1.229871e-01 -1.599522e-01 4.399167e-02 -9.861440e-01 2.226423e+02 +-9.789343e-01 4.546082e-02 1.990502e-01 -1.788929e+02 5.346045e-02 9.979565e-01 3.499788e-02 -1.104466e-01 -1.970524e-01 4.490194e-02 -9.793641e-01 2.222223e+02 +-9.696995e-01 4.495261e-02 2.401297e-01 -1.787547e+02 5.471419e-02 9.979183e-01 3.413684e-02 -1.001665e-01 -2.380953e-01 4.624097e-02 -9.701404e-01 2.217930e+02 +-9.579931e-01 4.207432e-02 2.836882e-01 -1.786098e+02 5.364381e-02 9.980102e-01 3.313421e-02 -9.114754e-02 -2.817296e-01 4.696045e-02 -9.583439e-01 2.213982e+02 +-9.437424e-01 3.627054e-02 3.286865e-01 -1.784408e+02 4.936241e-02 9.982818e-01 3.157163e-02 -8.341023e-02 -3.269766e-01 4.602023e-02 -9.439112e-01 2.210195e+02 +-9.270163e-01 2.981371e-02 3.738342e-01 -1.782271e+02 4.357582e-02 9.986460e-01 2.841404e-02 -8.023768e-02 -3.724809e-01 4.263040e-02 -9.270602e-01 2.206320e+02 +-9.080299e-01 2.583418e-02 4.181080e-01 -1.780215e+02 4.009846e-02 9.988737e-01 2.536548e-02 -7.354154e-02 -4.169818e-01 3.979810e-02 -9.080431e-01 2.202778e+02 +-8.860333e-01 2.591017e-02 4.628971e-01 -1.777993e+02 4.042793e-02 9.989518e-01 2.146798e-02 -6.734474e-02 -4.618556e-01 3.773531e-02 -8.861520e-01 2.199124e+02 +-8.613422e-01 2.659761e-02 5.073286e-01 -1.775389e+02 4.176415e-02 9.989555e-01 1.853508e-02 -5.918083e-02 -5.063057e-01 3.715318e-02 -8.615533e-01 2.195279e+02 +-8.339021e-01 2.570727e-02 5.513135e-01 -1.772817e+02 4.226276e-02 9.989559e-01 1.734504e-02 -5.065815e-02 -5.502920e-01 3.776408e-02 -8.341178e-01 2.191907e+02 +-8.033851e-01 2.262152e-02 5.950300e-01 -1.769931e+02 4.169966e-02 9.989621e-01 1.832317e-02 -4.192789e-02 -5.939980e-01 3.953310e-02 -8.034945e-01 2.188687e+02 +-7.691809e-01 2.055460e-02 6.387005e-01 -1.766523e+02 4.340114e-02 9.988550e-01 2.012250e-02 -3.061677e-02 -6.375556e-01 4.319817e-02 -7.691922e-01 2.185186e+02 +-7.313145e-01 2.024783e-02 6.817399e-01 -1.763154e+02 4.764827e-02 9.986337e-01 2.145348e-02 -1.959867e-02 -6.803740e-01 4.817296e-02 -7.312800e-01 2.182050e+02 +-6.902558e-01 2.086270e-02 7.232647e-01 -1.759537e+02 5.022648e-02 9.985546e-01 1.913070e-02 -8.613545e-03 -7.218201e-01 4.953210e-02 -6.903059e-01 2.179086e+02 +-6.461045e-01 2.114756e-02 7.629560e-01 -1.755342e+02 4.967208e-02 9.986620e-01 1.438363e-02 1.303197e-03 -7.616309e-01 4.719092e-02 -6.462904e-01 2.176015e+02 +-5.989000e-01 2.034696e-02 8.005653e-01 -1.751080e+02 4.812566e-02 9.987848e-01 1.061777e-02 8.884163e-03 -7.993764e-01 4.488671e-02 -5.991514e-01 2.173396e+02 +-5.500654e-01 2.032669e-02 8.348742e-01 -1.746464e+02 4.556859e-02 9.989449e-01 5.701999e-03 1.392669e-02 -8.338774e-01 4.118050e-02 -5.504112e-01 2.170988e+02 +-5.003583e-01 2.474633e-02 8.654648e-01 -1.741229e+02 4.654100e-02 9.989150e-01 -1.654963e-03 1.612814e-02 -8.645666e-01 3.945151e-02 -5.009671e-01 2.168298e+02 +-4.506962e-01 2.898178e-02 8.922068e-01 -1.735983e+02 4.783918e-02 9.988207e-01 -8.279107e-03 1.603695e-02 -8.913946e-01 3.895107e-02 -4.515512e-01 2.166318e+02 +-4.000276e-01 2.866854e-02 9.160546e-01 -1.730375e+02 4.709700e-02 9.988331e-01 -1.069259e-02 1.526395e-02 -9.152922e-01 3.886609e-02 -4.009110e-01 2.164235e+02 +-3.485587e-01 2.464741e-02 9.369628e-01 -1.724740e+02 4.444381e-02 9.989643e-01 -9.744902e-03 1.245219e-02 -9.362326e-01 3.824552e-02 -3.492931e-01 2.162595e+02 +-2.963673e-01 2.040642e-02 9.548560e-01 -1.718842e+02 3.855601e-02 9.992123e-01 -9.387394e-03 1.226133e-02 -9.542954e-01 3.403331e-02 -2.969206e-01 2.161281e+02 +-2.447217e-01 1.766386e-02 9.694325e-01 -1.712424e+02 3.118455e-02 9.994601e-01 -1.033883e-02 6.738538e-03 -9.690917e-01 2.770117e-02 -2.451404e-01 2.159877e+02 +-1.965382e-01 1.272851e-02 9.804136e-01 -1.706006e+02 2.523249e-02 9.996502e-01 -7.920038e-03 -6.340179e-04 -9.801714e-01 2.318167e-02 -1.967906e-01 2.158959e+02 +-1.543085e-01 7.278431e-03 9.879959e-01 -1.699389e+02 2.371097e-02 9.997121e-01 -3.661491e-03 -7.785711e-03 -9.877381e-01 2.286133e-02 -1.544366e-01 2.158249e+02 +-1.185439e-01 7.015819e-03 9.929241e-01 -1.692517e+02 2.303227e-02 9.997254e-01 -4.314090e-03 -1.961535e-02 -9.926816e-01 2.235788e-02 -1.186729e-01 2.157481e+02 +-8.853081e-02 1.174770e-02 9.960042e-01 -1.685656e+02 1.983274e-02 9.997530e-01 -1.002907e-02 -3.513643e-02 -9.958759e-01 1.886560e-02 -8.874193e-02 2.157053e+02 +-6.421770e-02 1.800979e-02 9.977734e-01 -1.678625e+02 1.532884e-02 9.997370e-01 -1.705866e-02 -4.809223e-02 -9.978181e-01 1.419924e-02 -6.447687e-02 2.156708e+02 +-4.477947e-02 2.512077e-02 9.986810e-01 -1.671609e+02 1.179472e-02 9.996274e-01 -2.461573e-02 -5.831758e-02 -9.989272e-01 1.067688e-02 -4.505908e-02 2.156513e+02 +-2.908638e-02 2.533780e-02 9.992557e-01 -1.664434e+02 1.122628e-02 9.996239e-01 -2.502037e-02 -7.436568e-02 -9.995138e-01 1.049017e-02 -2.935988e-02 2.156216e+02 +-1.873924e-02 1.827257e-02 9.996574e-01 -1.657179e+02 1.263633e-02 9.997574e-01 -1.803753e-02 -9.615531e-02 -9.997445e-01 1.229399e-02 -1.896559e-02 2.155997e+02 +-1.235537e-02 1.235622e-02 9.998474e-01 -1.649838e+02 1.354171e-02 9.998340e-01 -1.218873e-02 -1.188212e-01 -9.998319e-01 1.338904e-02 -1.252064e-02 2.155792e+02 +-7.260480e-03 1.067545e-02 9.999167e-01 -1.642460e+02 1.512135e-02 9.998298e-01 -1.056473e-02 -1.389040e-01 -9.998593e-01 1.504338e-02 -7.420670e-03 2.155684e+02 +-3.185157e-03 1.326303e-02 9.999070e-01 -1.635009e+02 1.741937e-02 9.997610e-01 -1.320561e-02 -1.556038e-01 -9.998432e-01 1.737568e-02 -3.415428e-03 2.155524e+02 +8.592044e-04 2.293189e-02 9.997367e-01 -1.627532e+02 1.972934e-02 9.995420e-01 -2.294439e-02 -1.745427e-01 -9.998049e-01 1.974385e-02 4.063811e-04 2.155422e+02 +3.731294e-03 3.081124e-02 9.995183e-01 -1.619912e+02 1.921589e-02 9.993384e-01 -3.087744e-02 -1.972969e-01 -9.998084e-01 1.932183e-02 3.136761e-03 2.155327e+02 +5.863838e-03 3.318676e-02 9.994320e-01 -1.612119e+02 2.102289e-02 9.992241e-01 -3.330322e-02 -2.213943e-01 -9.997618e-01 2.120623e-02 5.161607e-03 2.155241e+02 +8.073372e-03 2.852556e-02 9.995605e-01 -1.604196e+02 2.328480e-02 9.993166e-01 -2.870668e-02 -2.475348e-01 -9.996962e-01 2.350632e-02 7.403643e-03 2.155174e+02 +1.008213e-02 1.819469e-02 9.997837e-01 -1.596089e+02 2.389380e-02 9.995446e-01 -1.843130e-02 -2.795917e-01 -9.996636e-01 2.407444e-02 9.642803e-03 2.155124e+02 +1.219213e-02 1.489025e-02 9.998148e-01 -1.587983e+02 2.615664e-02 9.995422e-01 -1.520516e-02 -3.074569e-01 -9.995835e-01 2.633718e-02 1.179707e-02 2.155063e+02 +1.451325e-02 1.561239e-02 9.997728e-01 -1.579869e+02 2.950628e-02 9.994359e-01 -1.603547e-02 -3.292413e-01 -9.994592e-01 2.973229e-02 1.404440e-02 2.154944e+02 +1.695341e-02 1.836247e-02 9.996877e-01 -1.571687e+02 3.207913e-02 9.993066e-01 -1.889950e-02 -3.490628e-01 -9.993415e-01 3.238951e-02 1.635260e-02 2.154909e+02 +1.889659e-02 1.992290e-02 9.996230e-01 -1.563334e+02 3.362382e-02 9.992232e-01 -2.055056e-02 -3.744766e-01 -9.992559e-01 3.399947e-02 1.821203e-02 2.154749e+02 +2.043865e-02 2.028840e-02 9.995853e-01 -1.554939e+02 3.465424e-02 9.991789e-01 -2.098874e-02 -3.999312e-01 -9.991903e-01 3.506884e-02 1.971879e-02 2.154766e+02 +2.199562e-02 2.159573e-02 9.995248e-01 -1.546509e+02 3.134288e-02 9.992603e-01 -2.227975e-02 -4.260836e-01 -9.992666e-01 3.181804e-02 2.130248e-02 2.154909e+02 +2.294006e-02 2.251953e-02 9.994832e-01 -1.537980e+02 3.022963e-02 9.992735e-01 -2.320864e-02 -4.491774e-01 -9.992797e-01 3.074641e-02 2.224263e-02 2.155215e+02 +2.446594e-02 2.227928e-02 9.994524e-01 -1.529246e+02 3.099251e-02 9.992542e-01 -2.303354e-02 -4.765393e-01 -9.992201e-01 3.153906e-02 2.375720e-02 2.155288e+02 +2.540903e-02 1.744622e-02 9.995249e-01 -1.520430e+02 3.392248e-02 9.992568e-01 -1.830389e-02 -5.017483e-01 -9.991014e-01 3.437144e-02 2.479833e-02 2.155373e+02 +2.646854e-02 1.295087e-02 9.995658e-01 -1.511495e+02 3.538576e-02 9.992773e-01 -1.388415e-02 -5.295159e-01 -9.990231e-01 3.573788e-02 2.599113e-02 2.155450e+02 +2.835642e-02 1.228304e-02 9.995224e-01 -1.502503e+02 3.596512e-02 9.992645e-01 -1.330020e-02 -5.601175e-01 -9.989506e-01 3.632508e-02 2.789380e-02 2.155562e+02 +3.147828e-02 1.497887e-02 9.993922e-01 -1.493558e+02 4.054759e-02 9.990454e-01 -1.625082e-02 -5.823925e-01 -9.986816e-01 4.103448e-02 3.084087e-02 2.155771e+02 +3.613727e-02 1.652910e-02 9.992102e-01 -1.484648e+02 4.473946e-02 9.988339e-01 -1.814092e-02 -6.008344e-01 -9.983448e-01 4.535968e-02 3.535562e-02 2.156092e+02 +4.041012e-02 1.371443e-02 9.990891e-01 -1.475671e+02 4.564691e-02 9.988365e-01 -1.555725e-02 -6.198851e-01 -9.981399e-01 4.623399e-02 3.973708e-02 2.156569e+02 +4.491279e-02 1.033987e-02 9.989374e-01 -1.466647e+02 4.472494e-02 9.989230e-01 -1.235058e-02 -6.483958e-01 -9.979892e-01 4.523210e-02 4.440196e-02 2.156906e+02 +4.976907e-02 9.341506e-03 9.987171e-01 -1.457612e+02 4.437813e-02 9.989480e-01 -1.155517e-02 -6.795057e-01 -9.977743e-01 4.489627e-02 4.930215e-02 2.157217e+02 +5.504587e-02 9.230824e-03 9.984412e-01 -1.448559e+02 4.651039e-02 9.988481e-01 -1.179879e-02 -7.108617e-01 -9.973999e-01 4.708736e-02 5.455313e-02 2.157519e+02 +6.038061e-02 5.292635e-03 9.981614e-01 -1.439508e+02 4.518336e-02 9.989464e-01 -8.030026e-03 -7.389006e-01 -9.971522e-01 4.558513e-02 6.007785e-02 2.157977e+02 +6.523002e-02 1.276598e-03 9.978695e-01 -1.430473e+02 4.547140e-02 9.989566e-01 -4.250427e-03 -7.706459e-01 -9.968336e-01 4.565177e-02 6.510391e-02 2.158453e+02 +7.038445e-02 1.445692e-03 9.975189e-01 -1.421458e+02 4.433840e-02 9.990061e-01 -4.576348e-03 -8.040035e-01 -9.965340e-01 4.455048e-02 7.025039e-02 2.158968e+02 +7.518003e-02 1.083875e-02 9.971111e-01 -1.412479e+02 3.949540e-02 9.991239e-01 -1.383850e-02 -8.410487e-01 -9.963875e-01 4.042167e-02 7.468608e-02 2.159462e+02 +7.997385e-02 1.697851e-02 9.966524e-01 -1.403543e+02 3.694618e-02 9.991174e-01 -1.998516e-02 -8.685023e-01 -9.961120e-01 3.842078e-02 7.927597e-02 2.160153e+02 +8.455566e-02 1.490481e-02 9.963073e-01 -1.394551e+02 3.748894e-02 9.991326e-01 -1.812873e-02 -8.905654e-01 -9.957132e-01 3.888338e-02 8.392355e-02 2.160874e+02 +8.833661e-02 9.933680e-03 9.960412e-01 -1.385557e+02 3.406495e-02 9.993352e-01 -1.298768e-02 -9.204463e-01 -9.955080e-01 3.507737e-02 8.793949e-02 2.161647e+02 +9.023938e-02 5.326776e-03 9.959059e-01 -1.376571e+02 2.809989e-02 9.995739e-01 -7.892541e-03 -9.524096e-01 -9.955236e-01 2.869705e-02 9.005124e-02 2.162474e+02 +9.116475e-02 6.387730e-03 9.958154e-01 -1.367684e+02 2.662971e-02 9.996062e-01 -8.849944e-03 -9.745783e-01 -9.954797e-01 2.732506e-02 9.095874e-02 2.163308e+02 +9.108455e-02 8.534801e-03 9.958066e-01 -1.358805e+02 2.547840e-02 9.996159e-01 -1.089792e-02 -9.967056e-01 -9.955171e-01 2.636418e-02 9.083211e-02 2.164147e+02 +9.024122e-02 9.460066e-03 9.958750e-01 -1.349897e+02 2.256011e-02 9.996789e-01 -1.154049e-02 -1.024534e+00 -9.956643e-01 2.350847e-02 8.999881e-02 2.164855e+02 +8.939503e-02 9.507446e-03 9.959509e-01 -1.341037e+02 1.865576e-02 9.997630e-01 -1.121836e-02 -1.047336e+00 -9.958215e-01 1.958308e-02 8.919647e-02 2.165623e+02 +8.827417e-02 1.144954e-02 9.960304e-01 -1.332288e+02 1.100799e-02 9.998616e-01 -1.246918e-02 -1.071600e+00 -9.960353e-01 1.206499e-02 8.813592e-02 2.166465e+02 +8.633051e-02 1.330099e-02 9.961778e-01 -1.323612e+02 8.337092e-03 9.998662e-01 -1.407275e-02 -1.094509e+00 -9.962316e-01 9.520128e-03 8.620806e-02 2.167257e+02 +8.483742e-02 1.871565e-02 9.962190e-01 -1.315054e+02 7.252038e-03 9.997855e-01 -1.940024e-02 -1.117805e+00 -9.963684e-01 8.870479e-03 8.468349e-02 2.168030e+02 +8.242280e-02 2.001024e-02 9.963966e-01 -1.306583e+02 1.937441e-03 9.997933e-01 -2.023872e-02 -1.143989e+00 -9.965955e-01 3.598587e-03 8.236698e-02 2.168839e+02 +8.108829e-02 2.048022e-02 9.964965e-01 -1.298199e+02 1.424722e-03 9.997854e-01 -2.066376e-02 -1.168113e+00 -9.967059e-01 3.095316e-03 8.104171e-02 2.169542e+02 +7.907886e-02 1.820206e-02 9.967022e-01 -1.289928e+02 3.361164e-03 9.998227e-01 -1.852573e-02 -1.194745e+00 -9.968627e-01 4.815068e-03 7.900366e-02 2.170182e+02 +7.633885e-02 1.626123e-02 9.969494e-01 -1.281705e+02 2.200203e-03 9.998618e-01 -1.647722e-02 -1.232860e+00 -9.970795e-01 3.451338e-03 7.629252e-02 2.170757e+02 +7.342230e-02 1.586447e-02 9.971748e-01 -1.273692e+02 -5.401203e-04 9.998739e-01 -1.586765e-02 -1.272130e+00 -9.973008e-01 6.264412e-04 7.342161e-02 2.171305e+02 +7.050436e-02 1.591698e-02 9.973845e-01 -1.265849e+02 -4.223094e-03 9.998685e-01 -1.565810e-02 -1.306515e+00 -9.975025e-01 -3.108086e-03 7.056231e-02 2.171910e+02 +6.662052e-02 1.555635e-02 9.976571e-01 -1.258229e+02 -6.457742e-03 9.998642e-01 -1.515955e-02 -1.342639e+00 -9.977574e-01 -5.432678e-03 6.671193e-02 2.172500e+02 +6.171212e-02 1.568753e-02 9.979707e-01 -1.250760e+02 -5.548005e-03 9.998664e-01 -1.537426e-02 -1.381566e+00 -9.980785e-01 -4.587971e-03 6.179091e-02 2.172890e+02 +5.572867e-02 1.809429e-02 9.982820e-01 -1.243571e+02 -6.040366e-03 9.998236e-01 -1.778504e-02 -1.421077e+00 -9.984276e-01 -5.038854e-03 5.582813e-02 2.173301e+02 +4.896490e-02 2.049042e-02 9.985903e-01 -1.236574e+02 -5.455572e-03 9.997801e-01 -2.024733e-02 -1.453254e+00 -9.987856e-01 -4.456476e-03 4.906591e-02 2.173657e+02 +4.310026e-02 2.075216e-02 9.988552e-01 -1.229783e+02 -3.520074e-03 9.997812e-01 -2.061952e-02 -1.493099e+00 -9.990645e-01 -2.627341e-03 4.316388e-02 2.173942e+02 +3.776879e-02 1.981509e-02 9.990901e-01 -1.223261e+02 -1.107404e-03 9.998036e-01 -1.978739e-02 -1.535093e+00 -9.992858e-01 -3.590538e-04 3.778332e-02 2.174189e+02 +3.210016e-02 2.033701e-02 9.992778e-01 -1.216962e+02 2.442903e-03 9.997884e-01 -2.042588e-02 -1.572983e+00 -9.994816e-01 3.096808e-03 3.204368e-02 2.174395e+02 +2.605659e-02 2.176843e-02 9.994235e-01 -1.210747e+02 5.880197e-03 9.997422e-01 -2.192868e-02 -1.610957e+00 -9.996431e-01 6.448189e-03 2.592187e-02 2.174520e+02 +2.032068e-02 2.379152e-02 9.995104e-01 -1.204635e+02 5.416513e-03 9.996995e-01 -2.390615e-02 -1.644178e+00 -9.997788e-01 5.899646e-03 2.018570e-02 2.174662e+02 +1.409916e-02 2.666648e-02 9.995450e-01 -1.198581e+02 8.048893e-03 9.996089e-01 -2.678173e-02 -1.678712e+00 -9.998682e-01 8.422825e-03 1.387901e-02 2.174794e+02 +8.621016e-03 2.835402e-02 9.995608e-01 -1.192538e+02 8.505430e-03 9.995597e-01 -2.842735e-02 -1.711980e+00 -9.999266e-01 8.746762e-03 8.376057e-03 2.174870e+02 +3.515091e-03 2.853458e-02 9.995867e-01 -1.186536e+02 6.907448e-03 9.995682e-01 -2.855836e-02 -1.742730e+00 -9.999699e-01 7.004973e-03 3.316473e-03 2.174972e+02 +-1.628374e-03 2.984565e-02 9.995532e-01 -1.180529e+02 5.409591e-03 9.995401e-01 -2.983646e-02 -1.765239e+00 -9.999840e-01 5.358585e-03 -1.789077e-03 2.175009e+02 +-5.179471e-03 2.569942e-02 9.996563e-01 -1.174528e+02 6.715550e-03 9.996480e-01 -2.566442e-02 -1.789865e+00 -9.999640e-01 6.580309e-03 -5.350232e-03 2.175015e+02 +-6.471473e-03 1.843254e-02 9.998092e-01 -1.168496e+02 9.144750e-03 9.997894e-01 -1.837299e-02 -1.815262e+00 -9.999372e-01 9.024100e-03 -6.638669e-03 2.174959e+02 +-7.568888e-03 1.213899e-02 9.998977e-01 -1.162506e+02 1.053290e-02 9.998718e-01 -1.205895e-02 -1.840900e+00 -9.999158e-01 1.044054e-02 -7.695775e-03 2.174919e+02 +-7.038889e-03 8.675549e-03 9.999376e-01 -1.156610e+02 1.094106e-02 9.999032e-01 -8.598238e-03 -1.856427e+00 -9.999153e-01 1.087985e-02 -7.133125e-03 2.175002e+02 +-4.737082e-03 2.515654e-03 9.999856e-01 -1.150678e+02 7.560565e-03 9.999683e-01 -2.479800e-03 -1.864826e+00 -9.999602e-01 7.548704e-03 -4.755950e-03 2.175140e+02 +-2.149378e-03 -2.889002e-03 9.999935e-01 -1.144769e+02 6.545977e-03 9.999743e-01 2.903012e-03 -1.869443e+00 -9.999762e-01 6.552170e-03 -2.130410e-03 2.175287e+02 +3.025416e-03 -1.089564e-03 9.999949e-01 -1.138982e+02 1.168629e-02 9.999311e-01 1.054134e-03 -1.885694e+00 -9.999271e-01 1.168303e-02 3.037942e-03 2.175304e+02 +1.111706e-02 1.428958e-03 9.999372e-01 -1.133240e+02 1.999914e-02 9.997986e-01 -1.651110e-03 -1.905071e+00 -9.997381e-01 2.001623e-02 1.108624e-02 2.175353e+02 +2.266651e-02 6.675049e-03 9.997208e-01 -1.127521e+02 2.450370e-02 9.996736e-01 -7.230308e-03 -1.917050e+00 -9.994427e-01 2.466073e-02 2.249555e-02 2.175543e+02 +3.911843e-02 1.623123e-02 9.991028e-01 -1.121880e+02 3.053812e-02 9.993816e-01 -1.743144e-02 -1.923584e+00 -9.987678e-01 3.119260e-02 3.859857e-02 2.175872e+02 +5.957786e-02 1.941745e-02 9.980348e-01 -1.116160e+02 3.533581e-02 9.991431e-01 -2.154840e-02 -1.935585e+00 -9.975980e-01 3.655017e-02 5.884067e-02 2.176231e+02 +8.199681e-02 1.592890e-02 9.965053e-01 -1.110473e+02 3.694496e-02 9.991364e-01 -1.901095e-02 -1.945084e+00 -9.959475e-01 3.837467e-02 8.133750e-02 2.176962e+02 +1.056730e-01 1.716449e-02 9.942528e-01 -1.104838e+02 3.735413e-02 9.990768e-01 -2.121791e-02 -1.964158e+00 -9.936991e-01 3.938160e-02 1.049343e-01 2.177775e+02 +1.312508e-01 2.099860e-02 9.911268e-01 -1.099277e+02 3.728450e-02 9.989637e-01 -2.610207e-02 -1.976780e+00 -9.906478e-01 4.037957e-02 1.303319e-01 2.178753e+02 +1.610889e-01 2.084459e-02 9.867198e-01 -1.093774e+02 3.592609e-02 9.989905e-01 -2.696900e-02 -1.987256e+00 -9.862858e-01 3.979338e-02 1.601774e-01 2.180015e+02 +1.942726e-01 1.835305e-02 9.807759e-01 -1.088327e+02 3.626557e-02 9.990071e-01 -2.587771e-02 -1.995466e+00 -9.802769e-01 4.059572e-02 1.934141e-01 2.181458e+02 +2.298126e-01 1.656791e-02 9.730939e-01 -1.082909e+02 3.397316e-02 9.991091e-01 -2.503419e-02 -2.004646e+00 -9.726417e-01 3.881223e-02 2.290450e-01 2.183013e+02 +2.679109e-01 1.205567e-02 9.633683e-01 -1.077640e+02 2.793854e-02 9.994040e-01 -2.027628e-02 -2.019178e+00 -9.630385e-01 3.234733e-02 2.674143e-01 2.184985e+02 +3.096707e-01 7.249328e-03 9.508163e-01 -1.072563e+02 2.372564e-02 9.996007e-01 -1.534847e-02 -2.021587e+00 -9.505478e-01 2.731169e-02 3.093750e-01 2.187282e+02 +3.536117e-01 7.421920e-03 9.353629e-01 -1.067495e+02 2.241190e-02 9.996142e-01 -1.640451e-02 -2.025929e+00 -9.351238e-01 2.676408e-02 3.533089e-01 2.189454e+02 +3.986985e-01 7.783227e-03 9.170491e-01 -1.062729e+02 2.113521e-02 9.996204e-01 -1.767283e-02 -2.029648e+00 -9.168385e-01 2.642815e-02 3.983826e-01 2.192153e+02 +4.452357e-01 7.557993e-03 8.953815e-01 -1.057926e+02 1.968046e-02 9.996402e-01 -1.822432e-02 -2.038583e+00 -8.951971e-01 2.573563e-02 4.449267e-01 2.194762e+02 +4.922363e-01 9.732946e-03 8.704072e-01 -1.053492e+02 1.766807e-02 9.996198e-01 -2.116953e-02 -2.045845e+00 -8.702823e-01 2.579882e-02 4.918771e-01 2.197938e+02 +5.386538e-01 1.318341e-02 8.424241e-01 -1.049255e+02 1.787414e-02 9.994737e-01 -2.707003e-02 -2.060392e+00 -8.423375e-01 2.963898e-02 5.381347e-01 2.201308e+02 +5.839280e-01 1.797787e-02 8.116064e-01 -1.045035e+02 1.688669e-02 9.992694e-01 -3.428429e-02 -2.078284e+00 -8.116298e-01 3.372489e-02 5.831978e-01 2.204538e+02 +6.280457e-01 2.106081e-02 7.778914e-01 -1.041155e+02 1.379795e-02 9.991751e-01 -3.819194e-02 -2.105153e+00 -7.780541e-01 3.471958e-02 6.272371e-01 2.208349e+02 +6.699816e-01 2.135417e-02 7.420706e-01 -1.037453e+02 1.414829e-02 9.990374e-01 -4.152262e-02 -2.129794e+00 -7.422429e-01 3.831841e-02 6.690345e-01 2.212334e+02 +7.095755e-01 1.505440e-02 7.044687e-01 -1.033709e+02 1.959886e-02 9.989632e-01 -4.108865e-02 -2.158418e+00 -7.043568e-01 4.296227e-02 7.085447e-01 2.216160e+02 +7.461192e-01 7.924154e-03 6.657653e-01 -1.030360e+02 2.160188e-02 9.991146e-01 -3.610088e-02 -2.189144e+00 -6.654619e-01 4.131733e-02 7.452873e-01 2.220512e+02 +7.795734e-01 3.816531e-03 6.262993e-01 -1.027308e+02 2.121189e-02 9.992468e-01 -3.249226e-02 -2.232675e+00 -6.259516e-01 3.861508e-02 7.789052e-01 2.225002e+02 +8.104792e-01 4.235603e-03 5.857521e-01 -1.024376e+02 1.762740e-02 9.993446e-01 -3.161657e-02 -2.273704e+00 -5.855021e-01 3.594985e-02 8.098733e-01 2.229327e+02 +8.391007e-01 2.362030e-03 5.439711e-01 -1.021791e+02 1.911380e-02 9.992450e-01 -3.382284e-02 -2.315727e+00 -5.436403e-01 3.877811e-02 8.384220e-01 2.234001e+02 +8.652185e-01 2.006879e-03 5.013911e-01 -1.019309e+02 1.863895e-02 9.991720e-01 -3.616335e-02 -2.347150e+00 -5.010485e-01 4.063459e-02 8.644647e-01 2.238528e+02 +8.882291e-01 3.490833e-03 4.593876e-01 -1.017237e+02 1.510501e-02 9.992085e-01 -3.679852e-02 -2.383609e+00 -4.591524e-01 3.962456e-02 8.874733e-01 2.243458e+02 +9.085359e-01 7.092991e-03 4.177468e-01 -1.015432e+02 8.964448e-03 9.992948e-01 -3.646351e-02 -2.415078e+00 -4.177108e-01 3.687327e-02 9.078315e-01 2.248487e+02 +9.263823e-01 1.230380e-02 3.763835e-01 -1.013752e+02 6.735876e-04 9.994104e-01 -3.432813e-02 -2.444928e+00 -3.765839e-01 3.205449e-02 9.258277e-01 2.253389e+02 +9.409404e-01 1.635955e-02 3.381769e-01 -1.012366e+02 -5.611613e-03 9.994483e-01 -3.273532e-02 -2.472231e+00 -3.385258e-01 2.890427e-02 9.405130e-01 2.258512e+02 +9.521679e-01 2.134674e-02 3.048288e-01 -1.011157e+02 -1.312290e-02 9.994932e-01 -2.900225e-02 -2.499770e+00 -3.052934e-01 2.361477e-02 9.519654e-01 2.263838e+02 +9.603605e-01 2.881652e-02 2.772676e-01 -1.010069e+02 -2.235077e-02 9.994002e-01 -2.645255e-02 -2.526393e+00 -2.778636e-01 1.920684e-02 9.604285e-01 2.269101e+02 +9.657553e-01 4.070631e-02 2.562416e-01 -1.009157e+02 -3.565333e-02 9.990678e-01 -2.433635e-02 -2.553482e+00 -2.569933e-01 1.436709e-02 9.663063e-01 2.274386e+02 +9.692204e-01 5.063334e-02 2.409319e-01 -1.008306e+02 -4.662699e-02 9.986633e-01 -2.230435e-02 -2.570641e+00 -2.417392e-01 1.038390e-02 9.702856e-01 2.279686e+02 +9.717072e-01 5.214659e-02 2.303605e-01 -1.007342e+02 -4.831000e-02 9.985841e-01 -2.226766e-02 -2.585013e+00 -2.311955e-01 1.050893e-02 9.728505e-01 2.284882e+02 +9.734555e-01 5.283127e-02 2.226958e-01 -1.006347e+02 -4.872709e-02 9.985264e-01 -2.388812e-02 -2.600567e+00 -2.236296e-01 1.240270e-02 9.745952e-01 2.290030e+02 +9.744748e-01 5.195808e-02 2.184017e-01 -1.005311e+02 -4.756034e-02 9.985466e-01 -2.534884e-02 -2.625163e+00 -2.194013e-01 1.431455e-02 9.755296e-01 2.295011e+02 +9.743505e-01 5.548929e-02 2.180874e-01 -1.004466e+02 -5.122549e-02 9.983701e-01 -2.516092e-02 -2.640569e+00 -2.191281e-01 1.334392e-02 9.756048e-01 2.300159e+02 +9.737176e-01 5.964601e-02 2.198101e-01 -1.003557e+02 -5.532738e-02 9.981360e-01 -2.575674e-02 -2.656963e+00 -2.209367e-01 1.291827e-02 9.752025e-01 2.305209e+02 +9.730356e-01 5.589260e-02 2.237807e-01 -1.002521e+02 -5.085892e-02 9.983076e-01 -2.819939e-02 -2.672563e+00 -2.249781e-01 1.605776e-02 9.742314e-01 2.310179e+02 +9.710135e-01 5.148934e-02 2.334130e-01 -1.001357e+02 -4.553357e-02 9.984867e-01 -3.083685e-02 -2.688480e+00 -2.346475e-01 1.931486e-02 9.718886e-01 2.315079e+02 +9.672846e-01 4.711881e-02 2.492797e-01 -1.000122e+02 -4.065866e-02 9.986919e-01 -3.100408e-02 -2.703396e+00 -2.504145e-01 1.985439e-02 9.679351e-01 2.319873e+02 +9.619036e-01 4.635601e-02 2.694303e-01 -9.988399e+01 -3.977828e-02 9.987633e-01 -2.982522e-02 -2.718972e+00 -2.704797e-01 1.797151e-02 9.625579e-01 2.324635e+02 +9.538843e-01 4.783415e-02 2.963387e-01 -9.975006e+01 -4.175051e-02 9.987678e-01 -2.682763e-02 -2.728487e+00 -2.972568e-01 1.321816e-02 9.547060e-01 2.329331e+02 +9.430510e-01 4.628199e-02 3.294129e-01 -9.959956e+01 -4.177250e-02 9.989115e-01 -2.075819e-02 -2.739823e+00 -3.300150e-01 5.815627e-03 9.439577e-01 2.333861e+02 +9.300200e-01 3.943292e-02 3.653874e-01 -9.942555e+01 -3.755768e-02 9.992195e-01 -1.224113e-02 -2.754618e+00 -3.655849e-01 -2.338610e-03 9.307750e-01 2.338241e+02 +9.147938e-01 1.963845e-02 4.034436e-01 -9.920992e+01 -1.710494e-02 9.998048e-01 -9.882732e-03 -2.762877e+00 -4.035589e-01 2.139780e-03 9.149511e-01 2.341986e+02 +8.956362e-01 7.946240e-03 4.447165e-01 -9.899629e+01 -1.542821e-03 9.998899e-01 -1.475898e-02 -2.777882e+00 -4.447848e-01 1.253255e-02 8.955497e-01 2.345599e+02 +8.716996e-01 7.796969e-03 4.899787e-01 -9.877588e+01 4.330226e-03 9.997118e-01 -2.361200e-02 -2.797730e+00 -4.900216e-01 2.270429e-02 8.714145e-01 2.348729e+02 +8.436311e-01 1.892265e-02 5.365898e-01 -9.856661e+01 -1.449129e-03 9.994554e-01 -3.296710e-02 -2.811248e+00 -5.369214e-01 2.703448e-02 8.431989e-01 2.352085e+02 +8.108383e-01 3.265384e-02 5.843586e-01 -9.834855e+01 -1.268840e-02 9.991884e-01 -3.822843e-02 -2.820092e+00 -5.851326e-01 2.358249e-02 8.105946e-01 2.355401e+02 +7.736779e-01 3.805772e-02 6.324351e-01 -9.808610e+01 -1.856547e-02 9.991274e-01 -3.741226e-02 -2.826192e+00 -6.333071e-01 1.720357e-02 7.737093e-01 2.358063e+02 +7.344721e-01 2.984541e-02 6.779823e-01 -9.780747e+01 -1.146224e-02 9.994355e-01 -3.157880e-02 -2.837866e+00 -6.785420e-01 1.542254e-02 7.343996e-01 2.360797e+02 +6.932109e-01 1.608133e-02 7.205554e-01 -9.749142e+01 2.527732e-03 9.996906e-01 -2.474288e-02 -2.846074e+00 -7.207303e-01 1.897340e-02 6.929558e-01 2.362814e+02 +6.493595e-01 1.094814e-02 7.604028e-01 -9.717427e+01 9.988631e-03 9.996873e-01 -2.292329e-02 -2.873917e+00 -7.604160e-01 2.248083e-02 6.490470e-01 2.364687e+02 +6.032829e-01 1.070930e-02 7.974554e-01 -9.687881e+01 1.427774e-02 9.996045e-01 -2.422528e-02 -2.878181e+00 -7.973994e-01 2.600055e-02 6.028914e-01 2.366544e+02 +5.559095e-01 1.195141e-02 8.311569e-01 -9.656356e+01 1.846361e-02 9.994724e-01 -2.672083e-02 -2.881999e+00 -8.310377e-01 3.020051e-02 5.553955e-01 2.367815e+02 +5.092309e-01 1.366507e-02 8.605215e-01 -9.625415e+01 2.157604e-02 9.993569e-01 -2.863784e-02 -2.886378e+00 -8.603594e-01 3.314991e-02 5.086085e-01 2.369311e+02 +4.655531e-01 1.536932e-02 8.848865e-01 -9.593153e+01 2.154589e-02 9.993560e-01 -2.869315e-02 -2.889154e+00 -8.847576e-01 3.242385e-02 4.649221e-01 2.370532e+02 +4.248062e-01 1.627647e-02 9.051380e-01 -9.561348e+01 1.885866e-02 9.994623e-01 -2.682353e-02 -2.892253e+00 -9.050878e-01 2.846448e-02 4.242708e-01 2.372126e+02 +3.842488e-01 1.725238e-02 9.230684e-01 -9.528315e+01 1.582146e-02 9.995555e-01 -2.526800e-02 -2.893774e+00 -9.230940e-01 2.431349e-02 3.838050e-01 2.373588e+02 +3.431131e-01 1.670352e-02 9.391456e-01 -9.493043e+01 1.613095e-02 9.995896e-01 -2.367195e-02 -2.895213e+00 -9.391555e-01 2.327146e-02 3.427028e-01 2.374685e+02 +3.038695e-01 1.257638e-02 9.526307e-01 -9.456472e+01 1.977829e-02 9.996141e-01 -1.950552e-02 -2.904768e+00 -9.525083e-01 2.476853e-02 3.035035e-01 2.375781e+02 +2.673359e-01 8.349815e-03 9.635672e-01 -9.418508e+01 2.410965e-02 9.995914e-01 -1.535106e-02 -2.914728e+00 -9.633017e-01 2.733515e-02 2.670254e-01 2.376748e+02 +2.330441e-01 7.533274e-03 9.724370e-01 -9.378494e+01 2.767581e-02 9.995136e-01 -1.437553e-02 -2.924129e+00 -9.720722e-01 3.026311e-02 2.327222e-01 2.377469e+02 +2.036372e-01 9.433099e-03 9.790010e-01 -9.337827e+01 3.073600e-02 9.993991e-01 -1.602289e-02 -2.929392e+00 -9.785638e-01 3.335343e-02 2.032248e-01 2.378266e+02 +1.803070e-01 1.292666e-02 9.835255e-01 -9.295531e+01 3.277506e-02 9.992794e-01 -1.914228e-02 -2.934146e+00 -9.830641e-01 3.568658e-02 1.797533e-01 2.378988e+02 +1.611995e-01 1.757504e-02 9.867654e-01 -9.251885e+01 3.218672e-02 9.992159e-01 -2.305487e-02 -2.940151e+00 -9.863968e-01 3.547716e-02 1.605074e-01 2.379685e+02 +1.449885e-01 2.184479e-02 9.891922e-01 -9.206580e+01 3.094499e-02 9.991670e-01 -2.660077e-02 -2.947320e+00 -9.889493e-01 3.446734e-02 1.441917e-01 2.380376e+02 +1.298539e-01 2.601172e-02 9.911919e-01 -9.159685e+01 2.954899e-02 9.991103e-01 -3.009067e-02 -2.957697e+00 -9.910927e-01 3.319610e-02 1.289698e-01 2.381027e+02 +1.145835e-01 2.898269e-02 9.929908e-01 -9.110748e+01 2.919914e-02 9.990442e-01 -3.252874e-02 -2.970966e+00 -9.929844e-01 3.272172e-02 1.136277e-01 2.381588e+02 +9.991095e-02 3.003109e-02 9.945431e-01 -9.060052e+01 3.199429e-02 9.989306e-01 -3.337770e-02 -2.985924e+00 -9.944818e-01 3.515449e-02 9.884328e-02 2.382071e+02 +8.849140e-02 2.928028e-02 9.956465e-01 -9.007469e+01 3.633721e-02 9.988076e-01 -3.260284e-02 -3.000677e+00 -9.954139e-01 3.906407e-02 8.732192e-02 2.382483e+02 +8.077320e-02 2.799201e-02 9.963394e-01 -8.953204e+01 3.987548e-02 9.987145e-01 -3.129145e-02 -3.015435e+00 -9.959345e-01 4.225701e-02 7.955317e-02 2.382882e+02 +7.730756e-02 2.540700e-02 9.966835e-01 -8.896618e+01 4.244549e-02 9.986850e-01 -2.875030e-02 -3.031384e+00 -9.961033e-01 4.452733e-02 7.612749e-02 2.383336e+02 +7.686650e-02 2.248064e-02 9.967880e-01 -8.838745e+01 4.319333e-02 9.987321e-01 -2.585531e-02 -3.040495e+00 -9.961053e-01 4.504199e-02 7.579802e-02 2.383917e+02 +7.641245e-02 1.901453e-02 9.968950e-01 -8.776457e+01 4.261013e-02 9.988425e-01 -2.231777e-02 -3.050019e+00 -9.961654e-01 4.418316e-02 7.551379e-02 2.384470e+02 +7.451060e-02 1.839796e-02 9.970505e-01 -8.713484e+01 4.230253e-02 9.988715e-01 -2.159288e-02 -3.068087e+00 -9.963225e-01 4.378665e-02 7.364823e-02 2.384880e+02 +7.304468e-02 1.818219e-02 9.971629e-01 -8.648629e+01 4.140328e-02 9.989166e-01 -2.124707e-02 -3.071277e+00 -9.964688e-01 4.283779e-02 7.221273e-02 2.385401e+02 +7.181538e-02 1.845204e-02 9.972473e-01 -8.581893e+01 4.085014e-02 9.989355e-01 -2.142505e-02 -3.089892e+00 -9.965810e-01 4.227633e-02 7.098516e-02 2.385774e+02 +6.951287e-02 2.037270e-02 9.973730e-01 -8.513954e+01 4.086682e-02 9.988940e-01 -2.325203e-02 -3.109530e+00 -9.967436e-01 4.237577e-02 6.860342e-02 2.386147e+02 +6.708308e-02 2.279986e-02 9.974869e-01 -8.444349e+01 4.074323e-02 9.988424e-01 -2.557092e-02 -3.131581e+00 -9.969151e-01 4.235620e-02 6.607648e-02 2.386508e+02 +6.447766e-02 2.478679e-02 9.976113e-01 -8.373651e+01 3.983907e-02 9.988306e-01 -2.739197e-02 -3.141617e+00 -9.971236e-01 4.151006e-02 6.341477e-02 2.386890e+02 +6.193632e-02 2.616636e-02 9.977371e-01 -8.299599e+01 3.952459e-02 9.988078e-01 -2.864801e-02 -3.164465e+00 -9.972972e-01 4.120949e-02 6.082827e-02 2.387136e+02 +5.985783e-02 2.588744e-02 9.978712e-01 -8.225386e+01 3.787593e-02 9.988848e-01 -2.818575e-02 -3.188940e+00 -9.974880e-01 3.948243e-02 5.881056e-02 2.387468e+02 +5.768897e-02 2.528313e-02 9.980144e-01 -8.150100e+01 3.686986e-02 9.989433e-01 -2.743788e-02 -3.193174e+00 -9.976535e-01 3.837950e-02 5.669582e-02 2.387936e+02 +5.556419e-02 2.359773e-02 9.981762e-01 -8.073125e+01 3.730068e-02 9.989737e-01 -2.569296e-02 -3.204779e+00 -9.977581e-01 3.866025e-02 5.462695e-02 2.388359e+02 +5.332103e-02 2.221788e-02 9.983303e-01 -7.994014e+01 3.798230e-02 9.989838e-01 -2.426107e-02 -3.188593e+00 -9.978548e-01 3.921250e-02 5.242296e-02 2.388723e+02 +5.033489e-02 2.129089e-02 9.985055e-01 -7.914001e+01 3.843736e-02 9.989907e-01 -2.323888e-02 -3.199573e+00 -9.979924e-01 3.954963e-02 4.946572e-02 2.389059e+02 +4.754663e-02 2.035523e-02 9.986616e-01 -7.833890e+01 3.883068e-02 9.989989e-01 -2.221085e-02 -3.201263e+00 -9.981139e-01 3.983475e-02 4.670862e-02 2.389574e+02 +4.541860e-02 2.108926e-02 9.987454e-01 -7.753959e+01 3.934008e-02 9.989638e-01 -2.288290e-02 -3.204957e+00 -9.981931e-01 4.033002e-02 4.454188e-02 2.390111e+02 +4.354915e-02 2.059931e-02 9.988389e-01 -7.672966e+01 4.213669e-02 9.988599e-01 -2.243690e-02 -3.214693e+00 -9.981623e-01 4.306486e-02 4.263151e-02 2.390557e+02 +4.228548e-02 2.055011e-02 9.988942e-01 -7.591108e+01 4.355843e-02 9.987999e-01 -2.239210e-02 -3.224093e+00 -9.981556e-01 4.445711e-02 4.133960e-02 2.391026e+02 +4.067563e-02 2.143888e-02 9.989424e-01 -7.508744e+01 4.330933e-02 9.987923e-01 -2.319917e-02 -3.239402e+00 -9.982333e-01 4.420715e-02 3.969800e-02 2.391507e+02 +3.921250e-02 2.325049e-02 9.989604e-01 -7.425346e+01 4.279786e-02 9.987727e-01 -2.492609e-02 -3.253523e+00 -9.983139e-01 4.373077e-02 3.816931e-02 2.392005e+02 +3.780913e-02 2.688977e-02 9.989232e-01 -7.341834e+01 4.231995e-02 9.986979e-01 -2.848552e-02 -3.272699e+00 -9.983884e-01 4.335138e-02 3.662193e-02 2.392470e+02 +3.618408e-02 2.876116e-02 9.989312e-01 -7.257493e+01 4.050586e-02 9.987221e-01 -3.022238e-02 -3.292981e+00 -9.985239e-01 4.155613e-02 3.497284e-02 2.393139e+02 +3.468729e-02 3.072415e-02 9.989259e-01 -7.172614e+01 3.818142e-02 9.987569e-01 -3.204480e-02 -3.314227e+00 -9.986686e-01 3.925194e-02 3.347108e-02 2.393683e+02 +3.332270e-02 3.014757e-02 9.989899e-01 -7.086221e+01 3.898065e-02 9.987452e-01 -3.144044e-02 -3.338660e+00 -9.986841e-01 3.998894e-02 3.210571e-02 2.394117e+02 +3.311988e-02 2.821177e-02 9.990532e-01 -6.999191e+01 4.009829e-02 9.987592e-01 -2.953279e-02 -3.366787e+00 -9.986466e-01 4.103844e-02 3.194754e-02 2.394464e+02 +3.408332e-02 2.480590e-02 9.991111e-01 -6.911572e+01 4.201732e-02 9.987725e-01 -2.623087e-02 -3.390705e+00 -9.985353e-01 4.287400e-02 3.299920e-02 2.394810e+02 +3.659189e-02 2.210989e-02 9.990857e-01 -6.823645e+01 4.515142e-02 9.986977e-01 -2.375499e-02 -3.412566e+00 -9.983097e-01 4.597937e-02 3.554594e-02 2.395130e+02 +3.987932e-02 2.059004e-02 9.989924e-01 -6.735162e+01 4.873321e-02 9.985578e-01 -2.252649e-02 -3.440482e+00 -9.980153e-01 4.958243e-02 3.881838e-02 2.395488e+02 +4.322326e-02 2.045162e-02 9.988561e-01 -6.645635e+01 5.064293e-02 9.984603e-01 -2.263498e-02 -3.487813e+00 -9.977810e-01 5.156334e-02 4.212098e-02 2.395791e+02 +4.660282e-02 2.112581e-02 9.986901e-01 -6.556589e+01 5.146178e-02 9.983979e-01 -2.352105e-02 -3.534768e+00 -9.975870e-01 5.249050e-02 4.544099e-02 2.396210e+02 +4.970645e-02 2.369500e-02 9.984828e-01 -6.466636e+01 5.098192e-02 9.983550e-01 -2.622996e-02 -3.602912e+00 -9.974618e-01 5.220835e-02 4.841667e-02 2.396577e+02 +5.247616e-02 2.580241e-02 9.982888e-01 -6.377679e+01 4.984492e-02 9.983524e-01 -2.842421e-02 -3.651501e+00 -9.973774e-01 5.125120e-02 5.110358e-02 2.397007e+02 +5.440976e-02 2.620447e-02 9.981748e-01 -6.288482e+01 4.973583e-02 9.983436e-01 -2.891997e-02 -3.696764e+00 -9.972792e-01 5.121857e-02 5.301633e-02 2.397540e+02 +5.575086e-02 2.684014e-02 9.980839e-01 -6.199803e+01 4.724734e-02 9.984478e-01 -2.948907e-02 -3.746013e+00 -9.973261e-01 4.880083e-02 5.439619e-02 2.398088e+02 +5.676508e-02 2.650235e-02 9.980358e-01 -6.110321e+01 4.556960e-02 9.985370e-01 -2.910752e-02 -3.809388e+00 -9.973470e-01 4.713237e-02 5.547433e-02 2.398603e+02 +5.821248e-02 2.335632e-02 9.980310e-01 -6.020898e+01 4.457672e-02 9.986683e-01 -2.597128e-02 -3.873130e+00 -9.973084e-01 4.600079e-02 5.709381e-02 2.399033e+02 +5.993401e-02 1.452023e-02 9.980968e-01 -5.931175e+01 4.058046e-02 9.990321e-01 -1.697063e-02 -3.939659e+00 -9.973771e-01 4.152033e-02 5.928676e-02 2.399526e+02 +6.154102e-02 8.979593e-03 9.980642e-01 -5.843050e+01 4.653743e-02 9.988462e-01 -1.185615e-02 -3.980641e+00 -9.970190e-01 4.717697e-02 6.105212e-02 2.400059e+02 +6.394604e-02 1.213018e-02 9.978797e-01 -5.756113e+01 4.725105e-02 9.987678e-01 -1.516892e-02 -4.020154e+00 -9.968341e-01 4.812084e-02 6.329408e-02 2.400565e+02 +6.452445e-02 2.318654e-02 9.976467e-01 -5.670195e+01 4.431491e-02 9.986772e-01 -2.607664e-02 -4.060627e+00 -9.969316e-01 4.589319e-02 6.341159e-02 2.401091e+02 +6.575963e-02 3.168409e-02 9.973324e-01 -5.585398e+01 4.459527e-02 9.984037e-01 -3.465855e-02 -4.101583e+00 -9.968384e-01 4.675543e-02 6.424170e-02 2.401600e+02 +6.674302e-02 3.215427e-02 9.972520e-01 -5.500292e+01 4.769386e-02 9.982353e-01 -3.537799e-02 -4.143154e+00 -9.966296e-01 4.992402e-02 6.509167e-02 2.402089e+02 +6.634772e-02 2.574414e-02 9.974644e-01 -5.415113e+01 5.022662e-02 9.983136e-01 -2.910696e-02 -4.172782e+00 -9.965316e-01 5.203044e-02 6.494279e-02 2.402676e+02 +6.558209e-02 1.700928e-02 9.977022e-01 -5.330353e+01 4.852038e-02 9.986176e-01 -2.021429e-02 -4.205374e+00 -9.966668e-01 4.973457e-02 6.466613e-02 2.403305e+02 +6.470055e-02 1.304684e-02 9.978195e-01 -5.246197e+01 4.727867e-02 9.987516e-01 -1.612468e-02 -4.242766e+00 -9.967841e-01 4.821884e-02 6.400293e-02 2.403855e+02 +6.471257e-02 1.720553e-02 9.977556e-01 -5.162594e+01 5.053810e-02 9.985118e-01 -2.049639e-02 -4.290144e+00 -9.966233e-01 5.175103e-02 6.374673e-02 2.404271e+02 +6.531460e-02 2.167297e-02 9.976294e-01 -5.079621e+01 5.343501e-02 9.982537e-01 -2.518492e-02 -4.332237e+00 -9.964329e-01 5.495326e-02 6.404244e-02 2.404708e+02 +6.599738e-02 2.168398e-02 9.975842e-01 -4.996026e+01 5.559544e-02 9.981309e-01 -2.537391e-02 -4.376671e+00 -9.962697e-01 5.713573e-02 6.466849e-02 2.405163e+02 +6.718694e-02 1.832064e-02 9.975722e-01 -4.912739e+01 5.502092e-02 9.982419e-01 -2.203863e-02 -4.421564e+00 -9.962221e-01 5.636804e-02 6.606080e-02 2.405643e+02 +6.808073e-02 1.583371e-02 9.975542e-01 -4.829973e+01 5.370469e-02 9.983662e-01 -1.951182e-02 -4.464891e+00 -9.962333e-01 5.490170e-02 6.711915e-02 2.406143e+02 +6.921989e-02 1.685799e-02 9.974590e-01 -4.747830e+01 5.360339e-02 9.983499e-01 -2.059293e-02 -4.504143e+00 -9.961602e-01 5.489261e-02 6.820202e-02 2.406616e+02 +7.046255e-02 1.990850e-02 9.973158e-01 -4.666587e+01 5.337431e-02 9.982933e-01 -2.369903e-02 -4.538667e+00 -9.960854e-01 5.490092e-02 6.927968e-02 2.407127e+02 +7.145922e-02 2.186448e-02 9.972039e-01 -4.585726e+01 5.435565e-02 9.981887e-01 -2.578118e-02 -4.571703e+00 -9.959613e-01 5.604595e-02 7.014132e-02 2.407706e+02 +7.267546e-02 2.174184e-02 9.971187e-01 -4.504822e+01 5.484924e-02 9.981622e-01 -2.576231e-02 -4.610806e+00 -9.958462e-01 5.656348e-02 7.134938e-02 2.408271e+02 +7.360728e-02 2.015605e-02 9.970836e-01 -4.424057e+01 5.550483e-02 9.981633e-01 -2.427539e-02 -4.651036e+00 -9.957415e-01 5.712979e-02 7.235332e-02 2.408863e+02 +7.487035e-02 1.792003e-02 9.970323e-01 -4.344076e+01 5.546826e-02 9.982157e-01 -2.210660e-02 -4.687337e+00 -9.956493e-01 5.695876e-02 7.374276e-02 2.409476e+02 +7.615531e-02 1.668653e-02 9.969564e-01 -4.265454e+01 5.534835e-02 9.982476e-01 -2.093609e-02 -4.714944e+00 -9.955586e-01 5.677427e-02 7.509828e-02 2.410187e+02 +7.735897e-02 1.602126e-02 9.968746e-01 -4.187896e+01 5.559801e-02 9.982456e-01 -2.035779e-02 -4.728352e+00 -9.954518e-01 5.699909e-02 7.633250e-02 2.410889e+02 +7.874542e-02 1.604372e-02 9.967657e-01 -4.111857e+01 5.539489e-02 9.982552e-01 -2.044395e-02 -4.737337e+00 -9.953544e-01 5.682558e-02 7.771928e-02 2.411620e+02 +7.972552e-02 1.609303e-02 9.966870e-01 -4.037476e+01 5.313762e-02 9.983794e-01 -2.037087e-02 -4.751432e+00 -9.953995e-01 5.458564e-02 7.874116e-02 2.412360e+02 +8.062340e-02 1.598065e-02 9.966165e-01 -3.964902e+01 5.011546e-02 9.985418e-01 -2.006573e-02 -4.769963e+00 -9.954839e-01 5.156365e-02 7.970495e-02 2.413128e+02 +8.172832e-02 1.691030e-02 9.965112e-01 -3.893985e+01 4.724897e-02 9.986661e-01 -2.082197e-02 -4.793176e+00 -9.955340e-01 4.878586e-02 8.082030e-02 2.413846e+02 +8.261518e-02 1.805425e-02 9.964180e-01 -3.824412e+01 4.376309e-02 9.988057e-01 -2.172601e-02 -4.801646e+00 -9.956201e-01 4.540122e-02 8.172640e-02 2.414615e+02 +8.263138e-02 1.968892e-02 9.963857e-01 -3.755243e+01 4.030950e-02 9.989206e-01 -2.308193e-02 -4.809079e+00 -9.957646e-01 4.207109e-02 8.174853e-02 2.415394e+02 +8.219274e-02 2.106272e-02 9.963939e-01 -3.686290e+01 3.773431e-02 9.989940e-01 -2.423040e-02 -4.824751e+00 -9.959018e-01 3.958978e-02 8.131526e-02 2.416097e+02 +8.150379e-02 2.114477e-02 9.964487e-01 -3.617526e+01 3.639746e-02 9.990449e-01 -2.417697e-02 -4.839722e+00 -9.960082e-01 3.823871e-02 8.065632e-02 2.416749e+02 +8.077332e-02 2.167639e-02 9.964968e-01 -3.548874e+01 3.259883e-02 9.991712e-01 -2.437695e-02 -4.855125e+00 -9.961992e-01 3.445362e-02 7.999975e-02 2.417431e+02 +7.964735e-02 2.006328e-02 9.966212e-01 -3.480489e+01 3.159797e-02 9.992442e-01 -2.264131e-02 -4.857816e+00 -9.963221e-01 3.329452e-02 7.895318e-02 2.418164e+02 +7.867938e-02 1.797641e-02 9.967379e-01 -3.412746e+01 3.246389e-02 9.992609e-01 -2.058452e-02 -4.863699e+00 -9.963712e-01 3.397756e-02 7.803764e-02 2.418815e+02 +7.735895e-02 1.576701e-02 9.968787e-01 -3.345670e+01 3.466775e-02 9.992277e-01 -1.849443e-02 -4.876482e+00 -9.964003e-01 3.599024e-02 7.675259e-02 2.419390e+02 +7.517046e-02 1.558807e-02 9.970489e-01 -3.279782e+01 3.592306e-02 9.991864e-01 -1.832984e-02 -4.885648e+00 -9.965234e-01 3.719490e-02 7.454933e-02 2.419976e+02 +7.304583e-02 1.694724e-02 9.971846e-01 -3.215573e+01 3.585347e-02 9.991647e-01 -1.960724e-02 -4.889678e+00 -9.966839e-01 3.718475e-02 7.237719e-02 2.420644e+02 +7.102186e-02 1.934385e-02 9.972872e-01 -3.153309e+01 3.574376e-02 9.991204e-01 -2.192491e-02 -4.898054e+00 -9.968341e-01 3.720393e-02 7.026797e-02 2.421248e+02 +6.835045e-02 2.180431e-02 9.974231e-01 -3.092804e+01 3.543928e-02 9.990771e-01 -2.426903e-02 -4.908945e+00 -9.970317e-01 3.700674e-02 6.751464e-02 2.421843e+02 +6.519191e-02 2.211371e-02 9.976277e-01 -3.033630e+01 3.572530e-02 9.990618e-01 -2.448004e-02 -4.922557e+00 -9.972330e-01 3.723644e-02 6.434072e-02 2.422396e+02 +6.126871e-02 2.144594e-02 9.978909e-01 -2.976456e+01 3.421169e-02 9.991365e-01 -2.357325e-02 -4.942867e+00 -9.975348e-01 3.558383e-02 6.048211e-02 2.422879e+02 +5.641752e-02 2.059850e-02 9.981948e-01 -2.921431e+01 3.380813e-02 9.991744e-01 -2.252954e-02 -4.965689e+00 -9.978347e-01 3.501815e-02 5.567454e-02 2.423367e+02 +5.116057e-02 1.835047e-02 9.985219e-01 -2.868168e+01 3.268423e-02 9.992648e-01 -2.003875e-02 -4.986696e+00 -9.981554e-01 3.366110e-02 5.052318e-02 2.423730e+02 +4.490137e-02 1.672152e-02 9.988515e-01 -2.817242e+01 3.138189e-02 9.993428e-01 -1.814046e-02 -5.007234e+00 -9.984984e-01 3.216037e-02 4.434711e-02 2.424081e+02 +3.756281e-02 1.708595e-02 9.991482e-01 -2.768212e+01 3.085268e-02 9.993573e-01 -1.824943e-02 -5.025891e+00 -9.988178e-01 3.151189e-02 3.701152e-02 2.424320e+02 +2.986987e-02 1.770445e-02 9.993970e-01 -2.720634e+01 3.067144e-02 9.993560e-01 -1.862043e-02 -5.041519e+00 -9.990831e-01 3.120912e-02 2.930762e-02 2.424537e+02 +2.163067e-02 1.734513e-02 9.996156e-01 -2.674717e+01 3.233434e-02 9.993143e-01 -1.803960e-02 -5.053168e+00 -9.992430e-01 3.271211e-02 2.105499e-02 2.424689e+02 +1.284501e-02 1.667668e-02 9.997785e-01 -2.630096e+01 3.358374e-02 9.992896e-01 -1.710001e-02 -5.053968e+00 -9.993533e-01 3.379593e-02 1.227582e-02 2.424792e+02 +3.463876e-03 1.665669e-02 9.998553e-01 -2.587211e+01 3.470988e-02 9.992567e-01 -1.676697e-02 -5.060170e+00 -9.993914e-01 3.476293e-02 2.883151e-03 2.424793e+02 +-5.956811e-03 1.722856e-02 9.998339e-01 -2.546026e+01 3.510783e-02 9.992388e-01 -1.700915e-02 -5.070177e+00 -9.993657e-01 3.500067e-02 -6.557132e-03 2.424733e+02 +-1.542424e-02 1.682896e-02 9.997394e-01 -2.506402e+01 3.592944e-02 9.992219e-01 -1.626592e-02 -5.079540e+00 -9.992352e-01 3.566918e-02 -1.601690e-02 2.424658e+02 +-2.543958e-02 1.546335e-02 9.995568e-01 -2.468451e+01 3.606020e-02 9.992438e-01 -1.454075e-02 -5.088412e+00 -9.990257e-01 3.567429e-02 -2.597796e-02 2.424560e+02 +-3.580316e-02 1.392939e-02 9.992618e-01 -2.431871e+01 3.556374e-02 9.992873e-01 -1.265551e-02 -5.104554e+00 -9.987258e-01 3.508437e-02 -3.627302e-02 2.424374e+02 +-4.662970e-02 1.230011e-02 9.988365e-01 -2.396790e+01 3.614151e-02 9.992902e-01 -1.061848e-02 -5.119929e+00 -9.982582e-01 3.560431e-02 -4.704115e-02 2.424093e+02 +-5.790550e-02 1.332491e-02 9.982332e-01 -2.363681e+01 4.062757e-02 9.991140e-01 -1.097995e-02 -5.143724e+00 -9.974950e-01 3.991998e-02 -5.839555e-02 2.423685e+02 +-6.958454e-02 1.556840e-02 9.974546e-01 -2.332420e+01 4.693663e-02 9.988219e-01 -1.231535e-02 -5.163532e+00 -9.964712e-01 4.596019e-02 -7.023329e-02 2.423223e+02 +-8.148075e-02 1.551686e-02 9.965541e-01 -2.302391e+01 5.325803e-02 9.985180e-01 -1.119294e-02 -5.190213e+00 -9.952509e-01 5.216249e-02 -8.218639e-02 2.422745e+02 +-9.336097e-02 1.321402e-02 9.955447e-01 -2.274508e+01 5.511753e-02 9.984471e-01 -8.083696e-03 -5.206460e+00 -9.941055e-01 5.411725e-02 -9.394430e-02 2.422312e+02 +-1.057725e-01 1.102888e-02 9.943292e-01 -2.248378e+01 5.521546e-02 9.984609e-01 -5.201133e-03 -5.221438e+00 -9.928562e-01 5.435219e-02 -1.062186e-01 2.421869e+02 +-1.187021e-01 9.999348e-03 9.928796e-01 -2.224922e+01 5.228095e-02 9.986251e-01 -3.806854e-03 -5.234780e+00 -9.915525e-01 5.145679e-02 -1.190617e-01 2.421494e+02 +-1.320468e-01 9.060890e-03 9.912021e-01 -2.203471e+01 5.041384e-02 9.987255e-01 -2.413597e-03 -5.248313e+00 -9.899606e-01 4.965158e-02 -1.323353e-01 2.421124e+02 +-1.453125e-01 8.694113e-03 9.893476e-01 -2.184323e+01 5.015977e-02 9.987402e-01 -1.409339e-03 -5.259766e+00 -9.881135e-01 4.942064e-02 -1.455655e-01 2.420695e+02 +-1.583770e-01 1.079704e-02 9.873197e-01 -2.167523e+01 5.157588e-02 9.986655e-01 -2.647779e-03 -5.265402e+00 -9.860307e-01 5.050252e-02 -1.587225e-01 2.420269e+02 +-1.721290e-01 1.485890e-02 9.849624e-01 -2.151618e+01 5.257529e-02 9.985996e-01 -5.876736e-03 -5.267841e+00 -9.836704e-01 5.077311e-02 -1.726691e-01 2.419847e+02 +-1.850382e-01 1.843142e-02 9.825585e-01 -2.135727e+01 5.483779e-02 9.984599e-01 -8.402510e-03 -5.274070e+00 -9.812001e-01 5.232653e-02 -1.857639e-01 2.419371e+02 +-1.980443e-01 1.883505e-02 9.800121e-01 -2.119397e+01 5.901298e-02 9.982308e-01 -7.259660e-03 -5.291182e+00 -9.784150e-01 5.639568e-02 -1.988054e-01 2.418882e+02 +-2.125056e-01 1.764831e-02 9.770005e-01 -2.103260e+01 6.212656e-02 9.980580e-01 -4.515656e-03 -5.299016e+00 -9.751828e-01 5.973806e-02 -2.131894e-01 2.418351e+02 +-2.271283e-01 1.768008e-02 9.737044e-01 -2.087495e+01 6.378608e-02 9.979583e-01 -3.241609e-03 -5.301724e+00 -9.717736e-01 6.137251e-02 -2.277923e-01 2.417910e+02 +-2.410412e-01 1.878098e-02 9.703332e-01 -2.071927e+01 6.363221e-02 9.979672e-01 -3.508926e-03 -5.302050e+00 -9.684266e-01 6.089864e-02 -2.417463e-01 2.417434e+02 +-2.559619e-01 2.010973e-02 9.664777e-01 -2.056416e+01 6.301497e-02 9.980042e-01 -4.076838e-03 -5.302307e+00 -9.646308e-01 5.985903e-02 -2.567183e-01 2.416928e+02 +-2.714485e-01 2.135033e-02 9.622162e-01 -2.041009e+01 6.195239e-02 9.980682e-01 -4.668608e-03 -5.302005e+00 -9.604569e-01 5.834429e-02 -2.722468e-01 2.416410e+02 +-2.868997e-01 2.263699e-02 9.576931e-01 -2.025737e+01 6.072074e-02 9.981401e-01 -5.402698e-03 -5.299092e+00 -9.560342e-01 5.660179e-02 -2.877407e-01 2.415861e+02 +-3.038683e-01 2.583471e-02 9.523637e-01 -2.010375e+01 5.896141e-02 9.982260e-01 -8.266157e-03 -5.291935e+00 -9.508878e-01 5.364087e-02 -3.048525e-01 2.415245e+02 +-3.231923e-01 3.055241e-02 9.458400e-01 -1.993858e+01 5.830801e-02 9.982226e-01 -1.232071e-02 -5.286906e+00 -9.445352e-01 5.116808e-02 -3.243993e-01 2.414532e+02 +-3.445536e-01 3.408879e-02 9.381475e-01 -1.975489e+01 5.834479e-02 9.981861e-01 -1.484208e-02 -5.289635e+00 -9.369518e-01 4.962212e-02 -3.459175e-01 2.413621e+02 +-3.693305e-01 3.560528e-02 9.286158e-01 -1.955122e+01 5.830265e-02 9.981850e-01 -1.508452e-02 -5.298940e+00 -9.274674e-01 4.856958e-02 -3.707360e-01 2.412652e+02 +-3.974700e-01 3.632026e-02 9.168961e-01 -1.933089e+01 5.907909e-02 9.981561e-01 -1.392866e-02 -5.318294e+00 -9.157113e-01 4.863315e-02 -3.988829e-01 2.411505e+02 +-4.295416e-01 3.713322e-02 9.022833e-01 -1.909778e+01 6.018823e-02 9.981097e-01 -1.242369e-02 -5.342702e+00 -9.010390e-01 4.897033e-02 -4.309646e-01 2.410007e+02 +-4.641450e-01 3.779531e-02 8.849525e-01 -1.885305e+01 6.070113e-02 9.980976e-01 -1.079074e-02 -5.382576e+00 -8.836768e-01 4.870914e-02 -4.655562e-01 2.408454e+02 +-4.990937e-01 3.806856e-02 8.657114e-01 -1.860355e+01 6.120557e-02 9.980881e-01 -8.603883e-03 -5.404650e+00 -8.643838e-01 4.869220e-02 -5.004695e-01 2.406741e+02 +-5.354343e-01 3.880701e-02 8.436849e-01 -1.834637e+01 6.143977e-02 9.980868e-01 -6.917066e-03 -5.427006e+00 -8.423392e-01 4.813216e-02 -5.367941e-01 2.404655e+02 +-5.739593e-01 3.868090e-02 8.179698e-01 -1.808613e+01 5.884817e-02 9.982494e-01 -5.913111e-03 -5.451539e+00 -8.167665e-01 4.474213e-02 -5.752308e-01 2.402581e+02 +-6.133838e-01 3.698406e-02 7.889186e-01 -1.781755e+01 5.460115e-02 9.984987e-01 -4.356707e-03 -5.481176e+00 -7.878953e-01 4.040352e-02 -6.144823e-01 2.400003e+02 +-6.526185e-01 3.467073e-02 7.568930e-01 -1.755440e+01 5.052589e-02 9.987203e-01 -2.182926e-03 -5.502023e+00 -7.560001e-01 3.681806e-02 -6.535351e-01 2.397443e+02 +-6.911038e-01 3.462877e-02 7.219255e-01 -1.729903e+01 4.978988e-02 9.987597e-01 -2.435898e-04 -5.512958e+00 -7.210385e-01 3.577623e-02 -6.919707e-01 2.394659e+02 +-7.294523e-01 3.662226e-02 6.830507e-01 -1.704794e+01 5.097496e-02 9.986995e-01 8.918126e-04 -5.517479e+00 -6.821297e-01 3.546900e-02 -7.303704e-01 2.391300e+02 +-7.669016e-01 3.878138e-02 6.405919e-01 -1.681073e+01 5.262823e-02 9.986109e-01 2.549445e-03 -5.516022e+00 -6.396032e-01 3.566838e-02 -7.678772e-01 2.388014e+02 +-8.029273e-01 4.284191e-02 5.945354e-01 -1.658565e+01 5.498521e-02 9.984845e-01 2.307899e-03 -5.514193e+00 -5.935355e-01 3.454372e-02 -8.040661e-01 2.384559e+02 +-8.371323e-01 4.474184e-02 5.451676e-01 -1.637144e+01 5.471324e-02 9.984999e-01 2.068134e-03 -5.510814e+00 -5.442573e-01 3.155918e-02 -8.383245e-01 2.380411e+02 +-8.688056e-01 4.463225e-02 4.931379e-01 -1.616855e+01 5.325569e-02 9.985749e-01 3.447679e-03 -5.520163e+00 -4.922812e-01 2.925775e-02 -8.699443e-01 2.376457e+02 +-8.966380e-01 4.295866e-02 4.406756e-01 -1.598030e+01 5.125953e-02 9.986612e-01 6.944043e-03 -5.524629e+00 -4.397873e-01 2.881511e-02 -8.976395e-01 2.371817e+02 +-9.202281e-01 4.560300e-02 3.887168e-01 -1.581914e+01 5.351473e-02 9.985214e-01 9.544660e-03 -5.521756e+00 -3.877067e-01 2.958533e-02 -9.213078e-01 2.367315e+02 +-9.392864e-01 5.267972e-02 3.390664e-01 -1.568153e+01 6.026755e-02 9.981115e-01 1.188040e-02 -5.512250e+00 -3.378002e-01 3.159379e-02 -9.406874e-01 2.362441e+02 +-9.548918e-01 5.616821e-02 2.915936e-01 -1.555169e+01 6.337940e-02 9.978716e-01 1.533568e-02 -5.508345e+00 -2.901116e-01 3.312493e-02 -9.564193e-01 2.357056e+02 +-9.676208e-01 5.507723e-02 2.463260e-01 -1.543172e+01 6.211042e-02 9.978511e-01 2.086847e-02 -5.507429e+00 -2.446472e-01 3.549217e-02 -9.689623e-01 2.351643e+02 +-9.772346e-01 5.274359e-02 2.055011e-01 -1.532649e+01 5.936071e-02 9.978936e-01 2.616449e-02 -5.502579e+00 -2.036883e-01 3.776753e-02 -9.783070e-01 2.345950e+02 +-9.839256e-01 5.253744e-02 1.706758e-01 -1.523713e+01 5.857235e-02 9.978167e-01 3.051452e-02 -5.494907e+00 -1.687000e-01 4.002089e-02 -9.848546e-01 2.339880e+02 +-9.883645e-01 5.421274e-02 1.421151e-01 -1.516093e+01 5.954473e-02 9.976621e-01 3.353537e-02 -5.481781e+00 -1.399648e-01 4.160737e-02 -9.892818e-01 2.333669e+02 +-9.913580e-01 5.598539e-02 1.186384e-01 -1.509436e+01 6.044190e-02 9.975821e-01 3.430192e-02 -5.468998e+00 -1.164311e-01 4.117620e-02 -9.923448e-01 2.327201e+02 +-9.934117e-01 5.733969e-02 9.922383e-02 -1.503583e+01 6.102452e-02 9.975396e-01 3.450632e-02 -5.450609e+00 -9.700112e-02 4.033406e-02 -9.944666e-01 2.320487e+02 +-9.950471e-01 5.682338e-02 8.156199e-02 -1.498543e+01 5.992686e-02 9.975491e-01 3.611878e-02 -5.428723e+00 -7.930970e-02 4.082764e-02 -9.960135e-01 2.313598e+02 +-9.963821e-01 5.489789e-02 6.487673e-02 -1.494039e+01 5.738157e-02 9.976642e-01 3.705930e-02 -5.407624e+00 -6.269072e-02 4.064794e-02 -9.972048e-01 2.306501e+02 +-9.972026e-01 5.496372e-02 5.065623e-02 -1.490294e+01 5.696563e-02 9.976156e-01 3.896042e-02 -5.388280e+00 -4.839404e-02 4.173709e-02 -9.979559e-01 2.299214e+02 +-9.975121e-01 5.812147e-02 3.989373e-02 -1.487945e+01 5.977783e-02 9.973418e-01 4.166365e-02 -5.367708e+00 -3.736613e-02 4.394475e-02 -9.983349e-01 2.291661e+02 +-9.976001e-01 6.140476e-02 3.199403e-02 -1.486457e+01 6.274870e-02 9.971092e-01 4.284647e-02 -5.343652e+00 -2.927056e-02 4.475122e-02 -9.985692e-01 2.283904e+02 +-9.976451e-01 6.360688e-02 2.566043e-02 -1.485183e+01 6.469025e-02 9.969408e-01 4.386502e-02 -5.322829e+00 -2.279181e-02 4.542170e-02 -9.987078e-01 2.275959e+02 +-9.977316e-01 6.375142e-02 2.162314e-02 -1.483457e+01 6.466194e-02 9.969185e-01 4.440950e-02 -5.296103e+00 -1.872534e-02 4.570695e-02 -9.987793e-01 2.267838e+02 +-9.977120e-01 6.478573e-02 1.933163e-02 -1.482178e+01 6.560289e-02 9.968238e-01 4.514945e-02 -5.263447e+00 -1.634519e-02 4.631435e-02 -9.987931e-01 2.259532e+02 +-9.976308e-01 6.649962e-02 1.762439e-02 -1.481286e+01 6.724168e-02 9.966976e-01 4.552460e-02 -5.232088e+00 -1.453881e-02 4.660183e-02 -9.988077e-01 2.251006e+02 +-9.975689e-01 6.761777e-02 1.686084e-02 -1.480591e+01 6.832551e-02 9.966161e-01 4.569292e-02 -5.202901e+00 -1.371413e-02 4.673386e-02 -9.988132e-01 2.242273e+02 +-9.975169e-01 6.836840e-02 1.690900e-02 -1.479638e+01 6.908045e-02 9.965548e-01 4.589512e-02 -5.167708e+00 -1.371297e-02 4.694923e-02 -9.988031e-01 2.233371e+02 +-9.974062e-01 6.976417e-02 1.771528e-02 -1.479054e+01 7.050150e-02 9.964908e-01 4.511724e-02 -5.127437e+00 -1.450554e-02 4.624916e-02 -9.988246e-01 2.224301e+02 +-9.973462e-01 7.029188e-02 1.896398e-02 -1.477615e+01 7.107343e-02 9.964875e-01 4.428471e-02 -5.093850e+00 -1.578452e-02 4.551502e-02 -9.988389e-01 2.215037e+02 +-9.971564e-01 7.276255e-02 1.961861e-02 -1.476205e+01 7.355100e-02 9.963634e-01 4.301457e-02 -5.057931e+00 -1.641742e-02 4.433521e-02 -9.988817e-01 2.205627e+02 +-9.970850e-01 7.347211e-02 2.057883e-02 -1.474402e+01 7.426374e-02 9.964042e-01 4.078531e-02 -5.024081e+00 -1.750825e-02 4.219467e-02 -9.989559e-01 2.196008e+02 +-9.969265e-01 7.519607e-02 2.198199e-02 -1.472619e+01 7.601142e-02 9.963453e-01 3.896476e-02 -4.990431e+00 -1.897165e-02 4.051588e-02 -9.989987e-01 2.186252e+02 +-9.966278e-01 7.839320e-02 2.424171e-02 -1.470817e+01 7.928360e-02 9.961178e-01 3.825448e-02 -4.958863e+00 -2.114871e-02 4.004745e-02 -9.989739e-01 2.176308e+02 +-9.964774e-01 7.913667e-02 2.775339e-02 -1.468116e+01 8.017596e-02 9.960338e-01 3.857951e-02 -4.929982e+00 -2.459026e-02 4.066876e-02 -9.988700e-01 2.166246e+02 +-9.964381e-01 7.817124e-02 3.163049e-02 -1.464681e+01 7.933262e-02 9.961502e-01 3.729720e-02 -4.902737e+00 -2.859315e-02 3.967368e-02 -9.988034e-01 2.156024e+02 +-9.964322e-01 7.648872e-02 3.567037e-02 -1.460524e+01 7.777771e-02 9.963108e-01 3.626690e-02 -4.874120e+00 -3.276477e-02 3.891186e-02 -9.987053e-01 2.145685e+02 +-9.964564e-01 7.423901e-02 3.953891e-02 -1.455998e+01 7.570552e-02 9.964442e-01 3.698104e-02 -4.842500e+00 -3.665288e-02 3.984330e-02 -9.985334e-01 2.135193e+02 +-9.964861e-01 7.196444e-02 4.285538e-02 -1.450969e+01 7.361086e-02 9.965565e-01 3.816448e-02 -4.811522e+00 -3.996132e-02 4.118499e-02 -9.983520e-01 2.124596e+02 +-9.964379e-01 7.092381e-02 4.562324e-02 -1.445902e+01 7.265404e-02 9.966537e-01 3.745324e-02 -4.783106e+00 -4.281424e-02 4.063453e-02 -9.982563e-01 2.113863e+02 +-9.963237e-01 7.087906e-02 4.811786e-02 -1.440526e+01 7.270085e-02 9.966587e-01 3.722791e-02 -4.757659e+00 -4.531840e-02 4.058925e-02 -9.981476e-01 2.102990e+02 +-9.961282e-01 7.194233e-02 5.052670e-02 -1.435348e+01 7.392284e-02 9.965211e-01 3.848570e-02 -4.732652e+00 -4.758217e-02 4.207176e-02 -9.979809e-01 2.092013e+02 +-9.959165e-01 7.324016e-02 5.278576e-02 -1.430092e+01 7.539234e-02 9.963512e-01 4.000204e-02 -4.705401e+00 -4.966340e-02 4.381833e-02 -9.978043e-01 2.080965e+02 +-9.957023e-01 7.442569e-02 5.511606e-02 -1.424429e+01 7.667328e-02 9.962595e-01 3.985110e-02 -4.677533e+00 -5.194395e-02 4.390575e-02 -9.976843e-01 2.069852e+02 +-9.955777e-01 7.440811e-02 5.734580e-02 -1.417974e+01 7.671066e-02 9.962883e-01 3.905213e-02 -4.652377e+00 -5.422715e-02 4.327846e-02 -9.975902e-01 2.058696e+02 +-9.955268e-01 7.346709e-02 5.940558e-02 -1.410941e+01 7.585453e-02 9.963566e-01 3.898243e-02 -4.627366e+00 -5.632521e-02 4.331423e-02 -9.974724e-01 2.047443e+02 +-9.955752e-01 7.173969e-02 6.069279e-02 -1.403640e+01 7.418114e-02 9.964828e-01 3.897503e-02 -4.606409e+00 -5.768326e-02 4.330482e-02 -9.973952e-01 2.036142e+02 +-9.955987e-01 7.076558e-02 6.144599e-02 -1.396238e+01 7.325940e-02 9.965373e-01 3.932570e-02 -4.581422e+00 -5.845031e-02 4.365410e-02 -9.973353e-01 2.024788e+02 +-9.955844e-01 7.038020e-02 6.211542e-02 -1.388728e+01 7.292393e-02 9.965479e-01 3.967897e-02 -4.560121e+00 -5.910837e-02 4.403346e-02 -9.972799e-01 2.013360e+02 +-9.955256e-01 7.063052e-02 6.277018e-02 -1.381270e+01 7.320690e-02 9.965248e-01 3.973643e-02 -4.535794e+00 -5.974543e-02 4.415384e-02 -9.972366e-01 2.001913e+02 +-9.954390e-01 7.129491e-02 6.338987e-02 -1.373912e+01 7.389359e-02 9.964780e-01 3.963932e-02 -4.511093e+00 -6.034052e-02 4.414262e-02 -9.972013e-01 1.990451e+02 +-9.953862e-01 7.186251e-02 6.357821e-02 -1.366580e+01 7.449041e-02 9.964202e-01 3.997353e-02 -4.484373e+00 -6.047801e-02 4.452506e-02 -9.971759e-01 1.978919e+02 +-9.954351e-01 7.121114e-02 6.354601e-02 -1.359150e+01 7.389669e-02 9.964244e-01 4.095963e-02 -4.461457e+00 -6.040201e-02 4.546849e-02 -9.971380e-01 1.967326e+02 +-9.955612e-01 6.994617e-02 6.297265e-02 -1.351493e+01 7.265320e-02 9.964820e-01 4.177335e-02 -4.432709e+00 -5.982922e-02 4.616309e-02 -9.971406e-01 1.955722e+02 +-9.957100e-01 6.833713e-02 6.238295e-02 -1.343473e+01 7.104753e-02 9.965750e-01 4.231351e-02 -4.406072e+00 -5.927770e-02 4.656414e-02 -9.971549e-01 1.944028e+02 +-9.959128e-01 6.632279e-02 6.131195e-02 -1.335421e+01 6.899516e-02 9.967093e-01 4.254637e-02 -4.381680e+00 -5.828840e-02 4.660269e-02 -9.972114e-01 1.932295e+02 +-9.960885e-01 6.494764e-02 5.991293e-02 -1.327544e+01 6.750041e-02 9.968510e-01 4.161449e-02 -4.356643e+00 -5.702150e-02 4.549586e-02 -9.973357e-01 1.920549e+02 +-9.962335e-01 6.417577e-02 5.831182e-02 -1.319833e+01 6.660458e-02 9.969487e-01 4.070791e-02 -4.332718e+00 -5.552143e-02 4.443841e-02 -9.974680e-01 1.908763e+02 +-9.963532e-01 6.379072e-02 5.666649e-02 -1.312607e+01 6.616707e-02 9.969618e-01 4.109736e-02 -4.306670e+00 -5.387270e-02 4.469693e-02 -9.975469e-01 1.896900e+02 +-9.964024e-01 6.434789e-02 5.515069e-02 -1.305200e+01 6.680852e-02 9.967953e-01 4.399722e-02 -4.285346e+00 -5.214282e-02 4.752346e-02 -9.975082e-01 1.884996e+02 +-9.964679e-01 6.439028e-02 5.390480e-02 -1.298336e+01 6.699077e-02 9.966026e-01 4.791070e-02 -4.253796e+00 -5.063667e-02 5.135259e-02 -9.973960e-01 1.872995e+02 +-9.965055e-01 6.501694e-02 5.243767e-02 -1.291699e+01 6.763714e-02 9.964641e-01 4.984429e-02 -4.220079e+00 -4.901153e-02 5.321683e-02 -9.973794e-01 1.860940e+02 +-9.965331e-01 6.594263e-02 5.072826e-02 -1.285457e+01 6.849215e-02 9.963839e-01 5.027770e-02 -4.178980e+00 -4.722938e-02 5.357787e-02 -9.974461e-01 1.848847e+02 +-9.966056e-01 6.602274e-02 4.917591e-02 -1.279407e+01 6.843616e-02 9.964452e-01 4.912557e-02 -4.140603e+00 -4.575770e-02 5.232422e-02 -9.975812e-01 1.836729e+02 +-9.966002e-01 6.738282e-02 4.741049e-02 -1.273190e+01 6.962713e-02 9.964466e-01 4.739500e-02 -4.103990e+00 -4.404841e-02 5.053491e-02 -9.977504e-01 1.824501e+02 +-9.965373e-01 6.923428e-02 4.604472e-02 -1.267514e+01 7.136241e-02 9.963752e-01 4.630206e-02 -4.065229e+00 -4.267213e-02 4.942758e-02 -9.978657e-01 1.812202e+02 +-9.964261e-01 7.174208e-02 4.458941e-02 -1.262118e+01 7.376311e-02 9.962389e-01 4.546410e-02 -4.027475e+00 -4.116002e-02 4.859066e-02 -9.979703e-01 1.799874e+02 +-9.962973e-01 7.431542e-02 4.323151e-02 -1.256693e+01 7.621845e-02 9.961121e-01 4.417433e-02 -3.991746e+00 -3.978060e-02 4.730580e-02 -9.980879e-01 1.787452e+02 +-9.962323e-01 7.572461e-02 4.227339e-02 -1.250803e+01 7.751599e-02 9.960857e-01 4.247850e-02 -3.960138e+00 -3.889125e-02 4.559531e-02 -9.982026e-01 1.775020e+02 +-9.962535e-01 7.594410e-02 4.137134e-02 -1.245081e+01 7.763843e-02 9.961376e-01 4.101309e-02 -3.927740e+00 -3.809684e-02 4.407143e-02 -9.983017e-01 1.762461e+02 +-9.963806e-01 7.484723e-02 4.029417e-02 -1.239605e+01 7.650981e-02 9.962076e-01 4.143279e-02 -3.895038e+00 -3.704022e-02 4.436572e-02 -9.983284e-01 1.749872e+02 +-9.965700e-01 7.267309e-02 3.958545e-02 -1.234119e+01 7.440862e-02 9.962438e-01 4.429050e-02 -3.859344e+00 -3.621803e-02 4.708407e-02 -9.982341e-01 1.737187e+02 +-9.967878e-01 6.994415e-02 3.901255e-02 -1.228401e+01 7.173826e-02 9.963316e-01 4.665770e-02 -3.823790e+00 -3.560600e-02 4.930651e-02 -9.981488e-01 1.724501e+02 +-9.968291e-01 6.959328e-02 3.858233e-02 -1.222752e+01 7.130737e-02 9.964393e-01 4.498870e-02 -3.789130e+00 -3.531404e-02 4.759724e-02 -9.982421e-01 1.711789e+02 +-9.967983e-01 7.014577e-02 3.837800e-02 -1.217501e+01 7.172342e-02 9.965649e-01 4.140270e-02 -3.753055e+00 -3.534194e-02 4.402273e-02 -9.984051e-01 1.698980e+02 +-9.967383e-01 7.092261e-02 3.850635e-02 -1.212392e+01 7.243228e-02 9.965973e-01 3.933729e-02 -3.718784e+00 -3.558542e-02 4.199808e-02 -9.984837e-01 1.686150e+02 +-9.966624e-01 7.176217e-02 3.891486e-02 -1.207148e+01 7.326825e-02 9.965586e-01 3.876355e-02 -3.687339e+00 -3.599918e-02 4.148539e-02 -9.984903e-01 1.673260e+02 +-9.965866e-01 7.250476e-02 3.947590e-02 -1.201825e+01 7.413206e-02 9.963867e-01 4.144863e-02 -3.654372e+00 -3.632804e-02 4.423357e-02 -9.983604e-01 1.660281e+02 +-9.965516e-01 7.264605e-02 4.009448e-02 -1.196120e+01 7.441859e-02 9.962273e-01 4.464387e-02 -3.624176e+00 -3.670001e-02 4.747368e-02 -9.981980e-01 1.647280e+02 +-9.964585e-01 7.364473e-02 4.058204e-02 -1.190192e+01 7.542380e-02 9.961713e-01 4.420445e-02 -3.591375e+00 -3.717123e-02 4.710875e-02 -9.981979e-01 1.634318e+02 +-9.963913e-01 7.421798e-02 4.118428e-02 -1.184135e+01 7.598927e-02 9.961701e-01 4.325200e-02 -3.554551e+00 -3.781647e-02 4.622547e-02 -9.982149e-01 1.621341e+02 +-9.963561e-01 7.438640e-02 4.172768e-02 -1.177885e+01 7.616290e-02 9.961792e-01 4.273363e-02 -3.523863e+00 -3.838944e-02 4.575600e-02 -9.982147e-01 1.608345e+02 +-9.962880e-01 7.494299e-02 4.235494e-02 -1.172026e+01 7.672619e-02 9.961599e-01 4.217127e-02 -3.495831e+00 -3.903185e-02 4.526446e-02 -9.982122e-01 1.595304e+02 +-9.962547e-01 7.500587e-02 4.302109e-02 -1.165518e+01 7.680993e-02 9.961634e-01 4.193594e-02 -3.475071e+00 -3.971059e-02 4.508331e-02 -9.981936e-01 1.582205e+02 +-9.962885e-01 7.416001e-02 4.369938e-02 -1.159110e+01 7.603687e-02 9.961784e-01 4.297618e-02 -3.449080e+00 -4.034526e-02 4.613943e-02 -9.981199e-01 1.569119e+02 +-9.962911e-01 7.369567e-02 4.441888e-02 -1.152805e+01 7.564548e-02 9.961662e-01 4.393995e-02 -3.427408e+00 -4.101040e-02 4.713706e-02 -9.980462e-01 1.556018e+02 +-9.963031e-01 7.297865e-02 4.532553e-02 -1.146658e+01 7.499232e-02 9.961934e-01 4.443854e-02 -3.404632e+00 -4.190993e-02 4.767332e-02 -9.979833e-01 1.542873e+02 +-9.962748e-01 7.279099e-02 4.623878e-02 -1.140471e+01 7.489538e-02 9.961511e-01 4.553618e-02 -3.379760e+00 -4.274619e-02 4.882961e-02 -9.978919e-01 1.529761e+02 +-9.962278e-01 7.287466e-02 4.711133e-02 -1.134344e+01 7.505487e-02 9.961042e-01 4.629416e-02 -3.361264e+00 -4.355412e-02 4.965545e-02 -9.978162e-01 1.516424e+02 +-9.961849e-01 7.285137e-02 4.804677e-02 -1.128131e+01 7.508169e-02 9.960985e-01 4.637312e-02 -3.336424e+00 -4.448096e-02 4.980362e-02 -9.977680e-01 1.503200e+02 +-9.961416e-01 7.292889e-02 4.881951e-02 -1.121753e+01 7.516300e-02 9.961278e-01 4.560633e-02 -3.312790e+00 -4.530445e-02 4.909977e-02 -9.977658e-01 1.489982e+02 +-9.960832e-01 7.324312e-02 4.953564e-02 -1.114296e+01 7.546769e-02 9.961487e-01 4.463524e-02 -3.265873e+00 -4.607564e-02 4.819875e-02 -9.977744e-01 1.476896e+02 +-9.960388e-01 7.327843e-02 5.036998e-02 -1.105762e+01 7.554981e-02 9.961363e-01 4.477304e-02 -3.207848e+00 -4.689447e-02 4.840112e-02 -9.977265e-01 1.463791e+02 +-9.959557e-01 7.396547e-02 5.100468e-02 -1.097994e+01 7.627722e-02 9.960719e-01 4.497192e-02 -3.164960e+00 -4.747796e-02 4.868052e-02 -9.976853e-01 1.450648e+02 +-9.959725e-01 7.318364e-02 5.179774e-02 -1.089652e+01 7.550720e-02 9.961554e-01 4.441888e-02 -3.120438e+00 -4.834786e-02 4.815108e-02 -9.976692e-01 1.437492e+02 +-9.960276e-01 7.178739e-02 5.268533e-02 -1.081524e+01 7.413313e-02 9.962769e-01 4.400659e-02 -3.079246e+00 -4.933006e-02 4.773750e-02 -9.976410e-01 1.424436e+02 +-9.960538e-01 7.087358e-02 5.342194e-02 -1.073215e+01 7.335144e-02 9.962474e-01 4.594267e-02 -3.035455e+00 -4.996534e-02 4.967994e-02 -9.975145e-01 1.411379e+02 +-9.961426e-01 6.913243e-02 5.404403e-02 -1.065026e+01 7.195440e-02 9.960441e-01 5.214031e-02 -2.995802e+00 -5.022565e-02 5.582788e-02 -9.971763e-01 1.398272e+02 +-9.960495e-01 6.973046e-02 5.498337e-02 -1.057055e+01 7.281400e-02 9.957593e-01 5.622763e-02 -2.953729e+00 -5.082942e-02 6.000905e-02 -9.969028e-01 1.385179e+02 +-9.959282e-01 7.056879e-02 5.609982e-02 -1.049042e+01 7.370374e-02 9.957107e-01 5.592734e-02 -2.907447e+00 -5.191247e-02 5.983437e-02 -9.968575e-01 1.372165e+02 +-9.958169e-01 7.156016e-02 5.681466e-02 -1.041078e+01 7.461969e-02 9.957657e-01 5.369004e-02 -2.860157e+00 -5.273202e-02 5.770493e-02 -9.969400e-01 1.359273e+02 +-9.957630e-01 7.161020e-02 5.768947e-02 -1.033398e+01 7.467311e-02 9.958086e-01 5.281123e-02 -2.818003e+00 -5.366585e-02 5.689531e-02 -9.969367e-01 1.346391e+02 +-9.956926e-01 7.185240e-02 5.859737e-02 -1.026756e+01 7.499671e-02 9.957556e-01 5.335090e-02 -2.782459e+00 -5.451527e-02 5.751569e-02 -9.968550e-01 1.333539e+02 +-9.955485e-01 7.307127e-02 5.953011e-02 -1.019703e+01 7.634218e-02 9.955824e-01 5.465886e-02 -2.769770e+00 -5.527313e-02 5.896019e-02 -9.967289e-01 1.320608e+02 +-9.954176e-01 7.415226e-02 6.037700e-02 -1.012324e+01 7.752538e-02 9.954397e-01 5.558409e-02 -2.741915e+00 -5.597997e-02 6.001012e-02 -9.966268e-01 1.307858e+02 +-9.952523e-01 7.597763e-02 6.083024e-02 -1.005361e+01 7.944774e-02 9.952185e-01 5.681686e-02 -2.722968e+00 -5.622257e-02 6.137993e-02 -9.965297e-01 1.295177e+02 +-9.952297e-01 7.600679e-02 6.116269e-02 -9.983675e+00 7.946414e-02 9.952504e-01 5.623136e-02 -2.704977e+00 -5.659822e-02 6.082335e-02 -9.965425e-01 1.282716e+02 +-9.952049e-01 7.641744e-02 6.105434e-02 -9.914350e+00 7.971245e-02 9.953818e-01 5.348805e-02 -2.693324e+00 -5.668495e-02 5.809835e-02 -9.967002e-01 1.270275e+02 +-9.953209e-01 7.534886e-02 6.048868e-02 -9.842207e+00 7.847462e-02 9.956068e-01 5.107690e-02 -2.676072e+00 -5.637435e-02 5.558473e-02 -9.968612e-01 1.257959e+02 +-9.955321e-01 7.262602e-02 6.034348e-02 -9.768507e+00 7.570540e-02 9.958550e-01 5.041391e-02 -2.668058e+00 -5.643199e-02 5.475698e-02 -9.969037e-01 1.245864e+02 +-9.956184e-01 7.193217e-02 5.974740e-02 -9.696148e+00 7.493906e-02 9.959484e-01 4.970876e-02 -2.675813e+00 -5.592966e-02 5.396837e-02 -9.969750e-01 1.233957e+02 +-9.957201e-01 7.142144e-02 5.865536e-02 -9.626526e+00 7.438912e-02 9.959714e-01 5.007235e-02 -2.673222e+00 -5.484281e-02 5.422136e-02 -9.970217e-01 1.222269e+02 +-9.958299e-01 7.075025e-02 5.759566e-02 -9.557928e+00 7.363915e-02 9.960466e-01 4.968260e-02 -2.676765e+00 -5.385291e-02 5.371670e-02 -9.971029e-01 1.210553e+02 +-9.958620e-01 7.110237e-02 5.659893e-02 -9.493383e+00 7.390922e-02 9.960532e-01 4.914614e-02 -2.664828e+00 -5.288114e-02 5.312595e-02 -9.971866e-01 1.199144e+02 +-9.959578e-01 7.065617e-02 5.546017e-02 -9.430385e+00 7.342022e-02 9.960723e-01 4.949069e-02 -2.656282e+00 -5.174551e-02 5.336253e-02 -9.972335e-01 1.187910e+02 +-9.960527e-01 7.026569e-02 5.423830e-02 -9.369618e+00 7.295424e-02 9.961165e-01 4.929064e-02 -2.640186e+00 -5.056422e-02 5.305298e-02 -9.973106e-01 1.176937e+02 +-9.961715e-01 6.950390e-02 5.302564e-02 -9.310280e+00 7.208599e-02 9.962213e-01 4.844310e-02 -2.629674e+00 -4.945828e-02 5.208003e-02 -9.974174e-01 1.166077e+02 +-9.961917e-01 7.005536e-02 5.190701e-02 -9.254439e+00 7.254160e-02 9.962255e-01 4.766941e-02 -2.616277e+00 -4.837159e-02 5.125328e-02 -9.975135e-01 1.155322e+02 +-9.962258e-01 7.034187e-02 5.085580e-02 -9.200535e+00 7.277434e-02 9.962083e-01 4.767399e-02 -2.603835e+00 -4.730949e-02 5.119504e-02 -9.975674e-01 1.144721e+02 +-9.961880e-01 7.172591e-02 4.964830e-02 -9.151332e+00 7.409011e-02 9.961178e-01 4.753843e-02 -2.588856e+00 -4.604582e-02 5.103565e-02 -9.976347e-01 1.134423e+02 +-9.961531e-01 7.289656e-02 4.863228e-02 -9.105417e+00 7.521117e-02 9.960312e-01 4.759325e-02 -2.570260e+00 -4.496988e-02 5.106784e-02 -9.976822e-01 1.124364e+02 +-9.961733e-01 7.332033e-02 4.757049e-02 -9.061229e+00 7.562751e-02 9.959480e-01 4.866140e-02 -2.551094e+00 -4.380986e-02 5.207281e-02 -9.976818e-01 1.114494e+02 +-9.962187e-01 7.340937e-02 4.647002e-02 -9.017561e+00 7.568432e-02 9.959148e-01 4.924961e-02 -2.534579e+00 -4.266480e-02 5.258043e-02 -9.977048e-01 1.104820e+02 +-9.962591e-01 7.354235e-02 4.538023e-02 -8.973774e+00 7.579749e-02 9.958611e-01 5.015305e-02 -2.518585e+00 -4.150404e-02 5.340513e-02 -9.977100e-01 1.095389e+02 +-9.963828e-01 7.264441e-02 4.409188e-02 -8.931383e+00 7.484917e-02 9.959102e-01 5.060113e-02 -2.500910e+00 -4.023567e-02 5.371832e-02 -9.977451e-01 1.086310e+02 +-9.965194e-01 7.152238e-02 4.282180e-02 -8.888960e+00 7.370262e-02 9.959389e-01 5.170601e-02 -2.499823e+00 -3.894976e-02 5.468211e-02 -9.977438e-01 1.077448e+02 +-9.965622e-01 7.156850e-02 4.173568e-02 -8.850383e+00 7.373292e-02 9.958762e-01 5.285779e-02 -2.490803e+00 -3.778062e-02 5.575336e-02 -9.977295e-01 1.068841e+02 +-9.966037e-01 7.157097e-02 4.072852e-02 -8.810192e+00 7.374684e-02 9.957759e-01 5.469652e-02 -2.484177e+00 -3.664179e-02 5.751434e-02 -9.976720e-01 1.060361e+02 +-9.965274e-01 7.286890e-02 4.029183e-02 -8.774269e+00 7.507494e-02 9.955897e-01 5.625643e-02 -2.471963e+00 -3.601478e-02 5.908597e-02 -9.976030e-01 1.052229e+02 +-9.963119e-01 7.520760e-02 4.130905e-02 -8.743349e+00 7.752694e-02 9.953162e-01 5.775139e-02 -2.456480e+00 -3.677222e-02 6.074095e-02 -9.974759e-01 1.044293e+02 +-9.958914e-01 7.849169e-02 4.515929e-02 -8.714586e+00 8.103601e-02 9.950467e-01 5.757750e-02 -2.438815e+00 -4.041625e-02 6.100046e-02 -9.973191e-01 1.036667e+02 +-9.951967e-01 8.263177e-02 5.249461e-02 -8.679794e+00 8.558221e-02 9.947170e-01 5.668933e-02 -2.425206e+00 -4.753294e-02 6.090963e-02 -9.970108e-01 1.029180e+02 +-9.941419e-01 8.671496e-02 6.451678e-02 -8.637154e+00 9.037707e-02 9.943213e-01 5.618827e-02 -2.411937e+00 -5.927805e-02 6.168994e-02 -9.963335e-01 1.021865e+02 +-9.927004e-01 8.903931e-02 8.135159e-02 -8.579986e+00 9.370763e-02 9.940524e-01 5.548560e-02 -2.398460e+00 -7.592734e-02 6.270383e-02 -9.951398e-01 1.014891e+02 +-9.906796e-01 9.047763e-02 1.018221e-01 -8.504861e+00 9.642566e-02 9.938147e-01 5.508541e-02 -2.388482e+00 -9.620829e-02 6.439024e-02 -9.932763e-01 1.008128e+02 +-9.877818e-01 9.109262e-02 1.264489e-01 -8.410845e+00 9.849788e-02 9.936933e-01 5.358900e-02 -2.378517e+00 -1.207698e-01 6.538917e-02 -9.905245e-01 1.001642e+02 +-9.833359e-01 9.348022e-02 1.559230e-01 -8.297513e+00 1.024351e-01 9.934619e-01 5.040344e-02 -2.373526e+00 -1.501918e-01 6.553548e-02 -9.864823e-01 9.952950e+01 +-9.776056e-01 9.280749e-02 1.888760e-01 -8.163715e+00 1.035149e-01 9.934874e-01 4.761647e-02 -2.367550e+00 -1.832268e-01 6.610159e-02 -9.808458e-01 9.891972e+01 +-9.701360e-01 9.043999e-02 2.250708e-01 -8.004362e+00 1.027903e-01 9.937405e-01 4.374899e-02 -2.365664e+00 -2.197053e-01 6.557753e-02 -9.733597e-01 9.833881e+01 +-9.609776e-01 8.558626e-02 2.630533e-01 -7.822238e+00 9.957581e-02 9.942138e-01 4.029245e-02 -2.363865e+00 -2.580828e-01 6.491388e-02 -9.639395e-01 9.778786e+01 +-9.499461e-01 7.969838e-02 3.020771e-01 -7.618518e+00 9.535430e-02 9.947400e-01 3.741516e-02 -2.365779e+00 -2.975063e-01 6.434673e-02 -9.525489e-01 9.724366e+01 +-9.360883e-01 7.451328e-02 3.437827e-01 -7.391983e+00 9.209469e-02 9.951323e-01 3.507498e-02 -2.368503e+00 -3.394957e-01 6.449383e-02 -9.383939e-01 9.672212e+01 +-9.195393e-01 6.644626e-02 3.873401e-01 -7.139675e+00 8.604633e-02 9.957291e-01 3.346023e-02 -2.371668e+00 -3.834625e-01 6.409718e-02 -9.213294e-01 9.622046e+01 +-9.001217e-01 5.680061e-02 4.319198e-01 -6.858427e+00 7.819436e-02 9.964270e-01 3.191973e-02 -2.377152e+00 -4.285634e-01 6.250532e-02 -9.013470e-01 9.572524e+01 +-8.770849e-01 4.699130e-02 4.780313e-01 -6.558989e+00 7.063488e-02 9.970018e-01 3.159283e-02 -2.382497e+00 -4.751135e-01 6.147527e-02 -8.777744e-01 9.526713e+01 +-8.504074e-01 3.805485e-02 5.247468e-01 -6.241788e+00 6.375191e-02 9.974848e-01 3.097865e-02 -2.391400e+00 -5.222480e-01 5.979807e-02 -8.506945e-01 9.482915e+01 +-8.208033e-01 3.049720e-02 5.703963e-01 -5.899838e+00 5.886994e-02 9.977727e-01 3.136653e-02 -2.396299e+00 -5.681693e-01 5.932493e-02 -8.207705e-01 9.439238e+01 +-7.883662e-01 2.270087e-02 6.147874e-01 -5.538427e+00 5.370952e-02 9.980430e-01 3.202133e-02 -2.402837e+00 -6.128573e-01 5.826445e-02 -7.880426e-01 9.399153e+01 +-7.519757e-01 1.698164e-02 6.589721e-01 -5.158326e+00 5.106535e-02 9.981647e-01 3.254981e-02 -2.408911e+00 -6.572099e-01 5.812730e-02 -7.514627e-01 9.362076e+01 +-7.112647e-01 1.414579e-02 7.027820e-01 -4.759829e+00 5.104987e-02 9.981968e-01 3.157407e-02 -2.414550e+00 -7.010681e-01 5.833444e-02 -7.107043e-01 9.325390e+01 +-6.682819e-01 1.388988e-02 7.437785e-01 -4.350995e+00 5.322919e-02 9.981557e-01 2.918587e-02 -2.417305e+00 -7.420013e-01 5.909511e-02 -6.677886e-01 9.293117e+01 +-6.228704e-01 1.465697e-02 7.821878e-01 -3.910527e+00 5.456684e-02 9.982034e-01 2.474779e-02 -2.412408e+00 -7.804197e-01 5.809617e-02 -6.225511e-01 9.263366e+01 +-5.752228e-01 1.473772e-02 8.178641e-01 -3.450087e+00 5.406313e-02 9.983365e-01 2.003404e-02 -2.407850e+00 -8.162083e-01 5.574031e-02 -5.750626e-01 9.234876e+01 +-5.261793e-01 1.216376e-02 8.502867e-01 -2.971838e+00 5.327719e-02 9.984049e-01 1.868662e-02 -2.408021e+00 -8.487031e-01 5.513339e-02 -5.259880e-01 9.210569e+01 +-4.750880e-01 9.326973e-03 8.798889e-01 -2.475933e+00 5.099495e-02 9.985550e-01 1.694940e-02 -2.410053e+00 -8.784594e-01 5.292234e-02 -4.748771e-01 9.187573e+01 +-4.226279e-01 6.764292e-03 9.062781e-01 -1.973871e+00 4.659141e-02 9.988120e-01 1.427218e-02 -2.417222e+00 -9.051049e-01 4.825658e-02 -4.224410e-01 9.169173e+01 +-3.702129e-01 6.034494e-03 9.289274e-01 -1.461824e+00 4.572878e-02 9.988849e-01 1.173570e-02 -2.425884e+00 -9.278207e-01 4.682341e-02 -3.700760e-01 9.152700e+01 +-3.190705e-01 7.948320e-03 9.476977e-01 -9.535855e-01 4.679551e-02 9.988772e-01 7.377527e-03 -2.435403e+00 -9.465749e-01 4.670193e-02 -3.190842e-01 9.137699e+01 +-2.707671e-01 1.132841e-02 9.625783e-01 -4.368032e-01 4.725783e-02 9.988815e-01 1.537664e-03 -2.446763e+00 -9.614842e-01 4.590570e-02 -2.709996e-01 9.126186e+01 +-2.261652e-01 1.067749e-02 9.740305e-01 8.493472e-02 3.975518e-02 9.992079e-01 -1.722539e-03 -2.456413e+00 -9.732773e-01 3.833317e-02 -2.264105e-01 9.118058e+01 +-1.860257e-01 8.681791e-03 9.825066e-01 6.102987e-01 3.606891e-02 9.993473e-01 -2.001399e-03 -2.466161e+00 -9.818826e-01 3.506562e-02 -1.862174e-01 9.109177e+01 +-1.504744e-01 1.003583e-02 9.885630e-01 1.138073e+00 3.389616e-02 9.994129e-01 -4.986469e-03 -2.480120e+00 -9.880326e-01 3.275815e-02 -1.507262e-01 9.102634e+01 +-1.206036e-01 1.253365e-02 9.926217e-01 1.669864e+00 3.609708e-02 9.993144e-01 -8.232369e-03 -2.501031e+00 -9.920442e-01 3.483788e-02 -1.209733e-01 9.096038e+01 +-9.649840e-02 1.447502e-02 9.952279e-01 2.208440e+00 3.664238e-02 9.992681e-01 -1.098090e-02 -2.524745e+00 -9.946584e-01 3.540787e-02 -9.695816e-02 9.091501e+01 +-7.720147e-02 1.815333e-02 9.968503e-01 2.751248e+00 3.393141e-02 9.993028e-01 -1.557017e-02 -2.544208e+00 -9.964379e-01 3.262248e-02 -7.776361e-02 9.088197e+01 +-6.177846e-02 2.661506e-02 9.977350e-01 3.299026e+00 3.328086e-02 9.991434e-01 -2.459193e-02 -2.557680e+00 -9.975348e-01 3.168622e-02 -6.261131e-02 9.084272e+01 +-5.011074e-02 2.866767e-02 9.983322e-01 3.858709e+00 3.535214e-02 9.990125e-01 -2.691273e-02 -2.572712e+00 -9.981178e-01 3.394455e-02 -5.107471e-02 9.080590e+01 +-4.104311e-02 2.556380e-02 9.988303e-01 4.431705e+00 3.833365e-02 9.989769e-01 -2.399238e-02 -2.590718e+00 -9.984217e-01 3.730408e-02 -4.198107e-02 9.076614e+01 +-3.414277e-02 2.062906e-02 9.992041e-01 5.016199e+00 3.918087e-02 9.990460e-01 -1.928700e-02 -2.612554e+00 -9.986486e-01 3.849116e-02 -3.491846e-02 9.073841e+01 +-2.960733e-02 1.776081e-02 9.994038e-01 5.610331e+00 3.861348e-02 9.991161e-01 -1.661178e-02 -2.632315e+00 -9.988155e-01 3.809862e-02 -3.026696e-02 9.071049e+01 +-2.786768e-02 1.757846e-02 9.994571e-01 6.211745e+00 3.866760e-02 9.991160e-01 -1.649431e-02 -2.650403e+00 -9.988634e-01 3.818693e-02 -2.852275e-02 9.068357e+01 +-2.722461e-02 1.829836e-02 9.994619e-01 6.821468e+00 4.119832e-02 9.990035e-01 -1.716776e-02 -2.665408e+00 -9.987800e-01 4.070875e-02 -2.795134e-02 9.064843e+01 +-2.616227e-02 1.900282e-02 9.994771e-01 7.446192e+00 4.497527e-02 9.988292e-01 -1.781324e-02 -2.681728e+00 -9.986454e-01 4.448571e-02 -2.698630e-02 9.061850e+01 +-2.567020e-02 2.032244e-02 9.994639e-01 8.081090e+00 4.852036e-02 9.986403e-01 -1.905950e-02 -2.703699e+00 -9.984922e-01 4.800508e-02 -2.662134e-02 9.057853e+01 +-2.617453e-02 2.102096e-02 9.994364e-01 8.731175e+00 5.109047e-02 9.985004e-01 -1.966326e-02 -2.727805e+00 -9.983509e-01 5.054698e-02 -2.720924e-02 9.054284e+01 +-2.633504e-02 2.105336e-02 9.994315e-01 9.399524e+00 5.266188e-02 9.984191e-01 -1.964440e-02 -2.754209e+00 -9.982650e-01 5.211459e-02 -2.740212e-02 9.050118e+01 +-2.610918e-02 2.061157e-02 9.994466e-01 1.007658e+01 5.422092e-02 9.983449e-01 -1.917241e-02 -2.773656e+00 -9.981875e-01 5.369032e-02 -2.718354e-02 9.046928e+01 +-2.549808e-02 2.042503e-02 9.994662e-01 1.077161e+01 5.726642e-02 9.981793e-01 -1.893777e-02 -2.793484e+00 -9.980332e-01 5.675296e-02 -2.662132e-02 9.043670e+01 +-2.421406e-02 2.064081e-02 9.994937e-01 1.147973e+01 6.272400e-02 9.978484e-01 -1.908727e-02 -2.812970e+00 -9.977371e-01 6.223005e-02 -2.545663e-02 9.040048e+01 +-2.149124e-02 2.091953e-02 9.995502e-01 1.220589e+01 6.682984e-02 9.975749e-01 -1.944129e-02 -2.834519e+00 -9.975329e-01 6.638194e-02 -2.283717e-02 9.036536e+01 +-1.700505e-02 2.095003e-02 9.996359e-01 1.295106e+01 7.041597e-02 9.973231e-01 -1.970370e-02 -2.856224e+00 -9.973727e-01 7.005525e-02 -1.843474e-02 9.033131e+01 +-1.058114e-02 2.102745e-02 9.997229e-01 1.371186e+01 7.352996e-02 9.970885e-01 -2.019380e-02 -2.879219e+00 -9.972368e-01 7.329590e-02 -1.209648e-02 9.030931e+01 +-2.234786e-03 2.082290e-02 9.997807e-01 1.448981e+01 7.655804e-02 9.968525e-01 -2.059079e-02 -2.901943e+00 -9.970626e-01 7.649522e-02 -3.821910e-03 9.029031e+01 +7.417937e-03 1.924772e-02 9.997873e-01 1.528482e+01 7.928270e-02 9.966560e-01 -1.977569e-02 -2.923415e+00 -9.968245e-01 7.941250e-02 5.867121e-03 9.028642e+01 +1.826995e-02 1.817013e-02 9.996680e-01 1.608562e+01 8.031803e-02 9.965769e-01 -1.958184e-02 -2.939984e+00 -9.966018e-01 8.064910e-02 1.674802e-02 9.029611e+01 +2.942269e-02 1.608883e-02 9.994376e-01 1.691051e+01 7.712420e-02 9.968532e-01 -1.831771e-02 -2.960754e+00 -9.965872e-01 7.761976e-02 2.808926e-02 9.032149e+01 +4.042898e-02 1.579351e-02 9.990576e-01 1.774494e+01 7.510559e-02 9.969983e-01 -1.880027e-02 -2.980526e+00 -9.963556e-01 7.579487e-02 3.912144e-02 9.035587e+01 +5.153679e-02 1.733169e-02 9.985207e-01 1.859667e+01 7.264508e-02 9.971355e-01 -2.105709e-02 -3.005455e+00 -9.960254e-01 7.362282e-02 5.013010e-02 9.040215e+01 +6.239743e-02 2.161166e-02 9.978174e-01 1.945362e+01 6.886126e-02 9.972898e-01 -2.590640e-02 -3.034010e+00 -9.956729e-01 7.032744e-02 6.074011e-02 9.045965e+01 +7.183922e-02 2.638636e-02 9.970672e-01 2.031322e+01 6.496402e-02 9.974036e-01 -3.107596e-02 -3.064211e+00 -9.952983e-01 6.700595e-02 6.993852e-02 9.052235e+01 +7.884940e-02 2.761002e-02 9.965041e-01 2.117745e+01 5.843742e-02 9.977694e-01 -3.226900e-02 -3.096855e+00 -9.951722e-01 6.077751e-02 7.706006e-02 9.059661e+01 +8.232797e-02 2.532889e-02 9.962834e-01 2.204573e+01 5.228415e-02 9.981905e-01 -2.969789e-02 -3.131090e+00 -9.952328e-01 5.453478e-02 8.085470e-02 9.067111e+01 +8.322809e-02 2.389315e-02 9.962441e-01 2.291460e+01 4.730782e-02 9.984906e-01 -2.789923e-02 -3.169221e+00 -9.954069e-01 4.945212e-02 8.197213e-02 9.074940e+01 +8.118946e-02 2.210037e-02 9.964537e-01 2.377962e+01 4.346288e-02 9.987246e-01 -2.569203e-02 -3.210301e+00 -9.957506e-01 4.539465e-02 8.012536e-02 9.082667e+01 +7.732120e-02 2.206442e-02 9.967621e-01 2.464428e+01 3.914086e-02 9.989172e-01 -2.514838e-02 -3.253324e+00 -9.962376e-01 4.095862e-02 7.637385e-02 9.089534e+01 +7.116311e-02 2.247313e-02 9.972115e-01 2.549897e+01 3.594641e-02 9.990390e-01 -2.507953e-02 -3.294820e+00 -9.968167e-01 3.763090e-02 7.028689e-02 9.095836e+01 +6.298164e-02 2.367836e-02 9.977338e-01 2.635325e+01 3.297296e-02 9.991234e-01 -2.579275e-02 -3.334796e+00 -9.974698e-01 3.452270e-02 6.214568e-02 9.101462e+01 +5.312298e-02 2.413278e-02 9.982964e-01 2.720785e+01 3.029610e-02 9.992088e-01 -2.576701e-02 -3.371323e+00 -9.981283e-01 3.161329e-02 5.234982e-02 9.106401e+01 +4.210354e-02 2.288973e-02 9.988510e-01 2.806008e+01 2.863046e-02 9.992993e-01 -2.410684e-02 -3.405154e+00 -9.987029e-01 2.961254e-02 4.141869e-02 9.109881e+01 +3.056435e-02 2.036693e-02 9.993253e-01 2.891571e+01 2.791101e-02 9.993851e-01 -2.122182e-02 -3.438232e+00 -9.991430e-01 2.854080e-02 2.997710e-02 9.112023e+01 +1.863177e-02 1.828016e-02 9.996593e-01 2.976478e+01 2.766332e-02 9.994406e-01 -1.879176e-02 -3.470581e+00 -9.994436e-01 2.800401e-02 1.811566e-02 9.113015e+01 +6.673685e-03 1.899539e-02 9.997973e-01 3.060909e+01 2.894733e-02 9.993969e-01 -1.918101e-02 -3.500672e+00 -9.995586e-01 2.906946e-02 6.119795e-03 9.112702e+01 +-5.312876e-03 2.093624e-02 9.997667e-01 3.144794e+01 3.060848e-02 9.993157e-01 -2.076415e-02 -3.527684e+00 -9.995173e-01 3.049101e-02 -5.950066e-03 9.111123e+01 +-1.745769e-02 2.181656e-02 9.996096e-01 3.228769e+01 3.242736e-02 9.992483e-01 -2.124235e-02 -3.554151e+00 -9.993216e-01 3.204384e-02 -1.815202e-02 9.108555e+01 +-2.949662e-02 2.077817e-02 9.993489e-01 3.312438e+01 3.387243e-02 9.992305e-01 -1.977594e-02 -3.582327e+00 -9.989908e-01 3.326705e-02 -3.017773e-02 9.104470e+01 +-4.096088e-02 1.973606e-02 9.989658e-01 3.396442e+01 3.498441e-02 9.992202e-01 -1.830662e-02 -3.611519e+00 -9.985481e-01 3.419837e-02 -4.161939e-02 9.099774e+01 +-5.118554e-02 2.004373e-02 9.984880e-01 3.480342e+01 3.749714e-02 9.991322e-01 -1.813445e-02 -3.638640e+00 -9.979849e-01 3.651222e-02 -5.189270e-02 9.093780e+01 +-5.899193e-02 2.063119e-02 9.980453e-01 3.564157e+01 3.994307e-02 9.990345e-01 -1.829072e-02 -3.664619e+00 -9.974590e-01 3.878598e-02 -5.975904e-02 9.087112e+01 +-6.473322e-02 2.188563e-02 9.976626e-01 3.648132e+01 4.172831e-02 9.989444e-01 -1.920622e-02 -3.695783e+00 -9.970297e-01 4.038748e-02 -6.557813e-02 9.080032e+01 +-6.864488e-02 2.476225e-02 9.973338e-01 3.732512e+01 4.248099e-02 9.988577e-01 -2.187620e-02 -3.725465e+00 -9.967363e-01 4.086603e-02 -6.961839e-02 9.072894e+01 +-7.088885e-02 2.748791e-02 9.971054e-01 3.817446e+01 4.356661e-02 9.987516e-01 -2.443595e-02 -3.753578e+00 -9.965323e-01 4.170825e-02 -7.199790e-02 9.065326e+01 +-7.180171e-02 2.948397e-02 9.969831e-01 3.903116e+01 4.452366e-02 9.986613e-01 -2.632706e-02 -3.784327e+00 -9.964246e-01 4.249900e-02 -7.301832e-02 9.058010e+01 +-7.113755e-02 2.980377e-02 9.970212e-01 3.989617e+01 4.524815e-02 9.986209e-01 -2.662314e-02 -3.816446e+00 -9.964396e-01 4.321945e-02 -7.238800e-02 9.050847e+01 +-6.922094e-02 2.925645e-02 9.971723e-01 4.077155e+01 4.530176e-02 9.986309e-01 -2.615453e-02 -3.849569e+00 -9.965722e-01 4.336321e-02 -7.045153e-02 9.043290e+01 +-6.685229e-02 2.726587e-02 9.973903e-01 4.165672e+01 4.523435e-02 9.986815e-01 -2.426925e-02 -3.883158e+00 -9.967369e-01 4.349383e-02 -6.799750e-02 9.036243e+01 +-6.434591e-02 2.479427e-02 9.976196e-01 4.254796e+01 4.558345e-02 9.987208e-01 -2.188154e-02 -3.919092e+00 -9.968860e-01 4.406694e-02 -6.539381e-02 9.028996e+01 +-6.200928e-02 2.307069e-02 9.978089e-01 4.344429e+01 4.589850e-02 9.987410e-01 -2.023987e-02 -3.955976e+00 -9.970196e-01 4.454286e-02 -6.299012e-02 9.022418e+01 +-6.043167e-02 2.117074e-02 9.979478e-01 4.434296e+01 4.379820e-02 9.988684e-01 -1.853804e-02 -3.993405e+00 -9.972109e-01 4.258803e-02 -6.129052e-02 9.016105e+01 +-6.011656e-02 2.100958e-02 9.979703e-01 4.524463e+01 4.149121e-02 9.989670e-01 -1.853119e-02 -4.029977e+00 -9.973286e-01 4.029295e-02 -6.092617e-02 9.009781e+01 +-6.154090e-02 2.124792e-02 9.978784e-01 4.614374e+01 3.761506e-02 9.991125e-01 -1.895442e-02 -4.066554e+00 -9.973955e-01 3.636877e-02 -6.228551e-02 9.003424e+01 +-6.556336e-02 2.205229e-02 9.976047e-01 4.704273e+01 3.296996e-02 9.992577e-01 -1.992203e-02 -4.102566e+00 -9.973035e-01 3.158482e-02 -6.624175e-02 8.997108e+01 +-7.184265e-02 2.161185e-02 9.971818e-01 4.794302e+01 2.704114e-02 9.994399e-01 -1.971260e-02 -4.137800e+00 -9.970493e-01 2.554872e-02 -7.238681e-02 8.990361e+01 +-8.156536e-02 2.211756e-02 9.964226e-01 4.883973e+01 2.205123e-02 9.995490e-01 -2.038189e-02 -4.172906e+00 -9.964240e-01 2.030988e-02 -8.201629e-02 8.982867e+01 +-9.481393e-02 2.440724e-02 9.951958e-01 4.973213e+01 1.863746e-02 9.995677e-01 -2.273885e-02 -4.209393e+00 -9.953205e-01 1.639196e-02 -9.522782e-02 8.973697e+01 +-1.110383e-01 2.817634e-02 9.934167e-01 5.061799e+01 1.411047e-02 9.995419e-01 -2.677290e-02 -4.246250e+00 -9.937159e-01 1.104475e-02 -1.113850e-01 8.962973e+01 +-1.292450e-01 2.965948e-02 9.911691e-01 5.150038e+01 1.391428e-02 9.995084e-01 -2.809466e-02 -4.280657e+00 -9.915150e-01 1.016030e-02 -1.295941e-01 8.950388e+01 +-1.487487e-01 2.680706e-02 9.885116e-01 5.237928e+01 1.581220e-02 9.995691e-01 -2.472756e-02 -4.315191e+00 -9.887486e-01 1.195234e-02 -1.491084e-01 8.935421e+01 +-1.696414e-01 2.120907e-02 9.852776e-01 5.325215e+01 1.853868e-02 9.996601e-01 -1.832676e-02 -4.349397e+00 -9.853314e-01 1.515676e-02 -1.699769e-01 8.918563e+01 +-1.911515e-01 1.998029e-02 9.813572e-01 5.411543e+01 2.029024e-02 9.996596e-01 -1.640074e-02 -4.383180e+00 -9.813508e-01 1.677694e-02 -1.914918e-01 8.899543e+01 +-2.120472e-01 2.060376e-02 9.770422e-01 5.496850e+01 2.407821e-02 9.995843e-01 -1.585345e-02 -4.412621e+00 -9.769627e-01 2.016374e-02 -2.124551e-01 8.878682e+01 +-2.322954e-01 2.352450e-02 9.723608e-01 5.581415e+01 3.052651e-02 9.993913e-01 -1.688574e-02 -4.435513e+00 -9.721661e-01 2.576030e-02 -2.328721e-01 8.855772e+01 +-2.522846e-01 2.228046e-02 9.673966e-01 5.665441e+01 3.448592e-02 9.993068e-01 -1.402192e-02 -4.458280e+00 -9.670383e-01 2.982404e-02 -2.528781e-01 8.831973e+01 +-2.713065e-01 2.242172e-02 9.622318e-01 5.748695e+01 3.839920e-02 9.991848e-01 -1.245593e-02 -4.481396e+00 -9.617267e-01 3.356955e-02 -2.719463e-01 8.806451e+01 +-2.876833e-01 2.376735e-02 9.574307e-01 5.831330e+01 4.324194e-02 9.989948e-01 -1.180606e-02 -4.506276e+00 -9.567489e-01 3.800474e-02 -2.884219e-01 8.779163e+01 +-3.023285e-01 2.585022e-02 9.528532e-01 5.913858e+01 4.509189e-02 9.989009e-01 -1.279237e-02 -4.526147e+00 -9.521366e-01 3.909845e-02 -3.031618e-01 8.751373e+01 +-3.154350e-01 2.463118e-02 9.486275e-01 5.996701e+01 4.794971e-02 9.987998e-01 -9.989808e-03 -4.542452e+00 -9.477350e-01 4.233527e-02 -3.162374e-01 8.722223e+01 +-3.256915e-01 1.558251e-02 9.453477e-01 6.080547e+01 5.057203e-02 9.987199e-01 9.608141e-04 -4.550111e+00 -9.441226e-01 4.812107e-02 -3.260626e-01 8.692074e+01 +-3.335314e-01 5.416807e-03 9.427234e-01 6.165008e+01 4.912119e-02 9.987250e-01 1.164027e-02 -4.554028e+00 -9.414583e-01 5.019008e-02 -3.333722e-01 8.661605e+01 +-3.386003e-01 5.953644e-04 9.409301e-01 6.248920e+01 4.878757e-02 9.986658e-01 1.692465e-02 -4.559425e+00 -9.396646e-01 5.163637e-02 -3.381776e-01 8.630672e+01 +-3.400358e-01 7.198371e-03 9.403850e-01 6.332202e+01 5.061897e-02 9.986611e-01 1.065895e-02 -4.563838e+00 -9.390492e-01 5.122573e-02 -3.399449e-01 8.599410e+01 +-3.403208e-01 1.987700e-02 9.400993e-01 6.415230e+01 5.337924e-02 9.985727e-01 -1.789782e-03 -4.568649e+00 -9.387930e-01 4.957268e-02 -3.408961e-01 8.568272e+01 +-3.396877e-01 3.040815e-02 9.400466e-01 6.498797e+01 5.467388e-02 9.984255e-01 -1.254006e-02 -4.579089e+00 -9.389478e-01 4.713629e-02 -3.408153e-01 8.537187e+01 +-3.391444e-01 3.207577e-02 9.401874e-01 6.583372e+01 5.471004e-02 9.983995e-01 -1.432676e-02 -4.600068e+00 -9.391421e-01 4.657884e-02 -3.403564e-01 8.505504e+01 +-3.398005e-01 2.843763e-02 9.400675e-01 6.668849e+01 5.454409e-02 9.984563e-01 -1.048822e-02 -4.622012e+00 -9.389145e-01 4.771122e-02 -3.408270e-01 8.473494e+01 +-3.419605e-01 2.322833e-02 9.394272e-01 6.754801e+01 5.417162e-02 9.985192e-01 -4.970464e-03 -4.642618e+00 -9.381516e-01 4.919058e-02 -3.427124e-01 8.441083e+01 +-3.464151e-01 1.908796e-02 9.378871e-01 6.840622e+01 5.502992e-02 9.984847e-01 4.427112e-06 -4.658949e+00 -9.364658e-01 5.161338e-02 -3.469406e-01 8.408078e+01 +-3.523198e-01 1.658184e-02 9.357328e-01 6.926862e+01 5.529304e-02 9.984653e-01 3.125292e-03 -4.671587e+00 -9.342448e-01 5.284060e-02 -3.526960e-01 8.374444e+01 +-3.607043e-01 1.712735e-02 9.325230e-01 7.013521e+01 5.471058e-02 9.984982e-01 2.823198e-03 -4.683307e+00 -9.310742e-01 5.203720e-02 -3.610996e-01 8.340015e+01 +-3.714754e-01 2.047584e-02 9.282170e-01 7.099861e+01 5.373385e-02 9.985551e-01 -5.230010e-04 -4.693642e+00 -9.268865e-01 4.968238e-02 -3.720389e-01 8.304535e+01 +-3.850640e-01 2.328394e-02 9.225961e-01 7.185907e+01 5.551004e-02 9.984560e-01 -2.030228e-03 -4.703205e+00 -9.212189e-01 5.043157e-02 -3.857620e-01 8.267153e+01 +-3.993903e-01 2.482154e-02 9.164449e-01 7.272096e+01 5.597997e-02 9.984284e-01 -2.645742e-03 -4.717954e+00 -9.150702e-01 5.024587e-02 -4.001521e-01 8.228193e+01 +-4.133231e-01 2.894187e-02 9.101244e-01 7.357852e+01 5.535210e-02 9.984450e-01 -6.612919e-03 -4.736698e+00 -9.089005e-01 4.764401e-02 -4.142823e-01 8.187928e+01 +-4.254372e-01 3.877125e-02 9.041571e-01 7.443372e+01 5.882827e-02 9.981536e-01 -1.512120e-02 -4.755133e+00 -9.030739e-01 4.675686e-02 -4.269325e-01 8.145699e+01 +-4.357161e-01 4.483909e-02 8.989666e-01 7.529464e+01 6.148719e-02 9.979080e-01 -1.997220e-02 -4.777015e+00 -8.979815e-01 4.657271e-02 -4.375615e-01 8.102618e+01 +-4.440250e-01 4.137235e-02 8.950588e-01 7.617016e+01 6.031586e-02 9.980477e-01 -1.621106e-02 -4.804992e+00 -8.939820e-01 4.678811e-02 -4.456535e-01 8.058697e+01 +-4.489518e-01 3.625468e-02 8.928202e-01 7.705191e+01 6.128903e-02 9.980728e-01 -9.709677e-03 -4.831255e+00 -8.914515e-01 5.036089e-02 -4.503086e-01 8.013589e+01 +-4.513088e-01 3.433810e-02 8.917070e-01 7.793475e+01 6.228078e-02 9.980347e-01 -6.911194e-03 -4.854281e+00 -8.901918e-01 5.241711e-02 -4.525604e-01 7.967880e+01 +-4.525031e-01 3.558518e-02 8.910526e-01 7.881983e+01 6.436490e-02 9.979007e-01 -7.165870e-03 -4.873979e+00 -8.894369e-01 5.410992e-02 -4.538436e-01 7.921929e+01 +-4.529457e-01 3.550914e-02 8.908307e-01 7.970720e+01 6.531479e-02 9.978431e-01 -6.565232e-03 -4.893911e+00 -8.891423e-01 5.521072e-02 -4.542880e-01 7.875908e+01 +-4.538885e-01 3.489319e-02 8.903751e-01 8.059512e+01 6.430896e-02 9.979100e-01 -6.324504e-03 -4.918047e+00 -8.887348e-01 5.438846e-02 -4.551837e-01 7.830009e+01 +-4.547656e-01 3.315342e-02 8.899939e-01 8.148042e+01 6.295391e-02 9.980038e-01 -5.008994e-03 -4.940816e+00 -8.883834e-01 5.375067e-02 -4.559449e-01 7.784269e+01 +-4.558152e-01 3.184394e-02 8.895046e-01 8.236123e+01 5.998150e-02 9.981870e-01 -4.997996e-03 -4.964461e+00 -8.880510e-01 5.107564e-02 -4.568988e-01 7.738417e+01 +-4.579730e-01 2.982886e-02 8.884655e-01 8.323781e+01 5.622121e-02 9.984080e-01 -4.539948e-03 -4.987705e+00 -8.871865e-01 4.787142e-02 -4.589209e-01 7.692792e+01 +-4.622218e-01 2.821657e-02 8.863153e-01 8.410869e+01 5.251293e-02 9.986105e-01 -4.405595e-03 -5.012160e+00 -8.852081e-01 4.450664e-02 -4.630613e-01 7.646987e+01 +-4.690880e-01 2.605465e-02 8.827670e-01 8.497689e+01 4.833222e-02 9.988241e-01 -3.797098e-03 -5.033660e+00 -8.818279e-01 4.088491e-02 -4.697957e-01 7.600608e+01 +-4.777510e-01 2.122747e-02 8.782388e-01 8.584043e+01 4.152061e-02 9.991364e-01 -1.562936e-03 -5.054052e+00 -8.775135e-01 3.571831e-02 -4.782197e-01 7.553882e+01 +-4.878093e-01 1.807010e-02 8.727632e-01 8.669522e+01 4.023335e-02 9.991887e-01 1.799750e-03 -5.077013e+00 -8.720226e-01 3.599211e-02 -4.881405e-01 7.505529e+01 +-4.986973e-01 1.621601e-02 8.666246e-01 8.753763e+01 4.046721e-02 9.991703e-01 4.590591e-03 -5.096609e+00 -8.658310e-01 3.735918e-02 -4.989397e-01 7.456077e+01 +-5.102223e-01 1.496338e-02 8.599124e-01 8.836918e+01 3.825995e-02 9.992537e-01 5.313174e-03 -5.112170e+00 -8.591911e-01 3.561110e-02 -5.104140e-01 7.406297e+01 +-5.223375e-01 1.417692e-02 8.526211e-01 8.918892e+01 3.814880e-02 9.992492e-01 6.755949e-03 -5.126981e+00 -8.518851e-01 3.605534e-02 -5.224861e-01 7.355603e+01 +-5.347818e-01 1.350912e-02 8.448822e-01 8.999811e+01 3.708245e-02 9.992841e-01 7.494019e-03 -5.142400e+00 -8.441761e-01 3.533796e-02 -5.348998e-01 7.303782e+01 +-5.478056e-01 1.498096e-02 8.364716e-01 9.079262e+01 3.712312e-02 9.992901e-01 6.414949e-03 -5.157865e+00 -8.357816e-01 3.456657e-02 -5.479728e-01 7.250815e+01 +-5.606699e-01 1.645000e-02 8.278760e-01 9.157304e+01 3.584719e-02 9.993475e-01 4.419939e-03 -5.173387e+00 -8.272631e-01 3.215515e-02 -5.608937e-01 7.196849e+01 +-5.733897e-01 1.763660e-02 8.190930e-01 9.234400e+01 3.550062e-02 9.993641e-01 3.333316e-03 -5.186461e+00 -8.185133e-01 3.098959e-02 -5.736511e-01 7.141911e+01 +-5.857014e-01 1.643024e-02 8.103604e-01 9.310435e+01 3.523788e-02 9.993654e-01 5.206389e-03 -5.202598e+00 -8.097606e-01 3.160477e-02 -5.859086e-01 7.085573e+01 +-5.979125e-01 1.516468e-02 8.014180e-01 9.385038e+01 3.553763e-02 9.993394e-01 7.603677e-03 -5.217836e+00 -8.007732e-01 3.302682e-02 -5.980564e-01 7.028594e+01 +-6.095362e-01 1.558934e-02 7.926050e-01 9.458632e+01 3.714912e-02 9.992699e-01 8.914616e-03 -5.232682e+00 -7.918874e-01 3.487835e-02 -6.096703e-01 6.970255e+01 +-6.198271e-01 1.708865e-02 7.845523e-01 9.530854e+01 3.919053e-02 9.991894e-01 9.198296e-03 -5.243985e+00 -7.837592e-01 3.644837e-02 -6.199944e-01 6.911483e+01 +-6.280129e-01 1.934875e-02 7.779624e-01 9.602056e+01 4.249902e-02 9.990517e-01 9.459996e-03 -5.253594e+00 -7.770416e-01 3.900363e-02 -6.282396e-01 6.852145e+01 +-6.341159e-01 2.218777e-02 7.729197e-01 9.672259e+01 4.717956e-02 9.988360e-01 1.003384e-02 -5.262948e+00 -7.717974e-01 4.282862e-02 -6.344245e-01 6.792319e+01 +-6.382177e-01 2.404221e-02 7.694805e-01 9.741618e+01 5.062572e-02 9.986594e-01 1.078680e-02 -5.274783e+00 -7.681896e-01 4.583982e-02 -6.385792e-01 6.733056e+01 +-6.406394e-01 2.584892e-02 7.674067e-01 9.810389e+01 5.347434e-02 9.985085e-01 1.100771e-02 -5.288861e+00 -7.659776e-01 4.808853e-02 -6.410661e-01 6.674088e+01 +-6.414842e-01 2.722138e-02 7.666532e-01 9.878369e+01 5.542143e-02 9.984033e-01 1.092287e-02 -5.300088e+00 -7.651317e-01 4.949585e-02 -6.419685e-01 6.616141e+01 +-6.407053e-01 2.956684e-02 7.672175e-01 9.945129e+01 5.908683e-02 9.981936e-01 1.087540e-02 -5.311916e+00 -7.655100e-01 5.230036e-02 -6.412948e-01 6.559079e+01 +-6.384371e-01 3.053163e-02 7.690683e-01 1.001077e+02 6.147774e-02 9.980432e-01 1.141352e-02 -5.322308e+00 -7.672148e-01 5.456738e-02 -6.390647e-01 6.503401e+01 +-6.348862e-01 3.097431e-02 7.719846e-01 1.007513e+02 6.292350e-02 9.979497e-01 1.170806e-02 -5.332047e+00 -7.700391e-01 5.600924e-02 -6.355334e-01 6.449082e+01 +-6.301973e-01 3.218236e-02 7.757678e-01 1.013805e+02 6.539560e-02 9.977904e-01 1.173142e-02 -5.343843e+00 -7.736761e-01 5.812490e-02 -6.309094e-01 6.396662e+01 +-6.246871e-01 3.291404e-02 7.801812e-01 1.019969e+02 6.709390e-02 9.976788e-01 1.163197e-02 -5.356329e+00 -7.779874e-01 5.961173e-02 -6.254454e-01 6.345978e+01 +-6.195979e-01 3.275934e-02 7.842355e-01 1.026011e+02 6.754660e-02 9.976476e-01 1.169220e-02 -5.366131e+00 -7.820076e-01 6.021689e-02 -6.203531e-01 6.297546e+01 +-6.147912e-01 3.165442e-02 7.880545e-01 1.031925e+02 6.636922e-02 9.977265e-01 1.170064e-02 -5.375732e+00 -7.858924e-01 5.949600e-02 -6.154943e-01 6.251471e+01 +-6.104187e-01 3.060823e-02 7.914873e-01 1.037649e+02 6.594865e-02 9.977475e-01 1.227689e-02 -5.381607e+00 -7.893287e-01 5.969155e-02 -6.110623e-01 6.207033e+01 +-6.070105e-01 2.997522e-02 7.941283e-01 1.043198e+02 6.577074e-02 9.977550e-01 1.261206e-02 -5.387971e+00 -7.919674e-01 5.988604e-02 -6.076192e-01 6.164210e+01 +-6.046072e-01 3.148064e-02 7.959015e-01 1.048666e+02 6.546040e-02 9.978024e-01 1.026051e-02 -5.395081e+00 -7.938293e-01 5.830359e-02 -6.053392e-01 6.122103e+01 +-6.042090e-01 3.377057e-02 7.961100e-01 1.054086e+02 6.501546e-02 9.978596e-01 7.014881e-03 -5.405058e+00 -7.941691e-01 5.599790e-02 -6.051113e-01 6.080105e+01 +-6.056417e-01 3.876580e-02 7.947927e-01 1.059435e+02 6.615622e-02 9.978077e-01 1.744020e-03 -5.417450e+00 -7.929827e-01 5.363672e-02 -6.068785e-01 6.038059e+01 +-6.080864e-01 4.473539e-02 7.926095e-01 1.064720e+02 6.933534e-02 9.975885e-01 -3.110808e-03 -5.428230e+00 -7.908373e-01 5.306419e-02 -6.097217e-01 5.995676e+01 +-6.114291e-01 4.641389e-02 7.899368e-01 1.070032e+02 7.145501e-02 9.974383e-01 -3.298161e-03 -5.431921e+00 -7.880663e-01 5.442834e-02 -6.131793e-01 5.953031e+01 +-6.155426e-01 4.298110e-02 7.869307e-01 1.075343e+02 7.223474e-02 9.973856e-01 2.026629e-03 -5.433950e+00 -7.847862e-01 5.809120e-02 -6.170380e-01 5.910283e+01 +-6.197251e-01 3.451389e-02 7.840597e-01 1.080659e+02 7.043828e-02 9.974467e-01 1.176772e-02 -5.438101e+00 -7.816516e-01 6.252055e-02 -6.205738e-01 5.867499e+01 +-6.244219e-01 2.769098e-02 7.805963e-01 1.085895e+02 6.885058e-02 9.974326e-01 1.969253e-02 -5.444140e+00 -7.780468e-01 6.604094e-02 -6.247253e-01 5.824739e+01 +-6.295767e-01 2.597734e-02 7.765040e-01 1.091088e+02 6.580914e-02 9.976321e-01 1.998194e-02 -5.447240e+00 -7.741462e-01 6.368121e-02 -6.297954e-01 5.782387e+01 +-6.335674e-01 2.932711e-02 7.731315e-01 1.096210e+02 6.433075e-02 9.978178e-01 1.486778e-02 -5.443059e+00 -7.710083e-01 5.915585e-02 -6.340715e-01 5.740047e+01 +-6.364415e-01 3.321850e-02 7.706094e-01 1.101347e+02 6.322953e-02 9.979566e-01 9.202148e-03 -5.438721e+00 -7.687290e-01 5.458189e-02 -6.372413e-01 5.697052e+01 +-6.387524e-01 3.424343e-02 7.686500e-01 1.106568e+02 6.092352e-02 9.981234e-01 6.161273e-03 -5.438021e+00 -7.669965e-01 5.076438e-02 -6.396399e-01 5.653321e+01 +-6.404581e-01 3.276151e-02 7.672941e-01 1.111840e+02 5.830311e-02 9.982806e-01 6.041361e-03 -5.441619e+00 -7.657768e-01 4.860486e-02 -6.412670e-01 5.609051e+01 +-6.419500e-01 3.244187e-02 7.660599e-01 1.117175e+02 5.696712e-02 9.983611e-01 5.458226e-03 -5.449228e+00 -7.646273e-01 4.714412e-02 -6.427460e-01 5.563752e+01 +-6.427054e-01 3.282606e-02 7.654099e-01 1.122550e+02 5.569933e-02 9.984398e-01 3.950048e-03 -5.453527e+00 -7.640860e-01 4.517153e-02 -6.435309e-01 5.518251e+01 +-6.422485e-01 3.355497e-02 7.657617e-01 1.127974e+02 5.725170e-02 9.983506e-01 4.270491e-03 -5.457903e+00 -7.643553e-01 4.658386e-02 -6.431102e-01 5.471893e+01 +-6.411919e-01 2.963790e-02 7.668080e-01 1.133534e+02 5.816615e-02 9.982563e-01 1.005393e-02 -5.460142e+00 -7.651729e-01 5.104876e-02 -6.417977e-01 5.424711e+01 +-6.381135e-01 2.273562e-02 7.696066e-01 1.139193e+02 5.729589e-02 9.981946e-01 1.801790e-02 -5.461816e+00 -7.678075e-01 5.559275e-02 -6.382641e-01 5.377514e+01 +-6.327678e-01 2.082520e-02 7.740616e-01 1.144950e+02 5.919078e-02 9.980143e-01 2.153597e-02 -5.458762e+00 -7.720760e-01 5.944456e-02 -6.327439e-01 5.330169e+01 +-6.262972e-01 1.863611e-02 7.793616e-01 1.150778e+02 5.845864e-02 9.980222e-01 2.311279e-02 -5.455029e+00 -7.773895e-01 6.003588e-02 -6.261479e-01 5.283118e+01 +-6.191735e-01 2.178062e-02 7.849521e-01 1.156689e+02 5.728985e-02 9.982043e-01 1.749258e-02 -5.448047e+00 -7.831615e-01 5.580072e-02 -6.193095e-01 5.236680e+01 +-6.125545e-01 1.836904e-02 7.902149e-01 1.162817e+02 5.288585e-02 9.984421e-01 1.778634e-02 -5.434950e+00 -7.886571e-01 5.268628e-02 -6.125716e-01 5.190196e+01 +-6.060780e-01 1.450264e-02 7.952731e-01 1.169042e+02 4.672667e-02 9.987562e-01 1.739704e-02 -5.427523e+00 -7.940315e-01 4.770441e-02 -6.060017e-01 5.143942e+01 +-6.007378e-01 9.456598e-03 7.993903e-01 1.175404e+02 4.005683e-02 9.990301e-01 1.828420e-02 -5.429666e+00 -7.984420e-01 4.300504e-02 -6.005338e-01 5.097277e+01 +-5.971841e-01 9.766200e-03 8.020448e-01 1.181849e+02 3.129052e-02 9.994484e-01 1.112828e-02 -5.428109e+00 -8.014936e-01 3.174202e-02 -5.971602e-01 5.051552e+01 +-5.950455e-01 9.997867e-03 8.036298e-01 1.188368e+02 2.145527e-02 9.997638e-01 3.448540e-03 -5.424749e+00 -8.034055e-01 1.929413e-02 -5.951195e-01 5.005485e+01 +-5.929657e-01 7.668099e-03 8.051912e-01 1.195011e+02 1.153652e-02 9.999329e-01 -1.026877e-03 -5.427672e+00 -8.051451e-01 8.680197e-03 -5.930143e-01 4.958858e+01 +-5.911730e-01 7.255966e-03 8.065122e-01 1.201732e+02 1.151324e-02 9.999335e-01 -5.569393e-04 -5.435032e+00 -8.064626e-01 8.956314e-03 -5.912172e-01 4.910054e+01 +-5.891582e-01 5.830784e-03 8.079967e-01 1.208536e+02 1.289470e-02 9.999144e-01 2.186549e-03 -5.442470e+00 -8.079148e-01 1.170709e-02 -5.891829e-01 4.860209e+01 +-5.880861e-01 2.111739e-03 8.087956e-01 1.215468e+02 1.094391e-02 9.999258e-01 5.346679e-03 -5.448708e+00 -8.087243e-01 1.199569e-02 -5.880655e-01 4.810172e+01 +-5.873617e-01 6.297722e-04 8.093244e-01 1.222422e+02 9.644464e-03 9.999341e-01 6.221301e-03 -5.453884e+00 -8.092671e-01 1.145965e-02 -5.873290e-01 4.759932e+01 +-5.872525e-01 4.395187e-03 8.093919e-01 1.229380e+02 1.364042e-02 9.998970e-01 4.467093e-03 -5.457842e+00 -8.092889e-01 1.366375e-02 -5.872519e-01 4.708370e+01 +-5.887474e-01 8.776894e-03 8.082695e-01 1.236430e+02 1.626387e-02 9.998672e-01 9.892398e-04 -5.464293e+00 -8.081534e-01 1.372799e-02 -5.888120e-01 4.656055e+01 +-5.907008e-01 6.821827e-03 8.068619e-01 1.243646e+02 1.476423e-02 9.998882e-01 2.355008e-03 -5.474036e+00 -8.067556e-01 1.330379e-02 -5.907354e-01 4.602841e+01 +-5.918372e-01 5.311517e-03 8.060401e-01 1.250927e+02 1.606406e-02 9.998574e-01 5.206365e-03 -5.480393e+00 -8.058974e-01 1.602959e-02 -5.918381e-01 4.548530e+01 +-5.930751e-01 3.112271e-03 8.051412e-01 1.258296e+02 1.808709e-02 9.997917e-01 9.458428e-03 -5.486769e+00 -8.049440e-01 2.017221e-02 -5.930078e-01 4.493110e+01 +-5.943485e-01 2.346666e-03 8.042042e-01 1.265762e+02 1.555241e-02 9.998422e-01 8.576488e-03 -5.488875e+00 -8.040572e-01 1.760473e-02 -5.942912e-01 4.437813e+01 +-5.962034e-01 3.975874e-04 8.028334e-01 1.273300e+02 1.082895e-02 9.999129e-01 7.546639e-03 -5.493653e+00 -8.027604e-01 1.319317e-02 -5.961557e-01 4.382078e+01 +-5.974831e-01 4.260870e-04 8.018814e-01 1.280916e+02 1.043333e-02 9.999193e-01 7.242565e-03 -5.497699e+00 -8.018136e-01 1.269360e-02 -5.974393e-01 4.325051e+01 +-5.990944e-01 -1.270129e-03 8.006775e-01 1.288568e+02 1.105093e-02 9.998904e-01 9.854817e-03 -5.501943e+00 -8.006022e-01 1.475219e-02 -5.990146e-01 4.267077e+01 +-6.005203e-01 -7.926374e-03 7.995703e-01 1.296376e+02 7.978514e-03 9.998417e-01 1.590401e-02 -5.504398e+00 -7.995697e-01 1.593006e-02 -6.003619e-01 4.208783e+01 +-6.018413e-01 -1.437867e-02 7.984863e-01 1.304148e+02 6.820256e-03 9.997089e-01 2.314277e-02 -5.504810e+00 -7.985866e-01 1.937415e-02 -6.015679e-01 4.150532e+01 +-6.020677e-01 -2.036483e-02 7.981853e-01 1.311944e+02 4.375011e-03 9.995755e-01 2.880313e-02 -5.500901e+00 -7.984331e-01 2.083350e-02 -6.017230e-01 4.092278e+01 +-6.026707e-01 -1.924382e-02 7.977580e-01 1.319671e+02 1.043889e-03 9.996893e-01 2.490349e-02 -5.496770e+00 -7.979893e-01 1.584137e-02 -6.024633e-01 4.034476e+01 +-6.025785e-01 -1.705859e-02 7.978773e-01 1.327406e+02 -2.998241e-03 9.998128e-01 1.911160e-02 -5.491393e+00 -7.980540e-01 9.124008e-03 -6.025168e-01 3.976902e+01 +-6.017541e-01 -1.632980e-02 7.985145e-01 1.335180e+02 -8.097235e-03 9.998643e-01 1.434543e-02 -5.486478e+00 -7.986403e-01 2.166657e-03 -6.018046e-01 3.919400e+01 +-6.000987e-01 -1.774791e-02 7.997291e-01 1.342979e+02 -8.296370e-03 9.998381e-01 1.596339e-02 -5.490212e+00 -7.998829e-01 2.944759e-03 -6.001488e-01 3.860985e+01 +-5.979382e-01 -1.681949e-02 8.013658e-01 1.350764e+02 -5.643891e-03 9.998434e-01 1.677405e-02 -5.495403e+00 -8.015223e-01 5.507022e-03 -5.979394e-01 3.802133e+01 +-5.959977e-01 -1.194510e-02 8.028973e-01 1.358480e+02 4.140507e-03 9.998303e-01 1.794850e-02 -5.497469e+00 -8.029755e-01 1.402166e-02 -5.958470e-01 3.743039e+01 +-5.917640e-01 -7.285497e-03 8.060784e-01 1.366219e+02 8.914666e-03 9.998388e-01 1.558123e-02 -5.500053e+00 -8.060620e-01 1.640633e-02 -5.916036e-01 3.684905e+01 +-5.879279e-01 -1.979461e-03 8.089109e-01 1.373969e+02 1.512022e-02 9.997954e-01 1.343615e-02 -5.505042e+00 -8.087720e-01 2.013039e-02 -5.877776e-01 3.627032e+01 +-5.847057e-01 4.205512e-03 8.112346e-01 1.381660e+02 2.525042e-02 9.995964e-01 1.301750e-02 -5.511037e+00 -8.108524e-01 2.809542e-02 -5.845758e-01 3.569148e+01 +-5.837786e-01 3.292868e-03 8.119063e-01 1.389499e+02 2.325411e-02 9.996493e-01 1.266591e-02 -5.516939e+00 -8.115798e-01 2.627423e-02 -5.836504e-01 3.513111e+01 +-5.848985e-01 -1.504781e-04 8.111065e-01 1.397334e+02 2.041388e-02 9.996805e-01 1.490615e-02 -5.518711e+00 -8.108495e-01 2.527641e-02 -5.847085e-01 3.457697e+01 +-5.859899e-01 -6.414322e-03 8.102930e-01 1.405139e+02 1.785298e-02 9.996237e-01 2.082403e-02 -5.515813e+00 -8.101217e-01 2.666881e-02 -5.856548e-01 3.402156e+01 +-5.873445e-01 -1.306549e-02 8.092316e-01 1.412935e+02 1.129582e-02 9.996399e-01 2.433829e-02 -5.517039e+00 -8.092582e-01 2.343588e-02 -5.869854e-01 3.346473e+01 +-5.891969e-01 -1.254556e-02 8.078921e-01 1.420627e+02 1.041821e-02 9.996783e-01 2.312177e-02 -5.515589e+00 -8.079223e-01 2.204006e-02 -5.888766e-01 3.290818e+01 +-5.908730e-01 -1.448276e-02 8.066347e-01 1.428327e+02 7.467858e-03 9.996978e-01 2.341944e-02 -5.512398e+00 -8.067300e-01 1.986174e-02 -5.905862e-01 3.234819e+01 +-5.923399e-01 -1.802965e-02 8.054865e-01 1.436039e+02 -5.490664e-04 9.997584e-01 2.197437e-02 -5.509807e+00 -8.056880e-01 1.257402e-02 -5.922066e-01 3.179564e+01 +-5.945166e-01 -1.430203e-02 8.039562e-01 1.443637e+02 2.312001e-03 9.998072e-01 1.949583e-02 -5.515093e+00 -8.040800e-01 1.344934e-02 -5.943689e-01 3.123472e+01 +-5.956829e-01 -9.967938e-03 8.031579e-01 1.451188e+02 1.589264e-03 9.999064e-01 1.358848e-02 -5.521195e+00 -8.032181e-01 9.370852e-03 -5.956112e-01 3.067549e+01 +-5.980831e-01 -6.236022e-03 8.014099e-01 1.458718e+02 -1.778438e-03 9.999776e-01 6.453903e-03 -5.530850e+00 -8.014321e-01 2.434710e-03 -5.980807e-01 3.012158e+01 +-5.993217e-01 -3.351106e-03 8.005013e-01 1.466232e+02 3.280699e-03 9.999725e-01 6.642339e-03 -5.542701e+00 -8.005016e-01 6.607098e-03 -5.992942e-01 2.955170e+01 +-5.994469e-01 -8.527358e-03 8.003691e-01 1.473785e+02 5.386560e-03 9.998776e-01 1.468730e-02 -5.549202e+00 -8.003964e-01 1.311549e-02 -5.993276e-01 2.898277e+01 +-5.998303e-01 -1.274602e-02 8.000257e-01 1.481333e+02 3.900797e-03 9.998146e-01 1.885373e-02 -5.558442e+00 -8.001177e-01 1.442977e-02 -5.996694e-01 2.841820e+01 +-5.995356e-01 -9.377041e-03 8.002932e-01 1.488767e+02 8.878261e-03 9.997919e-01 1.836567e-02 -5.563610e+00 -8.002988e-01 1.811608e-02 -5.993276e-01 2.785319e+01 +-5.989863e-01 -6.029893e-03 8.007366e-01 1.496167e+02 7.508305e-03 9.998854e-01 1.314610e-02 -5.566991e+00 -8.007241e-01 1.388651e-02 -5.988723e-01 2.729900e+01 +-5.987928e-01 -3.264638e-03 8.008973e-01 1.503476e+02 6.496807e-03 9.999390e-01 8.933322e-03 -5.568938e+00 -8.008776e-01 1.055248e-02 -5.987350e-01 2.675099e+01 +-5.978793e-01 -3.403618e-03 8.015789e-01 1.510728e+02 3.822013e-03 9.999675e-01 7.096748e-03 -5.577653e+00 -8.015770e-01 7.306640e-03 -5.978468e-01 2.620853e+01 +-5.980526e-01 -1.036033e-02 8.013899e-01 1.517983e+02 -7.254328e-04 9.999230e-01 1.238558e-02 -5.586083e+00 -8.014565e-01 6.825871e-03 -5.980140e-01 2.567277e+01 +-5.985356e-01 -1.248056e-02 8.009990e-01 1.525061e+02 2.474445e-03 9.998450e-01 1.742781e-02 -5.591898e+00 -8.010924e-01 1.241319e-02 -5.984119e-01 2.513714e+01 +-5.994424e-01 -1.445651e-02 8.002874e-01 1.532005e+02 4.174724e-03 9.997668e-01 2.118694e-02 -5.599003e+00 -8.004070e-01 1.604133e-02 -5.992422e-01 2.461232e+01 +-6.014541e-01 -6.338801e-03 7.988822e-01 1.538709e+02 5.899078e-03 9.999060e-01 1.237507e-02 -5.607533e+00 -7.988855e-01 1.215570e-02 -6.013602e-01 2.410306e+01 +-6.037688e-01 5.012884e-03 7.971438e-01 1.545212e+02 7.932360e-03 9.999685e-01 -2.802797e-04 -5.616276e+00 -7.971200e-01 6.154003e-03 -6.037895e-01 2.360351e+01 +-6.069117e-01 9.582125e-03 7.947115e-01 1.551614e+02 1.295244e-02 9.999137e-01 -2.164707e-03 -5.627315e+00 -7.946637e-01 8.979666e-03 -6.069834e-01 2.309991e+01 +-6.110028e-01 3.254121e-03 7.916218e-01 1.557951e+02 1.530337e-02 9.998532e-01 7.701600e-03 -5.641768e+00 -7.914805e-01 1.682018e-02 -6.109629e-01 2.259936e+01 +-6.155539e-01 -5.603978e-03 7.880749e-01 1.564098e+02 1.801482e-02 9.996134e-01 2.117933e-02 -5.661844e+00 -7.878888e-01 2.723403e-02 -6.152149e-01 2.210430e+01 +-6.191710e-01 -1.354336e-02 7.851394e-01 1.570048e+02 1.505868e-02 9.994626e-01 2.911581e-02 -5.675327e+00 -7.851117e-01 2.985083e-02 -6.186343e-01 2.163112e+01 +-6.232684e-01 -7.770600e-03 7.819694e-01 1.575671e+02 1.680231e-02 9.995867e-01 2.332538e-02 -5.683060e+00 -7.818274e-01 2.767686e-02 -6.228802e-01 2.117512e+01 +-6.257394e-01 5.539719e-04 7.800320e-01 1.581026e+02 1.947670e-02 9.996990e-01 1.491416e-02 -5.694254e+00 -7.797890e-01 2.452482e-02 -6.255618e-01 2.072955e+01 +-6.278879e-01 1.022796e-02 7.782366e-01 1.586182e+02 2.218869e-02 9.997424e-01 4.762919e-03 -5.705713e+00 -7.779874e-01 2.025863e-02 -6.279531e-01 2.030073e+01 +-6.293214e-01 1.393136e-02 7.770203e-01 1.591201e+02 2.631197e-02 9.996480e-01 3.387581e-03 -5.720431e+00 -7.766996e-01 2.257680e-02 -6.294664e-01 1.988174e+01 +-6.265234e-01 1.604992e-02 7.792374e-01 1.596057e+02 3.296437e-02 9.994390e-01 5.918632e-03 -5.737221e+00 -7.787052e-01 2.939522e-02 -6.267009e-01 1.947009e+01 +-6.207529e-01 1.914330e-02 7.837725e-01 1.600792e+02 4.204697e-02 9.990760e-01 8.899472e-03 -5.755764e+00 -7.828779e-01 3.847963e-02 -6.209842e-01 1.906944e+01 +-6.088696e-01 2.106548e-02 7.929906e-01 1.605555e+02 4.829897e-02 9.987772e-01 1.055251e-02 -5.769695e+00 -7.917986e-01 4.472572e-02 -6.091425e-01 1.869011e+01 +-5.911877e-01 2.650757e-02 8.060983e-01 1.610344e+02 5.676595e-02 9.983487e-01 8.802305e-03 -5.781742e+00 -8.045339e-01 5.096274e-02 -5.917161e-01 1.832864e+01 +-5.676195e-01 3.275383e-02 8.226393e-01 1.615121e+02 6.590899e-02 9.978091e-01 5.748746e-03 -5.794799e+00 -8.206486e-01 5.748241e-02 -5.685346e-01 1.798182e+01 +-5.375079e-01 3.614787e-02 8.424836e-01 1.620108e+02 7.232769e-02 9.973753e-01 3.351643e-03 -5.806721e+00 -8.401511e-01 6.273641e-02 -5.387116e-01 1.766252e+01 +-5.028576e-01 3.473612e-02 8.636710e-01 1.625275e+02 7.546731e-02 9.971409e-01 3.835366e-03 -5.819248e+00 -8.610684e-01 6.710756e-02 -5.040413e-01 1.736993e+01 +-4.658409e-01 3.012666e-02 8.843555e-01 1.630425e+02 7.073727e-02 9.974896e-01 3.280664e-03 -5.828843e+00 -8.820365e-01 6.408515e-02 -4.668025e-01 1.711344e+01 +-4.266461e-01 2.851108e-02 9.039692e-01 1.635796e+02 6.671331e-02 9.977722e-01 1.703684e-05 -5.844660e+00 -9.019547e-01 6.031403e-02 -4.275977e-01 1.689122e+01 +-3.873896e-01 3.038864e-02 9.214152e-01 1.641020e+02 6.510685e-02 9.978629e-01 -5.537126e-03 -5.863518e+00 -9.196143e-01 5.784540e-02 -3.885401e-01 1.669004e+01 +-3.474703e-01 3.535677e-02 9.370242e-01 1.646402e+02 6.675743e-02 9.976859e-01 -1.289053e-02 -5.887082e+00 -9.353116e-01 5.807424e-02 -3.490266e-01 1.651101e+01 +-3.065741e-01 4.045207e-02 9.509869e-01 1.651817e+02 6.635851e-02 9.975739e-01 -2.104145e-02 -5.910052e+00 -9.495308e-01 5.665529e-02 -3.085146e-01 1.635980e+01 +-2.657549e-01 4.126525e-02 9.631571e-01 1.657257e+02 6.443960e-02 9.976094e-01 -2.496111e-02 -5.932357e+00 -9.618845e-01 5.543191e-02 -2.677787e-01 1.623124e+01 +-2.234930e-01 3.892703e-02 9.739279e-01 1.663020e+02 6.197244e-02 9.977480e-01 -2.565792e-02 -5.954339e+00 -9.727334e-01 5.462231e-02 -2.254021e-01 1.612414e+01 +-1.823750e-01 3.437639e-02 9.826279e-01 1.668844e+02 5.980630e-02 9.979259e-01 -2.381158e-02 -5.978445e+00 -9.814084e-01 5.442469e-02 -1.840526e-01 1.603917e+01 +-1.450693e-01 2.702584e-02 9.890524e-01 1.674654e+02 5.321185e-02 9.983933e-01 -1.947624e-02 -6.003373e+00 -9.879895e-01 4.980388e-02 -1.462743e-01 1.598023e+01 +-1.119875e-01 1.966634e-02 9.935150e-01 1.680665e+02 4.742017e-02 9.987708e-01 -1.442526e-02 -6.028742e+00 -9.925775e-01 4.549719e-02 -1.127824e-01 1.594135e+01 +-8.204748e-02 1.775142e-02 9.964703e-01 1.686674e+02 4.313046e-02 9.989679e-01 -1.424464e-02 -6.043175e+00 -9.956947e-01 4.180947e-02 -8.272841e-02 1.592211e+01 +-5.689049e-02 1.579990e-02 9.982554e-01 1.692753e+02 3.782040e-02 9.991912e-01 -1.365934e-02 -6.055693e+00 -9.976638e-01 3.697732e-02 -5.744202e-02 1.591281e+01 +-3.924801e-02 1.137962e-02 9.991647e-01 1.698988e+02 2.843079e-02 9.995430e-01 -1.026715e-02 -6.074099e+00 -9.988249e-01 2.800406e-02 -3.955360e-02 1.592521e+01 +-2.594042e-02 9.355596e-03 9.996197e-01 1.705258e+02 1.604419e-02 9.998313e-01 -8.941231e-03 -6.093598e+00 -9.995347e-01 1.580614e-02 -2.608614e-02 1.594180e+01 +-1.793801e-02 1.152393e-02 9.997727e-01 1.711572e+02 9.455914e-03 9.998908e-01 -1.135564e-02 -6.110564e+00 -9.997943e-01 9.250062e-03 -1.804502e-02 1.595774e+01 +-1.367089e-02 1.412014e-02 9.998069e-01 1.717940e+02 2.975861e-03 9.998964e-01 -1.408072e-02 -6.127817e+00 -9.999021e-01 2.782786e-03 -1.371149e-02 1.596664e+01 +-1.235513e-02 1.547868e-02 9.998039e-01 1.724402e+02 7.608754e-04 9.998800e-01 -1.547047e-02 -6.147256e+00 -9.999233e-01 5.695831e-04 -1.236542e-02 1.597113e+01 +-1.364737e-02 1.461402e-02 9.998001e-01 1.730987e+02 7.518024e-04 9.998930e-01 -1.460513e-02 -6.165077e+00 -9.999065e-01 5.523269e-04 -1.365690e-02 1.597268e+01 +-1.750263e-02 1.291904e-02 9.997634e-01 1.737678e+02 4.789400e-04 9.999165e-01 -1.291264e-02 -6.181189e+00 -9.998467e-01 2.528181e-04 -1.750736e-02 1.596818e+01 +-2.219561e-02 8.715634e-03 9.997157e-01 1.744440e+02 2.655289e-05 9.999620e-01 -8.717198e-03 -6.197603e+00 -9.997536e-01 -1.669415e-04 -2.219499e-02 1.595901e+01 +-2.809249e-02 8.390768e-03 9.995701e-01 1.751205e+02 -5.885110e-04 9.999644e-01 -8.410624e-03 -6.220298e+00 -9.996051e-01 -8.245365e-04 -2.808654e-02 1.594518e+01 +-3.379540e-02 1.624204e-02 9.992968e-01 1.757972e+02 -1.309588e-03 9.998663e-01 -1.629559e-02 -6.244754e+00 -9.994279e-01 -1.859386e-03 -3.376960e-02 1.592832e+01 +-4.035256e-02 2.582447e-02 9.988518e-01 1.764770e+02 -1.538470e-03 9.996631e-01 -2.590761e-02 -6.267177e+00 -9.991843e-01 -2.582145e-03 -4.029923e-02 1.590335e+01 +-4.724558e-02 3.243961e-02 9.983564e-01 1.771672e+02 -2.663024e-04 9.994721e-01 -3.248847e-02 -6.287121e+00 -9.988832e-01 -1.800804e-03 -4.721200e-02 1.587215e+01 +-5.327461e-02 2.996182e-02 9.981303e-01 1.778705e+02 2.150486e-04 9.995501e-01 -2.999297e-02 -6.309818e+00 -9.985798e-01 -1.383220e-03 -5.325708e-02 1.583326e+01 +-6.070740e-02 2.283224e-02 9.978945e-01 1.785853e+02 -1.663789e-03 9.997346e-01 -2.297556e-02 -6.342144e+00 -9.981542e-01 -3.055075e-03 -6.065329e-02 1.579677e+01 +-6.810493e-02 1.526560e-02 9.975614e-01 1.793053e+02 -6.842321e-03 9.998522e-01 -1.576780e-02 -6.377428e+00 -9.976547e-01 -7.899502e-03 -6.799041e-02 1.575628e+01 +-7.440709e-02 1.435313e-02 9.971247e-01 1.800295e+02 -1.031632e-02 9.998318e-01 -1.516192e-02 -6.404246e+00 -9.971745e-01 -1.141481e-02 -7.424649e-02 1.570949e+01 +-7.963810e-02 1.797420e-02 9.966618e-01 1.807506e+02 -1.249555e-02 9.997408e-01 -1.902819e-02 -6.426161e+00 -9.967455e-01 -1.396921e-02 -7.939286e-02 1.565927e+01 +-8.314285e-02 1.972672e-02 9.963424e-01 1.814770e+02 -1.101138e-02 9.997248e-01 -2.071258e-02 -6.448627e+00 -9.964768e-01 -1.269321e-02 -8.290275e-02 1.560401e+01 +-8.512564e-02 2.288512e-02 9.961074e-01 1.822109e+02 -2.261324e-03 9.997292e-01 -2.316159e-02 -6.474966e+00 -9.963676e-01 -4.224169e-03 -8.505082e-02 1.553203e+01 +-8.627319e-02 2.204272e-02 9.960277e-01 1.829538e+02 1.488543e-03 9.997569e-01 -2.199633e-02 -6.499988e+00 -9.962704e-01 -4.150668e-04 -8.628502e-02 1.546437e+01 +-8.681398e-02 1.964440e-02 9.960309e-01 1.837037e+02 -3.503155e-03 9.997933e-01 -2.002395e-02 -6.527412e+00 -9.962183e-01 -5.227611e-03 -8.672722e-02 1.541202e+01 +-8.522385e-02 1.596745e-02 9.962339e-01 1.844609e+02 -9.026224e-03 9.998182e-01 -1.679706e-02 -6.552659e+00 -9.963209e-01 -1.042374e-02 -8.506422e-02 1.536267e+01 +-8.276166e-02 1.488265e-02 9.964583e-01 1.852190e+02 -6.197950e-03 9.998614e-01 -1.544826e-02 -6.574898e+00 -9.965501e-01 -7.454524e-03 -8.265794e-02 1.530234e+01 +-8.118500e-02 1.556693e-02 9.965775e-01 1.859807e+02 -1.459851e-03 9.998751e-01 -1.573737e-02 -6.598723e+00 -9.966979e-01 -2.732496e-03 -8.115213e-02 1.523813e+01 +-8.100125e-02 1.426118e-02 9.966120e-01 1.867415e+02 -3.763366e-03 9.998861e-01 -1.461391e-02 -6.624110e+00 -9.967069e-01 -4.934362e-03 -8.093835e-02 1.518121e+01 +-8.097337e-02 1.207882e-02 9.966431e-01 1.875112e+02 -7.506419e-03 9.998908e-01 -1.272806e-02 -6.642920e+00 -9.966880e-01 -8.511856e-03 -8.087385e-02 1.513049e+01 +-7.958189e-02 8.273964e-03 9.967940e-01 1.882805e+02 -1.042908e-02 9.999039e-01 -9.132419e-03 -6.660596e+00 -9.967737e-01 -1.112242e-02 -7.948794e-02 1.507299e+01 +-7.805432e-02 5.314473e-03 9.969350e-01 1.890477e+02 -1.125534e-02 9.999173e-01 -6.211606e-03 -6.678413e+00 -9.968855e-01 -1.170568e-02 -7.798804e-02 1.501701e+01 +-7.733300e-02 7.428141e-03 9.969777e-01 1.898139e+02 -1.021435e-02 9.999138e-01 -8.242325e-03 -6.696543e+00 -9.969530e-01 -1.082089e-02 -7.725046e-02 1.495921e+01 +-7.623648e-02 1.212350e-02 9.970161e-01 1.905775e+02 -5.266648e-03 9.999072e-01 -1.256137e-02 -6.715856e+00 -9.970758e-01 -6.208570e-03 -7.616555e-02 1.489680e+01 +-7.637619e-02 1.621743e-02 9.969472e-01 1.913435e+02 -5.613517e-03 9.998449e-01 -1.669463e-02 -6.731426e+00 -9.970632e-01 -6.871454e-03 -7.627330e-02 1.483270e+01 +-7.778190e-02 1.899570e-02 9.967894e-01 1.921137e+02 -1.021884e-02 9.997507e-01 -1.984954e-02 -6.744713e+00 -9.969180e-01 -1.172997e-02 -7.756839e-02 1.477624e+01 +-7.935577e-02 1.536882e-02 9.967279e-01 1.928943e+02 -1.118727e-02 9.998044e-01 -1.630696e-02 -6.763373e+00 -9.967835e-01 -1.244472e-02 -7.916831e-02 1.471461e+01 +-8.018055e-02 1.214262e-02 9.967064e-01 1.936769e+02 -8.005828e-03 9.998857e-01 -1.282539e-02 -6.782223e+00 -9.967482e-01 -9.007809e-03 -8.007417e-02 1.464361e+01 +-8.146299e-02 1.380160e-02 9.965808e-01 1.944610e+02 -1.005176e-02 9.998419e-01 -1.466842e-02 -6.800695e+00 -9.966256e-01 -1.121233e-02 -8.131137e-02 1.457804e+01 +-8.427518e-02 1.955703e-02 9.962506e-01 1.952442e+02 -1.375677e-02 9.996892e-01 -2.078826e-02 -6.821679e+00 -9.963475e-01 -1.545713e-02 -8.397994e-02 1.451022e+01 +-8.680915e-02 2.338049e-02 9.959506e-01 1.960363e+02 -1.361029e-02 9.996034e-01 -2.465255e-02 -6.843719e+00 -9.961319e-01 -1.569525e-02 -8.645650e-02 1.443769e+01 +-9.004595e-02 2.556518e-02 9.956095e-01 1.968309e+02 -1.423900e-02 9.995352e-01 -2.695382e-02 -6.870881e+00 -9.958358e-01 -1.660357e-02 -8.964007e-02 1.436297e+01 +-9.329235e-02 2.640049e-02 9.952887e-01 1.976335e+02 -1.245398e-02 9.995392e-01 -2.768061e-02 -6.899957e+00 -9.955608e-01 -1.497769e-02 -9.292057e-02 1.428382e+01 +-9.461977e-02 2.241014e-02 9.952612e-01 1.984476e+02 -1.305399e-02 9.996327e-01 -2.374962e-02 -6.926056e+00 -9.954279e-01 -1.523931e-02 -9.429247e-02 1.420270e+01 +-9.637709e-02 2.395552e-02 9.950566e-01 1.992633e+02 -7.150833e-03 9.996678e-01 -2.475914e-02 -6.951110e+00 -9.953192e-01 -9.501699e-03 -9.617377e-02 1.411607e+01 +-9.653529e-02 2.113942e-02 9.951051e-01 2.000900e+02 -3.384296e-03 9.997617e-01 -2.156666e-02 -6.975899e+00 -9.953238e-01 -5.449676e-03 -9.644074e-02 1.403013e+01 +-9.662727e-02 1.657852e-02 9.951826e-01 2.009222e+02 -3.354450e-03 9.998501e-01 -1.698198e-02 -7.003243e+00 -9.953149e-01 -4.979215e-03 -9.655717e-02 1.395074e+01 +-9.703310e-02 1.640242e-02 9.951460e-01 2.017552e+02 4.259526e-04 9.998648e-01 -1.643867e-02 -7.033032e+00 -9.952810e-01 -1.171213e-03 -9.702695e-02 1.386980e+01 +-9.647752e-02 1.548902e-02 9.952147e-01 2.025921e+02 2.229680e-03 9.998797e-01 -1.534548e-02 -7.057848e+00 -9.953326e-01 7.385126e-04 -9.650044e-02 1.378530e+01 +-9.616667e-02 1.696433e-02 9.952207e-01 2.034268e+02 5.089313e-03 9.998500e-01 -1.655148e-02 -7.080672e+00 -9.953522e-01 3.473285e-03 -9.623857e-02 1.370436e+01 +-9.489924e-02 1.833236e-02 9.953181e-01 2.042626e+02 1.170632e-02 9.997818e-01 -1.729844e-02 -7.105891e+00 -9.954180e-01 1.000990e-02 -9.509313e-02 1.361782e+01 +-9.292034e-02 1.850693e-02 9.955016e-01 2.051049e+02 1.433271e-02 9.997485e-01 -1.724807e-02 -7.133726e+00 -9.955703e-01 1.266553e-02 -9.316222e-02 1.353411e+01 +-9.073915e-02 1.826601e-02 9.957072e-01 2.059506e+02 9.394459e-03 9.998030e-01 -1.748503e-02 -7.160891e+00 -9.958303e-01 7.767548e-03 -9.089286e-02 1.345887e+01 +-8.754861e-02 1.638025e-02 9.960256e-01 2.067960e+02 5.632082e-03 9.998569e-01 -1.594822e-02 -7.183536e+00 -9.961443e-01 4.213450e-03 -8.762834e-02 1.338910e+01 +-8.477974e-02 1.398360e-02 9.963016e-01 2.076407e+02 8.420279e-03 9.998758e-01 -1.331725e-02 -7.212206e+00 -9.963641e-01 7.260100e-03 -8.488695e-02 1.331007e+01 +-8.234073e-02 1.993588e-02 9.964048e-01 2.084765e+02 9.781573e-03 9.997679e-01 -1.919484e-02 -7.243658e+00 -9.965562e-01 8.165884e-03 -8.251661e-02 1.323858e+01 +-8.126266e-02 3.269127e-02 9.961565e-01 2.093057e+02 8.148951e-03 9.994503e-01 -3.213461e-02 -7.272696e+00 -9.966594e-01 5.506282e-03 -8.148438e-02 1.317348e+01 +-7.958072e-02 3.306522e-02 9.962799e-01 2.101489e+02 5.615453e-03 9.994487e-01 -3.272185e-02 -7.301560e+00 -9.968126e-01 2.990531e-03 -7.972252e-02 1.311109e+01 +-7.899809e-02 2.151984e-02 9.966425e-01 2.110003e+02 1.925666e-03 9.997684e-01 -2.143471e-02 -7.337463e+00 -9.968729e-01 2.258957e-04 -7.902123e-02 1.304697e+01 +-7.987383e-02 8.892020e-03 9.967653e-01 2.118545e+02 9.467885e-04 9.999604e-01 -8.844660e-03 -7.375526e+00 -9.968045e-01 2.372657e-04 -7.987908e-02 1.297973e+01 +-8.114280e-02 8.917724e-03 9.966626e-01 2.126973e+02 1.023606e-03 9.999602e-01 -8.863899e-03 -7.402686e+00 -9.967019e-01 3.009449e-04 -8.114869e-02 1.291574e+01 +-8.279248e-02 1.556640e-02 9.964453e-01 2.135357e+02 -1.949911e-03 9.998735e-01 -1.578197e-02 -7.424758e+00 -9.965649e-01 -3.249611e-03 -8.275165e-02 1.285506e+01 +-8.414544e-02 2.117115e-02 9.962286e-01 2.143760e+02 -9.954508e-03 9.997065e-01 -2.208587e-02 -7.447524e+00 -9.964037e-01 -1.177539e-02 -8.390999e-02 1.280054e+01 +-8.541943e-02 2.164057e-02 9.961101e-01 2.152247e+02 -1.272836e-02 9.996588e-01 -2.280917e-02 -7.474428e+00 -9.962637e-01 -1.462719e-02 -8.511483e-02 1.273783e+01 +-8.580104e-02 1.676606e-02 9.961712e-01 2.160829e+02 -9.461199e-03 9.997996e-01 -1.764203e-02 -7.501955e+00 -9.962673e-01 -1.093868e-02 -8.562521e-02 1.266143e+01 +-8.615260e-02 1.028798e-02 9.962289e-01 2.169447e+02 -7.685555e-03 9.999100e-01 -1.099063e-02 -7.527571e+00 -9.962523e-01 -8.603445e-03 -8.606577e-02 1.258792e+01 +-8.674103e-02 7.002636e-03 9.962063e-01 2.178080e+02 -5.114517e-03 9.999590e-01 -7.474348e-03 -7.551199e+00 -9.962177e-01 -5.743449e-03 -8.670164e-02 1.251318e+01 +-8.633150e-02 1.099684e-02 9.962058e-01 2.186649e+02 -9.504835e-04 9.999377e-01 -1.112041e-02 -7.577625e+00 -9.962660e-01 -1.906922e-03 -8.631566e-02 1.243313e+01 +-8.567454e-02 1.744821e-02 9.961704e-01 2.195233e+02 2.014139e-03 9.998476e-01 -1.733940e-02 -7.604253e+00 -9.963211e-01 5.208770e-04 -8.569661e-02 1.235733e+01 +-8.464285e-02 2.219382e-02 9.961642e-01 2.203895e+02 5.542556e-03 9.997469e-01 -2.180271e-02 -7.631751e+00 -9.963959e-01 3.675848e-03 -8.474443e-02 1.228270e+01 +-8.303465e-02 2.009378e-02 9.963441e-01 2.212664e+02 8.270822e-03 9.997761e-01 -1.947372e-02 -7.667763e+00 -9.965123e-01 6.623586e-03 -8.318225e-02 1.220917e+01 +-8.240877e-02 1.478314e-02 9.964890e-01 2.221519e+02 1.084376e-02 9.998441e-01 -1.393615e-02 -7.701483e+00 -9.965396e-01 9.657217e-03 -8.255621e-02 1.213701e+01 +-8.200145e-02 1.273098e-02 9.965509e-01 2.230375e+02 1.199619e-02 9.998586e-01 -1.178613e-02 -7.731282e+00 -9.965600e-01 1.098833e-02 -8.214256e-02 1.206855e+01 +-8.191883e-02 1.286426e-02 9.965560e-01 2.239226e+02 4.300428e-03 9.999119e-01 -1.255409e-02 -7.757379e+00 -9.966297e-01 3.257197e-03 -8.196693e-02 1.200953e+01 +-8.203990e-02 1.364394e-02 9.965357e-01 2.248091e+02 2.885113e-04 9.999065e-01 -1.366635e-02 -7.784350e+00 -9.966290e-01 -8.336770e-04 -8.203616e-02 1.194495e+01 +-8.237865e-02 1.245217e-02 9.965233e-01 2.256999e+02 -3.003953e-04 9.999216e-01 -1.251947e-02 -7.812128e+00 -9.966010e-01 -1.330691e-03 -8.236844e-02 1.187296e+01 +-8.397316e-02 1.294523e-02 9.963840e-01 2.265911e+02 -4.592499e-03 9.998999e-01 -1.337796e-02 -7.846308e+00 -9.964574e-01 -5.699284e-03 -8.390530e-02 1.180622e+01 +-8.595810e-02 1.318869e-02 9.962115e-01 2.274843e+02 -7.654405e-03 9.998741e-01 -1.389764e-02 -7.873427e+00 -9.962693e-01 -8.820022e-03 -8.584631e-02 1.173678e+01 +-8.790897e-02 1.154202e-02 9.960617e-01 2.283808e+02 -4.411111e-03 9.999185e-01 -1.197603e-02 -7.899172e+00 -9.961187e-01 -5.446541e-03 -8.785088e-02 1.165757e+01 +-8.977953e-02 7.229880e-03 9.959355e-01 2.292805e+02 -1.207309e-03 9.999721e-01 -7.368024e-03 -7.929607e+00 -9.959609e-01 -1.863903e-03 -8.976828e-02 1.157203e+01 +-9.091573e-02 1.203973e-02 9.957858e-01 2.301748e+02 -1.097474e-03 9.999251e-01 -1.218998e-02 -7.962599e+00 -9.958579e-01 -2.201114e-03 -9.089570e-02 1.149123e+01 +-9.237283e-02 1.924013e-02 9.955386e-01 2.310638e+02 5.431961e-03 9.998081e-01 -1.881863e-02 -7.987456e+00 -9.957096e-01 3.669393e-03 -9.245961e-02 1.140077e+01 +-9.294313e-02 2.204973e-02 9.954273e-01 2.319589e+02 8.431966e-03 9.997363e-01 -2.135789e-02 -8.014843e+00 -9.956357e-01 6.408335e-03 -9.310454e-02 1.131023e+01 +-9.467232e-02 1.504487e-02 9.953948e-01 2.328634e+02 2.149084e-03 9.998865e-01 -1.490836e-02 -8.047081e+00 -9.955061e-01 7.277748e-04 -9.469390e-02 1.123237e+01 +-9.673557e-02 4.960678e-03 9.952978e-01 2.337688e+02 -5.328830e-03 9.999706e-01 -5.501897e-03 -8.077315e+00 -9.952958e-01 -5.836004e-03 -9.670629e-02 1.115712e+01 +-9.808272e-02 1.244037e-03 9.951775e-01 2.346716e+02 -8.816435e-03 9.999589e-01 -2.118949e-03 -8.101966e+00 -9.951392e-01 -8.981752e-03 -9.806771e-02 1.107600e+01 +-1.004820e-01 4.490813e-03 9.949288e-01 2.355637e+02 -1.037558e-02 9.999307e-01 -5.561269e-03 -8.124246e+00 -9.948847e-01 -1.088177e-02 -1.004285e-01 1.099112e+01 +-1.007824e-01 1.044428e-02 9.948537e-01 2.364527e+02 -1.509232e-02 9.998138e-01 -1.202526e-02 -8.151328e+00 -9.947940e-01 -1.622658e-02 -1.006060e-01 1.090857e+01 +-1.006063e-01 1.590387e-02 9.947992e-01 2.373404e+02 -1.255094e-02 9.997724e-01 -1.725269e-02 -8.183767e+00 -9.948471e-01 -1.422139e-02 -1.003837e-01 1.081600e+01 +-1.000779e-01 2.197418e-02 9.947369e-01 2.382244e+02 -7.048972e-03 9.997153e-01 -2.279334e-02 -8.217037e+00 -9.949546e-01 -9.292985e-03 -9.989455e-02 1.071992e+01 +-9.946360e-02 1.936369e-02 9.948528e-01 2.391154e+02 -3.587847e-03 9.997971e-01 -1.981864e-02 -8.251307e+00 -9.950347e-01 -5.540615e-03 -9.937393e-02 1.062832e+01 +-9.764598e-02 1.441209e-02 9.951169e-01 2.400045e+02 -2.841663e-03 9.998870e-01 -1.476002e-02 -8.292030e+00 -9.952171e-01 -4.269046e-03 -9.759399e-02 1.054401e+01 +-9.480073e-02 1.355055e-02 9.954041e-01 2.408856e+02 -4.325245e-03 9.998923e-01 -1.402358e-02 -8.332096e+00 -9.954868e-01 -5.634814e-03 -9.473190e-02 1.046736e+01 +-9.288538e-02 2.030032e-02 9.954699e-01 2.417562e+02 -4.486150e-03 9.997734e-01 -2.080668e-02 -8.367849e+00 -9.956667e-01 -6.398466e-03 -9.277326e-02 1.039098e+01 +-9.023279e-02 2.560115e-02 9.955916e-01 2.426249e+02 -3.696055e-03 9.996540e-01 -2.604060e-02 -8.408269e+00 -9.959138e-01 -6.029480e-03 -9.010694e-02 1.031952e+01 +-8.840812e-02 2.071551e-02 9.958689e-01 2.435008e+02 -3.874415e-03 9.997690e-01 -2.114060e-02 -8.447662e+00 -9.960768e-01 -5.727412e-03 -8.830743e-02 1.024877e+01 +-8.667361e-02 1.130192e-02 9.961727e-01 2.443762e+02 -2.589973e-03 9.999297e-01 -1.156989e-02 -8.492051e+00 -9.962334e-01 -3.582867e-03 -8.663824e-02 1.017767e+01 +-8.457565e-02 1.231196e-02 9.963410e-01 2.452395e+02 -1.043194e-03 9.999220e-01 -1.244477e-02 -8.531326e+00 -9.964165e-01 -2.091905e-03 -8.455620e-02 1.010603e+01 +-8.283668e-02 2.100874e-02 9.963417e-01 2.460908e+02 -3.383793e-03 9.997661e-01 -2.136229e-02 -8.565326e+00 -9.965573e-01 -5.140998e-03 -8.274620e-02 1.004291e+01 +-8.105971e-02 2.764788e-02 9.963257e-01 2.469424e+02 -2.692794e-03 9.996054e-01 -2.795799e-02 -8.603928e+00 -9.967056e-01 -4.949169e-03 -8.095327e-02 9.977031e+00 +-7.926717e-02 2.404408e-02 9.965634e-01 2.477997e+02 -4.799469e-05 9.997090e-01 -2.412379e-02 -8.641954e+00 -9.968534e-01 -1.960058e-03 -7.924294e-02 9.910329e+00 +-7.837681e-02 1.542385e-02 9.968045e-01 2.486556e+02 -3.242125e-03 9.998711e-01 -1.572623e-02 -8.680654e+00 -9.969185e-01 -4.464340e-03 -7.831669e-02 9.850928e+00 +-7.663806e-02 1.042669e-02 9.970045e-01 2.495031e+02 -5.292416e-03 9.999270e-01 -1.086408e-02 -8.716152e+00 -9.970449e-01 -6.109167e-03 -7.657727e-02 9.796410e+00 +-7.410993e-02 1.215690e-02 9.971760e-01 2.503337e+02 -1.831420e-03 9.999223e-01 -1.232650e-02 -8.745963e+00 -9.972484e-01 -2.739767e-03 -7.408190e-02 9.735576e+00 +-7.168237e-02 1.527945e-02 9.973105e-01 2.511539e+02 3.741120e-03 9.998797e-01 -1.504993e-02 -8.776984e+00 -9.974205e-01 2.652240e-03 -7.173090e-02 9.672126e+00 +-6.969719e-02 1.716240e-02 9.974206e-01 2.519624e+02 4.065964e-03 9.998486e-01 -1.692007e-02 -8.813807e+00 -9.975599e-01 2.876191e-03 -6.975641e-02 9.616742e+00 +-6.828961e-02 1.703939e-02 9.975200e-01 2.527631e+02 2.461954e-03 9.998539e-01 -1.691072e-02 -8.849214e+00 -9.976625e-01 1.301018e-03 -6.832158e-02 9.565370e+00 +-6.695463e-02 1.364649e-02 9.976627e-01 2.535514e+02 2.856412e-03 9.999050e-01 -1.348547e-02 -8.883502e+00 -9.977519e-01 1.946818e-03 -6.698724e-02 9.508367e+00 +-6.664667e-02 6.915517e-03 9.977527e-01 2.543298e+02 3.260745e-03 9.999721e-01 -6.713099e-03 -8.915950e+00 -9.977713e-01 2.806007e-03 -6.666735e-02 9.452561e+00 +-6.703620e-02 2.066923e-03 9.977484e-01 2.550932e+02 4.985503e-04 9.999978e-01 -2.038092e-03 -8.949611e+00 -9.977504e-01 3.607984e-04 -6.703708e-02 9.401473e+00 +-6.727331e-02 5.398346e-03 9.977200e-01 2.558336e+02 1.585951e-03 9.999847e-01 -5.303669e-03 -8.976456e+00 -9.977333e-01 1.225536e-03 -6.728083e-02 9.349230e+00 +-6.759994e-02 1.274632e-02 9.976311e-01 2.565572e+02 1.795611e-03 9.999183e-01 -1.265388e-02 -9.002864e+00 -9.977108e-01 9.359526e-04 -6.761730e-02 9.297183e+00 +-6.901831e-02 1.759124e-02 9.974603e-01 2.572723e+02 1.591304e-03 9.998452e-01 -1.752319e-02 -9.027674e+00 -9.976141e-01 3.778377e-04 -6.903561e-02 9.248384e+00 +-7.057872e-02 1.949577e-02 9.973157e-01 2.579792e+02 1.868680e-03 9.998098e-01 -1.941228e-02 -9.054980e+00 -9.975044e-01 4.935665e-04 -7.060172e-02 9.197519e+00 +-7.362924e-02 1.812946e-02 9.971209e-01 2.586815e+02 3.870480e-03 9.998324e-01 -1.789296e-02 -9.085217e+00 -9.972781e-01 2.541888e-03 -7.368706e-02 9.140396e+00 +-7.835569e-02 1.715726e-02 9.967778e-01 2.593643e+02 5.094722e-03 9.998457e-01 -1.680958e-02 -9.115183e+00 -9.969124e-01 3.761176e-03 -7.843101e-02 9.079415e+00 +-8.809153e-02 1.653635e-02 9.959751e-01 2.599257e+02 8.092081e-03 9.998411e-01 -1.588482e-02 -9.134049e+00 -9.960795e-01 6.660188e-03 -8.821133e-02 8.975124e+00 +-9.783723e-02 1.596976e-02 9.950743e-01 2.604879e+02 1.109054e-02 9.998266e-01 -1.495560e-02 -9.152938e+00 -9.951406e-01 9.572697e-03 -9.799737e-02 8.870715e+00 +-1.075635e-01 1.545921e-02 9.940780e-01 2.610492e+02 1.408139e-02 9.998025e-01 -1.402458e-02 -9.171786e+00 -9.940984e-01 1.248947e-02 -1.077599e-01 8.766490e+00 +-1.172804e-01 1.500414e-02 9.929855e-01 2.616101e+02 1.706801e-02 9.997686e-01 -1.309075e-02 -9.190618e+00 -9.929521e-01 1.541299e-02 -1.175093e-01 8.662332e+00 +-1.269908e-01 1.460445e-02 9.917964e-01 2.621710e+02 2.005159e-02 9.997250e-01 -1.215378e-02 -9.209445e+00 -9.917012e-01 1.834367e-02 -1.272487e-01 8.558198e+00 +-1.366933e-01 1.426028e-02 9.905108e-01 2.627319e+02 2.303201e-02 9.996718e-01 -1.121369e-02 -9.228266e+00 -9.903456e-01 2.128062e-02 -1.369768e-01 8.454091e+00 +-1.463855e-01 1.397178e-02 9.891290e-01 2.632926e+02 2.600884e-02 9.996089e-01 -1.027066e-02 -9.247078e+00 -9.888856e-01 2.422261e-02 -1.466916e-01 8.350028e+00 +-1.560623e-01 1.373911e-02 9.876517e-01 2.638529e+02 2.898077e-02 9.995364e-01 -9.325096e-03 -9.265872e+00 -9.873219e-01 2.716761e-02 -1.563881e-01 8.246051e+00 +-1.657313e-01 1.356215e-02 9.860777e-01 2.644134e+02 3.195048e-02 9.994543e-01 -8.376182e-03 -9.284669e+00 -9.856532e-01 3.011745e-02 -1.660742e-01 8.142069e+00 +-1.753698e-01 1.344122e-02 9.844109e-01 2.649728e+02 3.491129e-02 9.993628e-01 -7.426045e-03 -9.303418e+00 -9.838834e-01 3.306474e-02 -1.757273e-01 8.038313e+00 +-1.850214e-01 1.337597e-02 9.826435e-01 2.655337e+02 3.787687e-02 9.992614e-01 -6.470367e-03 -9.322224e+00 -9.820042e-01 3.602230e-02 -1.853914e-01 7.934305e+00 +-1.946288e-01 1.336673e-02 9.807859e-01 2.660928e+02 4.082991e-02 9.991509e-01 -5.514671e-03 -9.340956e+00 -9.800268e-01 3.897208e-02 -1.950093e-01 7.830650e+00 +-2.042373e-01 1.341347e-02 9.788295e-01 2.666529e+02 4.378468e-02 9.990306e-01 -4.554425e-03 -9.359723e+00 -9.779417e-01 4.192755e-02 -2.046266e-01 7.726849e+00 +-2.138163e-01 1.351607e-02 9.767804e-01 2.672122e+02 4.673207e-02 9.989010e-01 -3.592564e-03 -9.378456e+00 -9.757554e-01 4.487881e-02 -2.142129e-01 7.623220e+00 +-2.233809e-01 1.367469e-02 9.746353e-01 2.677717e+02 4.967698e-02 9.987619e-01 -2.627529e-03 -9.397193e+00 -9.734645e-01 4.782999e-02 -2.237836e-01 7.519590e+00 +-2.328638e-01 1.389894e-02 9.724101e-01 2.683296e+02 5.261463e-02 9.986135e-01 -1.673813e-03 -9.415850e+00 -9.710850e-01 5.077322e-02 -2.332722e-01 7.415961e+00 +-2.356841e-01 1.510242e-02 9.717124e-01 2.687197e+02 5.511818e-02 9.984775e-01 -2.149772e-03 -9.429499e+00 -9.702654e-01 5.305233e-02 -2.361576e-01 7.309828e+00 +-2.361440e-01 1.508151e-02 9.716010e-01 2.690908e+02 5.698212e-02 9.983738e-01 -1.647804e-03 -9.443289e+00 -9.700459e-01 5.497475e-02 -2.366194e-01 7.211929e+00 +-2.334910e-01 1.487578e-02 9.722452e-01 2.694389e+02 5.939409e-02 9.982341e-01 -1.009554e-03 -9.454256e+00 -9.705433e-01 5.750989e-02 -2.339622e-01 7.121329e+00 +-2.286292e-01 1.538044e-02 9.733921e-01 2.697686e+02 6.059210e-02 9.981614e-01 -1.540025e-03 -9.463785e+00 -9.716261e-01 5.862776e-02 -2.291407e-01 7.040605e+00 +-2.211366e-01 1.648228e-02 9.751036e-01 2.700809e+02 5.992423e-02 9.981975e-01 -3.282872e-03 -9.473729e+00 -9.734000e-01 5.770635e-02 -2.217257e-01 6.972944e+00 +-2.102571e-01 1.774915e-02 9.774850e-01 2.703777e+02 5.829770e-02 9.982836e-01 -5.586984e-03 -9.484841e+00 -9.759064e-01 5.581041e-02 -2.109309e-01 6.915676e+00 +-1.967017e-01 2.028628e-02 9.802535e-01 2.706548e+02 5.577289e-02 9.983985e-01 -9.470180e-03 -9.498230e+00 -9.788758e-01 5.280875e-02 -1.975181e-01 6.869143e+00 +-1.806319e-01 2.351400e-02 9.832697e-01 2.709235e+02 5.556675e-02 9.983614e-01 -1.366700e-02 -9.511336e+00 -9.819798e-01 5.216839e-02 -1.816425e-01 6.829242e+00 +-1.610958e-01 2.495492e-02 9.866233e-01 2.711802e+02 5.531383e-02 9.983372e-01 -1.621958e-02 -9.529927e+00 -9.853875e-01 5.196099e-02 -1.622083e-01 6.803106e+00 +-1.389799e-01 2.353185e-02 9.900156e-01 2.714334e+02 5.634238e-02 9.982862e-01 -1.581902e-02 -9.544996e+00 -9.886911e-01 5.358129e-02 -1.400675e-01 6.780906e+00 +-1.136676e-01 2.240003e-02 9.932663e-01 2.716890e+02 5.573097e-02 9.983154e-01 -1.613616e-02 -9.559927e+00 -9.919545e-01 5.352152e-02 -1.147245e-01 6.775710e+00 +-8.372953e-02 2.194371e-02 9.962469e-01 2.719474e+02 5.303783e-02 9.984385e-01 -1.753443e-02 -9.573521e+00 -9.950760e-01 5.137061e-02 -8.476263e-02 6.781844e+00 +-5.082579e-02 2.073706e-02 9.984922e-01 2.721883e+02 5.065284e-02 9.985512e-01 -1.815994e-02 -9.586484e+00 -9.974221e-01 4.965346e-02 -5.180254e-02 6.798910e+00 +-1.621006e-02 1.693418e-02 9.997252e-01 2.724487e+02 4.776928e-02 9.987279e-01 -1.614273e-02 -9.599096e+00 -9.987268e-01 4.749447e-02 -1.699837e-02 6.826436e+00 +1.994941e-02 1.227483e-02 9.997257e-01 2.727085e+02 4.600685e-02 9.988541e-01 -1.318220e-02 -9.612324e+00 -9.987419e-01 4.625719e-02 1.936182e-02 6.863175e+00 +5.867973e-02 9.173971e-03 9.982347e-01 2.729398e+02 4.097646e-02 9.990929e-01 -1.159060e-02 -9.626310e+00 -9.974355e-01 4.158425e-02 5.825058e-02 6.915555e+00 +1.003292e-01 7.991341e-03 9.949222e-01 2.731906e+02 3.543775e-02 9.993045e-01 -1.160013e-02 -9.643554e+00 -9.943230e-01 3.642162e-02 9.997622e-02 6.984555e+00 +1.460155e-01 8.329760e-03 9.892473e-01 2.734483e+02 2.704353e-02 9.995572e-01 -1.240827e-02 -9.662857e+00 -9.889125e-01 2.856453e-02 1.457256e-01 7.056585e+00 +1.938408e-01 9.289321e-03 9.809891e-01 2.736741e+02 2.296611e-02 9.996381e-01 -1.400396e-02 -9.677120e+00 -9.807641e-01 2.524403e-02 1.935573e-01 7.139266e+00 +2.438794e-01 1.129196e-02 9.697399e-01 2.739370e+02 1.940377e-02 9.996752e-01 -1.652038e-02 -9.693740e+00 -9.696114e-01 2.284559e-02 2.435811e-01 7.237626e+00 +2.953493e-01 1.334585e-02 9.552962e-01 2.741601e+02 1.621396e-02 9.996884e-01 -1.897891e-02 -9.711016e+00 -9.552517e-01 2.109454e-02 2.950409e-01 7.353067e+00 +3.500849e-01 1.375018e-02 9.366171e-01 2.744355e+02 1.903687e-02 9.995813e-01 -2.179006e-02 -9.726740e+00 -9.365245e-01 2.545862e-02 3.496766e-01 7.486302e+00 +4.058729e-01 1.428730e-02 9.138179e-01 2.747081e+02 2.853173e-02 9.991923e-01 -2.829450e-02 -9.734573e+00 -9.134840e-01 3.755677e-02 4.051375e-01 7.634910e+00 +4.609076e-01 1.267508e-02 8.873576e-01 2.749354e+02 3.407831e-02 9.989077e-01 -3.196928e-02 -9.744474e+00 -8.867935e-01 4.497453e-02 4.599722e-01 7.808509e+00 +5.149155e-01 1.247167e-02 8.571503e-01 2.752061e+02 2.881971e-02 9.990771e-01 -3.184958e-02 -9.760267e+00 -8.567563e-01 4.110265e-02 5.140808e-01 8.021776e+00 +5.677527e-01 1.598069e-02 8.230441e-01 2.754581e+02 2.133431e-02 9.991901e-01 -3.411769e-02 -9.778040e+00 -8.229227e-01 3.692947e-02 5.669518e-01 8.264455e+00 +6.056124e-01 1.724098e-02 7.955730e-01 2.756510e+02 1.671439e-02 9.992691e-01 -3.437877e-02 -9.794470e+00 -7.955842e-01 3.411771e-02 6.048815e-01 8.694219e+00 +6.421416e-01 1.871794e-02 7.663576e-01 2.758414e+02 1.208548e-02 9.993304e-01 -3.453480e-02 -9.810775e+00 -7.664908e-01 3.143802e-02 6.414853e-01 9.123003e+00 +6.773074e-01 2.040430e-02 7.354172e-01 2.760300e+02 7.446072e-03 9.993740e-01 -3.458555e-02 -9.827008e+00 -7.356624e-01 2.890101e-02 6.767314e-01 9.551308e+00 +7.109247e-01 2.228400e-02 7.029151e-01 2.762154e+02 2.815373e-03 9.993996e-01 -3.453070e-02 -9.843049e+00 -7.032625e-01 2.652769e-02 7.104351e-01 9.977662e+00 +7.430629e-01 2.435422e-02 6.687783e-01 2.763997e+02 -1.821832e-03 9.994075e-01 -3.437023e-02 -9.859061e+00 -6.692191e-01 2.432083e-02 7.426670e-01 1.040388e+01 +7.735546e-01 2.659749e-02 6.331714e-01 2.765818e+02 -6.447541e-03 9.993975e-01 -3.410443e-02 -9.874937e+00 -6.336969e-01 2.229923e-02 7.732599e-01 1.082860e+01 +8.023024e-01 2.899810e-02 5.962130e-01 2.767610e+02 -1.105189e-02 9.993697e-01 -3.373436e-02 -9.890639e+00 -5.968154e-01 2.047588e-02 8.021172e-01 1.125127e+01 +8.293099e-01 3.154810e-02 5.578978e-01 2.769388e+02 -1.564075e-02 9.993243e-01 -3.326014e-02 -9.906249e+00 -5.585701e-01 1.885702e-02 8.292429e-01 1.167280e+01 +8.545088e-01 3.423353e-02 5.183077e-01 2.771150e+02 -2.020886e-02 9.992614e-01 -3.268252e-02 -9.921765e+00 -5.190437e-01 1.745308e-02 8.545694e-01 1.209308e+01 +8.778116e-01 3.703669e-02 4.775721e-01 2.772893e+02 -2.474623e-02 9.991814e-01 -3.200322e-02 -9.937146e+00 -4.783664e-01 1.627468e-02 8.780095e-01 1.251150e+01 +8.991665e-01 3.994221e-02 4.357802e-01 2.774617e+02 -2.924813e-02 9.990844e-01 -3.122378e-02 -9.952392e+00 -4.366283e-01 1.532962e-02 8.995113e-01 1.292799e+01 +9.185229e-01 4.293380e-02 3.930299e-01 2.776324e+02 -3.370924e-02 9.989708e-01 -3.034608e-02 -9.967501e+00 -3.939282e-01 1.462482e-02 9.190248e-01 1.334241e+01 +9.358408e-01 4.599565e-02 3.494087e-01 2.778014e+02 -3.812565e-02 9.988412e-01 -2.937196e-02 -9.982477e+00 -3.503548e-01 1.416605e-02 9.365099e-01 1.375473e+01 +9.510964e-01 4.911451e-02 3.049648e-01 2.779693e+02 -4.249747e-02 9.986956e-01 -2.830248e-02 -9.997356e+00 -3.059571e-01 1.395815e-02 9.519429e-01 1.416535e+01 +9.642109e-01 5.226371e-02 2.599346e-01 2.781350e+02 -4.680684e-02 9.985351e-01 -2.714330e-02 -1.001204e+01 -2.609724e-01 1.400515e-02 9.652446e-01 1.457286e+01 +9.750681e-01 5.530532e-02 2.149039e-01 2.782922e+02 -5.093218e-02 9.983678e-01 -2.583812e-02 -1.002657e+01 -2.159821e-01 1.424840e-02 9.762933e-01 1.498313e+01 +9.806319e-01 5.394348e-02 1.882849e-01 2.784020e+02 -5.064110e-02 9.984677e-01 -2.230955e-02 -1.004318e+01 -1.891999e-01 1.234250e-02 9.818610e-01 1.560076e+01 +9.848867e-01 5.335417e-02 1.647774e-01 2.785111e+02 -5.010966e-02 9.984604e-01 -2.378781e-02 -1.007051e+01 -1.657929e-01 1.517136e-02 9.860438e-01 1.622890e+01 +9.879243e-01 5.740584e-02 1.439105e-01 2.785999e+02 -5.386267e-02 9.981444e-01 -2.840019e-02 -1.010274e+01 -1.452738e-01 2.030582e-02 9.891830e-01 1.687504e+01 +9.900744e-01 6.355418e-02 1.253540e-01 2.786755e+02 -5.969482e-02 9.976268e-01 -3.431117e-02 -1.013097e+01 -1.272371e-01 2.648762e-02 9.915185e-01 1.754087e+01 +9.916821e-01 6.671441e-02 1.100719e-01 2.787489e+02 -6.229849e-02 9.971271e-01 -4.308508e-02 -1.014776e+01 -1.126301e-01 3.586939e-02 9.929893e-01 1.822626e+01 +9.930479e-01 6.842705e-02 9.577925e-02 2.788166e+02 -6.516723e-02 9.971969e-01 -3.676246e-02 -1.017090e+01 -9.802631e-02 3.026521e-02 9.947235e-01 1.894345e+01 +9.944750e-01 6.433402e-02 8.294980e-02 2.788871e+02 -6.264976e-02 9.977762e-01 -2.275279e-02 -1.020698e+01 -8.422911e-02 1.743029e-02 9.962939e-01 1.968959e+01 +9.955555e-01 5.974325e-02 7.280169e-02 2.789518e+02 -5.878482e-02 9.981543e-01 -1.523922e-02 -1.024079e+01 -7.357776e-02 1.089186e-02 9.972299e-01 2.044628e+01 +9.961723e-01 5.941056e-02 6.411927e-02 2.790064e+02 -5.847166e-02 9.981539e-01 -1.642336e-02 -1.026544e+01 -6.497662e-02 1.261133e-02 9.978070e-01 2.121270e+01 +9.962312e-01 6.437953e-02 5.812715e-02 2.790503e+02 -6.325085e-02 9.977755e-01 -2.105485e-02 -1.028186e+01 -5.935335e-02 1.729890e-02 9.980871e-01 2.200409e+01 +9.961865e-01 6.838144e-02 5.418897e-02 2.790817e+02 -6.712758e-02 9.974403e-01 -2.463277e-02 -1.029864e+01 -5.573468e-02 2.090125e-02 9.982268e-01 2.282539e+01 +9.961255e-01 7.112069e-02 5.172907e-02 2.791188e+02 -6.997358e-02 9.972682e-01 -2.366081e-02 -1.032374e+01 -5.327053e-02 1.994947e-02 9.983808e-01 2.365989e+01 +9.959335e-01 7.420515e-02 5.108998e-02 2.791531e+02 -7.311329e-02 9.970602e-01 -2.292105e-02 -1.034729e+01 -5.264064e-02 1.909248e-02 9.984309e-01 2.451304e+01 +9.960960e-01 7.169975e-02 5.149782e-02 2.791989e+02 -7.052098e-02 9.972129e-01 -2.435563e-02 -1.037467e+01 -5.310058e-02 2.062887e-02 9.983760e-01 2.537629e+01 +9.962631e-01 6.826151e-02 5.291774e-02 2.792569e+02 -6.696379e-02 9.974186e-01 -2.592247e-02 -1.040958e+01 -5.455064e-02 2.228203e-02 9.982623e-01 2.625637e+01 +9.960773e-01 6.913572e-02 5.523011e-02 2.793100e+02 -6.764909e-02 9.973063e-01 -2.835003e-02 -1.044057e+01 -5.704134e-02 2.450255e-02 9.980710e-01 2.714755e+01 +9.958293e-01 6.989583e-02 5.863981e-02 2.793670e+02 -6.848520e-02 9.973202e-01 -2.573276e-02 -1.047041e+01 -6.028128e-02 2.160947e-02 9.979474e-01 2.805463e+01 +9.961028e-01 6.327448e-02 6.144551e-02 2.794300e+02 -6.225581e-02 9.978914e-01 -1.835570e-02 -1.049615e+01 -6.247739e-02 1.445882e-02 9.979416e-01 2.898177e+01 +9.960000e-01 6.184018e-02 6.449784e-02 2.794920e+02 -6.106382e-02 9.980365e-01 -1.394158e-02 -1.052519e+01 -6.523334e-02 9.947323e-03 9.978204e-01 2.991016e+01 +9.959468e-01 5.954303e-02 6.741393e-02 2.795555e+02 -5.868528e-02 9.981692e-01 -1.463512e-02 -1.054802e+01 -6.816193e-02 1.061960e-02 9.976177e-01 3.084221e+01 +9.960013e-01 5.622204e-02 6.943080e-02 2.796233e+02 -5.507740e-02 9.983145e-01 -1.829339e-02 -1.057151e+01 -7.034226e-02 1.439617e-02 9.974190e-01 3.177604e+01 +9.959256e-01 5.439153e-02 7.192941e-02 2.796820e+02 -5.277817e-02 9.983143e-01 -2.414478e-02 -1.060332e+01 -7.312143e-02 2.025010e-02 9.971174e-01 3.272243e+01 +9.957581e-01 5.439853e-02 7.420682e-02 2.797476e+02 -5.223628e-02 9.981604e-01 -3.077568e-02 -1.063896e+01 -7.574446e-02 2.676884e-02 9.967678e-01 3.367308e+01 +9.956260e-01 5.455080e-02 7.584953e-02 2.798150e+02 -5.227298e-02 9.981295e-01 -3.170017e-02 -1.067413e+01 -7.743692e-02 2.759663e-02 9.966152e-01 3.464065e+01 +9.956407e-01 5.179737e-02 7.756711e-02 2.798916e+02 -5.007458e-02 9.984572e-01 -2.399435e-02 -1.071570e+01 -7.869028e-02 2.000561e-02 9.966983e-01 3.561870e+01 +9.957716e-01 4.757250e-02 7.858603e-02 2.799697e+02 -4.652088e-02 9.988023e-01 -1.515993e-02 -1.075207e+01 -7.921310e-02 1.143993e-02 9.967920e-01 3.660789e+01 +9.958436e-01 4.505057e-02 7.915852e-02 2.800476e+02 -4.418864e-02 9.989436e-01 -1.260775e-02 -1.078236e+01 -7.964288e-02 9.057442e-03 9.967823e-01 3.759549e+01 +9.957008e-01 4.799311e-02 7.922543e-02 2.801173e+02 -4.706765e-02 9.988003e-01 -1.350885e-02 -1.081541e+01 -7.977872e-02 9.721818e-03 9.967651e-01 3.858797e+01 +9.958215e-01 4.619938e-02 7.877372e-02 2.801964e+02 -4.452406e-02 9.987459e-01 -2.289394e-02 -1.085174e+01 -7.973261e-02 1.929095e-02 9.966295e-01 3.957091e+01 +9.958053e-01 4.743640e-02 7.824163e-02 2.802713e+02 -4.526279e-02 9.985446e-01 -2.932506e-02 -1.088964e+01 -7.951882e-02 2.566061e-02 9.965030e-01 4.056118e+01 +9.956153e-01 5.105855e-02 7.837862e-02 2.803408e+02 -4.903721e-02 9.984182e-01 -2.750223e-02 -1.093233e+01 -7.965886e-02 2.353817e-02 9.965442e-01 4.156315e+01 +9.955594e-01 5.244100e-02 7.817608e-02 2.804126e+02 -5.100185e-02 9.984923e-01 -2.029477e-02 -1.097462e+01 -7.912249e-02 1.621752e-02 9.967329e-01 4.257375e+01 +9.955600e-01 5.300544e-02 7.778680e-02 2.804856e+02 -5.193443e-02 9.985266e-01 -1.572898e-02 -1.101262e+01 -7.850591e-02 1.161933e-02 9.968459e-01 4.359155e+01 +9.953295e-01 5.765077e-02 7.743210e-02 2.805539e+02 -5.660129e-02 9.982737e-01 -1.568250e-02 -1.104830e+01 -7.820253e-02 1.122650e-02 9.968742e-01 4.460279e+01 +9.951933e-01 6.026571e-02 7.719121e-02 2.806232e+02 -5.928053e-02 9.981287e-01 -1.499350e-02 -1.108050e+01 -7.795036e-02 1.034549e-02 9.969035e-01 4.561968e+01 +9.949059e-01 6.617181e-02 7.604954e-02 2.806912e+02 -6.566650e-02 9.977998e-01 -9.128744e-03 -1.110898e+01 -7.648628e-02 4.088334e-03 9.970622e-01 4.663824e+01 +9.948310e-01 6.731904e-02 7.602278e-02 2.807575e+02 -6.737918e-02 9.977258e-01 -1.776569e-03 -1.114183e+01 -7.596948e-02 -3.354965e-03 9.971044e-01 4.766917e+01 +9.948398e-01 6.926645e-02 7.413452e-02 2.808247e+02 -6.919141e-02 9.975969e-01 -3.583198e-03 -1.116933e+01 -7.420456e-02 -1.564763e-03 9.972418e-01 4.868662e+01 +9.950316e-01 6.843401e-02 7.231177e-02 2.808942e+02 -6.784169e-02 9.976396e-01 -1.061883e-02 -1.119345e+01 -7.286777e-02 5.660316e-03 9.973255e-01 4.969895e+01 +9.951638e-01 6.740927e-02 7.145007e-02 2.809667e+02 -6.698358e-02 9.977192e-01 -8.340177e-03 -1.121703e+01 -7.184930e-02 3.513861e-03 9.974093e-01 5.071799e+01 +9.951705e-01 6.744520e-02 7.132218e-02 2.810372e+02 -6.680968e-02 9.977022e-01 -1.126163e-02 -1.124770e+01 -7.191784e-02 6.442233e-03 9.973897e-01 5.172891e+01 +9.950633e-01 6.890809e-02 7.142032e-02 2.811096e+02 -6.757960e-02 9.974958e-01 -2.085629e-02 -1.128176e+01 -7.267864e-02 1.592677e-02 9.972282e-01 5.274541e+01 +9.953629e-01 6.382479e-02 7.196587e-02 2.811898e+02 -6.221197e-02 9.977637e-01 -2.443642e-02 -1.131856e+01 -7.336458e-02 1.984596e-02 9.971076e-01 5.376325e+01 +9.954290e-01 6.122670e-02 7.329761e-02 2.812698e+02 -6.018968e-02 9.980542e-01 -1.627646e-02 -1.135809e+01 -7.415154e-02 1.179030e-02 9.971772e-01 5.479308e+01 +9.948658e-01 6.767070e-02 7.525108e-02 2.813237e+02 -6.691675e-02 9.976803e-01 -1.249882e-02 -1.139973e+01 -7.592231e-02 7.399089e-03 9.970862e-01 5.582211e+01 +9.948128e-01 6.670008e-02 7.680326e-02 2.813875e+02 -6.582081e-02 9.977343e-01 -1.392618e-02 -1.143904e+01 -7.755811e-02 8.798685e-03 9.969490e-01 5.684029e+01 +9.941975e-01 7.366220e-02 7.839249e-02 2.814570e+02 -7.246143e-02 9.972077e-01 -1.805738e-02 -1.147506e+01 -7.950374e-02 1.227216e-02 9.967590e-01 5.786125e+01 +9.937271e-01 7.556547e-02 8.244051e-02 2.815355e+02 -7.425104e-02 9.970605e-01 -1.889954e-02 -1.151657e+01 -8.362632e-02 1.265969e-02 9.964167e-01 5.889446e+01 +9.931127e-01 8.029882e-02 8.531901e-02 2.816092e+02 -7.947297e-02 9.967517e-01 -1.303791e-02 -1.155132e+01 -8.608879e-02 6.167561e-03 9.962683e-01 5.991592e+01 +9.927050e-01 8.106097e-02 8.925248e-02 2.816941e+02 -8.085186e-02 9.967083e-01 -5.961919e-03 -1.157887e+01 -8.944196e-02 -1.297802e-03 9.959911e-01 6.094640e+01 +9.927726e-01 7.879411e-02 9.052159e-02 2.817904e+02 -7.888362e-02 9.968804e-01 -2.594076e-03 -1.160922e+01 -9.044360e-02 -4.565343e-03 9.958911e-01 6.197385e+01 +9.932073e-01 7.354668e-02 9.016811e-02 2.818928e+02 -7.322593e-02 9.972917e-01 -6.864756e-03 -1.164024e+01 -9.042879e-02 2.154823e-04 9.959028e-01 6.299394e+01 +9.941004e-01 6.303642e-02 8.826649e-02 2.820000e+02 -6.191416e-02 9.979627e-01 -1.539785e-02 -1.166955e+01 -8.905728e-02 9.842060e-03 9.959778e-01 6.400966e+01 +9.942679e-01 6.388651e-02 8.573156e-02 2.820889e+02 -6.269505e-02 9.978959e-01 -1.652158e-02 -1.170038e+01 -8.660667e-02 1.105193e-02 9.961812e-01 6.503015e+01 +9.945102e-01 6.296877e-02 8.357277e-02 2.821681e+02 -6.240074e-02 9.980069e-01 -9.394279e-03 -1.173370e+01 -8.399774e-02 4.127704e-03 9.964573e-01 6.606144e+01 +9.946978e-01 6.392828e-02 8.055830e-02 2.822464e+02 -6.391395e-02 9.979516e-01 -2.759114e-03 -1.176324e+01 -8.056966e-02 -2.404314e-03 9.967460e-01 6.709490e+01 +9.947241e-01 6.678803e-02 7.786851e-02 2.823171e+02 -6.651521e-02 9.977668e-01 -6.094968e-03 -1.179410e+01 -7.810168e-02 8.833703e-04 9.969450e-01 6.812345e+01 +9.946012e-01 7.178659e-02 7.493467e-02 2.823862e+02 -7.066601e-02 9.973464e-01 -1.750338e-02 -1.182862e+01 -7.599233e-02 1.211355e-02 9.970348e-01 6.913786e+01 +9.945628e-01 7.571410e-02 7.150038e-02 2.824545e+02 -7.394973e-02 9.968960e-01 -2.701315e-02 -1.186542e+01 -7.332371e-02 2.157883e-02 9.970747e-01 7.015552e+01 +9.948563e-01 7.387187e-02 6.931051e-02 2.825238e+02 -7.222419e-02 9.970498e-01 -2.598801e-02 -1.190562e+01 -7.102581e-02 2.084844e-02 9.972565e-01 7.117579e+01 +9.949103e-01 7.431902e-02 6.804647e-02 2.825814e+02 -7.330470e-02 9.971597e-01 -1.728734e-02 -1.194809e+01 -6.913797e-02 1.221122e-02 9.975323e-01 7.220572e+01 +9.948512e-01 7.599914e-02 6.704762e-02 2.826307e+02 -7.525197e-02 9.970717e-01 -1.360373e-02 -1.198360e+01 -6.788516e-02 8.488218e-03 9.976570e-01 7.322797e+01 +9.947044e-01 7.880580e-02 6.597631e-02 2.826806e+02 -7.801502e-02 9.968470e-01 -1.448169e-02 -1.201441e+01 -6.690952e-02 9.257858e-03 9.977160e-01 7.424511e+01 +9.946239e-01 7.977263e-02 6.602820e-02 2.827411e+02 -7.885337e-02 9.967510e-01 -1.641741e-02 -1.204708e+01 -6.712334e-02 1.112260e-02 9.976826e-01 7.526042e+01 +9.944161e-01 8.159960e-02 6.691993e-02 2.828004e+02 -8.040454e-02 9.965542e-01 -2.036564e-02 -1.208175e+01 -6.835117e-02 1.487125e-02 9.975504e-01 7.627062e+01 +9.942241e-01 8.265824e-02 6.845509e-02 2.828649e+02 -8.139591e-02 9.964599e-01 -2.103355e-02 -1.212188e+01 -6.995134e-02 1.534010e-02 9.974324e-01 7.728264e+01 +9.944030e-01 7.925357e-02 6.986912e-02 2.829456e+02 -7.822258e-02 9.967845e-01 -1.737500e-02 -1.215944e+01 -7.102148e-02 1.181241e-02 9.974048e-01 7.830048e+01 +9.943705e-01 7.795148e-02 7.177040e-02 2.830180e+02 -7.715821e-02 9.969238e-01 -1.376410e-02 -1.219137e+01 -7.262255e-02 8.148942e-03 9.973261e-01 7.931696e+01 +9.944183e-01 7.544151e-02 7.376304e-02 2.830985e+02 -7.469245e-02 9.971236e-01 -1.286533e-02 -1.223081e+01 -7.452145e-02 7.283979e-03 9.971928e-01 8.032553e+01 +9.946829e-01 7.195798e-02 7.367573e-02 2.831854e+02 -7.054769e-02 9.972751e-01 -2.157190e-02 -1.226467e+01 -7.502724e-02 1.625954e-02 9.970489e-01 8.132284e+01 +9.947905e-01 6.981717e-02 7.428007e-02 2.832718e+02 -6.794836e-02 9.973125e-01 -2.739860e-02 -1.229917e+01 -7.599333e-02 2.220865e-02 9.968609e-01 8.232352e+01 +9.946765e-01 6.918316e-02 7.636991e-02 2.833571e+02 -6.770810e-02 9.974682e-01 -2.174095e-02 -1.233753e+01 -7.768066e-02 1.645435e-02 9.968424e-01 8.333901e+01 +9.946891e-01 6.619557e-02 7.881510e-02 2.834417e+02 -6.584825e-02 9.978051e-01 -7.000552e-03 -1.237684e+01 -7.910551e-02 1.773536e-03 9.968646e-01 8.436387e+01 +9.947020e-01 6.433678e-02 8.017993e-02 2.835256e+02 -6.441513e-02 9.979219e-01 -1.611709e-03 -1.240882e+01 -8.011700e-02 -3.561630e-03 9.967790e-01 8.537498e+01 +9.945309e-01 6.583346e-02 8.108242e-02 2.836047e+02 -6.502945e-02 9.978048e-01 -1.252006e-02 -1.243749e+01 -8.172866e-02 7.178838e-03 9.966287e-01 8.636577e+01 +9.943989e-01 6.743004e-02 8.138816e-02 2.836838e+02 -6.533238e-02 9.974658e-01 -2.817028e-02 -1.247110e+01 -8.308142e-02 2.269521e-02 9.962842e-01 8.735330e+01 +9.942211e-01 6.759971e-02 8.339535e-02 2.837655e+02 -6.476082e-02 9.972406e-01 -3.629236e-02 -1.251326e+01 -8.561858e-02 3.068187e-02 9.958554e-01 8.834335e+01 +9.939708e-01 6.698360e-02 8.680579e-02 2.838524e+02 -6.465100e-02 9.974743e-01 -2.941300e-02 -1.256371e+01 -8.855674e-02 2.362358e-02 9.957909e-01 8.934530e+01 +9.936270e-01 6.639506e-02 9.108927e-02 2.839401e+02 -6.503064e-02 9.977232e-01 -1.786933e-02 -1.260724e+01 -9.206831e-02 1.183185e-02 9.956823e-01 9.035215e+01 +9.934272e-01 6.396914e-02 9.492313e-02 2.840338e+02 -6.336968e-02 9.979466e-01 -9.319390e-03 -1.264165e+01 -9.532436e-02 3.242887e-03 9.954409e-01 9.135817e+01 +9.932876e-01 6.100488e-02 9.827658e-02 2.841298e+02 -6.049992e-02 9.981352e-01 -8.112864e-03 -1.267030e+01 -9.858823e-02 2.112681e-03 9.951260e-01 9.236134e+01 +9.930084e-01 5.973996e-02 1.018111e-01 2.842313e+02 -5.868737e-02 9.981877e-01 -1.330545e-02 -1.269838e+01 -1.024214e-01 7.237394e-03 9.947147e-01 9.335526e+01 +9.925856e-01 6.026566e-02 1.055554e-01 2.843305e+02 -5.848636e-02 9.980903e-01 -1.987450e-02 -1.272971e+01 -1.065515e-01 1.355359e-02 9.942147e-01 9.434479e+01 +9.918536e-01 6.320656e-02 1.105959e-01 2.844303e+02 -6.094560e-02 9.978594e-01 -2.370932e-02 -1.276707e+01 -1.118578e-01 1.677583e-02 9.935826e-01 9.534096e+01 +9.912924e-01 6.040523e-02 1.170075e-01 2.845419e+02 -5.825942e-02 9.980661e-01 -2.167642e-02 -1.280761e+01 -1.180906e-01 1.467088e-02 9.928944e-01 9.634510e+01 +9.906894e-01 5.754886e-02 1.233800e-01 2.846672e+02 -5.559815e-02 9.982686e-01 -1.919869e-02 -1.284708e+01 -1.242713e-01 1.216023e-02 9.921737e-01 9.734234e+01 +9.897377e-01 5.956727e-02 1.298885e-01 2.847930e+02 -5.772536e-02 9.981719e-01 -1.790318e-02 -1.288414e+01 -1.307174e-01 1.022160e-02 9.913669e-01 9.833546e+01 +9.894464e-01 5.059501e-02 1.357797e-01 2.849380e+02 -4.899896e-02 9.986851e-01 -1.507333e-02 -1.291595e+01 -1.363638e-01 8.261186e-03 9.906243e-01 9.932058e+01 +9.889520e-01 4.736796e-02 1.404646e-01 2.850835e+02 -4.610523e-02 9.988617e-01 -1.223217e-02 -1.294839e+01 -1.408841e-01 5.620871e-03 9.900101e-01 1.003058e+02 +9.883429e-01 4.124660e-02 1.465508e-01 2.852372e+02 -3.980413e-02 9.991260e-01 -1.276298e-02 -1.298065e+01 -1.469491e-01 6.780873e-03 9.891208e-01 1.012855e+02 +9.878306e-01 3.673413e-02 1.511340e-01 2.853950e+02 -3.473504e-02 9.992709e-01 -1.584700e-02 -1.301542e+01 -1.516059e-01 1.040451e-02 9.883862e-01 1.022595e+02 +9.869511e-01 4.359110e-02 1.550078e-01 2.855419e+02 -4.181653e-02 9.990173e-01 -1.469211e-02 -1.305481e+01 -1.554959e-01 8.018506e-03 9.878039e-01 1.032332e+02 +9.860711e-01 4.984959e-02 1.586786e-01 2.856886e+02 -4.774076e-02 9.987138e-01 -1.707659e-02 -1.309108e+01 -1.593258e-01 9.263293e-03 9.871825e-01 1.042036e+02 +9.856634e-01 5.050868e-02 1.609864e-01 2.858441e+02 -4.763957e-02 9.986302e-01 -2.163492e-02 -1.312913e+01 -1.618586e-01 1.365542e-02 9.867194e-01 1.051632e+02 +9.852472e-01 5.281612e-02 1.627838e-01 2.859984e+02 -4.974140e-02 9.984993e-01 -2.290952e-02 -1.316767e+01 -1.637495e-01 1.447444e-02 9.863957e-01 1.061292e+02 +9.851163e-01 5.214476e-02 1.637889e-01 2.861578e+02 -4.970552e-02 9.985839e-01 -1.895860e-02 -1.320807e+01 -1.645456e-01 1.053522e-02 9.863132e-01 1.070955e+02 +9.854300e-01 4.841488e-02 1.630454e-01 2.863219e+02 -4.626508e-02 9.987852e-01 -1.695889e-02 -1.325071e+01 -1.636684e-01 9.168485e-03 9.864728e-01 1.080537e+02 +9.860995e-01 4.148697e-02 1.608937e-01 2.864851e+02 -3.911793e-02 9.990749e-01 -1.786539e-02 -1.328753e+01 -1.614860e-01 1.132322e-02 9.868100e-01 1.090066e+02 +9.867770e-01 3.568008e-02 1.581080e-01 2.866417e+02 -3.341209e-02 9.992974e-01 -1.698039e-02 -1.332242e+01 -1.586028e-01 1.147313e-02 9.872758e-01 1.099571e+02 +9.874257e-01 3.224614e-02 1.547601e-01 2.867938e+02 -3.053742e-02 9.994437e-01 -1.340637e-02 -1.335867e+01 -1.551063e-01 8.511816e-03 9.878611e-01 1.109122e+02 +9.879797e-01 3.322151e-02 1.509720e-01 2.869362e+02 -3.176099e-02 9.994225e-01 -1.207583e-02 -1.339700e+01 -1.512859e-01 7.135652e-03 9.884642e-01 1.118603e+02 +9.886135e-01 3.280421e-02 1.468581e-01 2.870770e+02 -3.103349e-02 9.994156e-01 -1.433295e-02 -1.343180e+01 -1.472425e-01 9.612226e-03 9.890537e-01 1.128028e+02 +9.891959e-01 3.213855e-02 1.430338e-01 2.872169e+02 -2.939177e-02 9.993415e-01 -2.127591e-02 -1.347199e+01 -1.436233e-01 1.684202e-02 9.894890e-01 1.137365e+02 +9.896387e-01 2.983259e-02 1.404473e-01 2.873536e+02 -2.645810e-02 9.993160e-01 -2.583341e-02 -1.351254e+01 -1.411219e-01 2.184976e-02 9.897510e-01 1.146651e+02 +9.900155e-01 2.662197e-02 1.384223e-01 2.874910e+02 -2.352154e-02 9.994355e-01 -2.398648e-02 -1.356000e+01 -1.389827e-01 2.049107e-02 9.900827e-01 1.155929e+02 +9.903541e-01 2.069235e-02 1.370058e-01 2.876309e+02 -1.870616e-02 9.997006e-01 -1.576900e-02 -1.360737e+01 -1.372911e-01 1.305404e-02 9.904447e-01 1.165185e+02 +9.906344e-01 1.071487e-02 1.361202e-01 2.877744e+02 -9.927284e-03 9.999298e-01 -6.463472e-03 -1.365070e+01 -1.361799e-01 5.051633e-03 9.906712e-01 1.174361e+02 +9.908081e-01 2.470638e-04 1.352748e-01 2.879206e+02 -8.283130e-05 9.999992e-01 -1.219694e-03 -1.368599e+01 -1.352750e-01 1.197277e-03 9.908073e-01 1.183379e+02 +9.907837e-01 -4.037341e-03 1.353934e-01 2.880587e+02 4.310644e-03 9.999892e-01 -1.725471e-03 -1.372267e+01 -1.353850e-01 2.293201e-03 9.907904e-01 1.192193e+02 +9.906465e-01 -2.862894e-03 1.364239e-01 2.881900e+02 3.934601e-03 9.999635e-01 -7.586710e-03 -1.376306e+01 -1.363972e-01 8.052519e-03 9.906214e-01 1.200844e+02 +9.904250e-01 -7.741897e-04 1.380499e-01 2.883171e+02 2.963701e-03 9.998730e-01 -1.565544e-02 -1.379791e+01 -1.380203e-01 1.591467e-02 9.903015e-01 1.209359e+02 +9.900810e-01 -9.614440e-04 1.404945e-01 2.884488e+02 3.500617e-03 9.998349e-01 -1.782710e-02 -1.383618e+01 -1.404542e-01 1.814208e-02 9.899209e-01 1.217809e+02 +9.895547e-01 -2.364167e-04 1.441582e-01 2.885773e+02 1.842821e-03 9.999377e-01 -1.100992e-02 -1.387237e+01 -1.441466e-01 1.116057e-02 9.894933e-01 1.226291e+02 +9.888756e-01 -3.926532e-04 1.487450e-01 2.887102e+02 1.267845e-03 9.999824e-01 -5.789067e-03 -1.390798e+01 -1.487401e-01 5.913251e-03 9.888586e-01 1.234632e+02 +9.880462e-01 -1.311528e-03 1.541527e-01 2.888464e+02 2.111554e-03 9.999851e-01 -5.026212e-03 -1.393832e+01 -1.541438e-01 5.291631e-03 9.880342e-01 1.242806e+02 +9.869974e-01 -2.272381e-03 1.607206e-01 2.889881e+02 3.269075e-03 9.999770e-01 -5.937258e-03 -1.396658e+01 -1.607034e-01 6.385465e-03 9.869820e-01 1.250820e+02 +9.857593e-01 -3.540913e-03 1.681256e-01 2.891349e+02 5.032636e-03 9.999516e-01 -8.447410e-03 -1.399570e+01 -1.680875e-01 9.173226e-03 9.857293e-01 1.258653e+02 +9.842807e-01 -5.509228e-03 1.765252e-01 2.892853e+02 7.593788e-03 9.999091e-01 -1.113546e-02 -1.402651e+01 -1.764478e-01 1.230092e-02 9.842331e-01 1.266301e+02 +9.825554e-01 -5.585028e-03 1.858863e-01 2.894380e+02 8.165972e-03 9.998805e-01 -1.312177e-02 -1.405307e+01 -1.857908e-01 1.441081e-02 9.824836e-01 1.273821e+02 +9.806437e-01 -2.801404e-03 1.957810e-01 2.895906e+02 5.260063e-03 9.999137e-01 -1.203939e-02 -1.407820e+01 -1.957304e-01 1.283617e-02 9.805737e-01 1.281183e+02 +9.786013e-01 8.549226e-06 2.057657e-01 2.897435e+02 1.861460e-03 9.999587e-01 -8.894468e-03 -1.410606e+01 -2.057572e-01 9.087161e-03 9.785608e-01 1.288354e+02 +9.766453e-01 2.155630e-03 2.148475e-01 2.899024e+02 -1.112036e-04 9.999546e-01 -9.527347e-03 -1.413734e+01 -2.148582e-01 9.280944e-03 9.766011e-01 1.295255e+02 +9.745758e-01 6.160374e-03 2.239735e-01 2.900588e+02 -2.457503e-03 9.998557e-01 -1.680763e-02 -1.416961e+01 -2.240447e-01 1.582989e-02 9.744502e-01 1.301828e+02 +9.723461e-01 1.204043e-02 2.332341e-01 2.902130e+02 -6.386251e-03 9.996675e-01 -2.498255e-02 -1.419655e+01 -2.334573e-01 2.280219e-02 9.720996e-01 1.308211e+02 +9.703111e-01 1.602358e-02 2.413289e-01 2.903682e+02 -9.625385e-03 9.995708e-01 -2.766798e-02 -1.421879e+01 -2.416687e-01 2.452366e-02 9.700488e-01 1.314393e+02 +9.686044e-01 1.804972e-02 2.479511e-01 2.905237e+02 -1.265319e-02 9.996475e-01 -2.334099e-02 -1.424517e+01 -2.482850e-01 1.947081e-02 9.684913e-01 1.320390e+02 +9.670919e-01 1.559798e-02 2.539490e-01 2.906836e+02 -1.304927e-02 9.998462e-01 -1.171787e-02 -1.427296e+01 -2.540927e-01 8.018402e-03 9.671466e-01 1.326260e+02 +9.660759e-01 1.108302e-02 2.580206e-01 2.908457e+02 -1.030489e-02 9.999373e-01 -4.367970e-03 -1.430013e+01 -2.580529e-01 1.560916e-03 9.661295e-01 1.331895e+02 +9.655003e-01 3.299459e-03 2.603811e-01 2.910103e+02 -2.137197e-03 9.999864e-01 -4.746696e-03 -1.432375e+01 -2.603932e-01 4.026449e-03 9.654942e-01 1.337319e+02 +9.653899e-01 -3.073954e-04 2.608110e-01 2.911662e+02 2.050802e-03 9.999773e-01 -6.412443e-03 -1.434499e+01 -2.608031e-01 6.725378e-03 9.653685e-01 1.342620e+02 +9.656345e-01 3.007119e-03 2.598865e-01 2.913078e+02 -1.177049e-04 9.999380e-01 -1.113283e-02 -1.436365e+01 -2.599039e-01 1.071965e-02 9.655749e-01 1.347893e+02 +9.664966e-01 8.454522e-03 2.565403e-01 2.914387e+02 -3.519176e-03 9.997999e-01 -1.969110e-02 -1.438105e+01 -2.566554e-01 1.812856e-02 9.663329e-01 1.353099e+02 +9.681031e-01 4.215975e-03 2.505169e-01 2.915808e+02 1.619359e-03 9.997322e-01 -2.308249e-02 -1.439899e+01 -2.505471e-01 2.275190e-02 9.678370e-01 1.358325e+02 +9.704463e-01 -5.752899e-03 2.412490e-01 2.917267e+02 1.114746e-02 9.997173e-01 -2.100209e-02 -1.441589e+01 -2.410599e-01 2.307071e-02 9.702359e-01 1.363603e+02 +9.734370e-01 -1.201617e-02 2.286396e-01 2.918558e+02 1.628553e-02 9.997263e-01 -1.679525e-02 -1.443191e+01 -2.283752e-01 2.007263e-02 9.733662e-01 1.368918e+02 +9.770671e-01 -1.037141e-02 2.126790e-01 2.919617e+02 1.328393e-02 9.998365e-01 -1.226999e-02 -1.445144e+01 -2.125169e-01 1.481381e-02 9.770450e-01 1.374264e+02 +9.812611e-01 -5.278120e-03 1.926109e-01 2.920425e+02 6.666048e-03 9.999563e-01 -6.558520e-03 -1.447554e+01 -1.925679e-01 7.719572e-03 9.812532e-01 1.379609e+02 +9.860165e-01 -6.979756e-03 1.665017e-01 2.921239e+02 8.059672e-03 9.999506e-01 -5.811091e-03 -1.449602e+01 -1.664529e-01 7.071780e-03 9.860240e-01 1.384900e+02 +9.906926e-01 -9.339760e-03 1.357975e-01 2.921940e+02 1.061907e-02 9.999058e-01 -8.699345e-03 -1.451375e+01 -1.357035e-01 1.006042e-02 9.906984e-01 1.390201e+02 +9.947455e-01 -9.549321e-03 1.019330e-01 2.922216e+02 1.100309e-02 9.998455e-01 -1.370925e-02 -1.453151e+01 -1.017864e-01 1.475879e-02 9.946967e-01 1.395377e+02 +9.979445e-01 -7.546865e-03 6.363957e-02 2.922395e+02 8.781174e-03 9.997783e-01 -1.913796e-02 -1.454607e+01 -6.348102e-02 1.965744e-02 9.977894e-01 1.400685e+02 +9.997695e-01 -6.334002e-03 2.051851e-02 2.922379e+02 6.785853e-03 9.997343e-01 -2.202735e-02 -1.456311e+01 -2.037354e-02 2.216150e-02 9.995467e-01 1.406044e+02 +9.996353e-01 -7.292827e-03 -2.600221e-02 2.921809e+02 6.706055e-03 9.997225e-01 -2.258250e-02 -1.457853e+01 2.615968e-02 2.239989e-02 9.994067e-01 1.411316e+02 +9.971942e-01 -6.751992e-03 -7.455281e-02 2.921276e+02 5.331233e-03 9.998007e-01 -1.923968e-02 -1.459807e+01 7.466785e-02 1.878824e-02 9.970314e-01 1.416769e+02 +9.913688e-01 -4.471404e-03 -1.310267e-01 2.917623e+02 2.263437e-03 9.998530e-01 -1.699536e-02 -1.460962e+01 1.310834e-01 1.655210e-02 9.912331e-01 1.421582e+02 +9.823566e-01 -2.081704e-03 -1.870062e-01 2.913960e+02 -6.730589e-04 9.998922e-01 -1.466616e-02 -1.462098e+01 1.870166e-01 1.453326e-02 9.822492e-01 1.426347e+02 +9.701549e-01 4.076394e-04 -2.424857e-01 2.910295e+02 -3.482536e-03 9.999189e-01 -1.225224e-02 -1.463229e+01 2.424610e-01 1.273103e-02 9.700776e-01 1.431088e+02 +9.548354e-01 2.972094e-03 -2.971206e-01 2.906625e+02 -6.152089e-03 9.999333e-01 -9.768209e-03 -1.464343e+01 2.970717e-01 1.115494e-02 9.547899e-01 1.435781e+02 +9.364252e-01 5.598286e-03 -3.508228e-01 2.902955e+02 -8.682181e-03 9.999362e-01 -7.218125e-03 -1.465447e+01 3.507600e-01 9.805141e-03 9.364140e-01 1.440439e+02 +9.149882e-01 8.267732e-03 -4.033961e-01 2.899287e+02 -1.106815e-02 9.999281e-01 -4.611072e-03 -1.466542e+01 4.033289e-01 8.683926e-03 9.150138e-01 1.445058e+02 +8.905694e-01 1.096540e-02 -4.547153e-01 2.895624e+02 -1.330886e-02 9.999095e-01 -1.952993e-03 -1.467631e+01 4.546527e-01 7.791020e-03 8.906346e-01 1.449646e+02 +8.632689e-01 1.367117e-02 -5.045592e-01 2.891967e+02 -1.539921e-02 9.998811e-01 7.449790e-04 -1.468710e+01 5.045094e-01 7.126699e-03 8.633767e-01 1.454195e+02 +8.331680e-01 1.636851e-02 -5.527778e-01 2.888319e+02 -1.733760e-02 9.998436e-01 3.474853e-03 -1.469782e+01 5.527482e-01 6.688705e-03 8.333214e-01 1.458707e+02 +8.003688e-01 1.904004e-02 -5.992056e-01 2.884681e+02 -1.912204e-02 9.997977e-01 6.227420e-03 -1.470847e+01 5.992029e-01 6.473803e-03 8.005710e-01 1.463181e+02 +7.649758e-01 2.166938e-02 -6.436944e-01 2.881056e+02 -2.075155e-02 9.997442e-01 8.994019e-03 -1.471907e+01 6.437246e-01 6.477454e-03 7.652297e-01 1.467619e+02 +7.270108e-01 2.424637e-02 -6.861979e-01 2.877451e+02 -2.222885e-02 9.996836e-01 1.177224e-02 -1.472969e+01 6.862661e-01 6.694839e-03 7.273197e-01 1.472039e+02 +6.867285e-01 2.674618e-02 -7.264218e-01 2.873860e+02 -2.354827e-02 9.996169e-01 1.454344e-02 -1.474024e+01 7.265325e-01 7.118590e-03 6.870952e-01 1.476415e+02 +6.441627e-01 2.915974e-02 -7.643326e-01 2.870291e+02 -2.471347e-02 9.995448e-01 1.730526e-02 -1.475079e+01 7.644892e-01 7.741906e-03 6.445900e-01 1.480766e+02 +5.995009e-01 3.146954e-02 -7.997552e-01 2.866742e+02 -2.572364e-02 9.994681e-01 2.004545e-02 -1.476132e+01 7.999606e-01 8.555353e-03 5.999915e-01 1.485084e+02 +5.508725e-01 3.437757e-02 -8.338811e-01 2.863994e+02 -2.594433e-02 9.993738e-01 2.406102e-02 -1.478195e+01 8.341861e-01 8.379938e-03 5.514194e-01 1.489762e+02 +5.171396e-01 3.114512e-02 -8.553342e-01 2.858334e+02 -3.136806e-02 9.993560e-01 1.742407e-02 -1.478774e+01 8.553260e-01 1.781950e-02 5.177835e-01 1.493063e+02 +4.904783e-01 3.433853e-02 -8.707767e-01 2.852184e+02 -3.778333e-02 9.991217e-01 1.811770e-02 -1.479780e+01 8.706339e-01 2.401450e-02 4.913449e-01 1.496157e+02 +4.704194e-01 4.280493e-02 -8.814042e-01 2.845719e+02 -4.429686e-02 9.987090e-01 2.485985e-02 -1.480978e+01 8.813304e-01 2.734889e-02 4.717082e-01 1.499194e+02 +4.564363e-01 4.948111e-02 -8.883792e-01 2.839252e+02 -4.686304e-02 9.984035e-01 3.153173e-02 -1.481823e+01 8.885211e-01 2.723993e-02 4.580264e-01 1.502242e+02 +4.467789e-01 5.588476e-02 -8.928973e-01 2.832644e+02 -5.078708e-02 9.980219e-01 3.705200e-02 -1.482401e+01 8.932017e-01 2.879360e-02 4.487333e-01 1.505268e+02 +4.419837e-01 5.896435e-02 -8.950830e-01 2.825986e+02 -5.395537e-02 9.977780e-01 3.908681e-02 -1.481969e+01 8.953989e-01 3.101880e-02 4.441831e-01 1.508355e+02 +4.407294e-01 5.917028e-02 -8.956878e-01 2.819257e+02 -5.792303e-02 9.976201e-01 3.740264e-02 -1.483474e+01 8.957692e-01 3.539650e-02 4.431078e-01 1.511481e+02 +4.413447e-01 5.910100e-02 -8.953893e-01 2.812436e+02 -6.068408e-02 9.975101e-01 3.592991e-02 -1.483739e+01 8.952834e-01 3.847840e-02 4.438322e-01 1.514721e+02 +4.420600e-01 5.878923e-02 -8.950569e-01 2.805534e+02 -6.118167e-02 9.975022e-01 3.530102e-02 -1.484138e+01 8.948965e-01 3.915590e-02 4.445526e-01 1.518054e+02 +4.439269e-01 5.818474e-02 -8.941719e-01 2.798546e+02 -6.232227e-02 9.974779e-01 3.396603e-02 -1.483845e+01 8.938930e-01 4.064839e-02 4.464335e-01 1.521458e+02 +4.463569e-01 5.917448e-02 -8.928964e-01 2.791422e+02 -6.674274e-02 9.972334e-01 3.272462e-02 -1.485001e+01 8.923625e-01 4.498749e-02 4.490714e-01 1.524892e+02 +4.495609e-01 5.830193e-02 -8.913450e-01 2.784185e+02 -6.990870e-02 9.971034e-01 2.996016e-02 -1.486430e+01 8.905098e-01 4.884385e-02 4.523345e-01 1.528470e+02 +4.525449e-01 5.659976e-02 -8.899436e-01 2.776855e+02 -7.527132e-02 9.968465e-01 2.512253e-02 -1.488056e+01 8.885591e-01 5.561815e-02 4.553781e-01 1.532088e+02 +4.561196e-01 5.547102e-02 -8.881880e-01 2.769430e+02 -7.760443e-02 9.967326e-01 2.239715e-02 -1.489145e+01 8.865283e-01 5.871154e-02 4.589341e-01 1.535835e+02 +4.597848e-01 5.605008e-02 -8.862598e-01 2.761870e+02 -7.742938e-02 9.967355e-01 2.286718e-02 -1.490243e+01 8.846483e-01 5.810855e-02 4.626238e-01 1.539729e+02 +4.636368e-01 5.779616e-02 -8.841383e-01 2.754205e+02 -7.851917e-02 9.966243e-01 2.397440e-02 -1.491059e+01 8.825393e-01 5.830638e-02 4.666098e-01 1.543706e+02 +4.671865e-01 6.054826e-02 -8.820832e-01 2.746402e+02 -7.951878e-02 9.964867e-01 2.628488e-02 -1.491202e+01 8.805756e-01 5.786223e-02 4.703599e-01 1.547801e+02 +4.696492e-01 6.065301e-02 -8.807672e-01 2.738488e+02 -7.924542e-02 9.965063e-01 2.636743e-02 -1.491226e+01 8.792893e-01 5.741332e-02 4.728149e-01 1.552017e+02 +4.713839e-01 5.851986e-02 -8.799845e-01 2.730503e+02 -7.647763e-02 9.967498e-01 2.531788e-02 -1.491816e+01 8.786059e-01 5.536468e-02 4.743272e-01 1.556341e+02 +4.724708e-01 5.597397e-02 -8.795671e-01 2.722412e+02 -7.425683e-02 9.969609e-01 2.355668e-02 -1.493058e+01 8.782125e-01 5.418402e-02 4.751914e-01 1.560747e+02 +4.732616e-01 5.450978e-02 -8.792339e-01 2.714235e+02 -7.325586e-02 9.970619e-01 2.238364e-02 -1.493703e+01 8.778707e-01 5.381571e-02 4.758643e-01 1.565160e+02 +4.741148e-01 5.726319e-02 -8.785990e-01 2.705906e+02 -7.356616e-02 9.969699e-01 2.527988e-02 -1.493860e+01 8.773843e-01 5.264958e-02 4.768907e-01 1.569672e+02 +4.751844e-01 6.203666e-02 -8.776966e-01 2.697527e+02 -7.372503e-02 9.968108e-01 3.054112e-02 -1.493865e+01 8.767921e-01 5.019554e-02 4.782426e-01 1.574220e+02 +4.773532e-01 6.723742e-02 -8.761354e-01 2.689095e+02 -7.485073e-02 9.965556e-01 3.569723e-02 -1.493740e+01 8.755177e-01 4.853918e-02 4.807417e-01 1.578809e+02 +4.803400e-01 6.321322e-02 -8.748015e-01 2.680716e+02 -7.387211e-02 9.967712e-01 3.146474e-02 -1.493337e+01 8.739659e-01 4.950965e-02 4.834587e-01 1.583428e+02 +4.834496e-01 5.504520e-02 -8.736399e-01 2.672366e+02 -7.309837e-02 9.970738e-01 2.237164e-02 -1.492951e+01 8.723148e-01 5.304609e-02 4.860585e-01 1.588076e+02 +4.870183e-01 5.042459e-02 -8.719349e-01 2.663931e+02 -7.411799e-02 9.971168e-01 1.626542e-02 -1.492764e+01 8.702411e-01 5.670450e-02 4.893515e-01 1.592788e+02 +4.909782e-01 5.233890e-02 -8.695983e-01 2.655431e+02 -7.578582e-02 9.969755e-01 1.721649e-02 -1.493282e+01 8.678692e-01 5.745029e-02 4.934597e-01 1.597433e+02 +4.965062e-01 5.730163e-02 -8.661398e-01 2.646843e+02 -7.574002e-02 9.968729e-01 2.253339e-02 -1.495190e+01 8.647225e-01 5.441347e-02 4.992935e-01 1.602224e+02 +5.037342e-01 6.233516e-02 -8.616068e-01 2.638317e+02 -7.602554e-02 9.967221e-01 2.766248e-02 -1.496713e+01 8.605068e-01 5.156958e-02 5.068220e-01 1.607122e+02 +5.123371e-01 6.398076e-02 -8.563978e-01 2.629761e+02 -7.693836e-02 9.966304e-01 2.842931e-02 -1.497995e+01 8.553310e-01 5.132445e-02 5.155333e-01 1.612125e+02 +5.211720e-01 6.170989e-02 -8.512178e-01 2.621606e+02 -7.669410e-02 9.967336e-01 2.530200e-02 -1.497143e+01 8.499987e-01 5.209668e-02 5.242023e-01 1.617093e+02 +5.301848e-01 5.702590e-02 -8.459623e-01 2.613431e+02 -7.311648e-02 9.970940e-01 2.138978e-02 -1.495873e+01 8.447236e-01 5.051324e-02 5.328136e-01 1.622294e+02 +5.393351e-01 5.538765e-02 -8.402678e-01 2.605331e+02 -6.992809e-02 9.973340e-01 2.085683e-02 -1.495181e+01 8.391828e-01 4.750950e-02 5.417703e-01 1.627589e+02 +5.480156e-01 5.619910e-02 -8.345781e-01 2.597251e+02 -6.912712e-02 9.973703e-01 2.176978e-02 -1.494049e+01 8.336068e-01 4.576179e-02 5.504593e-01 1.632934e+02 +5.568587e-01 5.632836e-02 -8.286951e-01 2.589277e+02 -6.583899e-02 9.975520e-01 2.356410e-02 -1.492164e+01 8.279937e-01 4.143857e-02 5.592041e-01 1.638391e+02 +5.649508e-01 5.472345e-02 -8.233080e-01 2.581366e+02 -5.928442e-02 9.979116e-01 2.564824e-02 -1.490177e+01 8.229921e-01 3.431934e-02 5.670151e-01 1.643956e+02 +5.713244e-01 5.475531e-02 -8.188958e-01 2.573499e+02 -5.660736e-02 9.980248e-01 2.723913e-02 -1.488677e+01 8.187698e-01 3.079316e-02 5.732954e-01 1.649528e+02 +5.760926e-01 5.210708e-02 -8.157219e-01 2.565679e+02 -5.185624e-02 9.982855e-01 2.714621e-02 -1.487254e+01 8.157378e-01 2.666154e-02 5.778069e-01 1.655157e+02 +5.790174e-01 4.523714e-02 -8.140593e-01 2.557909e+02 -4.260851e-02 9.987741e-01 2.519549e-02 -1.485131e+01 8.142011e-01 2.009722e-02 5.802350e-01 1.660834e+02 +5.795838e-01 4.026331e-02 -8.139174e-01 2.550110e+02 -3.576372e-02 9.990731e-01 2.395566e-02 -1.482236e+01 8.141275e-01 1.522440e-02 5.804865e-01 1.666515e+02 +5.781798e-01 3.952305e-02 -8.149516e-01 2.542206e+02 -3.188346e-02 9.991576e-01 2.583637e-02 -1.478342e+01 8.152862e-01 1.104542e-02 5.789528e-01 1.672198e+02 +5.748458e-01 4.141828e-02 -8.172129e-01 2.534213e+02 -3.005098e-02 9.991130e-01 2.949888e-02 -1.476026e+01 8.177098e-01 7.600747e-03 5.755805e-01 1.677851e+02 +5.700229e-01 3.909996e-02 -8.206980e-01 2.526195e+02 -2.584412e-02 9.992260e-01 2.965520e-02 -1.472574e+01 8.212222e-01 4.306082e-03 5.705922e-01 1.683511e+02 +5.646348e-01 3.657263e-02 -8.245302e-01 2.518124e+02 -1.877016e-02 9.993283e-01 3.147221e-02 -1.469464e+01 8.251274e-01 -2.293737e-03 5.649420e-01 1.689153e+02 +5.582592e-01 3.740193e-02 -8.288232e-01 2.509912e+02 -2.063112e-02 9.993002e-01 3.119876e-02 -1.465667e+01 8.294101e-01 -3.174385e-04 5.586401e-01 1.694706e+02 +5.515355e-01 3.922665e-02 -8.332286e-01 2.501643e+02 -2.350498e-02 9.992278e-01 3.148300e-02 -1.461797e+01 8.338202e-01 2.221032e-03 5.520316e-01 1.700182e+02 +5.440084e-01 3.333297e-02 -8.384175e-01 2.493429e+02 -1.950330e-02 9.994430e-01 2.708012e-02 -1.457610e+01 8.388531e-01 1.620096e-03 5.443554e-01 1.705648e+02 +5.373406e-01 2.653666e-02 -8.429478e-01 2.485162e+02 -1.534386e-02 9.996470e-01 2.168867e-02 -1.454374e+01 8.432257e-01 1.279870e-03 5.375581e-01 1.711031e+02 +5.311679e-01 2.269359e-02 -8.469626e-01 2.476823e+02 -1.096373e-02 9.997416e-01 1.991132e-02 -1.451402e+01 8.471956e-01 -1.290385e-03 5.312795e-01 1.716359e+02 +5.239739e-01 2.746361e-02 -8.512915e-01 2.468297e+02 -8.776716e-03 9.996010e-01 2.684614e-02 -1.448307e+01 8.516891e-01 -6.595125e-03 5.240058e-01 1.721711e+02 +5.170137e-01 2.948047e-02 -8.554693e-01 2.459791e+02 -1.669024e-03 9.994395e-01 3.343317e-02 -1.445692e+01 8.559754e-01 -1.585760e-02 5.167731e-01 1.727018e+02 +5.102721e-01 2.883266e-02 -8.595296e-01 2.451263e+02 4.521727e-03 9.993341e-01 3.620675e-02 -1.442624e+01 8.600011e-01 -2.236185e-02 5.098019e-01 1.732240e+02 +5.037941e-01 2.790445e-02 -8.633730e-01 2.442688e+02 7.586430e-03 9.992966e-01 3.672437e-02 -1.440057e+01 8.637904e-01 -2.505143e-02 5.032280e-01 1.737284e+02 +4.969454e-01 2.661618e-02 -8.673736e-01 2.434072e+02 9.429590e-03 9.993049e-01 3.606713e-02 -1.437066e+01 8.677305e-01 -2.610236e-02 4.963489e-01 1.742274e+02 +4.900908e-01 2.130586e-02 -8.714110e-01 2.425488e+02 1.474679e-02 9.993555e-01 3.272783e-02 -1.434179e+01 8.715466e-01 -2.889011e-02 4.894607e-01 1.747220e+02 +4.835622e-01 1.711863e-02 -8.751426e-01 2.416878e+02 1.784857e-02 9.994080e-01 2.941165e-02 -1.431200e+01 8.751280e-01 -2.984239e-02 4.829703e-01 1.752111e+02 +4.782141e-01 1.551209e-02 -8.781063e-01 2.408196e+02 1.970680e-02 9.994027e-01 2.838710e-02 -1.428753e+01 8.780221e-01 -3.087976e-02 4.776228e-01 1.756926e+02 +4.735843e-01 1.691760e-02 -8.805861e-01 2.399455e+02 2.170171e-02 9.992878e-01 3.086938e-02 -1.426868e+01 8.804811e-01 -3.372947e-02 4.728798e-01 1.761723e+02 +4.694526e-01 2.047347e-02 -8.827203e-01 2.390666e+02 2.280313e-02 9.991165e-01 3.530040e-02 -1.425265e+01 8.826631e-01 -3.670064e-02 4.685710e-01 1.766464e+02 +4.655699e-01 2.519035e-02 -8.846526e-01 2.381863e+02 1.837166e-02 9.991043e-01 3.811789e-02 -1.423471e+01 8.848204e-01 -3.399907e-02 4.646901e-01 1.771088e+02 +4.632740e-01 2.635855e-02 -8.858231e-01 2.373097e+02 1.891660e-02 9.990357e-01 3.962045e-02 -1.421372e+01 8.860132e-01 -3.511187e-02 4.623286e-01 1.775718e+02 +4.618357e-01 2.831917e-02 -8.865133e-01 2.364351e+02 1.678627e-02 9.990321e-01 4.065846e-02 -1.418734e+01 8.868066e-01 -3.365876e-02 4.609133e-01 1.780277e+02 +4.619413e-01 2.846357e-02 -8.864537e-01 2.355599e+02 1.206805e-02 9.991906e-01 3.837230e-02 -1.416623e+01 8.868284e-01 -2.842350e-02 4.612238e-01 1.784782e+02 +4.618181e-01 2.279829e-02 -8.866817e-01 2.346932e+02 1.193017e-02 9.994195e-01 3.191070e-02 -1.414473e+01 8.868944e-01 -2.531519e-02 4.612780e-01 1.789321e+02 +4.616016e-01 1.798896e-02 -8.869050e-01 2.338286e+02 1.215064e-02 9.995723e-01 2.659814e-02 -1.411729e+01 8.870041e-01 -2.305420e-02 4.611856e-01 1.793917e+02 +4.623985e-01 1.726948e-02 -8.865040e-01 2.329645e+02 1.537525e-02 9.995038e-01 2.749046e-02 -1.410097e+01 8.865389e-01 -2.634176e-02 4.619035e-01 1.798511e+02 +4.642328e-01 1.804312e-02 -8.855294e-01 2.321043e+02 1.152037e-02 9.995849e-01 2.640654e-02 -1.409140e+01 8.856382e-01 -2.246040e-02 4.638322e-01 1.803056e+02 +4.672270e-01 1.580026e-02 -8.839962e-01 2.312512e+02 6.991158e-03 9.997430e-01 2.156419e-02 -1.408309e+01 8.841097e-01 -1.625552e-02 4.669965e-01 1.807526e+02 +4.700517e-01 1.428596e-02 -8.825233e-01 2.304022e+02 2.619721e-03 9.998420e-01 1.758040e-02 -1.406977e+01 8.826350e-01 -1.057565e-02 4.699400e-01 1.812038e+02 +4.727249e-01 1.920178e-02 -8.810009e-01 2.295516e+02 2.912329e-04 9.997591e-01 2.194644e-02 -1.406684e+01 8.812100e-01 -1.063120e-02 4.726054e-01 1.816586e+02 +4.750387e-01 2.438918e-02 -8.796269e-01 2.287077e+02 -2.073831e-03 9.996441e-01 2.659690e-02 -1.406108e+01 8.799625e-01 -1.081035e-02 4.749201e-01 1.821131e+02 +4.769137e-01 2.715035e-02 -8.785307e-01 2.278697e+02 -2.067665e-03 9.995547e-01 2.976807e-02 -1.404863e+01 8.789476e-01 -1.238029e-02 4.767575e-01 1.825698e+02 +4.774260e-01 2.860964e-02 -8.782061e-01 2.270432e+02 5.237217e-04 9.994603e-01 3.284450e-02 -1.403677e+01 8.786718e-01 -1.614075e-02 4.771533e-01 1.830248e+02 +4.767459e-01 2.907285e-02 -8.785603e-01 2.262149e+02 3.056755e-03 9.993920e-01 3.473008e-02 -1.401951e+01 8.790358e-01 -1.924296e-02 4.763671e-01 1.834845e+02 +4.755753e-01 2.885000e-02 -8.792018e-01 2.253932e+02 3.142599e-03 9.993999e-01 3.449405e-02 -1.400774e+01 8.796694e-01 -1.916749e-02 4.751992e-01 1.839336e+02 +4.746047e-01 2.601797e-02 -8.798145e-01 2.245795e+02 3.465267e-03 9.995000e-01 3.142663e-02 -1.399773e+01 8.801922e-01 -1.796401e-02 4.742773e-01 1.843764e+02 +4.736067e-01 2.283874e-02 -8.804403e-01 2.237699e+02 1.192063e-03 9.996462e-01 2.657220e-02 -1.398644e+01 8.807356e-01 -1.363431e-02 4.734119e-01 1.848117e+02 +4.729552e-01 2.428356e-02 -8.807518e-01 2.229616e+02 -2.894965e-03 9.996575e-01 2.600739e-02 -1.396843e+01 8.810817e-01 -9.750578e-03 4.728635e-01 1.852426e+02 +4.718172e-01 2.793270e-02 -8.812538e-01 2.221602e+02 -4.042620e-03 9.995560e-01 2.951809e-02 -1.395469e+01 8.816871e-01 -1.036456e-02 4.717207e-01 1.856726e+02 +4.703146e-01 3.021966e-02 -8.819813e-01 2.213673e+02 2.475656e-04 9.994089e-01 3.437514e-02 -1.394050e+01 8.824988e-01 -1.638547e-02 4.700291e-01 1.861071e+02 +4.689199e-01 3.163535e-02 -8.826740e-01 2.205869e+02 4.725210e-03 9.992542e-01 3.832389e-02 -1.392145e+01 8.832280e-01 -2.214165e-02 4.684206e-01 1.865343e+02 +4.675889e-01 3.394553e-02 -8.832941e-01 2.198147e+02 1.874438e-03 9.992220e-01 3.939299e-02 -1.391172e+01 8.839440e-01 -2.007539e-02 4.671614e-01 1.869443e+02 +4.661391e-01 3.000521e-02 -8.842025e-01 2.190592e+02 3.993942e-04 9.994175e-01 3.412556e-02 -1.390122e+01 8.847113e-01 -1.626039e-02 4.658555e-01 1.873440e+02 +4.643023e-01 1.892128e-02 -8.854747e-01 2.183174e+02 3.894118e-03 9.997185e-01 2.340440e-02 -1.389010e+01 8.856682e-01 -1.431485e-02 4.640979e-01 1.877425e+02 +4.628199e-01 1.399383e-02 -8.863419e-01 2.175792e+02 8.092561e-03 9.997670e-01 2.001030e-02 -1.387919e+01 8.864154e-01 -1.643393e-02 4.625988e-01 1.881373e+02 +4.615098e-01 1.944890e-02 -8.869219e-01 2.168437e+02 6.723798e-03 9.996542e-01 2.541969e-02 -1.387317e+01 8.871096e-01 -1.769491e-02 4.612194e-01 1.885212e+02 +4.593783e-01 3.048412e-02 -8.877175e-01 2.161150e+02 4.768152e-03 9.993119e-01 3.678369e-02 -1.387181e+01 8.882279e-01 -2.113039e-02 4.589168e-01 1.888953e+02 +4.572805e-01 3.358023e-02 -8.886883e-01 2.154108e+02 5.641299e-03 9.991572e-01 4.065722e-02 -1.386559e+01 8.893046e-01 -2.360510e-02 4.567057e-01 1.892597e+02 +4.551794e-01 2.889664e-02 -8.899308e-01 2.147303e+02 5.942319e-03 9.993524e-01 3.548900e-02 -1.385704e+01 8.903799e-01 -2.144211e-02 4.547129e-01 1.896122e+02 +4.536993e-01 2.497728e-02 -8.908048e-01 2.140622e+02 3.270306e-03 9.995537e-01 2.969211e-02 -1.384865e+01 8.911488e-01 -1.638449e-02 4.534151e-01 1.899494e+02 +4.529661e-01 2.483148e-02 -8.911819e-01 2.134036e+02 -6.709007e-04 9.996212e-01 2.751198e-02 -1.384168e+01 8.915275e-01 -1.186409e-02 4.528111e-01 1.902779e+02 +4.517110e-01 2.848173e-02 -8.917096e-01 2.127616e+02 -1.972238e-03 9.995197e-01 3.092618e-02 -1.384026e+01 8.921621e-01 -1.221103e-02 4.515502e-01 1.906006e+02 +4.505465e-01 3.068438e-02 -8.922255e-01 2.121380e+02 -2.918172e-03 9.994544e-01 3.289849e-02 -1.383654e+01 8.927482e-01 -1.221862e-02 4.503902e-01 1.909167e+02 +4.493466e-01 3.472918e-02 -8.926822e-01 2.115271e+02 -7.228593e-03 9.993527e-01 3.524049e-02 -1.382577e+01 8.933282e-01 -9.382352e-03 4.493068e-01 1.912219e+02 +4.482361e-01 3.995274e-02 -8.930220e-01 2.109341e+02 -9.529233e-03 9.991575e-01 3.991810e-02 -1.381376e+01 8.938644e-01 -9.382912e-03 4.482392e-01 1.915188e+02 +4.472812e-01 4.107426e-02 -8.934498e-01 2.103623e+02 -6.698120e-03 9.990707e-01 4.257672e-02 -1.380460e+01 8.943683e-01 -1.305933e-02 4.471407e-01 1.918132e+02 +4.462374e-01 3.961846e-02 -8.940373e-01 2.098176e+02 -3.841588e-03 9.990951e-01 4.235658e-02 -1.380196e+01 8.949063e-01 -1.546656e-02 4.459858e-01 1.920958e+02 +4.467443e-01 3.482255e-02 -8.939838e-01 2.092935e+02 -3.653884e-03 9.993049e-01 3.709910e-02 -1.379138e+01 8.946542e-01 -1.330729e-02 4.465610e-01 1.923649e+02 +4.479671e-01 3.186131e-02 -8.934822e-01 2.087857e+02 -5.657310e-03 9.994458e-01 3.280353e-02 -1.377793e+01 8.940321e-01 -9.640190e-03 4.478990e-01 1.926184e+02 +4.491810e-01 3.192326e-02 -8.928703e-01 2.082977e+02 -6.820188e-03 9.994548e-01 3.230297e-02 -1.376580e+01 8.934147e-01 -8.420330e-03 4.491538e-01 1.928681e+02 +4.520879e-01 3.286185e-02 -8.913679e-01 2.078314e+02 -5.236514e-03 9.994016e-01 3.418883e-02 -1.376168e+01 8.919580e-01 -1.078869e-02 4.519894e-01 1.931133e+02 +4.561874e-01 3.594035e-02 -8.891577e-01 2.073857e+02 -5.469835e-03 9.992784e-01 3.758518e-02 -1.376465e+01 8.898669e-01 -1.228233e-02 4.560548e-01 1.933514e+02 +4.608607e-01 3.637360e-02 -8.867268e-01 2.069682e+02 -6.138347e-03 9.992665e-01 3.779970e-02 -1.375997e+01 8.874512e-01 -1.197735e-02 4.607459e-01 1.935784e+02 +4.658034e-01 3.343784e-02 -8.842563e-01 2.065767e+02 -3.899857e-03 9.993536e-01 3.573587e-02 -1.374741e+01 8.848796e-01 -1.319741e-02 4.656327e-01 1.937983e+02 +4.720979e-01 3.154808e-02 -8.809815e-01 2.062106e+02 -3.115087e-03 9.994129e-01 3.411983e-02 -1.373804e+01 8.815406e-01 -1.336356e-02 4.719190e-01 1.940068e+02 +4.794562e-01 3.261563e-02 -8.769595e-01 2.058653e+02 -2.715488e-03 9.993594e-01 3.568328e-02 -1.372880e+01 8.775616e-01 -1.472719e-02 4.792376e-01 1.942062e+02 +4.863374e-01 3.745268e-02 -8.729681e-01 2.055399e+02 -4.215510e-03 9.991699e-01 4.051859e-02 -1.371886e+01 8.737609e-01 -1.602569e-02 4.860915e-01 1.943956e+02 +4.943822e-01 4.274491e-02 -8.681930e-01 2.052423e+02 -5.585015e-03 9.989258e-01 4.600114e-02 -1.371347e+01 8.692267e-01 -1.789327e-02 4.940898e-01 1.945792e+02 +5.030600e-01 4.525584e-02 -8.630658e-01 2.049738e+02 -7.000773e-03 9.988087e-01 4.829310e-02 -1.371400e+01 8.642231e-01 -1.825219e-02 5.027775e-01 1.947476e+02 +5.118968e-01 4.561105e-02 -8.578353e-01 2.047297e+02 -8.865431e-03 9.988168e-01 4.781676e-02 -1.371641e+01 8.590012e-01 -1.687216e-02 5.116954e-01 1.949016e+02 +5.214969e-01 4.521142e-02 -8.520545e-01 2.045148e+02 -1.018415e-02 9.988539e-01 4.676766e-02 -1.371967e+01 8.531923e-01 -1.571173e-02 5.213596e-01 1.950410e+02 +5.301027e-01 4.374822e-02 -8.468042e-01 2.043163e+02 -9.813257e-03 9.989178e-01 4.546370e-02 -1.372167e+01 8.478766e-01 -1.579051e-02 5.299583e-01 1.951811e+02 +5.384578e-01 4.059801e-02 -8.416740e-01 2.041223e+02 -8.135773e-03 9.990426e-01 4.298384e-02 -1.372114e+01 8.426132e-01 -1.629731e-02 5.382725e-01 1.953215e+02 +5.465675e-01 3.745693e-02 -8.365770e-01 2.039306e+02 -8.478972e-03 9.991955e-01 3.919840e-02 -1.372379e+01 8.373721e-01 -1.433125e-02 5.464453e-01 1.954618e+02 +5.545530e-01 3.577840e-02 -8.313789e-01 2.037374e+02 -1.105057e-02 9.993038e-01 3.563402e-02 -1.372460e+01 8.320750e-01 -1.057373e-02 5.545623e-01 1.956023e+02 +5.627119e-01 3.474146e-02 -8.259228e-01 2.035463e+02 -1.348840e-02 9.993693e-01 3.284747e-02 -1.372293e+01 8.265430e-01 -7.343276e-03 5.628256e-01 1.957452e+02 +5.705820e-01 3.319930e-02 -8.205693e-01 2.033726e+02 -1.504083e-02 9.994374e-01 2.997747e-02 -1.371801e+01 8.211028e-01 -4.762561e-03 5.707603e-01 1.959171e+02 +5.780036e-01 2.966194e-02 -8.154950e-01 2.032102e+02 -1.387787e-02 9.995519e-01 2.652033e-02 -1.371300e+01 8.159162e-01 -4.011508e-03 5.781562e-01 1.961058e+02 +5.854633e-01 2.690854e-02 -8.102523e-01 2.030429e+02 -1.249317e-02 9.996298e-01 2.417061e-02 -1.371067e+01 8.106027e-01 -4.028380e-03 5.855826e-01 1.962824e+02 +5.930122e-01 2.631166e-02 -8.047635e-01 2.028747e+02 -1.369308e-02 9.996509e-01 2.259337e-02 -1.370872e+01 8.050771e-01 -2.378443e-03 5.931654e-01 1.964607e+02 +6.001986e-01 2.823031e-02 -7.993527e-01 2.026968e+02 -1.842488e-02 9.995997e-01 2.146790e-02 -1.370926e+01 7.996388e-01 1.842978e-03 6.004784e-01 1.966206e+02 +6.069455e-01 3.200059e-02 -7.940990e-01 2.025157e+02 -2.422065e-02 9.994697e-01 2.176430e-02 -1.370786e+01 7.943743e-01 6.023855e-03 6.073986e-01 1.967881e+02 +6.133084e-01 3.538476e-02 -7.890506e-01 2.023296e+02 -2.866225e-02 9.993350e-01 2.253649e-02 -1.370617e+01 7.893233e-01 8.794153e-03 6.139147e-01 1.969507e+02 +6.195930e-01 3.070439e-02 -7.843226e-01 2.021442e+02 -2.736788e-02 9.994721e-01 1.750714e-02 -1.370430e+01 7.844460e-01 1.061795e-02 6.201061e-01 1.971330e+02 +6.259051e-01 2.123132e-02 -7.796102e-01 2.019454e+02 -2.370683e-02 9.996854e-01 8.191808e-03 -1.370466e+01 7.795388e-01 1.335480e-02 6.262115e-01 1.973255e+02 +6.316219e-01 1.322153e-02 -7.751639e-01 2.017259e+02 -2.057036e-02 9.997883e-01 2.916079e-04 -1.370537e+01 7.750037e-01 1.576122e-02 6.317601e-01 1.975340e+02 +6.368497e-01 1.128826e-02 -7.709054e-01 2.014737e+02 -2.150214e-02 9.997639e-01 -3.123649e-03 -1.370834e+01 7.706881e-01 1.856541e-02 6.369420e-01 1.977594e+02 +6.407806e-01 1.435373e-02 -7.675899e-01 2.011953e+02 -2.453023e-02 9.996975e-01 -1.783642e-03 -1.371162e+01 7.673321e-01 1.997208e-02 6.409388e-01 1.980000e+02 +6.427590e-01 1.719987e-02 -7.658753e-01 2.008951e+02 -2.609284e-02 9.996593e-01 5.517974e-04 -1.371056e+01 7.656239e-01 1.962919e-02 6.429888e-01 1.982595e+02 +6.424791e-01 1.954642e-02 -7.660540e-01 2.005732e+02 -3.036962e-02 9.995387e-01 3.336422e-05 -1.370783e+01 7.657012e-01 2.324333e-02 6.427763e-01 1.985288e+02 +6.404168e-01 2.053883e-02 -7.677529e-01 2.002274e+02 -3.506204e-02 9.993820e-01 -2.511452e-03 -1.370269e+01 7.672268e-01 2.852736e-02 6.407411e-01 1.988085e+02 +6.367910e-01 2.126632e-02 -7.707432e-01 1.998632e+02 -3.585757e-02 9.993548e-01 -2.051485e-03 -1.370194e+01 7.702022e-01 2.894334e-02 6.371426e-01 1.991068e+02 +6.329430e-01 2.147065e-02 -7.739006e-01 1.994820e+02 -3.134706e-02 9.995063e-01 2.092193e-03 -1.370715e+01 7.735635e-01 2.293527e-02 6.333036e-01 1.994285e+02 +6.279217e-01 2.389882e-02 -7.779096e-01 1.990768e+02 -2.939477e-02 9.995435e-01 6.980623e-03 -1.371403e+01 7.777212e-01 1.848319e-02 6.283375e-01 1.997600e+02 +6.216983e-01 2.770993e-02 -7.827665e-01 1.986508e+02 -2.831573e-02 9.995158e-01 1.289360e-02 -1.371219e+01 7.827448e-01 1.414868e-02 6.221819e-01 2.001013e+02 +6.138574e-01 3.550098e-02 -7.886183e-01 1.981987e+02 -3.056402e-02 9.993081e-01 2.119463e-02 -1.370683e+01 7.888250e-01 1.109287e-02 6.145177e-01 2.004467e+02 +6.051325e-01 4.101799e-02 -7.950675e-01 1.977307e+02 -3.257744e-02 9.991112e-01 2.674977e-02 -1.369801e+01 7.954580e-01 9.714111e-03 6.059308e-01 2.007917e+02 +5.959167e-01 4.341784e-02 -8.018717e-01 1.972529e+02 -3.091400e-02 9.990375e-01 3.111955e-02 -1.369486e+01 8.024510e-01 6.244404e-03 5.966852e-01 2.011456e+02 +5.868903e-01 4.366091e-02 -8.084884e-01 1.967611e+02 -2.548603e-02 9.990464e-01 3.545107e-02 -1.368933e+01 8.092652e-01 -2.007230e-04 5.874433e-01 2.015088e+02 +5.774318e-01 3.850325e-02 -8.155305e-01 1.962530e+02 -1.971235e-02 9.992536e-01 3.322007e-02 -1.367872e+01 8.162009e-01 -3.106295e-03 5.777598e-01 2.018720e+02 +5.677095e-01 3.186389e-02 -8.226121e-01 1.957323e+02 -1.557899e-02 9.994875e-01 2.796363e-02 -1.366522e+01 8.230816e-01 -3.059751e-03 5.679149e-01 2.022339e+02 +5.571491e-01 2.847505e-02 -8.299241e-01 1.951849e+02 -1.378596e-02 9.995913e-01 2.504155e-02 -1.365300e+01 8.302980e-01 -2.510572e-03 5.573140e-01 2.025990e+02 +5.464707e-01 2.428149e-02 -8.371262e-01 1.946237e+02 -9.969527e-03 9.996974e-01 2.248896e-02 -1.364311e+01 8.374189e-01 -3.943797e-03 5.465473e-01 2.029671e+02 +5.424802e-01 2.376208e-02 -8.397325e-01 1.939554e+02 -8.732601e-03 9.997054e-01 2.264747e-02 -1.363086e+01 8.400232e-01 -4.952749e-03 5.425278e-01 2.033509e+02 +5.384823e-01 2.325272e-02 -8.423160e-01 1.932881e+02 -7.496301e-03 9.997118e-01 2.280546e-02 -1.361862e+01 8.426034e-01 -5.966077e-03 5.385014e-01 2.037342e+02 +5.344663e-01 2.275211e-02 -8.448835e-01 1.926198e+02 -6.257289e-03 9.997167e-01 2.296335e-02 -1.360636e+01 8.451666e-01 -6.986455e-03 5.344573e-01 2.041179e+02 +5.304375e-01 2.226094e-02 -8.474317e-01 1.919516e+02 -5.017165e-03 9.997201e-01 2.312095e-02 -1.359410e+01 8.477092e-01 -8.012507e-03 5.304007e-01 2.045017e+02 +5.263973e-01 2.177941e-02 -8.499598e-01 1.912835e+02 -3.776330e-03 9.997219e-01 2.327817e-02 -1.358184e+01 8.502303e-01 -9.043832e-03 5.263331e-01 2.048853e+02 +5.223440e-01 2.130736e-02 -8.524687e-01 1.906153e+02 -2.534266e-03 9.997221e-01 2.343510e-02 -1.356958e+01 8.527311e-01 -1.008080e-02 5.222528e-01 2.052690e+02 +5.182782e-01 2.084488e-02 -8.549581e-01 1.899472e+02 -1.291088e-03 9.997208e-01 2.359171e-02 -1.355732e+01 8.552111e-01 -1.112324e-02 5.181603e-01 2.056527e+02 +5.142000e-01 2.039202e-02 -8.574279e-01 1.892790e+02 -4.684839e-05 9.997180e-01 2.374799e-02 -1.354506e+01 8.576703e-01 -1.217104e-02 5.140559e-01 2.060363e+02 +5.101148e-01 1.994937e-02 -8.598750e-01 1.886116e+02 1.196902e-03 9.997135e-01 2.390373e-02 -1.353281e+01 8.601054e-01 -1.322283e-02 5.099448e-01 2.064195e+02 +5.060127e-01 1.951589e-02 -8.623053e-01 1.879435e+02 2.443210e-03 9.997075e-01 2.405932e-02 -1.352055e+01 8.625226e-01 -1.428111e-02 5.058169e-01 2.068031e+02 +5.018984e-01 1.909215e-02 -8.647159e-01 1.872753e+02 3.690598e-03 9.996999e-01 2.421458e-02 -1.350828e+01 8.649187e-01 -1.534457e-02 5.016773e-01 2.071867e+02 +4.977778e-01 1.867872e-02 -8.671035e-01 1.866080e+02 4.937409e-03 9.996908e-01 2.436927e-02 -1.349603e+01 8.672905e-01 -1.641172e-02 4.975316e-01 2.075698e+02 +4.936400e-01 1.827458e-02 -8.694744e-01 1.859399e+02 6.186880e-03 9.996801e-01 2.452381e-02 -1.348376e+01 8.696443e-01 -1.748526e-02 4.933690e-01 2.079534e+02 +4.894959e-01 1.788079e-02 -8.718223e-01 1.852726e+02 7.435807e-03 9.996678e-01 2.467780e-02 -1.347150e+01 8.719739e-01 -1.856238e-02 4.892003e-01 2.083365e+02 +4.853355e-01 1.749644e-02 -8.741530e-01 1.846045e+02 8.687236e-03 9.996539e-01 2.483160e-02 -1.345923e+01 8.742848e-01 -1.964562e-02 4.850155e-01 2.087201e+02 +4.806292e-01 1.721423e-02 -8.767550e-01 1.839471e+02 1.022455e-02 9.996293e-01 2.523176e-02 -1.344679e+01 8.768643e-01 -2.109154e-02 4.802750e-01 2.091004e+02 +4.806903e-01 1.613907e-02 -8.767419e-01 1.832041e+02 9.232008e-03 9.996820e-01 2.346378e-02 -1.343628e+01 8.768418e-01 -1.937289e-02 4.803885e-01 2.095084e+02 +4.808418e-01 1.803466e-02 -8.766219e-01 1.824520e+02 9.369177e-03 9.996257e-01 2.570436e-02 -1.342599e+01 8.767573e-01 -2.057295e-02 4.804928e-01 2.099238e+02 +4.811037e-01 2.114766e-02 -8.764086e-01 1.816952e+02 1.179488e-02 9.994623e-01 3.059172e-02 -1.341608e+01 8.765843e-01 -2.505492e-02 4.805955e-01 2.103474e+02 +4.812579e-01 2.621332e-02 -8.761871e-01 1.809299e+02 1.304140e-02 9.992280e-01 3.705757e-02 -1.340242e+01 8.764820e-01 -2.926094e-02 4.805444e-01 2.107743e+02 +4.816574e-01 2.942202e-02 -8.758656e-01 1.801626e+02 1.402504e-02 9.990495e-01 4.127269e-02 -1.338372e+01 8.762473e-01 -3.216334e-02 4.807869e-01 2.112023e+02 +4.822548e-01 3.144000e-02 -8.754667e-01 1.793913e+02 1.015670e-02 9.990879e-01 4.147440e-02 -1.336666e+01 8.759721e-01 -2.889307e-02 4.814956e-01 2.116252e+02 +4.833627e-01 3.187627e-02 -8.748397e-01 1.786193e+02 5.062070e-03 9.992183e-01 3.920509e-02 -1.334759e+01 8.754055e-01 -2.337877e-02 4.828234e-01 2.120481e+02 +4.837351e-01 2.753810e-02 -8.747812e-01 1.778550e+02 5.532440e-03 9.993887e-01 3.452007e-02 -1.332749e+01 8.751970e-01 -2.153823e-02 4.832870e-01 2.124736e+02 +4.838463e-01 2.740406e-02 -8.747239e-01 1.770882e+02 5.515287e-03 9.993943e-01 3.436058e-02 -1.331082e+01 8.751356e-01 -2.144958e-02 4.834021e-01 2.129016e+02 +4.835302e-01 2.769406e-02 -8.748895e-01 1.763215e+02 5.234356e-03 9.993900e-01 3.452794e-02 -1.329865e+01 8.753120e-01 -2.127478e-02 4.830902e-01 2.133302e+02 +4.834054e-01 3.025502e-02 -8.748737e-01 1.755541e+02 6.716409e-03 9.992449e-01 3.826717e-02 -1.328287e+01 8.753708e-01 -2.437455e-02 4.828372e-01 2.137612e+02 +4.828400e-01 2.843214e-02 -8.752469e-01 1.747915e+02 7.572747e-03 9.992998e-01 3.663956e-02 -1.326848e+01 8.756758e-01 -2.431906e-02 4.822866e-01 2.141877e+02 +4.827552e-01 3.095142e-02 -8.752083e-01 1.740245e+02 4.922988e-03 9.992635e-01 3.805406e-02 -1.325105e+01 8.757415e-01 -2.267943e-02 4.822473e-01 2.146087e+02 +4.825788e-01 3.241064e-02 -8.752527e-01 1.732609e+02 5.750594e-03 9.991763e-01 4.017019e-02 -1.323227e+01 8.758337e-01 -2.441849e-02 4.819948e-01 2.150319e+02 +4.827705e-01 3.128451e-02 -8.751880e-01 1.725056e+02 9.977850e-03 9.991003e-01 4.121787e-02 -1.321744e+01 8.756900e-01 -2.863126e-02 4.820240e-01 2.154573e+02 +4.824646e-01 2.676319e-02 -8.755065e-01 1.717547e+02 1.122813e-02 9.992620e-01 3.673373e-02 -1.320315e+01 8.758435e-01 -2.755301e-02 4.818080e-01 2.158789e+02 +4.816990e-01 1.890539e-02 -8.761328e-01 1.710068e+02 1.172856e-02 9.995386e-01 2.801665e-02 -1.318941e+01 8.762582e-01 -2.377135e-02 4.812550e-01 2.162961e+02 +4.799277e-01 1.319982e-02 -8.772088e-01 1.702629e+02 1.425661e-02 9.996374e-01 2.284198e-02 -1.317494e+01 8.771922e-01 -2.346852e-02 4.795655e-01 2.167166e+02 +4.787752e-01 1.428541e-02 -8.778213e-01 1.695153e+02 1.878649e-02 9.994719e-01 2.651152e-02 -1.316501e+01 8.777365e-01 -2.918423e-02 4.782540e-01 2.171385e+02 +4.785343e-01 2.162892e-02 -8.778025e-01 1.687701e+02 1.653830e-02 9.992972e-01 3.363840e-02 -1.316245e+01 8.779131e-01 -3.061448e-02 4.778402e-01 2.175493e+02 +4.782023e-01 2.460729e-02 -8.779050e-01 1.680394e+02 1.224111e-02 9.993235e-01 3.467844e-02 -1.315694e+01 8.781644e-01 -2.732984e-02 4.775776e-01 2.179446e+02 +4.774434e-01 2.113787e-02 -8.784082e-01 1.673275e+02 1.284774e-02 9.994357e-01 3.103342e-02 -1.314619e+01 8.785685e-01 -2.610226e-02 4.769024e-01 2.183360e+02 +4.764047e-01 1.744598e-02 -8.790531e-01 1.666357e+02 1.827781e-02 9.993905e-01 2.973994e-02 -1.313813e+01 8.790361e-01 -3.023540e-02 4.757954e-01 2.187259e+02 +4.751464e-01 1.941584e-02 -8.796926e-01 1.659531e+02 1.820225e-02 9.993257e-01 3.188782e-02 -1.313633e+01 8.797185e-01 -3.116376e-02 4.744725e-01 2.191019e+02 +4.739792e-01 2.258406e-02 -8.802464e-01 1.652855e+02 1.795794e-02 9.992152e-01 3.530606e-02 -1.313005e+01 8.803529e-01 -3.254173e-02 4.732016e-01 2.194665e+02 +4.714124e-01 2.039358e-02 -8.816771e-01 1.646404e+02 2.144318e-02 9.991720e-01 3.457647e-02 -1.312098e+01 8.816521e-01 -3.520572e-02 4.705847e-01 2.198238e+02 +4.679308e-01 2.019021e-02 -8.835345e-01 1.640103e+02 2.243096e-02 9.991456e-01 3.471183e-02 -1.311339e+01 8.834804e-01 -3.606125e-02 4.670781e-01 2.201651e+02 +4.638685e-01 2.300696e-02 -8.856053e-01 1.633948e+02 1.929897e-02 9.991630e-01 3.606561e-02 -1.310511e+01 8.856938e-01 -3.382095e-02 4.630362e-01 2.204854e+02 +4.581512e-01 2.338595e-02 -8.885666e-01 1.628000e+02 1.781532e-02 9.992114e-01 3.548369e-02 -1.309912e+01 8.886957e-01 -3.208698e-02 4.573733e-01 2.207923e+02 +4.510456e-01 2.793047e-02 -8.920638e-01 1.622184e+02 1.493453e-02 9.991340e-01 3.883404e-02 -1.309520e+01 8.923759e-01 -3.083846e-02 4.502378e-01 2.210836e+02 +4.430413e-01 3.016908e-02 -8.959935e-01 1.616533e+02 1.310484e-02 9.991089e-01 4.012103e-02 -1.308579e+01 8.964054e-01 -2.951711e-02 4.422511e-01 2.213597e+02 +4.336028e-01 2.863614e-02 -9.006490e-01 1.611099e+02 1.093821e-02 9.992540e-01 3.703732e-02 -1.307790e+01 9.010377e-01 -2.591097e-02 4.329661e-01 2.216184e+02 +4.224025e-01 2.276732e-02 -9.061224e-01 1.605745e+02 1.262654e-02 9.994397e-01 3.099807e-02 -1.307197e+01 9.063204e-01 -2.453484e-02 4.218783e-01 2.218666e+02 +4.072767e-01 1.488145e-02 -9.131836e-01 1.600450e+02 1.779051e-02 9.995482e-01 2.422338e-02 -1.306665e+01 9.131315e-01 -2.611161e-02 4.068279e-01 2.221078e+02 +3.877417e-01 1.048569e-02 -9.217084e-01 1.595105e+02 2.082597e-02 9.995804e-01 2.013260e-02 -1.305916e+01 9.215327e-01 -2.700172e-02 3.873606e-01 2.223344e+02 +3.628980e-01 1.152449e-02 -9.317576e-01 1.589597e+02 2.048369e-02 9.995832e-01 2.034132e-02 -1.304750e+01 9.316037e-01 -2.646765e-02 3.625106e-01 2.225303e+02 +3.341617e-01 1.780759e-02 -9.423475e-01 1.584078e+02 1.731034e-02 9.995369e-01 2.502665e-02 -1.304181e+01 9.423567e-01 -2.467529e-02 3.336987e-01 2.227128e+02 +3.033347e-01 2.437600e-02 -9.525723e-01 1.578455e+02 1.333916e-02 9.994661e-01 2.982369e-02 -1.303627e+01 9.527907e-01 -2.175307e-02 3.028476e-01 2.228609e+02 +2.701181e-01 2.950691e-02 -9.623750e-01 1.572935e+02 1.067282e-02 9.993771e-01 3.363705e-02 -1.303293e+01 9.627680e-01 -1.935722e-02 2.696349e-01 2.230029e+02 +2.350725e-01 3.438459e-02 -9.713695e-01 1.567418e+02 6.247567e-03 9.993000e-01 3.688520e-02 -1.302324e+01 9.719577e-01 -1.473939e-02 2.346931e-01 2.231194e+02 +1.995452e-01 3.764310e-02 -9.791653e-01 1.561813e+02 3.874573e-03 9.992237e-01 3.920384e-02 -1.301146e+01 9.798809e-01 -1.161678e-02 1.992444e-01 2.232029e+02 +1.643203e-01 3.965515e-02 -9.856096e-01 1.556330e+02 1.418464e-03 9.991810e-01 4.043768e-02 -1.299975e+01 9.864060e-01 -8.042776e-03 1.641294e-01 2.232797e+02 +1.295844e-01 4.156620e-02 -9.906968e-01 1.550797e+02 -6.588615e-05 9.991213e-01 4.191105e-02 -1.298801e+01 9.915683e-01 -5.365741e-03 1.294733e-01 2.233373e+02 +9.428605e-02 4.334018e-02 -9.946013e-01 1.545111e+02 -2.901006e-03 9.990596e-01 4.325945e-02 -1.297570e+01 9.955409e-01 -1.193413e-03 9.432311e-02 2.233640e+02 +5.949781e-02 4.230450e-02 -9.973316e-01 1.539455e+02 -7.614139e-03 9.990917e-01 4.192493e-02 -1.296146e+01 9.981994e-01 5.099384e-03 5.976588e-02 2.233808e+02 +2.711923e-02 4.203405e-02 -9.987481e-01 1.533752e+02 -1.414789e-02 9.990316e-01 4.166182e-02 -1.294579e+01 9.995320e-01 1.300035e-02 2.768766e-02 2.233752e+02 +-8.222368e-04 4.416913e-02 -9.990238e-01 1.527869e+02 -1.960906e-02 9.988312e-01 4.417676e-02 -1.292888e+01 9.998073e-01 1.962624e-02 4.483795e-05 2.233501e+02 +-2.354346e-02 4.834786e-02 -9.985531e-01 1.521943e+02 -1.988611e-02 9.986096e-01 4.881948e-02 -1.290903e+01 9.995250e-01 2.100672e-02 -2.254927e-02 2.233270e+02 +-4.207706e-02 5.533234e-02 -9.975810e-01 1.515876e+02 -2.064122e-02 9.982040e-01 5.623753e-02 -1.288729e+01 9.989011e-01 2.295760e-02 -4.085936e-02 2.232912e+02 +-5.590427e-02 6.205942e-02 -9.965056e-01 1.509690e+02 -2.323179e-02 9.977153e-01 6.343808e-02 -1.286332e+01 9.981658e-01 2.669706e-02 -5.433480e-02 2.232450e+02 +-6.760167e-02 6.335309e-02 -9.956990e-01 1.503433e+02 -2.894645e-02 9.974373e-01 6.542899e-02 -1.283453e+01 9.972924e-01 3.324506e-02 -6.559458e-02 2.231852e+02 +-7.737906e-02 6.446982e-02 -9.949152e-01 1.497033e+02 -3.350369e-02 9.971753e-01 6.722203e-02 -1.280137e+01 9.964386e-01 3.853491e-02 -7.500051e-02 2.231223e+02 +-8.222978e-02 6.470021e-02 -9.945110e-01 1.490484e+02 -3.312732e-02 9.971616e-01 6.761175e-02 -1.276027e+01 9.960626e-01 3.850518e-02 -7.985303e-02 2.230606e+02 +-8.474431e-02 6.409654e-02 -9.943390e-01 1.483828e+02 -2.982754e-02 9.973184e-01 6.683071e-02 -1.271981e+01 9.959561e-01 3.532221e-02 -8.260521e-02 2.230039e+02 +-8.683990e-02 6.418345e-02 -9.941526e-01 1.476974e+02 -2.443302e-02 9.974850e-01 6.653285e-02 -1.268253e+01 9.959226e-01 3.006785e-02 -8.505330e-02 2.229478e+02 +-8.789487e-02 6.205017e-02 -9.941953e-01 1.469992e+02 -2.222927e-02 9.976873e-01 6.423337e-02 -1.264604e+01 9.958817e-01 2.774602e-02 -8.631226e-02 2.228867e+02 +-8.824412e-02 5.733500e-02 -9.944474e-01 1.462857e+02 -1.887895e-02 9.980665e-01 5.921892e-02 -1.260905e+01 9.959199e-01 2.399985e-02 -8.699107e-02 2.228246e+02 +-8.816590e-02 5.293815e-02 -9.946981e-01 1.455594e+02 -1.384197e-02 9.984252e-01 5.436342e-02 -1.257239e+01 9.960096e-01 1.856159e-02 -8.729429e-02 2.227680e+02 +-8.796910e-02 5.058553e-02 -9.948380e-01 1.448114e+02 -1.098608e-02 9.985997e-01 5.174827e-02 -1.253739e+01 9.960626e-01 1.548162e-02 -8.729018e-02 2.227091e+02 +-8.706422e-02 5.263787e-02 -9.948111e-01 1.440411e+02 -1.053615e-02 9.984985e-01 5.375510e-02 -1.250132e+01 9.961469e-01 1.516162e-02 -8.637889e-02 2.226439e+02 +-8.567685e-02 5.812097e-02 -9.946263e-01 1.432551e+02 -1.049497e-02 9.981890e-01 5.923320e-02 -1.246716e+01 9.962677e-01 1.551349e-02 -8.491170e-02 2.225763e+02 +-8.373952e-02 6.198262e-02 -9.945581e-01 1.424524e+02 -9.759367e-03 9.979647e-01 6.301665e-02 -1.242912e+01 9.964398e-01 1.498324e-02 -8.296417e-02 2.225073e+02 +-8.115212e-02 5.786517e-02 -9.950206e-01 1.416445e+02 -1.214950e-02 9.981817e-01 5.903990e-02 -1.239462e+01 9.966276e-01 1.688022e-02 -8.030152e-02 2.224364e+02 +-7.746158e-02 4.914391e-02 -9.957834e-01 1.408253e+02 -1.369209e-02 9.986378e-01 5.034989e-02 -1.236158e+01 9.969013e-01 1.753454e-02 -7.668317e-02 2.223675e+02 +-7.342452e-02 4.264017e-02 -9.963888e-01 1.399857e+02 -1.080014e-02 9.989930e-01 4.354749e-02 -1.232580e+01 9.972423e-01 1.395859e-02 -7.289005e-02 2.223071e+02 +-6.883671e-02 4.252423e-02 -9.967213e-01 1.391198e+02 -4.787056e-03 9.990655e-01 4.295487e-02 -1.229070e+01 9.976164e-01 7.728236e-03 -6.856882e-02 2.222589e+02 +-6.404852e-02 4.637848e-02 -9.968685e-01 1.382383e+02 1.526372e-05 9.989195e-01 4.647293e-02 -1.226035e+01 9.979467e-01 2.961311e-03 -6.398002e-02 2.222126e+02 +-5.971975e-02 4.959708e-02 -9.969823e-01 1.373423e+02 7.468267e-04 9.987668e-01 4.964113e-02 -1.222648e+01 9.982149e-01 2.219988e-03 -5.968314e-02 2.221626e+02 +-5.528257e-02 5.117367e-02 -9.971585e-01 1.364334e+02 2.871919e-03 9.986897e-01 5.109304e-02 -1.218824e+01 9.984666e-01 -3.919844e-05 -5.535710e-02 2.221176e+02 +-5.123481e-02 5.504755e-02 -9.971684e-01 1.355059e+02 4.787304e-03 9.984818e-01 5.487409e-02 -1.214967e+01 9.986751e-01 -1.962279e-03 -5.142055e-02 2.220757e+02 +-4.778735e-02 5.725098e-02 -9.972155e-01 1.345688e+02 3.078980e-03 9.983597e-01 5.716914e-02 -1.210689e+01 9.988527e-01 -3.384395e-04 -4.788524e-02 2.220299e+02 +-4.498307e-02 5.438516e-02 -9.975063e-01 1.336194e+02 8.721299e-03 9.985003e-01 5.404608e-02 -1.206380e+01 9.989496e-01 -6.268385e-03 -4.538992e-02 2.219953e+02 +-4.329342e-02 4.907870e-02 -9.978562e-01 1.326636e+02 1.847181e-02 9.986612e-01 4.831688e-02 -1.202327e+01 9.988916e-01 -1.634040e-02 -4.414203e-02 2.219695e+02 +-4.287589e-02 4.056530e-02 -9.982566e-01 1.316955e+02 1.911436e-02 9.990258e-01 3.977559e-02 -1.198937e+01 9.988975e-01 -1.737561e-02 -4.360949e-02 2.219321e+02 +-4.281996e-02 3.536587e-02 -9.984567e-01 1.307148e+02 2.188384e-02 9.991667e-01 3.445251e-02 -1.195903e+01 9.988431e-01 -2.037480e-02 -4.355822e-02 2.218936e+02 +-4.313959e-02 3.283780e-02 -9.985293e-01 1.297209e+02 2.569699e-02 9.991655e-01 3.174854e-02 -1.193204e+01 9.987385e-01 -2.428956e-02 -4.394742e-02 2.218580e+02 +-4.221006e-02 3.988414e-02 -9.983124e-01 1.287110e+02 1.902553e-02 9.990538e-01 3.910934e-02 -1.190519e+01 9.989276e-01 -1.734261e-02 -4.292894e-02 2.218030e+02 +-4.245654e-02 5.257085e-02 -9.977143e-01 1.276893e+02 1.468555e-02 9.985396e-01 5.198943e-02 -1.187237e+01 9.989903e-01 -1.244468e-02 -4.316657e-02 2.217498e+02 +-4.420843e-02 6.335304e-02 -9.970116e-01 1.266632e+02 1.248776e-02 9.979443e-01 6.285860e-02 -1.183110e+01 9.989442e-01 -9.671552e-03 -4.490869e-02 2.216993e+02 +-4.653768e-02 6.326343e-02 -9.969112e-01 1.256473e+02 1.289920e-02 9.979473e-01 6.272703e-02 -1.178857e+01 9.988332e-01 -9.940182e-03 -4.725820e-02 2.216501e+02 +-4.920968e-02 5.379329e-02 -9.973388e-01 1.246384e+02 1.758151e-02 9.984405e-01 5.298524e-02 -1.174693e+01 9.986337e-01 -1.492732e-02 -5.007870e-02 2.216057e+02 +-5.209370e-02 4.310859e-02 -9.977114e-01 1.236299e+02 1.937767e-02 9.989234e-01 4.214920e-02 -1.171079e+01 9.984541e-01 -1.713760e-02 -5.287295e-02 2.215549e+02 +-5.475037e-02 4.017399e-02 -9.976916e-01 1.226154e+02 2.046168e-02 9.990256e-01 3.910484e-02 -1.168307e+01 9.982904e-01 -1.827343e-02 -5.551905e-02 2.215000e+02 +-5.755884e-02 4.181232e-02 -9.974662e-01 1.215907e+02 2.072184e-02 9.989573e-01 4.067908e-02 -1.165845e+01 9.981270e-01 -1.832789e-02 -5.836525e-02 2.214404e+02 +-6.016527e-02 4.621742e-02 -9.971179e-01 1.205664e+02 1.831304e-02 9.988105e-01 4.519089e-02 -1.163185e+01 9.980204e-01 -1.554133e-02 -6.094008e-02 2.213745e+02 +-6.172986e-02 5.304327e-02 -9.966824e-01 1.195438e+02 1.870497e-02 9.984729e-01 5.198007e-02 -1.159800e+01 9.979176e-01 -1.543418e-02 -6.262776e-02 2.213095e+02 +-6.299868e-02 6.183956e-02 -9.960959e-01 1.185197e+02 1.829928e-02 9.979822e-01 6.079933e-02 -1.156188e+01 9.978458e-01 -1.439755e-02 -6.400317e-02 2.212430e+02 +-6.395264e-02 6.360303e-02 -9.959241e-01 1.175108e+02 1.491932e-02 9.979163e-01 6.277224e-02 -1.152450e+01 9.978414e-01 -1.084405e-02 -6.476830e-02 2.211714e+02 +-6.511373e-02 5.612872e-02 -9.962981e-01 1.165115e+02 1.335764e-02 9.983764e-01 5.537282e-02 -1.148765e+01 9.977884e-01 -9.702649e-03 -6.575776e-02 2.211021e+02 +-6.600840e-02 4.829726e-02 -9.966495e-01 1.155151e+02 1.510763e-02 9.987618e-01 4.739904e-02 -1.145162e+01 9.977046e-01 -1.192827e-02 -6.665632e-02 2.210361e+02 +-6.649185e-02 4.678938e-02 -9.966893e-01 1.145179e+02 1.451720e-02 9.988395e-01 4.592185e-02 -1.142118e+01 9.976813e-01 -1.141570e-02 -6.709393e-02 2.209683e+02 +-6.611564e-02 5.211902e-02 -9.964499e-01 1.135168e+02 1.660082e-02 9.985541e-01 5.112761e-02 -1.139041e+01 9.976738e-01 -1.316154e-02 -6.688526e-02 2.209036e+02 +-6.598619e-02 5.817925e-02 -9.961230e-01 1.125172e+02 1.694346e-02 9.982201e-01 5.717936e-02 -1.135672e+01 9.976766e-01 -1.310471e-02 -6.685450e-02 2.208376e+02 +-6.538092e-02 6.172327e-02 -9.959496e-01 1.115259e+02 1.706100e-02 9.980083e-01 6.073087e-02 -1.132203e+01 9.977145e-01 -1.302125e-02 -6.630376e-02 2.207722e+02 +-6.438417e-02 5.847910e-02 -9.962103e-01 1.105452e+02 1.706225e-02 9.982001e-01 5.749319e-02 -1.128441e+01 9.977793e-01 -1.329593e-02 -6.526606e-02 2.207080e+02 +-6.288162e-02 5.270532e-02 -9.966284e-01 1.095712e+02 1.755352e-02 9.985085e-01 5.169724e-02 -1.124841e+01 9.978666e-01 -1.424352e-02 -6.371299e-02 2.206447e+02 +-6.185701e-02 4.867887e-02 -9.968973e-01 1.086011e+02 1.910165e-02 9.986847e-01 4.758091e-02 -1.122102e+01 9.979022e-01 -1.609916e-02 -6.270549e-02 2.205858e+02 +-6.101832e-02 4.141712e-02 -9.972770e-01 1.076362e+02 2.275870e-02 9.989367e-01 4.009357e-02 -1.119656e+01 9.978771e-01 -2.025028e-02 -6.189603e-02 2.205323e+02 +-6.016690e-02 3.843186e-02 -9.974482e-01 1.066654e+02 2.383373e-02 9.990289e-01 3.705510e-02 -1.117178e+01 9.979037e-01 -2.154341e-02 -6.102445e-02 2.204773e+02 +-5.900779e-02 4.480234e-02 -9.972517e-01 1.056915e+02 2.679659e-02 9.987034e-01 4.328200e-02 -1.114687e+01 9.978978e-01 -2.416896e-02 -6.013183e-02 2.204242e+02 +-5.762142e-02 5.284110e-02 -9.969391e-01 1.047172e+02 3.046797e-02 9.982262e-01 5.114833e-02 -1.112293e+01 9.978734e-01 -2.742746e-02 -5.912917e-02 2.203737e+02 +-5.614698e-02 5.313310e-02 -9.970077e-01 1.037569e+02 3.048556e-02 9.982086e-01 5.148030e-02 -1.109404e+01 9.979569e-01 -2.750386e-02 -5.766618e-02 2.203198e+02 +-5.524411e-02 5.181467e-02 -9.971276e-01 1.027971e+02 2.953877e-02 9.983003e-01 5.023907e-02 -1.106032e+01 9.980358e-01 -2.667850e-02 -5.668075e-02 2.202638e+02 +-5.532778e-02 5.055064e-02 -9.971878e-01 1.018406e+02 3.512902e-02 9.981978e-01 4.865276e-02 -1.103196e+01 9.978500e-01 -3.233837e-02 -5.700386e-02 2.202186e+02 +-5.566757e-02 4.917557e-02 -9.972377e-01 1.008893e+02 3.771766e-02 9.981770e-01 4.711643e-02 -1.100563e+01 9.977366e-01 -3.499060e-02 -5.742088e-02 2.201704e+02 +-5.618866e-02 4.662701e-02 -9.973308e-01 9.994290e+01 3.818941e-02 9.982783e-01 4.451976e-02 -1.097856e+01 9.976895e-01 -3.558596e-02 -5.787257e-02 2.201170e+02 +-5.738883e-02 5.079896e-02 -9.970587e-01 9.899470e+01 4.214831e-02 9.979375e-01 4.841776e-02 -1.095124e+01 9.974618e-01 -3.924569e-02 -5.941155e-02 2.200673e+02 +-5.917256e-02 5.669648e-02 -9.966364e-01 9.804753e+01 4.544570e-02 9.975036e-01 5.404761e-02 -1.092193e+01 9.972127e-01 -4.209469e-02 -6.160145e-02 2.200164e+02 +-6.122286e-02 5.897351e-02 -9.963804e-01 9.710870e+01 4.446148e-02 9.974232e-01 5.630329e-02 -1.089294e+01 9.971333e-01 -4.085348e-02 -6.368715e-02 2.199567e+02 +-6.392814e-02 5.713134e-02 -9.963179e-01 9.618155e+01 4.447136e-02 9.975313e-01 5.434745e-02 -1.086098e+01 9.969631e-01 -4.083327e-02 -6.631102e-02 2.198951e+02 +-6.716587e-02 5.803618e-02 -9.960525e-01 9.525961e+01 4.472701e-02 9.974784e-01 5.510324e-02 -1.082502e+01 9.967388e-01 -4.084938e-02 -6.959229e-02 2.198316e+02 +-7.007779e-02 6.227517e-02 -9.955958e-01 9.434372e+01 4.210452e-02 9.973446e-01 5.942093e-02 -1.079240e+01 9.966525e-01 -3.775498e-02 -7.251377e-02 2.197619e+02 +-7.311413e-02 6.435516e-02 -9.952451e-01 9.343862e+01 3.880986e-02 9.973436e-01 6.163977e-02 -1.076804e+01 9.965681e-01 -3.411857e-02 -7.541753e-02 2.196865e+02 +-7.611799e-02 6.110345e-02 -9.952248e-01 9.256677e+01 3.729284e-02 9.975966e-01 5.839681e-02 -1.074452e+01 9.964011e-01 -3.266970e-02 -7.821377e-02 2.196263e+02 +-7.886360e-02 5.909924e-02 -9.951321e-01 9.170406e+01 3.778002e-02 9.977012e-01 5.625779e-02 -1.071985e+01 9.961692e-01 -3.315940e-02 -8.091508e-02 2.195641e+02 +-8.095666e-02 5.858101e-02 -9.949946e-01 9.085546e+01 3.758085e-02 9.977409e-01 5.568498e-02 -1.069919e+01 9.960088e-01 -3.288466e-02 -8.297529e-02 2.195006e+02 +-8.221203e-02 5.828648e-02 -9.949090e-01 9.001191e+01 3.510154e-02 9.978383e-01 5.555757e-02 -1.067400e+01 9.959965e-01 -3.035533e-02 -8.408025e-02 2.194376e+02 +-8.265354e-02 5.687800e-02 -9.949539e-01 8.918744e+01 3.360684e-02 9.979612e-01 5.425812e-02 -1.065382e+01 9.960115e-01 -2.895262e-02 -8.439651e-02 2.193826e+02 +-8.290909e-02 5.828925e-02 -9.948510e-01 8.838861e+01 3.293543e-02 9.979029e-01 5.572330e-02 -1.063021e+01 9.960127e-01 -2.814586e-02 -8.465500e-02 2.193263e+02 +-8.260331e-02 6.002373e-02 -9.947733e-01 8.760818e+01 3.067178e-02 9.978648e-01 5.766337e-02 -1.060537e+01 9.961104e-01 -2.574827e-02 -8.426797e-02 2.192647e+02 +-8.075290e-02 6.138104e-02 -9.948424e-01 8.685337e+01 2.736189e-02 9.978624e-01 5.934637e-02 -1.058478e+01 9.963585e-01 -2.242836e-02 -8.225978e-02 2.192079e+02 +-7.789468e-02 6.278269e-02 -9.949828e-01 8.612368e+01 2.616745e-02 9.978001e-01 6.091188e-02 -1.056501e+01 9.966181e-01 -2.129145e-02 -7.936617e-02 2.191578e+02 +-7.335971e-02 6.360745e-02 -9.952751e-01 8.541269e+01 2.694566e-02 9.977261e-01 6.177799e-02 -1.054111e+01 9.969414e-01 -2.228632e-02 -7.490684e-02 2.191163e+02 +-6.694243e-02 6.464425e-02 -9.956605e-01 8.472207e+01 2.633264e-02 9.976658e-01 6.300400e-02 -1.051592e+01 9.974093e-01 -2.200072e-02 -6.848842e-02 2.190786e+02 +-5.900766e-02 6.581064e-02 -9.960859e-01 8.404997e+01 2.404269e-02 9.976288e-01 6.448831e-02 -1.049659e+01 9.979679e-01 -2.014327e-02 -6.045000e-02 2.190453e+02 +-4.825011e-02 6.534961e-02 -9.966952e-01 8.340009e+01 2.226408e-02 9.976799e-01 6.433637e-02 -1.047658e+01 9.985871e-01 -1.908626e-02 -4.959311e-02 2.190227e+02 +-3.465075e-02 6.271342e-02 -9.974299e-01 8.276889e+01 2.162952e-02 9.978425e-01 6.198796e-02 -1.045391e+01 9.991654e-01 -1.942599e-02 -3.593245e-02 2.190137e+02 +-1.800414e-02 5.973792e-02 -9.980517e-01 8.215288e+01 2.218497e-02 9.979916e-01 5.933413e-02 -1.043065e+01 9.995917e-01 -2.107348e-02 -1.929327e-02 2.190163e+02 +2.347454e-03 5.836181e-02 -9.982928e-01 8.155702e+01 2.469122e-02 9.979877e-01 5.840204e-02 -1.041040e+01 9.996923e-01 -2.478615e-02 9.017052e-04 2.190383e+02 +2.461488e-02 5.794631e-02 -9.980162e-01 8.097264e+01 2.475644e-02 9.979772e-01 5.855464e-02 -1.039008e+01 9.993904e-01 -2.614864e-02 2.313054e-02 2.190755e+02 +4.988773e-02 5.871985e-02 -9.970272e-01 8.038801e+01 2.281815e-02 9.979426e-01 5.991552e-02 -1.036871e+01 9.984941e-01 -2.573935e-02 4.844520e-02 2.191151e+02 +7.814719e-02 5.980696e-02 -9.951463e-01 7.980795e+01 1.925929e-02 9.979221e-01 6.148619e-02 -1.034835e+01 9.967557e-01 -2.397078e-02 7.683296e-02 2.191809e+02 +1.088557e-01 6.069805e-02 -9.922027e-01 7.922930e+01 1.613180e-02 9.978947e-01 6.281611e-02 -1.033041e+01 9.939266e-01 -2.284390e-02 1.076474e-01 2.192545e+02 +1.428723e-01 5.949249e-02 -9.879515e-01 7.866476e+01 1.501882e-02 9.979465e-01 6.226632e-02 -1.031093e+01 9.896271e-01 -2.373399e-02 1.416854e-01 2.193662e+02 +1.799362e-01 5.567118e-02 -9.821017e-01 7.811041e+01 1.108945e-02 9.982190e-01 5.861657e-02 -1.028769e+01 9.836157e-01 -2.143821e-02 1.789984e-01 2.194970e+02 +2.187947e-01 5.142446e-02 -9.744149e-01 7.755609e+01 3.083292e-03 9.985689e-01 5.339151e-02 -1.026351e+01 9.757660e-01 -1.468618e-02 2.183230e-01 2.196228e+02 +2.600820e-01 4.854472e-02 -9.643655e-01 7.701629e+01 -3.204376e-03 9.987733e-01 4.941257e-02 -1.024585e+01 9.655812e-01 -9.761125e-03 2.599185e-01 2.197960e+02 +3.040580e-01 4.761603e-02 -9.514628e-01 7.647664e+01 -1.056109e-02 9.988572e-01 4.661289e-02 -1.023081e+01 9.525950e-01 -4.124528e-03 3.042133e-01 2.199684e+02 +3.515675e-01 4.739889e-02 -9.349619e-01 7.596056e+01 -2.008972e-02 9.988694e-01 4.308455e-02 -1.021989e+01 9.359469e-01 3.636004e-03 3.521222e-01 2.201937e+02 +4.015910e-01 4.747507e-02 -9.145878e-01 7.546148e+01 -3.139309e-02 9.987822e-01 3.806095e-02 -1.020937e+01 9.152809e-01 1.342680e-02 4.025923e-01 2.204461e+02 +4.529098e-01 4.937159e-02 -8.901883e-01 7.496605e+01 -3.240722e-02 9.987173e-01 3.890269e-02 -1.019899e+01 8.909671e-01 1.122912e-02 4.539289e-01 2.207050e+02 +5.044661e-01 5.053854e-02 -8.619512e-01 7.450344e+01 -3.434884e-02 9.986699e-01 3.845172e-02 -1.018687e+01 8.627480e-01 1.020944e-02 5.055310e-01 2.210328e+02 +5.567192e-01 5.307627e-02 -8.290034e-01 7.406909e+01 -3.582561e-02 9.985623e-01 3.987337e-02 -1.018099e+01 8.299278e-01 7.501287e-03 5.578203e-01 2.214112e+02 +6.071100e-01 5.575844e-02 -7.926592e-01 7.363537e+01 -3.721733e-02 9.984356e-01 4.172815e-02 -1.017688e+01 7.937458e-01 4.167086e-03 6.082353e-01 2.217675e+02 +6.542676e-01 5.301950e-02 -7.544024e-01 7.324704e+01 -3.489686e-02 9.985934e-01 3.991643e-02 -1.017531e+01 7.554576e-01 2.102548e-04 6.551975e-01 2.221970e+02 +6.975065e-01 4.789029e-02 -7.149764e-01 7.286285e+01 -3.329548e-02 9.988526e-01 3.442285e-02 -1.017148e+01 7.158045e-01 -2.046786e-04 6.983006e-01 2.226040e+02 +7.374695e-01 4.549857e-02 -6.738461e-01 7.250725e+01 -3.816655e-02 9.989414e-01 2.567906e-02 -1.017451e+01 6.743011e-01 6.780861e-03 7.384253e-01 2.230666e+02 +7.744188e-01 4.443070e-02 -6.311113e-01 7.216890e+01 -4.684947e-02 9.988195e-01 1.282998e-02 -1.017618e+01 6.309363e-01 1.963145e-02 7.755862e-01 2.235403e+02 +8.082989e-01 3.717410e-02 -5.875977e-01 7.184185e+01 -4.554020e-02 9.989623e-01 5.538454e-04 -1.017024e+01 5.870086e-01 2.631164e-02 8.091530e-01 2.240153e+02 +8.396443e-01 2.758955e-02 -5.424355e-01 7.155033e+01 -3.608562e-02 9.993360e-01 -5.028881e-03 -1.017198e+01 5.419366e-01 2.379659e-02 8.400823e-01 2.245696e+02 +8.685969e-01 2.232557e-02 -4.950162e-01 7.128157e+01 -2.902154e-02 9.995617e-01 -5.842703e-03 -1.017650e+01 4.946688e-01 1.944109e-02 8.688640e-01 2.251433e+02 +8.942540e-01 2.215078e-02 -4.470115e-01 7.102342e+01 -2.724884e-02 9.996163e-01 -4.977720e-03 -1.018054e+01 4.467296e-01 1.663189e-02 8.945143e-01 2.256999e+02 +9.164636e-01 2.299835e-02 -3.994566e-01 7.079740e+01 -2.779695e-02 9.995942e-01 -6.223134e-03 -1.018818e+01 3.991513e-01 1.680695e-02 9.167309e-01 2.263027e+02 +9.354029e-01 1.930074e-02 -3.530566e-01 7.060149e+01 -2.337059e-02 9.997004e-01 -7.267829e-03 -1.019211e+01 3.528105e-01 1.504949e-02 9.355737e-01 2.269267e+02 +9.513064e-01 1.744320e-02 -3.077531e-01 7.042167e+01 -2.084440e-02 9.997525e-01 -7.767681e-03 -1.020149e+01 3.075414e-01 1.380437e-02 9.514345e-01 2.275400e+02 +9.646614e-01 2.045116e-02 -2.626979e-01 7.026524e+01 -2.391619e-02 9.996639e-01 -9.999105e-03 -1.021211e+01 2.624051e-01 1.592848e-02 9.648263e-01 2.281954e+02 +9.753250e-01 2.066793e-02 -2.198048e-01 7.012770e+01 -2.435327e-02 9.996044e-01 -1.406976e-02 -1.022504e+01 2.194271e-01 1.907556e-02 9.754424e-01 2.288409e+02 +9.831866e-01 9.612003e-03 -1.823510e-01 7.003455e+01 -1.409269e-02 9.996294e-01 -2.329187e-02 -1.024406e+01 1.820595e-01 2.547007e-02 9.829575e-01 2.295184e+02 +9.884949e-01 2.776275e-03 -1.512287e-01 6.995561e+01 -7.821380e-03 9.994321e-01 -3.277615e-02 -1.026536e+01 1.510518e-01 3.358187e-02 9.879552e-01 2.302032e+02 +9.923675e-01 6.593881e-04 -1.233145e-01 6.987830e+01 -5.183574e-03 9.993249e-01 -3.637096e-02 -1.028480e+01 1.232073e-01 3.673256e-02 9.917008e-01 2.308964e+02 +9.949636e-01 1.120980e-03 -1.002306e-01 6.981376e+01 -4.372740e-03 9.994709e-01 -3.222898e-02 -1.030134e+01 1.001415e-01 3.250494e-02 9.944421e-01 2.316107e+02 +9.966757e-01 1.090469e-03 -8.146390e-02 6.976113e+01 -2.871854e-03 9.997592e-01 -2.175320e-02 -1.031780e+01 8.142056e-02 2.191483e-02 9.964388e-01 2.323354e+02 +9.978820e-01 3.943078e-03 -6.493113e-02 6.971324e+01 -4.686066e-03 9.999252e-01 -1.129438e-02 -1.033202e+01 6.488174e-02 1.157473e-02 9.978258e-01 2.330647e+02 +9.986297e-01 9.290676e-04 -5.232624e-02 6.967008e+01 -1.331731e-03 9.999697e-01 -7.660902e-03 -1.034910e+01 5.231754e-02 7.720087e-03 9.986006e-01 2.338003e+02 +9.989955e-01 -7.581621e-03 -4.416583e-02 6.963999e+01 7.267931e-03 9.999472e-01 -7.258830e-03 -1.036057e+01 4.421853e-02 6.930543e-03 9.989978e-01 2.345350e+02 +9.991442e-01 -1.472181e-02 -3.865457e-02 6.962499e+01 1.426981e-02 9.998268e-01 -1.194338e-02 -1.037864e+01 3.882370e-02 1.138156e-02 9.991812e-01 2.352773e+02 +9.992350e-01 -1.811761e-02 -3.465922e-02 6.960369e+01 1.754870e-02 9.997074e-01 -1.664893e-02 -1.040114e+01 3.495071e-02 1.602797e-02 9.992604e-01 2.360228e+02 +9.992565e-01 -1.966312e-02 -3.316507e-02 6.958210e+01 1.904407e-02 9.996404e-01 -1.887979e-02 -1.042199e+01 3.352438e-02 1.823415e-02 9.992715e-01 2.367854e+02 +9.992235e-01 -2.170496e-02 -3.288369e-02 6.956092e+01 2.109931e-02 9.996033e-01 -1.865437e-02 -1.044222e+01 3.327554e-02 1.794606e-02 9.992850e-01 2.375595e+02 +9.992660e-01 -2.181829e-02 -3.148786e-02 6.954591e+01 2.136719e-02 9.996652e-01 -1.459219e-02 -1.047452e+01 3.179569e-02 1.390867e-02 9.993976e-01 2.383426e+02 +9.991444e-01 -2.696035e-02 -3.136284e-02 6.953554e+01 2.653211e-02 9.995500e-01 -1.399132e-02 -1.050860e+01 3.172594e-02 1.314723e-02 9.994101e-01 2.391330e+02 +9.990830e-01 -2.883186e-02 -3.165456e-02 6.952027e+01 2.828358e-02 9.994444e-01 -1.763417e-02 -1.054974e+01 3.214540e-02 1.672269e-02 9.993432e-01 2.399198e+02 +9.989859e-01 -3.182985e-02 -3.184474e-02 6.949940e+01 3.099191e-02 9.991691e-01 -2.646982e-02 -1.059153e+01 3.266081e-02 2.545604e-02 9.991422e-01 2.407197e+02 +9.986173e-01 -4.103620e-02 -3.285827e-02 6.948807e+01 3.995360e-02 9.986580e-01 -3.295314e-02 -1.063608e+01 3.416644e-02 3.159477e-02 9.989166e-01 2.415298e+02 +9.980863e-01 -5.133182e-02 -3.448041e-02 6.948017e+01 5.006289e-02 9.980712e-01 -3.670878e-02 -1.068200e+01 3.629823e-02 3.491234e-02 9.987309e-01 2.423555e+02 +9.975505e-01 -5.984302e-02 -3.621931e-02 6.946940e+01 5.853580e-02 9.976310e-01 -3.613659e-02 -1.073043e+01 3.829603e-02 3.392794e-02 9.986902e-01 2.431928e+02 +9.971341e-01 -6.525994e-02 -3.827178e-02 6.944972e+01 6.404611e-02 9.974296e-01 -3.212918e-02 -1.077141e+01 4.027015e-02 2.958594e-02 9.987507e-01 2.440434e+02 +9.969578e-01 -6.618579e-02 -4.116713e-02 6.942243e+01 6.520826e-02 9.975671e-01 -2.465281e-02 -1.081483e+01 4.269864e-02 2.189337e-02 9.988480e-01 2.449043e+02 +9.971171e-01 -6.204160e-02 -4.368616e-02 6.938453e+01 6.141720e-02 9.979919e-01 -1.549436e-02 -1.085518e+01 4.455973e-02 1.276661e-02 9.989251e-01 2.457764e+02 +9.973962e-01 -5.583721e-02 -4.564079e-02 6.933841e+01 5.536521e-02 9.983994e-01 -1.154223e-02 -1.088638e+01 4.621222e-02 8.985264e-03 9.988912e-01 2.466525e+02 +9.976785e-01 -4.975729e-02 -4.649607e-02 6.928696e+01 4.942183e-02 9.987432e-01 -8.337367e-03 -1.091134e+01 4.685248e-02 6.020090e-03 9.988836e-01 2.475373e+02 +9.980139e-01 -4.151412e-02 -4.737970e-02 6.923258e+01 4.127318e-02 9.991295e-01 -6.052836e-03 -1.093709e+01 4.758973e-02 4.085304e-03 9.988586e-01 2.484328e+02 +9.980674e-01 -3.988496e-02 -4.765209e-02 6.918578e+01 3.938421e-02 9.991591e-01 -1.140197e-02 -1.096374e+01 4.806679e-02 9.503193e-03 9.987989e-01 2.493312e+02 +9.980885e-01 -3.886791e-02 -4.804959e-02 6.914107e+01 3.788594e-02 9.990575e-01 -2.118163e-02 -1.099093e+01 4.882758e-02 1.932074e-02 9.986203e-01 2.502287e+02 +9.981421e-01 -3.774956e-02 -4.782585e-02 6.909464e+01 3.644718e-02 9.989483e-01 -2.781761e-02 -1.102141e+01 4.882565e-02 2.602280e-02 9.984682e-01 2.511460e+02 +9.981996e-01 -3.659371e-02 -4.752496e-02 6.904817e+01 3.529995e-02 9.989905e-01 -2.778274e-02 -1.105722e+01 4.849366e-02 2.605508e-02 9.984835e-01 2.520780e+02 +9.983881e-01 -3.239677e-02 -4.660225e-02 6.899988e+01 3.137572e-02 9.992549e-01 -2.247727e-02 -1.109595e+01 4.729572e-02 2.097885e-02 9.986605e-01 2.530256e+02 +9.985908e-01 -2.825775e-02 -4.492132e-02 6.895099e+01 2.752156e-02 9.994779e-01 -1.692345e-02 -1.112932e+01 4.537609e-02 1.566329e-02 9.988471e-01 2.539827e+02 +9.987636e-01 -2.409933e-02 -4.348121e-02 6.890225e+01 2.361257e-02 9.996530e-01 -1.167392e-02 -1.115833e+01 4.374745e-02 1.063278e-02 9.989860e-01 2.549496e+02 +9.988820e-01 -2.175531e-02 -4.197082e-02 6.885691e+01 2.148102e-02 9.997449e-01 -6.975412e-03 -1.118181e+01 4.211186e-02 6.066037e-03 9.990944e-01 2.559309e+02 +9.989956e-01 -1.902185e-02 -4.057092e-02 6.881186e+01 1.877924e-02 9.998034e-01 -6.352704e-03 -1.120662e+01 4.068378e-02 5.584432e-03 9.991564e-01 2.569171e+02 +9.990138e-01 -1.948392e-02 -3.989736e-02 6.875672e+01 1.901111e-02 9.997449e-01 -1.219610e-02 -1.124290e+01 4.012481e-02 1.142557e-02 9.991293e-01 2.579108e+02 +9.989758e-01 -2.059777e-02 -4.028771e-02 6.870360e+01 1.964366e-02 9.995204e-01 -2.393674e-02 -1.128031e+01 4.076144e-02 2.312082e-02 9.989013e-01 2.589078e+02 +9.988700e-01 -2.360822e-02 -4.124983e-02 6.865058e+01 2.247757e-02 9.993646e-01 -2.766209e-02 -1.131950e+01 4.187667e-02 2.670363e-02 9.987658e-01 2.599201e+02 +9.988001e-01 -2.224466e-02 -4.363108e-02 6.858719e+01 2.149665e-02 9.996150e-01 -1.753887e-02 -1.136666e+01 4.400443e-02 1.657990e-02 9.988937e-01 2.609702e+02 +9.987453e-01 -2.181438e-02 -4.507869e-02 6.851787e+01 2.156364e-02 9.997492e-01 -6.041118e-03 -1.141027e+01 4.519916e-02 5.061477e-03 9.989651e-01 2.620295e+02 +9.987029e-01 -2.133334e-02 -4.623277e-02 6.846220e+01 2.114072e-02 9.997657e-01 -4.651451e-03 -1.144220e+01 4.632117e-02 3.668024e-03 9.989198e-01 2.630821e+02 +9.986435e-01 -2.185571e-02 -4.725989e-02 6.840379e+01 2.141395e-02 9.997223e-01 -9.833753e-03 -1.146949e+01 4.746168e-02 8.808392e-03 9.988342e-01 2.641348e+02 +9.985251e-01 -2.479338e-02 -4.830024e-02 6.835062e+01 2.404452e-02 9.995824e-01 -1.602410e-02 -1.149978e+01 4.867736e-02 1.483911e-02 9.987043e-01 2.651864e+02 +9.985002e-01 -2.354771e-02 -4.942683e-02 6.828856e+01 2.272417e-02 9.995945e-01 -1.715826e-02 -1.153683e+01 4.981082e-02 1.600934e-02 9.986303e-01 2.662528e+02 +9.984717e-01 -2.300823e-02 -5.024907e-02 6.822673e+01 2.225496e-02 9.996322e-01 -1.549925e-02 -1.158104e+01 5.058719e-02 1.435726e-02 9.986164e-01 2.673248e+02 +9.984219e-01 -2.326774e-02 -5.111194e-02 6.816394e+01 2.264712e-02 9.996630e-01 -1.268812e-02 -1.161771e+01 5.138993e-02 1.151055e-02 9.986123e-01 2.683960e+02 +9.984721e-01 -1.969636e-02 -5.162865e-02 6.809665e+01 1.915398e-02 9.997562e-01 -1.097931e-02 -1.165107e+01 5.183231e-02 9.973643e-03 9.986059e-01 2.694641e+02 +9.984899e-01 -1.798414e-02 -5.191008e-02 6.803033e+01 1.764011e-02 9.998193e-01 -7.078199e-03 -1.168154e+01 5.202799e-02 6.151810e-03 9.986266e-01 2.705387e+02 +9.984746e-01 -1.764710e-02 -5.231817e-02 6.796554e+01 1.742231e-02 9.998369e-01 -4.749557e-03 -1.170880e+01 5.239345e-02 3.830809e-03 9.986191e-01 2.716135e+02 +9.984527e-01 -1.851719e-02 -5.243392e-02 6.790383e+01 1.826667e-02 9.998193e-01 -5.253170e-03 -1.173743e+01 5.252172e-02 4.287249e-03 9.986105e-01 2.726830e+02 +9.984002e-01 -2.122321e-02 -5.240813e-02 6.784423e+01 2.077418e-02 9.997428e-01 -9.098062e-03 -1.176733e+01 5.258773e-02 7.994771e-03 9.985842e-01 2.737493e+02 +9.983175e-01 -2.270571e-02 -5.335480e-02 6.778534e+01 2.193455e-02 9.996469e-01 -1.499507e-02 -1.179767e+01 5.367644e-02 1.379952e-02 9.984630e-01 2.748066e+02 +9.982677e-01 -2.249830e-02 -5.436489e-02 6.772147e+01 2.171010e-02 9.996511e-01 -1.504573e-02 -1.183323e+01 5.468442e-02 1.383939e-02 9.984077e-01 2.758724e+02 +9.981288e-01 -2.490332e-02 -5.584548e-02 6.765981e+01 2.408004e-02 9.995919e-01 -1.536704e-02 -1.187068e+01 5.620538e-02 1.399353e-02 9.983211e-01 2.769334e+02 +9.980663e-01 -2.474973e-02 -5.702002e-02 6.759292e+01 2.360278e-02 9.995070e-01 -2.070134e-02 -1.191077e+01 5.750426e-02 1.931548e-02 9.981583e-01 2.779886e+02 +9.980204e-01 -2.436777e-02 -5.797948e-02 6.752546e+01 2.311648e-02 9.994872e-01 -2.215554e-02 -1.195025e+01 5.848962e-02 2.077140e-02 9.980718e-01 2.790433e+02 +9.979945e-01 -2.284510e-02 -5.903584e-02 6.745634e+01 2.200462e-02 9.996476e-01 -1.484803e-02 -1.198777e+01 5.935424e-02 1.351919e-02 9.981454e-01 2.801032e+02 +9.980009e-01 -2.060482e-02 -5.974734e-02 6.738662e+01 2.029993e-02 9.997776e-01 -5.705626e-03 -1.202617e+01 5.985162e-02 4.481353e-03 9.981972e-01 2.811665e+02 +9.980446e-01 -1.973479e-02 -5.930918e-02 6.731745e+01 1.948727e-02 9.997988e-01 -4.748994e-03 -1.205628e+01 5.939097e-02 3.583934e-03 9.982283e-01 2.822191e+02 +9.981253e-01 -1.853929e-02 -5.832924e-02 6.724878e+01 1.794236e-02 9.997813e-01 -1.074103e-02 -1.208302e+01 5.851562e-02 9.674331e-03 9.982396e-01 2.832603e+02 +9.982273e-01 -1.630187e-02 -5.724079e-02 6.717999e+01 1.546716e-02 9.997679e-01 -1.499546e-02 -1.211419e+01 5.747196e-02 1.408352e-02 9.982477e-01 2.843009e+02 +9.983448e-01 -1.353025e-02 -5.589911e-02 6.711165e+01 1.263846e-02 9.997876e-01 -1.627634e-02 -1.214831e+01 5.610746e-02 1.554291e-02 9.983037e-01 2.853435e+02 +9.984509e-01 -1.058534e-02 -5.462534e-02 6.704325e+01 9.853090e-03 9.998582e-01 -1.365697e-02 -1.218235e+01 5.476216e-02 1.309758e-02 9.984135e-01 2.863985e+02 +9.985405e-01 -8.388309e-03 -5.335305e-02 6.697369e+01 7.803442e-03 9.999072e-01 -1.116110e-02 -1.220862e+01 5.344172e-02 1.072847e-02 9.985133e-01 2.874563e+02 +9.986095e-01 -4.680366e-03 -5.250875e-02 6.690135e+01 4.203729e-03 9.999490e-01 -9.184071e-03 -1.222821e+01 5.254905e-02 8.950567e-03 9.985782e-01 2.885084e+02 +9.986289e-01 -4.086813e-03 -5.218850e-02 6.682893e+01 3.523414e-03 9.999345e-01 -1.088291e-02 -1.224028e+01 5.222956e-02 1.068411e-02 9.985779e-01 2.895582e+02 +9.986271e-01 -4.266920e-03 -5.220891e-02 6.675997e+01 3.505086e-03 9.998862e-01 -1.467492e-02 -1.225277e+01 5.226558e-02 1.447177e-02 9.985283e-01 2.906051e+02 +9.986449e-01 -2.474452e-03 -5.198401e-02 6.668814e+01 1.581929e-03 9.998507e-01 -1.720332e-02 -1.225402e+01 5.201882e-02 1.709777e-02 9.984997e-01 2.916524e+02 +9.986721e-01 -1.182120e-03 -5.150540e-02 6.661920e+01 3.892283e-04 9.998813e-01 -1.540165e-02 -1.227164e+01 5.151749e-02 1.536115e-02 9.985539e-01 2.926968e+02 +9.987046e-01 7.320975e-04 -5.087911e-02 6.654974e+01 -1.246394e-03 9.999484e-01 -1.007720e-02 -1.228572e+01 5.086910e-02 1.012756e-02 9.986539e-01 2.937418e+02 +9.987328e-01 1.815456e-03 -5.029582e-02 6.647880e+01 -2.168904e-03 9.999733e-01 -6.973696e-03 -1.229898e+01 5.028182e-02 7.073945e-03 9.987100e-01 2.947822e+02 +9.987191e-01 5.373140e-03 -5.031370e-02 6.640794e+01 -5.693581e-03 9.999644e-01 -6.227691e-03 -1.231508e+01 5.027844e-02 6.506178e-03 9.987140e-01 2.958182e+02 +9.986934e-01 4.446866e-04 -5.110187e-02 6.634676e+01 -7.859861e-04 9.999775e-01 -6.658906e-03 -1.232714e+01 5.109775e-02 6.690370e-03 9.986712e-01 2.968507e+02 +9.985957e-01 -4.913242e-03 -5.274987e-02 6.628919e+01 4.500582e-03 9.999583e-01 -7.938910e-03 -1.234465e+01 5.278668e-02 7.690355e-03 9.985761e-01 2.978782e+02 +9.984951e-01 -5.923744e-03 -5.452091e-02 6.622145e+01 5.322213e-03 9.999234e-01 -1.117163e-02 -1.236302e+01 5.458291e-02 1.086464e-02 9.984501e-01 2.989033e+02 +9.983993e-01 -2.114474e-03 -5.651912e-02 6.614628e+01 1.430187e-03 9.999252e-01 -1.214489e-02 -1.238715e+01 5.654057e-02 1.204461e-02 9.983276e-01 2.999198e+02 +9.982359e-01 -6.522325e-03 -5.901408e-02 6.607807e+01 5.870068e-03 9.999198e-01 -1.121919e-02 -1.240214e+01 5.908252e-02 1.085298e-02 9.981940e-01 3.009445e+02 +9.980499e-01 -4.405967e-03 -6.226632e-02 6.599903e+01 4.280742e-03 9.999885e-01 -2.144377e-03 -1.242256e+01 6.227505e-02 1.873649e-03 9.980572e-01 3.019709e+02 +9.979030e-01 2.958168e-03 -6.466081e-02 6.590919e+01 -2.626042e-03 9.999829e-01 5.220821e-03 -1.243954e+01 6.467515e-02 -5.040069e-03 9.978936e-01 3.029910e+02 +9.976877e-01 2.631545e-03 -6.791529e-02 6.582627e+01 -2.309656e-03 9.999857e-01 4.817655e-03 -1.245262e+01 6.792700e-02 -4.649652e-03 9.976794e-01 3.040085e+02 +9.974702e-01 5.610345e-04 -7.108405e-02 6.574479e+01 -4.871111e-04 9.999993e-01 1.057273e-03 -1.246723e+01 7.108459e-02 -1.019972e-03 9.974697e-01 3.050138e+02 +9.972165e-01 -4.010025e-03 -7.445359e-02 6.566126e+01 3.499052e-03 9.999694e-01 -6.992146e-03 -1.247957e+01 7.447934e-02 6.712166e-03 9.971999e-01 3.060167e+02 +9.969554e-01 -7.998305e-03 -7.756322e-02 6.557359e+01 6.892605e-03 9.998709e-01 -1.451272e-02 -1.249164e+01 7.766928e-02 1.393392e-02 9.968817e-01 3.070182e+02 +9.966494e-01 -1.060870e-02 -8.110156e-02 6.548054e+01 9.503459e-03 9.998568e-01 -1.400173e-02 -1.250702e+01 8.123848e-02 1.318407e-02 9.966074e-01 3.080259e+02 +9.962654e-01 -1.226778e-02 -8.546880e-02 6.538313e+01 1.142528e-02 9.998812e-01 -1.033961e-02 -1.253112e+01 8.558549e-02 9.324490e-03 9.962871e-01 3.090388e+02 +9.958380e-01 -9.738008e-03 -9.062021e-02 6.527471e+01 8.466516e-03 9.998604e-01 -1.440487e-02 -1.255384e+01 9.074782e-02 1.357767e-02 9.957813e-01 3.100323e+02 +9.953505e-01 -1.200291e-02 -9.556931e-02 6.516792e+01 1.014763e-02 9.997509e-01 -1.987533e-02 -1.257651e+01 9.578407e-02 1.881311e-02 9.952243e-01 3.110292e+02 +9.949651e-01 -8.611550e-03 -9.985154e-02 6.504766e+01 6.669039e-03 9.997823e-01 -1.977151e-02 -1.260101e+01 1.000001e-01 1.900604e-02 9.948058e-01 3.120284e+02 +9.944586e-01 -7.137047e-03 -1.048869e-01 6.492447e+01 5.748209e-03 9.998918e-01 -1.353763e-02 -1.263184e+01 1.049721e-01 1.285970e-02 9.943920e-01 3.130306e+02 +9.938460e-01 -2.837663e-03 -1.107349e-01 6.479958e+01 2.083452e-03 9.999738e-01 -6.926077e-03 -1.265875e+01 1.107517e-01 6.652743e-03 9.938258e-01 3.140236e+02 +9.932380e-01 -3.616121e-03 -1.160402e-01 6.467468e+01 2.723054e-03 9.999654e-01 -7.853797e-03 -1.268260e+01 1.160646e-01 7.484705e-03 9.932134e-01 3.150083e+02 +9.927316e-01 -1.882054e-04 -1.203500e-01 6.454061e+01 -7.510160e-04 9.999696e-01 -7.758680e-03 -1.270404e+01 1.203478e-01 7.792671e-03 9.927012e-01 3.159953e+02 +9.923847e-01 8.974862e-03 -1.228497e-01 6.439547e+01 -9.927870e-03 9.999251e-01 -7.147556e-03 -1.272666e+01 1.227764e-01 8.312761e-03 9.923995e-01 3.169795e+02 +9.920343e-01 2.088319e-02 -1.242252e-01 6.424186e+01 -2.199521e-02 9.997293e-01 -7.586732e-03 -1.275115e+01 1.240331e-01 1.025866e-02 9.922250e-01 3.179632e+02 +9.917372e-01 2.946745e-02 -1.248562e-01 6.408999e+01 -3.057802e-02 9.995079e-01 -6.987221e-03 -1.277584e+01 1.245888e-01 1.074734e-02 9.921502e-01 3.189476e+02 +9.916108e-01 3.662278e-02 -1.239635e-01 6.394426e+01 -3.801263e-02 9.992379e-01 -8.864350e-03 -1.279599e+01 1.235444e-01 1.350216e-02 9.922471e-01 3.199305e+02 +9.917801e-01 3.769811e-02 -1.222747e-01 6.380681e+01 -3.968484e-02 9.991162e-01 -1.385270e-02 -1.281874e+01 1.216444e-01 1.859128e-02 9.923996e-01 3.209166e+02 +9.920440e-01 3.920098e-02 -1.196332e-01 6.367172e+01 -4.129916e-02 9.990326e-01 -1.510884e-02 -1.284441e+01 1.189252e-01 1.992938e-02 9.927031e-01 3.219037e+02 +9.924467e-01 4.162653e-02 -1.153986e-01 6.354101e+01 -4.328732e-02 9.989915e-01 -1.192217e-02 -1.287181e+01 1.147860e-01 1.682742e-02 9.932477e-01 3.228976e+02 +9.931005e-01 4.033344e-02 -1.101123e-01 6.342010e+01 -4.146227e-02 9.991082e-01 -7.980235e-03 -1.289752e+01 1.096922e-01 1.249068e-02 9.938871e-01 3.238960e+02 +9.937005e-01 4.135580e-02 -1.041586e-01 6.330426e+01 -4.209706e-02 9.991014e-01 -4.927456e-03 -1.291743e+01 1.038612e-01 9.281185e-03 9.945484e-01 3.248959e+02 +9.942791e-01 4.385231e-02 -9.739689e-02 6.319056e+01 -4.407888e-02 9.990280e-01 -1.746928e-04 -1.293434e+01 9.729455e-02 4.466839e-03 9.952456e-01 3.258993e+02 +9.945135e-01 5.151928e-02 -9.104240e-02 6.307559e+01 -5.151522e-02 9.986693e-01 2.396205e-03 -1.295117e+01 9.104470e-02 2.307011e-03 9.958441e-01 3.269016e+02 +9.947637e-01 5.664034e-02 -8.507174e-02 6.296758e+01 -5.704031e-02 9.983693e-01 -2.276287e-03 -1.296731e+01 8.480407e-02 7.116886e-03 9.963722e-01 3.278981e+02 +9.950931e-01 5.870086e-02 -7.964956e-02 6.286847e+01 -5.977361e-02 9.981497e-01 -1.114953e-02 -1.298511e+01 7.884769e-02 1.585576e-02 9.967605e-01 3.288954e+02 +9.954553e-01 5.966727e-02 -7.422036e-02 6.277719e+01 -6.099094e-02 9.980149e-01 -1.569545e-02 -1.300726e+01 7.313651e-02 2.015088e-02 9.971183e-01 3.298966e+02 +9.960827e-01 5.522104e-02 -6.906473e-02 6.269908e+01 -5.634147e-02 9.983080e-01 -1.438002e-02 -1.303326e+01 6.815378e-02 1.821489e-02 9.975085e-01 3.309092e+02 +9.966194e-01 5.012351e-02 -6.509591e-02 6.264298e+01 -5.080434e-02 9.986694e-01 -8.844863e-03 -1.306157e+01 6.456595e-02 1.212211e-02 9.978398e-01 3.319218e+02 +9.972039e-01 4.234907e-02 -6.157053e-02 6.259494e+01 -4.291380e-02 9.990477e-01 -7.878194e-03 -1.308971e+01 6.117826e-02 1.049839e-02 9.980716e-01 3.329321e+02 +9.974886e-01 3.826066e-02 -5.960426e-02 6.255359e+01 -3.908766e-02 9.991542e-01 -1.277072e-02 -1.310731e+01 5.906522e-02 1.506844e-02 9.981403e-01 3.339290e+02 +9.975766e-01 4.068064e-02 -5.644512e-02 6.250140e+01 -4.151227e-02 9.990449e-01 -1.363951e-02 -1.312676e+01 5.583634e-02 1.594962e-02 9.983125e-01 3.349352e+02 +9.977240e-01 4.227708e-02 -5.253100e-02 6.245476e+01 -4.287660e-02 9.990269e-01 -1.033806e-02 -1.314928e+01 5.204281e-02 1.256688e-02 9.985657e-01 3.359506e+02 +9.977282e-01 4.609041e-02 -4.913486e-02 6.240233e+01 -4.672688e-02 9.988370e-01 -1.188371e-02 -1.317243e+01 4.852999e-02 1.415263e-02 9.987214e-01 3.369634e+02 +9.976480e-01 5.019246e-02 -4.668328e-02 6.235329e+01 -5.102380e-02 9.985563e-01 -1.678945e-02 -1.319165e+01 4.577317e-02 1.913191e-02 9.987686e-01 3.379738e+02 +9.977851e-01 4.870591e-02 -4.530578e-02 6.231050e+01 -4.934935e-02 9.986944e-01 -1.319298e-02 -1.321303e+01 4.460405e-02 1.539957e-02 9.988860e-01 3.389940e+02 +9.979131e-01 4.713268e-02 -4.413646e-02 6.226657e+01 -4.735276e-02 9.988704e-01 -3.953408e-03 -1.324241e+01 4.390027e-02 6.035140e-03 9.990176e-01 3.400213e+02 +9.978938e-01 4.844563e-02 -4.313914e-02 6.221832e+01 -4.852655e-02 9.988215e-01 -8.298428e-04 -1.326965e+01 4.304810e-02 2.921489e-03 9.990687e-01 3.410391e+02 +9.977850e-01 5.094350e-02 -4.277814e-02 6.216440e+01 -5.127576e-02 9.986620e-01 -6.705136e-03 -1.330210e+01 4.237932e-02 8.883764e-03 9.990620e-01 3.420414e+02 +9.977879e-01 5.084846e-02 -4.282283e-02 6.211650e+01 -5.153060e-02 9.985591e-01 -1.497841e-02 -1.333378e+01 4.199949e-02 1.715196e-02 9.989703e-01 3.430358e+02 +9.978637e-01 4.927457e-02 -4.289628e-02 6.207180e+01 -5.007133e-02 9.985887e-01 -1.770146e-02 -1.335633e+01 4.196351e-02 1.981151e-02 9.989226e-01 3.440311e+02 +9.979993e-01 4.707050e-02 -4.221227e-02 6.203277e+01 -4.760057e-02 9.987986e-01 -1.164064e-02 -1.338222e+01 4.161362e-02 1.362668e-02 9.990408e-01 3.450315e+02 +9.981832e-01 4.340187e-02 -4.179275e-02 6.199350e+01 -4.373612e-02 9.990177e-01 -7.116624e-03 -1.340929e+01 4.144282e-02 8.931546e-03 9.991009e-01 3.460329e+02 +9.983687e-01 3.856272e-02 -4.210603e-02 6.195688e+01 -3.899478e-02 9.991943e-01 -9.488201e-03 -1.342898e+01 4.170621e-02 1.111464e-02 9.990680e-01 3.470203e+02 +9.984029e-01 3.756726e-02 -4.219620e-02 6.191201e+01 -3.802337e-02 9.992262e-01 -1.005893e-02 -1.344291e+01 4.178566e-02 1.164730e-02 9.990587e-01 3.480069e+02 +9.984251e-01 3.752178e-02 -4.170669e-02 6.186637e+01 -3.777253e-02 9.992726e-01 -5.240163e-03 -1.345810e+01 4.147973e-02 6.807277e-03 9.991161e-01 3.489891e+02 +9.984943e-01 3.692021e-02 -4.057141e-02 6.182440e+01 -3.703212e-02 9.993120e-01 -2.010048e-03 -1.347425e+01 4.046929e-02 3.509467e-03 9.991746e-01 3.499622e+02 +9.985995e-01 3.473026e-02 -3.991228e-02 6.178986e+01 -3.496255e-02 9.993754e-01 -5.136563e-03 -1.348794e+01 3.970896e-02 6.524803e-03 9.991899e-01 3.509183e+02 +9.987485e-01 3.091859e-02 -3.931436e-02 6.176087e+01 -3.130925e-02 9.994659e-01 -9.360158e-03 -1.349829e+01 3.900396e-02 1.057935e-02 9.991830e-01 3.518578e+02 +9.989210e-01 2.602149e-02 -3.846837e-02 6.173422e+01 -2.645850e-02 9.995905e-01 -1.089499e-02 -1.351502e+01 3.816911e-02 1.190104e-02 9.992004e-01 3.527875e+02 +9.990267e-01 2.405496e-02 -3.697300e-02 6.170791e+01 -2.442913e-02 9.996545e-01 -9.701672e-03 -1.353427e+01 3.672685e-02 1.059545e-02 9.992691e-01 3.537061e+02 +9.991527e-01 2.243239e-02 -3.450609e-02 6.167929e+01 -2.283415e-02 9.996755e-01 -1.129335e-02 -1.355394e+01 3.424155e-02 1.207170e-02 9.993406e-01 3.546117e+02 +9.991254e-01 2.789222e-02 -3.115283e-02 6.164661e+01 -2.824770e-02 9.995401e-01 -1.102969e-02 -1.357062e+01 3.083086e-02 1.190004e-02 9.994537e-01 3.555074e+02 +9.991359e-01 3.202827e-02 -2.649101e-02 6.161399e+01 -3.228926e-02 9.994335e-01 -9.483627e-03 -1.359330e+01 2.617226e-02 1.033081e-02 9.996040e-01 3.563914e+02 +9.990853e-01 3.715171e-02 -2.117577e-02 6.158630e+01 -3.734555e-02 9.992634e-01 -8.832942e-03 -1.361600e+01 2.083202e-02 9.615682e-03 9.997367e-01 3.572614e+02 +9.990908e-01 3.972863e-02 -1.546714e-02 6.156519e+01 -3.995136e-02 9.990983e-01 -1.436708e-02 -1.364223e+01 1.488241e-02 1.497195e-02 9.997771e-01 3.581135e+02 +9.991446e-01 4.021899e-02 -9.620930e-03 6.155241e+01 -4.038004e-02 9.990367e-01 -1.717618e-02 -1.366753e+01 8.920854e-03 1.754998e-02 9.998061e-01 3.589535e+02 +9.992508e-01 3.844574e-02 -4.456123e-03 6.155060e+01 -3.851154e-02 9.991338e-01 -1.576470e-02 -1.369303e+01 3.846177e-03 1.592450e-02 9.998657e-01 3.597769e+02 +9.993635e-01 3.564648e-02 1.403407e-03 6.155571e+01 -3.563430e-02 9.993335e-01 -7.917158e-03 -1.371943e+01 -1.684690e-03 7.862109e-03 9.999676e-01 3.605893e+02 +9.994939e-01 3.114453e-02 6.485400e-03 6.156597e+01 -3.114582e-02 9.995148e-01 9.663890e-05 -1.374183e+01 -6.479243e-03 -2.985825e-04 9.999789e-01 3.613787e+02 +9.995767e-01 2.712678e-02 1.052295e-02 6.157724e+01 -2.715720e-02 9.996273e-01 2.758650e-03 -1.376060e+01 -1.044420e-02 -3.043255e-03 9.999408e-01 3.621457e+02 +9.995327e-01 2.788579e-02 1.252096e-02 6.158359e+01 -2.787020e-02 9.996105e-01 -1.418467e-03 -1.377996e+01 -1.255564e-02 1.068843e-03 9.999205e-01 3.628822e+02 +9.995267e-01 2.759619e-02 1.360043e-02 6.159020e+01 -2.750985e-02 9.996004e-01 -6.495708e-03 -1.379541e+01 -1.377425e-02 6.118487e-03 9.998864e-01 3.635975e+02 +9.996216e-01 2.388269e-02 1.365376e-02 6.160302e+01 -2.373683e-02 9.996605e-01 -1.074684e-02 -1.380916e+01 -1.390579e-02 1.041868e-02 9.998490e-01 3.642908e+02 +9.997351e-01 1.848675e-02 1.371125e-02 6.161817e+01 -1.829084e-02 9.997307e-01 -1.427873e-02 -1.382908e+01 -1.397153e-02 1.402415e-02 9.998040e-01 3.649720e+02 +9.997380e-01 1.840285e-02 1.361530e-02 6.162589e+01 -1.814442e-02 9.996573e-01 -1.886694e-02 -1.385587e+01 -1.395784e-02 1.861495e-02 9.997292e-01 3.656500e+02 +9.997291e-01 1.957617e-02 1.259032e-02 6.162869e+01 -1.927196e-02 9.995298e-01 -2.384592e-02 -1.387890e+01 -1.305122e-02 2.359681e-02 9.996363e-01 3.663231e+02 +9.997378e-01 2.026922e-02 1.065955e-02 6.163203e+01 -1.997851e-02 9.994437e-01 -2.670572e-02 -1.389660e+01 -1.119492e-02 2.648575e-02 9.995864e-01 3.669963e+02 +9.998508e-01 1.545104e-02 7.722933e-03 6.164140e+01 -1.526891e-02 9.996163e-01 -2.310967e-02 -1.391728e+01 -8.077038e-03 2.298830e-02 9.997031e-01 3.676727e+02 +9.999369e-01 1.069681e-02 3.443033e-03 6.164988e+01 -1.064540e-02 9.998364e-01 -1.461902e-02 -1.394262e+01 -3.598846e-03 1.458145e-02 9.998872e-01 3.683524e+02 +9.999740e-01 6.783105e-03 -2.484346e-03 6.165211e+01 -6.804285e-03 9.999397e-01 -8.618236e-03 -1.396674e+01 2.425737e-03 8.634914e-03 9.999597e-01 3.690280e+02 +9.999260e-01 4.578028e-03 -1.127121e-02 6.164391e+01 -4.687291e-03 9.999421e-01 -9.686658e-03 -1.398697e+01 1.122621e-02 9.738771e-03 9.998895e-01 3.696924e+02 +9.997343e-01 4.889872e-03 -2.252869e-02 6.162473e+01 -5.155290e-03 9.999178e-01 -1.173836e-02 -1.400683e+01 2.246944e-02 1.185138e-02 9.996772e-01 3.703558e+02 +9.993596e-01 5.393021e-03 -3.537569e-02 6.159376e+01 -5.902486e-03 9.998801e-01 -1.431295e-02 -1.401984e+01 3.529426e-02 1.451259e-02 9.992715e-01 3.710126e+02 +9.987549e-01 2.553714e-03 -4.982189e-02 6.155833e+01 -3.346129e-03 9.998691e-01 -1.582802e-02 -1.403029e+01 4.977495e-02 1.597502e-02 9.986326e-01 3.716756e+02 +9.978625e-01 1.387390e-03 -6.533414e-02 6.151118e+01 -2.378888e-03 9.998831e-01 -1.510046e-02 -1.404429e+01 6.530555e-02 1.522360e-02 9.977491e-01 3.723395e+02 +9.967445e-01 6.407730e-03 -8.037040e-02 6.144542e+01 -7.537106e-03 9.998769e-01 -1.375664e-02 -1.406530e+01 8.027236e-02 1.431762e-02 9.966701e-01 3.730157e+02 +9.954055e-01 1.418819e-02 -9.469278e-02 6.136189e+01 -1.542687e-02 9.998046e-01 -1.236181e-02 -1.408297e+01 9.449888e-02 1.376582e-02 9.954297e-01 3.736982e+02 +9.938740e-01 1.956935e-02 -1.087734e-01 6.127159e+01 -2.091332e-02 9.997182e-01 -1.122853e-02 -1.409856e+01 1.085230e-01 1.343456e-02 9.940031e-01 3.743882e+02 +9.924002e-01 1.969220e-02 -1.214663e-01 6.118214e+01 -2.155956e-02 9.996684e-01 -1.407829e-02 -1.411114e+01 1.211487e-01 1.659006e-02 9.924957e-01 3.750910e+02 +9.910718e-01 2.489039e-02 -1.309853e-01 6.108059e+01 -2.715475e-02 9.995106e-01 -1.552919e-02 -1.412641e+01 1.305347e-01 1.894741e-02 9.912626e-01 3.758055e+02 +9.899912e-01 3.335339e-02 -1.371314e-01 6.096671e+01 -3.619836e-02 9.991770e-01 -1.830451e-02 -1.414594e+01 1.364080e-01 2.308523e-02 9.903837e-01 3.765284e+02 +9.892476e-01 4.035227e-02 -1.405739e-01 6.084972e+01 -4.367394e-02 9.988329e-01 -2.062371e-02 -1.416784e+01 1.395777e-01 2.654137e-02 9.898553e-01 3.772646e+02 +9.892228e-01 3.794109e-02 -1.414171e-01 6.074507e+01 -4.128656e-02 9.989309e-01 -2.079716e-02 -1.418454e+01 1.404769e-01 2.641165e-02 9.897316e-01 3.780220e+02 +9.893746e-01 3.981161e-02 -1.398318e-01 6.063715e+01 -4.265277e-02 9.989388e-01 -1.737944e-02 -1.419874e+01 1.389915e-01 2.315898e-02 9.900227e-01 3.787962e+02 +9.896605e-01 4.732865e-02 -1.353962e-01 6.052298e+01 -4.899293e-02 9.987587e-01 -8.984459e-03 -1.421763e+01 1.348029e-01 1.552502e-02 9.907507e-01 3.795900e+02 +9.902836e-01 5.104442e-02 -1.293559e-01 6.041374e+01 -5.195479e-02 9.986427e-01 -3.670775e-03 -1.423869e+01 1.289929e-01 1.035577e-02 9.915914e-01 3.803936e+02 +9.914581e-01 4.482361e-02 -1.224818e-01 6.032454e+01 -4.608718e-02 9.989092e-01 -7.501371e-03 -1.425909e+01 1.220120e-01 1.308214e-02 9.924424e-01 3.812080e+02 +9.926911e-01 4.044807e-02 -1.137033e-01 6.023753e+01 -4.260300e-02 9.989544e-01 -1.658553e-02 -1.427425e+01 1.129136e-01 2.130841e-02 9.933762e-01 3.820327e+02 +9.936781e-01 4.279511e-02 -1.037906e-01 6.014740e+01 -4.516548e-02 9.987672e-01 -2.059523e-02 -1.429007e+01 1.027812e-01 2.515278e-02 9.943859e-01 3.828751e+02 +9.946449e-01 4.431672e-02 -9.336844e-02 6.006557e+01 -4.628627e-02 9.987468e-01 -1.903439e-02 -1.431204e+01 9.240789e-02 2.325413e-02 9.954496e-01 3.837413e+02 +9.956186e-01 4.522462e-02 -8.184403e-02 5.999739e+01 -4.647432e-02 9.988292e-01 -1.342821e-02 -1.434133e+01 8.114092e-02 1.717302e-02 9.965546e-01 3.846238e+02 +9.965303e-01 4.595035e-02 -6.939722e-02 5.993719e+01 -4.684395e-02 9.988382e-01 -1.130358e-02 -1.436719e+01 6.879719e-02 1.451520e-02 9.975250e-01 3.855155e+02 +9.972227e-01 4.739595e-02 -5.745106e-02 5.988483e+01 -4.843075e-02 9.986860e-01 -1.675456e-02 -1.439286e+01 5.658147e-02 1.949042e-02 9.982077e-01 3.864137e+02 +9.978573e-01 4.561471e-02 -4.690587e-02 5.984353e+01 -4.683766e-02 9.985817e-01 -2.531186e-02 -1.442481e+01 4.568475e-02 2.745458e-02 9.985785e-01 3.873252e+02 +9.984140e-01 4.120166e-02 -3.836761e-02 5.981431e+01 -4.246533e-02 9.985618e-01 -3.272474e-02 -1.445856e+01 3.696411e-02 3.430212e-02 9.987276e-01 3.882519e+02 +9.987456e-01 3.904881e-02 -3.134605e-02 5.978983e+01 -4.008176e-02 9.986503e-01 -3.303043e-02 -1.449961e+01 3.001394e-02 3.424539e-02 9.989626e-01 3.891956e+02 +9.989850e-01 3.739707e-02 -2.510909e-02 5.976798e+01 -3.805854e-02 9.989266e-01 -2.640403e-02 -1.453983e+01 2.409470e-02 2.733284e-02 9.993359e-01 3.901599e+02 +9.992481e-01 3.336376e-02 -1.975042e-02 5.976610e+01 -3.377836e-02 9.992078e-01 -2.104396e-02 -1.459815e+01 1.903267e-02 2.169527e-02 9.995834e-01 3.911281e+02 +9.994201e-01 3.087210e-02 -1.436767e-02 5.976542e+01 -3.112204e-02 9.993622e-01 -1.751030e-02 -1.464881e+01 1.381792e-02 1.794729e-02 9.997434e-01 3.921067e+02 +9.995018e-01 2.980479e-02 -1.038472e-02 5.976528e+01 -2.999023e-02 9.993848e-01 -1.818282e-02 -1.469849e+01 9.836393e-03 1.848520e-02 9.997807e-01 3.930928e+02 +9.995547e-01 2.826470e-02 -9.568011e-03 5.976442e+01 -2.845219e-02 9.993938e-01 -2.006229e-02 -1.473892e+01 8.995156e-03 2.032558e-02 9.997529e-01 3.940969e+02 +9.996729e-01 2.332855e-02 -1.048252e-02 5.976640e+01 -2.352398e-02 9.995441e-01 -1.892361e-02 -1.477563e+01 1.003628e-02 1.916400e-02 9.997659e-01 3.951213e+02 +9.996774e-01 2.212832e-02 -1.247129e-02 5.976162e+01 -2.230830e-02 9.996462e-01 -1.448188e-02 -1.481712e+01 1.214642e-02 1.475542e-02 9.998173e-01 3.961597e+02 +9.996204e-01 2.321541e-02 -1.484071e-02 5.974722e+01 -2.342056e-02 9.996304e-01 -1.380254e-02 -1.485438e+01 1.451479e-02 1.414488e-02 9.997945e-01 3.972110e+02 +9.995224e-01 2.537689e-02 -1.763504e-02 5.972862e+01 -2.566101e-02 9.995414e-01 -1.607559e-02 -1.489124e+01 1.721900e-02 1.652044e-02 9.997152e-01 3.982688e+02 +9.995163e-01 2.270545e-02 -2.125416e-02 5.971318e+01 -2.302647e-02 9.996226e-01 -1.498263e-02 -1.492621e+01 2.090595e-02 1.546479e-02 9.996618e-01 3.993403e+02 +9.994952e-01 1.960538e-02 -2.500109e-02 5.969604e+01 -1.987732e-02 9.997454e-01 -1.067525e-02 -1.496445e+01 2.478543e-02 1.116681e-02 9.996304e-01 4.004182e+02 +9.994541e-01 1.627503e-02 -2.875150e-02 5.967327e+01 -1.654800e-02 9.998200e-01 -9.281686e-03 -1.500203e+01 2.859526e-02 9.752398e-03 9.995434e-01 4.014929e+02 +9.993650e-01 1.277137e-02 -3.326484e-02 5.964675e+01 -1.326629e-02 9.998039e-01 -1.469996e-02 -1.504264e+01 3.307058e-02 1.513193e-02 9.993384e-01 4.025603e+02 +9.992601e-01 8.587248e-03 -3.749044e-02 5.961590e+01 -9.380820e-03 9.997345e-01 -2.104296e-02 -1.508099e+01 3.729978e-02 2.137908e-02 9.990753e-01 4.036242e+02 +9.991191e-01 8.361482e-03 -4.112422e-02 5.957539e+01 -9.225307e-03 9.997398e-01 -2.086052e-02 -1.512563e+01 4.093910e-02 2.122152e-02 9.989362e-01 4.046946e+02 +9.990015e-01 1.094108e-02 -4.331784e-02 5.952883e+01 -1.152359e-02 9.998462e-01 -1.322054e-02 -1.516690e+01 4.316653e-02 1.370651e-02 9.989738e-01 4.057719e+02 +9.988715e-01 1.528517e-02 -4.496800e-02 5.947664e+01 -1.552287e-02 9.998673e-01 -4.941489e-03 -1.520557e+01 4.488649e-02 5.633945e-03 9.989762e-01 4.068490e+02 +9.987741e-01 1.748304e-02 -4.631015e-02 5.942514e+01 -1.774454e-02 9.998288e-01 -5.241646e-03 -1.523835e+01 4.621058e-02 6.056972e-03 9.989133e-01 4.079166e+02 +9.986826e-01 1.764641e-02 -4.818558e-02 5.937438e+01 -1.809721e-02 9.997963e-01 -8.935191e-03 -1.526821e+01 4.801809e-02 9.795442e-03 9.987984e-01 4.089796e+02 +9.985789e-01 1.888472e-02 -4.983612e-02 5.932089e+01 -1.939893e-02 9.997632e-01 -9.854464e-03 -1.529901e+01 4.963822e-02 1.080723e-02 9.987087e-01 4.100425e+02 +9.984863e-01 1.946309e-02 -5.144309e-02 5.926700e+01 -1.989426e-02 9.997710e-01 -7.882592e-03 -1.533264e+01 5.127789e-02 8.894082e-03 9.986448e-01 4.111043e+02 +9.983562e-01 2.141033e-02 -5.316587e-02 5.920589e+01 -2.205126e-02 9.996907e-01 -1.149810e-02 -1.537085e+01 5.290325e-02 1.265157e-02 9.985194e-01 4.121563e+02 +9.982978e-01 2.264134e-02 -5.374810e-02 5.914511e+01 -2.358740e-02 9.995766e-01 -1.703306e-02 -1.540570e+01 5.333969e-02 1.827184e-02 9.984092e-01 4.132056e+02 +9.982897e-01 2.255339e-02 -5.393667e-02 5.908467e+01 -2.354278e-02 9.995647e-01 -1.777896e-02 -1.544272e+01 5.351221e-02 1.901837e-02 9.983860e-01 4.142578e+02 +9.983170e-01 2.260390e-02 -5.340649e-02 5.902650e+01 -2.336425e-02 9.996337e-01 -1.365569e-02 -1.547985e+01 5.307826e-02 1.488051e-02 9.984794e-01 4.153126e+02 +9.983455e-01 2.245892e-02 -5.293351e-02 5.896893e+01 -2.284731e-02 9.997162e-01 -6.743582e-03 -1.551299e+01 5.276704e-02 7.941813e-03 9.985752e-01 4.163646e+02 +9.983765e-01 2.154102e-02 -5.272957e-02 5.891368e+01 -2.160224e-02 9.997664e-01 -5.913803e-04 -1.554099e+01 5.270452e-02 1.729498e-03 9.986086e-01 4.174171e+02 +9.984060e-01 2.077367e-02 -5.247853e-02 5.885967e+01 -2.076041e-02 9.997841e-01 7.978581e-04 -1.556518e+01 5.248378e-02 2.928902e-04 9.986217e-01 4.184607e+02 +9.984284e-01 2.053422e-02 -5.214627e-02 5.880686e+01 -2.083301e-02 9.997695e-01 -5.192683e-03 -1.559016e+01 5.202762e-02 6.270885e-03 9.986259e-01 4.194964e+02 +9.983888e-01 2.355659e-02 -5.162411e-02 5.874881e+01 -2.413414e-02 9.996526e-01 -1.059284e-02 -1.561868e+01 5.135664e-02 1.182167e-02 9.986104e-01 4.205281e+02 +9.982837e-01 2.788857e-02 -5.149634e-02 5.868504e+01 -2.870058e-02 9.994740e-01 -1.509662e-02 -1.564958e+01 5.104823e-02 1.654868e-02 9.985590e-01 4.215570e+02 +9.983316e-01 2.711233e-02 -5.098085e-02 5.862784e+01 -2.802014e-02 9.994597e-01 -1.717721e-02 -1.568558e+01 5.048759e-02 1.857704e-02 9.985518e-01 4.225846e+02 +9.984142e-01 2.485602e-02 -5.051004e-02 5.857414e+01 -2.590557e-02 9.994596e-01 -2.023170e-02 -1.572120e+01 4.997986e-02 2.150811e-02 9.985186e-01 4.236042e+02 +9.985779e-01 2.013589e-02 -4.936321e-02 5.852715e+01 -2.106721e-02 9.996083e-01 -1.841946e-02 -1.575751e+01 4.897298e-02 1.943321e-02 9.986110e-01 4.246242e+02 +9.986212e-01 1.789890e-02 -4.935052e-02 5.848082e+01 -1.845751e-02 9.997703e-01 -1.088680e-02 -1.579727e+01 4.914433e-02 1.178268e-02 9.987221e-01 4.256365e+02 +9.986872e-01 1.495140e-02 -4.899479e-02 5.843720e+01 -1.525002e-02 9.998673e-01 -5.726675e-03 -1.583191e+01 4.890266e-02 6.466328e-03 9.987826e-01 4.266354e+02 +9.987031e-01 1.444444e-02 -4.882272e-02 5.839171e+01 -1.483208e-02 9.998612e-01 -7.586856e-03 -1.586596e+01 4.870635e-02 8.301158e-03 9.987786e-01 4.276159e+02 +9.987065e-01 1.551986e-02 -4.842087e-02 5.834298e+01 -1.611382e-02 9.997993e-01 -1.190045e-02 -1.589808e+01 4.822646e-02 1.266530e-02 9.987561e-01 4.285773e+02 +9.985456e-01 2.089953e-02 -4.969854e-02 5.828685e+01 -2.168221e-02 9.996484e-01 -1.526175e-02 -1.593052e+01 4.936210e-02 1.631712e-02 9.986476e-01 4.295233e+02 +9.983508e-01 2.305804e-02 -5.257499e-02 5.823246e+01 -2.385038e-02 9.996105e-01 -1.449318e-02 -1.596625e+01 5.222033e-02 1.572321e-02 9.985117e-01 4.304576e+02 +9.981267e-01 2.206719e-02 -5.706338e-02 5.817911e+01 -2.282332e-02 9.996597e-01 -1.263311e-02 -1.600040e+01 5.676518e-02 1.391182e-02 9.982906e-01 4.313774e+02 +9.977805e-01 2.364094e-02 -6.225105e-02 5.811757e+01 -2.443097e-02 9.996299e-01 -1.196036e-02 -1.603584e+01 6.194525e-02 1.345466e-02 9.979888e-01 4.322805e+02 +9.974423e-01 2.201620e-02 -6.800181e-02 5.805705e+01 -2.277426e-02 9.996866e-01 -1.039252e-02 -1.606875e+01 6.775169e-02 1.191463e-02 9.976310e-01 4.331686e+02 +9.969984e-01 1.891711e-02 -7.507620e-02 5.799581e+01 -1.957555e-02 9.997760e-01 -8.044067e-03 -1.609857e+01 7.490721e-02 9.489579e-03 9.971453e-01 4.340437e+02 +9.964350e-01 2.019540e-02 -8.191151e-02 5.792410e+01 -2.052128e-02 9.997845e-01 -3.138386e-03 -1.612658e+01 8.183047e-02 4.808127e-03 9.966346e-01 4.349020e+02 +9.958084e-01 2.233470e-02 -8.869541e-02 5.784065e+01 -2.241981e-02 9.997486e-01 3.658255e-05 -1.615406e+01 8.867393e-02 1.952106e-03 9.960587e-01 4.357462e+02 +9.951076e-01 2.412563e-02 -9.580706e-02 5.775392e+01 -2.430545e-02 9.997043e-01 -7.101303e-04 -1.617716e+01 9.576159e-02 3.035290e-03 9.953996e-01 4.365721e+02 +9.944583e-01 2.424696e-02 -1.022978e-01 5.766319e+01 -2.469173e-02 9.996903e-01 -3.083521e-03 -1.619800e+01 1.021914e-01 5.592344e-03 9.947490e-01 4.373827e+02 +9.937696e-01 2.498655e-02 -1.086173e-01 5.756910e+01 -2.583583e-02 9.996456e-01 -6.418549e-03 -1.621944e+01 1.084184e-01 9.184776e-03 9.940629e-01 4.381737e+02 +9.929671e-01 2.559625e-02 -1.155906e-01 5.747062e+01 -2.685547e-02 9.995956e-01 -9.349353e-03 -1.624168e+01 1.153046e-01 1.238784e-02 9.932529e-01 4.389478e+02 +9.919474e-01 2.618599e-02 -1.239140e-01 5.736825e+01 -2.787191e-02 9.995407e-01 -1.189135e-02 -1.626608e+01 1.235457e-01 1.524931e-02 9.922217e-01 4.397104e+02 +9.906949e-01 2.817153e-02 -1.331541e-01 5.725999e+01 -3.009753e-02 9.994691e-01 -1.247349e-02 -1.629215e+01 1.327320e-01 1.636503e-02 9.910168e-01 4.404555e+02 +9.893724e-01 2.760883e-02 -1.427590e-01 5.714887e+01 -2.947052e-02 9.995057e-01 -1.094245e-02 -1.631654e+01 1.423863e-01 1.503334e-02 9.896969e-01 4.411817e+02 +9.879735e-01 2.909761e-02 -1.518609e-01 5.703669e+01 -3.069163e-02 9.994955e-01 -8.162632e-03 -1.634238e+01 1.515468e-01 1.272532e-02 9.883681e-01 4.418890e+02 +9.865583e-01 3.284145e-02 -1.600758e-01 5.691449e+01 -3.419738e-02 9.993987e-01 -5.722322e-03 -1.636661e+01 1.597916e-01 1.111958e-02 9.870881e-01 4.425732e+02 +9.851823e-01 3.732886e-02 -1.673991e-01 5.678747e+01 -3.837863e-02 9.992586e-01 -3.039189e-03 -1.638826e+01 1.671615e-01 9.418703e-03 9.858845e-01 4.432379e+02 +9.839853e-01 4.564169e-02 -1.723076e-01 5.665685e+01 -4.642832e-02 9.989215e-01 -5.357432e-04 -1.640569e+01 1.720973e-01 8.527117e-03 9.850430e-01 4.438748e+02 +9.834822e-01 5.510353e-02 -1.724136e-01 5.653228e+01 -5.558776e-02 9.984517e-01 2.022146e-03 -1.642058e+01 1.722580e-01 7.595340e-03 9.850225e-01 4.444878e+02 +9.841082e-01 6.288296e-02 -1.660627e-01 5.641955e+01 -6.309557e-02 9.979994e-01 4.000303e-03 -1.643657e+01 1.659821e-01 6.541091e-03 9.861070e-01 4.450756e+02 +9.856350e-01 6.761158e-02 -1.547656e-01 5.632386e+01 -6.761341e-02 9.976977e-01 5.258197e-03 -1.645398e+01 1.547648e-01 5.281565e-03 9.879372e-01 4.456454e+02 +9.878039e-01 7.043923e-02 -1.388589e-01 5.624445e+01 -7.065205e-02 9.974952e-01 3.402288e-03 -1.647357e+01 1.387507e-01 6.449872e-03 9.903063e-01 4.461921e+02 +9.904503e-01 7.383614e-02 -1.164324e-01 5.618642e+01 -7.443566e-02 9.972255e-01 -8.032975e-04 -1.649151e+01 1.160500e-01 9.462344e-03 9.931982e-01 4.467321e+02 +9.931144e-01 7.845409e-02 -8.699861e-02 5.614866e+01 -7.908678e-02 9.968603e-01 -3.844192e-03 -1.650757e+01 8.642387e-02 1.069816e-02 9.962010e-01 4.472701e+02 +9.953993e-01 8.142196e-02 -5.050473e-02 5.612959e+01 -8.174735e-02 9.966433e-01 -4.407293e-03 -1.652522e+01 4.997634e-02 8.515643e-03 9.987140e-01 4.477627e+02 +9.969734e-01 7.629190e-02 1.495884e-02 5.637354e+01 -7.619468e-02 9.970686e-01 -6.966210e-03 -1.654917e+01 -1.544645e-02 5.805341e-03 9.998638e-01 4.481493e+02 +9.942326e-01 7.101582e-02 8.036447e-02 5.661613e+01 -7.048836e-02 9.974684e-01 -9.384972e-03 -1.657290e+01 -8.082749e-02 3.666085e-03 9.967213e-01 4.485308e+02 +9.871759e-01 6.563932e-02 1.455171e-01 5.685753e+01 -6.463015e-02 9.978412e-01 -1.165700e-02 -1.659654e+01 -1.459681e-01 2.102719e-03 9.892870e-01 4.489090e+02 +9.758535e-01 6.023011e-02 2.099580e-01 5.709636e+01 -5.864639e-02 9.981839e-01 -1.376677e-02 -1.661978e+01 -2.104058e-01 1.121075e-03 9.776134e-01 4.492805e+02 +9.602731e-01 5.482307e-02 2.736239e-01 5.733354e+01 -5.252787e-02 9.984958e-01 -1.571325e-02 -1.664298e+01 -2.740738e-01 7.161289e-04 9.617083e-01 4.496498e+02 +9.406050e-01 4.950145e-02 3.358749e-01 5.756660e+01 -4.632182e-02 9.987736e-01 -1.747739e-02 -1.666551e+01 -3.363281e-01 8.809839e-04 9.417444e-01 4.500094e+02 +9.168127e-01 4.428157e-02 3.968548e-01 5.779766e+01 -3.999948e-02 9.990178e-01 -1.906504e-02 -1.668805e+01 -3.973092e-01 1.605078e-03 9.176833e-01 4.503681e+02 +8.890326e-01 3.922545e-02 4.561605e-01 5.802562e+01 -3.358655e-02 9.992262e-01 -2.046552e-02 -1.671036e+01 -4.566103e-01 2.873655e-03 8.896621e-01 4.507233e+02 +8.575594e-01 3.440684e-02 5.132329e-01 5.824828e+01 -2.713046e-02 9.993970e-01 -2.166680e-02 -1.673191e+01 -5.136689e-01 4.656320e-03 8.579758e-01 4.510683e+02 +8.221816e-01 2.982081e-02 5.684437e-01 5.846928e+01 -2.057385e-02 9.995311e-01 -2.267839e-02 -1.675378e+01 -5.688534e-01 6.950677e-03 8.224095e-01 4.514173e+02 +7.835769e-01 2.557555e-02 6.207682e-01 5.868323e+01 -1.402482e-02 9.996259e-01 -2.348132e-02 -1.677453e+01 -6.211365e-01 9.693247e-03 7.836424e-01 4.517521e+02 +7.415393e-01 2.166513e-02 6.705596e-01 5.889364e+01 -7.428033e-03 9.996823e-01 -2.408448e-02 -1.679522e+01 -6.708683e-01 1.287864e-02 7.414646e-01 4.520863e+02 +6.962757e-01 1.813334e-02 7.175454e-01 5.909996e+01 -8.031080e-04 9.996999e-01 -2.448446e-02 -1.681575e+01 -7.177740e-01 1.647166e-02 6.960812e-01 4.524190e+02 +6.481558e-01 1.502733e-02 7.613595e-01 5.930076e+01 5.811945e-03 9.996785e-01 -2.467895e-02 -1.683577e+01 -7.614856e-01 2.042078e-02 6.478600e-01 4.527459e+02 +5.971621e-01 1.236460e-02 8.020253e-01 5.949747e+01 1.243492e-02 9.996183e-01 -2.466947e-02 -1.685573e+01 -8.020242e-01 2.470478e-02 5.967803e-01 4.530732e+02 +5.436244e-01 1.016424e-02 8.392671e-01 5.969389e+01 1.890164e-02 9.995248e-01 -2.434840e-02 -1.687518e+01 -8.391157e-01 2.909990e-02 5.431739e-01 4.533957e+02 +4.879108e-01 7.485277e-03 8.728614e-01 6.005191e+01 1.988916e-02 9.996083e-01 -1.968982e-02 -1.688418e+01 -8.726668e-01 2.696735e-02 4.875708e-01 4.534931e+02 +4.302463e-01 6.225964e-03 9.026901e-01 6.043550e+01 1.580295e-02 9.997710e-01 -1.442766e-02 -1.689523e+01 -9.025732e-01 2.047261e-02 4.300493e-01 4.536732e+02 +3.722910e-01 9.087113e-03 9.280716e-01 6.082955e+01 1.366215e-02 9.997900e-01 -1.526984e-02 -1.690196e+01 -9.280154e-01 1.836427e-02 3.720887e-01 4.538234e+02 +3.162863e-01 1.066007e-02 9.486039e-01 6.123210e+01 2.216902e-02 9.995807e-01 -1.862459e-02 -1.690829e+01 -9.484047e-01 2.692031e-02 3.159173e-01 4.538636e+02 +2.642663e-01 9.338816e-03 9.644046e-01 6.166843e+01 3.416858e-02 9.992347e-01 -1.903898e-02 -1.692438e+01 -9.638443e-01 3.798368e-02 2.637449e-01 4.539541e+02 +2.172398e-01 1.042850e-02 9.760626e-01 6.211760e+01 3.763461e-02 9.991099e-01 -1.905099e-02 -1.693856e+01 -9.753924e-01 4.087235e-02 2.166540e-01 4.540315e+02 +1.747380e-01 1.549462e-02 9.844931e-01 6.257515e+01 3.435994e-02 9.991712e-01 -2.182420e-02 -1.695047e+01 -9.840152e-01 3.764063e-02 1.740608e-01 4.540722e+02 +1.364044e-01 2.170969e-02 9.904154e-01 6.305511e+01 2.949719e-02 9.992275e-01 -2.596534e-02 -1.695654e+01 -9.902140e-01 3.275624e-02 1.356586e-01 4.541371e+02 +1.029939e-01 2.472847e-02 9.943746e-01 6.355579e+01 2.882486e-02 9.991969e-01 -2.783398e-02 -1.696640e+01 -9.942642e-01 3.152943e-02 1.021984e-01 4.541813e+02 +7.625369e-02 2.305829e-02 9.968218e-01 6.407556e+01 3.398803e-02 9.990914e-01 -2.571077e-02 -1.697911e+01 -9.965090e-01 3.584054e-02 7.540070e-02 4.541936e+02 +5.641671e-02 2.187309e-02 9.981677e-01 6.461298e+01 3.884386e-02 9.989549e-01 -2.408582e-02 -1.699897e+01 -9.976514e-01 4.013152e-02 5.550812e-02 4.542096e+02 +4.226780e-02 2.337194e-02 9.988329e-01 6.516526e+01 4.299000e-02 9.987579e-01 -2.518941e-02 -1.701404e+01 -9.981809e-01 4.400451e-02 4.121054e-02 4.542240e+02 +3.536481e-02 2.354254e-02 9.990972e-01 6.572987e+01 4.611383e-02 9.986192e-01 -2.516356e-02 -1.702729e+01 -9.983100e-01 4.696209e-02 3.423034e-02 4.542378e+02 +3.500886e-02 2.199664e-02 9.991449e-01 6.631685e+01 4.599504e-02 9.986629e-01 -2.359765e-02 -1.703923e+01 -9.983280e-01 4.678182e-02 3.395031e-02 4.542609e+02 +3.751487e-02 2.046368e-02 9.990865e-01 6.691875e+01 4.534492e-02 9.987256e-01 -2.215896e-02 -1.705511e+01 -9.982667e-01 4.613478e-02 3.653913e-02 4.542886e+02 +4.034753e-02 1.824313e-02 9.990192e-01 6.753618e+01 4.335879e-02 9.988595e-01 -1.999136e-02 -1.707471e+01 -9.982445e-01 4.412286e-02 3.951052e-02 4.543204e+02 +4.291222e-02 1.756834e-02 9.989244e-01 6.816862e+01 4.481491e-02 9.988051e-01 -1.949143e-02 -1.709206e+01 -9.980732e-01 4.560311e-02 4.207362e-02 4.543493e+02 +4.578439e-02 1.832632e-02 9.987833e-01 6.881514e+01 4.539742e-02 9.987605e-01 -2.040693e-02 -1.710837e+01 -9.979192e-01 4.627649e-02 4.489568e-02 4.543800e+02 +4.812445e-02 1.853747e-02 9.986693e-01 6.948192e+01 4.564110e-02 9.987426e-01 -2.073821e-02 -1.712311e+01 -9.977980e-01 4.657837e-02 4.721786e-02 4.544136e+02 +5.097248e-02 1.747688e-02 9.985472e-01 7.016492e+01 4.581171e-02 9.987534e-01 -1.981903e-02 -1.714124e+01 -9.976487e-01 4.675537e-02 5.010829e-02 4.544484e+02 +5.359697e-02 1.815910e-02 9.983976e-01 7.086176e+01 4.587746e-02 9.987340e-01 -2.062806e-02 -1.716519e+01 -9.975082e-01 4.690953e-02 5.269602e-02 4.544814e+02 +5.597240e-02 2.192663e-02 9.981916e-01 7.156844e+01 4.451789e-02 9.987097e-01 -2.443430e-02 -1.719316e+01 -9.974393e-01 4.580502e-02 5.492405e-02 4.545179e+02 +5.802165e-02 2.803357e-02 9.979217e-01 7.228750e+01 4.490768e-02 9.985205e-01 -3.066145e-02 -1.722009e+01 -9.973047e-01 4.659336e-02 5.667688e-02 4.545529e+02 +6.049124e-02 3.278686e-02 9.976301e-01 7.302494e+01 4.386901e-02 9.984073e-01 -3.547240e-02 -1.724416e+01 -9.972042e-01 4.591080e-02 5.895657e-02 4.545937e+02 +6.228593e-02 3.129396e-02 9.975676e-01 7.378323e+01 4.188244e-02 9.985459e-01 -3.393970e-02 -1.727336e+01 -9.971791e-01 4.389452e-02 6.088469e-02 4.546373e+02 +6.357711e-02 2.618480e-02 9.976334e-01 7.456180e+01 3.834275e-02 9.988535e-01 -2.866034e-02 -1.730779e+01 -9.972400e-01 4.007414e-02 6.250022e-02 4.546890e+02 +6.489430e-02 1.916324e-02 9.977082e-01 7.535567e+01 3.650126e-02 9.991009e-01 -2.156416e-02 -1.734186e+01 -9.972243e-01 3.781699e-02 6.413647e-02 4.547396e+02 +6.675369e-02 1.892068e-02 9.975901e-01 7.615867e+01 3.695043e-02 9.990875e-01 -2.142163e-02 -1.736898e+01 -9.970850e-01 3.829134e-02 6.599364e-02 4.547898e+02 +6.800454e-02 1.896079e-02 9.975049e-01 7.697382e+01 3.633122e-02 9.991092e-01 -2.146815e-02 -1.739434e+01 -9.970232e-01 3.770049e-02 6.725509e-02 4.548427e+02 +6.937030e-02 1.756557e-02 9.974363e-01 7.780419e+01 3.627932e-02 9.991391e-01 -2.011874e-02 -1.742263e+01 -9.969310e-01 3.758195e-02 6.867331e-02 4.548927e+02 +7.031176e-02 1.427567e-02 9.974229e-01 7.864677e+01 3.884485e-02 9.991000e-01 -1.703799e-02 -1.745272e+01 -9.967684e-01 3.994271e-02 6.969393e-02 4.549431e+02 +7.087090e-02 1.211018e-02 9.974120e-01 7.949974e+01 4.053485e-02 9.990653e-01 -1.501045e-02 -1.748584e+01 -9.966615e-01 4.149374e-02 7.031378e-02 4.549938e+02 +7.121039e-02 1.458030e-02 9.973548e-01 8.035896e+01 4.141585e-02 9.989876e-01 -1.756124e-02 -1.751605e+01 -9.966011e-01 4.255683e-02 7.053444e-02 4.550524e+02 +7.134070e-02 2.473540e-02 9.971453e-01 8.122587e+01 3.803515e-02 9.988979e-01 -2.750011e-02 -1.754771e+01 -9.967265e-01 3.988843e-02 7.032125e-02 4.551156e+02 +7.056942e-02 3.447901e-02 9.969108e-01 8.210395e+01 3.660642e-02 9.986397e-01 -3.713011e-02 -1.758020e+01 -9.968349e-01 3.911358e-02 6.921127e-02 4.551780e+02 +6.893404e-02 3.824959e-02 9.968877e-01 8.300244e+01 3.476391e-02 9.985657e-01 -4.071788e-02 -1.761761e+01 -9.970153e-01 3.746255e-02 6.750546e-02 4.552393e+02 +6.632842e-02 3.400260e-02 9.972183e-01 8.391678e+01 3.174620e-02 9.988413e-01 -3.616950e-02 -1.766024e+01 -9.972927e-01 3.405694e-02 6.517211e-02 4.553023e+02 +6.321145e-02 2.561646e-02 9.976714e-01 8.483881e+01 2.753333e-02 9.992452e-01 -2.740137e-02 -1.770174e+01 -9.976202e-01 2.920129e-02 6.245843e-02 4.553630e+02 +5.984630e-02 1.935479e-02 9.980200e-01 8.577095e+01 2.865769e-02 9.993666e-01 -2.109938e-02 -1.773483e+01 -9.977961e-01 2.986366e-02 5.925372e-02 4.554132e+02 +5.719878e-02 1.799107e-02 9.982007e-01 8.670202e+01 3.169981e-02 9.993007e-01 -1.982736e-02 -1.776588e+01 -9.978594e-01 3.277686e-02 5.658847e-02 4.554567e+02 +5.487749e-02 1.766998e-02 9.983368e-01 8.763539e+01 3.325057e-02 9.992565e-01 -1.951401e-02 -1.779453e+01 -9.979393e-01 3.426614e-02 5.424915e-02 4.554985e+02 +5.329551e-02 2.091217e-02 9.983598e-01 8.857696e+01 3.837362e-02 9.989993e-01 -2.297407e-02 -1.782493e+01 -9.978412e-01 3.953509e-02 5.243970e-02 4.555371e+02 +5.307553e-02 2.078145e-02 9.983743e-01 8.952635e+01 4.013475e-02 9.989312e-01 -2.292670e-02 -1.785708e+01 -9.977836e-01 4.128633e-02 5.218474e-02 4.555783e+02 +5.332045e-02 2.077350e-02 9.983614e-01 9.048321e+01 3.682276e-02 9.990627e-01 -2.275472e-02 -1.789014e+01 -9.978983e-01 3.797570e-02 5.250553e-02 4.556301e+02 +5.359366e-02 2.014235e-02 9.983597e-01 9.144549e+01 3.395478e-02 9.991816e-01 -2.198169e-02 -1.792387e+01 -9.979853e-01 3.507715e-02 5.286587e-02 4.556821e+02 +5.404909e-02 1.976583e-02 9.983427e-01 9.241235e+01 3.297041e-02 9.992236e-01 -2.156826e-02 -1.795632e+01 -9.979938e-01 3.408150e-02 5.335543e-02 4.557337e+02 +5.433614e-02 1.889604e-02 9.983439e-01 9.338406e+01 3.082520e-02 9.993126e-01 -2.059208e-02 -1.798828e+01 -9.980467e-01 3.189304e-02 5.371631e-02 4.557873e+02 +5.445703e-02 1.845589e-02 9.983456e-01 9.436001e+01 2.753679e-02 9.994211e-01 -1.997784e-02 -1.802480e+01 -9.981363e-01 2.857916e-02 5.391729e-02 4.558435e+02 +5.511189e-02 2.308575e-02 9.982133e-01 9.532857e+01 2.671805e-02 9.993406e-01 -2.458695e-02 -1.806266e+01 -9.981226e-01 2.802533e-02 5.445874e-02 4.558954e+02 +5.586691e-02 2.560801e-02 9.981098e-01 9.630089e+01 2.652800e-02 9.992800e-01 -2.712288e-02 -1.809746e+01 -9.980857e-01 2.799312e-02 5.514736e-02 4.559483e+02 +5.639448e-02 2.617408e-02 9.980654e-01 9.727373e+01 2.589288e-02 9.992817e-01 -2.766903e-02 -1.813883e+01 -9.980727e-01 2.740316e-02 5.567625e-02 4.560023e+02 +5.690987e-02 2.497994e-02 9.980668e-01 9.824989e+01 2.711704e-02 9.992794e-01 -2.655651e-02 -1.818222e+01 -9.980109e-01 2.857594e-02 5.619147e-02 4.560543e+02 +5.761101e-02 2.265503e-02 9.980821e-01 9.922807e+01 2.826720e-02 9.993046e-01 -2.431442e-02 -1.822030e+01 -9.979388e-01 2.961376e-02 5.693055e-02 4.561087e+02 +5.708315e-02 1.743407e-02 9.982172e-01 1.002052e+02 3.026114e-02 9.993579e-01 -1.918448e-02 -1.825342e+01 -9.979107e-01 3.130229e-02 5.651892e-02 4.561674e+02 +5.702203e-02 1.155349e-02 9.983061e-01 1.011841e+02 3.156234e-02 9.994123e-01 -1.336910e-02 -1.828197e+01 -9.978739e-01 3.227120e-02 5.662386e-02 4.562242e+02 +5.588595e-02 1.035456e-02 9.983835e-01 1.021590e+02 3.124252e-02 9.994384e-01 -1.211435e-02 -1.830903e+01 -9.979482e-01 3.186903e-02 5.553106e-02 4.562817e+02 +5.478572e-02 1.070967e-02 9.984407e-01 1.031275e+02 2.945142e-02 9.994901e-01 -1.233697e-02 -1.833657e+01 -9.980637e-01 3.008137e-02 5.444237e-02 4.563403e+02 +5.303450e-02 1.430796e-02 9.984902e-01 1.040931e+02 3.011042e-02 9.994198e-01 -1.592060e-02 -1.837090e+01 -9.981386e-01 3.090929e-02 5.257291e-02 4.563931e+02 +5.128927e-02 1.802538e-02 9.985212e-01 1.050596e+02 3.273219e-02 9.992696e-01 -1.972020e-02 -1.840604e+01 -9.981472e-01 3.369521e-02 5.066180e-02 4.564396e+02 +4.974969e-02 1.943737e-02 9.985726e-01 1.060275e+02 3.355566e-02 9.992136e-01 -2.112162e-02 -1.844084e+01 -9.981978e-01 3.455854e-02 4.905834e-02 4.564855e+02 +4.901332e-02 1.636413e-02 9.986641e-01 1.069989e+02 3.735889e-02 9.991360e-01 -1.820540e-02 -1.847595e+01 -9.980992e-01 3.820128e-02 4.835963e-02 4.565256e+02 +4.928242e-02 1.478644e-02 9.986755e-01 1.079675e+02 4.096478e-02 9.990191e-01 -1.681306e-02 -1.851114e+01 -9.979444e-01 4.173910e-02 4.862836e-02 4.565652e+02 +4.983410e-02 1.488866e-02 9.986466e-01 1.089376e+02 4.131862e-02 9.990021e-01 -1.695583e-02 -1.854235e+01 -9.979024e-01 4.210766e-02 4.916919e-02 4.566076e+02 +5.040173e-02 1.956617e-02 9.985374e-01 1.098972e+02 3.974748e-02 9.989767e-01 -2.158106e-02 -1.857694e+01 -9.979377e-01 4.077706e-02 4.957244e-02 4.566545e+02 +5.127320e-02 2.603087e-02 9.983454e-01 1.108532e+02 3.677140e-02 9.989332e-01 -2.793472e-02 -1.861336e+01 -9.980074e-01 3.814285e-02 5.026131e-02 4.567044e+02 +5.166154e-02 3.415921e-02 9.980803e-01 1.118011e+02 3.135161e-02 9.988667e-01 -3.580893e-02 -1.865851e+01 -9.981724e-01 3.314136e-02 5.053205e-02 4.567610e+02 +5.228197e-02 3.663078e-02 9.979603e-01 1.127497e+02 2.940459e-02 9.988372e-01 -3.820345e-02 -1.870618e+01 -9.981993e-01 3.134196e-02 5.114407e-02 4.568166e+02 +5.272315e-02 3.117220e-02 9.981225e-01 1.137043e+02 3.232296e-02 9.989357e-01 -3.290497e-02 -1.874798e+01 -9.980859e-01 3.399711e-02 5.165945e-02 4.568631e+02 +5.277900e-02 1.970723e-02 9.984118e-01 1.146632e+02 2.906394e-02 9.993514e-01 -2.126219e-02 -1.879289e+01 -9.981831e-01 3.013997e-02 5.217199e-02 4.569174e+02 +5.295409e-02 1.128703e-02 9.985332e-01 1.156102e+02 3.125706e-02 9.994274e-01 -1.295476e-02 -1.883295e+01 -9.981076e-01 3.189721e-02 5.257097e-02 4.569655e+02 +5.436259e-02 1.139746e-02 9.984562e-01 1.165475e+02 3.613459e-02 9.992574e-01 -1.337402e-02 -1.886475e+01 -9.978672e-01 3.680584e-02 5.391038e-02 4.570069e+02 +5.472439e-02 1.486753e-02 9.983908e-01 1.174761e+02 4.006794e-02 9.990511e-01 -1.707360e-02 -1.889868e+01 -9.976972e-01 4.093780e-02 5.407675e-02 4.570505e+02 +5.533853e-02 2.019913e-02 9.982633e-01 1.184001e+02 3.940135e-02 9.989724e-01 -2.239769e-02 -1.893406e+01 -9.976899e-01 4.057236e-02 5.448578e-02 4.570993e+02 +5.593605e-02 2.525757e-02 9.981149e-01 1.193194e+02 3.713231e-02 9.989357e-01 -2.735931e-02 -1.897438e+01 -9.977436e-01 3.859267e-02 5.493864e-02 4.571524e+02 +5.707011e-02 2.920474e-02 9.979430e-01 1.202357e+02 3.529744e-02 9.988881e-01 -3.125099e-02 -1.901741e+01 -9.977460e-01 3.700832e-02 5.597580e-02 4.572047e+02 +5.779613e-02 3.319939e-02 9.977763e-01 1.211459e+02 3.395211e-02 9.988034e-01 -3.520025e-02 -1.906799e+01 -9.977509e-01 3.591104e-02 5.659977e-02 4.572589e+02 +5.893482e-02 3.310280e-02 9.977129e-01 1.220572e+02 2.942610e-02 9.989581e-01 -3.488232e-02 -1.911893e+01 -9.978280e-01 3.141457e-02 5.789933e-02 4.573218e+02 +6.156396e-02 3.122859e-02 9.976145e-01 1.229661e+02 2.731975e-02 9.990832e-01 -3.296051e-02 -1.916630e+01 -9.977291e-01 2.928375e-02 6.065435e-02 4.573856e+02 +6.612858e-02 2.403198e-02 9.975217e-01 1.238765e+02 2.675784e-02 9.993077e-01 -2.584886e-02 -1.921379e+01 -9.974522e-01 2.840087e-02 6.543975e-02 4.574481e+02 +7.197113e-02 1.847829e-02 9.972356e-01 1.247831e+02 2.855969e-02 9.993802e-01 -2.057921e-02 -1.925654e+01 -9.969977e-01 2.996183e-02 7.139878e-02 4.575153e+02 +7.953218e-02 1.486883e-02 9.967214e-01 1.256834e+02 2.872214e-02 9.994394e-01 -1.720123e-02 -1.929294e+01 -9.964184e-01 2.999602e-02 7.906053e-02 4.575899e+02 +8.823503e-02 1.125662e-02 9.960361e-01 1.265838e+02 3.267794e-02 9.993652e-01 -1.418906e-02 -1.932717e+01 -9.955635e-01 3.380037e-02 8.781117e-02 4.576665e+02 +9.848879e-02 9.712496e-03 9.950908e-01 1.274757e+02 3.499230e-02 9.993002e-01 -1.321694e-02 -1.936016e+01 -9.945227e-01 3.612222e-02 9.808000e-02 4.577576e+02 +1.090300e-01 1.153683e-02 9.939715e-01 1.283608e+02 3.079457e-02 9.994135e-01 -1.497790e-02 -1.939938e+01 -9.935613e-01 3.224196e-02 1.086108e-01 4.578608e+02 +1.197771e-01 1.629454e-02 9.926671e-01 1.292416e+02 2.797439e-02 9.994129e-01 -1.978072e-02 -1.943961e+01 -9.924066e-01 3.013852e-02 1.192510e-01 4.579727e+02 +1.305472e-01 2.090905e-02 9.912216e-01 1.301192e+02 2.673978e-02 9.993396e-01 -2.460202e-02 -1.948080e+01 -9.910814e-01 2.971676e-02 1.299019e-01 4.580905e+02 +1.403262e-01 2.062925e-02 9.898904e-01 1.309968e+02 2.347724e-02 9.994325e-01 -2.415623e-02 -1.952025e+01 -9.898269e-01 2.662964e-02 1.397622e-01 4.582201e+02 +1.499819e-01 1.526744e-02 9.885709e-01 1.318773e+02 2.041917e-02 9.996196e-01 -1.853600e-02 -1.955770e+01 -9.884778e-01 2.296586e-02 1.496131e-01 4.583602e+02 +1.598231e-01 1.059456e-02 9.870888e-01 1.327527e+02 1.998022e-02 9.997028e-01 -1.396502e-02 -1.959831e+01 -9.869434e-01 2.195417e-02 1.595640e-01 4.585038e+02 +1.689358e-01 1.161787e-02 9.855586e-01 1.336179e+02 1.876439e-02 9.997114e-01 -1.500114e-02 -1.963306e+01 -9.854484e-01 2.102763e-02 1.686691e-01 4.586527e+02 +1.766944e-01 2.000768e-02 9.840624e-01 1.344723e+02 1.741317e-02 9.995733e-01 -2.344969e-02 -1.966674e+01 -9.841117e-01 2.127907e-02 1.762706e-01 4.588109e+02 +1.839622e-01 2.359862e-02 9.826500e-01 1.353263e+02 1.799304e-02 9.994634e-01 -2.737089e-02 -1.970045e+01 -9.827686e-01 2.271606e-02 1.834388e-01 4.589774e+02 +1.913139e-01 2.147594e-02 9.812940e-01 1.361843e+02 1.766404e-02 9.995233e-01 -2.531870e-02 -1.973513e+01 -9.813699e-01 2.217743e-02 1.908434e-01 4.591490e+02 +1.983963e-01 1.294421e-02 9.800364e-01 1.370478e+02 1.749522e-02 9.997067e-01 -1.674571e-02 -1.976674e+01 -9.799657e-01 2.046824e-02 1.981117e-01 4.593281e+02 +2.065171e-01 4.947218e-03 9.784305e-01 1.379053e+02 2.043983e-02 9.997472e-01 -9.369236e-03 -1.979615e+01 -9.782294e-01 2.193385e-02 2.063638e-01 4.595119e+02 +2.156262e-01 5.567123e-03 9.764601e-01 1.387477e+02 1.835738e-02 9.997839e-01 -9.753860e-03 -1.982313e+01 -9.763034e-01 2.002843e-02 2.154774e-01 4.597078e+02 +2.255337e-01 1.479107e-02 9.741231e-01 1.395789e+02 1.721012e-02 9.996682e-01 -1.916353e-02 -1.985194e+01 -9.740833e-01 2.108679e-02 2.252043e-01 4.599093e+02 +2.354444e-01 2.050072e-02 9.716716e-01 1.404094e+02 1.891349e-02 9.994915e-01 -2.567058e-02 -1.987662e+01 -9.717037e-01 2.442169e-02 2.349369e-01 4.601134e+02 +2.450595e-01 1.608453e-02 9.693746e-01 1.412456e+02 2.126084e-02 9.995327e-01 -2.195972e-02 -1.990477e+01 -9.692748e-01 2.599115e-02 2.446031e-01 4.603268e+02 +2.552755e-01 7.482232e-03 9.668394e-01 1.420823e+02 2.327587e-02 9.996327e-01 -1.388157e-02 -1.993899e+01 -9.665881e-01 2.604765e-02 2.550075e-01 4.605481e+02 +2.673780e-01 1.474146e-03 9.635906e-01 1.429125e+02 2.679017e-02 9.996009e-01 -8.962998e-03 -1.996853e+01 -9.632192e-01 2.821125e-02 2.672317e-01 4.607721e+02 +2.800040e-01 3.185173e-03 9.599936e-01 1.437300e+02 3.254200e-02 9.993883e-01 -1.280750e-02 -1.999516e+01 -9.594471e-01 3.482625e-02 2.797291e-01 4.610046e+02 +2.908361e-01 9.019465e-03 9.567304e-01 1.445361e+02 3.638179e-02 9.991281e-01 -2.047885e-02 -2.002408e+01 -9.560809e-01 4.076354e-02 2.902543e-01 4.612404e+02 +3.009031e-01 1.623041e-02 9.535166e-01 1.453404e+02 4.117997e-02 9.987014e-01 -2.999477e-02 -2.005968e+01 -9.527652e-01 4.829129e-02 2.998439e-01 4.614895e+02 +3.099385e-01 1.837043e-02 9.505791e-01 1.461388e+02 4.112312e-02 9.986186e-01 -3.270711e-02 -2.009772e+01 -9.498668e-01 4.922796e-02 3.087549e-01 4.617549e+02 +3.179520e-01 1.928961e-02 9.479106e-01 1.469351e+02 3.561348e-02 9.988444e-01 -3.227171e-02 -2.014307e+01 -9.474377e-01 4.401924e-02 3.168976e-01 4.620357e+02 +3.251450e-01 1.375072e-02 9.455642e-01 1.477346e+02 3.539163e-02 9.990168e-01 -2.669794e-02 -2.018213e+01 -9.450016e-01 4.214575e-02 3.243386e-01 4.623184e+02 +3.324508e-01 6.753672e-03 9.430964e-01 1.485333e+02 3.779320e-02 9.990757e-01 -2.047703e-02 -2.021462e+01 -9.423630e-01 4.245023e-02 3.318883e-01 4.626011e+02 +3.390362e-01 -1.675636e-04 9.407734e-01 1.493239e+02 3.768832e-02 9.991996e-01 -1.340416e-02 -2.025038e+01 -9.400181e-01 4.000066e-02 3.387711e-01 4.628908e+02 +3.456806e-01 2.694680e-04 9.383522e-01 1.501033e+02 3.238581e-02 9.994007e-01 -1.221765e-02 -2.028734e+01 -9.377931e-01 3.461269e-02 3.454647e-01 4.631915e+02 +3.527380e-01 7.383346e-03 9.356930e-01 1.508754e+02 3.112033e-02 9.993231e-01 -1.961720e-02 -2.032187e+01 -9.352045e-01 3.603879e-02 3.522694e-01 4.634939e+02 +3.604424e-01 1.234908e-02 9.326998e-01 1.516452e+02 3.488812e-02 9.990342e-01 -2.670990e-02 -2.035285e+01 -9.321288e-01 4.216751e-02 3.596634e-01 4.637897e+02 +3.676796e-01 1.458651e-02 9.298381e-01 1.524141e+02 3.258260e-02 9.990610e-01 -2.855634e-02 -2.038880e+01 -9.293815e-01 4.079612e-02 3.668591e-01 4.641031e+02 +3.740929e-01 1.164206e-02 9.273182e-01 1.531854e+02 2.799060e-02 9.993239e-01 -2.383786e-02 -2.042917e+01 -9.269687e-01 3.487376e-02 3.735141e-01 4.644271e+02 +3.815945e-01 7.028949e-03 9.243031e-01 1.539537e+02 3.020924e-02 9.993420e-01 -2.007134e-02 -2.046787e+01 -9.238360e-01 3.558160e-02 3.811310e-01 4.647460e+02 +3.889158e-01 8.280901e-03 9.212361e-01 1.547170e+02 3.353602e-02 9.991696e-01 -2.313925e-02 -2.050819e+01 -9.206627e-01 3.989380e-02 3.883151e-01 4.650650e+02 +3.956064e-01 1.480446e-02 9.183009e-01 1.554665e+02 3.322363e-02 9.989849e-01 -3.041805e-02 -2.054749e+01 -9.178190e-01 4.254285e-02 3.947129e-01 4.653898e+02 +4.030160e-01 2.090326e-02 9.149542e-01 1.562163e+02 3.267122e-02 9.987733e-01 -3.720913e-02 -2.059044e+01 -9.146095e-01 4.488853e-02 4.018387e-01 4.657191e+02 +4.109411e-01 2.138820e-02 9.114110e-01 1.569634e+02 3.163627e-02 9.987881e-01 -3.770300e-02 -2.063939e+01 -9.111128e-01 4.432735e-02 4.097664e-01 4.660557e+02 +4.198345e-01 1.909277e-02 9.073999e-01 1.577066e+02 2.865832e-02 9.990013e-01 -3.427977e-02 -2.069316e+01 -9.071481e-01 4.039637e-02 4.188680e-01 4.664014e+02 +4.285453e-01 1.898644e-02 9.033208e-01 1.584420e+02 2.645953e-02 9.990866e-01 -3.355199e-02 -2.074416e+01 -9.031327e-01 3.827998e-02 4.276515e-01 4.667550e+02 +4.375805e-01 2.038194e-02 8.989482e-01 1.591689e+02 2.289312e-02 9.991664e-01 -3.379787e-02 -2.079448e+01 -8.988877e-01 3.536901e-02 4.367491e-01 4.671119e+02 +4.457623e-01 2.174886e-02 8.948872e-01 1.598906e+02 2.184526e-02 9.991427e-01 -3.516422e-02 -2.084541e+01 -8.948847e-01 3.522391e-02 4.449050e-01 4.674750e+02 +4.541728e-01 2.060763e-02 8.906753e-01 1.606108e+02 2.104242e-02 9.992054e-01 -3.384865e-02 -2.089615e+01 -8.906650e-01 3.411509e-02 4.533783e-01 4.678441e+02 +4.623871e-01 1.980487e-02 8.864570e-01 1.613226e+02 1.899733e-02 9.992997e-01 -3.223521e-02 -2.094383e+01 -8.864746e-01 3.174546e-02 4.616871e-01 4.682182e+02 +4.705003e-01 2.016147e-02 8.821695e-01 1.620266e+02 1.687966e-02 9.993503e-01 -3.184225e-02 -2.099503e+01 -8.822383e-01 2.987251e-02 4.698543e-01 4.685968e+02 +4.791301e-01 2.389928e-02 8.774185e-01 1.627215e+02 1.538565e-02 9.992470e-01 -3.561928e-02 -2.104596e+01 -8.776090e-01 3.056591e-02 4.784016e-01 4.689764e+02 +4.877785e-01 2.936067e-02 8.724736e-01 1.634071e+02 1.567817e-02 9.989784e-01 -4.238313e-02 -2.109630e+01 -8.728266e-01 3.435235e-02 4.868198e-01 4.693527e+02 +4.959820e-01 3.284609e-02 8.677114e-01 1.640863e+02 1.528273e-02 9.987993e-01 -4.654384e-02 -2.114614e+01 -8.681983e-01 3.634589e-02 4.948844e-01 4.697397e+02 +5.038631e-01 2.999627e-02 8.632625e-01 1.647652e+02 1.391212e-02 9.989854e-01 -4.283244e-02 -2.119682e+01 -8.636714e-01 3.359149e-02 5.029346e-01 4.701362e+02 +5.118681e-01 2.131669e-02 8.587996e-01 1.654415e+02 1.382847e-02 9.993581e-01 -3.304771e-02 -2.125193e+01 -8.589527e-01 2.879195e-02 5.112447e-01 4.705344e+02 +5.197791e-01 1.161916e-02 8.542217e-01 1.661130e+02 1.529449e-02 9.996207e-01 -2.290332e-02 -2.130275e+01 -8.541638e-01 2.496954e-02 5.194042e-01 4.709380e+02 +5.277919e-01 5.177362e-03 8.493580e-01 1.667724e+02 1.735689e-02 9.997068e-01 -1.687942e-02 -2.134913e+01 -8.491963e-01 2.365103e-02 5.275473e-01 4.713359e+02 +5.358729e-01 5.677966e-03 8.442796e-01 1.674102e+02 1.917432e-02 9.996376e-01 -1.889292e-02 -2.139105e+01 -8.440809e-01 2.631269e-02 5.355698e-01 4.717323e+02 +5.438114e-01 1.019405e-02 8.391456e-01 1.680300e+02 1.818670e-02 9.995482e-01 -2.392860e-02 -2.143463e+01 -8.390103e-01 2.827393e-02 5.433803e-01 4.721300e+02 +5.511932e-01 1.374534e-02 8.342645e-01 1.686322e+02 1.669008e-02 9.994826e-01 -2.749451e-02 -2.147504e+01 -8.342107e-01 2.907872e-02 5.506786e-01 4.725260e+02 +5.583232e-01 1.592191e-02 8.294707e-01 1.692195e+02 1.549350e-02 9.994413e-01 -2.961333e-02 -2.151842e+01 -8.294788e-01 2.938521e-02 5.577646e-01 4.729195e+02 +5.646148e-01 1.673600e-02 8.251849e-01 1.697904e+02 1.314177e-02 9.994853e-01 -2.926305e-02 -2.156296e+01 -8.252499e-01 2.736673e-02 5.641042e-01 4.733119e+02 +5.697092e-01 1.557953e-02 8.216987e-01 1.703465e+02 1.124439e-02 9.995789e-01 -2.674825e-02 -2.160638e+01 -8.217694e-01 2.447821e-02 5.692941e-01 4.736974e+02 +5.736358e-01 1.675102e-02 8.189392e-01 1.708840e+02 8.766874e-03 9.996080e-01 -2.658739e-02 -2.164716e+01 -8.190635e-01 2.243101e-02 5.732641e-01 4.740754e+02 +5.759752e-01 1.687474e-02 8.172931e-01 1.714059e+02 8.308700e-03 9.996144e-01 -2.649459e-02 -2.168710e+01 -8.174250e-01 2.205086e-02 5.756128e-01 4.744416e+02 +5.772236e-01 1.793641e-02 8.163892e-01 1.719093e+02 6.407015e-03 9.996285e-01 -2.649230e-02 -2.172668e+01 -8.165610e-01 2.052259e-02 5.768942e-01 4.747970e+02 +5.768077e-01 2.160017e-02 8.165943e-01 1.723931e+02 4.761851e-03 9.995444e-01 -2.980305e-02 -2.176205e+01 -8.168660e-01 2.107913e-02 5.764421e-01 4.751370e+02 +5.746037e-01 2.618728e-02 8.180127e-01 1.728551e+02 1.818400e-03 9.994446e-01 -3.327284e-02 -2.179969e+01 -8.184297e-01 2.060616e-02 5.742370e-01 4.754692e+02 +5.703315e-01 2.861970e-02 8.209159e-01 1.733028e+02 5.058412e-04 9.993804e-01 -3.519297e-02 -2.183433e+01 -8.214144e-01 2.048691e-02 5.699636e-01 4.757833e+02 +5.635956e-01 2.934948e-02 8.255293e-01 1.737348e+02 -8.752135e-04 9.993892e-01 -3.493310e-02 -2.186508e+01 -8.260503e-01 1.896562e-02 5.632771e-01 4.760821e+02 +5.544213e-01 2.576928e-02 8.318371e-01 1.741541e+02 -1.430915e-03 9.995485e-01 -3.001107e-02 -2.189308e+01 -8.322349e-01 1.544848e-02 5.542078e-01 4.763598e+02 +5.436271e-01 1.943252e-02 8.391019e-01 1.745565e+02 -1.113972e-03 9.997477e-01 -2.243117e-02 -2.192165e+01 -8.393261e-01 1.125945e-02 5.435116e-01 4.766254e+02 +5.316060e-01 1.239284e-02 8.469011e-01 1.749418e+02 8.682660e-04 9.998844e-01 -1.517649e-02 -2.194546e+01 -8.469913e-01 8.803242e-03 5.315338e-01 4.768610e+02 +5.191476e-01 6.870781e-03 8.546570e-01 1.753061e+02 5.119078e-03 9.999247e-01 -1.114813e-02 -2.196707e+01 -8.546692e-01 1.016257e-02 5.190734e-01 4.770785e+02 +5.056287e-01 4.176889e-03 8.627411e-01 1.756567e+02 1.033369e-02 9.998872e-01 -1.089716e-02 -2.198635e+01 -8.626893e-01 1.442521e-02 5.055285e-01 4.772739e+02 +4.906938e-01 4.687981e-03 8.713195e-01 1.759911e+02 1.304385e-02 9.998339e-01 -1.272523e-02 -2.200100e+01 -8.712344e-01 1.760955e-02 4.905511e-01 4.774531e+02 +4.739069e-01 7.968889e-03 8.805389e-01 1.763286e+02 1.857892e-02 9.996460e-01 -1.904601e-02 -2.201675e+01 -8.803789e-01 2.538549e-02 4.735910e-01 4.776235e+02 +4.549659e-01 1.521192e-02 8.903790e-01 1.766674e+02 1.863215e-02 9.994726e-01 -2.659642e-02 -2.202875e+01 -8.903139e-01 2.869013e-02 4.544424e-01 4.777914e+02 +4.327960e-01 2.143670e-02 9.012370e-01 1.770022e+02 1.666267e-02 9.993562e-01 -3.177238e-02 -2.204077e+01 -9.013378e-01 2.876796e-02 4.321602e-01 4.779380e+02 +4.063014e-01 2.451254e-02 9.134103e-01 1.773495e+02 1.273318e-02 9.993911e-01 -3.248391e-02 -2.205233e+01 -9.136504e-01 2.482887e-02 4.057419e-01 4.780911e+02 +3.765741e-01 2.365574e-02 9.260845e-01 1.776937e+02 1.393197e-02 9.994162e-01 -3.119409e-02 -2.205946e+01 -9.262817e-01 2.464905e-02 3.760246e-01 4.781992e+02 +3.439993e-01 2.166224e-02 9.387200e-01 1.780557e+02 1.633373e-02 9.994445e-01 -2.904914e-02 -2.207282e+01 -9.388278e-01 2.532568e-02 3.434544e-01 4.783098e+02 +3.085024e-01 1.955943e-02 9.510225e-01 1.784188e+02 2.115188e-02 9.994003e-01 -2.741587e-02 -2.208797e+01 -9.509883e-01 2.857377e-02 3.079037e-01 4.784065e+02 +2.719650e-01 1.541738e-02 9.621836e-01 1.787692e+02 2.785668e-02 9.993265e-01 -2.388633e-02 -2.210040e+01 -9.619038e-01 3.329948e-02 2.713524e-01 4.784452e+02 +2.340961e-01 1.336752e-02 9.721216e-01 1.791282e+02 3.228266e-02 9.992472e-01 -2.151449e-02 -2.211690e+01 -9.716773e-01 3.641911e-02 2.334883e-01 4.785046e+02 +1.940697e-01 1.526500e-02 9.808690e-01 1.794833e+02 3.287434e-02 9.992161e-01 -2.205488e-02 -2.213229e+01 -9.804367e-01 3.652560e-02 1.934158e-01 4.785578e+02 +1.515676e-01 1.924280e-02 9.882596e-01 1.798202e+02 2.821096e-02 9.993190e-01 -2.378482e-02 -2.214906e+01 -9.880442e-01 3.148475e-02 1.509215e-01 4.785605e+02 +1.066424e-01 2.383907e-02 9.940116e-01 1.801822e+02 2.461864e-02 9.993427e-01 -2.660814e-02 -2.216095e+01 -9.939926e-01 2.730877e-02 1.059854e-01 4.785915e+02 +5.960510e-02 2.658720e-02 9.978679e-01 1.805320e+02 2.566309e-02 9.992740e-01 -2.815759e-02 -2.217144e+01 -9.978921e-01 2.728670e-02 5.887951e-02 4.785456e+02 +1.050348e-02 2.966864e-02 9.995046e-01 1.809112e+02 2.717231e-02 9.991821e-01 -2.994462e-02 -2.217927e+01 -9.995755e-01 2.747336e-02 9.688726e-03 4.785316e+02 +-3.980096e-02 3.215287e-02 9.986902e-01 1.812983e+02 3.252240e-02 9.989942e-01 -3.086655e-02 -2.218668e+01 -9.986782e-01 3.125128e-02 -4.080661e-02 4.784953e+02 +-9.136758e-02 3.134533e-02 9.953238e-01 1.816648e+02 3.456582e-02 9.990020e-01 -2.828815e-02 -2.219406e+01 -9.952171e-01 3.181955e-02 -9.235986e-02 4.783846e+02 +-1.438537e-01 2.637938e-02 9.892473e-01 1.820686e+02 3.295505e-02 9.992179e-01 -2.185303e-02 -2.221025e+01 -9.890500e-01 2.945705e-02 -1.446105e-01 4.783237e+02 +-1.964730e-01 2.045321e-02 9.802959e-01 1.824750e+02 2.888558e-02 9.994692e-01 -1.506394e-02 -2.222634e+01 -9.800836e-01 2.535675e-02 -1.969595e-01 4.782446e+02 +-2.495938e-01 1.604798e-02 9.682177e-01 1.828536e+02 2.663778e-02 9.995981e-01 -9.701243e-03 -2.223521e+01 -9.679841e-01 2.336979e-02 -2.499210e-01 4.780686e+02 +-3.036409e-01 1.288727e-02 9.526994e-01 1.832622e+02 2.550979e-02 9.996600e-01 -5.392135e-03 -2.224815e+01 -9.524450e-01 2.266588e-02 -3.038664e-01 4.779351e+02 +-3.584045e-01 1.042843e-02 9.335082e-01 1.836426e+02 2.494340e-02 9.996876e-01 -1.591157e-03 -2.225515e+01 -9.332331e-01 2.271458e-02 -3.585526e-01 4.776936e+02 +-4.133503e-01 8.705867e-03 9.105305e-01 1.840625e+02 2.324248e-02 9.997293e-01 9.925735e-04 -2.226385e+01 -9.102754e-01 2.157326e-02 -4.134407e-01 4.775051e+02 +-4.674428e-01 7.849424e-03 8.839885e-01 1.844883e+02 2.040310e-02 9.997900e-01 1.911223e-03 -2.226981e+01 -8.837878e-01 1.892949e-02 -4.675047e-01 4.772852e+02 +-5.199215e-01 7.071037e-03 8.541848e-01 1.848880e+02 1.748907e-02 9.998442e-01 2.368341e-03 -2.227390e+01 -8.540349e-01 1.617024e-02 -5.199642e-01 4.769508e+02 +-5.682859e-01 6.108230e-03 8.228086e-01 1.853240e+02 1.616386e-02 9.998623e-01 3.741208e-03 -2.227835e+01 -8.226724e-01 1.542583e-02 -5.683063e-01 4.766519e+02 +-6.109399e-01 6.343671e-03 7.916516e-01 1.857594e+02 1.717988e-02 9.998386e-01 5.246274e-03 -2.228346e+01 -7.914905e-01 1.680563e-02 -6.109503e-01 4.763068e+02 +-6.470006e-01 7.169332e-03 7.624558e-01 1.861803e+02 1.962940e-02 9.997810e-01 7.256109e-03 -2.228821e+01 -7.622367e-01 1.966125e-02 -6.469996e-01 4.758804e+02 +-6.760413e-01 7.683644e-03 7.368237e-01 1.866263e+02 2.128898e-02 9.997319e-01 9.107522e-03 -2.229195e+01 -7.365561e-01 2.184328e-02 -6.760236e-01 4.754610e+02 +-6.991496e-01 8.143192e-03 7.149291e-01 1.870774e+02 2.252500e-02 9.996896e-01 1.064116e-02 -2.229447e+01 -7.146205e-01 2.354354e-02 -6.991160e-01 4.750069e+02 +-7.176211e-01 8.450355e-03 6.963826e-01 1.875314e+02 2.321978e-02 9.996608e-01 1.179741e-02 -2.229466e+01 -6.960466e-01 2.463592e-02 -7.175738e-01 4.745112e+02 +-7.323401e-01 9.152447e-03 6.808776e-01 1.880019e+02 2.386389e-02 9.996404e-01 1.223027e-02 -2.229351e+01 -6.805208e-01 2.520510e-02 -7.322951e-01 4.740017e+02 +-7.444937e-01 1.015969e-02 6.675522e-01 1.884787e+02 2.459606e-02 9.996228e-01 1.221740e-02 -2.229192e+01 -6.671762e-01 2.551493e-02 -7.444627e-01 4.734645e+02 +-7.545365e-01 1.127238e-02 6.561613e-01 1.889610e+02 2.554549e-02 9.995992e-01 1.220299e-02 -2.228926e+01 -6.557607e-01 2.596956e-02 -7.545220e-01 4.729010e+02 +-7.632839e-01 1.157748e-02 6.459595e-01 1.894552e+02 2.518526e-02 9.996126e-01 1.184361e-02 -2.228709e+01 -6.455722e-01 2.530869e-02 -7.632797e-01 4.723165e+02 +-7.709380e-01 1.184660e-02 6.368001e-01 1.899537e+02 2.587150e-02 9.995843e-01 1.272556e-02 -2.228748e+01 -6.363846e-01 2.628558e-02 -7.709239e-01 4.717035e+02 +-7.769622e-01 1.193999e-02 6.294340e-01 1.904622e+02 2.724266e-02 9.995212e-01 1.466752e-02 -2.227854e+01 -6.289575e-01 2.854356e-02 -7.769154e-01 4.710648e+02 +-7.809281e-01 1.148275e-02 6.245155e-01 1.909835e+02 2.896247e-02 9.994213e-01 1.784021e-02 -2.226966e+01 -6.239491e-01 3.201942e-02 -7.808086e-01 4.704042e+02 +-7.831914e-01 1.151200e-02 6.216742e-01 1.915189e+02 3.075173e-02 9.993222e-01 2.023614e-02 -2.225842e+01 -6.210198e-01 3.496632e-02 -7.830145e-01 4.697252e+02 +-7.847382e-01 1.333012e-02 6.196840e-01 1.920640e+02 3.160829e-02 9.993285e-01 1.853049e-02 -2.225096e+01 -6.190209e-01 3.412873e-02 -7.846326e-01 4.690332e+02 +-7.858391e-01 1.566965e-02 6.182326e-01 1.926283e+02 3.086225e-02 9.994270e-01 1.389781e-02 -2.223395e+01 -6.176605e-01 3.000149e-02 -7.858723e-01 4.683284e+02 +-7.868479e-01 1.661999e-02 6.169233e-01 1.932083e+02 2.940628e-02 9.995115e-01 1.057892e-02 -2.221621e+01 -6.164461e-01 2.646541e-02 -7.869522e-01 4.676084e+02 +-7.879402e-01 1.569703e-02 6.155517e-01 1.938022e+02 2.941310e-02 9.994933e-01 1.216256e-02 -2.219934e+01 -6.150488e-01 2.768865e-02 -7.880026e-01 4.668666e+02 +-7.893553e-01 1.194066e-02 6.138206e-01 1.944076e+02 2.925014e-02 9.994069e-01 1.817333e-02 -2.218783e+01 -6.132395e-01 3.229954e-02 -7.892363e-01 4.661013e+02 +-7.907708e-01 1.065037e-02 6.120198e-01 1.950174e+02 2.966847e-02 9.993403e-01 2.094313e-02 -2.217589e+01 -6.113930e-01 3.471890e-02 -7.905651e-01 4.653209e+02 +-7.918078e-01 1.085745e-02 6.106739e-01 1.956296e+02 3.044271e-02 9.993008e-01 2.170537e-02 -2.215831e+01 -6.100112e-01 3.577704e-02 -7.915846e-01 4.645323e+02 +-7.921312e-01 1.262709e-02 6.102203e-01 1.962448e+02 3.208603e-02 9.992650e-01 2.097362e-02 -2.213909e+01 -6.095069e-01 3.619340e-02 -7.919541e-01 4.637361e+02 +-7.922391e-01 1.468929e-02 6.100341e-01 1.968637e+02 3.399396e-02 9.992201e-01 2.008659e-02 -2.212306e+01 -6.092632e-01 3.665085e-02 -7.921205e-01 4.629331e+02 +-7.919029e-01 1.746930e-02 6.103971e-01 1.974824e+02 3.627109e-02 9.991714e-01 1.846068e-02 -2.211544e+01 -6.095688e-01 3.675883e-02 -7.918804e-01 4.621293e+02 +-7.911274e-01 1.888848e-02 6.113598e-01 1.981054e+02 3.688706e-02 9.991771e-01 1.686309e-02 -2.210943e+01 -6.105382e-01 3.589211e-02 -7.911731e-01 4.613258e+02 +-7.898463e-01 2.023706e-02 6.129710e-01 1.987291e+02 3.841487e-02 9.991254e-01 1.651379e-02 -2.210434e+01 -6.121006e-01 3.659055e-02 -7.899328e-01 4.605227e+02 +-7.884338e-01 2.105112e-02 6.147594e-01 1.993558e+02 3.978259e-02 9.990669e-01 1.681057e-02 -2.209633e+01 -6.138318e-01 3.771074e-02 -7.885355e-01 4.597229e+02 +-7.872558e-01 2.067332e-02 6.162800e-01 1.999852e+02 4.066670e-02 9.990026e-01 1.843704e-02 -2.209257e+01 -6.152842e-01 3.957673e-02 -7.873112e-01 4.589205e+02 +-7.861491e-01 2.024244e-02 6.177054e-01 2.006142e+02 4.137084e-02 9.989453e-01 1.991653e-02 -2.208882e+01 -6.166507e-01 4.121234e-02 -7.861573e-01 4.581214e+02 +-7.850313e-01 2.027045e-02 6.191245e-01 2.012443e+02 4.206962e-02 9.989015e-01 2.063845e-02 -2.208544e+01 -6.180260e-01 4.224815e-02 -7.850216e-01 4.573244e+02 +-7.838649e-01 2.091971e-02 6.205789e-01 2.018766e+02 4.262356e-02 9.988876e-01 2.016610e-02 -2.207920e+01 -6.194667e-01 4.225877e-02 -7.838846e-01 4.565279e+02 +-7.827980e-01 2.113753e-02 6.219169e-01 2.025105e+02 4.338556e-02 9.988447e-01 2.066034e-02 -2.206915e+01 -6.207617e-01 4.315508e-02 -7.828106e-01 4.557302e+02 +-7.816798e-01 2.116361e-02 6.233208e-01 2.031447e+02 4.366163e-02 9.988290e-01 2.084092e-02 -2.206266e+01 -6.221498e-01 4.350612e-02 -7.816884e-01 4.549361e+02 +-7.806489e-01 2.267534e-02 6.245584e-01 2.037796e+02 4.423390e-02 9.988400e-01 1.902480e-02 -2.205633e+01 -6.234025e-01 4.247833e-02 -7.807463e-01 4.541445e+02 +-7.795383e-01 2.573364e-02 6.258257e-01 2.044110e+02 4.560877e-02 9.988354e-01 1.573937e-02 -2.205293e+01 -6.246918e-01 4.081258e-02 -7.798041e-01 4.533583e+02 +-7.787489e-01 2.544459e-02 6.268196e-01 2.050471e+02 4.465558e-02 9.988908e-01 1.493110e-02 -2.204931e+01 -6.257444e-01 3.961856e-02 -7.790214e-01 4.525724e+02 +-7.782935e-01 2.365748e-02 6.274548e-01 2.056848e+02 4.389513e-02 9.988951e-01 1.678519e-02 -2.205096e+01 -6.263645e-01 4.060601e-02 -7.784720e-01 4.517853e+02 +-7.781083e-01 2.038530e-02 6.277993e-01 2.063218e+02 4.226262e-02 9.989074e-01 1.994564e-02 -2.205089e+01 -6.267067e-01 4.205230e-02 -7.781197e-01 4.510010e+02 +-7.780237e-01 1.895226e-02 6.279491e-01 2.069558e+02 4.148207e-02 9.989133e-01 2.124752e-02 -2.205042e+01 -6.268639e-01 4.257969e-02 -7.779643e-01 4.502194e+02 +-7.780656e-01 1.908808e-02 6.278930e-01 2.075876e+02 4.116912e-02 9.989388e-01 2.064753e-02 -2.204869e+01 -6.268326e-01 4.191493e-02 -7.780257e-01 4.494396e+02 +-7.780300e-01 1.849977e-02 6.279548e-01 2.082220e+02 3.934366e-02 9.990390e-01 1.931435e-02 -2.204485e+01 -6.269940e-01 3.973318e-02 -7.780101e-01 4.486651e+02 +-7.782215e-01 1.823176e-02 6.277253e-01 2.088544e+02 3.840544e-02 9.990892e-01 1.859535e-02 -2.204239e+01 -6.268145e-01 3.857936e-02 -7.782128e-01 4.478904e+02 +-7.785812e-01 1.788197e-02 6.272891e-01 2.094864e+02 3.820420e-02 9.990905e-01 1.893761e-02 -2.203971e+01 -6.263799e-01 3.870954e-02 -7.785562e-01 4.471139e+02 +-7.792701e-01 1.752041e-02 6.264433e-01 2.101144e+02 3.798319e-02 9.990918e-01 1.930687e-02 -2.203950e+01 -6.255360e-01 3.883957e-02 -7.792279e-01 4.463379e+02 +-7.796828e-01 1.829890e-02 6.259073e-01 2.107393e+02 3.925895e-02 9.990349e-01 1.969664e-02 -2.203900e+01 -6.249427e-01 3.992958e-02 -7.796487e-01 4.455612e+02 +-7.801946e-01 1.908503e-02 6.252458e-01 2.113594e+02 4.033886e-02 9.989890e-01 1.984247e-02 -2.203932e+01 -6.242349e-01 4.070267e-02 -7.801756e-01 4.447863e+02 +-7.805389e-01 2.023304e-02 6.247797e-01 2.119765e+02 4.090725e-02 9.989869e-01 1.875405e-02 -2.204187e+01 -6.237672e-01 4.019628e-02 -7.805758e-01 4.440145e+02 +-7.806757e-01 2.107192e-02 6.245810e-01 2.125952e+02 4.081055e-02 9.990170e-01 1.730534e-02 -2.204275e+01 -6.236024e-01 3.899934e-02 -7.807682e-01 4.432430e+02 +-7.804618e-01 1.939587e-02 6.249026e-01 2.132149e+02 4.025924e-02 9.990033e-01 1.927381e-02 -2.204257e+01 -6.239059e-01 4.020056e-02 -7.804648e-01 4.424742e+02 +-7.800145e-01 1.540460e-02 6.255718e-01 2.138362e+02 3.900491e-02 9.989499e-01 2.403555e-02 -2.204023e+01 -6.245446e-01 4.314844e-02 -7.797962e-01 4.417066e+02 +-7.794661e-01 1.225732e-02 6.263245e-01 2.144556e+02 3.783862e-02 9.989042e-01 2.754168e-02 -2.203412e+01 -6.253006e-01 4.516705e-02 -7.790757e-01 4.409403e+02 +-7.785806e-01 1.188408e-02 6.274321e-01 2.150695e+02 3.760977e-02 9.989071e-01 2.774984e-02 -2.202541e+01 -6.264166e-01 4.520306e-02 -7.781766e-01 4.401808e+02 +-7.769155e-01 1.290895e-02 6.294726e-01 2.156837e+02 3.863907e-02 9.988828e-01 2.720493e-02 -2.201679e+01 -6.284181e-01 4.545816e-02 -7.765463e-01 4.394205e+02 +-7.749132e-01 1.310981e-02 6.319317e-01 2.163021e+02 3.682207e-02 9.990232e-01 2.442810e-02 -2.200978e+01 -6.309942e-01 4.219868e-02 -7.746390e-01 4.386654e+02 +-7.731737e-01 1.473830e-02 6.340232e-01 2.169249e+02 3.677864e-02 9.990894e-01 2.162601e-02 -2.200300e+01 -6.331270e-01 4.003916e-02 -7.730116e-01 4.379084e+02 +-7.715675e-01 1.539341e-02 6.359612e-01 2.175556e+02 3.722159e-02 9.990869e-01 2.097550e-02 -2.199467e+01 -6.350576e-01 3.985549e-02 -7.714359e-01 4.371433e+02 +-7.704077e-01 1.415664e-02 6.373945e-01 2.181929e+02 3.678418e-02 9.990750e-01 2.227076e-02 -2.198857e+01 -6.364896e-01 4.060359e-02 -7.702157e-01 4.363755e+02 +-7.691183e-01 1.690981e-02 6.388828e-01 2.188302e+02 3.820884e-02 9.990784e-01 1.955427e-02 -2.198274e+01 -6.379633e-01 3.945050e-02 -7.690555e-01 4.356032e+02 +-7.679626e-01 2.189733e-02 6.401203e-01 2.194713e+02 4.126639e-02 9.990305e-01 1.533296e-02 -2.197423e+01 -6.391640e-01 3.819058e-02 -7.681216e-01 4.348241e+02 +-7.672652e-01 2.273704e-02 6.409269e-01 2.201217e+02 4.262868e-02 9.989693e-01 1.559286e-02 -2.196754e+01 -6.399117e-01 3.928572e-02 -7.674435e-01 4.340346e+02 +-7.671918e-01 1.906414e-02 6.411345e-01 2.207841e+02 3.985243e-02 9.990437e-01 1.798147e-02 -2.196566e+01 -6.401786e-01 3.934599e-02 -7.672178e-01 4.332420e+02 +-7.675270e-01 1.832190e-02 6.407547e-01 2.214505e+02 3.682684e-02 9.992008e-01 1.554156e-02 -2.196227e+01 -6.399578e-01 3.552553e-02 -7.675883e-01 4.324471e+02 +-7.681766e-01 1.640919e-02 6.400277e-01 2.221189e+02 3.301799e-02 9.993566e-01 1.400721e-02 -2.195656e+01 -6.393860e-01 3.189243e-02 -7.682241e-01 4.316474e+02 +-7.689608e-01 1.226341e-02 6.391784e-01 2.227897e+02 2.899708e-02 9.994560e-01 1.570903e-02 -2.195169e+01 -6.386380e-01 3.061393e-02 -7.688980e-01 4.308401e+02 +-7.695775e-01 9.357356e-03 6.384849e-01 2.234667e+02 2.790353e-02 9.994303e-01 1.898540e-02 -2.194718e+01 -6.379435e-01 3.242671e-02 -7.694001e-01 4.300171e+02 +-7.690962e-01 9.368566e-03 6.390644e-01 2.241398e+02 2.795555e-02 9.994287e-01 1.899227e-02 -2.194408e+01 -6.385213e-01 3.247227e-02 -7.689187e-01 4.292130e+02 +-7.686141e-01 9.379703e-03 6.396440e-01 2.248136e+02 2.800759e-02 9.994271e-01 1.899914e-02 -2.194098e+01 -6.390993e-01 3.251789e-02 -7.684364e-01 4.284082e+02 +-7.681320e-01 9.390746e-03 6.402228e-01 2.254867e+02 2.805955e-02 9.994255e-01 1.900601e-02 -2.193788e+01 -6.396765e-01 3.256348e-02 -7.679541e-01 4.276041e+02 +-7.676490e-01 9.401715e-03 6.408016e-01 2.261604e+02 2.811153e-02 9.994239e-01 1.901288e-02 -2.193478e+01 -6.402537e-01 3.260912e-02 -7.674710e-01 4.267994e+02 +-7.671660e-01 9.412590e-03 6.413796e-01 2.268335e+02 2.816344e-02 9.994223e-01 1.901974e-02 -2.193169e+01 -6.408300e-01 3.265475e-02 -7.669879e-01 4.259954e+02 +-7.666827e-01 9.423379e-03 6.419571e-01 2.275065e+02 2.821531e-02 9.994208e-01 1.902660e-02 -2.192859e+01 -6.414059e-01 3.270037e-02 -7.665044e-01 4.251915e+02 +-7.661988e-01 9.434090e-03 6.425345e-01 2.281797e+02 2.826717e-02 9.994192e-01 1.903346e-02 -2.192549e+01 -6.419817e-01 3.274604e-02 -7.660203e-01 4.243873e+02 +-7.657144e-01 9.444715e-03 6.431114e-01 2.288529e+02 2.831901e-02 9.994176e-01 1.904032e-02 -2.192240e+01 -6.425570e-01 3.279172e-02 -7.655359e-01 4.235832e+02 +-7.652296e-01 9.455258e-03 6.436880e-01 2.295261e+02 2.837081e-02 9.994160e-01 1.904718e-02 -2.191930e+01 -6.431320e-01 3.283741e-02 -7.650509e-01 4.227791e+02 +-7.647446e-01 9.465712e-03 6.442640e-01 2.301991e+02 2.842257e-02 9.994144e-01 1.905404e-02 -2.191620e+01 -6.437063e-01 3.288310e-02 -7.645657e-01 4.219752e+02 +-7.642595e-01 9.476076e-03 6.448393e-01 2.308716e+02 2.847427e-02 9.994128e-01 1.906089e-02 -2.191311e+01 -6.442800e-01 3.292878e-02 -7.640804e-01 4.211719e+02 +-7.637730e-01 9.486376e-03 6.454153e-01 2.315454e+02 2.852604e-02 9.994111e-01 1.906775e-02 -2.191001e+01 -6.448543e-01 3.297456e-02 -7.635938e-01 4.203671e+02 +-7.632865e-01 9.496583e-03 6.459905e-01 2.322186e+02 2.857774e-02 9.994095e-01 1.907461e-02 -2.190691e+01 -6.454279e-01 3.302032e-02 -7.631071e-01 4.195630e+02 +-7.627997e-01 9.506704e-03 6.465651e-01 2.328916e+02 2.862939e-02 9.994079e-01 1.908146e-02 -2.190382e+01 -6.460008e-01 3.306609e-02 -7.626201e-01 4.187591e+02 +-7.623125e-01 9.516739e-03 6.471392e-01 2.335644e+02 2.868101e-02 9.994063e-01 1.908831e-02 -2.190072e+01 -6.465733e-01 3.311185e-02 -7.621328e-01 4.179553e+02 +-7.618248e-01 9.526693e-03 6.477131e-01 2.342375e+02 2.873261e-02 9.994047e-01 1.909516e-02 -2.189762e+01 -6.471456e-01 3.315765e-02 -7.616450e-01 4.171513e+02 +-7.613487e-01 9.525737e-03 6.482727e-01 2.349109e+02 2.878533e-02 9.994027e-01 1.912099e-02 -2.189458e+01 -6.477033e-01 3.321847e-02 -7.611681e-01 4.163472e+02 +-7.617155e-01 8.773513e-03 6.478523e-01 2.355593e+02 2.887119e-02 9.993747e-01 2.041144e-02 -2.189533e+01 -6.472680e-01 3.425197e-02 -7.614925e-01 4.155883e+02 +-7.623643e-01 8.314187e-03 6.470947e-01 2.361975e+02 2.985455e-02 9.993047e-01 2.233310e-02 -2.189377e+01 -6.464591e-01 3.634467e-02 -7.620824e-01 4.148396e+02 +-7.633639e-01 6.171204e-03 6.459393e-01 2.368230e+02 2.896891e-02 9.992754e-01 2.468820e-02 -2.189260e+01 -6.453188e-01 3.755823e-02 -7.629895e-01 4.141078e+02 +-7.646142e-01 5.854825e-03 6.444617e-01 2.374368e+02 2.950878e-02 9.992280e-01 2.593252e-02 -2.189242e+01 -6.438124e-01 3.884564e-02 -7.641967e-01 4.133890e+02 +-7.688284e-01 5.989919e-03 6.394271e-01 2.380064e+02 2.971273e-02 9.992107e-01 2.636547e-02 -2.188979e+01 -6.387644e-01 3.926964e-02 -7.683995e-01 4.127220e+02 +-7.840339e-01 6.991709e-03 6.206787e-01 2.383941e+02 2.989330e-02 9.992016e-01 2.650522e-02 -2.188674e+01 -6.199978e-01 3.933511e-02 -7.836169e-01 4.121137e+02 +-7.987423e-01 7.976195e-03 6.016205e-01 2.387802e+02 3.004554e-02 9.991934e-01 2.664283e-02 -2.188372e+01 -6.009227e-01 3.935676e-02 -7.983376e-01 4.115074e+02 +-8.129861e-01 8.944538e-03 5.822145e-01 2.391660e+02 3.017003e-02 9.991860e-01 2.677802e-02 -2.188070e+01 -5.815010e-01 3.933558e-02 -8.125941e-01 4.109017e+02 +-8.267811e-01 9.896909e-03 5.624368e-01 2.395523e+02 3.026696e-02 9.991795e-01 2.691032e-02 -2.187770e+01 -5.617090e-01 3.927219e-02 -8.264022e-01 4.102957e+02 +-8.400787e-01 1.082907e-02 5.423565e-01 2.399378e+02 3.033615e-02 9.991739e-01 2.703870e-02 -2.187471e+01 -5.416157e-01 3.916763e-02 -8.397132e-01 4.096908e+02 +-8.529149e-01 1.174266e-02 5.219179e-01 2.403239e+02 3.037785e-02 9.991693e-01 2.716290e-02 -2.187172e+01 -5.211654e-01 3.902237e-02 -8.525631e-01 4.090855e+02 +-8.652410e-01 1.263338e-02 5.011970e-01 2.407094e+02 3.039204e-02 9.991656e-01 2.728185e-02 -2.186876e+01 -5.004342e-01 3.883777e-02 -8.649030e-01 4.084813e+02 +-8.770774e-01 1.350185e-02 4.801593e-01 2.410951e+02 3.037885e-02 9.991629e-01 2.739517e-02 -2.186580e+01 -4.793875e-01 3.861436e-02 -8.767534e-01 4.078770e+02 +-8.883894e-01 1.434471e-02 4.588666e-01 2.414802e+02 3.033850e-02 9.991612e-01 2.750192e-02 -2.186286e+01 -4.580872e-01 3.835373e-02 -8.880794e-01 4.072739e+02 +-8.992007e-01 1.516290e-02 4.372737e-01 2.418657e+02 3.027099e-02 9.991605e-01 2.760173e-02 -2.185993e+01 -4.364881e-01 3.805619e-02 -8.989048e-01 4.066707e+02 +-9.094889e-01 1.595400e-02 4.154220e-01 2.422512e+02 3.017654e-02 9.991608e-01 2.769379e-02 -2.185702e+01 -4.146315e-01 3.772318e-02 -9.092071e-01 4.060680e+02 +-9.192474e-01 1.671672e-02 3.933254e-01 2.426366e+02 3.005534e-02 9.991622e-01 2.777744e-02 -2.185412e+01 -3.925315e-01 3.735586e-02 -9.189796e-01 4.054659e+02 +-9.284824e-01 1.745083e-02 3.709664e-01 2.430226e+02 2.990737e-02 9.991645e-01 2.785213e-02 -2.185123e+01 -3.701704e-01 3.695483e-02 -9.282285e-01 4.048637e+02 +-9.371662e-01 1.815346e-02 3.484107e-01 2.434080e+02 2.973321e-02 9.991679e-01 2.791704e-02 -2.184837e+01 -3.476140e-01 3.652227e-02 -9.369261e-01 4.042625e+02 +-9.437329e-01 1.894385e-02 3.301657e-01 2.437764e+02 2.957872e-02 9.991918e-01 2.721621e-02 -2.183716e+01 -3.293833e-01 3.545071e-02 -9.435305e-01 4.035786e+02 +-9.624580e-01 1.874921e-02 2.707826e-01 2.439660e+02 2.881721e-02 9.990314e-01 3.325284e-02 -2.183791e+01 -2.698968e-01 3.980765e-02 -9.620660e-01 4.031131e+02 +-9.785276e-01 1.868605e-02 2.052671e-01 2.440110e+02 2.730254e-02 9.988573e-01 3.922490e-02 -2.182444e+01 -2.042996e-01 4.398695e-02 -9.779196e-01 4.024840e+02 +-9.907267e-01 2.005063e-02 1.343826e-01 2.440732e+02 2.607779e-02 9.987242e-01 4.324149e-02 -2.181585e+01 -1.333442e-01 4.634489e-02 -9.899855e-01 4.019623e+02 +-9.978940e-01 2.253704e-02 6.082496e-02 2.440922e+02 2.528558e-02 9.986758e-01 4.480260e-02 -2.180229e+01 -5.973469e-02 4.624623e-02 -9.971424e-01 4.014518e+02 +-9.996072e-01 2.459279e-02 -1.344200e-02 2.440014e+02 2.395159e-02 9.986568e-01 4.594403e-02 -2.178347e+01 1.455383e-02 4.560402e-02 -9.988535e-01 4.008392e+02 +-9.957923e-01 2.713017e-02 -8.753093e-02 2.439346e+02 2.301380e-02 9.985966e-01 4.769901e-02 -2.176626e+01 8.870217e-02 4.548388e-02 -9.950191e-01 4.003437e+02 +-9.865740e-01 3.011763e-02 -1.605141e-01 2.437613e+02 2.241888e-02 9.985195e-01 4.956059e-02 -2.174572e+01 1.617691e-01 4.529663e-02 -9.857884e-01 3.997517e+02 +-9.719507e-01 3.403303e-02 -2.327093e-01 2.436168e+02 2.264365e-02 9.984193e-01 5.144072e-02 -2.172614e+01 2.340921e-01 4.472845e-02 -9.711849e-01 3.992840e+02 +-9.523131e-01 3.745213e-02 -3.028156e-01 2.434311e+02 2.217485e-02 9.983090e-01 5.373372e-02 -2.170597e+01 3.043159e-01 4.445643e-02 -9.515331e-01 3.988247e+02 +-9.280494e-01 4.045793e-02 -3.702534e-01 2.431502e+02 2.097283e-02 9.981821e-01 5.650337e-02 -2.168255e+01 3.718663e-01 4.467265e-02 -9.272107e-01 3.982754e+02 +-9.001400e-01 4.540055e-02 -4.332283e-01 2.428901e+02 2.155957e-02 9.979782e-01 5.978865e-02 -2.165624e+01 4.350668e-01 4.447794e-02 -8.992989e-01 3.978287e+02 +-8.701190e-01 4.810416e-02 -4.904885e-01 2.425958e+02 1.900820e-02 9.977602e-01 6.413408e-02 -2.163038e+01 4.924750e-01 4.648097e-02 -8.690844e-01 3.973850e+02 +-8.384504e-01 5.116408e-02 -5.425709e-01 2.422267e+02 1.657849e-02 9.975170e-01 6.844601e-02 -2.160289e+01 5.447257e-01 4.839358e-02 -8.372167e-01 3.968846e+02 +-8.059198e-01 5.234654e-02 -5.897060e-01 2.418736e+02 1.285376e-02 9.973956e-01 7.096948e-02 -2.157671e+01 5.918852e-01 4.961576e-02 -8.044937e-01 3.964620e+02 +-7.732530e-01 5.348638e-02 -6.318379e-01 2.414917e+02 9.717709e-03 9.973187e-01 7.253242e-02 -2.154843e+01 6.340232e-01 4.994589e-02 -7.716994e-01 3.960469e+02 +-7.414349e-01 5.328828e-02 -6.689056e-01 2.410610e+02 5.215145e-03 9.972693e-01 7.366672e-02 -2.151127e+01 6.710045e-01 5.113063e-02 -7.396881e-01 3.955998e+02 +-7.115578e-01 5.440858e-02 -7.005179e-01 2.406315e+02 1.994156e-03 9.971497e-01 7.542214e-02 -2.147767e+01 7.026247e-01 5.227026e-02 -7.096381e-01 3.952015e+02 +-6.841264e-01 5.448534e-02 -7.273256e-01 2.401694e+02 -2.852164e-03 9.969984e-01 7.736982e-02 -2.143638e+01 7.293579e-01 5.500518e-02 -6.819175e-01 3.947841e+02 +-6.574669e-01 5.390279e-02 -7.515530e-01 2.397059e+02 -8.858379e-03 9.968160e-01 7.924293e-02 -2.139698e+01 7.534314e-01 5.875714e-02 -6.548959e-01 3.944034e+02 +-6.289266e-01 5.317776e-02 -7.756439e-01 2.392216e+02 -1.497334e-02 9.966445e-01 8.047052e-02 -2.135682e+01 7.773204e-01 6.222403e-02 -6.260200e-01 3.940338e+02 +-5.990019e-01 5.025460e-02 -7.991691e-01 2.387074e+02 -2.293355e-02 9.965426e-01 7.985556e-02 -2.130633e+01 8.004191e-01 6.616141e-02 -5.957783e-01 3.936438e+02 +-5.695232e-01 4.854605e-02 -8.205405e-01 2.381753e+02 -2.829100e-02 9.965052e-01 7.859306e-02 -2.126486e+01 8.214882e-01 6.797447e-02 -5.661594e-01 3.932945e+02 +-5.394629e-01 4.724548e-02 -8.406829e-01 2.376186e+02 -3.238569e-02 9.965215e-01 7.678523e-02 -2.122262e+01 8.413863e-01 6.864887e-02 -5.360562e-01 3.929576e+02 +-5.101162e-01 4.562127e-02 -8.588948e-01 2.370248e+02 -3.637106e-02 9.965549e-01 7.453483e-02 -2.117762e+01 8.593361e-01 6.926033e-02 -5.066995e-01 3.926107e+02 +-4.819779e-01 4.562383e-02 -8.749948e-01 2.364194e+02 -3.655882e-02 9.967265e-01 7.210904e-02 -2.113375e+01 8.754203e-01 6.674373e-02 -4.787321e-01 3.923006e+02 +-4.543489e-01 4.580050e-02 -8.896457e-01 2.357934e+02 -3.648832e-02 9.968825e-01 6.995613e-02 -2.108324e+01 8.900762e-01 6.424616e-02 -4.512613e-01 3.919948e+02 +-4.272227e-01 4.664500e-02 -9.029425e-01 2.351318e+02 -3.568391e-02 9.970204e-01 6.838864e-02 -2.103338e+01 9.034420e-01 6.143768e-02 -4.242852e-01 3.916856e+02 +-4.008766e-01 4.698284e-02 -9.149266e-01 2.344594e+02 -3.555414e-02 9.971339e-01 6.678242e-02 -2.098293e+01 9.154419e-01 5.930093e-02 -3.980571e-01 3.914036e+02 +-3.750441e-01 4.689882e-02 -9.258199e-01 2.337646e+02 -3.308713e-02 9.974058e-01 6.392852e-02 -2.093953e+01 9.264163e-01 5.460873e-02 -3.725194e-01 3.911388e+02 +-3.507353e-01 4.774460e-02 -9.352568e-01 2.330421e+02 -2.879977e-02 9.976772e-01 6.173150e-02 -2.089645e+01 9.360316e-01 4.858659e-02 -3.485456e-01 3.908764e+02 +-3.270873e-01 5.054483e-02 -9.436415e-01 2.322968e+02 -2.169049e-02 9.979039e-01 6.096974e-02 -2.084930e+01 9.447451e-01 4.041047e-02 -3.253053e-01 3.906420e+02 +-3.052920e-01 5.451203e-02 -9.506973e-01 2.315269e+02 -1.673961e-02 9.978987e-01 6.259402e-02 -2.080401e+01 9.521116e-01 3.502376e-02 -3.037379e-01 3.904075e+02 +-2.848599e-01 5.982027e-02 -9.567008e-01 2.307368e+02 -1.221489e-02 9.977433e-01 6.602359e-02 -2.075455e+01 9.584913e-01 3.049347e-02 -2.834863e-01 3.901934e+02 +-2.666036e-01 6.239913e-02 -9.617842e-01 2.299283e+02 -1.110844e-02 9.976368e-01 6.780442e-02 -2.070711e+01 9.637422e-01 2.876082e-02 -2.652804e-01 3.899829e+02 +-2.501618e-01 6.072214e-02 -9.662981e-01 2.291019e+02 -1.245417e-02 9.977470e-01 6.592262e-02 -2.065620e+01 9.681239e-01 2.852576e-02 -2.488420e-01 3.897734e+02 +-2.333728e-01 5.670424e-02 -9.707326e-01 2.282594e+02 -1.438140e-02 9.979878e-01 6.175375e-02 -2.060504e+01 9.722809e-01 2.837214e-02 -2.320877e-01 3.895766e+02 +-2.160500e-01 5.385987e-02 -9.748957e-01 2.273933e+02 -1.747153e-02 9.981042e-01 5.901400e-02 -2.055167e+01 9.762259e-01 2.978289e-02 -2.146993e-01 3.893896e+02 +-1.981696e-01 5.435629e-02 -9.786594e-01 2.265029e+02 -2.127404e-02 9.979874e-01 5.973761e-02 -2.049991e+01 9.799368e-01 3.265822e-02 -1.966144e-01 3.892043e+02 +-1.815398e-01 5.739340e-02 -9.817074e-01 2.255961e+02 -1.989006e-02 9.978769e-01 6.201685e-02 -2.044670e+01 9.831824e-01 3.078474e-02 -1.800128e-01 3.890437e+02 +-1.673434e-01 5.757708e-02 -9.842160e-01 2.246689e+02 -1.643411e-02 9.979916e-01 6.117721e-02 -2.039489e+01 9.857616e-01 2.641232e-02 -1.660611e-01 3.888983e+02 +-1.554729e-01 5.440413e-02 -9.863409e-01 2.237259e+02 -1.144380e-02 9.983161e-01 5.686850e-02 -2.034260e+01 9.877738e-01 2.012900e-02 -1.545885e-01 3.887590e+02 +-1.457322e-01 4.843260e-02 -9.881379e-01 2.227697e+02 -8.901339e-03 9.986963e-01 5.026291e-02 -2.029340e+01 9.892840e-01 1.612067e-02 -1.451110e-01 3.886276e+02 +-1.365262e-01 4.327345e-02 -9.896909e-01 2.217934e+02 -6.684810e-03 9.989825e-01 4.460189e-02 -2.024699e+01 9.906139e-01 1.270523e-02 -1.360980e-01 3.884990e+02 +-1.289428e-01 4.162493e-02 -9.907781e-01 2.207978e+02 -5.257496e-03 9.990759e-01 4.265778e-02 -2.020494e+01 9.916381e-01 1.070943e-02 -1.286048e-01 3.883725e+02 +-1.246541e-01 4.407802e-02 -9.912207e-01 2.197826e+02 -6.753954e-03 9.989519e-01 4.527119e-02 -2.016738e+01 9.921772e-01 1.233790e-02 -1.242257e-01 3.882427e+02 +-1.214762e-01 4.616605e-02 -9.915202e-01 2.187530e+02 -6.618718e-03 9.988579e-01 4.731860e-02 -2.013310e+01 9.925722e-01 1.231068e-02 -1.210319e-01 3.881101e+02 +-1.177511e-01 4.829812e-02 -9.918680e-01 2.177107e+02 -4.636305e-03 9.987789e-01 4.918505e-02 -2.009684e+01 9.930323e-01 1.039020e-02 -1.173833e-01 3.879834e+02 +-1.144637e-01 4.700551e-02 -9.923148e-01 2.166597e+02 -5.793850e-03 9.988313e-01 4.798253e-02 -2.006123e+01 9.934105e-01 1.124158e-02 -1.140575e-01 3.878539e+02 +-1.121329e-01 4.716083e-02 -9.925735e-01 2.155989e+02 -6.739565e-03 9.988140e-01 4.821873e-02 -2.002189e+01 9.936703e-01 1.209642e-02 -1.116821e-01 3.877291e+02 +-1.097634e-01 4.788140e-02 -9.928038e-01 2.145306e+02 -6.247789e-03 9.987860e-01 4.886067e-02 -1.998678e+01 9.939381e-01 1.156594e-02 -1.093310e-01 3.876072e+02 +-1.066943e-01 4.700951e-02 -9.931800e-01 2.134542e+02 -6.191507e-03 9.988309e-01 4.794212e-02 -1.995111e+01 9.942726e-01 1.126444e-02 -1.062785e-01 3.874877e+02 +-1.039731e-01 4.479021e-02 -9.935711e-01 2.123743e+02 -9.951874e-03 9.988886e-01 4.607135e-02 -1.991528e+01 9.945303e-01 1.467808e-02 -1.034118e-01 3.873646e+02 +-1.013287e-01 4.531846e-02 -9.938203e-01 2.112818e+02 -1.196318e-02 9.988342e-01 4.676685e-02 -1.987803e+01 9.947810e-01 1.662808e-02 -1.006684e-01 3.872455e+02 +-9.938475e-02 4.649215e-02 -9.939624e-01 2.101870e+02 -1.441870e-02 9.987357e-01 4.815713e-02 -1.984214e+01 9.949446e-01 1.911773e-02 -9.858874e-02 3.871296e+02 +-9.671908e-02 4.593819e-02 -9.942511e-01 2.090903e+02 -1.499536e-02 9.987537e-01 4.760496e-02 -1.981323e+01 9.951987e-01 1.951346e-02 -9.590967e-02 3.870168e+02 +-9.385587e-02 4.602579e-02 -9.945214e-01 2.079899e+02 -1.732265e-02 9.987041e-01 4.785417e-02 -1.977988e+01 9.954350e-01 2.171914e-02 -9.293694e-02 3.869066e+02 +-9.059291e-02 4.693806e-02 -9.947813e-01 2.068819e+02 -1.946938e-02 9.986143e-01 4.889197e-02 -1.975329e+01 9.956976e-01 2.379704e-02 -8.955351e-02 3.868005e+02 +-8.808000e-02 4.692122e-02 -9.950077e-01 2.057692e+02 -2.153996e-02 9.985667e-01 4.899581e-02 -1.972236e+01 9.958804e-01 2.574798e-02 -8.694306e-02 3.866974e+02 +-8.602468e-02 4.645460e-02 -9.952094e-01 2.046580e+02 -2.132346e-02 9.985977e-01 4.845594e-02 -1.969466e+01 9.960647e-01 2.538971e-02 -8.491347e-02 3.865955e+02 +-8.390930e-02 4.737762e-02 -9.953465e-01 2.035387e+02 -2.239941e-02 9.985270e-01 4.941733e-02 -1.966376e+01 9.962216e-01 2.644175e-02 -8.272446e-02 3.864958e+02 +-8.159186e-02 5.001025e-02 -9.954104e-01 2.024126e+02 -2.421315e-02 9.983461e-01 5.214246e-02 -1.963786e+01 9.963716e-01 2.835642e-02 -8.024600e-02 3.863990e+02 +-7.896098e-02 5.071788e-02 -9.955867e-01 2.012868e+02 -2.581232e-02 9.982660e-01 5.290159e-02 -1.960862e+01 9.965434e-01 2.987557e-02 -7.751492e-02 3.863043e+02 +-7.642447e-02 4.888486e-02 -9.958763e-01 2.001657e+02 -2.802534e-02 9.982974e-01 5.115441e-02 -1.958025e+01 9.966814e-01 3.181922e-02 -7.492433e-02 3.862092e+02 +-7.355643e-02 4.781437e-02 -9.961442e-01 1.990457e+02 -2.922204e-02 9.983178e-01 5.007650e-02 -1.955141e+01 9.968628e-01 3.279281e-02 -7.203546e-02 3.861196e+02 +-7.107075e-02 4.901074e-02 -9.962665e-01 1.979189e+02 -3.112190e-02 9.981969e-01 5.132586e-02 -1.952670e+01 9.969856e-01 3.465347e-02 -6.941729e-02 3.860312e+02 +-6.842371e-02 4.884265e-02 -9.964601e-01 1.967958e+02 -3.151278e-02 9.981966e-01 5.109166e-02 -1.949713e+01 9.971585e-01 3.489710e-02 -6.676114e-02 3.859469e+02 +-6.650492e-02 4.895539e-02 -9.965844e-01 1.956736e+02 -3.068299e-02 9.982229e-01 5.108346e-02 -1.946311e+01 9.973142e-01 3.397549e-02 -6.488464e-02 3.858666e+02 +-6.472774e-02 5.026023e-02 -9.966365e-01 1.945558e+02 -3.037359e-02 9.981688e-01 5.231017e-02 -1.943016e+01 9.974406e-01 3.365734e-02 -6.308263e-02 3.857863e+02 +-6.312435e-02 5.215828e-02 -9.966418e-01 1.934288e+02 -3.193109e-02 9.980165e-01 5.425266e-02 -1.939507e+01 9.974947e-01 3.524852e-02 -6.133367e-02 3.857071e+02 +-6.151419e-02 5.337228e-02 -9.966782e-01 1.923184e+02 -3.349436e-02 9.978964e-01 5.550477e-02 -1.935928e+01 9.975440e-01 3.679743e-02 -5.959712e-02 3.856280e+02 +-5.989451e-02 5.392218e-02 -9.967473e-01 1.912072e+02 -3.433238e-02 9.978378e-01 5.604421e-02 -1.932368e+01 9.976141e-01 3.757744e-02 -5.791372e-02 3.855546e+02 +-5.837261e-02 5.546424e-02 -9.967529e-01 1.900993e+02 -3.351825e-02 9.977835e-01 5.748452e-02 -1.928759e+01 9.977320e-01 3.676494e-02 -5.638416e-02 3.854845e+02 +-5.698067e-02 5.768414e-02 -9.967075e-01 1.889927e+02 -3.279731e-02 9.976825e-01 5.961556e-02 -1.924749e+01 9.978364e-01 3.608626e-02 -5.495673e-02 3.854196e+02 +-5.558996e-02 5.915353e-02 -9.966999e-01 1.878862e+02 -3.220621e-02 9.976178e-01 6.100429e-02 -1.920522e+01 9.979341e-01 3.549115e-02 -5.355242e-02 3.853584e+02 +-5.417844e-02 5.992754e-02 -9.967314e-01 1.867861e+02 -3.130691e-02 9.976047e-01 6.168178e-02 -1.916163e+01 9.980403e-01 3.454640e-02 -5.217252e-02 3.853007e+02 +-5.276412e-02 5.899035e-02 -9.968632e-01 1.856895e+02 -3.127502e-02 9.976664e-01 6.069329e-02 -1.911846e+01 9.981171e-01 3.437935e-02 -5.079606e-02 3.852438e+02 +-5.156647e-02 5.689089e-02 -9.970478e-01 1.845992e+02 -3.185524e-02 9.977743e-01 5.857988e-02 -1.907700e+01 9.981613e-01 3.478196e-02 -4.963943e-02 3.851879e+02 +-5.093102e-02 5.525206e-02 -9.971727e-01 1.835108e+02 -3.186297e-02 9.978702e-01 5.691814e-02 -1.903621e+01 9.981937e-01 3.467178e-02 -4.906205e-02 3.851337e+02 +-5.075078e-02 5.567486e-02 -9.971583e-01 1.824291e+02 -3.073477e-02 9.978849e-01 5.727970e-02 -1.899790e+01 9.982383e-01 3.355442e-02 -4.893229e-02 3.850824e+02 +-5.098593e-02 5.749524e-02 -9.970430e-01 1.813482e+02 -2.959924e-02 9.978159e-01 5.905344e-02 -1.896222e+01 9.982606e-01 3.252261e-02 -4.917275e-02 3.850289e+02 +-5.092165e-02 5.921157e-02 -9.969459e-01 1.802696e+02 -2.769353e-02 9.977733e-01 6.067525e-02 -1.892984e+01 9.983186e-01 3.069864e-02 -4.916848e-02 3.849816e+02 +-5.099047e-02 6.060590e-02 -9.968585e-01 1.791914e+02 -2.701619e-02 9.977080e-01 6.203946e-02 -1.889174e+01 9.983336e-01 3.009474e-02 -4.923625e-02 3.849305e+02 +-5.126766e-02 6.004812e-02 -9.968781e-01 1.781253e+02 -2.805629e-02 9.977101e-01 6.154113e-02 -1.885706e+01 9.982907e-01 3.112377e-02 -4.946553e-02 3.848803e+02 +-5.155861e-02 5.939409e-02 -9.969023e-01 1.770607e+02 -2.832901e-02 9.977412e-01 6.090922e-02 -1.882032e+01 9.982680e-01 3.138165e-02 -4.975957e-02 3.848295e+02 +-5.150853e-02 5.949000e-02 -9.968991e-01 1.759984e+02 -2.917855e-02 9.977084e-01 6.104592e-02 -1.878602e+01 9.982462e-01 3.223245e-02 -4.965466e-02 3.847805e+02 +-5.154152e-02 5.952774e-02 -9.968952e-01 1.749402e+02 -2.982764e-02 9.976848e-01 6.111705e-02 -1.875404e+01 9.982253e-01 3.288509e-02 -4.964662e-02 3.847322e+02 +-5.157104e-02 5.914562e-02 -9.969164e-01 1.738847e+02 -3.006510e-02 9.977003e-01 6.074742e-02 -1.872164e+01 9.982166e-01 3.310520e-02 -4.967422e-02 3.846868e+02 +-5.120311e-02 5.916123e-02 -9.969344e-01 1.728338e+02 -2.833324e-02 9.977559e-01 6.066520e-02 -1.868858e+01 9.982862e-01 3.135263e-02 -4.941198e-02 3.846469e+02 +-5.092903e-02 5.916370e-02 -9.969483e-01 1.717870e+02 -2.765266e-02 9.977774e-01 6.062555e-02 -1.865210e+01 9.983193e-01 3.065587e-02 -4.917980e-02 3.846052e+02 +-5.045208e-02 5.883948e-02 -9.969918e-01 1.707419e+02 -2.740491e-02 9.978056e-01 6.027433e-02 -1.861307e+01 9.983504e-01 3.036344e-02 -4.872887e-02 3.845638e+02 +-4.926507e-02 5.870300e-02 -9.970592e-01 1.697031e+02 -2.796250e-02 9.977989e-01 6.012821e-02 -1.857224e+01 9.983942e-01 3.084249e-02 -4.751515e-02 3.845188e+02 +-4.735143e-02 5.769289e-02 -9.972108e-01 1.686675e+02 -2.786846e-02 9.978657e-01 5.905409e-02 -1.853010e+01 9.984894e-01 3.058703e-02 -4.564255e-02 3.844792e+02 +-4.525910e-02 5.478157e-02 -9.974721e-01 1.676400e+02 -2.858023e-02 9.980155e-01 5.610822e-02 -1.848970e+01 9.985663e-01 3.104739e-02 -4.360362e-02 3.844394e+02 +-4.273371e-02 5.154657e-02 -9.977559e-01 1.666211e+02 -2.799579e-02 9.982142e-01 5.276931e-02 -1.845106e+01 9.986941e-01 3.018799e-02 -4.121431e-02 3.844059e+02 +-3.989209e-02 5.026464e-02 -9.979389e-01 1.656100e+02 -2.573075e-02 9.983510e-01 5.131398e-02 -1.841574e+01 9.988726e-01 2.772474e-02 -3.853296e-02 3.843758e+02 +-3.713536e-02 5.113820e-02 -9.980010e-01 1.646091e+02 -2.632601e-02 9.982931e-01 5.213276e-02 -1.838192e+01 9.989634e-01 2.820935e-02 -3.572570e-02 3.843467e+02 +-3.404238e-02 5.330850e-02 -9.979977e-01 1.636235e+02 -2.451048e-02 9.982315e-01 5.415707e-02 -1.834801e+01 9.991197e-01 2.630504e-02 -3.267556e-02 3.843215e+02 +-3.104022e-02 5.529644e-02 -9.979874e-01 1.626519e+02 -2.259026e-02 9.981746e-01 5.600944e-02 -1.831433e+01 9.992628e-01 2.428334e-02 -2.973440e-02 3.843009e+02 +-2.779158e-02 5.599001e-02 -9.980445e-01 1.616951e+02 -2.225938e-02 9.981479e-01 5.661565e-02 -1.827983e+01 9.993658e-01 2.378929e-02 -2.649381e-02 3.842813e+02 +-2.411791e-02 5.616816e-02 -9.981300e-01 1.607589e+02 -2.269030e-02 9.981324e-01 5.671657e-02 -1.824832e+01 9.994515e-01 2.401575e-02 -2.279840e-02 3.842636e+02 +-2.023153e-02 5.555837e-02 -9.982505e-01 1.598416e+02 -2.178849e-02 9.981932e-01 5.599678e-02 -1.821543e+01 9.995578e-01 2.288327e-02 -1.898444e-02 3.842531e+02 +-1.620778e-02 5.510218e-02 -9.983492e-01 1.589475e+02 -2.072563e-02 9.982473e-01 5.543303e-02 -1.818488e+01 9.996538e-01 2.158986e-02 -1.503734e-02 3.842468e+02 +-1.320930e-02 5.596080e-02 -9.983456e-01 1.580686e+02 -1.969749e-02 9.982244e-01 5.621463e-02 -1.815401e+01 9.997187e-01 2.040746e-02 -1.208356e-02 3.842443e+02 +-1.190783e-02 5.467642e-02 -9.984331e-01 1.572128e+02 -1.709496e-02 9.983468e-01 5.487559e-02 -1.812740e+01 9.997829e-01 1.772163e-02 -1.095345e-02 3.842441e+02 +-1.285885e-02 5.380137e-02 -9.984689e-01 1.563762e+02 -1.342962e-02 9.984520e-01 5.397343e-02 -1.810128e+01 9.998271e-01 1.410310e-02 -1.211642e-02 3.842466e+02 +-1.540844e-02 5.268107e-02 -9.984925e-01 1.555590e+02 -1.031626e-02 9.985495e-01 5.284328e-02 -1.807348e+01 9.998280e-01 1.111495e-02 -1.484262e-02 3.842444e+02 +-1.884824e-02 5.378475e-02 -9.983747e-01 1.547575e+02 -8.261533e-03 9.985095e-01 5.394799e-02 -1.804594e+01 9.997882e-01 9.264933e-03 -1.837580e-02 3.842381e+02 +-2.441083e-02 5.708137e-02 -9.980711e-01 1.539750e+02 -5.194494e-03 9.983478e-01 5.722425e-02 -1.802334e+01 9.996885e-01 6.581370e-03 -2.407399e-02 3.842242e+02 +-3.245852e-02 5.889311e-02 -9.977365e-01 1.532125e+02 -1.836339e-03 9.982572e-01 5.898360e-02 -1.800096e+01 9.994714e-01 3.746707e-03 -3.229380e-02 3.842049e+02 +-4.280651e-02 5.867571e-02 -9.973589e-01 1.524655e+02 5.813138e-04 9.982752e-01 5.870467e-02 -1.797357e+01 9.990832e-01 1.933168e-03 -4.276678e-02 3.841773e+02 +-5.515255e-02 5.778085e-02 -9.968047e-01 1.517415e+02 2.488184e-03 9.983290e-01 5.773155e-02 -1.794639e+01 9.984748e-01 7.038134e-04 -5.520415e-02 3.841407e+02 +-6.890922e-02 5.806518e-02 -9.959317e-01 1.510337e+02 4.117129e-03 9.983128e-01 5.791914e-02 -1.791524e+01 9.976144e-01 -1.092116e-04 -6.903201e-02 3.840914e+02 +-8.442122e-02 6.017112e-02 -9.946118e-01 1.503495e+02 5.575170e-03 9.981879e-01 5.991427e-02 -1.788945e+01 9.964145e-01 -4.870887e-04 -8.460371e-02 3.840333e+02 +-1.024382e-01 6.266042e-02 -9.927639e-01 1.496934e+02 7.471485e-03 9.980343e-01 6.222214e-02 -1.786430e+01 9.947113e-01 -1.043492e-03 -1.027050e-01 3.839659e+02 +-1.250101e-01 6.579974e-02 -9.899712e-01 1.490594e+02 1.078838e-02 9.978295e-01 6.495975e-02 -1.783684e+01 9.920968e-01 -2.559555e-03 -1.254486e-01 3.838727e+02 +-1.549964e-01 6.839529e-02 -9.855447e-01 1.484628e+02 1.623012e-02 9.976422e-01 6.668235e-02 -1.781261e+01 9.877817e-01 -5.659976e-03 -1.557410e-01 3.837747e+02 +-1.918771e-01 6.989948e-02 -9.789266e-01 1.479058e+02 2.018107e-02 9.975305e-01 6.727224e-02 -1.777489e+01 9.812114e-01 -6.847782e-03 -1.928138e-01 3.836702e+02 +-2.344818e-01 7.101521e-02 -9.695232e-01 1.473608e+02 2.332577e-02 9.974520e-01 6.741954e-02 -1.773562e+01 9.718406e-01 -6.806216e-03 -2.355408e-01 3.835007e+02 +-2.835990e-01 7.147498e-02 -9.562756e-01 1.468618e+02 2.565189e-02 9.974270e-01 6.694329e-02 -1.770318e+01 9.585998e-01 -5.545223e-03 -2.847027e-01 3.833429e+02 +-3.376645e-01 7.181509e-02 -9.385230e-01 1.463906e+02 2.690063e-02 9.974142e-01 6.664303e-02 -1.767220e+01 9.408820e-01 -2.743869e-03 -3.387232e-01 3.831653e+02 +-3.947221e-01 7.207660e-02 -9.159692e-01 1.459170e+02 2.922589e-02 9.973988e-01 6.588979e-02 -1.764045e+01 9.183356e-01 -7.618544e-04 -3.958018e-01 3.828831e+02 +-4.543529e-01 7.272694e-02 -8.878481e-01 1.454930e+02 3.239254e-02 9.973515e-01 6.512003e-02 -1.761047e+01 8.902326e-01 8.278251e-04 -4.555053e-01 3.826521e+02 +-5.146912e-01 7.616227e-02 -8.539861e-01 1.450927e+02 3.957449e-02 9.970954e-01 6.507414e-02 -1.758068e+01 8.564618e-01 -3.029698e-04 -5.162103e-01 3.824018e+02 +-5.751265e-01 7.941620e-02 -8.142006e-01 1.446826e+02 4.349595e-02 9.968375e-01 6.650620e-02 -1.755212e+01 8.169073e-01 2.835054e-03 -5.767619e-01 3.820190e+02 +-6.335659e-01 8.065268e-02 -7.694735e-01 1.443429e+02 4.651340e-02 9.967234e-01 6.617398e-02 -1.752752e+01 7.722893e-01 6.134748e-03 -6.352413e-01 3.817103e+02 +-6.889992e-01 7.708669e-02 -7.206510e-01 1.440396e+02 4.520039e-02 9.969623e-01 6.342808e-02 -1.750561e+01 7.233513e-01 1.112819e-02 -6.903905e-01 3.813743e+02 +-7.404085e-01 7.664909e-02 -6.677726e-01 1.437264e+02 4.754980e-02 9.969607e-01 6.171243e-02 -1.747868e+01 6.704732e-01 1.393996e-02 -7.418027e-01 3.809254e+02 +-7.866919e-01 7.879388e-02 -6.122969e-01 1.434760e+02 5.060039e-02 9.967141e-01 6.325049e-02 -1.745602e+01 6.152687e-01 1.877618e-02 -7.880938e-01 3.805488e+02 +-8.285889e-01 8.043202e-02 -5.540497e-01 1.432571e+02 5.244700e-02 9.964259e-01 6.621708e-02 -1.742990e+01 5.573955e-01 2.580849e-02 -8.298458e-01 3.801573e+02 +-8.661553e-01 7.840396e-02 -4.935868e-01 1.430401e+02 5.041830e-02 9.962874e-01 6.978068e-02 -1.740436e+01 4.972253e-01 3.555509e-02 -8.668925e-01 3.796496e+02 +-8.980742e-01 7.334259e-02 -4.336862e-01 1.428859e+02 4.702899e-02 9.963591e-01 7.111143e-02 -1.738212e+01 4.373226e-01 4.346751e-02 -8.982535e-01 3.792150e+02 +-9.239148e-01 7.083455e-02 -3.759841e-01 1.427496e+02 4.740688e-02 9.963339e-01 7.121305e-02 -1.736260e+01 3.796500e-01 4.797055e-02 -9.238856e-01 3.787600e+02 +-9.445736e-01 6.802167e-02 -3.211757e-01 1.426110e+02 4.831214e-02 9.964494e-01 6.895231e-02 -1.734196e+01 3.247256e-01 4.961384e-02 -9.445060e-01 3.782309e+02 +-9.603305e-01 6.551412e-02 -2.710594e-01 1.425129e+02 4.990083e-02 9.966947e-01 6.410516e-02 -1.731765e+01 2.743633e-01 4.803604e-02 -9.604255e-01 3.777433e+02 +-9.723990e-01 5.945456e-02 -2.256222e-01 1.424206e+02 4.759487e-02 9.972017e-01 5.764946e-02 -1.729460e+01 2.284183e-01 4.531981e-02 -9.725076e-01 3.772050e+02 +-9.809463e-01 5.283752e-02 -1.869563e-01 1.423618e+02 4.390286e-02 9.977016e-01 5.161496e-02 -1.726700e+01 1.892538e-01 4.242358e-02 -9.810113e-01 3.766825e+02 +-9.870624e-01 4.211654e-02 -1.547067e-01 1.423178e+02 3.490681e-02 9.981872e-01 4.902831e-02 -1.724139e+01 1.564912e-01 4.299368e-02 -9.867431e-01 3.761366e+02 +-9.911395e-01 3.683883e-02 -1.276147e-01 1.422723e+02 3.061950e-02 9.982616e-01 5.035952e-02 -1.721971e+01 1.292481e-01 4.600580e-02 -9.905444e-01 3.755632e+02 +-9.939612e-01 3.711148e-02 -1.032664e-01 1.422304e+02 3.178696e-02 9.981023e-01 5.273794e-02 -1.719960e+01 1.050276e-01 4.913693e-02 -9.932546e-01 3.749889e+02 +-9.957754e-01 4.117005e-02 -8.207624e-02 1.421881e+02 3.664793e-02 9.977656e-01 5.586228e-02 -1.717908e+01 8.419270e-02 5.261835e-02 -9.950592e-01 3.743958e+02 +-9.970623e-01 4.171859e-02 -6.423749e-02 1.421618e+02 3.809798e-02 9.976702e-01 5.659243e-02 -1.715520e+01 6.644878e-02 5.397885e-02 -9.963286e-01 3.737981e+02 +-9.980184e-01 3.879603e-02 -4.953997e-02 1.421497e+02 3.612157e-02 9.978989e-01 5.378563e-02 -1.712791e+01 5.152255e-02 5.188958e-02 -9.973228e-01 3.731902e+02 +-9.987804e-01 3.322492e-02 -3.652141e-02 1.421472e+02 3.137437e-02 9.982500e-01 5.012624e-02 -1.710188e+01 3.812293e-02 4.891926e-02 -9.980749e-01 3.725674e+02 +-9.990586e-01 3.414510e-02 -2.675855e-02 1.421404e+02 3.283013e-02 9.983014e-01 4.813004e-02 -1.707609e+01 2.835650e-02 4.720624e-02 -9.984825e-01 3.719316e+02 +-9.990684e-01 3.897403e-02 -1.853204e-02 1.421298e+02 3.806706e-02 9.981690e-01 4.700448e-02 -1.704792e+01 2.033006e-02 4.625523e-02 -9.987227e-01 3.712791e+02 +-9.990835e-01 4.094679e-02 -1.247046e-02 1.421229e+02 4.033068e-02 9.981181e-01 4.619161e-02 -1.702105e+01 1.433839e-02 4.564633e-02 -9.988547e-01 3.706074e+02 +-9.991302e-01 4.057308e-02 -9.629084e-03 1.421210e+02 4.008970e-02 9.981378e-01 4.597569e-02 -1.699702e+01 1.147653e-02 4.554967e-02 -9.988961e-01 3.699188e+02 +-9.991373e-01 4.078289e-02 -7.843902e-03 1.421190e+02 4.039230e-02 9.981800e-01 4.477732e-02 -1.697384e+01 9.655775e-03 4.442185e-02 -9.989661e-01 3.692150e+02 +-9.990820e-01 4.267866e-02 -3.706634e-03 1.421176e+02 4.248378e-02 9.981987e-01 4.236097e-02 -1.694631e+01 5.507866e-03 4.216460e-02 -9.990954e-01 3.684949e+02 +-9.988172e-01 4.860028e-02 1.523622e-03 1.421154e+02 4.862216e-02 9.980005e-01 4.038400e-02 -1.691758e+01 4.420983e-04 4.041031e-02 -9.991830e-01 3.677599e+02 +-9.985410e-01 5.350619e-02 7.281598e-03 1.421175e+02 5.374853e-02 9.978073e-01 3.862152e-02 -1.689146e+01 -5.199141e-03 3.895654e-02 -9.992273e-01 3.670083e+02 +-9.984622e-01 5.375160e-02 1.356482e-02 1.421308e+02 5.425099e-02 9.977412e-01 3.961442e-02 -1.686816e+01 -1.140484e-02 4.028940e-02 -9.991229e-01 3.662338e+02 +-9.984225e-01 5.272142e-02 1.931344e-02 1.421534e+02 5.344621e-02 9.978025e-01 3.916050e-02 -1.684168e+01 -1.720640e-02 4.013095e-02 -9.990462e-01 3.654425e+02 +-9.982550e-01 5.320278e-02 2.562047e-02 1.421767e+02 5.414936e-02 9.978175e-01 3.778964e-02 -1.681628e+01 -2.355404e-02 3.911102e-02 -9.989572e-01 3.646373e+02 +-9.981093e-01 5.319974e-02 3.078548e-02 1.422044e+02 5.430455e-02 9.978666e-01 3.623840e-02 -1.679386e+01 -2.879192e-02 3.784167e-02 -9.988688e-01 3.638146e+02 +-9.980922e-01 5.160260e-02 3.390026e-02 1.422381e+02 5.274427e-02 9.980395e-01 3.369294e-02 -1.677059e+01 -3.209515e-02 3.541670e-02 -9.988571e-01 3.629724e+02 +-9.978370e-01 5.422086e-02 3.716736e-02 1.422697e+02 5.543515e-02 9.979346e-01 3.245748e-02 -1.674593e+01 -3.533072e-02 3.444765e-02 -9.987818e-01 3.621104e+02 +-9.974582e-01 5.880986e-02 4.023093e-02 1.422994e+02 6.020360e-02 9.975947e-01 3.435555e-02 -1.672269e+01 -3.811372e-02 3.669026e-02 -9.985995e-01 3.612310e+02 +-9.972308e-01 6.042218e-02 4.335908e-02 1.423344e+02 6.205338e-02 9.973750e-01 3.731518e-02 -1.669936e+01 -4.099059e-02 3.990242e-02 -9.983624e-01 3.603289e+02 +-9.969343e-01 6.319583e-02 4.613443e-02 1.423730e+02 6.506856e-02 9.970672e-01 4.028572e-02 -1.667234e+01 -4.345324e-02 4.316411e-02 -9.981225e-01 3.594117e+02 +-9.966817e-01 6.480243e-02 4.925711e-02 1.424153e+02 6.686146e-02 9.969042e-01 4.136986e-02 -1.664202e+01 -4.642375e-02 4.452598e-02 -9.979289e-01 3.584747e+02 +-9.967881e-01 6.103555e-02 5.184904e-02 1.424687e+02 6.326189e-02 9.970941e-01 4.244020e-02 -1.661061e+01 -4.910801e-02 4.558394e-02 -9.977527e-01 3.575224e+02 +-9.971242e-01 5.360876e-02 5.356707e-02 1.425268e+02 5.605000e-02 9.974061e-01 4.516013e-02 -1.657859e+01 -5.100714e-02 4.803268e-02 -9.975425e-01 3.565497e+02 +-9.974289e-01 4.669012e-02 5.436671e-02 1.425825e+02 4.942104e-02 9.975247e-01 5.001972e-02 -1.654547e+01 -5.189671e-02 5.257796e-02 -9.972674e-01 3.555581e+02 +-9.976584e-01 4.168216e-02 5.422592e-02 1.426387e+02 4.444365e-02 9.977216e-01 5.075741e-02 -1.651359e+01 -5.198669e-02 5.304854e-02 -9.972377e-01 3.545569e+02 +-9.976500e-01 4.283267e-02 5.347861e-02 1.426925e+02 4.529635e-02 9.979259e-01 4.573903e-02 -1.647653e+01 -5.140856e-02 4.805392e-02 -9.975209e-01 3.535517e+02 +-9.975958e-01 4.449517e-02 5.313015e-02 1.427397e+02 4.664238e-02 9.981152e-01 3.988178e-02 -1.644204e+01 -5.125546e-02 4.226401e-02 -9.977908e-01 3.525390e+02 +-9.974678e-01 4.739939e-02 5.302275e-02 1.427868e+02 4.958570e-02 9.979400e-01 4.070655e-02 -1.641262e+01 -5.098406e-02 4.323264e-02 -9.977632e-01 3.515111e+02 +-9.973310e-01 5.022115e-02 5.299839e-02 1.428356e+02 5.252472e-02 9.976932e-01 4.300545e-02 -1.638823e+01 -5.071635e-02 4.567438e-02 -9.976681e-01 3.504770e+02 +-9.974770e-01 4.772385e-02 5.255534e-02 1.428919e+02 4.999038e-02 9.978369e-01 4.269080e-02 -1.636326e+01 -5.040428e-02 4.521035e-02 -9.977050e-01 3.494391e+02 +-9.976570e-01 4.429927e-02 5.213603e-02 1.429521e+02 4.648533e-02 9.980569e-01 4.149164e-02 -1.633502e+01 -5.019667e-02 4.381797e-02 -9.977776e-01 3.483931e+02 +-9.977335e-01 4.252542e-02 5.214934e-02 1.430093e+02 4.481310e-02 9.980473e-01 4.351240e-02 -1.630742e+01 -5.019712e-02 4.575074e-02 -9.976908e-01 3.473390e+02 +-9.977048e-01 4.257431e-02 5.265581e-02 1.430645e+02 4.485152e-02 9.980743e-01 4.284871e-02 -1.628715e+01 -5.073015e-02 4.511205e-02 -9.976930e-01 3.462813e+02 +-9.975240e-01 4.574041e-02 5.342095e-02 1.431174e+02 4.789071e-02 9.980637e-01 3.968996e-02 -1.626189e+01 -5.150207e-02 4.215005e-02 -9.977829e-01 3.452218e+02 +-9.972545e-01 4.971784e-02 5.487889e-02 1.431694e+02 5.176598e-02 9.979901e-01 3.655199e-02 -1.623887e+01 -5.295130e-02 3.929249e-02 -9.978237e-01 3.441583e+02 +-9.970676e-01 5.108126e-02 5.698185e-02 1.432271e+02 5.322496e-02 9.979057e-01 3.675875e-02 -1.621907e+01 -5.498483e-02 3.968381e-02 -9.976982e-01 3.430910e+02 +-9.969347e-01 5.142548e-02 5.896431e-02 1.432881e+02 5.353115e-02 9.979629e-01 3.470435e-02 -1.619864e+01 -5.705950e-02 3.775439e-02 -9.976566e-01 3.420248e+02 +-9.970120e-01 4.836220e-02 6.023454e-02 1.433564e+02 5.075966e-02 9.979519e-01 3.892832e-02 -1.617981e+01 -5.822851e-02 4.186948e-02 -9.974248e-01 3.409554e+02 +-9.971260e-01 4.566944e-02 6.044861e-02 1.434252e+02 4.831286e-02 9.979056e-01 4.301507e-02 -1.615917e+01 -5.835752e-02 4.581188e-02 -9.972440e-01 3.398874e+02 +-9.972310e-01 4.395958e-02 5.998365e-02 1.434920e+02 4.643104e-02 9.981022e-01 4.044940e-02 -1.613849e+01 -5.809167e-02 4.312249e-02 -9.973794e-01 3.388256e+02 +-9.972362e-01 4.443067e-02 5.954854e-02 1.435561e+02 4.665539e-02 9.982438e-01 3.650448e-02 -1.611398e+01 -5.782204e-02 3.918184e-02 -9.975577e-01 3.377636e+02 +-9.970566e-01 4.845509e-02 5.941607e-02 1.436162e+02 5.064013e-02 9.980738e-01 3.583712e-02 -1.609250e+01 -5.756512e-02 3.874047e-02 -9.975898e-01 3.367005e+02 +-9.968703e-01 5.273534e-02 5.889473e-02 1.436725e+02 5.527321e-02 9.975737e-01 4.232658e-02 -1.606795e+01 -5.651972e-02 4.544941e-02 -9.973664e-01 3.356274e+02 +-9.967986e-01 5.471163e-02 5.830304e-02 1.437328e+02 5.754573e-02 9.971838e-01 4.809244e-02 -1.604233e+01 -5.550763e-02 5.129356e-02 -9.971398e-01 3.345637e+02 +-9.969431e-01 5.290140e-02 5.749840e-02 1.437959e+02 5.575877e-02 9.972273e-01 4.928093e-02 -1.601395e+01 -5.473195e-02 5.233631e-02 -9.971285e-01 3.335022e+02 +-9.970425e-01 5.200230e-02 5.658698e-02 1.438639e+02 5.460826e-02 9.974696e-01 4.552332e-02 -1.597726e+01 -5.407647e-02 4.847879e-02 -9.973592e-01 3.324462e+02 +-9.973379e-01 4.715442e-02 5.562136e-02 1.439354e+02 4.951173e-02 9.978987e-01 4.179274e-02 -1.594901e+01 -5.353377e-02 4.443538e-02 -9.975768e-01 3.313938e+02 +-9.975702e-01 4.350404e-02 5.441656e-02 1.440057e+02 4.578119e-02 9.980964e-01 4.132395e-02 -1.591901e+01 -5.251521e-02 4.371479e-02 -9.976628e-01 3.303375e+02 +-9.976186e-01 4.304609e-02 5.389049e-02 1.440831e+02 4.550321e-02 9.979397e-01 4.522940e-02 -1.588074e+01 -5.183251e-02 4.757387e-02 -9.975219e-01 3.292695e+02 +-9.978140e-01 3.908743e-02 5.328666e-02 1.441580e+02 4.180323e-02 9.978315e-01 5.084122e-02 -1.584408e+01 -5.118385e-02 5.295763e-02 -9.972841e-01 3.281979e+02 +-9.977903e-01 3.988104e-02 5.314290e-02 1.442300e+02 4.242563e-02 9.979628e-01 4.764649e-02 -1.580246e+01 -5.113445e-02 4.979581e-02 -9.974495e-01 3.271306e+02 +-9.976903e-01 4.237357e-02 5.309071e-02 1.442916e+02 4.468789e-02 9.980669e-01 4.319016e-02 -1.576302e+01 -5.115796e-02 4.546291e-02 -9.976552e-01 3.260621e+02 +-9.976149e-01 4.480946e-02 5.250397e-02 1.443566e+02 4.703222e-02 9.980145e-01 4.189287e-02 -1.572423e+01 -5.052253e-02 4.426232e-02 -9.977416e-01 3.249835e+02 +-9.976297e-01 4.491572e-02 5.213020e-02 1.444191e+02 4.735148e-02 9.977968e-01 4.646966e-02 -1.568803e+01 -4.992812e-02 4.882795e-02 -9.975585e-01 3.238962e+02 +-9.975218e-01 4.719475e-02 5.218198e-02 1.444784e+02 4.986573e-02 9.974464e-01 5.112689e-02 -1.565682e+01 -4.963580e-02 5.360227e-02 -9.973279e-01 3.227954e+02 +-9.973867e-01 4.981123e-02 5.233206e-02 1.445340e+02 5.254256e-02 9.972544e-01 5.218169e-02 -1.562183e+01 -4.958914e-02 5.479498e-02 -9.972654e-01 3.216953e+02 +-9.971543e-01 5.463150e-02 5.194990e-02 1.445874e+02 5.719458e-02 9.971499e-01 4.920144e-02 -1.558365e+01 -4.911389e-02 5.203267e-02 -9.974369e-01 3.205911e+02 +-9.970090e-01 5.738071e-02 5.177416e-02 1.446423e+02 5.998186e-02 9.969379e-01 5.016843e-02 -1.554565e+01 -4.873692e-02 5.312387e-02 -9.973978e-01 3.194803e+02 +-9.968944e-01 5.950530e-02 5.158218e-02 1.446980e+02 6.218152e-02 9.967129e-01 5.193062e-02 -1.550891e+01 -4.832248e-02 5.497679e-02 -9.973176e-01 3.183644e+02 +-9.967067e-01 6.231814e-02 5.188711e-02 1.447546e+02 6.498904e-02 9.965569e-01 5.148528e-02 -1.547325e+01 -4.849998e-02 5.468781e-02 -9.973249e-01 3.172390e+02 +-9.965441e-01 6.440538e-02 5.245918e-02 1.448153e+02 6.694527e-02 9.965922e-01 4.818965e-02 -1.543975e+01 -4.917674e-02 5.153499e-02 -9.974596e-01 3.161100e+02 +-9.964063e-01 6.624150e-02 5.278917e-02 1.448789e+02 6.859479e-02 9.966700e-01 4.408752e-02 -1.540967e+01 -4.969295e-02 4.755013e-02 -9.976319e-01 3.149702e+02 +-9.963675e-01 6.643559e-02 5.327514e-02 1.449419e+02 6.871397e-02 9.967460e-01 4.213863e-02 -1.537960e+01 -5.030228e-02 4.564630e-02 -9.976903e-01 3.138330e+02 +-9.965850e-01 6.286795e-02 5.353543e-02 1.450151e+02 6.520405e-02 9.969421e-01 4.306775e-02 -1.534786e+01 -5.066414e-02 4.641139e-02 -9.976367e-01 3.126776e+02 +-9.965389e-01 6.326003e-02 5.392991e-02 1.450817e+02 6.583811e-02 9.967016e-01 4.744770e-02 -1.531182e+01 -5.075048e-02 5.083412e-02 -9.974167e-01 3.115220e+02 +-9.966590e-01 6.113092e-02 5.416605e-02 1.451573e+02 6.390524e-02 9.966489e-01 5.105870e-02 -1.527397e+01 -5.086327e-02 5.434959e-02 -9.972256e-01 3.103630e+02 +-9.966950e-01 6.124587e-02 5.336671e-02 1.452305e+02 6.417251e-02 9.964237e-01 5.496986e-02 -1.523033e+01 -4.980918e-02 5.821285e-02 -9.970608e-01 3.091981e+02 +-9.966958e-01 6.184154e-02 5.266048e-02 1.453018e+02 6.483352e-02 9.962587e-01 5.714160e-02 -1.518478e+01 -4.892973e-02 6.036695e-02 -9.969762e-01 3.080316e+02 +-9.966950e-01 6.291087e-02 5.139523e-02 1.453685e+02 6.568698e-02 9.963650e-01 5.423993e-02 -1.513971e+01 -4.779612e-02 5.743665e-02 -9.972043e-01 3.068611e+02 +-9.967151e-01 6.329589e-02 5.052448e-02 1.454357e+02 6.579484e-02 9.966080e-01 4.943135e-02 -1.509515e+01 -4.722429e-02 5.259322e-02 -9.974987e-01 3.056890e+02 +-9.967026e-01 6.377482e-02 5.016708e-02 1.455038e+02 6.623722e-02 9.965973e-01 4.905557e-02 -1.505207e+01 -4.686786e-02 5.221673e-02 -9.975353e-01 3.045080e+02 +-9.967273e-01 6.342318e-02 5.012342e-02 1.455698e+02 6.596921e-02 9.965232e-01 5.088695e-02 -1.501009e+01 -4.672174e-02 5.402700e-02 -9.974458e-01 3.033221e+02 +-9.967002e-01 6.355282e-02 5.049620e-02 1.456403e+02 6.596026e-02 9.966895e-01 4.753154e-02 -1.496594e+01 -4.730826e-02 5.070543e-02 -9.975925e-01 3.021453e+02 +-9.966055e-01 6.452388e-02 5.112911e-02 1.457082e+02 6.674149e-02 9.968467e-01 4.292092e-02 -1.492580e+01 -4.819846e-02 4.618765e-02 -9.977693e-01 3.009640e+02 +-9.965299e-01 6.497408e-02 5.202599e-02 1.457796e+02 6.716830e-02 9.968741e-01 4.159884e-02 -1.489101e+01 -4.916051e-02 4.494897e-02 -9.977789e-01 2.997815e+02 +-9.965134e-01 6.469795e-02 5.268155e-02 1.458491e+02 6.701160e-02 9.968077e-01 4.340272e-02 -1.486174e+01 -4.970530e-02 4.678166e-02 -9.976677e-01 2.985951e+02 +-9.965050e-01 6.359091e-02 5.416726e-02 1.459238e+02 6.619345e-02 9.966665e-01 4.768835e-02 -1.482799e+01 -5.095414e-02 5.110719e-02 -9.973924e-01 2.974085e+02 +-9.963939e-01 6.367854e-02 5.607412e-02 1.459958e+02 6.659343e-02 9.964375e-01 5.174562e-02 -1.479097e+01 -5.257926e-02 5.529318e-02 -9.970847e-01 2.962243e+02 +-9.965093e-01 6.059881e-02 5.742039e-02 1.460741e+02 6.355253e-02 9.966698e-01 5.109085e-02 -1.475456e+01 -5.413312e-02 5.456171e-02 -9.970419e-01 2.950464e+02 +-9.965307e-01 5.993589e-02 5.774336e-02 1.461525e+02 6.243156e-02 9.971469e-01 4.243021e-02 -1.472282e+01 -5.503552e-02 4.588801e-02 -9.974293e-01 2.938828e+02 +-9.966361e-01 5.745562e-02 5.844116e-02 1.462328e+02 5.941308e-02 9.977099e-01 3.232588e-02 -1.469749e+01 -5.645002e-02 3.568930e-02 -9.977673e-01 2.927237e+02 +-9.965802e-01 5.709499e-02 5.973391e-02 1.463117e+02 5.905055e-02 9.977579e-01 3.149999e-02 -1.467747e+01 -5.780149e-02 3.491958e-02 -9.977171e-01 2.915585e+02 +-9.965327e-01 5.605135e-02 6.148974e-02 1.463904e+02 5.843432e-02 9.975805e-01 3.766413e-02 -1.465898e+01 -5.922984e-02 4.112664e-02 -9.973968e-01 2.903897e+02 +-9.963804e-01 5.779174e-02 6.234031e-02 1.464665e+02 6.061266e-02 9.971756e-01 4.434907e-02 -1.463779e+01 -5.960122e-02 4.796715e-02 -9.970691e-01 2.892215e+02 +-9.964076e-01 5.653257e-02 6.305658e-02 1.465443e+02 5.969151e-02 9.969942e-01 4.939071e-02 -1.460953e+01 -6.007486e-02 5.297721e-02 -9.967870e-01 2.880564e+02 +-9.964254e-01 5.632060e-02 6.296503e-02 1.466136e+02 5.971175e-02 9.967895e-01 5.333923e-02 -1.457882e+01 -5.975878e-02 5.690831e-02 -9.965893e-01 2.869004e+02 +-9.964636e-01 5.607361e-02 6.257888e-02 1.466852e+02 5.933524e-02 9.969067e-01 5.153861e-02 -1.454396e+01 -5.949535e-02 5.506948e-02 -9.967084e-01 2.857460e+02 +-9.965433e-01 5.594378e-02 6.141504e-02 1.467555e+02 5.912777e-02 9.969308e-01 5.131128e-02 -1.450797e+01 -5.835599e-02 5.476524e-02 -9.967925e-01 2.845909e+02 +-9.966006e-01 5.601757e-02 6.041022e-02 1.468261e+02 5.918875e-02 9.968890e-01 5.204781e-02 -1.447298e+01 -5.730669e-02 5.544647e-02 -9.968157e-01 2.834352e+02 +-9.966144e-01 5.673054e-02 5.951021e-02 1.468938e+02 5.960882e-02 9.970786e-01 4.775946e-02 -1.444182e+01 -5.662693e-02 5.114509e-02 -9.970845e-01 2.822812e+02 +-9.966628e-01 5.672039e-02 5.870337e-02 1.469629e+02 5.896488e-02 9.975654e-01 3.723443e-02 -1.441352e+01 -5.644850e-02 4.057160e-02 -9.975808e-01 2.811377e+02 +-9.967791e-01 5.539459e-02 5.799035e-02 1.470331e+02 5.744906e-02 9.977563e-01 3.438005e-02 -1.439034e+01 -5.595576e-02 3.760080e-02 -9.977249e-01 2.799936e+02 +-9.969809e-01 5.229671e-02 5.739610e-02 1.471037e+02 5.461178e-02 9.977247e-01 3.953510e-02 -1.437177e+01 -5.519794e-02 4.255023e-02 -9.975683e-01 2.788341e+02 +-9.973702e-01 4.506059e-02 5.676611e-02 1.471766e+02 4.779857e-02 9.977109e-01 4.783510e-02 -1.434568e+01 -5.448068e-02 5.042263e-02 -9.972408e-01 2.776828e+02 +-9.975915e-01 4.117280e-02 5.582136e-02 1.472446e+02 4.436242e-02 9.973790e-01 5.715866e-02 -1.431020e+01 -5.332167e-02 5.949736e-02 -9.968033e-01 2.765326e+02 +-9.976208e-01 4.213649e-02 5.456501e-02 1.473092e+02 4.562743e-02 9.968807e-01 6.439672e-02 -1.426940e+01 -5.168135e-02 6.673316e-02 -9.964314e-01 2.753800e+02 +-9.977436e-01 4.065970e-02 5.342881e-02 1.473720e+02 4.410506e-02 9.969119e-01 6.497217e-02 -1.422198e+01 -5.062206e-02 6.718203e-02 -9.964557e-01 2.742471e+02 +-9.974675e-01 4.734560e-02 5.307655e-02 1.474227e+02 5.028764e-02 9.971894e-01 5.553765e-02 -1.418018e+01 -5.029790e-02 5.806609e-02 -9.970448e-01 2.731258e+02 +-9.969635e-01 5.736389e-02 5.266196e-02 1.474690e+02 5.946498e-02 9.974590e-01 3.923646e-02 -1.414342e+01 -5.027738e-02 4.224885e-02 -9.978412e-01 2.720149e+02 +-9.968236e-01 6.019001e-02 5.215326e-02 1.475236e+02 6.182995e-02 9.976229e-01 3.042193e-02 -1.411790e+01 -5.019819e-02 3.354992e-02 -9.981756e-01 2.708995e+02 +-9.967923e-01 6.014206e-02 5.280181e-02 1.475825e+02 6.216242e-02 9.973616e-01 3.749165e-02 -1.409516e+01 -5.040767e-02 4.065367e-02 -9.979009e-01 2.697702e+02 +-9.967756e-01 5.966704e-02 5.364978e-02 1.476441e+02 6.239278e-02 9.967654e-01 5.065335e-02 -1.406534e+01 -5.045391e-02 5.383738e-02 -9.972742e-01 2.686405e+02 +-9.968689e-01 5.786643e-02 5.388797e-02 1.477037e+02 6.105618e-02 9.963559e-01 5.955760e-02 -1.403193e+01 -5.024521e-02 6.266130e-02 -9.967692e-01 2.675141e+02 +-9.969959e-01 5.529620e-02 5.423675e-02 1.477650e+02 5.883162e-02 9.960895e-01 6.591288e-02 -1.398885e+01 -5.037992e-02 6.890569e-02 -9.963502e-01 2.663995e+02 +-9.971343e-01 5.231074e-02 5.465125e-02 1.478280e+02 5.614437e-02 9.958848e-01 7.114174e-02 -1.394239e+01 -5.070487e-02 7.400622e-02 -9.959679e-01 2.652874e+02 +-9.972286e-01 5.007767e-02 5.502217e-02 1.478896e+02 5.384264e-02 9.961473e-01 6.922075e-02 -1.389624e+01 -5.134377e-02 7.199144e-02 -9.960828e-01 2.641887e+02 +-9.973673e-01 4.751679e-02 5.477942e-02 1.479547e+02 5.086547e-02 9.968132e-01 6.144961e-02 -1.384906e+01 -5.168496e-02 6.407420e-02 -9.966058e-01 2.630990e+02 +-9.974256e-01 4.740774e-02 5.380381e-02 1.480187e+02 5.028617e-02 9.973025e-01 5.346888e-02 -1.381143e+01 -5.112383e-02 5.603680e-02 -9.971189e-01 2.620113e+02 +-9.975043e-01 4.732967e-02 5.239422e-02 1.480798e+02 4.982668e-02 9.976313e-01 4.742417e-02 -1.378074e+01 -5.002554e-02 4.991643e-02 -9.974997e-01 2.609277e+02 +-9.976065e-01 4.793021e-02 4.983970e-02 1.481364e+02 4.999601e-02 9.979049e-01 4.106251e-02 -1.375580e+01 -4.776714e-02 4.345601e-02 -9.979127e-01 2.598532e+02 +-9.976560e-01 4.914232e-02 4.761955e-02 1.481916e+02 5.107985e-02 9.978786e-01 4.036220e-02 -1.373319e+01 -4.553504e-02 4.269998e-02 -9.980497e-01 2.587765e+02 +-9.976881e-01 5.009925e-02 4.591878e-02 1.482468e+02 5.213497e-02 9.976586e-01 4.426243e-02 -1.371001e+01 -4.359375e-02 4.655407e-02 -9.979640e-01 2.577052e+02 +-9.978047e-01 4.841334e-02 4.518941e-02 1.483039e+02 5.087741e-02 9.971853e-01 5.507121e-02 -1.368168e+01 -4.239604e-02 5.724942e-02 -9.974593e-01 2.566315e+02 +-9.979353e-01 4.506105e-02 4.576769e-02 1.483625e+02 4.796803e-02 9.967616e-01 6.454014e-02 -1.364657e+01 -4.271123e-02 6.660226e-02 -9.968650e-01 2.555680e+02 +-9.981243e-01 4.017393e-02 4.619457e-02 1.484218e+02 4.328883e-02 9.967091e-01 6.853400e-02 -1.360622e+01 -4.328927e-02 7.040515e-02 -9.965787e-01 2.545244e+02 +-9.983077e-01 3.481280e-02 4.658112e-02 1.484836e+02 3.783439e-02 9.971258e-01 6.564055e-02 -1.356624e+01 -4.416210e-02 6.729182e-02 -9.967554e-01 2.534954e+02 +-9.983906e-01 3.141424e-02 4.721714e-02 1.485427e+02 3.415315e-02 9.977109e-01 5.836546e-02 -1.352881e+01 -4.527554e-02 5.988412e-02 -9.971780e-01 2.524848e+02 +-9.981956e-01 3.467337e-02 4.902470e-02 1.485947e+02 3.706388e-02 9.981244e-01 4.872347e-02 -1.349617e+01 -4.724333e-02 5.045259e-02 -9.976084e-01 2.514866e+02 +-9.979971e-01 3.751763e-02 5.093455e-02 1.486459e+02 3.973010e-02 9.982786e-01 4.314277e-02 -1.347190e+01 -4.922826e-02 4.507999e-02 -9.977696e-01 2.505055e+02 +-9.977628e-01 4.127888e-02 5.258835e-02 1.486994e+02 4.351657e-02 9.981635e-01 4.214108e-02 -1.344786e+01 -5.075223e-02 4.433526e-02 -9.977267e-01 2.495301e+02 +-9.974933e-01 4.487808e-02 5.470897e-02 1.487515e+02 4.750900e-02 9.977275e-01 4.777650e-02 -1.342428e+01 -5.244053e-02 5.025590e-02 -9.973586e-01 2.485643e+02 +-9.972700e-01 4.747619e-02 5.655723e-02 1.488029e+02 5.046070e-02 9.973418e-01 5.256514e-02 -1.340250e+01 -5.391129e-02 5.527554e-02 -9.970146e-01 2.476198e+02 +-9.970904e-01 4.954793e-02 5.793025e-02 1.488551e+02 5.254347e-02 9.972958e-01 5.138284e-02 -1.337998e+01 -5.522768e-02 5.427718e-02 -9.969974e-01 2.466970e+02 +-9.969469e-01 5.092870e-02 5.918758e-02 1.489068e+02 5.359514e-02 9.975764e-01 4.437125e-02 -1.336041e+01 -5.678436e-02 4.740794e-02 -9.972602e-01 2.458032e+02 +-9.968231e-01 5.244402e-02 5.994584e-02 1.489571e+02 5.489394e-02 9.976915e-01 3.997899e-02 -1.334445e+01 -5.771080e-02 4.314264e-02 -9.974007e-01 2.449240e+02 +-9.969347e-01 4.854659e-02 6.135549e-02 1.490120e+02 5.099347e-02 9.979386e-01 3.896359e-02 -1.333483e+01 -5.933746e-02 4.197288e-02 -9.973551e-01 2.440596e+02 +-9.970477e-01 4.495153e-02 6.225256e-02 1.490714e+02 4.751575e-02 9.980555e-01 4.034113e-02 -1.332729e+01 -6.031811e-02 4.318000e-02 -9.972448e-01 2.432071e+02 +-9.969315e-01 4.573057e-02 6.353319e-02 1.491209e+02 4.830590e-02 9.980470e-01 3.960767e-02 -1.331957e+01 -6.159782e-02 4.255515e-02 -9.971934e-01 2.423762e+02 +-9.970060e-01 4.157336e-02 6.519764e-02 1.491775e+02 4.432682e-02 9.981601e-01 4.137000e-02 -1.331184e+01 -6.335779e-02 4.413614e-02 -9.970144e-01 2.415653e+02 +-9.972074e-01 3.378707e-02 6.660237e-02 1.492399e+02 3.691189e-02 9.982473e-01 4.625879e-02 -1.330447e+01 -6.492268e-02 4.858801e-02 -9.967066e-01 2.407729e+02 +-9.971622e-01 3.019194e-02 6.896484e-02 1.493001e+02 3.396521e-02 9.979516e-01 5.421186e-02 -1.329094e+01 -6.718681e-02 5.640041e-02 -9.961450e-01 2.399943e+02 +-9.969595e-01 3.018927e-02 7.183691e-02 1.493541e+02 3.441195e-02 9.977065e-01 5.828862e-02 -1.328784e+01 -6.991245e-02 6.058343e-02 -9.957117e-01 2.392408e+02 +-9.967759e-01 3.103597e-02 7.399152e-02 1.494097e+02 3.523568e-02 9.978006e-01 5.614626e-02 -1.327893e+01 -7.208623e-02 5.857237e-02 -9.956770e-01 2.385162e+02 +-9.966709e-01 2.945147e-02 7.602528e-02 1.494680e+02 3.343137e-02 9.981071e-01 5.161882e-02 -1.326869e+01 -7.436112e-02 5.398860e-02 -9.957688e-01 2.378162e+02 +-9.963671e-01 3.231927e-02 7.879159e-02 1.495185e+02 3.609914e-02 9.982409e-01 4.702997e-02 -1.325514e+01 -7.713301e-02 4.970342e-02 -9.957811e-01 2.371411e+02 +-9.961645e-01 3.074368e-02 8.192249e-02 1.495730e+02 3.483525e-02 9.981915e-01 4.899201e-02 -1.324552e+01 -8.026813e-02 5.165788e-02 -9.954338e-01 2.364857e+02 +-9.961317e-01 2.931240e-02 8.284031e-02 1.496281e+02 3.394049e-02 9.979081e-01 5.502273e-02 -1.323521e+01 -8.105416e-02 5.762151e-02 -9.950426e-01 2.358495e+02 +-9.963390e-01 2.211007e-02 8.258276e-02 1.496884e+02 2.701933e-02 9.979035e-01 5.880990e-02 -1.322470e+01 -8.110932e-02 6.082592e-02 -9.948474e-01 2.352411e+02 +-9.964933e-01 1.929280e-02 8.141790e-02 1.497405e+02 2.425824e-02 9.978767e-01 6.044521e-02 -1.321549e+01 -8.007886e-02 6.220829e-02 -9.948454e-01 2.346539e+02 +-9.967606e-01 1.634816e-02 7.874742e-02 1.497885e+02 2.123709e-02 9.978717e-01 6.165165e-02 -1.320388e+01 -7.757193e-02 6.312429e-02 -9.949863e-01 2.340855e+02 +-9.972882e-01 1.402750e-02 7.224609e-02 1.498316e+02 1.844377e-02 9.979778e-01 6.082828e-02 -1.319032e+01 -7.124672e-02 6.199581e-02 -9.955302e-01 2.335367e+02 +-9.978438e-01 1.292017e-02 6.434999e-02 1.498633e+02 1.664537e-02 9.981955e-01 5.769399e-02 -1.317359e+01 -6.348845e-02 5.864071e-02 -9.962582e-01 2.330076e+02 +-9.984998e-01 9.958047e-03 5.384363e-02 1.498883e+02 1.290405e-02 9.984224e-01 5.464604e-02 -1.316085e+01 -5.321451e-02 5.525885e-02 -9.970529e-01 2.324990e+02 +-9.992366e-01 6.904630e-03 3.845262e-02 1.499063e+02 8.985502e-03 9.984892e-01 5.420786e-02 -1.314923e+01 -3.802024e-02 5.451198e-02 -9.977890e-01 2.320049e+02 +-9.997985e-01 5.562976e-03 1.928935e-02 1.499055e+02 6.624025e-03 9.984430e-01 5.538630e-02 -1.313525e+01 -1.895120e-02 5.550291e-02 -9.982786e-01 2.315225e+02 +-9.999392e-01 1.007575e-02 -4.485011e-03 1.498867e+02 9.803723e-03 9.983247e-01 5.702365e-02 -1.311875e+01 5.052053e-03 5.697620e-02 -9.983627e-01 2.310661e+02 +-9.993515e-01 1.740077e-02 -3.152462e-02 1.498387e+02 1.558353e-02 9.982524e-01 5.700155e-02 -1.310236e+01 3.246139e-02 5.647331e-02 -9.978762e-01 2.306199e+02 +-9.977709e-01 1.963561e-02 -6.377968e-02 1.497894e+02 1.611074e-02 9.983388e-01 5.531831e-02 -1.309070e+01 6.475993e-02 5.416745e-02 -9.964296e-01 2.301941e+02 +-9.946854e-01 2.007931e-02 -1.009847e-01 1.497286e+02 1.455531e-02 9.983723e-01 5.514383e-02 -1.308007e+01 1.019275e-01 5.338089e-02 -9.933585e-01 2.297738e+02 +-9.900000e-01 2.174227e-02 -1.393823e-01 1.496351e+02 1.404675e-02 9.983342e-01 5.595970e-02 -1.306755e+01 1.403668e-01 5.344222e-02 -9.886562e-01 2.293441e+02 +-9.834666e-01 2.869085e-02 -1.788028e-01 1.495269e+02 1.887004e-02 9.982307e-01 5.638643e-02 -1.305107e+01 1.801042e-01 5.208015e-02 -9.822678e-01 2.289406e+02 +-9.750411e-01 3.623072e-02 -2.190484e-01 1.493990e+02 2.472488e-02 9.981778e-01 5.504233e-02 -1.303179e+01 2.206435e-01 4.825258e-02 -9.741602e-01 2.285521e+02 +-9.644037e-01 4.384489e-02 -2.607741e-01 1.492413e+02 3.073348e-02 9.980598e-01 5.414784e-02 -1.301446e+01 2.626422e-01 4.420588e-02 -9.638801e-01 2.281502e+02 +-9.517688e-01 4.767227e-02 -3.030901e-01 1.490871e+02 3.259296e-02 9.979751e-01 5.462003e-02 -1.299856e+01 3.050802e-01 4.210703e-02 -9.513953e-01 2.277785e+02 +-9.374479e-01 4.945788e-02 -3.445945e-01 1.489062e+02 3.165101e-02 9.978658e-01 5.711400e-02 -1.298572e+01 3.466838e-01 4.263463e-02 -9.370126e-01 2.273924e+02 +-9.207692e-01 5.488001e-02 -3.862284e-01 1.487161e+02 3.392309e-02 9.975688e-01 6.087402e-02 -1.296801e+01 3.886301e-01 4.294886e-02 -9.203923e-01 2.270396e+02 +-9.008653e-01 5.830380e-02 -4.301656e-01 1.485087e+02 3.388085e-02 9.973600e-01 6.422601e-02 -1.294524e+01 4.327746e-01 4.328460e-02 -9.004624e-01 2.266979e+02 +-8.767842e-01 6.107394e-02 -4.769901e-01 1.482570e+02 3.415315e-02 9.973061e-01 6.491641e-02 -1.291843e+01 4.796698e-01 4.062696e-02 -8.765080e-01 2.263348e+02 +-8.495950e-01 6.333934e-02 -5.236188e-01 1.480007e+02 3.293597e-02 9.971967e-01 6.718545e-02 -1.289513e+01 5.264064e-01 3.983453e-02 -8.492994e-01 2.260082e+02 +-8.197696e-01 6.595349e-02 -5.688831e-01 1.476976e+02 3.103640e-02 9.970030e-01 7.086367e-02 -1.286996e+01 5.718518e-01 4.043580e-02 -8.193597e-01 2.256569e+02 +-7.865526e-01 6.632064e-02 -6.139516e-01 1.473972e+02 2.656416e-02 9.969296e-01 7.365876e-02 -1.284664e+01 6.169516e-01 4.162737e-02 -7.858993e-01 2.253474e+02 +-7.500510e-01 6.608918e-02 -6.580698e-01 1.470757e+02 2.207522e-02 9.969421e-01 7.496100e-02 -1.282167e+01 6.610115e-01 4.169753e-02 -7.492163e-01 2.250489e+02 +-7.107173e-01 6.257634e-02 -7.006890e-01 1.467034e+02 1.572215e-02 9.972000e-01 7.310965e-02 -1.278496e+01 7.033020e-01 4.094395e-02 -7.097111e-01 2.247302e+02 +-6.689842e-01 5.852419e-02 -7.409690e-01 1.463321e+02 1.113545e-02 9.975726e-01 6.873797e-02 -1.275356e+01 7.431932e-01 3.773359e-02 -6.680120e-01 2.244633e+02 +-6.261037e-01 5.459629e-02 -7.778261e-01 1.459376e+02 7.592093e-03 9.979252e-01 6.393407e-02 -1.272341e+01 7.797028e-01 3.412403e-02 -6.252192e-01 2.242173e+02 +-5.821793e-01 5.106777e-02 -8.114551e-01 1.455026e+02 4.619519e-03 9.982172e-01 5.950711e-02 -1.269426e+01 8.130473e-01 3.089528e-02 -5.813773e-01 2.239490e+02 +-5.373361e-01 4.927613e-02 -8.419275e-01 1.450547e+02 1.473802e-03 9.983450e-01 5.749030e-02 -1.266419e+01 8.433669e-01 2.965078e-02 -5.365194e-01 2.237319e+02 +-4.915254e-01 4.898643e-02 -8.694844e-01 1.445644e+02 -3.349706e-03 9.983029e-01 5.813764e-02 -1.263282e+01 8.708568e-01 3.148864e-02 -4.905271e-01 2.234964e+02 +-4.471052e-01 5.054651e-02 -8.930521e-01 1.440680e+02 -7.381395e-03 9.981596e-01 6.019107e-02 -1.259687e+01 8.944509e-01 3.350371e-02 -4.459092e-01 2.233106e+02 +-4.029710e-01 5.246913e-02 -9.137075e-01 1.435569e+02 -7.943351e-03 9.981171e-01 6.081956e-02 -1.256130e+01 9.151782e-01 3.176642e-02 -4.017954e-01 2.231391e+02 +-3.592103e-01 5.477865e-02 -9.316476e-01 1.430108e+02 -7.139969e-03 9.980853e-01 6.143797e-02 -1.252742e+01 9.332293e-01 2.872109e-02 -3.581314e-01 2.229639e+02 +-3.166110e-01 5.685350e-02 -9.468502e-01 1.424641e+02 -9.976834e-03 9.979473e-01 6.325773e-02 -1.249939e+01 9.485030e-01 2.947466e-02 -3.153938e-01 2.228219e+02 +-2.777328e-01 5.453138e-02 -9.591094e-01 1.419041e+02 -1.550690e-02 9.980030e-01 6.123313e-02 -1.247404e+01 9.605332e-01 3.187926e-02 -2.763325e-01 2.226903e+02 +-2.424652e-01 4.970396e-02 -9.688861e-01 1.413166e+02 -1.741847e-02 9.983027e-01 5.557205e-02 -1.244205e+01 9.700037e-01 3.035081e-02 -2.411879e-01 2.225687e+02 +-2.111620e-01 4.587248e-02 -9.763741e-01 1.407198e+02 -1.538501e-02 9.986184e-01 5.024492e-02 -1.240933e+01 9.773300e-01 2.563134e-02 -2.101645e-01 2.224776e+02 +-1.836433e-01 4.418026e-02 -9.819997e-01 1.400954e+02 -1.037802e-02 9.988466e-01 4.687900e-02 -1.237499e+01 9.829381e-01 1.880022e-02 -1.829729e-01 2.224060e+02 +-1.594463e-01 4.454988e-02 -9.862009e-01 1.394545e+02 -5.869738e-03 9.989208e-01 4.607349e-02 -1.234570e+01 9.871891e-01 1.313499e-02 -1.590127e-01 2.223345e+02 +-1.382061e-01 4.656475e-02 -9.893083e-01 1.387945e+02 -3.038923e-03 9.988695e-01 4.743932e-02 -1.232055e+01 9.903988e-01 9.562837e-03 -1.379083e-01 2.222751e+02 +-1.203148e-01 4.608385e-02 -9.916656e-01 1.381225e+02 -3.988552e-03 9.988914e-01 4.690357e-02 -1.229664e+01 9.927277e-01 9.598506e-03 -1.199976e-01 2.222177e+02 +-1.047000e-01 4.649176e-02 -9.934166e-01 1.374250e+02 -2.628048e-03 9.988902e-01 4.702492e-02 -1.226601e+01 9.945003e-01 7.534257e-03 -1.044616e-01 2.221663e+02 +-9.248020e-02 4.787058e-02 -9.945632e-01 1.367075e+02 -1.143274e-03 9.988379e-01 4.818265e-02 -1.223195e+01 9.957138e-01 5.593003e-03 -9.231799e-02 2.221224e+02 +-8.272282e-02 5.072124e-02 -9.952810e-01 1.359678e+02 3.499814e-03 9.987126e-01 5.060524e-02 -1.219954e+01 9.965664e-01 7.029147e-04 -8.279383e-02 2.220857e+02 +-7.470635e-02 5.286556e-02 -9.958033e-01 1.352055e+02 4.858752e-03 9.986012e-01 5.264960e-02 -1.216821e+01 9.971937e-01 -9.050969e-04 -7.485871e-02 2.220501e+02 +-6.727714e-02 5.321467e-02 -9.963142e-01 1.344230e+02 1.869365e-03 9.985816e-01 5.320955e-02 -1.212915e+01 9.977325e-01 1.717317e-03 -6.728119e-02 2.220102e+02 +-5.945123e-02 4.838748e-02 -9.970578e-01 1.336210e+02 3.524091e-03 9.988284e-01 4.826329e-02 -1.209125e+01 9.982249e-01 -6.444052e-04 -5.955210e-02 2.219811e+02 +-5.207225e-02 4.468869e-02 -9.976430e-01 1.328040e+02 7.857689e-03 9.989856e-01 4.433871e-02 -1.205940e+01 9.986124e-01 -5.530345e-03 -5.237058e-02 2.219615e+02 +-4.513715e-02 3.604204e-02 -9.983304e-01 1.319851e+02 1.022190e-02 9.993133e-01 3.561537e-02 -1.203480e+01 9.989285e-01 -8.597255e-03 -4.547457e-02 2.219450e+02 +-4.072102e-02 3.145417e-02 -9.986754e-01 1.311365e+02 1.319421e-02 9.994341e-01 3.094008e-02 -1.201166e+01 9.990834e-01 -1.191682e-02 -4.111298e-02 2.219299e+02 +-3.855449e-02 2.910157e-02 -9.988327e-01 1.302674e+02 1.791719e-02 9.994352e-01 2.842754e-02 -1.199076e+01 9.990958e-01 -1.680026e-02 -3.905413e-02 2.219193e+02 +-3.706989e-02 3.242543e-02 -9.987865e-01 1.293683e+02 1.781927e-02 9.993359e-01 3.178192e-02 -1.197037e+01 9.991537e-01 -1.661948e-02 -3.762307e-02 2.219012e+02 +-3.606513e-02 3.897002e-02 -9.985894e-01 1.284498e+02 1.412935e-02 9.991594e-01 3.848197e-02 -1.194131e+01 9.992495e-01 -1.272155e-02 -3.658543e-02 2.218912e+02 +-3.630774e-02 4.872440e-02 -9.981522e-01 1.275087e+02 1.211792e-02 9.987587e-01 4.831323e-02 -1.190638e+01 9.992671e-01 -1.034137e-02 -3.685311e-02 2.218825e+02 +-3.661016e-02 5.594379e-02 -9.977625e-01 1.265508e+02 9.138398e-03 9.984088e-01 5.564472e-02 -1.186811e+01 9.992878e-01 -7.080782e-03 -3.706314e-02 2.218697e+02 +-3.584190e-02 5.446718e-02 -9.978721e-01 1.255892e+02 8.253717e-03 9.984957e-01 5.420477e-02 -1.182662e+01 9.993233e-01 -6.293346e-03 -3.623753e-02 2.218603e+02 +-3.589512e-02 4.634322e-02 -9.982805e-01 1.246227e+02 1.158736e-02 9.988763e-01 4.595424e-02 -1.178537e+01 9.992883e-01 -9.917897e-03 -3.639178e-02 2.218543e+02 +-3.623061e-02 3.829041e-02 -9.986097e-01 1.236490e+02 1.375279e-02 9.991901e-01 3.781371e-02 -1.174920e+01 9.992488e-01 -1.236365e-02 -3.672787e-02 2.218500e+02 +-3.610271e-02 3.831781e-02 -9.986132e-01 1.226588e+02 1.621798e-02 9.991555e-01 3.775230e-02 -1.172068e+01 9.992164e-01 -1.483252e-02 -3.669365e-02 2.218393e+02 +-3.629137e-02 4.196760e-02 -9.984597e-01 1.216640e+02 1.771186e-02 9.989879e-01 4.134603e-02 -1.169407e+01 9.991842e-01 -1.618407e-02 -3.699796e-02 2.218301e+02 +-3.751450e-02 4.446748e-02 -9.983062e-01 1.206638e+02 1.790666e-02 9.988789e-01 4.382010e-02 -1.166561e+01 9.991356e-01 -1.623243e-02 -3.826871e-02 2.218134e+02 +-3.983994e-02 4.942416e-02 -9.979830e-01 1.196649e+02 1.912022e-02 9.986307e-01 4.869296e-02 -1.163207e+01 9.990231e-01 -1.714172e-02 -4.073039e-02 2.217898e+02 +-4.323786e-02 5.591337e-02 -9.974990e-01 1.186572e+02 2.023234e-02 9.982769e-01 5.507999e-02 -1.159609e+01 9.988599e-01 -1.780019e-02 -4.429462e-02 2.217633e+02 +-4.665301e-02 6.040301e-02 -9.970833e-01 1.176466e+02 1.803364e-02 9.980583e-01 5.961831e-02 -1.155591e+01 9.987483e-01 -1.519966e-02 -4.765171e-02 2.217370e+02 +-4.985033e-02 5.433326e-02 -9.972777e-01 1.166441e+02 1.684269e-02 9.984229e-01 5.355376e-02 -1.151182e+01 9.986146e-01 -1.412716e-02 -5.068683e-02 2.217117e+02 +-5.346584e-02 4.695488e-02 -9.974651e-01 1.156416e+02 1.797375e-02 9.987773e-01 4.605323e-02 -1.147092e+01 9.984079e-01 -1.546590e-02 -5.424441e-02 2.216855e+02 +-5.657767e-02 4.495196e-02 -9.973858e-01 1.146347e+02 1.792275e-02 9.988706e-01 4.400221e-02 -1.143302e+01 9.982373e-01 -1.538634e-02 -5.731943e-02 2.216570e+02 +-5.869745e-02 4.952220e-02 -9.970467e-01 1.136256e+02 2.036836e-02 9.986202e-01 4.840126e-02 -1.139936e+01 9.980680e-01 -1.746716e-02 -5.962514e-02 2.216252e+02 +-6.169446e-02 5.597506e-02 -9.965243e-01 1.126273e+02 2.069333e-02 9.982833e-01 5.479276e-02 -1.136389e+01 9.978805e-01 -1.724099e-02 -6.274686e-02 2.215703e+02 +-6.381096e-02 6.135437e-02 -9.960742e-01 1.116312e+02 2.072597e-02 9.979745e-01 6.014367e-02 -1.132789e+01 9.977467e-01 -1.680678e-02 -6.495333e-02 2.215138e+02 +-6.549687e-02 5.867096e-02 -9.961265e-01 1.106494e+02 2.068259e-02 9.981353e-01 5.742938e-02 -1.129377e+01 9.976384e-01 -1.684102e-02 -6.658820e-02 2.214332e+02 +-6.624125e-02 5.314676e-02 -9.963873e-01 1.096735e+02 2.032809e-02 9.984451e-01 5.190510e-02 -1.125746e+01 9.975965e-01 -1.681638e-02 -6.721861e-02 2.213561e+02 +-6.641993e-02 4.790412e-02 -9.966412e-01 1.087020e+02 2.110403e-02 9.986908e-01 4.659620e-02 -1.122720e+01 9.975685e-01 -1.793822e-02 -6.734395e-02 2.212816e+02 +-6.706818e-02 4.245263e-02 -9.968449e-01 1.077265e+02 2.305029e-02 9.988937e-01 4.098906e-02 -1.119992e+01 9.974821e-01 -2.022849e-02 -6.797252e-02 2.212255e+02 +-6.665191e-02 3.689317e-02 -9.970940e-01 1.067549e+02 2.371972e-02 9.990923e-01 3.538155e-02 -1.117585e+01 9.974943e-01 -2.129253e-02 -6.746650e-02 2.211665e+02 +-6.548397e-02 4.189993e-02 -9.969736e-01 1.057727e+02 2.486684e-02 9.988762e-01 4.034658e-02 -1.115208e+01 9.975437e-01 -2.214952e-02 -6.645229e-02 2.210968e+02 +-6.413882e-02 5.077347e-02 -9.966485e-01 1.047898e+02 2.837870e-02 9.983937e-01 4.903609e-02 -1.112958e+01 9.975374e-01 -2.513846e-02 -6.547668e-02 2.210386e+02 +-6.286616e-02 5.366026e-02 -9.965784e-01 1.038159e+02 2.846943e-02 9.982436e-01 5.195402e-02 -1.110241e+01 9.976158e-01 -2.510586e-02 -6.428341e-02 2.209772e+02 +-6.175459e-02 5.133524e-02 -9.967703e-01 1.028522e+02 2.699044e-02 9.983971e-01 4.974684e-02 -1.106971e+01 9.977263e-01 -2.383116e-02 -6.304116e-02 2.209184e+02 +-6.093267e-02 4.921430e-02 -9.969279e-01 1.018926e+02 3.137947e-02 9.983845e-01 4.736829e-02 -1.103993e+01 9.976485e-01 -2.839678e-02 -6.237855e-02 2.208680e+02 +-6.021927e-02 4.869397e-02 -9.969968e-01 1.009339e+02 3.282208e-02 9.983659e-01 4.677838e-02 -1.101296e+01 9.976454e-01 -2.990654e-02 -6.171910e-02 2.208228e+02 +-5.915271e-02 4.584366e-02 -9.971958e-01 9.997800e+01 3.274869e-02 9.984963e-01 4.396084e-02 -1.099036e+01 9.977116e-01 -3.005644e-02 -6.056508e-02 2.207665e+02 +-5.945406e-02 4.798764e-02 -9.970770e-01 9.902616e+01 3.579355e-02 9.983040e-01 4.591239e-02 -1.096553e+01 9.975891e-01 -3.295924e-02 -6.107087e-02 2.207126e+02 +-6.112890e-02 5.383857e-02 -9.966768e-01 9.807546e+01 4.018050e-02 9.978675e-01 5.143852e-02 -1.093903e+01 9.973208e-01 -3.690258e-02 -6.316180e-02 2.206560e+02 +-6.244998e-02 5.690491e-02 -9.964246e-01 9.713185e+01 3.968096e-02 9.977254e-01 5.449225e-02 -1.091126e+01 9.972589e-01 -3.613603e-02 -6.456596e-02 2.205975e+02 +-6.350814e-02 5.567975e-02 -9.964269e-01 9.619303e+01 3.842615e-02 9.978384e-01 5.330952e-02 -1.088028e+01 9.972412e-01 -3.490324e-02 -6.551042e-02 2.205371e+02 +-6.494787e-02 5.593778e-02 -9.963196e-01 9.525302e+01 3.884521e-02 9.978126e-01 5.348937e-02 -1.084018e+01 9.971323e-01 -3.522821e-02 -6.697871e-02 2.204875e+02 +-6.622716e-02 5.924420e-02 -9.960442e-01 9.432411e+01 3.672451e-02 9.977041e-01 5.690112e-02 -1.080470e+01 9.971285e-01 -3.281082e-02 -6.825082e-02 2.204308e+02 +-6.674543e-02 6.183084e-02 -9.958524e-01 9.339619e+01 3.334513e-02 9.976588e-01 5.970810e-02 -1.076820e+01 9.972126e-01 -2.922157e-02 -6.865092e-02 2.203858e+02 +-6.750451e-02 5.996356e-02 -9.959154e-01 9.248691e+01 3.300029e-02 9.977803e-01 5.783905e-02 -1.072514e+01 9.971730e-01 -2.896109e-02 -6.933348e-02 2.203445e+02 +-6.793116e-02 5.870488e-02 -9.959614e-01 9.159378e+01 3.383350e-02 9.978287e-01 5.650729e-02 -1.068222e+01 9.971161e-01 -2.985825e-02 -6.976985e-02 2.203070e+02 +-6.833944e-02 5.883447e-02 -9.959258e-01 9.072871e+01 3.456358e-02 9.978000e-01 5.657348e-02 -1.065304e+01 9.970632e-01 -3.055655e-02 -7.022261e-02 2.202621e+02 +-6.829056e-02 5.814399e-02 -9.959697e-01 8.987537e+01 3.346288e-02 9.978720e-01 5.596061e-02 -1.061699e+01 9.971041e-01 -2.950642e-02 -7.009090e-02 2.202232e+02 +-6.855852e-02 5.647786e-02 -9.960472e-01 8.904787e+01 3.282492e-02 9.979834e-01 5.432830e-02 -1.058572e+01 9.971069e-01 -2.897049e-02 -7.027414e-02 2.201828e+02 +-6.870573e-02 5.779632e-02 -9.959614e-01 8.823404e+01 3.345340e-02 9.978925e-01 5.560064e-02 -1.054672e+01 9.970759e-01 -2.949820e-02 -7.049441e-02 2.201492e+02 +-6.846254e-02 5.995237e-02 -9.958507e-01 8.745840e+01 3.192488e-02 9.978132e-01 5.787576e-02 -1.051504e+01 9.971427e-01 -2.783008e-02 -7.022679e-02 2.201031e+02 +-6.744632e-02 6.135034e-02 -9.958349e-01 8.671465e+01 2.933271e-02 9.977981e-01 5.948464e-02 -1.049284e+01 9.972916e-01 -2.519851e-02 -6.909738e-02 2.200422e+02 +-6.492948e-02 6.306564e-02 -9.958950e-01 8.599798e+01 2.794382e-02 9.977245e-01 6.135964e-02 -1.047093e+01 9.974985e-01 -2.384506e-02 -6.654403e-02 2.199855e+02 +-6.156876e-02 6.469863e-02 -9.960037e-01 8.530890e+01 2.934038e-02 9.975829e-01 6.298752e-02 -1.044371e+01 9.976715e-01 -2.534505e-02 -6.331822e-02 2.199404e+02 +-5.823449e-02 6.610262e-02 -9.961121e-01 8.464740e+01 3.164305e-02 9.974262e-01 6.433993e-02 -1.041398e+01 9.978013e-01 -2.777321e-02 -6.017629e-02 2.198978e+02 +-5.499043e-02 6.802990e-02 -9.961667e-01 8.401524e+01 3.089082e-02 9.973146e-01 6.640307e-02 -1.038697e+01 9.980089e-01 -2.712086e-02 -5.694426e-02 2.198549e+02 +-5.041776e-02 6.941376e-02 -9.963131e-01 8.340474e+01 3.050758e-02 9.972233e-01 6.793337e-02 -1.036095e+01 9.982621e-01 -2.697004e-02 -5.239541e-02 2.198149e+02 +-4.503729e-02 6.815415e-02 -9.966578e-01 8.284858e+01 2.998448e-02 9.973128e-01 6.684401e-02 -1.033884e+01 9.985352e-01 -2.687378e-02 -4.695983e-02 2.197832e+02 +-3.869471e-02 6.491006e-02 -9.971406e-01 8.232202e+01 3.079573e-02 9.974914e-01 6.373785e-02 -1.032295e+01 9.987764e-01 -2.824135e-02 -4.059659e-02 2.197409e+02 +-3.209372e-02 6.164133e-02 -9.975823e-01 8.181146e+01 3.176251e-02 9.976552e-01 6.062400e-02 -1.030473e+01 9.989800e-01 -2.974006e-02 -3.397635e-02 2.197194e+02 +-2.411864e-02 5.974658e-02 -9.979222e-01 8.132495e+01 3.417471e-02 9.976784e-01 5.890603e-02 -1.029169e+01 9.991248e-01 -3.268295e-02 -2.610447e-02 2.196989e+02 +-1.421121e-02 5.893500e-02 -9.981607e-01 8.085138e+01 3.318099e-02 9.977394e-01 5.843773e-02 -1.027763e+01 9.993483e-01 -3.228948e-02 -1.613460e-02 2.196917e+02 +-1.046417e-03 5.914053e-02 -9.982491e-01 8.038656e+01 2.877318e-02 9.978381e-01 5.908602e-02 -1.026264e+01 9.995854e-01 -2.866097e-02 -2.745817e-03 2.196824e+02 +1.551655e-02 5.867051e-02 -9.981568e-01 7.992744e+01 2.418978e-02 9.979628e-01 5.903515e-02 -1.024653e+01 9.995869e-01 -2.506120e-02 1.406571e-02 2.196926e+02 +3.550602e-02 5.814641e-02 -9.976765e-01 7.946687e+01 2.071333e-02 9.980486e-01 5.890527e-02 -1.023212e+01 9.991547e-01 -2.275668e-02 3.423232e-02 2.197241e+02 +5.907426e-02 5.827450e-02 -9.965512e-01 7.900373e+01 1.932157e-02 9.980409e-01 5.950698e-02 -1.022017e+01 9.980665e-01 -2.277025e-02 5.783256e-02 2.197672e+02 +8.593650e-02 5.759922e-02 -9.946343e-01 7.855048e+01 1.963346e-02 9.980356e-01 5.949254e-02 -1.020609e+01 9.961071e-01 -2.464068e-02 8.463681e-02 2.198365e+02 +1.164246e-01 5.545705e-02 -9.916501e-01 7.809421e+01 1.886574e-02 9.981363e-01 5.803472e-02 -1.018650e+01 9.930203e-01 -2.546487e-02 1.151614e-01 2.199124e+02 +1.493213e-01 5.233830e-02 -9.874026e-01 7.766070e+01 1.476016e-02 9.983689e-01 5.515171e-02 -1.016712e+01 9.886785e-01 -2.280954e-02 1.483052e-01 2.200076e+02 +1.854913e-01 4.948339e-02 -9.813992e-01 7.722736e+01 9.956843e-03 9.985853e-01 5.223185e-02 -1.015005e+01 9.825954e-01 -1.946018e-02 1.847362e-01 2.201243e+02 +2.240496e-01 4.793261e-02 -9.733983e-01 7.679460e+01 4.147398e-03 9.987338e-01 5.013482e-02 -1.013374e+01 9.745689e-01 -1.526975e-02 2.235671e-01 2.202395e+02 +2.644706e-01 4.812106e-02 -9.631925e-01 7.637158e+01 -1.905912e-03 9.987784e-01 4.937563e-02 -1.010898e+01 9.643918e-01 -1.122264e-02 2.642393e-01 2.204064e+02 +3.061285e-01 4.751261e-02 -9.508038e-01 7.595662e+01 -6.699001e-03 9.988365e-01 4.775599e-02 -1.008059e+01 9.519666e-01 -8.250028e-03 3.060906e-01 2.205847e+02 +3.483314e-01 4.449797e-02 -9.363147e-01 7.554616e+01 -1.153394e-02 9.990004e-01 4.318619e-02 -1.004834e+01 9.373004e-01 -4.243702e-03 3.484965e-01 2.207577e+02 +3.913789e-01 4.153320e-02 -9.192919e-01 7.515586e+01 -2.067059e-02 9.991257e-01 3.633978e-02 -1.002786e+01 9.199974e-01 4.779691e-03 3.918952e-01 2.209603e+02 +4.347570e-01 3.950985e-02 -8.996807e-01 7.476030e+01 -2.470077e-02 9.991844e-01 3.194333e-02 -1.000949e+01 9.002089e-01 8.335219e-03 4.353783e-01 2.211608e+02 +4.774632e-01 3.946535e-02 -8.777650e-01 7.438263e+01 -2.319707e-02 9.992087e-01 3.230749e-02 -9.995573e+00 8.783455e-01 4.935942e-03 4.780008e-01 2.214286e+02 +5.197986e-01 3.902316e-02 -8.533971e-01 7.401104e+01 -1.999615e-02 9.992382e-01 3.351250e-02 -9.980201e+00 8.540547e-01 -3.550922e-04 5.201829e-01 2.217265e+02 +5.620499e-01 4.208123e-02 -8.260321e-01 7.363107e+01 -2.238675e-02 9.991130e-01 3.566622e-02 -9.966355e+00 8.268003e-01 -1.554018e-03 5.624934e-01 2.220171e+02 +6.033987e-01 4.536908e-02 -7.961481e-01 7.326896e+01 -2.543553e-02 9.989672e-01 3.764936e-02 -9.954741e+00 7.970339e-01 -2.467118e-03 6.039294e-01 2.223547e+02 +6.435110e-01 4.692637e-02 -7.639971e-01 7.292347e+01 -2.854171e-02 9.988959e-01 3.731383e-02 -9.946438e+00 7.649046e-01 -2.206064e-03 6.441398e-01 2.227156e+02 +6.827244e-01 4.587456e-02 -7.292346e-01 7.258370e+01 -3.003232e-02 9.989456e-01 3.472463e-02 -9.937283e+00 7.300586e-01 -1.806744e-03 6.833821e-01 2.230651e+02 +7.210547e-01 4.593251e-02 -6.913540e-01 7.227192e+01 -3.497063e-02 9.989411e-01 2.989517e-02 -9.928401e+00 6.919950e-01 2.621034e-03 7.218974e-01 2.234606e+02 +7.567754e-01 4.322997e-02 -6.522440e-01 7.197887e+01 -3.815822e-02 9.990308e-01 2.194099e-02 -9.923860e+00 6.525603e-01 8.284075e-03 7.576914e-01 2.238724e+02 +7.896629e-01 4.034566e-02 -6.122130e-01 7.167867e+01 -4.249753e-02 9.990357e-01 1.102238e-02 -9.947983e+00 6.120674e-01 1.731357e-02 7.906160e-01 2.243103e+02 +8.201374e-01 3.244719e-02 -5.712459e-01 7.142380e+01 -3.624870e-02 9.993316e-01 4.720557e-03 -9.968415e+00 5.710173e-01 1.683542e-02 8.207653e-01 2.247909e+02 +8.478472e-01 2.088119e-02 -5.298294e-01 7.118452e+01 -2.438723e-02 9.997025e-01 3.743572e-04 -9.986514e+00 5.296796e-01 1.260367e-02 8.481041e-01 2.252667e+02 +8.715615e-01 1.366634e-02 -4.900958e-01 7.097076e+01 -1.648976e-02 9.998630e-01 -1.443339e-03 -1.000790e+01 4.900088e-01 9.339521e-03 8.716674e-01 2.257708e+02 +8.920682e-01 1.198793e-02 -4.517418e-01 7.076482e+01 -1.431331e-02 9.998960e-01 -1.730556e-03 -1.002861e+01 4.516741e-01 8.009695e-03 8.921470e-01 2.262719e+02 +9.103437e-01 1.660495e-02 -4.135200e-01 7.055968e+01 -1.844856e-02 9.998297e-01 -4.652670e-04 -1.005230e+01 4.134418e-01 8.052399e-03 9.104949e-01 2.267553e+02 +9.265644e-01 1.767904e-02 -3.757206e-01 7.038559e+01 -1.937735e-02 9.998119e-01 -7.416230e-04 -1.006762e+01 3.756368e-01 7.967632e-03 9.267327e-01 2.272363e+02 +9.406956e-01 1.345836e-02 -3.389849e-01 7.023832e+01 -1.471168e-02 9.998911e-01 -1.127822e-03 -1.008151e+01 3.389328e-01 6.047975e-03 9.407911e-01 2.277263e+02 +9.528103e-01 7.904519e-03 -3.034636e-01 7.010643e+01 -8.817365e-03 9.999598e-01 -1.638004e-03 -1.009299e+01 3.034384e-01 4.236457e-03 9.528416e-01 2.282124e+02 +9.629685e-01 8.069543e-03 -2.694932e-01 6.998684e+01 -9.370857e-03 9.999498e-01 -3.542581e-03 -1.010913e+01 2.694510e-01 5.936777e-03 9.629957e-01 2.287114e+02 +9.713949e-01 1.111735e-02 -2.372098e-01 6.987704e+01 -1.326168e-02 9.998843e-01 -7.445982e-03 -1.012546e+01 2.370995e-01 1.037879e-02 9.714299e-01 2.292182e+02 +9.784121e-01 1.110201e-02 -2.063652e-01 6.978035e+01 -1.381453e-02 9.998360e-01 -1.170794e-02 -1.014303e+01 2.062014e-01 1.430603e-02 9.784049e-01 2.297174e+02 +9.842544e-01 3.356104e-03 -1.767258e-01 6.971657e+01 -6.735039e-03 9.998057e-01 -1.852327e-02 -1.016163e+01 1.766293e-01 1.942186e-02 9.840857e-01 2.302351e+02 +9.887985e-01 -1.167468e-03 -1.492520e-01 6.966177e+01 -2.544270e-03 9.996923e-01 -2.467558e-02 -1.017931e+01 1.492348e-01 2.477891e-02 9.884912e-01 2.307540e+02 +9.923891e-01 -3.474340e-03 -1.230927e-01 6.961108e+01 5.885996e-05 9.996151e-01 -2.774000e-02 -1.019653e+01 1.231417e-01 2.752162e-02 9.920073e-01 2.312736e+02 +9.948317e-01 -2.181110e-03 -1.015143e-01 6.956616e+01 -5.163834e-04 9.996476e-01 -2.653869e-02 -1.021306e+01 1.015364e-01 2.645395e-02 9.944800e-01 2.318059e+02 +9.963444e-01 -5.409735e-03 -8.525599e-02 6.953310e+01 3.546329e-03 9.997518e-01 -2.199292e-02 -1.023146e+01 8.535380e-02 2.161018e-02 9.961163e-01 2.323432e+02 +9.972570e-01 -8.615302e-03 -7.351458e-02 6.950733e+01 7.499222e-03 9.998526e-01 -1.544431e-02 -1.025272e+01 7.363680e-02 1.485064e-02 9.971745e-01 2.328850e+02 +9.978924e-01 -9.297228e-03 -6.422140e-02 6.947790e+01 8.639287e-03 9.999074e-01 -1.051502e-02 -1.027264e+01 6.431321e-02 9.938032e-03 9.978802e-01 2.334257e+02 +9.983555e-01 -5.058996e-03 -5.710374e-02 6.944334e+01 4.646736e-03 9.999622e-01 -7.349975e-03 -1.029147e+01 5.713876e-02 7.072542e-03 9.983411e-01 2.339672e+02 +9.986160e-01 -4.579204e-03 -5.239411e-02 6.941371e+01 4.221307e-03 9.999670e-01 -6.939495e-03 -1.030773e+01 5.242415e-02 6.708719e-03 9.986023e-01 2.345089e+02 +9.985515e-01 -1.236418e-02 -5.236574e-02 6.939643e+01 1.204967e-02 9.999074e-01 -6.317477e-03 -1.032016e+01 5.243900e-02 5.677335e-03 9.986079e-01 2.350558e+02 +9.980869e-01 -2.190051e-02 -5.781807e-02 6.937884e+01 2.153395e-02 9.997439e-01 -6.955394e-03 -1.033077e+01 5.795559e-02 5.697036e-03 9.983029e-01 2.356015e+02 +9.973940e-01 -2.630845e-02 -6.718002e-02 6.934388e+01 2.575166e-02 9.996266e-01 -9.140766e-03 -1.034321e+01 6.739541e-02 7.386948e-03 9.976989e-01 2.361449e+02 +9.965070e-01 -2.567566e-02 -7.946466e-02 6.929189e+01 2.498963e-02 9.996414e-01 -9.615738e-03 -1.035888e+01 7.968306e-02 7.596357e-03 9.967912e-01 2.366903e+02 +9.951864e-01 -2.569200e-02 -9.457311e-02 6.923010e+01 2.488813e-02 9.996435e-01 -9.669886e-03 -1.037600e+01 9.478783e-02 7.269590e-03 9.954709e-01 2.372320e+02 +9.930185e-01 -2.967120e-02 -1.141664e-01 6.916533e+01 2.845359e-02 9.995197e-01 -1.228038e-02 -1.038807e+01 1.144759e-01 8.946202e-03 9.933857e-01 2.377751e+02 +9.899066e-01 -3.298320e-02 -1.378297e-01 6.908473e+01 3.159505e-02 9.994257e-01 -1.224780e-02 -1.040131e+01 1.381545e-01 7.769443e-03 9.903802e-01 2.383166e+02 +9.859246e-01 -3.060503e-02 -1.643658e-01 6.897871e+01 2.960095e-02 9.995252e-01 -8.555294e-03 -1.041441e+01 1.645495e-01 3.569493e-03 9.863623e-01 2.388478e+02 +9.804132e-01 -2.602558e-02 -1.952247e-01 6.885058e+01 2.553614e-02 9.996613e-01 -5.023915e-03 -1.043138e+01 1.952893e-01 -5.977129e-05 9.807456e-01 2.393772e+02 +9.726654e-01 -2.355779e-02 -2.310131e-01 6.870774e+01 2.300207e-02 9.997224e-01 -5.098975e-03 -1.044887e+01 2.310691e-01 -3.541835e-04 9.729372e-01 2.398978e+02 +9.627454e-01 -2.024061e-02 -2.696509e-01 6.857510e+01 1.874801e-02 9.997913e-01 -8.109850e-03 -1.043437e+01 2.697588e-01 2.752303e-03 9.629239e-01 2.403834e+02 +9.500989e-01 -1.569965e-02 -3.115535e-01 6.841101e+01 1.312643e-02 9.998602e-01 -1.035473e-02 -1.041370e+01 3.116725e-01 5.748430e-03 9.501721e-01 2.408273e+02 +9.341982e-01 -9.426163e-03 -3.566300e-01 6.821683e+01 5.620304e-03 9.999157e-01 -1.170651e-02 -1.040046e+01 3.567103e-01 8.931828e-03 9.341723e-01 2.412894e+02 +9.148738e-01 -2.358564e-04 -4.037400e-01 6.798830e+01 -6.126640e-03 9.998766e-01 -1.446706e-02 -1.033695e+01 4.036935e-01 1.570910e-02 9.147593e-01 2.416933e+02 +8.910773e-01 1.303515e-02 -4.536644e-01 6.772742e+01 -2.192814e-02 9.996566e-01 -1.434758e-02 -1.029006e+01 4.533215e-01 2.273282e-02 8.910571e-01 2.421112e+02 +8.633013e-01 2.784557e-02 -5.039202e-01 6.744470e+01 -3.781492e-02 9.992389e-01 -9.567550e-03 -1.023506e+01 5.032703e-01 2.731538e-02 8.636972e-01 2.424966e+02 +8.315041e-01 3.888847e-02 -5.541558e-01 6.712537e+01 -5.030250e-02 9.987194e-01 -5.392089e-03 -1.019844e+01 5.532365e-01 3.235896e-02 8.323955e-01 2.428311e+02 +7.953479e-01 4.648677e-02 -6.043681e-01 6.680310e+01 -5.825956e-02 9.983014e-01 1.178046e-04 -1.015367e+01 6.033470e-01 3.511652e-02 7.967052e-01 2.431829e+02 +7.551591e-01 5.233082e-02 -6.534495e-01 6.645921e+01 -5.900849e-02 9.981884e-01 1.174570e-02 -1.011992e+01 6.528804e-01 2.968919e-02 7.568789e-01 2.435343e+02 +7.115133e-01 6.001076e-02 -7.001054e-01 6.608635e+01 -6.017287e-02 9.978901e-01 2.438254e-02 -1.006972e+01 7.000915e-01 2.477885e-02 7.136230e-01 2.438073e+02 +6.651519e-01 6.745535e-02 -7.436550e-01 6.570179e+01 -6.066760e-02 9.975007e-01 3.621787e-02 -1.003379e+01 7.442395e-01 2.102538e-02 6.675818e-01 2.441078e+02 +6.162921e-01 7.725151e-02 -7.837195e-01 6.529720e+01 -6.728305e-02 9.967034e-01 4.533616e-02 -1.000031e+01 7.846381e-01 2.479071e-02 6.194581e-01 2.443710e+02 +5.641729e-01 8.038141e-02 -8.217347e-01 6.486954e+01 -6.944687e-02 9.963427e-01 4.978177e-02 -9.961987e+00 8.227308e-01 2.898137e-02 5.676918e-01 2.445565e+02 +5.079535e-01 7.498334e-02 -8.581147e-01 6.444825e+01 -6.404290e-02 9.967342e-01 4.918650e-02 -9.923632e+00 8.590004e-01 2.997169e-02 5.110968e-01 2.447822e+02 +4.498124e-01 6.477630e-02 -8.907710e-01 6.401807e+01 -5.152832e-02 9.975873e-01 4.652368e-02 -9.878884e+00 8.916354e-01 2.497301e-02 4.520648e-01 2.449865e+02 +3.893689e-01 5.828640e-02 -9.192359e-01 6.355563e+01 -4.022251e-02 9.981197e-01 4.625083e-02 -9.838486e+00 9.202032e-01 1.896534e-02 3.909812e-01 2.451196e+02 +3.299005e-01 5.855375e-02 -9.421981e-01 6.308080e+01 -3.619953e-02 9.981251e-01 4.935452e-02 -9.798650e+00 9.433214e-01 1.782505e-02 3.314015e-01 2.452600e+02 +2.739344e-01 6.269287e-02 -9.597029e-01 6.258919e+01 -3.776665e-02 9.978046e-01 5.440190e-02 -9.766015e+00 9.610065e-01 2.134221e-02 2.757007e-01 2.453658e+02 +2.218518e-01 6.583776e-02 -9.728552e-01 6.208369e+01 -4.015829e-02 9.974883e-01 5.834703e-02 -9.729817e+00 9.742530e-01 2.612380e-02 2.239385e-01 2.454135e+02 +1.736747e-01 6.603133e-02 -9.825869e-01 6.158075e+01 -4.052634e-02 9.973836e-01 5.986257e-02 -9.695895e+00 9.839688e-01 2.942404e-02 1.758963e-01 2.454747e+02 +1.293567e-01 6.456627e-02 -9.894939e-01 6.106677e+01 -3.758707e-02 9.974800e-01 6.017362e-02 -9.663459e+00 9.908854e-01 2.940831e-02 1.314576e-01 2.455028e+02 +8.984261e-02 6.148548e-02 -9.940563e-01 6.054783e+01 -3.581451e-02 9.976465e-01 5.847064e-02 -9.629494e+00 9.953118e-01 3.034849e-02 9.183323e-02 2.455341e+02 +5.669005e-02 5.799537e-02 -9.967060e-01 6.002194e+01 -3.639654e-02 9.977679e-01 5.598703e-02 -9.593959e+00 9.977281e-01 3.310274e-02 5.867434e-02 2.455451e+02 +2.974916e-02 5.587639e-02 -9.979944e-01 5.948324e+01 -4.025348e-02 9.976933e-01 5.465963e-02 -9.559976e+00 9.987465e-01 3.854667e-02 3.192976e-02 2.455337e+02 +9.653026e-03 5.357301e-02 -9.985173e-01 5.893583e+01 -4.471565e-02 9.975880e-01 5.309087e-02 -9.528225e+00 9.989531e-01 4.413686e-02 1.202529e-02 2.455202e+02 +-5.367240e-03 5.187898e-02 -9.986390e-01 5.837363e+01 -4.758073e-02 9.975090e-01 5.207601e-02 -9.496583e+00 9.988529e-01 4.779547e-02 -2.885431e-03 2.455013e+02 +-1.809084e-02 5.039661e-02 -9.985655e-01 5.778293e+01 -4.670382e-02 9.975961e-01 5.119382e-02 -9.482206e+00 9.987449e-01 4.756295e-02 -1.569364e-02 2.454620e+02 +-2.801364e-02 4.863872e-02 -9.984235e-01 5.717641e+01 -4.459136e-02 9.977604e-01 4.985756e-02 -9.440360e+00 9.986124e-01 4.591776e-02 -2.578203e-02 2.454243e+02 +-3.400568e-02 4.762773e-02 -9.982862e-01 5.655779e+01 -4.499580e-02 9.977780e-01 4.913624e-02 -9.402285e+00 9.984082e-01 4.658959e-02 -3.178707e-02 2.453877e+02 +-3.713073e-02 4.791171e-02 -9.981612e-01 5.591578e+01 -4.708729e-02 9.976566e-01 4.963910e-02 -9.362804e+00 9.982004e-01 4.884384e-02 -3.478768e-02 2.453431e+02 +-3.834668e-02 4.829377e-02 -9.980968e-01 5.525735e+01 -4.817210e-02 9.975808e-01 5.011958e-02 -9.324777e+00 9.981026e-01 5.000233e-02 -3.592750e-02 2.453053e+02 +-3.727636e-02 4.911273e-02 -9.980974e-01 5.457570e+01 -4.738024e-02 9.975814e-01 5.085688e-02 -9.285086e+00 9.981811e-01 4.918585e-02 -3.485923e-02 2.452676e+02 +-3.624355e-02 4.934787e-02 -9.981239e-01 5.387733e+01 -4.586641e-02 9.976454e-01 5.098971e-02 -9.249048e+00 9.982898e-01 4.762840e-02 -3.389480e-02 2.452345e+02 +-3.524759e-02 4.817378e-02 -9.982169e-01 5.315948e+01 -4.360048e-02 9.978123e-01 4.969382e-02 -9.212307e+00 9.984270e-01 4.527432e-02 -3.307008e-02 2.452012e+02 +-3.403347e-02 4.584723e-02 -9.983686e-01 5.242232e+01 -4.039077e-02 9.980680e-01 4.721032e-02 -9.177032e+00 9.986041e-01 4.193161e-02 -3.211592e-02 2.451719e+02 +-3.339829e-02 4.455994e-02 -9.984483e-01 5.166476e+01 -3.926779e-02 9.981757e-01 4.586130e-02 -9.139110e+00 9.986704e-01 4.073855e-02 -3.158759e-02 2.451412e+02 +-3.258092e-02 4.383273e-02 -9.985075e-01 5.088664e+01 -3.935916e-02 9.982066e-01 4.510381e-02 -9.096874e+00 9.986938e-01 4.076993e-02 -3.079727e-02 2.451114e+02 +-3.209051e-02 4.426563e-02 -9.985043e-01 5.008793e+01 -3.958302e-02 9.981787e-01 4.552334e-02 -9.057067e+00 9.987008e-01 4.098468e-02 -3.027990e-02 2.450819e+02 +-3.183461e-02 4.547036e-02 -9.984583e-01 4.926867e+01 -3.771969e-02 9.981983e-01 4.666117e-02 -9.011002e+00 9.987811e-01 3.914698e-02 -3.006212e-02 2.450587e+02 +-3.111467e-02 4.540085e-02 -9.984842e-01 4.843438e+01 -3.459195e-02 9.983205e-01 4.647136e-02 -8.968180e+00 9.989170e-01 3.598545e-02 -2.949191e-02 2.450351e+02 +-3.106506e-02 4.496827e-02 -9.985053e-01 4.758164e+01 -3.206073e-02 9.984285e-01 4.596228e-02 -8.929268e+00 9.990030e-01 3.344062e-02 -2.957452e-02 2.450089e+02 +-3.142502e-02 4.461540e-02 -9.985099e-01 4.670967e+01 -3.024418e-02 9.985033e-01 4.556696e-02 -8.895416e+00 9.990484e-01 3.163105e-02 -3.002863e-02 2.449855e+02 +-3.335764e-02 4.572485e-02 -9.983970e-01 4.582014e+01 -2.847243e-02 9.985040e-01 4.668105e-02 -8.854608e+00 9.990378e-01 2.998396e-02 -3.200584e-02 2.449638e+02 +-3.606580e-02 4.821853e-02 -9.981855e-01 4.491897e+01 -2.625094e-02 9.984449e-01 4.917955e-02 -8.803572e+00 9.990045e-01 2.797700e-02 -3.474393e-02 2.449376e+02 +-3.918556e-02 5.047400e-02 -9.979564e-01 4.400529e+01 -2.489504e-02 9.983641e-01 5.147215e-02 -8.749626e+00 9.989217e-01 2.686113e-02 -3.786490e-02 2.449075e+02 +-4.252786e-02 4.847058e-02 -9.979189e-01 4.306932e+01 -2.525220e-02 9.984512e-01 4.957261e-02 -8.707462e+00 9.987761e-01 2.730787e-02 -4.123800e-02 2.448643e+02 +-4.569615e-02 4.364905e-02 -9.980013e-01 4.212282e+01 -2.667135e-02 9.986354e-01 4.489801e-02 -8.671159e+00 9.985992e-01 2.866971e-02 -4.446962e-02 2.448172e+02 +-4.823405e-02 4.003240e-02 -9.980335e-01 4.115791e+01 -2.577903e-02 9.988138e-01 4.130958e-02 -8.634776e+00 9.985033e-01 2.772086e-02 -4.714484e-02 2.447715e+02 +-5.031424e-02 4.171680e-02 -9.978618e-01 4.017207e+01 -2.456477e-02 9.987733e-01 4.299352e-02 -8.596479e+00 9.984313e-01 2.667543e-02 -4.922775e-02 2.447238e+02 +-5.181400e-02 4.792876e-02 -9.975060e-01 3.916472e+01 -2.317078e-02 9.985210e-01 4.918112e-02 -8.559737e+00 9.983879e-01 2.566126e-02 -5.062683e-02 2.446724e+02 +-5.301383e-02 5.443536e-02 -9.971090e-01 3.813727e+01 -2.124554e-02 9.982256e-01 5.562590e-02 -8.510418e+00 9.983677e-01 2.413306e-02 -5.176325e-02 2.446196e+02 +-5.383321e-02 5.468975e-02 -9.970512e-01 3.710263e+01 -1.771139e-02 9.982896e-01 5.571398e-02 -8.453846e+00 9.983928e-01 2.065843e-02 -5.277250e-02 2.445684e+02 +-5.486648e-02 5.308811e-02 -9.970814e-01 3.605706e+01 -1.767946e-02 9.983774e-01 5.412997e-02 -8.397715e+00 9.983371e-01 2.059779e-02 -5.383888e-02 2.445107e+02 +-5.549851e-02 5.048846e-02 -9.971815e-01 3.499762e+01 -1.916674e-02 9.984828e-01 5.162109e-02 -8.342557e+00 9.982747e-01 2.197761e-02 -5.444660e-02 2.444496e+02 +-5.561886e-02 4.957916e-02 -9.972204e-01 3.392407e+01 -1.986287e-02 9.985138e-01 5.075131e-02 -8.289686e+00 9.982544e-01 2.263039e-02 -5.455141e-02 2.443860e+02 +-5.506402e-02 4.947618e-02 -9.972563e-01 3.284010e+01 -2.337642e-02 9.984339e-01 5.082536e-02 -8.240889e+00 9.982091e-01 2.611093e-02 -5.382120e-02 2.443182e+02 +-5.440495e-02 4.825164e-02 -9.973525e-01 3.175524e+01 -2.817307e-02 9.983599e-01 4.983721e-02 -8.195062e+00 9.981214e-01 3.080987e-02 -5.295632e-02 2.442483e+02 +-5.404230e-02 4.645458e-02 -9.974575e-01 3.067633e+01 -2.935109e-02 9.984117e-01 4.808927e-02 -8.137184e+00 9.981071e-01 3.187532e-02 -5.259296e-02 2.441839e+02 +-5.373800e-02 4.654161e-02 -9.974699e-01 2.959544e+01 -3.168074e-02 9.983309e-01 4.828857e-02 -8.086906e+00 9.980523e-01 3.419551e-02 -5.217383e-02 2.441190e+02 +-5.263858e-02 4.693780e-02 -9.975099e-01 2.851574e+01 -3.093755e-02 9.983386e-01 4.860938e-02 -8.039974e+00 9.981342e-01 3.341924e-02 -5.109898e-02 2.440567e+02 +-5.237234e-02 4.706576e-02 -9.975179e-01 2.743854e+01 -2.944567e-02 9.983816e-01 4.865250e-02 -7.979478e+00 9.981934e-01 3.192062e-02 -5.090170e-02 2.439942e+02 +-5.184967e-02 4.868328e-02 -9.974676e-01 2.635603e+01 -2.659324e-02 9.983895e-01 5.011064e-02 -7.929510e+00 9.983007e-01 2.912411e-02 -5.047152e-02 2.439385e+02 +-5.165916e-02 5.048031e-02 -9.973882e-01 2.527991e+01 -1.851375e-02 9.985016e-01 5.149558e-02 -7.868716e+00 9.984931e-01 2.112561e-02 -5.064717e-02 2.438910e+02 +-5.210805e-02 5.053857e-02 -9.973619e-01 2.420857e+01 -1.590955e-02 9.985498e-01 5.142999e-02 -7.813927e+00 9.985147e-01 1.854750e-02 -5.122844e-02 2.438374e+02 +-5.312255e-02 5.067353e-02 -9.973015e-01 2.313628e+01 -1.281644e-02 9.985948e-01 5.142194e-02 -7.757005e+00 9.985057e-01 1.551353e-02 -5.239844e-02 2.437781e+02 +-5.589718e-02 5.203177e-02 -9.970799e-01 2.206412e+01 -9.577439e-03 9.985673e-01 5.264632e-02 -7.706868e+00 9.983906e-01 1.249226e-02 -5.531876e-02 2.437192e+02 +-5.861000e-02 5.649529e-02 -9.966811e-01 2.099349e+01 -1.219935e-02 9.982822e-01 5.730344e-02 -7.661799e+00 9.982064e-01 1.551742e-02 -5.782011e-02 2.436491e+02 +-6.151420e-02 5.972326e-02 -9.963178e-01 1.992389e+01 -1.433032e-02 9.980524e-01 6.071203e-02 -7.612126e+00 9.980033e-01 1.801221e-02 -6.053854e-02 2.435746e+02 +-6.476204e-02 5.896297e-02 -9.961573e-01 1.886942e+01 -1.796815e-02 9.980221e-01 6.024150e-02 -7.563301e+00 9.977389e-01 2.180047e-02 -6.357448e-02 2.434972e+02 +-6.683295e-02 5.462737e-02 -9.962677e-01 1.781625e+01 -2.068253e-02 9.982097e-01 5.612132e-02 -7.513550e+00 9.975498e-01 2.435609e-02 -6.558347e-02 2.434157e+02 +-6.849796e-02 5.110422e-02 -9.963415e-01 1.677167e+01 -2.388933e-02 9.983168e-01 5.284792e-02 -7.476025e+00 9.973652e-01 2.742191e-02 -6.716182e-02 2.433337e+02 +-6.990284e-02 4.958745e-02 -9.963206e-01 1.572923e+01 -2.562939e-02 9.983448e-01 5.148638e-02 -7.445710e+00 9.972245e-01 2.913413e-02 -6.851624e-02 2.432513e+02 +-7.124759e-02 5.147227e-02 -9.961297e-01 1.469270e+01 -2.839208e-02 9.981583e-01 5.360783e-02 -7.414939e+00 9.970545e-01 3.210162e-02 -6.965496e-02 2.431677e+02 +-7.211286e-02 5.602313e-02 -9.958219e-01 1.366194e+01 -3.153355e-02 9.977941e-01 5.841761e-02 -7.392199e+00 9.968978e-01 3.561446e-02 -7.018717e-02 2.430825e+02 +-7.330661e-02 5.849357e-02 -9.955926e-01 1.264677e+01 -3.617651e-02 9.974656e-01 6.126733e-02 -7.360999e+00 9.966531e-01 4.050837e-02 -7.100472e-02 2.429949e+02 +-7.416172e-02 5.798562e-02 -9.955590e-01 1.164596e+01 -3.999730e-02 9.973319e-01 6.106838e-02 -7.332324e+00 9.964438e-01 4.434860e-02 -7.164457e-02 2.429079e+02 +-7.529792e-02 5.614125e-02 -9.955794e-01 1.066639e+01 -4.620619e-02 9.971449e-01 5.972422e-02 -7.304335e+00 9.960899e-01 5.049904e-02 -7.248886e-02 2.428183e+02 +-7.577645e-02 5.569604e-02 -9.955681e-01 9.697182e+00 -4.966858e-02 9.969885e-01 5.955598e-02 -7.281012e+00 9.958870e-01 5.396139e-02 -7.278190e-02 2.427289e+02 +-7.635941e-02 5.575849e-02 -9.955201e-01 8.749169e+00 -5.306604e-02 9.967928e-01 5.990011e-02 -7.254310e+00 9.956672e-01 5.740224e-02 -7.315562e-02 2.426424e+02 +-7.629943e-02 5.520812e-02 -9.955554e-01 7.814747e+00 -5.685215e-02 9.966007e-01 5.962325e-02 -7.229902e+00 9.954628e-01 6.114867e-02 -7.290136e-02 2.425552e+02 +-7.604025e-02 5.507384e-02 -9.955826e-01 6.904974e+00 -5.880584e-02 9.964877e-01 5.961537e-02 -7.200265e+00 9.953691e-01 6.307923e-02 -7.253451e-02 2.424742e+02 +-7.602500e-02 5.726563e-02 -9.954601e-01 6.011306e+00 -5.953250e-02 9.963077e-01 6.186100e-02 -7.168860e+00 9.953271e-01 6.396520e-02 -7.233512e-02 2.423982e+02 +-7.604756e-02 5.943514e-02 -9.953312e-01 5.139292e+00 -6.003481e-02 9.961379e-01 6.407023e-02 -7.146637e+00 9.952952e-01 6.462690e-02 -7.218568e-02 2.423252e+02 +-7.603218e-02 5.905873e-02 -9.953548e-01 4.296050e+00 -6.128090e-02 9.960805e-01 6.378287e-02 -7.127999e+00 9.952204e-01 6.584578e-02 -7.211500e-02 2.422525e+02 +-7.609936e-02 5.835176e-02 -9.953914e-01 3.474518e+00 -6.098669e-02 9.961447e-01 6.305847e-02 -7.110408e+00 9.952334e-01 6.550432e-02 -7.224728e-02 2.421822e+02 +-7.642529e-02 5.749494e-02 -9.954163e-01 2.679849e+00 -5.872327e-02 9.963435e-01 6.205712e-02 -7.089124e+00 9.953445e-01 6.319683e-02 -7.276955e-02 2.421187e+02 +-7.708117e-02 5.719954e-02 -9.953827e-01 1.910133e+00 -5.838389e-02 9.963808e-01 6.177808e-02 -7.073093e+00 9.953139e-01 6.287623e-02 -7.346266e-02 2.420550e+02 +-7.690222e-02 5.824151e-02 -9.953361e-01 1.168286e+00 -5.871979e-02 9.962950e-01 6.283447e-02 -7.052345e+00 9.953080e-01 6.327804e-02 -7.319736e-02 2.419926e+02 +-7.665759e-02 5.793452e-02 -9.953729e-01 4.503087e-01 -6.032739e-02 9.962119e-01 6.262942e-02 -7.034578e+00 9.952307e-01 6.484926e-02 -7.287216e-02 2.419307e+02 +-7.539126e-02 5.839331e-02 -9.954428e-01 -2.363936e-01 -6.095442e-02 9.961471e-01 6.305110e-02 -7.012744e+00 9.952892e-01 6.543014e-02 -7.154145e-02 2.418736e+02 +-7.317061e-02 6.042684e-02 -9.954872e-01 -8.987715e-01 -6.091835e-02 9.960281e-01 6.493733e-02 -6.989223e+00 9.954571e-01 6.539494e-02 -6.919888e-02 2.418210e+02 +-6.993858e-02 6.236856e-02 -9.955997e-01 -1.528966e+00 -6.029823e-02 9.959543e-01 6.662660e-02 -6.964258e+00 9.957272e-01 6.469267e-02 -6.589491e-02 2.417760e+02 +-6.590134e-02 6.434813e-02 -9.957492e-01 -2.127276e+00 -6.165501e-02 9.957490e-01 6.842863e-02 -6.941613e+00 9.959195e-01 6.590245e-02 -6.165381e-02 2.417339e+02 +-6.055624e-02 6.632598e-02 -9.959588e-01 -2.696521e+00 -6.201134e-02 9.956125e-01 7.007335e-02 -6.920228e+00 9.962366e-01 6.600410e-02 -5.617759e-02 2.416984e+02 +-5.450908e-02 6.754004e-02 -9.962265e-01 -3.228819e+00 -6.212506e-02 9.955474e-01 7.089322e-02 -6.897384e+00 9.965787e-01 6.575494e-02 -5.007044e-02 2.416707e+02 +-4.734800e-02 6.735504e-02 -9.966050e-01 -3.728376e+00 -6.101841e-02 9.956656e-01 7.019051e-02 -6.876520e+00 9.970130e-01 6.413463e-02 -4.303287e-02 2.416522e+02 +-3.964776e-02 6.573368e-02 -9.970492e-01 -4.190561e+00 -5.955881e-02 9.959042e-01 6.802656e-02 -6.860267e+00 9.974371e-01 6.208016e-02 -3.557035e-02 2.416401e+02 +-3.100336e-02 6.415434e-02 -9.974583e-01 -4.618300e+00 -5.863363e-02 9.961027e-01 6.588964e-02 -6.851022e+00 9.977980e-01 6.052740e-02 -2.712093e-02 2.416335e+02 +-2.180203e-02 6.241744e-02 -9.978120e-01 -5.015158e+00 -5.842099e-02 9.962642e-01 6.359712e-02 -6.841571e+00 9.980539e-01 5.967970e-02 -1.807409e-02 2.416281e+02 +-1.280422e-02 6.166828e-02 -9.980146e-01 -5.386511e+00 -5.856867e-02 9.963365e-01 6.231601e-02 -6.836364e+00 9.982012e-01 5.925029e-02 -9.145484e-03 2.416295e+02 +-3.636745e-03 6.104361e-02 -9.981285e-01 -5.727634e+00 -5.871357e-02 9.964001e-01 6.115184e-02 -6.828673e+00 9.982682e-01 5.882608e-02 -3.956605e-05 2.416356e+02 +5.746315e-03 5.629747e-02 -9.983975e-01 -6.042761e+00 -5.687366e-02 9.968163e-01 5.588098e-02 -6.828111e+00 9.983648e-01 5.646141e-02 8.929861e-03 2.416461e+02 +1.550660e-02 5.049864e-02 -9.986038e-01 -6.326933e+00 -5.481396e-02 9.972649e-01 4.957978e-02 -6.826022e+00 9.983761e-01 5.396861e-02 1.823221e-02 2.416600e+02 +2.627633e-02 4.791057e-02 -9.985060e-01 -6.594910e+00 -5.325786e-02 9.974993e-01 4.646077e-02 -6.821755e+00 9.982350e-01 5.195747e-02 2.876223e-02 2.416763e+02 +3.687121e-02 4.777290e-02 -9.981775e-01 -6.845250e+00 -5.271683e-02 9.975588e-01 4.579602e-02 -6.815427e+00 9.979285e-01 5.093219e-02 3.929963e-02 2.416926e+02 +4.790024e-02 4.620213e-02 -9.977830e-01 -7.082572e+00 -5.266346e-02 9.976571e-01 4.366811e-02 -6.808075e+00 9.974628e-01 5.045499e-02 5.022118e-02 2.417122e+02 +6.031997e-02 4.299534e-02 -9.972527e-01 -7.316062e+00 -5.234086e-02 9.978337e-01 3.985450e-02 -6.803870e+00 9.968058e-01 4.979303e-02 6.243970e-02 2.417365e+02 +7.412221e-02 3.951940e-02 -9.964658e-01 -7.544603e+00 -5.244539e-02 9.979862e-01 3.567855e-02 -6.799465e+00 9.958691e-01 4.961546e-02 7.604555e-02 2.417619e+02 +9.102819e-02 3.663909e-02 -9.951741e-01 -7.774661e+00 -5.254989e-02 9.981073e-01 3.194037e-02 -6.788214e+00 9.944608e-01 4.938881e-02 9.278128e-02 2.417928e+02 +1.093310e-01 3.487800e-02 -9.933933e-01 -7.999830e+00 -5.333978e-02 9.981501e-01 2.917454e-02 -6.777323e+00 9.925732e-01 4.979769e-02 1.109892e-01 2.418246e+02 +1.288159e-01 3.374409e-02 -9.910943e-01 -8.225849e+00 -5.425893e-02 9.981636e-01 2.693257e-02 -6.762931e+00 9.901830e-01 5.030637e-02 1.304103e-01 2.418676e+02 +1.485469e-01 3.491618e-02 -9.882888e-01 -8.447696e+00 -5.256606e-02 9.982424e-01 2.736679e-02 -6.755170e+00 9.875072e-01 4.788519e-02 1.501212e-01 2.419199e+02 +1.695803e-01 3.891885e-02 -9.847476e-01 -8.668434e+00 -5.107783e-02 9.982240e-01 3.065552e-02 -6.750084e+00 9.841918e-01 4.510020e-02 1.712670e-01 2.419718e+02 +1.917481e-01 4.259726e-02 -9.805194e-01 -8.884203e+00 -5.093003e-02 9.981434e-01 3.340316e-02 -6.748442e+00 9.801218e-01 4.353289e-02 1.935616e-01 2.420306e+02 +2.146542e-01 4.198544e-02 -9.757873e-01 -9.095550e+00 -5.280999e-02 9.981130e-01 3.132890e-02 -6.745895e+00 9.752613e-01 4.480643e-02 2.164664e-01 2.420944e+02 +2.406255e-01 3.622996e-02 -9.699417e-01 -9.310473e+00 -5.296199e-02 9.983044e-01 2.415045e-02 -6.737931e+00 9.691720e-01 4.555882e-02 2.421363e-01 2.421598e+02 +2.696716e-01 2.958224e-02 -9.624979e-01 -9.536865e+00 -5.065029e-02 9.985801e-01 1.650008e-02 -6.731274e+00 9.616193e-01 4.430118e-02 2.707871e-01 2.422532e+02 +3.002726e-01 2.658295e-02 -9.534830e-01 -9.780101e+00 -4.672566e-02 9.988214e-01 1.313206e-02 -6.722858e+00 9.527082e-01 4.060892e-02 3.011608e-01 2.423536e+02 +3.337358e-01 2.790531e-02 -9.422536e-01 -1.004028e+01 -4.112212e-02 9.990412e-01 1.502211e-02 -6.717894e+00 9.417692e-01 3.373405e-02 3.345633e-01 2.424896e+02 +3.703076e-01 3.162716e-02 -9.283707e-01 -1.031625e+01 -3.917736e-02 9.990627e-01 1.840843e-02 -6.710409e+00 9.280826e-01 2.955433e-02 3.711995e-01 2.426457e+02 +4.095053e-01 3.740001e-02 -9.115408e-01 -1.060398e+01 -4.021440e-02 9.989282e-01 2.291934e-02 -6.704932e+00 9.114210e-01 2.727148e-02 4.105704e-01 2.427928e+02 +4.502066e-01 4.272660e-02 -8.919016e-01 -1.090063e+01 -4.398185e-02 9.987032e-01 2.564215e-02 -6.698509e+00 8.918406e-01 2.768322e-02 4.515019e-01 2.429867e+02 +4.929454e-01 4.646108e-02 -8.688189e-01 -1.120097e+01 -4.773396e-02 9.985134e-01 2.631364e-02 -6.692741e+00 8.687498e-01 2.850097e-02 4.944304e-01 2.432065e+02 +5.365411e-01 4.893406e-02 -8.424542e-01 -1.149833e+01 -4.869405e-02 9.984492e-01 2.698285e-02 -6.689810e+00 8.424681e-01 2.654509e-02 5.380918e-01 2.434202e+02 +5.807729e-01 4.947012e-02 -8.125611e-01 -1.178884e+01 -4.622707e-02 9.985453e-01 2.775266e-02 -6.688949e+00 8.127520e-01 2.144433e-02 5.822149e-01 2.436969e+02 +6.259864e-01 4.765468e-02 -7.783766e-01 -1.207090e+01 -4.353656e-02 9.987100e-01 2.613121e-02 -6.688420e+00 7.786178e-01 1.753006e-02 6.272535e-01 2.439575e+02 +6.712781e-01 4.527160e-02 -7.398218e-01 -1.234428e+01 -4.350012e-02 9.988188e-01 2.165042e-02 -6.687590e+00 7.399280e-01 1.764888e-02 6.724544e-01 2.442799e+02 +7.164322e-01 4.036880e-02 -6.964878e-01 -1.260568e+01 -4.319203e-02 9.989759e-01 1.347232e-02 -6.684619e+00 6.963184e-01 2.043072e-02 7.174421e-01 2.446299e+02 +7.602273e-01 3.804431e-02 -6.485423e-01 -1.285639e+01 -4.500172e-02 9.989698e-01 5.849400e-03 -6.678676e+00 6.480966e-01 2.473864e-02 7.611561e-01 2.449548e+02 +8.015137e-01 3.803052e-02 -5.967659e-01 -1.309955e+01 -4.685767e-02 9.989013e-01 7.233622e-04 -6.675619e+00 5.961377e-01 2.738327e-02 8.024150e-01 2.453621e+02 +8.393979e-01 3.816677e-02 -5.421757e-01 -1.332519e+01 -4.576826e-02 9.989519e-01 -5.367554e-04 -6.676025e+00 5.415869e-01 2.526499e-02 8.402650e-01 2.458054e+02 +8.731126e-01 3.489720e-02 -4.862681e-01 -1.352690e+01 -4.098398e-02 9.991580e-01 -1.883348e-03 -6.678304e+00 4.857929e-01 2.157358e-02 8.738076e-01 2.462275e+02 +9.023501e-01 3.145702e-02 -4.298544e-01 -1.371079e+01 -3.584909e-02 9.993549e-01 -2.120943e-03 -6.687935e+00 4.295104e-01 1.732372e-02 9.028957e-01 2.467307e+02 +9.270626e-01 2.885887e-02 -3.737943e-01 -1.387609e+01 -3.287392e-02 9.994499e-01 -4.369190e-03 -6.693307e+00 3.734625e-01 1.633859e-02 9.275013e-01 2.472121e+02 +9.474538e-01 2.683863e-02 -3.187649e-01 -1.402343e+01 -3.171953e-02 9.994455e-01 -1.012986e-02 -6.696054e+00 3.183163e-01 1.970865e-02 9.477796e-01 2.477627e+02 +9.639915e-01 2.646981e-02 -2.646127e-01 -1.415234e+01 -3.171795e-02 9.993754e-01 -1.557958e-02 -6.699757e+00 2.640350e-01 2.341155e-02 9.642289e-01 2.483368e+02 +9.767452e-01 2.793246e-02 -2.125761e-01 -1.426228e+01 -3.226000e-02 9.993363e-01 -1.691570e-02 -6.709090e+00 2.119625e-01 2.338004e-02 9.769980e-01 2.489039e+02 +9.859099e-01 2.853811e-02 -1.648250e-01 -1.434841e+01 -3.178168e-02 9.993490e-01 -1.707476e-02 -6.721040e+00 1.642304e-01 2.207259e-02 9.861750e-01 2.495347e+02 +9.919632e-01 2.603261e-02 -1.238200e-01 -1.441196e+01 -2.840814e-02 9.994439e-01 -1.745832e-02 -6.733875e+00 1.232967e-01 2.083550e-02 9.921511e-01 2.501838e+02 +9.956664e-01 2.164276e-02 -9.044382e-02 -1.445672e+01 -2.336493e-02 9.995645e-01 -1.802593e-02 -6.746994e+00 9.001429e-02 2.006102e-02 9.957384e-01 2.508432e+02 +9.977697e-01 1.629015e-02 -6.473238e-02 -1.448790e+01 -1.752270e-02 9.996749e-01 -1.851865e-02 -6.761766e+00 6.440967e-02 1.961163e-02 9.977308e-01 2.515375e+02 +9.988656e-01 1.161639e-02 -4.618058e-02 -1.451196e+01 -1.248109e-02 9.997513e-01 -1.848032e-02 -6.778409e+00 4.595442e-02 1.903574e-02 9.987621e-01 2.522550e+02 +9.993719e-01 9.193214e-03 -3.422423e-02 -1.453435e+01 -9.833383e-03 9.997789e-01 -1.858401e-02 -6.795428e+00 3.404582e-02 1.890888e-02 9.992413e-01 2.529941e+02 +9.996020e-01 6.369113e-03 -2.748533e-02 -1.455485e+01 -6.904773e-03 9.997872e-01 -1.943824e-02 -6.812917e+00 2.735567e-02 1.962028e-02 9.994331e-01 2.537579e+02 +9.996962e-01 4.640308e-03 -2.420992e-02 -1.457516e+01 -5.141249e-03 9.997731e-01 -2.067049e-02 -6.830954e+00 2.410850e-02 2.078868e-02 9.994931e-01 2.545436e+02 +9.997404e-01 4.984347e-03 -2.223427e-02 -1.459703e+01 -5.464946e-03 9.997516e-01 -2.160708e-02 -6.852364e+00 2.212104e-02 2.172297e-02 9.995192e-01 2.553502e+02 +9.997598e-01 5.217851e-03 -2.128954e-02 -1.461988e+01 -5.669558e-03 9.997589e-01 -2.121241e-02 -6.874307e+00 2.117372e-02 2.132801e-02 9.995482e-01 2.561819e+02 +9.997607e-01 5.746823e-03 -2.111051e-02 -1.464407e+01 -6.153143e-03 9.997961e-01 -1.923301e-02 -6.896091e+00 2.099568e-02 1.935830e-02 9.995921e-01 2.570344e+02 +9.997560e-01 5.119028e-03 -2.149187e-02 -1.466709e+01 -5.466354e-03 9.998549e-01 -1.613329e-02 -6.918247e+00 2.140616e-02 1.624683e-02 9.996388e-01 2.579107e+02 +9.997295e-01 5.266340e-03 -2.265540e-02 -1.468821e+01 -5.583176e-03 9.998872e-01 -1.394454e-02 -6.939815e+00 2.257941e-02 1.406725e-02 9.996460e-01 2.588052e+02 +9.996915e-01 4.827160e-03 -2.436772e-02 -1.471049e+01 -5.177702e-03 9.998837e-01 -1.434295e-02 -6.961615e+00 2.429565e-02 1.446469e-02 9.996001e-01 2.597176e+02 +9.996289e-01 3.198870e-03 -2.705216e-02 -1.473599e+01 -3.683048e-03 9.998336e-01 -1.786711e-02 -6.981897e+00 2.699050e-02 1.796011e-02 9.994743e-01 2.606496e+02 +9.995480e-01 3.214811e-03 -2.989201e-02 -1.476705e+01 -3.957523e-03 9.996841e-01 -2.482061e-02 -7.003600e+00 2.980277e-02 2.492768e-02 9.992449e-01 2.616006e+02 +9.994506e-01 5.468723e-03 -3.269174e-02 -1.480748e+01 -6.466633e-03 9.995139e-01 -3.049744e-02 -7.028589e+00 3.250907e-02 3.069209e-02 9.990000e-01 2.625760e+02 +9.993656e-01 7.749248e-03 -3.476113e-02 -1.484952e+01 -8.832100e-03 9.994770e-01 -3.110661e-02 -7.051911e+00 3.450189e-02 3.139389e-02 9.989114e-01 2.635759e+02 +9.993246e-01 9.737354e-03 -3.543353e-02 -1.489391e+01 -1.051452e-02 9.997068e-01 -2.181314e-02 -7.076486e+00 3.521073e-02 2.217097e-02 9.991339e-01 2.646079e+02 +9.993294e-01 9.145133e-03 -3.545603e-02 -1.492906e+01 -9.575942e-03 9.998821e-01 -1.199979e-02 -7.097279e+00 3.534211e-02 1.233127e-02 9.992991e-01 2.656633e+02 +9.993448e-01 6.130598e-03 -3.567262e-02 -1.495748e+01 -6.461052e-03 9.999372e-01 -9.155627e-03 -7.110536e+00 3.561425e-02 9.380110e-03 9.993215e-01 2.667298e+02 +9.993301e-01 1.536956e-03 -3.656730e-02 -1.498774e+01 -2.109735e-03 9.998756e-01 -1.563027e-02 -7.122595e+00 3.653872e-02 1.569695e-02 9.992089e-01 2.678080e+02 +9.992988e-01 -7.298224e-04 -3.743566e-02 -1.502077e+01 -2.002828e-04 9.996915e-01 -2.483567e-02 -7.139046e+00 3.744224e-02 2.482575e-02 9.989903e-01 2.689020e+02 +9.992740e-01 -1.800961e-03 -3.805628e-02 -1.505963e+01 6.541212e-04 9.995459e-01 -3.012636e-02 -7.166925e+00 3.809325e-02 3.007959e-02 9.988213e-01 2.700156e+02 +9.992704e-01 2.910066e-04 -3.819373e-02 -1.509872e+01 -1.408505e-03 9.995715e-01 -2.923505e-02 -7.199147e+00 3.816885e-02 2.926751e-02 9.988426e-01 2.711538e+02 +9.992604e-01 2.282914e-03 -3.838555e-02 -1.514305e+01 -3.126073e-03 9.997548e-01 -2.191989e-02 -7.232552e+00 3.832610e-02 2.202367e-02 9.990225e-01 2.723074e+02 +9.992436e-01 3.586591e-03 -3.872303e-02 -1.518271e+01 -4.052840e-03 9.999201e-01 -1.196885e-02 -7.258803e+00 3.867701e-02 1.211673e-02 9.991782e-01 2.734772e+02 +9.992329e-01 4.283696e-03 -3.892800e-02 -1.522418e+01 -4.557529e-03 9.999655e-01 -6.948327e-03 -7.277390e+00 3.889689e-02 7.120412e-03 9.992178e-01 2.746540e+02 +9.992252e-01 1.699934e-03 -3.932040e-02 -1.526136e+01 -2.057426e-03 9.999569e-01 -9.053075e-03 -7.291634e+00 3.930332e-02 9.126959e-03 9.991856e-01 2.758308e+02 +9.991962e-01 6.158513e-04 -4.008437e-02 -1.530315e+01 -1.209270e-03 9.998900e-01 -1.478168e-02 -7.309677e+00 4.007085e-02 1.481827e-02 9.990869e-01 2.770214e+02 +9.991599e-01 -1.398380e-03 -4.095968e-02 -1.534577e+01 6.082578e-04 9.998136e-01 -1.929635e-02 -7.332706e+00 4.097902e-02 1.925523e-02 9.989744e-01 2.782198e+02 +9.991244e-01 -1.298084e-03 -4.181945e-02 -1.539143e+01 3.996136e-04 9.997691e-01 -2.148571e-02 -7.362888e+00 4.183768e-02 2.145018e-02 9.988941e-01 2.794335e+02 +9.991085e-01 -1.922202e-03 -4.217392e-02 -1.544023e+01 1.134563e-03 9.998246e-01 -1.869199e-02 -7.394637e+00 4.220245e-02 1.862747e-02 9.989354e-01 2.806585e+02 +9.990839e-01 -6.789334e-04 -4.278968e-02 -1.549104e+01 1.026017e-04 9.999093e-01 -1.346970e-02 -7.427375e+00 4.279494e-02 1.345297e-02 9.989932e-01 2.818920e+02 +9.990444e-01 -2.237245e-03 -4.365161e-02 -1.554177e+01 1.596797e-03 9.998906e-01 -1.470117e-02 -7.458635e+00 4.367972e-02 1.461741e-02 9.989386e-01 2.831286e+02 +9.989948e-01 -4.078626e-03 -4.464107e-02 -1.559058e+01 3.196042e-03 9.997983e-01 -1.982423e-02 -7.489167e+00 4.471292e-02 1.966162e-02 9.988063e-01 2.843516e+02 +9.989629e-01 -4.269014e-03 -4.533257e-02 -1.564569e+01 3.199965e-03 9.997157e-01 -2.362879e-02 -7.524950e+00 4.542055e-02 2.345922e-02 9.986924e-01 2.855828e+02 +9.989272e-01 -3.277193e-03 -4.619311e-02 -1.570314e+01 2.165064e-03 9.997071e-01 -2.410516e-02 -7.562304e+00 4.625858e-02 2.397929e-02 9.986416e-01 2.868240e+02 +9.989164e-01 -9.774785e-04 -4.653221e-02 -1.576449e+01 -4.126441e-05 9.997604e-01 -2.188729e-02 -7.603002e+00 4.654246e-02 2.186549e-02 9.986769e-01 2.880682e+02 +9.989168e-01 1.379015e-03 -4.651225e-02 -1.582556e+01 -2.171361e-03 9.998533e-01 -1.698899e-02 -7.641323e+00 4.648200e-02 1.707158e-02 9.987732e-01 2.893170e+02 +9.989508e-01 4.482574e-03 -4.557787e-02 -1.588743e+01 -5.088715e-03 9.999000e-01 -1.319168e-02 -7.676762e+00 4.551418e-02 1.340977e-02 9.988736e-01 2.905656e+02 +9.989977e-01 6.374307e-03 -4.430720e-02 -1.594680e+01 -6.905083e-03 9.999061e-01 -1.183673e-02 -7.707939e+00 4.422759e-02 1.213081e-02 9.989478e-01 2.918117e+02 +9.990621e-01 4.737662e-03 -4.304069e-02 -1.599936e+01 -5.294473e-03 9.999036e-01 -1.283208e-02 -7.737233e+00 4.297574e-02 1.304792e-02 9.989909e-01 2.930549e+02 +9.991072e-01 4.950869e-03 -4.195602e-02 -1.605246e+01 -5.662160e-03 9.998419e-01 -1.685140e-02 -7.771299e+00 4.186596e-02 1.707392e-02 9.989773e-01 2.943017e+02 +9.991529e-01 3.503029e-03 -4.100335e-02 -1.609994e+01 -4.418586e-03 9.997424e-01 -2.225954e-02 -7.813183e+00 4.091481e-02 2.242186e-02 9.989110e-01 2.955434e+02 +9.991944e-01 2.802028e-03 -4.003524e-02 -1.614863e+01 -3.789777e-03 9.996897e-01 -2.461742e-02 -7.859032e+00 3.995384e-02 2.474931e-02 9.988949e-01 2.967911e+02 +9.992451e-01 3.698055e-03 -3.867407e-02 -1.620391e+01 -4.578231e-03 9.997319e-01 -2.269506e-02 -7.906555e+00 3.857977e-02 2.285499e-02 9.989941e-01 2.980516e+02 +9.992630e-01 6.222291e-03 -3.788016e-02 -1.626006e+01 -6.928839e-03 9.998039e-01 -1.854958e-02 -7.954308e+00 3.775731e-02 1.879837e-02 9.991101e-01 2.993084e+02 +9.992693e-01 7.474533e-03 -3.748358e-02 -1.631526e+01 -8.097118e-03 9.998313e-01 -1.648529e-02 -8.000839e+00 3.735404e-02 1.677675e-02 9.991612e-01 3.005703e+02 +9.992661e-01 1.032653e-02 -3.688813e-02 -1.637063e+01 -1.077598e-02 9.998698e-01 -1.200604e-02 -8.040366e+00 3.675934e-02 1.239473e-02 9.992472e-01 3.018367e+02 +9.992609e-01 1.267851e-02 -3.628932e-02 -1.642531e+01 -1.291475e-02 9.998968e-01 -6.282763e-03 -8.077115e+00 3.620592e-02 6.746787e-03 9.993215e-01 3.031058e+02 +9.992157e-01 1.616603e-02 -3.614776e-02 -1.648034e+01 -1.646654e-02 9.998321e-01 -8.031087e-03 -8.109685e+00 3.601186e-02 8.620016e-03 9.993141e-01 3.043697e+02 +9.991776e-01 1.846009e-02 -3.610175e-02 -1.653456e+01 -1.896678e-02 9.997256e-01 -1.374324e-02 -8.143183e+00 3.583815e-02 1.441667e-02 9.992536e-01 3.056299e+02 +9.991014e-01 2.162902e-02 -3.645036e-02 -1.659014e+01 -2.230836e-02 9.995830e-01 -1.833499e-02 -8.181496e+00 3.603859e-02 1.913166e-02 9.991672e-01 3.068933e+02 +9.990033e-01 2.518494e-02 -3.685513e-02 -1.664720e+01 -2.595932e-02 9.994489e-01 -2.068563e-02 -8.224857e+00 3.631385e-02 2.162174e-02 9.991064e-01 3.081607e+02 +9.989452e-01 2.687656e-02 -3.723194e-02 -1.670249e+01 -2.768399e-02 9.993888e-01 -2.134333e-02 -8.270500e+00 3.663555e-02 2.235154e-02 9.990786e-01 3.094306e+02 +9.988879e-01 2.806302e-02 -3.788818e-02 -1.675668e+01 -2.876432e-02 9.994224e-01 -1.809318e-02 -8.315321e+00 3.735855e-02 1.916289e-02 9.991181e-01 3.107059e+02 +9.988979e-01 2.702485e-02 -3.837644e-02 -1.680650e+01 -2.760774e-02 9.995101e-01 -1.474065e-02 -8.353996e+00 3.795927e-02 1.578389e-02 9.991546e-01 3.119815e+02 +9.988762e-01 2.692065e-02 -3.900939e-02 -1.685845e+01 -2.742692e-02 9.995456e-01 -1.250151e-02 -8.388980e+00 3.865511e-02 1.355737e-02 9.991606e-01 3.132591e+02 +9.988727e-01 2.605478e-02 -3.968143e-02 -1.691025e+01 -2.656054e-02 9.995719e-01 -1.227201e-02 -8.422400e+00 3.934470e-02 1.331214e-02 9.991370e-01 3.145361e+02 +9.988555e-01 2.576317e-02 -4.029844e-02 -1.696357e+01 -2.626100e-02 9.995846e-01 -1.187303e-02 -8.454940e+00 3.997581e-02 1.291771e-02 9.991171e-01 3.158158e+02 +9.988468e-01 2.512435e-02 -4.091252e-02 -1.701429e+01 -2.564222e-02 9.995969e-01 -1.218257e-02 -8.486316e+00 4.058995e-02 1.321761e-02 9.990884e-01 3.170938e+02 +9.987829e-01 2.582171e-02 -4.202477e-02 -1.706216e+01 -2.633761e-02 9.995838e-01 -1.176888e-02 -8.514715e+00 4.170338e-02 1.286139e-02 9.990472e-01 3.183716e+02 +9.987549e-01 2.592811e-02 -4.261934e-02 -1.710889e+01 -2.639327e-02 9.995976e-01 -1.038800e-02 -8.543556e+00 4.233285e-02 1.149993e-02 9.990373e-01 3.196428e+02 +9.986996e-01 2.736063e-02 -4.301924e-02 -1.716005e+01 -2.792064e-02 9.995323e-01 -1.247098e-02 -8.574624e+00 4.265790e-02 1.365588e-02 9.989964e-01 3.209152e+02 +9.986733e-01 2.780499e-02 -4.334394e-02 -1.721170e+01 -2.858599e-02 9.994380e-01 -1.750411e-02 -8.606204e+00 4.283288e-02 1.871991e-02 9.989068e-01 3.221833e+02 +9.987074e-01 2.640602e-02 -4.343098e-02 -1.725927e+01 -2.716736e-02 9.994857e-01 -1.703376e-02 -8.641599e+00 4.295885e-02 1.819165e-02 9.989112e-01 3.234533e+02 +9.986852e-01 2.797993e-02 -4.295511e-02 -1.731098e+01 -2.855539e-02 9.995097e-01 -1.284181e-02 -8.680667e+00 4.257474e-02 1.405152e-02 9.989944e-01 3.247256e+02 +9.987442e-01 2.687988e-02 -4.228066e-02 -1.735960e+01 -2.732422e-02 9.995769e-01 -9.966724e-03 -8.713173e+00 4.199486e-02 1.110949e-02 9.990560e-01 3.259958e+02 +9.987754e-01 2.673440e-02 -4.163050e-02 -1.740874e+01 -2.708483e-02 9.996021e-01 -7.876277e-03 -8.741762e+00 4.140337e-02 8.994185e-03 9.991020e-01 3.272626e+02 +9.988053e-01 2.634388e-02 -4.115954e-02 -1.745799e+01 -2.665306e-02 9.996203e-01 -6.980972e-03 -8.765928e+00 4.096001e-02 8.069659e-03 9.991281e-01 3.285260e+02 +9.989021e-01 2.230485e-02 -4.119556e-02 -1.750324e+01 -2.268257e-02 9.997046e-01 -8.724361e-03 -8.787718e+00 4.098880e-02 9.649203e-03 9.991130e-01 3.297779e+02 +9.989320e-01 2.091916e-02 -4.119963e-02 -1.755187e+01 -2.140578e-02 9.997058e-01 -1.140579e-02 -8.813935e+00 4.094891e-02 1.227552e-02 9.990858e-01 3.310352e+02 +9.989785e-01 1.778614e-02 -4.154197e-02 -1.760106e+01 -1.834450e-02 9.997459e-01 -1.309853e-02 -8.842975e+00 4.129844e-02 1.384722e-02 9.990508e-01 3.322864e+02 +9.989957e-01 1.553856e-02 -4.202650e-02 -1.765295e+01 -1.604867e-02 9.998012e-01 -1.182766e-02 -8.873266e+00 4.183436e-02 1.249025e-02 9.990464e-01 3.335377e+02 +9.990152e-01 1.270819e-02 -4.251085e-02 -1.770297e+01 -1.307735e-02 9.998790e-01 -8.417044e-03 -8.901412e+00 4.239874e-02 8.964683e-03 9.990605e-01 3.347888e+02 +9.990082e-01 9.601887e-03 -4.347953e-02 -1.775287e+01 -9.809778e-03 9.999414e-01 -4.570498e-03 -8.927774e+00 4.343309e-02 4.992490e-03 9.990438e-01 3.360357e+02 +9.989947e-01 5.909934e-03 -4.443872e-02 -1.780347e+01 -6.160016e-03 9.999659e-01 -5.492732e-03 -8.954791e+00 4.440474e-02 5.760953e-03 9.989970e-01 3.372744e+02 +9.989658e-01 1.783329e-03 -4.543492e-02 -1.785329e+01 -2.245747e-03 9.999462e-01 -1.012857e-02 -8.980762e+00 4.541441e-02 1.022013e-02 9.989159e-01 3.385021e+02 +9.989260e-01 1.870776e-04 -4.633489e-02 -1.790716e+01 -7.272722e-04 9.999319e-01 -1.164190e-02 -9.010778e+00 4.632956e-02 1.166309e-02 9.988581e-01 3.397189e+02 +9.988863e-01 -6.961590e-04 -4.717810e-02 -1.796551e+01 2.065847e-04 9.999461e-01 -1.038124e-02 -9.049782e+00 4.718278e-02 1.035993e-02 9.988325e-01 3.409283e+02 +9.988532e-01 -2.368995e-03 -4.782057e-02 -1.802521e+01 2.023185e-03 9.999714e-01 -7.278509e-03 -9.091240e+00 4.783644e-02 7.173412e-03 9.988294e-01 3.421240e+02 +9.988193e-01 -4.323830e-03 -4.838751e-02 -1.808204e+01 4.187423e-03 9.999869e-01 -2.920062e-03 -9.126276e+00 4.839950e-02 2.713995e-03 9.988243e-01 3.433053e+02 +9.987825e-01 -6.821854e-03 -4.885761e-02 -1.813902e+01 6.822398e-03 9.999767e-01 -1.556329e-04 -9.160291e+00 4.885753e-02 -1.778819e-04 9.988057e-01 3.444674e+02 +9.987249e-01 -9.125774e-03 -4.965266e-02 -1.819339e+01 9.116231e-03 9.999583e-01 -4.186719e-04 -9.189315e+00 4.965441e-02 -3.450643e-05 9.987664e-01 3.456059e+02 +9.986706e-01 -1.065035e-02 -5.043561e-02 -1.824881e+01 1.053229e-02 9.999411e-01 -2.606057e-03 -9.217085e+00 5.046040e-02 2.071390e-03 9.987239e-01 3.467269e+02 +9.986685e-01 -8.934298e-03 -5.080797e-02 -1.830956e+01 8.672809e-03 9.999480e-01 -5.364770e-03 -9.247842e+00 5.085326e-02 4.916979e-03 9.986940e-01 3.478273e+02 +9.986677e-01 -8.115319e-03 -5.096063e-02 -1.837352e+01 7.726522e-03 9.999395e-01 -7.821753e-03 -9.282638e+00 5.102103e-02 7.417583e-03 9.986700e-01 3.489181e+02 +9.986986e-01 -7.058272e-03 -5.051110e-02 -1.843736e+01 6.639518e-03 9.999422e-01 -8.453354e-03 -9.318634e+00 5.056784e-02 8.106983e-03 9.986877e-01 3.499985e+02 +9.987875e-01 -4.679533e-03 -4.900636e-02 -1.849843e+01 4.342100e-03 9.999661e-01 -6.989703e-03 -9.351679e+00 4.903740e-02 6.768437e-03 9.987740e-01 3.510693e+02 +9.988872e-01 -2.128075e-03 -4.711688e-02 -1.855833e+01 1.799141e-03 9.999737e-01 -7.022549e-03 -9.386278e+00 4.713058e-02 6.929963e-03 9.988646e-01 3.521217e+02 +9.989870e-01 -2.039985e-03 -4.495479e-02 -1.860997e+01 1.639083e-03 9.999586e-01 -8.952944e-03 -9.417944e+00 4.497119e-02 8.870189e-03 9.989488e-01 3.531589e+02 +9.990973e-01 -3.177081e-03 -4.236243e-02 -1.865783e+01 2.787789e-03 9.999534e-01 -9.245470e-03 -9.450543e+00 4.238982e-02 9.119026e-03 9.990595e-01 3.541778e+02 +9.992052e-01 -2.837672e-03 -3.976083e-02 -1.870101e+01 2.496541e-03 9.999597e-01 -8.626605e-03 -9.481883e+00 3.978371e-02 8.520483e-03 9.991719e-01 3.551795e+02 +9.993008e-01 -4.434889e-03 -3.712585e-02 -1.874328e+01 4.164894e-03 9.999643e-01 -7.346608e-03 -9.516554e+00 3.715710e-02 7.186846e-03 9.992835e-01 3.561601e+02 +9.993655e-01 -6.686793e-03 -3.498642e-02 -1.877927e+01 6.464418e-03 9.999582e-01 -6.465315e-03 -9.547960e+00 3.502819e-02 6.235045e-03 9.993668e-01 3.571136e+02 +9.994370e-01 -7.334277e-03 -3.274083e-02 -1.881665e+01 7.153917e-03 9.999586e-01 -5.622488e-03 -9.582259e+00 3.278071e-02 5.385097e-03 9.994480e-01 3.580516e+02 +9.994761e-01 -1.082458e-02 -3.050418e-02 -1.884448e+01 1.072182e-02 9.999363e-01 -3.530325e-03 -9.609743e+00 3.054045e-02 3.201415e-03 9.995283e-01 3.589666e+02 +9.995367e-01 -1.078223e-02 -2.846398e-02 -1.887016e+01 1.075442e-02 9.999415e-01 -1.130082e-03 -9.638001e+00 2.847450e-02 8.234456e-04 9.995941e-01 3.598640e+02 +9.996110e-01 -9.734673e-03 -2.613566e-02 -1.889630e+01 9.749024e-03 9.999524e-01 4.216831e-04 -9.667497e+00 2.613031e-02 -6.763156e-04 9.996583e-01 3.607366e+02 +9.996683e-01 -9.513488e-03 -2.393479e-02 -1.892083e+01 9.472247e-03 9.999534e-01 -1.835878e-03 -9.687682e+00 2.395114e-02 1.608554e-03 9.997118e-01 3.615833e+02 +9.997257e-01 -8.421073e-03 -2.185546e-02 -1.894620e+01 8.262609e-03 9.999390e-01 -7.330763e-03 -9.710378e+00 2.191586e-02 7.148168e-03 9.997342e-01 3.624023e+02 +9.997788e-01 -7.229136e-03 -1.975527e-02 -1.896398e+01 7.019251e-03 9.999184e-01 -1.067303e-02 -9.726873e+00 1.983082e-02 1.053200e-02 9.997478e-01 3.631942e+02 +9.998067e-01 -7.492429e-03 -1.817881e-02 -1.897790e+01 7.309196e-03 9.999220e-01 -1.012514e-02 -9.742016e+00 1.825325e-02 9.990312e-03 9.997834e-01 3.639639e+02 +9.998368e-01 -6.850526e-03 -1.671846e-02 -1.899092e+01 6.750619e-03 9.999590e-01 -6.025047e-03 -9.761579e+00 1.675905e-02 5.911203e-03 9.998420e-01 3.647112e+02 +9.998612e-01 -6.009856e-03 -1.553951e-02 -1.900849e+01 5.959839e-03 9.999769e-01 -3.263046e-03 -9.780495e+00 1.555876e-02 3.169980e-03 9.998739e-01 3.654351e+02 +9.998428e-01 -4.502548e-03 -1.715475e-02 -1.902819e+01 4.393412e-03 9.999699e-01 -6.394287e-03 -9.797774e+00 1.718302e-02 6.317913e-03 9.998323e-01 3.661228e+02 +9.997683e-01 -3.712583e-03 -2.120419e-02 -1.905061e+01 3.496189e-03 9.999415e-01 -1.023324e-02 -9.812531e+00 2.124094e-02 1.015673e-02 9.997227e-01 3.667844e+02 +9.996376e-01 -2.477342e-03 -2.680715e-02 -1.907614e+01 2.156070e-03 9.999256e-01 -1.200684e-02 -9.827076e+00 2.683490e-02 1.194469e-02 9.995685e-01 3.674159e+02 +9.994454e-01 1.690099e-03 -3.325942e-02 -1.910983e+01 -2.091983e-03 9.999252e-01 -1.205223e-02 -9.842937e+00 3.323656e-02 1.211512e-02 9.993740e-01 3.680192e+02 +9.991562e-01 5.810746e-03 -4.066003e-02 -1.915077e+01 -6.284502e-03 9.999137e-01 -1.153352e-02 -9.861440e+00 4.058950e-02 1.177931e-02 9.991064e-01 3.685996e+02 +9.986087e-01 8.992317e-03 -5.196116e-02 -1.919069e+01 -9.557324e-03 9.998977e-01 -1.063539e-02 -9.882918e+00 5.186021e-02 1.111720e-02 9.985924e-01 3.691635e+02 +9.976379e-01 8.356618e-03 -6.818277e-02 -1.923495e+01 -8.992568e-03 9.999188e-01 -9.025541e-03 -9.901782e+00 6.810181e-02 9.617358e-03 9.976320e-01 3.697126e+02 +9.960390e-01 7.496261e-03 -8.860142e-02 -1.928863e+01 -8.311506e-03 9.999264e-01 -8.835902e-03 -9.917890e+00 8.852866e-02 9.537313e-03 9.960279e-01 3.702326e+02 +9.932427e-01 5.537908e-03 -1.159239e-01 -1.936721e+01 -6.555477e-03 9.999432e-01 -8.398487e-03 -9.928671e+00 1.158708e-01 9.101672e-03 9.932225e-01 3.707560e+02 +9.882676e-01 5.134749e-03 -1.526460e-01 -1.946935e+01 -6.181513e-03 9.999605e-01 -6.383676e-03 -9.943388e+00 1.526072e-01 7.252363e-03 9.882603e-01 3.712737e+02 +9.804091e-01 6.271988e-03 -1.968722e-01 -1.960077e+01 -6.879654e-03 9.999734e-01 -2.402848e-03 -9.956625e+00 1.968518e-01 3.710187e-03 9.804262e-01 3.717463e+02 +9.688504e-01 6.779711e-03 -2.475540e-01 -1.976475e+01 -6.612999e-03 9.999770e-01 1.504919e-03 -9.968575e+00 2.475585e-01 1.790340e-04 9.688729e-01 3.722444e+02 +9.524673e-01 8.244002e-03 -3.045293e-01 -1.995933e+01 -6.586317e-03 9.999574e-01 6.470312e-03 -9.981102e+00 3.045696e-01 -4.157032e-03 9.524809e-01 3.727380e+02 +9.307297e-01 1.125478e-02 -3.655348e-01 -2.018106e+01 -6.862256e-03 9.998878e-01 1.331369e-02 -9.992426e+00 3.656436e-01 -9.883048e-03 9.307024e-01 3.731340e+02 +9.036257e-01 1.648839e-02 -4.280056e-01 -2.044152e+01 -8.546339e-03 9.997539e-01 2.047086e-02 -1.000330e+01 4.282377e-01 -1.484011e-02 9.035442e-01 3.735895e+02 +8.712325e-01 2.415245e-02 -4.902760e-01 -2.073791e+01 -1.141443e-02 9.995155e-01 2.895538e-02 -1.000991e+01 4.907378e-01 -1.963065e-02 8.710861e-01 3.740328e+02 +8.344593e-01 3.098478e-02 -5.501978e-01 -2.104624e+01 -1.309412e-02 9.992510e-01 3.641429e-02 -1.000255e+01 5.509140e-01 -2.318188e-02 8.342400e-01 3.743529e+02 +7.930888e-01 3.516297e-02 -6.080903e-01 -2.138775e+01 -1.309678e-02 9.990859e-01 4.069121e-02 -1.000130e+01 6.089653e-01 -2.430771e-02 7.928243e-01 3.747420e+02 +7.457960e-01 3.655331e-02 -6.651709e-01 -2.174853e+01 -8.777127e-03 9.989460e-01 4.505434e-02 -9.994063e+00 6.661166e-01 -2.776305e-02 7.453306e-01 3.751143e+02 +6.921079e-01 3.988696e-02 -7.206912e-01 -2.212778e+01 -6.476277e-03 9.987749e-01 4.905820e-02 -9.981493e+00 7.217650e-01 -2.928616e-02 6.915182e-01 3.753538e+02 +6.333004e-01 4.475311e-02 -7.726111e-01 -2.254840e+01 -7.678504e-03 9.986408e-01 5.155180e-02 -9.966478e+00 7.738680e-01 -2.671527e-02 6.327832e-01 3.756649e+02 +5.698802e-01 5.186144e-02 -8.200896e-01 -2.299937e+01 -9.380917e-03 9.983519e-01 5.661574e-02 -9.945359e+00 8.216742e-01 -2.457099e-02 5.694275e-01 3.759545e+02 +5.023263e-01 5.353638e-02 -8.630192e-01 -2.345704e+01 -7.507291e-04 9.981080e-01 6.147950e-02 -9.928836e+00 8.646778e-01 -3.023487e-02 5.014161e-01 3.760984e+02 +4.298491e-01 4.836477e-02 -9.016045e-01 -2.393364e+01 1.304251e-02 9.981275e-01 5.976071e-02 -9.900892e+00 9.028065e-01 -3.744726e-02 4.284133e-01 3.763352e+02 +3.533671e-01 4.419040e-02 -9.344404e-01 -2.443257e+01 1.943524e-02 9.983213e-01 5.456100e-02 -9.880766e+00 9.352828e-01 -3.744113e-02 3.519150e-01 3.765292e+02 +2.749623e-01 3.865119e-02 -9.606778e-01 -2.493449e+01 2.288038e-02 9.986456e-01 4.672752e-02 -9.871383e+00 9.611827e-01 -3.482897e-02 2.737055e-01 3.765567e+02 +1.981369e-01 3.442426e-02 -9.795697e-01 -2.546406e+01 2.372000e-02 9.989220e-01 3.990218e-02 -9.842394e+00 9.798873e-01 -3.114148e-02 1.971067e-01 3.766584e+02 +1.254741e-01 3.099903e-02 -9.916125e-01 -2.599906e+01 2.706225e-02 9.990328e-01 3.465534e-02 -9.809242e+00 9.917277e-01 -3.118361e-02 1.245138e-01 3.766402e+02 +5.992767e-02 3.384527e-02 -9.976288e-01 -2.655504e+01 2.617261e-02 9.990281e-01 3.546495e-02 -9.788800e+00 9.978595e-01 -2.823587e-02 5.898360e-02 3.766704e+02 +2.395075e-03 4.341615e-02 -9.990542e-01 -2.712760e+01 2.273981e-02 9.987963e-01 4.345947e-02 -9.784421e+00 9.997385e-01 -2.282238e-02 1.404915e-03 3.766575e+02 +-4.631821e-02 5.225251e-02 -9.975592e-01 -2.770081e+01 1.911529e-02 9.984944e-01 5.141396e-02 -9.774028e+00 9.987438e-01 -1.668722e-02 -4.724730e-02 3.765814e+02 +-8.516605e-02 5.332009e-02 -9.949391e-01 -2.827676e+01 1.746117e-02 9.984936e-01 5.201593e-02 -9.756490e+00 9.962137e-01 -1.294280e-02 -8.596878e-02 3.765217e+02 +-1.163316e-01 4.865421e-02 -9.920180e-01 -2.885234e+01 1.333859e-02 9.987859e-01 4.742197e-02 -9.734980e+00 9.931208e-01 -7.715442e-03 -1.168394e-01 3.764301e+02 +-1.384491e-01 4.945990e-02 -9.891338e-01 -2.944552e+01 8.502567e-03 9.987747e-01 4.875189e-02 -9.710442e+00 9.903330e-01 -1.660516e-03 -1.387000e-01 3.763345e+02 +-1.532994e-01 5.490300e-02 -9.866534e-01 -3.005628e+01 5.510044e-03 9.984873e-01 5.470540e-02 -9.682160e+00 9.881644e-01 2.949803e-03 -1.533700e-01 3.762316e+02 +-1.619166e-01 5.884593e-02 -9.850483e-01 -3.068482e+01 3.704923e-03 9.982496e-01 5.902558e-02 -9.658371e+00 9.867974e-01 5.907698e-03 -1.618512e-01 3.761156e+02 +-1.648855e-01 6.130619e-02 -9.844056e-01 -3.132405e+01 2.954225e-03 9.980926e-01 6.166377e-02 -9.636330e+00 9.863083e-01 7.259307e-03 -1.647521e-01 3.760024e+02 +-1.663391e-01 5.661815e-02 -9.844418e-01 -3.197597e+01 4.457854e-04 9.983544e-01 5.734300e-02 -9.615390e+00 9.860685e-01 9.099536e-03 -1.660906e-01 3.758815e+02 +-1.667556e-01 4.476692e-02 -9.849815e-01 -3.263815e+01 2.434315e-03 9.989844e-01 4.499124e-02 -9.585791e+00 9.859952e-01 5.104792e-03 -1.666953e-01 3.757672e+02 +-1.662938e-01 3.659263e-02 -9.853971e-01 -3.332757e+01 6.029546e-03 9.993302e-01 3.609252e-02 -9.557240e+00 9.860578e-01 6.046876e-05 -1.664030e-01 3.756519e+02 +-1.655692e-01 3.579635e-02 -9.855483e-01 -3.404157e+01 1.000601e-02 9.993505e-01 3.461669e-02 -9.532153e+00 9.861474e-01 -4.129945e-03 -1.658198e-01 3.755388e+02 +-1.639134e-01 4.047041e-02 -9.856443e-01 -3.478313e+01 1.204863e-02 9.991657e-01 3.902191e-02 -9.517546e+00 9.864011e-01 -5.479444e-03 -1.642642e-01 3.754202e+02 +-1.614159e-01 4.175041e-02 -9.860030e-01 -3.553523e+01 9.953988e-03 9.991228e-01 4.067641e-02 -9.501098e+00 9.868362e-01 -3.248836e-03 -1.616899e-01 3.752992e+02 +-1.573019e-01 4.215369e-02 -9.866505e-01 -3.631240e+01 6.592892e-03 9.991111e-01 4.163496e-02 -9.484900e+00 9.875285e-01 4.438550e-05 -1.574400e-01 3.751747e+02 +-1.512948e-01 4.156512e-02 -9.876144e-01 -3.710423e+01 1.139337e-03 9.991222e-01 4.187491e-02 -9.463320e+00 9.884880e-01 5.210236e-03 -1.512094e-01 3.750527e+02 +-1.439978e-01 3.933052e-02 -9.887961e-01 -3.791338e+01 -6.284182e-03 9.991534e-01 4.065766e-02 -9.443687e+00 9.895580e-01 1.206839e-02 -1.436287e-01 3.749285e+02 +-1.344550e-01 3.850764e-02 -9.901712e-01 -3.874067e+01 -1.124128e-02 9.991210e-01 4.038215e-02 -9.419001e+00 9.908559e-01 1.656038e-02 -1.339040e-01 3.748155e+02 +-1.243623e-01 4.017431e-02 -9.914233e-01 -3.958997e+01 -1.474944e-02 9.989947e-01 4.233127e-02 -9.392673e+00 9.921272e-01 1.988735e-02 -1.236447e-01 3.747074e+02 +-1.143050e-01 4.438223e-02 -9.924538e-01 -4.046144e+01 -2.076670e-02 9.986765e-01 4.705230e-02 -9.365232e+00 9.932286e-01 2.598830e-02 -1.132320e-01 3.746064e+02 +-1.039431e-01 4.738717e-02 -9.934537e-01 -4.134951e+01 -2.500227e-02 9.984241e-01 5.024020e-02 -9.336701e+00 9.942689e-01 3.006072e-02 -1.025945e-01 3.745135e+02 +-9.413498e-02 4.658164e-02 -9.944691e-01 -4.225178e+01 -2.815245e-02 9.983807e-01 4.942974e-02 -9.304159e+00 9.951613e-01 3.264981e-02 -9.267115e-02 3.744289e+02 +-8.551499e-02 4.463443e-02 -9.953366e-01 -4.316492e+01 -2.618221e-02 9.985504e-01 4.702801e-02 -9.272700e+00 9.959928e-01 3.008171e-02 -8.422240e-02 3.743425e+02 +-7.881271e-02 4.586150e-02 -9.958340e-01 -4.409779e+01 -2.351866e-02 9.985776e-01 4.784919e-02 -9.243094e+00 9.966119e-01 2.719181e-02 -7.762200e-02 3.742608e+02 +-7.371098e-02 5.013192e-02 -9.960188e-01 -4.505263e+01 -2.201048e-02 9.984107e-01 5.188121e-02 -9.211296e+00 9.970367e-01 2.574707e-02 -7.249039e-02 3.741861e+02 +-7.087634e-02 5.575143e-02 -9.959259e-01 -4.602671e+01 -2.075931e-02 9.981381e-01 5.735264e-02 -9.169842e+00 9.972690e-01 2.473968e-02 -6.958701e-02 3.741085e+02 +-6.932194e-02 5.798799e-02 -9.959076e-01 -4.701136e+01 -1.807909e-02 9.980721e-01 5.937246e-02 -9.119413e+00 9.974305e-01 2.212092e-02 -6.813992e-02 3.740407e+02 +-6.812015e-02 5.895223e-02 -9.959339e-01 -4.800886e+01 -1.855929e-02 9.980050e-01 6.034426e-02 -9.069119e+00 9.975044e-01 2.259449e-02 -6.689013e-02 3.739643e+02 +-6.702925e-02 5.567479e-02 -9.961965e-01 -4.901850e+01 -2.280157e-02 9.980957e-01 5.731515e-02 -9.024967e+00 9.974904e-01 2.655664e-02 -6.563213e-02 3.738935e+02 +-6.595859e-02 5.147459e-02 -9.964938e-01 -5.004015e+01 -2.505128e-02 9.982683e-01 5.322442e-02 -8.976937e+00 9.975078e-01 2.847405e-02 -6.455486e-02 3.738239e+02 +-6.491924e-02 4.969127e-02 -9.966526e-01 -5.107674e+01 -2.596933e-02 9.983370e-01 5.146684e-02 -8.927044e+00 9.975525e-01 2.922359e-02 -6.352082e-02 3.737545e+02 +-6.365759e-02 4.959609e-02 -9.967387e-01 -5.212515e+01 -2.711673e-02 9.983096e-01 5.140610e-02 -8.879053e+00 9.976033e-01 3.030068e-02 -6.220509e-02 3.736856e+02 +-6.187467e-02 5.039090e-02 -9.968111e-01 -5.318568e+01 -2.654302e-02 9.982884e-01 5.211318e-02 -8.832441e+00 9.977309e-01 2.968286e-02 -6.043123e-02 3.736189e+02 +-6.006279e-02 5.094295e-02 -9.968938e-01 -5.425307e+01 -2.792894e-02 9.982201e-01 5.269345e-02 -8.787266e+00 9.978038e-01 3.100710e-02 -5.853310e-02 3.735542e+02 +-5.804583e-02 5.221823e-02 -9.969473e-01 -5.532812e+01 -3.023166e-02 9.980811e-01 5.403782e-02 -8.742463e+00 9.978560e-01 3.327604e-02 -5.635580e-02 3.734872e+02 +-5.637068e-02 5.335576e-02 -9.969832e-01 -5.640627e+01 -3.248306e-02 9.979443e-01 5.524384e-02 -8.699294e+00 9.978813e-01 3.549919e-02 -5.452164e-02 3.734219e+02 +-5.441224e-02 5.496525e-02 -9.970046e-01 -5.748887e+01 -3.185978e-02 9.978798e-01 5.675228e-02 -8.659593e+00 9.980101e-01 3.485236e-02 -5.254569e-02 3.733621e+02 +-5.359951e-02 5.482379e-02 -9.970564e-01 -5.857119e+01 -3.295094e-02 9.978508e-01 5.663885e-02 -8.617614e+00 9.980187e-01 3.588976e-02 -5.167782e-02 3.733061e+02 +-5.339265e-02 5.325299e-02 -9.971526e-01 -5.965341e+01 -3.265754e-02 9.979497e-01 5.504422e-02 -8.582225e+00 9.980394e-01 3.550350e-02 -5.154406e-02 3.732513e+02 +-5.383101e-02 5.208171e-02 -9.971909e-01 -6.074575e+01 -3.237519e-02 9.980228e-01 5.387287e-02 -8.543403e+00 9.980250e-01 3.518428e-02 -5.203841e-02 3.731973e+02 +-5.403428e-02 5.578783e-02 -9.969795e-01 -6.184440e+01 -3.317536e-02 9.977866e-01 5.763104e-02 -8.506757e+00 9.979878e-01 3.618920e-02 -5.206390e-02 3.731406e+02 +-5.456934e-02 5.962990e-02 -9.967279e-01 -6.294306e+01 -3.433121e-02 9.975130e-01 6.155646e-02 -8.464322e+00 9.979196e-01 3.757797e-02 -5.238646e-02 3.730836e+02 +-5.554685e-02 5.964143e-02 -9.966732e-01 -6.403405e+01 -3.751243e-02 9.973849e-01 6.177468e-02 -8.415622e+00 9.977511e-01 4.081902e-02 -5.316430e-02 3.730231e+02 +-5.660991e-02 5.786711e-02 -9.967180e-01 -6.512951e+01 -3.759763e-02 9.974872e-01 6.004719e-02 -8.368280e+00 9.976882e-01 4.087349e-02 -5.429199e-02 3.729642e+02 +-5.873926e-02 5.417954e-02 -9.968021e-01 -6.621957e+01 -3.431856e-02 9.978263e-01 5.625753e-02 -8.326584e+00 9.976832e-01 3.751334e-02 -5.675221e-02 3.729093e+02 +-6.054844e-02 5.216995e-02 -9.968010e-01 -6.730807e+01 -3.498392e-02 9.979087e-01 5.435295e-02 -8.286409e+00 9.975520e-01 3.816299e-02 -5.859670e-02 3.728504e+02 +-6.202998e-02 5.493595e-02 -9.965613e-01 -6.839938e+01 -3.163116e-02 9.978743e-01 5.697719e-02 -8.242833e+00 9.975729e-01 3.505668e-02 -6.016043e-02 3.727923e+02 +-6.357276e-02 5.811517e-02 -9.962837e-01 -6.948687e+01 -3.102100e-02 9.977055e-01 6.017756e-02 -8.202328e+00 9.974949e-01 3.473137e-02 -6.162410e-02 3.727320e+02 +-6.483178e-02 5.531143e-02 -9.963622e-01 -7.056942e+01 -3.037231e-02 9.978907e-01 5.737257e-02 -8.157450e+00 9.974338e-01 3.398138e-02 -6.301509e-02 3.726691e+02 +-6.562999e-02 5.369456e-02 -9.963983e-01 -7.164810e+01 -3.263113e-02 9.979016e-01 5.592490e-02 -8.116213e+00 9.973103e-01 3.618395e-02 -6.374016e-02 3.726024e+02 +-6.539097e-02 5.450925e-02 -9.963698e-01 -7.272612e+01 -3.552890e-02 9.977466e-01 5.691631e-02 -8.074099e+00 9.972270e-01 3.912173e-02 -6.330695e-02 3.725329e+02 +-6.434910e-02 5.715196e-02 -9.962896e-01 -7.380592e+01 -3.687505e-02 9.975407e-01 5.960545e-02 -8.034820e+00 9.972459e-01 4.057378e-02 -6.208336e-02 3.724658e+02 +-6.225249e-02 5.918735e-02 -9.963039e-01 -7.487976e+01 -3.805554e-02 9.973734e-01 6.162874e-02 -7.995837e+00 9.973346e-01 4.175142e-02 -5.983657e-02 3.724034e+02 +-5.968061e-02 6.052164e-02 -9.963812e-01 -7.594999e+01 -3.748806e-02 9.973203e-01 6.282413e-02 -7.958251e+00 9.975133e-01 4.110178e-02 -5.725184e-02 3.723488e+02 +-5.671638e-02 6.026185e-02 -9.965700e-01 -7.701652e+01 -3.741548e-02 9.973472e-01 6.243823e-02 -7.920701e+00 9.976890e-01 4.082841e-02 -5.431120e-02 3.722963e+02 +-5.314911e-02 5.786940e-02 -9.969084e-01 -7.807571e+01 -3.776699e-02 9.974887e-01 5.991660e-02 -7.882137e+00 9.978721e-01 4.083474e-02 -5.083008e-02 3.722465e+02 +-4.943831e-02 5.504690e-02 -9.972591e-01 -7.913236e+01 -3.943482e-02 9.975939e-01 5.702034e-02 -7.845224e+00 9.979983e-01 4.214572e-02 -4.714859e-02 3.721988e+02 +-4.562206e-02 5.419976e-02 -9.974874e-01 -8.018446e+01 -4.058358e-02 9.976021e-01 5.606218e-02 -7.809958e+00 9.981340e-01 4.303927e-02 -4.331304e-02 3.721566e+02 +-4.183270e-02 5.525439e-02 -9.975956e-01 -8.123435e+01 -4.186522e-02 9.974957e-01 5.700443e-02 -7.776644e+00 9.982471e-01 4.414920e-02 -3.941470e-02 3.721199e+02 +-3.794368e-02 5.833302e-02 -9.975759e-01 -8.227667e+01 -4.353651e-02 9.972503e-01 5.996994e-02 -7.738710e+00 9.983310e-01 4.570644e-02 -3.529973e-02 3.720859e+02 +-3.398374e-02 6.255745e-02 -9.974626e-01 -8.330662e+01 -4.381491e-02 9.969863e-01 6.402036e-02 -7.696401e+00 9.984615e-01 4.587939e-02 -3.114037e-02 3.720596e+02 +-3.022301e-02 6.508779e-02 -9.974218e-01 -8.432209e+01 -4.339181e-02 9.968514e-01 6.636540e-02 -7.655593e+00 9.986008e-01 4.528569e-02 -2.730357e-02 3.720376e+02 +-2.640584e-02 6.424633e-02 -9.975847e-01 -8.531838e+01 -4.202997e-02 9.969788e-01 6.531984e-02 -7.620704e+00 9.987673e-01 4.365327e-02 -2.362579e-02 3.720213e+02 +-2.322094e-02 6.016838e-02 -9.979181e-01 -8.629444e+01 -4.020708e-02 9.973234e-01 6.106813e-02 -7.583183e+00 9.989215e-01 4.154143e-02 -2.073959e-02 3.720098e+02 +-2.051127e-02 5.752796e-02 -9.981332e-01 -8.725699e+01 -3.742752e-02 9.975992e-01 5.826631e-02 -7.547871e+00 9.990888e-01 3.855277e-02 -1.830889e-02 3.720031e+02 +-1.844195e-02 5.699337e-02 -9.982042e-01 -8.820287e+01 -3.422533e-02 9.977529e-01 5.759993e-02 -7.515820e+00 9.992439e-01 3.522613e-02 -1.644989e-02 3.719992e+02 +-1.701258e-02 5.498548e-02 -9.983422e-01 -8.912695e+01 -3.121572e-02 9.979708e-01 5.549698e-02 -7.488594e+00 9.993678e-01 3.210811e-02 -1.526165e-02 3.719958e+02 +-1.583773e-02 5.432731e-02 -9.983976e-01 -9.003634e+01 -2.951956e-02 9.980621e-01 5.477734e-02 -7.460881e+00 9.994387e-01 3.033980e-02 -1.420332e-02 3.719926e+02 +-1.503872e-02 5.386374e-02 -9.984351e-01 -9.092745e+01 -2.696547e-02 9.981629e-01 5.425523e-02 -7.429303e+00 9.995232e-01 2.773920e-02 -1.355863e-02 3.719896e+02 +-1.505443e-02 5.465576e-02 -9.983918e-01 -9.181075e+01 -2.474442e-02 9.981787e-01 5.501722e-02 -7.399767e+00 9.995804e-01 2.553287e-02 -1.367459e-02 3.719848e+02 +-1.702228e-02 5.289773e-02 -9.984549e-01 -9.268534e+01 -2.195670e-02 9.983389e-01 5.326593e-02 -7.370240e+00 9.996140e-01 2.282948e-02 -1.583255e-02 3.719798e+02 +-2.079009e-02 5.255801e-02 -9.984015e-01 -9.355555e+01 -1.668562e-02 9.984599e-01 5.290855e-02 -7.337048e+00 9.996446e-01 1.775892e-02 -1.988111e-02 3.719749e+02 +-2.765363e-02 5.371561e-02 -9.981733e-01 -9.443191e+01 -1.223304e-02 9.984622e-01 5.407007e-02 -7.302020e+00 9.995427e-01 1.370594e-02 -2.695399e-02 3.719620e+02 +-3.690922e-02 5.663107e-02 -9.977127e-01 -9.530320e+01 -8.694464e-03 9.983370e-01 5.698816e-02 -7.263870e+00 9.992808e-01 1.077797e-02 -3.635546e-02 3.719349e+02 +-4.859588e-02 5.783229e-02 -9.971429e-01 -9.616931e+01 -8.287038e-03 9.982646e-01 5.830123e-02 -7.227268e+00 9.987841e-01 1.109656e-02 -4.803229e-02 3.718941e+02 +-6.158758e-02 5.438623e-02 -9.966189e-01 -9.702694e+01 -8.399058e-03 9.984507e-01 5.500524e-02 -7.193924e+00 9.980663e-01 1.175830e-02 -6.103537e-02 3.718401e+02 +-7.517879e-02 4.825661e-02 -9.960018e-01 -9.787921e+01 -8.973064e-03 9.987551e-01 4.906731e-02 -7.164166e+00 9.971297e-01 1.262601e-02 -7.465219e-02 3.717755e+02 +-8.837727e-02 4.257101e-02 -9.951770e-01 -9.873520e+01 -9.653659e-03 9.990028e-01 4.359198e-02 -7.136757e+00 9.960403e-01 1.345964e-02 -8.787817e-02 3.716994e+02 +-9.995662e-02 3.890591e-02 -9.942309e-01 -9.959406e+01 -1.347775e-02 9.990906e-01 4.045109e-02 -7.113516e+00 9.949005e-01 1.744336e-02 -9.934134e-02 3.716064e+02 +-1.088161e-01 3.778830e-02 -9.933434e-01 -1.004613e+02 -1.728307e-02 9.990542e-01 3.989884e-02 -7.090644e+00 9.939116e-01 2.150966e-02 -1.080601e-01 3.715074e+02 +-1.146553e-01 3.829921e-02 -9.926668e-01 -1.013359e+02 -1.879305e-02 9.989941e-01 4.071398e-02 -7.068917e+00 9.932275e-01 2.332331e-02 -1.138202e-01 3.714057e+02 +-1.184190e-01 3.736302e-02 -9.922606e-01 -1.022157e+02 -2.276589e-02 9.989270e-01 4.033099e-02 -7.049875e+00 9.927027e-01 2.736564e-02 -1.174413e-01 3.713023e+02 +-1.194453e-01 3.573360e-02 -9.921976e-01 -1.031086e+02 -2.681924e-02 9.988713e-01 3.920258e-02 -7.033049e+00 9.924784e-01 3.129255e-02 -1.183521e-01 3.711939e+02 +-1.189183e-01 3.432154e-02 -9.923107e-01 -1.040061e+02 -2.865962e-02 9.988673e-01 3.798289e-02 -7.012862e+00 9.924903e-01 3.295611e-02 -1.178000e-01 3.710901e+02 +-1.171599e-01 3.446873e-02 -9.925147e-01 -1.049115e+02 -2.775901e-02 9.988933e-01 3.796703e-02 -6.992092e+00 9.927250e-01 3.199944e-02 -1.160735e-01 3.709916e+02 +-1.152103e-01 3.837956e-02 -9.925994e-01 -1.058331e+02 -2.740730e-02 9.987501e-01 4.179854e-02 -6.968820e+00 9.929629e-01 3.202009e-02 -1.140144e-01 3.708926e+02 +-1.132829e-01 4.605843e-02 -9.924947e-01 -1.067711e+02 -2.817441e-02 9.983743e-01 4.954711e-02 -6.945607e+00 9.931632e-01 3.357579e-02 -1.118011e-01 3.707922e+02 +-1.099810e-01 6.133441e-02 -9.920395e-01 -1.077376e+02 -3.324483e-02 9.973087e-01 6.534585e-02 -6.905404e+00 9.933775e-01 4.016698e-02 -1.076460e-01 3.706851e+02 +-1.053865e-01 6.712731e-02 -9.921631e-01 -1.087068e+02 -3.592485e-02 9.968108e-01 7.125767e-02 -6.862932e+00 9.937822e-01 4.315290e-02 -1.026389e-01 3.705839e+02 +-9.967221e-02 5.957683e-02 -9.932352e-01 -1.096822e+02 -4.677153e-02 9.968219e-01 6.448556e-02 -6.817108e+00 9.939204e-01 5.288254e-02 -9.656894e-02 3.704778e+02 +-9.222868e-02 4.645047e-02 -9.946539e-01 -1.106676e+02 -4.708702e-02 9.975903e-01 5.095373e-02 -6.764922e+00 9.946238e-01 5.153468e-02 -8.981922e-02 3.703877e+02 +-8.636797e-02 4.673647e-02 -9.951665e-01 -1.116894e+02 -4.736361e-02 9.975769e-01 5.096025e-02 -6.717120e+00 9.951368e-01 5.153600e-02 -8.394508e-02 3.703035e+02 +-8.045849e-02 5.976597e-02 -9.949646e-01 -1.127391e+02 -4.643138e-02 9.968924e-01 6.363649e-02 -6.673776e+00 9.956759e-01 5.131767e-02 -7.743344e-02 3.702285e+02 +-7.531554e-02 6.328173e-02 -9.951498e-01 -1.137970e+02 -4.315445e-02 9.968424e-01 6.665542e-02 -6.626579e+00 9.962255e-01 4.796533e-02 -7.234683e-02 3.701647e+02 +-7.069485e-02 5.461681e-02 -9.960017e-01 -1.148615e+02 -4.172866e-02 9.974638e-01 5.765884e-02 -6.574629e+00 9.966247e-01 4.563799e-02 -6.823646e-02 3.701005e+02 +-6.720583e-02 4.339841e-02 -9.967949e-01 -1.159316e+02 -4.322569e-02 9.979889e-01 4.636476e-02 -6.529774e+00 9.968023e-01 4.620312e-02 -6.519474e-02 3.700364e+02 +-6.342834e-02 4.409115e-02 -9.970120e-01 -1.170364e+02 -5.068512e-02 9.975920e-01 4.734132e-02 -6.486705e+00 9.966984e-01 5.353645e-02 -6.104084e-02 3.699626e+02 +-5.843135e-02 5.178533e-02 -9.969474e-01 -1.181603e+02 -5.784793e-02 9.967999e-01 5.516816e-02 -6.449135e+00 9.966139e-01 6.089489e-02 -5.524869e-02 3.698888e+02 +-5.278949e-02 4.772985e-02 -9.974644e-01 -1.192866e+02 -6.169575e-02 9.967930e-01 5.096290e-02 -6.410174e+00 9.966980e-01 6.422961e-02 -4.967546e-02 3.698286e+02 +-4.698395e-02 3.478802e-02 -9.982897e-01 -1.204129e+02 -5.820321e-02 9.976000e-01 3.750330e-02 -6.370320e+00 9.971985e-01 5.986571e-02 -4.484641e-02 3.697840e+02 +-4.200463e-02 2.656194e-02 -9.987643e-01 -1.215557e+02 -5.052751e-02 9.983109e-01 2.867491e-02 -6.338214e+00 9.978389e-01 5.166955e-02 -4.059156e-02 3.697516e+02 +-3.646022e-02 3.328978e-02 -9.987805e-01 -1.227295e+02 -4.548352e-02 9.983540e-01 3.493593e-02 -6.313111e+00 9.982995e-01 4.670182e-02 -3.488606e-02 3.697246e+02 +-3.034585e-02 4.591760e-02 -9.984842e-01 -1.239184e+02 -4.307963e-02 9.979559e-01 4.720258e-02 -6.285628e+00 9.986106e-01 4.444673e-02 -2.830571e-02 3.697019e+02 +-2.384468e-02 5.285803e-02 -9.983173e-01 -1.251055e+02 -4.311646e-02 9.976177e-01 5.385082e-02 -6.247853e+00 9.987854e-01 4.432796e-02 -2.150883e-02 3.696828e+02 +-1.840532e-02 5.286477e-02 -9.984321e-01 -1.262887e+02 -4.444159e-02 9.975710e-01 5.363843e-02 -6.203627e+00 9.988424e-01 4.535914e-02 -1.601121e-02 3.696712e+02 +-1.432789e-02 5.015907e-02 -9.986385e-01 -1.274712e+02 -4.361592e-02 9.977590e-01 5.074068e-02 -6.159301e+00 9.989456e-01 4.428354e-02 -1.210805e-02 3.696638e+02 +-1.135737e-02 4.839508e-02 -9.987637e-01 -1.286559e+02 -4.052920e-02 9.979850e-01 4.881823e-02 -6.123569e+00 9.991138e-01 4.103354e-02 -9.373068e-03 3.696624e+02 +-9.321924e-03 4.825774e-02 -9.987914e-01 -1.298397e+02 -3.851285e-02 9.980764e-01 4.858265e-02 -6.090263e+00 9.992146e-01 3.891919e-02 -7.445449e-03 3.696623e+02 +-8.535431e-03 5.203173e-02 -9.986090e-01 -1.310280e+02 -3.890263e-02 9.978720e-01 5.232585e-02 -6.051368e+00 9.992065e-01 3.929514e-02 -6.493097e-03 3.696587e+02 +-8.684802e-03 5.678546e-02 -9.983487e-01 -1.322129e+02 -3.897947e-02 9.976082e-01 5.708245e-02 -6.009283e+00 9.992022e-01 3.941085e-02 -6.450564e-03 3.696554e+02 +-9.643575e-03 5.484784e-02 -9.984482e-01 -1.333856e+02 -3.743381e-02 9.977749e-01 5.517242e-02 -5.970026e+00 9.992525e-01 3.790777e-02 -7.568954e-03 3.696509e+02 +-1.215267e-02 4.639066e-02 -9.988495e-01 -1.345543e+02 -3.042410e-02 9.984435e-01 4.674197e-02 -5.935395e+00 9.994632e-01 3.095713e-02 -1.072236e-02 3.696476e+02 +-1.775549e-02 3.981287e-02 -9.990494e-01 -1.357203e+02 -2.117827e-02 9.989677e-01 4.018601e-02 -5.903866e+00 9.996180e-01 2.187166e-02 -1.689399e-02 3.696460e+02 +-2.493832e-02 4.322669e-02 -9.987540e-01 -1.368944e+02 -1.504131e-02 9.989354e-01 4.361013e-02 -5.879570e+00 9.995758e-01 1.611014e-02 -2.426158e-02 3.696340e+02 +-3.210374e-02 5.034875e-02 -9.982156e-01 -1.380705e+02 -1.236244e-02 9.986340e-01 5.076745e-02 -5.850333e+00 9.994080e-01 1.397020e-02 -3.143745e-02 3.696092e+02 +-3.890683e-02 5.190424e-02 -9.978939e-01 -1.392367e+02 -1.528731e-02 9.985022e-01 5.253192e-02 -5.819392e+00 9.991259e-01 1.729896e-02 -3.805507e-02 3.695683e+02 +-4.448749e-02 4.905582e-02 -9.978048e-01 -1.403981e+02 -2.165725e-02 9.985115e-01 5.005617e-02 -5.784160e+00 9.987751e-01 2.383658e-02 -4.335886e-02 3.695144e+02 +-4.891853e-02 4.504741e-02 -9.977864e-01 -1.415541e+02 -2.718655e-02 9.985522e-01 4.641487e-02 -5.751590e+00 9.984327e-01 2.939692e-02 -4.762302e-02 3.694563e+02 +-5.190322e-02 4.322410e-02 -9.977163e-01 -1.427082e+02 -2.907478e-02 9.985739e-01 4.477380e-02 -5.719895e+00 9.982287e-01 3.133229e-02 -5.057247e-02 3.693988e+02 +-5.405641e-02 4.415548e-02 -9.975612e-01 -1.438621e+02 -2.904287e-02 9.985296e-01 4.577215e-02 -5.687958e+00 9.981154e-01 3.144632e-02 -5.269452e-02 3.693405e+02 +-5.591326e-02 5.120575e-02 -9.971217e-01 -1.450234e+02 -2.512261e-02 9.982956e-01 5.267479e-02 -5.651594e+00 9.981195e-01 2.799552e-02 -5.453153e-02 3.692862e+02 +-5.808629e-02 5.905198e-02 -9.965635e-01 -1.461786e+02 -2.331240e-02 9.978965e-01 6.048977e-02 -5.609570e+00 9.980393e-01 2.674591e-02 -5.658746e-02 3.692290e+02 +-5.937891e-02 6.223616e-02 -9.962936e-01 -1.473276e+02 -2.372751e-02 9.976846e-01 6.373722e-02 -5.563013e+00 9.979534e-01 2.742421e-02 -5.776471e-02 3.691664e+02 +-5.957293e-02 5.518337e-02 -9.966975e-01 -1.484660e+02 -2.708928e-02 9.980137e-01 5.687539e-02 -5.517301e+00 9.978563e-01 3.038805e-02 -5.795971e-02 3.690988e+02 +-6.005162e-02 4.671951e-02 -9.971014e-01 -1.495961e+02 -2.889519e-02 9.984041e-01 4.852080e-02 -5.476203e+00 9.977769e-01 3.172518e-02 -5.860581e-02 3.690322e+02 +-6.020996e-02 4.658009e-02 -9.970983e-01 -1.507370e+02 -2.559081e-02 9.985102e-01 4.819136e-02 -5.432874e+00 9.978576e-01 2.841815e-02 -5.892824e-02 3.689711e+02 +-6.210155e-02 5.205490e-02 -9.967115e-01 -1.518818e+02 -2.377177e-02 9.982785e-01 5.361788e-02 -5.397091e+00 9.977867e-01 2.702335e-02 -6.075720e-02 3.689079e+02 +-6.514920e-02 5.663029e-02 -9.962674e-01 -1.530299e+02 -1.931849e-02 9.981297e-01 5.799945e-02 -5.355110e+00 9.976885e-01 2.302500e-02 -6.393334e-02 3.688467e+02 +-6.837115e-02 6.209834e-02 -9.957255e-01 -1.541586e+02 -1.561092e-02 9.978722e-01 6.330415e-02 -5.306809e+00 9.975378e-01 1.987237e-02 -6.725625e-02 3.687819e+02 +-7.111670e-02 6.356489e-02 -9.954406e-01 -1.552876e+02 -1.599787e-02 9.977663e-01 6.485634e-02 -5.257637e+00 9.973397e-01 2.053730e-02 -6.994094e-02 3.687083e+02 +-7.360294e-02 6.239097e-02 -9.953341e-01 -1.564144e+02 -1.863141e-02 9.977809e-01 6.392212e-02 -5.210757e+00 9.971135e-01 2.324933e-02 -7.227717e-02 3.686264e+02 +-7.644561e-02 5.995589e-02 -9.952695e-01 -1.575339e+02 -2.290902e-02 9.978213e-01 6.186924e-02 -5.161697e+00 9.968105e-01 2.753028e-02 -7.490552e-02 3.685391e+02 +-7.877595e-02 5.565447e-02 -9.953376e-01 -1.586476e+02 -2.648469e-02 9.979711e-01 5.789786e-02 -5.117612e+00 9.965404e-01 3.092217e-02 -7.714212e-02 3.684516e+02 +-8.051738e-02 5.164412e-02 -9.954144e-01 -1.597555e+02 -2.508831e-02 9.982354e-01 5.381984e-02 -5.077488e+00 9.964374e-01 2.930670e-02 -7.907963e-02 3.683680e+02 +-8.188354e-02 5.021787e-02 -9.953760e-01 -1.608631e+02 -2.498632e-02 9.983124e-01 5.242150e-02 -5.037247e+00 9.963286e-01 2.916324e-02 -8.049059e-02 3.682819e+02 +-8.319574e-02 5.594175e-02 -9.949618e-01 -1.619767e+02 -2.253351e-02 9.980622e-01 5.800027e-02 -4.998850e+00 9.962784e-01 2.724536e-02 -8.177396e-02 3.681974e+02 +-8.463348e-02 6.315798e-02 -9.944085e-01 -1.630853e+02 -2.078044e-02 9.976602e-01 6.513313e-02 -4.955172e+00 9.961954e-01 2.617669e-02 -8.312300e-02 3.681135e+02 +-8.520815e-02 6.549488e-02 -9.942083e-01 -1.641857e+02 -2.171261e-02 9.974781e-01 6.757117e-02 -4.907712e+00 9.961265e-01 2.734447e-02 -8.357120e-02 3.680250e+02 +-8.475432e-02 6.346121e-02 -9.943789e-01 -1.652717e+02 -2.185307e-02 9.976112e-01 6.553012e-02 -4.855746e+00 9.961622e-01 2.728419e-02 -8.316504e-02 3.679349e+02 +-8.492544e-02 5.926061e-02 -9.946235e-01 -1.663509e+02 -2.369381e-02 9.978274e-01 6.147460e-02 -4.813324e+00 9.961055e-01 2.878717e-02 -8.333681e-02 3.678400e+02 +-8.508518e-02 5.853494e-02 -9.946528e-01 -1.674328e+02 -2.599631e-02 9.978026e-01 6.094411e-02 -4.772560e+00 9.960344e-01 3.104274e-02 -8.337651e-02 3.677486e+02 +-8.529565e-02 6.185633e-02 -9.944338e-01 -1.685130e+02 -2.657477e-02 9.975747e-01 6.433112e-02 -4.733896e+00 9.960012e-01 3.191402e-02 -8.344496e-02 3.676578e+02 +-8.536531e-02 6.018363e-02 -9.945304e-01 -1.695842e+02 -2.262731e-02 9.977994e-01 6.232368e-02 -4.695860e+00 9.960927e-01 2.782383e-02 -8.381566e-02 3.675744e+02 +-8.553232e-02 5.154417e-02 -9.950012e-01 -1.706424e+02 -2.124150e-02 9.983396e-01 5.354308e-02 -4.656983e+00 9.961089e-01 2.571498e-02 -8.429542e-02 3.674884e+02 +-8.517997e-02 4.735391e-02 -9.952397e-01 -1.717000e+02 -1.783732e-02 9.986374e-01 4.904223e-02 -4.623281e+00 9.962059e-01 2.192983e-02 -8.421923e-02 3.674038e+02 +-8.642691e-02 5.169398e-02 -9.949162e-01 -1.727727e+02 -1.514604e-02 9.984693e-01 5.319432e-02 -4.592437e+00 9.961430e-01 1.966646e-02 -8.551165e-02 3.673198e+02 +-8.622111e-02 5.622673e-02 -9.946882e-01 -1.738414e+02 -1.774023e-02 9.981612e-01 5.796082e-02 -4.561133e+00 9.961180e-01 2.264344e-02 -8.506508e-02 3.672271e+02 +-8.485160e-02 5.286237e-02 -9.949904e-01 -1.748995e+02 -2.044776e-02 9.982890e-01 5.478139e-02 -4.524537e+00 9.961837e-01 2.499361e-02 -8.362549e-02 3.671366e+02 +-8.296979e-02 4.564258e-02 -9.955063e-01 -1.759578e+02 -2.731173e-02 9.984712e-01 4.805481e-02 -4.488888e+00 9.961777e-01 3.117609e-02 -8.159636e-02 3.670444e+02 +-7.999965e-02 4.331256e-02 -9.958535e-01 -1.770237e+02 -3.433893e-02 9.983428e-01 4.617938e-02 -4.457455e+00 9.962032e-01 3.789088e-02 -7.837976e-02 3.669514e+02 +-7.662911e-02 4.742926e-02 -9.959310e-01 -1.780974e+02 -3.877316e-02 9.979706e-01 5.050970e-02 -4.429870e+00 9.963054e-01 4.248590e-02 -7.463461e-02 3.668671e+02 +-7.239201e-02 4.989966e-02 -9.961272e-01 -1.791720e+02 -3.915381e-02 9.978356e-01 5.283069e-02 -4.398167e+00 9.966074e-01 4.282669e-02 -7.028155e-02 3.667944e+02 +-6.784459e-02 4.952118e-02 -9.964662e-01 -1.802445e+02 -3.677597e-02 9.979645e-01 5.209955e-02 -4.366461e+00 9.970178e-01 4.018068e-02 -6.588530e-02 3.667304e+02 +-6.303127e-02 4.821053e-02 -9.968465e-01 -1.813162e+02 -3.398891e-02 9.981494e-01 5.042270e-02 -4.334028e+00 9.974326e-01 3.705992e-02 -6.127600e-02 3.666741e+02 +-5.849042e-02 4.595638e-02 -9.972296e-01 -1.823951e+02 -2.904653e-02 9.984385e-01 4.771576e-02 -4.306321e+00 9.978653e-01 3.175698e-02 -5.706421e-02 3.666251e+02 +-5.432208e-02 4.438197e-02 -9.975367e-01 -1.834739e+02 -2.470184e-02 9.986462e-01 4.577651e-02 -4.281270e+00 9.982178e-01 2.712766e-02 -5.315222e-02 3.665809e+02 +-5.016020e-02 4.189294e-02 -9.978622e-01 -1.845558e+02 -1.875533e-02 9.989042e-01 4.287948e-02 -4.255802e+00 9.985650e-01 2.086608e-02 -4.931951e-02 3.665426e+02 +-4.674467e-02 4.789234e-02 -9.977581e-01 -1.856479e+02 -1.438859e-02 9.987141e-01 4.861234e-02 -4.229744e+00 9.988032e-01 1.662870e-02 -4.599545e-02 3.665044e+02 +-4.405224e-02 5.520512e-02 -9.975028e-01 -1.867448e+02 -8.977824e-03 9.984099e-01 5.565181e-02 -4.199807e+00 9.989888e-01 1.140699e-02 -4.348656e-02 3.664720e+02 +-4.257189e-02 5.593100e-02 -9.975266e-01 -1.878389e+02 -7.496379e-03 9.983858e-01 5.629911e-02 -4.167223e+00 9.990652e-01 9.874601e-03 -4.208388e-02 3.664364e+02 +-4.107822e-02 5.393180e-02 -9.976994e-01 -1.889337e+02 -4.658798e-03 9.985209e-01 5.416804e-02 -4.128173e+00 9.991450e-01 6.873210e-03 -4.076620e-02 3.664037e+02 +-3.996354e-02 5.439839e-02 -9.977193e-01 -1.900335e+02 -6.260723e-03 9.984837e-01 5.469085e-02 -4.091253e+00 9.991815e-01 8.432088e-03 -3.956237e-02 3.663673e+02 +-3.753677e-02 5.631364e-02 -9.977073e-01 -1.911399e+02 -1.094968e-02 9.983277e-01 5.676063e-02 -4.054400e+00 9.992352e-01 1.305518e-02 -3.685738e-02 3.663277e+02 +-3.445172e-02 5.743690e-02 -9.977545e-01 -1.922453e+02 -1.843511e-02 9.981408e-01 5.809569e-02 -4.016796e+00 9.992363e-01 2.039521e-02 -3.332881e-02 3.662856e+02 +-3.037586e-02 5.461480e-02 -9.980454e-01 -1.933554e+02 -2.451624e-02 9.981650e-01 5.536752e-02 -3.977329e+00 9.992378e-01 2.615015e-02 -2.898116e-02 3.662505e+02 +-2.585525e-02 5.262524e-02 -9.982796e-01 -1.944689e+02 -2.922115e-02 9.981469e-01 5.337507e-02 -3.936207e+00 9.992385e-01 3.055090e-02 -2.426956e-02 3.662225e+02 +-2.121044e-02 5.364090e-02 -9.983350e-01 -1.955898e+02 -3.288489e-02 9.979819e-01 5.432061e-02 -3.897886e+00 9.992340e-01 3.398230e-02 -1.940366e-02 3.662012e+02 +-1.661007e-02 5.503956e-02 -9.983460e-01 -1.967169e+02 -3.422839e-02 9.978672e-01 5.558265e-02 -3.857159e+00 9.992760e-01 3.509501e-02 -1.469073e-02 3.661886e+02 +-1.250041e-02 5.650884e-02 -9.983239e-01 -1.978457e+02 -3.429457e-02 9.977902e-01 5.690806e-02 -3.817161e+00 9.993335e-01 3.494846e-02 -1.053484e-02 3.661803e+02 +-8.858140e-03 5.899163e-02 -9.982192e-01 -1.989817e+02 -3.352108e-02 9.976797e-01 5.925722e-02 -3.773023e+00 9.993987e-01 3.398629e-02 -6.860125e-03 3.661789e+02 +-6.320329e-03 6.070198e-02 -9.981360e-01 -2.001212e+02 -3.193904e-02 9.976343e-01 6.087372e-02 -3.728399e+00 9.994698e-01 3.226424e-02 -4.366616e-03 3.661826e+02 +-4.490271e-03 6.055906e-02 -9.981545e-01 -2.012603e+02 -3.094353e-02 9.976781e-01 6.066937e-02 -3.682710e+00 9.995110e-01 3.115885e-02 -2.605935e-03 3.661882e+02 +-2.918892e-03 5.964847e-02 -9.982152e-01 -2.023996e+02 -3.120966e-02 9.977277e-01 5.971061e-02 -3.636529e+00 9.995086e-01 3.132825e-02 -1.050652e-03 3.661935e+02 +-1.508157e-03 6.082858e-02 -9.981471e-01 -2.035405e+02 -3.098703e-02 9.976660e-01 6.084610e-02 -3.588992e+00 9.995186e-01 3.102138e-02 3.802586e-04 3.661998e+02 +1.856796e-04 6.342025e-02 -9.979869e-01 -2.046831e+02 -3.174951e-02 9.974841e-01 6.338240e-02 -3.542463e+00 9.994958e-01 3.167382e-02 2.198773e-03 3.662058e+02 +1.663446e-03 6.441683e-02 -9.979217e-01 -2.058219e+02 -3.151640e-02 9.974307e-01 6.433262e-02 -3.494788e+00 9.995018e-01 3.134389e-02 3.689358e-03 3.662146e+02 +3.112342e-03 6.160170e-02 -9.980960e-01 -2.069527e+02 -3.024221e-02 9.976500e-01 6.147988e-02 -3.446857e+00 9.995377e-01 2.999329e-02 4.967998e-03 3.662275e+02 +4.506414e-03 6.072790e-02 -9.981442e-01 -2.080863e+02 -2.780278e-02 9.977760e-01 6.057999e-02 -3.399686e+00 9.996032e-01 2.747818e-02 6.184795e-03 3.662469e+02 +6.157302e-03 6.132945e-02 -9.980986e-01 -2.092212e+02 -2.802170e-02 9.977361e-01 6.113432e-02 -3.356508e+00 9.995883e-01 2.759200e-02 7.861916e-03 3.662656e+02 +8.562885e-03 5.960993e-02 -9.981850e-01 -2.103479e+02 -2.745326e-02 9.978593e-01 5.935499e-02 -3.315181e+00 9.995864e-01 2.689518e-02 1.018104e-02 3.662855e+02 +1.137625e-02 5.687092e-02 -9.983168e-01 -2.114708e+02 -2.572292e-02 9.980676e-01 5.656362e-02 -3.272869e+00 9.996043e-01 2.503614e-02 1.281715e-02 3.663102e+02 +1.474288e-02 5.695463e-02 -9.982679e-01 -2.125902e+02 -2.623911e-02 9.980546e-01 5.655496e-02 -3.231126e+00 9.995469e-01 2.535988e-02 1.620864e-02 3.663364e+02 +1.859512e-02 6.046512e-02 -9.979971e-01 -2.137062e+02 -2.621831e-02 9.978559e-01 5.996806e-02 -3.189682e+00 9.994832e-01 2.505069e-02 2.014054e-02 3.663659e+02 +2.285028e-02 6.370088e-02 -9.977074e-01 -2.148180e+02 -2.626007e-02 9.976619e-01 6.309655e-02 -3.148845e+00 9.993939e-01 2.475809e-02 2.446964e-02 3.664016e+02 +2.825814e-02 6.555037e-02 -9.974491e-01 -2.159200e+02 -2.842379e-02 9.974967e-01 6.474826e-02 -3.105251e+00 9.991964e-01 2.652162e-02 3.005059e-02 3.664402e+02 +3.434996e-02 6.638344e-02 -9.972028e-01 -2.170095e+02 -3.148528e-02 9.973682e-01 6.530991e-02 -3.061988e+00 9.989137e-01 2.915382e-02 3.634966e-02 3.664819e+02 +4.118335e-02 6.524676e-02 -9.970190e-01 -2.180811e+02 -3.311736e-02 9.974064e-01 6.390416e-02 -3.019584e+00 9.986026e-01 3.038685e-02 4.323733e-02 3.665299e+02 +4.818115e-02 6.316292e-02 -9.968395e-01 -2.191371e+02 -3.404919e-02 9.975224e-01 6.156047e-02 -2.980028e+00 9.982581e-01 3.097552e-02 5.021241e-02 3.665880e+02 +5.499586e-02 6.242479e-02 -9.965333e-01 -2.201797e+02 -3.376172e-02 9.975893e-01 6.062774e-02 -2.943384e+00 9.979156e-01 3.031041e-02 5.697085e-02 3.666545e+02 +6.007425e-02 6.301128e-02 -9.962032e-01 -2.212023e+02 -3.197259e-02 9.976150e-01 6.117254e-02 -2.912970e+00 9.976817e-01 2.817630e-02 6.194559e-02 3.667266e+02 +6.368795e-02 6.233262e-02 -9.960214e-01 -2.222038e+02 -2.969695e-02 9.977239e-01 6.054029e-02 -2.881915e+00 9.975279e-01 2.572311e-02 6.539407e-02 3.668008e+02 +6.661529e-02 6.101816e-02 -9.959113e-01 -2.231912e+02 -2.746777e-02 9.978622e-01 5.930042e-02 -2.852383e+00 9.974005e-01 2.340515e-02 6.814890e-02 3.668790e+02 +6.926483e-02 6.225865e-02 -9.956537e-01 -2.241684e+02 -2.685242e-02 9.978054e-01 6.052516e-02 -2.823349e+00 9.972368e-01 2.254345e-02 7.078461e-02 3.669567e+02 +7.178189e-02 6.795909e-02 -9.951025e-01 -2.251444e+02 -2.371384e-02 9.975104e-01 6.641294e-02 -2.791621e+00 9.971384e-01 1.883046e-02 7.321475e-02 3.670358e+02 +7.353503e-02 7.058814e-02 -9.947914e-01 -2.260970e+02 -2.105086e-02 9.973796e-01 6.921572e-02 -2.764003e+00 9.970704e-01 1.585144e-02 7.482827e-02 3.671149e+02 +7.570471e-02 6.301778e-02 -9.951370e-01 -2.270200e+02 -1.995351e-02 9.978968e-01 6.167460e-02 -2.740336e+00 9.969306e-01 1.518742e-02 7.680291e-02 3.671918e+02 +7.834039e-02 5.165111e-02 -9.955878e-01 -2.279211e+02 -1.833775e-02 9.985626e-01 5.036250e-02 -2.712085e+00 9.967580e-01 1.431142e-02 7.917495e-02 3.672699e+02 +8.107820e-02 5.167088e-02 -9.953675e-01 -2.288148e+02 -2.252740e-02 9.984952e-01 4.999827e-02 -2.682417e+00 9.964531e-01 1.836928e-02 8.212020e-02 3.673454e+02 +8.611021e-02 6.547295e-02 -9.941320e-01 -2.297008e+02 -2.740870e-02 9.976163e-01 6.332833e-02 -2.658722e+00 9.959085e-01 2.179465e-02 8.769947e-02 3.674212e+02 +9.178659e-02 7.491474e-02 -9.929567e-01 -2.305604e+02 -3.174086e-02 9.968794e-01 7.227666e-02 -2.634793e+00 9.952727e-01 2.488327e-02 9.387801e-02 3.675004e+02 +9.987472e-02 7.271169e-02 -9.923397e-01 -2.313863e+02 -3.504290e-02 9.969646e-01 6.952367e-02 -2.607196e+00 9.943827e-01 2.783080e-02 1.021196e-01 3.675840e+02 +1.089074e-01 6.874587e-02 -9.916719e-01 -2.321842e+02 -3.681593e-02 9.972003e-01 6.508592e-02 -2.575303e+00 9.933699e-01 2.942099e-02 1.111334e-01 3.676735e+02 +1.190556e-01 7.029089e-02 -9.903964e-01 -2.329631e+02 -3.628217e-02 9.971327e-01 6.640751e-02 -2.546665e+00 9.922244e-01 2.802755e-02 1.212645e-01 3.677771e+02 +1.313800e-01 6.850277e-02 -9.889624e-01 -2.337126e+02 -3.532543e-02 9.972995e-01 6.438741e-02 -2.531497e+00 9.907024e-01 2.647631e-02 1.334451e-01 3.678877e+02 +1.464772e-01 6.072771e-02 -9.873483e-01 -2.344282e+02 -3.507039e-02 9.978052e-01 5.616804e-02 -2.513757e+00 9.885921e-01 2.639935e-02 1.482855e-01 3.680027e+02 +1.634767e-01 5.083020e-02 -9.852369e-01 -2.351142e+02 -3.305470e-02 9.983933e-01 4.602433e-02 -2.492462e+00 9.859932e-01 2.504280e-02 1.648942e-01 3.681319e+02 +1.796045e-01 4.702238e-02 -9.826145e-01 -2.357820e+02 -2.843512e-02 9.986877e-01 4.259413e-02 -2.474425e+00 9.833278e-01 2.029067e-02 1.807059e-01 3.682758e+02 +1.953272e-01 5.204971e-02 -9.793560e-01 -2.364378e+02 -2.233086e-02 9.985678e-01 4.861700e-02 -2.464522e+00 9.804838e-01 1.237365e-02 1.962097e-01 3.684236e+02 +2.103093e-01 5.727133e-02 -9.759560e-01 -2.370696e+02 -1.670030e-02 9.983474e-01 5.498657e-02 -2.458118e+00 9.774922e-01 4.734573e-03 2.109182e-01 3.685806e+02 +2.239254e-01 5.807196e-02 -9.728747e-01 -2.376754e+02 -1.020972e-02 9.983082e-01 5.724016e-02 -2.445853e+00 9.745528e-01 -2.884739e-03 2.241394e-01 3.687379e+02 +2.339965e-01 5.635645e-02 -9.706027e-01 -2.382590e+02 -3.327268e-03 9.983591e-01 5.716594e-02 -2.431902e+00 9.722317e-01 -1.014717e-02 2.338000e-01 3.689000e+02 +2.406247e-01 5.414283e-02 -9.691070e-01 -2.388228e+02 1.681016e-03 9.984182e-01 5.619781e-02 -2.416555e+00 9.706167e-01 -1.515165e-02 2.401530e-01 3.690562e+02 +2.446073e-01 5.115017e-02 -9.682722e-01 -2.393694e+02 5.455487e-03 9.985192e-01 5.412619e-02 -2.403606e+00 9.696068e-01 -1.852205e-02 2.439661e-01 3.692062e+02 +2.463259e-01 4.909766e-02 -9.679427e-01 -2.399009e+02 9.162731e-03 9.985534e-01 5.298212e-02 -2.389863e+00 9.691437e-01 -2.191986e-02 2.455197e-01 3.693516e+02 +2.461955e-01 4.952976e-02 -9.679538e-01 -2.404195e+02 1.132456e-02 9.984782e-01 5.397205e-02 -2.380637e+00 9.691540e-01 -2.424932e-02 2.452599e-01 3.694881e+02 +2.435384e-01 5.038600e-02 -9.685816e-01 -2.409239e+02 1.364796e-02 9.983727e-01 5.536737e-02 -2.371763e+00 9.697952e-01 -2.670323e-02 2.424544e-01 3.696176e+02 +2.380427e-01 5.168521e-02 -9.698785e-01 -2.414113e+02 1.421580e-02 9.982907e-01 5.668838e-02 -2.367036e+00 9.711506e-01 -2.728185e-02 2.369011e-01 3.697379e+02 +2.310051e-01 5.353920e-02 -9.714784e-01 -2.418871e+02 1.285419e-02 9.982297e-01 5.807007e-02 -2.362070e+00 9.728676e-01 -2.590204e-02 2.299080e-01 3.698465e+02 +2.226901e-01 5.455254e-02 -9.733618e-01 -2.423437e+02 1.211123e-02 9.982013e-01 5.871555e-02 -2.356458e+00 9.748140e-01 -2.486397e-02 2.216288e-01 3.699466e+02 +2.128052e-01 5.333092e-02 -9.756381e-01 -2.427831e+02 1.205361e-02 9.982900e-01 5.719827e-02 -2.350995e+00 9.770202e-01 -2.393204e-02 2.117985e-01 3.700378e+02 +2.013852e-01 5.191661e-02 -9.781353e-01 -2.432045e+02 1.396549e-02 9.983407e-01 5.586438e-02 -2.347796e+00 9.794125e-01 -2.491039e-02 2.003260e-01 3.701234e+02 +1.865563e-01 5.046099e-02 -9.811475e-01 -2.436178e+02 1.630886e-02 9.983834e-01 5.444843e-02 -2.342781e+00 9.823089e-01 -2.615908e-02 1.854317e-01 3.702007e+02 +1.671225e-01 4.921918e-02 -9.847069e-01 -2.440346e+02 1.799519e-02 9.984345e-01 5.295945e-02 -2.340872e+00 9.857719e-01 -2.657069e-02 1.659751e-01 3.702666e+02 +1.453678e-01 4.995386e-02 -9.881158e-01 -2.444445e+02 1.732525e-02 9.984429e-01 5.302478e-02 -2.337193e+00 9.892259e-01 -2.482744e-02 1.442759e-01 3.703053e+02 +1.236647e-01 5.166661e-02 -9.909781e-01 -2.448594e+02 1.468176e-02 9.984390e-01 5.388776e-02 -2.330489e+00 9.922154e-01 -2.121330e-02 1.227131e-01 3.703406e+02 +1.027641e-01 5.339013e-02 -9.932719e-01 -2.452712e+02 1.245735e-02 9.984111e-01 5.495522e-02 -2.321873e+00 9.946277e-01 -1.802095e-02 1.019357e-01 3.703665e+02 +8.170161e-02 5.474606e-02 -9.951521e-01 -2.456744e+02 1.097083e-02 9.983803e-01 5.582436e-02 -2.312545e+00 9.965964e-01 -1.547858e-02 8.096866e-02 3.703787e+02 +6.147264e-02 5.562292e-02 -9.965577e-01 -2.460773e+02 9.679030e-03 9.983658e-01 5.632089e-02 -2.300412e+00 9.980618e-01 -1.310790e-02 6.083379e-02 3.703917e+02 +4.220919e-02 5.616670e-02 -9.975288e-01 -2.464779e+02 8.723527e-03 9.983598e-01 5.658262e-02 -2.287939e+00 9.990707e-01 -1.109027e-02 4.164998e-02 3.703958e+02 +2.401014e-02 5.626210e-02 -9.981273e-01 -2.468718e+02 6.907500e-03 9.983819e-01 5.644263e-02 -2.274355e+00 9.996878e-01 -8.249753e-03 2.358266e-02 3.703881e+02 +8.416935e-03 5.596005e-02 -9.983976e-01 -2.472677e+02 3.919355e-03 9.984234e-01 5.599455e-02 -2.260463e+00 9.999569e-01 -4.384371e-03 8.184335e-03 3.703798e+02 +-3.697319e-03 5.441628e-02 -9.985115e-01 -2.476659e+02 2.329361e-04 9.985183e-01 5.441580e-02 -2.246632e+00 9.999931e-01 -3.139156e-05 -3.704517e-03 3.703647e+02 +-1.140740e-02 5.310846e-02 -9.985236e-01 -2.480750e+02 -5.003955e-03 9.985730e-01 5.316826e-02 -2.232871e+00 9.999224e-01 5.603083e-03 -1.112537e-02 3.703492e+02 +-1.590803e-02 5.348830e-02 -9.984418e-01 -2.484935e+02 -9.471421e-03 9.985152e-01 5.364315e-02 -2.218646e+00 9.998286e-01 1.031002e-02 -1.537780e-02 3.703337e+02 +-1.816045e-02 5.442387e-02 -9.983528e-01 -2.489198e+02 -1.199602e-02 9.984337e-01 5.464650e-02 -2.203372e+00 9.997631e-01 1.296867e-02 -1.747914e-02 3.703217e+02 +-1.727253e-02 5.529708e-02 -9.983206e-01 -2.493488e+02 -1.421731e-02 9.983549e-01 5.554498e-02 -2.190826e+00 9.997497e-01 1.515284e-02 -1.645794e-02 3.703141e+02 +-1.414199e-02 5.595012e-02 -9.983334e-01 -2.497837e+02 -1.757884e-02 9.982650e-01 5.619531e-02 -2.176850e+00 9.997454e-01 1.834426e-02 -1.313391e-02 3.703066e+02 +-1.076087e-02 5.608611e-02 -9.983680e-01 -2.502166e+02 -1.959791e-02 9.982221e-01 5.628916e-02 -2.162385e+00 9.997500e-01 2.017165e-02 -9.642567e-03 3.703022e+02 +-6.530376e-03 5.609491e-02 -9.984041e-01 -2.506487e+02 -2.328184e-02 9.981462e-01 5.623271e-02 -2.146243e+00 9.997076e-01 2.361190e-02 -5.212279e-03 3.703001e+02 +9.865837e-04 5.539700e-02 -9.984639e-01 -2.510788e+02 -2.763669e-02 9.980845e-01 5.534866e-02 -2.130858e+00 9.996175e-01 2.753964e-02 2.515682e-03 3.702992e+02 +1.110841e-02 5.474909e-02 -9.984384e-01 -2.515068e+02 -3.163698e-02 9.980193e-01 5.437414e-02 -2.116129e+00 9.994377e-01 3.098356e-02 1.281850e-02 3.703093e+02 +2.208667e-02 5.493479e-02 -9.982457e-01 -2.519337e+02 -3.387002e-02 9.979571e-01 5.416954e-02 -2.100918e+00 9.991821e-01 3.261418e-02 2.390219e-02 3.703279e+02 +3.304670e-02 5.613024e-02 -9.978764e-01 -2.523582e+02 -3.512301e-02 9.978702e-01 5.496673e-02 -2.084785e+00 9.988364e-01 3.323196e-02 3.494778e-02 3.703499e+02 +4.383583e-02 5.792220e-02 -9.973583e-01 -2.527844e+02 -3.576233e-02 9.977690e-01 5.637424e-02 -2.069893e+00 9.983984e-01 3.319664e-02 4.580946e-02 3.703789e+02 +5.426060e-02 6.000230e-02 -9.967224e-01 -2.532091e+02 -3.917454e-02 9.975523e-01 5.791965e-02 -2.051974e+00 9.977580e-01 3.590339e-02 5.647835e-02 3.704072e+02 +6.588207e-02 6.424131e-02 -9.957573e-01 -2.536321e+02 -4.243392e-02 9.972030e-01 6.152704e-02 -2.035602e+00 9.969247e-01 3.820036e-02 6.842380e-02 3.704365e+02 +7.733276e-02 6.659113e-02 -9.947790e-01 -2.540521e+02 -4.505242e-02 9.969811e-01 6.323624e-02 -2.021253e+00 9.959869e-01 3.992696e-02 8.009938e-02 3.704768e+02 +8.870868e-02 6.515045e-02 -9.939247e-01 -2.544577e+02 -4.304270e-02 9.971772e-01 6.152206e-02 -2.009520e+00 9.951271e-01 3.732366e-02 9.126251e-02 3.705258e+02 +9.945177e-02 6.318996e-02 -9.930340e-01 -2.548506e+02 -4.008601e-02 9.974258e-01 5.945485e-02 -1.999342e+00 9.942346e-01 3.389388e-02 1.017288e-01 3.705818e+02 +1.100545e-01 6.195611e-02 -9.919927e-01 -2.552299e+02 -3.996930e-02 9.975238e-01 5.786727e-02 -1.984999e+00 9.931215e-01 3.328070e-02 1.122583e-01 3.706363e+02 +1.194436e-01 6.092159e-02 -9.909701e-01 -2.555940e+02 -4.267485e-02 9.975082e-01 5.617985e-02 -1.969759e+00 9.919234e-01 3.557917e-02 1.217458e-01 3.706831e+02 +1.274114e-01 5.910522e-02 -9.900874e-01 -2.559406e+02 -4.561685e-02 9.975158e-01 5.367839e-02 -1.953994e+00 9.908004e-01 3.832542e-02 1.297910e-01 3.707299e+02 +1.338134e-01 5.494402e-02 -9.894823e-01 -2.562695e+02 -4.556106e-02 9.977472e-01 4.924148e-02 -1.939161e+00 9.899586e-01 3.849269e-02 1.360152e-01 3.707808e+02 +1.387611e-01 5.043869e-02 -9.890406e-01 -2.565925e+02 -4.128269e-02 9.981286e-01 4.511026e-02 -1.927459e+00 9.894650e-01 3.457071e-02 1.405836e-01 3.708359e+02 +1.416815e-01 4.937109e-02 -9.886804e-01 -2.569157e+02 -3.462072e-02 9.983916e-01 4.489477e-02 -1.922542e+00 9.893067e-01 2.786807e-02 1.431629e-01 3.708956e+02 +1.412481e-01 5.016055e-02 -9.887027e-01 -2.572400e+02 -3.073248e-02 9.984563e-01 4.626489e-02 -1.917165e+00 9.894971e-01 2.385046e-02 1.425716e-01 3.709487e+02 +1.371847e-01 5.034357e-02 -9.892654e-01 -2.575605e+02 -2.927258e-02 9.984775e-01 4.675306e-02 -1.908885e+00 9.901128e-01 2.254455e-02 1.384495e-01 3.709918e+02 +1.278250e-01 5.040243e-02 -9.905152e-01 -2.578803e+02 -2.921482e-02 9.984658e-01 4.703686e-02 -1.899168e+00 9.913663e-01 2.292524e-02 1.291014e-01 3.710266e+02 +1.133356e-01 5.098619e-02 -9.922477e-01 -2.581997e+02 -3.062387e-02 9.983872e-01 4.780378e-02 -1.887866e+00 9.930847e-01 2.496859e-02 1.147142e-01 3.710539e+02 +9.502575e-02 5.086282e-02 -9.941746e-01 -2.585102e+02 -3.135418e-02 9.983513e-01 4.807960e-02 -1.877972e+00 9.949809e-01 2.660273e-02 9.646383e-02 3.710637e+02 +7.268064e-02 5.026437e-02 -9.960879e-01 -2.588253e+02 -3.119128e-02 9.983552e-01 4.810289e-02 -1.868641e+00 9.968674e-01 2.757311e-02 7.412890e-02 3.710747e+02 +4.642534e-02 4.758791e-02 -9.977876e-01 -2.591424e+02 -2.876505e-02 9.985140e-01 4.628418e-02 -1.859898e+00 9.985075e-01 2.655265e-02 4.772522e-02 3.710795e+02 +1.720013e-02 4.398321e-02 -9.988842e-01 -2.594536e+02 -2.737923e-02 9.986781e-01 4.350269e-02 -1.853707e+00 9.994771e-01 2.660043e-02 1.838162e-02 3.710566e+02 +-1.478251e-02 4.243455e-02 -9.989899e-01 -2.597902e+02 -2.681590e-02 9.987228e-01 4.282002e-02 -1.842268e+00 9.995310e-01 2.742180e-02 -1.362571e-02 3.710367e+02 +-5.021000e-02 4.358302e-02 -9.977873e-01 -2.601398e+02 -2.860378e-02 9.985748e-01 4.505681e-02 -1.829167e+00 9.983290e-01 3.080279e-02 -4.889180e-02 3.710027e+02 +-8.924312e-02 4.594769e-02 -9.949495e-01 -2.604827e+02 -2.995016e-02 9.983598e-01 4.879160e-02 -1.812082e+00 9.955594e-01 3.415321e-02 -8.772059e-02 3.709267e+02 +-1.308267e-01 4.831922e-02 -9.902271e-01 -2.608538e+02 -2.786169e-02 9.982379e-01 5.239116e-02 -1.795956e+00 9.910136e-01 3.444356e-02 -1.292499e-01 3.708650e+02 +-1.746393e-01 4.827663e-02 -9.834483e-01 -2.612046e+02 -2.424811e-02 9.982835e-01 5.331083e-02 -1.779009e+00 9.843338e-01 3.315693e-02 -1.731689e-01 3.707495e+02 +-2.209639e-01 4.867020e-02 -9.740669e-01 -2.615907e+02 -2.088376e-02 9.982889e-01 5.461790e-02 -1.760933e+00 9.750583e-01 3.241076e-02 -2.195693e-01 3.706494e+02 +-2.689760e-01 4.992273e-02 -9.618522e-01 -2.619813e+02 -1.894212e-02 9.981884e-01 5.710573e-02 -1.738415e+00 9.629606e-01 3.357959e-02 -2.675430e-01 3.705256e+02 +-3.176642e-01 5.004455e-02 -9.468817e-01 -2.623441e+02 -1.862190e-02 9.980844e-01 5.899808e-02 -1.718545e+00 9.480204e-01 3.637432e-02 -3.161237e-01 3.703254e+02 +-3.670115e-01 4.782171e-02 -9.289864e-01 -2.627437e+02 -1.517111e-02 9.982371e-01 5.738016e-02 -1.694404e+00 9.300927e-01 3.515293e-02 -3.656389e-01 3.701514e+02 +-4.175198e-01 4.499654e-02 -9.075531e-01 -2.631499e+02 -1.073874e-02 9.984591e-01 5.444403e-02 -1.669085e+00 9.086043e-01 3.247743e-02 -4.163932e-01 3.699554e+02 +-4.681870e-01 4.309669e-02 -8.825779e-01 -2.635125e+02 -4.369219e-03 9.986848e-01 5.108403e-02 -1.645564e+00 8.836186e-01 2.777305e-02 -4.673829e-01 3.696714e+02 +-5.195031e-01 4.482979e-02 -8.532918e-01 -2.639245e+02 9.539145e-04 9.986525e-01 5.188592e-02 -1.624289e+00 8.544680e-01 2.614093e-02 -5.188458e-01 3.694151e+02 +-5.698641e-01 4.830062e-02 -8.203182e-01 -2.643343e+02 7.736774e-03 9.985421e-01 5.341989e-02 -1.601451e+00 8.217025e-01 2.409546e-02 -5.694070e-01 3.691288e+02 +-6.193761e-01 5.069385e-02 -7.834561e-01 -2.646835e+02 1.148010e-02 9.983912e-01 5.552552e-02 -1.575511e+00 7.850104e-01 2.539703e-02 -6.189616e-01 3.687352e+02 +-6.674588e-01 5.175911e-02 -7.428458e-01 -2.650731e+02 1.454303e-02 9.982972e-01 5.649102e-02 -1.549228e+00 7.445047e-01 2.690219e-02 -6.670749e-01 3.683762e+02 +-7.131119e-01 5.423873e-02 -6.989490e-01 -2.654532e+02 1.980517e-02 9.981633e-01 5.725143e-02 -1.522155e+00 7.007705e-01 2.698387e-02 -7.128762e-01 3.679838e+02 +-7.556659e-01 5.798002e-02 -6.523860e-01 -2.657710e+02 2.607369e-02 9.979474e-01 5.848996e-02 -1.493142e+00 6.544381e-01 2.718876e-02 -7.556265e-01 3.674886e+02 +-7.950333e-01 6.167903e-02 -6.034217e-01 -2.661217e+02 3.260469e-02 9.977239e-01 5.902479e-02 -1.467416e+00 6.056889e-01 2.725229e-02 -7.952347e-01 3.670280e+02 +-8.302375e-01 6.313617e-02 -5.538226e-01 -2.664510e+02 3.655601e-02 9.975928e-01 5.892506e-02 -1.440143e+00 5.562098e-01 2.867625e-02 -8.305470e-01 3.665252e+02 +-8.603971e-01 6.415426e-02 -5.055702e-01 -2.667197e+02 3.958947e-02 9.974609e-01 5.919795e-02 -1.408592e+00 5.080843e-01 3.091848e-02 -8.607522e-01 3.659366e+02 +-8.857291e-01 6.380009e-02 -4.597974e-01 -2.670078e+02 4.074403e-02 9.973722e-01 5.990526e-02 -1.374613e+00 4.624110e-01 3.432583e-02 -8.860009e-01 3.653626e+02 +-9.063143e-01 6.373376e-02 -4.177708e-01 -2.672518e+02 4.214039e-02 9.972649e-01 6.071993e-02 -1.337219e+00 4.204980e-01 3.742632e-02 -9.065211e-01 3.647238e+02 +-9.231490e-01 6.437941e-02 -3.790136e-01 -2.675078e+02 4.437810e-02 9.971333e-01 6.128347e-02 -1.302547e+00 3.818724e-01 3.975387e-02 -9.233596e-01 3.640868e+02 +-9.375857e-01 6.604607e-02 -3.414250e-01 -2.677469e+02 4.751933e-02 9.969222e-01 6.235444e-02 -1.267399e+00 3.444924e-01 4.223834e-02 -9.378384e-01 3.634232e+02 +-9.496827e-01 6.672660e-02 -3.060235e-01 -2.679495e+02 5.005857e-02 9.968197e-01 6.200390e-02 -1.230084e+00 3.091876e-01 4.356492e-02 -9.500026e-01 3.627093e+02 +-9.592289e-01 6.799661e-02 -2.743292e-01 -2.681502e+02 5.374968e-02 9.968022e-01 5.912945e-02 -1.193968e+00 2.774726e-01 4.197356e-02 -9.598162e-01 3.619941e+02 +-9.667690e-01 7.137306e-02 -2.454867e-01 -2.683408e+02 6.002537e-02 9.967669e-01 5.341085e-02 -1.159372e+00 2.485051e-01 3.690051e-02 -9.679274e-01 3.612561e+02 +-9.729963e-01 7.289191e-02 -2.190091e-01 -2.685065e+02 6.438942e-02 9.968768e-01 4.572232e-02 -1.125956e+00 2.216579e-01 3.038578e-02 -9.746509e-01 3.604852e+02 +-9.782656e-01 7.602974e-02 -1.929142e-01 -2.686673e+02 6.914302e-02 9.967141e-01 4.219329e-02 -1.092700e+00 1.954882e-01 2.793757e-02 -9.803080e-01 3.596972e+02 +-9.825147e-01 8.193307e-02 -1.671880e-01 -2.688089e+02 7.584885e-02 9.962145e-01 4.246907e-02 -1.060003e+00 1.700347e-01 2.904546e-02 -9.850099e-01 3.588705e+02 +-9.859987e-01 8.655684e-02 -1.425292e-01 -2.689415e+02 8.074269e-02 9.956686e-01 4.609410e-02 -1.030964e+00 1.459016e-01 3.394053e-02 -9.887167e-01 3.580268e+02 +-9.889214e-01 8.703438e-02 -1.202482e-01 -2.690509e+02 8.176028e-02 9.954893e-01 4.812819e-02 -9.979144e-01 1.238946e-01 3.776347e-02 -9.915765e-01 3.571544e+02 +-9.909708e-01 8.675687e-02 -1.022258e-01 -2.691431e+02 8.235772e-02 9.955172e-01 4.650373e-02 -9.680067e-01 1.058021e-01 3.766475e-02 -9.936736e-01 3.562606e+02 +-9.927362e-01 8.048477e-02 -8.942668e-02 -2.692204e+02 7.682653e-02 9.960894e-01 4.362871e-02 -9.334670e-01 9.258841e-02 3.644145e-02 -9.950373e-01 3.553486e+02 +-9.938855e-01 7.320323e-02 -8.266216e-02 -2.692894e+02 7.013360e-02 9.967572e-01 3.945102e-02 -8.989503e-01 8.528203e-02 3.341239e-02 -9.957964e-01 3.544158e+02 +-9.945306e-01 6.854885e-02 -7.880321e-02 -2.693640e+02 6.574371e-02 9.971256e-01 3.765963e-02 -8.668551e-01 8.115822e-02 3.227284e-02 -9.961785e-01 3.534604e+02 +-9.944866e-01 7.056510e-02 -7.757015e-02 -2.694488e+02 6.767538e-02 9.969341e-01 3.927423e-02 -8.347736e-01 8.010371e-02 3.380810e-02 -9.962130e-01 3.524773e+02 +-9.944779e-01 7.146719e-02 -7.685189e-02 -2.695388e+02 6.850200e-02 9.968264e-01 4.055417e-02 -8.074597e-01 7.950628e-02 3.506571e-02 -9.962174e-01 3.514737e+02 +-9.943552e-01 7.402769e-02 -7.601160e-02 -2.696285e+02 7.105876e-02 9.966270e-01 4.105130e-02 -7.752988e-01 7.879414e-02 3.541827e-02 -9.962615e-01 3.504510e+02 +-9.944300e-01 7.408382e-02 -7.497139e-02 -2.697180e+02 7.113855e-02 9.966141e-01 4.122504e-02 -7.432067e-01 7.777166e-02 3.566206e-02 -9.963331e-01 3.494071e+02 +-9.944729e-01 7.439307e-02 -7.409115e-02 -2.698046e+02 7.134851e-02 9.965272e-01 4.292801e-02 -7.077913e-01 7.702739e-02 3.740444e-02 -9.963270e-01 3.483477e+02 +-9.946195e-01 7.334779e-02 -7.315900e-02 -2.698981e+02 7.024942e-02 9.965557e-01 4.406477e-02 -6.752965e-01 7.613907e-02 3.868830e-02 -9.963463e-01 3.472685e+02 +-9.948100e-01 7.197182e-02 -7.192516e-02 -2.699857e+02 6.884473e-02 9.966096e-01 4.505235e-02 -6.396188e-01 7.492380e-02 3.986686e-02 -9.963920e-01 3.461777e+02 +-9.949922e-01 7.050336e-02 -7.085136e-02 -2.700781e+02 6.723888e-02 9.966078e-01 4.745234e-02 -6.044389e-01 7.395656e-02 4.245074e-02 -9.963575e-01 3.450728e+02 +-9.951524e-01 6.973214e-02 -6.934791e-02 -2.701670e+02 6.643746e-02 9.965997e-01 4.873468e-02 -5.681308e-01 7.251048e-02 4.389113e-02 -9.964014e-01 3.439592e+02 +-9.952719e-01 6.957271e-02 -6.777569e-02 -2.702576e+02 6.643108e-02 9.966570e-01 4.755634e-02 -5.329150e-01 7.085774e-02 4.282907e-02 -9.965665e-01 3.428410e+02 +-9.953864e-01 7.009043e-02 -6.552363e-02 -2.703457e+02 6.722255e-02 9.967228e-01 4.499660e-02 -4.961709e-01 6.846273e-02 4.038433e-02 -9.968359e-01 3.417088e+02 +-9.954890e-01 7.098331e-02 -6.295385e-02 -2.704321e+02 6.827999e-02 9.966909e-01 4.410301e-02 -4.597162e-01 6.587611e-02 3.960557e-02 -9.970414e-01 3.405645e+02 +-9.955646e-01 7.226277e-02 -6.024401e-02 -2.705181e+02 6.958564e-02 9.965417e-01 4.541347e-02 -4.241724e-01 6.331737e-02 4.101992e-02 -9.971500e-01 3.394089e+02 +-9.957030e-01 7.283750e-02 -5.718665e-02 -2.705990e+02 7.015935e-02 9.964031e-01 4.752267e-02 -3.861946e-01 6.044238e-02 4.330628e-02 -9.972318e-01 3.382395e+02 +-9.957444e-01 7.481285e-02 -5.381704e-02 -2.706795e+02 7.200627e-02 9.960306e-01 5.232679e-02 -3.431655e-01 5.751814e-02 4.822894e-02 -9.971788e-01 3.370523e+02 +-9.958315e-01 7.642866e-02 -4.978319e-02 -2.707545e+02 7.342864e-02 9.955218e-01 5.953562e-02 -2.933356e-01 5.411048e-02 5.563192e-02 -9.969840e-01 3.358508e+02 +-9.957975e-01 7.920045e-02 -4.598588e-02 -2.708291e+02 7.624050e-02 9.951034e-01 6.290113e-02 -2.407114e-01 5.074250e-02 5.913079e-02 -9.969597e-01 3.346520e+02 +-9.958967e-01 7.958413e-02 -4.308389e-02 -2.708950e+02 7.709926e-02 9.954181e-01 5.655495e-02 -1.900227e-01 4.738736e-02 5.300114e-02 -9.974694e-01 3.334617e+02 +-9.961736e-01 7.681930e-02 -4.167822e-02 -2.709555e+02 7.503229e-02 9.962591e-01 4.287041e-02 -1.489872e-01 4.481558e-02 3.957915e-02 -9.982109e-01 3.322792e+02 +-9.965104e-01 7.288765e-02 -4.067542e-02 -2.710093e+02 7.163075e-02 9.969321e-01 3.154914e-02 -1.216968e-01 4.285018e-02 2.852544e-02 -9.986741e-01 3.310954e+02 +-9.968862e-01 6.917515e-02 -3.785272e-02 -2.710556e+02 6.804240e-02 9.972180e-01 3.043887e-02 -1.013445e-01 3.985303e-02 2.776849e-02 -9.988196e-01 3.299025e+02 +-9.971641e-01 6.728411e-02 -3.371384e-02 -2.711007e+02 6.585148e-02 9.969476e-01 4.194163e-02 -8.058966e-02 3.643294e-02 3.960258e-02 -9.985510e-01 3.286998e+02 +-9.973700e-01 6.644121e-02 -2.896235e-02 -2.711435e+02 6.486956e-02 9.965279e-01 5.219162e-02 -5.039465e-02 3.232946e-02 5.017557e-02 -9.982170e-01 3.275012e+02 +-9.975588e-01 6.574960e-02 -2.352587e-02 -2.711760e+02 6.438128e-02 9.964178e-01 5.483248e-02 -7.761684e-03 2.704681e-02 5.318399e-02 -9.982183e-01 3.263136e+02 +-9.976775e-01 6.568276e-02 -1.804203e-02 -2.712052e+02 6.463639e-02 9.964746e-01 5.348349e-02 3.310083e-02 2.149137e-02 5.219309e-02 -9.984057e-01 3.251264e+02 +-9.977647e-01 6.566128e-02 -1.242496e-02 -2.712318e+02 6.493222e-02 9.965321e-01 5.203395e-02 7.494099e-02 1.579849e-02 5.111085e-02 -9.985680e-01 3.239446e+02 +-9.978074e-01 6.582104e-02 -6.926571e-03 -2.712514e+02 6.537422e-02 9.965053e-01 5.199474e-02 1.141247e-01 1.032471e-02 5.142791e-02 -9.986233e-01 3.227624e+02 +-9.977604e-01 6.687953e-02 -1.192345e-03 -2.712677e+02 6.672501e-02 9.963904e-01 5.247749e-02 1.520703e-01 4.697711e-03 5.228039e-02 -9.986213e-01 3.215873e+02 +-9.977015e-01 6.760803e-02 4.569895e-03 -2.712761e+02 6.775570e-02 9.962751e-01 5.333896e-02 1.893840e-01 -9.467305e-04 5.352599e-02 -9.985660e-01 3.204122e+02 +-9.975340e-01 6.942821e-02 1.028616e-02 -2.712806e+02 6.988797e-02 9.960649e-01 5.450084e-02 2.268718e-01 -6.461783e-03 5.508530e-02 -9.984607e-01 3.192394e+02 +-9.973632e-01 7.074716e-02 1.617177e-02 -2.712752e+02 7.153995e-02 9.959052e-01 5.527077e-02 2.664564e-01 -1.219530e-02 5.628195e-02 -9.983404e-01 3.180705e+02 +-9.971886e-01 7.163696e-02 2.198084e-02 -2.712636e+02 7.273679e-02 9.958795e-01 5.416084e-02 3.061820e-01 -1.801035e-02 5.560738e-02 -9.982902e-01 3.169064e+02 +-9.968139e-01 7.481418e-02 2.765800e-02 -2.712490e+02 7.620951e-02 9.956604e-01 5.340825e-02 3.486559e-01 -2.354228e-02 5.534588e-02 -9.981896e-01 3.157431e+02 +-9.966498e-01 7.479605e-02 3.308823e-02 -2.712229e+02 7.648599e-02 9.956527e-01 5.315615e-02 3.873162e-01 -2.896852e-02 5.550884e-02 -9.980378e-01 3.145820e+02 +-9.964208e-01 7.538519e-02 3.824592e-02 -2.711913e+02 7.736894e-02 9.955740e-01 5.335110e-02 4.270762e-01 -3.405476e-02 5.611918e-02 -9.978431e-01 3.134226e+02 +-9.961519e-01 7.641674e-02 4.291773e-02 -2.711557e+02 7.860147e-02 9.955615e-01 5.175995e-02 4.663933e-01 -3.877191e-02 5.493416e-02 -9.977369e-01 3.122684e+02 +-9.956684e-01 8.010701e-02 4.719433e-02 -2.711200e+02 8.241492e-02 9.953843e-01 4.917223e-02 5.038023e-01 -4.303745e-02 5.284874e-02 -9.976746e-01 3.111206e+02 +-9.952743e-01 8.216140e-02 5.175631e-02 -2.710773e+02 8.467576e-02 9.952314e-01 4.841867e-02 5.413927e-01 -4.753136e-02 5.257235e-02 -9.974852e-01 3.099715e+02 +-9.948169e-01 8.415365e-02 5.707466e-02 -2.710307e+02 8.704820e-02 9.949345e-01 5.027860e-02 5.733950e-01 -5.255442e-02 5.498623e-02 -9.971030e-01 3.088260e+02 +-9.942616e-01 8.693081e-02 6.234615e-02 -2.709780e+02 9.003529e-02 9.947403e-01 4.884083e-02 6.073762e-01 -5.777245e-02 5.417391e-02 -9.968588e-01 3.076838e+02 +-9.937422e-01 8.920411e-02 6.722477e-02 -2.709193e+02 9.247303e-02 9.945964e-01 4.718865e-02 6.429063e-01 -6.265209e-02 5.310982e-02 -9.966213e-01 3.065447e+02 +-9.932863e-01 9.040520e-02 7.217516e-02 -2.708532e+02 9.407040e-02 9.943538e-01 4.910363e-02 6.769844e-01 -6.732842e-02 5.556350e-02 -9.961824e-01 3.054053e+02 +-9.928274e-01 9.204529e-02 7.629900e-02 -2.707827e+02 9.606595e-02 9.940773e-01 5.080987e-02 7.114903e-01 -7.117029e-02 5.777515e-02 -9.957895e-01 3.042656e+02 +-9.924589e-01 9.280009e-02 8.008425e-02 -2.707055e+02 9.694584e-02 9.940567e-01 4.952537e-02 7.448834e-01 -7.501232e-02 5.691572e-02 -9.955570e-01 3.031267e+02 +-9.922473e-01 9.207426e-02 8.347329e-02 -2.706208e+02 9.621119e-02 9.942524e-01 4.696378e-02 7.792041e-01 -7.866935e-02 5.463074e-02 -9.954027e-01 3.019899e+02 +-9.921506e-01 9.031474e-02 8.649043e-02 -2.705286e+02 9.447878e-02 9.944948e-01 4.531846e-02 8.152040e-01 -8.192136e-02 5.313423e-02 -9.952213e-01 3.008531e+02 +-9.918996e-01 9.023486e-02 8.940374e-02 -2.704364e+02 9.448154e-02 9.945335e-01 4.445669e-02 8.483700e-01 -8.490347e-02 5.254357e-02 -9.950027e-01 2.997147e+02 +-9.916109e-01 9.047224e-02 9.231853e-02 -2.703399e+02 9.489726e-02 9.944823e-01 4.471575e-02 8.804023e-01 -8.776360e-02 5.310139e-02 -9.947249e-01 2.985740e+02 +-9.912128e-01 9.157351e-02 9.545401e-02 -2.702420e+02 9.612952e-02 9.943839e-01 4.426804e-02 9.113774e-01 -9.086415e-02 5.305499e-02 -9.944490e-01 2.974294e+02 +-9.907236e-01 9.327854e-02 9.882264e-02 -2.701397e+02 9.785017e-02 9.942949e-01 4.246059e-02 9.429296e-01 -9.429819e-02 5.173651e-02 -9.941987e-01 2.962861e+02 +-9.903366e-01 9.374056e-02 1.022063e-01 -2.700337e+02 9.837716e-02 9.942919e-01 4.129893e-02 9.728408e-01 -9.775149e-02 5.095460e-02 -9.939055e-01 2.951400e+02 +-9.900694e-01 9.285004e-02 1.055531e-01 -2.699196e+02 9.767389e-02 9.943537e-01 4.147806e-02 1.000896e+00 -1.011058e-01 5.137592e-02 -9.935482e-01 2.939899e+02 +-9.899517e-01 9.021888e-02 1.088867e-01 -2.697986e+02 9.526031e-02 9.945655e-01 4.201159e-02 1.026210e+00 -1.045047e-01 5.196202e-02 -9.931660e-01 2.928398e+02 +-9.897360e-01 8.858977e-02 1.121362e-01 -2.696736e+02 9.376428e-02 9.947193e-01 4.173416e-02 1.050612e+00 -1.078468e-01 5.182016e-02 -9.928160e-01 2.916854e+02 +-9.893787e-01 8.841039e-02 1.153841e-01 -2.695452e+02 9.372535e-02 9.947340e-01 4.147042e-02 1.077503e+00 -1.111100e-01 5.184435e-02 -9.924548e-01 2.905285e+02 +-9.889695e-01 8.855236e-02 1.187342e-01 -2.694146e+02 9.401464e-02 9.947175e-01 4.120975e-02 1.103750e+00 -1.144578e-01 5.191793e-02 -9.920705e-01 2.893691e+02 +-9.884294e-01 8.971990e-02 1.223021e-01 -2.692797e+02 9.530973e-02 9.946179e-01 4.063617e-02 1.127733e+00 -1.179980e-01 5.182256e-02 -9.916606e-01 2.882058e+02 +-9.879254e-01 9.033917e-02 1.258663e-01 -2.691417e+02 9.621368e-02 9.944997e-01 4.139025e-02 1.153037e+00 -1.214348e-01 5.300053e-02 -9.911833e-01 2.870421e+02 +-9.875118e-01 8.970845e-02 1.295100e-01 -2.689946e+02 9.589498e-02 9.944906e-01 4.233795e-02 1.179905e+00 -1.249984e-01 5.422858e-02 -9.906738e-01 2.858684e+02 +-9.871120e-01 8.908498e-02 1.329432e-01 -2.688454e+02 9.551043e-02 9.945099e-01 4.275186e-02 1.208103e+00 -1.284048e-01 5.489833e-02 -9.902011e-01 2.846997e+02 +-9.867916e-01 8.733446e-02 1.364374e-01 -2.686883e+02 9.396902e-02 9.946480e-01 4.295568e-02 1.237435e+00 -1.319557e-01 5.520918e-02 -9.897169e-01 2.835282e+02 +-9.864770e-01 8.557021e-02 1.397893e-01 -2.685263e+02 9.226600e-02 9.948427e-01 4.213030e-02 1.268181e+00 -1.354632e-01 5.445836e-02 -9.892845e-01 2.823529e+02 +-9.861652e-01 8.360779e-02 1.431362e-01 -2.683591e+02 9.024700e-02 9.950945e-01 4.052626e-02 1.298323e+00 -1.390457e-01 5.288319e-02 -9.888729e-01 2.811767e+02 +-9.858601e-01 8.129920e-02 1.465279e-01 -2.681889e+02 8.783796e-02 9.953823e-01 3.871024e-02 1.326161e+00 -1.427042e-01 5.103358e-02 -9.884488e-01 2.799981e+02 +-9.855767e-01 7.823214e-02 1.500613e-01 -2.680123e+02 8.483830e-02 9.956649e-01 3.812866e-02 1.352951e+00 -1.464279e-01 5.030966e-02 -9.879411e-01 2.788149e+02 +-9.851662e-01 7.565081e-02 1.540276e-01 -2.678302e+02 8.263458e-02 9.957989e-01 3.944602e-02 1.379858e+00 -1.503964e-01 5.158889e-02 -9.872788e-01 2.776277e+02 +-9.846767e-01 7.400812e-02 1.579074e-01 -2.676449e+02 8.142720e-02 9.958342e-01 4.103436e-02 1.407297e+00 -1.542127e-01 5.326352e-02 -9.866009e-01 2.764384e+02 +-9.840784e-01 7.289897e-02 1.620975e-01 -2.674543e+02 8.047588e-02 9.959265e-01 4.067020e-02 1.433716e+00 -1.584724e-01 5.306759e-02 -9.859362e-01 2.752487e+02 +-9.833353e-01 7.280203e-02 1.665884e-01 -2.672599e+02 8.038420e-02 9.959918e-01 3.922465e-02 1.461436e+00 -1.630650e-01 5.196205e-02 -9.852460e-01 2.740573e+02 +-9.824828e-01 7.347186e-02 1.712588e-01 -2.670607e+02 8.113623e-02 9.959714e-01 3.818228e-02 1.488638e+00 -1.677635e-01 5.140872e-02 -9.844859e-01 2.728648e+02 +-9.816678e-01 7.315541e-02 1.760021e-01 -2.668545e+02 8.119869e-02 9.959373e-01 3.893088e-02 1.516615e+00 -1.724390e-01 5.250832e-02 -9.836196e-01 2.716678e+02 +-9.808425e-01 7.149137e-02 1.812099e-01 -2.666390e+02 8.031775e-02 9.958909e-01 4.183787e-02 1.544442e+00 -1.774742e-01 5.559073e-02 -9.825540e-01 2.704691e+02 +-9.799766e-01 6.971420e-02 1.865095e-01 -2.664156e+02 7.928227e-02 9.958658e-01 4.433429e-02 1.572240e+00 -1.826477e-01 5.823346e-02 -9.814523e-01 2.692676e+02 +-9.790573e-01 6.796493e-02 1.919053e-01 -2.661840e+02 7.789732e-02 9.959594e-01 4.468667e-02 1.602224e+00 -1.880928e-01 5.869970e-02 -9.803955e-01 2.680655e+02 +-9.780783e-01 6.652413e-02 1.973259e-01 -2.659467e+02 7.653354e-02 9.961162e-01 4.353210e-02 1.632894e+00 -1.936636e-01 5.767984e-02 -9.793709e-01 2.668630e+02 +-9.769548e-01 6.680383e-02 2.027230e-01 -2.657037e+02 7.659329e-02 9.962262e-01 4.082633e-02 1.663368e+00 -1.992306e-01 5.541269e-02 -9.783846e-01 2.656599e+02 +-9.757858e-01 6.695569e-02 2.082284e-01 -2.654539e+02 7.653733e-02 9.963310e-01 3.829442e-02 1.691837e+00 -2.049004e-01 5.330439e-02 -9.773302e-01 2.644563e+02 +-9.745438e-01 6.813991e-02 2.135919e-01 -2.651976e+02 7.775180e-02 9.962889e-01 3.691846e-02 1.718526e+00 -2.102836e-01 5.258579e-02 -9.762251e-01 2.632442e+02 +-9.733848e-01 6.775471e-02 2.189324e-01 -2.649337e+02 7.784777e-02 9.962484e-01 3.779840e-02 1.742552e+00 -2.155500e-01 5.383577e-02 -9.750076e-01 2.620285e+02 +-9.723630e-01 6.562223e-02 2.240627e-01 -2.646581e+02 7.647466e-02 9.962650e-01 4.009582e-02 1.765839e+00 -2.205946e-01 5.612279e-02 -9.737495e-01 2.608069e+02 +-9.713754e-01 6.313514e-02 2.290065e-01 -2.643736e+02 7.477152e-02 9.962951e-01 4.248774e-02 1.789773e+00 -2.254755e-01 5.839469e-02 -9.724972e-01 2.595807e+02 +-9.703849e-01 6.076794e-02 2.337956e-01 -2.640836e+02 7.315597e-02 9.963193e-01 4.467645e-02 1.816046e+00 -2.302202e-01 6.045689e-02 -9.712587e-01 2.583561e+02 +-9.691849e-01 6.140342e-02 2.385590e-01 -2.637905e+02 7.405334e-02 9.962644e-01 4.442217e-02 1.840519e+00 -2.349402e-01 6.071938e-02 -9.701114e-01 2.571331e+02 +-9.677367e-01 6.396998e-02 2.437081e-01 -2.634962e+02 7.639038e-02 9.961993e-01 4.184884e-02 1.865352e+00 -2.401048e-01 5.911560e-02 -9.689453e-01 2.559137e+02 +-9.659869e-01 6.891989e-02 2.492377e-01 -2.631986e+02 8.144594e-02 9.958632e-01 4.028647e-02 1.889323e+00 -2.454302e-01 5.921559e-02 -9.676040e-01 2.546945e+02 +-9.642653e-01 7.135705e-02 2.551483e-01 -2.628927e+02 8.425482e-02 9.956423e-01 3.996848e-02 1.911243e+00 -2.511844e-01 6.003768e-02 -9.660755e-01 2.534794e+02 +-9.625236e-01 7.331616e-02 2.610999e-01 -2.625790e+02 8.662878e-02 9.954440e-01 3.983185e-02 1.931685e+00 -2.569900e-01 6.095785e-02 -9.644896e-01 2.522687e+02 +-9.608804e-01 7.433512e-02 2.668019e-01 -2.622495e+02 8.825249e-02 9.952728e-01 4.054076e-02 1.955211e+00 -2.625270e-01 6.250074e-02 -9.628983e-01 2.510443e+02 +-9.595227e-01 7.368490e-02 2.718212e-01 -2.619183e+02 8.858720e-02 9.951420e-01 4.294909e-02 1.979130e+00 -2.673360e-01 6.529049e-02 -9.613888e-01 2.498414e+02 +-9.582683e-01 7.384542e-02 2.761681e-01 -2.615786e+02 8.933864e-02 9.950321e-01 4.392907e-02 2.003568e+00 -2.715521e-01 6.676830e-02 -9.601049e-01 2.486317e+02 +-9.570234e-01 7.528777e-02 2.800681e-01 -2.612373e+02 9.044385e-02 9.950335e-01 4.157206e-02 2.029564e+00 -2.755472e-01 6.511585e-02 -9.590795e-01 2.474298e+02 +-9.558055e-01 7.878243e-02 2.832475e-01 -2.608939e+02 9.287582e-02 9.950027e-01 3.665509e-02 2.053603e+00 -2.789443e-01 6.134197e-02 -9.583460e-01 2.462342e+02 +-9.547763e-01 7.959008e-02 2.864745e-01 -2.605436e+02 9.275947e-02 9.951523e-01 3.267401e-02 2.073950e+00 -2.824852e-01 5.776958e-02 -9.575305e-01 2.450380e+02 +-9.536873e-01 8.091347e-02 2.897130e-01 -2.601893e+02 9.395803e-02 9.950815e-01 3.137955e-02 2.089988e+00 -2.857490e-01 5.714713e-02 -9.565990e-01 2.438398e+02 +-9.525884e-01 8.069721e-02 2.933657e-01 -2.598303e+02 9.502108e-02 9.948639e-01 3.488212e-02 2.109210e+00 -2.890440e-01 6.110421e-02 -9.553637e-01 2.426400e+02 +-9.516789e-01 7.867988e-02 2.968448e-01 -2.594631e+02 9.437786e-02 9.947760e-01 3.890429e-02 2.130851e+00 -2.922331e-01 6.503996e-02 -9.541329e-01 2.414419e+02 +-9.505083e-01 7.923331e-02 3.004265e-01 -2.590940e+02 9.526147e-02 9.946857e-01 3.905968e-02 2.156640e+00 -2.957351e-01 6.574561e-02 -9.530048e-01 2.402461e+02 +-9.494500e-01 7.873549e-02 3.038841e-01 -2.587192e+02 9.474295e-02 9.947658e-01 3.827217e-02 2.181900e+00 -2.992801e-01 6.512837e-02 -9.519399e-01 2.390521e+02 +-9.483478e-01 7.882646e-02 3.072832e-01 -2.583388e+02 9.486225e-02 9.947809e-01 3.757878e-02 2.205692e+00 -3.027172e-01 6.478731e-02 -9.508758e-01 2.378580e+02 +-9.469170e-01 8.023515e-02 3.113045e-01 -2.579556e+02 9.603721e-02 9.947358e-01 3.574144e-02 2.227076e+00 -3.067980e-01 6.374098e-02 -9.496378e-01 2.366662e+02 +-9.451569e-01 8.200113e-02 3.161555e-01 -2.575677e+02 9.734037e-02 9.947037e-01 3.300614e-02 2.247151e+00 -3.117745e-01 6.197066e-02 -9.481330e-01 2.354799e+02 +-9.432132e-01 8.480714e-02 3.211802e-01 -2.571743e+02 9.964282e-02 9.945707e-01 3.000716e-02 2.265334e+00 -3.168916e-01 6.030644e-02 -9.465425e-01 2.342908e+02 +-9.414341e-01 8.577984e-02 3.261039e-01 -2.567727e+02 1.009218e-01 9.944489e-01 2.976834e-02 2.283581e+00 -3.217401e-01 6.093592e-02 -9.448651e-01 2.331048e+02 +-9.397855e-01 8.502834e-02 3.310189e-01 -2.563644e+02 1.013855e-01 9.943184e-01 3.243124e-02 2.301503e+00 -3.263806e-01 6.403892e-02 -9.430666e-01 2.319181e+02 +-9.380280e-01 8.430929e-02 3.361481e-01 -2.559481e+02 1.025515e-01 9.940447e-01 3.685563e-02 2.322949e+00 -3.310389e-01 6.904408e-02 -9.410877e-01 2.307297e+02 +-9.361410e-01 8.590669e-02 3.409693e-01 -2.555313e+02 1.054889e-01 9.936445e-01 3.927555e-02 2.344781e+00 -3.354282e-01 7.273592e-02 -9.392536e-01 2.295485e+02 +-9.343416e-01 8.779132e-02 3.453963e-01 -2.551075e+02 1.078813e-01 9.933852e-01 3.933843e-02 2.368457e+00 -3.396580e-01 7.401731e-02 -9.376320e-01 2.283692e+02 +-9.327473e-01 9.027214e-02 3.490465e-01 -2.546801e+02 1.099127e-01 9.932584e-01 3.683526e-02 2.391368e+00 -3.433681e-01 7.272262e-02 -9.363811e-01 2.271953e+02 +-9.313230e-01 9.223402e-02 3.523216e-01 -2.542484e+02 1.107796e-01 9.933037e-01 3.279723e-02 2.411210e+00 -3.469373e-01 6.957485e-02 -9.353041e-01 2.260281e+02 +-9.302222e-01 9.176865e-02 3.553381e-01 -2.538095e+02 1.090956e-01 9.936084e-01 2.898925e-02 2.427567e+00 -3.504066e-01 6.573224e-02 -9.342882e-01 2.248654e+02 +-9.294076e-01 8.965632e-02 3.579990e-01 -2.533654e+02 1.067946e-01 9.938769e-01 2.834753e-02 2.442942e+00 -3.532654e-01 6.457877e-02 -9.332915e-01 2.237046e+02 +-9.287395e-01 8.595073e-02 3.606321e-01 -2.529191e+02 1.038557e-01 9.941237e-01 3.052761e-02 2.455450e+00 -3.558890e-01 6.580589e-02 -9.322084e-01 2.225440e+02 +-9.280700e-01 8.336548e-02 3.629549e-01 -2.524734e+02 1.021337e-01 9.942300e-01 3.279400e-02 2.469371e+00 -3.581268e-01 6.750505e-02 -9.312294e-01 2.213861e+02 +-9.272910e-01 8.248526e-02 3.651405e-01 -2.520240e+02 1.014024e-01 9.943012e-01 3.290331e-02 2.489475e+00 -3.603456e-01 6.753706e-02 -9.303707e-01 2.202307e+02 +-9.262944e-01 8.303124e-02 3.675386e-01 -2.515748e+02 1.015451e-01 9.943388e-01 3.128769e-02 2.508039e+00 -3.628600e-01 6.630333e-02 -9.294818e-01 2.190796e+02 +-9.254431e-01 8.261416e-02 3.697703e-01 -2.511219e+02 1.005807e-01 9.944903e-01 2.953906e-02 2.528700e+00 -3.652926e-01 6.452845e-02 -9.286535e-01 2.179313e+02 +-9.245149e-01 8.284573e-02 3.720334e-01 -2.506671e+02 1.010007e-01 9.944476e-01 2.954288e-02 2.547424e+00 -3.675202e-01 6.488847e-02 -9.277490e-01 2.167823e+02 +-9.236877e-01 8.175644e-02 3.743221e-01 -2.502088e+02 1.011529e-01 9.943421e-01 3.243138e-02 2.567341e+00 -3.695528e-01 6.782022e-02 -9.267314e-01 2.156338e+02 +-9.227484e-01 8.028408e-02 3.769482e-01 -2.497482e+02 1.011494e-01 9.942250e-01 3.585359e-02 2.587206e+00 -3.718928e-01 7.121190e-02 -9.255401e-01 2.144875e+02 +-9.214783e-01 8.130169e-02 3.798262e-01 -2.492875e+02 1.020807e-01 9.941654e-01 3.485234e-02 2.607730e+00 -3.747765e-01 7.088860e-02 -9.244010e-01 2.133483e+02 +-9.200681e-01 8.257470e-02 3.829572e-01 -2.488235e+02 1.020702e-01 9.942993e-01 3.083245e-02 2.629771e+00 -3.782280e-01 6.745643e-02 -9.232514e-01 2.122123e+02 +-9.186800e-01 8.241647e-02 3.863090e-01 -2.483518e+02 1.013135e-01 9.944383e-01 2.877627e-02 2.649914e+00 -3.817888e-01 6.557447e-02 -9.219204e-01 2.110781e+02 +-9.173459e-01 8.187360e-02 3.895810e-01 -2.478753e+02 1.008063e-01 9.945016e-01 2.836578e-02 2.667369e+00 -3.851165e-01 6.529342e-02 -9.205552e-01 2.099454e+02 +-9.158936e-01 8.158913e-02 3.930423e-01 -2.473962e+02 1.012288e-01 9.944268e-01 2.946340e-02 2.684589e+00 -3.884479e-01 6.677252e-02 -9.190482e-01 2.088161e+02 +-9.143172e-01 8.071936e-02 3.968734e-01 -2.469117e+02 1.016429e-01 9.943082e-01 3.193436e-02 2.703437e+00 -3.920368e-01 6.953748e-02 -9.173176e-01 2.076871e+02 +-9.128017e-01 7.876962e-02 4.007350e-01 -2.464218e+02 1.005465e-01 9.943658e-01 3.357125e-02 2.721040e+00 -3.958328e-01 7.093638e-02 -9.155787e-01 2.065587e+02 +-9.113985e-01 7.527294e-02 4.045822e-01 -2.459246e+02 9.692621e-02 9.947352e-01 3.327319e-02 2.741308e+00 -3.999476e-01 6.953974e-02 -9.138961e-01 2.054384e+02 +-9.100804e-01 7.191683e-02 4.081443e-01 -2.454226e+02 9.292987e-02 9.951627e-01 3.186295e-02 2.759334e+00 -4.038785e-01 6.692663e-02 -9.123612e-01 2.043216e+02 +-9.088628e-01 6.855324e-02 4.114231e-01 -2.449168e+02 8.842681e-02 9.956475e-01 2.944161e-02 2.775884e+00 -4.076140e-01 6.313920e-02 -9.109688e-01 2.032077e+02 +-9.074337e-01 6.622012e-02 4.149446e-01 -2.444075e+02 8.501849e-02 9.960142e-01 2.697335e-02 2.791578e+00 -4.115045e-01 5.975448e-02 -9.094467e-01 2.020960e+02 +-9.057280e-01 6.502386e-02 4.188421e-01 -2.438972e+02 8.375218e-02 9.961351e-01 2.646373e-02 2.804890e+00 -4.155025e-01 5.904786e-02 -9.076733e-01 2.009836e+02 +-9.036124e-01 6.434870e-02 4.234901e-01 -2.433840e+02 8.444567e-02 9.960106e-01 2.884164e-02 2.819677e+00 -4.199447e-01 6.182356e-02 -9.054414e-01 1.998708e+02 +-9.012472e-01 6.237515e-02 4.287925e-01 -2.428649e+02 8.442637e-02 9.958969e-01 3.257936e-02 2.835793e+00 -4.250009e-01 6.556343e-02 -9.028153e-01 1.987617e+02 +-8.988452e-01 6.122669e-02 4.339685e-01 -2.423403e+02 8.486241e-02 9.957679e-01 3.528039e-02 2.855221e+00 -4.299717e-01 6.853921e-02 -9.002370e-01 1.976577e+02 +-8.965096e-01 6.039429e-02 4.388886e-01 -2.418132e+02 8.414526e-02 9.958440e-01 3.484647e-02 2.873074e+00 -4.349601e-01 6.817058e-02 -8.978655e-01 1.965651e+02 +-8.942391e-01 6.059770e-02 4.434686e-01 -2.412790e+02 8.395396e-02 9.959163e-01 3.320340e-02 2.895059e+00 -4.396455e-01 6.692271e-02 -8.956747e-01 1.954744e+02 +-8.920227e-01 6.034029e-02 4.479449e-01 -2.407392e+02 8.351968e-02 9.959872e-01 3.215412e-02 2.915425e+00 -4.442072e-01 6.609440e-02 -8.934827e-01 1.943889e+02 +-8.898880e-01 5.973277e-02 4.522515e-01 -2.401964e+02 8.297114e-02 9.960475e-01 3.170432e-02 2.935009e+00 -4.485702e-01 6.573710e-02 -8.913267e-01 1.933099e+02 +-8.878884e-01 5.924858e-02 4.562279e-01 -2.396493e+02 8.219510e-02 9.961464e-01 3.059830e-02 2.952041e+00 -4.526569e-01 6.466756e-02 -8.893367e-01 1.922358e+02 +-8.860484e-01 5.818340e-02 4.599272e-01 -2.390982e+02 8.078032e-02 9.962927e-01 2.958632e-02 2.968590e+00 -4.565007e-01 6.336797e-02 -8.874635e-01 1.911669e+02 +-8.843000e-01 5.728354e-02 4.633921e-01 -2.385422e+02 7.994259e-02 9.963662e-01 2.938727e-02 2.983923e+00 -4.600248e-01 6.303191e-02 -8.856659e-01 1.900992e+02 +-8.825944e-01 5.557932e-02 4.668385e-01 -2.379832e+02 7.920763e-02 9.963721e-01 3.112535e-02 2.999715e+00 -4.634149e-01 6.444822e-02 -8.837946e-01 1.890354e+02 +-8.807099e-01 5.476385e-02 4.704797e-01 -2.374220e+02 7.992850e-02 9.962321e-01 3.365990e-02 3.017412e+00 -4.668636e-01 6.724933e-02 -8.817686e-01 1.879731e+02 +-8.785514e-01 5.724164e-02 4.742055e-01 -2.368616e+02 8.366913e-02 9.958858e-01 3.479815e-02 3.036881e+00 -4.702626e-01 7.024831e-02 -8.797262e-01 1.869137e+02 +-8.763699e-01 5.965879e-02 4.779297e-01 -2.362989e+02 8.649903e-02 9.956604e-01 3.432562e-02 3.056255e+00 -4.738078e-01 7.142238e-02 -8.777271e-01 1.858588e+02 +-8.741598e-01 6.213568e-02 4.816470e-01 -2.357340e+02 8.948327e-02 9.954081e-01 3.399232e-02 3.073288e+00 -4.773232e-01 7.281406e-02 -8.757058e-01 1.848044e+02 +-8.719349e-01 6.365986e-02 4.854658e-01 -2.351650e+02 9.210139e-02 9.951369e-01 3.492753e-02 3.089834e+00 -4.808814e-01 7.516659e-02 -8.735577e-01 1.837520e+02 +-8.698879e-01 6.355452e-02 4.891379e-01 -2.345884e+02 9.306812e-02 9.950003e-01 3.623119e-02 3.108160e+00 -4.843897e-01 7.704021e-02 -8.714536e-01 1.827027e+02 +-8.677588e-01 6.630878e-02 4.925423e-01 -2.340133e+02 9.519785e-02 9.948850e-01 3.378215e-02 3.130057e+00 -4.877828e-01 7.620371e-02 -8.696326e-01 1.816605e+02 +-8.657147e-01 6.826472e-02 4.958609e-01 -2.334293e+02 9.530833e-02 9.950131e-01 2.941454e-02 3.152357e+00 -4.913801e-01 7.272425e-02 -8.679036e-01 1.806245e+02 +-8.637456e-01 6.785668e-02 4.993387e-01 -2.328356e+02 9.460738e-02 9.951089e-01 2.842139e-02 3.172514e+00 -4.949678e-01 7.178996e-02 -8.659405e-01 1.795899e+02 +-8.618721e-01 6.482011e-02 5.029662e-01 -2.322316e+02 9.304495e-02 9.951734e-01 3.118614e-02 3.189631e+00 -4.985170e-01 7.367691e-02 -8.637432e-01 1.785543e+02 +-8.601191e-01 6.251760e-02 5.062478e-01 -2.316222e+02 9.063850e-02 9.953990e-01 3.107160e-02 3.205925e+00 -5.019760e-01 7.261079e-02 -8.618281e-01 1.775215e+02 +-8.582762e-01 6.278684e-02 5.093328e-01 -2.310093e+02 8.974146e-02 9.955573e-01 2.849815e-02 3.225534e+00 -5.052807e-01 7.016754e-02 -8.600976e-01 1.764910e+02 +-8.562480e-01 6.138408e-02 5.129049e-01 -2.303786e+02 8.736738e-02 9.958190e-01 2.667298e-02 3.203285e+00 -5.091231e-01 6.764983e-02 -8.580309e-01 1.754065e+02 +-8.541709e-01 6.123299e-02 5.163746e-01 -2.297438e+02 8.659697e-02 9.959260e-01 2.514659e-02 3.175702e+00 -5.127311e-01 6.619594e-02 -8.559935e-01 1.743210e+02 +-8.516190e-01 6.591762e-02 5.200000e-01 -2.291117e+02 9.009027e-02 9.957053e-01 2.132316e-02 3.160404e+00 -5.163612e-01 6.500614e-02 -8.539000e-01 1.732459e+02 +-8.492780e-01 6.809899e-02 5.235355e-01 -2.284694e+02 9.197708e-02 9.955661e-01 1.970649e-02 3.139283e+00 -5.198722e-01 6.488955e-02 -8.517759e-01 1.721658e+02 +-8.464209e-01 7.071033e-02 5.277991e-01 -2.278261e+02 9.616752e-02 9.951457e-01 2.090018e-02 3.129332e+00 -5.237591e-01 6.844746e-02 -8.491121e-01 1.710979e+02 +-8.434195e-01 7.282976e-02 5.322965e-01 -2.271763e+02 9.944667e-02 9.948114e-01 2.146052e-02 3.108331e+00 -5.279716e-01 7.103531e-02 -8.462859e-01 1.700218e+02 +-8.407242e-01 7.480081e-02 5.362721e-01 -2.265195e+02 1.011530e-01 9.946730e-01 1.983954e-02 3.097749e+00 -5.319313e-01 7.092509e-02 -8.438119e-01 1.689598e+02 +-8.382015e-01 7.562036e-02 5.400925e-01 -2.258528e+02 1.010647e-01 9.947246e-01 1.757310e-02 3.085601e+00 -5.359144e-01 6.931406e-02 -8.414221e-01 1.678978e+02 +-8.357196e-01 7.602738e-02 5.438682e-01 -2.251771e+02 1.015375e-01 9.946868e-01 1.697726e-02 3.078616e+00 -5.396878e-01 6.941121e-02 -8.389989e-01 1.668381e+02 +-8.333601e-01 7.288267e-02 5.479043e-01 -2.244955e+02 9.993827e-02 9.947990e-01 1.967668e-02 3.072032e+00 -5.436205e-01 7.115435e-02 -8.363096e-01 1.657801e+02 +-8.307063e-01 7.190805e-02 5.520474e-01 -2.238105e+02 1.008283e-01 9.946569e-01 2.216267e-02 3.063938e+00 -5.475041e-01 7.407265e-02 -8.335181e-01 1.647226e+02 +-8.282706e-01 6.960754e-02 5.559880e-01 -2.231211e+02 9.831946e-02 9.949137e-01 2.190984e-02 3.059714e+00 -5.516350e-01 7.281170e-02 -8.309014e-01 1.636783e+02 +-8.261623e-01 6.750987e-02 5.593731e-01 -2.224230e+02 9.496395e-02 9.952770e-01 2.013791e-02 3.053051e+00 -5.553716e-01 6.975744e-02 -8.286713e-01 1.626405e+02 +-8.241182e-01 6.459648e-02 5.627225e-01 -2.217245e+02 9.092672e-02 9.956788e-01 1.886719e-02 3.046865e+00 -5.590721e-01 6.671530e-02 -8.264305e-01 1.616121e+02 +-8.220745e-01 6.106070e-02 5.660964e-01 -2.210218e+02 8.758762e-02 9.959607e-01 1.976602e-02 3.035788e+00 -5.626028e-01 6.583217e-02 -8.241020e-01 1.605835e+02 +-8.198510e-01 5.983971e-02 5.694415e-01 -2.203177e+02 8.750914e-02 9.959352e-01 2.133312e-02 3.028763e+00 -5.658503e-01 6.732130e-02 -8.217549e-01 1.595595e+02 +-8.174532e-01 5.927868e-02 5.729367e-01 -2.196138e+02 8.706186e-02 9.959779e-01 2.116939e-02 3.021908e+00 -5.693774e-01 6.718590e-02 -8.193262e-01 1.585430e+02 +-8.150366e-01 5.951567e-02 5.763448e-01 -2.189067e+02 8.790939e-02 9.958969e-01 2.147652e-02 3.020274e+00 -5.727018e-01 6.817025e-02 -8.169243e-01 1.575282e+02 +-8.127269e-01 5.723559e-02 5.798268e-01 -2.181954e+02 8.672652e-02 9.959608e-01 2.324928e-02 3.019379e+00 -5.761541e-01 6.918166e-02 -8.144079e-01 1.565189e+02 +-8.108704e-01 5.367352e-02 5.827593e-01 -2.174781e+02 8.353454e-02 9.962041e-01 2.447990e-02 3.015846e+00 -5.792332e-01 6.853054e-02 -8.122760e-01 1.555150e+02 +-8.089763e-01 5.144277e-02 5.855861e-01 -2.167583e+02 8.042198e-02 9.964824e-01 2.356210e-02 3.014110e+00 -5.823141e-01 6.615516e-02 -8.102676e-01 1.545161e+02 +-8.068861e-01 5.000831e-02 5.885866e-01 -2.160368e+02 7.907978e-02 9.965856e-01 2.373617e-02 3.013882e+00 -5.853899e-01 6.569767e-02 -8.080856e-01 1.535195e+02 +-8.046609e-01 4.975703e-02 5.916462e-01 -2.153166e+02 7.965003e-02 9.965212e-01 2.452025e-02 3.013904e+00 -5.883679e-01 6.685510e-02 -8.058247e-01 1.525275e+02 +-8.021477e-01 5.345632e-02 5.947282e-01 -2.145989e+02 8.139030e-02 9.964774e-01 2.020923e-02 3.012023e+00 -5.915529e-01 6.461588e-02 -8.036728e-01 1.515422e+02 +-7.997644e-01 5.640521e-02 5.976582e-01 -2.138780e+02 8.119804e-02 9.965910e-01 1.460093e-02 3.007333e+00 -5.947972e-01 6.020597e-02 -8.016180e-01 1.505654e+02 +-7.977655e-01 5.576530e-02 6.003837e-01 -2.131507e+02 7.977474e-02 9.967225e-01 1.342307e-02 2.996851e+00 -5.976673e-01 5.860390e-02 -7.995994e-01 1.495868e+02 +-7.960572e-01 5.200307e-02 6.029831e-01 -2.124194e+02 7.808361e-02 9.967998e-01 1.711881e-02 2.988454e+00 -6.001632e-01 6.071064e-02 -7.975702e-01 1.486134e+02 +-7.939176e-01 5.090883e-02 6.058905e-01 -2.116906e+02 7.905791e-02 9.966724e-01 1.984851e-02 2.984573e+00 -6.028638e-01 6.365850e-02 -7.953004e-01 1.476420e+02 +-7.910368e-01 5.255806e-02 6.095067e-01 -2.109622e+02 8.142709e-02 9.964836e-01 1.975132e-02 2.984366e+00 -6.063253e-01 6.525437e-02 -7.925348e-01 1.466808e+02 +-7.875371e-01 5.436968e-02 6.138643e-01 -2.102282e+02 8.291594e-02 9.963917e-01 1.812430e-02 2.984566e+00 -6.106639e-01 6.517268e-02 -7.892034e-01 1.457230e+02 +-7.841139e-01 5.464721e-02 6.182064e-01 -2.094877e+02 8.290003e-02 9.964117e-01 1.706861e-02 2.985244e+00 -6.150553e-01 6.463305e-02 -7.858304e-01 1.447707e+02 +-7.813731e-01 5.120650e-02 6.219599e-01 -2.087378e+02 8.065493e-02 9.965556e-01 1.928011e-02 2.986185e+00 -6.188303e-01 6.522908e-02 -7.828117e-01 1.438226e+02 +-7.787636e-01 4.893977e-02 6.254057e-01 -2.079845e+02 8.104193e-02 9.964467e-01 2.293968e-02 2.989498e+00 -6.220607e-01 6.854866e-02 -7.799624e-01 1.428752e+02 +-7.757137e-01 4.866184e-02 6.292061e-01 -2.072294e+02 8.211089e-02 9.963299e-01 2.417535e-02 2.995588e+00 -6.257204e-01 7.041780e-02 -7.768624e-01 1.419322e+02 +-7.719634e-01 5.370565e-02 6.333942e-01 -2.064719e+02 8.799033e-02 9.958603e-01 2.280092e-02 3.001932e+00 -6.295476e-01 7.333403e-02 -7.734933e-01 1.409849e+02 +-7.683124e-01 5.604530e-02 6.376167e-01 -2.057093e+02 9.028619e-02 9.956886e-01 2.127346e-02 3.009769e+00 -6.336754e-01 7.391263e-02 -7.700600e-01 1.400446e+02 +-7.649822e-01 5.527095e-02 6.416755e-01 -2.049370e+02 9.089979e-02 9.956033e-01 2.261075e-02 3.018818e+00 -6.376045e-01 7.562497e-02 -7.666429e-01 1.391073e+02 +-7.618200e-01 5.170873e-02 6.457217e-01 -2.041551e+02 8.887733e-02 9.957257e-01 2.512041e-02 3.027309e+00 -6.416628e-01 7.652724e-02 -7.631595e-01 1.381762e+02 +-7.588285e-01 4.967617e-02 6.493933e-01 -2.033677e+02 8.677130e-02 9.959092e-01 2.521055e-02 3.036529e+00 -6.454844e-01 7.547917e-02 -7.600347e-01 1.372526e+02 +-7.556051e-01 5.234984e-02 6.529323e-01 -2.025764e+02 8.876994e-02 9.957891e-01 2.288997e-02 3.043947e+00 -6.489845e-01 7.525652e-02 -7.570703e-01 1.363244e+02 +-7.523744e-01 5.627872e-02 6.563273e-01 -2.017844e+02 9.132072e-02 9.956343e-01 1.931099e-02 3.049451e+00 -6.523751e-01 7.446536e-02 -7.542291e-01 1.354006e+02 +-7.493392e-01 5.979232e-02 6.594814e-01 -2.009869e+02 9.374761e-02 9.954631e-01 1.626686e-02 3.051527e+00 -6.555167e-01 7.401418e-02 -7.515448e-01 1.344760e+02 +-7.465929e-01 6.126261e-02 6.624545e-01 -2.001807e+02 9.550469e-02 9.953069e-01 1.559054e-02 3.054536e+00 -6.583903e-01 7.490728e-02 -7.489399e-01 1.335527e+02 +-7.439385e-01 5.974274e-02 6.655722e-01 -1.993662e+02 9.549048e-02 9.952783e-01 1.739612e-02 3.057003e+00 -6.613903e-01 7.649744e-02 -7.461306e-01 1.326301e+02 +-7.415943e-01 5.890962e-02 6.682572e-01 -1.985452e+02 9.467978e-02 9.953570e-01 1.732546e-02 3.059230e+00 -6.641338e-01 7.611889e-02 -7.437285e-01 1.317097e+02 +-7.390999e-01 5.876594e-02 6.710275e-01 -1.977204e+02 9.580996e-02 9.952301e-01 1.837106e-02 3.061735e+00 -6.667471e-01 7.786915e-02 -7.412048e-01 1.307861e+02 +-7.361423e-01 5.904089e-02 6.742468e-01 -1.968909e+02 9.726284e-02 9.950762e-01 1.905694e-02 3.062822e+00 -6.698018e-01 7.960776e-02 -7.382601e-01 1.298617e+02 +-7.330754e-01 6.231758e-02 6.772866e-01 -1.960593e+02 1.005345e-01 9.947834e-01 1.728498e-02 3.066053e+00 -6.726762e-01 8.076187e-02 -7.355162e-01 1.289395e+02 +-7.296919e-01 6.621103e-02 6.805630e-01 -1.952214e+02 1.017888e-01 9.947292e-01 1.236097e-02 3.068689e+00 -6.761574e-01 7.829340e-02 -7.325853e-01 1.280235e+02 +-7.263658e-01 6.618099e-02 6.841147e-01 -1.943702e+02 1.001355e-01 9.949228e-01 1.007138e-02 3.068446e+00 -6.799747e-01 7.581963e-02 -7.293049e-01 1.271085e+02 +-7.236389e-01 6.343420e-02 6.872575e-01 -1.935102e+02 9.674164e-02 9.952593e-01 9.999915e-03 3.060761e+00 -6.833651e-01 7.372273e-02 -7.263450e-01 1.261968e+02 +-7.211213e-01 6.124459e-02 6.900965e-01 -1.926453e+02 9.286630e-02 9.956407e-01 8.680295e-03 3.050508e+00 -6.865566e-01 7.034624e-02 -7.236653e-01 1.252869e+02 +-7.184836e-01 5.993655e-02 6.929567e-01 -1.917750e+02 9.083111e-02 9.958338e-01 8.043515e-03 3.043875e+00 -6.895875e-01 6.872114e-02 -7.209343e-01 1.243786e+02 +-7.153793e-01 5.926678e-02 6.962184e-01 -1.908973e+02 9.036589e-02 9.958759e-01 8.077233e-03 3.035985e+00 -6.928683e-01 6.869266e-02 -7.177846e-01 1.234689e+02 +-7.121966e-01 5.794794e-02 6.995843e-01 -1.900135e+02 9.067339e-02 9.958322e-01 9.821313e-03 3.030430e+00 -6.960994e-01 7.042837e-02 -7.144826e-01 1.225625e+02 +-7.091331e-01 5.638011e-02 7.028169e-01 -1.891240e+02 9.094869e-02 9.957846e-01 1.188397e-02 3.026804e+00 -6.991842e-01 7.234758e-02 -7.112715e-01 1.216581e+02 +-7.060753e-01 5.580201e-02 7.059348e-01 -1.882274e+02 8.966506e-02 9.959117e-01 1.095906e-02 3.024492e+00 -7.024371e-01 7.103559e-02 -7.081920e-01 1.207620e+02 +-7.027405e-01 5.698175e-02 7.091607e-01 -1.873269e+02 9.068833e-02 9.958306e-01 9.851343e-03 3.024239e+00 -7.056425e-01 7.123552e-02 -7.049780e-01 1.198668e+02 +-6.994991e-01 5.496928e-02 7.125163e-01 -1.864133e+02 8.941720e-02 9.959341e-01 1.094916e-02 3.024331e+00 -7.090173e-01 7.137013e-02 -7.015701e-01 1.189721e+02 +-6.960434e-01 5.358803e-02 7.159972e-01 -1.854970e+02 8.969192e-02 9.958891e-01 1.265609e-02 3.022723e+00 -7.123756e-01 7.302833e-02 -6.979884e-01 1.180768e+02 +-6.925442e-01 5.452249e-02 7.193121e-01 -1.845755e+02 8.889560e-02 9.959898e-01 1.009335e-02 3.022062e+00 -7.158772e-01 7.093376e-02 -6.946137e-01 1.171900e+02 +-6.891017e-01 5.763781e-02 7.223689e-01 -1.836521e+02 9.042922e-02 9.958796e-01 6.803434e-03 3.016858e+00 -7.190003e-01 7.001150e-02 -6.914744e-01 1.162999e+02 +-6.857774e-01 5.873478e-02 7.254376e-01 -1.827240e+02 9.103188e-02 9.958332e-01 5.427828e-03 3.010089e+00 -7.220960e-01 6.976022e-02 -6.882665e-01 1.154147e+02 +-6.823644e-01 5.750766e-02 7.287467e-01 -1.817820e+02 9.204558e-02 9.957257e-01 7.611366e-03 3.002371e+00 -7.251941e-01 7.227162e-02 -6.847410e-01 1.145233e+02 +-6.793755e-01 5.408794e-02 7.317947e-01 -1.808339e+02 9.100181e-02 9.957912e-01 1.088294e-02 2.995427e+00 -7.281261e-01 7.398823e-02 -6.814382e-01 1.136362e+02 +-6.765217e-01 5.046263e-02 7.346918e-01 -1.798749e+02 8.828483e-02 9.960119e-01 1.288323e-02 2.993221e+00 -7.311116e-01 7.357790e-02 -6.782787e-01 1.127562e+02 +-6.740094e-01 4.852953e-02 7.371271e-01 -1.789094e+02 8.346170e-02 9.964534e-01 1.071258e-02 2.992135e+00 -7.339929e-01 6.874224e-02 -6.756692e-01 1.118817e+02 +-6.717848e-01 4.773200e-02 7.392070e-01 -1.779410e+02 7.917641e-02 9.968317e-01 7.587487e-03 2.989644e+00 -7.365028e-01 6.362490e-02 -6.734356e-01 1.110123e+02 +-6.697021e-01 4.605810e-02 7.412003e-01 -1.769635e+02 7.596797e-02 9.970879e-01 6.680943e-03 2.987661e+00 -7.387340e-01 6.078171e-02 -6.712507e-01 1.101297e+02 +-6.677155e-01 4.510918e-02 7.430486e-01 -1.759837e+02 7.498700e-02 9.971610e-01 6.848612e-03 2.981990e+00 -7.406301e-01 6.029190e-02 -6.692024e-01 1.092458e+02 +-6.658292e-01 4.452294e-02 7.447746e-01 -1.750048e+02 7.519483e-02 9.971398e-01 7.614798e-03 2.975721e+00 -7.423053e-01 6.107334e-02 -6.672726e-01 1.083640e+02 +-6.640916e-01 4.536080e-02 7.462739e-01 -1.740227e+02 7.744914e-02 9.969616e-01 8.321798e-03 2.968000e+00 -7.436289e-01 6.332470e-02 -6.655869e-01 1.074788e+02 +-6.626707e-01 4.511867e-02 7.475506e-01 -1.730399e+02 7.867535e-02 9.968543e-01 9.576734e-03 2.959505e+00 -7.447669e-01 6.516002e-02 -6.641358e-01 1.065961e+02 +-6.614379e-01 4.451722e-02 7.486776e-01 -1.720539e+02 7.828727e-02 9.968818e-01 9.889102e-03 2.949002e+00 -7.459028e-01 6.515294e-02 -6.628605e-01 1.057095e+02 +-6.602839e-01 4.162432e-02 7.498618e-01 -1.710627e+02 7.484664e-02 9.971392e-01 1.055497e-02 2.940399e+00 -7.472772e-01 6.309390e-02 -6.615103e-01 1.048302e+02 +-6.595502e-01 4.039126e-02 7.505745e-01 -1.700685e+02 7.234822e-02 9.973302e-01 9.904209e-03 2.931385e+00 -7.481706e-01 6.083504e-02 -6.607116e-01 1.039537e+02 +-6.590549e-01 3.916434e-02 7.510744e-01 -1.690696e+02 6.796986e-02 9.976583e-01 7.620064e-03 2.924665e+00 -7.490171e-01 5.607245e-02 -6.601735e-01 1.030802e+02 +-6.580988e-01 3.763959e-02 7.519902e-01 -1.680722e+02 6.581368e-02 9.978026e-01 7.653042e-03 2.915289e+00 -7.500497e-01 5.452768e-02 -6.591298e-01 1.022054e+02 +-6.573243e-01 3.385862e-02 7.528469e-01 -1.670695e+02 6.493919e-02 9.978192e-01 1.182354e-02 2.905433e+00 -7.508046e-01 5.666115e-02 -6.580895e-01 1.013233e+02 +-6.573715e-01 2.877692e-02 7.530171e-01 -1.660661e+02 6.193829e-02 9.979528e-01 1.593383e-02 2.900670e+00 -7.510169e-01 5.711502e-02 -6.578080e-01 1.004465e+02 +-6.579111e-01 2.461645e-02 7.526932e-01 -1.650635e+02 5.799796e-02 9.981535e-01 1.805052e-02 2.900265e+00 -7.508589e-01 5.553030e-02 -6.581240e-01 9.957208e+01 +-6.589268e-01 2.333599e-02 7.518451e-01 -1.640660e+02 5.588518e-02 9.982750e-01 1.799373e-02 2.900205e+00 -7.501282e-01 5.387354e-02 -6.590942e-01 9.869821e+01 +-6.602107e-01 2.788328e-02 7.505627e-01 -1.630751e+02 6.056898e-02 9.980325e-01 1.620098e-02 2.902397e+00 -7.486342e-01 5.615686e-02 -6.606006e-01 9.781222e+01 +-6.611281e-01 3.475154e-02 7.494679e-01 -1.620942e+02 6.764014e-02 9.976196e-01 1.340946e-02 2.901447e+00 -7.472178e-01 5.955947e-02 -6.619049e-01 9.692524e+01 +-6.612025e-01 4.268276e-02 7.489923e-01 -1.611164e+02 7.918623e-02 9.967737e-01 1.310168e-02 2.897791e+00 -7.460166e-01 6.797273e-02 -6.624491e-01 9.602783e+01 +-6.614368e-01 4.759661e-02 7.484891e-01 -1.601382e+02 8.795128e-02 9.960209e-01 1.438496e-02 2.895574e+00 -7.448261e-01 7.534530e-02 -6.629910e-01 9.513410e+01 +-6.624632e-01 5.022449e-02 7.474089e-01 -1.591581e+02 9.250161e-02 9.955982e-01 1.508610e-02 2.894591e+00 -7.433612e-01 7.913049e-02 -6.641930e-01 9.424562e+01 +-6.638030e-01 5.362105e-02 7.459828e-01 -1.581795e+02 9.534047e-02 9.953560e-01 1.329153e-02 2.891041e+00 -7.418057e-01 7.994529e-02 -6.658325e-01 9.335920e+01 +-6.651350e-01 5.135706e-02 7.449550e-01 -1.572001e+02 9.256238e-02 9.956083e-01 1.400748e-02 2.885337e+00 -7.409640e-01 7.827165e-02 -6.669676e-01 9.247581e+01 +-6.665791e-01 4.797982e-02 7.438886e-01 -1.562220e+02 9.054735e-02 9.957485e-01 1.691265e-02 2.880710e+00 -7.399145e-01 7.863074e-02 -6.680895e-01 9.159122e+01 +-6.676058e-01 4.677791e-02 7.430440e-01 -1.552468e+02 8.684505e-02 9.961040e-01 1.531884e-02 2.875950e+00 -7.394325e-01 7.475663e-02 -6.690672e-01 9.071005e+01 +-6.687665e-01 4.700381e-02 7.419852e-01 -1.542756e+02 8.391207e-02 9.963946e-01 1.251133e-02 2.870667e+00 -7.387220e-01 7.062865e-02 -6.702995e-01 8.983086e+01 +-6.693417e-01 4.606850e-02 7.415251e-01 -1.533026e+02 8.144161e-02 9.966106e-01 1.159758e-02 2.863059e+00 -7.384774e-01 6.815372e-02 -6.708249e-01 8.894902e+01 +-6.694547e-01 4.905554e-02 7.412314e-01 -1.523396e+02 8.366750e-02 9.964473e-01 9.619570e-03 2.852516e+00 -7.381261e-01 6.845683e-02 -6.711806e-01 8.806282e+01 +-6.695601e-01 5.190292e-02 7.409423e-01 -1.513751e+02 8.424368e-02 9.964251e-01 6.328182e-03 2.841158e+00 -7.379650e-01 6.665679e-02 -6.715389e-01 8.717952e+01 +-6.695792e-01 5.575472e-02 7.406451e-01 -1.504157e+02 8.743748e-02 9.961617e-01 4.058076e-03 2.824285e+00 -7.375760e-01 6.747733e-02 -6.718842e-01 8.629097e+01 +-6.689637e-01 5.795881e-02 7.410319e-01 -1.494554e+02 9.135831e-02 9.958075e-01 4.587611e-03 2.807029e+00 -7.376592e-01 7.076836e-02 -6.714541e-01 8.540040e+01 +-6.682490e-01 5.912149e-02 7.415848e-01 -1.484922e+02 9.564737e-02 9.953918e-01 6.832918e-03 2.790432e+00 -7.377634e-01 7.549671e-02 -6.708243e-01 8.450752e+01 +-6.672560e-01 5.929246e-02 7.424648e-01 -1.475257e+02 9.942128e-02 9.949962e-01 9.890910e-03 2.776141e+00 -7.381632e-01 8.041655e-02 -6.698121e-01 8.361670e+01 +-6.662122e-01 6.154282e-02 7.432186e-01 -1.465607e+02 1.026260e-01 9.946734e-01 9.627982e-03 2.762336e+00 -7.386672e-01 8.268785e-02 -6.689794e-01 8.273094e+01 +-6.651234e-01 6.343023e-02 7.440347e-01 -1.455908e+02 1.037354e-01 9.945732e-01 7.944313e-03 2.748604e+00 -7.394930e-01 8.246669e-02 -6.680938e-01 8.184727e+01 +-6.644378e-01 6.216628e-02 7.447536e-01 -1.446168e+02 1.019214e-01 9.947611e-01 7.895012e-03 2.733728e+00 -7.403610e-01 8.115208e-02 -6.672929e-01 8.096788e+01 +-6.640393e-01 5.886572e-02 7.453769e-01 -1.436400e+02 9.950497e-02 9.949861e-01 1.006823e-02 2.723400e+00 -7.410469e-01 8.085438e-02 -6.665673e-01 8.008940e+01 +-6.638925e-01 5.477046e-02 7.458197e-01 -1.426605e+02 9.705759e-02 9.951897e-01 1.331260e-02 2.715466e+00 -7.415029e-01 8.122558e-02 -6.660148e-01 7.921159e+01 +-6.637130e-01 5.298577e-02 7.461083e-01 -1.416800e+02 9.530672e-02 9.953481e-01 1.409582e-02 2.712409e+00 -7.418906e-01 8.046470e-02 -6.656754e-01 7.833403e+01 +-6.634247e-01 5.343482e-02 7.463327e-01 -1.407016e+02 9.431897e-02 9.954627e-01 1.256967e-02 2.709629e+00 -7.422746e-01 7.873234e-02 -6.654544e-01 7.745701e+01 +-6.632224e-01 5.547718e-02 7.463634e-01 -1.397247e+02 9.487093e-02 9.954361e-01 1.031204e-02 2.707677e+00 -7.423850e-01 7.764735e-02 -6.654587e-01 7.658021e+01 +-6.633414e-01 5.674721e-02 7.461622e-01 -1.387449e+02 9.504863e-02 9.954338e-01 8.793780e-03 2.704225e+00 -7.422560e-01 7.675495e-02 -6.657061e-01 7.570191e+01 +-6.633471e-01 5.754899e-02 7.460957e-01 -1.377656e+02 9.572588e-02 9.953728e-01 8.332393e-03 2.700066e+00 -7.421639e-01 7.694792e-02 -6.657865e-01 7.482429e+01 +-6.632971e-01 5.674598e-02 7.462016e-01 -1.367842e+02 9.657945e-02 9.952734e-01 1.016226e-02 2.694608e+00 -7.420979e-01 7.880833e-02 -6.656424e-01 7.394395e+01 +-6.633301e-01 5.512297e-02 7.462939e-01 -1.358030e+02 9.543349e-02 9.953716e-01 1.130393e-02 2.688508e+00 -7.422167e-01 7.871965e-02 -6.655205e-01 7.306679e+01 +-6.635306e-01 5.518775e-02 7.461109e-01 -1.348206e+02 9.485516e-02 9.954333e-01 1.072704e-02 2.681476e+00 -7.421116e-01 7.789017e-02 -6.657353e-01 7.218649e+01 +-6.638822e-01 5.630525e-02 7.457146e-01 -1.338412e+02 9.363724e-02 9.955727e-01 8.190952e-03 2.672027e+00 -7.419518e-01 7.526446e-02 -6.662152e-01 7.130810e+01 +-6.640214e-01 5.748984e-02 7.455002e-01 -1.328638e+02 9.138687e-02 9.958048e-01 4.606530e-03 2.660835e+00 -7.421078e-01 7.118775e-02 -6.664895e-01 7.043461e+01 +-6.640526e-01 5.953934e-02 7.453115e-01 -1.318869e+02 9.256415e-02 9.957024e-01 2.930296e-03 2.646004e+00 -7.419340e-01 7.093498e-02 -6.667099e-01 6.955422e+01 +-6.640140e-01 5.790765e-02 7.454745e-01 -1.309107e+02 9.145885e-02 9.958003e-01 4.112123e-03 2.625878e+00 -7.421056e-01 7.091073e-02 -6.665215e-01 6.867674e+01 +-6.641401e-01 5.688642e-02 7.454408e-01 -1.299330e+02 9.204440e-02 9.957367e-01 6.018545e-03 2.606906e+00 -7.419203e-01 7.261079e-02 -6.665447e-01 6.779665e+01 +-6.641263e-01 5.444551e-02 7.456353e-01 -1.289577e+02 9.151295e-02 9.957650e-01 8.799489e-03 2.589498e+00 -7.419984e-01 7.407924e-02 -6.662961e-01 6.691789e+01 +-6.643774e-01 5.181856e-02 7.455988e-01 -1.279849e+02 9.015676e-02 9.958654e-01 1.112365e-02 2.573845e+00 -7.419397e-01 7.461106e-02 -6.663022e-01 6.604028e+01 +-6.645529e-01 4.750411e-02 7.457297e-01 -1.270093e+02 8.743156e-02 9.960655e-01 1.446325e-02 2.561805e+00 -7.421086e-01 7.481189e-02 -6.660916e-01 6.516549e+01 +-6.650472e-01 4.351927e-02 7.455323e-01 -1.260361e+02 8.340172e-02 9.963837e-01 1.623561e-02 2.552233e+00 -7.421296e-01 7.297610e-02 -6.662717e-01 6.429977e+01 +-6.652594e-01 4.259470e-02 7.453963e-01 -1.250631e+02 7.964796e-02 9.967229e-01 1.412863e-02 2.546862e+00 -7.423517e-01 6.876849e-02 -6.664718e-01 6.343043e+01 +-6.655621e-01 4.231182e-02 7.451422e-01 -1.240943e+02 7.599076e-02 9.970449e-01 1.125928e-02 2.541933e+00 -7.424638e-01 6.411766e-02 -6.668105e-01 6.256520e+01 +-6.657797e-01 4.179948e-02 7.449767e-01 -1.231255e+02 7.365296e-02 9.972351e-01 9.869740e-03 2.535710e+00 -7.425043e-01 6.144080e-02 -6.670174e-01 6.169830e+01 +-6.658302e-01 4.103077e-02 7.449743e-01 -1.221569e+02 7.118693e-02 9.974251e-01 8.689260e-03 2.527256e+00 -7.426995e-01 5.881799e-02 -6.670366e-01 6.083136e+01 +-6.658005e-01 4.024219e-02 7.450438e-01 -1.211858e+02 6.953849e-02 9.975450e-01 8.261741e-03 2.518958e+00 -7.428822e-01 5.730988e-02 -6.669644e-01 5.996185e+01 +-6.658251e-01 3.906167e-02 7.450847e-01 -1.202166e+02 6.941764e-02 9.975402e-01 9.736351e-03 2.511323e+00 -7.428716e-01 5.820471e-02 -6.668988e-01 5.909597e+01 +-6.658210e-01 3.646972e-02 7.452197e-01 -1.192453e+02 6.804517e-02 9.976104e-01 1.197409e-02 2.503723e+00 -7.430022e-01 5.868119e-02 -6.667115e-01 5.822817e+01 +-6.656899e-01 3.525386e-02 7.453953e-01 -1.182758e+02 6.840777e-02 9.975604e-01 1.391274e-02 2.497254e+00 -7.430863e-01 6.025239e-02 -6.664775e-01 5.735815e+01 +-6.654022e-01 3.694470e-02 7.455703e-01 -1.173104e+02 6.897261e-02 9.975448e-01 1.212565e-02 2.491816e+00 -7.432918e-01 5.949235e-02 -6.663167e-01 5.648854e+01 +-6.650588e-01 4.042568e-02 7.456960e-01 -1.163473e+02 7.110545e-02 9.974250e-01 9.343898e-03 2.486165e+00 -7.433981e-01 5.923728e-02 -6.662208e-01 5.561772e+01 +-6.646445e-01 4.290238e-02 7.459270e-01 -1.153835e+02 7.334431e-02 9.972746e-01 7.993300e-03 2.478395e+00 -7.435511e-01 6.002219e-02 -6.659797e-01 5.474648e+01 +-6.641626e-01 4.619433e-02 7.461596e-01 -1.144194e+02 7.725433e-02 9.969865e-01 7.041784e-03 2.467266e+00 -7.435858e-01 6.232093e-02 -6.657298e-01 5.387296e+01 +-6.635466e-01 4.902199e-02 7.465272e-01 -1.134557e+02 7.863871e-02 9.968933e-01 4.434862e-03 2.454513e+00 -7.439905e-01 6.164866e-02 -6.653401e-01 5.300378e+01 +-6.630702e-01 4.790426e-02 7.470229e-01 -1.124871e+02 7.988827e-02 9.967793e-01 6.989797e-03 2.444569e+00 -7.442821e-01 6.431308e-02 -6.647616e-01 5.213291e+01 +-6.630652e-01 4.190315e-02 7.473879e-01 -1.115106e+02 7.810416e-02 9.968551e-01 1.340237e-02 2.434157e+00 -7.444758e-01 6.726074e-02 -6.642527e-01 5.125861e+01 +-6.631192e-01 3.925803e-02 7.474836e-01 -1.105329e+02 7.840175e-02 9.967734e-01 1.720216e-02 2.429370e+00 -7.443964e-01 7.001109e-02 -6.640575e-01 5.038129e+01 +-6.625951e-01 4.077258e-02 7.478672e-01 -1.095631e+02 7.952594e-02 9.967024e-01 1.611965e-02 2.425984e+00 -7.447438e-01 7.015563e-02 -6.636526e-01 4.950780e+01 +-6.620984e-01 4.535741e-02 7.480431e-01 -1.085957e+02 8.252090e-02 9.965094e-01 1.261673e-02 2.426625e+00 -7.448597e-01 7.008269e-02 -6.635302e-01 4.863615e+01 +-6.614901e-01 4.810985e-02 7.484092e-01 -1.076265e+02 8.425973e-02 9.963893e-01 1.042322e-02 2.423411e+00 -7.452054e-01 6.995560e-02 -6.631553e-01 4.776271e+01 +-6.611049e-01 4.801154e-02 7.487558e-01 -1.066494e+02 8.593140e-02 9.962289e-01 1.199212e-02 2.414926e+00 -7.453564e-01 7.226967e-02 -6.627374e-01 4.688231e+01 +-6.606446e-01 4.656725e-02 7.492531e-01 -1.056724e+02 8.760845e-02 9.960368e-01 1.534240e-02 2.407864e+00 -7.455692e-01 7.577676e-02 -6.621060e-01 4.600298e+01 +-6.599742e-01 4.632686e-02 7.498586e-01 -1.046945e+02 9.100072e-02 9.956775e-01 1.857883e-02 2.403883e+00 -7.457566e-01 8.049920e-02 -6.613372e-01 4.512013e+01 +-6.590679e-01 4.857629e-02 7.505131e-01 -1.037172e+02 9.388745e-02 9.954197e-01 1.802019e-02 2.402926e+00 -7.462001e-01 8.234027e-02 -6.606098e-01 4.424062e+01 +-6.584608e-01 5.425314e-02 7.506571e-01 -1.027447e+02 9.514126e-02 9.953972e-01 1.151438e-02 2.392828e+00 -7.465772e-01 7.900021e-02 -6.605916e-01 4.336614e+01 +-6.583063e-01 5.893129e-02 7.504399e-01 -1.017638e+02 9.486939e-02 9.954769e-01 5.048177e-03 2.366051e+00 -7.467481e-01 7.451700e-02 -6.609194e-01 4.248734e+01 +-6.585748e-01 5.772037e-02 7.502983e-01 -1.007767e+02 9.143462e-02 9.958044e-01 3.649646e-03 2.330149e+00 -7.469397e-01 7.100679e-02 -6.610893e-01 4.160772e+01 +-6.590381e-01 5.354826e-02 7.502009e-01 -9.978508e+01 8.953269e-02 9.959551e-01 7.563009e-03 2.302773e+00 -7.467615e-01 7.215181e-02 -6.611667e-01 4.072590e+01 +-6.593094e-01 5.120638e-02 7.501260e-01 -9.879828e+01 8.995890e-02 9.958838e-01 1.108499e-02 2.278169e+00 -7.464707e-01 7.478893e-02 -6.612020e-01 3.984163e+01 +-6.591390e-01 5.480665e-02 7.500214e-01 -9.781596e+01 9.352658e-02 9.955720e-01 9.443788e-03 2.258319e+00 -7.461826e-01 7.637169e-02 -6.613462e-01 3.895596e+01 +-6.586548e-01 6.005571e-02 7.500449e-01 -9.683488e+01 9.725792e-02 9.952428e-01 5.718807e-03 2.234755e+00 -7.461332e-01 7.671450e-02 -6.613622e-01 3.806946e+01 +-6.585659e-01 6.260155e-02 7.499147e-01 -9.585214e+01 9.908793e-02 9.950708e-01 3.951032e-03 2.210109e+00 -7.459709e-01 7.690950e-02 -6.615227e-01 3.718355e+01 +-6.588869e-01 6.147082e-02 7.497262e-01 -9.486317e+01 9.739947e-02 9.952373e-01 3.997680e-03 2.180517e+00 -7.459097e-01 7.565694e-02 -6.617360e-01 3.629944e+01 +-6.593839e-01 6.007848e-02 7.494021e-01 -9.387330e+01 9.585255e-02 9.953852e-01 4.540144e-03 2.156117e+00 -7.456709e-01 7.482578e-02 -6.620996e-01 3.541680e+01 +-6.598900e-01 5.593187e-02 7.492775e-01 -9.288044e+01 9.402347e-02 9.955337e-01 8.492277e-03 2.134559e+00 -7.454560e-01 7.605363e-02 -6.622017e-01 3.453240e+01 +-6.600457e-01 5.197821e-02 7.494251e-01 -9.188444e+01 9.356421e-02 9.955236e-01 1.335838e-02 2.116878e+00 -7.453760e-01 7.893650e-02 -6.619543e-01 3.364306e+01 +-6.598949e-01 5.187404e-02 7.495651e-01 -9.089290e+01 9.341779e-02 9.955375e-01 1.334555e-02 2.105305e+00 -7.455278e-01 7.882936e-02 -6.617961e-01 3.275735e+01 +-6.597431e-01 5.447615e-02 7.495141e-01 -8.990287e+01 9.288709e-02 9.956323e-01 9.397275e-03 2.093797e+00 -7.457285e-01 7.581996e-02 -6.619216e-01 3.187427e+01 +-6.596977e-01 5.585996e-02 7.494523e-01 -8.890972e+01 9.204680e-02 9.957314e-01 6.807015e-03 2.081807e+00 -7.458729e-01 7.347524e-02 -6.620234e-01 3.098976e+01 +-6.595887e-01 5.446370e-02 7.496509e-01 -8.791257e+01 9.102984e-02 9.958180e-01 7.745344e-03 2.064689e+00 -7.460940e-01 7.334933e-02 -6.617881e-01 3.010303e+01 +-6.593262e-01 5.305403e-02 7.499829e-01 -8.691401e+01 9.045859e-02 9.958588e-01 9.076704e-03 2.048978e+00 -7.463955e-01 7.382689e-02 -6.613949e-01 2.921299e+01 +-6.587683e-01 5.302189e-02 7.504753e-01 -8.591748e+01 9.150735e-02 9.957544e-01 9.974143e-03 2.035368e+00 -7.467602e-01 7.524464e-02 -6.608232e-01 2.832268e+01 +-6.583478e-01 5.122249e-02 7.509690e-01 -8.492133e+01 9.112825e-02 9.957672e-01 1.196906e-02 2.024104e+00 -7.471772e-01 7.631427e-02 -6.602289e-01 2.743622e+01 +-6.582001e-01 5.117761e-02 7.511015e-01 -8.392618e+01 9.106262e-02 9.957734e-01 1.195059e-02 2.012668e+00 -7.473153e-01 7.626314e-02 -6.600785e-01 2.655097e+01 +-6.579552e-01 5.121636e-02 7.513134e-01 -8.292905e+01 9.010141e-02 9.958716e-01 1.101771e-02 1.999986e+00 -7.476474e-01 7.494354e-02 -6.598536e-01 2.566841e+01 +-6.578773e-01 4.960454e-02 7.514898e-01 -8.193302e+01 8.717611e-02 9.961369e-01 1.056336e-02 1.986745e+00 -7.480627e-01 7.246133e-02 -6.596601e-01 2.479002e+01 +-6.576945e-01 4.789214e-02 7.517608e-01 -8.093700e+01 8.503151e-02 9.963184e-01 1.091959e-02 1.973457e+00 -7.484701e-01 7.110509e-02 -6.593455e-01 2.391304e+01 +-6.578618e-01 4.506581e-02 7.517892e-01 -7.994198e+01 8.283025e-02 9.964821e-01 1.274767e-02 1.961549e+00 -7.485700e-01 7.065707e-02 -6.592803e-01 2.303803e+01 +-6.578705e-01 4.277067e-02 7.519157e-01 -7.894882e+01 8.113440e-02 9.966006e-01 1.429766e-02 1.949545e+00 -7.487481e-01 7.041222e-02 -6.591042e-01 2.216558e+01 +-6.576423e-01 4.072858e-02 7.522286e-01 -7.795447e+01 8.046116e-02 9.966231e-01 1.638279e-02 1.940907e+00 -7.490210e-01 7.129918e-02 -6.586986e-01 2.129083e+01 +-6.575517e-01 3.873549e-02 7.524131e-01 -7.696272e+01 7.834052e-02 9.967792e-01 1.714775e-02 1.932076e+00 -7.493254e-01 7.021995e-02 -6.584683e-01 2.042165e+01 +-6.574607e-01 3.766221e-02 7.525470e-01 -7.597455e+01 7.655300e-02 9.969208e-01 1.698809e-02 1.924658e+00 -7.495899e-01 6.877872e-02 -6.583193e-01 1.955456e+01 +-6.577693e-01 3.649444e-02 7.523349e-01 -7.498848e+01 7.570151e-02 9.969712e-01 1.782479e-02 1.917272e+00 -7.494056e-01 6.867747e-02 -6.585397e-01 1.868698e+01 +-6.582080e-01 3.568736e-02 7.519898e-01 -7.400752e+01 7.542237e-02 9.969762e-01 1.870257e-02 1.912210e+00 -7.490485e-01 6.902702e-02 -6.589093e-01 1.782351e+01 +-6.587614e-01 3.685501e-02 7.514488e-01 -7.302762e+01 7.717065e-02 9.968413e-01 1.876167e-02 1.907459e+00 -7.483837e-01 7.034923e-02 -6.595246e-01 1.695634e+01 +-6.593925e-01 3.966827e-02 7.507517e-01 -7.205728e+01 8.006036e-02 9.966336e-01 1.765758e-02 1.903210e+00 -7.475239e-01 7.174870e-02 -6.603485e-01 1.609136e+01 +-6.602288e-01 4.350804e-02 7.498034e-01 -7.109240e+01 8.413647e-02 9.963213e-01 1.627269e-02 1.898035e+00 -7.463371e-01 7.382949e-02 -6.614606e-01 1.522690e+01 +-6.609705e-01 4.653753e-02 7.489675e-01 -7.012924e+01 8.697651e-02 9.960994e-01 1.486431e-02 1.891136e+00 -7.453544e-01 7.496744e-02 -6.624399e-01 1.436346e+01 +-6.617324e-01 4.893717e-02 7.481413e-01 -6.916990e+01 9.005831e-02 9.958307e-01 1.451778e-02 1.883908e+00 -7.443115e-01 7.698321e-02 -6.633806e-01 1.350034e+01 +-6.625974e-01 4.975717e-02 7.473212e-01 -6.820924e+01 9.321432e-02 9.955115e-01 1.636472e-02 1.876891e+00 -7.431526e-01 8.050424e-02 -6.642614e-01 1.263450e+01 +-6.635800e-01 4.724596e-02 7.466120e-01 -6.725104e+01 9.329125e-02 9.954395e-01 1.992428e-02 1.871594e+00 -7.422656e-01 8.287370e-02 -6.649613e-01 1.177228e+01 +-6.646051e-01 4.805603e-02 7.456479e-01 -6.629969e+01 9.520942e-02 9.952416e-01 2.071928e-02 1.869532e+00 -7.411040e-01 8.476282e-02 -6.660180e-01 1.091092e+01 +-6.656147e-01 5.143551e-02 7.445210e-01 -6.535425e+01 9.718017e-02 9.951016e-01 1.813379e-02 1.869446e+00 -7.399412e-01 8.442277e-02 -6.673527e-01 1.005197e+01 +-6.665572e-01 5.529758e-02 7.434001e-01 -6.441531e+01 9.727520e-02 9.951700e-01 1.319475e-02 1.862267e+00 -7.390798e-01 8.110943e-02 -6.687168e-01 9.197751e+00 +-6.667926e-01 6.041853e-02 7.427902e-01 -6.347903e+01 9.966960e-02 9.949839e-01 8.540062e-03 1.854003e+00 -7.385483e-01 7.972803e-02 -6.694698e-01 8.339491e+00 +-6.672422e-01 6.093008e-02 7.423445e-01 -6.254235e+01 1.015837e-01 9.947801e-01 9.657136e-03 1.842782e+00 -7.378811e-01 8.185377e-02 -6.699487e-01 7.481356e+00 +-6.673759e-01 5.965611e-02 7.423279e-01 -6.160909e+01 1.030592e-01 9.945938e-01 1.272434e-02 1.830242e+00 -7.375556e-01 8.499565e-02 -6.699160e-01 6.622286e+00 +-6.677271e-01 5.937361e-02 7.420346e-01 -6.067980e+01 1.035762e-01 9.945281e-01 1.362722e-02 1.820919e+00 -7.371652e-01 8.595635e-02 -6.702230e-01 5.771217e+00 +-6.679546e-01 5.880627e-02 7.418750e-01 -5.975404e+01 1.032650e-01 9.945533e-01 1.414030e-02 1.812094e+00 -7.370027e-01 8.605477e-02 -6.703890e-01 4.927046e+00 +-6.682192e-01 5.736298e-02 7.417498e-01 -5.883165e+01 1.030929e-01 9.945436e-01 1.596047e-02 1.802791e+00 -7.367869e-01 8.713423e-02 -6.704868e-01 4.084132e+00 +-6.684938e-01 5.498557e-02 7.416823e-01 -5.791510e+01 1.016931e-01 9.946544e-01 1.791808e-02 1.793339e+00 -7.367323e-01 8.740205e-02 -6.705119e-01 3.248503e+00 +-6.686946e-01 5.399040e-02 7.415744e-01 -5.700918e+01 1.007021e-01 9.947468e-01 1.838277e-02 1.785299e+00 -7.366862e-01 8.697058e-02 -6.706187e-01 2.422195e+00 +-6.686476e-01 5.362004e-02 7.416436e-01 -5.611243e+01 9.891814e-02 9.949461e-01 1.724861e-02 1.778582e+00 -7.369705e-01 8.489523e-02 -6.705723e-01 1.607982e+00 +-6.682577e-01 5.207806e-02 7.421048e-01 -5.522177e+01 9.666462e-02 9.951682e-01 1.720839e-02 1.773091e+00 -7.376229e-01 8.323490e-02 -6.700629e-01 8.039621e-01 +-6.673516e-01 4.961403e-02 7.430884e-01 -5.434009e+01 9.436045e-02 9.953701e-01 1.828485e-02 1.766582e+00 -7.387408e-01 8.232056e-02 -6.689434e-01 9.828463e-03 +-6.663950e-01 4.659512e-02 7.441416e-01 -5.346936e+01 9.337165e-02 9.954037e-01 2.128820e-02 1.761258e+00 -7.397293e-01 8.366806e-02 -6.676826e-01 -7.739216e-01 +-6.653764e-01 4.374578e-02 7.452253e-01 -5.261116e+01 9.103034e-02 9.955863e-01 2.283434e-02 1.754369e+00 -7.409371e-01 8.303152e-02 -6.664217e-01 -1.543085e+00 +-6.641664e-01 4.330859e-02 7.463293e-01 -5.176699e+01 8.801003e-02 9.959080e-01 2.052970e-02 1.747753e+00 -7.423862e-01 7.931959e-02 -6.652601e-01 -2.296378e+00 +-6.629940e-01 4.493820e-02 7.472747e-01 -5.092493e+01 8.605109e-02 9.961550e-01 1.644099e-02 1.742437e+00 -7.436626e-01 7.520407e-02 -6.643118e-01 -3.045921e+00 +-6.618748e-01 4.627638e-02 7.481847e-01 -5.008888e+01 8.483725e-02 9.963043e-01 1.342753e-02 1.736205e+00 -7.447982e-01 7.236126e-02 -6.633546e-01 -3.789114e+00 +-6.607855e-01 4.697223e-02 7.491036e-01 -4.926090e+01 8.571325e-02 9.962332e-01 1.313940e-02 1.727906e+00 -7.456646e-01 7.289041e-02 -6.623225e-01 -4.526641e+00 +-6.591799e-01 4.795630e-02 7.504546e-01 -4.844466e+01 8.831194e-02 9.959955e-01 1.392379e-02 1.718201e+00 -7.467817e-01 7.545237e-02 -6.607753e-01 -5.256118e+00 +-6.575982e-01 5.020516e-02 7.516941e-01 -4.764379e+01 9.206940e-02 9.956535e-01 1.404523e-02 1.707765e+00 -7.477217e-01 7.844413e-02 -6.593623e-01 -5.973092e+00 +-6.559614e-01 5.319967e-02 7.529173e-01 -4.685380e+01 9.672841e-02 9.952130e-01 1.395250e-02 1.699326e+00 -7.485708e-01 8.198078e-02 -6.579672e-01 -6.677798e+00 +-6.544574e-01 5.431363e-02 7.541456e-01 -4.607808e+01 9.906497e-02 9.949780e-01 1.431144e-02 1.689784e+00 -7.495810e-01 8.407562e-02 -6.565513e-01 -7.365478e+00 +-6.530861e-01 5.373542e-02 7.553749e-01 -4.531586e+01 9.887297e-02 9.949914e-01 1.470298e-02 1.680201e+00 -7.508014e-01 8.428845e-02 -6.551280e-01 -8.034447e+00 +-6.510931e-01 5.477019e-02 7.570192e-01 -4.456973e+01 9.858095e-02 9.950467e-01 1.279553e-02 1.669438e+00 -7.525686e-01 8.295873e-02 -6.532673e-01 -8.685225e+00 +-6.485598e-01 5.385640e-02 7.592561e-01 -4.383554e+01 9.763225e-02 9.951401e-01 1.280948e-02 1.657330e+00 -7.548762e-01 8.243557e-02 -6.506659e-01 -9.318460e+00 +-6.455813e-01 5.021203e-02 7.620392e-01 -4.311323e+01 9.533600e-02 9.953293e-01 1.518243e-02 1.645713e+00 -7.577175e-01 8.245123e-02 -6.473529e-01 -9.933193e+00 +-6.419473e-01 4.605628e-02 7.653643e-01 -4.240432e+01 9.258995e-02 9.955460e-01 1.775195e-02 1.633933e+00 -7.611378e-01 8.226084e-02 -6.433524e-01 -1.052834e+01 +-6.377280e-01 4.403903e-02 7.690017e-01 -4.171061e+01 9.056568e-02 9.957263e-01 1.808246e-02 1.622183e+00 -7.649189e-01 8.117684e-02 -6.389909e-01 -1.110464e+01 +-6.328777e-01 4.342123e-02 7.730333e-01 -4.103145e+01 8.896073e-02 9.958919e-01 1.689242e-02 1.611745e+00 -7.691240e-01 7.946042e-02 -6.341405e-01 -1.166237e+01 +-6.264748e-01 4.419869e-02 7.781875e-01 -4.036420e+01 8.819958e-02 9.959982e-01 1.443481e-02 1.603231e+00 -7.744354e-01 7.767884e-02 -6.278660e-01 -1.219871e+01 +-6.177586e-01 4.519401e-02 7.850681e-01 -3.970295e+01 8.732340e-02 9.961151e-01 1.137013e-02 1.594994e+00 -7.815043e-01 7.557880e-02 -6.193051e-01 -1.271700e+01 +-6.070334e-01 4.513872e-02 7.933934e-01 -3.904694e+01 8.606579e-02 9.962472e-01 9.170065e-03 1.585238e+00 -7.900020e-01 7.385054e-02 -6.086402e-01 -1.321425e+01 +-5.938738e-01 4.366894e-02 8.033722e-01 -3.838980e+01 8.491802e-02 9.963507e-01 8.614927e-03 1.572992e+00 -8.000642e-01 7.333694e-02 -5.954148e-01 -1.369543e+01 +-5.786913e-01 4.197681e-02 8.144657e-01 -3.773783e+01 8.470277e-02 9.963671e-01 8.830850e-03 1.559272e+00 -8.111361e-01 7.409782e-02 -5.801445e-01 -1.415540e+01 +-5.607749e-01 4.018023e-02 8.269928e-01 -3.708227e+01 8.268049e-02 9.965467e-01 7.646567e-03 1.543363e+00 -8.238297e-01 7.266416e-02 -5.621605e-01 -1.459178e+01 +-5.406775e-01 3.831314e-02 8.403571e-01 -3.642322e+01 7.999977e-02 9.967766e-01 6.026508e-03 1.527558e+00 -8.374174e-01 7.048675e-02 -5.419997e-01 -1.500371e+01 +-5.175644e-01 3.673824e-02 8.548552e-01 -3.576383e+01 7.796871e-02 9.969462e-01 4.360704e-03 1.510807e+00 -8.520845e-01 6.890889e-02 -5.188483e-01 -1.539289e+01 +-4.910500e-01 3.479733e-02 8.704361e-01 -3.509735e+01 7.614864e-02 9.970916e-01 3.098053e-03 1.492150e+00 -8.677968e-01 6.780381e-02 -4.922716e-01 -1.576067e+01 +-4.622563e-01 3.188771e-02 8.861728e-01 -3.442320e+01 7.348991e-02 9.972929e-01 2.448487e-03 1.471252e+00 -8.836958e-01 6.625658e-02 -4.633484e-01 -1.609790e+01 +-4.296838e-01 2.973698e-02 9.024897e-01 -3.374281e+01 6.929032e-02 9.975965e-01 1.190177e-04 1.450101e+00 -9.003170e-01 6.258492e-02 -4.307115e-01 -1.640328e+01 +-3.931403e-01 2.833074e-02 9.190420e-01 -3.305817e+01 6.384982e-02 9.979535e-01 -3.450153e-03 1.428664e+00 -9.172589e-01 5.732426e-02 -3.941446e-01 -1.667333e+01 +-3.533077e-01 2.621879e-02 9.351397e-01 -3.236465e+01 6.102623e-02 9.981240e-01 -4.928224e-03 1.409914e+00 -9.335145e-01 5.532686e-02 -3.542449e-01 -1.691383e+01 +-3.110711e-01 2.303200e-02 9.501076e-01 -3.166962e+01 5.570635e-02 9.984294e-01 -5.964802e-03 1.390296e+00 -9.487526e-01 5.107153e-02 -3.118655e-01 -1.711651e+01 +-2.682452e-01 2.007882e-02 9.631414e-01 -3.097187e+01 4.865687e-02 9.987891e-01 -7.270520e-03 1.365556e+00 -9.621211e-01 4.491316e-02 -2.688973e-01 -1.728046e+01 +-2.234724e-01 1.781507e-02 9.745475e-01 -3.026512e+01 4.310684e-02 9.990353e-01 -8.377942e-03 1.342013e+00 -9.737565e-01 4.013741e-02 -2.240248e-01 -1.741174e+01 +-1.752445e-01 1.805725e-02 9.843594e-01 -2.956612e+01 4.275914e-02 9.990279e-01 -1.071397e-02 1.321679e+00 -9.835959e-01 4.021278e-02 -1.758463e-01 -1.751437e+01 +-1.248458e-01 1.637157e-02 9.920411e-01 -2.886576e+01 4.147107e-02 9.990761e-01 -1.126865e-02 1.300262e+00 -9.913090e-01 3.973415e-02 -1.254094e-01 -1.758161e+01 +-7.305942e-02 1.211709e-02 9.972540e-01 -2.816342e+01 3.842559e-02 9.992179e-01 -9.325876e-03 1.277820e+00 -9.965870e-01 3.763872e-02 -7.346789e-02 -1.760491e+01 +-1.996364e-02 9.462323e-03 9.997560e-01 -2.747080e+01 3.703314e-02 9.992760e-01 -8.718289e-03 1.254902e+00 -9.991146e-01 3.685005e-02 -2.029960e-02 -1.759454e+01 +3.381026e-02 1.136931e-02 9.993636e-01 -2.678497e+01 3.532384e-02 9.992969e-01 -1.256363e-02 1.229833e+00 -9.988038e-01 3.572613e-02 3.338488e-02 -1.754516e+01 +8.742328e-02 1.297186e-02 9.960868e-01 -2.611056e+01 3.242623e-02 9.993483e-01 -1.586028e-02 1.204420e+00 -9.956433e-01 3.368589e-02 8.694567e-02 -1.745996e+01 +1.404157e-01 1.550981e-02 9.899712e-01 -2.544513e+01 3.019355e-02 9.993452e-01 -1.993927e-02 1.181948e+00 -9.896321e-01 3.269052e-02 1.398555e-01 -1.733697e+01 +1.933578e-01 1.868756e-02 9.809504e-01 -2.478637e+01 2.763709e-02 9.993181e-01 -2.448510e-02 1.158174e+00 -9.807389e-01 3.184499e-02 1.927095e-01 -1.718003e+01 +2.451349e-01 1.766463e-02 9.693281e-01 -2.414336e+01 2.418742e-02 9.994113e-01 -2.432966e-02 1.134314e+00 -9.691872e-01 2.940958e-02 2.445633e-01 -1.698722e+01 +2.956025e-01 1.784049e-02 9.551445e-01 -2.351365e+01 1.885870e-02 9.995218e-01 -2.450586e-02 1.108388e+00 -9.551248e-01 2.525677e-02 2.951247e-01 -1.675975e+01 +3.439077e-01 1.630411e-02 9.388619e-01 -2.289539e+01 1.360936e-02 9.996577e-01 -2.234503e-02 1.080425e+00 -9.389048e-01 2.046193e-02 3.435680e-01 -1.650174e+01 +3.890033e-01 1.512743e-02 9.211122e-01 -2.229698e+01 8.711438e-03 9.997600e-01 -2.009808e-02 1.047658e+00 -9.211951e-01 1.584243e-02 3.887781e-01 -1.621780e+01 +4.304391e-01 1.590783e-02 9.024795e-01 -2.171314e+01 5.088844e-03 9.997860e-01 -2.005017e-02 1.016386e+00 -9.026052e-01 1.322295e-02 4.302660e-01 -1.591129e+01 +4.666966e-01 2.095507e-02 8.841692e-01 -2.115192e+01 -1.863376e-03 9.997403e-01 -2.271059e-02 9.883421e-01 -8.844155e-01 8.951411e-03 4.666144e-01 -1.557956e+01 +4.956295e-01 2.840417e-02 8.680695e-01 -2.060465e+01 -9.714982e-03 9.995839e-01 -2.716064e-02 9.603896e-01 -8.684797e-01 5.028330e-03 4.956991e-01 -1.523140e+01 +5.178157e-01 3.657697e-02 8.547099e-01 -2.006747e+01 -1.796443e-02 9.993301e-01 -3.188241e-02 9.316118e-01 -8.553035e-01 1.154836e-03 5.181259e-01 -1.487238e+01 +5.337850e-01 4.167422e-02 8.445928e-01 -1.953624e+01 -2.261891e-02 9.991311e-01 -3.500430e-02 9.003617e-01 -8.453177e-01 -4.190027e-04 5.342638e-01 -1.451275e+01 +5.448956e-01 4.281668e-02 8.374100e-01 -1.900891e+01 -2.351869e-02 9.990829e-01 -3.577959e-02 8.643181e-01 -8.381739e-01 -1.986525e-04 5.454029e-01 -1.415364e+01 +5.519991e-01 4.184372e-02 8.327942e-01 -1.847786e+01 -2.258719e-02 9.991239e-01 -3.522955e-02 8.290798e-01 -8.335387e-01 6.361923e-04 5.524606e-01 -1.379381e+01 +5.556621e-01 4.050173e-02 8.304212e-01 -1.795240e+01 -2.166653e-02 9.991789e-01 -3.423470e-02 7.918610e-01 -8.311259e-01 1.030570e-03 5.560833e-01 -1.343935e+01 +5.569920e-01 3.858300e-02 8.296212e-01 -1.742718e+01 -1.938938e-02 9.992521e-01 -3.345433e-02 7.543507e-01 -8.302915e-01 2.547958e-03 5.573235e-01 -1.309013e+01 +5.573918e-01 3.696434e-02 8.294264e-01 -1.690498e+01 -1.759024e-02 9.993099e-01 -3.271439e-02 7.153450e-01 -8.300632e-01 3.644921e-03 5.576573e-01 -1.274653e+01 +5.570950e-01 3.517210e-02 8.297036e-01 -1.638799e+01 -1.494201e-02 9.993655e-01 -3.233163e-02 6.799779e-01 -8.303143e-01 5.614345e-03 5.572671e-01 -1.240644e+01 +5.554371e-01 3.320217e-02 8.308955e-01 -1.587464e+01 -1.246060e-02 9.994227e-01 -3.160678e-02 6.482271e-01 -8.314651e-01 7.202121e-03 5.555302e-01 -1.206932e+01 +5.516085e-01 3.203289e-02 8.334879e-01 -1.536708e+01 -1.066301e-02 9.994514e-01 -3.135441e-02 6.164130e-01 -8.340350e-01 8.407861e-03 5.516474e-01 -1.173945e+01 +5.462558e-01 3.078565e-02 8.370525e-01 -1.486310e+01 -9.206790e-03 9.994846e-01 -3.075139e-02 5.853326e-01 -8.375678e-01 9.091552e-03 5.462576e-01 -1.141748e+01 +5.400629e-01 2.855788e-02 8.411401e-01 -1.436358e+01 -6.185860e-03 9.995318e-01 -2.996381e-02 5.539444e-01 -8.416019e-01 1.097916e-02 5.399866e-01 -1.110693e+01 +5.343926e-01 2.635277e-02 8.448255e-01 -1.387316e+01 -1.770812e-03 9.995465e-01 -3.005890e-02 5.226973e-01 -8.452345e-01 1.456722e-02 5.341969e-01 -1.080922e+01 +5.292431e-01 2.513356e-02 8.480980e-01 -1.339333e+01 1.918343e-03 9.995231e-01 -3.081820e-02 4.936346e-01 -8.484681e-01 1.793725e-02 5.289424e-01 -1.052211e+01 +5.235449e-01 2.440251e-02 8.516486e-01 -1.292267e+01 4.403922e-03 9.994989e-01 -3.134619e-02 4.645181e-01 -8.519867e-01 2.016173e-02 5.231751e-01 -1.024262e+01 +5.177704e-01 2.466935e-02 8.551639e-01 -1.246406e+01 5.605283e-03 9.994649e-01 -3.222587e-02 4.364960e-01 -8.555012e-01 2.147903e-02 5.173550e-01 -9.972850e+00 +5.125070e-01 2.446316e-02 8.583346e-01 -1.201256e+01 7.010353e-03 9.994416e-01 -3.267066e-02 4.084713e-01 -8.586544e-01 2.276116e-02 5.120492e-01 -9.712136e+00 +5.074175e-01 2.386879e-02 8.613697e-01 -1.157478e+01 9.189271e-03 9.994095e-01 -3.310715e-02 3.801443e-01 -8.616513e-01 2.471450e-02 5.068985e-01 -9.466819e+00 +5.019300e-01 2.165062e-02 8.646372e-01 -1.114413e+01 1.258254e-02 9.993980e-01 -3.232934e-02 3.513900e-01 -8.648167e-01 2.710639e-02 5.013554e-01 -9.231205e+00 +4.966777e-01 1.906779e-02 8.677256e-01 -1.072406e+01 1.576590e-02 9.993955e-01 -3.098542e-02 3.234019e-01 -8.677918e-01 2.907023e-02 4.960768e-01 -9.005949e+00 +4.917680e-01 1.738682e-02 8.705527e-01 -1.031791e+01 1.729472e-02 9.994083e-01 -2.973000e-02 2.969119e-01 -8.705544e-01 2.967621e-02 4.911763e-01 -8.788752e+00 +4.868646e-01 1.702632e-02 8.733115e-01 -9.925651e+00 1.569748e-02 9.994780e-01 -2.823733e-02 2.717875e-01 -8.733363e-01 2.745654e-02 4.863432e-01 -8.577088e+00 +4.817468e-01 1.615353e-02 8.761616e-01 -9.550035e+00 1.545132e-02 9.995181e-01 -2.692354e-02 2.470296e-01 -8.761742e-01 2.650817e-02 4.812650e-01 -8.378380e+00 +4.772789e-01 1.557987e-02 8.786138e-01 -9.188230e+00 1.610619e-02 9.995197e-01 -2.647299e-02 2.217585e-01 -8.786042e-01 2.678611e-02 4.767987e-01 -8.193104e+00 +4.732671e-01 1.452920e-02 8.807992e-01 -8.843007e+00 1.849921e-02 9.994795e-01 -2.642681e-02 1.979693e-01 -8.807247e-01 2.880102e-02 4.727520e-01 -8.023430e+00 +4.696391e-01 1.337119e-02 8.827573e-01 -8.515855e+00 2.050900e-02 9.994502e-01 -2.604982e-02 1.770073e-01 -8.826202e-01 3.033847e-02 4.691067e-01 -7.864360e+00 +4.658156e-01 1.301368e-02 8.847862e-01 -8.211014e+00 2.203305e-02 9.994112e-01 -2.629941e-02 1.574511e-01 -8.846074e-01 3.174520e-02 4.652546e-01 -7.716742e+00 +4.626758e-01 1.353184e-02 8.864243e-01 -7.926879e+00 2.237008e-02 9.993869e-01 -2.693253e-02 1.385032e-01 -8.862453e-01 3.229040e-02 4.620894e-01 -7.578078e+00 +4.599587e-01 1.564454e-02 8.878025e-01 -7.666677e+00 2.180944e-02 9.993441e-01 -2.890927e-02 1.212137e-01 -8.876724e-01 3.265954e-02 4.593157e-01 -7.451274e+00 +4.581729e-01 1.780628e-02 8.886848e-01 -7.426664e+00 2.149900e-02 9.992848e-01 -3.110643e-02 1.043387e-01 -8.886030e-01 3.335795e-02 4.574624e-01 -7.335419e+00 +4.574193e-01 2.064414e-02 8.890115e-01 -7.195608e+00 2.173616e-02 9.991722e-01 -3.438605e-02 8.690973e-02 -8.889854e-01 3.505253e-02 4.565919e-01 -7.225477e+00 +4.580054e-01 2.300707e-02 8.886517e-01 -6.965634e+00 2.399934e-02 9.989806e-01 -3.823259e-02 6.980096e-02 -8.886253e-01 3.883777e-02 4.569864e-01 -7.116444e+00 +4.603458e-01 2.346199e-02 8.874296e-01 -6.732949e+00 2.647110e-02 9.988434e-01 -4.013921e-02 5.536442e-02 -8.873449e-01 4.196915e-02 4.591923e-01 -7.004384e+00 +4.646731e-01 2.295985e-02 8.851846e-01 -6.509157e+00 2.739505e-02 9.988125e-01 -4.028802e-02 4.498962e-02 -8.850584e-01 4.297042e-02 4.634923e-01 -6.882267e+00 +4.717340e-01 2.221782e-02 8.814610e-01 -6.290034e+00 2.668982e-02 9.988646e-01 -3.946073e-02 3.483157e-02 -8.813369e-01 4.214099e-02 4.706053e-01 -6.754992e+00 +4.807006e-01 2.485092e-02 8.765326e-01 -6.081177e+00 2.381464e-02 9.988596e-01 -4.137929e-02 2.288921e-02 -8.765613e-01 4.076535e-02 4.795606e-01 -6.624412e+00 +4.915793e-01 2.907040e-02 8.703475e-01 -5.880260e+00 2.214281e-02 9.987022e-01 -4.586401e-02 7.391935e-03 -8.705513e-01 4.181772e-02 4.902976e-01 -6.496252e+00 +5.044140e-01 3.228266e-02 8.628583e-01 -5.683176e+00 2.130874e-02 9.985311e-01 -4.981545e-02 -7.289078e-03 -8.631989e-01 4.351403e-02 5.029851e-01 -6.365703e+00 +5.190654e-01 3.364022e-02 8.540723e-01 -5.489078e+00 2.112580e-02 9.984150e-01 -5.216488e-02 -2.195396e-02 -8.544734e-01 4.511993e-02 5.175319e-01 -6.233971e+00 +5.352225e-01 3.366225e-02 8.440402e-01 -5.299828e+00 2.005515e-02 9.984176e-01 -5.253655e-02 -3.518676e-02 -8.444730e-01 4.504608e-02 5.337004e-01 -6.094816e+00 +5.520796e-01 3.445039e-02 8.330794e-01 -5.115930e+00 1.741012e-02 9.984519e-01 -5.282670e-02 -5.023552e-02 -8.336096e-01 4.366855e-02 5.506251e-01 -5.951422e+00 +5.699734e-01 3.563471e-02 8.208901e-01 -4.934984e+00 1.585904e-02 9.983959e-01 -5.435171e-02 -6.430690e-02 -8.215101e-01 4.399755e-02 5.684939e-01 -5.802268e+00 +5.901721e-01 3.814704e-02 8.063757e-01 -4.745745e+00 1.542878e-02 9.981674e-01 -5.851215e-02 -7.864708e-02 -8.071300e-01 4.697362e-02 5.885019e-01 -5.644725e+00 +6.109687e-01 3.920078e-02 7.906836e-01 -4.546901e+00 1.645771e-02 9.979284e-01 -6.219267e-02 -9.511714e-02 -7.914836e-01 5.101060e-02 6.090579e-01 -5.474396e+00 +6.319729e-01 3.879883e-02 7.740187e-01 -4.339961e+00 1.612521e-02 9.978715e-01 -6.318575e-02 -1.133601e-01 -7.748227e-01 5.241289e-02 6.300021e-01 -5.285216e+00 +6.534976e-01 3.915886e-02 7.559150e-01 -4.130458e+00 1.165876e-02 9.980217e-01 -6.177992e-02 -1.325004e-01 -7.568387e-01 4.918605e-02 6.517482e-01 -5.073841e+00 +6.749762e-01 3.860696e-02 7.368289e-01 -3.918483e+00 5.235747e-03 9.983544e-01 -5.710612e-02 -1.545950e-01 -7.378210e-01 4.240311e-02 6.736632e-01 -4.841217e+00 +6.967523e-01 3.488786e-02 7.164629e-01 -3.697865e+00 1.686952e-03 9.987340e-01 -5.027348e-02 -1.802182e-01 -7.173098e-01 3.623679e-02 6.958113e-01 -4.592905e+00 +7.183685e-01 2.960816e-02 6.950324e-01 -3.473372e+00 3.035099e-03 9.989509e-01 -4.569201e-02 -2.037006e-01 -6.956561e-01 3.493318e-02 7.175250e-01 -4.334121e+00 +7.397501e-01 2.685171e-02 6.723458e-01 -3.251958e+00 3.400964e-03 9.990415e-01 -4.364100e-02 -2.245399e-01 -6.728731e-01 3.457005e-02 7.389497e-01 -4.063126e+00 +7.612835e-01 2.602284e-02 6.478969e-01 -3.037676e+00 2.050853e-03 9.990927e-01 -4.253843e-02 -2.463900e-01 -6.484160e-01 3.371254e-02 7.605393e-01 -3.769289e+00 +7.826368e-01 2.687946e-02 6.218981e-01 -2.828032e+00 -2.246108e-03 9.991827e-01 -4.035969e-02 -2.688144e-01 -6.224746e-01 3.019012e-02 7.820574e-01 -3.456951e+00 +8.029185e-01 2.563701e-02 5.955373e-01 -2.618666e+00 -3.745083e-03 9.992719e-01 -3.796798e-02 -2.919692e-01 -5.960771e-01 2.825485e-02 8.024298e-01 -3.132043e+00 +8.230044e-01 2.367897e-02 5.675413e-01 -2.408137e+00 -3.048275e-03 9.993005e-01 -3.727247e-02 -3.142259e-01 -5.680268e-01 2.894538e-02 8.225008e-01 -2.790908e+00 +8.430290e-01 2.035561e-02 5.374828e-01 -2.199410e+00 9.791069e-04 9.992239e-01 -3.937843e-02 -3.329592e-01 -5.378672e-01 3.372340e-02 8.423548e-01 -2.430206e+00 +8.624118e-01 1.751042e-02 5.059044e-01 -1.995823e+00 3.107650e-03 9.991995e-01 -3.988200e-02 -3.521711e-01 -5.061978e-01 3.596687e-02 8.616670e-01 -2.041747e+00 +8.807641e-01 1.512267e-02 4.733139e-01 -1.801721e+00 2.564983e-03 9.993229e-01 -3.670202e-02 -3.710700e-01 -4.735484e-01 3.353986e-02 8.801289e-01 -1.625169e+00 +8.979859e-01 1.603472e-02 4.397322e-01 -1.619301e+00 -1.605042e-03 9.994485e-01 -3.316695e-02 -3.905415e-01 -4.400215e-01 2.907766e-02 8.975163e-01 -1.177136e+00 +9.142476e-01 1.697871e-02 4.048002e-01 -1.444291e+00 -4.665837e-03 9.994965e-01 -3.138445e-02 -4.091277e-01 -4.051292e-01 2.680442e-02 9.138664e-01 -7.098437e-01 +9.293015e-01 1.175271e-02 3.691351e-01 -1.269630e+00 -1.794683e-03 9.996254e-01 -2.730845e-02 -4.288300e-01 -3.693178e-01 2.471530e-02 9.289744e-01 -2.150744e-01 +9.430129e-01 4.554133e-03 3.327250e-01 -1.102382e+00 3.438296e-03 9.997196e-01 -2.342840e-02 -4.503757e-01 -3.327384e-01 2.323728e-02 9.427328e-01 3.018002e-01 +9.556077e-01 -4.713593e-03 2.946046e-01 -9.458897e-01 1.148510e-02 9.997080e-01 -2.125910e-02 -4.699004e-01 -2.944183e-01 2.369892e-02 9.553827e-01 8.454409e-01 +9.667553e-01 -1.039661e-02 2.554919e-01 -8.121858e-01 1.619852e-02 9.996562e-01 -2.061502e-02 -4.869598e-01 -2.551897e-01 2.406826e-02 9.665913e-01 1.417145e+00 +9.763638e-01 -1.200627e-02 2.158003e-01 -7.128327e-01 1.705916e-02 9.996218e-01 -2.156723e-02 -5.013363e-01 -2.154597e-01 2.473882e-02 9.761993e-01 2.020444e+00 +9.840273e-01 -1.038824e-02 1.777143e-01 -6.378581e-01 1.460092e-02 9.996421e-01 -2.241338e-02 -5.154859e-01 -1.774179e-01 2.465016e-02 9.838268e-01 2.648628e+00 +9.897170e-01 -9.874901e-03 1.426985e-01 -5.774130e-01 1.343789e-02 9.996210e-01 -2.402653e-02 -5.276563e-01 -1.424071e-01 2.569703e-02 9.894745e-01 3.304554e+00 +9.937803e-01 -1.050678e-02 1.108618e-01 -5.289363e-01 1.338549e-02 9.995914e-01 -2.525440e-02 -5.401560e-01 -1.105512e-01 2.658126e-02 9.935149e-01 3.992533e+00 +9.965121e-01 -1.271911e-02 8.247366e-02 -4.902611e-01 1.477706e-02 9.995933e-01 -2.439053e-02 -5.581546e-01 -8.212989e-02 2.552417e-02 9.962947e-01 4.697446e+00 +9.983110e-01 -1.348660e-02 5.650902e-02 -4.709248e-01 1.488386e-02 9.995920e-01 -2.437880e-02 -5.760638e-01 -5.615717e-02 2.517869e-02 9.981044e-01 5.426109e+00 +9.993849e-01 -1.301802e-02 3.256524e-02 -4.637439e-01 1.384848e-02 9.995812e-01 -2.540737e-02 -5.976769e-01 -3.222085e-02 2.584272e-02 9.991466e-01 6.162183e+00 +9.998655e-01 -1.134766e-02 1.184681e-02 -4.641394e-01 1.163743e-02 9.996275e-01 -2.468459e-02 -6.120160e-01 -1.156228e-02 2.481914e-02 9.996250e-01 6.920857e+00 +9.999316e-01 -9.466175e-03 -6.877324e-03 -4.766370e-01 9.311525e-03 9.997106e-01 -2.218139e-02 -6.276445e-01 7.085306e-03 2.211583e-02 9.997303e-01 7.694492e+00 +9.997347e-01 -8.921921e-03 -2.123679e-02 -4.970589e-01 8.515965e-03 9.997807e-01 -1.913006e-02 -6.434513e-01 2.140281e-02 1.894413e-02 9.995914e-01 8.489033e+00 +9.995322e-01 -3.646739e-03 -3.036747e-02 -5.313984e-01 3.104036e-03 9.998350e-01 -1.789922e-02 -6.633061e-01 3.042773e-02 1.779658e-02 9.993785e-01 9.295931e+00 +9.993754e-01 1.325286e-03 -3.531589e-02 -5.707381e-01 -2.022584e-03 9.998035e-01 -1.971621e-02 -6.757426e-01 3.528282e-02 1.977532e-02 9.991816e-01 1.011987e+01 +9.993099e-01 1.808124e-03 -3.710089e-02 -6.048110e-01 -2.613311e-03 9.997618e-01 -2.166562e-02 -6.892524e-01 3.705288e-02 2.174762e-02 9.990766e-01 1.095905e+01 +9.992863e-01 -9.650904e-04 -3.776342e-02 -6.242421e-01 1.504223e-04 9.997673e-01 -2.156984e-02 -7.023164e-01 3.777545e-02 2.154876e-02 9.990538e-01 1.181777e+01 +9.992870e-01 -2.282807e-03 -3.768894e-02 -6.484508e-01 1.536398e-03 9.998023e-01 -1.982155e-02 -7.264710e-01 3.772674e-02 1.974951e-02 9.990929e-01 1.268675e+01 +9.992798e-01 -3.911630e-04 -3.794498e-02 -6.801171e-01 -3.604084e-04 9.998039e-01 -1.979801e-02 -7.525259e-01 3.794528e-02 1.979743e-02 9.990836e-01 1.356921e+01 +9.992673e-01 1.237887e-03 -3.825395e-02 -7.118728e-01 -2.115448e-03 9.997353e-01 -2.290842e-02 -7.792859e-01 3.821547e-02 2.297256e-02 9.990054e-01 1.446601e+01 +9.992507e-01 4.110066e-03 -3.848721e-02 -7.483848e-01 -5.080577e-03 9.996707e-01 -2.515268e-02 -8.066043e-01 3.837116e-02 2.532937e-02 9.989424e-01 1.537850e+01 +9.992121e-01 7.504414e-03 -3.897420e-02 -7.865066e-01 -8.524887e-03 9.996234e-01 -2.608344e-02 -8.385639e-01 3.876378e-02 2.639513e-02 9.988997e-01 1.630730e+01 +9.991758e-01 8.870216e-03 -3.961127e-02 -8.252649e-01 -9.823865e-03 9.996650e-01 -2.394578e-02 -8.761044e-01 3.938559e-02 2.431517e-02 9.989281e-01 1.724745e+01 +9.991345e-01 6.169517e-03 -4.113703e-02 -8.608237e-01 -7.056113e-03 9.997452e-01 -2.144200e-02 -9.147192e-01 4.099426e-02 2.171371e-02 9.989234e-01 1.819174e+01 +9.990317e-01 6.336356e-03 -4.353747e-02 -9.050122e-01 -7.225485e-03 9.997679e-01 -2.029522e-02 -9.533412e-01 4.339876e-02 2.059015e-02 9.988456e-01 1.914491e+01 +9.988869e-01 5.412752e-03 -4.685889e-02 -9.508667e-01 -6.411686e-03 9.997548e-01 -2.119391e-02 -9.934983e-01 4.673268e-02 2.147076e-02 9.986766e-01 2.010698e+01 +9.986886e-01 2.725992e-03 -5.112422e-02 -9.982187e-01 -3.872697e-03 9.997428e-01 -2.234414e-02 -1.029351e+00 5.105016e-02 2.251282e-02 9.984423e-01 2.108440e+01 +9.984608e-01 7.126212e-04 -5.545880e-02 -1.050402e+00 -1.982371e-03 9.997371e-01 -2.284373e-02 -1.065831e+00 5.542794e-02 2.291850e-02 9.981996e-01 2.207364e+01 +9.982289e-01 1.151927e-03 -5.948024e-02 -1.111700e+00 -2.333633e-03 9.998012e-01 -1.980156e-02 -1.101589e+00 5.944560e-02 1.990529e-02 9.980330e-01 2.308151e+01 +9.980000e-01 2.866564e-04 -6.321365e-02 -1.176238e+00 -1.288799e-03 9.998741e-01 -1.581305e-02 -1.135143e+00 6.320115e-02 1.586290e-02 9.978747e-01 2.410049e+01 +9.977530e-01 5.367514e-04 -6.699836e-02 -1.245567e+00 -1.330644e-03 9.999294e-01 -1.180537e-02 -1.165681e+00 6.698729e-02 1.186799e-02 9.976832e-01 2.513554e+01 +9.975440e-01 1.221290e-03 -7.003307e-02 -1.318962e+00 -1.918705e-03 9.999492e-01 -9.891966e-03 -1.193623e+00 7.001743e-02 1.000204e-02 9.974956e-01 2.617785e+01 +9.973693e-01 2.486522e-03 -7.244577e-02 -1.395968e+00 -3.442847e-03 9.999085e-01 -1.307868e-02 -1.222323e+00 7.240661e-02 1.329370e-02 9.972865e-01 2.722466e+01 +9.972240e-01 3.612189e-03 -7.437345e-02 -1.477065e+00 -5.032127e-03 9.998084e-01 -1.891346e-02 -1.250185e+00 7.429088e-02 1.923521e-02 9.970510e-01 2.827774e+01 +9.971173e-01 3.081023e-03 -7.581292e-02 -1.558337e+00 -4.671273e-03 9.997726e-01 -2.080760e-02 -1.281898e+00 7.573156e-02 2.110176e-02 9.969049e-01 2.934201e+01 +9.970078e-01 2.486793e-03 -7.726099e-02 -1.640741e+00 -3.745539e-03 9.998625e-01 -1.615149e-02 -1.315662e+00 7.721020e-02 1.639255e-02 9.968800e-01 3.042088e+01 +9.969060e-01 2.573458e-03 -7.856076e-02 -1.724717e+00 -3.335734e-03 9.999486e-01 -9.573322e-03 -1.350706e+00 7.853208e-02 9.805760e-03 9.968633e-01 3.150487e+01 +9.967643e-01 -3.909575e-03 -8.028551e-02 -1.802380e+00 3.293692e-03 9.999641e-01 -7.802165e-03 -1.379426e+00 8.031313e-02 7.512483e-03 9.967413e-01 3.259080e+01 +9.966451e-01 -7.810978e-03 -8.147111e-02 -1.879320e+00 6.886688e-03 9.999087e-01 -1.161985e-02 -1.407888e+00 8.155444e-02 1.101980e-02 9.966079e-01 3.366468e+01 +9.966224e-01 -7.018970e-03 -8.182096e-02 -1.966625e+00 5.653365e-03 9.998410e-01 -1.690991e-02 -1.447013e+00 8.192664e-02 1.639023e-02 9.965035e-01 3.474244e+01 +9.966235e-01 -4.983852e-03 -8.195652e-02 -2.057718e+00 3.471261e-03 9.998212e-01 -1.858817e-02 -1.487218e+00 8.203450e-02 1.824091e-02 9.964625e-01 3.582986e+01 +9.967386e-01 -1.396567e-03 -8.068617e-02 -2.150183e+00 3.349680e-05 9.998573e-01 -1.689237e-02 -1.530548e+00 8.069825e-02 1.683457e-02 9.965963e-01 3.692359e+01 +9.968688e-01 2.642999e-03 -7.902991e-02 -2.238254e+00 -3.782436e-03 9.998910e-01 -1.427157e-02 -1.569943e+00 7.898357e-02 1.452580e-02 9.967700e-01 3.802774e+01 +9.969725e-01 2.749507e-03 -7.770694e-02 -2.317142e+00 -3.799372e-03 9.999034e-01 -1.336595e-02 -1.606535e+00 7.766268e-02 1.362072e-02 9.968866e-01 3.913464e+01 +9.970910e-01 2.862993e-03 -7.616721e-02 -2.397389e+00 -3.681576e-03 9.999369e-01 -1.060893e-02 -1.638706e+00 7.613203e-02 1.085848e-02 9.970386e-01 4.024904e+01 +9.971702e-01 9.331554e-03 -7.459634e-02 -2.481505e+00 -9.880389e-03 9.999267e-01 -6.991735e-03 -1.670571e+00 7.452563e-02 7.708990e-03 9.971892e-01 4.136383e+01 +9.973164e-01 1.223167e-02 -7.218377e-02 -2.563489e+00 -1.272979e-02 9.998982e-01 -6.444779e-03 -1.700399e+00 7.209759e-02 7.346367e-03 9.973705e-01 4.247906e+01 +9.974598e-01 1.332772e-02 -6.997458e-02 -2.638864e+00 -1.396436e-02 9.998653e-01 -8.616922e-03 -1.730020e+00 6.985031e-02 9.572183e-03 9.975115e-01 4.359428e+01 +9.975934e-01 1.621102e-02 -6.741456e-02 -2.715061e+00 -1.708946e-02 9.997761e-01 -1.247404e-02 -1.765263e+00 6.719725e-02 1.359610e-02 9.976470e-01 4.471026e+01 +9.977395e-01 1.579921e-02 -6.531783e-02 -2.782512e+00 -1.668325e-02 9.997761e-01 -1.301107e-02 -1.803738e+00 6.509764e-02 1.407137e-02 9.977796e-01 4.583249e+01 +9.978718e-01 1.542677e-02 -6.335591e-02 -2.848280e+00 -1.615549e-02 9.998089e-01 -1.100577e-02 -1.840111e+00 6.317402e-02 1.200589e-02 9.979303e-01 4.696257e+01 +9.980055e-01 1.563743e-02 -6.116015e-02 -2.914760e+00 -1.630573e-02 9.998125e-01 -1.044312e-02 -1.877642e+00 6.098538e-02 1.141955e-02 9.980733e-01 4.809641e+01 +9.980727e-01 1.785388e-02 -5.943303e-02 -2.981824e+00 -1.879918e-02 9.997049e-01 -1.538429e-02 -1.915142e+00 5.914082e-02 1.647193e-02 9.981137e-01 4.922285e+01 +9.981330e-01 1.645449e-02 -5.882099e-02 -3.041372e+00 -1.765671e-02 9.996445e-01 -1.997763e-02 -1.951517e+00 5.847135e-02 2.097891e-02 9.980686e-01 5.035697e+01 +9.981519e-01 1.447239e-02 -5.901996e-02 -3.098225e+00 -1.561081e-02 9.997000e-01 -1.887344e-02 -1.990571e+00 5.872910e-02 1.975991e-02 9.980783e-01 5.150882e+01 +9.981622e-01 1.256095e-02 -5.928416e-02 -3.156600e+00 -1.345292e-02 9.998019e-01 -1.467064e-02 -2.028592e+00 5.908813e-02 1.544122e-02 9.981333e-01 5.266326e+01 +9.982264e-01 8.707782e-03 -5.889307e-02 -3.212653e+00 -9.492043e-03 9.998698e-01 -1.305006e-02 -2.065955e+00 5.877176e-02 1.358592e-02 9.981789e-01 5.382038e+01 +9.982826e-01 3.593007e-03 -5.847319e-02 -3.268258e+00 -4.416541e-03 9.998928e-01 -1.396081e-02 -2.101998e+00 5.841675e-02 1.419508e-02 9.981913e-01 5.497678e+01 +9.983025e-01 2.381471e-03 -5.819370e-02 -3.326194e+00 -3.242111e-03 9.998867e-01 -1.469930e-02 -2.137882e+00 5.815209e-02 1.486302e-02 9.981970e-01 5.613489e+01 +9.983384e-01 -1.945878e-03 -5.759066e-02 -3.380992e+00 1.316070e-03 9.999389e-01 -1.097186e-02 -2.170759e+00 5.760849e-02 1.087783e-02 9.982799e-01 5.730736e+01 +9.983750e-01 -3.236659e-03 -5.689506e-02 -3.437582e+00 2.960420e-03 9.999834e-01 -4.938856e-03 -2.199954e+00 5.691010e-02 4.762397e-03 9.983679e-01 5.848395e+01 +9.984334e-01 -3.123410e-03 -5.586689e-02 -3.502086e+00 2.967275e-03 9.999914e-01 -2.877501e-03 -2.229392e+00 5.587540e-02 2.707220e-03 9.984340e-01 5.966130e+01 +9.984207e-01 -1.978011e-03 -5.614530e-02 -3.567609e+00 1.438735e-03 9.999524e-01 -9.643816e-03 -2.260389e+00 5.616170e-02 9.547806e-03 9.983760e-01 6.083477e+01 +9.984294e-01 6.590204e-05 -5.602514e-02 -3.637028e+00 -1.090354e-03 9.998327e-01 -1.825521e-02 -2.299040e+00 5.601456e-02 1.828762e-02 9.982624e-01 6.200855e+01 +9.984213e-01 5.675464e-03 -5.588271e-02 -3.713046e+00 -6.858339e-03 9.997560e-01 -2.099811e-02 -2.342808e+00 5.574990e-02 2.134822e-02 9.982165e-01 6.319369e+01 +9.984266e-01 8.129750e-03 -5.548270e-02 -3.786600e+00 -9.204457e-03 9.997744e-01 -1.914214e-02 -2.393096e+00 5.531456e-02 1.962270e-02 9.982761e-01 6.438572e+01 +9.984088e-01 9.915797e-03 -5.551167e-02 -3.857193e+00 -1.096885e-02 9.997650e-01 -1.869746e-02 -2.442419e+00 5.531322e-02 1.927661e-02 9.982829e-01 6.557899e+01 +9.983853e-01 1.046428e-02 -5.583406e-02 -3.925554e+00 -1.130035e-02 9.998284e-01 -1.467957e-02 -2.488376e+00 5.567087e-02 1.528681e-02 9.983321e-01 6.677803e+01 +9.983683e-01 9.468162e-03 -5.631298e-02 -3.981904e+00 -1.017903e-02 9.998719e-01 -1.235006e-02 -2.529631e+00 5.618883e-02 1.290312e-02 9.983367e-01 6.797354e+01 +9.983745e-01 8.291212e-03 -5.638792e-02 -4.036864e+00 -8.972448e-03 9.998896e-01 -1.183880e-02 -2.569024e+00 5.628353e-02 1.232549e-02 9.983387e-01 6.916868e+01 +9.983417e-01 1.042504e-02 -5.661523e-02 -4.099562e+00 -1.087209e-02 9.999120e-01 -7.593888e-03 -2.604193e+00 5.653108e-02 8.196820e-03 9.983671e-01 7.036636e+01 +9.983297e-01 1.142732e-02 -5.663382e-02 -4.173959e+00 -1.165790e-02 9.999250e-01 -3.742596e-03 -2.646996e+00 5.658681e-02 4.396576e-03 9.983879e-01 7.156592e+01 +9.982830e-01 1.386138e-02 -5.691296e-02 -4.251058e+00 -1.434715e-02 9.998640e-01 -8.135505e-03 -2.694670e+00 5.679244e-02 8.938074e-03 9.983459e-01 7.275276e+01 +9.982798e-01 1.274442e-02 -5.722932e-02 -4.323029e+00 -1.383145e-02 9.997306e-01 -1.863855e-02 -2.744968e+00 5.697636e-02 1.939805e-02 9.981870e-01 7.392846e+01 +9.982780e-01 1.296168e-02 -5.721025e-02 -4.396788e+00 -1.429501e-02 9.996342e-01 -2.295835e-02 -2.802467e+00 5.689175e-02 2.373663e-02 9.980981e-01 7.510649e+01 +9.982961e-01 1.041136e-02 -5.741566e-02 -4.465029e+00 -1.172032e-02 9.996779e-01 -2.250857e-02 -2.863069e+00 5.716282e-02 2.314314e-02 9.980965e-01 7.628381e+01 +9.983466e-01 3.244646e-03 -5.739036e-02 -4.525824e+00 -4.717933e-03 9.996623e-01 -2.555449e-02 -2.925207e+00 5.728806e-02 2.578300e-02 9.980247e-01 7.745626e+01 +9.983658e-01 3.691504e-03 -5.702748e-02 -4.593996e+00 -5.239377e-03 9.996212e-01 -2.701694e-02 -2.983030e+00 5.690614e-02 2.727158e-02 9.980069e-01 7.862373e+01 +9.984042e-01 -2.420659e-03 -5.642121e-02 -4.660434e+00 1.148301e-03 9.997445e-01 -2.257258e-02 -3.039445e+00 5.646143e-02 2.247176e-02 9.981518e-01 7.979891e+01 +9.984173e-01 -3.625946e-03 -5.612367e-02 -4.726372e+00 2.776288e-03 9.998804e-01 -1.520962e-02 -3.092053e+00 5.617211e-02 1.502973e-02 9.983079e-01 8.096885e+01 +9.984861e-01 -7.615133e-04 -5.500021e-02 -4.800834e+00 2.479803e-04 9.999563e-01 -9.343151e-03 -3.138830e+00 5.500492e-02 9.315366e-03 9.984426e-01 8.213644e+01 +9.985195e-01 1.081753e-03 -5.438531e-02 -4.871285e+00 -1.483063e-03 9.999719e-01 -7.339205e-03 -3.178547e+00 5.437584e-02 7.408995e-03 9.984930e-01 8.329433e+01 +9.985410e-01 5.346180e-03 -5.373445e-02 -4.944700e+00 -5.602005e-03 9.999737e-01 -4.611426e-03 -3.214267e+00 5.370838e-02 4.905718e-03 9.985446e-01 8.445032e+01 +9.985646e-01 9.151735e-03 -5.277358e-02 -5.016400e+00 -9.450020e-03 9.999407e-01 -5.405399e-03 -3.250277e+00 5.272098e-02 5.896351e-03 9.985918e-01 8.559727e+01 +9.985602e-01 1.291144e-02 -5.206642e-02 -5.086740e+00 -1.354239e-02 9.998388e-01 -1.178365e-02 -3.288225e+00 5.190588e-02 1.247178e-02 9.985740e-01 8.673570e+01 +9.985257e-01 1.610948e-02 -5.183638e-02 -5.155943e+00 -1.706535e-02 9.996914e-01 -1.805064e-02 -3.328985e+00 5.152959e-02 1.890863e-02 9.984924e-01 8.786812e+01 +9.986073e-01 1.277185e-02 -5.118999e-02 -5.214554e+00 -1.369076e-02 9.997506e-01 -1.764069e-02 -3.368601e+00 5.095192e-02 1.831695e-02 9.985331e-01 8.900816e+01 +9.986455e-01 1.239836e-02 -5.053210e-02 -5.275069e+00 -1.304564e-02 9.998367e-01 -1.249957e-02 -3.403659e+00 5.036888e-02 1.314186e-02 9.986442e-01 9.015079e+01 +9.987584e-01 8.385163e-03 -4.910641e-02 -5.329539e+00 -8.705803e-03 9.999421e-01 -6.319235e-03 -3.435396e+00 4.905058e-02 6.738899e-03 9.987735e-01 9.129492e+01 +9.987935e-01 3.096949e-03 -4.901132e-02 -5.369648e+00 -3.267539e-03 9.999889e-01 -3.400893e-03 -3.459248e+00 4.900023e-02 3.556936e-03 9.987924e-01 9.243554e+01 +9.988405e-01 -1.632819e-03 -4.811549e-02 -5.418986e+00 1.437775e-03 9.999906e-01 -4.088007e-03 -3.482548e+00 4.812171e-02 4.014088e-03 9.988334e-01 9.356768e+01 +9.988745e-01 -4.879842e-03 -4.718123e-02 -5.470861e+00 4.550713e-03 9.999646e-01 -7.080753e-03 -3.498163e+00 4.721411e-02 6.858075e-03 9.988612e-01 9.470089e+01 +9.988872e-01 -7.351853e-03 -4.658741e-02 -5.524006e+00 6.830398e-03 9.999123e-01 -1.134240e-02 -3.526732e+00 4.666671e-02 1.101157e-02 9.988498e-01 9.582761e+01 +9.989093e-01 -9.331753e-03 -4.575093e-02 -5.583931e+00 8.633629e-03 9.998436e-01 -1.543319e-02 -3.562758e+00 4.588779e-02 1.502136e-02 9.988336e-01 9.696153e+01 diff --git a/tools/Ground-Truth/dataset/poses/01.txt b/tools/Ground-Truth/dataset/poses/01.txt new file mode 100644 index 0000000..4e8e68c --- /dev/null +++ b/tools/Ground-Truth/dataset/poses/01.txt @@ -0,0 +1,1101 @@ +1.000000e+00 9.043683e-12 2.326809e-11 1.110223e-16 9.043683e-12 1.000000e+00 2.392370e-10 2.220446e-16 2.326810e-11 2.392370e-10 9.999999e-01 -2.220446e-16 +9.990498e-01 -1.649780e-03 4.355194e-02 5.154656e-02 1.760423e-03 9.999953e-01 -2.502237e-03 -2.424883e-02 -4.354760e-02 2.576529e-03 9.990480e-01 1.000725e+00 +9.960495e-01 -5.367949e-03 8.863831e-02 1.464632e-01 6.010224e-03 9.999575e-01 -6.980718e-03 -5.051622e-02 -8.859707e-02 7.485875e-03 9.960394e-01 1.995659e+00 +9.909271e-01 -5.886878e-03 1.342721e-01 2.879204e-01 7.448178e-03 9.999103e-01 -1.112852e-02 -7.903059e-02 -1.341946e-01 1.202763e-02 9.908820e-01 2.986691e+00 +9.836222e-01 -3.565066e-03 1.802072e-01 4.657503e-01 6.172884e-03 9.998841e-01 -1.391250e-02 -1.102928e-01 -1.801368e-01 1.479704e-02 9.835302e-01 3.963845e+00 +9.740479e-01 -6.173619e-03 2.262579e-01 6.971645e-01 9.486835e-03 9.998630e-01 -1.355912e-02 -1.438770e-01 -2.261432e-01 1.535370e-02 9.739730e-01 4.934639e+00 +9.624212e-01 -7.368625e-03 2.714613e-01 9.715689e-01 1.164015e-02 9.998324e-01 -1.412847e-02 -1.802237e-01 -2.713117e-01 1.675739e-02 9.623456e-01 5.887651e+00 +9.488374e-01 -9.693544e-03 3.156164e-01 1.288079e+00 1.587616e-02 9.997290e-01 -1.702376e-02 -2.184877e-01 -3.153658e-01 2.116355e-02 9.487341e-01 6.826202e+00 +9.336202e-01 -1.263857e-02 3.580415e-01 1.651331e+00 2.080461e-02 9.996037e-01 -1.896441e-02 -2.547290e-01 -3.576599e-01 2.515446e-02 9.335130e-01 7.743952e+00 +9.161945e-01 -1.228394e-02 4.005456e-01 2.050498e+00 2.177648e-02 9.995793e-01 -1.915567e-02 -2.919528e-01 -4.001417e-01 2.627278e-02 9.160765e-01 8.646240e+00 +8.965559e-01 -1.307765e-02 4.427376e-01 2.488685e+00 2.341790e-02 9.995655e-01 -1.789659e-02 -3.309237e-01 -4.423112e-01 2.641328e-02 8.964725e-01 9.527392e+00 +8.745113e-01 -1.351429e-02 4.848168e-01 2.966292e+00 2.447754e-02 9.995676e-01 -1.628953e-02 -3.697385e-01 -4.843870e-01 2.611249e-02 8.744640e-01 1.038417e+01 +8.503691e-01 -1.348162e-02 5.260139e-01 3.483068e+00 2.517723e-02 9.995692e-01 -1.508348e-02 -4.086031e-01 -5.255839e-01 2.607010e-02 8.503422e-01 1.121560e+01 +8.245429e-01 -1.401100e-02 5.656260e-01 4.036690e+00 2.696390e-02 9.995305e-01 -1.454755e-02 -4.439735e-01 -5.651566e-01 2.724656e-02 8.245336e-01 1.201878e+01 +7.970302e-01 -1.619333e-02 6.037224e-01 4.631439e+00 3.126104e-02 9.994066e-01 -1.446406e-02 -4.790227e-01 -6.031299e-01 3.040128e-02 7.970634e-01 1.279006e+01 +7.681511e-01 -1.510445e-02 6.400904e-01 5.252124e+00 3.186802e-02 9.993845e-01 -1.466090e-02 -5.136186e-01 -6.394750e-01 3.166020e-02 7.681597e-01 1.353058e+01 +7.374230e-01 -1.831697e-02 6.751828e-01 5.913461e+00 3.718619e-02 9.992171e-01 -1.350645e-02 -5.462713e-01 -6.744067e-01 3.506743e-02 7.375268e-01 1.423731e+01 +7.051666e-01 -1.811309e-02 7.088103e-01 6.602643e+00 3.829943e-02 9.991872e-01 -1.256911e-02 -5.777429e-01 -7.080065e-01 3.601033e-02 7.052871e-01 1.491216e+01 +6.706801e-01 -1.682164e-02 7.415560e-01 7.315983e+00 3.848398e-02 9.991854e-01 -1.214001e-02 -6.091556e-01 -7.407478e-01 3.668008e-02 6.707811e-01 1.555483e+01 +6.350649e-01 -1.784306e-02 7.722528e-01 8.059654e+00 4.358563e-02 9.989682e-01 -1.276143e-02 -6.362920e-01 -7.712282e-01 4.176345e-02 6.351872e-01 1.615500e+01 +5.983915e-01 -1.631634e-02 8.010377e-01 8.824947e+00 4.435618e-02 9.989339e-01 -1.278768e-02 -6.652783e-01 -7.999751e-01 4.318299e-02 5.984773e-01 1.672174e+01 +5.606382e-01 -1.560419e-02 8.279139e-01 9.617499e+00 4.722424e-02 9.987977e-01 -1.315388e-02 -6.938755e-01 -8.267132e-01 4.647216e-02 5.607010e-01 1.724835e+01 +5.217303e-01 -1.415459e-02 8.529931e-01 1.043572e+01 5.299064e-02 9.984693e-01 -1.584291e-02 -7.209802e-01 -8.514631e-01 5.346636e-02 5.216817e-01 1.773582e+01 +4.824023e-01 -1.314333e-02 8.758512e-01 1.127339e+01 5.466343e-02 9.983902e-01 -1.512539e-02 -7.448949e-01 -8.742425e-01 5.517354e-02 4.823441e-01 1.818861e+01 +4.437520e-01 -1.483490e-02 8.960269e-01 1.213844e+01 5.962892e-02 9.981359e-01 -1.300543e-02 -7.707228e-01 -8.941636e-01 5.920028e-02 4.438094e-01 1.860541e+01 +4.063321e-01 -1.567329e-02 9.135911e-01 1.302386e+01 6.333168e-02 9.979314e-01 -1.104743e-02 -7.968987e-01 -9.115280e-01 6.234817e-02 4.064841e-01 1.898486e+01 +3.705969e-01 -1.336462e-02 9.286977e-01 1.392282e+01 6.549873e-02 9.977831e-01 -1.177846e-02 -8.194983e-01 -9.264814e-01 6.519356e-02 3.706506e-01 1.933529e+01 +3.367104e-01 -1.369924e-02 9.415086e-01 1.484567e+01 6.695770e-02 9.977112e-01 -9.428981e-03 -8.398217e-01 -9.392245e-01 6.621607e-02 3.368570e-01 1.965558e+01 +3.032101e-01 -1.606372e-02 9.527884e-01 1.578819e+01 6.893784e-02 9.976078e-01 -5.119036e-03 -8.590110e-01 -9.504268e-01 6.723530e-02 3.035921e-01 1.994858e+01 +2.700383e-01 -1.584084e-02 9.627193e-01 1.674609e+01 6.970552e-02 9.975627e-01 -3.137907e-03 -8.779579e-01 -9.603231e-01 6.795419e-02 2.704843e-01 2.020959e+01 +2.373841e-01 -1.301040e-02 9.713288e-01 1.771096e+01 6.752450e-02 9.977127e-01 -3.138591e-03 -8.926428e-01 -9.690661e-01 6.633352e-02 2.377196e-01 2.044290e+01 +2.058013e-01 -1.089049e-02 9.785332e-01 1.869074e+01 6.752573e-02 9.977127e-01 -3.097801e-03 -9.066816e-01 -9.762612e-01 6.671368e-02 2.060660e-01 2.064544e+01 +1.748760e-01 -1.056614e-02 9.845338e-01 1.969166e+01 6.930053e-02 9.975945e-01 -1.603074e-03 -9.204752e-01 -9.821485e-01 6.850903e-02 1.751876e-01 2.081649e+01 +1.440159e-01 -1.095260e-02 9.895148e-01 2.070872e+01 7.093837e-02 9.974804e-01 7.162510e-04 -9.323174e-01 -9.870294e-01 7.009140e-02 1.444300e-01 2.095890e+01 +1.132280e-01 -1.188899e-02 9.934979e-01 2.174157e+01 6.960632e-02 9.975665e-01 4.004714e-03 -9.423525e-01 -9.911278e-01 6.870027e-02 1.137800e-01 2.107450e+01 +8.347506e-02 -1.182121e-02 9.964398e-01 2.279076e+01 7.016375e-02 9.975177e-01 5.956143e-03 -9.484050e-01 -9.940367e-01 6.941674e-02 8.409726e-02 2.116118e+01 +5.575869e-02 -1.119487e-02 9.983815e-01 2.385365e+01 7.276066e-02 9.973240e-01 7.119389e-03 -9.510470e-01 -9.957895e-01 7.224591e-02 5.642402e-02 2.121468e+01 +3.022405e-02 -1.055359e-02 9.994875e-01 2.493112e+01 7.695768e-02 9.970006e-01 8.200162e-03 -9.519265e-01 -9.965761e-01 7.667038e-02 3.094558e-02 2.124069e+01 +7.200764e-03 -1.011089e-02 9.999230e-01 2.602348e+01 8.125250e-02 9.966483e-01 9.492647e-03 -9.509506e-01 -9.966675e-01 8.117787e-02 7.998165e-03 2.124027e+01 +-1.358780e-02 -9.968577e-03 9.998580e-01 2.712723e+01 8.719664e-02 9.961291e-01 1.111637e-02 -9.489508e-01 -9.960984e-01 8.733528e-02 -1.266597e-02 2.121564e+01 +-3.162964e-02 -1.065186e-02 9.994429e-01 2.824249e+01 9.165357e-02 9.956992e-01 1.351254e-02 -9.456288e-01 -9.952885e-01 9.202989e-02 -3.051732e-02 2.116969e+01 +-4.749041e-02 -1.030237e-02 9.988186e-01 2.937022e+01 9.488928e-02 9.953781e-01 1.477854e-02 -9.414386e-01 -9.943544e-01 9.547900e-02 -4.629333e-02 2.110741e+01 +-6.213432e-02 -1.086217e-02 9.980087e-01 3.050291e+01 9.737473e-02 9.951044e-01 1.689294e-02 -9.363594e-01 -9.933063e-01 9.823044e-02 -6.077243e-02 2.102960e+01 +-7.560868e-02 -1.193509e-02 9.970662e-01 3.164196e+01 9.751631e-02 9.950466e-01 1.930569e-02 -9.296868e-01 -9.923577e-01 9.868987e-02 -7.407029e-02 2.093984e+01 +-8.805539e-02 -1.198809e-02 9.960435e-01 3.278682e+01 9.729037e-02 9.950433e-01 2.057702e-02 -9.216773e-01 -9.913530e-01 9.871733e-02 -8.645259e-02 2.083696e+01 +-9.947788e-02 -9.193596e-03 9.949973e-01 3.394232e+01 9.735338e-02 9.950699e-01 1.892746e-02 -9.117462e-01 -9.902658e-01 9.874920e-02 -9.809240e-02 2.071859e+01 +-1.097967e-01 -5.360682e-03 9.939396e-01 3.511473e+01 9.798071e-02 9.950566e-01 1.619026e-02 -9.007201e-01 -9.891129e-01 9.916453e-02 -1.087287e-01 2.058533e+01 +-1.194554e-01 -2.512059e-03 9.928364e-01 3.630912e+01 9.905114e-02 9.949776e-01 1.443504e-02 -8.891584e-01 -9.878862e-01 1.000659e-01 -1.186066e-01 2.043698e+01 +-1.270885e-01 -1.278670e-03 9.918906e-01 3.752680e+01 9.888957e-02 9.950006e-01 1.395315e-02 -8.781568e-01 -9.869495e-01 9.986090e-02 -1.263266e-01 2.027890e+01 +-1.329871e-01 -7.149781e-04 9.911175e-01 3.876733e+01 9.839198e-02 9.950504e-01 1.391994e-02 -8.670199e-01 -9.862218e-01 9.936917e-02 -1.322585e-01 2.011085e+01 +-1.381591e-01 8.940047e-04 9.904097e-01 4.002403e+01 9.941083e-02 9.949619e-01 1.296938e-02 -8.564479e-01 -9.854083e-01 1.002493e-01 -1.375519e-01 1.993253e+01 +-1.426852e-01 2.815813e-03 9.897642e-01 4.130550e+01 9.869170e-02 9.950528e-01 1.139661e-02 -8.460362e-01 -9.848354e-01 9.930761e-02 -1.422571e-01 1.974648e+01 +-1.468253e-01 3.917606e-03 9.891547e-01 4.260679e+01 9.897322e-02 9.950320e-01 1.075021e-02 -8.375480e-01 -9.841984e-01 9.947820e-02 -1.464836e-01 1.955065e+01 +-1.499193e-01 3.009372e-03 9.886937e-01 4.393278e+01 9.873932e-02 9.950416e-01 1.194351e-02 -8.295496e-01 -9.837554e-01 9.941348e-02 -1.494731e-01 1.934786e+01 +-1.522300e-01 5.817954e-04 9.883450e-01 4.528137e+01 9.933371e-02 9.949454e-01 1.471420e-02 -8.187903e-01 -9.833406e-01 1.004159e-01 -1.515183e-01 1.913753e+01 +-1.545076e-01 -3.897853e-04 9.879916e-01 4.664850e+01 9.937378e-02 9.949226e-01 1.593314e-02 -8.059921e-01 -9.829813e-01 1.006422e-01 -1.536843e-01 1.892231e+01 +-1.565155e-01 3.425744e-04 9.876755e-01 4.803559e+01 1.016061e-01 9.946999e-01 1.575634e-02 -7.907530e-01 -9.824353e-01 1.028199e-01 -1.557207e-01 1.869944e+01 +-1.575241e-01 8.739825e-04 9.875148e-01 4.944201e+01 1.013351e-01 9.947349e-01 1.528416e-02 -7.765930e-01 -9.823020e-01 1.024775e-01 -1.567833e-01 1.847318e+01 +-1.580662e-01 1.736308e-03 9.874270e-01 5.087125e+01 1.033930e-01 9.945304e-01 1.480223e-02 -7.612088e-01 -9.820004e-01 1.044328e-01 -1.573812e-01 1.823994e+01 +-1.581475e-01 2.246276e-03 9.874130e-01 5.231634e+01 1.029209e-01 9.945878e-01 1.422156e-02 -7.488661e-01 -9.820370e-01 1.038745e-01 -1.575227e-01 1.800571e+01 +-1.576227e-01 3.491308e-03 9.874933e-01 5.378414e+01 1.029740e-01 9.946001e-01 1.292016e-02 -7.385593e-01 -9.821158e-01 1.037226e-01 -1.571310e-01 1.776822e+01 +-1.564353e-01 3.535458e-03 9.876819e-01 5.527561e+01 1.033158e-01 9.945662e-01 1.280369e-02 -7.282464e-01 -9.822697e-01 1.040460e-01 -1.559505e-01 1.752865e+01 +-1.549453e-01 2.303011e-03 9.879204e-01 5.678690e+01 1.024081e-01 9.946475e-01 1.374297e-02 -7.193216e-01 -9.826009e-01 1.033004e-01 -1.543518e-01 1.728947e+01 +-1.538084e-01 3.054216e-03 9.880960e-01 5.831970e+01 1.033843e-01 9.945563e-01 1.301875e-02 -7.090229e-01 -9.826773e-01 1.041560e-01 -1.532869e-01 1.704698e+01 +-1.525997e-01 3.933834e-03 9.882803e-01 5.987004e+01 1.033114e-01 9.945767e-01 1.199334e-02 -6.982294e-01 -9.828733e-01 1.039308e-01 -1.521785e-01 1.680555e+01 +-1.516316e-01 4.600354e-03 9.884264e-01 6.144932e+01 1.043179e-01 9.944789e-01 1.137458e-02 -6.898538e-01 -9.829169e-01 1.048353e-01 -1.512744e-01 1.656009e+01 +-1.505876e-01 4.530984e-03 9.885863e-01 6.304564e+01 1.038798e-01 9.945260e-01 1.126540e-02 -6.822340e-01 -9.831237e-01 1.043906e-01 -1.502339e-01 1.631483e+01 +-1.496365e-01 2.801779e-03 9.887371e-01 6.466146e+01 1.056381e-01 9.943174e-01 1.316978e-02 -6.742945e-01 -9.830816e-01 1.064190e-01 -1.490821e-01 1.606555e+01 +-1.489502e-01 1.053388e-03 9.888442e-01 6.629273e+01 1.069190e-01 9.941539e-01 1.504623e-02 -6.659320e-01 -9.830473e-01 1.079674e-01 -1.481921e-01 1.581429e+01 +-1.481741e-01 1.587223e-03 9.889600e-01 6.793358e+01 1.084503e-01 9.939938e-01 1.465361e-02 -6.566595e-01 -9.829969e-01 1.094243e-01 -1.474563e-01 1.556429e+01 +-1.471094e-01 3.907489e-03 9.891125e-01 6.959146e+01 1.108431e-01 9.937585e-01 1.255970e-02 -6.495479e-01 -9.828899e-01 1.114840e-01 -1.466243e-01 1.531065e+01 +-1.464650e-01 3.603548e-03 9.892093e-01 7.126348e+01 1.101154e-01 9.938379e-01 1.268356e-02 -6.455501e-01 -9.830679e-01 1.107848e-01 -1.459592e-01 1.506048e+01 +-1.462604e-01 3.233250e-03 9.892409e-01 7.294957e+01 1.105105e-01 9.937887e-01 1.309099e-02 -6.411509e-01 -9.830540e-01 1.112362e-01 -1.457092e-01 1.480708e+01 +-1.460361e-01 1.690015e-03 9.892778e-01 7.465679e+01 1.098325e-01 9.938441e-01 1.451553e-02 -6.351425e-01 -9.831634e-01 1.107746e-01 -1.453227e-01 1.455382e+01 +-1.456358e-01 1.966691e-03 9.893363e-01 7.637583e+01 1.116862e-01 9.936382e-01 1.446557e-02 -6.266393e-01 -9.830139e-01 1.126019e-01 -1.449289e-01 1.429583e+01 +-1.456204e-01 2.152571e-03 9.893382e-01 7.811207e+01 1.123679e-01 9.935626e-01 1.437762e-02 -6.192733e-01 -9.829385e-01 1.132635e-01 -1.449248e-01 1.403765e+01 +-1.456043e-01 3.177492e-03 9.893378e-01 7.986417e+01 1.128566e-01 9.935207e-01 1.341856e-02 -6.121849e-01 -9.828849e-01 1.136071e-01 -1.450194e-01 1.377611e+01 +-1.459369e-01 3.866772e-03 9.892864e-01 8.162656e+01 1.123299e-01 9.935899e-01 1.268701e-02 -6.069533e-01 -9.828959e-01 1.129779e-01 -1.454358e-01 1.351471e+01 +-1.470604e-01 4.142622e-03 9.891189e-01 8.340315e+01 1.112117e-01 9.937197e-01 1.237285e-02 -6.037449e-01 -9.828556e-01 1.118211e-01 -1.465975e-01 1.324930e+01 +-1.482341e-01 4.952492e-03 9.889399e-01 8.519377e+01 1.106078e-01 9.937964e-01 1.160240e-02 -6.018080e-01 -9.827474e-01 1.111043e-01 -1.478623e-01 1.298000e+01 +-1.492423e-01 4.338053e-03 9.887912e-01 8.700538e+01 1.094671e-01 9.939160e-01 1.216177e-02 -5.994816e-01 -9.827226e-01 1.100551e-01 -1.488091e-01 1.270711e+01 +-1.502286e-01 3.835819e-03 9.886439e-01 8.882747e+01 1.096199e-01 9.938911e-01 1.280101e-02 -5.948763e-01 -9.825552e-01 1.102981e-01 -1.497313e-01 1.242843e+01 +-1.506723e-01 2.811838e-03 9.885798e-01 9.066661e+01 1.070118e-01 9.941663e-01 1.348224e-02 -5.892579e-01 -9.827748e-01 1.078211e-01 -1.500942e-01 1.214861e+01 +-1.520677e-01 3.896026e-03 9.883624e-01 9.251613e+01 1.068060e-01 9.942011e-01 1.251394e-02 -5.822604e-01 -9.825822e-01 1.074660e-01 -1.516020e-01 1.186127e+01 +-1.546860e-01 5.230309e-03 9.879499e-01 9.438417e+01 1.057142e-01 9.943325e-01 1.128785e-02 -5.761580e-01 -9.822915e-01 1.061864e-01 -1.543622e-01 1.156935e+01 +-1.584947e-01 5.190445e-03 9.873462e-01 9.626377e+01 1.064537e-01 9.942469e-01 1.186186e-02 -5.690865e-01 -9.816043e-01 1.069867e-01 -1.581354e-01 1.126751e+01 +-1.632049e-01 4.743000e-03 9.865808e-01 9.815387e+01 1.041819e-01 9.944803e-01 1.245328e-02 -5.670654e-01 -9.810760e-01 1.048163e-01 -1.627982e-01 1.095901e+01 +-1.680724e-01 3.613141e-03 9.857681e-01 1.000527e+02 1.019229e-01 9.946975e-01 1.373188e-02 -5.652429e-01 -9.804914e-01 1.027803e-01 -1.675495e-01 1.063988e+01 +-1.727782e-01 4.875200e-03 9.849487e-01 1.019553e+02 1.009596e-01 9.948083e-01 1.278618e-02 -5.641477e-01 -9.797728e-01 1.016492e-01 -1.723734e-01 1.030991e+01 +-1.774521e-01 6.239531e-03 9.841097e-01 1.038698e+02 1.014658e-01 9.947668e-01 1.198894e-02 -5.624452e-01 -9.788848e-01 1.019809e-01 -1.771565e-01 9.966128e+00 +-1.820546e-01 7.979443e-03 9.832561e-01 1.057910e+02 1.011783e-01 9.948112e-01 1.066042e-02 -5.643553e-01 -9.780690e-01 1.014249e-01 -1.819173e-01 9.611618e+00 +-1.868758e-01 8.786952e-03 9.823443e-01 1.077248e+02 1.001207e-01 9.949235e-01 1.014694e-02 -5.687973e-01 -9.772682e-01 1.002492e-01 -1.868069e-01 9.246382e+00 +-1.918873e-01 7.633132e-03 9.813873e-01 1.096683e+02 9.794174e-02 9.951267e-01 1.141021e-02 -5.717942e-01 -9.765176e-01 9.830823e-02 -1.916997e-01 8.871585e+00 +-1.972643e-01 7.480826e-03 9.803218e-01 1.116206e+02 9.606302e-02 9.953061e-01 1.173501e-02 -5.733449e-01 -9.756324e-01 9.648755e-02 -1.970570e-01 8.486629e+00 +-2.028929e-01 6.576712e-03 9.791789e-01 1.135815e+02 9.508165e-02 9.953844e-01 1.301604e-02 -5.728043e-01 -9.745737e-01 9.574279e-02 -2.025817e-01 8.086921e+00 +-2.084031e-01 6.469213e-03 9.780216e-01 1.155478e+02 9.502287e-02 9.953813e-01 1.366404e-02 -5.705380e-01 -9.734160e-01 9.578203e-02 -2.080553e-01 7.674193e+00 +-2.138450e-01 7.858298e-03 9.768360e-01 1.175182e+02 9.558616e-02 9.953373e-01 1.291820e-02 -5.680584e-01 -9.721798e-01 9.613447e-02 -2.135991e-01 7.246929e+00 +-2.195383e-01 8.856306e-03 9.755637e-01 1.194963e+02 9.521901e-02 9.953792e-01 1.239164e-02 -5.658779e-01 -9.709460e-01 9.561263e-02 -2.193671e-01 6.808278e+00 +-2.254576e-01 8.853206e-03 9.742128e-01 1.214861e+02 9.566882e-02 9.953271e-01 1.309511e-02 -5.645652e-01 -9.695444e-01 9.615416e-02 -2.252510e-01 6.351224e+00 +-2.310452e-01 9.190854e-03 9.728996e-01 1.234817e+02 9.472620e-02 9.954172e-01 1.309209e-02 -5.636678e-01 -9.683207e-01 9.518392e-02 -2.308570e-01 5.883248e+00 +-2.362092e-01 9.550857e-03 9.716553e-01 1.254794e+02 9.420289e-02 9.954666e-01 1.311579e-02 -5.607338e-01 -9.671251e-01 9.463079e-02 -2.360381e-01 5.403529e+00 +-2.414041e-01 9.719218e-03 9.703760e-01 1.274889e+02 9.294890e-02 9.955840e-01 1.315154e-02 -5.591517e-01 -9.659630e-01 9.337020e-02 -2.412414e-01 4.911013e+00 +-2.458159e-01 9.821942e-03 9.692668e-01 1.295004e+02 9.457506e-02 9.954207e-01 1.389822e-02 -5.556139e-01 -9.646917e-01 9.508485e-02 -2.456191e-01 4.402279e+00 +-2.497010e-01 8.595703e-03 9.682849e-01 1.315233e+02 9.625855e-02 9.952279e-01 1.598823e-02 -5.494115e-01 -9.635267e-01 9.719796e-02 -2.493368e-01 3.880107e+00 +-2.532929e-01 9.879226e-03 9.673392e-01 1.335486e+02 9.768544e-02 9.950979e-01 1.541572e-02 -5.427542e-01 -9.624449e-01 9.839963e-02 -2.530163e-01 3.348158e+00 +-2.563419e-01 1.033140e-02 9.665310e-01 1.355837e+02 9.797856e-02 9.950701e-01 1.534925e-02 -5.360354e-01 -9.616075e-01 9.863395e-02 -2.560904e-01 2.806947e+00 +-2.597614e-01 1.013191e-02 9.656197e-01 1.376250e+02 9.708426e-02 9.951527e-01 1.567485e-02 -5.295973e-01 -9.607802e-01 9.781817e-02 -2.594859e-01 2.257989e+00 +-2.637027e-01 1.035061e-02 9.645485e-01 1.396797e+02 9.579549e-02 9.952802e-01 1.550960e-02 -5.224538e-01 -9.598354e-01 9.648930e-02 -2.634496e-01 1.699296e+00 +-2.681714e-01 1.125920e-02 9.633055e-01 1.417304e+02 9.446872e-02 9.954198e-01 1.466427e-02 -5.179993e-01 -9.587282e-01 9.493475e-02 -2.680067e-01 1.132152e+00 +-2.726489e-01 1.108767e-02 9.620497e-01 1.437927e+02 9.357615e-02 9.954984e-01 1.504669e-02 -5.127373e-01 -9.575521e-01 9.412736e-02 -2.724590e-01 5.515872e-01 +-2.772301e-01 1.132109e-02 9.607369e-01 1.458618e+02 9.373713e-02 9.954791e-01 1.531828e-02 -5.061993e-01 -9.562200e-01 9.430339e-02 -2.770379e-01 -4.137210e-02 +-2.817308e-01 1.185782e-02 9.594203e-01 1.479305e+02 9.322617e-02 9.955309e-01 1.507145e-02 -5.006247e-01 -9.549537e-01 9.368914e-02 -2.815771e-01 -6.449311e-01 +-2.862852e-01 1.239653e-02 9.580643e-01 1.500068e+02 9.286516e-02 9.955677e-01 1.486782e-02 -4.959689e-01 -9.536335e-01 9.322721e-02 -2.861674e-01 -1.261108e+00 +-2.904967e-01 1.139404e-02 9.568082e-01 1.520968e+02 9.253122e-02 9.955774e-01 1.623769e-02 -4.898301e-01 -9.523915e-01 9.325161e-02 -2.902662e-01 -1.892338e+00 +-2.947361e-01 1.147144e-02 9.555099e-01 1.541812e+02 9.310741e-02 9.955148e-01 1.676813e-02 -4.829921e-01 -9.510318e-01 9.390720e-02 -2.944822e-01 -2.533182e+00 +-2.986660e-01 1.208825e-02 9.542812e-01 1.562753e+02 9.410159e-02 9.954201e-01 1.684205e-02 -4.753909e-01 -9.497070e-01 9.482950e-02 -2.984357e-01 -3.187653e+00 +-3.022573e-01 1.327702e-02 9.531339e-01 1.583734e+02 9.424427e-02 9.954202e-01 1.602063e-02 -4.676840e-01 -9.485560e-01 9.466974e-02 -3.021243e-01 -3.851462e+00 +-3.058439e-01 1.542536e-02 9.519567e-01 1.604737e+02 9.475529e-02 9.953977e-01 1.431362e-02 -4.608735e-01 -9.473547e-01 9.458065e-02 -3.058979e-01 -4.525316e+00 +-3.092558e-01 1.602772e-02 9.508438e-01 1.625875e+02 9.539849e-02 9.953371e-01 1.425001e-02 -4.555311e-01 -9.461818e-01 9.511594e-02 -3.093428e-01 -5.211974e+00 +-3.126266e-01 1.689296e-02 9.497259e-01 1.647037e+02 9.518253e-02 9.953665e-01 1.362698e-02 -4.525483e-01 -9.450952e-01 9.465745e-02 -3.127859e-01 -5.908582e+00 +-3.161339e-01 1.703662e-02 9.485616e-01 1.668257e+02 9.503047e-02 9.953788e-01 1.379400e-02 -4.495307e-01 -9.439430e-01 9.450299e-02 -3.162920e-01 -6.614701e+00 +-3.201365e-01 1.695749e-02 9.472197e-01 1.689537e+02 9.501387e-02 9.953733e-01 1.429274e-02 -4.456125e-01 -9.425948e-01 9.457461e-02 -3.202665e-01 -7.331463e+00 +-3.239253e-01 1.718208e-02 9.459266e-01 1.710871e+02 9.640571e-02 9.952300e-01 1.493575e-02 -4.416744e-01 -9.411579e-01 9.603078e-02 -3.240366e-01 -8.063072e+00 +-3.271325e-01 1.815461e-02 9.448041e-01 1.732245e+02 9.878847e-02 9.949941e-01 1.508585e-02 -4.365523e-01 -9.398006e-01 9.827080e-02 -3.272883e-01 -8.806086e+00 +-3.298961e-01 1.768240e-02 9.438517e-01 1.753665e+02 9.945702e-02 9.949112e-01 1.612335e-02 -4.294089e-01 -9.387634e-01 9.919169e-02 -3.299759e-01 -9.557829e+00 +-3.325870e-01 1.703682e-02 9.429187e-01 1.775169e+02 9.930238e-02 9.949112e-01 1.704978e-02 -4.209330e-01 -9.378299e-01 9.930458e-02 -3.325864e-01 -1.031827e+01 +-3.353595e-01 1.698544e-02 9.419371e-01 1.796714e+02 9.814417e-02 9.950270e-01 1.699965e-02 -4.118277e-01 -9.369641e-01 9.814661e-02 -3.353588e-01 -1.108560e+01 +-3.383518e-01 1.880925e-02 9.408317e-01 1.818303e+02 9.724016e-02 9.951467e-01 1.507538e-02 -4.043634e-01 -9.359820e-01 9.658739e-02 -3.385386e-01 -1.186225e+01 +-3.416162e-01 2.028947e-02 9.396206e-01 1.839969e+02 9.708227e-02 9.951806e-01 1.380682e-02 -3.985802e-01 -9.348119e-01 9.593711e-02 -3.419395e-01 -1.264986e+01 +-3.448185e-01 2.159976e-02 9.384208e-01 1.861699e+02 9.545937e-02 9.953590e-01 1.216580e-02 -3.990509e-01 -9.338028e-01 9.377604e-02 -3.452801e-01 -1.344797e+01 +-3.481357e-01 2.308833e-02 9.371598e-01 1.883440e+02 9.427365e-02 9.954910e-01 1.049532e-02 -4.000549e-01 -9.326918e-01 9.200325e-02 -3.487425e-01 -1.425545e+01 +-3.519011e-01 2.312204e-02 9.357516e-01 1.905195e+02 9.504064e-02 9.954110e-01 1.114501e-02 -4.013833e-01 -9.311997e-01 9.285635e-02 -3.524837e-01 -1.507493e+01 +-3.555047e-01 2.192990e-02 9.344172e-01 1.927087e+02 9.415617e-02 9.954795e-01 1.245931e-02 -4.038655e-01 -9.299198e-01 9.241047e-02 -3.559625e-01 -1.590879e+01 +-3.592385e-01 2.119195e-02 9.330052e-01 1.949010e+02 9.384472e-02 9.954950e-01 1.352206e-02 -4.035663e-01 -9.285154e-01 9.241523e-02 -3.596089e-01 -1.675316e+01 +-3.631389e-01 2.128419e-02 9.314919e-01 1.970930e+02 9.410306e-02 9.954648e-01 1.393979e-02 -4.021162e-01 -9.269707e-01 9.271829e-02 -3.634949e-01 -1.760738e+01 +-3.666020e-01 2.143330e-02 9.301310e-01 1.992958e+02 9.312059e-02 9.955597e-01 1.376156e-02 -4.006638e-01 -9.257059e-01 9.165934e-02 -3.669700e-01 -1.847484e+01 +-3.703490e-01 2.201051e-02 9.286319e-01 2.014804e+02 9.212319e-02 9.956609e-01 1.314053e-02 -4.011965e-01 -9.243132e-01 9.041510e-02 -3.707697e-01 -1.934449e+01 +-3.735992e-01 2.206369e-02 9.273278e-01 2.036882e+02 9.207681e-02 9.956616e-01 1.340610e-02 -4.030819e-01 -9.230089e-01 9.039387e-02 -3.740100e-01 -2.023459e+01 +-3.763962e-01 2.270051e-02 9.261807e-01 2.058770e+02 9.308605e-02 9.955675e-01 1.342863e-02 -4.061955e-01 -9.217705e-01 9.126896e-02 -3.768409e-01 -2.112723e+01 +-3.789168e-01 2.285844e-02 9.251484e-01 2.080748e+02 9.433619e-02 9.954413e-01 1.404241e-02 -4.083230e-01 -9.206100e-01 9.259586e-02 -3.793458e-01 -2.203665e+01 +-3.816064e-01 2.250176e-02 9.240510e-01 2.102746e+02 9.526666e-02 9.953372e-01 1.510471e-02 -4.072563e-01 -9.194024e-01 9.379529e-02 -3.819707e-01 -2.295396e+01 +-3.840978e-01 2.314782e-02 9.230022e-01 2.124744e+02 9.628035e-02 9.952396e-01 1.510660e-02 -4.051777e-01 -9.182586e-01 9.466937e-02 -3.844980e-01 -2.387896e+01 +-3.866127e-01 2.432739e-02 9.219213e-01 2.146697e+02 9.675317e-02 9.952055e-01 1.431277e-02 -4.036944e-01 -9.171529e-01 9.473228e-02 -3.871128e-01 -2.480688e+01 +-3.893716e-01 2.450055e-02 9.207549e-01 2.168716e+02 9.604304e-02 9.952768e-01 1.413145e-02 -4.053455e-01 -9.160597e-01 9.393446e-02 -3.898856e-01 -2.574520e+01 +-3.920958e-01 2.535895e-02 9.195748e-01 2.190854e+02 9.548806e-02 9.953421e-01 1.326659e-02 -4.089666e-01 -9.149551e-01 9.301017e-02 -3.926909e-01 -2.669513e+01 +-3.949738e-01 2.652036e-02 9.183096e-01 2.212752e+02 9.548710e-02 9.953543e-01 1.232452e-02 -4.145729e-01 -9.137165e-01 9.255456e-02 -3.956712e-01 -2.764230e+01 +-3.974300e-01 2.654920e-02 9.172484e-01 2.234748e+02 9.359537e-02 9.955411e-01 1.173812e-02 -4.227878e-01 -9.128468e-01 9.051527e-02 -3.981427e-01 -2.859890e+01 +-4.003449e-01 2.717994e-02 9.159614e-01 2.256743e+02 9.384581e-02 9.955206e-01 1.147700e-02 -4.323730e-01 -9.115464e-01 9.055388e-02 -4.011023e-01 -2.956630e+01 +-4.029066e-01 2.696929e-02 9.148437e-01 2.278686e+02 9.567667e-02 9.953302e-01 1.279497e-02 -4.418329e-01 -9.102265e-01 9.268435e-02 -4.036054e-01 -3.054211e+01 +-4.054481e-01 2.628911e-02 9.137400e-01 2.300656e+02 9.575560e-02 9.953085e-01 1.385312e-02 -4.485622e-01 -9.090889e-01 9.311242e-02 -4.060633e-01 -3.152450e+01 +-4.086398e-01 2.546329e-02 9.123405e-01 2.322584e+02 9.487381e-02 9.953805e-01 1.471329e-02 -4.502008e-01 -9.077513e-01 9.256963e-02 -4.091678e-01 -3.251137e+01 +-4.116808e-01 2.580665e-02 9.109627e-01 2.344478e+02 9.367349e-02 9.955027e-01 1.413118e-02 -4.516442e-01 -9.065011e-01 9.115057e-02 -4.122467e-01 -3.350409e+01 +-4.150772e-01 2.524700e-02 9.094358e-01 2.366402e+02 9.211869e-02 9.956438e-01 1.440382e-02 -4.545615e-01 -9.051105e-01 8.975472e-02 -4.155948e-01 -3.450713e+01 +-4.185234e-01 2.430782e-02 9.078807e-01 2.388266e+02 9.099928e-02 9.957336e-01 1.528968e-02 -4.565040e-01 -9.036356e-01 8.901555e-02 -4.189498e-01 -3.551552e+01 +-4.220821e-01 2.436985e-02 9.062300e-01 2.410098e+02 9.041717e-02 9.957859e-01 1.533419e-02 -4.583595e-01 -9.020374e-01 8.841102e-02 -4.225068e-01 -3.653355e+01 +-4.257271e-01 2.389500e-02 9.045361e-01 2.431866e+02 8.957398e-02 9.958540e-01 1.585137e-02 -4.598154e-01 -9.004071e-01 8.777123e-02 -4.261024e-01 -3.755871e+01 +-4.295873e-01 2.463815e-02 9.026892e-01 2.453571e+02 8.910321e-02 9.959061e-01 1.522154e-02 -4.618584e-01 -8.986186e-01 8.697147e-02 -4.300239e-01 -3.859114e+01 +-4.336948e-01 2.386280e-02 9.007439e-01 2.475244e+02 8.796735e-02 9.959953e-01 1.596872e-02 -4.614750e-01 -8.967556e-01 8.616158e-02 -4.340571e-01 -3.963198e+01 +-4.375346e-01 2.399626e-02 8.988814e-01 2.496839e+02 8.785629e-02 9.960018e-01 1.617549e-02 -4.614460e-01 -8.948993e-01 8.604970e-02 -4.378935e-01 -4.068364e+01 +-4.410215e-01 2.505593e-02 8.971467e-01 2.518424e+02 8.852924e-02 9.959498e-01 1.570406e-02 -4.628392e-01 -8.931196e-01 8.634953e-02 -4.414534e-01 -4.174631e+01 +-4.446551e-01 2.500281e-02 8.953529e-01 2.539896e+02 8.810197e-02 9.959839e-01 1.594074e-02 -4.623208e-01 -8.913584e-01 8.597047e-02 -4.450721e-01 -4.281371e+01 +-4.483033e-01 2.521558e-02 8.935258e-01 2.561425e+02 8.717879e-02 9.960700e-01 1.563027e-02 -4.599411e-01 -8.896201e-01 8.490359e-02 -4.487397e-01 -4.389031e+01 +-4.519337e-01 2.507050e-02 8.916992e-01 2.582951e+02 8.700532e-02 9.960779e-01 1.609113e-02 -4.566041e-01 -8.877984e-01 8.485468e-02 -4.523424e-01 -4.497777e+01 +-4.553868e-01 2.592550e-02 8.899162e-01 2.604446e+02 8.760414e-02 9.960298e-01 1.581181e-02 -4.515860e-01 -8.859731e-01 8.516081e-02 -4.558499e-01 -4.607408e+01 +-4.588898e-01 2.701655e-02 8.880824e-01 2.625925e+02 8.903314e-02 9.959048e-01 1.570853e-02 -4.468931e-01 -8.840210e-01 8.627723e-02 -4.594159e-01 -4.718398e+01 +-4.621008e-01 2.899750e-02 8.863532e-01 2.647340e+02 9.121464e-02 9.957186e-01 1.497936e-02 -4.443228e-01 -8.821240e-01 8.777034e-02 -4.627673e-01 -4.830007e+01 +-4.649723e-01 2.982926e-02 8.848226e-01 2.668920e+02 9.212184e-02 9.956371e-01 1.484476e-02 -4.426920e-01 -8.805193e-01 8.841387e-02 -4.656915e-01 -4.943452e+01 +-4.678605e-01 3.190777e-02 8.832262e-01 2.690255e+02 9.402770e-02 9.954733e-01 1.384527e-02 -4.394885e-01 -8.787863e-01 8.952536e-02 -4.687428e-01 -5.056793e+01 +-4.704908e-01 3.425764e-02 8.817397e-01 2.711744e+02 9.593141e-02 9.953092e-01 1.251830e-02 -4.357941e-01 -8.771747e-01 9.047625e-02 -4.715702e-01 -5.172041e+01 +-4.732870e-01 3.502027e-02 8.802119e-01 2.733318e+02 9.677821e-02 9.952282e-01 1.244098e-02 -4.312748e-01 -8.755760e-01 9.107347e-02 -4.744177e-01 -5.288771e+01 +-4.764989e-01 3.618638e-02 8.784301e-01 2.754870e+02 9.750257e-02 9.951642e-01 1.189447e-02 -4.244063e-01 -8.737517e-01 9.131687e-02 -4.777228e-01 -5.406212e+01 +-4.797661e-01 3.625912e-02 8.766469e-01 2.776580e+02 9.648349e-02 9.952665e-01 1.163754e-02 -4.182424e-01 -8.720753e-01 9.016523e-02 -4.809935e-01 -5.525311e+01 +-4.830450e-01 3.738275e-02 8.747972e-01 2.798273e+02 9.727560e-02 9.951946e-01 1.118587e-02 -4.128268e-01 -8.701752e-01 9.049968e-02 -4.843602e-01 -5.645514e+01 +-4.863612e-01 3.769826e-02 8.729443e-01 2.820168e+02 9.634686e-02 9.952903e-01 1.069788e-02 -4.105826e-01 -8.684296e-01 8.930846e-02 -4.877027e-01 -5.767414e+01 +-4.891485e-01 3.754739e-02 8.713920e-01 2.841885e+02 9.474989e-02 9.954479e-01 1.029420e-02 -4.095589e-01 -8.670387e-01 8.759967e-02 -4.904794e-01 -5.889251e+01 +-4.918877e-01 3.780488e-02 8.698375e-01 2.863724e+02 9.587566e-02 9.953330e-01 1.095791e-02 -4.079618e-01 -8.653637e-01 8.878629e-02 -4.932166e-01 -6.012956e+01 +-4.938980e-01 3.783481e-02 8.686964e-01 2.885702e+02 9.748770e-02 9.951633e-01 1.208380e-02 -4.045488e-01 -8.640375e-01 9.065535e-02 -4.951976e-01 -6.138495e+01 +-4.959533e-01 3.775471e-02 8.675281e-01 2.907704e+02 9.815965e-02 9.950882e-01 1.281034e-02 -3.986685e-01 -8.627832e-01 9.150956e-02 -4.972233e-01 -6.264929e+01 +-4.981567e-01 3.777312e-02 8.662639e-01 2.929827e+02 9.815975e-02 9.950850e-01 1.305774e-02 -3.908822e-01 -8.615130e-01 9.153703e-02 -4.994160e-01 -6.392341e+01 +-5.004590e-01 3.710110e-02 8.649649e-01 2.951953e+02 9.755645e-02 9.951348e-01 1.376055e-02 -3.821466e-01 -8.602462e-01 9.126948e-02 -5.016436e-01 -6.520624e+01 +-5.030179e-01 3.703289e-02 8.634823e-01 2.974212e+02 9.842723e-02 9.950362e-01 1.466339e-02 -3.713999e-01 -8.586531e-01 9.236610e-02 -5.041660e-01 -6.650521e+01 +-5.051574e-01 3.705698e-02 8.622313e-01 2.996423e+02 9.892841e-02 9.949785e-01 1.519721e-02 -3.587114e-01 -8.573384e-01 9.297614e-02 -5.062867e-01 -6.780874e+01 +-5.071269e-01 3.780852e-02 8.610417e-01 3.018763e+02 9.853901e-02 9.950298e-01 1.434445e-02 -3.470056e-01 -8.562198e-01 9.212063e-02 -5.083320e-01 -6.912560e+01 +-5.093585e-01 4.004183e-02 8.596224e-01 3.041141e+02 9.794371e-02 9.951234e-01 1.168175e-02 -3.372516e-01 -8.549625e-01 9.014478e-02 -5.107963e-01 -7.045170e+01 +-5.126685e-01 3.931280e-02 8.576862e-01 3.063593e+02 9.633206e-02 9.952774e-01 1.196155e-02 -3.307952e-01 -8.531654e-01 8.875497e-02 -5.140344e-01 -7.179168e+01 +-5.171586e-01 3.690592e-02 8.550936e-01 3.086134e+02 9.360376e-02 9.955160e-01 1.364476e-02 -3.233356e-01 -8.507557e-01 8.709646e-02 -5.182942e-01 -7.314403e+01 +-5.220571e-01 3.451451e-02 8.522120e-01 3.108714e+02 9.114758e-02 9.957166e-01 1.550971e-02 -3.126191e-01 -8.480262e-01 8.577399e-02 -5.229668e-01 -7.451245e+01 +-5.268235e-01 3.309434e-02 8.493302e-01 3.131301e+02 8.979367e-02 9.958171e-01 1.689507e-02 -2.971879e-01 -8.452184e-01 8.516518e-02 -5.275914e-01 -7.590012e+01 +-5.311682e-01 3.348928e-02 8.466043e-01 3.153852e+02 9.017544e-02 9.957776e-01 1.718683e-02 -2.796424e-01 -8.424540e-01 8.547199e-02 -5.319453e-01 -7.730725e+01 +-5.353072e-01 3.467362e-02 8.439455e-01 3.176383e+02 9.238538e-02 9.955660e-01 1.769624e-02 -2.578412e-01 -8.395898e-01 8.744113e-02 -5.361370e-01 -7.872988e+01 +-5.390292e-01 3.588530e-02 8.415223e-01 3.198954e+02 9.381170e-02 9.954336e-01 1.764160e-02 -2.381554e-01 -8.370465e-01 8.845395e-02 -5.399342e-01 -8.017271e+01 +-5.426799e-01 3.583575e-02 8.391748e-01 3.221579e+02 9.420860e-02 9.953821e-01 1.841670e-02 -2.197853e-01 -8.346396e-01 8.905184e-02 -5.435499e-01 -8.163211e+01 +-5.466164e-01 3.426157e-02 8.366820e-01 3.244120e+02 9.455334e-02 9.952979e-01 2.101626e-02 -2.016825e-01 -8.320277e-01 9.059888e-02 -5.472856e-01 -8.310009e+01 +-5.505309e-01 3.288636e-02 8.341668e-01 3.266626e+02 9.308915e-02 9.954104e-01 2.219342e-02 -1.825361e-01 -8.296084e-01 8.987002e-02 -5.510655e-01 -8.457972e+01 +-5.542889e-01 3.278444e-02 8.316784e-01 3.289055e+02 9.233886e-02 9.954779e-01 2.229974e-02 -1.608324e-01 -8.271864e-01 8.915672e-02 -5.548096e-01 -8.606826e+01 +-5.583189e-01 3.221365e-02 8.290008e-01 3.311477e+02 9.187847e-02 9.955000e-01 2.319514e-02 -1.383913e-01 -8.245231e-01 8.911758e-02 -5.587662e-01 -8.757051e+01 +-5.624024e-01 3.172657e-02 8.262548e-01 3.333840e+02 9.317394e-02 9.953308e-01 2.520143e-02 -1.125608e-01 -8.215973e-01 9.115875e-02 -5.627325e-01 -8.908675e+01 +-5.662656e-01 3.200649e-02 8.236012e-01 3.356133e+02 9.376371e-02 9.952604e-01 2.578962e-02 -8.455148e-02 -8.188722e-01 9.182766e-02 -5.665827e-01 -9.061426e+01 +-5.699347e-01 3.105914e-02 8.211028e-01 3.378389e+02 9.197118e-02 9.954173e-01 2.618521e-02 -5.242768e-02 -8.165266e-01 9.044163e-02 -5.701793e-01 -9.215154e+01 +-5.734629e-01 2.980165e-02 8.186893e-01 3.400560e+02 9.146806e-02 9.954189e-01 2.783523e-02 -1.599584e-02 -8.141093e-01 9.084638e-02 -5.735616e-01 -9.370014e+01 +-5.764348e-01 2.883221e-02 8.166344e-01 3.422752e+02 9.162022e-02 9.953561e-01 2.952944e-02 2.333862e-02 -8.119905e-01 9.184199e-02 -5.763994e-01 -9.526502e+01 +-5.792285e-01 2.833649e-02 8.146726e-01 3.444892e+02 8.960529e-02 9.955527e-01 2.908096e-02 6.337510e-02 -8.102254e-01 8.984348e-02 -5.791916e-01 -9.683616e+01 +-5.821727e-01 2.738547e-02 8.126039e-01 3.467010e+02 8.552969e-02 9.959502e-01 2.771149e-02 1.024766e-01 -8.085540e-01 8.563461e-02 -5.821572e-01 -9.841195e+01 +-5.852817e-01 2.656025e-02 8.103950e-01 3.489103e+02 8.243732e-02 9.962335e-01 2.688668e-02 1.402984e-01 -8.066284e-01 8.254305e-02 -5.852667e-01 -9.999813e+01 +-5.884897e-01 2.360915e-02 8.081600e-01 3.511094e+02 7.975283e-02 9.963937e-01 2.896666e-02 1.754218e-01 -8.045616e-01 8.149961e-02 -5.882502e-01 -1.015909e+02 +-5.915552e-01 2.271379e-02 8.059445e-01 3.533107e+02 8.013301e-02 9.963101e-01 3.073798e-02 2.141195e-01 -8.022725e-01 8.276596e-02 -5.911925e-01 -1.032033e+02 +-5.945947e-01 2.268037e-02 8.037057e-01 3.554996e+02 7.939344e-02 9.963730e-01 3.061917e-02 2.539708e-01 -8.000961e-01 8.201493e-02 -5.942387e-01 -1.048170e+02 +-5.974407e-01 2.308157e-02 8.015809e-01 3.576809e+02 7.813459e-02 9.965050e-01 2.954148e-02 2.903191e-01 -7.980974e-01 8.028046e-02 -5.971561e-01 -1.064411e+02 +-6.007205e-01 1.876716e-02 7.992389e-01 3.598670e+02 7.511391e-02 9.966269e-01 3.305469e-02 3.297903e-01 -7.959226e-01 7.989057e-02 -6.001039e-01 -1.080781e+02 +-6.038752e-01 1.623428e-02 7.969136e-01 3.620386e+02 7.242569e-02 9.967743e-01 3.457609e-02 3.801369e-01 -7.937816e-01 7.859665e-02 -6.031030e-01 -1.097167e+02 +-6.068475e-01 1.634159e-02 7.946503e-01 3.642051e+02 7.194258e-02 9.968139e-01 3.444111e-02 4.335940e-01 -7.915556e-01 7.806967e-02 -6.060897e-01 -1.113631e+02 +-6.095901e-01 1.605467e-02 7.925543e-01 3.663626e+02 7.126306e-02 9.968566e-01 3.461851e-02 4.855505e-01 -7.895071e-01 7.758292e-02 -6.088179e-01 -1.130176e+02 +-6.122075e-01 1.580857e-02 7.905392e-01 3.685148e+02 7.108644e-02 9.968518e-01 3.511634e-02 5.357534e-01 -7.874952e-01 7.769508e-02 -6.114039e-01 -1.146817e+02 +-6.150181e-01 1.428418e-02 7.883836e-01 3.706543e+02 7.043109e-02 9.968345e-01 3.688232e-02 5.857535e-01 -7.853612e-01 7.820999e-02 -6.140773e-01 -1.163494e+02 +-6.177963e-01 1.359792e-02 7.862206e-01 3.727925e+02 6.786551e-02 9.970417e-01 3.608321e-02 6.347512e-01 -7.834041e-01 7.564932e-02 -6.168915e-01 -1.180262e+02 +-6.206707e-01 1.085791e-02 7.839962e-01 3.749322e+02 5.885749e-02 9.977281e-01 3.277805e-02 6.806409e-01 -7.818591e-01 6.648841e-02 -6.198996e-01 -1.197055e+02 +-6.239941e-01 1.192773e-02 7.813381e-01 3.770444e+02 4.951205e-02 9.984779e-01 2.429889e-02 7.141844e-01 -7.798589e-01 5.384800e-02 -6.236348e-01 -1.213733e+02 +-6.266260e-01 2.205789e-02 7.790079e-01 3.791489e+02 5.900870e-02 9.980727e-01 1.920520e-02 7.322390e-01 -7.770829e-01 5.800271e-02 -6.267199e-01 -1.230734e+02 +-6.274763e-01 2.388148e-02 7.782693e-01 3.812460e+02 6.664289e-02 9.975089e-01 2.312160e-02 7.514499e-01 -7.757784e-01 6.637436e-02 -6.275047e-01 -1.247861e+02 +-6.293392e-01 1.350458e-02 7.770134e-01 3.833531e+02 6.579098e-02 9.971854e-01 3.595595e-02 7.912642e-01 -7.743408e-01 7.374895e-02 -6.284563e-01 -1.264979e+02 +-6.322787e-01 3.794990e-03 7.747318e-01 3.854625e+02 6.029882e-02 9.971956e-01 4.432671e-02 8.581189e-01 -7.723909e-01 7.474223e-02 -6.307344e-01 -1.282062e+02 +-6.354821e-01 -2.169544e-03 7.721126e-01 3.875638e+02 5.428748e-02 9.973957e-01 4.748350e-02 9.375737e-01 -7.702048e-01 7.209095e-02 -6.337093e-01 -1.299140e+02 +-6.382772e-01 -2.563005e-03 7.698024e-01 3.896489e+02 5.281065e-02 9.974927e-01 4.710871e-02 1.015440e+00 -7.679930e-01 7.072216e-02 -6.365415e-01 -1.316273e+02 +-6.407552e-01 2.180977e-03 7.677422e-01 3.917168e+02 5.798493e-02 9.972772e-01 4.556100e-02 1.088896e+00 -7.655524e-01 7.371091e-02 -6.391370e-01 -1.333507e+02 +-6.427141e-01 9.281153e-03 7.660500e-01 3.937800e+02 6.314894e-02 9.971656e-01 4.090054e-02 1.154913e+00 -7.634991e-01 7.466258e-02 -6.414785e-01 -1.350831e+02 +-6.451251e-01 1.299057e-02 7.639665e-01 3.958385e+02 6.465990e-02 9.971970e-01 3.764505e-02 1.214067e+00 -7.613361e-01 7.368375e-02 -6.441568e-01 -1.368244e+02 +-6.480120e-01 1.202720e-02 7.615352e-01 3.978934e+02 6.400803e-02 9.971980e-01 3.871714e-02 1.272858e+00 -7.589357e-01 7.383352e-02 -6.469661e-01 -1.385702e+02 +-6.508502e-01 1.161103e-02 7.591174e-01 3.999429e+02 6.462644e-02 9.971011e-01 4.015815e-02 1.334967e+00 -7.564505e-01 7.519598e-02 -6.497138e-01 -1.403176e+02 +-6.532311e-01 1.121137e-02 7.570756e-01 4.019775e+02 6.522569e-02 9.970066e-01 4.151452e-02 1.399861e+00 -7.543439e-01 7.649933e-02 -6.520070e-01 -1.420688e+02 +-6.550600e-01 1.168809e-02 7.554865e-01 4.040132e+02 6.588239e-02 9.969556e-01 4.170082e-02 1.463950e+00 -7.526991e-01 7.708978e-02 -6.538357e-01 -1.438398e+02 +-6.564592e-01 1.172668e-02 7.542705e-01 4.060396e+02 6.614536e-02 9.969228e-01 4.206862e-02 1.530570e+00 -7.514560e-01 7.750781e-02 -6.552147e-01 -1.456094e+02 +-6.576740e-01 1.232267e-02 7.532019e-01 4.080639e+02 6.689873e-02 9.968710e-01 4.210482e-02 1.596786e+00 -7.503263e-01 7.807948e-02 -6.564404e-01 -1.473861e+02 +-6.587023e-01 1.203487e-02 7.523075e-01 4.100865e+02 6.824368e-02 9.967064e-01 4.380791e-02 1.665192e+00 -7.493024e-01 8.019658e-02 -6.573540e-01 -1.491653e+02 +-6.597711e-01 1.115265e-02 7.513839e-01 4.120999e+02 6.999913e-02 9.964545e-01 4.667426e-02 1.739480e+00 -7.481993e-01 8.339053e-02 -6.582125e-01 -1.509391e+02 +-6.608928e-01 1.078191e-02 7.504029e-01 4.141199e+02 7.151847e-02 9.962510e-01 4.867325e-02 1.820766e+00 -7.470648e-01 8.583545e-02 -6.591862e-01 -1.527256e+02 +-6.619843e-01 1.147200e-02 7.494300e-01 4.161297e+02 7.086687e-02 9.963615e-01 4.734596e-02 1.902123e+00 -7.461600e-01 8.445202e-02 -6.603886e-01 -1.545063e+02 +-6.634470e-01 1.166464e-02 7.481324e-01 4.181369e+02 6.703205e-02 9.967844e-01 4.390275e-02 1.980352e+00 -7.452146e-01 7.927598e-02 -6.620955e-01 -1.562858e+02 +-6.647307e-01 1.113233e-02 7.470002e-01 4.201401e+02 6.397313e-02 9.970645e-01 4.206859e-02 2.051261e+00 -7.443390e-01 7.575220e-02 -6.634915e-01 -1.580701e+02 +-6.658022e-01 1.000833e-02 7.460613e-01 4.221413e+02 6.306201e-02 9.970870e-01 4.290216e-02 2.117805e+00 -7.434586e-01 7.561245e-02 -6.644938e-01 -1.598579e+02 +-6.666894e-01 8.669528e-03 7.452853e-01 4.241424e+02 6.129618e-02 9.971829e-01 4.323230e-02 2.186326e+00 -7.428109e-01 7.450564e-02 -6.653426e-01 -1.616509e+02 +-6.676013e-01 8.285427e-03 7.444729e-01 4.261357e+02 5.852154e-02 9.974282e-01 4.137817e-02 2.256082e+00 -7.422154e-01 7.119181e-02 -6.663692e-01 -1.634423e+02 +-6.684511e-01 6.991256e-03 7.437233e-01 4.281288e+02 5.725191e-02 9.974725e-01 4.208085e-02 2.325413e+00 -7.415493e-01 7.070856e-02 -6.671618e-01 -1.652378e+02 +-6.688990e-01 5.516573e-03 7.433329e-01 4.301109e+02 5.777251e-02 9.973336e-01 4.458581e-02 2.396912e+00 -7.411049e-01 7.276759e-02 -6.674341e-01 -1.670320e+02 +-6.688562e-01 4.782552e-03 7.433765e-01 4.320961e+02 5.962807e-02 9.971024e-01 4.723569e-02 2.471810e+00 -7.409965e-01 7.591998e-02 -6.672033e-01 -1.688310e+02 +-6.679607e-01 3.317931e-03 7.441892e-01 4.340721e+02 6.413589e-02 9.965262e-01 5.312338e-02 2.549279e+00 -7.414277e-01 8.321354e-02 -6.658531e-01 -1.706280e+02 +-6.664665e-01 2.245014e-03 7.455316e-01 4.360531e+02 6.807604e-02 9.960011e-01 5.785718e-02 2.650572e+00 -7.424204e-01 8.931269e-02 -6.639541e-01 -1.724221e+02 +-6.646993e-01 4.525680e-04 7.471109e-01 4.380420e+02 6.387629e-02 9.963726e-01 5.622671e-02 2.755615e+00 -7.443754e-01 8.509651e-02 -6.623170e-01 -1.742029e+02 +-6.640222e-01 7.332386e-04 7.477126e-01 4.400300e+02 5.667972e-02 9.971716e-01 4.935776e-02 2.843910e+00 -7.455615e-01 7.515477e-02 -6.621855e-01 -1.759705e+02 +-6.623343e-01 -1.685100e-03 7.492066e-01 4.420339e+02 5.114571e-02 9.975629e-01 4.745893e-02 2.921911e+00 -7.474606e-01 6.975236e-02 -6.606339e-01 -1.777475e+02 +-6.599321e-01 -2.489415e-03 7.513212e-01 4.440392e+02 4.941883e-02 9.976851e-01 4.671333e-02 3.006852e+00 -7.496982e-01 6.795703e-02 -6.582813e-01 -1.795200e+02 +-6.571388e-01 -2.384720e-03 7.537658e-01 4.460460e+02 5.118087e-02 9.975460e-01 4.777584e-02 3.098726e+00 -7.520300e-01 6.997374e-02 -6.554041e-01 -1.812884e+02 +-6.542341e-01 -2.031108e-03 7.562894e-01 4.480532e+02 5.211326e-02 9.974985e-01 4.775987e-02 3.192574e+00 -7.544945e-01 7.065882e-02 -6.524916e-01 -1.830447e+02 +-6.518127e-01 -7.487279e-04 7.583797e-01 4.500640e+02 5.035348e-02 9.977501e-01 4.426288e-02 3.278015e+00 -7.567065e-01 6.703814e-02 -6.503084e-01 -1.847916e+02 +-6.502861e-01 -5.694727e-03 7.596681e-01 4.520924e+02 4.340385e-02 9.980600e-01 4.463606e-02 3.358861e+00 -7.584485e-01 6.199872e-02 -6.487773e-01 -1.865327e+02 +-6.493819e-01 -1.250006e-02 7.603597e-01 4.541251e+02 3.451564e-02 9.983500e-01 4.589046e-02 3.436998e+00 -7.596787e-01 5.604473e-02 -6.478790e-01 -1.882652e+02 +-6.487774e-01 -1.541144e-02 7.608223e-01 4.561580e+02 2.766377e-02 9.986564e-01 4.381885e-02 3.516788e+00 -7.604753e-01 4.947588e-02 -6.474793e-01 -1.899924e+02 +-6.482236e-01 -1.648422e-02 7.612716e-01 4.581873e+02 2.535380e-02 9.987440e-01 4.321512e-02 3.593514e+00 -7.610278e-01 4.731418e-02 -6.469915e-01 -1.917203e+02 +-6.471136e-01 -1.651054e-02 7.622149e-01 4.602152e+02 2.716600e-02 9.986312e-01 4.469530e-02 3.669483e+00 -7.619095e-01 4.962925e-02 -6.457792e-01 -1.934519e+02 +-6.457730e-01 -1.750312e-02 7.633289e-01 4.622462e+02 2.915962e-02 9.984425e-01 4.756317e-02 3.750848e+00 -7.629724e-01 5.297338e-02 -6.442568e-01 -1.951830e+02 +-6.444217e-01 -1.938661e-02 7.644245e-01 4.642791e+02 2.790781e-02 9.984163e-01 4.884760e-02 3.835891e+00 -7.641608e-01 5.281186e-02 -6.428600e-01 -1.969059e+02 +-6.434782e-01 -2.002168e-02 7.652026e-01 4.663135e+02 2.551058e-02 9.985416e-01 4.757953e-02 3.921999e+00 -7.650392e-01 5.013714e-02 -6.420289e-01 -1.986214e+02 +-6.425776e-01 -1.892421e-02 7.659869e-01 4.683509e+02 2.470557e-02 9.986634e-01 4.539785e-02 4.004216e+00 -7.658222e-01 4.809577e-02 -6.412512e-01 -2.003376e+02 +-6.415126e-01 -1.754977e-02 7.669117e-01 4.703839e+02 2.511503e-02 9.987218e-01 4.386287e-02 4.079549e+00 -7.667012e-01 4.739958e-02 -6.402518e-01 -2.020483e+02 +-6.403523e-01 -1.703864e-02 7.678924e-01 4.724259e+02 2.727744e-02 9.986188e-01 4.490509e-02 4.154116e+00 -7.675968e-01 4.970120e-02 -6.390030e-01 -2.037656e+02 +-6.391027e-01 -1.702761e-02 7.689330e-01 4.744683e+02 2.897557e-02 9.985121e-01 4.619471e-02 4.230210e+00 -7.685754e-01 5.180342e-02 -6.376583e-01 -2.054787e+02 +-6.382048e-01 -1.757702e-02 7.696660e-01 4.765113e+02 2.911652e-02 9.984730e-01 4.694565e-02 4.309712e+00 -7.693159e-01 5.237092e-02 -6.367184e-01 -2.071855e+02 +-6.372622e-01 -1.757278e-02 7.704467e-01 4.785558e+02 2.893845e-02 9.984892e-01 4.671006e-02 4.389454e+00 -7.701035e-01 5.206208e-02 -6.357909e-01 -2.088868e+02 +-6.364662e-01 -1.871761e-02 7.710775e-01 4.806060e+02 2.856500e-02 9.984476e-01 4.781518e-02 4.471449e+00 -7.707754e-01 5.245856e-02 -6.349435e-01 -2.105886e+02 +-6.357276e-01 -1.991678e-02 7.716565e-01 4.826545e+02 2.804295e-02 9.984112e-01 4.887253e-02 4.555624e+00 -7.714039e-01 5.270913e-02 -6.341590e-01 -2.122853e+02 +-6.352032e-01 -1.912085e-02 7.721084e-01 4.847071e+02 2.761545e-02 9.984920e-01 4.744597e-02 4.640076e+00 -7.718512e-01 5.145993e-02 -6.337172e-01 -2.139826e+02 +-6.347825e-01 -1.785998e-02 7.724845e-01 4.867577e+02 2.769275e-02 9.985647e-01 4.584327e-02 4.720801e+00 -7.721945e-01 5.049271e-02 -6.333767e-01 -2.156770e+02 +-6.342247e-01 -1.826709e-02 7.729330e-01 4.888066e+02 2.810945e-02 9.985151e-01 4.666338e-02 4.799764e+00 -7.726376e-01 5.132177e-02 -6.327694e-01 -2.173707e+02 +-6.337660e-01 -1.964247e-02 7.732754e-01 4.908629e+02 2.766558e-02 9.984623e-01 4.803691e-02 4.880930e+00 -7.730299e-01 5.183726e-02 -6.322480e-01 -2.190659e+02 +-6.336457e-01 -2.085277e-02 7.733423e-01 4.929166e+02 2.629011e-02 9.984788e-01 4.846451e-02 4.960767e+00 -7.731765e-01 5.104058e-02 -6.321335e-01 -2.207576e+02 +-6.337949e-01 -2.127668e-02 7.732085e-01 4.949713e+02 2.566601e-02 9.984927e-01 4.851420e-02 5.038016e+00 -7.730752e-01 5.059322e-02 -6.322934e-01 -2.224476e+02 +-6.339828e-01 -2.092726e-02 7.730640e-01 4.970247e+02 2.586268e-02 9.985009e-01 4.823971e-02 5.116707e+00 -7.729146e-01 5.057664e-02 -6.324911e-01 -2.241389e+02 +-6.341946e-01 -2.049598e-02 7.729018e-01 4.990722e+02 2.633335e-02 9.984960e-01 4.808582e-02 5.193552e+00 -7.727248e-01 5.084886e-02 -6.327010e-01 -2.258270e+02 +-6.344122e-01 -2.200092e-02 7.726818e-01 5.011328e+02 2.608151e-02 9.984165e-01 4.984264e-02 5.267707e+00 -7.725548e-01 5.177347e-02 -6.328337e-01 -2.275274e+02 +-6.346633e-01 -2.373341e-02 7.724243e-01 5.031867e+02 2.489555e-02 9.983816e-01 5.113160e-02 5.349108e+00 -7.723877e-01 5.168127e-02 -6.330452e-01 -2.292205e+02 +-6.349280e-01 -2.408225e-02 7.721959e-01 5.052390e+02 2.462954e-02 9.983750e-01 5.138734e-02 5.432770e+00 -7.721786e-01 5.164608e-02 -6.333031e-01 -2.309143e+02 +-6.349925e-01 -2.411289e-02 7.721420e-01 5.072915e+02 2.397188e-02 9.984163e-01 5.089305e-02 5.519275e+00 -7.721463e-01 5.082639e-02 -6.334088e-01 -2.326072e+02 +-6.350791e-01 -2.372020e-02 7.720828e-01 5.093381e+02 2.396973e-02 9.984419e-01 5.039085e-02 5.605249e+00 -7.720751e-01 5.050878e-02 -6.335210e-01 -2.342975e+02 +-6.348712e-01 -2.289225e-02 7.722788e-01 5.113939e+02 2.500734e-02 9.984284e-01 5.015379e-02 5.689304e+00 -7.722131e-01 5.115382e-02 -6.333009e-01 -2.359969e+02 +-6.346135e-01 -2.306910e-02 7.724854e-01 5.134454e+02 2.490848e-02 9.984245e-01 5.027928e-02 5.773309e+00 -7.724282e-01 5.114933e-02 -6.330390e-01 -2.376908e+02 +-6.346300e-01 -2.317670e-02 7.724686e-01 5.154974e+02 2.483037e-02 9.984226e-01 5.035575e-02 5.857608e+00 -7.724171e-01 5.113794e-02 -6.330534e-01 -2.393843e+02 +-6.345169e-01 -2.292727e-02 7.725689e-01 5.175493e+02 2.443340e-02 9.984653e-01 4.969846e-02 5.942483e+00 -7.725227e-01 5.041099e-02 -6.329829e-01 -2.410762e+02 +-6.344472e-01 -2.404252e-02 7.725922e-01 5.196014e+02 2.355973e-02 9.984503e-01 5.041814e-02 6.026971e+00 -7.726070e-01 5.018971e-02 -6.328975e-01 -2.427680e+02 +-6.342276e-01 -2.435609e-02 7.727627e-01 5.216574e+02 2.402674e-02 9.984000e-01 5.118716e-02 6.115358e+00 -7.727729e-01 5.103127e-02 -6.326276e-01 -2.444639e+02 +-6.339935e-01 -2.575882e-02 7.729093e-01 5.237106e+02 2.390444e-02 9.983148e-01 5.287899e-02 6.206642e+00 -7.729689e-01 5.200088e-02 -6.323092e-01 -2.461557e+02 +-6.337744e-01 -2.490629e-02 7.731169e-01 5.257627e+02 2.433043e-02 9.983450e-01 5.210735e-02 6.299720e+00 -7.731352e-01 5.183455e-02 -6.321195e-01 -2.478455e+02 +-6.335759e-01 -2.408283e-02 7.733057e-01 5.278159e+02 2.550849e-02 9.983218e-01 5.198975e-02 6.392878e+00 -7.732599e-01 5.266529e-02 -6.318982e-01 -2.495367e+02 +-6.332811e-01 -2.430248e-02 7.735402e-01 5.298651e+02 2.598185e-02 9.982758e-01 5.263383e-02 6.486799e+00 -7.734856e-01 5.343001e-02 -6.315578e-01 -2.512228e+02 +-6.330458e-01 -2.523112e-02 7.737031e-01 5.319262e+02 2.543230e-02 9.982513e-01 5.336260e-02 6.582378e+00 -7.736964e-01 5.345801e-02 -6.312970e-01 -2.529158e+02 +-6.331693e-01 -2.508594e-02 7.736068e-01 5.339814e+02 2.469044e-02 9.983114e-01 5.258073e-02 6.677372e+00 -7.736194e-01 5.239318e-02 -6.314807e-01 -2.546036e+02 +-6.333535e-01 -2.499187e-02 7.734590e-01 5.360377e+02 2.464368e-02 9.983201e-01 5.243722e-02 6.771372e+00 -7.734701e-01 5.227216e-02 -6.316735e-01 -2.562925e+02 +-6.334203e-01 -2.622209e-02 7.733636e-01 5.380951e+02 2.429114e-02 9.982593e-01 5.374308e-02 6.865967e+00 -7.734266e-01 5.282782e-02 -6.316806e-01 -2.579830e+02 +-6.335756e-01 -2.797597e-02 7.731749e-01 5.401536e+02 2.391813e-02 9.981601e-01 5.571629e-02 6.964906e+00 -7.733110e-01 5.379337e-02 -6.317407e-01 -2.596746e+02 +-6.338700e-01 -2.930732e-02 7.728842e-01 5.422136e+02 2.279970e-02 9.981395e-01 5.654772e-02 7.066817e+00 -7.731035e-01 5.346542e-02 -6.320225e-01 -2.613661e+02 +-6.341505e-01 -2.755763e-02 7.727184e-01 5.442679e+02 2.260292e-02 9.982769e-01 5.415140e-02 7.168745e+00 -7.728792e-01 5.180582e-02 -6.324348e-01 -2.630547e+02 +-6.343956e-01 -2.556962e-02 7.725856e-01 5.463253e+02 2.211949e-02 9.984430e-01 5.120768e-02 7.265256e+00 -7.726920e-01 4.957512e-02 -6.328422e-01 -2.647478e+02 +-6.344558e-01 -2.524481e-02 7.725468e-01 5.483760e+02 2.236926e-02 9.984482e-01 5.099748e-02 7.357150e+00 -7.726354e-01 4.963694e-02 -6.329065e-01 -2.664366e+02 +-6.343588e-01 -2.722893e-02 7.725591e-01 5.504365e+02 2.286776e-02 9.982811e-01 5.396156e-02 7.450904e+00 -7.727004e-01 5.189768e-02 -6.326457e-01 -2.681343e+02 +-6.343774e-01 -2.825764e-02 7.725069e-01 5.524956e+02 2.358501e-02 9.981589e-01 5.587963e-02 7.551427e+00 -7.726636e-01 5.366835e-02 -6.325429e-01 -2.698319e+02 +-6.343860e-01 -2.725994e-02 7.725357e-01 5.545493e+02 2.445367e-02 9.981701e-01 5.530245e-02 7.654529e+00 -7.726295e-01 5.397442e-02 -6.325585e-01 -2.715254e+02 +-6.344427e-01 -2.643894e-02 7.725176e-01 5.566051e+02 2.466001e-02 9.982138e-01 5.441568e-02 7.757167e+00 -7.725764e-01 5.357391e-02 -6.326574e-01 -2.732200e+02 +-6.344310e-01 -2.582120e-02 7.725481e-01 5.586591e+02 2.523755e-02 9.982171e-01 5.408937e-02 7.857401e+00 -7.725674e-01 5.381318e-02 -6.326482e-01 -2.749141e+02 +-6.343300e-01 -2.548778e-02 7.726421e-01 5.607204e+02 2.640100e-02 9.981591e-01 5.460200e-02 7.957556e+00 -7.726114e-01 5.503420e-02 -6.324894e-01 -2.766146e+02 +-6.341833e-01 -2.586426e-02 7.727501e-01 5.627775e+02 2.725792e-02 9.980711e-01 5.577597e-02 8.058037e+00 -7.727021e-01 5.643573e-02 -6.322549e-01 -2.783114e+02 +-6.339634e-01 -2.711272e-02 7.728877e-01 5.648386e+02 2.651517e-02 9.980357e-01 5.675999e-02 8.161795e+00 -7.729084e-01 5.647699e-02 -6.319991e-01 -2.800085e+02 +-6.338899e-01 -2.726787e-02 7.729425e-01 5.668959e+02 2.672909e-02 9.980090e-01 5.712828e-02 8.267916e+00 -7.729613e-01 5.687308e-02 -6.318989e-01 -2.817021e+02 +-6.335856e-01 -2.659240e-02 7.732155e-01 5.689502e+02 2.770724e-02 9.979881e-01 5.702654e-02 8.373989e+00 -7.731763e-01 5.755485e-02 -6.315740e-01 -2.833947e+02 +-6.332114e-01 -2.777469e-02 7.734804e-01 5.710150e+02 2.817505e-02 9.978663e-01 5.889766e-02 8.483450e+00 -7.734659e-01 5.908751e-02 -6.310777e-01 -2.850936e+02 +-6.328038e-01 -2.864444e-02 7.737822e-01 5.730773e+02 2.691291e-02 9.978980e-01 5.895046e-02 8.593947e+00 -7.738443e-01 5.812879e-02 -6.307027e-01 -2.867871e+02 +-6.325817e-01 -3.043971e-02 7.738953e-01 5.751384e+02 2.506042e-02 9.978996e-01 5.973487e-02 8.705148e+00 -7.740881e-01 5.718131e-02 -6.304902e-01 -2.884766e+02 +-6.322726e-01 -2.939367e-02 7.741882e-01 5.772007e+02 2.522994e-02 9.979688e-01 5.849503e-02 8.816896e+00 -7.743350e-01 5.651752e-02 -6.302467e-01 -2.901677e+02 +-6.317201e-01 -2.792959e-02 7.746933e-01 5.792540e+02 2.653593e-02 9.979859e-01 5.761843e-02 8.924907e+00 -7.747422e-01 5.695591e-02 -6.297066e-01 -2.918529e+02 +-6.309177e-01 -2.685553e-02 7.753849e-01 5.813141e+02 2.800142e-02 9.979614e-01 5.734878e-02 9.031620e+00 -7.753443e-01 5.789422e-02 -6.288795e-01 -2.935428e+02 +-6.302434e-01 -2.707487e-02 7.759254e-01 5.833713e+02 2.843217e-02 9.979165e-01 5.791490e-02 9.137328e+00 -7.758768e-01 5.856172e-02 -6.281605e-01 -2.952267e+02 +-6.296791e-01 -2.867949e-02 7.763258e-01 5.854383e+02 2.819705e-02 9.978161e-01 5.973258e-02 9.245509e+00 -7.763434e-01 5.950244e-02 -6.274952e-01 -2.969139e+02 +-6.291126e-01 -2.733405e-02 7.768334e-01 5.875190e+02 2.864647e-02 9.978873e-01 5.831129e-02 9.353208e+00 -7.767861e-01 5.893789e-02 -6.270005e-01 -2.986121e+02 +-6.284360e-01 -2.762615e-02 7.773706e-01 5.895489e+02 2.792536e-02 9.979236e-01 5.803934e-02 9.456599e+00 -7.773598e-01 5.818235e-02 -6.263596e-01 -3.002630e+02 +-6.279511e-01 -2.810392e-02 7.777453e-01 5.916108e+02 2.729992e-02 9.979373e-01 5.810251e-02 9.561344e+00 -7.777739e-01 5.771790e-02 -6.258885e-01 -3.019383e+02 +-6.272855e-01 -2.848438e-02 7.782683e-01 5.936716e+02 2.691617e-02 9.979409e-01 5.821879e-02 9.666809e+00 -7.783241e-01 5.746779e-02 -6.252271e-01 -3.036091e+02 +-6.267515e-01 -2.929572e-02 7.786683e-01 5.957370e+02 2.626936e-02 9.979306e-01 5.868924e-02 9.775807e+00 -7.787763e-01 5.723867e-02 -6.246849e-01 -3.052800e+02 +-6.263289e-01 -3.020898e-02 7.789734e-01 5.978027e+02 2.504597e-02 9.979532e-01 5.883918e-02 9.883665e+00 -7.791565e-01 5.636281e-02 -6.242903e-01 -3.069488e+02 +-6.259289e-01 -3.096285e-02 7.792653e-01 5.998670e+02 2.347051e-02 9.980111e-01 5.850656e-02 9.992222e+00 -7.795268e-01 5.491069e-02 -6.239572e-01 -3.086131e+02 +-6.260867e-01 -3.038338e-02 7.791613e-01 6.019345e+02 2.246797e-02 9.981227e-01 5.697568e-02 1.009861e+01 -7.794296e-01 5.317788e-02 -6.242287e-01 -3.102813e+02 +-6.262648e-01 -3.113537e-02 7.789885e-01 6.040024e+02 2.281137e-02 9.980425e-01 5.822984e-02 1.020684e+01 -7.792766e-01 5.423708e-02 -6.243286e-01 -3.119523e+02 +-6.263989e-01 -3.193005e-02 7.788485e-01 6.060701e+02 2.349138e-02 9.979336e-01 5.980501e-02 1.031717e+01 -7.791486e-01 5.575801e-02 -6.243544e-01 -3.136242e+02 +-6.265124e-01 -3.312816e-02 7.787071e-01 6.081333e+02 2.244936e-02 9.979148e-01 6.051553e-02 1.043016e+01 -7.790881e-01 5.539520e-02 -6.244622e-01 -3.152902e+02 +-6.266982e-01 -3.264678e-02 7.785779e-01 6.102041e+02 2.151846e-02 9.980160e-01 5.916888e-02 1.054205e+01 -7.789649e-01 5.383482e-02 -6.247523e-01 -3.169635e+02 +-6.267867e-01 -3.057031e-02 7.785910e-01 6.122707e+02 2.202105e-02 9.981359e-01 5.691797e-02 1.065103e+01 -7.788797e-01 5.282080e-02 -6.249451e-01 -3.186358e+02 +-6.266057e-01 -2.915437e-02 7.787910e-01 6.143316e+02 2.264969e-02 9.981966e-01 5.559156e-02 1.075646e+01 -7.790073e-01 5.247334e-02 -6.248153e-01 -3.203039e+02 +-6.265023e-01 -2.875580e-02 7.788890e-01 6.164014e+02 2.309928e-02 9.981952e-01 5.543235e-02 1.085851e+01 -7.790772e-01 5.272026e-02 -6.247073e-01 -3.219781e+02 +-6.265290e-01 -3.015212e-02 7.788147e-01 6.184658e+02 2.294946e-02 9.981044e-01 5.710404e-02 1.096062e+01 -7.790601e-01 5.365070e-02 -6.246494e-01 -3.236462e+02 +-6.264904e-01 -3.068870e-02 7.788248e-01 6.205350e+02 2.368425e-02 9.980136e-01 5.837730e-02 1.106765e+01 -7.790692e-01 5.501868e-02 -6.245190e-01 -3.253171e+02 +-6.263612e-01 -3.072541e-02 7.789272e-01 6.226067e+02 2.406871e-02 9.979842e-01 5.872073e-02 1.117705e+01 -7.791613e-01 5.552815e-02 -6.243591e-01 -3.269891e+02 +-6.261498e-01 -3.047621e-02 7.791070e-01 6.246751e+02 2.373232e-02 9.980279e-01 5.811281e-02 1.128685e+01 -7.793415e-01 5.487733e-02 -6.241916e-01 -3.286575e+02 +-6.259098e-01 -3.013968e-02 7.793129e-01 6.267459e+02 2.363144e-02 9.980612e-01 5.757943e-02 1.139641e+01 -7.795373e-01 5.445581e-02 -6.239840e-01 -3.303270e+02 +-6.256200e-01 -3.038161e-02 7.795362e-01 6.288138e+02 2.390428e-02 9.980256e-01 5.808148e-02 1.150486e+01 -7.797616e-01 5.497117e-02 -6.236585e-01 -3.319942e+02 +-6.252310e-01 -3.031342e-02 7.798508e-01 6.308887e+02 2.380432e-02 9.980397e-01 5.787927e-02 1.161229e+01 -7.800766e-01 5.475173e-02 -6.232838e-01 -3.336656e+02 +-6.249644e-01 -3.121197e-02 7.800291e-01 6.329587e+02 2.325251e-02 9.980128e-01 5.856440e-02 1.172232e+01 -7.803069e-01 5.473828e-02 -6.229967e-01 -3.353308e+02 +-6.246102e-01 -3.173476e-02 7.802916e-01 6.350324e+02 2.267172e-02 9.980159e-01 5.873801e-02 1.183193e+01 -7.806075e-01 5.437890e-02 -6.226514e-01 -3.369998e+02 +-6.242585e-01 -3.023636e-02 7.806325e-01 6.370951e+02 2.295669e-02 9.981092e-01 5.701798e-02 1.194090e+01 -7.808805e-01 5.351468e-02 -6.223840e-01 -3.386594e+02 +-6.237826e-01 -3.043697e-02 7.810051e-01 6.391659e+02 2.287771e-02 9.981023e-01 5.716983e-02 1.204805e+01 -7.812630e-01 5.352914e-02 -6.219025e-01 -3.403234e+02 +-6.234237e-01 -3.101860e-02 7.812687e-01 6.412374e+02 2.321209e-02 9.980381e-01 5.814735e-02 1.215564e+01 -7.815396e-01 5.438530e-02 -6.214805e-01 -3.419886e+02 +-6.230705e-01 -3.122445e-02 7.815422e-01 6.433047e+02 2.380466e-02 9.979830e-01 5.884960e-02 1.226642e+01 -7.818034e-01 5.527178e-02 -6.210704e-01 -3.436496e+02 +-6.226340e-01 -3.036108e-02 7.819241e-01 6.453750e+02 2.387978e-02 9.980444e-01 5.776784e-02 1.237656e+01 -7.821488e-01 5.464038e-02 -6.206913e-01 -3.453101e+02 +-6.222250e-01 -2.898656e-02 7.823017e-01 6.474454e+02 2.429167e-02 9.981181e-01 5.630423e-02 1.248249e+01 -7.824615e-01 5.403730e-02 -6.203498e-01 -3.469686e+02 +-6.216649e-01 -2.849663e-02 7.827648e-01 6.495155e+02 2.497983e-02 9.981084e-01 5.617498e-02 1.258629e+01 -7.828849e-01 5.447533e-02 -6.197771e-01 -3.486239e+02 +-6.210310e-01 -2.943427e-02 7.832332e-01 6.515913e+02 2.579591e-02 9.979856e-01 5.795851e-02 1.269235e+01 -7.833614e-01 5.619823e-02 -6.190207e-01 -3.502820e+02 +-6.205815e-01 -3.013895e-02 7.835626e-01 6.536623e+02 2.582840e-02 9.979332e-01 5.884059e-02 1.280042e+01 -7.837165e-01 5.675353e-02 -6.185204e-01 -3.519355e+02 +-6.201170e-01 -3.023961e-02 7.839263e-01 6.557358e+02 2.584500e-02 9.979269e-01 5.893901e-02 1.291009e+01 -7.840835e-01 5.680964e-02 -6.180499e-01 -3.535870e+02 +-6.197503e-01 -3.095389e-02 7.841885e-01 6.578057e+02 2.526742e-02 9.979168e-01 5.935931e-02 1.302023e+01 -7.843922e-01 5.660235e-02 -6.176770e-01 -3.552341e+02 +-6.192251e-01 -3.037229e-02 7.846259e-01 6.598779e+02 2.531333e-02 9.979601e-01 5.860753e-02 1.313000e+01 -7.848054e-01 5.615274e-02 -6.171931e-01 -3.568806e+02 +-6.187172e-01 -2.938215e-02 7.850642e-01 6.619586e+02 2.526392e-02 9.980394e-01 5.726380e-02 1.323887e+01 -7.852075e-01 5.526388e-02 -6.167618e-01 -3.585328e+02 +-6.183042e-01 -2.895769e-02 7.854053e-01 6.640361e+02 2.521061e-02 9.980760e-01 5.664565e-02 1.334665e+01 -7.855344e-01 5.482478e-02 -6.163845e-01 -3.601819e+02 +-6.181475e-01 -2.899896e-02 7.855271e-01 6.661120e+02 2.486200e-02 9.980980e-01 5.641076e-02 1.345227e+01 -7.856689e-01 5.439993e-02 -6.162508e-01 -3.618289e+02 +-6.181211e-01 -2.959064e-02 7.855258e-01 6.681904e+02 2.430014e-02 9.980944e-01 5.671956e-02 1.355813e+01 -7.857072e-01 5.414793e-02 -6.162241e-01 -3.634752e+02 +-6.182589e-01 -2.961843e-02 7.854163e-01 6.702712e+02 2.373143e-02 9.981306e-01 5.632074e-02 1.366357e+01 -7.856161e-01 5.345984e-02 -6.164002e-01 -3.651232e+02 +-6.185260e-01 -3.030074e-02 7.851799e-01 6.723505e+02 2.298237e-02 9.981311e-01 5.662307e-02 1.376872e+01 -7.854281e-01 5.306812e-02 -6.166736e-01 -3.667695e+02 +-6.188770e-01 -3.062233e-02 7.848909e-01 6.744325e+02 2.193799e-02 9.981761e-01 5.624143e-02 1.387413e+01 -7.851815e-01 5.202544e-02 -6.170764e-01 -3.684192e+02 +-6.192450e-01 -3.059867e-02 7.846014e-01 6.765090e+02 2.157463e-02 9.982001e-01 5.595653e-02 1.397893e+01 -7.849013e-01 5.157828e-02 -6.174702e-01 -3.700675e+02 +-6.195896e-01 -3.090942e-02 7.843171e-01 6.785876e+02 2.192674e-02 9.981528e-01 5.665807e-02 1.408324e+01 -7.846196e-01 5.230226e-02 -6.177673e-01 -3.717203e+02 +-6.199262e-01 -3.124605e-02 7.840378e-01 6.806657e+02 2.229805e-02 9.981017e-01 5.740779e-02 1.418850e+01 -7.843432e-01 5.307110e-02 -6.180527e-01 -3.733743e+02 +-6.203275e-01 -3.106536e-02 7.837275e-01 6.827432e+02 2.367638e-02 9.980183e-01 5.829948e-02 1.429713e+01 -7.839855e-01 5.472059e-02 -6.183626e-01 -3.750304e+02 +-6.204869e-01 -3.143224e-02 7.835867e-01 6.848198e+02 2.338258e-02 9.980106e-01 5.854909e-02 1.440571e+01 -7.838681e-01 5.465121e-02 -6.185175e-01 -3.766842e+02 +-6.206549e-01 -3.096139e-02 7.834724e-01 6.868945e+02 2.296153e-02 9.980738e-01 5.763181e-02 1.451349e+01 -7.837476e-01 5.375918e-02 -6.187484e-01 -3.783370e+02 +-6.205936e-01 -2.976116e-02 7.835674e-01 6.889656e+02 2.350369e-02 9.981244e-01 5.652555e-02 1.461921e+01 -7.837800e-01 5.349611e-02 -6.187301e-01 -3.799902e+02 +-6.204054e-01 -2.873466e-02 7.837548e-01 6.910408e+02 2.516469e-02 9.980847e-01 5.651249e-02 1.472406e+01 -7.838775e-01 5.478359e-02 -6.184940e-01 -3.816488e+02 +-6.199039e-01 -2.777842e-02 7.841859e-01 6.931156e+02 2.640585e-02 9.980686e-01 5.622883e-02 1.482707e+01 -7.842333e-01 5.556355e-02 -6.179731e-01 -3.833046e+02 +-6.194259e-01 -2.764355e-02 7.845683e-01 6.951930e+02 2.762599e-02 9.979933e-01 5.697441e-02 1.492975e+01 -7.845689e-01 5.696589e-02 -6.174192e-01 -3.849613e+02 +-6.189651e-01 -2.720965e-02 7.849471e-01 6.972710e+02 2.818073e-02 9.979868e-01 5.681626e-02 1.503283e+01 -7.849128e-01 5.728765e-02 -6.169522e-01 -3.866143e+02 +-6.184733e-01 -2.691439e-02 7.853448e-01 6.993457e+02 2.789353e-02 9.980315e-01 5.616999e-02 1.513859e+01 -7.853106e-01 5.664566e-02 -6.165050e-01 -3.882646e+02 +-6.180394e-01 -2.712765e-02 7.856790e-01 7.014274e+02 2.687530e-02 9.980912e-01 5.560269e-02 1.524435e+01 -7.856876e-01 5.548000e-02 -6.161306e-01 -3.899181e+02 +-6.176405e-01 -2.677779e-02 7.860046e-01 7.035065e+02 2.660958e-02 9.981364e-01 5.491448e-02 1.534668e+01 -7.860103e-01 5.483265e-02 -6.157768e-01 -3.915686e+02 +-6.171660e-01 -2.735725e-02 7.863573e-01 7.055829e+02 2.604813e-02 9.981372e-01 5.516869e-02 1.544804e+01 -7.864017e-01 5.453136e-02 -6.153037e-01 -3.932168e+02 +-6.167027e-01 -2.825224e-02 7.866891e-01 7.076613e+02 2.705064e-02 9.980050e-01 5.704677e-02 1.554996e+01 -7.867312e-01 5.646132e-02 -6.147080e-01 -3.948665e+02 +-6.160735e-01 -2.860175e-02 7.871692e-01 7.097441e+02 2.784834e-02 9.979249e-01 5.805488e-02 1.565581e+01 -7.871962e-01 5.768742e-02 -6.139986e-01 -3.965177e+02 +-6.155892e-01 -2.809754e-02 7.875662e-01 7.118243e+02 2.864569e-02 9.979060e-01 5.799218e-02 1.576531e+01 -7.875464e-01 5.825973e-02 -6.134953e-01 -3.981607e+02 +-6.150152e-01 -2.666353e-02 7.880644e-01 7.139054e+02 2.958742e-02 9.979439e-01 5.685502e-02 1.587836e+01 -7.879600e-01 5.828347e-02 -6.129617e-01 -3.998001e+02 +-6.142781e-01 -2.593378e-02 7.886634e-01 7.159839e+02 2.957014e-02 9.980012e-01 5.584921e-02 1.599116e+01 -7.885354e-01 5.762782e-02 -6.122833e-01 -4.014338e+02 +-6.135181e-01 -2.465817e-02 7.892956e-01 7.180631e+02 2.992731e-02 9.980683e-01 5.444283e-02 1.610183e+01 -7.891133e-01 5.702314e-02 -6.115950e-01 -4.030674e+02 +-6.128317e-01 -2.458664e-02 7.898309e-01 7.201441e+02 2.991372e-02 9.980776e-01 5.427927e-02 1.621513e+01 -7.896470e-01 5.689083e-02 -6.109181e-01 -4.046980e+02 +-6.121955e-01 -2.349402e-02 7.903574e-01 7.222296e+02 3.054747e-02 9.981095e-01 5.333110e-02 1.632798e+01 -7.901162e-01 5.679246e-02 -6.103204e-01 -4.063296e+02 +-6.114061e-01 -2.297364e-02 7.909835e-01 7.243156e+02 3.086806e-02 9.981252e-01 5.285001e-02 1.644029e+01 -7.907147e-01 5.672893e-02 -6.095506e-01 -4.079582e+02 +-6.106438e-01 -2.477735e-02 7.915177e-01 7.264057e+02 2.932406e-02 9.981174e-01 5.386772e-02 1.654399e+01 -7.913623e-01 5.610449e-02 -6.087676e-01 -4.095850e+02 +-6.101021e-01 -2.603302e-02 7.918951e-01 7.284983e+02 2.725090e-02 9.981793e-01 5.380946e-02 1.666273e+01 -7.918540e-01 5.440910e-02 -6.082818e-01 -4.112077e+02 +-6.096062e-01 -2.574941e-02 7.922862e-01 7.305888e+02 2.684648e-02 9.982283e-01 5.309895e-02 1.677343e+01 -7.922497e-01 5.363952e-02 -6.078348e-01 -4.128287e+02 +-6.089475e-01 -2.434435e-02 7.928369e-01 7.326752e+02 2.817377e-02 9.982344e-01 5.229034e-02 1.688104e+01 -7.927100e-01 5.417927e-02 -6.071864e-01 -4.144501e+02 +-6.082262e-01 -2.245372e-02 7.934462e-01 7.347664e+02 2.985769e-02 9.982452e-01 5.113711e-02 1.698171e+01 -7.932020e-01 5.479338e-02 -6.064884e-01 -4.160734e+02 +-6.078688e-01 -2.256547e-02 7.937168e-01 7.368556e+02 2.987733e-02 9.982382e-01 5.126162e-02 1.707951e+01 -7.934752e-01 5.487447e-02 -6.061237e-01 -4.176935e+02 +-6.078964e-01 -2.428475e-02 7.936449e-01 7.389533e+02 2.923173e-02 9.981701e-01 5.293321e-02 1.717540e+01 -7.934781e-01 5.537751e-02 -6.060741e-01 -4.193157e+02 +-6.080761e-01 -2.619893e-02 7.934464e-01 7.410479e+02 2.721968e-02 9.981796e-01 5.381948e-02 1.727242e+01 -7.934120e-01 5.432368e-02 -6.062560e-01 -4.209340e+02 +-6.082645e-01 -2.631943e-02 7.932980e-01 7.431419e+02 2.598236e-02 9.982542e-01 5.304138e-02 1.737146e+01 -7.933090e-01 5.287493e-02 -6.065187e-01 -4.225508e+02 +-6.081614e-01 -2.464044e-02 7.934309e-01 7.452354e+02 2.571500e-02 9.983820e-01 5.071575e-02 1.746720e+01 -7.933968e-01 5.124643e-02 -6.065437e-01 -4.241692e+02 +-6.077041e-01 -2.493766e-02 7.937719e-01 7.473289e+02 2.681944e-02 9.982923e-01 5.189571e-02 1.755500e+01 -7.937105e-01 5.282575e-02 -6.059975e-01 -4.257917e+02 +-6.070151e-01 -2.472784e-02 7.943055e-01 7.494207e+02 2.930458e-02 9.981394e-01 5.346828e-02 1.765191e+01 -7.941498e-01 5.573283e-02 -6.051611e-01 -4.274134e+02 +-6.064594e-01 -2.383008e-02 7.947573e-01 7.515173e+02 3.164025e-02 9.980358e-01 5.406908e-02 1.775413e+01 -7.944846e-01 5.793701e-02 -6.045142e-01 -4.290362e+02 +-6.059118e-01 -2.210289e-02 7.952248e-01 7.536116e+02 3.317071e-02 9.980427e-01 5.301413e-02 1.785404e+01 -7.948400e-01 5.850004e-02 -6.039926e-01 -4.306541e+02 +-6.053864e-01 -1.987480e-02 7.956836e-01 7.557109e+02 3.322671e-02 9.981856e-01 5.021309e-02 1.794006e+01 -7.952379e-01 5.683625e-02 -6.036276e-01 -4.322706e+02 +-6.047465e-01 -1.806800e-02 7.962131e-01 7.578089e+02 3.349565e-02 9.982810e-01 4.809431e-02 1.802205e+01 -7.957133e-01 5.575453e-02 -6.031017e-01 -4.338840e+02 +-6.037548e-01 -1.753328e-02 7.969773e-01 7.599091e+02 3.433796e-02 9.982581e-01 4.797432e-02 1.809594e+01 -7.964302e-01 5.633129e-02 -6.021010e-01 -4.354976e+02 +-6.028142e-01 -1.885826e-02 7.976587e-01 7.620181e+02 3.464792e-02 9.981589e-01 4.978294e-02 1.817308e+01 -7.971289e-01 5.764707e-02 -6.010509e-01 -4.371125e+02 +-6.020180e-01 -1.978524e-02 7.982374e-01 7.641249e+02 3.417750e-02 9.981383e-01 5.051613e-02 1.825478e+01 -7.977507e-01 5.769337e-02 -6.002209e-01 -4.387221e+02 +-6.011824e-01 -1.958408e-02 7.988719e-01 7.662346e+02 3.373856e-02 9.981862e-01 4.985979e-02 1.833932e+01 -7.983993e-01 5.692760e-02 -5.994312e-01 -4.403295e+02 +-6.004185e-01 -2.003886e-02 7.994349e-01 7.683468e+02 3.292078e-02 9.982191e-01 4.974691e-02 1.842281e+01 -7.990080e-01 5.618697e-02 -5.986895e-01 -4.419355e+02 +-5.996115e-01 -2.043146e-02 8.000304e-01 7.704571e+02 3.264030e-02 9.982179e-01 4.995629e-02 1.850284e+01 -7.996253e-01 5.606759e-02 -5.978760e-01 -4.435378e+02 +-5.987543e-01 -1.969439e-02 8.006906e-01 7.725730e+02 3.265637e-02 9.982660e-01 4.897443e-02 1.858489e+01 -8.002667e-01 5.547129e-02 -5.970729e-01 -4.451404e+02 +-5.979070e-01 -1.961354e-02 8.013255e-01 7.746901e+02 3.156589e-02 9.983490e-01 4.798876e-02 1.866585e+01 -8.009437e-01 5.398735e-02 -5.963006e-01 -4.467409e+02 +-5.974378e-01 -1.903383e-02 8.016893e-01 7.768050e+02 3.277318e-02 9.983035e-01 4.812521e-02 1.874823e+01 -8.012452e-01 5.502572e-02 -5.958004e-01 -4.483389e+02 +-5.969748e-01 -1.940370e-02 8.020253e-01 7.789176e+02 3.276996e-02 9.982833e-01 4.854363e-02 1.882798e+01 -8.015904e-01 5.526165e-02 -5.953141e-01 -4.499322e+02 +-5.969038e-01 -2.058569e-02 8.020487e-01 7.810382e+02 3.201801e-02 9.982632e-01 4.945037e-02 1.891026e+01 -8.016737e-01 5.519710e-02 -5.952079e-01 -4.515290e+02 +-5.971140e-01 -2.216649e-02 8.018501e-01 7.831553e+02 3.051299e-02 9.982670e-01 5.031838e-02 1.899428e+01 -8.015758e-01 5.451264e-02 -5.954028e-01 -4.531207e+02 +-5.974656e-01 -2.224858e-02 8.015859e-01 7.852706e+02 2.912478e-02 9.983534e-01 4.941828e-02 1.907913e+01 -8.013655e-01 5.287172e-02 -5.958338e-01 -4.547110e+02 +-5.977074e-01 -2.169289e-02 8.014208e-01 7.873866e+02 2.831947e-02 9.984387e-01 4.814671e-02 1.916217e+01 -8.012140e-01 5.147344e-02 -5.961599e-01 -4.563036e+02 +-5.981217e-01 -2.168296e-02 8.011120e-01 7.894935e+02 2.823897e-02 9.984429e-01 4.810754e-02 1.924372e+01 -8.009076e-01 5.139672e-02 -5.965780e-01 -4.578927e+02 +-5.986519e-01 -2.119986e-02 8.007288e-01 7.916044e+02 2.913865e-02 9.984117e-01 4.821870e-02 1.932538e+01 -8.004791e-01 5.219836e-02 -5.970832e-01 -4.594876e+02 +-5.992125e-01 -2.052399e-02 8.003270e-01 7.937097e+02 3.030339e-02 9.983735e-01 4.829123e-02 1.940541e+01 -8.000163e-01 5.318931e-02 -5.976158e-01 -4.610817e+02 +-5.997323e-01 -2.016021e-02 7.999468e-01 7.958137e+02 3.100145e-02 9.983467e-01 4.840253e-02 1.948576e+01 -7.996000e-01 5.382806e-02 -5.981157e-01 -4.626772e+02 +-6.002782e-01 -2.124403e-02 7.995091e-01 7.979140e+02 3.131762e-02 9.982561e-01 5.003853e-02 1.956981e+01 -7.991778e-01 5.507575e-02 -5.985661e-01 -4.642714e+02 +-6.006295e-01 -2.189010e-02 7.992278e-01 8.000123e+02 3.066110e-02 9.982592e-01 5.038357e-02 1.965533e+01 -7.989393e-01 5.476705e-02 -5.989127e-01 -4.658635e+02 +-6.006924e-01 -2.038464e-02 7.992204e-01 8.021083e+02 2.956262e-02 9.984248e-01 4.768468e-02 1.973792e+01 -7.989335e-01 5.227086e-02 -5.991435e-01 -4.674543e+02 +-6.006100e-01 -1.876403e-02 7.993219e-01 8.042028e+02 2.924259e-02 9.985402e-01 4.541352e-02 1.981630e+01 -7.990072e-01 5.065004e-02 -5.991845e-01 -4.690448e+02 +-6.003047e-01 -1.760474e-02 7.995777e-01 8.062987e+02 2.964167e-02 9.985810e-01 4.424059e-02 1.988938e+01 -7.992219e-01 5.025863e-02 -5.989310e-01 -4.706373e+02 +-5.999157e-01 -1.798477e-02 7.998611e-01 8.083959e+02 3.010632e-02 9.985317e-01 4.503233e-02 1.996249e+01 -7.994966e-01 5.109646e-02 -5.984934e-01 -4.722307e+02 +-5.993871e-01 -1.845460e-02 8.002466e-01 8.104902e+02 3.014063e-02 9.985049e-01 4.560208e-02 2.003686e+01 -7.998916e-01 5.145323e-02 -5.979347e-01 -4.738196e+02 +-5.988091e-01 -1.841164e-02 8.006802e-01 8.125910e+02 3.084472e-02 9.984638e-01 4.602768e-02 2.011443e+01 -8.002976e-01 5.225853e-02 -5.973213e-01 -4.754125e+02 +-5.979350e-01 -1.814869e-02 8.013392e-01 8.146888e+02 3.220231e-02 9.983925e-01 4.663993e-02 2.019413e+01 -8.008975e-01 5.369261e-02 -5.963893e-01 -4.770013e+02 +-5.969630e-01 -1.773576e-02 8.020727e-01 8.167915e+02 3.319959e-02 9.983531e-01 4.678563e-02 2.027321e+01 -8.015815e-01 5.455777e-02 -5.953910e-01 -4.785905e+02 +-5.957648e-01 -1.758585e-02 8.029665e-01 8.188949e+02 3.362588e-02 9.983375e-01 4.681356e-02 2.035380e+01 -8.024547e-01 5.489031e-02 -5.941829e-01 -4.801748e+02 +-5.946218e-01 -1.789188e-02 8.038065e-01 8.210023e+02 3.387370e-02 9.983072e-01 4.727957e-02 2.043563e+01 -8.032916e-01 5.534135e-02 -5.930091e-01 -4.817573e+02 +-5.934821e-01 -1.771187e-02 8.046523e-01 8.231164e+02 3.443497e-02 9.982836e-01 4.737201e-02 2.051693e+01 -8.041102e-01 5.582260e-02 -5.918535e-01 -4.833404e+02 +-5.923353e-01 -1.795207e-02 8.054916e-01 8.252301e+02 3.449196e-02 9.982701e-01 4.761293e-02 2.059912e+01 -8.049529e-01 5.598579e-02 -5.906914e-01 -4.849182e+02 +-5.912662e-01 -1.944743e-02 8.062420e-01 8.273472e+02 3.392734e-02 9.982244e-01 4.895922e-02 2.068385e+01 -8.057625e-01 5.630156e-02 -5.895565e-01 -4.864927e+02 +-5.902021e-01 -2.047535e-02 8.069959e-01 8.294645e+02 3.339052e-02 9.982035e-01 4.974711e-02 2.077068e+01 -8.065647e-01 5.630684e-02 -5.884580e-01 -4.880614e+02 +-5.892913e-01 -2.045812e-02 8.076616e-01 8.315909e+02 3.198517e-02 9.983049e-01 4.862434e-02 2.085797e+01 -8.072872e-01 5.448708e-02 -5.876380e-01 -4.896319e+02 +-5.885032e-01 -2.056920e-02 8.082332e-01 8.337229e+02 3.174578e-02 9.983175e-01 4.852198e-02 2.094602e+01 -8.078714e-01 5.421332e-02 -5.868600e-01 -4.912049e+02 +-5.877450e-01 -2.021865e-02 8.087936e-01 8.358541e+02 3.277724e-02 9.982718e-01 4.877434e-02 2.103407e+01 -8.083820e-01 5.517688e-02 -5.860666e-01 -4.927761e+02 +-5.873742e-01 -2.061282e-02 8.090530e-01 8.379860e+02 3.284056e-02 9.982452e-01 4.927531e-02 2.112295e+01 -8.086489e-01 5.551278e-02 -5.856665e-01 -4.943446e+02 +-5.874257e-01 -2.070708e-02 8.090132e-01 8.401199e+02 3.293225e-02 9.982329e-01 4.946239e-02 2.121212e+01 -8.086078e-01 5.569809e-02 -5.857056e-01 -4.959132e+02 +-5.876351e-01 -2.378478e-02 8.087764e-01 8.422623e+02 3.150144e-02 9.981375e-01 5.224166e-02 2.130359e+01 -8.085126e-01 5.617664e-02 -5.857914e-01 -4.974854e+02 +-5.879267e-01 -2.452503e-02 8.085424e-01 8.444038e+02 3.016698e-02 9.981802e-01 5.221293e-02 2.139780e+01 -8.083515e-01 5.508865e-02 -5.861169e-01 -4.990558e+02 +-5.881475e-01 -2.531938e-02 8.083573e-01 8.465437e+02 2.869503e-02 9.982272e-01 5.214451e-02 2.149439e+01 -8.082445e-01 5.386448e-02 -5.863782e-01 -5.006257e+02 +-5.880676e-01 -2.430593e-02 8.084466e-01 8.486827e+02 2.797456e-02 9.983391e-01 5.036386e-02 2.158726e+01 -8.083279e-01 5.223327e-02 -5.864108e-01 -5.021964e+02 +-5.876245e-01 -2.492353e-02 8.087498e-01 8.508213e+02 2.758645e-02 9.983273e-01 5.080966e-02 2.167907e+01 -8.086633e-01 5.216753e-02 -5.859540e-01 -5.037670e+02 +-5.871744e-01 -2.662307e-02 8.090226e-01 8.529722e+02 2.690961e-02 9.982645e-01 5.238110e-02 2.177339e+01 -8.090130e-01 5.252731e-02 -5.854389e-01 -5.053431e+02 +-5.868245e-01 -2.557033e-02 8.093104e-01 8.551147e+02 2.658898e-02 9.983537e-01 5.082265e-02 2.186598e+01 -8.092775e-01 5.134270e-02 -5.851784e-01 -5.069135e+02 +-5.864304e-01 -2.422785e-02 8.096372e-01 8.572619e+02 2.689668e-02 9.984189e-01 4.935861e-02 2.195643e+01 -8.095529e-01 5.072193e-02 -5.848515e-01 -5.084874e+02 +-5.860720e-01 -2.386218e-02 8.099075e-01 8.594084e+02 2.870361e-02 9.983274e-01 5.018431e-02 2.204762e+01 -8.097504e-01 5.265888e-02 -5.844068e-01 -5.100613e+02 +-5.858605e-01 -2.526315e-02 8.100181e-01 8.615570e+02 2.936743e-02 9.981957e-01 5.237264e-02 2.214020e+01 -8.098796e-01 5.447120e-02 -5.840615e-01 -5.116370e+02 +-5.857699e-01 -2.664137e-02 8.100395e-01 8.637104e+02 2.993255e-02 9.980666e-01 5.447074e-02 2.223641e+01 -8.099245e-01 5.615385e-02 -5.838399e-01 -5.132137e+02 +-5.855253e-01 -2.740359e-02 8.101909e-01 8.658589e+02 2.941737e-02 9.980519e-01 5.501766e-02 2.233432e+01 -8.101202e-01 5.604790e-02 -5.835784e-01 -5.147848e+02 +-5.850150e-01 -2.910390e-02 8.105002e-01 8.680116e+02 2.882214e-02 9.979786e-01 5.663965e-02 2.243636e+01 -8.105102e-01 5.649538e-02 -5.829935e-01 -5.163554e+02 +-5.842077e-01 -2.789300e-02 8.111248e-01 8.701571e+02 2.951821e-02 9.980178e-01 5.558019e-02 2.253588e+01 -8.110672e-01 5.641332e-02 -5.822263e-01 -5.179222e+02 +-5.830875e-01 -2.604763e-02 8.119917e-01 8.722938e+02 3.142991e-02 9.980143e-01 5.458467e-02 2.263292e+01 -8.118011e-01 5.734845e-02 -5.811110e-01 -5.194836e+02 +-5.816662e-01 -2.466697e-02 8.130536e-01 8.744419e+02 3.378701e-02 9.979448e-01 5.444786e-02 2.272987e+01 -8.127256e-01 5.914111e-02 -5.796373e-01 -5.210493e+02 +-5.801933e-01 -2.464661e-02 8.141059e-01 8.765885e+02 3.495258e-02 9.978678e-01 5.511975e-02 2.282659e+01 -8.137285e-01 6.043520e-02 -5.780946e-01 -5.226080e+02 +-5.788923e-01 -2.588364e-02 8.149931e-01 8.787368e+02 3.523110e-02 9.977687e-01 5.671323e-02 2.292504e+01 -8.146425e-01 6.154394e-02 -5.766887e-01 -5.241609e+02 +-5.777592e-01 -2.630999e-02 8.157832e-01 8.808822e+02 3.565396e-02 9.977127e-01 5.742850e-02 2.302388e+01 -8.154282e-01 6.226573e-02 -5.754996e-01 -5.257065e+02 +-5.765635e-01 -2.716794e-02 8.166006e-01 8.830323e+02 3.590484e-02 9.976390e-01 5.854173e-02 2.312541e+01 -8.162630e-01 6.307292e-02 -5.742267e-01 -5.272479e+02 +-5.754862e-01 -2.817993e-02 8.173259e-01 8.852001e+02 3.502889e-02 9.976396e-01 5.906097e-02 2.322957e+01 -8.170609e-01 6.261878e-02 -5.731407e-01 -5.287963e+02 +-5.744051e-01 -2.847432e-02 8.180758e-01 8.873238e+02 3.381906e-02 9.977160e-01 5.847272e-02 2.332974e+01 -8.178723e-01 6.125357e-02 -5.721301e-01 -5.303079e+02 +-5.732515e-01 -2.867449e-02 8.188776e-01 8.894706e+02 3.329040e-02 9.977472e-01 5.824273e-02 2.343087e+01 -8.187029e-01 6.064848e-02 -5.710055e-01 -5.318310e+02 +-5.721907e-01 -2.890800e-02 8.196110e-01 8.916091e+02 3.355917e-02 9.977162e-01 5.861832e-02 2.353263e+01 -8.194337e-01 6.104631e-02 -5.699138e-01 -5.333456e+02 +-5.709912e-01 -2.870008e-02 8.204544e-01 8.937550e+02 3.395848e-02 9.977077e-01 5.853376e-02 2.363418e+01 -8.202535e-01 6.128363e-02 -5.687077e-01 -5.348619e+02 +-5.699506e-01 -2.781134e-02 8.212082e-01 8.958952e+02 3.468735e-02 9.977217e-01 5.786358e-02 2.373415e+01 -8.209465e-01 6.146490e-02 -5.676873e-01 -5.363697e+02 +-5.690353e-01 -2.909090e-02 8.217984e-01 8.980347e+02 3.454584e-02 9.976460e-01 5.923622e-02 2.383529e+01 -8.215871e-01 6.209720e-02 -5.666908e-01 -5.378732e+02 +-5.682635e-01 -2.932919e-02 8.223238e-01 9.001742e+02 3.565867e-02 9.975479e-01 6.022055e-02 2.394138e+01 -8.220736e-01 6.354410e-02 -5.658242e-01 -5.393743e+02 +-5.674666e-01 -2.987107e-02 8.228544e-01 9.023079e+02 3.527361e-02 9.975424e-01 6.053835e-02 2.404861e+01 -8.226405e-01 6.337853e-02 -5.650183e-01 -5.408662e+02 +-5.667491e-01 -3.057614e-02 8.233229e-01 9.044565e+02 3.453723e-02 9.975510e-01 6.082085e-02 2.415887e+01 -8.231662e-01 6.290544e-02 -5.643051e-01 -5.423632e+02 +-5.660981e-01 -3.034901e-02 8.237791e-01 9.065910e+02 3.419117e-02 9.975976e-01 6.024874e-02 2.426707e+01 -8.236285e-01 6.227265e-02 -5.637004e-01 -5.438481e+02 +-5.655556e-01 -3.067740e-02 8.241394e-01 9.087272e+02 3.299448e-02 9.976662e-01 5.977874e-02 2.437286e+01 -8.240499e-01 6.100024e-02 -5.632235e-01 -5.453321e+02 +-5.650646e-01 -3.086228e-02 8.244693e-01 9.108623e+02 3.262427e-02 9.976827e-01 5.970578e-02 2.447974e+01 -8.244014e-01 6.063531e-02 -5.627483e-01 -5.468143e+02 +-5.646629e-01 -2.991198e-02 8.247795e-01 9.129899e+02 3.330632e-02 9.977030e-01 5.898560e-02 2.458493e+01 -8.246493e-01 6.077733e-02 -5.623696e-01 -5.482919e+02 +-5.642681e-01 -2.785301e-02 8.251217e-01 9.151230e+02 3.442717e-02 9.977676e-01 5.722426e-02 2.468802e+01 -8.248735e-01 6.069641e-02 -5.620495e-01 -5.497727e+02 +-5.639883e-01 -2.826633e-02 8.252989e-01 9.172617e+02 3.514762e-02 9.976866e-01 5.818957e-02 2.478905e+01 -8.250344e-01 6.182552e-02 -5.616901e-01 -5.512578e+02 +-5.636683e-01 -3.042815e-02 8.254406e-01 9.194006e+02 3.603064e-02 9.974643e-01 6.137366e-02 2.489471e+01 -8.252150e-01 6.433553e-02 -5.611426e-01 -5.527312e+02 +-5.635347e-01 -3.195231e-02 8.254742e-01 9.215445e+02 3.447316e-02 9.974716e-01 6.214409e-02 2.501399e+01 -8.253727e-01 6.347705e-02 -5.610084e-01 -5.542024e+02 +-5.634154e-01 -2.712992e-02 8.257282e-01 9.236762e+02 3.179125e-02 9.980085e-01 5.448229e-02 2.512190e+01 -8.255619e-01 5.694708e-02 -5.614308e-01 -5.556621e+02 +-5.633396e-01 -2.350582e-02 8.258911e-01 9.258066e+02 3.081412e-02 9.983021e-01 4.943112e-02 2.521008e+01 -8.256507e-01 5.329560e-02 -5.616587e-01 -5.571257e+02 +-5.632295e-01 -2.787898e-02 8.258301e-01 9.279450e+02 2.946396e-02 9.981175e-01 5.379008e-02 2.530080e+01 -8.257750e-01 5.462837e-02 -5.613477e-01 -5.585951e+02 +-5.630537e-01 -3.359089e-02 8.257374e-01 9.300863e+02 2.975654e-02 9.977016e-01 6.087675e-02 2.541005e+01 -8.258844e-01 5.884795e-02 -5.607600e-01 -5.600649e+02 +-5.628334e-01 -3.494786e-02 8.258313e-01 9.322263e+02 3.062719e-02 9.975379e-01 6.308772e-02 2.552985e+01 -8.260027e-01 6.080075e-02 -5.603772e-01 -5.615352e+02 +-5.624224e-01 -3.384311e-02 8.261572e-01 9.343539e+02 3.197187e-02 9.975246e-01 6.262855e-02 2.565168e+01 -8.262317e-01 6.163748e-02 -5.599481e-01 -5.629959e+02 +-5.618793e-01 -3.279564e-02 8.265689e-01 9.364928e+02 3.331943e-02 9.975056e-01 6.222751e-02 2.577269e+01 -8.265479e-01 6.250514e-02 -5.593850e-01 -5.644662e+02 +-5.613193e-01 -3.387633e-02 8.269057e-01 9.386325e+02 3.342527e-02 9.974186e-01 6.355154e-02 2.589232e+01 -8.269240e-01 6.331224e-02 -5.587380e-01 -5.659327e+02 +-5.606886e-01 -3.528829e-02 8.272745e-01 9.407719e+02 3.256962e-02 9.973784e-01 6.461844e-02 2.601411e+01 -8.273860e-01 6.317482e-02 -5.580693e-01 -5.673969e+02 +-5.600649e-01 -3.610179e-02 8.276618e-01 9.429158e+02 3.199557e-02 9.973621e-01 6.515481e-02 2.613759e+01 -8.278306e-01 6.297242e-02 -5.574323e-01 -5.688595e+02 +-5.591300e-01 -3.379536e-02 8.283910e-01 9.450575e+02 3.244663e-02 9.975114e-01 6.259500e-02 2.626007e+01 -8.284448e-01 6.187722e-02 -5.566420e-01 -5.703220e+02 +-5.582337e-01 -3.325722e-02 8.290170e-01 9.472049e+02 3.304581e-02 9.975122e-01 6.226864e-02 2.638159e+01 -8.290254e-01 6.215598e-02 -5.557459e-01 -5.717862e+02 +-5.571162e-01 -3.320684e-02 8.297704e-01 9.493532e+02 3.399055e-02 9.974510e-01 6.273890e-02 2.650083e+01 -8.297386e-01 6.315719e-02 -5.545673e-01 -5.732481e+02 +-5.561817e-01 -3.341497e-02 8.303887e-01 9.515077e+02 3.423518e-02 9.974219e-01 6.306662e-02 2.662079e+01 -8.303552e-01 6.350499e-02 -5.536039e-01 -5.747102e+02 +-5.553392e-01 -3.263775e-02 8.309833e-01 9.536604e+02 3.456643e-02 9.974601e-01 6.227676e-02 2.674228e+01 -8.309052e-01 6.330884e-02 -5.528005e-01 -5.761661e+02 +-5.543396e-01 -3.248722e-02 8.316563e-01 9.558153e+02 3.432931e-02 9.974950e-01 6.184758e-02 2.686169e+01 -8.315823e-01 6.283473e-02 -5.518357e-01 -5.776191e+02 +-5.535517e-01 -3.450245e-02 8.320999e-01 9.579804e+02 3.366854e-02 9.973975e-01 6.375429e-02 2.698219e+01 -8.321340e-01 6.330686e-02 -5.509494e-01 -5.790749e+02 +-5.528544e-01 -3.437076e-02 8.325688e-01 9.601378e+02 3.448732e-02 9.973490e-01 6.407411e-02 2.709965e+01 -8.325639e-01 6.413671e-02 -5.502034e-01 -5.805258e+02 +-5.520804e-01 -3.611249e-02 8.330085e-01 9.623019e+02 3.443755e-02 9.972215e-01 6.605508e-02 2.722009e+01 -8.330794e-01 6.515447e-02 -5.493028e-01 -5.819778e+02 +-5.513720e-01 -3.997975e-02 8.333010e-01 9.644640e+02 3.437589e-02 9.969139e-01 7.057506e-02 2.734830e+01 -8.335509e-01 6.755856e-02 -5.482961e-01 -5.834246e+02 +-5.507354e-01 -4.295808e-02 8.335737e-01 9.666368e+02 3.245409e-02 9.968174e-01 7.281296e-02 2.748447e+01 -8.340487e-01 6.715354e-02 -5.475885e-01 -5.848741e+02 +-5.504126e-01 -4.409681e-02 8.337275e-01 9.688004e+02 3.139081e-02 9.968050e-01 7.344585e-02 2.762785e+01 -8.343024e-01 6.659688e-02 -5.472698e-01 -5.863150e+02 +-5.502515e-01 -4.128691e-02 8.339777e-01 9.709633e+02 3.248457e-02 9.969622e-01 7.078866e-02 2.776619e+01 -8.343668e-01 6.604296e-02 -5.472387e-01 -5.877582e+02 +-5.501084e-01 -3.854849e-02 8.342031e-01 9.731252e+02 3.528348e-02 9.969691e-01 6.933730e-02 2.789962e+01 -8.343475e-01 6.757660e-02 -5.470809e-01 -5.892041e+02 +-5.500852e-01 -3.759317e-02 8.342620e-01 9.752876e+02 3.691059e-02 9.969155e-01 6.926024e-02 2.802995e+01 -8.342924e-01 6.889212e-02 -5.470008e-01 -5.906491e+02 +-5.500894e-01 -3.775979e-02 8.342517e-01 9.774553e+02 3.618891e-02 9.969610e-01 6.898658e-02 2.816051e+01 -8.343213e-01 6.813943e-02 -5.470512e-01 -5.920933e+02 +-5.501493e-01 -4.023139e-02 8.340966e-01 9.796246e+02 3.247564e-02 9.970524e-01 6.951143e-02 2.829193e+01 -8.344345e-01 6.532947e-02 -5.472211e-01 -5.935333e+02 +-5.503828e-01 -3.947930e-02 8.339786e-01 9.817949e+02 3.088337e-02 9.972351e-01 6.758904e-02 2.842396e+01 -8.343410e-01 6.295590e-02 -5.476417e-01 -5.949757e+02 +-5.503592e-01 -3.822153e-02 8.340527e-01 9.839617e+02 3.237353e-02 9.972235e-01 6.706108e-02 2.855465e+01 -8.343001e-01 6.390890e-02 -5.475938e-01 -5.964211e+02 +-5.502465e-01 -3.801555e-02 8.341365e-01 9.861268e+02 3.522866e-02 9.970167e-01 6.867771e-02 2.868428e+01 -8.342588e-01 6.717516e-02 -5.472656e-01 -5.978687e+02 +-5.499773e-01 -3.656917e-02 8.343786e-01 9.882929e+02 3.744759e-02 9.969564e-01 6.837806e-02 2.881455e+01 -8.343396e-01 6.885184e-02 -5.469339e-01 -5.993177e+02 +-5.497537e-01 -3.514821e-02 8.345870e-01 9.904617e+02 3.858719e-02 9.969792e-01 6.740518e-02 2.894540e+01 -8.344350e-01 6.926060e-02 -5.467367e-01 -6.007664e+02 +-5.495194e-01 -3.520775e-02 8.347388e-01 9.926304e+02 3.886528e-02 9.969528e-01 6.763515e-02 2.907443e+01 -8.345765e-01 6.960917e-02 -5.464765e-01 -6.022122e+02 +-5.491390e-01 -3.568978e-02 8.349687e-01 9.947990e+02 3.896771e-02 9.969076e-01 6.823981e-02 2.920365e+01 -8.348221e-01 7.000994e-02 -5.460500e-01 -6.036558e+02 +-5.485848e-01 -3.552427e-02 8.353399e-01 9.969663e+02 3.886245e-02 9.969337e-01 6.791809e-02 2.933236e+01 -8.351912e-01 6.972217e-02 -5.455221e-01 -6.050961e+02 +-5.479865e-01 -3.468556e-02 8.357678e-01 9.991375e+02 3.821203e-02 9.970588e-01 6.643379e-02 2.945851e+01 -8.356139e-01 6.834119e-02 -5.450493e-01 -6.065369e+02 +-5.474074e-01 -3.461217e-02 8.361502e-01 1.001304e+03 3.781124e-02 9.971010e-01 6.602878e-02 2.958125e+01 -8.360116e-01 6.776051e-02 -5.445118e-01 -6.079732e+02 +-5.468532e-01 -3.517708e-02 8.364892e-01 1.003471e+03 3.800864e-02 9.970437e-01 6.677699e-02 2.970297e+01 -8.363653e-01 6.831102e-02 -5.438995e-01 -6.094078e+02 +-5.463162e-01 -3.695163e-02 8.367635e-01 1.005637e+03 3.793326e-02 9.969097e-01 6.879004e-02 2.982681e+01 -8.367195e-01 6.932227e-02 -5.432262e-01 -6.108397e+02 +-5.457976e-01 -3.898003e-02 8.370099e-01 1.007806e+03 3.724647e-02 9.968013e-01 7.070929e-02 2.995555e+01 -8.370888e-01 6.976861e-02 -5.425998e-01 -6.122697e+02 +-5.455799e-01 -4.045406e-02 8.370819e-01 1.009973e+03 3.551895e-02 9.968206e-01 7.132380e-02 3.008734e+01 -8.373058e-01 6.864508e-02 -5.424083e-01 -6.136954e+02 +-5.452264e-01 -3.889550e-02 8.373860e-01 1.012137e+03 3.458862e-02 9.970285e-01 6.883151e-02 3.021781e+01 -8.375749e-01 6.649277e-02 -5.422609e-01 -6.151186e+02 +-5.448414e-01 -3.822483e-02 8.376675e-01 1.014298e+03 3.338113e-02 9.971799e-01 6.721575e-02 3.034490e+01 -8.378744e-01 6.458419e-02 -5.420288e-01 -6.165381e+02 +-5.444560e-01 -3.796338e-02 8.379299e-01 1.016458e+03 3.427748e-02 9.971337e-01 6.744854e-02 3.047099e+01 -8.380887e-01 6.544487e-02 -5.415942e-01 -6.179592e+02 +-5.441087e-01 -3.800943e-02 8.381534e-01 1.018616e+03 3.548209e-02 9.970372e-01 6.824876e-02 3.059832e+01 -8.382641e-01 6.687416e-02 -5.411479e-01 -6.193811e+02 +-5.437373e-01 -3.675178e-02 8.384505e-01 1.020773e+03 3.622857e-02 9.970816e-01 6.719937e-02 3.072311e+01 -8.384732e-01 6.691465e-02 -5.408189e-01 -6.208006e+02 +-5.435794e-01 -3.612226e-02 8.385802e-01 1.022925e+03 3.759495e-02 9.970231e-01 6.731684e-02 3.084525e+01 -8.385154e-01 6.811841e-02 -5.406031e-01 -6.222172e+02 +-5.433033e-01 -3.622549e-02 8.387546e-01 1.025074e+03 3.929996e-02 9.968760e-01 6.851123e-02 3.096719e+01 -8.386161e-01 7.018538e-02 -5.401823e-01 -6.236311e+02 +-5.429270e-01 -3.403014e-02 8.390901e-01 1.027219e+03 4.171011e-02 9.968527e-01 6.741657e-02 3.108777e+01 -8.387434e-01 7.160081e-02 -5.397988e-01 -6.250420e+02 +-5.422457e-01 -3.379927e-02 8.395399e-01 1.029367e+03 4.268953e-02 9.967918e-01 6.770262e-02 3.120927e+01 -8.391348e-01 7.255100e-02 -5.390632e-01 -6.264527e+02 +-5.416384e-01 -3.513940e-02 8.398768e-01 1.031514e+03 4.190967e-02 9.967546e-01 6.873060e-02 3.133270e+01 -8.395662e-01 7.242608e-02 -5.384078e-01 -6.278572e+02 +-5.409550e-01 -3.630774e-02 8.402675e-01 1.033658e+03 3.845124e-02 9.969555e-01 6.783267e-02 3.145684e+01 -8.401721e-01 6.900373e-02 -5.379119e-01 -6.292527e+02 +-5.404372e-01 -3.945466e-02 8.404588e-01 1.035804e+03 3.349250e-02 9.970994e-01 6.834458e-02 3.158219e+01 -8.407175e-01 6.508500e-02 -5.375481e-01 -6.306416e+02 +-5.397773e-01 -4.008306e-02 8.408530e-01 1.037942e+03 3.015976e-02 9.973036e-01 6.690174e-02 3.170698e+01 -8.412674e-01 6.147195e-02 -5.371130e-01 -6.320242e+02 +-5.389445e-01 -3.930075e-02 8.414240e-01 1.040088e+03 2.807220e-02 9.975181e-01 6.457215e-02 3.182813e+01 -8.418734e-01 5.842142e-02 -5.365036e-01 -6.334108e+02 +-5.379388e-01 -3.805643e-02 8.421245e-01 1.042231e+03 2.958728e-02 9.975126e-01 6.397856e-02 3.194674e+01 -8.424645e-01 5.933271e-02 -5.354747e-01 -6.347988e+02 +-5.367965e-01 -3.857213e-02 8.428296e-01 1.044372e+03 3.114443e-02 9.973677e-01 6.548039e-02 3.206456e+01 -8.431367e-01 6.139908e-02 -5.341821e-01 -6.361849e+02 +-5.355808e-01 -3.847344e-02 8.436072e-01 1.046514e+03 3.297732e-02 9.972469e-01 6.641662e-02 3.218651e+01 -8.438398e-01 6.339135e-02 -5.328375e-01 -6.375675e+02 +-5.345253e-01 -3.841169e-02 8.442791e-01 1.048656e+03 3.436234e-02 9.971528e-01 6.712219e-02 3.231052e+01 -8.444536e-01 6.488990e-02 -5.316835e-01 -6.389462e+02 +-5.335690e-01 -3.687330e-02 8.449524e-01 1.050796e+03 3.398114e-02 9.973078e-01 6.498035e-02 3.243167e+01 -8.450736e-01 6.338393e-02 -5.308794e-01 -6.403174e+02 +-5.328425e-01 -3.505044e-02 8.454883e-01 1.052940e+03 3.358970e-02 9.974783e-01 6.252017e-02 3.254722e+01 -8.455475e-01 6.171309e-02 -5.303214e-01 -6.416850e+02 +-5.321070e-01 -3.374254e-02 8.460045e-01 1.055084e+03 3.484134e-02 9.974865e-01 6.169830e-02 3.265961e+01 -8.459599e-01 6.230601e-02 -5.295939e-01 -6.430515e+02 +-5.311356e-01 -3.497407e-02 8.465647e-01 1.057226e+03 3.704119e-02 9.972340e-01 6.443834e-02 3.277429e+01 -8.464767e-01 6.558325e-02 -5.283710e-01 -6.444173e+02 +-5.304844e-01 -3.806809e-02 8.468395e-01 1.059374e+03 3.788884e-02 9.969279e-01 6.854968e-02 3.289861e+01 -8.468475e-01 6.845029e-02 -5.274124e-01 -6.457840e+02 +-5.296565e-01 -3.954401e-02 8.472900e-01 1.061525e+03 3.656364e-02 9.969197e-01 6.938401e-02 3.302930e+01 -8.474237e-01 6.772969e-02 -5.265791e-01 -6.471441e+02 +-5.291392e-01 -4.250205e-02 8.474700e-01 1.063674e+03 3.172423e-02 9.970556e-01 6.981184e-02 3.316135e+01 -8.479418e-01 6.382550e-02 -5.262328e-01 -6.484919e+02 +-5.288308e-01 -4.329705e-02 8.476222e-01 1.065821e+03 2.799712e-02 9.972645e-01 6.840825e-02 3.329059e+01 -8.482653e-01 5.990736e-02 -5.261719e-01 -6.498375e+02 +-5.285037e-01 -4.307558e-02 8.478375e-01 1.067966e+03 2.679502e-02 9.973678e-01 6.737548e-02 3.341620e+01 -8.485080e-01 5.832600e-02 -5.259583e-01 -6.511855e+02 +-5.281628e-01 -4.163947e-02 8.481216e-01 1.070112e+03 2.679493e-02 9.974823e-01 6.565888e-02 3.353835e+01 -8.487202e-01 5.740392e-02 -5.257173e-01 -6.525347e+02 +-5.279950e-01 -4.015087e-02 8.482979e-01 1.072257e+03 2.790603e-02 9.975221e-01 6.458301e-02 3.365737e+01 -8.487888e-01 5.777212e-02 -5.255662e-01 -6.538847e+02 +-5.278709e-01 -3.886398e-02 8.484350e-01 1.074401e+03 2.956622e-02 9.975062e-01 6.408765e-02 3.377429e+01 -8.488098e-01 5.891501e-02 -5.254054e-01 -6.552353e+02 +-5.278019e-01 -3.706576e-02 8.485584e-01 1.076547e+03 3.291772e-02 9.974041e-01 6.404224e-02 3.389027e+01 -8.487294e-01 6.173421e-02 -5.252116e-01 -6.565901e+02 +-5.275716e-01 -3.665528e-02 8.487194e-01 1.078687e+03 3.484186e-02 9.972943e-01 6.473008e-02 3.400470e+01 -8.487958e-01 6.372070e-02 -5.248670e-01 -6.579412e+02 +-5.273678e-01 -3.935569e-02 8.487251e-01 1.080840e+03 3.402209e-02 9.971472e-01 6.737820e-02 3.412492e+01 -8.489556e-01 6.440848e-02 -5.245244e-01 -6.592934e+02 +-5.271365e-01 -3.918053e-02 8.488769e-01 1.082986e+03 3.380511e-02 9.971789e-01 6.701785e-02 3.424794e+01 -8.491079e-01 6.402392e-02 -5.243249e-01 -6.606391e+02 +-5.263838e-01 -3.562586e-02 8.495004e-01 1.085128e+03 3.506672e-02 9.973620e-01 6.355550e-02 3.436709e+01 -8.495236e-01 6.324376e-02 -5.237459e-01 -6.619814e+02 +-5.253784e-01 -3.101834e-02 8.503032e-01 1.087270e+03 3.918553e-02 9.973929e-01 6.059569e-02 3.448078e+01 -8.499659e-01 6.515523e-02 -5.227932e-01 -6.633284e+02 +-5.238240e-01 -2.923611e-02 8.513247e-01 1.089413e+03 4.077114e-02 9.974049e-01 5.933944e-02 3.458710e+01 -8.508502e-01 6.579289e-02 -5.212726e-01 -6.646693e+02 +-5.229823e-01 -3.085688e-02 8.517848e-01 1.091568e+03 4.168796e-02 9.972224e-01 6.172126e-02 3.469434e+01 -8.513234e-01 6.778829e-02 -5.202433e-01 -6.660140e+02 +-5.221043e-01 -2.889706e-02 8.523920e-01 1.093718e+03 4.211144e-02 9.973334e-01 5.960469e-02 3.480575e+01 -8.518413e-01 6.701530e-02 -5.194951e-01 -6.673474e+02 +-5.213969e-01 -3.492930e-02 8.525991e-01 1.095878e+03 3.904888e-02 9.971384e-01 6.473067e-02 3.492102e+01 -8.524203e-01 6.704340e-02 -5.185409e-01 -6.686777e+02 +-5.209506e-01 -3.930016e-02 8.526817e-01 1.098041e+03 3.786647e-02 9.968921e-01 6.908155e-02 3.504702e+01 -8.527465e-01 6.827610e-02 -5.178433e-01 -6.700112e+02 +-5.202820e-01 -3.976978e-02 8.530681e-01 1.100195e+03 3.908837e-02 9.967591e-01 7.030842e-02 3.517977e+01 -8.530995e-01 6.992523e-02 -5.170412e-01 -6.713409e+02 +-5.192332e-01 -3.745058e-02 8.538117e-01 1.102354e+03 4.001063e-02 9.968788e-01 6.805778e-02 3.531100e+01 -8.536955e-01 6.949939e-02 -5.161140e-01 -6.726726e+02 +-5.182364e-01 -3.465334e-02 8.545351e-01 1.104507e+03 4.023702e-02 9.970844e-01 6.483594e-02 3.543368e+01 -8.542904e-01 6.798427e-02 -5.153310e-01 -6.739958e+02 +-5.172653e-01 -3.497892e-02 8.551100e-01 1.106668e+03 3.945567e-02 9.971273e-01 6.465540e-02 3.554872e+01 -8.549151e-01 6.718292e-02 -5.143992e-01 -6.753171e+02 +-5.164039e-01 -3.575465e-02 8.555984e-01 1.108829e+03 3.949356e-02 9.970705e-01 6.550331e-02 3.566545e+01 -8.554340e-01 6.761678e-02 -5.134789e-01 -6.766374e+02 +-5.154866e-01 -3.610481e-02 8.561367e-01 1.110993e+03 3.957762e-02 9.970425e-01 6.587705e-02 3.578536e+01 -8.559831e-01 6.784258e-02 -5.125331e-01 -6.779581e+02 +-5.146440e-01 -3.737188e-02 8.565891e-01 1.113157e+03 3.924913e-02 9.969754e-01 6.707787e-02 3.590472e+01 -8.565051e-01 6.814158e-02 -5.116206e-01 -6.792720e+02 +-5.138482e-01 -3.859073e-02 8.570127e-01 1.115326e+03 3.938384e-02 9.968733e-01 6.850235e-02 3.602658e+01 -8.569766e-01 6.895225e-02 -5.107217e-01 -6.805868e+02 +-5.130265e-01 -3.837217e-02 8.575147e-01 1.117494e+03 3.911889e-02 9.969171e-01 6.801388e-02 3.614825e+01 -8.574809e-01 6.843794e-02 -5.099438e-01 -6.818958e+02 +-5.121516e-01 -3.677019e-02 8.581077e-01 1.119659e+03 3.949030e-02 9.970185e-01 6.629190e-02 3.626861e+01 -8.579867e-01 6.783841e-02 -5.091725e-01 -6.832010e+02 +-5.112027e-01 -3.633454e-02 8.586918e-01 1.121838e+03 3.921539e-02 9.970793e-01 6.553623e-02 3.638796e+01 -8.585650e-01 6.717622e-02 -5.082847e-01 -6.845117e+02 +-5.103242e-01 -3.756592e-02 8.591613e-01 1.124019e+03 3.820478e-02 9.970688e-01 6.628863e-02 3.651109e+01 -8.591330e-01 6.665274e-02 -5.073931e-01 -6.858237e+02 +-5.095496e-01 -3.781413e-02 8.596100e-01 1.126198e+03 3.824837e-02 9.970509e-01 6.653256e-02 3.663445e+01 -8.595907e-01 6.678030e-02 -5.066005e-01 -6.871319e+02 +-5.086589e-01 -3.613258e-02 8.602096e-01 1.128381e+03 3.915477e-02 9.971144e-01 6.503616e-02 3.675667e+01 -8.600773e-01 6.676252e-02 -5.057763e-01 -6.884392e+02 +-5.075778e-01 -3.497763e-02 8.608957e-01 1.130564e+03 3.864487e-02 9.972459e-01 6.330218e-02 3.687463e+01 -8.607388e-01 6.539997e-02 -5.048281e-01 -6.897431e+02 +-5.065972e-01 -3.485421e-02 8.614781e-01 1.132753e+03 3.822998e-02 9.972917e-01 6.283040e-02 3.699032e+01 -8.613348e-01 6.476399e-02 -5.038927e-01 -6.910464e+02 +-5.057981e-01 -3.389163e-02 8.619859e-01 1.134946e+03 3.856897e-02 9.973403e-01 6.184508e-02 3.710266e+01 -8.617892e-01 6.452701e-02 -5.031456e-01 -6.923504e+02 +-5.049198e-01 -3.308991e-02 8.625318e-01 1.137143e+03 3.883964e-02 9.973818e-01 6.099969e-02 3.721242e+01 -8.622920e-01 6.430036e-02 -5.023126e-01 -6.936540e+02 +-5.041816e-01 -3.300760e-02 8.629667e-01 1.139341e+03 3.923736e-02 9.973618e-01 6.107220e-02 3.732204e+01 -8.627058e-01 6.465200e-02 -5.015563e-01 -6.949554e+02 +-5.033773e-01 -3.346126e-02 8.634186e-01 1.141541e+03 3.941136e-02 9.973208e-01 6.162757e-02 3.743261e+01 -8.631674e-01 6.505041e-02 -5.007099e-01 -6.962551e+02 +-5.027135e-01 -3.389140e-02 8.637885e-01 1.143749e+03 3.903632e-02 9.973218e-01 6.184930e-02 3.754673e+01 -8.635713e-01 6.481158e-02 -5.000441e-01 -6.975560e+02 +-5.023498e-01 -3.525588e-02 8.639455e-01 1.145954e+03 3.785579e-02 9.973136e-01 6.270999e-02 3.766114e+01 -8.638354e-01 6.420767e-02 -4.996656e-01 -6.988522e+02 +-5.021790e-01 -3.558053e-02 8.640314e-01 1.148163e+03 3.679896e-02 9.973689e-01 6.245905e-02 3.777645e+01 -8.639803e-01 6.316107e-02 -4.995483e-01 -7.001487e+02 +-5.022953e-01 -3.581665e-02 8.639541e-01 1.150376e+03 3.555618e-02 9.974412e-01 6.202263e-02 3.789135e+01 -8.639648e-01 6.187256e-02 -4.997365e-01 -7.014450e+02 +-5.025890e-01 -3.683229e-02 8.637406e-01 1.152585e+03 3.537324e-02 9.973792e-01 6.311381e-02 3.800681e+01 -8.638015e-01 6.227359e-02 -4.999689e-01 -7.027408e+02 +-5.028628e-01 -3.664102e-02 8.635893e-01 1.154800e+03 3.577497e-02 9.973627e-01 6.314841e-02 3.812449e+01 -8.636255e-01 6.264986e-02 -5.002258e-01 -7.040408e+02 +-5.030194e-01 -3.510970e-02 8.635617e-01 1.157012e+03 3.622457e-02 9.974400e-01 6.165336e-02 3.824356e+01 -8.635156e-01 6.229497e-02 -5.004598e-01 -7.053377e+02 +-5.031328e-01 -3.599091e-02 8.634594e-01 1.159229e+03 3.680543e-02 9.973335e-01 6.301739e-02 3.836214e+01 -8.634250e-01 6.348609e-02 -5.004665e-01 -7.066378e+02 +-5.033083e-01 -3.555327e-02 8.633752e-01 1.161448e+03 3.787397e-02 9.972853e-01 6.314639e-02 3.848244e+01 -8.632765e-01 6.448153e-02 -5.005954e-01 -7.079363e+02 +-5.034927e-01 -3.274506e-02 8.633788e-01 1.163663e+03 3.877204e-02 9.974186e-01 6.043925e-02 3.860075e+01 -8.631291e-01 6.390566e-02 -5.009233e-01 -7.092369e+02 +-5.036455e-01 -3.330733e-02 8.632681e-01 1.165886e+03 3.899425e-02 9.973616e-01 6.123095e-02 3.871705e+01 -8.630299e-01 6.450117e-02 -5.010179e-01 -7.105384e+02 +-5.038034e-01 -3.526568e-02 8.630982e-01 1.168110e+03 3.807084e-02 9.972889e-01 6.297115e-02 3.883461e+01 -8.629790e-01 6.458394e-02 -5.010949e-01 -7.118436e+02 +-5.039031e-01 -3.504066e-02 8.630492e-01 1.170337e+03 3.829730e-02 9.972878e-01 6.285128e-02 3.895544e+01 -8.629108e-01 6.472339e-02 -5.011944e-01 -7.131505e+02 +-5.037058e-01 -3.305809e-02 8.632426e-01 1.172562e+03 3.933438e-02 9.973535e-01 6.114568e-02 3.907728e+01 -8.629793e-01 6.475453e-02 -5.010724e-01 -7.144590e+02 +-5.031224e-01 -3.041031e-02 8.636800e-01 1.174790e+03 4.071460e-02 9.974369e-01 5.883752e-02 3.919328e+01 -8.632556e-01 6.476685e-02 -5.005947e-01 -7.157678e+02 +-5.024903e-01 -3.102951e-02 8.640259e-01 1.177083e+03 4.142900e-02 9.973436e-01 5.991111e-02 3.930786e+01 -8.635897e-01 6.590047e-02 -4.998699e-01 -7.171122e+02 +-5.020098e-01 -3.281038e-02 8.642394e-01 1.179271e+03 4.146768e-02 9.972177e-01 6.194611e-02 3.941873e+01 -8.638672e-01 6.693554e-02 -4.992524e-01 -7.183940e+02 +-5.017803e-01 -3.616806e-02 8.642386e-01 1.181516e+03 4.143355e-02 9.969736e-01 6.577945e-02 3.954154e+01 -8.640021e-01 6.881529e-02 -4.987631e-01 -7.197105e+02 +-5.016674e-01 -3.743195e-02 8.642504e-01 1.183758e+03 4.127892e-02 9.968894e-01 6.713771e-02 3.967071e+01 -8.640752e-01 6.935610e-02 -4.985617e-01 -7.210223e+02 +-5.014015e-01 -3.761285e-02 8.643968e-01 1.186021e+03 4.043427e-02 9.969444e-01 6.683473e-02 3.980234e+01 -8.642694e-01 6.846227e-02 -4.983486e-01 -7.223448e+02 +-5.011283e-01 -3.664291e-02 8.645969e-01 1.188272e+03 3.934465e-02 9.971052e-01 6.506332e-02 3.993274e+01 -8.644781e-01 6.662232e-02 -4.982359e-01 -7.236591e+02 +-5.008074e-01 -3.594900e-02 8.648120e-01 1.190524e+03 3.913494e-02 9.971749e-01 6.411394e-02 4.006015e+01 -8.646736e-01 6.595308e-02 -4.979856e-01 -7.249743e+02 +-5.002405e-01 -3.607974e-02 8.651345e-01 1.192784e+03 3.954090e-02 9.971373e-01 6.444826e-02 4.018605e+01 -8.649832e-01 6.644781e-02 -4.973818e-01 -7.262948e+02 +-4.994819e-01 -3.515332e-02 8.656108e-01 1.195054e+03 3.989960e-02 9.971826e-01 6.351978e-02 4.030956e+01 -8.654050e-01 6.626449e-02 -4.966721e-01 -7.276201e+02 +-4.985463e-01 -3.378706e-02 8.662044e-01 1.197315e+03 4.053673e-02 9.972383e-01 6.222918e-02 4.043252e+01 -8.659147e-01 6.613720e-02 -4.957998e-01 -7.289370e+02 +-4.978729e-01 -3.237222e-02 8.666457e-01 1.199585e+03 4.102389e-02 9.973053e-01 6.082032e-02 4.055332e+01 -8.662792e-01 6.583395e-02 -4.952032e-01 -7.302584e+02 +-4.970255e-01 -3.263259e-02 8.671222e-01 1.201867e+03 4.126176e-02 9.972734e-01 6.118141e-02 4.067201e+01 -8.667543e-01 6.618769e-02 -4.943238e-01 -7.315819e+02 +-4.963348e-01 -3.341418e-02 8.674879e-01 1.204142e+03 4.194541e-02 9.971689e-01 6.240841e-02 4.079001e+01 -8.671172e-01 6.736258e-02 -4.935280e-01 -7.328978e+02 +-4.956990e-01 -3.323065e-02 8.678584e-01 1.206417e+03 4.220870e-02 9.971651e-01 6.229041e-02 4.090637e+01 -8.674681e-01 6.750846e-02 -4.928911e-01 -7.342126e+02 +-4.951215e-01 -3.371898e-02 8.681692e-01 1.208709e+03 4.247196e-02 9.971126e-01 6.294901e-02 4.102557e+01 -8.677850e-01 6.804024e-02 -4.922597e-01 -7.355340e+02 +-4.944594e-01 -3.504143e-02 8.684941e-01 1.210993e+03 4.168451e-02 9.970814e-01 6.396180e-02 4.114443e+01 -8.682006e-01 6.782925e-02 -4.915555e-01 -7.368459e+02 +-4.936828e-01 -3.478054e-02 8.689463e-01 1.213283e+03 4.165409e-02 9.971073e-01 6.357565e-02 4.126512e+01 -8.686439e-01 6.758135e-02 -4.908059e-01 -7.381592e+02 +-4.927929e-01 -3.458554e-02 8.694590e-01 1.215578e+03 4.250989e-02 9.970598e-01 6.375507e-02 4.138330e+01 -8.691076e-01 6.837864e-02 -4.898737e-01 -7.394756e+02 +-4.914235e-01 -3.376637e-02 8.702660e-01 1.217874e+03 4.315538e-02 9.970765e-01 6.305569e-02 4.150237e+01 -8.698509e-01 6.854369e-02 -4.885296e-01 -7.407904e+02 +-4.897948e-01 -3.214880e-02 8.712448e-01 1.220173e+03 4.339884e-02 9.971819e-01 6.119374e-02 4.161726e+01 -8.707569e-01 6.778338e-02 -4.870193e-01 -7.421052e+02 +-4.882299e-01 -3.093513e-02 8.721666e-01 1.222478e+03 4.327920e-02 9.972837e-01 5.960019e-02 4.172981e+01 -8.716412e-01 6.684526e-02 -4.855648e-01 -7.434152e+02 +-4.866466e-01 -2.912757e-02 8.731133e-01 1.224787e+03 4.363457e-02 9.973860e-01 5.759395e-02 4.183738e+01 -8.725085e-01 6.612581e-02 -4.841035e-01 -7.447223e+02 +-4.852072e-01 -2.865753e-02 8.739295e-01 1.227101e+03 4.392202e-02 9.974023e-01 5.709198e-02 4.194350e+01 -8.732953e-01 6.608618e-02 -4.826881e-01 -7.460279e+02 +-4.839808e-01 -2.937514e-02 8.745855e-01 1.229416e+03 4.405987e-02 9.973508e-01 5.788050e-02 4.204989e+01 -8.739687e-01 6.654716e-02 -4.814043e-01 -7.473281e+02 +-4.830361e-01 -3.069926e-02 8.750622e-01 1.231744e+03 4.274072e-02 9.973671e-01 5.858296e-02 4.215831e+01 -8.745567e-01 6.569845e-02 -4.804522e-01 -7.486314e+02 +-4.824974e-01 -3.015414e-02 8.753782e-01 1.234074e+03 4.149738e-02 9.974980e-01 5.723362e-02 4.226955e+01 -8.749138e-01 6.394096e-02 -4.800389e-01 -7.499294e+02 +-4.818709e-01 -2.891977e-02 8.757649e-01 1.236405e+03 4.054171e-02 9.976490e-01 5.525187e-02 4.237920e+01 -8.753038e-01 6.212926e-02 -4.795655e-01 -7.512267e+02 +-4.812640e-01 -2.785717e-02 8.761330e-01 1.238735e+03 4.022915e-02 9.977398e-01 5.382179e-02 4.248429e+01 -8.756520e-01 6.114856e-02 -4.790556e-01 -7.525197e+02 +-4.806926e-01 -2.658732e-02 8.764861e-01 1.241082e+03 4.127268e-02 9.977465e-01 5.290087e-02 4.258650e+01 -8.759173e-01 6.160397e-02 -4.785120e-01 -7.538235e+02 +-4.800560e-01 -2.679695e-02 8.768285e-01 1.243423e+03 4.189717e-02 9.976923e-01 5.342904e-02 4.268651e+01 -8.762367e-01 6.238555e-02 -4.778255e-01 -7.551203e+02 +-4.795872e-01 -2.704466e-02 8.770774e-01 1.245771e+03 4.237194e-02 9.976452e-01 5.393140e-02 4.278686e+01 -8.764706e-01 6.302826e-02 -4.773119e-01 -7.564194e+02 +-4.789601e-01 -2.763047e-02 8.774018e-01 1.248123e+03 4.198479e-02 9.976396e-01 5.433576e-02 4.288754e+01 -8.768321e-01 6.286217e-02 -4.766694e-01 -7.577175e+02 +-4.783352e-01 -2.882378e-02 8.777042e-01 1.250478e+03 4.131594e-02 9.976158e-01 5.527822e-02 4.299082e+01 -8.772049e-01 6.270468e-02 -4.760038e-01 -7.590137e+02 +-4.777230e-01 -2.987704e-02 8.780024e-01 1.252841e+03 4.093862e-02 9.975787e-01 5.622082e-02 4.309761e+01 -8.775561e-01 6.280217e-02 -4.753431e-01 -7.603120e+02 +-4.770816e-01 -3.079840e-02 8.783192e-01 1.255209e+03 4.074245e-02 9.975362e-01 5.710906e-02 4.320690e+01 -8.779141e-01 6.303055e-02 -4.746514e-01 -7.616116e+02 +-4.764179e-01 -3.243485e-02 8.786205e-01 1.257579e+03 4.162571e-02 9.973666e-01 5.938931e-02 4.332063e+01 -8.782330e-01 6.486732e-02 -4.738131e-01 -7.629110e+02 +-4.757567e-01 -3.155398e-02 8.790108e-01 1.259949e+03 4.252331e-02 9.973626e-01 5.881783e-02 4.343590e+01 -8.785484e-01 6.536141e-02 -4.731602e-01 -7.642087e+02 +-4.750737e-01 -2.886688e-02 8.794724e-01 1.262318e+03 4.213284e-02 9.975692e-01 5.550249e-02 4.354782e+01 -8.789367e-01 6.342243e-02 -4.727026e-01 -7.655015e+02 +-4.743670e-01 -2.406703e-02 8.799982e-01 1.264716e+03 4.159496e-02 9.978970e-01 4.971339e-02 4.365179e+01 -8.793439e-01 6.018586e-02 -4.723683e-01 -7.668074e+02 +-4.736037e-01 -1.816824e-02 8.805507e-01 1.267084e+03 4.172330e-02 9.982019e-01 4.303656e-02 4.373951e+01 -8.797492e-01 5.712174e-02 -4.719940e-01 -7.680952e+02 +-4.727143e-01 -1.714449e-02 8.810490e-01 1.269473e+03 4.211108e-02 9.982289e-01 4.201881e-02 4.381598e+01 -8.802090e-01 5.696480e-02 -4.711551e-01 -7.693932e+02 +-4.720049e-01 -1.949420e-02 8.813804e-01 1.271868e+03 4.262014e-02 9.980819e-01 4.489970e-02 4.389318e+01 -8.805651e-01 5.875742e-02 -4.702687e-01 -7.706928e+02 +-4.714063e-01 -2.046813e-02 8.816786e-01 1.274261e+03 4.231779e-02 9.980541e-01 4.579579e-02 4.397657e+01 -8.809003e-01 5.889910e-02 -4.696228e-01 -7.719869e+02 +-4.710468e-01 -2.340182e-02 8.817978e-01 1.276670e+03 4.182801e-02 9.979310e-01 4.882791e-02 4.406634e+01 -8.811159e-01 5.988406e-02 -4.690933e-01 -7.732870e+02 +-4.706896e-01 -2.523269e-02 8.819380e-01 1.279074e+03 4.141190e-02 9.978575e-01 5.065069e-02 4.415904e+01 -8.813265e-01 6.036346e-02 -4.686361e-01 -7.745821e+02 +-4.702340e-01 -2.543327e-02 8.821753e-01 1.281478e+03 4.185084e-02 9.978175e-01 5.107540e-02 4.425252e+01 -8.815489e-01 6.093715e-02 -4.681433e-01 -7.758763e+02 +-4.697773e-01 -2.548182e-02 8.824172e-01 1.283885e+03 4.201929e-02 9.978049e-01 5.118394e-02 4.434661e+01 -8.817844e-01 6.112358e-02 -4.676753e-01 -7.771708e+02 +-4.691742e-01 -2.447601e-02 8.827664e-01 1.286290e+03 4.199495e-02 9.978666e-01 4.998688e-02 4.443881e+01 -8.821066e-01 6.052427e-02 -4.671453e-01 -7.784617e+02 +-4.686361e-01 -2.366345e-02 8.830744e-01 1.288696e+03 4.167369e-02 9.979360e-01 4.885704e-02 4.452846e+01 -8.824078e-01 5.969712e-02 -4.666826e-01 -7.797516e+02 +-4.681761e-01 -2.201472e-02 8.833609e-01 1.291103e+03 4.169577e-02 9.980256e-01 4.697086e-02 4.461411e+01 -8.826508e-01 5.882303e-02 -4.663338e-01 -7.810407e+02 +-4.675683e-01 -2.099316e-02 8.837076e-01 1.293510e+03 4.225906e-02 9.980440e-01 4.606851e-02 4.469610e+01 -8.829462e-01 5.888481e-02 -4.657666e-01 -7.823282e+02 +-4.670401e-01 -2.177379e-02 8.839681e-01 1.295919e+03 4.229333e-02 9.980025e-01 4.692813e-02 4.477631e+01 -8.832241e-01 5.930326e-02 -4.651862e-01 -7.836147e+02 +-4.664224e-01 -2.271908e-02 8.842704e-01 1.298329e+03 4.184723e-02 9.979841e-01 4.771364e-02 4.485866e+01 -8.835717e-01 5.925897e-02 -4.645313e-01 -7.848990e+02 +-4.659909e-01 -2.233297e-02 8.845077e-01 1.300742e+03 4.178726e-02 9.980103e-01 4.721386e-02 4.494119e+01 -8.838022e-01 5.896236e-02 -4.641304e-01 -7.861825e+02 +-4.655366e-01 -2.258759e-02 8.847404e-01 1.303154e+03 4.168539e-02 9.980051e-01 4.741346e-02 4.502280e+01 -8.840463e-01 5.895343e-02 -4.636663e-01 -7.874640e+02 +-4.649276e-01 -2.138350e-02 8.850905e-01 1.305561e+03 4.229027e-02 9.980307e-01 4.632668e-02 4.510370e+01 -8.843381e-01 5.896925e-02 -4.631077e-01 -7.887421e+02 +-4.642827e-01 -1.980744e-02 8.854656e-01 1.307966e+03 4.264627e-02 9.980903e-01 4.468783e-02 4.518137e+01 -8.846597e-01 5.850957e-02 -4.625513e-01 -7.900173e+02 +-4.637683e-01 -1.810327e-02 8.857716e-01 1.310380e+03 4.307176e-02 9.981483e-01 4.295132e-02 4.525492e+01 -8.849089e-01 5.807119e-02 -4.621298e-01 -7.912954e+02 +-4.633665e-01 -1.774400e-02 8.859891e-01 1.312794e+03 4.306842e-02 9.981671e-01 4.251513e-02 4.532493e+01 -8.851195e-01 5.785823e-02 -4.617530e-01 -7.925713e+02 +-4.628104e-01 -1.850341e-02 8.862642e-01 1.315208e+03 4.257494e-02 9.981644e-01 4.307244e-02 4.539321e+01 -8.854343e-01 5.766701e-02 -4.611730e-01 -7.938437e+02 +-4.622418e-01 -2.039662e-02 8.865193e-01 1.317624e+03 4.251477e-02 9.980760e-01 4.513096e-02 4.546362e+01 -8.857341e-01 5.855157e-02 -4.604853e-01 -7.951168e+02 +-4.616834e-01 -1.965204e-02 8.868271e-01 1.320032e+03 4.395773e-02 9.980194e-01 4.500050e-02 4.553831e+01 -8.859549e-01 5.975888e-02 -4.599051e-01 -7.963846e+02 +-4.610104e-01 -1.804203e-02 8.872113e-01 1.322449e+03 4.442970e-02 9.980701e-01 4.338286e-02 4.562651e+01 -8.862818e-01 5.941847e-02 -4.593191e-01 -7.976481e+02 +-4.604053e-01 -1.812090e-02 8.875239e-01 1.324867e+03 4.409868e-02 9.980903e-01 4.325468e-02 4.570716e+01 -8.866128e-01 5.905331e-02 -4.587269e-01 -7.989070e+02 +-4.599869e-01 -1.855658e-02 8.877318e-01 1.327287e+03 4.317472e-02 9.981315e-01 4.323571e-02 4.580071e+01 -8.868754e-01 5.821542e-02 -4.583263e-01 -8.001723e+02 +-4.594641e-01 -1.777702e-02 8.880185e-01 1.329709e+03 4.256761e-02 9.982101e-01 4.200755e-02 4.586664e+01 -8.871757e-01 5.710177e-02 -4.578849e-01 -8.014285e+02 +-4.588565e-01 -1.549390e-02 8.883753e-01 1.332123e+03 4.186330e-02 9.983605e-01 3.903501e-02 4.592005e+01 -8.875236e-01 5.510178e-02 -4.574555e-01 -8.026887e+02 +-4.584249e-01 -1.394862e-02 8.886237e-01 1.334542e+03 4.163794e-02 9.984417e-01 3.715267e-02 4.596958e+01 -8.877572e-01 5.403216e-02 -4.571297e-01 -8.039500e+02 +-4.579285e-01 -1.459570e-02 8.888692e-01 1.336962e+03 4.179100e-02 9.984063e-01 3.792428e-02 4.601545e+01 -8.880062e-01 5.451333e-02 -4.565887e-01 -8.052106e+02 +-4.574775e-01 -1.539285e-02 8.890880e-01 1.339380e+03 4.295617e-02 9.983003e-01 3.938660e-02 4.606417e+01 -8.881830e-01 5.621028e-02 -4.560386e-01 -8.064689e+02 +-4.570247e-01 -1.638847e-02 8.893030e-01 1.341797e+03 4.310083e-02 9.982476e-01 4.054624e-02 4.611465e+01 -8.884091e-01 5.686032e-02 -4.555175e-01 -8.077231e+02 +-4.566051e-01 -1.532619e-02 8.895375e-01 1.344212e+03 4.242098e-02 9.983393e-01 3.897573e-02 4.616921e+01 -8.886575e-01 5.553156e-02 -4.551966e-01 -8.089741e+02 +-4.561369e-01 -1.415073e-02 8.897971e-01 1.346638e+03 4.159980e-02 9.984414e-01 3.720384e-02 4.621961e+01 -8.889367e-01 5.398542e-02 -4.548373e-01 -8.102296e+02 +-4.558015e-01 -1.351150e-02 8.899789e-01 1.349058e+03 4.146560e-02 9.984768e-01 3.639524e-02 4.627189e+01 -8.891150e-01 5.349250e-02 -4.545470e-01 -8.114819e+02 +-4.553181e-01 -1.245396e-02 8.902417e-01 1.351478e+03 4.176598e-02 9.985026e-01 3.532985e-02 4.632033e+01 -8.893486e-01 5.326813e-02 -4.541161e-01 -8.127339e+02 +-4.547521e-01 -1.244782e-02 8.905311e-01 1.353902e+03 4.197514e-02 9.984916e-01 3.539161e-02 4.636595e+01 -8.896283e-01 5.347457e-02 -4.535436e-01 -8.139856e+02 +-4.542477e-01 -1.307768e-02 8.907795e-01 1.356319e+03 4.258238e-02 9.984306e-01 3.637274e-02 4.641171e+01 -8.898572e-01 5.445373e-02 -4.529779e-01 -8.152327e+02 +-4.536658e-01 -1.372142e-02 8.910663e-01 1.358741e+03 4.260303e-02 9.984043e-01 3.706465e-02 4.645846e+01 -8.901530e-01 5.477708e-02 -4.523573e-01 -8.164808e+02 +-4.531468e-01 -1.363795e-02 8.913316e-01 1.361156e+03 4.217544e-02 9.984352e-01 3.671841e-02 4.650728e+01 -8.904376e-01 5.423112e-02 -4.518625e-01 -8.177234e+02 +-4.527136e-01 -1.390433e-02 8.915476e-01 1.363568e+03 4.179714e-02 9.984483e-01 3.679544e-02 4.655681e+01 -8.906758e-01 5.392192e-02 -4.514299e-01 -8.189605e+02 +-4.522222e-01 -1.282279e-02 8.918132e-01 1.365979e+03 4.208703e-02 9.984760e-01 3.569798e-02 4.660484e+01 -8.909117e-01 5.367717e-02 -4.509933e-01 -8.201971e+02 +-4.516635e-01 -1.330597e-02 8.920892e-01 1.368388e+03 4.170599e-02 9.984808e-01 3.600854e-02 4.665299e+01 -8.912130e-01 5.346919e-02 -4.504224e-01 -8.214312e+02 +-4.512406e-01 -1.308845e-02 8.923064e-01 1.370797e+03 4.172756e-02 9.984893e-01 3.574763e-02 4.670062e+01 -8.914262e-01 5.336454e-02 -4.500127e-01 -8.226635e+02 +-4.506717e-01 -1.260549e-02 8.926008e-01 1.373206e+03 4.172711e-02 9.985099e-01 3.516905e-02 4.674966e+01 -8.917140e-01 5.309534e-02 -4.494741e-01 -8.238932e+02 +-4.501576e-01 -1.202649e-02 8.928682e-01 1.375612e+03 4.206122e-02 9.985138e-01 3.465550e-02 4.679807e+01 -8.919579e-01 5.315554e-02 -4.489827e-01 -8.251194e+02 +-4.493873e-01 -1.021222e-02 8.932787e-01 1.378014e+03 4.308524e-02 9.985232e-01 3.309056e-02 4.684358e+01 -8.922974e-01 5.335759e-02 -4.482837e-01 -8.263424e+02 +-4.485076e-01 -9.481038e-03 8.937288e-01 1.380423e+03 4.352432e-02 9.985257e-01 3.243494e-02 4.688691e+01 -8.927186e-01 5.344624e-02 -4.474337e-01 -8.275660e+02 +-4.475542e-01 -8.030314e-03 8.942208e-01 1.382830e+03 4.359172e-02 9.985750e-01 3.078492e-02 4.692624e+01 -8.931937e-01 5.275853e-02 -4.465663e-01 -8.287850e+02 +-4.468154e-01 -7.428410e-03 8.945954e-01 1.385241e+03 4.340099e-02 9.986081e-01 2.996919e-02 4.696243e+01 -8.935728e-01 5.221700e-02 -4.458711e-01 -8.300028e+02 +-4.461190e-01 -6.109051e-03 8.949529e-01 1.387647e+03 4.298235e-02 9.986765e-01 2.824305e-02 4.699431e+01 -8.939409e-01 5.106692e-02 -4.452659e-01 -8.312155e+02 +-4.453789e-01 -6.296544e-03 8.953201e-01 1.390058e+03 4.204644e-02 9.987249e-01 2.793985e-02 4.702338e+01 -8.943543e-01 5.008883e-02 -4.445462e-01 -8.324280e+02 +-4.447396e-01 -6.797164e-03 8.956342e-01 1.392473e+03 4.116234e-02 9.987595e-01 2.801953e-02 4.705185e+01 -8.947135e-01 4.932778e-02 -4.439081e-01 -8.336398e+02 +-4.440097e-01 -7.494033e-03 8.959907e-01 1.394883e+03 4.056791e-02 9.987714e-01 2.845718e-02 4.707894e+01 -8.951031e-01 4.898372e-02 -4.431602e-01 -8.348470e+02 +-4.431812e-01 -7.331661e-03 8.964021e-01 1.397297e+03 4.064830e-02 9.987736e-01 2.826547e-02 4.710779e+01 -8.955099e-01 4.896394e-02 -4.423397e-01 -8.360545e+02 +-4.423161e-01 -7.928393e-03 8.968242e-01 1.399712e+03 4.083333e-02 9.987459e-01 2.896854e-02 4.713563e+01 -8.959291e-01 4.943356e-02 -4.414376e-01 -8.372586e+02 +-4.415503e-01 -7.757886e-03 8.972030e-01 1.402118e+03 4.109353e-02 9.987384e-01 2.885964e-02 4.716495e+01 -8.962949e-01 4.961221e-02 -4.406744e-01 -8.384586e+02 +-4.408141e-01 -6.864951e-03 8.975722e-01 1.404531e+03 4.206684e-02 9.987139e-01 2.829830e-02 4.719420e+01 -8.966121e-01 5.023230e-02 -4.399584e-01 -8.396596e+02 +-4.400229e-01 -6.675482e-03 8.979618e-01 1.406940e+03 4.260319e-02 9.986911e-01 2.830089e-02 4.722089e+01 -8.969753e-01 5.070907e-02 -4.391625e-01 -8.408560e+02 +-4.392519e-01 -6.508715e-03 8.983404e-01 1.409345e+03 4.344643e-02 9.986497e-01 2.847901e-02 4.724749e+01 -8.973127e-01 5.153913e-02 -4.383760e-01 -8.420488e+02 +-4.383762e-01 -4.929933e-03 8.987781e-01 1.411748e+03 4.373426e-02 9.986834e-01 2.680917e-02 4.727064e+01 -8.977269e-01 5.105988e-02 -4.375834e-01 -8.432372e+02 +-4.375662e-01 -4.113388e-03 8.991768e-01 1.414145e+03 4.385315e-02 9.987019e-01 2.590892e-02 4.729259e+01 -8.981162e-01 5.076859e-02 -4.368178e-01 -8.444199e+02 +-4.367389e-01 -3.102551e-03 8.995830e-01 1.416545e+03 4.374984e-02 9.987375e-01 2.468465e-02 4.731261e+01 -8.985238e-01 5.013735e-02 -4.360518e-01 -8.456026e+02 +-4.358876e-01 -1.574316e-03 8.999997e-01 1.418942e+03 4.471321e-02 9.987257e-01 2.340249e-02 4.732869e+01 -8.988897e-01 5.044272e-02 -4.352618e-01 -8.467820e+02 +-4.350416e-01 -1.159341e-03 9.004097e-01 1.421338e+03 4.516932e-02 9.987120e-01 2.310989e-02 4.734203e+01 -8.992767e-01 5.072464e-02 -4.344288e-01 -8.479587e+02 +-4.343995e-01 -2.052241e-03 9.007180e-01 1.423739e+03 4.460160e-02 9.987216e-01 2.378605e-02 4.735820e+01 -8.996153e-01 5.050610e-02 -4.337526e-01 -8.491316e+02 +-4.339416e-01 -1.842975e-03 9.009391e-01 1.426137e+03 4.385551e-02 9.987692e-01 2.316631e-02 4.737431e+01 -8.998729e-01 4.956396e-02 -4.333267e-01 -8.503038e+02 +-4.334386e-01 -1.343399e-03 9.011822e-01 1.428540e+03 4.357482e-02 9.987979e-01 2.244694e-02 4.739107e+01 -9.001290e-01 4.899821e-02 -4.328590e-01 -8.514737e+02 +-4.329478e-01 7.404537e-05 9.014190e-01 1.430939e+03 4.315982e-02 9.988548e-01 2.064743e-02 4.740614e+01 -9.003851e-01 4.784433e-02 -4.324551e-01 -8.526428e+02 +-4.323331e-01 1.401061e-03 9.017129e-01 1.433338e+03 4.286540e-02 9.989002e-01 1.900006e-02 4.741639e+01 -9.006945e-01 4.686663e-02 -4.319176e-01 -8.538098e+02 +-4.318036e-01 1.893540e-03 9.019657e-01 1.435735e+03 4.310806e-02 9.988983e-01 1.854034e-02 4.742141e+01 -9.009369e-01 4.688776e-02 -4.314095e-01 -8.549747e+02 +-4.312015e-01 1.795337e-03 9.022539e-01 1.438134e+03 4.309415e-02 9.988977e-01 1.860773e-02 4.742352e+01 -9.012259e-01 4.690553e-02 -4.308036e-01 -8.561389e+02 +-4.307241e-01 1.516974e-04 9.024837e-01 1.440537e+03 4.246544e-02 9.988957e-01 2.009937e-02 4.742646e+01 -9.014840e-01 4.698163e-02 -4.302548e-01 -8.573020e+02 +-4.302672e-01 3.617582e-04 9.027015e-01 1.442936e+03 4.193924e-02 9.989281e-01 1.958976e-02 4.743237e+01 -9.017268e-01 4.628744e-02 -4.298211e-01 -8.584621e+02 +-4.297253e-01 1.296619e-03 9.029588e-01 1.445330e+03 4.221789e-02 9.989342e-01 1.865738e-02 4.743887e+01 -9.019722e-01 4.613855e-02 -4.293220e-01 -8.596177e+02 +-4.289482e-01 8.136587e-04 9.033288e-01 1.447721e+03 4.221544e-02 9.989250e-01 1.914635e-02 4.744620e+01 -9.023421e-01 4.634720e-02 -4.285214e-01 -8.607713e+02 +-4.283672e-01 8.065164e-04 9.036044e-01 1.450116e+03 4.186370e-02 9.989435e-01 1.895449e-02 4.745202e+01 -9.026344e-01 4.594769e-02 -4.279484e-01 -8.619226e+02 +-4.279515e-01 1.090654e-03 9.038011e-01 1.452509e+03 4.158581e-02 9.989639e-01 1.848546e-02 4.745636e+01 -9.028444e-01 4.549616e-02 -4.275534e-01 -8.630706e+02 +-4.274579e-01 5.215355e-04 9.040351e-01 1.454899e+03 4.122704e-02 9.989707e-01 1.891721e-02 4.745953e+01 -9.030947e-01 4.535699e-02 -4.270394e-01 -8.642129e+02 +-4.269578e-01 -1.631143e-04 9.042716e-01 1.457288e+03 4.163262e-02 9.989360e-01 1.983730e-02 4.746458e+01 -9.033126e-01 4.611687e-02 -4.264967e-01 -8.653539e+02 +-4.263508e-01 -7.456581e-04 9.045576e-01 1.459672e+03 4.212068e-02 9.988985e-01 2.067642e-02 4.746995e+01 -9.035766e-01 4.691598e-02 -4.258498e-01 -8.664905e+02 +-4.257562e-01 -1.093507e-03 9.048373e-01 1.462058e+03 4.241997e-02 9.988756e-01 2.116716e-02 4.747405e+01 -9.038430e-01 4.739521e-02 -4.252311e-01 -8.676272e+02 +-4.251587e-01 -8.591846e-04 9.051184e-01 1.464432e+03 4.309736e-02 9.988461e-01 2.119215e-02 4.747977e+01 -9.040922e-01 4.801823e-02 -4.246311e-01 -8.687581e+02 +-4.245447e-01 -6.486388e-04 9.054068e-01 1.466807e+03 4.298163e-02 9.988578e-01 2.086964e-02 4.747599e+01 -9.043862e-01 4.777594e-02 -4.240319e-01 -8.698865e+02 +-4.240617e-01 -8.900667e-04 9.056329e-01 1.469182e+03 4.262046e-02 9.988719e-01 2.093868e-02 4.746689e+01 -9.046298e-01 4.747777e-02 -4.235454e-01 -8.710138e+02 +-4.233020e-01 -3.050497e-04 9.059886e-01 1.471550e+03 4.241106e-02 9.988970e-01 2.015190e-02 4.746029e+01 -9.049954e-01 4.695427e-02 -4.228221e-01 -8.721350e+02 +-4.228103e-01 6.555064e-06 9.062182e-01 1.473920e+03 4.267192e-02 9.988909e-01 1.990202e-02 4.745073e+01 -9.052129e-01 4.708484e-02 -4.223416e-01 -8.732573e+02 +-4.222627e-01 -1.799469e-04 9.064735e-01 1.476283e+03 4.245951e-02 9.988984e-01 1.997721e-02 4.743923e+01 -9.054785e-01 4.692404e-02 -4.217899e-01 -8.743734e+02 +-4.216964e-01 -3.894153e-04 9.067370e-01 1.478642e+03 4.232400e-02 9.989015e-01 2.011262e-02 4.742685e+01 -9.057487e-01 4.685814e-02 -4.212167e-01 -8.754851e+02 +-4.213519e-01 -8.263058e-04 9.068969e-01 1.481001e+03 4.227854e-02 9.988944e-01 2.055308e-02 4.742477e+01 -9.059112e-01 4.700234e-02 -4.208511e-01 -8.765934e+02 +-4.213238e-01 -1.291479e-03 9.069094e-01 1.483348e+03 4.156309e-02 9.989208e-01 2.073150e-02 4.742592e+01 -9.059574e-01 4.642862e-02 -4.208153e-01 -8.776953e+02 +-4.214195e-01 -2.631344e-03 9.068620e-01 1.485696e+03 4.104568e-02 9.989156e-01 2.197240e-02 4.743611e+01 -9.059364e-01 4.648236e-02 -4.208545e-01 -8.787965e+02 +-4.216268e-01 -3.387924e-03 9.067632e-01 1.488042e+03 4.161059e-02 9.988673e-01 2.308014e-02 4.744804e+01 -9.058142e-01 4.746214e-02 -4.210082e-01 -8.798970e+02 +-4.217234e-01 -3.761429e-03 9.067167e-01 1.490381e+03 4.155880e-02 9.988603e-01 2.347310e-02 4.745675e+01 -9.057716e-01 4.758121e-02 -4.210864e-01 -8.809934e+02 +-4.216739e-01 -4.360895e-03 9.067371e-01 1.492712e+03 4.118089e-02 9.988645e-01 2.395495e-02 4.746804e+01 -9.058119e-01 4.744141e-02 -4.210155e-01 -8.820850e+02 +-4.215525e-01 -3.800101e-03 9.067961e-01 1.495041e+03 4.064297e-02 9.989071e-01 2.308026e-02 4.747876e+01 -9.058927e-01 4.658442e-02 -4.209373e-01 -8.831750e+02 +-4.214202e-01 -3.904039e-03 9.068571e-01 1.497363e+03 4.026236e-02 9.989241e-01 2.301046e-02 4.749161e+01 -9.059713e-01 4.620927e-02 -4.208096e-01 -8.842612e+02 +-4.212827e-01 -5.427972e-03 9.069132e-01 1.499686e+03 3.990886e-02 9.989025e-01 2.451715e-02 4.751405e+01 -9.060508e-01 4.652251e-02 -4.206037e-01 -8.853464e+02 +-4.210012e-01 -4.289538e-03 9.070500e-01 1.501996e+03 4.116449e-02 9.988681e-01 2.382997e-02 4.753210e+01 -9.061255e-01 4.737068e-02 -4.203481e-01 -8.864270e+02 +-4.203835e-01 -2.312733e-03 9.073436e-01 1.504298e+03 4.143365e-02 9.989046e-01 2.174283e-02 4.754396e+01 -9.064000e-01 4.673487e-02 -4.198272e-01 -8.875023e+02 +-4.198049e-01 -2.796147e-03 9.076101e-01 1.506608e+03 4.168256e-02 9.988807e-01 2.235713e-02 4.755386e+01 -9.066567e-01 4.721713e-02 -4.192184e-01 -8.885793e+02 +-4.191708e-01 -3.871822e-03 9.078992e-01 1.508913e+03 4.296582e-02 9.987859e-01 2.409643e-02 4.756552e+01 -9.068901e-01 4.910914e-02 -4.184955e-01 -8.896524e+02 +-4.186422e-01 -5.166499e-03 9.081366e-01 1.511216e+03 4.348520e-02 9.987227e-01 2.572810e-02 4.758029e+01 -9.071095e-01 5.026136e-02 -4.178827e-01 -8.907229e+02 +-4.180522e-01 -3.871311e-03 9.084148e-01 1.513510e+03 4.362082e-02 9.987518e-01 2.433057e-02 4.759751e+01 -9.073751e-01 4.979723e-02 -4.173615e-01 -8.917874e+02 +-4.175271e-01 -2.714199e-03 9.086605e-01 1.515801e+03 4.413380e-02 9.987547e-01 2.326267e-02 4.761124e+01 -9.075920e-01 4.981542e-02 -4.168873e-01 -8.928485e+02 +-4.168562e-01 -1.810196e-03 9.089707e-01 1.518096e+03 4.425264e-02 9.987718e-01 2.228339e-02 4.762399e+01 -9.078946e-01 4.951331e-02 -4.162640e-01 -8.939096e+02 +-4.163398e-01 -2.818590e-03 9.092047e-01 1.520388e+03 4.379281e-02 9.987724e-01 2.314970e-02 4.763313e+01 -9.081538e-01 4.945476e-02 -4.157052e-01 -8.949665e+02 +-4.157740e-01 -4.596890e-03 9.094564e-01 1.522676e+03 4.362042e-02 9.987356e-01 2.498999e-02 4.764596e+01 -9.084213e-01 5.006105e-02 -4.150477e-01 -8.960191e+02 +-4.153066e-01 -5.407107e-03 9.096654e-01 1.524961e+03 4.369478e-02 9.987095e-01 2.588518e-02 4.766736e+01 -9.086314e-01 5.049791e-02 -4.145344e-01 -8.970705e+02 +-4.146836e-01 -6.265259e-03 9.099442e-01 1.527242e+03 4.329189e-02 9.987081e-01 2.660558e-02 4.768706e+01 -9.089353e-01 5.042608e-02 -4.138766e-01 -8.981170e+02 +-4.141134e-01 -5.765739e-03 9.102071e-01 1.529523e+03 4.354750e-02 9.987093e-01 2.613899e-02 4.770517e+01 -9.091829e-01 5.046173e-02 -4.133278e-01 -8.991623e+02 +-4.134721e-01 -3.057610e-03 9.105117e-01 1.531795e+03 4.374900e-02 9.987726e-01 2.322083e-02 4.772020e+01 -9.094651e-01 4.943512e-02 -4.128308e-01 -9.002017e+02 +-4.127471e-01 -5.885758e-04 9.108455e-01 1.534067e+03 4.408609e-02 9.988148e-01 2.062291e-02 4.773131e+01 -9.097781e-01 4.866765e-02 -4.122320e-01 -9.012401e+02 +-4.120512e-01 -2.077011e-03 9.111583e-01 1.536337e+03 4.372837e-02 9.988000e-01 2.205198e-02 4.773818e+01 -9.101107e-01 4.893000e-02 -4.114659e-01 -9.022742e+02 +-4.114881e-01 -4.698936e-03 9.114031e-01 1.538605e+03 4.330304e-02 9.987566e-01 2.470013e-02 4.775082e+01 -9.103858e-01 4.963031e-02 -4.107729e-01 -9.033060e+02 +-4.109377e-01 -8.137194e-03 9.116271e-01 1.540873e+03 4.298603e-02 9.986750e-01 2.829116e-02 4.776928e+01 -9.106494e-01 5.081312e-02 -4.100434e-01 -9.043349e+02 +-4.104003e-01 -8.466604e-03 9.118662e-01 1.543134e+03 4.316855e-02 9.986554e-01 2.870114e-02 4.779346e+01 -9.108831e-01 5.114288e-02 -4.094829e-01 -9.053584e+02 +-4.098924e-01 -7.215828e-03 9.121054e-01 1.545392e+03 4.264259e-02 9.987237e-01 2.706429e-02 4.781679e+01 -9.111365e-01 4.998797e-02 -4.090615e-01 -9.063787e+02 +-4.090887e-01 -5.394616e-03 9.124787e-01 1.547641e+03 4.250447e-02 9.987844e-01 2.496075e-02 4.783343e+01 -9.115041e-01 4.899557e-02 -4.083621e-01 -9.073939e+02 +-4.083700e-01 -4.332459e-03 9.128062e-01 1.549884e+03 4.407901e-02 9.987285e-01 2.446027e-02 4.784794e+01 -9.117516e-01 5.022442e-02 -4.076598e-01 -9.084067e+02 +-4.076285e-01 -5.019878e-03 9.131341e-01 1.552134e+03 4.453146e-02 9.986858e-01 2.536930e-02 4.786034e+01 -9.120613e-01 5.100443e-02 -4.068692e-01 -9.094203e+02 +-4.072216e-01 -6.471444e-03 9.133065e-01 1.554374e+03 4.317673e-02 9.987205e-01 2.632813e-02 4.787274e+01 -9.123082e-01 5.015496e-02 -4.064211e-01 -9.104252e+02 +-4.074005e-01 -7.939396e-03 9.132151e-01 1.556611e+03 4.216223e-02 9.987324e-01 2.749214e-02 4.788768e+01 -9.122758e-01 4.970348e-02 -4.065493e-01 -9.114271e+02 +-4.079076e-01 -8.854263e-03 9.129803e-01 1.558842e+03 4.101198e-02 9.987659e-01 2.800984e-02 4.790468e+01 -9.121016e-01 4.886854e-02 -4.070410e-01 -9.124266e+02 +-4.087268e-01 -1.094511e-02 9.125912e-01 1.561071e+03 4.029120e-02 9.987368e-01 3.002371e-02 4.792615e+01 -9.117670e-01 4.904088e-02 -4.077694e-01 -9.134263e+02 +-4.095265e-01 -1.088907e-02 9.122332e-01 1.563292e+03 4.079286e-02 9.987101e-01 3.023435e-02 4.794997e+01 -9.113857e-01 4.959436e-02 -4.085541e-01 -9.144261e+02 +-4.102545e-01 -9.769812e-03 9.119188e-01 1.565507e+03 4.114888e-02 9.987259e-01 2.921189e-02 4.797397e+01 -9.110422e-01 4.950873e-02 -4.093298e-01 -9.154256e+02 +-4.109523e-01 -9.193792e-03 9.116105e-01 1.567716e+03 4.054410e-02 9.987755e-01 2.835007e-02 4.799707e+01 -9.107548e-01 4.861095e-02 -4.100763e-01 -9.164241e+02 +-4.115826e-01 -9.531422e-03 9.113227e-01 1.569920e+03 4.036102e-02 9.987736e-01 2.867439e-02 4.801985e+01 -9.104783e-01 4.858378e-02 -4.106931e-01 -9.174222e+02 +-4.121763e-01 -9.627893e-03 9.110533e-01 1.572126e+03 3.985681e-02 9.987964e-01 2.858706e-02 4.804377e+01 -9.102319e-01 4.809457e-02 -4.112964e-01 -9.184232e+02 +-4.128402e-01 -1.068480e-02 9.107408e-01 1.574331e+03 3.982414e-02 9.987631e-01 2.976981e-02 4.806802e+01 -9.099324e-01 4.855963e-02 -4.119041e-01 -9.194263e+02 +-4.135007e-01 -9.862737e-03 9.104504e-01 1.576528e+03 4.058907e-02 9.987476e-01 2.925364e-02 4.809301e+01 -9.095986e-01 4.905073e-02 -4.125824e-01 -9.204289e+02 +-4.140446e-01 -9.090209e-03 9.102112e-01 1.578723e+03 4.070736e-02 9.987648e-01 2.849189e-02 4.811923e+01 -9.093459e-01 4.884920e-02 -4.131631e-01 -9.214312e+02 +-4.147282e-01 -8.807796e-03 9.099028e-01 1.580910e+03 4.066240e-02 9.987748e-01 2.820174e-02 4.814314e+01 -9.090363e-01 4.869488e-02 -4.138619e-01 -9.224315e+02 +-4.155247e-01 -8.597172e-03 9.095413e-01 1.583106e+03 4.133159e-02 9.987440e-01 2.832270e-02 4.816606e+01 -9.086423e-01 4.936156e-02 -4.146474e-01 -9.234386e+02 +-4.166357e-01 -8.618182e-03 9.090327e-01 1.585294e+03 4.142320e-02 9.987364e-01 2.845406e-02 4.818910e+01 -9.081293e-01 4.951001e-02 -4.157522e-01 -9.244438e+02 +-4.183437e-01 -9.871278e-03 9.082352e-01 1.587477e+03 4.061757e-02 9.987373e-01 2.956383e-02 4.821155e+01 -9.073801e-01 4.925814e-02 -4.174145e-01 -9.254494e+02 +-4.206667e-01 -1.117204e-02 9.071465e-01 1.589656e+03 3.971371e-02 9.987388e-01 3.071629e-02 4.823639e+01 -9.063456e-01 4.894746e-02 -4.196924e-01 -9.264574e+02 +-4.231883e-01 -1.237618e-02 9.059572e-01 1.591825e+03 3.842070e-02 9.987621e-01 3.159095e-02 4.826260e+01 -9.052267e-01 4.817642e-02 -4.221889e-01 -9.274666e+02 +-4.256683e-01 -1.316031e-02 9.047836e-01 1.593998e+03 3.804936e-02 9.987495e-01 3.242792e-02 4.829025e+01 -9.040789e-01 4.822997e-02 -4.246352e-01 -9.284840e+02 +-4.281436e-01 -1.329417e-02 9.036129e-01 1.596156e+03 3.837214e-02 9.987226e-01 3.287467e-02 4.831939e+01 -9.028956e-01 4.874863e-02 -4.270866e-01 -9.295025e+02 +-4.304913e-01 -1.352137e-02 9.024935e-01 1.598309e+03 3.814354e-02 9.987220e-01 3.315763e-02 4.834906e+01 -9.017883e-01 4.869836e-02 -4.294254e-01 -9.305255e+02 +-4.330003e-01 -1.346674e-02 9.012932e-01 1.600456e+03 3.720227e-02 9.987694e-01 3.279594e-02 4.837802e+01 -9.006257e-01 4.773080e-02 -4.319665e-01 -9.315523e+02 +-4.357487e-01 -1.337277e-02 8.999691e-01 1.602594e+03 3.647518e-02 9.988059e-01 3.250201e-02 4.840548e+01 -8.993290e-01 4.698923e-02 -4.347406e-01 -9.325808e+02 +-4.386786e-01 -1.359226e-02 8.985413e-01 1.604728e+03 3.563269e-02 9.988361e-01 3.250572e-02 4.843406e+01 -8.979373e-01 4.627699e-02 -4.376837e-01 -9.336148e+02 +-4.415746e-01 -1.445748e-02 8.971081e-01 1.606851e+03 3.561672e-02 9.987996e-01 3.362756e-02 4.846143e+01 -8.965173e-01 4.680111e-02 -4.405295e-01 -9.346535e+02 +-4.438257e-01 -1.472488e-02 8.959922e-01 1.608968e+03 3.692825e-02 9.987151e-01 3.470528e-02 4.849195e+01 -8.953519e-01 4.849050e-02 -4.427116e-01 -9.356991e+02 +-4.459256e-01 -1.584629e-02 8.949298e-01 1.611079e+03 3.719115e-02 9.986517e-01 3.621447e-02 4.852624e+01 -8.942970e-01 4.943241e-02 -4.447350e-01 -9.367470e+02 +-4.479351e-01 -1.562821e-02 8.939295e-01 1.613177e+03 3.722906e-02 9.986540e-01 3.611400e-02 4.856114e+01 -8.932906e-01 4.945687e-02 -4.467503e-01 -9.377953e+02 +-4.498476e-01 -1.563229e-02 8.929686e-01 1.615276e+03 3.673874e-02 9.986766e-01 3.599055e-02 4.859697e+01 -8.923494e-01 4.899679e-02 -4.486779e-01 -9.388488e+02 +-4.517221e-01 -1.582913e-02 8.920183e-01 1.617365e+03 3.630212e-02 9.986884e-01 3.610557e-02 4.863325e+01 -8.914198e-01 4.869183e-02 -4.505549e-01 -9.399034e+02 +-4.534910e-01 -1.676726e-02 8.911031e-01 1.619446e+03 3.640867e-02 9.986399e-01 3.731942e-02 4.867009e+01 -8.905168e-01 4.936789e-02 -4.522637e-01 -9.409606e+02 +-4.545884e-01 -1.524846e-02 8.905711e-01 1.621514e+03 3.779730e-02 9.986225e-01 3.639200e-02 4.870767e+01 -8.898993e-01 5.020456e-02 -4.533858e-01 -9.420174e+02 +-4.552092e-01 -1.459109e-02 8.902650e-01 1.623582e+03 3.977792e-02 9.985341e-01 3.670477e-02 4.874551e+01 -8.894955e-01 5.212122e-02 -4.539615e-01 -9.430798e+02 +-4.557221e-01 -1.334544e-02 8.900221e-01 1.625639e+03 4.106013e-02 9.985080e-01 3.599633e-02 4.878112e+01 -8.891745e-01 5.294873e-02 -4.544942e-01 -9.441387e+02 +-4.564350e-01 -1.141528e-02 8.896835e-01 1.627692e+03 4.109182e-02 9.985803e-01 3.389387e-02 4.881364e+01 -8.888073e-01 5.202905e-02 -4.553179e-01 -9.451948e+02 +-4.570505e-01 -1.108080e-02 8.893717e-01 1.629739e+03 3.964558e-02 9.986747e-01 3.281658e-02 4.884336e+01 -8.885567e-01 5.025849e-02 -4.560055e-01 -9.462493e+02 +-4.576683e-01 -1.104152e-02 8.890545e-01 1.631780e+03 3.910888e-02 9.987051e-01 3.253581e-02 4.887178e+01 -8.882624e-01 4.966052e-02 -4.566438e-01 -9.473020e+02 +-4.581958e-01 -1.066483e-02 8.887874e-01 1.633819e+03 3.933739e-02 9.987050e-01 3.226333e-02 4.889792e+01 -8.879804e-01 4.974548e-02 -4.571828e-01 -9.483574e+02 +-4.586472e-01 -9.302314e-03 8.885698e-01 1.635848e+03 4.000421e-02 9.987153e-01 3.110411e-02 4.892252e+01 -8.877175e-01 4.981234e-02 -4.576858e-01 -9.494093e+02 +-4.588527e-01 -1.016203e-02 8.884543e-01 1.637876e+03 4.016529e-02 9.986751e-01 3.216655e-02 4.894713e+01 -8.876040e-01 5.044472e-02 -4.578365e-01 -9.504616e+02 +-4.589215e-01 -1.142128e-02 8.884034e-01 1.639898e+03 3.972457e-02 9.986536e-01 3.335912e-02 4.897459e+01 -8.875883e-01 5.060065e-02 -4.578499e-01 -9.515090e+02 +-4.587044e-01 -1.029289e-02 8.885293e-01 1.641905e+03 3.987364e-02 9.986872e-01 3.215379e-02 4.900261e+01 -8.876938e-01 5.017797e-02 -4.576918e-01 -9.525509e+02 +-4.582282e-01 -1.086147e-02 8.887682e-01 1.643920e+03 3.999595e-02 9.986605e-01 3.282542e-02 4.903083e+01 -8.879342e-01 5.058865e-02 -4.571800e-01 -9.535981e+02 +-4.571762e-01 -1.260490e-02 8.892869e-01 1.645927e+03 3.876005e-02 9.986671e-01 3.408155e-02 4.906123e+01 -8.885311e-01 5.005007e-02 -4.560782e-01 -9.546358e+02 +-4.561798e-01 -1.380230e-02 8.897806e-01 1.647929e+03 4.017898e-02 9.985405e-01 3.608866e-02 4.909362e+01 -8.889801e-01 5.221338e-02 -4.549595e-01 -9.556718e+02 +-4.544318e-01 -1.675632e-02 8.906240e-01 1.649931e+03 4.130967e-02 9.983509e-01 3.986094e-02 4.913070e+01 -8.898231e-01 5.490544e-02 -4.529902e-01 -9.567025e+02 +-4.526643e-01 -1.878678e-02 8.914831e-01 1.651926e+03 4.184379e-02 9.982290e-01 4.228313e-02 4.917785e+01 -8.906986e-01 5.644308e-02 -4.510765e-01 -9.577232e+02 +-4.511600e-01 -1.964903e-02 8.922268e-01 1.653922e+03 4.075170e-02 9.982611e-01 4.259052e-02 4.922771e+01 -8.915121e-01 5.557488e-02 -4.495748e-01 -9.587392e+02 +-4.492144e-01 -1.781738e-02 8.932464e-01 1.655907e+03 3.822723e-02 9.985022e-01 3.914139e-02 4.927404e+01 -8.926058e-01 5.172920e-02 -4.478604e-01 -9.597429e+02 +-4.469770e-01 -9.115964e-03 8.944990e-01 1.657888e+03 4.213817e-02 9.986235e-01 3.123335e-02 4.931059e+01 -8.935524e-01 5.165312e-02 -4.459776e-01 -9.607445e+02 +-4.442249e-01 -5.603634e-03 8.958978e-01 1.659868e+03 4.454230e-02 9.986056e-01 2.833204e-02 4.933671e+01 -8.948073e-01 5.249114e-02 -4.433558e-01 -9.617407e+02 +-4.414256e-01 -8.985450e-03 8.972529e-01 1.661857e+03 4.608914e-02 9.984028e-01 3.267308e-02 4.936368e+01 -8.961134e-01 5.577634e-02 -4.403064e-01 -9.627322e+02 +-4.384893e-01 -1.020494e-02 8.986785e-01 1.663845e+03 4.665346e-02 9.983289e-01 3.409999e-02 4.939845e+01 -8.975247e-01 5.687893e-02 -4.372804e-01 -9.637141e+02 +-4.360327e-01 -1.279549e-02 8.998399e-01 1.665835e+03 4.595345e-02 9.982779e-01 3.646277e-02 4.943882e+01 -8.987568e-01 5.724969e-02 -4.346938e-01 -9.646864e+02 +-4.339565e-01 -1.519535e-02 9.008057e-01 1.667828e+03 4.473483e-02 9.982610e-01 3.838995e-02 4.948118e+01 -8.998225e-01 5.695694e-02 -4.325220e-01 -9.656520e+02 +-4.322282e-01 -1.467230e-02 9.016449e-01 1.669813e+03 4.510260e-02 9.982644e-01 3.786574e-02 4.952421e+01 -9.006356e-01 5.703316e-02 -4.308163e-01 -9.666100e+02 +-4.306709e-01 -1.319839e-02 9.024126e-01 1.671797e+03 4.708549e-02 9.982027e-01 3.707065e-02 4.956456e+01 -9.012799e-01 5.845577e-02 -4.292754e-01 -9.675649e+02 +-4.289901e-01 -1.489036e-02 9.031865e-01 1.673786e+03 4.775220e-02 9.980922e-01 3.913607e-02 4.960599e+01 -9.020461e-01 5.991812e-02 -4.274606e-01 -9.685170e+02 +-4.276366e-01 -1.595066e-02 9.038100e-01 1.675782e+03 4.603490e-02 9.981626e-01 3.939716e-02 4.965130e+01 -9.027778e-01 5.845446e-02 -4.261165e-01 -9.694644e+02 +-4.271062e-01 -1.697163e-02 9.040422e-01 1.677761e+03 4.370839e-02 9.982675e-01 3.939013e-02 4.969653e+01 -9.031444e-01 5.633798e-02 -4.256244e-01 -9.703985e+02 +-4.268472e-01 -1.675697e-02 9.041685e-01 1.679740e+03 4.187379e-02 9.983896e-01 3.827128e-02 4.974000e+01 -9.033538e-01 5.419694e-02 -4.254581e-01 -9.713312e+02 +-4.264020e-01 -1.762622e-02 9.043620e-01 1.681723e+03 3.991334e-02 9.984696e-01 3.827932e-02 4.978185e+01 -9.036527e-01 5.241848e-02 -4.250459e-01 -9.722641e+02 +-4.260693e-01 -1.862467e-02 9.044988e-01 1.683703e+03 3.898819e-02 9.984812e-01 3.892548e-02 4.982334e+01 -9.038500e-01 5.184971e-02 -4.246960e-01 -9.731964e+02 +-4.259164e-01 -1.948363e-02 9.045527e-01 1.685682e+03 3.873070e-02 9.984590e-01 3.974301e-02 4.986559e+01 -9.039331e-01 5.196115e-02 -4.245054e-01 -9.741288e+02 +-4.258981e-01 -1.897799e-02 9.045721e-01 1.687655e+03 3.967661e-02 9.984264e-01 3.962792e-02 4.990905e+01 -9.039007e-01 5.276780e-02 -4.244749e-01 -9.750597e+02 +-4.258275e-01 -1.911967e-02 9.046024e-01 1.689621e+03 3.922920e-02 9.984464e-01 3.956969e-02 4.995262e+01 -9.039535e-01 5.233667e-02 -4.244159e-01 -9.759855e+02 +-4.258707e-01 -1.864644e-02 9.045919e-01 1.691585e+03 3.931747e-02 9.984618e-01 3.909156e-02 4.999582e+01 -9.039293e-01 5.221421e-02 -4.244825e-01 -9.769105e+02 +-4.259242e-01 -1.796021e-02 9.045806e-01 1.693546e+03 3.924694e-02 9.984951e-01 3.830438e-02 5.003776e+01 -9.039072e-01 5.181677e-02 -4.245783e-01 -9.778338e+02 +-4.257577e-01 -1.798169e-02 9.046585e-01 1.695506e+03 3.998007e-02 9.984522e-01 3.866175e-02 5.007832e+01 -9.039535e-01 5.262883e-02 -4.243798e-01 -9.787577e+02 +-4.252649e-01 -1.878445e-02 9.048740e-01 1.697460e+03 4.078557e-02 9.983712e-01 3.989342e-02 5.012017e+01 -9.041495e-01 5.387106e-02 -4.238060e-01 -9.796789e+02 +-4.246267e-01 -2.004468e-02 9.051466e-01 1.699416e+03 4.164701e-02 9.982641e-01 4.164443e-02 5.016515e+01 -9.044101e-01 5.537997e-02 -4.230548e-01 -9.805994e+02 +-4.239562e-01 -1.983420e-02 9.054655e-01 1.701378e+03 4.150721e-02 9.982842e-01 4.130185e-02 5.021139e+01 -9.047310e-01 5.509350e-02 -4.224055e-01 -9.815203e+02 +-4.234708e-01 -2.034466e-02 9.056813e-01 1.703321e+03 4.241405e-02 9.982062e-01 4.225468e-02 5.025832e+01 -9.049163e-01 5.630722e-02 -4.218483e-01 -9.824311e+02 +-4.225106e-01 -2.135127e-02 9.061065e-01 1.705258e+03 4.089649e-02 9.982551e-01 4.259235e-02 5.030572e+01 -9.054348e-01 5.505228e-02 -4.209001e-01 -9.833354e+02 +-4.217969e-01 -2.174798e-02 9.064295e-01 1.707206e+03 4.103037e-02 9.982303e-01 4.304358e-02 5.035512e+01 -9.057614e-01 5.534677e-02 -4.201581e-01 -9.842435e+02 +-4.205769e-01 -2.270020e-02 9.069729e-01 1.709144e+03 4.172128e-02 9.981454e-01 4.432889e-02 5.040598e+01 -9.062970e-01 5.648376e-02 -4.188498e-01 -9.851451e+02 +-4.190212e-01 -2.055121e-02 9.077439e-01 1.711078e+03 4.313329e-02 9.981645e-01 4.250895e-02 5.045685e+01 -9.069513e-01 5.696612e-02 -4.173656e-01 -9.860442e+02 +-4.173166e-01 -1.717224e-02 9.085989e-01 1.713011e+03 4.462982e-02 9.982277e-01 3.936453e-02 5.050409e+01 -9.076646e-01 5.697807e-02 -4.158106e-01 -9.869390e+02 +-4.157161e-01 -1.647886e-02 9.093452e-01 1.714950e+03 4.433244e-02 9.982802e-01 3.835752e-02 5.054622e+01 -9.084133e-01 5.625931e-02 -4.142705e-01 -9.878314e+02 +-4.142656e-01 -2.002378e-02 9.099358e-01 1.716881e+03 4.352983e-02 9.981780e-01 4.178339e-02 5.058931e+01 -9.091145e-01 5.691875e-02 -4.126391e-01 -9.887143e+02 +-4.129037e-01 -2.332800e-02 9.104759e-01 1.718815e+03 4.151617e-02 9.981507e-01 4.440210e-02 5.063886e+01 -9.098279e-01 5.613325e-02 -4.111716e-01 -9.895928e+02 +-4.115483e-01 -2.473077e-02 9.110524e-01 1.720748e+03 4.005045e-02 9.981753e-01 4.518767e-02 5.069222e+01 -9.105075e-01 5.508495e-02 -4.098069e-01 -9.904667e+02 +-4.101367e-01 -2.653642e-02 9.116380e-01 1.722678e+03 3.934141e-02 9.981314e-01 4.675342e-02 5.074708e+01 -9.111751e-01 5.504040e-02 -4.083263e-01 -9.913366e+02 +-4.087440e-01 -2.711979e-02 9.122461e-01 1.724608e+03 3.932092e-02 9.981069e-01 4.729057e-02 5.080392e+01 -9.118016e-01 5.520008e-02 -4.069038e-01 -9.922037e+02 +-4.073065e-01 -2.565541e-02 9.129312e-01 1.726528e+03 3.886076e-02 9.982132e-01 4.538985e-02 5.085882e+01 -9.124644e-01 5.396476e-02 -4.055817e-01 -9.930631e+02 +-4.061531e-01 -2.657136e-02 9.134187e-01 1.728444e+03 3.902502e-02 9.981608e-01 4.638904e-02 5.091307e+01 -9.129713e-01 5.448723e-02 -4.043692e-01 -9.939181e+02 +-4.052057e-01 -2.849192e-02 9.137815e-01 1.730369e+03 3.956064e-02 9.980315e-01 4.866155e-02 5.096953e+01 -9.133692e-01 5.586771e-02 -4.032809e-01 -9.947738e+02 +-4.044522e-01 -2.578428e-02 9.141956e-01 1.732261e+03 3.913894e-02 9.981987e-01 4.546911e-02 5.102122e+01 -9.137212e-01 5.417071e-02 -4.027145e-01 -9.956156e+02 +-4.038860e-01 -2.518360e-02 9.144627e-01 1.734159e+03 3.963915e-02 9.982004e-01 4.499688e-02 5.107170e+01 -9.139501e-01 5.442212e-02 -4.021609e-01 -9.964578e+02 +-4.034386e-01 -2.394467e-02 9.146934e-01 1.736038e+03 4.291652e-02 9.980622e-01 4.505603e-02 5.112203e+01 -9.139997e-01 5.743279e-02 -4.016292e-01 -9.972930e+02 +-4.031621e-01 -2.297198e-02 9.148403e-01 1.737915e+03 4.549679e-02 9.979455e-01 4.510882e-02 5.117020e+01 -9.139969e-01 5.980845e-02 -4.012886e-01 -9.981264e+02 +-4.033294e-01 -2.394972e-02 9.147414e-01 1.739776e+03 4.803797e-02 9.977248e-01 4.730337e-02 5.121849e+01 -9.137930e-01 6.302115e-02 -4.012612e-01 -9.989527e+02 +-4.036867e-01 -2.484830e-02 9.145598e-01 1.741629e+03 4.916800e-02 9.975973e-01 4.880715e-02 5.126880e+01 -9.135751e-01 6.466986e-02 -4.014949e-01 -9.997741e+02 +-4.041289e-01 -2.568992e-02 9.143413e-01 1.743475e+03 4.800506e-02 9.976323e-01 4.924783e-02 5.132253e+01 -9.134415e-01 6.379546e-02 -4.019387e-01 -1.000590e+03 +-4.046679e-01 -2.602824e-02 9.140933e-01 1.745308e+03 4.578735e-02 9.977643e-01 4.868072e-02 5.137573e+01 -9.133167e-01 6.155341e-02 -4.025714e-01 -1.001398e+03 +-4.053477e-01 -2.604120e-02 9.137917e-01 1.747151e+03 4.287157e-02 9.979528e-01 4.745696e-02 5.144766e+01 -9.131567e-01 5.841223e-02 -4.034014e-01 -1.002199e+03 +-4.060930e-01 -2.645875e-02 9.134487e-01 1.748971e+03 4.084785e-02 9.980561e-01 4.706924e-02 5.150814e+01 -9.129183e-01 5.642689e-02 -4.042228e-01 -1.002990e+03 +-4.066935e-01 -2.735939e-02 9.131549e-01 1.750784e+03 3.966111e-02 9.980803e-01 4.756781e-02 5.155995e+01 -9.127033e-01 5.556224e-02 -4.048277e-01 -1.003788e+03 +-4.074005e-01 -2.867884e-02 9.127992e-01 1.752592e+03 3.948719e-02 9.980189e-01 4.898023e-02 5.160635e+01 -9.123955e-01 5.599844e-02 -4.054609e-01 -1.004589e+03 +-4.081243e-01 -2.983948e-02 9.124386e-01 1.754388e+03 3.846660e-02 9.980160e-01 4.984383e-02 5.165386e+01 -9.121156e-01 5.544088e-02 -4.061667e-01 -1.005375e+03 +-4.091196e-01 -3.168265e-02 9.119306e-01 1.756187e+03 3.682209e-02 9.980097e-01 5.119274e-02 5.170578e+01 -9.117375e-01 5.452313e-02 -4.071387e-01 -1.006165e+03 +-4.105918e-01 -3.381276e-02 9.111921e-01 1.757974e+03 3.578011e-02 9.979450e-01 5.315486e-02 5.176265e+01 -9.111169e-01 5.442749e-02 -4.085382e-01 -1.006957e+03 +-4.119566e-01 -3.466631e-02 9.105438e-01 1.759751e+03 3.564875e-02 9.978978e-01 5.412059e-02 5.182311e+01 -9.105058e-01 5.475507e-02 -4.098548e-01 -1.007751e+03 +-4.131189e-01 -3.419022e-02 9.100351e-01 1.761513e+03 3.742083e-02 9.978136e-01 5.447561e-02 5.188342e+01 -9.099079e-01 5.655916e-02 -4.109362e-01 -1.008544e+03 +-4.142105e-01 -3.438054e-02 9.095316e-01 1.763261e+03 4.024363e-02 9.976173e-01 5.603758e-02 5.195285e+01 -9.092910e-01 5.981420e-02 -4.118399e-01 -1.009335e+03 +-4.152352e-01 -3.413369e-02 9.090735e-01 1.764998e+03 4.364126e-02 9.973979e-01 5.738398e-02 5.201045e+01 -9.086667e-01 6.350095e-02 -4.126650e-01 -1.010123e+03 +-4.162592e-01 -3.236671e-02 9.086698e-01 1.766720e+03 4.714623e-02 9.972535e-01 5.711960e-02 5.207058e+01 -9.080228e-01 6.661690e-02 -4.135899e-01 -1.010909e+03 +-4.174463e-01 -2.971773e-02 9.082156e-01 1.768424e+03 5.059251e-02 9.971547e-01 5.588191e-02 5.212901e+01 -9.072921e-01 6.927658e-02 -4.147550e-01 -1.011690e+03 +-4.185407e-01 -2.865671e-02 9.077459e-01 1.770113e+03 5.346707e-02 9.969910e-01 5.612652e-02 5.218615e+01 -9.066228e-01 7.202572e-02 -4.157490e-01 -1.012467e+03 +-4.197411e-01 -2.733766e-02 9.072321e-01 1.771786e+03 5.677297e-02 9.967982e-01 5.630321e-02 5.224293e+01 -9.058665e-01 7.513902e-02 -4.168452e-01 -1.013242e+03 +-4.212029e-01 -2.530508e-02 9.066134e-01 1.773447e+03 5.992450e-02 9.966500e-01 5.565842e-02 5.230027e+01 -9.049846e-01 7.777182e-02 -4.182754e-01 -1.014014e+03 +-4.225884e-01 -2.359028e-02 9.060147e-01 1.775097e+03 6.274887e-02 9.965009e-01 5.521398e-02 5.235761e+01 -9.041469e-01 8.018417e-02 -4.196294e-01 -1.014785e+03 +-4.245079e-01 -2.240697e-02 9.051469e-01 1.776731e+03 6.497912e-02 9.963620e-01 5.513978e-02 5.241430e+01 -9.030895e-01 8.222291e-02 -4.215076e-01 -1.015552e+03 +-4.266768e-01 -2.157757e-02 9.041468e-01 1.778350e+03 6.726673e-02 9.961892e-01 5.551809e-02 5.247129e+01 -9.018991e-01 8.450726e-02 -4.235994e-01 -1.016316e+03 +-4.289311e-01 -2.072171e-02 9.030995e-01 1.779954e+03 7.034166e-02 9.959351e-01 5.626091e-02 5.252858e+01 -9.005943e-01 8.765756e-02 -4.257299e-01 -1.017080e+03 +-4.311326e-01 -1.921921e-02 9.020839e-01 1.781539e+03 7.349952e-02 9.957025e-01 5.634138e-02 5.258609e+01 -8.992900e-01 9.059332e-02 -4.278671e-01 -1.017840e+03 +-4.334541e-01 -1.795788e-02 9.009968e-01 1.783104e+03 7.644386e-02 9.954651e-01 5.661657e-02 5.264253e+01 -8.979275e-01 9.341633e-02 -4.301156e-01 -1.018596e+03 +-4.367904e-01 -1.663218e-02 8.994096e-01 1.784649e+03 7.802832e-02 9.953601e-01 5.630030e-02 5.269797e+01 -8.961728e-01 9.477083e-02 -4.334660e-01 -1.019347e+03 +-4.413488e-01 -1.675766e-02 8.971792e-01 1.786178e+03 7.842689e-02 9.952792e-01 5.717048e-02 5.275441e+01 -8.939018e-01 9.559508e-02 -4.379510e-01 -1.020097e+03 +-4.469695e-01 -1.721247e-02 8.943836e-01 1.787688e+03 7.905211e-02 9.951432e-01 5.865800e-02 5.281142e+01 -8.910493e-01 9.692123e-02 -4.434380e-01 -1.020850e+03 +-4.533024e-01 -1.701695e-02 8.911944e-01 1.789178e+03 8.004657e-02 9.950008e-01 5.971444e-02 5.287006e+01 -8.877553e-01 9.840573e-02 -4.496741e-01 -1.021604e+03 +-4.602830e-01 -1.629974e-02 8.876226e-01 1.790644e+03 8.031326e-02 9.949671e-01 5.991795e-02 5.292871e+01 -8.841320e-01 9.886706e-02 -4.566573e-01 -1.022359e+03 +-4.685690e-01 -1.628453e-02 8.832768e-01 1.792093e+03 7.885797e-02 9.950678e-01 6.017888e-02 5.298756e+01 -8.799002e-01 9.785135e-02 -4.649737e-01 -1.023119e+03 +-4.787360e-01 -1.566270e-02 8.778192e-01 1.793508e+03 7.710013e-02 9.952280e-01 5.980566e-02 5.304491e+01 -8.745670e-01 9.631108e-02 -4.752438e-01 -1.023881e+03 +-4.907492e-01 -1.491830e-02 8.711732e-01 1.794918e+03 7.588578e-02 9.953222e-01 5.979224e-02 5.310413e+01 -8.679900e-01 9.545263e-02 -4.873214e-01 -1.024665e+03 +-5.038178e-01 -1.369983e-02 8.637014e-01 1.796305e+03 7.624756e-02 9.952661e-01 6.026370e-02 5.316251e+01 -8.604382e-01 9.621702e-02 -5.003881e-01 -1.025467e+03 +-5.174962e-01 -1.258371e-02 8.555930e-01 1.797645e+03 7.761762e-02 9.950795e-01 6.158139e-02 5.322561e+01 -8.521579e-01 9.827721e-02 -5.139731e-01 -1.026269e+03 +-5.314990e-01 -1.042313e-02 8.469948e-01 1.798986e+03 8.013816e-02 9.948205e-01 6.252989e-02 5.328640e+01 -8.432595e-01 1.011112e-01 -5.279108e-01 -1.027105e+03 +-5.456592e-01 -9.288754e-03 8.379558e-01 1.800303e+03 8.159625e-02 9.945982e-01 6.415889e-02 5.334948e+01 -8.340252e-01 1.033829e-01 -5.419537e-01 -1.027957e+03 +-5.605297e-01 -7.384185e-03 8.281015e-01 1.801573e+03 8.355700e-02 9.943529e-01 6.542515e-02 5.341860e+01 -8.239082e-01 1.058664e-01 -5.567473e-01 -1.028814e+03 +-5.757601e-01 -6.659574e-03 8.175916e-01 1.802849e+03 8.351870e-02 9.942571e-01 6.691367e-02 5.348746e+01 -8.133418e-01 1.068104e-01 -5.718973e-01 -1.029705e+03 +-5.913339e-01 -4.205444e-03 8.064159e-01 1.804070e+03 8.380143e-02 9.942520e-01 6.663545e-02 5.355687e+01 -8.020608e-01 1.069826e-01 -5.875824e-01 -1.030593e+03 +-6.074469e-01 -1.646386e-03 7.943586e-01 1.805302e+03 8.432396e-02 9.942140e-01 6.654322e-02 5.362778e+01 -7.898720e-01 1.074049e-01 -6.037933e-01 -1.031525e+03 +-6.241370e-01 -2.498253e-03 7.813110e-01 1.806512e+03 8.446983e-02 9.939178e-01 7.065534e-02 5.370201e+01 -7.767354e-01 1.100958e-01 -6.201298e-01 -1.032479e+03 +-6.412298e-01 -1.351058e-03 7.673477e-01 1.807659e+03 8.512927e-02 9.937004e-01 7.288738e-02 5.378134e+01 -7.626121e-01 1.120613e-01 -6.370753e-01 -1.033436e+03 +-6.584790e-01 -7.394657e-04 7.525988e-01 1.808823e+03 8.462526e-02 9.935848e-01 7.501829e-02 5.386369e+01 -7.478262e-01 1.130868e-01 -6.541921e-01 -1.034439e+03 +-6.756468e-01 -7.525258e-04 7.372251e-01 1.809965e+03 8.281779e-02 9.935921e-01 7.691446e-02 5.394892e+01 -7.325590e-01 1.130223e-01 -6.712550e-01 -1.035467e+03 +-6.929748e-01 9.823978e-04 7.209612e-01 1.811032e+03 8.155942e-02 9.936865e-01 7.703940e-02 5.403157e+01 -7.163337e-01 1.121875e-01 -6.886798e-01 -1.036486e+03 +-7.104957e-01 2.390099e-03 7.036975e-01 1.812120e+03 7.983333e-02 9.938120e-01 7.722910e-02 5.411921e+01 -6.991584e-01 1.110494e-01 -7.062899e-01 -1.037563e+03 +-7.281675e-01 2.917429e-03 6.853931e-01 1.813127e+03 7.855473e-02 9.937566e-01 7.922721e-02 5.420740e+01 -6.808827e-01 1.115315e-01 -7.238504e-01 -1.038631e+03 +-7.458652e-01 3.360279e-03 6.660885e-01 1.814163e+03 7.814376e-02 9.935234e-01 8.249081e-02 5.429748e+01 -6.614973e-01 1.135777e-01 -7.412970e-01 -1.039764e+03 +-7.630394e-01 2.589499e-03 6.463468e-01 1.815169e+03 7.723005e-02 9.931932e-01 8.719419e-02 5.439358e+01 -6.417214e-01 1.164500e-01 -7.580455e-01 -1.040921e+03 +-7.798990e-01 1.178343e-03 6.259043e-01 1.816083e+03 7.506237e-02 9.929571e-01 9.166100e-02 5.449432e+01 -6.213881e-01 1.184682e-01 -7.744947e-01 -1.042062e+03 +-7.962824e-01 4.487571e-03 6.049085e-01 1.817025e+03 7.564642e-02 9.928617e-01 9.221290e-02 5.459850e+01 -6.001766e-01 1.191866e-01 -7.909377e-01 -1.043266e+03 +-8.120046e-01 7.370535e-03 5.836045e-01 1.817931e+03 7.410084e-02 9.931305e-01 9.055843e-02 5.470465e+01 -5.789280e-01 1.167794e-01 -8.069727e-01 -1.044484e+03 +-8.270558e-01 1.039820e-02 5.620236e-01 1.818744e+03 7.374898e-02 9.931937e-01 9.015116e-02 5.481008e+01 -5.572609e-01 1.160087e-01 -8.221935e-01 -1.045693e+03 +-8.418277e-01 1.226999e-02 5.396069e-01 1.819586e+03 7.253956e-02 9.932436e-01 9.058206e-02 5.491601e+01 -5.348497e-01 1.153973e-01 -8.370300e-01 -1.046959e+03 +-8.562640e-01 1.406553e-02 5.163470e-01 1.820326e+03 7.167946e-02 9.931931e-01 9.181181e-02 5.502254e+01 -5.115409e-01 1.156266e-01 -8.514437e-01 -1.048207e+03 +-8.702791e-01 1.458409e-02 4.923431e-01 1.821100e+03 7.029227e-02 9.930081e-01 9.483584e-02 5.513095e+01 -4.875176e-01 1.171415e-01 -8.652193e-01 -1.049517e+03 +-8.839303e-01 1.549109e-02 4.673620e-01 1.821838e+03 6.850511e-02 9.929578e-01 9.665256e-02 5.524358e+01 -4.625735e-01 1.174508e-01 -8.787667e-01 -1.050848e+03 +-8.970268e-01 1.767502e-02 4.416227e-01 1.822465e+03 6.717988e-02 9.930426e-01 9.671172e-02 5.535588e+01 -4.368408e-01 1.164211e-01 -8.919732e-01 -1.052152e+03 +-9.093276e-01 2.065437e-02 4.155681e-01 1.823124e+03 6.660924e-02 9.931121e-01 9.639217e-02 5.547132e+01 -4.107147e-01 1.153327e-01 -9.044400e-01 -1.053518e+03 +-9.207228e-01 2.292919e-02 3.895431e-01 1.823739e+03 6.583959e-02 9.930883e-01 9.716328e-02 5.558596e+01 -3.846228e-01 1.151078e-01 -9.158686e-01 -1.054897e+03 +-9.314508e-01 2.376850e-02 3.630902e-01 1.824255e+03 6.432307e-02 9.929047e-01 1.000135e-01 5.570364e+01 -3.581368e-01 1.165127e-01 -9.263707e-01 -1.056260e+03 +-9.415005e-01 2.367953e-02 3.361788e-01 1.824795e+03 6.162608e-02 9.928058e-01 1.026590e-01 5.582355e+01 -3.313294e-01 1.173709e-01 -9.361863e-01 -1.057672e+03 +-9.507943e-01 2.386232e-02 3.089028e-01 1.825228e+03 5.859560e-02 9.928856e-01 1.036565e-01 5.594070e+01 -3.042317e-01 1.166563e-01 -9.454281e-01 -1.059056e+03 +-9.591207e-01 2.480902e-02 2.819080e-01 1.825688e+03 5.602168e-02 9.930812e-01 1.032045e-01 5.606658e+01 -2.773972e-01 1.147785e-01 -9.538745e-01 -1.060491e+03 +-9.664959e-01 2.602892e-02 2.553590e-01 1.826105e+03 5.416093e-02 9.931265e-01 1.037610e-01 5.619032e+01 -2.509030e-01 1.141150e-01 -9.612624e-01 -1.061934e+03 +-9.730366e-01 2.817946e-02 2.289229e-01 1.826418e+03 5.367582e-02 9.929244e-01 1.059241e-01 5.631631e+01 -2.243183e-01 1.153556e-01 -9.676643e-01 -1.063357e+03 +-9.789047e-01 2.927053e-02 2.022099e-01 1.826758e+03 5.174350e-02 9.929374e-01 1.067610e-01 5.644401e+01 -1.976568e-01 1.149719e-01 -9.735056e-01 -1.064825e+03 +-9.839595e-01 3.175737e-02 1.755425e-01 1.827054e+03 5.122584e-02 9.928833e-01 1.075111e-01 5.657325e+01 -1.708790e-01 1.147789e-01 -9.785837e-01 -1.066300e+03 +-9.883293e-01 3.280838e-02 1.487581e-01 1.827248e+03 4.934467e-02 9.928303e-01 1.088721e-01 5.670276e+01 -1.441196e-01 1.149419e-01 -9.828620e-01 -1.067744e+03 +-9.920058e-01 3.362745e-02 1.216299e-01 1.827464e+03 4.701078e-02 9.929410e-01 1.088949e-01 5.683518e+01 -1.171095e-01 1.137422e-01 -9.865840e-01 -1.069230e+03 +-9.948791e-01 3.594145e-02 9.446602e-02 1.827640e+03 4.616213e-02 9.930416e-01 1.083391e-01 5.696880e+01 -8.991482e-02 1.121450e-01 -9.896154e-01 -1.070726e+03 +-9.969878e-01 3.695471e-02 6.818888e-02 1.827717e+03 4.423444e-02 9.931075e-01 1.085395e-01 5.709951e+01 -6.370783e-02 1.112288e-01 -9.917506e-01 -1.072185e+03 +-9.983341e-01 3.905308e-02 4.247216e-02 1.827812e+03 4.346119e-02 9.931598e-01 1.083728e-01 5.723215e+01 -3.794935e-02 1.100381e-01 -9.932026e-01 -1.073687e+03 +-9.990151e-01 4.096103e-02 1.706417e-02 1.827812e+03 4.258312e-02 9.931154e-01 1.091254e-01 5.736580e+01 -1.247680e-02 1.097446e-01 -9.938815e-01 -1.075152e+03 +-9.990711e-01 4.226804e-02 -8.393990e-03 1.827830e+03 4.108365e-02 9.930242e-01 1.105217e-01 5.749929e+01 1.300697e-02 1.100742e-01 -9.938382e-01 -1.076658e+03 +-9.984797e-01 4.345033e-02 -3.391864e-02 1.827812e+03 3.944917e-02 9.930554e-01 1.108361e-01 5.763595e+01 3.849895e-02 1.093295e-01 -9.932597e-01 -1.078165e+03 +-9.972192e-01 4.466020e-02 -5.966030e-02 1.827696e+03 3.787897e-02 9.931740e-01 1.103201e-01 5.776981e+01 6.417998e-02 1.077534e-01 -9.921038e-01 -1.079636e+03 +-9.953056e-01 4.497774e-02 -8.569654e-02 1.827601e+03 3.552680e-02 9.934305e-01 1.087822e-01 5.790771e+01 9.002633e-02 1.052270e-01 -9.903648e-01 -1.081139e+03 +-9.926189e-01 4.587320e-02 -1.122652e-01 1.827468e+03 3.394801e-02 9.937950e-01 1.059200e-01 5.804396e+01 1.164275e-01 1.013270e-01 -9.880169e-01 -1.082643e+03 +-9.892292e-01 4.606197e-02 -1.389388e-01 1.827234e+03 3.163408e-02 9.940405e-01 1.043202e-01 5.817193e+01 1.429160e-01 9.880140e-02 -9.847909e-01 -1.084111e+03 +-9.850962e-01 4.534016e-02 -1.659214e-01 1.827023e+03 2.813126e-02 9.941127e-01 1.046354e-01 5.830230e+01 1.696887e-01 9.840830e-02 -9.805720e-01 -1.085615e+03 +-9.800964e-01 4.645211e-02 -1.930112e-01 1.826704e+03 2.629591e-02 9.940493e-01 1.057098e-01 5.843592e+01 1.967730e-01 9.853037e-02 -9.754855e-01 -1.087072e+03 +-9.743663e-01 4.725869e-02 -2.199480e-01 1.826410e+03 2.372528e-02 9.938206e-01 1.084328e-01 5.856608e+01 2.237132e-01 1.004349e-01 -9.694664e-01 -1.088569e+03 +-9.677798e-01 4.820936e-02 -2.471400e-01 1.826076e+03 2.164604e-02 9.937956e-01 1.090947e-01 5.870315e+01 2.508660e-01 1.002300e-01 -9.628188e-01 -1.090056e+03 +-9.603291e-01 4.867644e-02 -2.745883e-01 1.825633e+03 1.991461e-02 9.941049e-01 1.065775e-01 5.883384e+01 2.781574e-01 9.688112e-02 -9.556372e-01 -1.091489e+03 +-9.521677e-01 4.944223e-02 -3.015497e-01 1.825214e+03 1.826495e-02 9.942677e-01 1.053476e-01 5.896963e+01 3.050297e-01 9.480079e-02 -9.476126e-01 -1.092954e+03 +-9.433431e-01 5.034768e-02 -3.279771e-01 1.824755e+03 1.627663e-02 9.942529e-01 1.058119e-01 5.910201e+01 3.314195e-01 9.447858e-02 -9.387411e-01 -1.094410e+03 +-9.335874e-01 5.182890e-02 -3.545819e-01 1.824183e+03 1.476422e-02 9.942085e-01 1.064495e-01 5.923540e+01 3.580455e-01 9.414474e-02 -9.289457e-01 -1.095811e+03 +-9.229795e-01 5.247184e-02 -3.812552e-01 1.823643e+03 1.248907e-02 9.942236e-01 1.065994e-01 5.936850e+01 3.846464e-01 9.362757e-02 -9.183033e-01 -1.097240e+03 +-9.113421e-01 5.276248e-02 -4.082544e-01 1.823060e+03 1.008111e-02 9.943149e-01 1.060005e-01 5.949507e+01 4.115263e-01 9.248709e-02 -9.066930e-01 -1.098648e+03 +-8.987703e-01 5.306918e-02 -4.351962e-01 1.822357e+03 8.175972e-03 9.945030e-01 1.043878e-01 5.960684e+01 4.383437e-01 9.026246e-02 -8.942636e-01 -1.099995e+03 +-8.852991e-01 5.314659e-02 -4.619751e-01 1.821684e+03 5.499736e-03 9.945747e-01 1.038787e-01 5.972051e+01 4.649896e-01 8.942293e-02 -8.807884e-01 -1.101364e+03 +-8.708889e-01 5.364515e-02 -4.885435e-01 1.820889e+03 3.413640e-03 9.946615e-01 1.031349e-01 5.984234e+01 4.914680e-01 8.815131e-02 -8.664228e-01 -1.102660e+03 +-8.558281e-01 5.342831e-02 -5.144937e-01 1.820139e+03 4.222588e-04 9.947230e-01 1.025960e-01 5.994356e+01 5.172603e-01 8.758728e-02 -8.513344e-01 -1.103994e+03 +-8.400483e-01 5.465624e-02 -5.397515e-01 1.819352e+03 -1.069544e-03 9.947433e-01 1.023942e-01 6.005208e+01 5.425106e-01 8.659333e-02 -8.355739e-01 -1.105305e+03 +-8.235898e-01 5.577809e-02 -5.644366e-01 1.818450e+03 -2.914012e-03 9.947234e-01 1.025514e-01 6.015961e+01 5.671784e-01 8.610501e-02 -8.190815e-01 -1.106542e+03 +-8.063777e-01 5.633202e-02 -5.887120e-01 1.817589e+03 -5.106352e-03 9.947529e-01 1.021792e-01 6.027091e+01 5.913789e-01 8.540114e-02 -8.018588e-01 -1.107799e+03 +-7.882972e-01 5.707804e-02 -6.126416e-01 1.816694e+03 -6.315484e-03 9.948849e-01 1.008168e-01 6.038345e+01 6.152623e-01 8.334272e-02 -7.839044e-01 -1.109029e+03 +-7.696143e-01 5.715578e-02 -6.359458e-01 1.815685e+03 -8.559710e-03 9.949725e-01 9.978227e-02 6.049128e+01 6.384517e-01 8.223736e-02 -7.652558e-01 -1.110182e+03 +-7.501463e-01 5.675138e-02 -6.588322e-01 1.814723e+03 -1.039659e-02 9.951752e-01 9.756133e-02 6.060227e+01 6.611901e-01 8.003487e-02 -7.459369e-01 -1.111351e+03 +-7.299676e-01 5.777645e-02 -6.810354e-01 1.813646e+03 -1.164159e-02 9.952251e-01 9.690916e-02 6.071216e+01 6.833826e-01 7.866887e-02 -7.258095e-01 -1.112443e+03 +-7.092895e-01 5.905573e-02 -7.024393e-01 1.812614e+03 -1.363899e-02 9.951483e-01 9.743649e-02 6.082078e+01 7.047854e-01 7.869123e-02 -7.050427e-01 -1.113551e+03 +-6.875763e-01 5.914201e-02 -7.236996e-01 1.811551e+03 -1.530082e-02 9.952760e-01 9.587282e-02 6.093013e+01 7.259509e-01 7.699307e-02 -6.834232e-01 -1.114626e+03 +-6.652344e-01 5.867719e-02 -7.443254e-01 1.810378e+03 -1.723003e-02 9.954351e-01 9.387205e-02 6.103586e+01 7.464358e-01 7.527165e-02 -6.611866e-01 -1.115622e+03 +-6.425864e-01 5.792434e-02 -7.640206e-01 1.809249e+03 -1.828933e-02 9.956947e-01 9.087117e-02 6.114424e+01 7.659949e-01 7.236600e-02 -6.387604e-01 -1.116631e+03 +-6.197276e-01 5.695400e-02 -7.827478e-01 1.808088e+03 -1.968722e-02 9.959213e-01 8.805191e-02 6.124884e+01 7.845700e-01 6.997831e-02 -6.160786e-01 -1.117606e+03 +-5.966860e-01 5.702868e-02 -8.004459e-01 1.806825e+03 -2.102465e-02 9.960182e-01 8.663514e-02 6.134899e+01 8.021993e-01 6.852307e-02 -5.931111e-01 -1.118505e+03 +-5.734655e-01 5.771894e-02 -8.171939e-01 1.805603e+03 -2.251667e-02 9.960276e-01 8.615115e-02 6.144839e+01 8.189202e-01 6.780519e-02 -5.698878e-01 -1.119412e+03 +-5.499392e-01 5.884076e-02 -8.331295e-01 1.804284e+03 -2.446239e-02 9.959525e-01 8.648769e-02 6.154684e+01 8.348464e-01 6.794330e-02 -5.462739e-01 -1.120246e+03 +-5.262180e-01 5.855615e-02 -8.483312e-01 1.803008e+03 -2.576480e-02 9.960703e-01 8.473572e-02 6.164582e+01 8.499593e-01 6.644654e-02 -5.226414e-01 -1.121087e+03 +-5.025283e-01 5.723932e-02 -8.626639e-01 1.801706e+03 -2.779528e-02 9.962205e-01 8.229267e-02 6.174346e+01 8.641138e-01 6.533237e-02 -4.990380e-01 -1.121892e+03 +-4.790919e-01 5.805443e-02 -8.758428e-01 1.800315e+03 -2.831643e-02 9.962689e-01 8.152605e-02 6.183906e+01 8.773078e-01 6.385920e-02 -4.756605e-01 -1.122623e+03 +-4.561076e-01 5.848882e-02 -8.880006e-01 1.798960e+03 -2.885693e-02 9.963411e-01 8.044667e-02 6.193421e+01 8.894566e-01 6.231730e-02 -4.527509e-01 -1.123358e+03 +-4.334258e-01 5.885301e-02 -8.992655e-01 1.797579e+03 -2.861084e-02 9.964636e-01 7.900399e-02 6.202920e+01 9.007349e-01 5.997110e-02 -4.302092e-01 -1.124058e+03 +-4.108375e-01 5.815070e-02 -9.098523e-01 1.796124e+03 -2.825904e-02 9.966721e-01 7.645974e-02 6.211734e+01 9.112705e-01 5.712407e-02 -4.078269e-01 -1.124692e+03 +-3.886183e-01 5.760973e-02 -9.195961e-01 1.794701e+03 -2.974063e-02 9.967391e-01 7.501079e-02 6.220732e+01 9.209187e-01 5.649992e-02 -3.856376e-01 -1.125325e+03 +-3.663693e-01 5.936927e-02 -9.285736e-01 1.793253e+03 -3.061930e-02 9.966526e-01 7.580284e-02 6.229534e+01 9.299656e-01 5.620410e-02 -3.633250e-01 -1.125928e+03 +-3.444089e-01 5.946866e-02 -9.369344e-01 1.791742e+03 -3.375427e-02 9.965621e-01 7.566112e-02 6.238523e+01 9.382127e-01 5.768390e-02 -3.412175e-01 -1.126471e+03 +-3.228764e-01 5.781123e-02 -9.446739e-01 1.790258e+03 -3.325646e-02 9.968233e-01 7.236922e-02 6.247435e+01 9.458566e-01 5.478282e-02 -3.199281e-01 -1.127004e+03 +-3.025182e-01 5.750029e-02 -9.514076e-01 1.788716e+03 -3.421384e-02 9.968803e-01 7.112748e-02 6.256090e+01 9.525293e-01 5.406867e-02 -2.996071e-01 -1.127485e+03 +-2.832310e-01 5.801876e-02 -9.572952e-01 1.787194e+03 -3.440325e-02 9.969113e-01 7.059853e-02 6.264482e+01 9.584344e-01 5.292975e-02 -2.803601e-01 -1.127955e+03 +-2.649301e-01 5.841344e-02 -9.624967e-01 1.785654e+03 -3.346408e-02 9.970052e-01 6.971884e-02 6.272812e+01 9.636867e-01 5.067968e-02 -2.621819e-01 -1.128395e+03 +-2.481821e-01 5.889709e-02 -9.669213e-01 1.784075e+03 -3.305438e-02 9.970539e-01 6.921669e-02 6.280871e+01 9.681493e-01 4.913932e-02 -2.455041e-01 -1.128793e+03 +-2.326862e-01 5.794229e-02 -9.708243e-01 1.782506e+03 -3.184933e-02 9.972343e-01 6.715215e-02 6.289076e+01 9.720302e-01 4.654548e-02 -2.301972e-01 -1.129180e+03 +-2.181425e-01 5.666397e-02 -9.742705e-01 1.780922e+03 -3.044199e-02 9.974320e-01 6.482713e-02 6.297071e+01 9.754420e-01 4.380029e-02 -2.158574e-01 -1.129541e+03 +-2.044746e-01 5.582103e-02 -9.772790e-01 1.779311e+03 -2.955575e-02 9.975654e-01 6.316369e-02 6.304728e+01 9.784255e-01 4.179958e-02 -2.023270e-01 -1.129873e+03 +-1.915386e-01 5.612688e-02 -9.798790e-01 1.777702e+03 -2.861513e-02 9.976198e-01 6.273652e-02 6.312234e+01 9.810678e-01 4.005583e-02 -1.894766e-01 -1.130193e+03 +-1.793648e-01 5.548689e-02 -9.822166e-01 1.776082e+03 -2.857597e-02 9.976930e-01 6.157951e-02 6.319501e+01 9.833675e-01 3.911298e-02 -1.773654e-01 -1.130494e+03 +-1.676605e-01 5.542711e-02 -9.842854e-01 1.774439e+03 -2.856574e-02 9.977259e-01 6.104978e-02 6.326738e+01 9.854308e-01 3.835248e-02 -1.656959e-01 -1.130771e+03 +-1.567693e-01 5.456269e-02 -9.861269e-01 1.772797e+03 -3.022364e-02 9.977401e-01 6.001005e-02 6.333921e+01 9.871726e-01 3.921208e-02 -1.547659e-01 -1.131038e+03 +-1.466219e-01 5.479787e-02 -9.876737e-01 1.771135e+03 -3.065907e-02 9.977330e-01 5.990738e-02 6.341172e+01 9.887173e-01 3.906489e-02 -1.446095e-01 -1.131284e+03 +-1.382909e-01 5.631293e-02 -9.887894e-01 1.769479e+03 -3.054090e-02 9.976649e-01 6.108982e-02 6.348361e+01 9.899206e-01 3.864668e-02 -1.362481e-01 -1.131517e+03 +-1.317118e-01 5.778641e-02 -9.896023e-01 1.767796e+03 -2.979443e-02 9.976176e-01 6.221998e-02 6.355799e+01 9.908402e-01 3.767974e-02 -1.296763e-01 -1.131740e+03 +-1.263034e-01 5.752688e-02 -9.903223e-01 1.766113e+03 -2.875790e-02 9.976851e-01 6.162231e-02 6.363222e+01 9.915747e-01 3.626269e-02 -1.243566e-01 -1.131949e+03 +-1.209431e-01 5.797475e-02 -9.909651e-01 1.764428e+03 -2.887820e-02 9.976650e-01 6.189119e-02 6.370596e+01 9.922393e-01 3.610259e-02 -1.189865e-01 -1.132152e+03 +-1.154768e-01 5.841438e-02 -9.915911e-01 1.762736e+03 -2.950149e-02 9.976272e-01 6.220561e-02 6.377872e+01 9.928719e-01 3.643672e-02 -1.134795e-01 -1.132348e+03 +-1.105002e-01 5.846845e-02 -9.921548e-01 1.761046e+03 -3.057396e-02 9.975956e-01 6.219423e-02 6.385109e+01 9.934057e-01 3.720658e-02 -1.084469e-01 -1.132534e+03 +-1.063190e-01 5.861222e-02 -9.926031e-01 1.759353e+03 -3.121115e-02 9.975725e-01 6.224873e-02 6.392280e+01 9.938421e-01 3.759851e-02 -1.042316e-01 -1.132713e+03 +-1.027942e-01 5.934961e-02 -9.929305e-01 1.757655e+03 -3.178182e-02 9.975128e-01 6.291376e-02 6.399476e+01 9.941947e-01 3.802431e-02 -1.006523e-01 -1.132885e+03 +-9.977778e-02 5.936350e-02 -9.932373e-01 1.755959e+03 -3.195093e-02 9.975127e-01 6.282874e-02 6.406682e+01 9.944966e-01 3.800377e-02 -9.763288e-02 -1.133051e+03 +-9.717913e-02 5.893143e-02 -9.935207e-01 1.754261e+03 -3.162266e-02 9.975586e-01 6.226405e-02 6.413795e+01 9.947644e-01 3.746853e-02 -9.507831e-02 -1.133210e+03 +-9.503044e-02 5.793185e-02 -9.937873e-01 1.752565e+03 -3.182955e-02 9.976179e-01 6.119886e-02 6.420815e+01 9.949653e-01 3.744755e-02 -9.296012e-02 -1.133366e+03 +-9.328989e-02 5.823081e-02 -9.939347e-01 1.750863e+03 -3.129907e-02 9.976233e-01 6.138462e-02 6.427888e+01 9.951469e-01 3.683579e-02 -9.124560e-02 -1.133519e+03 +-9.178813e-02 5.811216e-02 -9.940815e-01 1.749163e+03 -3.140816e-02 9.976300e-01 6.121967e-02 6.434811e+01 9.952831e-01 3.684151e-02 -8.974539e-02 -1.133669e+03 +-9.046658e-02 5.777346e-02 -9.942224e-01 1.747458e+03 -3.169043e-02 9.976433e-01 6.085585e-02 6.441721e+01 9.953951e-01 3.701275e-02 -8.842251e-02 -1.133818e+03 +-8.925571e-02 5.780325e-02 -9.943301e-01 1.745755e+03 -3.147815e-02 9.976521e-01 6.082201e-02 6.448641e+01 9.955112e-01 3.672838e-02 -8.722660e-02 -1.133964e+03 +-8.806950e-02 5.922988e-02 -9.943519e-01 1.744051e+03 -3.129743e-02 9.975732e-01 6.219379e-02 6.455659e+01 9.956225e-01 3.659803e-02 -8.600203e-02 -1.134108e+03 +-8.710990e-02 5.967851e-02 -9.944096e-01 1.742342e+03 -3.137518e-02 9.975444e-01 6.261511e-02 6.462863e+01 9.957045e-01 3.665417e-02 -8.502357e-02 -1.134251e+03 +-8.584574e-02 6.061538e-02 -9.944628e-01 1.740635e+03 -3.152541e-02 9.974824e-01 6.352084e-02 6.470178e+01 9.958095e-01 3.680384e-02 -8.371869e-02 -1.134391e+03 +-8.458501e-02 6.089766e-02 -9.945536e-01 1.738929e+03 -3.190061e-02 9.974534e-01 6.378832e-02 6.477564e+01 9.959054e-01 3.712240e-02 -8.242693e-02 -1.134530e+03 +-8.331165e-02 6.008702e-02 -9.947104e-01 1.737220e+03 -3.237664e-02 9.974903e-01 6.296665e-02 6.484950e+01 9.959974e-01 3.745123e-02 -8.115714e-02 -1.134667e+03 +-8.217235e-02 5.928233e-02 -9.948534e-01 1.735516e+03 -3.261582e-02 9.975346e-01 6.213610e-02 6.492197e+01 9.960842e-01 3.755382e-02 -8.003621e-02 -1.134802e+03 +-8.099462e-02 6.068374e-02 -9.948655e-01 1.733810e+03 -3.241230e-02 9.974566e-01 6.348057e-02 6.499470e+01 9.961873e-01 3.738746e-02 -7.882171e-02 -1.134934e+03 +-7.971126e-02 6.155007e-02 -9.949160e-01 1.732115e+03 -3.319252e-02 9.973745e-01 6.436151e-02 6.506585e+01 9.962652e-01 3.815411e-02 -7.745897e-02 -1.135064e+03 +-7.827298e-02 6.136502e-02 -9.950416e-01 1.730426e+03 -3.326734e-02 9.973871e-01 6.412659e-02 6.513665e+01 9.963767e-01 3.812176e-02 -7.602700e-02 -1.135192e+03 +-7.715745e-02 5.908689e-02 -9.952666e-01 1.728748e+03 -3.461864e-02 9.974816e-01 6.190220e-02 6.520511e+01 9.964177e-01 3.923098e-02 -7.491763e-02 -1.135319e+03 +-7.557209e-02 5.711624e-02 -9.955032e-01 1.727075e+03 -3.497757e-02 9.975919e-01 5.989135e-02 6.527167e+01 9.965266e-01 3.934640e-02 -7.339231e-02 -1.135441e+03 +-7.402504e-02 5.574841e-02 -9.956970e-01 1.725404e+03 -3.509961e-02 9.976720e-01 5.846848e-02 6.533481e+01 9.966385e-01 3.927671e-02 -7.189596e-02 -1.135561e+03 +-7.232180e-02 5.440579e-02 -9.958964e-01 1.723740e+03 -3.502555e-02 9.977567e-01 5.705098e-02 6.539481e+01 9.967661e-01 3.900785e-02 -7.025396e-02 -1.135676e+03 +-7.000011e-02 5.405768e-02 -9.960812e-01 1.722082e+03 -3.481429e-02 9.977899e-01 5.659701e-02 6.545266e+01 9.969392e-01 3.863965e-02 -6.796342e-02 -1.135788e+03 +-6.632490e-02 5.526572e-02 -9.962664e-01 1.720432e+03 -3.453184e-02 9.977396e-01 5.764636e-02 6.551240e+01 9.972003e-01 3.822630e-02 -6.426655e-02 -1.135894e+03 +-6.138499e-02 5.608486e-02 -9.965372e-01 1.718787e+03 -3.590170e-02 9.976499e-01 5.835898e-02 6.556950e+01 9.974682e-01 3.935974e-02 -5.922718e-02 -1.135995e+03 +-5.491158e-02 5.530353e-02 -9.969585e-01 1.717161e+03 -3.702598e-02 9.976654e-01 5.738211e-02 6.562471e+01 9.978044e-01 4.006431e-02 -5.273572e-02 -1.136086e+03 +-4.692679e-02 5.537937e-02 -9.973621e-01 1.715535e+03 -3.849256e-02 9.976201e-01 5.720482e-02 6.567949e+01 9.981564e-01 4.107546e-02 -4.468341e-02 -1.136161e+03 +-3.772032e-02 5.454595e-02 -9.977986e-01 1.713931e+03 -3.957049e-02 9.976444e-01 5.603344e-02 6.573199e+01 9.985045e-01 4.159698e-02 -3.547305e-02 -1.136225e+03 +-2.729193e-02 5.429700e-02 -9.981518e-01 1.712341e+03 -3.950661e-02 9.976850e-01 5.535182e-02 6.578231e+01 9.988465e-01 4.094425e-02 -2.508365e-02 -1.136271e+03 +-1.568665e-02 5.521271e-02 -9.983514e-01 1.710746e+03 -4.085460e-02 9.976050e-01 5.581337e-02 6.583270e+01 9.990419e-01 4.166277e-02 -1.339338e-02 -1.136295e+03 +-2.069798e-03 5.561306e-02 -9.984503e-01 1.709184e+03 -4.260759e-02 9.975407e-01 5.565073e-02 6.588013e+01 9.990897e-01 4.265674e-02 3.048289e-04 -1.136308e+03 +1.326404e-02 5.560159e-02 -9.983650e-01 1.707613e+03 -4.386383e-02 9.975239e-01 5.497199e-02 6.592724e+01 9.989494e-01 4.306296e-02 1.567010e-02 -1.136285e+03 +3.001700e-02 5.486326e-02 -9.980426e-01 1.706078e+03 -4.509388e-02 9.975502e-01 5.347997e-02 6.597128e+01 9.985316e-01 4.340030e-02 3.241746e-02 -1.136253e+03 +4.809052e-02 5.257386e-02 -9.974584e-01 1.704565e+03 -4.588863e-02 9.976757e-01 5.037289e-02 6.601230e+01 9.977883e-01 4.334954e-02 5.039128e-02 -1.136194e+03 +6.768449e-02 5.080095e-02 -9.964126e-01 1.703031e+03 -4.617136e-02 9.977923e-01 4.773497e-02 6.604779e+01 9.966378e-01 4.277480e-02 6.988061e-02 -1.136085e+03 +8.830477e-02 4.905510e-02 -9.948849e-01 1.701548e+03 -4.635154e-02 9.979070e-01 4.509002e-02 6.608116e+01 9.950144e-01 4.213278e-02 9.039372e-02 -1.135967e+03 +1.099876e-01 4.797113e-02 -9.927747e-01 1.700082e+03 -4.605926e-02 9.980075e-01 4.312118e-02 6.611041e+01 9.928651e-01 4.098367e-02 1.119779e-01 -1.135821e+03 +1.327435e-01 4.845110e-02 -9.899655e-01 1.698586e+03 -4.608298e-02 9.980260e-01 4.266639e-02 6.613649e+01 9.900785e-01 3.995687e-02 1.347142e-01 -1.135613e+03 +1.573736e-01 4.774558e-02 -9.863843e-01 1.697155e+03 -4.566256e-02 9.981140e-01 4.102809e-02 6.616215e+01 9.864828e-01 3.858409e-02 1.592570e-01 -1.135401e+03 +1.837440e-01 4.579162e-02 -9.819070e-01 1.695669e+03 -4.632433e-02 9.982078e-01 3.788317e-02 6.618653e+01 9.818819e-01 3.852538e-02 1.855359e-01 -1.135102e+03 +2.111468e-01 4.451899e-02 -9.764400e-01 1.694241e+03 -4.619151e-02 9.983006e-01 3.552717e-02 6.621043e+01 9.763623e-01 3.760179e-02 2.128444e-01 -1.134791e+03 +2.391828e-01 4.209080e-02 -9.700619e-01 1.692835e+03 -4.478005e-02 9.984751e-01 3.228248e-02 6.621801e+01 9.699414e-01 3.571801e-02 2.407029e-01 -1.134472e+03 +2.673739e-01 3.866590e-02 -9.628168e-01 1.691371e+03 -4.137859e-02 9.987336e-01 2.861747e-02 6.620730e+01 9.627040e-01 3.218844e-02 2.686352e-01 -1.134067e+03 +2.955659e-01 3.672114e-02 -9.546164e-01 1.689991e+03 -4.009286e-02 9.988574e-01 2.600951e-02 6.619591e+01 9.544806e-01 3.058577e-02 2.967004e-01 -1.133671e+03 +3.243968e-01 3.504788e-02 -9.452716e-01 1.688621e+03 -3.736641e-02 9.990081e-01 2.421694e-02 6.617116e+01 9.451827e-01 2.746551e-02 3.253846e-01 -1.133232e+03 +3.538818e-01 3.463379e-02 -9.346487e-01 1.687197e+03 -3.608619e-02 9.990756e-01 2.335801e-02 6.614385e+01 9.345937e-01 2.546194e-02 3.548044e-01 -1.132693e+03 +3.842016e-01 3.472738e-02 -9.225959e-01 1.685870e+03 -3.524090e-02 9.991157e-01 2.293210e-02 6.609641e+01 9.225764e-01 2.370256e-02 3.850856e-01 -1.132171e+03 +4.155458e-01 3.438311e-02 -9.089222e-01 1.684476e+03 -3.476651e-02 9.991554e-01 2.190177e-02 6.606232e+01 9.089075e-01 2.249886e-02 4.163902e-01 -1.131541e+03 +4.472590e-01 3.320388e-02 -8.937880e-01 1.683200e+03 -3.539640e-02 9.991849e-01 1.940669e-02 6.601776e+01 8.937038e-01 2.295707e-02 4.480696e-01 -1.130935e+03 +4.788870e-01 2.996798e-02 -8.773650e-01 1.681961e+03 -3.478371e-02 9.992801e-01 1.514643e-02 6.598452e+01 8.771872e-01 2.326458e-02 4.795845e-01 -1.130284e+03 +5.098544e-01 2.653525e-02 -8.598514e-01 1.680643e+03 -3.373571e-02 9.993720e-01 1.083710e-02 6.594241e+01 8.595989e-01 2.348236e-02 5.104294e-01 -1.129520e+03 +5.395908e-01 2.573206e-02 -8.415341e-01 1.679457e+03 -3.247694e-02 9.994250e-01 9.735798e-03 6.590758e+01 8.413008e-01 2.207711e-02 5.401162e-01 -1.128777e+03 +5.689942e-01 2.368763e-02 -8.220004e-01 1.678306e+03 -3.062191e-02 9.995021e-01 7.606015e-03 6.587101e+01 8.217712e-01 2.084345e-02 5.694362e-01 -1.127996e+03 +5.982109e-01 2.181991e-02 -8.010416e-01 1.677079e+03 -2.962312e-02 9.995481e-01 5.104824e-03 6.582757e+01 8.007909e-01 2.067559e-02 5.985869e-01 -1.127102e+03 +6.265443e-01 2.180327e-02 -7.790808e-01 1.675989e+03 -2.910498e-02 9.995659e-01 4.567251e-03 6.578896e+01 7.788422e-01 1.981355e-02 6.269068e-01 -1.126240e+03 +6.542394e-01 2.201501e-02 -7.559670e-01 1.674826e+03 -2.938470e-02 9.995614e-01 3.678379e-03 6.574585e+01 7.557164e-01 1.980732e-02 6.545993e-01 -1.125267e+03 +6.813462e-01 1.960019e-02 -7.316989e-01 1.673811e+03 -2.810085e-02 9.996049e-01 6.095976e-04 6.570668e+01 7.314217e-01 2.014602e-02 6.816277e-01 -1.124329e+03 +7.073149e-01 1.675192e-02 -7.067001e-01 1.672831e+03 -2.738214e-02 9.996181e-01 -3.710585e-03 6.566320e+01 7.063681e-01 2.197552e-02 7.075034e-01 -1.123355e+03 +7.321014e-01 1.297323e-02 -6.810722e-01 1.671787e+03 -2.461156e-02 9.996696e-01 -7.413617e-03 6.561313e+01 6.807509e-01 2.218977e-02 7.321787e-01 -1.122274e+03 +7.558130e-01 1.003143e-02 -6.547108e-01 1.670884e+03 -2.209244e-02 9.997040e-01 -1.018662e-02 6.556276e+01 6.544148e-01 2.216333e-02 7.558108e-01 -1.121227e+03 +7.788319e-01 6.818475e-03 -6.271957e-01 1.670025e+03 -1.941976e-02 9.997236e-01 -1.324647e-02 6.550954e+01 6.269321e-01 2.249676e-02 7.787490e-01 -1.120149e+03 +8.006604e-01 4.479414e-03 -5.991018e-01 1.669099e+03 -1.726900e-02 9.997291e-01 -1.560403e-02 6.544746e+01 5.988696e-01 2.283942e-02 8.005207e-01 -1.118972e+03 +8.212534e-01 1.000793e-03 -5.705628e-01 1.668319e+03 -1.395926e-02 9.997344e-01 -1.833902e-02 6.538886e+01 5.703928e-01 2.302562e-02 8.210492e-01 -1.117831e+03 +8.405103e-01 -2.178237e-03 -5.417912e-01 1.667481e+03 -1.174613e-02 9.996836e-01 -2.224157e-02 6.532217e+01 5.416682e-01 2.505822e-02 8.402188e-01 -1.116599e+03 +8.581794e-01 -6.730521e-03 -5.133058e-01 1.666783e+03 -8.490415e-03 9.995912e-01 -2.730160e-02 6.525392e+01 5.132797e-01 2.778785e-02 8.577714e-01 -1.115408e+03 +8.742059e-01 -9.606721e-03 -4.854605e-01 1.666116e+03 -5.480528e-03 9.995453e-01 -2.964909e-02 6.518499e+01 4.855246e-01 2.857999e-02 8.737557e-01 -1.114183e+03 +8.886360e-01 -1.070589e-02 -4.584884e-01 1.665409e+03 -2.431333e-03 9.996034e-01 -2.805352e-02 6.510462e+01 4.586069e-01 2.604410e-02 8.882575e-01 -1.112881e+03 +9.020746e-01 -1.341731e-02 -4.313716e-01 1.664817e+03 1.078755e-03 9.995836e-01 -2.883501e-02 6.503254e+01 4.315788e-01 2.554598e-02 9.017134e-01 -1.111609e+03 +9.146832e-01 -1.625626e-02 -4.038446e-01 1.664267e+03 4.198298e-03 9.995190e-01 -3.072552e-02 6.495835e+01 4.041498e-01 2.640865e-02 9.143115e-01 -1.110320e+03 +9.264230e-01 -1.982426e-02 -3.759622e-01 1.663679e+03 7.605818e-03 9.993944e-01 -3.395568e-02 6.487654e+01 3.764076e-01 2.859782e-02 9.260126e-01 -1.108960e+03 +9.373292e-01 -2.458246e-02 -3.475769e-01 1.663209e+03 1.182822e-02 9.991782e-01 -3.876932e-02 6.479507e+01 3.482442e-01 3.222840e-02 9.368496e-01 -1.107637e+03 +9.477057e-01 -2.414421e-02 -3.182312e-01 1.662781e+03 1.232836e-02 9.991595e-01 -3.909189e-02 6.471287e+01 3.189076e-01 3.312433e-02 9.472067e-01 -1.106297e+03 +9.576077e-01 -2.204863e-02 -2.872305e-01 1.662301e+03 1.240239e-02 9.992977e-01 -3.536016e-02 6.462431e+01 2.878084e-01 3.029882e-02 9.572085e-01 -1.104878e+03 +9.669170e-01 -1.794194e-02 -2.544595e-01 1.661958e+03 1.002308e-02 9.994253e-01 -3.238295e-02 6.453800e+01 2.548943e-01 2.876116e-02 9.665410e-01 -1.103507e+03 +9.751786e-01 -1.920244e-02 -2.205858e-01 1.661562e+03 1.067229e-02 9.991507e-01 -3.979745e-02 6.446915e+01 2.211627e-01 3.645546e-02 9.745553e-01 -1.102062e+03 +9.822344e-01 -2.039840e-02 -1.865463e-01 1.661319e+03 1.067481e-02 9.985384e-01 -5.298109e-02 6.436320e+01 1.873544e-01 5.004849e-02 9.810165e-01 -1.100685e+03 +9.879549e-01 -1.942424e-02 -1.535184e-01 1.661115e+03 1.077373e-02 9.983171e-01 -5.698075e-02 6.426554e+01 1.543668e-01 5.464044e-02 9.865015e-01 -1.099284e+03 +9.924238e-01 -2.044096e-02 -1.211499e-01 1.660875e+03 1.419420e-02 9.985356e-01 -5.220278e-02 6.414444e+01 1.220396e-01 5.008765e-02 9.912605e-01 -1.097802e+03 +9.958314e-01 -2.293293e-02 -8.828326e-02 1.660772e+03 1.895974e-02 9.987806e-01 -4.558349e-02 6.405174e+01 8.922096e-02 4.371964e-02 9.950518e-01 -1.096370e+03 +9.981608e-01 -2.628905e-02 -5.462549e-02 1.660724e+03 2.390616e-02 9.987530e-01 -4.382723e-02 6.395351e+01 5.570955e-02 4.244073e-02 9.975445e-01 -1.094939e+03 +9.994056e-01 -2.762807e-02 -2.062100e-02 1.660624e+03 2.664551e-02 9.985632e-01 -4.649173e-02 6.386049e+01 2.187585e-02 4.591463e-02 9.987058e-01 -1.093444e+03 +9.995243e-01 -2.786679e-02 1.321703e-02 1.660666e+03 2.851243e-02 9.982671e-01 -5.147652e-02 6.375655e+01 -1.175964e-02 5.182888e-02 9.985867e-01 -1.092014e+03 +9.985330e-01 -2.736828e-02 4.672160e-02 1.660665e+03 2.995913e-02 9.979988e-01 -5.568447e-02 6.365347e+01 -4.510411e-02 5.700251e-02 9.973546e-01 -1.090516e+03 +9.964045e-01 -2.700445e-02 8.030464e-02 1.660808e+03 3.175546e-02 9.977830e-01 -5.848604e-02 6.353899e+01 -7.854722e-02 6.082585e-02 9.950530e-01 -1.089081e+03 +9.931890e-01 -2.432640e-02 1.139466e-01 1.660998e+03 3.122845e-02 9.977585e-01 -5.918452e-02 6.342386e+01 -1.122514e-01 6.233978e-02 9.917224e-01 -1.087649e+03 +9.887981e-01 -2.277580e-02 1.475114e-01 1.661140e+03 3.165788e-02 9.978059e-01 -5.814749e-02 6.330548e+01 -1.458634e-01 6.216602e-02 9.873496e-01 -1.086159e+03 +9.833614e-01 -1.891371e-02 1.806729e-01 1.661423e+03 2.968287e-02 9.979277e-01 -5.708923e-02 6.318844e+01 -1.792187e-01 6.150222e-02 9.818849e-01 -1.084736e+03 +9.768935e-01 -1.719355e-02 2.130342e-01 1.661752e+03 3.031733e-02 9.978274e-01 -5.849108e-02 6.307257e+01 -2.115657e-01 6.359817e-02 9.752923e-01 -1.083312e+03 +9.697164e-01 -1.547483e-02 2.437432e-01 1.662049e+03 3.071336e-02 9.977947e-01 -5.884284e-02 6.295694e+01 -2.422950e-01 6.454702e-02 9.680530e-01 -1.081841e+03 +9.619374e-01 -1.444162e-02 2.728883e-01 1.662469e+03 3.155093e-02 9.977938e-01 -5.841316e-02 6.284239e+01 -2.714426e-01 6.479967e-02 9.602707e-01 -1.080424e+03 +9.536688e-01 -1.499145e-02 3.004847e-01 1.662869e+03 3.370866e-02 9.977933e-01 -5.720267e-02 6.272406e+01 -2.989641e-01 6.468133e-02 9.520697e-01 -1.078968e+03 +9.451801e-01 -1.565151e-02 3.261743e-01 1.663374e+03 3.543498e-02 9.978684e-01 -5.479982e-02 6.261487e+01 -3.246213e-01 6.335366e-02 9.437199e-01 -1.077556e+03 +9.365940e-01 -1.562359e-02 3.500680e-01 1.663914e+03 3.653840e-02 9.979141e-01 -5.322009e-02 6.250419e+01 -3.485063e-01 6.263653e-02 9.352112e-01 -1.076148e+03 +9.278710e-01 -1.634448e-02 3.725430e-01 1.664445e+03 3.892327e-02 9.978268e-01 -5.316650e-02 6.239675e+01 -3.708644e-01 6.383223e-02 9.264907e-01 -1.074719e+03 +9.195111e-01 -1.574831e-02 3.927485e-01 1.665055e+03 4.038143e-02 9.976949e-01 -5.453659e-02 6.228661e+01 -3.909842e-01 6.600673e-02 9.180274e-01 -1.073325e+03 +9.116997e-01 -1.795842e-02 4.104647e-01 1.665691e+03 4.468971e-02 9.974512e-01 -5.562220e-02 6.217659e+01 -4.084196e-01 6.905427e-02 9.101785e-01 -1.071933e+03 +9.043365e-01 -1.922964e-02 4.263869e-01 1.666334e+03 4.764100e-02 9.972898e-01 -5.606639e-02 6.206217e+01 -4.241532e-01 7.101636e-02 9.028016e-01 -1.070534e+03 +8.972198e-01 -2.194620e-02 4.410385e-01 1.667040e+03 5.044131e-02 9.973204e-01 -5.298754e-02 6.195260e+01 -4.386938e-01 6.978802e-02 8.959226e-01 -1.069131e+03 +8.902401e-01 -2.240794e-02 4.549402e-01 1.667748e+03 5.056764e-02 9.974771e-01 -4.982176e-02 6.184362e+01 -4.526760e-01 6.735857e-02 8.891272e-01 -1.067757e+03 +8.829660e-01 -2.295421e-02 4.688755e-01 1.668471e+03 5.225693e-02 9.974022e-01 -4.957929e-02 6.173872e+01 -4.665193e-01 6.827881e-02 8.818716e-01 -1.066365e+03 +8.763189e-01 -2.169326e-02 4.812428e-01 1.669233e+03 5.257645e-02 9.973248e-01 -5.078207e-02 6.163280e+01 -4.788538e-01 6.980332e-02 8.751151e-01 -1.064989e+03 +8.705961e-01 -2.327041e-02 4.914478e-01 1.670011e+03 5.602876e-02 9.970719e-01 -5.204244e-02 6.152604e+01 -4.887977e-01 7.284314e-02 8.693506e-01 -1.063611e+03 +8.663534e-01 -2.521643e-02 4.987945e-01 1.670820e+03 5.782938e-02 9.970717e-01 -5.003683e-02 6.141849e+01 -4.960721e-01 7.219454e-02 8.652747e-01 -1.062227e+03 +8.633705e-01 -2.536821e-02 5.039324e-01 1.671640e+03 5.765903e-02 9.971532e-01 -4.858807e-02 6.131031e+01 -5.012652e-01 7.100574e-02 8.623754e-01 -1.060840e+03 +8.611027e-01 -2.428920e-02 5.078507e-01 1.672455e+03 5.664728e-02 9.972225e-01 -4.835552e-02 6.120477e+01 -5.052656e-01 7.040740e-02 8.600868e-01 -1.059464e+03 +8.593376e-01 -2.317274e-02 5.108835e-01 1.673289e+03 5.557859e-02 9.972877e-01 -4.825147e-02 6.109890e+01 -5.083797e-01 6.985848e-02 8.582947e-01 -1.058082e+03 +8.580712e-01 -2.354544e-02 5.129907e-01 1.674135e+03 5.525307e-02 9.973823e-01 -4.664266e-02 6.099427e+01 -5.105496e-01 6.836702e-02 8.571260e-01 -1.056683e+03 +8.570403e-01 -2.520571e-02 5.146325e-01 1.674989e+03 5.544691e-02 9.975144e-01 -4.348185e-02 6.089092e+01 -5.122573e-01 6.580046e-02 8.563076e-01 -1.055278e+03 +8.560464e-01 -2.551605e-02 5.162688e-01 1.675853e+03 5.531686e-02 9.975673e-01 -4.241941e-02 6.079000e+01 -5.139305e-01 6.487134e-02 8.553754e-01 -1.053860e+03 +8.550524e-01 -2.540964e-02 5.179188e-01 1.676716e+03 5.541743e-02 9.975562e-01 -4.254964e-02 6.069111e+01 -5.155719e-01 6.508389e-02 8.543709e-01 -1.052451e+03 +8.539939e-01 -2.525201e-02 5.196700e-01 1.677591e+03 5.568039e-02 9.975210e-01 -4.302981e-02 6.059208e+01 -5.172951e-01 6.568260e-02 8.532828e-01 -1.051033e+03 +8.530547e-01 -2.489872e-02 5.212272e-01 1.678473e+03 5.593059e-02 9.974695e-01 -4.388899e-02 6.049193e+01 -5.188155e-01 6.659224e-02 8.522886e-01 -1.049604e+03 +8.521727e-01 -2.191437e-02 5.228017e-01 1.679381e+03 5.383890e-02 9.974920e-01 -4.594596e-02 6.038454e+01 -5.204836e-01 6.730095e-02 8.512152e-01 -1.048145e+03 +8.510645e-01 -2.217815e-02 5.245927e-01 1.680259e+03 5.415929e-02 9.974862e-01 -4.569382e-02 6.028089e+01 -5.222605e-01 6.729994e-02 8.501262e-01 -1.046739e+03 +8.499437e-01 -2.495543e-02 5.262823e-01 1.681167e+03 5.556347e-02 9.975531e-01 -4.243247e-02 6.017613e+01 -5.239356e-01 6.530726e-02 8.492505e-01 -1.045291e+03 diff --git a/tools/Ground-Truth/dataset/poses/02.txt b/tools/Ground-Truth/dataset/poses/02.txt new file mode 100644 index 0000000..403638d --- /dev/null +++ b/tools/Ground-Truth/dataset/poses/02.txt @@ -0,0 +1,4661 @@ +1.000000e+00 9.043683e-12 2.326809e-11 1.110223e-16 9.043683e-12 1.000000e+00 2.392370e-10 3.330669e-16 2.326810e-11 2.392370e-10 9.999999e-01 -2.220446e-16 +9.999967e-01 -2.220141e-03 -1.303943e-03 5.542524e-03 2.223603e-03 9.999940e-01 2.659561e-03 -3.047694e-02 1.298030e-03 -2.662451e-03 9.999956e-01 1.528975e+00 +9.999915e-01 -3.006968e-03 -2.825820e-03 5.664279e-03 3.016952e-03 9.999892e-01 3.535540e-03 -6.012991e-02 2.815159e-03 -3.544035e-03 9.999897e-01 3.052409e+00 +9.999889e-01 -2.128535e-03 -4.205819e-03 3.267206e-03 2.141750e-03 9.999928e-01 3.139851e-03 -8.838230e-02 4.199105e-03 -3.148823e-03 9.999862e-01 4.566315e+00 +9.999830e-01 -1.524541e-03 -5.643893e-03 -6.648871e-03 1.542552e-03 9.999937e-01 3.188330e-03 -1.107150e-01 5.638997e-03 -3.196981e-03 9.999789e-01 6.079413e+00 +9.999747e-01 -1.625829e-03 -6.926312e-03 -1.843176e-02 1.651081e-03 9.999920e-01 3.641708e-03 -1.314352e-01 6.920335e-03 -3.653051e-03 9.999693e-01 7.615299e+00 +9.999623e-01 -1.739691e-03 -8.516225e-03 -3.171614e-02 1.772274e-03 9.999911e-01 3.819954e-03 -1.529581e-01 8.509503e-03 -3.834901e-03 9.999564e-01 9.099118e+00 +9.999409e-01 -3.535931e-03 -1.028736e-02 -4.480997e-02 3.566679e-03 9.999892e-01 2.972015e-03 -1.743687e-01 1.027674e-02 -3.008530e-03 9.999426e-01 1.059934e+01 +9.999212e-01 -4.713044e-03 -1.163888e-02 -6.193958e-02 4.751315e-03 9.999834e-01 3.262684e-03 -1.890327e-01 1.162331e-02 -3.317725e-03 9.999269e-01 1.209423e+01 +9.999054e-01 -4.749818e-03 -1.290980e-02 -8.195167e-02 4.793738e-03 9.999828e-01 3.373208e-03 -2.057869e-01 1.289355e-02 -3.434774e-03 9.999109e-01 1.358737e+01 +9.998920e-01 -4.228781e-03 -1.407697e-02 -1.077803e-01 4.271543e-03 9.999863e-01 3.009020e-03 -2.249050e-01 1.406406e-02 -3.068824e-03 9.998963e-01 1.507594e+01 +9.998907e-01 -2.623327e-03 -1.455505e-02 -1.383473e-01 2.676639e-03 9.999898e-01 3.644477e-03 -2.492411e-01 1.454534e-02 -3.683036e-03 9.998874e-01 1.656039e+01 +9.998870e-01 -1.053198e-03 -1.499950e-02 -1.727573e-01 1.118768e-03 9.999898e-01 4.363721e-03 -2.723182e-01 1.499475e-02 -4.380008e-03 9.998779e-01 1.804280e+01 +9.998788e-01 -2.451032e-05 -1.557320e-02 -2.058484e-01 1.051712e-04 9.999866e-01 5.178666e-03 -2.957765e-01 1.557286e-02 -5.179675e-03 9.998653e-01 1.951642e+01 +9.998719e-01 -2.353867e-05 -1.600922e-02 -2.386867e-01 1.097502e-04 9.999855e-01 5.384263e-03 -3.132795e-01 1.600886e-02 -5.385328e-03 9.998573e-01 2.098968e+01 +9.998636e-01 4.413866e-04 -1.651007e-02 -2.678747e-01 -3.508676e-04 9.999849e-01 5.485152e-03 -3.280154e-01 1.651224e-02 -5.478609e-03 9.998486e-01 2.245164e+01 +9.998625e-01 1.119432e-03 -1.654724e-02 -2.977989e-01 -1.019277e-03 9.999811e-01 6.059863e-03 -3.414779e-01 1.655371e-02 -6.042162e-03 9.998447e-01 2.390871e+01 +9.998615e-01 2.049949e-03 -1.651601e-02 -3.286901e-01 -1.931135e-03 9.999721e-01 7.206627e-03 -3.566005e-01 1.653032e-02 -7.173732e-03 9.998376e-01 2.536099e+01 +9.998618e-01 2.377257e-03 -1.645374e-02 -3.584000e-01 -2.272538e-03 9.999770e-01 6.380235e-03 -3.701780e-01 1.646853e-02 -6.341960e-03 9.998442e-01 2.680201e+01 +9.998620e-01 2.769091e-03 -1.638309e-02 -3.881643e-01 -2.708306e-03 9.999893e-01 3.731267e-03 -3.903781e-01 1.639325e-02 -3.686380e-03 9.998588e-01 2.823509e+01 +9.998699e-01 1.170299e-03 -1.608933e-02 -4.156875e-01 -1.111481e-03 9.999926e-01 3.664197e-03 -4.127461e-01 1.609350e-02 -3.645836e-03 9.998638e-01 2.966060e+01 +9.998749e-01 2.102192e-04 -1.582067e-02 -4.428034e-01 -1.086559e-04 9.999794e-01 6.420245e-03 -4.350600e-01 1.582169e-02 -6.417721e-03 9.998542e-01 3.108204e+01 +9.998765e-01 -1.461067e-03 -1.565080e-02 -4.678629e-01 1.586742e-03 9.999666e-01 8.020524e-03 -4.539657e-01 1.563856e-02 -8.044365e-03 9.998453e-01 3.249337e+01 +9.998784e-01 -2.448086e-03 -1.540410e-02 -4.937117e-01 2.559861e-03 9.999705e-01 7.240648e-03 -4.678086e-01 1.538592e-02 -7.279197e-03 9.998551e-01 3.388789e+01 +9.998849e-01 -2.351353e-03 -1.499188e-02 -5.230180e-01 2.434640e-03 9.999817e-01 5.539601e-03 -4.845156e-01 1.497858e-02 -5.575461e-03 9.998722e-01 3.527199e+01 +9.998958e-01 -1.558195e-03 -1.435595e-02 -5.548668e-01 1.621394e-03 9.999890e-01 4.391701e-03 -5.027095e-01 1.434894e-02 -4.414519e-03 9.998872e-01 3.663973e+01 +9.999091e-01 -8.665701e-04 -1.345465e-02 -5.831612e-01 9.187323e-04 9.999921e-01 3.871189e-03 -5.237000e-01 1.345119e-02 -3.883197e-03 9.999019e-01 3.799599e+01 +9.999242e-01 -3.144412e-04 -1.231114e-02 -6.110062e-01 3.705383e-04 9.999895e-01 4.554592e-03 -5.446798e-01 1.230958e-02 -4.558807e-03 9.999138e-01 3.933019e+01 +9.999427e-01 3.341605e-04 -1.070505e-02 -6.351590e-01 -2.610086e-04 9.999766e-01 6.834073e-03 -5.650871e-01 1.070708e-02 -6.830885e-03 9.999193e-01 4.065401e+01 +9.999591e-01 -2.712027e-04 -9.045792e-03 -6.559744e-01 3.434903e-04 9.999680e-01 7.990691e-03 -5.837699e-01 9.043335e-03 -7.993469e-03 9.999271e-01 4.195719e+01 +9.999772e-01 6.777910e-05 -6.759562e-03 -6.731874e-01 -1.046744e-05 9.999640e-01 8.478279e-03 -6.012229e-01 6.759893e-03 -8.478013e-03 9.999412e-01 4.323955e+01 +9.999944e-01 5.490955e-05 -3.365373e-03 -6.865415e-01 -2.680498e-05 9.999651e-01 8.350575e-03 -6.178192e-01 3.365714e-03 -8.350436e-03 9.999594e-01 4.450289e+01 +9.999997e-01 -7.846738e-04 3.218970e-04 -6.935884e-01 7.826665e-04 9.999805e-01 6.189643e-03 -6.350241e-01 -3.267476e-04 -6.189388e-03 9.999807e-01 4.574413e+01 +9.999922e-01 -1.100101e-03 3.803485e-03 -6.959569e-01 1.082755e-03 9.999890e-01 4.559605e-03 -6.526707e-01 -3.808459e-03 -4.555450e-03 9.999823e-01 4.697748e+01 +9.999689e-01 -6.772935e-04 7.861748e-03 -7.001992e-01 6.368232e-04 9.999865e-01 5.149118e-03 -6.645447e-01 -7.865129e-03 -5.143950e-03 9.999558e-01 4.819774e+01 +9.999134e-01 -2.620471e-04 1.315831e-02 -6.975233e-01 1.937417e-04 9.999865e-01 5.192058e-03 -6.781882e-01 -1.315949e-02 -5.189058e-03 9.998999e-01 4.940741e+01 +9.998044e-01 1.185349e-03 1.974544e-02 -6.903610e-01 -1.267194e-03 9.999906e-01 4.133010e-03 -6.899979e-01 -1.974035e-02 -4.157221e-03 9.997964e-01 5.060553e+01 +9.996268e-01 2.727086e-03 2.718144e-02 -6.759702e-01 -2.833090e-03 9.999885e-01 3.862101e-03 -7.020690e-01 -2.717059e-02 -3.937667e-03 9.996230e-01 5.179127e+01 +9.993594e-01 3.728632e-03 3.559358e-02 -6.473751e-01 -3.917026e-03 9.999787e-01 5.224639e-03 -7.126113e-01 -3.557334e-02 -5.360712e-03 9.993526e-01 5.296880e+01 +9.989330e-01 5.955695e-03 4.579893e-02 -6.094624e-01 -6.221115e-03 9.999646e-01 5.654978e-03 -7.231034e-01 -4.576363e-02 -5.933863e-03 9.989346e-01 5.413296e+01 +9.982392e-01 8.248457e-03 5.874191e-02 -5.600621e-01 -8.602116e-03 9.999463e-01 5.770220e-03 -7.297775e-01 -5.869116e-02 -6.265363e-03 9.982565e-01 5.528110e+01 +9.972445e-01 1.030551e-02 7.346689e-02 -4.934098e-01 -1.079632e-02 9.999219e-01 6.286571e-03 -7.390768e-01 -7.339637e-02 -7.062419e-03 9.972778e-01 5.641219e+01 +9.958861e-01 1.264625e-02 8.972728e-02 -4.111119e-01 -1.336115e-02 9.998835e-01 7.371203e-03 -7.469047e-01 -8.962361e-02 -8.539736e-03 9.959390e-01 5.753105e+01 +9.941350e-01 1.287820e-02 1.073773e-01 -3.043738e-01 -1.390334e-02 9.998646e-01 8.803900e-03 -7.552160e-01 -1.072494e-01 -1.024517e-02 9.941793e-01 5.864015e+01 +9.919005e-01 1.254741e-02 1.263966e-01 -1.772585e-01 -1.369399e-02 9.998725e-01 8.206430e-03 -7.637425e-01 -1.262775e-01 -9.870833e-03 9.919458e-01 5.973159e+01 +9.891307e-01 1.167645e-02 1.465751e-01 -3.027954e-02 -1.282087e-02 9.998942e-01 6.865394e-03 -7.709585e-01 -1.464794e-01 -8.669990e-03 9.891757e-01 6.080734e+01 +9.858577e-01 9.109430e-03 1.673369e-01 1.414162e-01 -1.029133e-02 9.999278e-01 6.197189e-03 -7.801986e-01 -1.672684e-01 -7.831665e-03 9.858802e-01 6.186839e+01 +9.819655e-01 3.793581e-03 1.890225e-01 3.429236e-01 -5.471338e-03 9.999501e-01 8.354942e-03 -7.905714e-01 -1.889814e-01 -9.238469e-03 9.819372e-01 6.291291e+01 +9.773046e-01 -1.709232e-03 2.118322e-01 5.688516e-01 -4.745824e-04 9.999473e-01 1.025790e-02 -7.991531e-01 -2.118385e-01 -1.012562e-02 9.772522e-01 6.394069e+01 +9.718692e-01 -6.880933e-03 2.354211e-01 8.226070e-01 4.698978e-03 9.999406e-01 9.828066e-03 -8.026621e-01 -2.354747e-01 -8.445355e-03 9.718437e-01 6.494900e+01 +9.654653e-01 -1.331156e-02 2.601914e-01 1.098599e+00 1.166580e-02 9.999010e-01 7.868493e-03 -8.056283e-01 -2.602703e-01 -4.561416e-03 9.655250e-01 6.593481e+01 +9.580718e-01 -1.728534e-02 2.860065e-01 1.400581e+00 1.562878e-02 9.998452e-01 8.073843e-03 -8.048744e-01 -2.861018e-01 -3.265387e-03 9.581936e-01 6.690386e+01 +9.495606e-01 -2.005549e-02 3.129416e-01 1.719450e+00 1.762511e-02 9.997885e-01 1.059348e-02 -8.099221e-01 -3.130879e-01 -4.543522e-03 9.497132e-01 6.785621e+01 +9.399600e-01 -2.430701e-02 3.404181e-01 2.070873e+00 2.082730e-02 9.996868e-01 1.387286e-02 -8.116220e-01 -3.406487e-01 -5.949941e-03 9.401718e-01 6.879155e+01 +9.291719e-01 -2.800214e-02 3.685860e-01 2.445156e+00 2.471863e-02 9.996015e-01 1.362813e-02 -8.131263e-01 -3.688207e-01 -3.551935e-03 9.294937e-01 6.970243e+01 +9.172153e-01 -2.734522e-02 3.974524e-01 2.836652e+00 2.544892e-02 9.996256e-01 1.004610e-02 -8.139150e-01 -3.975783e-01 9.002929e-04 9.175678e-01 7.058836e+01 +9.041595e-01 -2.861151e-02 4.262360e-01 3.253649e+00 2.944809e-02 9.995556e-01 4.628971e-03 -8.166667e-01 -4.261790e-01 8.366502e-03 9.046001e-01 7.145272e+01 +8.900733e-01 -3.066895e-02 4.547845e-01 3.697183e+00 3.353669e-02 9.994359e-01 1.762472e-03 -8.217552e-01 -4.545820e-01 1.368323e-02 8.905997e-01 7.230010e+01 +8.745234e-01 -3.199557e-02 4.839268e-01 4.165770e+00 3.386512e-02 9.994145e-01 4.878839e-03 -8.265719e-01 -4.837995e-01 1.212158e-02 8.750948e-01 7.313220e+01 +8.569678e-01 -3.122428e-02 5.144232e-01 4.656399e+00 2.991533e-02 9.994937e-01 1.083157e-02 -8.326482e-01 -5.145010e-01 6.106832e-03 8.574680e-01 7.395134e+01 +8.375209e-01 -3.135402e-02 5.455050e-01 5.171922e+00 2.716620e-02 9.995070e-01 1.574010e-02 -8.379065e-01 -5.457295e-01 1.636631e-03 8.379597e-01 7.474042e+01 +8.164962e-01 -2.594618e-02 5.767676e-01 5.707425e+00 2.416207e-02 9.996501e-01 1.076493e-02 -8.397157e-01 -5.768450e-01 5.146369e-03 8.168373e-01 7.550137e+01 +7.946459e-01 -1.916753e-02 6.067706e-01 6.267395e+00 2.143011e-02 9.997641e-01 3.516416e-03 -8.402731e-01 -6.066949e-01 1.020885e-02 7.948692e-01 7.623592e+01 +7.722395e-01 -1.642356e-02 6.351193e-01 6.852965e+00 2.055808e-02 9.997883e-01 8.570305e-04 -8.436503e-01 -6.349988e-01 1.239500e-02 7.724136e-01 7.694187e+01 +7.490502e-01 -1.930171e-02 6.622321e-01 7.469758e+00 2.196146e-02 9.997496e-01 4.298553e-03 -8.507153e-01 -6.621492e-01 1.132375e-02 7.492864e-01 7.762714e+01 +7.247325e-01 -1.953835e-02 6.887533e-01 8.102844e+00 2.116676e-02 9.997574e-01 6.088352e-03 -8.620809e-01 -6.887052e-01 1.016625e-02 7.249702e-01 7.828406e+01 +6.994597e-01 -1.826382e-02 7.144387e-01 8.750799e+00 2.269947e-02 9.997368e-01 3.333600e-03 -8.702408e-01 -7.143114e-01 1.388565e-02 6.996901e-01 7.890590e+01 +6.733401e-01 -1.581716e-02 7.391637e-01 9.420955e+00 2.290921e-02 9.997374e-01 5.239928e-04 -8.762188e-01 -7.389778e-01 1.658082e-02 6.735256e-01 7.950640e+01 +6.464027e-01 -1.342373e-02 7.628783e-01 1.010937e+01 2.085704e-02 9.997824e-01 -8.027689e-05 -8.844685e-01 -7.627113e-01 1.596327e-02 6.465420e-01 8.008158e+01 +6.186204e-01 -1.239589e-02 7.855922e-01 1.082345e+01 2.120024e-02 9.997748e-01 -9.188054e-04 -8.963087e-01 -7.854039e-01 1.722313e-02 6.187439e-01 8.063432e+01 +5.901006e-01 -6.313377e-03 8.073051e-01 1.155404e+01 2.023865e-02 9.997708e-01 -6.974943e-03 -9.103951e-01 -8.070760e-01 2.045467e-02 5.900931e-01 8.116168e+01 +5.602449e-01 2.835353e-03 8.283222e-01 1.229823e+01 1.892332e-02 9.996893e-01 -1.622094e-02 -9.440788e-01 -8.281109e-01 2.476230e-02 5.600171e-01 8.167543e+01 +5.295973e-01 1.127181e-02 8.481743e-01 1.306621e+01 1.835654e-02 9.995252e-01 -2.474496e-02 -9.899750e-01 -8.480505e-01 2.867440e-02 5.291390e-01 8.217844e+01 +4.980180e-01 1.631846e-02 8.670132e-01 1.385636e+01 1.612194e-02 9.994759e-01 -2.807216e-02 -1.044292e+00 -8.670168e-01 2.795836e-02 4.974939e-01 8.266054e+01 +4.656619e-01 1.582819e-02 8.848212e-01 1.467086e+01 1.381362e-02 9.995882e-01 -2.515102e-02 -1.091171e+00 -8.848548e-01 2.393445e-02 4.652515e-01 8.310277e+01 +4.327521e-01 1.418518e-02 9.014014e-01 1.550495e+01 9.386123e-03 9.997511e-01 -2.023906e-02 -1.141769e+00 -9.014641e-01 1.721915e-02 4.325112e-01 8.352640e+01 +3.985676e-01 1.506852e-02 9.170152e-01 1.635188e+01 5.370069e-03 9.998095e-01 -1.876304e-02 -1.182920e+00 -9.171232e-01 1.240277e-02 3.984108e-01 8.390596e+01 +3.634390e-01 1.801940e-02 9.314438e-01 1.721884e+01 -1.324542e-03 9.998219e-01 -1.882540e-02 -1.223975e+00 -9.316170e-01 5.608144e-03 3.633981e-01 8.426630e+01 +3.276884e-01 2.019548e-02 9.445700e-01 1.810134e+01 -6.744494e-03 9.997960e-01 -1.903646e-02 -1.258474e+00 -9.447617e-01 -1.326205e-04 3.277578e-01 8.458881e+01 +2.915840e-01 1.934555e-02 9.563496e-01 1.900345e+01 -9.648340e-03 9.998041e-01 -1.728287e-02 -1.292921e+00 -9.564965e-01 -4.187781e-03 2.917135e-01 8.487369e+01 +2.554161e-01 1.898680e-02 9.666448e-01 1.992032e+01 -1.046188e-02 9.998029e-01 -1.687376e-02 -1.333845e+00 -9.667746e-01 -5.803097e-03 2.555644e-01 8.512286e+01 +2.195925e-01 1.816829e-02 9.754225e-01 2.085317e+01 -9.854782e-03 9.998169e-01 -1.640410e-02 -1.389328e+00 -9.755419e-01 -6.010360e-03 2.197313e-01 8.533947e+01 +1.842613e-01 1.726802e-02 9.827256e-01 2.179622e+01 -7.939294e-03 9.998392e-01 -1.608012e-02 -1.441902e+00 -9.828452e-01 -4.839206e-03 1.843688e-01 8.551592e+01 +1.497064e-01 1.548325e-02 9.886093e-01 2.274979e+01 -4.622691e-04 9.998783e-01 -1.558975e-02 -1.487418e+00 -9.887303e-01 1.876878e-03 1.496954e-01 8.565402e+01 +1.161094e-01 1.870304e-02 9.930603e-01 2.370411e+01 3.197353e-03 9.998105e-01 -1.920401e-02 -1.536455e+00 -9.932312e-01 5.404927e-03 1.160276e-01 8.575774e+01 +8.347086e-02 2.449840e-02 9.962091e-01 2.466336e+01 3.600780e-03 9.996838e-01 -2.488556e-02 -1.578857e+00 -9.965037e-01 5.664345e-03 8.335625e-02 8.583875e+01 +5.411487e-02 2.811233e-02 9.981389e-01 2.562625e+01 1.029633e-02 9.995347e-01 -2.870987e-02 -1.637414e+00 -9.984816e-01 1.183079e-02 5.380024e-02 8.588405e+01 +2.844833e-02 2.769310e-02 9.992116e-01 2.659670e+01 1.316383e-02 9.995191e-01 -2.807641e-02 -1.686769e+00 -9.995085e-01 1.395218e-02 2.807010e-02 8.590350e+01 +5.896436e-03 2.376380e-02 9.997002e-01 2.757774e+01 1.408032e-02 9.996165e-01 -2.384486e-02 -1.740061e+00 -9.998834e-01 1.421669e-02 5.559573e-03 8.590820e+01 +-1.322891e-02 2.055410e-02 9.997012e-01 2.856061e+01 1.436558e-02 9.996894e-01 -2.036377e-02 -1.785582e+00 -9.998093e-01 1.409189e-02 -1.352007e-02 8.589204e+01 +-2.974218e-02 2.343909e-02 9.992828e-01 2.953912e+01 1.629226e-02 9.996036e-01 -2.296170e-02 -1.850372e+00 -9.994248e-01 1.559764e-02 -3.011226e-02 8.586002e+01 +-4.451169e-02 2.917319e-02 9.985828e-01 3.052056e+01 1.897167e-02 9.994179e-01 -2.835194e-02 -1.910044e+00 -9.988287e-01 1.768279e-02 -4.503924e-02 8.580960e+01 +-5.644683e-02 3.313707e-02 9.978556e-01 3.150611e+01 2.335369e-02 9.992194e-01 -3.186129e-02 -1.968582e+00 -9.981324e-01 2.150513e-02 -5.717664e-02 8.574610e+01 +-6.558728e-02 3.696838e-02 9.971618e-01 3.249553e+01 2.936162e-02 9.989522e-01 -3.510353e-02 -2.034292e+00 -9.974147e-01 2.697593e-02 -6.660401e-02 8.566974e+01 +-7.133181e-02 4.201284e-02 9.965675e-01 3.348523e+01 3.294277e-02 9.986667e-01 -3.974338e-02 -2.096511e+00 -9.969085e-01 2.999472e-02 -7.262072e-02 8.558750e+01 +-7.497980e-02 4.736707e-02 9.960595e-01 3.447574e+01 3.484801e-02 9.983855e-01 -4.485447e-02 -2.165170e+00 -9.965759e-01 3.134750e-02 -7.650939e-02 8.550585e+01 +-7.772054e-02 5.100177e-02 9.956698e-01 3.547392e+01 3.710220e-02 9.981468e-01 -4.823252e-02 -2.230292e+00 -9.962845e-01 3.319288e-02 -7.946878e-02 8.541929e+01 +-8.041092e-02 5.455562e-02 9.952677e-01 3.647409e+01 3.755346e-02 9.979579e-01 -5.166903e-02 -2.302430e+00 -9.960541e-01 3.322099e-02 -8.229546e-02 8.533282e+01 +-8.277044e-02 5.712855e-02 9.949299e-01 3.747623e+01 3.843787e-02 9.977957e-01 -5.409539e-02 -2.372412e+00 -9.958270e-01 3.376548e-02 -8.478388e-02 8.524353e+01 +-8.466798e-02 6.126156e-02 9.945242e-01 3.847939e+01 3.950431e-02 9.975298e-01 -5.808354e-02 -2.446547e+00 -9.956258e-01 3.437017e-02 -8.687892e-02 8.515093e+01 +-8.668535e-02 6.295573e-02 9.942446e-01 3.948794e+01 4.222097e-02 9.973368e-01 -5.947041e-02 -2.531911e+00 -9.953406e-01 3.682275e-02 -8.911253e-02 8.504711e+01 +-8.870577e-02 6.205828e-02 9.941228e-01 4.050491e+01 4.252210e-02 9.973833e-01 -5.846758e-02 -2.620466e+00 -9.951498e-01 3.708576e-02 -9.111249e-02 8.494335e+01 +-9.119746e-02 6.078595e-02 9.939759e-01 4.152314e+01 4.136854e-02 9.975049e-01 -5.720620e-02 -2.703793e+00 -9.949732e-01 3.590226e-02 -9.348453e-02 8.484011e+01 +-9.318044e-02 6.236751e-02 9.936940e-01 4.254154e+01 4.189171e-02 9.973979e-01 -5.867174e-02 -2.782434e+00 -9.947675e-01 3.616047e-02 -9.555066e-02 8.473340e+01 +-9.565326e-02 6.425885e-02 9.933385e-01 4.356321e+01 4.068653e-02 9.973326e-01 -6.059934e-02 -2.862846e+00 -9.945828e-01 3.461896e-02 -9.801257e-02 8.462639e+01 +-9.826735e-02 6.680700e-02 9.929151e-01 4.459161e+01 3.932738e-02 9.972254e-01 -6.320485e-02 -2.947049e+00 -9.943826e-01 3.283776e-02 -1.006220e-01 8.451273e+01 +-1.008219e-01 7.017314e-02 9.924267e-01 4.562390e+01 3.714918e-02 9.970794e-01 -6.672811e-02 -3.034107e+00 -9.942106e-01 3.014017e-02 -1.031343e-01 8.439616e+01 +-1.030371e-01 7.454546e-02 9.918802e-01 4.665834e+01 3.383043e-02 9.968734e-01 -7.140641e-02 -3.121719e+00 -9.941020e-01 2.619821e-02 -1.052369e-01 8.428026e+01 +-1.055615e-01 7.713973e-02 9.914163e-01 4.769859e+01 3.158554e-02 9.967437e-01 -7.419117e-02 -3.212409e+00 -9.939110e-01 2.348268e-02 -1.076543e-01 8.415974e+01 +-1.082516e-01 7.568366e-02 9.912384e-01 4.874265e+01 2.980113e-02 9.968967e-01 -7.286116e-02 -3.300682e+00 -9.936767e-01 2.165268e-02 -1.101712e-01 8.403799e+01 +-1.113399e-01 7.123111e-02 9.912263e-01 4.979767e+01 2.642006e-02 9.972875e-01 -6.869905e-02 -3.399467e+00 -9.934311e-01 1.853930e-02 -1.129199e-01 8.391179e+01 +-1.139163e-01 6.959566e-02 9.910497e-01 5.085130e+01 2.627206e-02 9.974055e-01 -6.702216e-02 -3.491219e+00 -9.931429e-01 1.840200e-02 -1.154491e-01 8.378036e+01 +-1.158250e-01 6.985040e-02 9.908106e-01 5.190709e+01 2.598171e-02 9.973959e-01 -6.727743e-02 -3.581332e+00 -9.929297e-01 1.795053e-02 -1.173382e-01 8.364593e+01 +-1.171497e-01 7.263404e-02 9.904546e-01 5.296284e+01 2.737638e-02 9.971790e-01 -6.988915e-02 -3.668473e+00 -9.927368e-01 1.892756e-02 -1.188076e-01 8.350873e+01 +-1.177716e-01 7.541683e-02 9.901728e-01 5.402128e+01 2.790440e-02 9.969695e-01 -7.261556e-02 -3.758476e+00 -9.926485e-01 1.907812e-02 -1.195192e-01 8.337012e+01 +-1.182043e-01 7.659691e-02 9.900307e-01 5.508951e+01 2.708114e-02 9.968982e-01 -7.389492e-02 -3.853303e+00 -9.926199e-01 1.807646e-02 -1.199119e-01 8.323118e+01 +-1.180776e-01 7.482940e-02 9.901809e-01 5.616217e+01 2.374347e-02 9.970843e-01 -7.251974e-02 -3.946919e+00 -9.927204e-01 1.494737e-02 -1.195100e-01 8.309674e+01 +-1.183116e-01 7.450330e-02 9.901776e-01 5.723648e+01 1.999762e-02 9.971578e-01 -7.263910e-02 -4.043440e+00 -9.927751e-01 1.120714e-02 -1.194652e-01 8.296320e+01 +-1.184144e-01 7.536459e-02 9.901001e-01 5.831225e+01 1.629358e-02 9.971287e-01 -7.395092e-02 -4.137484e+00 -9.928305e-01 7.375422e-03 -1.193023e-01 8.283188e+01 +-1.187915e-01 7.570440e-02 9.900290e-01 5.939428e+01 1.225761e-02 9.971250e-01 -7.477625e-02 -4.235523e+00 -9.928435e-01 3.252604e-03 -1.193779e-01 8.269832e+01 +-1.192827e-01 7.481209e-02 9.900378e-01 6.048415e+01 8.649815e-03 9.971976e-01 -7.431098e-02 -4.332877e+00 -9.928226e-01 -3.003721e-04 -1.195955e-01 8.256445e+01 +-1.196761e-01 6.989088e-02 9.903499e-01 6.158947e+01 8.554825e-03 9.975546e-01 -6.936556e-02 -4.427686e+00 -9.927761e-01 1.708706e-04 -1.199813e-01 8.242007e+01 +-1.199740e-01 6.147785e-02 9.908717e-01 6.269201e+01 1.156217e-02 9.980996e-01 -6.052637e-02 -4.507440e+00 -9.927097e-01 4.195035e-03 -1.204568e-01 8.227636e+01 +-1.199894e-01 5.482827e-02 9.912600e-01 6.380163e+01 1.624666e-02 9.984485e-01 -5.325927e-02 -4.575110e+00 -9.926422e-01 9.714108e-03 -1.206940e-01 8.212657e+01 +-1.191900e-01 5.753560e-02 9.912030e-01 6.490299e+01 2.502529e-02 9.981765e-01 -5.493116e-02 -4.637324e+00 -9.925560e-01 1.825789e-02 -1.204125e-01 8.197173e+01 +-1.179477e-01 6.349043e-02 9.909881e-01 6.600675e+01 3.117512e-02 9.976988e-01 -6.020991e-02 -4.698824e+00 -9.925303e-01 2.379254e-02 -1.196556e-01 8.181847e+01 +-1.170727e-01 6.916153e-02 9.907122e-01 6.711535e+01 3.455186e-02 9.972519e-01 -6.553508e-02 -4.769758e+00 -9.925221e-01 2.655857e-02 -1.191407e-01 8.167129e+01 +-1.163451e-01 7.294952e-02 9.905262e-01 6.822842e+01 3.564820e-02 9.969631e-01 -6.923643e-02 -4.848159e+00 -9.925689e-01 2.725515e-02 -1.185923e-01 8.152737e+01 +-1.163709e-01 7.198808e-02 9.905936e-01 6.935294e+01 3.285757e-02 9.971029e-01 -6.860117e-02 -4.927907e+00 -9.926621e-01 2.456532e-02 -1.183991e-01 8.138834e+01 +-1.161347e-01 6.691418e-02 9.909769e-01 7.048500e+01 3.072070e-02 9.974927e-01 -6.375393e-02 -5.011017e+00 -9.927582e-01 2.303945e-02 -1.178991e-01 8.124871e+01 +-1.159475e-01 6.394350e-02 9.911950e-01 7.162116e+01 2.916131e-02 9.977145e-01 -6.095288e-02 -5.086994e+00 -9.928271e-01 2.183720e-02 -1.175472e-01 8.111025e+01 +-1.158279e-01 6.476000e-02 9.911559e-01 7.275311e+01 2.780437e-02 9.976926e-01 -6.193785e-02 -5.162949e+00 -9.928800e-01 2.038433e-02 -1.173612e-01 8.097266e+01 +-1.156249e-01 6.921292e-02 9.908787e-01 7.388909e+01 2.803964e-02 9.973992e-01 -6.639647e-02 -5.241054e+00 -9.928971e-01 2.010678e-02 -1.172649e-01 8.083141e+01 +-1.149327e-01 7.314930e-02 9.906764e-01 7.502755e+01 2.837532e-02 9.971199e-01 -7.033314e-02 -5.323826e+00 -9.929679e-01 2.002718e-02 -1.166773e-01 8.068962e+01 +-1.145607e-01 7.215451e-02 9.907924e-01 7.617779e+01 2.843230e-02 9.971883e-01 -6.933281e-02 -5.409080e+00 -9.930092e-01 2.022768e-02 -1.162901e-01 8.054753e+01 +-1.140320e-01 6.411854e-02 9.914059e-01 7.733948e+01 2.957171e-02 9.976920e-01 -6.112375e-02 -5.493650e+00 -9.930368e-01 2.234750e-02 -1.156649e-01 8.040286e+01 +-1.142248e-01 6.325840e-02 9.914389e-01 7.849684e+01 2.937545e-02 9.977493e-01 -6.027667e-02 -5.575395e+00 -9.930205e-01 2.223887e-02 -1.158259e-01 8.026070e+01 +-1.141173e-01 6.638015e-02 9.912472e-01 7.965385e+01 2.721180e-02 9.975997e-01 -6.367282e-02 -5.653289e+00 -9.930945e-01 1.970744e-02 -1.156497e-01 8.012242e+01 +-1.138666e-01 6.956512e-02 9.910576e-01 8.081443e+01 2.669236e-02 9.973996e-01 -6.694351e-02 -5.733271e+00 -9.931374e-01 1.883103e-02 -1.154274e-01 7.998194e+01 +-1.137738e-01 6.906425e-02 9.911033e-01 8.198866e+01 2.583138e-02 9.974492e-01 -6.654116e-02 -5.820181e+00 -9.931708e-01 1.803092e-02 -1.152676e-01 7.984084e+01 +-1.133275e-01 6.578657e-02 9.913774e-01 8.314911e+01 2.502350e-02 9.976780e-01 -6.334417e-02 -5.906836e+00 -9.932425e-01 1.762909e-02 -1.147106e-01 7.970180e+01 +-1.123304e-01 6.450052e-02 9.915753e-01 8.431156e+01 2.587357e-02 9.977425e-01 -6.197062e-02 -5.991644e+00 -9.933340e-01 1.869440e-02 -1.137457e-01 7.956056e+01 +-1.108700e-01 6.472693e-02 9.917249e-01 8.548133e+01 2.733133e-02 9.976980e-01 -6.206128e-02 -6.073437e+00 -9.934590e-01 2.022442e-02 -1.123838e-01 7.941861e+01 +-1.096846e-01 6.518914e-02 9.918265e-01 8.665574e+01 3.006997e-02 9.976079e-01 -6.224375e-02 -6.143337e+00 -9.935115e-01 2.299701e-02 -1.113824e-01 7.927416e+01 +-1.085184e-01 6.474185e-02 9.919840e-01 8.784314e+01 2.975946e-02 9.976413e-01 -6.185554e-02 -6.220092e+00 -9.936489e-01 2.280844e-02 -1.101891e-01 7.913297e+01 +-1.071260e-01 6.555051e-02 9.920823e-01 8.903034e+01 3.105347e-02 9.975580e-01 -6.255914e-02 -6.292724e+00 -9.937603e-01 2.410588e-02 -1.089000e-01 7.899178e+01 +-1.060845e-01 6.303828e-02 9.923569e-01 9.023925e+01 3.127932e-02 9.977061e-01 -6.003429e-02 -6.375416e+00 -9.938650e-01 2.467154e-02 -1.078129e-01 7.885004e+01 +-1.050696e-01 6.244270e-02 9.925026e-01 9.145274e+01 2.995006e-02 9.977727e-01 -5.960367e-02 -6.458889e+00 -9.940137e-01 2.346297e-02 -1.067057e-01 7.871205e+01 +-1.037604e-01 6.200648e-02 9.926676e-01 9.266639e+01 3.098535e-02 9.977718e-01 -5.908652e-02 -6.542150e+00 -9.941195e-01 2.462730e-02 -1.054505e-01 7.857336e+01 +-1.021775e-01 6.256298e-02 9.927969e-01 9.388743e+01 2.941137e-02 9.977740e-01 -5.984965e-02 -6.627664e+00 -9.943313e-01 2.308422e-02 -1.037901e-01 7.843781e+01 +-1.006056e-01 6.553057e-02 9.927660e-01 9.510911e+01 2.978588e-02 9.975797e-01 -6.282986e-02 -6.713115e+00 -9.944804e-01 2.324936e-02 -1.023140e-01 7.830262e+01 +-9.945430e-02 6.530825e-02 9.928966e-01 9.633804e+01 2.801108e-02 9.976321e-01 -6.281398e-02 -6.798660e+00 -9.946477e-01 2.156498e-02 -1.010481e-01 7.817155e+01 +-9.903252e-02 6.264174e-02 9.931106e-01 9.756935e+01 2.388010e-02 9.978788e-01 -6.056120e-02 -6.882331e+00 -9.947976e-01 1.771805e-02 -1.003183e-01 7.805765e+01 +-9.886702e-02 6.376206e-02 9.930558e-01 9.880208e+01 2.145327e-02 9.978496e-01 -6.193402e-02 -6.966266e+00 -9.948693e-01 1.518106e-02 -1.000223e-01 7.793983e+01 +-9.915247e-02 6.387177e-02 9.930203e-01 1.000429e+02 1.887214e-02 9.978790e-01 -6.229993e-02 -7.052411e+00 -9.948932e-01 1.256322e-02 -1.001476e-01 7.782180e+01 +-1.002303e-01 6.081209e-02 9.931041e-01 1.012886e+02 1.600489e-02 9.980998e-01 -5.950270e-02 -7.138670e+00 -9.948355e-01 9.930544e-03 -1.010131e-01 7.769989e+01 +-1.015079e-01 5.933445e-02 9.930638e-01 1.025376e+02 1.383515e-02 9.982074e-01 -5.822760e-02 -7.224808e+00 -9.947385e-01 7.828622e-03 -1.021469e-01 7.757772e+01 +-1.028405e-01 5.871368e-02 9.929635e-01 1.037849e+02 1.216107e-02 9.982560e-01 -5.776712e-02 -7.308559e+00 -9.946235e-01 6.134700e-03 -1.033751e-01 7.745043e+01 +-1.045565e-01 5.860639e-02 9.927907e-01 1.050341e+02 1.185647e-02 9.982646e-01 -5.768087e-02 -7.394646e+00 -9.944482e-01 5.740074e-03 -1.050700e-01 7.731942e+01 +-1.068276e-01 5.728775e-02 9.926258e-01 1.062831e+02 1.215405e-02 9.983394e-01 -5.630947e-02 -7.478364e+00 -9.942032e-01 6.049008e-03 -1.073465e-01 7.718259e+01 +-1.098782e-01 5.235797e-02 9.925651e-01 1.075331e+02 8.644135e-03 9.986242e-01 -5.172068e-02 -7.561306e+00 -9.939074e-01 2.896888e-03 -1.101796e-01 7.704728e+01 +-1.139706e-01 5.194301e-02 9.921253e-01 1.087743e+02 8.262714e-03 9.986473e-01 -5.133530e-02 -7.641329e+00 -9.934497e-01 2.346930e-03 -1.142456e-01 7.690436e+01 +-1.195938e-01 5.673661e-02 9.912005e-01 1.100019e+02 2.541051e-03 9.983800e-01 -5.684099e-02 -7.722951e+00 -9.928196e-01 -4.279140e-03 -1.195442e-01 7.676378e+01 +-1.267574e-01 6.210592e-02 9.899876e-01 1.112386e+02 3.716825e-03 9.980607e-01 -6.213650e-02 -7.807969e+00 -9.919267e-01 -4.196651e-03 -1.267424e-01 7.660787e+01 +-1.357632e-01 5.923628e-02 9.889689e-01 1.124618e+02 6.028125e-03 9.982419e-01 -5.896419e-02 -7.896792e+00 -9.907229e-01 -2.043545e-03 -1.358816e-01 7.643702e+01 +-1.468222e-01 5.383870e-02 9.876967e-01 1.136907e+02 5.285012e-03 9.985461e-01 -5.364448e-02 -7.983049e+00 -9.891487e-01 -2.656214e-03 -1.468933e-01 7.625308e+01 +-1.594597e-01 5.569923e-02 9.856319e-01 1.149114e+02 7.842035e-03 9.984470e-01 -5.515472e-02 -8.061834e+00 -9.871732e-01 -1.065599e-03 -1.596488e-01 7.604901e+01 +-1.737504e-01 5.634415e-02 9.831766e-01 1.161296e+02 9.453501e-03 9.984113e-01 -5.554659e-02 -8.141038e+00 -9.847443e-01 -3.567834e-04 -1.740070e-01 7.582078e+01 +-1.884259e-01 5.405645e-02 9.805986e-01 1.173410e+02 9.523557e-03 9.985376e-01 -5.321538e-02 -8.223598e+00 -9.820412e-01 -6.883714e-04 -1.886651e-01 7.558130e+01 +-2.036572e-01 5.590004e-02 9.774451e-01 1.185414e+02 1.458706e-02 9.984311e-01 -5.406093e-02 -8.306282e+00 -9.789336e-01 3.248151e-03 -2.041530e-01 7.531661e+01 +-2.190626e-01 5.932381e-02 9.739057e-01 1.197281e+02 1.460824e-02 9.982374e-01 -5.752009e-02 -8.388866e+00 -9.756014e-01 1.626542e-03 -2.195431e-01 7.504274e+01 +-2.343892e-01 6.389957e-02 9.700405e-01 1.209037e+02 1.493501e-02 9.979563e-01 -6.212977e-02 -8.474808e+00 -9.720281e-01 -7.498799e-05 -2.348645e-01 7.475130e+01 +-2.506675e-01 6.208529e-02 9.660804e-01 1.220798e+02 1.136813e-02 9.980613e-01 -6.119089e-02 -8.561332e+00 -9.680065e-01 -4.356038e-03 -2.508873e-01 7.444731e+01 +-2.670267e-01 5.550955e-02 9.620891e-01 1.232631e+02 5.398909e-03 9.984102e-01 -5.610671e-02 -8.644916e+00 -9.636740e-01 -9.787759e-03 -2.669018e-01 7.412704e+01 +-2.830064e-01 5.113256e-02 9.577541e-01 1.244375e+02 1.087702e-03 9.985943e-01 -5.299155e-02 -8.723087e+00 -9.591174e-01 -1.395520e-02 -2.826642e-01 7.378566e+01 +-2.984538e-01 5.237678e-02 9.529859e-01 1.255966e+02 -6.646978e-04 9.984814e-01 -5.508542e-02 -8.799145e+00 -9.544238e-01 -1.707390e-02 -2.979657e-01 7.342718e+01 +-3.131229e-01 5.450156e-02 9.481475e-01 1.267459e+02 -8.339620e-04 9.983358e-01 -5.766192e-02 -8.874807e+00 -9.497122e-01 -1.884598e-02 -3.125563e-01 7.304799e+01 +-3.271078e-01 5.623719e-02 9.433122e-01 1.278828e+02 5.194592e-04 9.982382e-01 -5.933158e-02 -8.954510e+00 -9.449869e-01 -1.891781e-02 -3.265607e-01 7.265186e+01 +-3.413455e-01 5.661713e-02 9.382312e-01 1.290149e+02 2.514476e-03 9.982356e-01 -5.932327e-02 -9.035824e+00 -9.399345e-01 -1.789057e-02 -3.408856e-01 7.223590e+01 +-3.555538e-01 5.435651e-02 9.330739e-01 1.301383e+02 2.025469e-03 9.983499e-01 -5.738738e-02 -9.118396e+00 -9.346536e-01 -1.851439e-02 -3.550772e-01 7.180658e+01 +-3.701034e-01 5.298037e-02 9.274786e-01 1.312536e+02 1.738222e-03 9.984102e-01 -5.633858e-02 -9.199095e+00 -9.289889e-01 -1.923894e-02 -3.696071e-01 7.136168e+01 +-3.850383e-01 5.379297e-02 9.213316e-01 1.323546e+02 1.404929e-04 9.983033e-01 -5.822835e-02 -9.279118e+00 -9.229006e-01 -2.229070e-02 -3.843925e-01 7.090448e+01 +-3.998406e-01 5.665126e-02 9.148323e-01 1.334422e+02 1.254572e-03 9.981210e-01 -6.126063e-02 -9.359054e+00 -9.165838e-01 -2.334676e-02 -3.991603e-01 7.042848e+01 +-4.147639e-01 5.782533e-02 9.080898e-01 1.345288e+02 1.957902e-03 9.980331e-01 -6.265849e-02 -9.441782e+00 -9.099269e-01 -2.421053e-02 -4.140613e-01 6.993130e+01 +-4.291460e-01 6.062984e-02 9.011980e-01 1.356043e+02 4.536845e-03 9.978766e-01 -6.497368e-02 -9.527433e+00 -9.032237e-01 -2.379459e-02 -4.285098e-01 6.941460e+01 +-4.440749e-01 6.369173e-02 8.937231e-01 1.366762e+02 4.605216e-03 9.976193e-01 -6.880773e-02 -9.614880e+00 -8.959778e-01 -2.644000e-02 -4.433110e-01 6.888030e+01 +-4.591859e-01 6.647746e-02 8.858494e-01 1.377420e+02 5.241398e-03 9.973814e-01 -7.213034e-02 -9.704590e+00 -8.883247e-01 -2.847814e-02 -4.583319e-01 6.832845e+01 +-4.745463e-01 6.377536e-02 8.779172e-01 1.388096e+02 4.079370e-03 9.975204e-01 -7.025878e-02 -9.795509e+00 -8.802211e-01 -2.975969e-02 -4.736297e-01 6.775361e+01 +-4.907005e-01 5.958726e-02 8.692885e-01 1.398723e+02 9.702285e-04 9.976956e-01 -6.784154e-02 -9.888913e+00 -8.713278e-01 -3.244647e-02 -4.896275e-01 6.716223e+01 +-5.068055e-01 5.910555e-02 8.600319e-01 1.409268e+02 3.201704e-04 9.976596e-01 -6.837534e-02 -9.978781e+00 -8.620604e-01 -3.437764e-02 -5.056382e-01 6.654673e+01 +-5.227946e-01 5.862140e-02 8.504407e-01 1.419671e+02 -9.632887e-04 9.975914e-01 -6.935677e-02 -1.006744e+01 -8.524581e-01 -3.707856e-02 -5.214789e-01 6.591185e+01 +-5.386551e-01 5.748528e-02 8.405630e-01 1.430034e+02 -1.762478e-03 9.975906e-01 -6.935370e-02 -1.015971e+01 -8.425245e-01 -3.883919e-02 -5.372558e-01 6.525392e+01 +-5.543975e-01 5.665967e-02 8.303211e-01 1.440312e+02 -3.289861e-03 9.975229e-01 -7.026585e-02 -1.025440e+01 -8.322455e-01 -4.168685e-02 -5.528378e-01 6.457481e+01 +-5.699025e-01 5.633664e-02 8.197789e-01 1.450446e+02 -3.767636e-03 9.974573e-01 -7.116625e-02 -1.034928e+01 -8.217037e-01 -4.364645e-02 -5.682411e-01 6.387549e+01 +-5.852070e-01 5.380572e-02 8.090969e-01 1.460542e+02 -4.333161e-03 9.975743e-01 -6.947377e-02 -1.044366e+01 -8.108724e-01 -4.416248e-02 -5.835543e-01 6.315165e+01 +-6.003517e-01 4.984753e-02 7.981811e-01 1.470512e+02 -4.691967e-03 9.978189e-01 -6.584427e-02 -1.053685e+01 -7.997223e-01 -4.327475e-02 -5.988083e-01 6.240627e+01 +-6.151770e-01 4.798841e-02 7.869272e-01 1.480355e+02 -3.861206e-03 9.979504e-01 -6.387552e-02 -1.062705e+01 -7.883796e-01 -4.233323e-02 -6.137308e-01 6.164068e+01 +-6.300491e-01 4.677825e-02 7.751451e-01 1.490120e+02 -4.430473e-03 9.979512e-01 -6.382526e-02 -1.071697e+01 -7.765426e-01 -4.364730e-02 -6.285510e-01 6.085284e+01 +-6.448530e-01 4.765821e-02 7.628194e-01 1.499695e+02 -5.932360e-03 9.977119e-01 -6.734842e-02 -1.080867e+01 -7.642836e-01 -4.795514e-02 -6.430947e-01 6.004930e+01 +-6.601554e-01 4.807287e-02 7.495892e-01 1.509179e+02 -7.959097e-03 9.974461e-01 -7.097801e-02 -1.090070e+01 -7.510869e-01 -5.282256e-02 -6.580868e-01 5.922635e+01 +-6.759769e-01 4.389162e-02 7.356145e-01 1.518570e+02 -1.026709e-02 9.975668e-01 -6.895616e-02 -1.099532e+01 -7.368512e-01 -5.416538e-02 -6.738815e-01 5.837761e+01 +-6.920178e-01 3.666505e-02 7.209487e-01 1.527818e+02 -1.387299e-02 9.978494e-01 -6.406359e-02 -1.108992e+01 -7.217471e-01 -5.433486e-02 -6.900208e-01 5.750416e+01 +-7.087861e-01 3.354619e-02 7.046254e-01 1.536878e+02 -1.554520e-02 9.978833e-01 -6.314479e-02 -1.118205e+01 -7.052521e-01 -5.570968e-02 -7.067643e-01 5.660812e+01 +-7.261680e-01 3.174083e-02 6.867843e-01 1.545733e+02 -1.701688e-02 9.977979e-01 -6.410755e-02 -1.126982e+01 -6.873067e-01 -5.823976e-02 -7.240287e-01 5.568878e+01 +-7.436033e-01 2.726223e-02 6.680651e-01 1.554368e+02 -2.066737e-02 9.977537e-01 -6.372032e-02 -1.136018e+01 -6.683016e-01 -6.118978e-02 -7.413695e-01 5.474664e+01 +-7.603254e-01 2.534661e-02 6.490477e-01 1.562981e+02 -2.095143e-02 9.977614e-01 -6.350810e-02 -1.144851e+01 -6.492044e-01 -6.188529e-02 -7.580922e-01 5.377203e+01 +-7.763938e-01 2.696189e-02 6.296712e-01 1.571378e+02 -1.901017e-02 9.976281e-01 -6.615727e-02 -1.153501e+01 -6.299614e-01 -6.333424e-02 -7.740396e-01 5.277454e+01 +-7.916322e-01 2.782679e-02 6.103640e-01 1.579474e+02 -1.540224e-02 9.977360e-01 -6.546375e-02 -1.162413e+01 -6.108037e-01 -6.122417e-02 -7.894114e-01 5.175294e+01 +-8.061937e-01 2.802466e-02 5.909876e-01 1.587557e+02 -1.178252e-02 9.979190e-01 -6.339446e-02 -1.172195e+01 -5.915343e-01 -5.807153e-02 -8.041857e-01 5.072638e+01 +-8.205562e-01 2.934926e-02 5.708119e-01 1.595353e+02 -1.020400e-02 9.977694e-01 -6.597051e-02 -1.182015e+01 -5.714748e-01 -5.995707e-02 -8.184263e-01 4.968737e+01 +-8.343732e-01 3.073320e-02 5.503426e-01 1.602798e+02 -9.666920e-03 9.974749e-01 -7.035876e-02 -1.191873e+01 -5.511152e-01 -6.402557e-02 -8.319691e-01 4.863458e+01 +-8.473601e-01 3.138936e-02 5.300903e-01 1.610032e+02 -7.512040e-03 9.974429e-01 -7.107187e-02 -1.202126e+01 -5.309656e-01 -6.420551e-02 -8.449574e-01 4.756063e+01 +-8.591530e-01 2.947331e-02 5.108694e-01 1.616863e+02 -5.867495e-03 9.977069e-01 -6.742782e-02 -1.212200e+01 -5.116852e-01 -6.092832e-02 -8.570098e-01 4.646556e+01 +-8.696587e-01 3.033618e-02 4.927205e-01 1.623490e+02 -4.478865e-03 9.975840e-01 -6.932527e-02 -1.223005e+01 -4.936332e-01 -6.249614e-02 -8.674217e-01 4.535334e+01 +-8.791217e-01 3.444202e-02 4.753513e-01 1.629730e+02 -4.303311e-04 9.973276e-01 -7.305819e-02 -1.233141e+01 -4.765972e-01 -6.443159e-02 -8.767574e-01 4.422905e+01 +-8.880977e-01 3.251626e-02 4.585033e-01 1.635887e+02 -1.746026e-03 9.972489e-01 -7.410516e-02 -1.244119e+01 -4.596515e-01 -6.661317e-02 -8.855976e-01 4.309552e+01 +-8.963481e-01 2.945246e-02 4.423716e-01 1.641798e+02 -3.886570e-03 9.972306e-01 -7.426928e-02 -1.255286e+01 -4.433339e-01 -6.829043e-02 -8.937513e-01 4.194672e+01 +-9.036836e-01 2.714888e-02 4.273395e-01 1.647509e+02 -4.750838e-03 9.972909e-01 -7.340441e-02 -1.266162e+01 -4.281746e-01 -6.836456e-02 -9.011064e-01 4.078883e+01 +-9.102455e-01 2.600678e-02 4.132515e-01 1.652989e+02 -4.902027e-03 9.972789e-01 -7.355827e-02 -1.277147e+01 -4.140400e-01 -6.898184e-02 -9.076411e-01 3.962170e+01 +-9.164022e-01 2.343048e-02 3.995724e-01 1.658309e+02 -6.282311e-03 9.973202e-01 -7.288999e-02 -1.287876e+01 -4.002094e-01 -6.930677e-02 -9.137991e-01 3.844779e+01 +-9.220764e-01 1.853237e-02 3.865639e-01 1.663487e+02 -8.920852e-03 9.975696e-01 -6.910382e-02 -1.298468e+01 -3.869050e-01 -6.716747e-02 -9.196700e-01 3.726247e+01 +-9.272038e-01 1.438065e-02 3.742813e-01 1.668523e+02 -1.080005e-02 9.978207e-01 -6.509320e-02 -1.308684e+01 -3.744017e-01 -6.439690e-02 -9.250277e-01 3.606610e+01 +-9.315300e-01 1.506714e-02 3.633523e-01 1.673354e+02 -8.349529e-03 9.979918e-01 -6.278956e-02 -1.318536e+01 -3.635687e-01 -6.152416e-02 -9.295335e-01 3.486197e+01 +-9.347864e-01 1.886181e-02 3.547094e-01 1.677973e+02 -4.031579e-03 9.979615e-01 -6.369168e-02 -1.327958e+01 -3.551876e-01 -6.096814e-02 -9.328047e-01 3.365811e+01 +-9.370317e-01 2.457554e-02 3.483787e-01 1.682484e+02 1.714583e-03 9.978328e-01 -6.577806e-02 -1.337387e+01 -3.492402e-01 -6.103879e-02 -9.350430e-01 3.244993e+01 +-9.387719e-01 2.887410e-02 3.433274e-01 1.686912e+02 5.720562e-03 9.976511e-01 -6.826133e-02 -1.347182e+01 -3.444919e-01 -6.211778e-02 -9.367319e-01 3.124282e+01 +-9.406262e-01 2.649369e-02 3.384089e-01 1.691379e+02 3.739559e-03 9.976977e-01 -6.771447e-02 -1.357156e+01 -3.394238e-01 -6.242849e-02 -9.385596e-01 3.002817e+01 +-9.425240e-01 1.898839e-02 3.335987e-01 1.695751e+02 -2.382830e-03 9.979766e-01 -6.353697e-02 -1.367179e+01 -3.341302e-01 -6.068001e-02 -9.405716e-01 2.881254e+01 +-9.443599e-01 1.275283e-02 3.286667e-01 1.699695e+02 -7.661388e-03 9.981240e-01 -6.074246e-02 -1.377138e+01 -3.288247e-01 -5.988078e-02 -9.424906e-01 2.758224e+01 +-9.460336e-01 6.644945e-03 3.240005e-01 1.703619e+02 -1.457739e-02 9.979051e-01 -6.302993e-02 -1.386787e+01 -3.237406e-01 -6.435150e-02 -9.439549e-01 2.635507e+01 +-9.473135e-01 4.236096e-03 3.202801e-01 1.707494e+02 -1.761706e-02 9.977099e-01 -6.530310e-02 -1.396352e+01 -3.198232e-01 -6.750488e-02 -9.450694e-01 2.513071e+01 +-9.481384e-01 4.640768e-03 3.178242e-01 1.711273e+02 -1.792368e-02 9.975218e-01 -6.803574e-02 -1.406469e+01 -3.173523e-01 -7.020386e-02 -9.457055e-01 2.390019e+01 +-9.484550e-01 4.732105e-03 3.168766e-01 1.715130e+02 -1.828631e-02 9.974054e-01 -6.962830e-02 -1.416740e+01 -3.163839e-01 -7.183380e-02 -9.459075e-01 2.267273e+01 +-9.483731e-01 7.781758e-03 3.170613e-01 1.718911e+02 -1.555184e-02 9.973553e-01 -7.099613e-02 -1.427268e+01 -3.167753e-01 -7.226170e-02 -9.457439e-01 2.144258e+01 +-9.480194e-01 9.724102e-03 3.180641e-01 1.722632e+02 -1.434561e-02 9.972107e-01 -7.324593e-02 -1.438257e+01 -3.178892e-01 -7.400137e-02 -9.452355e-01 2.022133e+01 +-9.476428e-01 9.822768e-03 3.191812e-01 1.726177e+02 -1.491672e-02 9.970740e-01 -7.497235e-02 -1.449077e+01 -3.189837e-01 -7.580813e-02 -9.447235e-01 1.901008e+01 +-9.470945e-01 1.100027e-02 3.207663e-01 1.729947e+02 -1.363043e-02 9.971323e-01 -7.444064e-02 -1.459753e+01 -3.206653e-01 -7.487449e-02 -9.442285e-01 1.779910e+01 +-9.462450e-01 1.157848e-02 3.232437e-01 1.733770e+02 -1.320085e-02 9.971440e-01 -7.436078e-02 -1.470734e+01 -3.231815e-01 -7.463059e-02 -9.433896e-01 1.659909e+01 +-9.449736e-01 1.047688e-02 3.269790e-01 1.737830e+02 -1.487282e-02 9.970778e-01 -7.493049e-02 -1.481889e+01 -3.268086e-01 -7.567042e-02 -9.420563e-01 1.540117e+01 +-9.434098e-01 9.139435e-03 3.315033e-01 1.741985e+02 -1.580782e-02 9.972445e-01 -7.248046e-02 -1.492971e+01 -3.312523e-01 -7.361911e-02 -9.406657e-01 1.420288e+01 +-9.413760e-01 6.548169e-03 3.372957e-01 1.746270e+02 -1.775362e-02 9.974646e-01 -6.891405e-02 -1.503629e+01 -3.368917e-01 -7.086224e-02 -9.388729e-01 1.300435e+01 +-9.389337e-01 4.898762e-03 3.440633e-01 1.750609e+02 -1.926985e-02 9.975809e-01 -6.679015e-02 -1.513842e+01 -3.435581e-01 -6.934156e-02 -9.365679e-01 1.181186e+01 +-9.361848e-01 6.838381e-03 3.514418e-01 1.754926e+02 -1.729108e-02 9.977044e-01 -6.547411e-02 -1.523869e+01 -3.510828e-01 -6.737266e-02 -9.339174e-01 1.062387e+01 +-9.329017e-01 7.633253e-03 3.600503e-01 1.759425e+02 -1.748685e-02 9.976359e-01 -6.645940e-02 -1.533995e+01 -3.597064e-01 -6.829622e-02 -9.305626e-01 9.442182e+00 +-9.292045e-01 9.590084e-03 3.694415e-01 1.763996e+02 -1.636866e-02 9.976142e-01 -6.706623e-02 -1.544296e+01 -3.692033e-01 -6.836549e-02 -9.268306e-01 8.270144e+00 +-9.249782e-01 1.243720e-02 3.798168e-01 1.768674e+02 -1.433284e-02 9.976114e-01 -6.757225e-02 -1.554426e+01 -3.797499e-01 -6.794669e-02 -9.225904e-01 7.090384e+00 +-9.200882e-01 1.406705e-02 3.914586e-01 1.773568e+02 -1.378514e-02 9.975731e-01 -6.824850e-02 -1.564895e+01 -3.914686e-01 -6.819094e-02 -9.176613e-01 5.917093e+00 +-9.144018e-01 1.656591e-02 4.044688e-01 1.778608e+02 -1.283812e-02 9.974729e-01 -6.987748e-02 -1.574904e+01 -4.046042e-01 -6.908870e-02 -9.118783e-01 4.751502e+00 +-9.082935e-01 1.851377e-02 4.179237e-01 1.783814e+02 -1.149285e-02 9.975388e-01 -6.916836e-02 -1.585596e+01 -4.181756e-01 -6.762830e-02 -9.058451e-01 3.587553e+00 +-9.020526e-01 1.808352e-02 4.312473e-01 1.789288e+02 -1.198908e-02 9.976867e-01 -6.691399e-02 -1.595971e+01 -4.314597e-01 -6.553018e-02 -8.997490e-01 2.434985e+00 +-8.954347e-01 2.025720e-02 4.447319e-01 1.794976e+02 -1.042715e-02 9.977359e-01 -6.644043e-02 -1.605749e+01 -4.450709e-01 -6.413034e-02 -8.931960e-01 1.286303e+00 +-8.885482e-01 2.304306e-02 4.582043e-01 1.800782e+02 -8.184333e-03 9.977828e-01 -6.604949e-02 -1.615417e+01 -4.587103e-01 -6.243824e-02 -8.863894e-01 1.518369e-01 +-8.811820e-01 2.466797e-02 4.721333e-01 1.806758e+02 -6.112156e-03 9.979600e-01 -6.354897e-02 -1.625068e+01 -4.727377e-01 -5.888395e-02 -8.792336e-01 -9.718759e-01 +-8.734527e-01 2.634193e-02 4.861960e-01 1.812884e+02 -3.474420e-03 9.981729e-01 -6.032250e-02 -1.634719e+01 -4.868966e-01 -5.437809e-02 -8.717652e-01 -2.083451e+00 +-8.652660e-01 2.933019e-02 5.004544e-01 1.819124e+02 4.676872e-05 9.982917e-01 -5.842616e-02 -1.644108e+01 -5.013131e-01 -5.053075e-02 -8.637892e-01 -3.175742e+00 +-8.561114e-01 3.255949e-02 5.157647e-01 1.825544e+02 3.561865e-03 9.983614e-01 -5.711286e-02 -1.653684e+01 -5.167791e-01 -4.705788e-02 -8.548244e-01 -4.252484e+00 +-8.457804e-01 3.547323e-02 5.323507e-01 1.832060e+02 6.694286e-03 9.984143e-01 -5.589378e-02 -1.662889e+01 -5.334893e-01 -4.371014e-02 -8.446766e-01 -5.312670e+00 +-8.347783e-01 3.853858e-02 5.492358e-01 1.838767e+02 1.002387e-02 9.984457e-01 -5.482341e-02 -1.671309e+01 -5.504950e-01 -4.025992e-02 -8.338671e-01 -6.356535e+00 +-8.235014e-01 4.043438e-02 5.658715e-01 1.845607e+02 1.185435e-02 9.984655e-01 -5.409403e-02 -1.678878e+01 -5.671904e-01 -3.783846e-02 -8.227169e-01 -7.384682e+00 +-8.116733e-01 4.254831e-02 5.825600e-01 1.852717e+02 1.357688e-02 9.984482e-01 -5.400698e-02 -1.685989e+01 -5.839538e-01 -3.592667e-02 -8.109914e-01 -8.397022e+00 +-7.989402e-01 4.453744e-02 5.997592e-01 1.860033e+02 1.539242e-02 9.984417e-01 -5.363892e-02 -1.693795e+01 -6.012135e-01 -3.362254e-02 -7.983807e-01 -9.390930e+00 +-7.851375e-01 4.563178e-02 6.176382e-01 1.867509e+02 1.726200e-02 9.985068e-01 -5.182745e-02 -1.701685e+01 -6.190809e-01 -3.002999e-02 -7.847528e-01 -1.036879e+01 +-7.698594e-01 4.679091e-02 6.364961e-01 1.875240e+02 1.954956e-02 9.985697e-01 -4.976242e-02 -1.709398e+01 -6.379141e-01 -2.586684e-02 -7.696729e-01 -1.132239e+01 +-7.531570e-01 4.964898e-02 6.559647e-01 1.883161e+02 2.159436e-02 9.984764e-01 -5.077926e-02 -1.717484e+01 -6.574863e-01 -2.407961e-02 -7.530815e-01 -1.224512e+01 +-7.357859e-01 5.257551e-02 6.751704e-01 1.891165e+02 2.279980e-02 9.983398e-01 -5.289401e-02 -1.725841e+01 -6.768303e-01 -2.352492e-02 -7.357630e-01 -1.313563e+01 +-7.179204e-01 5.335086e-02 6.940779e-01 1.899427e+02 2.251928e-02 9.983169e-01 -5.344362e-02 -1.734401e+01 -6.957609e-01 -2.273813e-02 -7.179134e-01 -1.400312e+01 +-6.988036e-01 5.334505e-02 7.133217e-01 1.907892e+02 2.243061e-02 9.983591e-01 -5.268723e-02 -1.742978e+01 -7.149618e-01 -2.081778e-02 -6.988534e-01 -1.484446e+01 +-6.788333e-01 5.270760e-02 7.323983e-01 1.916657e+02 2.088409e-02 9.984028e-01 -5.249414e-02 -1.751550e+01 -7.339954e-01 -2.033930e-02 -6.788498e-01 -1.565688e+01 +-6.583472e-01 5.283580e-02 7.508578e-01 1.925591e+02 1.914929e-02 9.983861e-01 -5.346373e-02 -1.760506e+01 -7.524708e-01 -2.081930e-02 -6.582964e-01 -1.643657e+01 +-6.375578e-01 5.240607e-02 7.686181e-01 1.934648e+02 1.687597e-02 9.983943e-01 -5.407435e-02 -1.768808e+01 -7.702177e-01 -2.150434e-02 -6.374184e-01 -1.719672e+01 +-6.161963e-01 5.218652e-02 7.858618e-01 1.943859e+02 1.587175e-02 9.984225e-01 -5.385692e-02 -1.776122e+01 -7.874326e-01 -2.071344e-02 -6.160525e-01 -1.793122e+01 +-5.936213e-01 5.189981e-02 8.030692e-01 1.953232e+02 1.617560e-02 9.984861e-01 -5.257214e-02 -1.783289e+01 -8.045819e-01 -1.821781e-02 -5.935621e-01 -1.864428e+01 +-5.694423e-01 5.213294e-02 8.203766e-01 1.962565e+02 1.603100e-02 9.985014e-01 -5.232487e-02 -1.790335e+01 -8.218750e-01 -1.664453e-02 -5.694246e-01 -1.932892e+01 +-5.440034e-01 5.521021e-02 8.372647e-01 1.972261e+02 1.809848e-02 9.983728e-01 -5.407460e-02 -1.797620e+01 -8.388878e-01 -1.426354e-02 -5.441174e-01 -1.998080e+01 +-5.171328e-01 5.632981e-02 8.540496e-01 1.982141e+02 1.860245e-02 9.983359e-01 -5.458249e-02 -1.804905e+01 -8.557030e-01 -1.233898e-02 -5.173201e-01 -2.060575e+01 +-4.899252e-01 5.488205e-02 8.700352e-01 1.992336e+02 1.716191e-02 9.984301e-01 -5.331722e-02 -1.812215e+01 -8.715955e-01 -1.118999e-02 -4.900979e-01 -2.119040e+01 +-4.618397e-01 5.266267e-02 8.853987e-01 2.002718e+02 1.614475e-02 9.985695e-01 -5.097259e-02 -1.819392e+01 -8.868165e-01 -9.246622e-03 -4.620292e-01 -2.174303e+01 +-4.322490e-01 5.332423e-02 9.001763e-01 2.013106e+02 1.663332e-02 9.985517e-01 -5.116472e-02 -1.827035e+01 -9.016008e-01 -7.142980e-03 -4.325099e-01 -2.226336e+01 +-4.011809e-01 5.580592e-02 9.142974e-01 2.023713e+02 1.725580e-02 9.984257e-01 -5.336927e-02 -1.833982e+01 -9.158363e-01 -5.633802e-03 -4.015123e-01 -2.274978e+01 +-3.691348e-01 5.748137e-02 9.275966e-01 2.034483e+02 1.897112e-02 9.983435e-01 -5.431593e-02 -1.840364e+01 -9.291822e-01 -2.452357e-03 -3.696138e-01 -2.320318e+01 +-3.369369e-01 5.817495e-02 9.397283e-01 2.045291e+02 2.099576e-02 9.983053e-01 -5.427327e-02 -1.847329e+01 -9.412931e-01 1.443641e-03 -3.375873e-01 -2.361922e+01 +-3.041173e-01 5.746240e-02 9.509000e-01 2.056382e+02 2.099531e-02 9.983409e-01 -5.361451e-02 -1.854755e+01 -9.524032e-01 3.659334e-03 -3.048191e-01 -2.399109e+01 +-2.704016e-01 5.656836e-02 9.610843e-01 2.067589e+02 2.278022e-02 9.983687e-01 -5.235367e-02 -1.862449e+01 -9.624780e-01 7.737187e-03 -2.712492e-01 -2.432519e+01 +-2.361937e-01 5.423640e-02 9.701912e-01 2.079046e+02 2.253868e-02 9.984782e-01 -5.033068e-02 -1.870354e+01 -9.714445e-01 9.979034e-03 -2.370567e-01 -2.461443e+01 +-2.011242e-01 5.287146e-02 9.781379e-01 2.090532e+02 2.351278e-02 9.985152e-01 -4.913824e-02 -1.878448e+01 -9.792835e-01 1.311585e-02 -2.020688e-01 -2.486248e+01 +-1.657778e-01 5.206309e-02 9.847879e-01 2.101843e+02 2.445446e-02 9.985154e-01 -4.867220e-02 -1.886430e+01 -9.858598e-01 1.601368e-02 -1.668048e-01 -2.506817e+01 +-1.300221e-01 5.177117e-02 9.901586e-01 2.113358e+02 2.493802e-02 9.984907e-01 -4.893211e-02 -1.894167e+01 -9.911974e-01 1.833034e-02 -1.311169e-01 -2.522909e+01 +-9.416868e-02 5.145834e-02 9.942255e-01 2.124889e+02 2.570050e-02 9.984561e-01 -4.924308e-02 -1.902022e+01 -9.952244e-01 2.091493e-02 -9.534579e-02 -2.534952e+01 +-5.873709e-02 5.163443e-02 9.969373e-01 2.136307e+02 2.461228e-02 9.984327e-01 -5.026180e-02 -1.910093e+01 -9.979700e-01 2.158465e-02 -5.991587e-02 -2.542449e+01 +-2.407939e-02 5.144077e-02 9.983857e-01 2.147979e+02 2.395692e-02 9.984182e-01 -5.086466e-02 -1.917493e+01 -9.994229e-01 2.269345e-02 -2.527366e-02 -2.546063e+01 +9.577161e-03 5.025395e-02 9.986906e-01 2.159576e+02 2.292501e-02 9.984628e-01 -5.046234e-02 -1.924675e+01 -9.996913e-01 2.337826e-02 8.410367e-03 -2.545508e+01 +4.275877e-02 5.033924e-02 9.978165e-01 2.171170e+02 2.152922e-02 9.984515e-01 -5.129387e-02 -1.932543e+01 -9.988534e-01 2.367547e-02 4.160879e-02 -2.540746e+01 +7.585907e-02 5.033438e-02 9.958473e-01 2.182711e+02 2.232151e-02 9.983891e-01 -5.216321e-02 -1.940655e+01 -9.968686e-01 2.618586e-02 7.461332e-02 -2.531946e+01 +1.081227e-01 4.825522e-02 9.929657e-01 2.194167e+02 2.335676e-02 9.984222e-01 -5.106369e-02 -1.948433e+01 -9.938631e-01 2.871360e-02 1.068250e-01 -2.519951e+01 +1.395127e-01 4.659667e-02 9.891234e-01 2.205719e+02 2.455047e-02 9.984224e-01 -5.049751e-02 -1.956459e+01 -9.899159e-01 3.132848e-02 1.381486e-01 -2.503982e+01 +1.699060e-01 4.654172e-02 9.843606e-01 2.217231e+02 2.572482e-02 9.983342e-01 -5.164266e-02 -1.964163e+01 -9.851244e-01 3.409688e-02 1.684257e-01 -2.484743e+01 +1.999265e-01 4.632560e-02 9.787152e-01 2.228707e+02 2.759799e-02 9.982191e-01 -5.288635e-02 -1.971631e+01 -9.794221e-01 3.758394e-02 1.982919e-01 -2.462354e+01 +2.299944e-01 4.534770e-02 9.721349e-01 2.240212e+02 2.968319e-02 9.981221e-01 -5.358260e-02 -1.979060e+01 -9.727391e-01 4.117974e-02 2.282164e-01 -2.436371e+01 +2.602941e-01 4.364096e-02 9.645426e-01 2.251627e+02 3.222907e-02 9.980286e-01 -5.385347e-02 -1.986716e+01 -9.649913e-01 4.510404e-02 2.583745e-01 -2.406861e+01 +2.902679e-01 4.198546e-02 9.560240e-01 2.263000e+02 3.400687e-02 9.979534e-01 -5.415204e-02 -1.994366e+01 -9.563409e-01 4.822997e-02 2.882460e-01 -2.373710e+01 +3.199517e-01 4.092864e-02 9.465494e-01 2.274299e+02 3.704000e-02 9.977623e-01 -5.566331e-02 -2.002061e+01 -9.467095e-01 5.286975e-02 3.177197e-01 -2.337292e+01 +3.485898e-01 4.031639e-02 9.364079e-01 2.285386e+02 3.749710e-02 9.976747e-01 -5.691297e-02 -2.009904e+01 -9.365250e-01 5.495185e-02 3.462675e-01 -2.297037e+01 +3.767229e-01 3.830567e-02 9.255337e-01 2.296486e+02 3.816295e-02 9.976545e-01 -5.682418e-02 -2.017834e+01 -9.255395e-01 5.672806e-02 3.743775e-01 -2.253278e+01 +4.047494e-01 3.726952e-02 9.136678e-01 2.307475e+02 3.819186e-02 9.976082e-01 -5.761231e-02 -2.025931e+01 -9.136297e-01 5.821321e-02 4.023579e-01 -2.205870e+01 +4.330703e-01 3.808961e-02 9.005550e-01 2.318181e+02 3.921906e-02 9.973642e-01 -6.104439e-02 -2.034293e+01 -9.005065e-01 6.175542e-02 4.304350e-01 -2.155490e+01 +4.612298e-01 3.877064e-02 8.864333e-01 2.328868e+02 4.053635e-02 9.970809e-01 -6.470205e-02 -2.042941e+01 -8.863542e-01 6.577526e-02 4.583118e-01 -2.101599e+01 +4.885604e-01 3.771474e-02 8.717146e-01 2.339284e+02 4.145481e-02 9.969338e-01 -6.636608e-02 -2.052253e+01 -8.715447e-01 6.856058e-02 4.854989e-01 -2.044385e+01 +5.151047e-01 3.453696e-02 8.564312e-01 2.349792e+02 4.224436e-02 9.969506e-01 -6.561171e-02 -2.060518e+01 -8.560856e-01 6.997627e-02 5.120749e-01 -1.983554e+01 +5.402185e-01 3.236943e-02 8.409021e-01 2.360124e+02 4.156516e-02 9.970139e-01 -6.508135e-02 -2.068599e+01 -8.404977e-01 7.011036e-02 5.372598e-01 -1.919422e+01 +5.633304e-01 3.210978e-02 8.256076e-01 2.370196e+02 3.971925e-02 9.970368e-01 -6.587839e-02 -2.076805e+01 -8.252764e-01 6.990380e-02 5.603857e-01 -1.852677e+01 +5.843328e-01 3.215985e-02 8.108767e-01 2.380160e+02 3.840815e-02 9.969987e-01 -6.721919e-02 -2.086008e+01 -8.106047e-01 7.042263e-02 5.813438e-01 -1.782777e+01 +6.037991e-01 3.082784e-02 7.965402e-01 2.389997e+02 3.739595e-02 9.970562e-01 -6.693539e-02 -2.095439e+01 -7.962589e-01 7.020289e-02 6.008688e-01 -1.710277e+01 +6.220780e-01 2.821468e-02 7.824468e-01 2.399610e+02 3.691618e-02 9.971820e-01 -6.530786e-02 -2.104741e+01 -7.820845e-01 6.951151e-02 6.192834e-01 -1.635594e+01 +6.391623e-01 2.490061e-02 7.686687e-01 2.409137e+02 3.780612e-02 9.972500e-01 -6.374188e-02 -2.113844e+01 -7.681420e-01 6.980177e-02 6.364632e-01 -1.558475e+01 +6.552142e-01 2.252144e-02 7.551074e-01 2.418488e+02 3.840746e-02 9.972697e-01 -6.307058e-02 -2.122694e+01 -7.544662e-01 7.032648e-02 6.525602e-01 -1.479112e+01 +6.705493e-01 2.011560e-02 7.415923e-01 2.427798e+02 4.002910e-02 9.971950e-01 -6.324320e-02 -2.130601e+01 -7.407843e-01 7.209293e-02 6.678632e-01 -1.398455e+01 +6.855542e-01 1.965789e-02 7.277562e-01 2.436978e+02 3.973815e-02 9.971347e-01 -6.436802e-02 -2.139183e+01 -7.269363e-01 7.304743e-02 6.828086e-01 -1.315891e+01 +7.005457e-01 1.820511e-02 7.133753e-01 2.445843e+02 4.015983e-02 9.970844e-01 -6.488286e-02 -2.148418e+01 -7.124766e-01 7.410242e-02 6.977721e-01 -1.230142e+01 +7.153220e-01 1.606306e-02 6.986104e-01 2.454585e+02 3.945976e-02 9.972121e-01 -6.333247e-02 -2.158194e+01 -6.976800e-01 7.287009e-02 7.126938e-01 -1.141406e+01 +7.294358e-01 1.271575e-02 6.839311e-01 2.463238e+02 3.969872e-02 9.973551e-01 -6.088302e-02 -2.166508e+01 -6.828963e-01 7.156143e-02 7.270017e-01 -1.051863e+01 +7.433877e-01 1.107941e-02 6.687691e-01 2.471693e+02 3.951499e-02 9.973889e-01 -6.044753e-02 -2.174737e+01 -6.676926e-01 7.136233e-02 7.410088e-01 -9.605238e+00 +7.568594e-01 1.001092e-02 6.535011e-01 2.479970e+02 4.109201e-02 9.971756e-01 -6.286679e-02 -2.183017e+01 -6.522847e-01 7.443498e-02 7.543103e-01 -8.674394e+00 +7.693900e-01 9.691660e-03 6.387058e-01 2.488108e+02 4.126419e-02 9.970424e-01 -6.483619e-02 -2.191923e+01 -6.374451e-01 7.623998e-02 7.667145e-01 -7.723093e+00 +7.809766e-01 8.669113e-03 6.245002e-01 2.496079e+02 4.051072e-02 9.970949e-01 -6.450254e-02 -2.200935e+01 -6.232451e-01 7.567391e-02 7.783565e-01 -6.749400e+00 +7.919238e-01 6.268942e-03 6.105879e-01 2.503906e+02 4.062092e-02 9.971914e-01 -6.292298e-02 -2.210053e+01 -6.092674e-01 7.463283e-02 7.894448e-01 -5.759310e+00 +8.025342e-01 3.050388e-03 5.965984e-01 2.511588e+02 4.208502e-02 9.972064e-01 -6.171075e-02 -2.219183e+01 -5.951200e-01 7.463283e-02 8.001638e-01 -4.750831e+00 +8.124464e-01 2.352376e-03 5.830311e-01 2.519117e+02 4.226955e-02 9.971227e-01 -6.292520e-02 -2.228256e+01 -5.815016e-01 7.576780e-02 8.100093e-01 -3.727347e+00 +8.215643e-01 -7.952617e-05 5.701160e-01 2.526556e+02 4.534549e-02 9.968410e-01 -6.520596e-02 -2.237398e+01 -5.683097e-01 7.942306e-02 8.189725e-01 -2.686673e+00 +8.300930e-01 -2.521415e-03 5.576193e-01 2.533816e+02 4.691222e-02 9.967605e-01 -6.532818e-02 -2.246494e+01 -5.556481e-01 8.038761e-02 8.275221e-01 -1.629795e+00 +8.378877e-01 -6.169470e-03 5.458078e-01 2.540996e+02 4.894939e-02 9.967566e-01 -6.387712e-02 -2.255787e+01 -5.436434e-01 8.023880e-02 8.354720e-01 -5.569069e-01 +8.448170e-01 -7.197428e-03 5.350070e-01 2.548065e+02 4.989954e-02 9.966115e-01 -6.538781e-02 -2.265094e+01 -5.327235e-01 8.193732e-02 8.423134e-01 5.340190e-01 +8.504416e-01 -8.997077e-03 5.259926e-01 2.554974e+02 5.076607e-02 9.965909e-01 -6.503357e-02 -2.274419e+01 -5.236143e-01 8.200981e-02 8.479990e-01 1.628717e+00 +8.544344e-01 -9.782287e-03 5.194673e-01 2.561826e+02 5.006762e-02 9.967198e-01 -6.358301e-02 -2.283906e+01 -5.171414e-01 8.033598e-02 8.521214e-01 2.742665e+00 +8.573847e-01 -1.135724e-02 5.145508e-01 2.568640e+02 5.049887e-02 9.967888e-01 -6.214388e-02 -2.293222e+01 -5.121927e-01 7.926543e-02 8.552049e-01 3.862410e+00 +8.600172e-01 -1.211744e-02 5.101212e-01 2.575400e+02 5.047970e-02 9.968343e-01 -6.142525e-02 -2.302562e+01 -5.077620e-01 7.857752e-02 8.579063e-01 4.989321e+00 +8.624972e-01 -1.352007e-02 5.058813e-01 2.582139e+02 5.180622e-02 9.967501e-01 -6.168755e-02 -2.311631e+01 -5.034032e-01 7.941312e-02 8.603945e-01 6.122792e+00 +8.646826e-01 -1.557921e-02 5.020770e-01 2.588844e+02 5.255451e-02 9.968392e-01 -5.957852e-02 -2.320738e+01 -4.995618e-01 7.790290e-02 8.627682e-01 7.263272e+00 +8.667994e-01 -1.776168e-02 4.983406e-01 2.595538e+02 5.415000e-02 9.968083e-01 -5.865907e-02 -2.329792e+01 -4.957082e-01 7.783077e-02 8.649946e-01 8.410914e+00 +8.690764e-01 -1.913789e-02 4.943076e-01 2.602177e+02 5.558421e-02 9.967011e-01 -5.913761e-02 -2.338751e+01 -4.915451e-01 7.887078e-02 8.672731e-01 9.561299e+00 +8.712172e-01 -2.014540e-02 4.904842e-01 2.608776e+02 5.633959e-02 9.966587e-01 -5.913732e-02 -2.347785e+01 -4.876540e-01 7.915511e-02 8.694412e-01 1.071832e+01 +8.733381e-01 -1.981769e-02 4.867114e-01 2.615318e+02 5.532408e-02 9.967422e-01 -5.868670e-02 -2.356959e+01 -4.839627e-01 7.818017e-02 8.715892e-01 1.188297e+01 +8.754505e-01 -2.043746e-02 4.828756e-01 2.621825e+02 5.556316e-02 9.967370e-01 -5.854927e-02 -2.366098e+01 -4.801034e-01 7.808706e-02 8.737294e-01 1.305063e+01 +8.773528e-01 -2.026634e-02 4.794177e-01 2.628287e+02 5.501302e-02 9.967681e-01 -5.853973e-02 -2.375316e+01 -4.766819e-01 7.773419e-02 8.756322e-01 1.422261e+01 +8.786943e-01 -1.898258e-02 4.770074e-01 2.634683e+02 5.327962e-02 9.968660e-01 -5.847584e-02 -2.384485e+01 -4.744024e-01 7.679714e-02 8.769518e-01 1.539509e+01 +8.795538e-01 -1.713225e-02 4.754911e-01 2.641063e+02 5.081091e-02 9.970188e-01 -5.806577e-02 -2.393728e+01 -4.730787e-01 7.523208e-02 8.778021e-01 1.657248e+01 +8.800517e-01 -1.679953e-02 4.745807e-01 2.647416e+02 5.024747e-02 9.970580e-01 -5.788325e-02 -2.402944e+01 -4.722120e-01 7.478671e-02 8.783067e-01 1.774592e+01 +8.806470e-01 -1.513616e-02 4.735313e-01 2.653736e+02 4.889292e-02 9.970565e-01 -5.905794e-02 -2.412178e+01 -4.712435e-01 7.516151e-02 8.787947e-01 1.891696e+01 +8.812814e-01 -1.324083e-02 4.724064e-01 2.660071e+02 4.753442e-02 9.970216e-01 -6.073120e-02 -2.421655e+01 -4.701952e-01 7.597683e-02 8.792860e-01 2.009385e+01 +8.816651e-01 -1.175852e-02 4.717293e-01 2.666376e+02 4.673882e-02 9.969496e-01 -6.250476e-02 -2.431116e+01 -4.695554e-01 7.715631e-02 8.795252e-01 2.126615e+01 +8.816461e-01 -1.002529e-02 4.718048e-01 2.672661e+02 4.469889e-02 9.970534e-01 -6.234112e-02 -2.440836e+01 -4.697896e-01 7.605194e-02 8.794963e-01 2.244106e+01 +8.818460e-01 -9.433519e-03 4.714433e-01 2.678947e+02 4.355353e-02 9.971554e-01 -6.151497e-02 -2.450560e+01 -4.695219e-01 7.477973e-02 8.797483e-01 2.361274e+01 +8.819981e-01 -1.112639e-02 4.711216e-01 2.685277e+02 4.481706e-02 9.971704e-01 -6.035313e-02 -2.460279e+01 -4.691170e-01 7.434562e-02 8.800011e-01 2.478610e+01 +8.821088e-01 -1.426371e-02 4.708297e-01 2.691617e+02 4.748292e-02 9.971427e-01 -5.875191e-02 -2.469678e+01 -4.686464e-01 7.418193e-02 8.802656e-01 2.595922e+01 +8.822045e-01 -1.636056e-02 4.705822e-01 2.697745e+02 4.929495e-02 9.971134e-01 -5.774737e-02 -2.479217e+01 -4.682790e-01 7.414230e-02 8.804644e-01 2.714565e+01 +8.824070e-01 -1.733486e-02 4.701674e-01 2.703750e+02 5.118227e-02 9.969271e-01 -5.930228e-02 -2.488855e+01 -4.676946e-01 7.639297e-02 8.805826e-01 2.833421e+01 +8.826342e-01 -1.769649e-02 4.697274e-01 2.709762e+02 5.275372e-02 9.967073e-01 -6.157617e-02 -2.498198e+01 -4.670910e-01 7.912908e-02 8.806614e-01 2.952576e+01 +8.827621e-01 -1.775061e-02 4.694848e-01 2.715972e+02 5.296702e-02 9.966753e-01 -6.190973e-02 -2.506758e+01 -4.668250e-01 7.951876e-02 8.807673e-01 3.072067e+01 +8.828171e-01 -1.795764e-02 4.693737e-01 2.722195e+02 5.217744e-02 9.968337e-01 -5.999987e-02 -2.515485e+01 -4.668100e-01 7.745961e-02 8.809587e-01 3.191781e+01 +8.828801e-01 -1.867902e-02 4.692270e-01 2.728429e+02 5.202131e-02 9.969489e-01 -5.819475e-02 -2.524066e+01 -4.667083e-01 7.578877e-02 8.811580e-01 3.312009e+01 +8.828738e-01 -1.899195e-02 4.692262e-01 2.734771e+02 5.173659e-02 9.970333e-01 -5.699015e-02 -2.532468e+01 -4.667518e-01 7.459126e-02 8.812371e-01 3.431742e+01 +8.829195e-01 -1.886100e-02 4.691454e-01 2.741247e+02 5.174333e-02 9.970154e-01 -5.729672e-02 -2.539916e+01 -4.666645e-01 7.486353e-02 8.812602e-01 3.550224e+01 +8.829802e-01 -1.872236e-02 4.690367e-01 2.747717e+02 5.183910e-02 9.969818e-01 -5.779301e-02 -2.547556e+01 -4.665390e-01 7.534451e-02 8.812857e-01 3.669434e+01 +8.830545e-01 -1.836151e-02 4.689112e-01 2.754146e+02 5.153257e-02 9.969853e-01 -5.800653e-02 -2.555348e+01 -4.664324e-01 7.538711e-02 8.813385e-01 3.787300e+01 +8.831713e-01 -1.727388e-02 4.687325e-01 2.760505e+02 5.078890e-02 9.969678e-01 -5.895430e-02 -2.564312e+01 -4.662929e-01 7.587314e-02 8.813706e-01 3.906005e+01 +8.832902e-01 -1.591472e-02 4.685565e-01 2.766804e+02 4.944939e-02 9.970114e-01 -5.935466e-02 -2.573958e+01 -4.662115e-01 7.559720e-02 8.814373e-01 4.025886e+01 +8.833160e-01 -1.717209e-02 4.684635e-01 2.773332e+02 4.849503e-02 9.973144e-01 -5.488254e-02 -2.581772e+01 -4.662629e-01 7.119676e-02 8.817765e-01 4.146026e+01 +8.833949e-01 -1.996735e-02 4.682038e-01 2.779897e+02 4.854712e-02 9.976157e-01 -4.905241e-02 -2.589095e+01 -4.661080e-01 6.606258e-02 8.822579e-01 4.266533e+01 +8.835419e-01 -2.080835e-02 4.678897e-01 2.786412e+02 4.837570e-02 9.977238e-01 -4.697897e-02 -2.596207e+01 -4.658471e-01 6.414237e-02 8.825373e-01 4.386931e+01 +8.837829e-01 -2.005834e-02 4.674671e-01 2.792787e+02 4.788040e-02 9.977129e-01 -4.771120e-02 -2.603112e+01 -4.654410e-01 6.454884e-02 8.827220e-01 4.507929e+01 +8.840439e-01 -1.962083e-02 4.669920e-01 2.799126e+02 4.760399e-02 9.977027e-01 -4.819839e-02 -2.608758e+01 -4.649735e-01 6.484016e-02 8.829470e-01 4.630183e+01 +8.844652e-01 -2.000550e-02 4.661772e-01 2.805375e+02 4.669350e-02 9.978602e-01 -4.576819e-02 -2.614117e+01 -4.642640e-01 6.224780e-02 8.835067e-01 4.751695e+01 +8.851486e-01 -2.172738e-02 4.648010e-01 2.811555e+02 4.723304e-02 9.979450e-01 -4.329922e-02 -2.620061e+01 -4.629051e-01 6.028020e-02 8.843558e-01 4.873888e+01 +8.859643e-01 -2.256063e-02 4.632045e-01 2.817758e+02 4.796379e-02 9.979172e-01 -4.313548e-02 -2.626818e+01 -4.612666e-01 6.043353e-02 8.852010e-01 4.994990e+01 +8.869182e-01 -2.297194e-02 4.613550e-01 2.823751e+02 4.866709e-02 9.978510e-01 -4.387327e-02 -2.634535e+01 -4.593557e-01 6.136480e-02 8.861301e-01 5.115076e+01 +8.882337e-01 -2.253104e-02 4.588391e-01 2.829719e+02 4.799828e-02 9.978815e-01 -4.391601e-02 -2.643327e+01 -4.568776e-01 6.103115e-02 8.874334e-01 5.234355e+01 +8.896842e-01 -2.297630e-02 4.559980e-01 2.835631e+02 4.761079e-02 9.979568e-01 -4.260810e-02 -2.652407e+01 -4.540873e-01 5.961816e-02 8.889602e-01 5.353272e+01 +8.910715e-01 -2.358221e-02 4.532500e-01 2.841668e+02 4.695450e-02 9.980804e-01 -4.038139e-02 -2.660443e+01 -4.514277e-01 5.726482e-02 8.904682e-01 5.471160e+01 +8.923803e-01 -2.533091e-02 4.505728e-01 2.847651e+02 4.718236e-02 9.981885e-01 -3.732933e-02 -2.668221e+01 -4.488110e-01 5.457103e-02 8.919588e-01 5.588580e+01 +8.937322e-01 -2.758897e-02 4.477518e-01 2.853565e+02 4.837207e-02 9.982143e-01 -3.504613e-02 -2.675282e+01 -4.459854e-01 5.298053e-02 8.934708e-01 5.705677e+01 +8.951369e-01 -2.863093e-02 4.448711e-01 2.859400e+02 4.942895e-02 9.981565e-01 -3.521814e-02 -2.681824e+01 -4.430426e-01 5.351455e-02 8.949019e-01 5.822462e+01 +8.965490e-01 -2.922661e-02 4.419794e-01 2.865120e+02 5.020654e-02 9.980955e-01 -3.584256e-02 -2.688396e+01 -4.400900e-01 5.432486e-02 8.963088e-01 5.938303e+01 +8.979296e-01 -2.825816e-02 4.392312e-01 2.870756e+02 4.972088e-02 9.980613e-01 -3.743464e-02 -2.695456e+01 -4.373218e-01 5.545262e-02 8.975937e-01 6.053646e+01 +8.990265e-01 -2.784710e-02 4.370080e-01 2.876286e+02 4.920081e-02 9.980802e-01 -3.761758e-02 -2.702747e+01 -4.351214e-01 5.532034e-02 8.986706e-01 6.168480e+01 +8.998586e-01 -2.744439e-02 4.353176e-01 2.881771e+02 4.789099e-02 9.982012e-01 -3.606582e-02 -2.709889e+01 -4.335448e-01 5.330191e-02 8.995542e-01 6.282951e+01 +9.002990e-01 -2.617090e-02 4.344847e-01 2.887120e+02 4.737827e-02 9.981520e-01 -3.804983e-02 -2.718433e+01 -4.326859e-01 5.484135e-02 8.998751e-01 6.395491e+01 +9.004102e-01 -2.505723e-02 4.343197e-01 2.892480e+02 4.852627e-02 9.978945e-01 -4.303068e-02 -2.726850e+01 -4.323270e-01 5.982116e-02 8.997303e-01 6.507854e+01 +9.004747e-01 -2.031906e-02 4.344336e-01 2.897689e+02 4.569844e-02 9.977988e-01 -4.805324e-02 -2.735745e+01 -4.325009e-01 6.312365e-02 8.994211e-01 6.618529e+01 +8.997096e-01 -1.748636e-02 4.361387e-01 2.902939e+02 4.313559e-02 9.978680e-01 -4.897622e-02 -2.744639e+01 -4.343524e-01 6.287746e-02 8.985457e-01 6.728910e+01 +8.980739e-01 -1.401572e-02 4.396214e-01 2.908162e+02 3.943145e-02 9.980332e-01 -4.873331e-02 -2.755177e+01 -4.380737e-01 6.110101e-02 8.968601e-01 6.838540e+01 +8.953256e-01 -8.339108e-03 4.453343e-01 2.913402e+02 3.396951e-02 9.981912e-01 -4.960260e-02 -2.765073e+01 -4.441151e-01 5.953825e-02 8.939893e-01 6.947439e+01 +8.916821e-01 -5.157048e-03 4.526329e-01 2.918711e+02 3.092781e-02 9.982925e-01 -4.955348e-02 -2.775392e+01 -4.516044e-01 5.818488e-02 8.903190e-01 7.055982e+01 +8.874219e-01 -3.436524e-03 4.609453e-01 2.924080e+02 2.966026e-02 9.983257e-01 -4.965967e-02 -2.785444e+01 -4.600029e-01 5.774082e-02 8.860380e-01 7.163397e+01 +8.824717e-01 -2.404826e-03 4.703594e-01 2.929650e+02 2.883561e-02 9.983826e-01 -4.899587e-02 -2.794039e+01 -4.694808e-01 5.680056e-02 8.811137e-01 7.269948e+01 +8.768318e-01 -2.218774e-03 4.807921e-01 2.935381e+02 2.865906e-02 9.984524e-01 -4.765851e-02 -2.801389e+01 -4.799423e-01 5.556753e-02 8.755384e-01 7.375360e+01 +8.703099e-01 -4.029010e-03 4.924880e-01 2.941300e+02 3.098748e-02 9.984332e-01 -4.659202e-02 -2.808563e+01 -4.915287e-01 5.581045e-02 8.690711e-01 7.479825e+01 +8.631432e-01 -2.886490e-03 5.049511e-01 2.947341e+02 2.996174e-02 9.985146e-01 -4.550751e-02 -2.815544e+01 -5.040696e-01 5.440869e-02 8.619474e-01 7.583600e+01 +8.551974e-01 -2.242481e-03 5.182976e-01 2.953511e+02 2.959165e-02 9.985707e-01 -4.450615e-02 -2.822322e+01 -5.174570e-01 5.339882e-02 8.540414e-01 7.686456e+01 +8.462370e-01 3.015126e-04 5.328066e-01 2.959714e+02 2.749574e-02 9.986427e-01 -4.423560e-02 -2.830366e+01 -5.320967e-01 5.208370e-02 8.450800e-01 7.788702e+01 +8.359234e-01 4.234362e-03 5.488299e-01 2.966105e+02 2.583621e-02 9.985581e-01 -4.705528e-02 -2.838466e+01 -5.482378e-01 5.351428e-02 8.346086e-01 7.889731e+01 +8.243849e-01 6.865350e-03 5.659880e-01 2.972617e+02 2.477404e-02 9.985306e-01 -4.819645e-02 -2.846592e+01 -5.654872e-01 5.375423e-02 8.230034e-01 7.989280e+01 +8.117974e-01 9.316890e-03 5.838649e-01 2.979466e+02 2.322763e-02 9.985661e-01 -4.822975e-02 -2.854581e+01 -5.834770e-01 5.271457e-02 8.104169e-01 8.087240e+01 +7.977762e-01 1.066194e-02 6.028595e-01 2.986448e+02 2.210333e-02 9.986544e-01 -4.691161e-02 -2.862837e+01 -6.025485e-01 5.075015e-02 7.964670e-01 8.183689e+01 +7.830685e-01 1.239010e-02 6.218121e-01 2.993679e+02 1.976829e-02 9.988005e-01 -4.479675e-02 -2.870452e+01 -6.216212e-01 4.737108e-02 7.818842e-01 8.277199e+01 +7.670636e-01 1.451887e-02 6.414068e-01 3.001134e+02 1.738000e-02 9.989067e-01 -4.339611e-02 -2.877963e+01 -6.413356e-01 4.443522e-02 7.659726e-01 8.368846e+01 +7.500728e-01 1.722674e-02 6.611310e-01 3.008679e+02 1.557867e-02 9.989231e-01 -4.370288e-02 -2.885420e+01 -6.611718e-01 4.307988e-02 7.489966e-01 8.457890e+01 +7.318410e-01 2.020307e-02 6.811760e-01 3.016547e+02 1.425274e-02 9.988880e-01 -4.493897e-02 -2.892578e+01 -6.813264e-01 4.259679e-02 7.307392e-01 8.544443e+01 +7.119818e-01 2.296702e-02 7.018223e-01 3.024631e+02 1.253375e-02 9.988901e-01 -4.540370e-02 -2.899859e+01 -7.020861e-01 4.112307e-02 7.109036e-01 8.628440e+01 +6.905519e-01 2.575476e-02 7.228242e-01 3.032798e+02 1.038920e-02 9.989095e-01 -4.551724e-02 -2.907074e+01 -7.232082e-01 3.894158e-02 6.895313e-01 8.709419e+01 +6.672326e-01 2.703787e-02 7.443586e-01 3.041299e+02 9.116819e-03 9.989696e-01 -4.445848e-02 -2.914176e+01 -7.447936e-01 3.645032e-02 6.662985e-01 8.787373e+01 +6.420709e-01 2.814106e-02 7.661286e-01 3.049878e+02 7.707750e-03 9.990386e-01 -4.315585e-02 -2.921197e+01 -7.666065e-01 3.361423e-02 6.412367e-01 8.861999e+01 +6.156333e-01 2.787550e-02 7.875396e-01 3.058818e+02 7.660545e-03 9.991152e-01 -4.135275e-02 -2.927962e+01 -7.879955e-01 3.149111e-02 6.148750e-01 8.933310e+01 +5.880299e-01 2.882443e-02 8.083254e-01 3.067958e+02 6.838965e-03 9.991519e-01 -4.060432e-02 -2.934553e+01 -8.088102e-01 2.940465e-02 5.873340e-01 9.000974e+01 +5.597121e-01 3.037988e-02 8.281301e-01 3.077053e+02 6.426586e-03 9.991386e-01 -4.099688e-02 -2.941041e+01 -8.286622e-01 2.826849e-02 5.590347e-01 9.064561e+01 +5.307598e-01 3.317570e-02 8.468727e-01 3.086449e+02 5.653365e-03 9.990727e-01 -4.268117e-02 -2.947378e+01 -8.475034e-01 2.744112e-02 5.300801e-01 9.124501e+01 +5.008540e-01 3.378160e-02 8.648723e-01 3.096103e+02 5.528904e-03 9.990928e-01 -4.222604e-02 -2.953513e+01 -8.655141e-01 2.593087e-02 5.002128e-01 9.181531e+01 +4.704945e-01 3.301070e-02 8.817853e-01 3.105669e+02 5.450799e-03 9.991722e-01 -4.031362e-02 -2.959748e+01 -8.823861e-01 2.377376e-02 4.699250e-01 9.234168e+01 +4.397830e-01 3.211367e-02 8.975298e-01 3.115574e+02 5.950806e-03 9.992344e-01 -3.866852e-02 -2.965731e+01 -8.980843e-01 2.234678e-02 4.392551e-01 9.283539e+01 +4.082298e-01 3.394773e-02 9.122478e-01 3.125406e+02 4.728995e-03 9.992162e-01 -3.930033e-02 -2.971672e+01 -9.128669e-01 2.035758e-02 4.077493e-01 9.328799e+01 +3.758892e-01 3.637339e-02 9.259505e-01 3.135495e+02 5.649057e-03 9.991208e-01 -4.154093e-02 -2.977541e+01 -9.266474e-01 2.084552e-02 3.753532e-01 9.370432e+01 +3.429078e-01 3.917740e-02 9.385518e-01 3.145745e+02 6.081535e-03 9.990164e-01 -4.392328e-02 -2.983560e+01 -9.393493e-01 2.076947e-02 3.423323e-01 9.408525e+01 +3.098186e-01 3.982746e-02 9.499612e-01 3.155897e+02 6.643982e-03 9.990072e-01 -4.405060e-02 -2.989502e+01 -9.507724e-01 1.995921e-02 3.092464e-01 9.442487e+01 +2.758771e-01 3.844616e-02 9.604237e-01 3.166366e+02 4.512634e-03 9.991369e-01 -4.129210e-02 -2.995473e+01 -9.611823e-01 1.572558e-02 2.754655e-01 9.473325e+01 +2.414517e-01 3.613818e-02 9.697397e-01 3.176908e+02 4.722397e-03 9.992507e-01 -3.841375e-02 -3.001187e+01 -9.704013e-01 1.385455e-02 2.411001e-01 9.500157e+01 +2.069094e-01 3.571477e-02 9.777080e-01 3.187311e+02 3.630099e-03 9.992986e-01 -3.727168e-02 -3.006850e+01 -9.783533e-01 1.126103e-02 2.066346e-01 9.523110e+01 +1.717369e-01 3.703548e-02 9.844465e-01 3.197947e+02 3.953233e-03 9.992591e-01 -3.828239e-02 -3.012356e+01 -9.851349e-01 1.046624e-02 1.714633e-01 9.542232e+01 +1.368249e-01 4.202488e-02 9.897034e-01 3.208590e+02 1.623560e-03 9.990888e-01 -4.264787e-02 -3.016824e+01 -9.905939e-01 7.442130e-03 1.366320e-01 9.558824e+01 +1.019517e-01 4.625686e-02 9.937133e-01 3.219470e+02 6.942772e-04 9.989148e-01 -4.657023e-02 -3.021446e+01 -9.947891e-01 5.437821e-03 1.018089e-01 9.571904e+01 +6.703631e-02 4.748231e-02 9.966201e-01 3.230375e+02 -2.666890e-04 9.988678e-01 -4.757147e-02 -3.026402e+01 -9.977505e-01 2.923224e-03 6.697307e-02 9.581136e+01 +3.156718e-02 4.484208e-02 9.984952e-01 3.241126e+02 -2.041458e-03 9.989939e-01 -4.479994e-02 -3.031537e+01 -9.994995e-01 -6.241818e-04 3.162696e-02 9.586232e+01 +-3.940387e-03 3.962768e-02 9.992068e-01 3.252020e+02 -2.810660e-03 9.992101e-01 -3.963891e-02 -3.036708e+01 -9.999882e-01 -2.964626e-03 -3.825893e-03 9.587514e+01 +-3.962908e-02 3.658258e-02 9.985446e-01 3.262896e+02 -4.638304e-03 9.993121e-01 -3.679479e-02 -3.041637e+01 -9.992037e-01 -6.089699e-03 -3.943213e-02 9.585109e+01 +-7.606457e-02 3.893567e-02 9.963424e-01 3.273400e+02 -4.138606e-03 9.992163e-01 -3.936394e-02 -3.046610e+01 -9.970943e-01 -7.117672e-03 -7.584382e-02 9.577936e+01 +-1.123520e-01 4.207939e-02 9.927771e-01 3.284041e+02 -2.828521e-03 9.990853e-01 -4.266688e-02 -3.051098e+01 -9.936644e-01 -7.601802e-03 -1.121302e-01 9.567252e+01 +-1.488951e-01 4.202969e-02 9.879594e-01 3.294405e+02 -4.514681e-03 9.990570e-01 -4.318222e-02 -3.056169e+01 -9.888427e-01 -1.088994e-02 -1.485649e-01 9.552365e+01 +-1.851665e-01 3.857334e-02 9.819499e-01 3.305458e+02 -7.005235e-03 9.991521e-01 -4.057007e-02 -3.060903e+01 -9.826822e-01 -1.439101e-02 -1.847392e-01 9.532182e+01 +-2.212745e-01 3.581193e-02 9.745538e-01 3.316354e+02 -7.939630e-03 9.992262e-01 -3.852128e-02 -3.065512e+01 -9.751792e-01 -1.626137e-02 -2.208189e-01 9.508603e+01 +-2.568828e-01 3.277614e-02 9.658866e-01 3.326914e+02 -9.884094e-03 9.992834e-01 -3.653816e-02 -3.069719e+01 -9.663920e-01 -1.893294e-02 -2.563747e-01 9.481170e+01 +-2.918987e-01 3.012843e-02 9.559746e-01 3.337304e+02 -9.656136e-03 9.993600e-01 -3.444419e-02 -3.073619e+01 -9.564004e-01 -1.928524e-02 -2.914210e-01 9.450986e+01 +-3.265623e-01 2.682701e-02 9.447949e-01 3.347562e+02 -9.887336e-03 9.994454e-01 -3.179629e-02 -3.077361e+01 -9.451239e-01 -1.972498e-02 -3.261160e-01 9.417190e+01 +-3.610514e-01 2.421858e-02 9.322314e-01 3.357192e+02 -9.562099e-03 9.995140e-01 -2.966992e-02 -3.078325e+01 -9.324969e-01 -1.962645e-02 -3.606443e-01 9.380084e+01 +-3.951080e-01 2.253221e-02 9.183583e-01 3.366889e+02 -1.073748e-02 9.995176e-01 -2.914310e-02 -3.081099e+01 -9.185719e-01 -2.137552e-02 -3.946754e-01 9.339796e+01 +-4.287009e-01 2.216813e-02 9.031745e-01 3.376369e+02 -1.193111e-02 9.994728e-01 -3.019497e-02 -3.085966e+01 -9.033677e-01 -2.372048e-02 -4.282103e-01 9.296335e+01 +-4.613655e-01 2.251846e-02 8.869244e-01 3.385572e+02 -1.070344e-02 9.994638e-01 -3.094355e-02 -3.090431e+01 -8.871456e-01 -2.376943e-02 -4.608770e-01 9.248807e+01 +-4.934209e-01 2.081948e-02 8.695415e-01 3.394758e+02 -1.154287e-02 9.994687e-01 -3.048034e-02 -3.093784e+01 -8.697140e-01 -2.507664e-02 -4.929184e-01 9.199528e+01 +-5.256449e-01 1.892426e-02 8.504936e-01 3.403632e+02 -1.286509e-02 9.994614e-01 -3.019017e-02 -3.097476e+01 -8.506068e-01 -2.681098e-02 -5.251182e-01 9.146107e+01 +-5.578479e-01 1.935754e-02 8.297175e-01 3.412507e+02 -1.388537e-02 9.993703e-01 -3.265122e-02 -3.101885e+01 -8.298270e-01 -2.973534e-02 -5.572278e-01 9.091840e+01 +-5.894881e-01 1.870110e-02 8.075606e-01 3.421278e+02 -1.663015e-02 9.992391e-01 -3.527928e-02 -3.106294e+01 -8.076058e-01 -3.422657e-02 -5.887285e-01 9.032548e+01 +-6.203686e-01 1.694081e-02 7.841275e-01 3.429641e+02 -1.844662e-02 9.991750e-01 -3.618104e-02 -3.111183e+01 -7.840934e-01 -3.691008e-02 -6.195442e-01 8.969218e+01 +-6.501193e-01 1.535427e-02 7.596771e-01 3.438048e+02 -1.920517e-02 9.991443e-01 -3.662976e-02 -3.116246e+01 -7.595894e-01 -3.840343e-02 -6.492680e-01 8.901640e+01 +-6.791392e-01 1.280569e-02 7.338979e-01 3.446277e+02 -2.178977e-02 9.990554e-01 -3.759636e-02 -3.122212e+01 -7.336860e-01 -4.152462e-02 -6.782186e-01 8.831983e+01 +-7.070121e-01 1.240558e-02 7.070927e-01 3.454033e+02 -2.158443e-02 9.990018e-01 -3.910897e-02 -3.128356e+01 -7.068720e-01 -4.291270e-02 -7.060385e-01 8.757917e+01 +-7.338981e-01 1.032965e-02 6.791811e-01 3.461744e+02 -2.348121e-02 9.989009e-01 -4.056520e-02 -3.133560e+01 -6.788536e-01 -4.571871e-02 -7.328489e-01 8.679168e+01 +-7.599961e-01 9.120945e-03 6.498636e-01 3.468926e+02 -2.446515e-02 9.987913e-01 -4.262948e-02 -3.139203e+01 -6.494670e-01 -4.829724e-02 -7.588544e-01 8.596231e+01 +-7.843105e-01 8.261315e-03 6.203135e-01 3.475922e+02 -2.341038e-02 9.988050e-01 -4.290162e-02 -3.143194e+01 -6.199266e-01 -4.816996e-02 -7.831798e-01 8.509257e+01 +-8.075909e-01 6.169080e-03 5.897109e-01 3.482601e+02 -2.269372e-02 9.988796e-01 -4.152784e-02 -3.147383e+01 -5.893064e-01 -4.692023e-02 -8.065460e-01 8.418825e+01 +-8.299145e-01 5.352765e-03 5.578650e-01 3.488732e+02 -2.086912e-02 9.989562e-01 -4.063128e-02 -3.152191e+01 -5.575002e-01 -4.536263e-02 -8.289365e-01 8.326112e+01 +-8.507188e-01 5.384843e-03 5.255936e-01 3.494634e+02 -1.916965e-02 9.989644e-01 -4.126241e-02 -3.156643e+01 -5.252714e-01 -4.517815e-02 -8.497345e-01 8.232149e+01 +-8.703117e-01 2.096763e-03 4.924969e-01 3.500267e+02 -2.005626e-02 9.990105e-01 -3.969547e-02 -3.161810e+01 -4.920928e-01 -4.442508e-02 -8.694084e-01 8.136120e+01 +-8.882599e-01 2.102433e-03 4.593365e-01 3.505207e+02 -1.612978e-02 9.992300e-01 -3.576520e-02 -3.166459e+01 -4.590580e-01 -3.917778e-02 -8.875420e-01 8.038229e+01 +-9.040897e-01 -1.517751e-03 4.273400e-01 3.510025e+02 -1.699108e-02 9.993306e-01 -3.239746e-02 -3.171342e+01 -4.270048e-01 -3.655117e-02 -9.035103e-01 7.939779e+01 +-9.185637e-01 -5.436511e-03 3.952357e-01 3.514504e+02 -1.945706e-02 9.993151e-01 -3.147430e-02 -3.176115e+01 -3.947938e-01 -3.660127e-02 -9.180403e-01 7.840742e+01 +-9.318690e-01 4.605406e-05 3.627950e-01 3.518307e+02 -1.342805e-02 9.993104e-01 -3.461792e-02 -3.180643e+01 -3.625464e-01 -3.713099e-02 -9.312257e-01 7.740523e+01 +-9.431365e-01 -1.769090e-03 3.324010e-01 3.522040e+02 -1.631811e-02 9.990266e-01 -4.098317e-02 -3.185273e+01 -3.320049e-01 -4.407687e-02 -9.422472e-01 7.640283e+01 +-9.521466e-01 -1.413377e-03 3.056386e-01 3.525292e+02 -1.618512e-02 9.988194e-01 -4.580216e-02 -3.190374e+01 -3.052130e-01 -4.855716e-02 -9.510453e-01 7.538747e+01 +-9.597008e-01 1.155832e-03 2.810216e-01 3.528360e+02 -1.185485e-02 9.989349e-01 -4.459344e-02 -3.195765e+01 -2.807738e-01 -4.612783e-02 -9.586648e-01 7.435964e+01 +-9.660147e-01 4.352187e-03 2.584507e-01 3.531078e+02 -6.851740e-03 9.990758e-01 -4.243383e-02 -3.201222e+01 -2.583965e-01 -4.276253e-02 -9.650920e-01 7.330649e+01 +-9.709271e-01 6.021935e-03 2.392999e-01 3.533538e+02 -3.789561e-03 9.991715e-01 -4.051963e-02 -3.206292e+01 -2.393456e-01 -4.024844e-02 -9.700998e-01 7.224390e+01 +-9.745985e-01 7.619454e-03 2.238300e-01 3.535839e+02 -1.346842e-03 9.992036e-01 -3.987859e-02 -3.210888e+01 -2.239556e-01 -3.916707e-02 -9.738120e-01 7.116473e+01 +-9.772849e-01 9.588432e-03 2.117129e-01 3.538112e+02 1.052517e-03 9.991832e-01 -4.039434e-02 -3.213885e+01 -2.119273e-01 -3.925393e-02 -9.764967e-01 7.009665e+01 +-9.792743e-01 9.971020e-03 2.022929e-01 3.540381e+02 1.582210e-03 9.991336e-01 -4.158808e-02 -3.216678e+01 -2.025323e-01 -4.040606e-02 -9.784416e-01 6.902950e+01 +-9.809430e-01 1.047483e-02 1.940132e-01 3.542547e+02 2.364847e-03 9.991154e-01 -4.198575e-02 -3.219995e+01 -1.942813e-01 -4.072681e-02 -9.801000e-01 6.796041e+01 +-9.824772e-01 1.000820e-02 1.861143e-01 3.544647e+02 2.313930e-03 9.991353e-01 -4.151307e-02 -3.224229e+01 -1.863688e-01 -4.035498e-02 -9.816507e-01 6.688905e+01 +-9.840022e-01 9.795356e-03 1.778869e-01 3.546730e+02 2.578459e-03 9.991658e-01 -4.075615e-02 -3.229780e+01 -1.781377e-01 -3.964546e-02 -9.832065e-01 6.581079e+01 +-9.854022e-01 9.583833e-03 1.699726e-01 3.548705e+02 2.568297e-03 9.991374e-01 -4.144651e-02 -3.235261e+01 -1.702232e-01 -4.040493e-02 -9.845768e-01 6.473818e+01 +-9.867794e-01 1.030711e-02 1.617415e-01 3.550474e+02 3.583864e-03 9.991193e-01 -4.180475e-02 -3.240759e+01 -1.620299e-01 -4.067240e-02 -9.859472e-01 6.366461e+01 +-9.880906e-01 1.052240e-02 1.535133e-01 3.552099e+02 4.172685e-03 9.991245e-01 -4.162641e-02 -3.246546e+01 -1.538169e-01 -4.049009e-02 -9.872694e-01 6.258830e+01 +-9.893378e-01 9.608208e-03 1.453222e-01 3.553577e+02 3.681741e-03 9.991525e-01 -4.099572e-02 -3.252830e+01 -1.455930e-01 -4.002356e-02 -9.885346e-01 6.151644e+01 +-9.904889e-01 9.780735e-03 1.372447e-01 3.555005e+02 4.359943e-03 9.992004e-01 -3.974250e-02 -3.258716e+01 -1.375237e-01 -3.876612e-02 -9.897395e-01 6.044910e+01 +-9.914795e-01 9.417587e-03 1.299225e-01 3.556323e+02 4.366222e-03 9.992253e-01 -3.911009e-02 -3.264747e+01 -1.301902e-01 -3.820957e-02 -9.907525e-01 5.938780e+01 +-9.921885e-01 1.116568e-02 1.242474e-01 3.557580e+02 6.344096e-03 9.992138e-01 -3.913463e-02 -3.270491e+01 -1.245867e-01 -3.804069e-02 -9.914792e-01 5.833524e+01 +-9.926419e-01 1.304932e-02 1.203818e-01 3.558669e+02 8.391197e-03 9.991992e-01 -3.912072e-02 -3.276051e+01 -1.207959e-01 -3.782271e-02 -9.919565e-01 5.729608e+01 +-9.928659e-01 1.570197e-02 1.181986e-01 3.559811e+02 1.136840e-02 9.992413e-01 -3.724898e-02 -3.283128e+01 -1.186938e-01 -3.563950e-02 -9.922910e-01 5.625903e+01 +-9.928830e-01 1.792028e-02 1.177379e-01 3.560912e+02 1.382365e-02 9.992733e-01 -3.551959e-02 -3.290197e+01 -1.182889e-01 -3.363922e-02 -9.924092e-01 5.522781e+01 +-9.927392e-01 2.009212e-02 1.185971e-01 3.561985e+02 1.603784e-02 9.992571e-01 -3.504143e-02 -3.297656e+01 -1.192131e-01 -3.288495e-02 -9.923239e-01 5.420816e+01 +-9.922906e-01 2.453684e-02 1.214798e-01 3.563117e+02 2.038991e-02 9.991700e-01 -3.526318e-02 -3.304706e+01 -1.222442e-01 -3.251436e-02 -9.919673e-01 5.320035e+01 +-9.916055e-01 2.780911e-02 1.262744e-01 3.564113e+02 2.334937e-02 9.990549e-01 -3.666205e-02 -3.310303e+01 -1.271745e-01 -3.340585e-02 -9.913176e-01 5.220450e+01 +-9.906151e-01 2.857293e-02 1.336614e-01 3.565258e+02 2.355103e-02 9.989615e-01 -3.900352e-02 -3.315419e+01 -1.346370e-01 -3.548961e-02 -9.902592e-01 5.122105e+01 +-9.891408e-01 2.975224e-02 1.439286e-01 3.566428e+02 2.421763e-02 9.989039e-01 -4.005457e-02 -3.319595e+01 -1.449626e-01 -3.613399e-02 -9.887771e-01 5.025407e+01 +-9.872740e-01 2.924524e-02 1.563165e-01 3.567934e+02 2.360484e-02 9.990058e-01 -3.781891e-02 -3.322211e+01 -1.572671e-01 -3.364779e-02 -9.869827e-01 4.930054e+01 +-9.850059e-01 2.811086e-02 1.702153e-01 3.569613e+02 2.269478e-02 9.991749e-01 -3.368197e-02 -3.323857e+01 -1.710217e-01 -2.931393e-02 -9.848310e-01 4.836940e+01 +-9.820579e-01 2.639948e-02 1.867229e-01 3.571465e+02 2.057740e-02 9.992418e-01 -3.305047e-02 -3.326250e+01 -1.874538e-01 -2.861520e-02 -9.818565e-01 4.747128e+01 +-9.780685e-01 2.702408e-02 2.065230e-01 3.573321e+02 2.034523e-02 9.992012e-01 -3.439558e-02 -3.328258e+01 -2.072876e-01 -2.943947e-02 -9.778369e-01 4.659630e+01 +-9.726318e-01 3.109031e-02 2.302627e-01 3.575389e+02 2.379552e-02 9.991251e-01 -3.439049e-02 -3.330692e+01 -2.311305e-01 -2.797006e-02 -9.725206e-01 4.575254e+01 +-9.659795e-01 3.113546e-02 2.567376e-01 3.577696e+02 2.320466e-02 9.991570e-01 -3.386338e-02 -3.333504e+01 -2.575755e-01 -2.675382e-02 -9.658877e-01 4.493893e+01 +-9.576885e-01 3.167717e-02 2.860584e-01 3.580029e+02 2.303872e-02 9.991726e-01 -3.351436e-02 -3.336145e+01 -2.868833e-01 -2.550589e-02 -9.576259e-01 4.414950e+01 +-9.468315e-01 3.499419e-02 3.198212e-01 3.582753e+02 2.504018e-02 9.990671e-01 -3.518441e-02 -3.338981e+01 -3.207541e-01 -2.530532e-02 -9.468243e-01 4.338883e+01 +-9.330286e-01 3.590855e-02 3.580061e-01 3.585870e+02 2.447176e-02 9.990366e-01 -3.642709e-02 -3.341599e+01 -3.589692e-01 -2.522647e-02 -9.330084e-01 4.264795e+01 +-9.157356e-01 3.666592e-02 4.001049e-01 3.588868e+02 2.460682e-02 9.990760e-01 -3.523754e-02 -3.344659e+01 -4.010272e-01 -2.242296e-02 -9.157916e-01 4.192556e+01 +-8.944732e-01 3.398493e-02 4.458282e-01 3.592668e+02 2.144982e-02 9.992207e-01 -3.313420e-02 -3.347315e+01 -4.466068e-01 -2.007472e-02 -8.945050e-01 4.123889e+01 +-8.696613e-01 2.858657e-02 4.928205e-01 3.596877e+02 1.572535e-02 9.994195e-01 -3.022249e-02 -3.349971e+01 -4.933983e-01 -1.853356e-02 -8.696059e-01 4.058576e+01 +-8.408458e-01 2.218100e-02 5.408202e-01 3.600826e+02 9.153789e-03 9.995998e-01 -2.676530e-02 -3.352433e+01 -5.411974e-01 -1.755493e-02 -8.407123e-01 3.995770e+01 +-8.079307e-01 1.467433e-02 5.890949e-01 3.605718e+02 2.279310e-03 9.997602e-01 -2.177798e-02 -3.354565e+01 -5.892732e-01 -1.625236e-02 -8.077703e-01 3.937383e+01 +-7.708360e-01 6.768953e-03 6.369978e-01 3.610953e+02 -4.617726e-03 9.998579e-01 -1.621279e-02 -3.356709e+01 -6.370169e-01 -1.543888e-02 -7.706951e-01 3.882716e+01 +-7.297351e-01 -8.736865e-04 6.837295e-01 3.615792e+02 -1.039472e-02 9.998978e-01 -9.816461e-03 -3.359500e+01 -6.836510e-01 -1.427059e-02 -7.296695e-01 3.830721e+01 +-6.852489e-01 -7.526310e-03 7.282701e-01 3.621563e+02 -1.446055e-02 9.998901e-01 -3.272961e-03 -3.361158e+01 -7.281654e-01 -1.277398e-02 -6.852824e-01 3.783554e+01 +-6.377288e-01 -1.374224e-02 7.701384e-01 3.627586e+02 -1.926288e-02 9.998126e-01 1.889488e-03 -3.362456e+01 -7.700200e-01 -1.363010e-02 -6.378740e-01 3.740528e+01 +-5.870550e-01 -1.534423e-02 8.094017e-01 3.633163e+02 -2.030223e-02 9.997849e-01 4.228306e-03 -3.363112e+01 -8.092924e-01 -1.395041e-02 -5.872402e-01 3.699907e+01 +-5.332807e-01 -1.429363e-02 8.458177e-01 3.639744e+02 -2.043037e-02 9.997832e-01 4.014346e-03 -3.363497e+01 -8.456916e-01 -1.513960e-02 -5.334570e-01 3.663830e+01 +-4.764013e-01 -1.331145e-02 8.791272e-01 3.645881e+02 -2.201997e-02 9.997524e-01 3.205230e-03 -3.363449e+01 -8.789522e-01 -1.783138e-02 -4.765764e-01 3.630391e+01 +-4.177350e-01 -1.467348e-02 9.084505e-01 3.653160e+02 -2.216797e-02 9.997365e-01 5.954392e-03 -3.362887e+01 -9.082984e-01 -1.765114e-02 -4.179502e-01 3.601420e+01 +-3.576935e-01 -1.960480e-02 9.336333e-01 3.660804e+02 -2.161635e-02 9.996855e-01 1.271013e-02 -3.361559e+01 -9.335888e-01 -1.563542e-02 -3.580048e-01 3.576111e+01 +-2.984808e-01 -2.937946e-02 9.539634e-01 3.668277e+02 -2.324905e-02 9.994533e-01 2.350614e-02 -3.356380e+01 -9.541324e-01 -1.516261e-02 -2.990007e-01 3.554989e+01 +-2.414009e-01 -3.767190e-02 9.696940e-01 3.676796e+02 -1.982693e-02 9.992291e-01 3.388350e-02 -3.349200e+01 -9.702229e-01 -1.104655e-02 -2.419617e-01 3.537805e+01 +-1.868591e-01 -4.220263e-02 9.814798e-01 3.685473e+02 -1.529209e-02 9.990807e-01 4.004806e-02 -3.344788e+01 -9.822677e-01 -7.525531e-03 -1.873327e-01 3.523449e+01 +-1.347443e-01 -4.053713e-02 9.900509e-01 3.693904e+02 -1.147526e-02 9.991596e-01 3.934832e-02 -3.337762e+01 -9.908139e-01 -6.059128e-03 -1.350962e-01 3.512647e+01 +-8.526409e-02 -3.221245e-02 9.958376e-01 3.702830e+02 -8.665872e-03 9.994634e-01 3.158776e-02 -3.330190e+01 -9.963207e-01 -5.936502e-03 -8.549748e-02 3.506860e+01 +-3.969895e-02 -2.144397e-02 9.989816e-01 3.711484e+02 -5.923247e-03 9.997572e-01 2.122523e-02 -3.323144e+01 -9.991941e-01 -5.074597e-03 -3.981632e-02 3.504506e+01 +8.915831e-04 -1.274252e-02 9.999184e-01 3.720553e+02 -2.865196e-03 9.999147e-01 1.274503e-02 -3.319996e+01 -9.999955e-01 -2.876328e-03 8.549985e-04 3.505669e+01 +3.820618e-02 -9.277852e-03 9.992268e-01 3.729801e+02 -4.560965e-04 9.999566e-01 9.302064e-03 -3.317309e+01 -9.992697e-01 -8.111434e-04 3.820029e-02 3.510059e+01 +7.412075e-02 -9.316757e-03 9.972058e-01 3.738995e+02 5.536779e-04 9.999566e-01 9.301300e-03 -3.315114e+01 -9.972491e-01 -1.372919e-04 7.412268e-02 3.517527e+01 +1.091164e-01 -7.927940e-03 9.939974e-01 3.748381e+02 2.850440e-03 9.999666e-01 7.662638e-03 -3.314269e+01 -9.940248e-01 1.997207e-03 1.091353e-01 3.529061e+01 +1.426449e-01 -5.254754e-03 9.897600e-01 3.757620e+02 3.850588e-03 9.999813e-01 4.754067e-03 -3.314812e+01 -9.897664e-01 3.133010e-03 1.426625e-01 3.543163e+01 +1.741228e-01 -2.284599e-03 9.847213e-01 3.766981e+02 2.469906e-03 9.999952e-01 1.883292e-03 -3.315656e+01 -9.847208e-01 2.104241e-03 1.741276e-01 3.561111e+01 +2.041557e-01 -9.918520e-04 9.789380e-01 3.776308e+02 1.946762e-03 9.999979e-01 6.071925e-04 -3.317151e+01 -9.789365e-01 1.781794e-03 2.041572e-01 3.581759e+01 +2.345111e-01 2.843718e-04 9.721134e-01 3.785394e+02 3.960190e-04 9.999998e-01 -3.880683e-04 -3.320483e+01 -9.721133e-01 4.759782e-04 2.345110e-01 3.605362e+01 +2.649021e-01 1.706481e-03 9.642738e-01 3.794709e+02 -8.573140e-04 9.999984e-01 -1.534189e-03 -3.323408e+01 -9.642749e-01 -4.202791e-04 2.649031e-01 3.632279e+01 +2.947547e-01 2.831736e-03 9.555688e-01 3.803812e+02 -1.044521e-03 9.999959e-01 -2.641202e-03 -3.326282e+01 -9.555723e-01 -2.196079e-04 2.947565e-01 3.661413e+01 +3.237599e-01 3.367060e-03 9.461333e-01 3.812994e+02 -7.172531e-04 9.999942e-01 -3.313303e-03 -3.328834e+01 -9.461390e-01 3.940943e-04 3.237604e-01 3.693969e+01 +3.518784e-01 4.424781e-03 9.360353e-01 3.822121e+02 -1.835825e-03 9.999901e-01 -4.036978e-03 -3.332490e+01 -9.360439e-01 -2.978750e-04 3.518830e-01 3.729447e+01 +3.796540e-01 5.876795e-03 9.251099e-01 3.830946e+02 -3.917350e-03 9.999810e-01 -4.744787e-03 -3.339281e+01 -9.251202e-01 -1.822605e-03 3.796698e-01 3.767709e+01 +4.089588e-01 4.061068e-03 9.125438e-01 3.839934e+02 -7.806332e-04 9.999913e-01 -4.100393e-03 -3.345613e+01 -9.125525e-01 9.645266e-04 4.089584e-01 3.808485e+01 +4.398912e-01 2.725818e-03 8.980470e-01 3.848677e+02 1.374979e-03 9.999922e-01 -3.708761e-03 -3.354234e+01 -8.980500e-01 2.866243e-03 4.398840e-01 3.851799e+01 +4.711869e-01 3.713947e-03 8.820256e-01 3.857123e+02 2.937914e-03 9.999790e-01 -5.780080e-03 -3.360364e+01 -8.820285e-01 5.314809e-03 4.711661e-01 3.897693e+01 +5.033558e-01 5.732545e-03 8.640603e-01 3.865588e+02 4.978345e-03 9.999421e-01 -9.534167e-03 -3.367128e+01 -8.640649e-01 9.100664e-03 5.032981e-01 3.946897e+01 +5.364980e-01 6.659652e-03 8.438754e-01 3.873641e+02 6.733585e-03 9.999032e-01 -1.217190e-02 -3.373586e+01 -8.438747e-01 1.221250e-02 5.364012e-01 3.999185e+01 +5.692474e-01 7.773993e-03 8.221295e-01 3.881748e+02 6.028589e-03 9.998889e-01 -1.362911e-02 -3.381662e+01 -8.221441e-01 1.271461e-02 5.691373e-01 4.055651e+01 +6.008739e-01 7.100588e-03 7.993123e-01 3.889690e+02 6.732682e-03 9.998801e-01 -1.394353e-02 -3.387763e+01 -7.993154e-01 1.375981e-02 6.007540e-01 4.115519e+01 +6.317929e-01 7.887445e-03 7.750971e-01 3.897015e+02 5.155966e-03 9.998833e-01 -1.437759e-02 -3.395798e+01 -7.751200e-01 1.308003e-02 6.316785e-01 4.178071e+01 +6.616220e-01 8.221083e-03 7.497925e-01 3.904374e+02 5.483713e-03 9.998601e-01 -1.580181e-02 -3.402704e+01 -7.498174e-01 1.456647e-02 6.614843e-01 4.244005e+01 +6.899681e-01 9.017717e-03 7.237836e-01 3.911447e+02 5.841473e-03 9.998204e-01 -1.802546e-02 -3.410827e+01 -7.238162e-01 1.666495e-02 6.897915e-01 4.312774e+01 +7.158190e-01 1.076350e-02 6.982030e-01 3.918027e+02 4.521019e-03 9.997888e-01 -2.004784e-02 -3.418143e+01 -6.982713e-01 1.750721e-02 7.156191e-01 4.383919e+01 +7.389816e-01 1.266783e-02 6.736065e-01 3.924645e+02 3.060188e-03 9.997498e-01 -2.215847e-02 -3.423077e+01 -6.737186e-01 1.843606e-02 7.387579e-01 4.457573e+01 +7.593860e-01 1.444666e-02 6.504800e-01 3.930816e+02 1.389448e-03 9.997152e-01 -2.382499e-02 -3.428262e+01 -6.506389e-01 1.899617e-02 7.591496e-01 4.532673e+01 +7.768003e-01 1.714039e-02 6.295137e-01 3.936894e+02 -4.172484e-04 9.996433e-01 -2.670341e-02 -3.434673e+01 -6.297468e-01 2.048055e-02 7.765303e-01 4.609901e+01 +7.917985e-01 2.024043e-02 6.104470e-01 3.942713e+02 -1.928549e-03 9.995286e-01 -3.063963e-02 -3.442028e+01 -6.107794e-01 2.308313e-02 7.914642e-01 4.688364e+01 +8.051408e-01 2.240385e-02 5.926605e-01 3.948301e+02 -2.565568e-03 9.994085e-01 -3.429444e-02 -3.448355e+01 -5.930782e-01 2.609134e-02 8.047220e-01 4.767295e+01 +8.174758e-01 2.168043e-02 5.755549e-01 3.953839e+02 -1.860193e-03 9.993854e-01 -3.500353e-02 -3.454300e+01 -5.759600e-01 2.754389e-02 8.170136e-01 4.847434e+01 +8.294927e-01 1.707175e-02 5.582566e-01 3.959193e+02 1.630840e-03 9.994544e-01 -3.298699e-02 -3.459666e+01 -5.585152e-01 2.827288e-02 8.290123e-01 4.928275e+01 +8.410505e-01 1.360605e-02 5.407855e-01 3.964402e+02 3.682510e-03 9.995165e-01 -3.087481e-02 -3.465811e+01 -5.409441e-01 2.795871e-02 8.405936e-01 5.010229e+01 +8.523070e-01 1.023580e-02 5.229417e-01 3.969422e+02 7.287317e-03 9.994790e-01 -3.144040e-02 -3.472440e+01 -5.229910e-01 3.060771e-02 8.517884e-01 5.092834e+01 +8.631015e-01 7.910946e-03 5.049686e-01 3.974155e+02 9.817751e-03 9.994255e-01 -3.243790e-02 -3.479064e+01 -5.049351e-01 3.295485e-02 8.625279e-01 5.175759e+01 +8.735747e-01 6.835699e-03 4.866422e-01 3.978788e+02 1.090884e-02 9.993751e-01 -3.362042e-02 -3.484613e+01 -4.865679e-01 3.467864e-02 8.729542e-01 5.260068e+01 +8.834929e-01 5.188626e-03 4.684158e-01 3.983255e+02 1.232518e-02 9.993350e-01 -3.431649e-02 -3.489413e+01 -4.682823e-01 3.609168e-02 8.828414e-01 5.345014e+01 +8.932636e-01 2.993198e-03 4.495235e-01 3.987455e+02 1.432759e-02 9.992802e-01 -3.512467e-02 -3.494183e+01 -4.493050e-01 3.781617e-02 8.925776e-01 5.430549e+01 +9.026616e-01 4.811902e-04 4.303509e-01 3.991586e+02 1.603413e-02 9.992674e-01 -3.474894e-02 -3.498917e+01 -4.300523e-01 3.826683e-02 9.019926e-01 5.517430e+01 +9.117332e-01 -2.504649e-03 4.107753e-01 3.995449e+02 1.786266e-02 9.992772e-01 -3.355396e-02 -3.503638e+01 -4.103943e-01 3.792979e-02 9.111189e-01 5.605255e+01 +9.203186e-01 -4.916431e-03 3.911389e-01 3.999185e+02 1.909062e-02 9.992940e-01 -3.235805e-02 -3.508258e+01 -3.907037e-01 3.724679e-02 9.197626e-01 5.693701e+01 +9.287947e-01 -8.417468e-03 3.704992e-01 4.002660e+02 2.205013e-02 9.992260e-01 -3.257519e-02 -3.513954e+01 -3.699382e-01 3.842521e-02 9.282613e-01 5.783029e+01 +9.374916e-01 -1.073849e-02 3.478422e-01 4.005797e+02 2.397034e-02 9.991425e-01 -3.375874e-02 -3.520410e+01 -3.471814e-01 3.998642e-02 9.369451e-01 5.872894e+01 +9.462958e-01 -1.358873e-02 3.230166e-01 4.008770e+02 2.621269e-02 9.990517e-01 -3.476326e-02 -3.527203e+01 -3.222379e-01 4.136345e-02 9.457546e-01 5.963632e+01 +9.547855e-01 -1.563078e-02 2.968845e-01 4.011550e+02 2.716251e-02 9.990266e-01 -3.475699e-02 -3.533263e+01 -2.960522e-01 4.124959e-02 9.542806e-01 6.055869e+01 +9.627559e-01 -1.709856e-02 2.698311e-01 4.013907e+02 2.729442e-02 9.990463e-01 -3.407911e-02 -3.539454e+01 -2.689911e-01 4.017474e-02 9.623044e-01 6.148659e+01 +9.701143e-01 -1.925216e-02 2.418838e-01 4.016180e+02 2.822661e-02 9.990336e-01 -3.369173e-02 -3.545124e+01 -2.410014e-01 3.951238e-02 9.697201e-01 6.243004e+01 +9.767613e-01 -2.015773e-02 2.133802e-01 4.018197e+02 2.811832e-02 9.990146e-01 -3.433787e-02 -3.550653e+01 -2.124777e-01 3.953979e-02 9.763656e-01 6.337956e+01 +9.825529e-01 -2.209944e-02 1.846657e-01 4.019780e+02 2.892493e-02 9.989912e-01 -3.434924e-02 -3.556119e+01 -1.837203e-01 3.909138e-02 9.822009e-01 6.433313e+01 +9.874699e-01 -2.573869e-02 1.556945e-01 4.021292e+02 3.144134e-02 9.989177e-01 -3.427567e-02 -3.561209e+01 -1.546438e-01 3.874143e-02 9.872104e-01 6.529724e+01 +9.914978e-01 -3.019192e-02 1.265730e-01 4.022378e+02 3.488513e-02 9.987773e-01 -3.502734e-02 -3.566599e+01 -1.253607e-01 3.914504e-02 9.913386e-01 6.626794e+01 +9.946653e-01 -3.347427e-02 9.757330e-02 4.023353e+02 3.722990e-02 9.986242e-01 -3.692682e-02 -3.571717e+01 -9.620295e-02 4.036246e-02 9.945430e-01 6.725027e+01 +9.969015e-01 -3.582260e-02 7.003050e-02 4.024043e+02 3.863067e-02 9.984858e-01 -3.916296e-02 -3.576867e+01 -6.852153e-02 4.174693e-02 9.967757e-01 6.824631e+01 +9.982942e-01 -3.735670e-02 4.486823e-02 4.024374e+02 3.922630e-02 9.983666e-01 -4.153723e-02 -3.582134e+01 -4.324324e-02 4.322638e-02 9.981289e-01 6.925254e+01 +9.990029e-01 -3.813275e-02 2.322225e-02 4.024746e+02 3.908604e-02 9.983493e-01 -4.208276e-02 -3.586056e+01 -2.157919e-02 4.294845e-02 9.988442e-01 7.025974e+01 +9.992823e-01 -3.761870e-02 4.441075e-03 4.024835e+02 3.776799e-02 9.984647e-01 -4.051807e-02 -3.590399e+01 -2.910020e-03 4.065671e-02 9.991689e-01 7.128524e+01 +9.993010e-01 -3.562078e-02 -1.135082e-02 4.024705e+02 3.512900e-02 9.985446e-01 -4.092233e-02 -3.595094e+01 1.279199e-02 4.049497e-02 9.990978e-01 7.231435e+01 +9.990558e-01 -3.646414e-02 -2.361984e-02 4.024473e+02 3.539206e-02 9.983903e-01 -4.431872e-02 -3.599860e+01 2.519786e-02 4.344091e-02 9.987381e-01 7.335603e+01 +9.988883e-01 -3.290724e-02 -3.375351e-02 4.024084e+02 3.124185e-02 9.983230e-01 -4.873390e-02 -3.604656e+01 3.530060e-02 4.762519e-02 9.982413e-01 7.440387e+01 +9.986452e-01 -3.177876e-02 -4.120588e-02 4.023695e+02 2.979452e-02 9.984074e-01 -4.790574e-02 -3.609455e+01 4.266263e-02 4.661312e-02 9.980015e-01 7.546715e+01 +9.983799e-01 -3.252266e-02 -4.668984e-02 4.023418e+02 3.034653e-02 9.984533e-01 -4.658402e-02 -3.613481e+01 4.813266e-02 4.509166e-02 9.978226e-01 7.654088e+01 +9.981451e-01 -3.322168e-02 -5.101798e-02 4.023114e+02 3.085736e-02 9.984438e-01 -4.645155e-02 -3.617662e+01 5.248178e-02 4.479109e-02 9.976168e-01 7.762106e+01 +9.978801e-01 -3.493503e-02 -5.490912e-02 4.022695e+02 3.228293e-02 9.983029e-01 -4.846658e-02 -3.622498e+01 5.650912e-02 4.659119e-02 9.973143e-01 7.871150e+01 +9.976107e-01 -3.681247e-02 -5.846282e-02 4.022288e+02 3.385489e-02 9.981349e-01 -5.079842e-02 -3.627946e+01 6.022379e-02 4.869778e-02 9.969962e-01 7.980545e+01 +9.973764e-01 -3.818270e-02 -6.150160e-02 4.021768e+02 3.504197e-02 9.980652e-01 -5.136116e-02 -3.633761e+01 6.334371e-02 4.907127e-02 9.967846e-01 8.090921e+01 +9.971849e-01 -3.883923e-02 -6.413906e-02 4.021342e+02 3.562043e-02 9.980842e-01 -5.058802e-02 -3.637271e+01 6.598097e-02 4.816094e-02 9.966579e-01 8.202781e+01 +9.970210e-01 -3.871934e-02 -6.670821e-02 4.020754e+02 3.548060e-02 9.981649e-01 -4.907023e-02 -3.641660e+01 6.848576e-02 4.655719e-02 9.965651e-01 8.315628e+01 +9.968327e-01 -3.910660e-02 -6.924846e-02 4.020279e+02 3.580426e-02 9.981907e-01 -4.830423e-02 -3.643488e+01 7.101218e-02 4.567184e-02 9.964292e-01 8.429960e+01 +9.966339e-01 -3.957262e-02 -7.179813e-02 4.019744e+02 3.614109e-02 9.981701e-01 -4.848001e-02 -3.645053e+01 7.358522e-02 4.572195e-02 9.962402e-01 8.544766e+01 +9.964069e-01 -4.055746e-02 -7.435416e-02 4.019278e+02 3.689236e-02 9.980666e-01 -5.002070e-02 -3.643837e+01 7.623911e-02 4.709786e-02 9.959765e-01 8.659712e+01 +9.961674e-01 -4.154138e-02 -7.697365e-02 4.018673e+02 3.770565e-02 9.980053e-01 -5.063280e-02 -3.644567e+01 7.892346e-02 4.753639e-02 9.957466e-01 8.775363e+01 +9.959357e-01 -4.259343e-02 -7.936024e-02 4.017996e+02 3.857915e-02 9.979302e-01 -5.144809e-02 -3.647053e+01 8.138733e-02 4.817732e-02 9.955174e-01 8.892411e+01 +9.957661e-01 -4.310387e-02 -8.119064e-02 4.017219e+02 3.895770e-02 9.978881e-01 -5.197756e-02 -3.650463e+01 8.325960e-02 4.859448e-02 9.953423e-01 9.011335e+01 +9.955983e-01 -4.389311e-02 -8.281020e-02 4.016330e+02 3.967730e-02 9.978644e-01 -5.188651e-02 -3.654365e+01 8.491081e-02 4.837242e-02 9.952136e-01 9.131072e+01 +9.954302e-01 -4.499830e-02 -8.422577e-02 4.015468e+02 4.079063e-02 9.978638e-01 -5.102894e-02 -3.657076e+01 8.634206e-02 4.736012e-02 9.951392e-01 9.252033e+01 +9.952554e-01 -4.624717e-02 -8.560362e-02 4.014558e+02 4.210320e-02 9.978814e-01 -4.959785e-02 -3.660726e+01 8.771602e-02 4.575834e-02 9.950939e-01 9.373745e+01 +9.950721e-01 -4.787148e-02 -8.683326e-02 4.013642e+02 4.374622e-02 9.978498e-01 -4.880518e-02 -3.663993e+01 8.898292e-02 4.476603e-02 9.950266e-01 9.496448e+01 +9.948675e-01 -4.912160e-02 -8.846399e-02 4.012664e+02 4.492889e-02 9.977986e-01 -4.877891e-02 -3.668642e+01 9.066533e-02 4.455395e-02 9.948842e-01 9.619591e+01 +9.946949e-01 -4.918958e-02 -9.034687e-02 4.011692e+02 4.483977e-02 9.977640e-01 -4.956134e-02 -3.672561e+01 9.258275e-02 4.524727e-02 9.946763e-01 9.743886e+01 +9.945354e-01 -4.877139e-02 -9.230797e-02 4.010628e+02 4.424280e-02 9.977443e-01 -5.048695e-02 -3.677594e+01 9.456206e-02 4.612709e-02 9.944497e-01 9.868403e+01 +9.944842e-01 -4.688527e-02 -9.382458e-02 4.009520e+02 4.222678e-02 9.978037e-01 -5.103607e-02 -3.682760e+01 9.601135e-02 4.679264e-02 9.942797e-01 9.993595e+01 +9.944029e-01 -4.530479e-02 -9.544848e-02 4.008354e+02 4.053321e-02 9.978577e-01 -5.135129e-02 -3.688777e+01 9.757046e-02 4.719503e-02 9.941089e-01 1.011967e+02 +9.942257e-01 -4.500693e-02 -9.741479e-02 4.007180e+02 4.009058e-02 9.978498e-01 -5.185121e-02 -3.695152e+01 9.953898e-02 4.764639e-02 9.938922e-01 1.024581e+02 +9.938676e-01 -4.711217e-02 -1.000382e-01 4.006006e+02 4.206215e-02 9.977606e-01 -5.200483e-02 -3.701471e+01 1.022642e-01 4.747809e-02 9.936235e-01 1.037201e+02 +9.934109e-01 -4.881931e-02 -1.036895e-01 4.004791e+02 4.359344e-02 9.976908e-01 -5.208226e-02 -3.708376e+01 1.059927e-01 4.721889e-02 9.932451e-01 1.049810e+02 +9.928054e-01 -5.314669e-02 -1.072986e-01 4.003560e+02 4.770991e-02 9.974744e-01 -5.261784e-02 -3.715294e+01 1.098240e-01 4.712007e-02 9.928335e-01 1.062395e+02 +9.922833e-01 -5.465481e-02 -1.112959e-01 4.002243e+02 4.879961e-02 9.973111e-01 -5.467242e-02 -3.722766e+01 1.139848e-01 4.881933e-02 9.922822e-01 1.074942e+02 +9.917686e-01 -5.633122e-02 -1.149868e-01 4.000867e+02 4.975985e-02 9.970026e-01 -5.924262e-02 -3.730404e+01 1.179794e-01 5.303323e-02 9.915988e-01 1.087452e+02 +9.912616e-01 -5.770097e-02 -1.186221e-01 3.999448e+02 5.058355e-02 9.967834e-01 -6.216254e-02 -3.738754e+01 1.218274e-01 5.561900e-02 9.909917e-01 1.099933e+02 +9.908821e-01 -5.678896e-02 -1.221791e-01 3.997943e+02 4.967930e-02 9.969328e-01 -6.047235e-02 -3.747207e+01 1.252385e-01 5.385119e-02 9.906641e-01 1.112460e+02 +9.904316e-01 -5.620168e-02 -1.260422e-01 3.996382e+02 4.917646e-02 9.970944e-01 -5.817471e-02 -3.755614e+01 1.289455e-01 5.141976e-02 9.903176e-01 1.124938e+02 +9.900728e-01 -5.443502e-02 -1.295867e-01 3.994758e+02 4.739647e-02 9.972602e-01 -5.679533e-02 -3.763933e+01 1.323233e-01 5.008955e-02 9.899401e-01 1.137409e+02 +9.897229e-01 -5.226642e-02 -1.331048e-01 3.993092e+02 4.543812e-02 9.975156e-01 -5.383295e-02 -3.772006e+01 1.355878e-01 4.723166e-02 9.896388e-01 1.149852e+02 +9.893510e-01 -5.018351e-02 -1.366250e-01 3.991387e+02 4.351423e-02 9.977311e-01 -5.137282e-02 -3.779904e+01 1.388930e-01 4.488061e-02 9.892898e-01 1.162267e+02 +9.889031e-01 -5.031507e-02 -1.397826e-01 3.989666e+02 4.351951e-02 9.977369e-01 -5.125552e-02 -3.787607e+01 1.420451e-01 4.460347e-02 9.888547e-01 1.174626e+02 +9.885162e-01 -4.869848e-02 -1.430533e-01 3.987884e+02 4.141417e-02 9.977105e-01 -5.346550e-02 -3.795302e+01 1.453294e-01 4.692708e-02 9.882697e-01 1.186936e+02 +9.881394e-01 -4.697070e-02 -1.461995e-01 3.986033e+02 3.917991e-02 9.976773e-01 -5.572109e-02 -3.803292e+01 1.484772e-01 4.933212e-02 9.876845e-01 1.199247e+02 +9.878296e-01 -4.442428e-02 -1.490609e-01 3.984149e+02 3.615904e-02 9.976784e-01 -5.770917e-02 -3.811462e+01 1.512785e-01 5.161692e-02 9.871425e-01 1.211540e+02 +9.875431e-01 -4.261044e-02 -1.514698e-01 3.982229e+02 3.394225e-02 9.976594e-01 -5.936024e-02 -3.819917e+01 1.536446e-01 5.347956e-02 9.866778e-01 1.223851e+02 +9.873993e-01 -3.747894e-02 -1.537466e-01 3.980254e+02 2.856167e-02 9.978014e-01 -5.980468e-02 -3.828481e+01 1.556500e-01 5.465983e-02 9.862988e-01 1.236120e+02 +9.872685e-01 -3.524505e-02 -1.551092e-01 3.978227e+02 2.604959e-02 9.978025e-01 -6.092263e-02 -3.837023e+01 1.569155e-01 5.610645e-02 9.860170e-01 1.248440e+02 +9.871427e-01 -3.527062e-02 -1.559015e-01 3.976174e+02 2.571495e-02 9.976890e-01 -6.289094e-02 -3.845625e+01 1.577594e-01 5.807332e-02 9.857684e-01 1.260811e+02 +9.871351e-01 -3.426716e-02 -1.561735e-01 3.974092e+02 2.401081e-02 9.974578e-01 -6.709293e-02 -3.854449e+01 1.580755e-01 6.247993e-02 9.854483e-01 1.273148e+02 +9.867421e-01 -4.006755e-02 -1.572728e-01 3.972149e+02 2.962350e-02 9.972318e-01 -6.819930e-02 -3.863636e+01 1.595700e-01 6.263614e-02 9.851974e-01 1.285449e+02 +9.863316e-01 -4.660881e-02 -1.580435e-01 3.970234e+02 3.611439e-02 9.969878e-01 -6.863720e-02 -3.873102e+01 1.607665e-01 6.199138e-02 9.850437e-01 1.297782e+02 +9.861903e-01 -4.987513e-02 -1.579281e-01 3.968290e+02 3.954305e-02 9.969079e-01 -6.790397e-02 -3.882647e+01 1.608265e-01 6.072127e-02 9.851130e-01 1.310131e+02 +9.862915e-01 -4.845442e-02 -1.577384e-01 3.966300e+02 3.806109e-02 9.969414e-01 -6.825793e-02 -3.892131e+01 1.605633e-01 6.131851e-02 9.851189e-01 1.322397e+02 +9.865898e-01 -4.488545e-02 -1.569267e-01 3.964264e+02 3.426247e-02 9.969754e-01 -6.975672e-02 -3.901734e+01 1.595831e-01 6.344456e-02 9.851436e-01 1.334657e+02 +9.870395e-01 -3.950657e-02 -1.555390e-01 3.962223e+02 2.866784e-02 9.970412e-01 -7.132225e-02 -3.911364e+01 1.578965e-01 6.593890e-02 9.852516e-01 1.346879e+02 +9.875198e-01 -3.522873e-02 -1.535047e-01 3.960105e+02 2.454728e-02 9.971790e-01 -7.093223e-02 -3.918304e+01 1.555706e-01 6.627885e-02 9.855987e-01 1.358919e+02 +9.878317e-01 -3.328620e-02 -1.519233e-01 3.958045e+02 2.282881e-02 9.972811e-01 -7.006622e-02 -3.924807e+01 1.538424e-01 6.574540e-02 9.859056e-01 1.370918e+02 +9.880871e-01 -3.393810e-02 -1.501075e-01 3.956019e+02 2.347871e-02 9.972063e-01 -7.091110e-02 -3.930405e+01 1.520947e-01 6.654200e-02 9.861234e-01 1.382817e+02 +9.882407e-01 -3.670734e-02 -1.484353e-01 3.954121e+02 2.625390e-02 9.970748e-01 -7.178074e-02 -3.937654e+01 1.506360e-01 6.703963e-02 9.863135e-01 1.394838e+02 +9.884560e-01 -3.720614e-02 -1.468690e-01 3.952192e+02 2.687168e-02 9.970618e-01 -7.173299e-02 -3.944585e+01 1.491064e-01 6.695828e-02 9.865515e-01 1.406813e+02 +9.887007e-01 -3.741370e-02 -1.451594e-01 3.950334e+02 2.741363e-02 9.971498e-01 -7.028961e-02 -3.952401e+01 1.473754e-01 6.551603e-02 9.869083e-01 1.418816e+02 +9.889703e-01 -3.608973e-02 -1.436498e-01 3.948470e+02 2.645614e-02 9.973059e-01 -6.841755e-02 -3.960208e+01 1.457320e-01 6.386250e-02 9.872607e-01 1.430836e+02 +9.893171e-01 -3.370745e-02 -1.418295e-01 3.946631e+02 2.417304e-02 9.973638e-01 -6.841869e-02 -3.968369e+01 1.437618e-01 6.425932e-02 9.875238e-01 1.442869e+02 +9.896007e-01 -3.280060e-02 -1.400522e-01 3.944836e+02 2.309428e-02 9.972531e-01 -7.037652e-02 -3.976651e+01 1.419759e-01 6.641024e-02 9.876398e-01 1.454875e+02 +9.898795e-01 -3.120772e-02 -1.384369e-01 3.943053e+02 2.119432e-02 9.970902e-01 -7.322542e-02 -3.985016e+01 1.403193e-01 6.955025e-02 9.876604e-01 1.466854e+02 +9.900064e-01 -3.189541e-02 -1.373686e-01 3.941325e+02 2.156112e-02 9.968692e-01 -7.607205e-02 -3.994140e+01 1.393649e-01 7.234998e-02 9.875945e-01 1.478874e+02 +9.900505e-01 -3.283523e-02 -1.368283e-01 3.939613e+02 2.253216e-02 9.968395e-01 -7.617930e-02 -4.003397e+01 1.388973e-01 7.233830e-02 9.876612e-01 1.490918e+02 +9.901275e-01 -3.255099e-02 -1.363378e-01 3.937918e+02 2.264905e-02 9.970336e-01 -7.355983e-02 -4.012842e+01 1.383278e-01 6.974568e-02 9.879276e-01 1.503004e+02 +9.901624e-01 -3.394578e-02 -1.357430e-01 3.936234e+02 2.433878e-02 9.971208e-01 -7.181738e-02 -4.022122e+01 1.377900e-01 6.780704e-02 9.881376e-01 1.515100e+02 +9.902029e-01 -3.476267e-02 -1.352398e-01 3.934567e+02 2.529491e-02 9.971479e-01 -7.110658e-02 -4.031116e+01 1.373259e-01 6.698905e-02 9.882580e-01 1.527245e+02 +9.902584e-01 -3.493036e-02 -1.347898e-01 3.932900e+02 2.541732e-02 9.971049e-01 -7.166366e-02 -4.040329e+01 1.369028e-01 6.753954e-02 9.882793e-01 1.539350e+02 +9.902550e-01 -3.694933e-02 -1.342752e-01 3.931276e+02 2.700991e-02 9.968097e-01 -7.510517e-02 -4.049668e+01 1.366219e-01 7.074650e-02 9.880938e-01 1.551466e+02 +9.902551e-01 -3.888055e-02 -1.337285e-01 3.929644e+02 2.886570e-02 9.966876e-01 -7.602991e-02 -4.059018e+01 1.362416e-01 7.142882e-02 9.880972e-01 1.563622e+02 +9.902200e-01 -3.893003e-02 -1.339735e-01 3.928000e+02 2.881383e-02 9.966426e-01 -7.663677e-02 -4.068860e+01 1.365072e-01 7.202695e-02 9.880171e-01 1.575782e+02 +9.902138e-01 -4.008925e-02 -1.336768e-01 3.926373e+02 2.978543e-02 9.964919e-01 -7.820860e-02 -4.078917e+01 1.363432e-01 7.346160e-02 9.879341e-01 1.587937e+02 +9.902858e-01 -3.936307e-02 -1.333589e-01 3.924739e+02 2.898528e-02 9.964622e-01 -7.888567e-02 -4.089190e+01 1.359923e-01 7.425391e-02 9.879232e-01 1.600122e+02 +9.903552e-01 -3.877187e-02 -1.330163e-01 3.923104e+02 2.867632e-02 9.966193e-01 -7.699095e-02 -4.099442e+01 1.355517e-01 7.243396e-02 9.881189e-01 1.612340e+02 +9.903708e-01 -3.898775e-02 -1.328371e-01 3.921486e+02 2.915023e-02 9.967413e-01 -7.521369e-02 -4.109616e+01 1.353366e-01 7.061720e-02 9.882799e-01 1.624570e+02 +9.903550e-01 -4.026436e-02 -1.325739e-01 3.919880e+02 3.046138e-02 9.967062e-01 -7.515923e-02 -4.119598e+01 1.351635e-01 7.039592e-02 9.883193e-01 1.636816e+02 +9.903232e-01 -4.210512e-02 -1.322394e-01 3.918289e+02 3.231550e-02 9.966354e-01 -7.532302e-02 -4.129426e+01 1.349660e-01 7.032073e-02 9.883517e-01 1.649038e+02 +9.903259e-01 -4.350416e-02 -1.317649e-01 3.916708e+02 3.390583e-02 9.966644e-01 -7.423242e-02 -4.139410e+01 1.345548e-01 6.904668e-02 9.884976e-01 1.661345e+02 +9.904064e-01 -4.277993e-02 -1.313967e-01 3.915112e+02 3.316512e-02 9.966685e-01 -7.451074e-02 -4.149409e+01 1.341465e-01 6.943812e-02 9.885256e-01 1.673605e+02 +9.904334e-01 -4.376044e-02 -1.308696e-01 3.913523e+02 3.382619e-02 9.964422e-01 -7.719264e-02 -4.159487e+01 1.337819e-01 7.202733e-02 9.883898e-01 1.685864e+02 +9.904354e-01 -4.546517e-02 -1.302715e-01 3.911952e+02 3.510790e-02 9.961177e-01 -8.072801e-02 -4.169751e+01 1.334361e-01 7.538230e-02 9.881863e-01 1.698123e+02 +9.904849e-01 -4.570835e-02 -1.298093e-01 3.910377e+02 3.519343e-02 9.959965e-01 -8.217288e-02 -4.180410e+01 1.330456e-01 7.682255e-02 9.881281e-01 1.710404e+02 +9.904312e-01 -4.761518e-02 -1.295334e-01 3.908835e+02 3.744750e-02 9.961049e-01 -7.982919e-02 -4.191197e+01 1.328299e-01 7.421460e-02 9.883564e-01 1.722722e+02 +9.903999e-01 -4.887116e-02 -1.293051e-01 3.907288e+02 3.923937e-02 9.963341e-01 -7.601666e-02 -4.201742e+01 1.325461e-01 7.021303e-02 9.886868e-01 1.735091e+02 +9.903728e-01 -5.063318e-02 -1.288339e-01 3.905744e+02 4.130788e-02 9.963983e-01 -7.405368e-02 -4.211892e+01 1.321194e-01 6.801888e-02 9.888973e-01 1.747432e+02 +9.904768e-01 -4.973635e-02 -1.283829e-01 3.904167e+02 4.038602e-02 9.964077e-01 -7.443573e-02 -4.221895e+01 1.316239e-01 6.854198e-02 9.889272e-01 1.759778e+02 +9.905150e-01 -5.173709e-02 -1.272923e-01 3.902658e+02 4.237798e-02 9.962701e-01 -7.516627e-02 -4.231681e+01 1.307064e-01 6.905892e-02 9.890129e-01 1.772086e+02 +9.909867e-01 -4.676930e-02 -1.255309e-01 3.901101e+02 3.717803e-02 9.962841e-01 -7.769068e-02 -4.241926e+01 1.286980e-01 7.232343e-02 9.890430e-01 1.784408e+02 +9.913829e-01 -4.712662e-02 -1.222258e-01 3.899597e+02 3.759944e-02 9.961560e-01 -7.911614e-02 -4.252017e+01 1.254845e-01 7.383875e-02 9.893439e-01 1.796764e+02 +9.920281e-01 -4.354304e-02 -1.182551e-01 3.898112e+02 3.421124e-02 9.962214e-01 -7.982741e-02 -4.262744e+01 1.212842e-01 7.514536e-02 9.897693e-01 1.809130e+02 +9.926348e-01 -4.262262e-02 -1.134001e-01 3.896629e+02 3.348813e-02 9.961293e-01 -8.127113e-02 -4.274446e+01 1.164252e-01 7.687498e-02 9.902198e-01 1.821477e+02 +9.932863e-01 -4.088183e-02 -1.082182e-01 3.895157e+02 3.214223e-02 9.961707e-01 -8.130664e-02 -4.287396e+01 1.111277e-01 7.728238e-02 9.907966e-01 1.833871e+02 +9.939218e-01 -3.940786e-02 -1.027934e-01 3.893780e+02 3.127857e-02 9.963415e-01 -7.953084e-02 -4.299507e+01 1.055514e-01 7.583219e-02 9.915182e-01 1.846305e+02 +9.943967e-01 -4.122704e-02 -9.734242e-02 3.892441e+02 3.398912e-02 9.966133e-01 -7.487745e-02 -4.310241e+01 1.000997e-01 7.114930e-02 9.924302e-01 1.858917e+02 +9.948636e-01 -4.146121e-02 -9.234421e-02 3.891189e+02 3.485062e-02 9.967895e-01 -7.208345e-02 -4.320361e+01 9.503640e-02 6.849493e-02 9.931145e-01 1.871548e+02 +9.952243e-01 -4.478326e-02 -8.673583e-02 3.890052e+02 3.859510e-02 9.966754e-01 -7.175349e-02 -4.329972e+01 8.966082e-02 6.806323e-02 9.936439e-01 1.884168e+02 +9.956580e-01 -4.575646e-02 -8.106471e-02 3.888948e+02 3.987811e-02 9.965558e-01 -7.270629e-02 -4.339572e+01 8.411229e-02 6.915788e-02 9.940534e-01 1.896775e+02 +9.961621e-01 -4.488010e-02 -7.514568e-02 3.887927e+02 3.946309e-02 9.966177e-01 -7.208231e-02 -4.349193e+01 7.812657e-02 6.884018e-02 9.945638e-01 1.909395e+02 +9.965557e-01 -4.561704e-02 -6.925203e-02 3.886970e+02 4.036571e-02 9.963343e-01 -7.542223e-02 -4.359040e+01 7.243871e-02 7.236704e-02 9.947440e-01 1.922008e+02 +9.970791e-01 -4.184996e-02 -6.389006e-02 3.886060e+02 3.695298e-02 9.964233e-01 -7.599366e-02 -4.368918e+01 6.684187e-02 7.341075e-02 9.950593e-01 1.934612e+02 +9.973273e-01 -4.407447e-02 -5.827342e-02 3.885290e+02 3.948892e-02 9.962001e-01 -7.762739e-02 -4.378989e+01 6.147337e-02 7.511874e-02 9.952779e-01 1.947207e+02 +9.978088e-01 -4.014174e-02 -5.259576e-02 3.884557e+02 3.597341e-02 9.963092e-01 -7.793427e-02 -4.389307e+01 5.553006e-02 7.587144e-02 9.955701e-01 1.959824e+02 +9.981194e-01 -3.908648e-02 -4.722191e-02 3.883928e+02 3.537213e-02 9.963969e-01 -7.708382e-02 -4.399637e+01 5.006470e-02 7.526850e-02 9.959057e-01 1.972500e+02 +9.984594e-01 -3.625501e-02 -4.200692e-02 3.883367e+02 3.304001e-02 9.966471e-01 -7.485295e-02 -4.409937e+01 4.457986e-02 7.334970e-02 9.963094e-01 1.985163e+02 +9.987722e-01 -3.352403e-02 -3.647437e-02 3.882844e+02 3.090263e-02 9.970540e-01 -7.020234e-02 -4.419940e+01 3.872038e-02 6.898898e-02 9.968657e-01 1.997905e+02 +9.989771e-01 -3.277539e-02 -3.115512e-02 3.882422e+02 3.059275e-02 9.972077e-01 -6.812441e-02 -4.429385e+01 3.330093e-02 6.710159e-02 9.971902e-01 2.010586e+02 +9.990583e-01 -3.455773e-02 -2.623766e-02 3.882089e+02 3.256602e-02 9.968091e-01 -7.287640e-02 -4.438768e+01 2.867238e-02 7.195330e-02 9.969957e-01 2.023185e+02 +9.991446e-01 -3.559948e-02 -2.104211e-02 3.881821e+02 3.377785e-02 9.961117e-01 -8.136596e-02 -4.448921e+01 2.385688e-02 8.058559e-02 9.964621e-01 2.035777e+02 +9.990787e-01 -3.988962e-02 -1.583135e-02 3.881672e+02 3.841645e-02 9.956888e-01 -8.442731e-02 -4.459709e+01 1.913087e-02 8.374132e-02 9.963038e-01 2.048437e+02 +9.991172e-01 -4.074295e-02 -1.024593e-02 3.881552e+02 3.978478e-02 9.959369e-01 -8.078909e-02 -4.470775e+01 1.349589e-02 8.031012e-02 9.966785e-01 2.061145e+02 +9.990658e-01 -4.300818e-02 -4.225886e-03 3.881541e+02 4.255149e-02 9.960786e-01 -7.756818e-02 -4.481433e+01 7.545381e-03 7.731589e-02 9.969780e-01 2.073859e+02 +9.990116e-01 -4.442287e-02 1.571457e-03 3.881649e+02 4.441205e-02 9.960465e-01 -7.693408e-02 -4.491740e+01 1.852388e-03 7.692781e-02 9.970349e-01 2.086567e+02 +9.989489e-01 -4.524709e-02 7.345044e-03 3.881790e+02 4.567768e-02 9.960101e-01 -7.666379e-02 -4.502016e+01 -3.846924e-03 7.691870e-02 9.970299e-01 2.099258e+02 +9.989374e-01 -4.422656e-02 1.297093e-02 3.881995e+02 4.509481e-02 9.960269e-01 -7.679062e-02 -4.512328e+01 -9.523207e-03 7.729392e-02 9.969628e-01 2.111959e+02 +9.988737e-01 -4.377506e-02 1.830905e-02 3.882258e+02 4.505064e-02 9.960664e-01 -7.630247e-02 -4.522639e+01 -1.489688e-02 7.704134e-02 9.969165e-01 2.124671e+02 +9.988541e-01 -4.196760e-02 2.300762e-02 3.882590e+02 4.359775e-02 9.961811e-01 -7.564670e-02 -4.532889e+01 -1.974504e-02 7.656308e-02 9.968692e-01 2.137347e+02 +9.989437e-01 -3.659747e-02 2.778810e-02 3.882956e+02 3.858458e-02 9.964588e-01 -7.470607e-02 -4.543119e+01 -2.495564e-02 7.569934e-02 9.968183e-01 2.150062e+02 +9.989160e-01 -3.268996e-02 3.314093e-02 3.883379e+02 3.516711e-02 9.963993e-01 -7.714704e-02 -4.553430e+01 -3.049966e-02 7.822886e-02 9.964687e-01 2.162771e+02 +9.987956e-01 -2.953726e-02 3.917819e-02 3.883866e+02 3.251910e-02 9.964389e-01 -7.779473e-02 -4.563550e+01 -3.674083e-02 7.897506e-02 9.961992e-01 2.175484e+02 +9.985639e-01 -2.847693e-02 4.537904e-02 3.884453e+02 3.179142e-02 9.967457e-01 -7.407616e-02 -4.573740e+01 -4.312190e-02 7.541243e-02 9.962195e-01 2.188252e+02 +9.982752e-01 -2.906487e-02 5.100941e-02 3.885185e+02 3.270172e-02 9.968702e-01 -7.197511e-02 -4.583688e+01 -4.875781e-02 7.351905e-02 9.961012e-01 2.201001e+02 +9.979212e-01 -3.050015e-02 5.677186e-02 3.886025e+02 3.457994e-02 9.967814e-01 -7.232593e-02 -4.593383e+01 -5.438318e-02 7.413874e-02 9.957639e-01 2.213712e+02 +9.975700e-01 -2.959581e-02 6.307346e-02 3.886918e+02 3.416996e-02 9.967667e-01 -7.272158e-02 -4.602973e+01 -6.071727e-02 7.470007e-02 9.953558e-01 2.226461e+02 +9.971775e-01 -2.722130e-02 6.997160e-02 3.887813e+02 3.220299e-02 9.969504e-01 -7.108330e-02 -4.612697e+01 -6.782323e-02 7.313595e-02 9.950131e-01 2.239240e+02 +9.967503e-01 -2.400090e-02 7.689581e-02 3.888809e+02 2.930257e-02 9.972154e-01 -6.857697e-02 -4.622307e+01 -7.503577e-02 7.060734e-02 9.946779e-01 2.252047e+02 +9.962051e-01 -2.293678e-02 8.396092e-02 3.889895e+02 2.863975e-02 9.973174e-01 -6.736252e-02 -4.631800e+01 -8.219060e-02 6.951149e-02 9.941895e-01 2.264811e+02 +9.956475e-01 -2.141658e-02 9.070543e-02 3.891104e+02 2.758646e-02 9.973498e-01 -6.732312e-02 -4.641085e+01 -8.902320e-02 6.953232e-02 9.935995e-01 2.277622e+02 +9.950118e-01 -2.112150e-02 9.749603e-02 3.892392e+02 2.772206e-02 9.973778e-01 -6.685051e-02 -4.650321e+01 -9.582839e-02 6.921983e-02 9.929881e-01 2.290426e+02 +9.943603e-01 -2.119073e-02 1.039163e-01 3.893764e+02 2.822967e-02 9.973709e-01 -6.674062e-02 -4.659543e+01 -1.022288e-01 6.929773e-02 9.923442e-01 2.303227e+02 +9.937755e-01 -2.032057e-02 1.095327e-01 3.895195e+02 2.773058e-02 9.973971e-01 -6.655809e-02 -4.668700e+01 -1.078951e-01 6.918119e-02 9.917522e-01 2.316003e+02 +9.932040e-01 -2.063370e-02 1.145429e-01 3.896732e+02 2.840642e-02 9.973722e-01 -6.664652e-02 -4.677896e+01 -1.128667e-01 6.944733e-02 9.911801e-01 2.328820e+02 +9.925704e-01 -2.214285e-02 1.196402e-01 3.898351e+02 2.996825e-02 9.974992e-01 -6.400950e-02 -4.686866e+01 -1.179237e-01 6.711933e-02 9.907517e-01 2.341705e+02 +9.919578e-01 -2.203302e-02 1.246370e-01 3.900007e+02 2.990200e-02 9.976516e-01 -6.162091e-02 -4.695815e+01 -1.229866e-01 6.485222e-02 9.902870e-01 2.354553e+02 +9.913179e-01 -2.199490e-02 1.296342e-01 3.901748e+02 3.023331e-02 9.976225e-01 -6.192969e-02 -4.704460e+01 -1.279639e-01 6.531127e-02 9.896260e-01 2.367424e+02 +9.906305e-01 -2.133625e-02 1.348927e-01 3.903516e+02 2.990210e-02 9.976407e-01 -6.179736e-02 -4.713057e+01 -1.332559e-01 6.525191e-02 9.889312e-01 2.380274e+02 +9.899255e-01 -1.735985e-02 1.405213e-01 3.905331e+02 2.600060e-02 9.978663e-01 -5.989020e-02 -4.721628e+01 -1.391818e-01 6.294046e-02 9.882645e-01 2.393231e+02 +9.891680e-01 -1.482987e-02 1.460373e-01 3.907200e+02 2.326148e-02 9.981486e-01 -5.619859e-02 -4.729858e+01 -1.449335e-01 5.898688e-02 9.876815e-01 2.406186e+02 +9.882717e-01 -1.416601e-02 1.520477e-01 3.909188e+02 2.276441e-02 9.982290e-01 -5.495971e-02 -4.738016e+01 -1.509998e-01 5.777639e-02 9.868439e-01 2.419079e+02 +9.872788e-01 -1.378476e-02 1.583999e-01 3.911265e+02 2.401402e-02 9.977342e-01 -6.284727e-02 -4.745985e+01 -1.571747e-01 6.585158e-02 9.853728e-01 2.431918e+02 +9.863201e-01 -1.662841e-02 1.640006e-01 3.913476e+02 2.753716e-02 9.975397e-01 -6.446902e-02 -4.754471e+01 -1.625251e-01 6.810319e-02 9.843513e-01 2.444856e+02 +9.851744e-01 -2.014672e-02 1.703690e-01 3.915796e+02 3.090661e-02 9.976749e-01 -6.074184e-02 -4.763218e+01 -1.687491e-01 6.510682e-02 9.835063e-01 2.457820e+02 +9.839722e-01 -2.143260e-02 1.770296e-01 3.918172e+02 3.194665e-02 9.978768e-01 -5.675617e-02 -4.771693e+01 -1.754372e-01 6.150198e-02 9.825676e-01 2.470829e+02 +9.826430e-01 -2.087079e-02 1.843291e-01 3.920612e+02 3.165004e-02 9.979440e-01 -5.573084e-02 -4.779773e+01 -1.827869e-01 6.059754e-02 9.812832e-01 2.483790e+02 +9.810823e-01 -1.900808e-02 1.926559e-01 3.922854e+02 3.050866e-02 9.979133e-01 -5.690499e-02 -4.788529e+01 -1.911722e-01 6.170614e-02 9.796149e-01 2.496757e+02 +9.793824e-01 -1.625516e-02 2.013603e-01 3.924465e+02 2.845646e-02 9.979197e-01 -5.784860e-02 -4.799844e+01 -2.000010e-01 6.238589e-02 9.778075e-01 2.509910e+02 +9.775293e-01 -1.522754e-02 2.102490e-01 3.926606e+02 2.756818e-02 9.980563e-01 -5.588976e-02 -4.810821e+01 -2.089892e-01 6.043004e-02 9.760490e-01 2.523075e+02 +9.755662e-01 -1.615271e-02 2.191112e-01 3.929026e+02 2.834516e-02 9.982124e-01 -5.261596e-02 -4.821618e+01 -2.178696e-01 5.754108e-02 9.742801e-01 2.536263e+02 +9.735163e-01 -1.670445e-02 2.280069e-01 3.931927e+02 2.868556e-02 9.983703e-01 -4.933460e-02 -4.830781e+01 -2.268112e-01 5.456853e-02 9.724088e-01 2.549332e+02 +9.713597e-01 -1.881421e-02 2.368679e-01 3.935004e+02 3.066492e-02 9.984500e-01 -4.644622e-02 -4.840234e+01 -2.356269e-01 5.237952e-02 9.704309e-01 2.562429e+02 +9.691985e-01 -2.018110e-02 2.454529e-01 3.938049e+02 3.209481e-02 9.984877e-01 -4.463447e-02 -4.849902e+01 -2.441809e-01 5.113741e-02 9.683804e-01 2.575452e+02 +9.670522e-01 -2.029532e-02 2.537680e-01 3.941298e+02 3.251190e-02 9.985006e-01 -4.403949e-02 -4.859495e+01 -2.524937e-01 5.083895e-02 9.662620e-01 2.588412e+02 +9.650568e-01 -2.098930e-02 2.611989e-01 3.944742e+02 3.330629e-02 9.985275e-01 -4.281822e-02 -4.869712e+01 -2.599155e-01 5.002157e-02 9.643348e-01 2.601400e+02 +9.631610e-01 -2.071869e-02 2.681262e-01 3.948379e+02 3.267125e-02 9.986576e-01 -4.019297e-02 -4.878275e+01 -2.669335e-01 4.747231e-02 9.625449e-01 2.614371e+02 +9.612953e-01 -1.945192e-02 2.748329e-01 3.952124e+02 3.097263e-02 9.988112e-01 -3.764119e-02 -4.886035e+01 -2.737740e-01 4.469659e-02 9.607549e-01 2.627257e+02 +9.594594e-01 -1.768407e-02 2.812917e-01 3.955942e+02 2.877740e-02 9.989604e-01 -3.535494e-02 -4.892759e+01 -2.803741e-01 4.201647e-02 9.589707e-01 2.640122e+02 +9.574942e-01 -1.727743e-02 2.879348e-01 3.959751e+02 2.794386e-02 9.990654e-01 -3.297551e-02 -4.900841e+01 -2.870960e-01 3.961987e-02 9.570820e-01 2.652914e+02 +9.555954e-01 -1.691426e-02 2.941961e-01 3.963813e+02 2.714679e-02 9.991589e-01 -3.073227e-02 -4.905497e+01 -2.934288e-01 3.735409e-02 9.552508e-01 2.665599e+02 +9.537079e-01 -1.808776e-02 3.001903e-01 3.967835e+02 2.788614e-02 9.992079e-01 -2.838797e-02 -4.909264e+01 -2.994390e-01 3.544497e-02 9.534568e-01 2.678176e+02 +9.519246e-01 -1.798140e-02 3.058044e-01 3.971767e+02 2.843686e-02 9.991522e-01 -2.976932e-02 -4.916385e+01 -3.050098e-01 3.703425e-02 9.516288e-01 2.690674e+02 +9.501328e-01 -1.862735e-02 3.112889e-01 3.975917e+02 2.952217e-02 9.991040e-01 -3.032331e-02 -4.922697e+01 -3.104452e-01 3.800109e-02 9.498314e-01 2.703092e+02 +9.483539e-01 -1.846797e-02 3.166765e-01 3.980217e+02 2.883589e-02 9.991895e-01 -2.808426e-02 -4.928682e+01 -3.159011e-01 3.576546e-02 9.481177e-01 2.715422e+02 +9.465283e-01 -1.811364e-02 3.221119e-01 3.984708e+02 2.805667e-02 9.992615e-01 -2.625227e-02 -4.932933e+01 -3.213985e-01 3.388590e-02 9.463375e-01 2.727667e+02 +9.448040e-01 -1.642266e-02 3.272243e-01 3.989156e+02 2.582253e-02 9.993686e-01 -2.440203e-02 -4.936276e+01 -3.266169e-01 3.150489e-02 9.446315e-01 2.739881e+02 +9.430965e-01 -1.439578e-02 3.322076e-01 3.993613e+02 2.345286e-02 9.994541e-01 -2.326975e-02 -4.939503e+01 -3.316913e-01 2.973683e-02 9.429191e-01 2.752038e+02 +9.415820e-01 -1.258721e-02 3.365487e-01 3.998013e+02 2.266617e-02 9.994040e-01 -2.603588e-02 -4.943716e+01 -3.360204e-01 3.214317e-02 9.413060e-01 2.764172e+02 +9.400759e-01 -1.564360e-02 3.406062e-01 4.002616e+02 2.737676e-02 9.991848e-01 -2.966884e-02 -4.946179e+01 -3.398644e-01 3.721565e-02 9.397378e-01 2.776201e+02 +9.387890e-01 -1.623509e-02 3.441100e-01 4.007313e+02 2.869754e-02 9.991025e-01 -3.115403e-02 -4.948351e+01 -3.432954e-01 3.912216e-02 9.384123e-01 2.788211e+02 +9.375980e-01 -2.017786e-02 3.471353e-01 4.012035e+02 3.287507e-02 9.989870e-01 -3.072630e-02 -4.952256e+01 -3.461636e-01 4.022100e-02 9.373115e-01 2.800248e+02 +9.363863e-01 -2.142075e-02 3.503168e-01 4.016749e+02 3.339589e-02 9.990449e-01 -2.817784e-02 -4.957155e+01 -3.493786e-01 3.808448e-02 9.362073e-01 2.812301e+02 +9.350042e-01 -2.203035e-02 3.539517e-01 4.021409e+02 3.312650e-02 9.991304e-01 -2.532048e-02 -4.961643e+01 -3.530861e-01 3.539993e-02 9.349208e-01 2.824359e+02 +9.337801e-01 -2.413478e-02 3.570325e-01 4.026156e+02 3.392611e-02 9.991997e-01 -2.118592e-02 -4.965547e+01 -3.562355e-01 3.189571e-02 9.338516e-01 2.836388e+02 +9.327281e-01 -2.524824e-02 3.596956e-01 4.030993e+02 3.354003e-02 9.992957e-01 -1.682886e-02 -4.968106e+01 -3.590173e-01 2.776094e-02 9.329179e-01 2.848362e+02 +9.318439e-01 -2.714206e-02 3.618429e-01 4.035935e+02 3.607197e-02 9.991880e-01 -1.794541e-02 -4.969607e+01 -3.610620e-01 2.977470e-02 9.320663e-01 2.860179e+02 +9.313792e-01 -2.569237e-02 3.631429e-01 4.040736e+02 3.557789e-02 9.991554e-01 -2.055894e-02 -4.972304e+01 -3.623079e-01 3.206801e-02 9.315066e-01 2.871951e+02 +9.309306e-01 -2.464485e-02 3.643638e-01 4.045526e+02 3.479498e-02 9.991671e-01 -2.131768e-02 -4.975569e+01 -3.635349e-01 3.252331e-02 9.310126e-01 2.883689e+02 +9.304086e-01 -2.510911e-02 3.656631e-01 4.050287e+02 3.472565e-02 9.992018e-01 -1.974486e-02 -4.979056e+01 -3.648754e-01 3.106867e-02 9.305378e-01 2.895384e+02 +9.299192e-01 -2.553068e-02 3.668766e-01 4.055034e+02 3.444833e-02 9.992483e-01 -1.777893e-02 -4.982507e+01 -3.661469e-01 2.917125e-02 9.300996e-01 2.907010e+02 +9.294337e-01 -2.749872e-02 3.679632e-01 4.059814e+02 3.575322e-02 9.992383e-01 -1.563329e-02 -4.985634e+01 -3.672530e-01 2.768597e-02 9.297089e-01 2.918586e+02 +9.289014e-01 -2.909003e-02 3.691829e-01 4.064546e+02 3.704947e-02 9.992084e-01 -1.448688e-02 -4.988691e+01 -3.684692e-01 2.713491e-02 9.292438e-01 2.930080e+02 +9.283668e-01 -3.069336e-02 3.703958e-01 4.069281e+02 3.858653e-02 9.991583e-01 -1.391734e-02 -4.991560e+01 -3.696569e-01 2.721268e-02 9.287697e-01 2.941501e+02 +9.278081e-01 -3.069731e-02 3.717929e-01 4.073967e+02 3.872624e-02 9.991497e-01 -1.414581e-02 -4.994467e+01 -3.710425e-01 2.752273e-02 9.282079e-01 2.952863e+02 +9.272795e-01 -2.973974e-02 3.731868e-01 4.078657e+02 3.780387e-02 9.991827e-01 -1.430733e-02 -4.997269e+01 -3.724563e-01 2.737479e-02 9.276458e-01 2.964165e+02 +9.268548e-01 -2.695543e-02 3.744513e-01 4.083278e+02 3.523327e-02 9.992623e-01 -1.527722e-02 -5.000237e+01 -3.737632e-01 2.735290e-02 9.271207e-01 2.975366e+02 +9.264969e-01 -2.264903e-02 3.756202e-01 4.087875e+02 3.117540e-02 9.993754e-01 -1.663655e-02 -5.003369e+01 -3.750088e-01 2.712382e-02 9.266243e-01 2.986544e+02 +9.261379e-01 -1.956445e-02 3.766775e-01 4.092454e+02 2.794868e-02 9.994681e-01 -1.680559e-02 -5.006504e+01 -3.761483e-01 2.609192e-02 9.261920e-01 2.997660e+02 +9.257766e-01 -1.790568e-02 3.776469e-01 4.097029e+02 2.544472e-02 9.995639e-01 -1.498293e-02 -5.009530e+01 -3.772140e-01 2.347996e-02 9.258284e-01 3.008713e+02 +9.253977e-01 -1.672172e-02 3.786285e-01 4.101603e+02 2.385900e-02 9.996149e-01 -1.416634e-02 -5.012560e+01 -3.782458e-01 2.214318e-02 9.254403e-01 3.019707e+02 +9.252146e-01 -1.539983e-02 3.791318e-01 4.106169e+02 2.298254e-02 9.996160e-01 -1.548237e-02 -5.015338e+01 -3.787478e-01 2.303792e-02 9.252131e-01 3.030620e+02 +9.250066e-01 -1.394934e-02 3.796949e-01 4.110752e+02 2.144208e-02 9.996497e-01 -1.551142e-02 -5.017964e+01 -3.793456e-01 2.248961e-02 9.249817e-01 3.041567e+02 +9.247377e-01 -1.333165e-02 3.803715e-01 4.115327e+02 2.023470e-02 9.996950e-01 -1.415514e-02 -5.020581e+01 -3.800667e-01 2.078649e-02 9.247254e-01 3.052486e+02 +9.245264e-01 -1.407726e-02 3.808581e-01 4.119926e+02 2.034382e-02 9.997157e-01 -1.243281e-02 -5.022978e+01 -3.805748e-01 1.924257e-02 9.245499e-01 3.063400e+02 +9.245754e-01 -1.344222e-02 3.807620e-01 4.124502e+02 1.963969e-02 9.997303e-01 -1.239560e-02 -5.025285e+01 -3.804927e-01 1.893871e-02 9.245899e-01 3.074279e+02 +9.249685e-01 -1.450879e-02 3.797669e-01 4.129102e+02 2.194671e-02 9.996426e-01 -1.526308e-02 -5.027516e+01 -3.794097e-01 2.245250e-02 9.249563e-01 3.085143e+02 +9.254868e-01 -1.555462e-02 3.784605e-01 4.133703e+02 2.357363e-02 9.995848e-01 -1.656425e-02 -5.029512e+01 -3.780457e-01 2.425168e-02 9.254692e-01 3.096081e+02 +9.258711e-01 -1.539645e-02 3.775259e-01 4.138293e+02 2.210449e-02 9.996653e-01 -1.344173e-02 -5.031800e+01 -3.771925e-01 2.079032e-02 9.259014e-01 3.107097e+02 +9.261389e-01 -1.608569e-02 3.768397e-01 4.142865e+02 2.166040e-02 9.997096e-01 -1.056024e-02 -5.034033e+01 -3.765603e-01 1.794275e-02 9.262183e-01 3.118152e+02 +9.263334e-01 -1.626177e-02 3.763537e-01 4.147414e+02 2.209821e-02 9.996931e-01 -1.119565e-02 -5.036460e+01 -3.760561e-01 1.868764e-02 9.264084e-01 3.129218e+02 +9.260759e-01 -1.515930e-02 3.770328e-01 4.151850e+02 2.150972e-02 9.996887e-01 -1.263829e-02 -5.037546e+01 -3.767238e-01 1.981388e-02 9.261136e-01 3.140367e+02 +9.252226e-01 -1.430889e-02 3.791550e-01 4.156324e+02 2.062594e-02 9.997078e-01 -1.260401e-02 -5.039335e+01 -3.788638e-01 1.948194e-02 9.252473e-01 3.151581e+02 +9.237468e-01 -1.205468e-02 3.828141e-01 4.160741e+02 1.776385e-02 9.997774e-01 -1.138228e-02 -5.042223e+01 -3.825917e-01 1.731459e-02 9.237552e-01 3.162881e+02 +9.215988e-01 -9.739051e-03 3.880218e-01 4.165185e+02 1.436449e-02 9.998561e-01 -9.021773e-03 -5.044333e+01 -3.878781e-01 1.388819e-02 9.216060e-01 3.174206e+02 +9.190167e-01 -6.799962e-03 3.941600e-01 4.169553e+02 1.055051e-02 9.999173e-01 -7.349038e-03 -5.046435e+01 -3.940774e-01 1.091248e-02 9.190124e-01 3.185546e+02 +9.159101e-01 -5.416200e-03 4.013470e-01 4.174115e+02 8.668583e-03 9.999426e-01 -6.288208e-03 -5.050360e+01 -4.012899e-01 9.238540e-03 9.159045e-01 3.196865e+02 +9.124637e-01 -4.249139e-03 4.091357e-01 4.178668e+02 7.824973e-03 9.999444e-01 -7.066363e-03 -5.054481e+01 -4.090829e-01 9.649272e-03 9.124461e-01 3.208200e+02 +9.087668e-01 -5.752046e-03 4.172648e-01 4.183565e+02 9.495446e-03 9.999311e-01 -6.896089e-03 -5.057667e+01 -4.171964e-01 1.022905e-02 9.087587e-01 3.219502e+02 +9.049689e-01 -9.641737e-03 4.253686e-01 4.188572e+02 1.219600e-02 9.999202e-01 -3.281938e-03 -5.062303e+01 -4.253030e-01 8.157845e-03 9.050142e-01 3.230886e+02 +9.011310e-01 -1.458733e-02 4.333016e-01 4.193825e+02 1.591999e-02 9.998731e-01 5.527135e-04 -5.065799e+01 -4.332546e-01 6.400085e-03 9.012488e-01 3.242258e+02 +8.974237e-01 -1.444578e-02 4.409332e-01 4.199191e+02 1.651501e-02 9.998632e-01 -8.553614e-04 -5.067274e+01 -4.408605e-01 8.049632e-03 8.975395e-01 3.253605e+02 +8.935528e-01 -1.027044e-02 4.488408e-01 4.204756e+02 1.536357e-02 9.998522e-01 -7.707056e-03 -5.067188e+01 -4.486953e-01 1.378245e-02 8.935785e-01 3.264945e+02 +8.896391e-01 -4.296185e-03 4.566441e-01 4.210434e+02 1.185488e-02 9.998360e-01 -1.368918e-02 -5.067756e+01 -4.565104e-01 1.759188e-02 8.895441e-01 3.276299e+02 +8.857160e-01 1.403117e-04 4.642276e-01 4.216195e+02 6.730839e-03 9.998909e-01 -1.314422e-02 -5.068966e+01 -4.641788e-01 1.476668e-02 8.856184e-01 3.287727e+02 +8.818555e-01 -4.994580e-03 4.714933e-01 4.222220e+02 8.911464e-03 9.999418e-01 -6.075027e-03 -5.070108e+01 -4.714355e-01 9.558988e-03 8.818487e-01 3.299184e+02 +8.785978e-01 -1.033846e-02 4.774507e-01 4.228378e+02 1.233461e-02 9.999234e-01 -1.046157e-03 -5.070339e+01 -4.774033e-01 6.808315e-03 8.786579e-01 3.310646e+02 +8.754808e-01 -1.482890e-02 4.830254e-01 4.234653e+02 1.695072e-02 9.998563e-01 -2.744814e-05 -5.070480e+01 -4.829555e-01 8.211655e-03 8.756063e-01 3.322051e+02 +8.727663e-01 -1.378140e-02 4.879438e-01 4.240972e+02 1.721219e-02 9.998486e-01 -2.547225e-03 -5.070857e+01 -4.878348e-01 1.062171e-02 8.728713e-01 3.333479e+02 +8.697126e-01 -1.352970e-02 4.933732e-01 4.247366e+02 1.648192e-02 9.998628e-01 -1.635044e-03 -5.071521e+01 -4.932833e-01 9.553751e-03 8.698162e-01 3.344946e+02 +8.666616e-01 -1.701191e-02 4.986065e-01 4.253894e+02 1.600090e-02 9.998521e-01 6.301630e-03 -5.071687e+01 -4.986399e-01 2.516770e-03 8.668055e-01 3.356485e+02 +8.638961e-01 -1.810590e-02 5.033445e-01 4.260497e+02 1.673352e-02 9.998337e-01 7.245278e-03 -5.071526e+01 -5.033920e-01 2.163555e-03 8.640554e-01 3.367933e+02 +8.611714e-01 -2.287192e-02 5.078000e-01 4.267189e+02 2.250469e-02 9.997232e-01 6.863318e-03 -5.070976e+01 -5.078164e-01 5.517387e-03 8.614476e-01 3.379277e+02 +8.583887e-01 -2.477028e-02 5.124015e-01 4.273937e+02 2.404482e-02 9.996785e-01 8.045497e-03 -5.070986e+01 -5.124360e-01 5.414433e-03 8.587083e-01 3.390621e+02 +8.557579e-01 -2.733834e-02 5.166538e-01 4.280714e+02 2.598052e-02 9.996138e-01 9.861063e-03 -5.070922e+01 -5.167238e-01 4.984247e-03 8.561376e-01 3.401914e+02 +8.534814e-01 -3.098499e-02 5.202014e-01 4.287528e+02 2.938657e-02 9.995040e-01 1.132011e-02 -5.070740e+01 -5.202941e-01 5.625426e-03 8.539685e-01 3.413095e+02 +8.513482e-01 -3.565003e-02 5.233883e-01 4.294414e+02 3.304348e-02 9.993513e-01 1.432092e-02 -5.070413e+01 -5.235593e-01 5.102481e-03 8.519739e-01 3.424274e+02 +8.498856e-01 -4.004551e-02 5.254435e-01 4.301287e+02 3.673630e-02 9.991849e-01 1.673105e-02 -5.069724e+01 -5.256852e-01 5.083368e-03 8.506640e-01 3.435367e+02 +8.487568e-01 -4.415968e-02 5.269364e-01 4.308174e+02 4.256836e-02 9.989786e-01 1.515250e-02 -5.068971e+01 -5.270673e-01 9.570028e-03 8.497696e-01 3.446357e+02 +8.479382e-01 -4.435365e-02 5.282363e-01 4.315028e+02 4.377650e-02 9.989487e-01 1.360614e-02 -5.068167e+01 -5.282844e-01 1.158717e-02 8.489883e-01 3.457360e+02 +8.469595e-01 -4.539715e-02 5.297157e-01 4.321864e+02 4.357113e-02 9.989231e-01 1.594303e-02 -5.067375e+01 -5.298690e-01 9.577206e-03 8.480254e-01 3.468369e+02 +8.459833e-01 -4.366646e-02 5.314184e-01 4.328699e+02 4.116201e-02 9.990152e-01 1.656151e-02 -5.066461e+01 -5.316182e-01 7.863486e-03 8.469476e-01 3.479396e+02 +8.449145e-01 -4.228955e-02 5.332272e-01 4.335555e+02 4.006301e-02 9.990729e-01 1.575415e-02 -5.065275e+01 -5.333990e-01 8.051772e-03 8.458254e-01 3.490376e+02 +8.440618e-01 -4.269861e-02 5.345434e-01 4.342472e+02 4.047373e-02 9.990542e-01 1.589374e-02 -5.064100e+01 -5.347164e-01 8.219659e-03 8.449916e-01 3.501372e+02 +8.433043e-01 -4.605265e-02 5.354597e-01 4.349485e+02 4.257821e-02 9.989152e-01 1.885540e-02 -5.062789e+01 -5.357471e-01 6.898073e-03 8.443503e-01 3.512422e+02 +8.427552e-01 -4.861789e-02 5.360971e-01 4.356474e+02 4.287945e-02 9.988114e-01 2.317348e-02 -5.061209e+01 -5.365865e-01 3.457979e-03 8.438381e-01 3.523451e+02 +8.425395e-01 -4.845591e-02 5.364507e-01 4.363479e+02 4.091262e-02 9.988253e-01 2.596418e-02 -5.059206e+01 -5.370786e-01 7.175806e-05 8.435321e-01 3.534559e+02 +8.431623e-01 -4.284696e-02 5.359492e-01 4.370414e+02 3.516830e-02 9.990799e-01 2.454515e-02 -5.057005e+01 -5.365077e-01 -1.847127e-03 8.438933e-01 3.545688e+02 +8.433080e-01 -4.173622e-02 5.358076e-01 4.377377e+02 3.727219e-02 9.991214e-01 1.916288e-02 -5.055040e+01 -5.361366e-01 3.810508e-03 8.441226e-01 3.556739e+02 +8.440995e-01 -3.820603e-02 5.348237e-01 4.384341e+02 3.613139e-02 9.992439e-01 1.435736e-02 -5.053344e+01 -5.349678e-01 7.204873e-03 8.448417e-01 3.567825e+02 +8.450063e-01 -4.638969e-02 5.327404e-01 4.391465e+02 4.075808e-02 9.989194e-01 2.233494e-02 -5.051716e+01 -5.332008e-01 2.840307e-03 8.459839e-01 3.579044e+02 +8.455395e-01 -5.792979e-02 5.307610e-01 4.398589e+02 4.906857e-02 9.983206e-01 3.079183e-02 -5.049673e+01 -5.316534e-01 7.970301e-06 8.469620e-01 3.590198e+02 +8.459052e-01 -5.954037e-02 5.299994e-01 4.405580e+02 5.192098e-02 9.982221e-01 2.927227e-02 -5.047024e+01 -5.308000e-01 2.756525e-03 8.474926e-01 3.601299e+02 +8.463100e-01 -5.683599e-02 5.296500e-01 4.412505e+02 5.258228e-02 9.983491e-01 2.311198e-02 -5.044780e+01 -5.300891e-01 8.290293e-03 8.479013e-01 3.612403e+02 +8.469717e-01 -5.362340e-02 5.289268e-01 4.419384e+02 4.944551e-02 9.985332e-01 2.205561e-02 -5.043091e+01 -5.293337e-01 7.472577e-03 8.483807e-01 3.623548e+02 +8.472027e-01 -5.361832e-02 5.285572e-01 4.426281e+02 4.790801e-02 9.985511e-01 2.450604e-02 -5.041375e+01 -5.291053e-01 4.560537e-03 8.485438e-01 3.634731e+02 +8.473918e-01 -5.548073e-02 5.280617e-01 4.433188e+02 4.789330e-02 9.984586e-01 2.804753e-02 -5.039240e+01 -5.288038e-01 1.523366e-03 8.487427e-01 3.645916e+02 +8.475334e-01 -5.935355e-02 5.274128e-01 4.440115e+02 4.962924e-02 9.982360e-01 3.258626e-02 -5.036612e+01 -5.284165e-01 -1.442853e-03 8.489840e-01 3.657076e+02 +8.477600e-01 -6.297726e-02 5.266279e-01 4.447041e+02 5.248407e-02 9.980131e-01 3.486001e-02 -5.033585e+01 -5.277769e-01 -1.913343e-03 8.493808e-01 3.668202e+02 +8.482221e-01 -6.303893e-02 5.258759e-01 4.453903e+02 5.285163e-02 9.980101e-01 3.438752e-02 -5.030406e+01 -5.269972e-01 -1.374855e-03 8.498658e-01 3.679305e+02 +8.485519e-01 -6.251521e-02 5.254061e-01 4.460742e+02 5.232518e-02 9.980428e-01 3.424441e-02 -5.027172e+01 -5.265185e-01 -1.566196e-03 8.501622e-01 3.690430e+02 +8.485461e-01 -6.306598e-02 5.253497e-01 4.467592e+02 5.126884e-02 9.979994e-01 3.699601e-02 -5.023884e+01 -5.266318e-01 -4.458751e-03 8.500817e-01 3.701604e+02 +8.486828e-01 -6.315186e-02 5.251185e-01 4.474413e+02 5.041421e-02 9.979844e-01 3.854160e-02 -5.020273e+01 -5.264940e-01 -6.236162e-03 8.501559e-01 3.712738e+02 +8.491383e-01 -6.257593e-02 5.244507e-01 4.481081e+02 5.099117e-02 9.980310e-01 3.652236e-02 -5.017839e+01 -5.257034e-01 -4.270186e-03 8.506571e-01 3.723930e+02 +8.492760e-01 -6.190915e-02 5.243067e-01 4.487750e+02 5.084747e-02 9.980757e-01 3.548779e-02 -5.014982e+01 -5.254948e-01 -3.479262e-03 8.507896e-01 3.735083e+02 +8.489440e-01 -6.107139e-02 5.249424e-01 4.494392e+02 4.898312e-02 9.981176e-01 3.690408e-02 -5.012704e+01 -5.262080e-01 -5.616178e-03 8.503373e-01 3.746319e+02 +8.484016e-01 -5.930652e-02 5.260205e-01 4.501062e+02 4.668440e-02 9.982149e-01 3.724864e-02 -5.010153e+01 -5.272905e-01 -7.044852e-03 8.496558e-01 3.757485e+02 +8.475575e-01 -5.814479e-02 5.275088e-01 4.507610e+02 4.567910e-02 9.982839e-01 3.664271e-02 -5.009137e+01 -5.287341e-01 -6.960679e-03 8.487589e-01 3.768612e+02 +8.466814e-01 -5.945196e-02 5.287685e-01 4.514169e+02 4.655291e-02 9.982045e-01 3.769086e-02 -5.008647e+01 -5.300599e-01 -7.296438e-03 8.479288e-01 3.779697e+02 +8.458521e-01 -6.129185e-02 5.298845e-01 4.520776e+02 4.744896e-02 9.980842e-01 3.970607e-02 -5.007631e+01 -5.313029e-01 -8.442993e-03 8.471398e-01 3.790761e+02 +8.449315e-01 -6.307558e-02 5.311424e-01 4.527397e+02 4.868696e-02 9.979696e-01 4.106314e-02 -5.006547e+01 -5.326540e-01 -8.835839e-03 8.462869e-01 3.801826e+02 +8.440052e-01 -6.323668e-02 5.325940e-01 4.534069e+02 4.916308e-02 9.979659e-01 4.058282e-02 -5.004426e+01 -5.340769e-01 -8.068156e-03 8.453973e-01 3.812831e+02 +8.429871e-01 -6.253770e-02 5.342863e-01 4.540727e+02 4.940776e-02 9.980223e-01 3.886292e-02 -5.002547e+01 -5.356600e-01 -6.363054e-03 8.444097e-01 3.823822e+02 +8.419143e-01 -6.259452e-02 5.359686e-01 4.547484e+02 4.927889e-02 9.980175e-01 3.914751e-02 -4.999923e+01 -5.373564e-01 -6.546913e-03 8.433298e-01 3.834829e+02 +8.409517e-01 -6.351120e-02 5.373701e-01 4.554386e+02 5.035054e-02 9.979638e-01 3.915274e-02 -4.996466e+01 -5.387626e-01 -5.868688e-03 8.424371e-01 3.845767e+02 +8.399578e-01 -6.324550e-02 5.389536e-01 4.561499e+02 5.060675e-02 9.979862e-01 3.824189e-02 -4.992720e+01 -5.402868e-01 -4.846888e-03 8.414669e-01 3.856718e+02 +8.383868e-01 -6.138115e-02 5.416087e-01 4.568676e+02 4.868710e-02 9.981004e-01 3.775039e-02 -4.989102e+01 -5.428970e-01 -5.280075e-03 8.397826e-01 3.867691e+02 +8.362876e-01 -5.970948e-02 5.450301e-01 4.575354e+02 4.643841e-02 9.981943e-01 3.810028e-02 -4.987387e+01 -5.463209e-01 -6.552456e-03 8.375503e-01 3.878709e+02 +8.341401e-01 -5.633722e-02 5.486680e-01 4.582246e+02 4.112109e-02 9.983534e-01 3.999452e-02 -4.984183e+01 -5.500177e-01 -1.079921e-02 8.350831e-01 3.889684e+02 +8.319430e-01 -5.358986e-02 5.522672e-01 4.589213e+02 3.919946e-02 9.985146e-01 3.784138e-02 -4.981625e+01 -5.534747e-01 -9.833299e-03 8.328079e-01 3.900529e+02 +8.299513e-01 -5.028827e-02 5.555645e-01 4.596319e+02 3.796147e-02 9.987111e-01 3.369057e-02 -4.979093e+01 -5.565427e-01 -6.871491e-03 8.307905e-01 3.911296e+02 +8.280768e-01 -5.189445e-02 5.582077e-01 4.603518e+02 3.935264e-02 9.986309e-01 3.446100e-02 -4.976661e+01 -5.592318e-01 -6.569409e-03 8.289853e-01 3.922056e+02 +8.262504e-01 -5.584297e-02 5.605282e-01 4.610755e+02 3.986585e-02 9.983758e-01 4.069929e-02 -4.973599e+01 -5.618906e-01 -1.128187e-02 8.271346e-01 3.932744e+02 +8.244199e-01 -5.900649e-02 5.628944e-01 4.617993e+02 3.980099e-02 9.981326e-01 4.633832e-02 -4.970462e+01 -5.645774e-01 -1.579848e-02 8.252288e-01 3.943336e+02 +8.229806e-01 -5.520510e-02 5.653807e-01 4.625031e+02 3.351257e-02 9.982515e-01 4.868999e-02 -4.967633e+01 -5.670801e-01 -2.112356e-02 8.233917e-01 3.953881e+02 +8.211088e-01 -5.287040e-02 5.683179e-01 4.632000e+02 3.121483e-02 9.983701e-01 4.777865e-02 -4.965751e+01 -5.699176e-01 -2.149153e-02 8.214207e-01 3.964219e+02 +8.197677e-01 -4.616507e-02 5.708325e-01 4.638813e+02 2.684225e-02 9.987475e-01 4.222402e-02 -4.964550e+01 -5.720668e-01 -1.929146e-02 8.199801e-01 3.974327e+02 +8.182417e-01 -4.698343e-02 5.729512e-01 4.645685e+02 3.310205e-02 9.988517e-01 3.463471e-02 -4.964502e+01 -5.739205e-01 -9.373710e-03 8.188573e-01 3.984196e+02 +8.173506e-01 -4.968898e-02 5.739940e-01 4.652577e+02 3.756118e-02 9.987502e-01 3.297286e-02 -4.963689e+01 -5.749150e-01 -5.390496e-03 8.181953e-01 3.993976e+02 +8.161949e-01 -5.547810e-02 5.751071e-01 4.659483e+02 4.045478e-02 9.984238e-01 3.890002e-02 -4.964295e+01 -5.763587e-01 -8.484169e-03 8.171527e-01 4.003768e+02 +8.152466e-01 -5.694576e-02 5.763074e-01 4.666320e+02 3.990343e-02 9.983121e-01 4.219713e-02 -4.964662e+01 -5.777376e-01 -1.140442e-02 8.161428e-01 4.013472e+02 +8.139535e-01 -5.305713e-02 5.785022e-01 4.673129e+02 3.446609e-02 9.984769e-01 4.308113e-02 -4.965217e+01 -5.799068e-01 -1.512733e-02 8.145423e-01 4.023110e+02 +8.128011e-01 -5.059527e-02 5.803401e-01 4.679866e+02 3.172265e-02 9.985872e-01 4.262948e-02 -4.966780e+01 -5.816770e-01 -1.623936e-02 8.132577e-01 4.032705e+02 +8.120738e-01 -4.646621e-02 5.817019e-01 4.686544e+02 2.721064e-02 9.987556e-01 4.179348e-02 -4.968339e+01 -5.829200e-01 -1.811091e-02 8.123276e-01 4.042217e+02 +8.116076e-01 -4.301011e-02 5.826177e-01 4.693241e+02 2.455886e-02 9.989165e-01 3.953082e-02 -4.970798e+01 -5.836866e-01 -1.777509e-02 8.117844e-01 4.051674e+02 +8.111254e-01 -4.218194e-02 5.833493e-01 4.699917e+02 2.607490e-02 9.990122e-01 3.598233e-02 -4.971571e+01 -5.842908e-01 -1.397541e-02 8.114240e-01 4.061039e+02 +8.103859e-01 -4.242740e-02 5.843583e-01 4.706576e+02 2.513621e-02 9.989740e-01 3.767182e-02 -4.972856e+01 -5.853570e-01 -1.584016e-02 8.106209e-01 4.070389e+02 +8.096526e-01 -4.263409e-02 5.853589e-01 4.713180e+02 2.332425e-02 9.989075e-01 4.049307e-02 -4.972550e+01 -5.864458e-01 -1.913226e-02 8.097624e-01 4.079723e+02 +8.090883e-01 -4.037001e-02 5.862990e-01 4.720000e+02 2.251230e-02 9.990346e-01 3.772239e-02 -4.972107e+01 -5.872558e-01 -1.732180e-02 8.092159e-01 4.088815e+02 +8.085266e-01 -4.033181e-02 5.870759e-01 4.726778e+02 2.421730e-02 9.990838e-01 3.528424e-02 -4.970555e+01 -5.879611e-01 -1.431085e-02 8.087625e-01 4.097837e+02 +8.080478e-01 -4.404145e-02 5.874685e-01 4.733486e+02 2.754969e-02 9.989356e-01 3.699451e-02 -4.971418e+01 -5.884725e-01 -1.370876e-02 8.084010e-01 4.106861e+02 +8.080251e-01 -4.261344e-02 5.876050e-01 4.740047e+02 2.511046e-02 9.989654e-01 3.791574e-02 -4.971943e+01 -5.886128e-01 -1.588184e-02 8.082590e-01 4.115882e+02 +8.084198e-01 -4.288799e-02 5.870418e-01 4.746572e+02 2.838406e-02 9.990221e-01 3.389846e-02 -4.971799e+01 -5.879216e-01 -1.074155e-02 8.088465e-01 4.124871e+02 +8.087301e-01 -4.450357e-02 5.864940e-01 4.753041e+02 3.022956e-02 9.989605e-01 3.411760e-02 -4.971770e+01 -5.874026e-01 -9.862477e-03 8.092347e-01 4.133816e+02 +8.090405e-01 -4.643652e-02 5.859156e-01 4.759525e+02 3.099677e-02 9.988578e-01 3.636333e-02 -4.971658e+01 -5.869350e-01 -1.125791e-02 8.095557e-01 4.142647e+02 +8.091605e-01 -4.928208e-02 5.855174e-01 4.765926e+02 3.320652e-02 9.987193e-01 3.817062e-02 -4.969435e+01 -5.866487e-01 -1.144316e-02 8.097606e-01 4.151395e+02 +8.090328e-01 -5.124243e-02 5.855256e-01 4.772277e+02 3.535064e-02 9.986311e-01 3.855079e-02 -4.967882e+01 -5.866995e-01 -1.049015e-02 8.097367e-01 4.160040e+02 +8.083054e-01 -5.154320e-02 5.865030e-01 4.778661e+02 3.643272e-02 9.986303e-01 3.755112e-02 -4.967507e+01 -5.876352e-01 -8.984873e-03 8.090761e-01 4.168581e+02 +8.068433e-01 -5.133585e-02 5.885308e-01 4.784963e+02 3.725662e-02 9.986559e-01 3.603312e-02 -4.967850e+01 -5.895895e-01 -7.146414e-03 8.076714e-01 4.177107e+02 +8.047808e-01 -5.149047e-02 5.913346e-01 4.791285e+02 3.823901e-02 9.986584e-01 3.491656e-02 -4.970981e+01 -5.923391e-01 -5.488130e-03 8.056700e-01 4.185547e+02 +8.024526e-01 -5.286432e-02 5.943697e-01 4.797502e+02 3.939519e-02 9.985883e-01 3.562921e-02 -4.971873e+01 -5.954140e-01 -5.175445e-03 8.034023e-01 4.193894e+02 +8.001658e-01 -5.329270e-02 5.974066e-01 4.803721e+02 3.927053e-02 9.985625e-01 3.647961e-02 -4.973913e+01 -5.984919e-01 -5.729263e-03 8.011083e-01 4.202133e+02 +7.976975e-01 -5.438129e-02 6.006009e-01 4.809890e+02 4.041211e-02 9.985075e-01 3.673571e-02 -4.974996e+01 -6.017023e-01 -5.032433e-03 7.987046e-01 4.210252e+02 +7.953807e-01 -5.458364e-02 6.036475e-01 4.815995e+02 4.046716e-02 9.984968e-01 3.696661e-02 -4.977732e+01 -6.047578e-01 -4.974626e-03 7.963938e-01 4.218233e+02 +7.925737e-01 -5.462434e-02 6.073246e-01 4.821954e+02 3.975822e-02 9.984895e-01 3.792126e-02 -4.979676e+01 -6.084786e-01 -5.909246e-03 7.935482e-01 4.226029e+02 +7.897214e-01 -5.457860e-02 6.110331e-01 4.827883e+02 3.908184e-02 9.984872e-01 3.867595e-02 -4.980163e+01 -6.122196e-01 -6.662929e-03 7.906597e-01 4.233674e+02 +7.868068e-01 -5.558920e-02 6.146910e-01 4.833777e+02 3.922604e-02 9.984261e-01 4.008259e-02 -4.980171e+01 -6.159517e-01 -7.425360e-03 7.877489e-01 4.241147e+02 +7.844210e-01 -5.411376e-02 6.178637e-01 4.839555e+02 3.738301e-02 9.985005e-01 3.999038e-02 -4.980038e+01 -6.191012e-01 -8.271686e-03 7.852676e-01 4.248437e+02 +7.822525e-01 -5.321709e-02 6.206843e-01 4.845264e+02 3.514153e-02 9.985276e-01 4.132405e-02 -4.980331e+01 -6.219695e-01 -1.051405e-02 7.829708e-01 4.255572e+02 +7.804182e-01 -5.385347e-02 6.229345e-01 4.850829e+02 3.524313e-02 9.984887e-01 4.216769e-02 -4.980460e+01 -6.242639e-01 -1.095427e-02 7.811367e-01 4.262513e+02 +7.788888e-01 -5.436482e-02 6.248014e-01 4.856285e+02 3.748901e-02 9.984903e-01 4.014552e-02 -4.982198e+01 -6.260406e-01 -7.845710e-03 7.797510e-01 4.269236e+02 +7.779924e-01 -5.051340e-02 6.262397e-01 4.861568e+02 3.835224e-02 9.987221e-01 3.291249e-02 -4.982520e+01 -6.271020e-01 -1.587974e-03 7.789355e-01 4.275808e+02 +7.776146e-01 -4.702968e-02 6.269799e-01 4.866754e+02 3.763970e-02 9.988921e-01 2.824397e-02 -4.983388e+01 -6.276136e-01 1.636411e-03 7.785232e-01 4.282275e+02 +7.780034e-01 -4.929364e-02 6.263233e-01 4.871908e+02 4.141447e-02 9.987727e-01 2.716256e-02 -4.984007e+01 -6.268935e-01 4.806276e-03 7.790900e-01 4.288658e+02 +7.787757e-01 -5.324259e-02 6.250390e-01 4.877030e+02 4.357792e-02 9.985762e-01 3.076507e-02 -4.983894e+01 -6.257870e-01 3.278807e-03 7.799870e-01 4.294980e+02 +7.792823e-01 -5.736298e-02 6.240421e-01 4.882066e+02 4.658905e-02 9.983492e-01 3.359111e-02 -4.982442e+01 -6.249388e-01 2.896567e-03 7.806683e-01 4.301206e+02 +7.802679e-01 -6.072224e-02 6.224908e-01 4.886994e+02 4.961284e-02 9.981488e-01 3.517887e-02 -4.980758e+01 -6.234746e-01 3.434592e-03 7.818360e-01 4.307312e+02 +7.812642e-01 -6.265481e-02 6.210481e-01 4.891779e+02 5.051423e-02 9.980325e-01 3.714138e-02 -4.979310e+01 -6.221532e-01 2.354537e-03 7.828919e-01 4.313315e+02 +7.820140e-01 -6.610942e-02 6.197449e-01 4.896458e+02 5.377237e-02 9.978074e-01 3.858641e-02 -4.977726e+01 -6.209370e-01 3.150038e-03 7.838541e-01 4.319182e+02 +7.833988e-01 -6.785747e-02 6.178040e-01 4.901080e+02 5.629223e-02 9.976832e-01 3.820144e-02 -4.973997e+01 -6.189649e-01 4.850598e-03 7.854036e-01 4.324918e+02 +7.842542e-01 -6.751717e-02 6.167551e-01 4.905495e+02 5.620144e-02 9.977053e-01 3.775573e-02 -4.970613e+01 -6.178889e-01 5.052425e-03 7.862491e-01 4.330534e+02 +7.850588e-01 -6.167192e-02 6.163435e-01 4.909717e+02 4.995359e-02 9.980937e-01 3.624254e-02 -4.967324e+01 -6.174037e-01 2.336043e-03 7.866429e-01 4.336022e+02 +7.857347e-01 -5.617523e-02 6.160077e-01 4.913754e+02 4.497780e-02 9.984201e-01 3.367795e-02 -4.965832e+01 -6.169263e-01 1.244736e-03 7.870199e-01 4.341389e+02 +7.864063e-01 -5.202109e-02 6.155152e-01 4.917693e+02 4.187214e-02 9.986449e-01 3.090432e-02 -4.964713e+01 -6.162888e-01 1.469582e-03 7.875188e-01 4.346570e+02 +7.872634e-01 -4.827511e-02 6.147242e-01 4.921531e+02 3.933582e-02 9.988319e-01 2.806310e-02 -4.963800e+01 -6.153609e-01 2.087623e-03 7.882427e-01 4.351618e+02 +7.879996e-01 -4.098379e-02 6.143102e-01 4.925217e+02 3.217697e-02 9.991598e-01 2.538445e-02 -4.963171e+01 -6.148343e-01 -2.362979e-04 7.886562e-01 4.356613e+02 +7.884235e-01 -3.108563e-02 6.143470e-01 4.928767e+02 2.374591e-02 9.995159e-01 2.010060e-02 -4.962904e+01 -6.146744e-01 -1.259560e-03 7.887799e-01 4.361475e+02 +7.896402e-01 -2.598998e-02 6.130196e-01 4.932305e+02 2.000657e-02 9.996618e-01 1.661154e-02 -4.962455e+01 -6.132439e-01 -8.527282e-04 7.898931e-01 4.366241e+02 +7.916779e-01 -2.778157e-02 6.103068e-01 4.935853e+02 2.324542e-02 9.996119e-01 1.534949e-02 -4.961814e+01 -6.104964e-01 2.034983e-03 7.920164e-01 4.370885e+02 +7.953617e-01 -3.060081e-02 6.053623e-01 4.939369e+02 2.672908e-02 9.995240e-01 1.540724e-02 -4.961294e+01 -6.055455e-01 3.926448e-03 7.958009e-01 4.375551e+02 +8.016963e-01 -3.378001e-02 5.967763e-01 4.942749e+02 2.905967e-02 9.994239e-01 1.753340e-02 -4.961151e+01 -5.970248e-01 3.285656e-03 8.022160e-01 4.380220e+02 +8.112000e-01 -3.509003e-02 5.837151e-01 4.946019e+02 2.903941e-02 9.993837e-01 1.972133e-02 -4.961280e+01 -5.840473e-01 9.528009e-04 8.117190e-01 4.384988e+02 +8.227213e-01 -3.688361e-02 5.672471e-01 4.949213e+02 3.208636e-02 9.993150e-01 1.844032e-02 -4.960976e+01 -5.675386e-01 3.029646e-03 8.233411e-01 4.389800e+02 +8.362579e-01 -3.801383e-02 5.470171e-01 4.952077e+02 3.501450e-02 9.992601e-01 1.591276e-02 -4.960753e+01 -5.472172e-01 5.846361e-03 8.369701e-01 4.394486e+02 +8.520630e-01 -3.990973e-02 5.219156e-01 4.954939e+02 3.800791e-02 9.991743e-01 1.435413e-02 -4.960276e+01 -5.220575e-01 7.606299e-03 8.528763e-01 4.399426e+02 +8.696793e-01 -4.259735e-02 4.917759e-01 4.957650e+02 4.149088e-02 9.990522e-01 1.316296e-02 -4.960024e+01 -4.918704e-01 8.956652e-03 8.706223e-01 4.404491e+02 +8.880524e-01 -4.624646e-02 4.574104e-01 4.959754e+02 4.487854e-02 9.988962e-01 1.386268e-02 -4.960064e+01 -4.575466e-01 8.217122e-03 8.891476e-01 4.409277e+02 +9.069168e-01 -4.810094e-02 4.185550e-01 4.961984e+02 4.549692e-02 9.988330e-01 1.620550e-02 -4.960097e+01 -4.188460e-01 4.345917e-03 9.080468e-01 4.414559e+02 +9.249621e-01 -4.676493e-02 3.771713e-01 4.963933e+02 4.327749e-02 9.989059e-01 1.772067e-02 -4.960346e+01 -3.775873e-01 -6.792008e-05 9.259739e-01 4.419933e+02 +9.414191e-01 -4.250018e-02 3.345502e-01 4.965069e+02 3.847109e-02 9.990854e-01 1.866353e-02 -4.959760e+01 -3.350374e-01 -4.699693e-03 9.421931e-01 4.424905e+02 +9.562745e-01 -3.744623e-02 2.900638e-01 4.966430e+02 3.334269e-02 9.992619e-01 1.907798e-02 -4.959751e+01 -2.905641e-01 -8.572278e-03 9.568171e-01 4.430389e+02 +9.692704e-01 -3.507490e-02 2.434844e-01 4.967626e+02 3.148698e-02 9.993308e-01 1.861323e-02 -4.959292e+01 -2.439743e-01 -1.037466e-02 9.697261e-01 4.435984e+02 +9.798407e-01 -3.552281e-02 1.965968e-01 4.968086e+02 3.243434e-02 9.992950e-01 1.890815e-02 -4.958843e+01 -1.971299e-01 -1.215048e-02 9.803020e-01 4.441158e+02 +9.880371e-01 -3.902360e-02 1.491979e-01 4.968949e+02 3.633094e-02 9.991247e-01 2.073179e-02 -4.960387e+01 -1.498764e-01 -1.506327e-02 9.885899e-01 4.446883e+02 +9.942234e-01 -3.808998e-02 1.003450e-01 4.968881e+02 3.584239e-02 9.990666e-01 2.410781e-02 -4.961772e+01 -1.011696e-01 -2.037194e-02 9.946605e-01 4.452211e+02 +9.981237e-01 -3.248846e-02 5.189994e-02 4.968701e+02 3.096877e-02 9.990753e-01 2.982204e-02 -4.968336e+01 -5.282082e-02 -2.815880e-02 9.982069e-01 4.458226e+02 +9.996030e-01 -2.808486e-02 2.265006e-03 4.968383e+02 2.798998e-02 9.990114e-01 3.453608e-02 -4.971952e+01 -3.232707e-03 -3.445896e-02 9.994008e-01 4.464343e+02 +9.984792e-01 -2.808010e-02 -4.744335e-02 4.967435e+02 2.985557e-02 9.988640e-01 3.713808e-02 -4.974811e+01 4.634661e-02 -3.849804e-02 9.981832e-01 4.469962e+02 +9.949190e-01 -3.305226e-02 -9.509850e-02 4.966830e+02 3.652141e-02 9.987207e-01 3.497280e-02 -4.975934e+01 9.382091e-02 -3.826823e-02 9.948533e-01 4.476148e+02 +9.893235e-01 -3.468806e-02 -1.415483e-01 4.965870e+02 3.969575e-02 9.986763e-01 3.270816e-02 -4.978044e+01 1.402264e-01 -3.797781e-02 9.893908e-01 4.482364e+02 +9.819861e-01 -3.246436e-02 -1.861434e-01 4.964079e+02 3.887311e-02 9.987668e-01 3.088222e-02 -4.980203e+01 1.849113e-01 -3.756188e-02 9.820371e-01 4.488134e+02 +9.732152e-01 -2.847095e-02 -2.281264e-01 4.962462e+02 3.655852e-02 9.988411e-01 3.130433e-02 -4.981681e+01 2.269707e-01 -3.880581e-02 9.731281e-01 4.494436e+02 +9.630903e-01 -2.578451e-02 -2.679409e-01 4.960205e+02 3.537419e-02 9.988925e-01 3.102394e-02 -4.984163e+01 2.668442e-01 -3.935704e-02 9.629357e-01 4.500358e+02 +9.514425e-01 -2.825912e-02 -3.065266e-01 4.958181e+02 3.895372e-02 9.988251e-01 2.882719e-02 -4.985596e+01 3.053518e-01 -3.936776e-02 9.514254e-01 4.506625e+02 +9.387507e-01 -3.279391e-02 -3.430331e-01 4.955938e+02 4.367656e-02 9.987563e-01 2.404511e-02 -4.987043e+01 3.418179e-01 -3.755486e-02 9.390155e-01 4.512852e+02 +9.256364e-01 -3.618192e-02 -3.766806e-01 4.953168e+02 4.666846e-02 9.987345e-01 1.874770e-02 -4.988507e+01 3.755255e-01 -3.493265e-02 9.261534e-01 4.518808e+02 +9.134186e-01 -3.271784e-02 -4.057045e-01 4.950279e+02 4.319555e-02 9.989271e-01 1.669411e-02 -4.992439e+01 4.047230e-01 -3.277333e-02 9.138518e-01 4.524962e+02 +9.030659e-01 -2.548822e-02 -4.287452e-01 4.947138e+02 3.692730e-02 9.991489e-01 1.838215e-02 -4.995152e+01 4.279117e-01 -3.243268e-02 9.032384e-01 4.531093e+02 +8.944352e-01 -1.909352e-02 -4.467899e-01 4.943826e+02 3.210889e-02 9.992514e-01 2.157634e-02 -4.997661e+01 4.460434e-01 -3.364456e-02 8.943787e-01 4.537147e+02 +8.875474e-01 -1.547471e-02 -4.604566e-01 4.940514e+02 3.117321e-02 9.991624e-01 2.650836e-02 -4.999201e+01 4.596607e-01 -3.788133e-02 8.872863e-01 4.543364e+02 +8.826765e-01 -1.455402e-02 -4.697558e-01 4.937108e+02 3.289848e-02 9.989819e-01 3.086607e-02 -5.001552e+01 4.688283e-01 -4.269899e-02 8.822566e-01 4.549611e+02 +8.793840e-01 -1.386564e-02 -4.759114e-01 4.933575e+02 3.267203e-02 9.989769e-01 3.126591e-02 -5.003302e+01 4.749910e-01 -4.304372e-02 8.789373e-01 4.555918e+02 +8.770838e-01 -1.314318e-02 -4.801575e-01 4.929929e+02 3.159292e-02 9.990395e-01 3.036311e-02 -5.003842e+01 4.792973e-01 -4.180056e-02 8.766566e-01 4.562268e+02 +8.755725e-01 -1.413794e-02 -4.828799e-01 4.926245e+02 3.194505e-02 9.990783e-01 2.867234e-02 -5.004331e+01 4.820294e-01 -4.053033e-02 8.752170e-01 4.568692e+02 +8.743712e-01 -1.580870e-02 -4.850002e-01 4.922596e+02 3.424796e-02 9.989872e-01 2.918089e-02 -5.003757e+01 4.840477e-01 -4.212519e-02 8.740270e-01 4.575252e+02 +8.737246e-01 -1.594819e-02 -4.861594e-01 4.918927e+02 3.597281e-02 9.988440e-01 3.188372e-02 -5.003104e+01 4.850889e-01 -4.534610e-02 8.732883e-01 4.581880e+02 +8.733320e-01 -1.457480e-02 -4.869075e-01 4.915187e+02 3.600934e-02 9.987491e-01 3.469147e-02 -5.002252e+01 4.857928e-01 -4.783038e-02 8.727643e-01 4.588573e+02 +8.727714e-01 -1.414250e-02 -4.879243e-01 4.911389e+02 3.593823e-02 9.987291e-01 3.533609e-02 -5.001834e+01 4.868044e-01 -4.837545e-02 8.721704e-01 4.595317e+02 +8.725840e-01 -1.486072e-02 -4.882381e-01 4.907531e+02 3.681106e-02 9.986953e-01 3.539136e-02 -5.001905e+01 4.870751e-01 -4.885449e-02 8.719925e-01 4.602104e+02 +8.724931e-01 -1.523591e-02 -4.883889e-01 4.903637e+02 3.716895e-02 9.986872e-01 3.524596e-02 -5.001317e+01 4.872107e-01 -4.890474e-02 8.719139e-01 4.608898e+02 +8.726971e-01 -1.508365e-02 -4.880291e-01 4.899688e+02 3.638853e-02 9.987523e-01 3.420151e-02 -5.001313e+01 4.869042e-01 -4.760620e-02 8.721570e-01 4.615830e+02 +8.729258e-01 -1.502778e-02 -4.876216e-01 4.895812e+02 3.594422e-02 9.987899e-01 3.356504e-02 -5.000961e+01 4.865271e-01 -4.682696e-02 8.724096e-01 4.622835e+02 +8.728796e-01 -1.597167e-02 -4.876743e-01 4.891860e+02 3.660854e-02 9.987908e-01 3.281387e-02 -5.000050e+01 4.865605e-01 -4.649559e-02 8.724087e-01 4.629979e+02 +8.730235e-01 -1.735431e-02 -4.873693e-01 4.887786e+02 3.782153e-02 9.987660e-01 3.218542e-02 -4.998303e+01 4.862093e-01 -4.653167e-02 8.726026e-01 4.637221e+02 +8.732026e-01 -1.649828e-02 -4.870782e-01 4.883646e+02 3.731606e-02 9.987562e-01 3.306803e-02 -4.995480e+01 4.859267e-01 -4.705091e-02 8.727321e-01 4.644658e+02 +8.732662e-01 -1.586891e-02 -4.869850e-01 4.879493e+02 3.744310e-02 9.986996e-01 3.459967e-02 -4.992563e+01 4.858026e-01 -4.844894e-02 8.727247e-01 4.652212e+02 +8.732663e-01 -1.364364e-02 -4.870523e-01 4.875277e+02 3.701760e-02 9.985766e-01 3.839834e-02 -4.989427e+01 4.858351e-01 -5.156147e-02 8.725282e-01 4.659874e+02 +8.732063e-01 -1.353551e-02 -4.871629e-01 4.871015e+02 3.883552e-02 9.983680e-01 4.187100e-02 -4.986543e+01 4.858011e-01 -5.548122e-02 8.723067e-01 4.667622e+02 +8.731273e-01 -1.397945e-02 -4.872918e-01 4.866711e+02 3.993382e-02 9.982803e-01 4.291451e-02 -4.983563e+01 4.858539e-01 -5.692924e-02 8.721840e-01 4.675456e+02 +8.730538e-01 -1.542375e-02 -4.873800e-01 4.862419e+02 4.038709e-02 9.983527e-01 4.075210e-02 -4.981952e+01 4.859486e-01 -5.526263e-02 8.722384e-01 4.683329e+02 +8.730035e-01 -1.728471e-02 -4.874077e-01 4.858094e+02 4.153059e-02 9.983765e-01 3.898112e-02 -4.980258e+01 4.859426e-01 -5.427297e-02 8.723039e-01 4.691342e+02 +8.728282e-01 -1.676914e-02 -4.877395e-01 4.853664e+02 4.134423e-02 9.983574e-01 3.966217e-02 -4.978304e+01 4.862733e-01 -5.478346e-02 8.720877e-01 4.699399e+02 +8.730520e-01 -1.666357e-02 -4.873423e-01 4.849292e+02 4.290922e-02 9.981643e-01 4.273997e-02 -4.977354e+01 4.857355e-01 -5.822568e-02 8.721644e-01 4.707503e+02 +8.731843e-01 -1.667762e-02 -4.871049e-01 4.844859e+02 4.362485e-02 9.980773e-01 4.402948e-02 -4.976059e+01 4.854340e-01 -5.969571e-02 8.722329e-01 4.715628e+02 +8.735009e-01 -1.539479e-02 -4.865791e-01 4.840420e+02 4.225590e-02 9.981252e-01 4.427778e-02 -4.975100e+01 4.849851e-01 -5.923751e-02 8.725137e-01 4.723748e+02 +8.736719e-01 -1.285208e-02 -4.863458e-01 4.835951e+02 4.062769e-02 9.980867e-01 4.660836e-02 -4.974409e+01 4.848163e-01 -6.047951e-02 8.725224e-01 4.731968e+02 +8.737858e-01 -1.097541e-02 -4.861873e-01 4.831471e+02 4.039648e-02 9.979282e-01 5.007370e-02 -4.972956e+01 4.846304e-01 -6.339393e-02 8.724188e-01 4.740231e+02 +8.740632e-01 -9.692505e-03 -4.857155e-01 4.826969e+02 3.911503e-02 9.979591e-01 5.047458e-02 -4.971656e+01 4.842350e-01 -6.311674e-02 8.726584e-01 4.748513e+02 +8.744121e-01 -1.157138e-02 -4.850460e-01 4.822409e+02 3.848325e-02 9.982200e-01 4.556153e-02 -4.969543e+01 4.836553e-01 -5.850568e-02 8.733009e-01 4.756804e+02 +8.745686e-01 -1.248322e-02 -4.847412e-01 4.817903e+02 3.733003e-02 9.984351e-01 4.163869e-02 -4.967114e+01 4.834628e-01 -5.451127e-02 8.736659e-01 4.765029e+02 +8.746601e-01 -1.363529e-02 -4.845449e-01 4.813353e+02 3.825821e-02 9.984279e-01 4.096435e-02 -4.965020e+01 4.832246e-01 -5.436769e-02 8.738066e-01 4.773394e+02 +8.746424e-01 -1.348247e-02 -4.845812e-01 4.808812e+02 3.909938e-02 9.983184e-01 4.279607e-02 -4.963150e+01 4.831893e-01 -5.637806e-02 8.736987e-01 4.781797e+02 +8.748254e-01 -1.276131e-02 -4.842703e-01 4.804207e+02 4.017984e-02 9.981200e-01 4.628204e-02 -4.961009e+01 4.827692e-01 -5.994659e-02 8.736934e-01 4.790245e+02 +8.749027e-01 -1.135022e-02 -4.841658e-01 4.799609e+02 4.036980e-02 9.979552e-01 4.955458e-02 -4.959677e+01 4.826133e-01 -6.290110e-02 8.735719e-01 4.798670e+02 +8.749695e-01 -1.163573e-02 -4.840382e-01 4.795067e+02 4.252252e-02 9.976950e-01 5.288219e-02 -4.957957e+01 4.823071e-01 -6.685281e-02 8.734474e-01 4.807152e+02 +8.749351e-01 -1.085554e-02 -4.841186e-01 4.790561e+02 4.395829e-02 9.974014e-01 5.707966e-02 -4.955748e+01 4.822409e-01 -7.122201e-02 8.731386e-01 4.815653e+02 +8.748591e-01 -9.869745e-03 -4.842769e-01 4.785979e+02 4.347569e-02 9.973570e-01 5.821347e-02 -4.953270e+01 4.824224e-01 -7.198285e-02 8.729759e-01 4.824145e+02 +8.746971e-01 -9.895429e-03 -4.845690e-01 4.781397e+02 3.860003e-02 9.980380e-01 4.929601e-02 -4.951240e+01 4.831305e-01 -6.182345e-02 8.733629e-01 4.832496e+02 +8.748028e-01 -1.524546e-02 -4.842392e-01 4.776797e+02 3.575624e-02 9.988106e-01 3.314959e-02 -4.949532e+01 4.831579e-01 -4.631392e-02 8.743074e-01 4.840849e+02 +8.749099e-01 -1.669282e-02 -4.839980e-01 4.772159e+02 3.199198e-02 9.992149e-01 2.336865e-02 -4.948050e+01 4.832279e-01 -3.592951e-02 8.747570e-01 4.849232e+02 +8.753152e-01 -1.047603e-02 -4.834393e-01 4.767418e+02 2.743100e-02 9.992311e-01 2.801344e-02 -4.947388e+01 4.827741e-01 -3.778180e-02 8.749295e-01 4.857766e+02 +8.751502e-01 -3.155341e-03 -4.838411e-01 4.762654e+02 2.579174e-02 9.988612e-01 4.013694e-02 -4.946616e+01 4.831635e-01 -4.760495e-02 8.742349e-01 4.866412e+02 +8.748089e-01 -5.062578e-04 -4.844680e-01 4.757958e+02 2.665420e-02 9.985351e-01 4.708633e-02 -4.945067e+01 4.837344e-01 -5.410463e-02 8.735408e-01 4.875018e+02 +8.743291e-01 -1.575064e-03 -4.853310e-01 4.753270e+02 2.842825e-02 9.984440e-01 4.797351e-02 -4.942845e+01 4.845003e-01 -5.574173e-02 8.730133e-01 4.883582e+02 +8.740073e-01 -3.598289e-03 -4.858996e-01 4.748583e+02 2.944223e-02 9.985274e-01 4.556441e-02 -4.940480e+01 4.850201e-01 -5.412958e-02 8.728261e-01 4.892141e+02 +8.737279e-01 -2.316597e-03 -4.864096e-01 4.743817e+02 2.673720e-02 9.987055e-01 4.327102e-02 -4.938263e+01 4.856796e-01 -5.081231e-02 8.726587e-01 4.900686e+02 +8.735391e-01 -1.688818e-03 -4.867511e-01 4.739057e+02 2.529724e-02 9.988001e-01 4.193383e-02 -4.936188e+01 4.860962e-01 -4.894429e-02 8.725336e-01 4.909230e+02 +8.731517e-01 2.418202e-04 -4.874485e-01 4.734256e+02 2.307781e-02 9.988580e-01 4.183410e-02 -4.934204e+01 4.869020e-01 -4.777675e-02 8.721489e-01 4.917812e+02 +8.728007e-01 1.612134e-03 -4.880741e-01 4.729456e+02 2.156930e-02 9.988902e-01 4.187078e-02 -4.932265e+01 4.875999e-01 -4.707225e-02 8.717972e-01 4.926383e+02 +8.724278e-01 3.228394e-03 -4.887325e-01 4.724636e+02 2.042011e-02 9.988642e-01 4.304972e-02 -4.930163e+01 4.883163e-01 -4.753773e-02 8.713709e-01 4.934991e+02 +8.721062e-01 4.471364e-03 -4.892963e-01 4.719820e+02 1.979943e-02 9.988168e-01 4.441743e-02 -4.928018e+01 4.889159e-01 -4.842449e-02 8.709857e-01 4.943582e+02 +8.718392e-01 6.876222e-03 -4.897441e-01 4.715030e+02 1.865829e-02 9.987094e-01 4.723769e-02 -4.925788e+01 4.894368e-01 -5.032144e-02 8.705856e-01 4.952100e+02 +8.714692e-01 8.730287e-03 -4.903726e-01 4.710309e+02 1.814255e-02 9.985834e-01 5.002031e-02 -4.923418e+01 4.901146e-01 -5.248775e-02 8.700762e-01 4.960487e+02 +8.711723e-01 1.068941e-02 -4.908611e-01 4.705649e+02 1.714449e-02 9.984909e-01 5.217175e-02 -4.921091e+01 4.906780e-01 -5.386613e-02 8.696743e-01 4.968752e+02 +8.710394e-01 1.086281e-02 -4.910930e-01 4.701065e+02 1.697746e-02 9.984924e-01 5.219880e-02 -4.918831e+01 4.909197e-01 -5.380471e-02 8.695417e-01 4.976889e+02 +8.709218e-01 9.403042e-03 -4.913318e-01 4.696544e+02 1.742557e-02 9.985972e-01 4.999913e-02 -4.916451e+01 4.911127e-01 -5.210706e-02 8.695361e-01 4.984939e+02 +8.708542e-01 7.520498e-03 -4.914840e-01 4.692034e+02 1.803479e-02 9.987208e-01 4.723765e-02 -4.914126e+01 4.912106e-01 -5.000091e-02 8.696045e-01 4.992966e+02 +8.706110e-01 7.237264e-03 -4.919188e-01 4.687553e+02 1.785441e-02 9.987683e-01 4.629341e-02 -4.911965e+01 4.916479e-01 -4.908646e-02 8.694094e-01 5.000919e+02 +8.704904e-01 5.342292e-03 -4.921565e-01 4.683110e+02 1.934563e-02 9.987970e-01 4.505894e-02 -4.909873e+01 4.918051e-01 -4.874444e-02 8.693397e-01 5.008837e+02 +8.703323e-01 5.664832e-03 -4.924324e-01 4.678675e+02 1.904120e-02 9.987990e-01 4.514366e-02 -4.907823e+01 4.920967e-01 -4.866648e-02 8.691791e-01 5.016703e+02 +8.703668e-01 5.775696e-03 -4.923701e-01 4.674324e+02 1.967554e-02 9.987247e-01 4.649607e-02 -4.905836e+01 4.920106e-01 -5.015627e-02 8.691431e-01 5.024423e+02 +8.702800e-01 6.839310e-03 -4.925100e-01 4.670033e+02 1.896429e-02 9.986969e-01 4.737902e-02 -4.904113e+01 4.921922e-01 -5.057310e-02 8.690162e-01 5.032010e+02 +8.702422e-01 8.181072e-03 -4.925562e-01 4.665823e+02 1.811151e-02 9.986547e-01 4.858626e-02 -4.902383e+01 4.922911e-01 -5.120273e-02 8.689233e-01 5.039443e+02 +8.702785e-01 8.642701e-03 -4.924843e-01 4.661711e+02 1.832996e-02 9.985852e-01 4.991558e-02 -4.900468e+01 4.922189e-01 -5.246766e-02 8.688887e-01 5.046729e+02 +8.703391e-01 1.015421e-02 -4.923483e-01 4.657676e+02 1.722397e-02 9.985480e-01 5.104144e-02 -4.898695e+01 4.921516e-01 -5.290354e-02 8.689004e-01 5.053857e+02 +8.704708e-01 1.088357e-02 -4.920997e-01 4.653733e+02 1.621860e-02 9.985784e-01 5.077409e-02 -4.897104e+01 4.919528e-01 -5.217851e-02 8.690568e-01 5.060805e+02 +8.704757e-01 1.037362e-02 -4.921021e-01 4.649905e+02 1.598848e-02 9.986543e-01 4.933375e-02 -4.895439e+01 4.919517e-01 -5.081178e-02 8.691384e-01 5.067590e+02 +8.706630e-01 9.892745e-03 -4.917807e-01 4.646180e+02 1.626250e-02 9.986722e-01 4.888108e-02 -4.893591e+01 4.916112e-01 -5.055652e-02 8.693459e-01 5.074212e+02 +8.711132e-01 1.132788e-02 -4.909518e-01 4.642539e+02 1.507246e-02 9.986462e-01 4.978568e-02 -4.891905e+01 4.908510e-01 -5.076880e-02 8.697630e-01 5.080661e+02 +8.714809e-01 1.238651e-02 -4.902730e-01 4.639022e+02 1.439751e-02 9.986039e-01 5.082144e-02 -4.890487e+01 4.902181e-01 -5.134861e-02 8.700859e-01 5.086921e+02 +8.719692e-01 1.156847e-02 -4.894242e-01 4.635632e+02 1.597256e-02 9.985163e-01 5.205891e-02 -4.889109e+01 4.893002e-01 -5.321111e-02 8.704905e-01 5.093035e+02 +8.723292e-01 1.101400e-02 -4.887951e-01 4.632322e+02 1.610535e-02 9.985563e-01 5.124287e-02 -4.887635e+01 4.886538e-01 -5.257285e-02 8.708923e-01 5.098989e+02 +8.727659e-01 9.045176e-03 -4.880553e-01 4.629057e+02 1.683093e-02 9.986762e-01 4.860650e-02 -4.886080e+01 4.878488e-01 -5.063651e-02 8.714582e-01 5.104883e+02 +8.732169e-01 6.843692e-03 -4.872838e-01 4.625817e+02 1.799308e-02 9.987668e-01 4.627101e-02 -4.884575e+01 4.869995e-01 -4.917235e-02 8.720169e-01 5.110771e+02 +8.734313e-01 5.034130e-03 -4.869214e-01 4.622598e+02 1.990448e-02 9.987417e-01 4.603000e-02 -4.883016e+01 4.865404e-01 -4.989594e-02 8.722320e-01 5.116660e+02 +8.737778e-01 4.530284e-03 -4.863044e-01 4.619394e+02 2.062221e-02 9.987120e-01 4.635713e-02 -4.881555e+01 4.858880e-01 -5.053449e-02 8.725589e-01 5.122491e+02 +8.742365e-01 5.270072e-03 -4.854719e-01 4.616209e+02 2.044266e-02 9.986547e-01 4.765405e-02 -4.880074e+01 4.850699e-01 -5.158523e-02 8.729525e-01 5.128275e+02 +8.745561e-01 5.663504e-03 -4.848914e-01 4.613082e+02 2.079695e-02 9.985737e-01 4.917292e-02 -4.878464e+01 4.844783e-01 -5.308873e-02 8.731909e-01 5.133979e+02 +8.749325e-01 5.182391e-03 -4.842173e-01 4.609991e+02 2.163725e-02 9.985256e-01 4.978321e-02 -4.876927e+01 4.837613e-01 -5.403406e-02 8.735303e-01 5.139630e+02 +8.754482e-01 3.482487e-03 -4.832995e-01 4.606988e+02 2.328654e-02 9.985087e-01 4.937612e-02 -4.875694e+01 4.827507e-01 -5.448059e-02 8.740615e-01 5.145161e+02 +8.757981e-01 3.993136e-03 -4.826613e-01 4.604026e+02 2.276965e-02 9.985107e-01 4.957681e-02 -4.874353e+01 4.821404e-01 -5.440929e-02 8.744028e-01 5.150584e+02 +8.761963e-01 6.523383e-03 -4.819104e-01 4.601080e+02 2.077047e-02 9.984683e-01 5.128008e-02 -4.872770e+01 4.815067e-01 -5.494091e-02 8.747186e-01 5.155921e+02 +8.766791e-01 6.787432e-03 -4.810279e-01 4.598256e+02 2.093975e-02 9.984144e-01 5.225085e-02 -4.871115e+01 4.806198e-01 -5.587982e-02 8.751468e-01 5.161118e+02 +8.767813e-01 6.080551e-03 -4.808510e-01 4.595521e+02 2.121413e-02 9.984575e-01 5.130763e-02 -4.869910e+01 4.804213e-01 -5.518639e-02 8.752998e-01 5.166187e+02 +8.768808e-01 4.029163e-03 -4.806910e-01 4.592904e+02 2.326420e-02 9.984374e-01 5.080768e-02 -4.868992e+01 4.801446e-01 -5.573516e-02 8.754168e-01 5.171099e+02 +8.769682e-01 2.085749e-03 -4.805439e-01 4.590358e+02 2.372960e-02 9.985827e-01 4.763956e-02 -4.867811e+01 4.799622e-01 -5.318148e-02 8.756757e-01 5.175825e+02 +8.767985e-01 8.029463e-04 -4.808573e-01 4.587887e+02 2.384013e-02 9.986962e-01 4.513790e-02 -4.866401e+01 4.802666e-01 -5.104054e-02 8.756362e-01 5.180375e+02 +8.757327e-01 4.600369e-04 -4.827962e-01 4.585487e+02 2.409635e-02 9.987116e-01 4.465944e-02 -4.865001e+01 4.821947e-01 -5.074334e-02 8.745932e-01 5.184798e+02 +8.742726e-01 -1.942247e-04 -4.854353e-01 4.583129e+02 2.553678e-02 9.986336e-01 4.559237e-02 -4.864034e+01 4.847632e-01 -5.225660e-02 8.730829e-01 5.189123e+02 +8.715292e-01 -1.774466e-03 -4.903405e-01 4.580773e+02 2.826559e-02 9.985124e-01 4.662568e-02 -4.863395e+01 4.895283e-01 -5.449540e-02 8.702828e-01 5.193360e+02 +8.664846e-01 -5.066220e-03 -4.991781e-01 4.578351e+02 3.281676e-02 9.983636e-01 4.683156e-02 -4.862754e+01 4.981239e-01 -5.696022e-02 8.652329e-01 5.197572e+02 +8.593891e-01 -8.865610e-03 -5.112455e-01 4.575892e+02 3.786106e-02 9.982083e-01 4.633323e-02 -4.861930e+01 5.099187e-01 -5.917456e-02 8.581848e-01 5.201766e+02 +8.500608e-01 -1.169082e-02 -5.265549e-01 4.573244e+02 4.178242e-02 9.980996e-01 4.529250e-02 -4.861075e+01 5.250247e-01 -6.050210e-02 8.489337e-01 5.205823e+02 +8.376851e-01 -1.376484e-02 -5.459801e-01 4.570571e+02 4.451986e-02 9.980765e-01 4.314307e-02 -4.859967e+01 5.443360e-01 -6.044724e-02 8.366866e-01 5.209848e+02 +8.221203e-01 -1.591752e-02 -5.690914e-01 4.567566e+02 4.735422e-02 9.980570e-01 4.049310e-02 -4.859192e+01 5.673411e-01 -6.023907e-02 8.212766e-01 5.213590e+02 +8.030899e-01 -1.749310e-02 -5.956011e-01 4.564625e+02 5.025670e-02 9.979958e-01 3.845292e-02 -4.858286e+01 5.937347e-01 -6.081408e-02 8.023594e-01 5.217483e+02 +7.805596e-01 -1.816370e-02 -6.248174e-01 4.561585e+02 5.328353e-02 9.978729e-01 3.755641e-02 -4.857548e+01 6.228062e-01 -6.260748e-02 7.798671e-01 5.221284e+02 +7.542327e-01 -1.829841e-02 -6.563523e-01 4.557980e+02 5.638695e-02 9.977239e-01 3.698032e-02 -4.857135e+01 6.541816e-01 -6.490145e-02 7.535477e-01 5.224465e+02 +7.237298e-01 -1.716883e-02 -6.898699e-01 4.554634e+02 5.800759e-02 9.976659e-01 3.602573e-02 -4.856757e+01 6.876411e-01 -6.609057e-02 7.230364e-01 5.227949e+02 +6.893709e-01 -1.501146e-02 -7.242530e-01 4.551163e+02 5.854478e-02 9.976694e-01 3.504658e-02 -4.856388e+01 7.220389e-01 -6.656131e-02 6.886431e-01 5.231260e+02 +6.515108e-01 -1.300591e-02 -7.585279e-01 4.546952e+02 5.890103e-02 9.977021e-01 3.348411e-02 -4.856255e+01 7.563493e-01 -6.649332e-02 6.507797e-01 5.233546e+02 +6.096846e-01 -1.112538e-02 -7.925661e-01 4.543170e+02 5.859308e-02 9.977984e-01 3.106670e-02 -4.855382e+01 7.904755e-01 -6.537976e-02 6.089942e-01 5.235924e+02 +5.645808e-01 -8.814688e-03 -8.253308e-01 4.539294e+02 5.777259e-02 9.979124e-01 2.886238e-02 -4.854452e+01 8.233534e-01 -6.397662e-02 5.639114e-01 5.238317e+02 +5.159272e-01 -8.046251e-03 -8.565947e-01 4.534567e+02 5.771707e-02 9.980101e-01 2.538840e-02 -4.853250e+01 8.546858e-01 -6.253868e-02 5.153649e-01 5.239633e+02 +4.637351e-01 -7.354976e-03 -8.859434e-01 4.530266e+02 5.785867e-02 9.980823e-01 2.199941e-02 -4.850687e+01 8.840826e-01 -6.146139e-02 4.632714e-01 5.241754e+02 +4.087651e-01 -5.239993e-03 -9.126246e-01 4.525758e+02 5.870559e-02 9.980635e-01 2.056371e-02 -4.848953e+01 9.107495e-01 -6.198188e-02 4.082811e-01 5.243701e+02 +3.507859e-01 -1.030445e-03 -9.364551e-01 4.520100e+02 6.039955e-02 9.979421e-01 2.152691e-02 -4.847439e+01 9.345058e-01 -6.411279e-02 3.501263e-01 5.244480e+02 +2.900921e-01 3.412199e-03 -9.569927e-01 4.515050e+02 6.080221e-02 9.979076e-01 2.198899e-02 -4.846726e+01 9.550652e-01 -6.456608e-02 2.892776e-01 5.245919e+02 +2.277626e-01 7.017301e-03 -9.736914e-01 4.509845e+02 6.268066e-02 9.977943e-01 2.185306e-02 -4.845007e+01 9.716971e-01 -6.600891e-02 2.268204e-01 5.246955e+02 +1.637406e-01 9.574219e-03 -9.864570e-01 4.503703e+02 6.428795e-02 9.977238e-01 2.035464e-02 -4.842951e+01 9.844064e-01 -6.675017e-02 1.627524e-01 5.246649e+02 +9.935451e-02 1.090919e-02 -9.949923e-01 4.498347e+02 6.680494e-02 9.976106e-01 1.760868e-02 -4.840359e+01 9.928070e-01 -6.821988e-02 9.838832e-02 5.247184e+02 +3.570559e-02 1.273541e-02 -9.992812e-01 4.492005e+02 7.068642e-02 9.973822e-01 1.523693e-02 -4.839561e+01 9.968593e-01 -7.117963e-02 3.471189e-02 5.246413e+02 +-2.732490e-02 1.371066e-02 -9.995326e-01 4.486458e+02 7.156311e-02 9.973671e-01 1.172459e-02 -4.837309e+01 9.970617e-01 -7.120927e-02 -2.823414e-02 5.246293e+02 +-8.834834e-02 1.448273e-02 -9.959844e-01 4.480835e+02 7.159462e-02 9.974005e-01 8.152557e-03 -4.835428e+01 9.935133e-01 -7.058683e-02 -8.915556e-02 5.245634e+02 +-1.468748e-01 1.641568e-02 -9.890189e-01 4.474401e+02 7.171011e-02 9.974080e-01 5.905580e-03 -4.833694e+01 9.865523e-01 -7.005526e-02 -1.476713e-01 5.243765e+02 +-2.016786e-01 1.984642e-02 -9.792507e-01 4.468537e+02 7.324522e-02 9.973008e-01 5.127244e-03 -4.831754e+01 9.767092e-01 -7.069136e-02 -2.025879e-01 5.242422e+02 +-2.514436e-01 1.955247e-02 -9.676745e-01 4.462562e+02 7.272953e-02 9.973509e-01 1.253840e-03 -4.830216e+01 9.651355e-01 -7.006322e-02 -2.521995e-01 5.240672e+02 +-2.956030e-01 1.626433e-02 -9.551725e-01 4.456137e+02 6.856448e-02 9.976377e-01 -4.231641e-03 -4.829910e+01 9.528472e-01 -6.674177e-02 -2.960198e-01 5.238120e+02 +-3.343081e-01 1.267116e-02 -9.423787e-01 4.450013e+02 6.366434e-02 9.979292e-01 -9.166781e-03 -4.830396e+01 9.403110e-01 -6.306043e-02 -3.344225e-01 5.235789e+02 +-3.683333e-01 9.529106e-03 -9.296450e-01 4.443475e+02 6.148779e-02 9.980078e-01 -1.413214e-02 -4.832183e+01 9.276582e-01 -6.236713e-02 -3.681854e-01 5.232997e+02 +-3.981962e-01 1.088280e-02 -9.172357e-01 4.437059e+02 6.135708e-02 9.980062e-01 -1.479559e-02 -4.834997e+01 9.152459e-01 -6.217043e-02 -3.980700e-01 5.230228e+02 +-4.250794e-01 1.405202e-02 -9.050470e-01 4.430537e+02 5.899378e-02 9.981837e-01 -1.220990e-02 -4.838394e+01 9.032315e-01 -5.858231e-02 -4.251363e-01 5.227150e+02 +-4.492395e-01 1.586574e-02 -8.932705e-01 4.423920e+02 5.432014e-02 9.984776e-01 -9.584058e-03 -4.840083e+01 8.917585e-01 -5.282810e-02 -4.494173e-01 5.223605e+02 +-4.708509e-01 1.760538e-02 -8.820372e-01 4.417368e+02 5.241650e-02 9.985928e-01 -8.049258e-03 -4.841693e+01 8.806542e-01 -5.002329e-02 -4.711111e-01 5.220065e+02 +-4.901805e-01 1.960809e-02 -8.714004e-01 4.410702e+02 5.143010e-02 9.986557e-01 -6.458909e-03 -4.843656e+01 8.701023e-01 -4.798223e-02 -4.905299e-01 5.216216e+02 +-5.062551e-01 2.160421e-02 -8.621132e-01 4.404065e+02 5.068469e-02 9.987035e-01 -4.736237e-03 -4.846267e+01 8.608930e-01 -4.609367e-02 -5.066937e-01 5.212266e+02 +-5.190592e-01 2.062893e-02 -8.544893e-01 4.397391e+02 4.549730e-02 9.989582e-01 -3.520629e-03 -4.849354e+01 8.535265e-01 -4.070436e-02 -5.194570e-01 5.208111e+02 +-5.279110e-01 2.075424e-02 -8.490461e-01 4.390686e+02 4.239302e-02 9.990991e-01 -1.936513e-03 -4.851889e+01 8.482410e-01 -3.701592e-02 -5.283152e-01 5.203850e+02 +-5.347966e-01 2.156099e-02 -8.447057e-01 4.384006e+02 4.144560e-02 9.991405e-01 -7.369412e-04 -4.853440e+01 8.439638e-01 -3.540344e-02 -5.352305e-01 5.199553e+02 +-5.421190e-01 2.340971e-02 -8.399756e-01 4.377256e+02 4.237089e-02 9.991018e-01 4.983790e-04 -4.855858e+01 8.392328e-01 -3.532032e-02 -5.426239e-01 5.195166e+02 +-5.514895e-01 2.629645e-02 -8.337673e-01 4.370676e+02 4.384480e-02 9.990352e-01 2.508064e-03 -4.858366e+01 8.330287e-01 -3.517318e-02 -5.521104e-01 5.190799e+02 +-5.622563e-01 2.785269e-02 -8.264939e-01 4.364150e+02 4.421910e-02 9.990154e-01 3.584798e-03 -4.860742e+01 8.257800e-01 -3.453123e-02 -5.629343e-01 5.186342e+02 +-5.723709e-01 2.864617e-02 -8.194944e-01 4.357672e+02 4.424047e-02 9.990128e-01 4.021917e-03 -4.863609e+01 8.188006e-01 -3.395278e-02 -5.730731e-01 5.181777e+02 +-5.823455e-01 2.782980e-02 -8.124650e-01 4.351319e+02 4.240468e-02 9.990932e-01 3.828346e-03 -4.865866e+01 8.118347e-01 -3.222289e-02 -5.829974e-01 5.177111e+02 +-5.921714e-01 2.664018e-02 -8.053716e-01 4.345009e+02 4.062118e-02 9.991695e-01 3.182839e-03 -4.867750e+01 8.047875e-01 -3.083035e-02 -5.927617e-01 5.172336e+02 +-6.016135e-01 2.611462e-02 -7.983604e-01 4.338754e+02 3.962609e-02 9.992106e-01 2.823810e-03 -4.869720e+01 7.978038e-01 -2.993705e-02 -6.021733e-01 5.167576e+02 +-6.109430e-01 2.661556e-02 -7.912271e-01 4.332487e+02 3.905980e-02 9.992309e-01 3.452594e-03 -4.872719e+01 7.907104e-01 -2.879582e-02 -6.115127e-01 5.162764e+02 +-6.202541e-01 2.695449e-02 -7.839378e-01 4.326266e+02 3.850295e-02 9.992509e-01 3.894051e-03 -4.874923e+01 7.834554e-01 -2.776861e-02 -6.208272e-01 5.157825e+02 +-6.300798e-01 2.597987e-02 -7.760957e-01 4.320152e+02 3.642267e-02 9.993289e-01 3.882586e-03 -4.876761e+01 7.756757e-01 -2.582113e-02 -6.306032e-01 5.152794e+02 +-6.397185e-01 2.771595e-02 -7.681095e-01 4.314091e+02 3.855163e-02 9.992488e-01 3.948590e-03 -4.877413e+01 7.676419e-01 -2.708588e-02 -6.403064e-01 5.147726e+02 +-6.496485e-01 2.863125e-02 -7.596954e-01 4.308070e+02 3.986223e-02 9.991988e-01 3.569706e-03 -4.878504e+01 7.591889e-01 -2.796409e-02 -6.502692e-01 5.142564e+02 +-6.597087e-01 2.277727e-02 -7.511762e-01 4.302276e+02 3.424615e-02 9.994134e-01 2.282253e-04 -4.880639e+01 7.507407e-01 -2.557432e-02 -6.601017e-01 5.137288e+02 +-6.692959e-01 1.715908e-02 -7.427979e-01 4.296538e+02 2.866547e-02 9.995853e-01 -2.737908e-03 -4.883304e+01 7.424428e-01 -2.312512e-02 -6.695101e-01 5.131884e+02 +-6.794651e-01 1.538706e-02 -7.335465e-01 4.290872e+02 2.910217e-02 9.995585e-01 -5.989578e-03 -4.885879e+01 7.331304e-01 -2.541749e-02 -6.796129e-01 5.126536e+02 +-6.884269e-01 1.622808e-02 -7.251242e-01 4.285259e+02 2.843452e-02 9.995849e-01 -4.625051e-03 -4.888739e+01 7.247482e-01 -2.380256e-02 -6.886025e-01 5.121083e+02 +-6.971643e-01 1.549246e-02 -7.167440e-01 4.279790e+02 2.404634e-02 9.997092e-01 -1.780675e-03 -4.892137e+01 7.165080e-01 -1.847649e-02 -6.973341e-01 5.115525e+02 +-7.062836e-01 1.613451e-02 -7.077451e-01 4.274377e+02 2.215762e-02 9.997542e-01 6.796092e-04 -4.894297e+01 7.075821e-01 -1.520194e-02 -7.064675e-01 5.109964e+02 +-7.153066e-01 1.816036e-02 -6.985748e-01 4.269067e+02 2.240072e-02 9.997444e-01 3.052416e-03 -4.896388e+01 6.984516e-01 -1.346516e-02 -7.155305e-01 5.104394e+02 +-7.243525e-01 1.966492e-02 -6.891494e-01 4.263762e+02 2.290595e-02 9.997277e-01 4.451286e-03 -4.897792e+01 6.890492e-01 -1.256131e-02 -7.246056e-01 5.098728e+02 +-7.331298e-01 1.694407e-02 -6.798777e-01 4.258728e+02 2.053748e-02 9.997852e-01 2.770800e-03 -4.899284e+01 6.797786e-01 -1.193161e-02 -7.333203e-01 5.093076e+02 +-7.419303e-01 1.119694e-02 -6.703836e-01 4.253844e+02 1.607312e-02 9.998702e-01 -1.088386e-03 -4.901180e+01 6.702844e-01 -1.158266e-02 -7.420139e-01 5.087369e+02 +-7.507407e-01 1.012612e-02 -6.605194e-01 4.248962e+02 1.554758e-02 9.998764e-01 -2.342595e-03 -4.902935e+01 6.604140e-01 -1.202815e-02 -7.508053e-01 5.081596e+02 +-7.594631e-01 1.234234e-02 -6.504333e-01 4.244148e+02 1.504490e-02 9.998858e-01 1.406594e-03 -4.904032e+01 6.503764e-01 -8.717440e-03 -7.595620e-01 5.075784e+02 +-7.678660e-01 1.432657e-02 -6.404503e-01 4.239413e+02 1.097718e-02 9.998973e-01 9.206181e-03 -4.905237e+01 6.405164e-01 3.877846e-05 -7.679444e-01 5.069799e+02 +-7.760533e-01 1.836748e-02 -6.303999e-01 4.234773e+02 1.033387e-02 9.998119e-01 1.640927e-02 -4.906198e+01 6.305827e-01 6.220000e-03 -7.760971e-01 5.063869e+02 +-7.847576e-01 2.135451e-02 -6.194349e-01 4.230273e+02 1.217079e-02 9.997445e-01 1.904629e-02 -4.907494e+01 6.196833e-01 7.407712e-03 -7.848169e-01 5.057979e+02 +-7.928776e-01 2.249502e-02 -6.089657e-01 4.225848e+02 1.449175e-02 9.997318e-01 1.806147e-02 -4.908805e+01 6.092086e-01 5.495561e-03 -7.929909e-01 5.052028e+02 +-8.007129e-01 2.229897e-02 -5.986332e-01 4.221517e+02 1.534711e-02 9.997425e-01 1.671242e-02 -4.909732e+01 5.988517e-01 4.194560e-03 -8.008489e-01 5.046038e+02 +-8.086040e-01 2.177775e-02 -5.879502e-01 4.217233e+02 1.543803e-02 9.997560e-01 1.579929e-02 -4.910656e+01 5.881507e-01 3.698580e-03 -8.087428e-01 5.039943e+02 +-8.159253e-01 2.158762e-02 -5.777543e-01 4.212976e+02 1.532227e-02 9.997590e-01 1.571706e-02 -4.911312e+01 5.779543e-01 3.971441e-03 -8.160594e-01 5.033755e+02 +-8.226703e-01 2.142141e-02 -5.681150e-01 4.208953e+02 1.487277e-02 9.997588e-01 1.616022e-02 -4.912035e+01 5.683241e-01 4.845092e-03 -8.227904e-01 5.027571e+02 +-8.292039e-01 2.181880e-02 -5.585203e-01 4.204855e+02 1.504615e-02 9.997470e-01 1.671732e-02 -4.912493e+01 5.587438e-01 5.458488e-03 -8.293223e-01 5.021259e+02 +-8.355867e-01 2.116023e-02 -5.489511e-01 4.200929e+02 1.437665e-02 9.997579e-01 1.665390e-02 -4.913194e+01 5.491705e-01 6.023704e-03 -8.356885e-01 5.014907e+02 +-8.417947e-01 1.946295e-02 -5.394468e-01 4.196988e+02 1.303889e-02 9.997913e-01 1.572506e-02 -4.914078e+01 5.396403e-01 6.203487e-03 -8.418728e-01 5.008476e+02 +-8.477292e-01 1.880764e-02 -5.300957e-01 4.193123e+02 1.254824e-02 9.998026e-01 1.540557e-02 -4.915709e+01 5.302808e-01 6.407989e-03 -8.477978e-01 5.001982e+02 +-8.532263e-01 1.872351e-02 -5.212047e-01 4.189313e+02 1.228560e-02 9.997996e-01 1.580448e-02 -4.917210e+01 5.213962e-01 7.081490e-03 -8.532853e-01 4.995418e+02 +-8.583257e-01 1.807306e-02 -5.127869e-01 4.185531e+02 1.152336e-02 9.998064e-01 1.594966e-02 -4.918514e+01 5.129758e-01 7.780983e-03 -8.583677e-01 4.988791e+02 +-8.630205e-01 1.681251e-02 -5.048891e-01 4.181788e+02 1.045032e-02 9.998263e-01 1.543064e-02 -4.920061e+01 5.050608e-01 8.040707e-03 -8.630463e-01 4.982093e+02 +-8.676481e-01 1.489964e-02 -4.969556e-01 4.178051e+02 8.792588e-03 9.998543e-01 1.462627e-02 -4.921332e+01 4.971011e-01 8.320933e-03 -8.676527e-01 4.975333e+02 +-8.720359e-01 1.457497e-02 -4.892249e-01 4.174361e+02 8.473266e-03 9.998563e-01 1.468424e-02 -4.922803e+01 4.893686e-01 8.659854e-03 -8.720340e-01 4.968522e+02 +-8.762085e-01 1.393243e-02 -4.817309e-01 4.170696e+02 7.762063e-03 9.998603e-01 1.479936e-02 -4.924292e+01 4.818698e-01 9.228099e-03 -8.761942e-01 4.961653e+02 +-8.801950e-01 1.397935e-02 -4.744064e-01 4.167056e+02 7.561039e-03 9.998523e-01 1.543426e-02 -4.926480e+01 4.745521e-01 9.998151e-03 -8.801706e-01 4.954731e+02 +-8.839701e-01 1.326997e-02 -4.673552e-01 4.163411e+02 7.076310e-03 9.998623e-01 1.500551e-02 -4.927624e+01 4.674899e-01 9.957274e-03 -8.839423e-01 4.947698e+02 +-8.878476e-01 1.180208e-02 -4.599863e-01 4.159856e+02 5.540777e-03 9.998727e-01 1.495963e-02 -4.928845e+01 4.601043e-01 1.073319e-02 -8.877999e-01 4.940607e+02 +-8.913211e-01 1.095470e-02 -4.532403e-01 4.156415e+02 4.315112e-03 9.998677e-01 1.568067e-02 -4.929664e+01 4.533521e-01 1.202073e-02 -8.912504e-01 4.933408e+02 +-8.945423e-01 1.073466e-02 -4.468545e-01 4.152994e+02 3.617567e-03 9.998527e-01 1.677732e-02 -4.929750e+01 4.469687e-01 1.339150e-02 -8.944493e-01 4.926132e+02 +-8.974789e-01 1.136792e-02 -4.409110e-01 4.149575e+02 3.520763e-03 9.998206e-01 1.861164e-02 -4.929478e+01 4.410435e-01 1.515121e-02 -8.973578e-01 4.918793e+02 +-9.001558e-01 1.054971e-02 -4.354403e-01 4.146198e+02 1.885307e-03 9.997916e-01 2.032530e-02 -4.929309e+01 4.355640e-01 1.747500e-02 -8.999881e-01 4.911412e+02 +-9.027632e-01 1.106327e-02 -4.299957e-01 4.142831e+02 1.606567e-03 9.997489e-01 2.234940e-02 -4.929233e+01 4.301350e-01 1.948540e-02 -9.025542e-01 4.904004e+02 +-9.052610e-01 9.686819e-03 -4.247455e-01 4.139494e+02 1.082362e-04 9.997452e-01 2.256970e-02 -4.928077e+01 4.248559e-01 2.038550e-02 -9.050314e-01 4.896600e+02 +-9.073054e-01 6.361974e-03 -4.204242e-01 4.136210e+02 -2.702672e-03 9.997766e-01 2.096147e-02 -4.926773e+01 4.204637e-01 2.015472e-02 -9.070854e-01 4.889171e+02 +-9.089599e-01 5.427327e-03 -4.168482e-01 4.132911e+02 -2.510172e-03 9.998258e-01 1.849123e-02 -4.925401e+01 4.168760e-01 1.785415e-02 -9.087880e-01 4.881741e+02 +-9.103950e-01 7.412076e-03 -4.136739e-01 4.129606e+02 6.774620e-04 9.998649e-01 1.642435e-02 -4.924405e+01 4.137397e-01 1.467240e-02 -9.102769e-01 4.874295e+02 +-9.118333e-01 6.941001e-03 -4.105020e-01 4.126323e+02 6.616661e-04 9.998806e-01 1.543684e-02 -4.924208e+01 4.105601e-01 1.380421e-02 -9.117290e-01 4.866822e+02 +-9.131512e-01 8.261127e-03 -4.075373e-01 4.123074e+02 1.645284e-03 9.998611e-01 1.658154e-02 -4.923864e+01 4.076177e-01 1.447094e-02 -9.130380e-01 4.859285e+02 +-9.147648e-01 1.220321e-02 -4.038025e-01 4.119731e+02 4.250713e-03 9.997791e-01 2.058463e-02 -4.923951e+01 4.039645e-01 1.711364e-02 -9.146145e-01 4.851725e+02 +-9.163801e-01 1.591340e-02 -3.999930e-01 4.116397e+02 6.950713e-03 9.996914e-01 2.384792e-02 -4.924268e+01 4.002490e-01 1.907352e-02 -9.162078e-01 4.844163e+02 +-9.179525e-01 1.541569e-02 -3.963907e-01 4.113211e+02 7.145955e-03 9.997251e-01 2.233103e-02 -4.923493e+01 3.966259e-01 1.766623e-02 -9.178103e-01 4.836596e+02 +-9.198668e-01 1.429749e-02 -3.919702e-01 4.110088e+02 7.134202e-03 9.997800e-01 1.972556e-02 -4.921765e+01 3.921660e-01 1.534850e-02 -9.197664e-01 4.829009e+02 +-9.215617e-01 1.537426e-02 -3.879275e-01 4.106956e+02 8.158842e-03 9.997618e-01 2.024020e-02 -4.920713e+01 3.881463e-01 1.548755e-02 -9.214676e-01 4.821377e+02 +-9.233194e-01 1.637557e-02 -3.836837e-01 4.103858e+02 7.334049e-03 9.996601e-01 2.501628e-02 -4.919995e+01 3.839629e-01 2.028406e-02 -9.231256e-01 4.813695e+02 +-9.251736e-01 1.872808e-02 -3.790819e-01 4.100803e+02 9.166973e-03 9.995931e-01 2.701112e-02 -4.918809e+01 3.794335e-01 2.151494e-02 -9.249688e-01 4.806039e+02 +-9.271356e-01 1.962121e-02 -3.742120e-01 4.097802e+02 9.700565e-03 9.995502e-01 2.837604e-02 -4.917323e+01 3.746004e-01 2.267837e-02 -9.269089e-01 4.798370e+02 +-9.287905e-01 2.087755e-02 -3.700167e-01 4.094843e+02 9.701249e-03 9.994395e-01 3.204025e-02 -4.915877e+01 3.704782e-01 2.616906e-02 -9.284724e-01 4.790702e+02 +-9.304203e-01 2.184110e-02 -3.658430e-01 4.091867e+02 9.092893e-03 9.992910e-01 3.653321e-02 -4.914571e+01 3.663815e-01 3.066467e-02 -9.299592e-01 4.782990e+02 +-9.319534e-01 1.913198e-02 -3.620730e-01 4.088949e+02 6.236487e-03 9.993050e-01 3.675108e-02 -4.913075e+01 3.625245e-01 3.199223e-02 -9.314249e-01 4.775332e+02 +-9.332468e-01 1.678061e-02 -3.588439e-01 4.086059e+02 5.370923e-03 9.994485e-01 3.276904e-02 -4.911227e+01 3.591959e-01 2.865428e-02 -9.328221e-01 4.767712e+02 +-9.345604e-01 1.434161e-02 -3.555155e-01 4.083165e+02 3.820967e-03 9.995342e-01 3.027722e-02 -4.909387e+01 3.557841e-01 2.693748e-02 -9.341798e-01 4.760074e+02 +-9.357027e-01 1.301055e-02 -3.525496e-01 4.080316e+02 2.528342e-03 9.995414e-01 3.017680e-02 -4.908189e+01 3.527805e-01 2.734514e-02 -9.353064e-01 4.752447e+02 +-9.368500e-01 1.332829e-02 -3.494775e-01 4.077476e+02 2.463866e-03 9.995003e-01 3.151380e-02 -4.906988e+01 3.497229e-01 2.866263e-02 -9.364146e-01 4.744822e+02 +-9.380297e-01 1.445025e-02 -3.462536e-01 4.074656e+02 3.121601e-03 9.994421e-01 3.325322e-02 -4.905459e+01 3.465409e-01 3.011163e-02 -9.375514e-01 4.737199e+02 +-9.390846e-01 1.347969e-02 -3.434218e-01 4.071891e+02 1.948150e-03 9.994233e-01 3.390131e-02 -4.904204e+01 3.436807e-01 3.116715e-02 -9.385692e-01 4.729576e+02 +-9.400143e-01 1.217139e-02 -3.409179e-01 4.069162e+02 2.525654e-04 9.993878e-01 3.498361e-02 -4.903174e+01 3.411350e-01 3.279898e-02 -9.394419e-01 4.721945e+02 +-9.407351e-01 1.233981e-02 -3.389177e-01 4.066447e+02 2.543984e-04 9.993632e-01 3.568018e-02 -4.902338e+01 3.391421e-01 3.347938e-02 -9.401392e-01 4.714344e+02 +-9.412584e-01 1.300825e-02 -3.374365e-01 4.063732e+02 9.216349e-04 9.993530e-01 3.595445e-02 -4.901414e+01 3.376859e-01 3.353143e-02 -9.406613e-01 4.706765e+02 +-9.416599e-01 1.240557e-02 -3.363375e-01 4.061062e+02 2.647985e-04 9.993474e-01 3.611887e-02 -4.900202e+01 3.365661e-01 3.392263e-02 -9.410486e-01 4.699238e+02 +-9.420104e-01 1.174579e-02 -3.353781e-01 4.058424e+02 -8.192326e-04 9.993038e-01 3.729925e-02 -4.898803e+01 3.355827e-01 3.541103e-02 -9.413449e-01 4.691780e+02 +-9.424151e-01 1.244529e-02 -3.342139e-01 4.055828e+02 -9.295614e-04 9.992060e-01 3.982914e-02 -4.897265e+01 3.344443e-01 3.784625e-02 -9.416552e-01 4.684410e+02 +-9.426655e-01 1.350862e-02 -3.334658e-01 4.053218e+02 -5.123956e-04 9.991207e-01 4.192264e-02 -4.896128e+01 3.337388e-01 3.968989e-02 -9.418296e-01 4.677141e+02 +-9.428860e-01 1.368969e-02 -3.328342e-01 4.050676e+02 -7.270225e-04 9.990682e-01 4.315194e-02 -4.894605e+01 3.331148e-01 4.092933e-02 -9.419975e-01 4.670002e+02 +-9.430117e-01 1.176819e-02 -3.325516e-01 4.048208e+02 -2.994595e-03 9.990338e-01 4.384512e-02 -4.892956e+01 3.327462e-01 4.234232e-02 -9.420653e-01 4.663001e+02 +-9.429361e-01 9.929051e-03 -3.328258e-01 4.045812e+02 -5.266716e-03 9.989855e-01 4.472358e-02 -4.891475e+01 3.329322e-01 4.392437e-02 -9.419271e-01 4.656132e+02 +-9.426978e-01 1.025696e-02 -3.334902e-01 4.043446e+02 -5.528751e-03 9.989099e-01 4.635138e-02 -4.890097e+01 3.336020e-01 4.553913e-02 -9.416134e-01 4.649432e+02 +-9.422261e-01 1.104607e-02 -3.347954e-01 4.041086e+02 -5.386620e-03 9.988273e-01 4.811458e-02 -4.889060e+01 3.349343e-01 4.713823e-02 -9.410616e-01 4.642835e+02 +-9.416584e-01 1.109780e-02 -3.363873e-01 4.038810e+02 -5.813649e-03 9.987708e-01 4.922492e-02 -4.887914e+01 3.365201e-01 4.830869e-02 -9.404363e-01 4.636471e+02 +-9.410090e-01 1.160259e-02 -3.381827e-01 4.036578e+02 -5.496851e-03 9.987559e-01 4.956125e-02 -4.886823e+01 3.383370e-01 4.849651e-02 -9.397745e-01 4.630275e+02 +-9.403571e-01 1.109209e-02 -3.400083e-01 4.034213e+02 -6.086927e-03 9.987597e-01 4.941710e-02 -4.883321e+01 3.401347e-01 4.853932e-02 -9.391231e-01 4.624297e+02 +-9.396630e-01 1.124515e-02 -3.419168e-01 4.031961e+02 -5.695197e-03 9.988069e-01 4.850101e-02 -4.879452e+01 3.420542e-01 4.752188e-02 -9.384778e-01 4.618429e+02 +-9.390108e-01 1.075847e-02 -3.437194e-01 4.029885e+02 -5.888121e-03 9.988610e-01 4.735035e-02 -4.878309e+01 3.438373e-01 4.648635e-02 -9.378778e-01 4.612532e+02 +-9.383048e-01 1.249100e-02 -3.455839e-01 4.027787e+02 -4.362996e-03 9.988402e-01 4.794884e-02 -4.877267e+01 3.457820e-01 4.649840e-02 -9.371620e-01 4.606615e+02 +-9.377072e-01 1.473578e-02 -3.471141e-01 4.025637e+02 -2.382067e-03 9.988039e-01 4.883652e-02 -4.875930e+01 3.474186e-01 4.662120e-02 -9.365504e-01 4.600743e+02 +-9.371285e-01 1.300589e-02 -3.487422e-01 4.023535e+02 -3.920280e-03 9.988499e-01 4.778529e-02 -4.874830e+01 3.489626e-01 4.614811e-02 -9.359996e-01 4.594866e+02 +-9.365353e-01 6.924633e-03 -3.505049e-01 4.021513e+02 -9.730401e-03 9.989062e-01 4.573383e-02 -4.873467e+01 3.504382e-01 4.624189e-02 -9.354435e-01 4.588973e+02 +-9.360203e-01 4.020111e-03 -3.519233e-01 4.019469e+02 -1.203741e-02 9.989840e-01 4.342791e-02 -4.871696e+01 3.517403e-01 4.488564e-02 -9.350208e-01 4.583056e+02 +-9.357587e-01 5.391624e-03 -3.525998e-01 4.017305e+02 -9.301436e-03 9.991578e-01 3.996313e-02 -4.869777e+01 3.525183e-01 4.067552e-02 -9.349204e-01 4.577227e+02 +-9.352797e-01 9.338108e-03 -3.537864e-01 4.015099e+02 -5.262753e-03 9.991743e-01 4.028576e-02 -4.868026e+01 3.538705e-01 3.954033e-02 -9.344582e-01 4.571373e+02 +-9.348018e-01 7.647709e-03 -3.550877e-01 4.012966e+02 -7.548668e-03 9.991145e-01 4.139105e-02 -4.866739e+01 3.550898e-01 4.137286e-02 -9.339162e-01 4.565486e+02 +-9.344785e-01 5.597382e-03 -3.559757e-01 4.010870e+02 -1.059346e-02 9.989965e-01 4.351741e-02 -4.864992e+01 3.558620e-01 4.443709e-02 -9.334814e-01 4.559552e+02 +-9.343053e-01 7.320179e-03 -3.563989e-01 4.008747e+02 -1.040075e-02 9.988037e-01 4.778047e-02 -4.863100e+01 3.563222e-01 4.834835e-02 -9.331113e-01 4.553598e+02 +-9.341863e-01 1.137592e-02 -3.566042e-01 4.006513e+02 -7.407759e-03 9.986577e-01 5.126379e-02 -4.861122e+01 3.567087e-01 5.053157e-02 -9.328480e-01 4.547704e+02 +-9.341021e-01 1.613473e-02 -3.566414e-01 4.004275e+02 -3.128122e-03 9.985699e-01 5.336918e-02 -4.859021e+01 3.569924e-01 5.096787e-02 -9.327157e-01 4.541811e+02 +-9.338633e-01 1.508349e-02 -3.573120e-01 4.002062e+02 -4.216691e-03 9.985763e-01 5.317437e-02 -4.856973e+01 3.576053e-01 5.116426e-02 -9.324701e-01 4.535898e+02 +-9.337018e-01 9.477470e-03 -3.579263e-01 3.999967e+02 -8.957294e-03 9.987185e-01 4.981130e-02 -4.854439e+01 3.579397e-01 4.971494e-02 -9.324202e-01 4.529847e+02 +-9.335747e-01 3.965665e-03 -3.583610e-01 3.997798e+02 -1.363509e-02 9.988217e-01 4.657421e-02 -4.851804e+01 3.581235e-01 4.836678e-02 -9.324206e-01 4.523757e+02 +-9.332748e-01 -3.176482e-04 -3.591630e-01 3.995571e+02 -1.784059e-02 9.988061e-01 4.547493e-02 -4.849123e+01 3.587197e-01 4.884827e-02 -9.321662e-01 4.517564e+02 +-9.329508e-01 -4.775546e-03 -3.599722e-01 3.993296e+02 -2.402764e-02 9.985084e-01 4.902655e-02 -4.846577e+01 3.592011e-01 5.438863e-02 -9.316739e-01 4.511259e+02 +-9.323282e-01 -5.090224e-03 -3.615774e-01 3.990948e+02 -2.590454e-02 9.982721e-01 5.274145e-02 -4.844147e+01 3.606842e-01 5.853883e-02 -9.308491e-01 4.504917e+02 +-9.317232e-01 -5.583424e-03 -3.631264e-01 3.988580e+02 -2.499871e-02 9.984962e-01 4.878979e-02 -4.841993e+01 3.623079e-01 5.453627e-02 -9.304615e-01 4.498538e+02 +-9.310099e-01 -9.105165e-03 -3.648805e-01 3.986184e+02 -2.610123e-02 9.987902e-01 4.167490e-02 -4.839987e+01 3.640596e-01 4.832357e-02 -9.301211e-01 4.492180e+02 +-9.297895e-01 -1.481947e-02 -3.677934e-01 3.983693e+02 -2.919685e-02 9.990102e-01 3.355726e-02 -4.838956e+01 3.669320e-01 4.193959e-02 -9.293018e-01 4.485693e+02 +-9.289422e-01 -1.269773e-02 -3.700070e-01 3.981029e+02 -2.615324e-02 9.991655e-01 3.137160e-02 -4.837883e+01 3.692999e-01 3.881928e-02 -9.284991e-01 4.479175e+02 +-9.283695e-01 -2.684247e-03 -3.716490e-01 3.978220e+02 -1.909478e-02 9.989977e-01 4.048299e-02 -4.837275e+01 3.711678e-01 4.467972e-02 -9.274902e-01 4.472497e+02 +-9.271100e-01 8.439925e-03 -3.746943e-01 3.975356e+02 -1.149251e-02 9.986361e-01 5.093017e-02 -4.836037e+01 3.746131e-01 5.152404e-02 -9.257484e-01 4.465725e+02 +-9.259732e-01 1.306468e-02 -3.773632e-01 3.972544e+02 -9.667193e-03 9.982533e-01 5.828185e-02 -4.834714e+01 3.774655e-01 5.761547e-02 -9.242295e-01 4.458892e+02 +-9.247740e-01 1.544356e-02 -3.802035e-01 3.969698e+02 -7.169567e-03 9.982915e-01 5.798847e-02 -4.832574e+01 3.804494e-01 5.635211e-02 -9.230832e-01 4.452080e+02 +-9.237657e-01 1.348398e-02 -3.827207e-01 3.966926e+02 -8.025116e-03 9.984789e-01 5.454840e-02 -4.830979e+01 3.828741e-01 5.346131e-02 -9.222523e-01 4.445162e+02 +-9.226640e-01 1.297096e-02 -3.853867e-01 3.964090e+02 -6.956619e-03 9.987115e-01 5.026868e-02 -4.828800e+01 3.855421e-01 4.906208e-02 -9.213849e-01 4.438205e+02 +-9.215429e-01 1.535433e-02 -3.879728e-01 3.961161e+02 -3.475999e-03 9.988515e-01 4.778683e-02 -4.826653e+01 3.882610e-01 4.538620e-02 -9.204311e-01 4.431166e+02 +-9.206017e-01 1.739648e-02 -3.901152e-01 3.958187e+02 -1.038869e-03 9.988945e-01 4.699546e-02 -4.824792e+01 3.905015e-01 4.366937e-02 -9.195659e-01 4.424050e+02 +-9.197158e-01 1.986220e-02 -3.920822e-01 3.955156e+02 1.421595e-03 9.988813e-01 4.726695e-02 -4.822929e+01 3.925823e-01 4.291477e-02 -9.187150e-01 4.416903e+02 +-9.190447e-01 2.219977e-02 -3.935278e-01 3.952112e+02 3.698163e-03 9.988543e-01 4.771092e-02 -4.821350e+01 3.941361e-01 4.239313e-02 -9.180738e-01 4.409678e+02 +-9.185152e-01 2.471990e-02 -3.946123e-01 3.949068e+02 6.548628e-03 9.988579e-01 4.732916e-02 -4.819960e+01 3.953315e-01 4.088838e-02 -9.176279e-01 4.402352e+02 +-9.178988e-01 2.899806e-02 -3.957536e-01 3.945994e+02 1.026372e-02 9.987276e-01 4.937443e-02 -4.818393e+01 3.966818e-01 4.125882e-02 -9.170284e-01 4.394902e+02 +-9.174369e-01 3.092963e-02 -3.966775e-01 3.942877e+02 1.091236e-02 9.985549e-01 5.262093e-02 -4.816327e+01 3.977318e-01 4.394768e-02 -9.164485e-01 4.387494e+02 +-9.172085e-01 3.300883e-02 -3.970379e-01 3.939771e+02 1.137978e-02 9.983258e-01 5.670983e-02 -4.814386e+01 3.982451e-01 4.749652e-02 -9.160485e-01 4.379990e+02 +-9.171604e-01 3.410242e-02 -3.970567e-01 3.936599e+02 1.168112e-02 9.982043e-01 5.875164e-02 -4.811261e+01 3.983472e-01 4.924661e-02 -9.159117e-01 4.372519e+02 +-9.172268e-01 3.181506e-02 -3.970931e-01 3.933419e+02 8.990218e-03 9.982050e-01 5.921002e-02 -4.807817e+01 3.982641e-01 5.073906e-02 -9.158663e-01 4.364977e+02 +-9.170146e-01 2.943890e-02 -3.977659e-01 3.930181e+02 6.315865e-03 9.982191e-01 5.931816e-02 -4.804759e+01 3.988038e-01 5.188338e-02 -9.155673e-01 4.357424e+02 +-9.167881e-01 2.693924e-02 -3.984646e-01 3.926907e+02 3.678913e-03 9.982497e-01 5.902487e-02 -4.801723e+01 3.993572e-01 5.264738e-02 -9.152824e-01 4.349821e+02 +-9.164414e-01 2.620114e-02 -3.993103e-01 3.923586e+02 3.273957e-03 9.983117e-01 5.799130e-02 -4.798606e+01 4.001556e-01 5.183829e-02 -9.149799e-01 4.342218e+02 +-9.158555e-01 2.493551e-02 -4.007330e-01 3.920250e+02 2.523885e-03 9.984074e-01 5.635747e-02 -4.795484e+01 4.015001e-01 5.060389e-02 -9.144598e-01 4.334576e+02 +-9.151183e-01 2.449097e-02 -4.024411e-01 3.916866e+02 2.715317e-03 9.985051e-01 5.459069e-02 -4.791412e+01 4.031765e-01 4.886417e-02 -9.138167e-01 4.326843e+02 +-9.142819e-01 2.510593e-02 -4.042998e-01 3.913438e+02 3.967383e-03 9.985846e-01 5.303761e-02 -4.786914e+01 4.050591e-01 4.688731e-02 -9.130874e-01 4.319077e+02 +-9.133839e-01 2.637126e-02 -4.062443e-01 3.909970e+02 4.990758e-03 9.985500e-01 5.359967e-02 -4.782220e+01 4.070687e-01 4.692960e-02 -9.121911e-01 4.311224e+02 +-9.122964e-01 2.823865e-02 -4.085559e-01 3.906410e+02 5.804080e-03 9.984112e-01 5.604802e-02 -4.778663e+01 4.094895e-01 4.876111e-02 -9.110108e-01 4.303321e+02 +-9.111912e-01 2.747094e-02 -4.110670e-01 3.902856e+02 2.114255e-03 9.980731e-01 6.201307e-02 -4.774063e+01 4.119785e-01 5.563665e-02 -9.094934e-01 4.295319e+02 +-9.094385e-01 3.076398e-02 -4.146989e-01 3.899203e+02 3.417490e-03 9.977789e-01 6.652456e-02 -4.769482e+01 4.158244e-01 5.908276e-02 -9.075237e-01 4.287288e+02 +-9.079567e-01 3.140257e-02 -4.178858e-01 3.895512e+02 3.098237e-03 9.976642e-01 6.823913e-02 -4.765278e+01 4.190526e-01 6.066346e-02 -9.059331e-01 4.279163e+02 +-9.061386e-01 2.984781e-02 -4.219266e-01 3.891779e+02 1.545078e-03 9.977340e-01 6.726320e-02 -4.760773e+01 4.229782e-01 6.029787e-02 -9.041314e-01 4.271043e+02 +-9.043242e-01 3.097886e-02 -4.257206e-01 3.887936e+02 2.049853e-03 9.976665e-01 6.824393e-02 -4.756049e+01 4.268413e-01 6.084197e-02 -9.022775e-01 4.262845e+02 +-9.026760e-01 3.449599e-02 -4.289360e-01 3.884003e+02 4.010133e-03 9.974128e-01 7.177504e-02 -4.751302e+01 4.303022e-01 6.306951e-02 -9.004788e-01 4.254607e+02 +-9.007338e-01 3.759876e-02 -4.327412e-01 3.880020e+02 5.976134e-03 9.972251e-01 7.420493e-02 -4.746533e+01 4.343304e-01 6.425277e-02 -8.984590e-01 4.246330e+02 +-8.989244e-01 3.832812e-02 -4.364241e-01 3.876017e+02 7.306124e-03 9.973387e-01 7.254064e-02 -4.741754e+01 4.380429e-01 6.201997e-02 -8.968120e-01 4.238067e+02 +-8.971298e-01 3.759605e-02 -4.401644e-01 3.871964e+02 8.138990e-03 9.976096e-01 6.862086e-02 -4.737011e+01 4.416921e-01 5.797932e-02 -8.952912e-01 4.229816e+02 +-8.956100e-01 3.734196e-02 -4.432700e-01 3.867860e+02 9.090109e-03 9.977986e-01 6.569037e-02 -4.732301e+01 4.447472e-01 5.480357e-02 -8.939778e-01 4.221536e+02 +-8.941099e-01 4.039500e-02 -4.460222e-01 3.863696e+02 1.135552e-02 9.976485e-01 6.759067e-02 -4.727603e+01 4.477037e-01 5.536866e-02 -8.924660e-01 4.213215e+02 +-8.928025e-01 4.168565e-02 -4.485154e-01 3.859511e+02 1.137654e-02 9.974778e-01 7.006117e-02 -4.723030e+01 4.503047e-01 5.744823e-02 -8.910248e-01 4.204820e+02 +-8.915488e-01 4.173789e-02 -4.509975e-01 3.855292e+02 1.095920e-02 9.974413e-01 7.064441e-02 -4.718503e+01 4.527921e-01 5.804036e-02 -8.897250e-01 4.196455e+02 +-8.906735e-01 3.618250e-02 -4.532016e-01 3.851104e+02 6.580994e-03 9.977497e-01 6.672434e-02 -4.714075e+01 4.545960e-01 5.644707e-02 -8.889073e-01 4.188046e+02 +-8.894937e-01 3.227461e-02 -4.558063e-01 3.846867e+02 4.467134e-03 9.980690e-01 6.195353e-02 -4.709746e+01 4.569257e-01 5.307112e-02 -8.879202e-01 4.179670e+02 +-8.881429e-01 3.417199e-02 -4.582953e-01 3.842528e+02 6.456426e-03 9.980610e-01 6.190663e-02 -4.704937e+01 4.595221e-01 5.202298e-02 -8.866414e-01 4.171229e+02 +-8.870391e-01 3.675997e-02 -4.602287e-01 3.838133e+02 5.327017e-03 9.975738e-01 6.941228e-02 -4.700284e+01 4.616637e-01 5.911974e-02 -8.850827e-01 4.162707e+02 +-8.860778e-01 3.846444e-02 -4.619379e-01 3.833721e+02 3.611066e-03 9.970937e-01 7.609892e-02 -4.695803e+01 4.635225e-01 6.576147e-02 -8.836415e-01 4.154182e+02 +-8.853480e-01 3.985081e-02 -4.632180e-01 3.829273e+02 6.339688e-03 9.972619e-01 7.367778e-02 -4.690702e+01 4.648858e-01 6.229381e-02 -8.831764e-01 4.145756e+02 +-8.844384e-01 4.013242e-02 -4.649282e-01 3.824801e+02 8.761275e-03 9.975475e-01 6.944126e-02 -4.685723e+01 4.665748e-01 5.734315e-02 -8.826209e-01 4.137345e+02 +-8.832175e-01 3.817746e-02 -4.674071e-01 3.820374e+02 7.947481e-03 9.977562e-01 6.647836e-02 -4.680509e+01 4.688963e-01 5.500013e-02 -8.815391e-01 4.128837e+02 +-8.822167e-01 3.578017e-02 -4.694821e-01 3.815915e+02 4.964636e-03 9.977599e-01 6.671211e-02 -4.675575e+01 4.708174e-01 5.652373e-02 -8.804180e-01 4.120301e+02 +-8.812010e-01 3.579502e-02 -4.713847e-01 3.811402e+02 3.393326e-03 9.975825e-01 6.940890e-02 -4.670624e+01 4.727296e-01 5.956363e-02 -8.791921e-01 4.111730e+02 +-8.802182e-01 3.603331e-02 -4.731994e-01 3.806820e+02 2.729461e-03 9.974811e-01 7.087929e-02 -4.665946e+01 4.745615e-01 6.109765e-02 -8.780993e-01 4.103171e+02 +-8.792327e-01 3.523394e-02 -4.750879e-01 3.802241e+02 2.824668e-03 9.976292e-01 6.875967e-02 -4.660879e+01 4.763842e-01 5.911378e-02 -8.772477e-01 4.094631e+02 +-8.782224e-01 3.407172e-02 -4.770373e-01 3.797646e+02 3.054136e-03 9.978382e-01 6.564657e-02 -4.655565e+01 4.782428e-01 5.619534e-02 -8.764279e-01 4.086087e+02 +-8.771967e-01 3.422586e-02 -4.789099e-01 3.793004e+02 3.320751e-03 9.978646e-01 6.523114e-02 -4.650342e+01 4.801198e-01 5.563019e-02 -8.754371e-01 4.077497e+02 +-8.761723e-01 3.548252e-02 -4.806903e-01 3.788301e+02 3.563130e-03 9.977362e-01 6.715404e-02 -4.645482e+01 4.819849e-01 5.712574e-02 -8.743152e-01 4.068894e+02 +-8.750408e-01 3.736319e-02 -4.826051e-01 3.783560e+02 4.347236e-03 9.975829e-01 6.935045e-02 -4.640539e+01 4.840298e-01 5.858646e-02 -8.730880e-01 4.060271e+02 +-8.738361e-01 3.703352e-02 -4.848083e-01 3.778816e+02 3.580686e-03 9.975582e-01 6.974752e-02 -4.635506e+01 4.862074e-01 5.921195e-02 -8.718349e-01 4.051668e+02 +-8.722658e-01 3.616282e-02 -4.876932e-01 3.774044e+02 2.867221e-03 9.976231e-01 6.884636e-02 -4.630289e+01 4.890237e-01 5.865399e-02 -8.702962e-01 4.043034e+02 +-8.705223e-01 3.644380e-02 -4.907778e-01 3.769219e+02 3.743040e-03 9.977157e-01 6.744836e-02 -4.625104e+01 4.921148e-01 5.687829e-02 -8.686701e-01 4.034425e+02 +-8.686887e-01 3.676444e-02 -4.939924e-01 3.764331e+02 4.978732e-03 9.978397e-01 6.550720e-02 -4.620149e+01 4.953335e-01 5.444590e-02 -8.669950e-01 4.025836e+02 +-8.667123e-01 3.649865e-02 -4.974713e-01 3.759407e+02 5.039757e-03 9.979092e-01 6.443453e-02 -4.615287e+01 4.987829e-01 5.333906e-02 -8.650841e-01 4.017223e+02 +-8.647624e-01 3.633316e-02 -5.008652e-01 3.754442e+02 4.847040e-03 9.979367e-01 6.402255e-02 -4.610620e+01 5.021579e-01 5.293657e-02 -8.631541e-01 4.008629e+02 +-8.626783e-01 3.949275e-02 -5.042089e-01 3.749413e+02 7.331339e-03 9.978183e-01 6.561172e-02 -4.605517e+01 5.057000e-01 5.290527e-02 -8.610856e-01 3.999989e+02 +-8.606148e-01 4.274528e-02 -5.074595e-01 3.744313e+02 9.392359e-03 9.976339e-01 6.810582e-02 -4.600568e+01 5.091700e-01 5.384662e-02 -8.589798e-01 3.991370e+02 +-8.583891e-01 4.426237e-02 -5.110861e-01 3.739184e+02 9.457005e-03 9.974668e-01 7.050175e-02 -4.595477e+01 5.129120e-01 5.568458e-02 -8.566332e-01 3.982723e+02 +-8.562447e-01 4.617867e-02 -5.145024e-01 3.733982e+02 1.161710e-02 9.974657e-01 7.019322e-02 -4.590227e+01 5.164399e-01 5.412554e-02 -8.546111e-01 3.974117e+02 +-8.541382e-01 4.782140e-02 -5.178427e-01 3.728782e+02 1.272591e-02 9.973869e-01 7.111575e-02 -4.584536e+01 5.198903e-01 5.415266e-02 -8.525148e-01 3.965502e+02 +-8.518708e-01 4.996294e-02 -5.213635e-01 3.723511e+02 1.373298e-02 9.972281e-01 7.312697e-02 -4.578943e+01 5.235719e-01 5.513485e-02 -8.501956e-01 3.956866e+02 +-8.498596e-01 4.997467e-02 -5.246343e-01 3.718211e+02 1.309853e-02 9.971892e-01 7.377007e-02 -4.573443e+01 5.268463e-01 5.582226e-02 -8.481254e-01 3.948239e+02 +-8.478567e-01 4.958712e-02 -5.279017e-01 3.712863e+02 1.301665e-02 9.972638e-01 7.276961e-02 -4.567818e+01 5.300657e-01 5.482668e-02 -8.461822e-01 3.939601e+02 +-8.460648e-01 5.012349e-02 -5.307184e-01 3.707451e+02 1.411136e-02 9.973267e-01 7.169598e-02 -4.562199e+01 5.328933e-01 5.317028e-02 -8.445103e-01 3.930985e+02 +-8.442916e-01 5.070172e-02 -5.334802e-01 3.702051e+02 1.392529e-02 9.972537e-01 7.274026e-02 -4.556095e+01 5.357031e-01 5.398512e-02 -8.426789e-01 3.922334e+02 +-8.425240e-01 4.703113e-02 -5.366017e-01 3.696626e+02 1.069835e-02 9.974456e-01 7.062480e-02 -4.550754e+01 5.385526e-01 5.376233e-02 -8.408749e-01 3.913678e+02 +-8.406125e-01 4.464946e-02 -5.397937e-01 3.691159e+02 1.104221e-02 9.978021e-01 6.533814e-02 -4.545132e+01 5.415245e-01 4.896353e-02 -8.392578e-01 3.905066e+02 +-8.386567e-01 4.499682e-02 -5.427986e-01 3.685571e+02 1.439940e-02 9.980649e-01 6.048948e-02 -4.539845e+01 5.444701e-01 4.291392e-02 -8.376817e-01 3.896492e+02 +-8.372876e-01 4.378596e-02 -5.450067e-01 3.680120e+02 1.229999e-02 9.980444e-01 6.128679e-02 -4.535325e+01 5.466244e-01 4.461108e-02 -8.361887e-01 3.887984e+02 +-8.359704e-01 4.508610e-02 -5.469194e-01 3.674656e+02 1.422441e-02 9.980647e-01 6.053483e-02 -4.530201e+01 5.485902e-01 4.282571e-02 -8.349938e-01 3.879524e+02 +-8.349547e-01 4.746663e-02 -5.482679e-01 3.669179e+02 1.708595e-02 9.980289e-01 6.038487e-02 -4.525070e+01 5.500535e-01 4.105094e-02 -8.341198e-01 3.871089e+02 +-8.338563e-01 5.234633e-02 -5.494940e-01 3.663572e+02 2.126603e-02 9.978006e-01 6.278213e-02 -4.520224e+01 5.515718e-01 4.066571e-02 -8.331355e-01 3.862583e+02 +-8.331729e-01 5.355740e-02 -5.504131e-01 3.657993e+02 1.973309e-02 9.975447e-01 6.719469e-02 -4.515228e+01 5.526605e-01 4.512343e-02 -8.321840e-01 3.854020e+02 +-8.325562e-01 5.333467e-02 -5.513672e-01 3.652461e+02 1.794191e-02 9.974282e-01 6.939091e-02 -4.509727e+01 5.536500e-01 4.787925e-02 -8.313718e-01 3.845459e+02 +-8.317451e-01 5.239798e-02 -5.526794e-01 3.646863e+02 1.474598e-02 9.972698e-01 7.235667e-02 -4.503855e+01 5.549618e-01 5.203251e-02 -8.302469e-01 3.836835e+02 +-8.306012e-01 5.326249e-02 -5.543147e-01 3.641251e+02 1.286254e-02 9.969848e-01 7.652379e-02 -4.497608e+01 5.567191e-01 5.643085e-02 -8.287818e-01 3.828214e+02 +-8.294215e-01 5.264542e-02 -5.561372e-01 3.635562e+02 1.049989e-02 9.968427e-01 7.870428e-02 -4.491414e+01 5.585247e-01 5.943963e-02 -8.273554e-01 3.819581e+02 +-8.280930e-01 5.119744e-02 -5.582480e-01 3.629905e+02 8.661328e-03 9.968705e-01 7.857591e-02 -4.484992e+01 5.605238e-01 6.023299e-02 -8.259449e-01 3.811031e+02 +-8.268157e-01 4.899227e-02 -5.603353e-01 3.624201e+02 6.435506e-03 9.969582e-01 7.767184e-02 -4.478549e+01 5.624362e-01 6.061425e-02 -8.246159e-01 3.802474e+02 +-8.251092e-01 4.872145e-02 -5.628687e-01 3.618506e+02 5.740281e-03 9.969462e-01 7.788019e-02 -4.471851e+01 5.649442e-01 6.102863e-02 -8.228690e-01 3.793942e+02 +-8.232131e-01 4.784541e-02 -5.657129e-01 3.612741e+02 4.145265e-03 9.969225e-01 7.828308e-02 -4.465545e+01 5.677174e-01 6.209862e-02 -8.208780e-01 3.785454e+02 +-8.208204e-01 4.674354e-02 -5.692706e-01 3.606663e+02 3.220171e-03 9.970087e-01 7.722258e-02 -4.458992e+01 5.711774e-01 6.155271e-02 -8.185155e-01 3.777094e+02 +-8.184344e-01 4.599815e-02 -5.727559e-01 3.600683e+02 3.728937e-03 9.971948e-01 7.475651e-02 -4.452913e+01 5.745879e-01 5.904752e-02 -8.163100e-01 3.768879e+02 +-8.161177e-01 4.334415e-02 -5.762580e-01 3.594795e+02 2.972307e-03 9.974848e-01 7.081791e-02 -4.447192e+01 5.778782e-01 5.608292e-02 -8.141937e-01 3.760796e+02 +-8.134918e-01 4.122204e-02 -5.801138e-01 3.588951e+02 2.402379e-03 9.977145e-01 6.752731e-02 -4.441537e+01 5.815715e-01 5.353925e-02 -8.117315e-01 3.752807e+02 +-8.109947e-01 4.016776e-02 -5.836731e-01 3.583167e+02 1.283039e-03 9.977600e-01 6.688205e-02 -4.436319e+01 5.850522e-01 5.349211e-02 -8.092295e-01 3.744920e+02 +-8.085258e-01 3.983699e-02 -5.871109e-01 3.577431e+02 -1.175721e-03 9.975946e-01 6.930850e-02 -4.431235e+01 5.884596e-01 5.672798e-02 -8.065340e-01 3.737137e+02 +-8.061266e-01 3.994120e-02 -5.903937e-01 3.571773e+02 -2.928993e-03 9.974379e-01 7.147776e-02 -4.426529e+01 5.917359e-01 5.934937e-02 -8.039442e-01 3.729445e+02 +-8.040354e-01 3.917590e-02 -5.932895e-01 3.566127e+02 -2.462213e-03 9.975991e-01 6.920998e-02 -4.422177e+01 5.945764e-01 5.710807e-02 -8.020084e-01 3.721828e+02 +-8.023004e-01 3.897377e-02 -5.956468e-01 3.560465e+02 -1.457465e-03 9.977353e-01 6.724596e-02 -4.417800e+01 5.969187e-01 5.481959e-02 -8.004267e-01 3.714244e+02 +-8.009172e-01 3.819773e-02 -5.975556e-01 3.554800e+02 -2.374223e-03 9.977527e-01 6.696190e-02 -4.413221e+01 5.987705e-01 5.504966e-02 -7.990265e-01 3.706677e+02 +-7.996893e-01 3.778884e-02 -5.992237e-01 3.549130e+02 -3.038459e-03 9.977499e-01 6.697607e-02 -4.408788e+01 6.004064e-01 5.538075e-02 -7.977751e-01 3.699142e+02 +-7.986669e-01 3.661742e-02 -6.006583e-01 3.543495e+02 -4.179095e-03 9.977854e-01 6.638391e-02 -4.404279e+01 6.017588e-01 5.552884e-02 -7.967451e-01 3.691684e+02 +-7.977604e-01 3.482771e-02 -6.019679e-01 3.537822e+02 -6.008368e-03 9.978218e-01 6.569303e-02 -4.399989e+01 6.029446e-01 5.602414e-02 -7.958134e-01 3.684201e+02 +-7.972281e-01 3.384399e-02 -6.027288e-01 3.532216e+02 -7.669808e-03 9.977788e-01 6.617141e-02 -4.395830e+01 6.036295e-01 5.737651e-02 -7.951977e-01 3.676793e+02 +-7.970001e-01 3.499148e-02 -6.029648e-01 3.526629e+02 -6.497730e-03 9.977658e-01 6.649145e-02 -4.391971e+01 6.039443e-01 5.691159e-02 -7.949920e-01 3.669440e+02 +-7.973690e-01 3.613986e-02 -6.024091e-01 3.521099e+02 -5.746484e-03 9.977054e-01 6.746082e-02 -4.388311e+01 6.034648e-01 5.725289e-02 -7.953316e-01 3.662148e+02 +-7.979518e-01 3.727581e-02 -6.015675e-01 3.515619e+02 -4.233959e-03 9.977144e-01 6.743901e-02 -4.384630e+01 6.027064e-01 5.636008e-02 -7.959701e-01 3.654919e+02 +-7.989404e-01 3.740510e-02 -6.002460e-01 3.510189e+02 -3.105282e-03 9.977941e-01 6.631205e-02 -4.381346e+01 6.014022e-01 5.484330e-02 -7.970618e-01 3.647805e+02 +-7.997746e-01 3.840994e-02 -5.990704e-01 3.504872e+02 -1.579434e-03 9.978128e-01 6.608429e-02 -4.378034e+01 6.002983e-01 5.379872e-02 -7.979646e-01 3.640754e+02 +-8.005482e-01 3.991479e-02 -5.979377e-01 3.499595e+02 -1.435449e-03 9.976488e-01 6.851900e-02 -4.374379e+01 5.992667e-01 5.571107e-02 -7.986086e-01 3.633718e+02 +-8.011911e-01 4.037588e-02 -5.970449e-01 3.494453e+02 -3.046232e-03 9.974330e-01 7.154046e-02 -4.371154e+01 5.984008e-01 5.913631e-02 -7.990114e-01 3.626792e+02 +-8.015299e-01 4.301864e-02 -5.964053e-01 3.489395e+02 -1.766679e-03 9.972340e-01 7.430468e-02 -4.367650e+01 5.979521e-01 6.061107e-02 -7.992368e-01 3.619995e+02 +-8.018540e-01 4.401364e-02 -5.958969e-01 3.484505e+02 -4.852138e-04 9.972351e-01 7.430989e-02 -4.364837e+01 5.975199e-01 5.987481e-02 -7.996155e-01 3.613287e+02 +-8.018383e-01 4.302819e-02 -5.959900e-01 3.479701e+02 -1.525864e-03 9.972533e-01 7.405077e-02 -4.361535e+01 5.975392e-01 6.028613e-02 -7.995701e-01 3.606698e+02 +-8.017185e-01 4.234475e-02 -5.962000e-01 3.475016e+02 -2.701987e-03 9.972203e-01 7.446040e-02 -4.357651e+01 5.976957e-01 6.130720e-02 -7.993755e-01 3.600185e+02 +-8.008458e-01 4.257239e-02 -5.973556e-01 3.470397e+02 -3.125349e-03 9.971594e-01 7.525566e-02 -4.353813e+01 5.988625e-01 6.213512e-02 -7.984378e-01 3.593817e+02 +-7.989562e-01 4.055948e-02 -6.000200e-01 3.465879e+02 -6.738101e-03 9.970568e-01 7.637006e-02 -4.350456e+01 6.013515e-01 6.505932e-02 -7.963313e-01 3.587607e+02 +-7.958402e-01 3.786791e-02 -6.043215e-01 3.461432e+02 -1.028659e-02 9.970529e-01 7.602378e-02 -4.347025e+01 6.054193e-01 6.671918e-02 -7.931052e-01 3.581555e+02 +-7.920407e-01 3.643406e-02 -6.093802e-01 3.457029e+02 -1.250431e-02 9.970397e-01 7.586420e-02 -4.343457e+01 6.103403e-01 6.770740e-02 -7.892404e-01 3.575703e+02 +-7.876785e-01 3.649939e-02 -6.150045e-01 3.452692e+02 -1.365989e-02 9.969635e-01 7.666315e-02 -4.340007e+01 6.159351e-01 6.878679e-02 -7.847880e-01 3.570049e+02 +-7.826663e-01 3.568313e-02 -6.214179e-01 3.448391e+02 -1.512716e-02 9.969701e-01 7.630057e-02 -4.336671e+01 6.222577e-01 6.911816e-02 -7.797550e-01 3.564568e+02 +-7.773359e-01 3.363276e-02 -6.281861e-01 3.444120e+02 -1.748873e-02 9.970285e-01 7.502147e-02 -4.333953e+01 6.288426e-01 6.930304e-02 -7.744378e-01 3.559302e+02 +-7.715377e-01 3.213434e-02 -6.353715e-01 3.439876e+02 -1.882494e-02 9.971330e-01 7.328999e-02 -4.330977e+01 6.359050e-01 6.850682e-02 -7.687207e-01 3.554200e+02 +-7.650940e-01 3.150752e-02 -6.431473e-01 3.435651e+02 -1.942001e-02 9.972187e-01 7.195558e-02 -4.328104e+01 6.436257e-01 6.754270e-02 -7.623542e-01 3.549170e+02 +-7.577926e-01 3.086460e-02 -6.517651e-01 3.431456e+02 -2.131604e-02 9.971764e-01 7.200538e-02 -4.325169e+01 6.521472e-01 6.845819e-02 -7.549950e-01 3.544278e+02 +-7.491918e-01 3.233980e-02 -6.615632e-01 3.427223e+02 -2.285623e-02 9.969502e-01 7.461853e-02 -4.322206e+01 6.619587e-01 7.102442e-02 -7.461677e-01 3.539423e+02 +-7.383771e-01 3.684624e-02 -6.733808e-01 3.422923e+02 -2.259852e-02 9.965937e-01 7.931169e-02 -4.319773e+01 6.740093e-01 7.377933e-02 -7.350292e-01 3.534794e+02 +-7.259135e-01 4.220456e-02 -6.864899e-01 3.418618e+02 -2.249252e-02 9.961249e-01 8.502478e-02 -4.316977e+01 6.874181e-01 7.716152e-02 -7.221512e-01 3.530354e+02 +-7.117126e-01 4.639778e-02 -7.009369e-01 3.414284e+02 -2.271981e-02 9.957739e-01 8.898331e-02 -4.314000e+01 7.021033e-01 7.925568e-02 -7.076506e-01 3.525991e+02 +-6.954582e-01 4.906949e-02 -7.168892e-01 3.410050e+02 -2.357748e-02 9.955701e-01 9.101726e-02 -4.311216e+01 7.181796e-01 8.020114e-02 -6.912205e-01 3.521907e+02 +-6.778398e-01 4.996596e-02 -7.335098e-01 3.405686e+02 -2.497516e-02 9.955472e-01 9.089536e-02 -4.308433e+01 7.347853e-01 7.993201e-02 -6.735736e-01 3.517904e+02 +-6.573801e-01 5.023900e-02 -7.518827e-01 3.401322e+02 -2.514450e-02 9.957571e-01 8.851827e-02 -4.305820e+01 7.531395e-01 7.709585e-02 -6.533276e-01 3.514231e+02 +-6.336017e-01 5.092103e-02 -7.719819e-01 3.396915e+02 -2.577975e-02 9.958879e-01 8.684886e-02 -4.303107e+01 7.732298e-01 7.492908e-02 -6.296834e-01 3.510819e+02 +-6.069691e-01 5.226183e-02 -7.930052e-01 3.392244e+02 -2.742422e-02 9.958637e-01 8.662153e-02 -4.299895e+01 7.942521e-01 7.432414e-02 -6.030253e-01 3.507405e+02 +-5.768808e-01 5.569391e-02 -8.149274e-01 3.387693e+02 -3.000428e-02 9.955547e-01 8.927818e-02 -4.297287e+01 8.162770e-01 7.595418e-02 -5.726453e-01 3.504412e+02 +-5.430860e-01 5.887291e-02 -8.376107e-01 3.382788e+02 -3.389687e-02 9.951887e-01 9.192645e-02 -4.294293e+01 8.389926e-01 7.831633e-02 -5.384773e-01 3.501358e+02 +-5.051388e-01 6.216908e-02 -8.607961e-01 3.378109e+02 -3.664028e-02 9.949580e-01 9.336016e-02 -4.291628e+01 8.622600e-01 7.869963e-02 -5.003139e-01 3.498928e+02 +-4.637605e-01 6.411934e-02 -8.836374e-01 3.373417e+02 -4.081019e-02 9.947729e-01 9.360214e-02 -4.289026e+01 8.850202e-01 7.947038e-02 -4.587196e-01 3.496813e+02 +-4.186701e-01 6.426752e-02 -9.058615e-01 3.368222e+02 -4.599544e-02 9.947119e-01 9.182926e-02 -4.285825e+01 9.069728e-01 8.011166e-02 -4.135001e-01 3.494508e+02 +-3.698683e-01 6.600550e-02 -9.267366e-01 3.363325e+02 -4.753666e-02 9.948223e-01 8.982710e-02 -4.282608e+01 9.278673e-01 7.727815e-02 -3.648155e-01 3.492997e+02 +-3.186940e-01 7.020887e-02 -9.452539e-01 3.357772e+02 -4.536591e-02 9.949802e-01 8.919752e-02 -4.279305e+01 9.467713e-01 7.130901e-02 -3.139092e-01 3.491284e+02 +-2.646203e-01 7.290234e-02 -9.615932e-01 3.352584e+02 -4.295364e-02 9.952578e-01 8.727499e-02 -4.276284e+01 9.633956e-01 6.439865e-02 -2.602340e-01 3.490457e+02 +-2.069215e-01 7.436834e-02 -9.755270e-01 3.347335e+02 -4.789638e-02 9.951412e-01 8.602305e-02 -4.274178e+01 9.771844e-01 6.452423e-02 -2.023541e-01 3.489906e+02 +-1.460993e-01 7.593116e-02 -9.863516e-01 3.341324e+02 -5.199781e-02 9.950823e-01 8.430524e-02 -4.271540e+01 9.879024e-01 6.360506e-02 -1.414326e-01 3.489082e+02 +-8.399090e-02 7.792792e-02 -9.934147e-01 3.335926e+02 -5.229834e-02 9.952186e-01 8.249114e-02 -4.268803e+01 9.950931e-01 5.888243e-02 -7.951380e-02 3.489310e+02 +-2.112737e-02 7.678372e-02 -9.968239e-01 3.329872e+02 -4.564025e-02 9.959329e-01 7.768243e-02 -4.266016e+01 9.987345e-01 4.713651e-02 -1.753702e-02 3.489332e+02 +4.270732e-02 7.197415e-02 -9.964918e-01 3.324524e+02 -4.414617e-02 9.965635e-01 7.008734e-02 -4.264262e+01 9.981118e-01 4.099805e-02 4.573793e-02 3.490313e+02 +1.072155e-01 6.589615e-02 -9.920497e-01 3.319180e+02 -4.756849e-02 9.969985e-01 6.108393e-02 -4.263882e+01 9.930972e-01 4.064116e-02 1.100283e-01 3.491556e+02 +1.713044e-01 5.897583e-02 -9.834514e-01 3.313217e+02 -5.524814e-02 9.972110e-01 5.017748e-02 -4.261755e+01 9.836678e-01 4.573823e-02 1.740850e-01 3.492350e+02 +2.337923e-01 5.268133e-02 -9.708583e-01 3.307978e+02 -5.541714e-02 9.976298e-01 4.078903e-02 -4.261614e+01 9.707059e-01 4.426603e-02 2.361576e-01 3.494281e+02 +2.939765e-01 4.813337e-02 -9.545999e-01 3.302227e+02 -5.346879e-02 9.979954e-01 3.385536e-02 -4.260336e+01 9.543159e-01 4.108862e-02 2.959608e-01 3.495927e+02 +3.507120e-01 4.100654e-02 -9.355852e-01 3.297179e+02 -4.697176e-02 9.985536e-01 2.615869e-02 -4.259168e+01 9.353046e-01 3.477191e-02 3.521308e-01 3.498685e+02 +4.009753e-01 3.548493e-02 -9.154014e-01 3.292111e+02 -3.798084e-02 9.990343e-01 2.209008e-02 -4.258089e+01 9.153012e-01 2.591014e-02 4.019358e-01 3.501673e+02 +4.454750e-01 3.237455e-02 -8.947089e-01 3.286616e+02 -3.478815e-02 9.992172e-01 1.883513e-02 -4.257839e+01 8.946182e-01 2.273469e-02 4.462525e-01 3.504405e+02 +4.854104e-01 2.995228e-02 -8.737732e-01 3.281540e+02 -3.545062e-02 9.992653e-01 1.456005e-02 -4.258564e+01 8.735674e-01 2.390820e-02 4.861156e-01 3.507608e+02 +5.201660e-01 2.563748e-02 -8.536803e-01 3.276418e+02 -3.587746e-02 9.993229e-01 8.150466e-03 -4.259763e+01 8.533112e-01 2.638829e-02 5.207336e-01 3.510983e+02 +5.491966e-01 1.658798e-02 -8.355286e-01 3.271143e+02 -3.001671e-02 9.995494e-01 1.142202e-04 -4.260501e+01 8.351539e-01 2.501709e-02 5.494470e-01 3.514450e+02 +5.734437e-01 7.073391e-03 -8.192145e-01 3.266094e+02 -2.171898e-02 9.997425e-01 -6.570978e-03 -4.261579e+01 8.189570e-01 2.156059e-02 5.734496e-01 3.518337e+02 +5.921349e-01 1.666338e-03 -8.058372e-01 3.260948e+02 -1.606990e-02 9.998234e-01 -9.740806e-03 -4.263358e+01 8.056786e-01 1.871760e-02 5.920571e-01 3.522360e+02 +6.056630e-01 -6.115064e-04 -7.957210e-01 3.255695e+02 -1.428878e-02 9.998301e-01 -1.164426e-02 -4.265550e+01 7.955929e-01 1.842238e-02 6.055513e-01 3.526406e+02 +6.159348e-01 -5.016829e-03 -7.877812e-01 3.250406e+02 -1.193657e-02 9.998055e-01 -1.569979e-02 -4.268243e+01 7.877066e-01 1.907346e-02 6.157551e-01 3.530599e+02 +6.238481e-01 -1.168057e-02 -7.814584e-01 3.245127e+02 -8.079255e-03 9.997385e-01 -2.139300e-02 -4.270271e+01 7.815038e-01 1.965959e-02 6.235905e-01 3.534897e+02 +6.292190e-01 -1.758467e-02 -7.770291e-01 3.239782e+02 -4.724818e-03 9.996390e-01 -2.644851e-02 -4.272978e+01 7.772137e-01 2.031323e-02 6.289087e-01 3.539346e+02 +6.326366e-01 -2.170396e-02 -7.741447e-01 3.234311e+02 -7.119431e-04 9.995905e-01 -2.860638e-02 -4.276207e+01 7.744485e-01 1.864859e-02 6.323620e-01 3.543938e+02 +6.339301e-01 -2.404014e-02 -7.730167e-01 3.228758e+02 3.219392e-03 9.995901e-01 -2.844625e-02 -4.279710e+01 7.733836e-01 1.554429e-02 6.337476e-01 3.548635e+02 +6.323556e-01 -2.809589e-02 -7.741687e-01 3.223129e+02 9.419260e-03 9.995471e-01 -2.858143e-02 -4.283155e+01 7.746210e-01 1.078153e-02 6.323337e-01 3.553429e+02 +6.274449e-01 -2.742922e-02 -7.781777e-01 3.217336e+02 1.057761e-02 9.995874e-01 -2.670475e-02 -4.286263e+01 7.785891e-01 8.524505e-03 6.274761e-01 3.558206e+02 +6.190621e-01 -2.481712e-02 -7.849499e-01 3.211355e+02 1.489033e-02 9.996918e-01 -1.986297e-02 -4.287959e+01 7.852009e-01 6.082578e-04 6.192408e-01 3.563020e+02 +6.070890e-01 -2.089374e-02 -7.943591e-01 3.205248e+02 1.992505e-02 9.997402e-01 -1.106808e-02 -4.289953e+01 7.943840e-01 -9.108328e-03 6.073476e-01 3.567876e+02 +5.929318e-01 -1.521849e-02 -8.051089e-01 3.198984e+02 2.210324e-02 9.997522e-01 -2.619526e-03 -4.292021e+01 8.049492e-01 -1.624230e-02 5.931213e-01 3.572633e+02 +5.773344e-01 -1.428740e-02 -8.163828e-01 3.192500e+02 1.935046e-02 9.998055e-01 -3.813082e-03 -4.294047e+01 8.162784e-01 -1.359595e-02 5.774985e-01 3.577101e+02 +5.593837e-01 -1.857768e-02 -8.287007e-01 3.185972e+02 1.854824e-02 9.997790e-01 -9.892587e-03 -4.295443e+01 8.287013e-01 -9.837183e-03 5.596046e-01 3.581534e+02 +5.409881e-01 -2.305420e-02 -8.407142e-01 3.179311e+02 2.018548e-02 9.996922e-01 -1.442463e-02 -4.297458e+01 8.407880e-01 -9.166661e-03 5.412869e-01 3.585872e+02 +5.220797e-01 -2.451975e-02 -8.525442e-01 3.172423e+02 2.122039e-02 9.996506e-01 -1.575573e-02 -4.300060e+01 8.526327e-01 -9.865571e-03 5.224175e-01 3.590024e+02 +5.018432e-01 -2.309763e-02 -8.646502e-01 3.165413e+02 1.868320e-02 9.996996e-01 -1.586150e-02 -4.303565e+01 8.647568e-01 -8.194438e-03 5.021239e-01 3.594078e+02 +4.802148e-01 -2.320117e-02 -8.768441e-01 3.158173e+02 1.796425e-02 9.997006e-01 -1.661359e-02 -4.307502e+01 8.769669e-01 -7.773751e-03 4.804878e-01 3.597875e+02 +4.572741e-01 -2.251431e-02 -8.890408e-01 3.150938e+02 1.761347e-02 9.997127e-01 -1.625759e-02 -4.310995e+01 8.891514e-01 -8.224917e-03 4.575392e-01 3.601600e+02 +4.341238e-01 -2.032939e-02 -9.006238e-01 3.143618e+02 1.653725e-02 9.997567e-01 -1.459570e-02 -4.313938e+01 9.007014e-01 -8.557496e-03 4.343544e-01 3.605179e+02 +4.108635e-01 -1.773829e-02 -9.115243e-01 3.136081e+02 1.447465e-02 9.998116e-01 -1.293201e-02 -4.317263e+01 9.115819e-01 -7.880702e-03 4.110428e-01 3.608459e+02 +3.870292e-01 -1.509257e-02 -9.219440e-01 3.128526e+02 1.273081e-02 9.998582e-01 -1.102370e-02 -4.320575e+01 9.219796e-01 -7.470598e-03 3.871664e-01 3.611674e+02 +3.628216e-01 -1.361411e-02 -9.317592e-01 3.120879e+02 1.222052e-02 9.998768e-01 -9.850787e-03 -4.323864e+01 9.317785e-01 -7.812500e-03 3.629432e-01 3.614726e+02 +3.383548e-01 -1.128181e-02 -9.409510e-01 3.113023e+02 1.106730e-02 9.999067e-01 -8.009010e-03 -4.326709e+01 9.409535e-01 -7.703891e-03 3.384480e-01 3.617443e+02 +3.135180e-01 -9.848212e-03 -9.495312e-01 3.105092e+02 9.218821e-03 9.999306e-01 -7.327048e-03 -4.330316e+01 9.495375e-01 -6.456391e-03 3.135871e-01 3.620082e+02 +2.882750e-01 -8.273196e-03 -9.575120e-01 3.097106e+02 9.258633e-03 9.999400e-01 -5.852319e-03 -4.332902e+01 9.575029e-01 -7.178168e-03 2.883342e-01 3.622510e+02 +2.628288e-01 -6.002087e-03 -9.648238e-01 3.088893e+02 7.586758e-03 9.999626e-01 -4.153963e-03 -4.335378e+01 9.648126e-01 -6.228098e-03 2.628645e-01 3.624627e+02 +2.380108e-01 -3.771515e-03 -9.712552e-01 3.080691e+02 6.644646e-03 9.999754e-01 -2.254734e-03 -4.337697e+01 9.712397e-01 -5.916990e-03 2.380300e-01 3.626622e+02 +2.132955e-01 -2.720101e-03 -9.769840e-01 3.072347e+02 6.018318e-03 9.999808e-01 -1.470204e-03 -4.339127e+01 9.769692e-01 -5.566206e-03 2.133077e-01 3.628384e+02 +1.888201e-01 -2.318989e-03 -9.820090e-01 3.064024e+02 5.886118e-03 9.999819e-01 -1.229650e-03 -4.340737e+01 9.819940e-01 -5.548032e-03 1.888303e-01 3.630034e+02 +1.646083e-01 -1.182720e-03 -9.863583e-01 3.055606e+02 6.461235e-03 9.999791e-01 -1.207668e-04 -4.342616e+01 9.863378e-01 -6.353208e-03 1.646125e-01 3.631467e+02 +1.405588e-01 4.497024e-04 -9.900723e-01 3.046939e+02 5.815036e-03 9.999823e-01 1.279757e-03 -4.344036e+01 9.900552e-01 -5.937180e-03 1.405537e-01 3.632570e+02 +1.169484e-01 4.467543e-04 -9.931379e-01 3.038279e+02 7.163607e-03 9.999735e-01 1.293393e-03 -4.345298e+01 9.931121e-01 -7.265704e-03 1.169420e-01 3.633572e+02 +9.353947e-02 3.955199e-04 -9.956155e-01 3.029539e+02 8.475089e-03 9.999634e-01 1.193497e-03 -4.346251e+01 9.955795e-01 -8.549562e-03 9.353269e-02 3.634381e+02 +7.068056e-02 9.749116e-04 -9.974986e-01 3.020747e+02 9.518421e-03 9.999533e-01 1.651769e-03 -4.346698e+01 9.974535e-01 -9.611352e-03 7.066797e-02 3.634942e+02 +4.926206e-02 2.003349e-03 -9.987839e-01 3.012016e+02 9.114232e-03 9.999554e-01 2.455235e-03 -4.347012e+01 9.987443e-01 -9.224091e-03 4.924160e-02 3.635377e+02 +2.924290e-02 1.155252e-03 -9.995717e-01 3.003133e+02 7.922267e-03 9.999676e-01 1.387483e-03 -4.347982e+01 9.995409e-01 -7.959442e-03 2.923280e-02 3.635585e+02 +1.114497e-02 -3.379823e-03 -9.999322e-01 2.994302e+02 6.943831e-03 9.999704e-01 -3.302555e-03 -4.350670e+01 9.999137e-01 -6.906547e-03 1.116811e-02 3.635616e+02 +-5.634711e-03 -7.100259e-03 -9.999589e-01 2.985375e+02 5.515408e-03 9.999593e-01 -7.131338e-03 -4.352959e+01 9.999689e-01 -5.555358e-03 -5.595322e-03 3.635505e+02 +-2.086277e-02 -8.575207e-03 -9.997456e-01 2.976318e+02 4.132404e-03 9.999539e-01 -8.663226e-03 -4.354233e+01 9.997738e-01 -4.312086e-03 -2.082637e-02 3.635226e+02 +-3.424904e-02 -8.421958e-03 -9.993779e-01 2.967236e+02 2.479032e-03 9.999607e-01 -8.511824e-03 -4.356106e+01 9.994102e-01 -2.769005e-03 -3.422682e-02 3.634866e+02 +-4.605007e-02 -7.507866e-03 -9.989109e-01 2.958065e+02 3.886030e-04 9.999715e-01 -7.533749e-03 -4.358126e+01 9.989390e-01 -7.351041e-04 -4.604584e-02 3.634401e+02 +-5.611352e-02 -6.146201e-03 -9.984055e-01 2.948851e+02 -2.728614e-03 9.999782e-01 -6.002523e-03 -4.359939e+01 9.984206e-01 2.387445e-03 -5.612906e-02 3.633810e+02 +-6.425941e-02 -5.126280e-03 -9.979201e-01 2.939599e+02 -5.290804e-03 9.999745e-01 -4.796137e-03 -4.361879e+01 9.979192e-01 4.971607e-03 -6.428489e-02 3.633179e+02 +-7.094122e-02 -4.747209e-03 -9.974692e-01 2.930319e+02 -9.073617e-03 9.999503e-01 -4.113688e-03 -4.363690e+01 9.974392e-01 8.758827e-03 -7.098077e-02 3.632453e+02 +-7.627125e-02 -6.050828e-03 -9.970688e-01 2.921042e+02 -1.056828e-02 9.999303e-01 -5.259764e-03 -4.365327e+01 9.970311e-01 1.013614e-02 -7.632987e-02 3.631723e+02 +-8.151479e-02 -8.035718e-03 -9.966398e-01 2.911722e+02 -1.199151e-02 9.999030e-01 -7.081245e-03 -4.366845e+01 9.965999e-01 1.137399e-02 -8.160324e-02 3.630961e+02 +-8.644396e-02 -9.756648e-03 -9.962090e-01 2.902382e+02 -1.118088e-02 9.998985e-01 -8.822582e-03 -4.368846e+01 9.961939e-01 1.037584e-02 -8.654427e-02 3.630176e+02 +-9.134741e-02 -1.292016e-02 -9.957353e-01 2.893009e+02 -8.223219e-03 9.998915e-01 -1.221970e-02 -4.371541e+01 9.957851e-01 7.071915e-03 -9.144374e-02 3.629390e+02 +-9.629932e-02 -1.763546e-02 -9.951962e-01 2.883655e+02 -4.908298e-03 9.998393e-01 -1.724278e-02 -4.374486e+01 9.953403e-01 3.224256e-03 -9.637039e-02 3.628565e+02 +-1.011083e-01 -1.881933e-02 -9.946974e-01 2.874297e+02 -4.261447e-03 9.998201e-01 -1.848308e-02 -4.376965e+01 9.948663e-01 2.370062e-03 -1.011703e-01 3.627691e+02 +-1.053444e-01 -1.427812e-02 -9.943333e-01 2.864910e+02 -2.797909e-03 9.998972e-01 -1.406159e-02 -4.379557e+01 9.944318e-01 1.300750e-03 -1.053735e-01 3.626785e+02 +-1.089125e-01 -7.439055e-03 -9.940235e-01 2.855492e+02 -2.798925e-03 9.999703e-01 -7.176885e-03 -4.382227e+01 9.940474e-01 2.000550e-03 -1.089301e-01 3.625827e+02 +-1.107486e-01 -6.910399e-03 -9.938245e-01 2.846186e+02 -6.231295e-03 9.999610e-01 -6.258669e-03 -4.384556e+01 9.938289e-01 5.499679e-03 -1.107874e-01 3.624774e+02 +-1.108717e-01 -9.216390e-03 -9.937920e-01 2.836935e+02 -9.514740e-03 9.999210e-01 -8.211722e-03 -4.386993e+01 9.937891e-01 8.545229e-03 -1.109506e-01 3.623702e+02 +-1.102942e-01 -1.329148e-02 -9.938101e-01 2.827670e+02 -1.052543e-02 9.998701e-01 -1.220440e-02 -4.389688e+01 9.938432e-01 9.114211e-03 -1.104198e-01 3.622727e+02 +-1.088514e-01 -1.673875e-02 -9.939171e-01 2.818446e+02 -9.932938e-03 9.998266e-01 -1.575044e-02 -4.392577e+01 9.940084e-01 8.158063e-03 -1.089988e-01 3.621813e+02 +-1.072588e-01 -1.856848e-02 -9.940578e-01 2.809206e+02 -8.070502e-03 9.998089e-01 -1.780510e-02 -4.395510e+01 9.941983e-01 6.112796e-03 -1.073881e-01 3.620980e+02 +-1.051630e-01 -1.933957e-02 -9.942670e-01 2.799996e+02 -5.596696e-03 9.998065e-01 -1.885536e-02 -4.398713e+01 9.944392e-01 3.581727e-03 -1.052509e-01 3.620134e+02 +-1.020811e-01 -2.024303e-02 -9.945701e-01 2.790830e+02 -3.952528e-03 9.997933e-01 -1.994365e-02 -4.402136e+01 9.947682e-01 1.895201e-03 -1.021400e-01 3.619348e+02 +-9.798115e-02 -2.112159e-02 -9.949641e-01 2.781690e+02 -1.499054e-03 9.997767e-01 -2.107613e-02 -4.405608e+01 9.951871e-01 -5.735536e-04 -9.799093e-02 3.618574e+02 +-9.297707e-02 -2.307830e-02 -9.954008e-01 2.772589e+02 -1.123788e-03 9.997331e-01 -2.307377e-02 -4.409029e+01 9.956676e-01 -1.026707e-03 -9.297818e-02 3.617862e+02 +-8.668897e-02 -2.480178e-02 -9.959267e-01 2.763529e+02 -2.730486e-04 9.996906e-01 -2.487174e-02 -4.412636e+01 9.962353e-01 -1.884164e-03 -8.666891e-02 3.617183e+02 +-7.991981e-02 -2.623437e-02 -9.964560e-01 2.754468e+02 9.336814e-04 9.996512e-01 -2.639338e-02 -4.416111e+01 9.968008e-01 -3.039720e-03 -7.986744e-02 3.616574e+02 +-7.164154e-02 -2.688511e-02 -9.970681e-01 2.745422e+02 1.518209e-03 9.996325e-01 -2.706334e-02 -4.419929e+01 9.974292e-01 -3.452612e-03 -7.157439e-02 3.616032e+02 +-6.268829e-02 -2.823510e-02 -9.976337e-01 2.736390e+02 2.650326e-03 9.995915e-01 -2.845704e-02 -4.423850e+01 9.980296e-01 -4.427972e-03 -6.258784e-02 3.615578e+02 +-5.367250e-02 -2.960456e-02 -9.981197e-01 2.727370e+02 4.466147e-03 9.995433e-01 -2.988694e-02 -4.427672e+01 9.985486e-01 -6.061850e-03 -5.351576e-02 3.615198e+02 +-4.355823e-02 -3.164381e-02 -9.985497e-01 2.718374e+02 4.295818e-03 9.994831e-01 -3.186078e-02 -4.431633e+01 9.990416e-01 -5.677380e-03 -4.339978e-02 3.614891e+02 +-3.241846e-02 -3.234671e-02 -9.989508e-01 2.709346e+02 4.844284e-03 9.994593e-01 -3.252038e-02 -4.435729e+01 9.994626e-01 -5.893456e-03 -3.224424e-02 3.614656e+02 +-2.014713e-02 -3.277079e-02 -9.992598e-01 2.700356e+02 4.899530e-03 9.994474e-01 -3.287572e-02 -4.440261e+01 9.997850e-01 -5.558248e-03 -1.997543e-02 3.614550e+02 +-6.203883e-03 -3.240378e-02 -9.994556e-01 2.691336e+02 5.333146e-03 9.994595e-01 -3.243701e-02 -4.444696e+01 9.999665e-01 -5.531472e-03 -6.027717e-03 3.614582e+02 +8.865310e-03 -3.068540e-02 -9.994898e-01 2.682285e+02 4.702259e-03 9.995193e-01 -3.064460e-02 -4.449161e+01 9.999496e-01 -4.428180e-03 9.005337e-03 3.614685e+02 +2.434982e-02 -3.025544e-02 -9.992456e-01 2.673277e+02 5.443249e-03 9.995311e-01 -3.013144e-02 -4.453555e+01 9.996886e-01 -4.705442e-03 2.450308e-02 3.614977e+02 +3.973084e-02 -3.153929e-02 -9.987126e-01 2.664269e+02 7.029380e-03 9.994858e-01 -3.128407e-02 -4.457871e+01 9.991857e-01 -5.777381e-03 3.993210e-02 3.615379e+02 +5.484618e-02 -3.200098e-02 -9.979819e-01 2.655290e+02 7.895823e-03 9.994689e-01 -3.161474e-02 -4.461683e+01 9.984636e-01 -6.145935e-03 5.506972e-02 3.616000e+02 +7.006432e-02 -3.129978e-02 -9.970513e-01 2.646304e+02 1.021857e-02 9.994777e-01 -3.065788e-02 -4.465564e+01 9.974901e-01 -8.040413e-03 7.034756e-02 3.616760e+02 +8.484743e-02 -3.149215e-02 -9.958962e-01 2.637298e+02 1.321252e-02 9.994481e-01 -3.047880e-02 -4.469721e+01 9.963063e-01 -1.057225e-02 8.521668e-02 3.617619e+02 +9.999068e-02 -3.403507e-02 -9.944061e-01 2.628312e+02 1.485687e-02 9.993544e-01 -3.271052e-02 -4.474314e+01 9.948774e-01 -1.150300e-02 1.004318e-01 3.618659e+02 +1.148543e-01 -3.914489e-02 -9.926108e-01 2.619403e+02 1.546651e-02 9.991726e-01 -3.761405e-02 -4.478819e+01 9.932619e-01 -1.103209e-02 1.153647e-01 3.619799e+02 +1.296329e-01 -4.401644e-02 -9.905846e-01 2.610436e+02 1.798333e-02 9.989543e-01 -4.203495e-02 -4.483401e+01 9.913989e-01 -1.236489e-02 1.302889e-01 3.621087e+02 +1.445669e-01 -4.661470e-02 -9.883964e-01 2.601499e+02 2.053394e-02 9.988159e-01 -4.410272e-02 -4.487971e+01 9.892819e-01 -1.391986e-02 1.453529e-01 3.622559e+02 +1.600443e-01 -4.479077e-02 -9.860931e-01 2.592509e+02 1.923246e-02 9.989218e-01 -4.225202e-02 -4.492851e+01 9.869224e-01 -1.220280e-02 1.607332e-01 3.624130e+02 +1.759957e-01 -4.172860e-02 -9.835061e-01 2.583525e+02 1.791012e-02 9.990715e-01 -3.918404e-02 -4.498115e+01 9.842279e-01 -1.071848e-02 1.765797e-01 3.625763e+02 +1.915950e-01 -4.161613e-02 -9.805914e-01 2.574629e+02 1.862011e-02 9.990749e-01 -3.876244e-02 -4.502768e+01 9.812974e-01 -1.083203e-02 1.921926e-01 3.627633e+02 +2.080022e-01 -4.378835e-02 -9.771478e-01 2.565736e+02 1.936197e-02 9.989860e-01 -4.064546e-02 -4.507509e+01 9.779367e-01 -1.046515e-02 2.086391e-01 3.629599e+02 +2.241509e-01 -4.406803e-02 -9.735576e-01 2.556860e+02 2.097258e-02 9.989639e-01 -4.038934e-02 -4.512034e+01 9.743287e-01 -1.136471e-02 2.248428e-01 3.631819e+02 +2.409032e-01 -4.473121e-02 -9.695178e-01 2.548028e+02 1.970445e-02 9.989569e-01 -4.119335e-02 -4.517233e+01 9.703491e-01 -9.180202e-03 2.415333e-01 3.634150e+02 +2.582305e-01 -4.571736e-02 -9.650010e-01 2.539173e+02 1.806500e-02 9.989335e-01 -4.249081e-02 -4.522560e+01 9.659144e-01 -6.460316e-03 2.587810e-01 3.636553e+02 +2.761769e-01 -5.144002e-02 -9.597293e-01 2.530459e+02 1.700012e-02 9.986719e-01 -4.863524e-02 -4.528030e+01 9.609564e-01 -2.883584e-03 2.766845e-01 3.639182e+02 +2.945875e-01 -5.435063e-02 -9.540777e-01 2.521699e+02 1.597667e-02 9.985219e-01 -5.194940e-02 -4.533774e+01 9.554909e-01 6.066863e-05 2.950204e-01 3.642027e+02 +3.138636e-01 -5.305055e-02 -9.479849e-01 2.512884e+02 1.352605e-02 9.985863e-01 -5.140401e-02 -4.539942e+01 9.493717e-01 3.311366e-03 3.141375e-01 3.644970e+02 +3.331467e-01 -4.839769e-02 -9.416321e-01 2.504117e+02 1.159496e-02 9.988165e-01 -4.723458e-02 -4.547218e+01 9.428037e-01 4.817866e-03 3.333136e-01 3.648207e+02 +3.522030e-01 -4.603969e-02 -9.347906e-01 2.495403e+02 1.012444e-02 9.989183e-01 -4.538347e-02 -4.554290e+01 9.358688e-01 6.519962e-03 3.522881e-01 3.651489e+02 +3.709662e-01 -4.849607e-02 -9.273792e-01 2.486803e+02 1.300166e-02 9.988088e-01 -4.703052e-02 -4.561075e+01 9.285553e-01 5.389268e-03 3.711549e-01 3.655049e+02 +3.901007e-01 -4.953980e-02 -9.194386e-01 2.478138e+02 1.381542e-02 9.987541e-01 -4.795174e-02 -4.569397e+01 9.206685e-01 6.003583e-03 3.902990e-01 3.658787e+02 +4.090518e-01 -4.912110e-02 -9.111881e-01 2.469495e+02 1.214778e-02 9.987547e-01 -4.838832e-02 -4.576825e+01 9.124302e-01 8.724421e-03 4.091391e-01 3.662595e+02 +4.277848e-01 -4.858087e-02 -9.025742e-01 2.460947e+02 1.116366e-02 9.987624e-01 -4.846704e-02 -4.584994e+01 9.038117e-01 1.065744e-02 4.277976e-01 3.666669e+02 +4.462796e-01 -4.905028e-02 -8.935484e-01 2.452516e+02 1.099320e-02 9.987219e-01 -4.933315e-02 -4.593119e+01 8.948260e-01 1.219343e-02 4.462483e-01 3.670926e+02 +4.650522e-01 -4.920691e-02 -8.839147e-01 2.444040e+02 1.096933e-02 9.986977e-01 -4.982553e-02 -4.602106e+01 8.852153e-01 1.347553e-02 4.649863e-01 3.675267e+02 +4.836740e-01 -4.793379e-02 -8.739347e-01 2.435626e+02 1.053965e-02 9.987458e-01 -4.894635e-02 -4.609848e+01 8.751847e-01 1.446311e-02 4.835726e-01 3.679940e+02 +5.019996e-01 -4.493285e-02 -8.636999e-01 2.427218e+02 1.013562e-02 9.988866e-01 -4.607474e-02 -4.617227e+01 8.648085e-01 1.437537e-02 5.018960e-01 3.684728e+02 +5.200606e-01 -4.390730e-02 -8.530001e-01 2.418990e+02 1.051530e-02 9.989313e-01 -4.500796e-02 -4.623809e+01 8.540646e-01 1.443732e-02 5.199665e-01 3.689809e+02 +5.378601e-01 -4.311821e-02 -8.419307e-01 2.410833e+02 1.142936e-02 9.989723e-01 -4.385932e-02 -4.630218e+01 8.429566e-01 1.396745e-02 5.378002e-01 3.695083e+02 +5.553278e-01 -4.300217e-02 -8.305191e-01 2.402685e+02 1.237552e-02 9.989789e-01 -4.344970e-02 -4.637947e+01 8.315394e-01 1.385072e-02 5.552929e-01 3.700436e+02 +5.722742e-01 -4.338950e-02 -8.189137e-01 2.394766e+02 1.326239e-02 9.989583e-01 -4.366099e-02 -4.645233e+01 8.199551e-01 1.412530e-02 5.722535e-01 3.706015e+02 +5.888382e-01 -4.573194e-02 -8.069562e-01 2.386973e+02 1.530293e-02 9.988498e-01 -4.544038e-02 -4.652478e+01 8.081060e-01 1.440824e-02 5.888607e-01 3.711749e+02 +6.049183e-01 -4.916971e-02 -7.947680e-01 2.379307e+02 1.954691e-02 9.987079e-01 -4.690916e-02 -4.658844e+01 7.960476e-01 1.284095e-02 6.050978e-01 3.717584e+02 +6.202974e-01 -5.169873e-02 -7.826612e-01 2.371792e+02 2.491996e-02 9.986207e-01 -4.621367e-02 -4.665505e+01 7.839708e-01 9.162337e-03 6.207300e-01 3.723676e+02 +6.352452e-01 -5.220725e-02 -7.705440e-01 2.364322e+02 2.887410e-02 9.986205e-01 -4.385617e-02 -4.672738e+01 7.717706e-01 5.610656e-03 6.358762e-01 3.729839e+02 +6.498392e-01 -5.232495e-02 -7.582685e-01 2.357011e+02 3.192866e-02 9.986262e-01 -4.154804e-02 -4.680192e+01 7.594008e-01 2.789049e-03 6.506171e-01 3.736192e+02 +6.636797e-01 -5.585751e-02 -7.459285e-01 2.349911e+02 3.666872e-02 9.984385e-01 -4.214079e-02 -4.686665e+01 7.471176e-01 6.157494e-04 6.646916e-01 3.742660e+02 +6.773904e-01 -5.829528e-02 -7.333103e-01 2.342824e+02 3.729471e-02 9.982946e-01 -4.490976e-02 -4.692759e+01 7.346778e-01 3.072851e-03 6.784092e-01 3.749156e+02 +6.912135e-01 -5.817305e-02 -7.203054e-01 2.335888e+02 3.841827e-02 9.983032e-01 -4.375800e-02 -4.698987e+01 7.216287e-01 2.573230e-03 6.922755e-01 3.755860e+02 +7.047724e-01 -5.645867e-02 -7.071834e-01 2.329005e+02 3.849533e-02 9.984031e-01 -4.134439e-02 -4.706178e+01 7.083883e-01 1.915128e-03 7.058203e-01 3.762719e+02 +7.180338e-01 -5.617017e-02 -6.937381e-01 2.322214e+02 3.991932e-02 9.984210e-01 -3.952220e-02 -4.713409e+01 6.948626e-01 6.847261e-04 7.191422e-01 3.769651e+02 +7.309217e-01 -5.689314e-02 -6.800858e-01 2.315636e+02 4.146177e-02 9.983802e-01 -3.895934e-02 -4.719660e+01 6.812007e-01 2.786678e-04 7.320966e-01 3.776779e+02 +7.435284e-01 -5.956078e-02 -6.660466e-01 2.309157e+02 4.397281e-02 9.982245e-01 -4.017738e-02 -4.725892e+01 6.672570e-01 5.850866e-04 7.448272e-01 3.783972e+02 +7.559557e-01 -5.899181e-02 -6.519593e-01 2.302839e+02 4.403885e-02 9.982580e-01 -3.926262e-02 -4.732254e+01 6.531397e-01 9.692693e-04 7.572367e-01 3.791360e+02 +7.684172e-01 -5.661870e-02 -6.374397e-01 2.296556e+02 4.260429e-02 9.983947e-01 -3.732110e-02 -4.739820e+01 6.385295e-01 1.520507e-03 7.695958e-01 3.798865e+02 +7.805448e-01 -5.427531e-02 -6.227392e-01 2.290420e+02 4.169653e-02 9.985253e-01 -3.476458e-02 -4.745996e+01 6.237077e-01 1.169247e-03 7.816567e-01 3.806398e+02 +7.932214e-01 -4.989191e-02 -6.068861e-01 2.284454e+02 3.636295e-02 9.987402e-01 -3.457847e-02 -4.752080e+01 6.078467e-01 5.360209e-03 7.940362e-01 3.814086e+02 +8.061105e-01 -4.703543e-02 -5.898929e-01 2.278707e+02 3.284888e-02 9.988558e-01 -3.475511e-02 -4.758149e+01 5.908526e-01 8.639141e-03 8.067332e-01 3.821899e+02 +8.184787e-01 -4.416770e-02 -5.728367e-01 2.273043e+02 3.078172e-02 9.989798e-01 -3.304339e-02 -4.765069e+01 5.737117e-01 9.412418e-03 8.190032e-01 3.829774e+02 +8.301935e-01 -4.334930e-02 -5.557875e-01 2.267627e+02 3.179200e-02 9.990311e-01 -3.043214e-02 -4.771692e+01 5.565682e-01 7.594969e-03 8.307672e-01 3.837895e+02 +8.415708e-01 -4.220760e-02 -5.384953e-01 2.262311e+02 3.257121e-02 9.990936e-01 -2.740667e-02 -4.778155e+01 5.391640e-01 5.525206e-03 8.421826e-01 3.846046e+02 +8.525766e-01 -4.279017e-02 -5.208476e-01 2.257277e+02 3.408525e-02 9.990732e-01 -2.628452e-02 -4.783365e+01 5.214895e-01 4.656349e-03 8.532449e-01 3.854392e+02 +8.629983e-01 -4.330093e-02 -5.033479e-01 2.252403e+02 3.524647e-02 9.990529e-01 -2.551374e-02 -4.788335e+01 5.039759e-01 4.277078e-03 8.637071e-01 3.862842e+02 +8.732564e-01 -4.385226e-02 -4.852837e-01 2.247615e+02 3.632393e-02 9.990295e-01 -2.491243e-02 -4.794630e+01 4.859052e-01 4.127523e-03 8.740017e-01 3.871299e+02 +8.833688e-01 -4.381467e-02 -4.666261e-01 2.243070e+02 3.651271e-02 9.990283e-01 -2.468337e-02 -4.800855e+01 4.672541e-01 4.766736e-03 8.841102e-01 3.879972e+02 +8.932562e-01 -4.401924e-02 -4.473877e-01 2.238705e+02 3.690960e-02 9.990157e-01 -2.460103e-02 -4.807293e+01 4.480303e-01 5.462122e-03 8.940016e-01 3.888753e+02 +9.028500e-01 -4.413645e-02 -4.276843e-01 2.234464e+02 3.748569e-02 9.990098e-01 -2.396346e-02 -4.812474e+01 4.283185e-01 5.603364e-03 9.036104e-01 3.897599e+02 +9.120668e-01 -4.422922e-02 -4.076493e-01 2.230451e+02 3.813855e-02 9.990063e-01 -2.305995e-02 -4.817623e+01 4.082642e-01 5.485061e-03 9.128473e-01 3.906671e+02 +9.208511e-01 -4.358881e-02 -3.874705e-01 2.226518e+02 3.821961e-02 9.990368e-01 -2.155587e-02 -4.823596e+01 3.880369e-01 5.040780e-03 9.216300e-01 3.915768e+02 +9.291448e-01 -4.360995e-02 -3.671350e-01 2.222866e+02 3.916216e-02 9.990414e-01 -1.955912e-02 -4.829510e+01 3.676360e-01 3.795462e-03 9.299620e-01 3.925113e+02 +9.371199e-01 -4.350790e-02 -3.462851e-01 2.219429e+02 3.953041e-02 9.990462e-01 -1.854449e-02 -4.834148e+01 3.467616e-01 3.689625e-03 9.379460e-01 3.934576e+02 +9.446237e-01 -4.315267e-02 -3.253061e-01 2.216103e+02 3.970364e-02 9.990628e-01 -1.723677e-02 -4.838564e+01 3.257451e-01 3.366426e-03 9.454516e-01 3.944076e+02 +9.516753e-01 -4.176640e-02 -3.042528e-01 2.213031e+02 3.865354e-02 9.991205e-01 -1.624982e-02 -4.842351e+01 3.046639e-01 3.704108e-03 9.524527e-01 3.953800e+02 +9.582783e-01 -3.971931e-02 -2.830639e-01 2.210093e+02 3.691878e-02 9.992023e-01 -1.522328e-02 -4.847463e+01 2.834428e-01 4.137767e-03 9.589802e-01 3.963636e+02 +9.643937e-01 -3.820810e-02 -2.616963e-01 2.207316e+02 3.542933e-02 9.992546e-01 -1.533000e-02 -4.852659e+01 2.620869e-01 5.512430e-03 9.650285e-01 3.973467e+02 +9.700968e-01 -3.616898e-02 -2.400085e-01 2.204810e+02 3.343651e-02 9.993214e-01 -1.544858e-02 -4.857114e+01 2.404044e-01 6.961568e-03 9.706478e-01 3.983491e+02 +9.751754e-01 -3.551022e-02 -2.185682e-01 2.202472e+02 3.236033e-02 9.993146e-01 -1.797559e-02 -4.861532e+01 2.190567e-01 1.045641e-02 9.756560e-01 3.993509e+02 +9.797919e-01 -3.341323e-02 -1.972092e-01 2.200361e+02 3.026534e-02 9.993621e-01 -1.895543e-02 -4.866537e+01 1.977168e-01 1.260378e-02 9.801781e-01 4.003749e+02 +9.838821e-01 -2.986410e-02 -1.763071e-01 2.198367e+02 2.687762e-02 9.994523e-01 -1.930350e-02 -4.872229e+01 1.767870e-01 1.425366e-02 9.841459e-01 4.014170e+02 +9.874589e-01 -2.657881e-02 -1.556235e-01 2.196530e+02 2.428197e-02 9.995666e-01 -1.664176e-02 -4.876299e+01 1.559983e-01 1.265421e-02 9.876762e-01 4.024705e+02 +9.904997e-01 -2.270003e-02 -1.356284e-01 2.194927e+02 2.107959e-02 9.996883e-01 -1.337208e-02 -4.880298e+01 1.358897e-01 1.038605e-02 9.906695e-01 4.035460e+02 +9.930877e-01 -1.941800e-02 -1.157578e-01 2.193562e+02 1.823943e-02 9.997705e-01 -1.123203e-02 -4.883562e+01 1.159493e-01 9.043033e-03 9.932139e-01 4.046346e+02 +9.951887e-01 -1.625025e-02 -9.661990e-02 2.192302e+02 1.535602e-02 9.998321e-01 -9.991606e-03 -4.887915e+01 9.676604e-02 8.459836e-03 9.952711e-01 4.057221e+02 +9.968971e-01 -1.291808e-02 -7.764866e-02 2.191311e+02 1.232199e-02 9.998908e-01 -8.151028e-03 -4.891744e+01 7.774547e-02 7.168950e-03 9.969474e-01 4.068297e+02 +9.981981e-01 -1.244384e-02 -5.870053e-02 2.190564e+02 1.207841e-02 9.999054e-01 -6.576068e-03 -4.895230e+01 5.877680e-02 5.855209e-03 9.982539e-01 4.079420e+02 +9.991289e-01 -1.009771e-02 -4.049026e-02 2.189905e+02 9.828386e-03 9.999282e-01 -6.845259e-03 -4.898368e+01 4.055648e-02 6.441342e-03 9.991564e-01 4.090537e+02 +9.997008e-01 -9.651129e-03 -2.247659e-02 2.189549e+02 9.476323e-03 9.999241e-01 -7.870880e-03 -4.901651e+01 2.255084e-02 7.655529e-03 9.997163e-01 4.101762e+02 +9.999210e-01 -1.147096e-02 -5.146388e-03 2.189366e+02 1.143735e-02 9.999134e-01 -6.513213e-03 -4.905613e+01 5.220655e-03 6.453837e-03 9.999655e-01 4.112973e+02 +9.998567e-01 -1.206689e-02 1.187508e-02 2.189394e+02 1.211486e-02 9.999187e-01 -3.976268e-03 -4.909352e+01 -1.182613e-02 4.119563e-03 9.999215e-01 4.124328e+02 +9.995200e-01 -1.278743e-02 2.821913e-02 2.189610e+02 1.287833e-02 9.999124e-01 -3.041996e-03 -4.912863e+01 -2.817776e-02 3.403951e-03 9.995971e-01 4.135661e+02 +9.989309e-01 -1.479148e-02 4.379882e-02 2.190027e+02 1.494188e-02 9.998835e-01 -3.108469e-03 -4.915265e+01 -4.374773e-02 3.759582e-03 9.990355e-01 4.146952e+02 +9.981154e-01 -1.764750e-02 5.877351e-02 2.190648e+02 1.782863e-02 9.998378e-01 -2.558812e-03 -4.917918e+01 -5.871881e-02 3.601840e-03 9.982680e-01 4.158316e+02 +9.970853e-01 -2.426935e-02 7.233206e-02 2.191459e+02 2.452987e-02 9.996954e-01 -2.715492e-03 -4.921616e+01 -7.224412e-02 4.481873e-03 9.973769e-01 4.169679e+02 +9.960874e-01 -2.839365e-02 8.368831e-02 2.192317e+02 2.888368e-02 9.995719e-01 -4.650259e-03 -4.925012e+01 -8.352044e-02 7.049289e-03 9.964811e-01 4.181039e+02 +9.950753e-01 -3.443037e-02 9.295092e-02 2.193371e+02 3.479042e-02 9.993921e-01 -2.255436e-03 -4.927663e+01 -9.281675e-02 5.478129e-03 9.956681e-01 4.192432e+02 +9.941419e-01 -3.857510e-02 1.009651e-01 2.194519e+02 3.845286e-02 9.992554e-01 3.157319e-03 -4.930084e+01 -1.010117e-01 7.435728e-04 9.948849e-01 4.203897e+02 +9.932120e-01 -3.977426e-02 1.093071e-01 2.195701e+02 3.936321e-02 9.992074e-01 5.916710e-03 -4.932401e+01 -1.094558e-01 -1.573868e-03 9.939904e-01 4.215272e+02 +9.922285e-01 -4.018453e-02 1.177619e-01 2.196975e+02 3.998394e-02 9.991920e-01 4.066370e-03 -4.935388e+01 -1.178302e-01 6.738157e-04 9.930335e-01 4.226680e+02 +9.912858e-01 -3.883125e-02 1.258753e-01 2.198298e+02 3.872584e-02 9.992445e-01 3.285320e-03 -4.938370e+01 -1.259078e-01 1.617936e-03 9.920406e-01 4.238066e+02 +9.902435e-01 -3.878268e-02 1.338422e-01 2.199796e+02 3.873736e-02 9.992451e-01 2.943632e-03 -4.940850e+01 -1.338553e-01 2.269780e-03 9.909982e-01 4.249678e+02 +9.892188e-01 -3.940265e-02 1.410453e-01 2.201363e+02 3.929151e-02 9.992214e-01 3.573919e-03 -4.943443e+01 -1.410763e-01 2.006493e-03 9.899966e-01 4.260926e+02 +9.880421e-01 -4.364310e-02 1.478788e-01 2.203105e+02 4.320854e-02 9.990471e-01 6.151420e-03 -4.944961e+01 -1.480063e-01 3.117640e-04 9.889863e-01 4.272372e+02 +9.871602e-01 -4.621065e-02 1.529031e-01 2.204887e+02 4.541462e-02 9.989303e-01 8.696487e-03 -4.948054e+01 -1.531415e-01 -1.640788e-03 9.882029e-01 4.283867e+02 +9.863586e-01 -5.105812e-02 1.564922e-01 2.206781e+02 5.044358e-02 9.986957e-01 7.898561e-03 -4.949522e+01 -1.566914e-01 1.032141e-04 9.876476e-01 4.295347e+02 +9.858317e-01 -5.323070e-02 1.590675e-01 2.208689e+02 5.273075e-02 9.985816e-01 7.365200e-03 -4.950951e+01 -1.592340e-01 1.126903e-03 9.872402e-01 4.306848e+02 +9.854620e-01 -5.357890e-02 1.612265e-01 2.210593e+02 5.289232e-02 9.985636e-01 8.550555e-03 -4.952103e+01 -1.614531e-01 1.013967e-04 9.868803e-01 4.318406e+02 +9.851158e-01 -5.341312e-02 1.633826e-01 2.212494e+02 5.244499e-02 9.985713e-01 1.023625e-02 -4.954229e+01 -1.636959e-01 -1.515292e-03 9.865096e-01 4.329996e+02 +9.848710e-01 -5.198165e-02 1.653093e-01 2.214414e+02 5.114277e-02 9.986477e-01 9.329993e-03 -4.956037e+01 -1.655707e-01 -7.344657e-04 9.861976e-01 4.341619e+02 +9.846097e-01 -5.089498e-02 1.671933e-01 2.216359e+02 5.029622e-02 9.987037e-01 7.816529e-03 -4.957560e+01 -1.673744e-01 7.129586e-04 9.858931e-01 4.353259e+02 +9.843181e-01 -5.078766e-02 1.689338e-01 2.218356e+02 5.026359e-02 9.987087e-01 7.379952e-03 -4.959405e+01 -1.690905e-01 1.227001e-03 9.855997e-01 4.364909e+02 +9.840181e-01 -5.074130e-02 1.706860e-01 2.220385e+02 4.995816e-02 9.987118e-01 8.883018e-03 -4.960949e+01 -1.709168e-01 -2.138943e-04 9.852854e-01 4.376634e+02 +9.838335e-01 -5.030295e-02 1.718757e-01 2.222454e+02 4.934525e-02 9.987333e-01 9.842694e-03 -4.964017e+01 -1.721530e-01 -1.202325e-03 9.850694e-01 4.388358e+02 +9.836673e-01 -5.097929e-02 1.726265e-01 2.224578e+02 4.999182e-02 9.986989e-01 1.006597e-02 -4.965998e+01 -1.729151e-01 -1.271651e-03 9.849359e-01 4.400148e+02 +9.835419e-01 -5.107547e-02 1.733112e-01 2.226742e+02 5.029823e-02 9.986948e-01 8.876497e-03 -4.968619e+01 -1.735383e-01 -1.316179e-05 9.848271e-01 4.411924e+02 +9.834312e-01 -5.226865e-02 1.735833e-01 2.228912e+02 5.159496e-02 9.986328e-01 8.394262e-03 -4.970076e+01 -1.737848e-01 7.008452e-04 9.847834e-01 4.423782e+02 +9.833499e-01 -5.422351e-02 1.734443e-01 2.231108e+02 5.348155e-02 9.985287e-01 8.951938e-03 -4.972005e+01 -1.736745e-01 4.731843e-04 9.848029e-01 4.435699e+02 +9.834716e-01 -5.332785e-02 1.730315e-01 2.233247e+02 5.248768e-02 9.985770e-01 9.430808e-03 -4.974417e+01 -1.732882e-01 -1.929069e-04 9.848711e-01 4.447664e+02 +9.834817e-01 -5.330342e-02 1.729817e-01 2.235434e+02 5.274110e-02 9.985774e-01 7.848726e-03 -4.976658e+01 -1.731539e-01 1.404164e-03 9.848937e-01 4.459677e+02 +9.834939e-01 -5.232787e-02 1.732096e-01 2.237601e+02 5.192739e-02 9.986274e-01 6.845932e-03 -4.978412e+01 -1.733301e-01 2.261390e-03 9.848611e-01 4.471766e+02 +9.834752e-01 -5.095009e-02 1.737257e-01 2.239768e+02 5.043179e-02 9.987001e-01 7.399315e-03 -4.979825e+01 -1.738768e-01 1.484254e-03 9.847662e-01 4.483904e+02 +9.834289e-01 -5.079520e-02 1.740330e-01 2.241973e+02 4.987140e-02 9.987087e-01 9.680040e-03 -4.981179e+01 -1.743000e-01 -8.403612e-04 9.846922e-01 4.496060e+02 +9.833095e-01 -5.206343e-02 1.743326e-01 2.244204e+02 5.077459e-02 9.986398e-01 1.184794e-02 -4.983187e+01 -1.747123e-01 -2.798522e-03 9.846155e-01 4.508301e+02 +9.831394e-01 -5.317039e-02 1.749568e-01 2.246451e+02 5.188174e-02 9.985819e-01 1.193441e-02 -4.985414e+01 -1.753432e-01 -2.656130e-03 9.845037e-01 4.520526e+02 +9.830364e-01 -5.323534e-02 1.755149e-01 2.248697e+02 5.226502e-02 9.985816e-01 1.014969e-02 -4.986755e+01 -1.758063e-01 -8.042282e-04 9.844244e-01 4.532755e+02 +9.830446e-01 -5.081971e-02 1.761837e-01 2.250968e+02 4.972310e-02 9.987064e-01 1.063635e-02 -4.988096e+01 -1.764963e-01 -1.695606e-03 9.842998e-01 4.545047e+02 +9.827653e-01 -5.133767e-02 1.775860e-01 2.253263e+02 4.962809e-02 9.986688e-01 1.405837e-02 -4.988756e+01 -1.780713e-01 -5.002824e-03 9.840048e-01 4.557380e+02 +9.827591e-01 -4.527461e-02 1.792619e-01 2.255500e+02 4.328073e-02 9.989500e-01 1.502017e-02 -4.990513e+01 -1.797537e-01 -7.002623e-03 9.836867e-01 4.569749e+02 +9.823815e-01 -4.451891e-02 1.815071e-01 2.257775e+02 4.267009e-02 9.989900e-01 1.408010e-02 -4.991188e+01 -1.819505e-01 -6.087104e-03 9.832888e-01 4.582064e+02 +9.820539e-01 -4.436349e-02 1.833085e-01 2.260135e+02 4.263551e-02 9.990014e-01 1.335899e-02 -4.992256e+01 -1.837181e-01 -5.303800e-03 9.829646e-01 4.594382e+02 +9.815838e-01 -4.492089e-02 1.856754e-01 2.262505e+02 4.388215e-02 9.989896e-01 9.702381e-03 -4.993232e+01 -1.859236e-01 -1.375863e-03 9.825632e-01 4.606683e+02 +9.810347e-01 -5.027231e-02 1.871999e-01 2.264965e+02 4.946603e-02 9.987354e-01 8.978936e-03 -4.994375e+01 -1.874145e-01 4.513855e-04 9.822808e-01 4.618961e+02 +9.805517e-01 -5.338881e-02 1.888598e-01 2.267427e+02 5.264910e-02 9.985731e-01 8.935056e-03 -4.996806e+01 -1.890673e-01 1.182011e-03 9.819634e-01 4.631314e+02 +9.800846e-01 -5.689955e-02 1.902545e-01 2.269927e+02 5.562730e-02 9.983792e-01 1.202534e-02 -4.998515e+01 -1.906303e-01 -1.202509e-03 9.816611e-01 4.643664e+02 +9.797569e-01 -5.753820e-02 1.917444e-01 2.272405e+02 5.588126e-02 9.983386e-01 1.404249e-02 -5.000328e+01 -1.922338e-01 -3.043308e-03 9.813444e-01 4.655987e+02 +9.793468e-01 -5.770973e-02 1.937768e-01 2.274891e+02 5.613734e-02 9.983304e-01 1.360049e-02 -5.001530e+01 -1.942381e-01 -2.441481e-03 9.809513e-01 4.668308e+02 +9.790105e-01 -5.830268e-02 1.952931e-01 2.277395e+02 5.691526e-02 9.982980e-01 1.271333e-02 -5.003507e+01 -1.957019e-01 -1.331331e-03 9.806625e-01 4.680600e+02 +9.786848e-01 -5.914085e-02 1.966683e-01 2.279924e+02 5.751279e-02 9.982468e-01 1.398435e-02 -5.004862e+01 -1.971505e-01 -2.375332e-03 9.803703e-01 4.692941e+02 +9.784188e-01 -6.054446e-02 1.975628e-01 2.282477e+02 5.855550e-02 9.981575e-01 1.589931e-02 -5.006723e+01 -1.981614e-01 -3.987795e-03 9.801612e-01 4.705270e+02 +9.782224e-01 -6.064512e-02 1.985022e-01 2.285021e+02 5.840133e-02 9.981459e-01 1.714442e-02 -5.007801e+01 -1.991739e-01 -5.178262e-03 9.799504e-01 4.717580e+02 +9.780647e-01 -6.116017e-02 1.991204e-01 2.287576e+02 5.856909e-02 9.981047e-01 1.888260e-02 -5.008696e+01 -1.998979e-01 -6.806103e-03 9.797930e-01 4.729900e+02 +9.779299e-01 -6.336698e-02 1.990924e-01 2.290121e+02 6.062249e-02 9.979632e-01 1.985699e-02 -5.009614e+01 -1.999452e-01 -7.349263e-03 9.797795e-01 4.742151e+02 +9.781043e-01 -6.262909e-02 1.984681e-01 2.292634e+02 6.018836e-02 9.980190e-01 1.831295e-02 -5.010928e+01 -1.992219e-01 -5.966501e-03 9.799362e-01 4.754435e+02 +9.784241e-01 -6.006501e-02 1.976830e-01 2.295124e+02 5.832027e-02 9.981905e-01 1.464148e-02 -5.011766e+01 -1.982047e-01 -2.796646e-03 9.801566e-01 4.766686e+02 +9.784422e-01 -6.044710e-02 1.974768e-01 2.297620e+02 5.871830e-02 9.981677e-01 1.460369e-02 -5.012297e+01 -1.979977e-01 -2.693361e-03 9.801987e-01 4.778971e+02 +9.788267e-01 -5.521532e-02 1.971030e-01 2.300052e+02 5.384828e-02 9.984734e-01 1.229258e-02 -5.013540e+01 -1.974808e-01 -1.418653e-03 9.803057e-01 4.791220e+02 +9.790191e-01 -5.328133e-02 1.966791e-01 2.302515e+02 5.219699e-02 9.985795e-01 1.069662e-02 -5.015140e+01 -1.969697e-01 -2.061416e-04 9.804095e-01 4.803451e+02 +9.791498e-01 -5.206044e-02 1.963557e-01 2.304993e+02 5.119065e-02 9.986436e-01 9.505823e-03 -5.017168e+01 -1.965842e-01 7.439487e-04 9.804866e-01 4.815679e+02 +9.792317e-01 -5.120768e-02 1.961710e-01 2.307470e+02 5.016112e-02 9.986880e-01 1.030294e-02 -5.018591e+01 -1.964412e-01 -2.488057e-04 9.805155e-01 4.827916e+02 +9.792896e-01 -5.164809e-02 1.957663e-01 2.309992e+02 5.025903e-02 9.986634e-01 1.205988e-02 -5.019899e+01 -1.961275e-01 -1.971092e-03 9.805764e-01 4.840153e+02 +9.792700e-01 -5.294956e-02 1.955164e-01 2.312529e+02 5.129426e-02 9.985920e-01 1.352358e-02 -5.020713e+01 -1.959571e-01 -3.214369e-03 9.806071e-01 4.852384e+02 +9.791297e-01 -5.438756e-02 1.958239e-01 2.315047e+02 5.262431e-02 9.985134e-01 1.419992e-02 -5.022188e+01 -1.963051e-01 -3.598465e-03 9.805362e-01 4.864533e+02 +9.789431e-01 -5.555460e-02 1.964287e-01 2.317580e+02 5.382418e-02 9.984503e-01 1.414106e-02 -5.023368e+01 -1.969098e-01 -3.270680e-03 9.804161e-01 4.876709e+02 +9.787660e-01 -5.571751e-02 1.972631e-01 2.320103e+02 5.408139e-02 9.984429e-01 1.367582e-02 -5.024569e+01 -1.977179e-01 -2.717163e-03 9.802551e-01 4.888863e+02 +9.785799e-01 -5.517812e-02 1.983353e-01 2.322626e+02 5.352186e-02 9.984726e-01 1.370626e-02 -5.025354e+01 -1.987887e-01 -2.797391e-03 9.800383e-01 4.901021e+02 +9.785034e-01 -5.340921e-02 1.991951e-01 2.325135e+02 5.177180e-02 9.985687e-01 1.342346e-02 -5.026352e+01 -1.996269e-01 -2.822212e-03 9.798679e-01 4.913169e+02 +9.783592e-01 -5.126174e-02 2.004637e-01 2.327633e+02 4.949821e-02 9.986788e-01 1.380296e-02 -5.027945e+01 -2.009064e-01 -3.581654e-03 9.796038e-01 4.925318e+02 +9.781256e-01 -5.143922e-02 2.015548e-01 2.330239e+02 4.910895e-02 9.986563e-01 1.654829e-02 -5.028831e+01 -2.021352e-01 -6.288164e-03 9.793374e-01 4.937487e+02 +9.778514e-01 -5.222416e-02 2.026806e-01 2.332859e+02 5.015607e-02 9.986237e-01 1.533010e-02 -5.030294e+01 -2.032022e-01 -4.824895e-03 9.791248e-01 4.949640e+02 +9.776388e-01 -5.162535e-02 2.038559e-01 2.335459e+02 5.108678e-02 9.986629e-01 7.907116e-03 -5.031031e+01 -2.039915e-01 2.684036e-03 9.789689e-01 4.961697e+02 +9.773631e-01 -5.313087e-02 2.047888e-01 2.338084e+02 5.261990e-02 9.985830e-01 7.944015e-03 -5.032066e+01 -2.049207e-01 3.011779e-03 9.787739e-01 4.973786e+02 +9.771596e-01 -5.320379e-02 2.057391e-01 2.340688e+02 5.147288e-02 9.985796e-01 1.376017e-02 -5.033320e+01 -2.061790e-01 -2.855899e-03 9.785101e-01 4.985970e+02 +9.768798e-01 -5.178482e-02 2.074230e-01 2.343282e+02 4.928800e-02 9.986366e-01 1.719085e-02 -5.034291e+01 -2.080304e-01 -6.569929e-03 9.781002e-01 4.998116e+02 +9.767796e-01 -4.842140e-02 2.087031e-01 2.345856e+02 4.573079e-02 9.987969e-01 1.770097e-02 -5.034560e+01 -2.093091e-01 -7.745786e-03 9.778188e-01 5.010199e+02 +9.766112e-01 -4.598300e-02 2.100384e-01 2.348450e+02 4.402704e-02 9.989325e-01 1.398134e-02 -5.034972e+01 -2.104570e-01 -4.406970e-03 9.775931e-01 5.022206e+02 +9.763788e-01 -4.584767e-02 2.111455e-01 2.351081e+02 4.460748e-02 9.989480e-01 1.063556e-02 -5.035938e+01 -2.114110e-01 -9.656627e-04 9.773967e-01 5.034200e+02 +9.762151e-01 -4.599091e-02 2.118704e-01 2.353724e+02 4.475613e-02 9.989414e-01 1.062263e-02 -5.037279e+01 -2.121347e-01 -8.874738e-04 9.772400e-01 5.046210e+02 +9.760581e-01 -4.808251e-02 2.121290e-01 2.356391e+02 4.651037e-02 9.988408e-01 1.239793e-02 -5.038639e+01 -2.124792e-01 -2.234902e-03 9.771630e-01 5.058212e+02 +9.760204e-01 -5.011302e-02 2.118322e-01 2.359075e+02 4.845850e-02 9.987406e-01 1.299814e-02 -5.039619e+01 -2.122168e-01 -2.421377e-03 9.772196e-01 5.070198e+02 +9.758932e-01 -5.264810e-02 2.118034e-01 2.361755e+02 5.078181e-02 9.986081e-01 1.424531e-02 -5.040362e+01 -2.122585e-01 -3.146146e-03 9.772084e-01 5.082160e+02 +9.758758e-01 -5.389672e-02 2.115695e-01 2.364401e+02 5.185677e-02 9.985391e-01 1.518282e-02 -5.041681e+01 -2.120787e-01 -3.845239e-03 9.772450e-01 5.094087e+02 +9.757939e-01 -5.420450e-02 2.118682e-01 2.367037e+02 5.214308e-02 9.985223e-01 1.530906e-02 -5.042945e+01 -2.123850e-01 -3.891025e-03 9.771783e-01 5.106033e+02 +9.759113e-01 -5.316643e-02 2.115905e-01 2.369648e+02 5.099618e-02 9.985753e-01 1.570460e-02 -5.043332e+01 -2.121240e-01 -4.535989e-03 9.772322e-01 5.117926e+02 +9.759357e-01 -5.208714e-02 2.117465e-01 2.372252e+02 4.987519e-02 9.986308e-01 1.577759e-02 -5.044430e+01 -2.122784e-01 -4.837009e-03 9.771972e-01 5.129801e+02 +9.761727e-01 -4.920488e-02 2.113428e-01 2.374810e+02 4.675299e-02 9.987688e-01 1.658590e-02 -5.045036e+01 -2.118987e-01 -6.309792e-03 9.772712e-01 5.141625e+02 +9.762436e-01 -4.766548e-02 2.113683e-01 2.377353e+02 4.526359e-02 9.988439e-01 1.619019e-02 -5.046259e+01 -2.118956e-01 -6.238279e-03 9.772723e-01 5.153417e+02 +9.764576e-01 -4.511373e-02 2.109391e-01 2.379895e+02 4.274176e-02 9.989613e-01 1.579297e-02 -5.047048e+01 -2.114325e-01 -6.405257e-03 9.773716e-01 5.165239e+02 +9.765764e-01 -4.521878e-02 2.103659e-01 2.382490e+02 4.239190e-02 9.989401e-01 1.793034e-02 -5.048027e+01 -2.109537e-01 -8.592533e-03 9.774582e-01 5.177042e+02 +9.766257e-01 -4.792555e-02 2.095362e-01 2.385080e+02 4.489315e-02 9.988071e-01 1.920709e-02 -5.048660e+01 -2.102068e-01 -9.351391e-03 9.776122e-01 5.188830e+02 +9.769265e-01 -4.694273e-02 2.083530e-01 2.387611e+02 4.443411e-02 9.988726e-01 1.670698e-02 -5.049223e+01 -2.089024e-01 -7.063506e-03 9.779109e-01 5.200557e+02 +9.772218e-01 -4.757702e-02 2.068189e-01 2.390144e+02 4.560676e-02 9.988573e-01 1.428663e-02 -5.050219e+01 -2.072622e-01 -4.528864e-03 9.782749e-01 5.212305e+02 +9.776441e-01 -4.617944e-02 2.051329e-01 2.392630e+02 4.428553e-02 9.989233e-01 1.381662e-02 -5.051139e+01 -2.055501e-01 -4.423318e-03 9.786366e-01 5.224001e+02 +9.780466e-01 -4.354165e-02 2.037869e-01 2.395061e+02 4.127686e-02 9.990298e-01 1.535293e-02 -5.052212e+01 -2.042577e-01 -6.604193e-03 9.788948e-01 5.235733e+02 +9.785464e-01 -4.148538e-02 2.018066e-01 2.397468e+02 3.855939e-02 9.990867e-01 1.841039e-02 -5.052768e+01 -2.023860e-01 -1.023388e-02 9.792523e-01 5.247416e+02 +9.789886e-01 -4.000047e-02 1.999535e-01 2.399845e+02 3.696313e-02 9.991378e-01 1.890192e-02 -5.053456e+01 -2.005372e-01 -1.111386e-02 9.796230e-01 5.259049e+02 +9.795028e-01 -3.847094e-02 1.977227e-01 2.402157e+02 3.580445e-02 9.992134e-01 1.704474e-02 -5.054060e+01 -1.982229e-01 -9.616012e-03 9.801097e-01 5.270676e+02 +9.799955e-01 -3.638330e-02 1.956658e-01 2.404366e+02 3.375636e-02 9.992898e-01 1.674483e-02 -5.055184e+01 -1.961361e-01 -9.804890e-03 9.805276e-01 5.282313e+02 +9.803392e-01 -3.540198e-02 1.941181e-01 2.406603e+02 3.287363e-02 9.993277e-01 1.623174e-02 -5.056055e+01 -1.945622e-01 -9.531245e-03 9.808438e-01 5.293897e+02 +9.806279e-01 -3.421560e-02 1.928687e-01 2.408801e+02 3.210765e-02 9.993857e-01 1.404543e-02 -5.057075e+01 -1.932307e-01 -7.580780e-03 9.811240e-01 5.305426e+02 +9.808614e-01 -3.457738e-02 1.916128e-01 2.411020e+02 3.325726e-02 9.993957e-01 1.010230e-02 -5.058397e+01 -1.918463e-01 -3.536437e-03 9.814186e-01 5.316895e+02 +9.810798e-01 -3.611530e-02 1.902056e-01 2.413164e+02 3.512540e-02 9.993461e-01 8.574251e-03 -5.060281e+01 -1.903908e-01 -1.730978e-03 9.817068e-01 5.328393e+02 +9.812728e-01 -3.801074e-02 1.888358e-01 2.415281e+02 3.671565e-02 9.992721e-01 1.035296e-02 -5.062441e+01 -1.890918e-01 -3.225852e-03 9.819541e-01 5.339867e+02 +9.814742e-01 -3.930876e-02 1.875190e-01 2.417409e+02 3.746936e-02 9.992086e-01 1.334502e-02 -5.064068e+01 -1.878951e-01 -6.071574e-03 9.821703e-01 5.351333e+02 +9.815985e-01 -3.933337e-02 1.868618e-01 2.419488e+02 3.741204e-02 9.992046e-01 1.379887e-02 -5.065390e+01 -1.872559e-01 -6.554072e-03 9.822892e-01 5.362751e+02 +9.817237e-01 -3.730350e-02 1.866200e-01 2.421547e+02 3.532885e-02 9.992791e-01 1.389694e-02 -5.066746e+01 -1.870038e-01 -7.049889e-03 9.823338e-01 5.374130e+02 +9.816704e-01 -3.671136e-02 1.870176e-01 2.423594e+02 3.462847e-02 9.992966e-01 1.439330e-02 -5.068338e+01 -1.874144e-01 -7.653343e-03 9.822511e-01 5.385503e+02 +9.815305e-01 -3.483372e-02 1.881076e-01 2.425680e+02 3.264188e-02 9.993584e-01 1.473821e-02 -5.069403e+01 -1.885003e-01 -8.325817e-03 9.820378e-01 5.396830e+02 +9.811659e-01 -3.453080e-02 1.900556e-01 2.427781e+02 3.240646e-02 9.993728e-01 1.427494e-02 -5.070648e+01 -1.904293e-01 -7.847054e-03 9.816695e-01 5.408117e+02 +9.807498e-01 -3.506904e-02 1.920938e-01 2.429939e+02 3.312717e-02 9.993625e-01 1.331239e-02 -5.071562e+01 -1.924382e-01 -6.692596e-03 9.812862e-01 5.419359e+02 +9.802349e-01 -3.533032e-02 1.946571e-01 2.432101e+02 3.382850e-02 9.993667e-01 1.103518e-02 -5.073020e+01 -1.949237e-01 -4.232114e-03 9.808092e-01 5.430574e+02 +9.797354e-01 -3.684950e-02 1.968777e-01 2.434323e+02 3.543938e-02 9.993147e-01 1.068196e-02 -5.074269e+01 -1.971364e-01 -3.488275e-03 9.803698e-01 5.441776e+02 +9.792198e-01 -3.858604e-02 1.990975e-01 2.436555e+02 3.674947e-02 9.992411e-01 1.291306e-02 -5.075562e+01 -1.994446e-01 -5.327994e-03 9.798946e-01 5.452958e+02 +9.787360e-01 -3.936247e-02 2.013118e-01 2.438742e+02 3.698512e-02 9.991947e-01 1.555851e-02 -5.077302e+01 -2.017621e-01 -7.782133e-03 9.794036e-01 5.464136e+02 +9.781860e-01 -4.020235e-02 2.038037e-01 2.440945e+02 3.751425e-02 9.991508e-01 1.703751e-02 -5.078632e+01 -2.043156e-01 -9.020306e-03 9.788635e-01 5.475256e+02 +9.776048e-01 -4.045568e-02 2.065244e-01 2.443078e+02 3.814915e-02 9.991573e-01 1.514015e-02 -5.080448e+01 -2.069628e-01 -6.922357e-03 9.783243e-01 5.486307e+02 +9.769797e-01 -4.155858e-02 2.092453e-01 2.445304e+02 3.969827e-02 9.991260e-01 1.308447e-02 -5.081777e+01 -2.096062e-01 -4.476587e-03 9.777756e-01 5.497309e+02 +9.762817e-01 -4.429545e-02 2.119246e-01 2.447549e+02 4.221401e-02 9.990057e-01 1.433834e-02 -5.083133e+01 -2.123490e-01 -5.052072e-03 9.771808e-01 5.508297e+02 +9.757375e-01 -4.556257e-02 2.141508e-01 2.449867e+02 4.291329e-02 9.989340e-01 1.700627e-02 -5.084192e+01 -2.146973e-01 -7.403741e-03 9.766525e-01 5.519245e+02 +9.751182e-01 -4.648556e-02 2.167572e-01 2.452162e+02 4.368621e-02 9.988886e-01 1.769118e-02 -5.085146e+01 -2.173387e-01 -7.781691e-03 9.760652e-01 5.530122e+02 +9.744825e-01 -4.634223e-02 2.196275e-01 2.454473e+02 4.336938e-02 9.988907e-01 1.834070e-02 -5.085911e+01 -2.202338e-01 -8.347586e-03 9.754113e-01 5.541019e+02 +9.735756e-01 -4.792241e-02 2.232803e-01 2.456866e+02 4.415912e-02 9.987862e-01 2.182012e-02 -5.087137e+01 -2.240549e-01 -1.138368e-02 9.745100e-01 5.551898e+02 +9.728908e-01 -4.437937e-02 2.269669e-01 2.459203e+02 4.058899e-02 9.989479e-01 2.134246e-02 -5.088198e+01 -2.276753e-01 -1.155152e-02 9.736685e-01 5.562701e+02 +9.719990e-01 -4.166864e-02 2.312611e-01 2.461568e+02 3.948743e-02 9.991212e-01 1.405460e-02 -5.089416e+01 -2.316435e-01 -4.529155e-03 9.727902e-01 5.573390e+02 +9.709826e-01 -4.120592e-02 2.355738e-01 2.464023e+02 4.034844e-02 9.991498e-01 8.461303e-03 -5.090884e+01 -2.357222e-01 1.289258e-03 9.718196e-01 5.584030e+02 +9.698402e-01 -4.020405e-02 2.404032e-01 2.466510e+02 3.837239e-02 9.991878e-01 1.229733e-02 -5.092834e+01 -2.407024e-01 -2.701601e-03 9.705952e-01 5.594769e+02 +9.687251e-01 -3.992563e-02 2.449034e-01 2.469027e+02 3.652489e-02 9.991631e-01 1.841396e-02 -5.094882e+01 -2.454337e-01 -8.892998e-03 9.693725e-01 5.605460e+02 +9.676943e-01 -3.912380e-02 2.490726e-01 2.471603e+02 3.560263e-02 9.991924e-01 1.862807e-02 -5.096137e+01 -2.496003e-01 -9.158634e-03 9.683056e-01 5.616040e+02 +9.666518e-01 -3.672629e-02 2.534472e-01 2.474200e+02 3.407241e-02 9.993090e-01 1.485419e-02 -5.097476e+01 -2.538176e-01 -5.723275e-03 9.672351e-01 5.626541e+02 +9.652709e-01 -3.376589e-02 2.590601e-01 2.476831e+02 3.169824e-02 9.994235e-01 1.215567e-02 -5.098727e+01 -2.593212e-01 -3.521769e-03 9.657847e-01 5.636958e+02 +9.635187e-01 -3.308882e-02 2.655878e-01 2.479543e+02 2.965343e-02 9.994167e-01 1.693561e-02 -5.100168e+01 -2.659933e-01 -8.442184e-03 9.639379e-01 5.647478e+02 +9.616709e-01 -3.062323e-02 2.724912e-01 2.482308e+02 2.475363e-02 9.993821e-01 2.495297e-02 -5.101228e+01 -2.730869e-01 -1.725140e-02 9.618346e-01 5.657925e+02 +9.598192e-01 -2.841450e-02 2.791770e-01 2.485097e+02 2.222415e-02 9.994324e-01 2.531444e-02 -5.101959e+01 -2.797378e-01 -1.809281e-02 9.599059e-01 5.668240e+02 +9.578784e-01 -2.785938e-02 2.858196e-01 2.487998e+02 2.353140e-02 9.995507e-01 1.856640e-02 -5.101910e+01 -2.862084e-01 -1.105862e-02 9.581035e-01 5.678432e+02 +9.557971e-01 -2.814116e-02 2.926775e-01 2.490971e+02 2.465629e-02 9.995744e-01 1.558979e-02 -5.102469e+01 -2.929916e-01 -7.684335e-03 9.560841e-01 5.688590e+02 +9.538558e-01 -2.673866e-02 2.990724e-01 2.494049e+02 2.334950e-02 9.996163e-01 1.490057e-02 -5.103175e+01 -2.993561e-01 -7.229802e-03 9.541140e-01 5.698721e+02 +9.519359e-01 -2.680745e-02 3.051222e-01 2.497197e+02 2.316911e-02 9.996108e-01 1.553972e-02 -5.103850e+01 -3.054200e-01 -7.723405e-03 9.521864e-01 5.708815e+02 +9.498635e-01 -2.871754e-02 3.113435e-01 2.500422e+02 2.446329e-02 9.995464e-01 1.756173e-02 -5.104301e+01 -3.117066e-01 -9.064756e-03 9.501351e-01 5.718852e+02 +9.477531e-01 -2.992935e-02 3.175977e-01 2.503668e+02 2.443236e-02 9.994750e-01 2.127785e-02 -5.104595e+01 -3.180678e-01 -1.240649e-02 9.479867e-01 5.728852e+02 +9.456593e-01 -3.180609e-02 3.236000e-01 2.506918e+02 2.572963e-02 9.994034e-01 2.303973e-02 -5.104856e+01 -3.241397e-01 -1.346162e-02 9.459134e-01 5.738755e+02 +9.436741e-01 -3.324631e-02 3.292019e-01 2.510302e+02 2.699408e-02 9.993582e-01 2.354593e-02 -5.104416e+01 -3.297735e-01 -1.333318e-02 9.439659e-01 5.748616e+02 +9.416990e-01 -3.548124e-02 3.345805e-01 2.513738e+02 2.941455e-02 9.992984e-01 2.318338e-02 -5.103406e+01 -3.351683e-01 -1.199023e-02 9.420819e-01 5.758404e+02 +9.398619e-01 -3.775441e-02 3.394619e-01 2.517225e+02 3.178494e-02 9.992270e-01 2.313009e-02 -5.102551e+01 -3.400728e-01 -1.094931e-02 9.403353e-01 5.768169e+02 +9.381248e-01 -4.092843e-02 3.438704e-01 2.520765e+02 3.485279e-02 9.991082e-01 2.383360e-02 -5.102099e+01 -3.445392e-01 -1.037405e-02 9.387146e-01 5.777867e+02 +9.366403e-01 -4.327366e-02 3.476095e-01 2.524326e+02 3.759137e-02 9.990267e-01 2.307747e-02 -5.102170e+01 -3.482698e-01 -8.548170e-03 9.373553e-01 5.787542e+02 +9.353683e-01 -4.571385e-02 3.507085e-01 2.527924e+02 4.098691e-02 9.989412e-01 2.089368e-02 -5.102187e+01 -3.512923e-01 -5.168824e-03 9.362515e-01 5.797192e+02 +9.344731e-01 -4.873724e-02 3.526823e-01 2.531612e+02 4.473314e-02 9.988086e-01 1.949987e-02 -5.102142e+01 -3.532124e-01 -2.445514e-03 9.355399e-01 5.806828e+02 +9.337987e-01 -5.214345e-02 3.539791e-01 2.535319e+02 4.787417e-02 9.986365e-01 2.081343e-02 -5.102438e+01 -3.545817e-01 -2.489101e-03 9.350217e-01 5.816506e+02 +9.334831e-01 -5.456211e-02 3.544466e-01 2.538992e+02 4.954289e-02 9.985018e-01 2.322754e-02 -5.102670e+01 -3.551829e-01 -4.122212e-03 9.347877e-01 5.826191e+02 +9.334094e-01 -5.616975e-02 3.543895e-01 2.542666e+02 5.075502e-02 9.984090e-01 2.456388e-02 -5.102835e+01 -3.552054e-01 -4.941107e-03 9.347752e-01 5.835910e+02 +9.336480e-01 -5.815195e-02 3.534401e-01 2.546334e+02 5.240033e-02 9.982920e-01 2.582947e-02 -5.102851e+01 -3.543385e-01 -5.595254e-03 9.351004e-01 5.845641e+02 +9.341135e-01 -6.089242e-02 3.517445e-01 2.549994e+02 5.463417e-02 9.981221e-01 2.770071e-02 -5.102435e+01 -3.527707e-01 -6.658335e-03 9.356861e-01 5.855388e+02 +9.348116e-01 -6.378538e-02 3.493692e-01 2.553686e+02 5.647135e-02 9.979199e-01 3.109216e-02 -5.101410e+01 -3.506257e-01 -9.335960e-03 9.364691e-01 5.865188e+02 +9.358365e-01 -6.258305e-02 3.468336e-01 2.557271e+02 5.579079e-02 9.980052e-01 2.954490e-02 -5.100817e+01 -3.479907e-01 -8.299077e-03 9.374612e-01 5.874922e+02 +9.369546e-01 -6.065742e-02 3.441465e-01 2.560840e+02 5.737213e-02 9.981578e-01 1.973175e-02 -5.100349e+01 -3.447094e-01 1.256665e-03 9.387085e-01 5.884646e+02 +9.383097e-01 -5.730795e-02 3.410143e-01 2.564358e+02 5.659090e-02 9.983246e-01 1.205861e-02 -5.100103e+01 -3.411340e-01 7.983589e-03 9.399807e-01 5.894394e+02 +9.395955e-01 -5.703036e-02 3.375025e-01 2.567842e+02 5.408022e-02 9.983717e-01 1.814495e-02 -5.100775e+01 -3.379877e-01 1.203293e-03 9.411497e-01 5.904226e+02 +9.407901e-01 -5.986220e-02 3.336625e-01 2.571322e+02 5.353642e-02 9.981696e-01 2.813052e-02 -5.100996e+01 -3.347357e-01 -8.601823e-03 9.422728e-01 5.914131e+02 +9.418615e-01 -6.323249e-02 3.299979e-01 2.574765e+02 5.537505e-02 9.979146e-01 3.316689e-02 -5.100969e+01 -3.314070e-01 -1.296496e-02 9.433988e-01 5.923943e+02 +9.430729e-01 -6.078410e-02 3.269845e-01 2.578106e+02 5.579890e-02 9.981386e-01 2.461440e-02 -5.100583e+01 -3.278720e-01 -4.967792e-03 9.447090e-01 5.933684e+02 +9.440538e-01 -5.991272e-02 3.243037e-01 2.581422e+02 5.868477e-02 9.981842e-01 1.357482e-02 -5.100111e+01 -3.245281e-01 6.216329e-03 9.458556e-01 5.943377e+02 +9.450793e-01 -6.010250e-02 3.212676e-01 2.584788e+02 6.004198e-02 9.981447e-01 1.010549e-02 -5.100061e+01 -3.212789e-01 9.739058e-03 9.469345e-01 5.953146e+02 +9.457004e-01 -6.039868e-02 3.193788e-01 2.588115e+02 5.802361e-02 9.981712e-01 1.695566e-02 -5.100442e+01 -3.198188e-01 2.496541e-03 9.474754e-01 5.963069e+02 +9.460547e-01 -6.121601e-02 3.181715e-01 2.591435e+02 5.695944e-02 9.981190e-01 2.267367e-02 -5.100430e+01 -3.189610e-01 -3.327657e-03 9.477619e-01 5.972951e+02 +9.461917e-01 -6.252694e-02 3.175087e-01 2.594759e+02 5.753632e-02 9.980283e-01 2.508049e-02 -5.099663e+01 -3.184509e-01 -5.462668e-03 9.479236e-01 5.982768e+02 +9.462794e-01 -6.381464e-02 3.169905e-01 2.598080e+02 5.867678e-02 9.979451e-01 2.573860e-02 -5.098760e+01 -3.179816e-01 -5.755925e-03 9.480793e-01 5.992527e+02 +9.463526e-01 -6.333626e-02 3.168679e-01 2.601323e+02 5.837183e-02 9.979781e-01 2.514573e-02 -5.097979e+01 -3.178199e-01 -5.300562e-03 9.481362e-01 6.002279e+02 +9.457064e-01 -6.411766e-02 3.186353e-01 2.604602e+02 5.890370e-02 9.979254e-01 2.598285e-02 -5.097103e+01 -3.196402e-01 -5.803355e-03 9.475212e-01 6.012038e+02 +9.445145e-01 -6.382432e-02 3.222094e-01 2.607884e+02 5.784734e-02 9.979298e-01 2.810144e-02 -5.096474e+01 -3.233360e-01 -7.903257e-03 9.462512e-01 6.021763e+02 +9.427500e-01 -6.296789e-02 3.275019e-01 2.611243e+02 5.641545e-02 9.979721e-01 2.947933e-02 -5.095947e+01 -3.286940e-01 -9.315469e-03 9.443905e-01 6.031464e+02 +9.402619e-01 -6.280988e-02 3.346081e-01 2.614684e+02 5.628916e-02 9.979886e-01 2.915946e-02 -5.095153e+01 -3.357666e-01 -8.582720e-03 9.419061e-01 6.041080e+02 +9.371350e-01 -6.147739e-02 3.435094e-01 2.618195e+02 5.496597e-02 9.980765e-01 2.867058e-02 -5.094287e+01 -3.446112e-01 -7.986876e-03 9.387115e-01 6.050649e+02 +9.331758e-01 -5.965521e-02 3.544352e-01 2.621750e+02 5.278522e-02 9.981838e-01 2.902926e-02 -5.093836e+01 -3.555232e-01 -8.380462e-03 9.346298e-01 6.060168e+02 +9.285191e-01 -5.799937e-02 3.667267e-01 2.625445e+02 5.027831e-02 9.982670e-01 3.057998e-02 -5.093334e+01 -3.678647e-01 -9.955695e-03 9.298260e-01 6.069674e+02 +9.233106e-01 -5.619575e-02 3.799206e-01 2.629266e+02 4.724581e-02 9.983430e-01 3.284917e-02 -5.092822e+01 -3.811371e-01 -1.238033e-02 9.244356e-01 6.079071e+02 +9.175593e-01 -5.534924e-02 3.937277e-01 2.633218e+02 4.525368e-02 9.983662e-01 3.488676e-02 -5.092012e+01 -3.950153e-01 -1.419304e-02 9.185648e-01 6.088442e+02 +9.111107e-01 -5.696856e-02 4.082057e-01 2.637333e+02 4.618398e-02 9.982755e-01 3.623567e-02 -5.091164e+01 -4.095661e-01 -1.416214e-02 9.121705e-01 6.097719e+02 +9.044669e-01 -5.527943e-02 4.229466e-01 2.641531e+02 4.398053e-02 9.983677e-01 3.643549e-02 -5.090253e+01 -4.242703e-01 -1.435328e-02 9.054218e-01 6.106848e+02 +8.973226e-01 -5.304466e-02 4.381764e-01 2.645927e+02 4.169111e-02 9.984997e-01 3.549874e-02 -5.090140e+01 -4.394020e-01 -1.358577e-02 8.981878e-01 6.116007e+02 +8.897168e-01 -5.279253e-02 4.534502e-01 2.650529e+02 4.140405e-02 9.985288e-01 3.501375e-02 -5.089051e+01 -4.546315e-01 -1.237764e-02 8.905935e-01 6.125045e+02 +8.814290e-01 -5.289350e-02 4.693457e-01 2.655213e+02 4.096746e-02 9.985263e-01 3.559349e-02 -5.087771e+01 -4.705366e-01 -1.214523e-02 8.822968e-01 6.133911e+02 +8.726080e-01 -5.306442e-02 4.855302e-01 2.660128e+02 4.075354e-02 9.985245e-01 3.588709e-02 -5.086314e+01 -4.867181e-01 -1.152829e-02 8.734829e-01 6.142799e+02 +8.634306e-01 -5.344618e-02 5.016285e-01 2.665162e+02 4.118303e-02 9.985207e-01 3.550125e-02 -5.085314e+01 -5.027838e-01 -9.994286e-03 8.643544e-01 6.151473e+02 +8.539640e-01 -5.316260e-02 5.176092e-01 2.670426e+02 4.095593e-02 9.985481e-01 3.498880e-02 -5.084209e+01 -5.187178e-01 -8.680009e-03 8.549014e-01 6.160170e+02 +8.439959e-01 -5.422866e-02 5.336012e-01 2.675881e+02 4.130576e-02 9.984927e-01 3.614129e-02 -5.082826e+01 -5.347568e-01 -8.462290e-03 8.449636e-01 6.168817e+02 +8.336947e-01 -5.441572e-02 5.495381e-01 2.681454e+02 3.972400e-02 9.984647e-01 3.860422e-02 -5.081185e+01 -5.507950e-01 -1.035428e-02 8.345762e-01 6.177307e+02 +8.230209e-01 -5.492854e-02 5.653491e-01 2.687256e+02 3.752150e-02 9.983967e-01 4.238001e-02 -5.079039e+01 -5.667705e-01 -1.366689e-02 8.237623e-01 6.185852e+02 +8.121714e-01 -5.649147e-02 5.806775e-01 2.693238e+02 3.686959e-02 9.982814e-01 4.555018e-02 -5.076785e+01 -5.822527e-01 -1.558521e-02 8.128584e-01 6.194283e+02 +8.015217e-01 -5.627951e-02 5.953114e-01 2.699334e+02 3.530465e-02 9.982782e-01 4.684132e-02 -5.074382e+01 -5.969226e-01 -1.652707e-02 8.021285e-01 6.202541e+02 +7.910235e-01 -5.600741e-02 6.092167e-01 2.705652e+02 3.561243e-02 9.983275e-01 4.553959e-02 -5.071811e+01 -6.107483e-01 -1.432720e-02 7.916951e-01 6.210773e+02 +7.807738e-01 -5.643669e-02 6.222598e-01 2.712101e+02 3.682472e-02 9.983375e-01 4.434015e-02 -5.068902e+01 -6.237277e-01 -1.170509e-02 7.815540e-01 6.218818e+02 +7.703889e-01 -5.825517e-02 6.349074e-01 2.718743e+02 3.784352e-02 9.982393e-01 4.567341e-02 -5.066036e+01 -6.364502e-01 -1.115916e-02 7.712370e-01 6.226852e+02 +7.598651e-01 -6.091595e-02 6.472205e-01 2.725520e+02 3.830360e-02 9.980656e-01 4.896717e-02 -5.063206e+01 -6.489514e-01 -1.241756e-02 7.607284e-01 6.234806e+02 +7.487162e-01 -6.345752e-02 6.598464e-01 2.732383e+02 3.970023e-02 9.979132e-01 5.092231e-02 -5.059795e+01 -6.617008e-01 -1.193030e-02 7.496730e-01 6.242549e+02 +7.371486e-01 -6.522088e-02 6.725758e-01 2.739393e+02 4.085804e-02 9.978120e-01 5.197887e-02 -5.056151e+01 -6.744943e-01 -1.083603e-02 7.382005e-01 6.250211e+02 +7.250811e-01 -6.692350e-02 6.854040e-01 2.746532e+02 4.148858e-02 9.977041e-01 5.352650e-02 -5.052037e+01 -6.874126e-01 -1.037461e-02 7.261930e-01 6.257775e+02 +7.127585e-01 -6.825806e-02 6.980804e-01 2.753733e+02 4.188697e-02 9.976195e-01 5.477920e-02 -5.047769e+01 -7.001577e-01 -9.803869e-03 7.139208e-01 6.265099e+02 +6.998130e-01 -7.024408e-02 7.108639e-01 2.761118e+02 4.288588e-02 9.974897e-01 5.634785e-02 -5.043775e+01 -7.130375e-01 -8.946937e-03 7.010687e-01 6.272392e+02 +6.863627e-01 -7.223808e-02 7.236629e-01 2.768581e+02 4.333751e-02 9.973489e-01 5.845446e-02 -5.039474e+01 -7.259670e-01 -8.759214e-03 6.876736e-01 6.279418e+02 +6.723043e-01 -7.416107e-02 7.365508e-01 2.776233e+02 4.406458e-02 9.972141e-01 6.018548e-02 -5.035023e+01 -7.389622e-01 -8.007160e-03 6.736992e-01 6.286370e+02 +6.577343e-01 -7.391172e-02 7.496150e-01 2.783992e+02 4.389105e-02 9.972440e-01 5.981653e-02 -5.030444e+01 -7.519701e-01 -6.441998e-03 6.591656e-01 6.293147e+02 +6.425060e-01 -7.174751e-02 7.629145e-01 2.791754e+02 4.274165e-02 9.974125e-01 5.780478e-02 -5.026201e+01 -7.650877e-01 -4.531694e-03 6.439100e-01 6.299634e+02 +6.264940e-01 -7.010805e-02 7.762668e-01 2.799766e+02 4.182012e-02 9.975354e-01 5.634043e-02 -5.021950e+01 -7.783035e-01 -2.833370e-03 6.278818e-01 6.306089e+02 +6.100031e-01 -6.848094e-02 7.894344e-01 2.807890e+02 3.995192e-02 9.976495e-01 5.567174e-02 -5.017661e+01 -7.913912e-01 -2.420521e-03 6.113052e-01 6.312395e+02 +5.929441e-01 -6.861908e-02 8.023146e-01 2.816103e+02 3.927736e-02 9.976412e-01 5.629705e-02 -5.013056e+01 -8.042851e-01 -1.868208e-03 5.942406e-01 6.318423e+02 +5.758405e-01 -6.994569e-02 8.145645e-01 2.824537e+02 3.972201e-02 9.975505e-01 5.757779e-02 -5.008337e+01 -8.165965e-01 -7.994876e-04 5.772083e-01 6.324388e+02 +5.587671e-01 -7.132651e-02 8.262517e-01 2.833041e+02 4.122716e-02 9.974518e-01 5.822485e-02 -5.003242e+01 -8.282992e-01 1.529878e-03 5.602838e-01 6.330033e+02 +5.417449e-01 -7.644756e-02 8.370593e-01 2.841815e+02 4.676189e-02 9.970543e-01 6.079541e-02 -4.998024e+01 -8.392412e-01 6.206863e-03 5.437239e-01 6.335624e+02 +5.262706e-01 -7.962516e-02 8.465809e-01 2.850656e+02 4.869939e-02 9.967942e-01 6.347988e-02 -4.992402e+01 -8.489214e-01 7.820373e-03 5.284611e-01 6.341087e+02 +5.117163e-01 -8.066888e-02 8.553590e-01 2.859564e+02 4.780023e-02 9.967133e-01 6.540365e-02 -4.986482e+01 -8.578237e-01 7.418235e-03 5.138904e-01 6.346390e+02 +4.979309e-01 -8.093240e-02 8.634320e-01 2.868643e+02 4.812330e-02 9.966803e-01 6.567009e-02 -4.980078e+01 -8.658804e-01 8.852032e-03 5.001726e-01 6.351627e+02 +4.843327e-01 -7.981382e-02 8.712357e-01 2.877818e+02 4.324040e-02 9.967968e-01 6.727850e-02 -4.973817e+01 -8.738146e-01 5.087397e-03 4.862324e-01 6.356842e+02 +4.703879e-01 -7.893460e-02 8.789224e-01 2.887092e+02 3.793906e-02 9.968795e-01 6.922365e-02 -4.967722e+01 -8.816438e-01 7.835220e-04 4.719147e-01 6.361888e+02 +4.569896e-01 -7.899379e-02 8.859574e-01 2.896536e+02 3.512136e-02 9.968743e-01 7.076727e-02 -4.961087e+01 -8.887783e-01 -1.223885e-03 4.583355e-01 6.366870e+02 +4.441290e-01 -7.646139e-02 8.926943e-01 2.906148e+02 3.306898e-02 9.970719e-01 6.894926e-02 -4.954778e+01 -8.953524e-01 -1.101874e-03 4.453570e-01 6.371704e+02 +4.321427e-01 -7.166229e-02 8.989534e-01 2.915838e+02 3.332637e-02 9.974257e-01 6.349168e-02 -4.948591e+01 -9.011892e-01 2.521380e-03 4.334185e-01 6.376358e+02 +4.219511e-01 -7.017962e-02 9.038983e-01 2.925686e+02 3.591611e-02 9.975108e-01 6.068170e-02 -4.942583e+01 -9.059069e-01 6.859794e-03 4.234213e-01 6.380945e+02 +4.135475e-01 -7.289195e-02 9.075601e-01 2.935720e+02 3.741372e-02 9.973087e-01 6.305195e-02 -4.936761e+01 -9.097135e-01 7.880220e-03 4.151617e-01 6.385513e+02 +4.065561e-01 -7.795295e-02 9.102942e-01 2.945887e+02 3.763634e-02 9.969366e-01 6.856340e-02 -4.930679e+01 -9.128502e-01 6.385263e-03 4.082445e-01 6.390066e+02 +3.998277e-01 -7.932659e-02 9.131512e-01 2.956113e+02 3.751620e-02 9.968294e-01 7.016918e-02 -4.924347e+01 -9.158222e-01 6.202371e-03 4.015360e-01 6.394570e+02 +3.928556e-01 -7.798550e-02 9.162875e-01 2.966400e+02 3.893467e-02 9.969147e-01 6.815459e-02 -4.917727e+01 -9.187755e-01 8.900430e-03 3.946799e-01 6.398978e+02 +3.862646e-01 -7.812955e-02 9.190731e-01 2.976851e+02 3.988350e-02 9.968890e-01 6.798252e-02 -4.911277e+01 -9.215253e-01 1.039661e-02 3.881790e-01 6.403370e+02 +3.803872e-01 -7.985264e-02 9.213735e-01 2.987461e+02 3.999293e-02 9.967538e-01 6.987462e-02 -4.904914e+01 -9.239622e-01 1.026901e-02 3.823459e-01 6.407714e+02 +3.750289e-01 -8.226589e-02 9.233557e-01 2.998159e+02 4.036639e-02 9.965590e-01 7.239275e-02 -4.898199e+01 -9.261338e-01 1.012315e-02 3.770592e-01 6.412032e+02 +3.707674e-01 -8.433323e-02 9.248889e-01 3.008994e+02 4.007232e-02 9.963939e-01 7.478910e-02 -4.891002e+01 -9.278608e-01 9.333074e-03 3.728098e-01 6.416341e+02 +3.675277e-01 -8.589311e-02 9.260377e-01 3.019827e+02 4.002383e-02 9.962642e-01 7.652212e-02 -4.883599e+01 -9.291509e-01 8.939576e-03 3.695924e-01 6.420630e+02 +3.651841e-01 -8.654866e-02 9.269034e-01 3.030764e+02 3.792835e-02 9.962255e-01 7.807842e-02 -4.876220e+01 -9.301623e-01 6.642915e-03 3.670884e-01 6.424945e+02 +3.623859e-01 -8.733207e-02 9.279276e-01 3.041693e+02 3.833852e-02 9.961545e-01 7.878082e-02 -4.868741e+01 -9.312393e-01 7.026308e-03 3.643405e-01 6.429208e+02 +3.601572e-01 -8.505563e-02 9.290061e-01 3.052617e+02 3.778058e-02 9.963478e-01 7.657436e-02 -4.861463e+01 -9.321263e-01 7.519579e-03 3.620553e-01 6.433435e+02 +3.579286e-01 -8.126561e-02 9.302059e-01 3.063571e+02 3.629323e-02 9.966635e-01 7.310649e-02 -4.854419e+01 -9.330433e-01 7.593273e-03 3.596837e-01 6.437658e+02 +3.556133e-01 -8.146773e-02 9.310759e-01 3.074586e+02 3.713915e-02 9.966387e-01 7.301954e-02 -4.847591e+01 -9.338950e-01 8.612643e-03 3.574436e-01 6.441845e+02 +3.532321e-01 -8.238979e-02 9.319008e-01 3.085669e+02 3.570911e-02 9.965760e-01 7.457242e-02 -4.841304e+01 -9.348539e-01 6.935973e-03 3.549647e-01 6.446051e+02 +3.505966e-01 -8.322095e-02 9.328217e-01 3.096749e+02 3.602165e-02 9.965052e-01 7.536386e-02 -4.834757e+01 -9.358335e-01 7.179454e-03 3.523691e-01 6.450213e+02 +3.485782e-01 -8.259295e-02 9.336336e-01 3.107821e+02 3.672019e-02 9.965485e-01 7.444894e-02 -4.828179e+01 -9.365601e-01 8.331922e-03 3.504079e-01 6.454324e+02 +3.466395e-01 -8.189009e-02 9.344170e-01 3.118902e+02 3.825558e-02 9.965872e-01 7.314691e-02 -4.821497e+01 -9.372180e-01 1.039105e-02 3.485892e-01 6.458397e+02 +3.448671e-01 -8.276426e-02 9.349956e-01 3.129997e+02 4.092873e-02 9.964836e-01 7.311079e-02 -4.815098e+01 -9.377587e-01 1.305467e-02 3.470419e-01 6.462438e+02 +3.436625e-01 -8.454901e-02 9.352794e-01 3.141132e+02 4.321763e-02 9.963075e-01 7.418589e-02 -4.808538e+01 -9.380982e-01 1.492565e-02 3.460475e-01 6.466484e+02 +3.428211e-01 -8.644617e-02 9.354148e-01 3.152269e+02 4.535554e-02 9.961188e-01 7.543373e-02 -4.802119e+01 -9.383051e-01 1.656596e-02 3.454113e-01 6.470515e+02 +3.430244e-01 -8.850061e-02 9.351481e-01 3.163410e+02 4.608324e-02 9.959384e-01 7.734977e-02 -4.795263e+01 -9.381953e-01 1.656179e-02 3.457096e-01 6.474574e+02 +3.442670e-01 -8.994477e-02 9.345535e-01 3.174509e+02 4.664169e-02 9.958099e-01 7.865864e-02 -4.788435e+01 -9.377125e-01 1.650957e-02 3.470197e-01 6.478638e+02 +3.467286e-01 -8.955278e-02 9.336807e-01 3.185571e+02 4.668007e-02 9.958458e-01 7.818031e-02 -4.781682e+01 -9.368032e-01 1.647692e-02 3.494685e-01 6.482747e+02 +3.508373e-01 -8.764458e-02 9.323259e-01 3.196565e+02 4.588471e-02 9.960235e-01 7.636600e-02 -4.775139e+01 -9.353116e-01 1.598745e-02 3.534637e-01 6.486892e+02 +3.560958e-01 -8.678912e-02 9.304104e-01 3.207551e+02 4.779889e-02 9.960658e-01 7.461944e-02 -4.768586e+01 -9.332261e-01 1.790091e-02 3.588433e-01 6.491055e+02 +3.623513e-01 -8.834309e-02 9.278454e-01 3.218549e+02 5.084954e-02 9.958889e-01 7.496348e-02 -4.761891e+01 -9.306534e-01 2.001739e-02 3.653538e-01 6.495291e+02 +3.692764e-01 -9.130352e-02 9.248236e-01 3.229485e+02 5.216536e-02 9.956294e-01 7.746455e-02 -4.755330e+01 -9.278543e-01 1.963792e-02 3.724253e-01 6.499610e+02 +3.767435e-01 -9.262825e-02 9.216748e-01 3.240281e+02 5.395324e-02 9.954929e-01 7.799307e-02 -4.748866e+01 -9.247450e-01 2.034396e-02 3.800430e-01 6.504026e+02 +3.842794e-01 -9.172088e-02 9.186494e-01 3.250969e+02 5.325900e-02 9.955979e-01 7.712495e-02 -4.742592e+01 -9.216793e-01 1.928881e-02 3.874727e-01 6.508541e+02 +3.910436e-01 -9.149333e-02 9.158132e-01 3.261668e+02 5.361546e-02 9.956214e-01 7.657319e-02 -4.735922e+01 -9.188091e-01 1.915828e-02 3.942368e-01 6.513117e+02 +3.979183e-01 -8.979247e-02 9.130161e-01 3.272280e+02 5.088868e-02 9.958268e-01 7.575794e-02 -4.729668e+01 -9.160084e-01 1.631671e-02 4.008271e-01 6.517823e+02 +4.046475e-01 -8.712358e-02 9.103131e-01 3.282862e+02 4.907830e-02 9.960856e-01 7.351662e-02 -4.723387e+01 -9.131548e-01 1.492829e-02 4.073394e-01 6.522582e+02 +4.110474e-01 -8.464637e-02 9.076756e-01 3.293361e+02 4.719688e-02 9.963205e-01 7.153962e-02 -4.717541e+01 -9.103914e-01 1.343328e-02 4.135300e-01 6.527391e+02 +4.167179e-01 -8.219669e-02 9.053121e-01 3.303813e+02 4.371083e-02 9.965634e-01 7.036152e-02 -4.711852e+01 -9.079843e-01 1.025104e-02 4.188786e-01 6.532279e+02 +4.213123e-01 -8.154113e-02 9.032425e-01 3.314174e+02 4.192903e-02 9.966362e-01 7.041479e-02 -4.706230e+01 -9.059458e-01 8.205457e-03 4.233140e-01 6.537162e+02 +4.256956e-01 -8.282301e-02 9.010681e-01 3.324442e+02 4.080218e-02 9.965463e-01 7.232269e-02 -4.700541e+01 -9.039460e-01 5.978085e-03 4.276047e-01 6.542056e+02 +4.299699e-01 -8.442538e-02 8.988873e-01 3.334522e+02 4.134102e-02 9.964150e-01 7.381052e-02 -4.695034e+01 -9.018962e-01 5.424613e-03 4.319186e-01 6.546942e+02 +4.340873e-01 -8.630114e-02 8.967276e-01 3.344337e+02 4.229397e-02 9.962555e-01 7.540609e-02 -4.689904e+01 -8.998774e-01 5.193342e-03 4.361118e-01 6.551805e+02 +4.382206e-01 -8.899318e-02 8.944512e-01 3.354005e+02 4.505428e-02 9.960107e-01 7.702428e-02 -4.684069e+01 -8.977376e-01 6.545219e-03 4.404819e-01 6.556592e+02 +4.421976e-01 -8.888276e-02 8.925027e-01 3.363417e+02 4.424228e-02 9.960279e-01 7.727246e-02 -4.678533e+01 -8.958258e-01 5.316651e-03 4.443735e-01 6.561377e+02 +4.456857e-01 -8.573071e-02 8.910749e-01 3.372740e+02 4.458062e-02 9.962941e-01 7.355618e-02 -4.672678e+01 -8.940787e-01 6.941732e-03 4.478560e-01 6.566144e+02 +4.496116e-01 -7.956947e-02 8.896731e-01 3.381779e+02 4.167102e-02 9.968084e-01 6.809215e-02 -4.667213e+01 -8.922516e-01 6.458554e-03 4.514923e-01 6.570911e+02 +4.528546e-01 -7.767356e-02 8.881946e-01 3.390875e+02 3.861527e-02 9.969718e-01 6.749789e-02 -4.661978e+01 -8.907477e-01 3.731140e-03 4.544826e-01 6.575703e+02 +4.559224e-01 -7.950044e-02 8.864618e-01 3.399788e+02 3.681620e-02 9.968347e-01 7.046381e-02 -4.657074e+01 -8.892577e-01 5.101217e-04 4.574061e-01 6.580471e+02 +4.585133e-01 -7.904540e-02 8.851652e-01 3.408536e+02 3.496802e-02 9.968698e-01 7.090730e-02 -4.652369e+01 -8.879993e-01 -1.559464e-03 4.598420e-01 6.585201e+02 +4.609927e-01 -7.525243e-02 8.842075e-01 3.417099e+02 3.207591e-02 9.971598e-01 6.814231e-02 -4.647692e+01 -8.868240e-01 -3.051344e-03 4.620971e-01 6.589884e+02 +4.628372e-01 -7.305772e-02 8.834276e-01 3.425568e+02 3.088936e-02 9.973219e-01 6.629329e-02 -4.643047e+01 -8.859049e-01 -3.394488e-03 4.638544e-01 6.594475e+02 +4.644662e-01 -7.330024e-02 8.825522e-01 3.433920e+02 3.044099e-02 9.973012e-01 6.681035e-02 -4.638757e+01 -8.850675e-01 -4.165390e-03 4.654440e-01 6.599013e+02 +4.658809e-01 -7.494152e-02 8.816682e-01 3.442098e+02 2.792578e-02 9.971559e-01 7.000173e-02 -4.634690e+01 -8.844066e-01 -7.991202e-03 4.666487e-01 6.603519e+02 +4.674020e-01 -7.591721e-02 8.807792e-01 3.450146e+02 2.665101e-02 9.970631e-01 7.179724e-02 -4.630406e+01 -8.836430e-01 -1.008452e-02 4.680525e-01 6.607923e+02 +4.689806e-01 -7.538693e-02 8.799853e-01 3.457975e+02 2.580446e-02 9.970947e-01 7.166725e-02 -4.626209e+01 -8.828314e-01 -1.090301e-02 4.695634e-01 6.612229e+02 +4.701841e-01 -7.343241e-02 8.795082e-01 3.465648e+02 2.508719e-02 9.972419e-01 6.985073e-02 -4.622240e+01 -8.822117e-01 -1.077832e-02 4.707295e-01 6.616441e+02 +4.712629e-01 -6.973877e-02 8.792314e-01 3.473153e+02 2.438207e-02 9.975182e-01 6.605239e-02 -4.618512e+01 -8.816557e-01 -9.690562e-03 4.717936e-01 6.620599e+02 +4.719460e-01 -6.737458e-02 8.790493e-01 3.480617e+02 2.394181e-02 9.976874e-01 6.361364e-02 -4.614579e+01 -8.813023e-01 -8.976180e-03 4.724676e-01 6.624702e+02 +4.722907e-01 -6.588441e-02 8.789771e-01 3.487954e+02 2.289738e-02 9.977831e-01 6.248642e-02 -4.611077e+01 -8.811454e-01 -9.385491e-03 4.727522e-01 6.628760e+02 +4.716902e-01 -6.405206e-02 8.794349e-01 3.495203e+02 2.213006e-02 9.979039e-01 6.081096e-02 -4.607697e+01 -8.814866e-01 -9.221984e-03 4.721189e-01 6.632734e+02 +4.704661e-01 -6.215940e-02 8.802261e-01 3.502278e+02 2.034625e-02 9.980148e-01 5.960262e-02 -4.604932e+01 -8.821834e-01 -1.013171e-02 4.707968e-01 6.636636e+02 +4.681785e-01 -5.997303e-02 8.815964e-01 3.509245e+02 2.031889e-02 9.981610e-01 5.711215e-02 -4.602088e+01 -8.834002e-01 -8.825621e-03 4.685361e-01 6.640404e+02 +4.655261e-01 -5.658093e-02 8.832237e-01 3.516049e+02 1.842382e-02 9.983576e-01 5.424587e-02 -4.599462e+01 -8.848423e-01 -8.980518e-03 4.658039e-01 6.644077e+02 +4.623306e-01 -5.373284e-02 8.850781e-01 3.522698e+02 1.657890e-02 9.985116e-01 5.195919e-02 -4.597052e+01 -8.865526e-01 -9.348704e-03 4.625332e-01 6.647645e+02 +4.588967e-01 -5.342901e-02 8.868817e-01 3.529208e+02 1.726682e-02 9.985380e-01 5.122127e-02 -4.594775e+01 -8.883218e-01 -8.191648e-03 4.591483e-01 6.651061e+02 +4.556032e-01 -5.491585e-02 8.884875e-01 3.535573e+02 1.948359e-02 9.984714e-01 5.172287e-02 -4.593311e+01 -8.899697e-01 -6.254184e-03 4.559767e-01 6.654315e+02 +4.524485e-01 -5.288851e-02 8.902209e-01 3.541715e+02 1.892312e-02 9.985844e-01 4.970891e-02 -4.592251e+01 -8.915897e-01 -5.644965e-03 4.528088e-01 6.657436e+02 +4.489446e-01 -4.493529e-02 8.924291e-01 3.547560e+02 1.392868e-02 9.989653e-01 4.329263e-02 -4.591782e+01 -8.934510e-01 -7.005631e-03 4.491059e-01 6.660454e+02 +4.452395e-01 -3.606391e-02 8.946850e-01 3.553172e+02 8.991196e-03 9.993182e-01 3.580712e-02 -4.591016e+01 -8.953663e-01 -7.898458e-03 4.452602e-01 6.663335e+02 +4.415701e-01 -2.728376e-02 8.968119e-01 3.558672e+02 6.692660e-03 9.996099e-01 2.711587e-02 -4.590290e+01 -8.972018e-01 -5.971503e-03 4.415804e-01 6.665966e+02 +4.372126e-01 -2.209692e-02 8.990867e-01 3.563955e+02 4.401658e-03 9.997387e-01 2.243019e-02 -4.589886e+01 -8.993474e-01 -5.849289e-03 4.371956e-01 6.668483e+02 +4.328266e-01 -2.149739e-02 9.012209e-01 3.569033e+02 -5.560133e-04 9.997090e-01 2.411372e-02 -4.590091e+01 -9.014770e-01 -1.093815e-02 4.326887e-01 6.670903e+02 +4.288936e-01 -2.122338e-02 9.031057e-01 3.573858e+02 -7.008119e-03 9.996157e-01 2.681964e-02 -4.590295e+01 -9.033278e-01 -1.783184e-02 4.285800e-01 6.673234e+02 +4.252223e-01 -1.781958e-02 9.049136e-01 3.578454e+02 -1.448893e-02 9.995440e-01 2.649145e-02 -4.590799e+01 -9.049729e-01 -2.437598e-02 4.247702e-01 6.675431e+02 +4.217187e-01 -1.386414e-02 9.066208e-01 3.582796e+02 -2.022165e-02 9.994906e-01 2.469050e-02 -4.591249e+01 -9.065012e-01 -2.874581e-02 4.212235e-01 6.677507e+02 +4.192726e-01 -9.403323e-03 9.078117e-01 3.586883e+02 -2.586998e-02 9.994165e-01 2.230023e-02 -4.591872e+01 -9.074917e-01 -3.283494e-02 4.187847e-01 6.679451e+02 +4.173598e-01 -4.469723e-03 9.087304e-01 3.590755e+02 -2.935758e-02 9.993996e-01 1.839898e-02 -4.592477e+01 -9.082670e-01 -3.435711e-02 4.169779e-01 6.681259e+02 +4.159444e-01 4.389025e-04 9.093900e-01 3.594402e+02 -3.262531e-02 9.993633e-01 1.444011e-02 -4.592544e+01 -9.088046e-01 -3.567541e-02 4.156938e-01 6.682950e+02 +4.148804e-01 2.440999e-03 9.098727e-01 3.597855e+02 -3.563575e-02 9.992727e-01 1.356821e-02 -4.592420e+01 -9.091778e-01 -3.805318e-02 4.146656e-01 6.684547e+02 +4.144209e-01 1.702036e-03 9.100838e-01 3.601081e+02 -3.967483e-02 9.990813e-01 1.619807e-02 -4.592316e+01 -9.092201e-01 -4.282024e-02 4.141076e-01 6.686075e+02 +4.145767e-01 2.985035e-04 9.100144e-01 3.604064e+02 -4.304338e-02 9.988871e-01 1.928168e-02 -4.592953e+01 -9.089958e-01 -4.716382e-02 4.141281e-01 6.687492e+02 +4.155065e-01 -1.100832e-03 9.095896e-01 3.606847e+02 -4.423547e-02 9.987915e-01 2.141584e-02 -4.593283e+01 -9.085139e-01 -4.913454e-02 4.149557e-01 6.688793e+02 +4.176025e-01 -2.275641e-03 9.086270e-01 3.609441e+02 -4.459276e-02 9.987405e-01 2.299604e-02 -4.593697e+01 -9.075349e-01 -5.012138e-02 4.169750e-01 6.690001e+02 +4.213119e-01 -3.204920e-03 9.069102e-01 3.611981e+02 -4.468696e-02 9.987057e-01 2.428897e-02 -4.593865e+01 -9.058142e-01 -5.076028e-02 4.206234e-01 6.691217e+02 +4.280453e-01 -4.686766e-03 9.037452e-01 3.614489e+02 -4.467205e-02 9.986545e-01 2.633720e-02 -4.594283e+01 -9.026525e-01 -5.164566e-02 4.272600e-01 6.692405e+02 +4.381751e-01 -6.980283e-03 8.988626e-01 3.617079e+02 -4.480262e-02 9.985574e-01 2.959474e-02 -4.594049e+01 -8.977724e-01 -5.323907e-02 4.372302e-01 6.693606e+02 +4.516673e-01 -8.797285e-03 8.921431e-01 3.619617e+02 -4.524789e-02 9.984387e-01 3.275320e-02 -4.593546e+01 -8.910383e-01 -5.516113e-02 4.505640e-01 6.694902e+02 +4.683838e-01 -9.790876e-03 8.834709e-01 3.622022e+02 -4.508988e-02 9.983707e-01 3.496922e-02 -4.592935e+01 -8.823738e-01 -5.621460e-02 4.671792e-01 6.696098e+02 +4.883456e-01 -1.004153e-02 8.725926e-01 3.624395e+02 -4.443267e-02 9.983506e-01 3.635542e-02 -4.591977e+01 -8.715184e-01 -5.652562e-02 4.870940e-01 6.697520e+02 +5.108513e-01 -1.058499e-02 8.596040e-01 3.626587e+02 -4.310364e-02 9.983511e-01 3.790942e-02 -4.591504e+01 -8.585878e-01 -5.641813e-02 5.095527e-01 6.698788e+02 +5.356411e-01 -1.109668e-02 8.443728e-01 3.628842e+02 -4.173656e-02 9.983437e-01 3.959640e-02 -4.590714e+01 -8.434137e-01 -5.645067e-02 5.342908e-01 6.700417e+02 +5.621843e-01 -1.186066e-02 8.269270e-01 3.631119e+02 -3.967419e-02 9.983591e-01 4.129192e-02 -4.589847e+01 -8.260598e-01 -5.602132e-02 5.607912e-01 6.702194e+02 +5.906003e-01 -1.133723e-02 8.068846e-01 3.633164e+02 -3.770010e-02 9.984218e-01 4.162308e-02 -4.588873e+01 -8.060831e-01 -5.500223e-02 5.892408e-01 6.703699e+02 +6.211704e-01 -9.988943e-03 7.836119e-01 3.635445e+02 -3.521466e-02 9.985529e-01 4.064358e-02 -4.587947e+01 -7.828839e-01 -5.284121e-02 6.199198e-01 6.705828e+02 +6.539635e-01 -8.753392e-03 7.564755e-01 3.637789e+02 -3.300851e-02 9.986506e-01 4.009110e-02 -4.586872e+01 -7.558057e-01 -5.118824e-02 6.527920e-01 6.708330e+02 +6.884677e-01 -8.631181e-03 7.252157e-01 3.639733e+02 -3.094653e-02 9.986689e-01 4.126410e-02 -4.586187e+01 -7.246064e-01 -5.085190e-02 6.872841e-01 6.710275e+02 +7.240291e-01 -9.454541e-03 6.897047e-01 3.642098e+02 -2.854756e-02 9.986386e-01 4.365772e-02 -4.584629e+01 -6.891784e-01 -5.129884e-02 7.227735e-01 6.713305e+02 +7.594384e-01 -1.038039e-02 6.504965e-01 3.644453e+02 -2.478272e-02 9.986854e-01 4.486987e-02 -4.582695e+01 -6.501070e-01 -5.019697e-02 7.581827e-01 6.716636e+02 +7.942240e-01 -1.240515e-02 6.074985e-01 3.646234e+02 -1.886104e-02 9.988065e-01 4.505400e-02 -4.581940e+01 -6.073323e-01 -4.724102e-02 7.930420e-01 6.719168e+02 +8.282055e-01 -1.384352e-02 5.602536e-01 3.648450e+02 -1.404601e-02 9.988681e-01 4.544518e-02 -4.580068e+01 -5.602486e-01 -4.550727e-02 8.270735e-01 6.723095e+02 +8.605409e-01 -1.353837e-02 5.092015e-01 3.649862e+02 -1.268251e-02 9.987674e-01 4.798788e-02 -4.578410e+01 -5.092235e-01 -4.775348e-02 8.593084e-01 6.726122e+02 +8.903362e-01 -1.254473e-02 4.551309e-01 3.651747e+02 -1.167795e-02 9.986623e-01 5.037068e-02 -4.576347e+01 -4.551539e-01 -5.016183e-02 8.889987e-01 6.730667e+02 +9.174953e-01 -1.298175e-02 3.975349e-01 3.653492e+02 -8.844401e-03 9.985542e-01 5.302094e-02 -4.573890e+01 -3.976484e-01 -5.216241e-02 9.160539e-01 6.735524e+02 +9.414289e-01 -1.471172e-02 3.368905e-01 3.654375e+02 -4.567834e-03 9.983998e-01 5.636392e-02 -4.570907e+01 -3.371806e-01 -5.460148e-02 9.398552e-01 6.739384e+02 +9.614001e-01 -1.696381e-02 2.746308e-01 3.655727e+02 3.580119e-04 9.981740e-01 6.040341e-02 -4.567051e+01 -2.751540e-01 -5.797352e-02 9.596506e-01 6.744968e+02 +9.772324e-01 -1.806534e-02 2.114015e-01 3.656931e+02 4.542203e-03 9.979215e-01 6.428053e-02 -4.562737e+01 -2.121234e-01 -6.185678e-02 9.752832e-01 6.750790e+02 +9.889695e-01 -1.748819e-02 1.470835e-01 3.657132e+02 7.516876e-03 9.976517e-01 6.807806e-02 -4.558344e+01 -1.479287e-01 -6.622150e-02 9.867784e-01 6.755436e+02 +9.964214e-01 -1.252317e-02 8.359240e-02 3.657584e+02 6.683055e-03 9.975399e-01 6.978173e-02 -4.553821e+01 -8.426063e-02 -6.897334e-02 9.940537e-01 6.761582e+02 +9.997171e-01 -9.020692e-03 2.201077e-02 3.657652e+02 7.412484e-03 9.973711e-01 7.208258e-02 -4.549311e+01 -2.260314e-02 -7.189901e-02 9.971557e-01 6.767824e+02 +9.993094e-01 -5.958439e-03 -3.667812e-02 3.656874e+02 8.731552e-03 9.970759e-01 7.591733e-02 -4.544439e+01 3.611852e-02 -7.618515e-02 9.964392e-01 6.773174e+02 +9.958580e-01 -6.608202e-03 -9.068172e-02 3.656377e+02 1.389175e-02 9.967040e-01 7.992554e-02 -4.539211e+01 8.985467e-02 -8.085421e-02 9.926674e-01 6.779627e+02 +9.900450e-01 -8.142547e-03 -1.405159e-01 3.655237e+02 2.013909e-02 9.962482e-01 8.416561e-02 -4.533884e+01 1.393034e-01 -8.615758e-02 9.864945e-01 6.785395e+02 +9.826478e-01 -7.702452e-03 -1.853216e-01 3.654154e+02 2.444358e-02 9.958009e-01 8.822133e-02 -4.528313e+01 1.838639e-01 -9.122040e-02 9.787098e-01 6.791995e+02 +9.744651e-01 -8.104972e-03 -2.243927e-01 3.652716e+02 2.857916e-02 9.956975e-01 8.814590e-02 -4.522646e+01 2.227128e-01 -9.230804e-02 9.705041e-01 6.798602e+02 +9.660557e-01 -1.226537e-02 -2.580426e-01 3.650891e+02 3.558847e-02 9.956671e-01 8.590913e-02 -4.517599e+01 2.558708e-01 -9.217632e-02 9.623064e-01 6.804893e+02 +9.576799e-01 -1.661763e-02 -2.873553e-01 3.649051e+02 4.244706e-02 9.955704e-01 8.389152e-02 -4.511727e+01 2.846883e-01 -9.253859e-02 9.541431e-01 6.811641e+02 +9.494987e-01 -2.233226e-02 -3.129753e-01 3.646890e+02 5.065837e-02 9.952888e-01 8.266788e-02 -4.506225e+01 3.096547e-01 -9.434785e-02 9.461566e-01 6.818238e+02 +9.415209e-01 -2.785344e-02 -3.358015e-01 3.644661e+02 5.869938e-02 9.948974e-01 8.205852e-02 -4.500192e+01 3.318024e-01 -9.697113e-02 9.383516e-01 6.825146e+02 +9.335803e-01 -3.045109e-02 -3.570724e-01 3.642128e+02 6.365167e-02 9.946307e-01 8.159788e-02 -4.495042e+01 3.526704e-01 -9.890640e-02 9.305058e-01 6.832142e+02 +9.254135e-01 -3.289664e-02 -3.775285e-01 3.639316e+02 6.785368e-02 9.945094e-01 7.966733e-02 -4.490320e+01 3.728349e-01 -9.934190e-02 9.225645e-01 6.839027e+02 +9.164547e-01 -3.443654e-02 -3.986540e-01 3.636163e+02 7.067322e-02 9.945573e-01 7.655685e-02 -4.484528e+01 3.938479e-01 -9.833502e-02 9.139004e-01 6.846108e+02 +9.069601e-01 -3.490424e-02 -4.197679e-01 3.632589e+02 7.322490e-02 9.944519e-01 7.552144e-02 -4.478500e+01 4.148029e-01 -9.923237e-02 9.044840e-01 6.853096e+02 +8.979010e-01 -3.342474e-02 -4.389267e-01 3.628926e+02 7.433470e-02 9.943065e-01 7.634707e-02 -4.472912e+01 4.338758e-01 -1.011796e-01 8.952734e-01 6.860324e+02 +8.902071e-01 -2.871577e-02 -4.546502e-01 3.625015e+02 7.128543e-02 9.944976e-01 7.676457e-02 -4.467898e+01 4.499442e-01 -1.007463e-01 8.873558e-01 6.867607e+02 +8.840638e-01 -2.449151e-02 -4.667242e-01 3.620888e+02 6.726968e-02 9.948958e-01 7.521398e-02 -4.462544e+01 4.624998e-01 -9.789032e-02 8.811988e-01 6.874867e+02 +8.793818e-01 -2.012778e-02 -4.756917e-01 3.616711e+02 6.262981e-02 9.953145e-01 7.366545e-02 -4.456814e+01 4.719800e-01 -9.457251e-02 8.765220e-01 6.882293e+02 +8.760166e-01 -1.740376e-02 -4.819669e-01 3.612402e+02 6.139860e-02 9.952416e-01 7.565924e-02 -4.450869e+01 4.783567e-01 -9.587082e-02 8.729167e-01 6.889880e+02 +8.737257e-01 -1.559238e-02 -4.861690e-01 3.608088e+02 6.212362e-02 9.948781e-01 7.973868e-02 -4.444816e+01 4.824356e-01 -9.987230e-02 8.702191e-01 6.897600e+02 +8.721986e-01 -1.467570e-02 -4.889318e-01 3.603626e+02 6.174795e-02 9.948571e-01 8.028982e-02 -4.439033e+01 4.852389e-01 -1.002192e-01 8.686191e-01 6.905451e+02 +8.709528e-01 -1.682532e-02 -4.910786e-01 3.599166e+02 6.143177e-02 9.953006e-01 7.485140e-02 -4.432913e+01 4.875114e-01 -9.535984e-02 8.678934e-01 6.913367e+02 +8.700153e-01 -1.946659e-02 -4.926404e-01 3.594591e+02 6.008936e-02 9.959577e-01 6.676423e-02 -4.426711e+01 4.893493e-01 -8.768833e-02 8.676681e-01 6.921401e+02 +8.694531e-01 -2.024939e-02 -4.936005e-01 3.589941e+02 5.894988e-02 9.962731e-01 6.296637e-02 -4.420625e+01 4.904858e-01 -8.384397e-02 8.674063e-01 6.929616e+02 +8.690489e-01 -1.810564e-02 -4.943949e-01 3.585174e+02 5.766774e-02 9.962250e-01 6.488494e-02 -4.415144e+01 4.913538e-01 -8.489880e-02 8.668123e-01 6.938003e+02 +8.687538e-01 -1.334632e-02 -4.950644e-01 3.580301e+02 5.570453e-02 9.959266e-01 7.090304e-02 -4.409491e+01 4.921015e-01 -8.917460e-02 8.659584e-01 6.946576e+02 +8.684819e-01 -8.688869e-03 -4.956447e-01 3.575346e+02 5.343346e-02 9.956618e-01 7.617315e-02 -4.403323e+01 4.928326e-01 -9.263900e-02 8.651785e-01 6.955250e+02 +8.679928e-01 -6.740013e-03 -4.965311e-01 3.570357e+02 5.376093e-02 9.953062e-01 8.046974e-02 -4.396431e+01 4.936580e-01 -9.654111e-02 8.642809e-01 6.964075e+02 +8.673350e-01 -8.508941e-03 -4.976522e-01 3.565341e+02 5.619457e-02 9.951349e-01 8.092392e-02 -4.389186e+01 4.945425e-01 -9.815348e-02 8.635934e-01 6.973010e+02 +8.668813e-01 -1.163110e-02 -4.983790e-01 3.560255e+02 5.781165e-02 9.953281e-01 7.732885e-02 -4.381979e+01 4.951512e-01 -9.584702e-02 8.635036e-01 6.982032e+02 +8.665143e-01 -1.396318e-02 -4.989570e-01 3.555088e+02 5.777009e-02 9.956966e-01 7.246220e-02 -4.374673e+01 4.957979e-01 -9.161430e-02 8.635920e-01 6.991156e+02 +8.661675e-01 -1.289999e-02 -4.995873e-01 3.549809e+02 5.631014e-02 9.958199e-01 7.191525e-02 -4.367414e+01 4.965713e-01 -9.042247e-02 8.632732e-01 7.000408e+02 +8.660909e-01 -8.344063e-03 -4.998170e-01 3.544446e+02 5.440688e-02 9.954944e-01 7.765808e-02 -4.360149e+01 4.969170e-01 -9.445241e-02 8.626425e-01 7.009810e+02 +8.661420e-01 -4.667320e-03 -4.997763e-01 3.539043e+02 5.366976e-02 9.950429e-01 8.372035e-02 -4.352657e+01 4.969081e-01 -9.933657e-02 8.620989e-01 7.019293e+02 +8.660950e-01 -3.245759e-03 -4.998689e-01 3.533606e+02 5.205291e-02 9.951282e-01 8.372759e-02 -4.344690e+01 4.971619e-01 -9.853566e-02 8.620445e-01 7.028832e+02 +8.657675e-01 -3.494242e-03 -5.004343e-01 3.528110e+02 5.219916e-02 9.951516e-01 8.335767e-02 -4.336195e+01 4.977167e-01 -9.829059e-02 8.617523e-01 7.038483e+02 +8.654464e-01 -3.562590e-03 -5.009890e-01 3.522574e+02 5.280628e-02 9.950532e-01 8.414564e-02 -4.327750e+01 4.982109e-01 -9.927888e-02 8.613533e-01 7.048238e+02 +8.653866e-01 -4.524694e-03 -5.010844e-01 3.516974e+02 5.210517e-02 9.953513e-01 8.099925e-02 -4.319568e+01 4.983885e-01 -9.620473e-02 8.615994e-01 7.058054e+02 +8.653760e-01 -7.962479e-03 -5.010599e-01 3.511366e+02 5.267494e-02 9.957800e-01 7.515020e-02 -4.311355e+01 4.983470e-01 -9.142646e-02 8.621435e-01 7.067915e+02 +8.650807e-01 -9.984551e-03 -5.015335e-01 3.505675e+02 5.421912e-02 9.958057e-01 7.369645e-02 -4.303342e+01 4.986941e-01 -9.094606e-02 8.619936e-01 7.077964e+02 +8.647270e-01 -9.470151e-03 -5.021530e-01 3.499923e+02 5.588127e-02 9.954284e-01 7.745684e-02 -4.295518e+01 4.991238e-01 -9.503994e-02 8.613029e-01 7.088127e+02 +8.644186e-01 -1.089727e-02 -5.026547e-01 3.494149e+02 5.913397e-02 9.950295e-01 8.012139e-02 -4.287380e+01 4.992831e-01 -9.898237e-02 8.607664e-01 7.098368e+02 +8.641648e-01 -1.421256e-02 -5.030082e-01 3.488414e+02 6.173336e-02 9.950447e-01 7.794240e-02 -4.279265e+01 4.994078e-01 -9.840744e-02 8.607599e-01 7.108532e+02 +8.640978e-01 -1.599877e-02 -5.030697e-01 3.482583e+02 6.062065e-02 9.955270e-01 7.246504e-02 -4.271245e+01 4.996600e-01 -9.311327e-02 8.612024e-01 7.118757e+02 +8.639137e-01 -1.313554e-02 -5.034687e-01 3.476637e+02 5.583633e-02 9.959953e-01 6.982525e-02 -4.263523e+01 5.005352e-01 -8.843481e-02 8.611874e-01 7.129059e+02 +8.638079e-01 -8.750421e-03 -5.037454e-01 3.470617e+02 5.155276e-02 9.961362e-01 7.109756e-02 -4.255925e+01 5.011768e-01 -8.738408e-02 8.609214e-01 7.139479e+02 +8.640821e-01 -3.021523e-03 -5.033419e-01 3.464528e+02 4.811041e-02 9.958995e-01 7.661234e-02 -4.248076e+01 5.010465e-01 -9.041532e-02 8.606842e-01 7.150017e+02 +8.644323e-01 -1.365485e-03 -5.027474e-01 3.458435e+02 4.671336e-02 9.958884e-01 7.761486e-02 -4.239931e+01 5.005743e-01 -9.057780e-02 8.609419e-01 7.160616e+02 +8.645641e-01 -4.491389e-03 -5.025025e-01 3.452406e+02 4.966414e-02 9.958283e-01 7.654724e-02 -4.231459e+01 5.000624e-01 -9.113633e-02 8.611804e-01 7.171265e+02 +8.641171e-01 -8.957659e-03 -5.032112e-01 3.446332e+02 5.422310e-02 9.956789e-01 7.538813e-02 -4.223064e+01 5.003614e-01 -9.242982e-02 8.608688e-01 7.182063e+02 +8.641044e-01 -1.120769e-02 -5.031880e-01 3.440215e+02 5.825673e-02 9.952596e-01 7.787415e-02 -4.214527e+01 4.999298e-01 -9.660545e-02 8.606610e-01 7.192928e+02 +8.647492e-01 -6.744441e-03 -5.021587e-01 3.433962e+02 5.505695e-02 9.951559e-01 8.144573e-02 -4.205857e+01 4.991769e-01 -9.807744e-02 8.609316e-01 7.203847e+02 +8.654392e-01 -4.223605e-03 -5.009962e-01 3.427696e+02 5.373851e-02 9.949782e-01 8.444179e-02 -4.196828e+01 4.981236e-01 -1.000020e-01 8.613201e-01 7.214820e+02 +8.661115e-01 -2.434736e-03 -4.998451e-01 3.421423e+02 5.113143e-02 9.951740e-01 8.375100e-02 -4.187603e+01 4.972289e-01 -9.809547e-02 8.620560e-01 7.225816e+02 +8.667211e-01 -3.952202e-03 -4.987775e-01 3.415171e+02 5.117354e-02 9.953966e-01 8.103649e-02 -4.178230e+01 4.961612e-01 -9.576022e-02 8.629334e-01 7.236888e+02 +8.666559e-01 -4.339114e-03 -4.988876e-01 3.408890e+02 5.177082e-02 9.953460e-01 8.127795e-02 -4.169008e+01 4.962131e-01 -9.626781e-02 8.628470e-01 7.248065e+02 +8.668230e-01 -4.335698e-03 -4.985972e-01 3.402575e+02 5.389666e-02 9.949180e-01 8.504901e-02 -4.159486e+01 4.956945e-01 -1.005951e-01 8.626514e-01 7.259315e+02 +8.669929e-01 -2.705386e-03 -4.983132e-01 3.396190e+02 5.361275e-02 9.946874e-01 8.787819e-02 -4.149517e+01 4.954281e-01 -1.029057e-01 8.625319e-01 7.270606e+02 +8.673925e-01 -1.681747e-03 -4.976219e-01 3.389807e+02 5.447284e-02 9.943058e-01 9.158993e-02 -4.139341e+01 4.946343e-01 -1.065513e-01 8.625449e-01 7.281963e+02 +8.677103e-01 -1.296415e-03 -4.970686e-01 3.383386e+02 5.569118e-02 9.939540e-01 9.462525e-02 -4.128755e+01 4.939406e-01 -1.097896e-01 8.625363e-01 7.293410e+02 +8.680292e-01 -2.282688e-03 -4.965079e-01 3.376978e+02 5.742269e-02 9.937408e-01 9.582159e-02 -4.117630e+01 4.931814e-01 -1.116867e-01 8.627271e-01 7.304883e+02 +8.682794e-01 -1.144633e-03 -4.960742e-01 3.370509e+02 5.648987e-02 9.937207e-01 9.658140e-02 -4.106322e+01 4.928487e-01 -1.118828e-01 8.628918e-01 7.316410e+02 +8.685595e-01 1.325697e-03 -4.955832e-01 3.364002e+02 5.424119e-02 9.937346e-01 9.772142e-02 -4.094834e+01 4.926077e-01 -1.117579e-01 8.630456e-01 7.328012e+02 +8.692716e-01 2.939478e-03 -4.943261e-01 3.357463e+02 5.237150e-02 9.938069e-01 9.800480e-02 -4.083231e+01 4.915528e-01 -1.110814e-01 8.637342e-01 7.339651e+02 +8.698371e-01 7.175216e-03 -4.932870e-01 3.350848e+02 4.765552e-02 9.939961e-01 9.849171e-02 -4.071617e+01 4.910320e-01 -1.091796e-01 8.642727e-01 7.351365e+02 +8.702468e-01 8.945588e-03 -4.925348e-01 3.344255e+02 4.603602e-02 9.939827e-01 9.939290e-02 -4.059888e+01 4.904602e-01 -1.091707e-01 8.645984e-01 7.363158e+02 +8.705762e-01 9.358408e-03 -4.919448e-01 3.337672e+02 4.549993e-02 9.940038e-01 9.942874e-02 -4.048040e+01 4.899254e-01 -1.089437e-01 8.649302e-01 7.375008e+02 +8.708568e-01 7.607362e-03 -4.914780e-01 3.331111e+02 4.581046e-02 9.942722e-01 9.656209e-02 -4.036271e+01 4.893975e-01 -1.066066e-01 8.655201e-01 7.386867e+02 +8.709611e-01 6.077397e-03 -4.913145e-01 3.324494e+02 4.742667e-02 9.942148e-01 9.637214e-02 -4.024359e+01 4.890578e-01 -1.072378e-01 8.656341e-01 7.398880e+02 +8.711594e-01 6.609368e-03 -4.909558e-01 3.317873e+02 4.915265e-02 9.937126e-01 1.005948e-01 -4.012409e+01 4.885338e-01 -1.117659e-01 8.653571e-01 7.410932e+02 +8.713616e-01 6.582738e-03 -4.905973e-01 3.311254e+02 5.039993e-02 9.934196e-01 1.028460e-01 -4.000253e+01 4.880460e-01 -1.143421e-01 8.652959e-01 7.422982e+02 +8.713322e-01 5.357628e-03 -4.906644e-01 3.304645e+02 5.124248e-02 9.934796e-01 1.018454e-01 -3.987927e+01 4.880106e-01 -1.138840e-01 8.653762e-01 7.435011e+02 +8.712573e-01 5.957595e-03 -4.907905e-01 3.298021e+02 5.094275e-02 9.934284e-01 1.024932e-01 -3.975675e+01 4.881758e-01 -1.143001e-01 8.652282e-01 7.446976e+02 +8.712551e-01 8.493618e-03 -4.907571e-01 3.291395e+02 4.825687e-02 9.935238e-01 1.028669e-01 -3.963677e+01 4.884526e-01 -1.133057e-01 8.652027e-01 7.458897e+02 +8.712589e-01 1.046153e-02 -4.907123e-01 3.284798e+02 4.577772e-02 9.936829e-01 1.024627e-01 -3.951862e+01 4.886843e-01 -1.117352e-01 8.652761e-01 7.470755e+02 +8.712657e-01 1.296909e-02 -4.906404e-01 3.278227e+02 4.271998e-02 9.938532e-01 1.021315e-01 -3.940155e+01 4.889490e-01 -1.099438e-01 8.653560e-01 7.482529e+02 +8.711857e-01 1.519874e-02 -4.907184e-01 3.271702e+02 4.007216e-02 9.939844e-01 1.019273e-01 -3.928620e+01 4.893156e-01 -1.084617e-01 8.653359e-01 7.494249e+02 +8.709806e-01 1.573489e-02 -4.910654e-01 3.265236e+02 3.905085e-02 9.941079e-01 1.011163e-01 -3.917105e+01 4.897631e-01 -1.072468e-01 8.652342e-01 7.505903e+02 +8.708033e-01 1.545084e-02 -4.913888e-01 3.258829e+02 4.010303e-02 9.939428e-01 1.023204e-01 -3.905555e+01 4.899933e-01 -1.088071e-01 8.649089e-01 7.517505e+02 +8.703404e-01 1.857280e-02 -4.921002e-01 3.252373e+02 3.739404e-02 9.939108e-01 1.036481e-01 -3.894135e+01 4.910288e-01 -1.086107e-01 8.643462e-01 7.529099e+02 +8.700252e-01 1.816968e-02 -4.926724e-01 3.245956e+02 3.718934e-02 9.940546e-01 1.023344e-01 -3.882467e+01 4.916026e-01 -1.073556e-01 8.641768e-01 7.540669e+02 +8.696565e-01 1.584432e-02 -4.934031e-01 3.239537e+02 3.696043e-02 9.945897e-01 9.708385e-02 -3.871130e+01 4.922719e-01 -1.026660e-01 8.643657e-01 7.552219e+02 +8.694679e-01 1.112762e-02 -4.938642e-01 3.233131e+02 3.833021e-02 9.952124e-01 8.990575e-02 -3.860026e+01 4.925002e-01 -9.710006e-02 8.648786e-01 7.563745e+02 +8.689064e-01 6.510138e-03 -4.949337e-01 3.226686e+02 4.214046e-02 9.953102e-01 8.707372e-02 -3.849399e+01 4.931794e-01 -9.651563e-02 8.645569e-01 7.575330e+02 +8.683532e-01 7.991153e-03 -4.958820e-01 3.220194e+02 4.315443e-02 9.948602e-01 9.160117e-02 -3.839083e+01 4.940652e-01 -1.009417e-01 8.635452e-01 7.586986e+02 +8.682875e-01 1.493921e-02 -4.958364e-01 3.213617e+02 3.999721e-02 9.941836e-01 9.999547e-02 -3.828137e+01 4.944463e-01 -1.066569e-01 8.626396e-01 7.598649e+02 +8.684388e-01 2.605804e-02 -4.951112e-01 3.206982e+02 3.299067e-02 9.933675e-01 1.101482e-01 -3.815815e+01 4.946976e-01 -1.119910e-01 8.618191e-01 7.610244e+02 +8.687499e-01 3.316360e-02 -4.941396e-01 3.200377e+02 2.533465e-02 9.934732e-01 1.112168e-01 -3.803123e+01 4.946028e-01 -1.091384e-01 8.622394e-01 7.621776e+02 +8.690312e-01 3.321804e-02 -4.936409e-01 3.193838e+02 2.123329e-02 9.943202e-01 1.042899e-01 -3.790656e+01 4.943014e-01 -1.011128e-01 8.633900e-01 7.633271e+02 +8.690302e-01 3.284726e-02 -4.936675e-01 3.187390e+02 1.886458e-02 9.948683e-01 9.940413e-02 -3.778813e+01 4.943993e-01 -9.569800e-02 8.639509e-01 7.644724e+02 +8.689864e-01 3.156591e-02 -4.938283e-01 3.180977e+02 2.018589e-02 9.948713e-01 9.911399e-02 -3.767595e+01 4.944242e-01 -9.609705e-02 8.638923e-01 7.656223e+02 +8.687614e-01 3.204287e-02 -4.941932e-01 3.174596e+02 2.039458e-02 9.947431e-01 1.003503e-01 -3.756350e+01 4.948108e-01 -9.725933e-02 8.635409e-01 7.667668e+02 +8.684091e-01 3.157610e-02 -4.948421e-01 3.168210e+02 2.150903e-02 9.946321e-01 1.012146e-01 -3.745101e+01 4.953817e-01 -9.853923e-02 8.630683e-01 7.679122e+02 +8.676877e-01 3.007268e-02 -4.961993e-01 3.161832e+02 2.368429e-02 9.945341e-01 1.016908e-01 -3.733623e+01 4.965451e-01 -9.998793e-02 8.622327e-01 7.690575e+02 +8.668299e-01 2.887407e-02 -4.977673e-01 3.155428e+02 2.466827e-02 9.946157e-01 1.006531e-01 -3.722087e+01 4.979935e-01 -9.952812e-02 8.614503e-01 7.702017e+02 +8.659436e-01 2.811879e-02 -4.993507e-01 3.148991e+02 2.599964e-02 9.945375e-01 1.010901e-01 -3.710408e+01 4.994655e-01 -1.005212e-01 8.604822e-01 7.713476e+02 +8.649613e-01 2.816438e-02 -5.010476e-01 3.142500e+02 2.596818e-02 9.945743e-01 1.007350e-01 -3.698755e+01 5.011662e-01 -1.001432e-01 8.595369e-01 7.724949e+02 +8.635644e-01 2.849466e-02 -5.034329e-01 3.135970e+02 2.563984e-02 9.946290e-01 1.002780e-01 -3.687047e+01 5.035863e-01 -9.950446e-02 8.581955e-01 7.736395e+02 +8.618294e-01 2.935490e-02 -5.063482e-01 3.129395e+02 2.573176e-02 9.945076e-01 1.014521e-01 -3.675341e+01 5.065452e-01 -1.004636e-01 8.563404e-01 7.747853e+02 +8.598932e-01 3.143378e-02 -5.095054e-01 3.122758e+02 2.595052e-02 9.941200e-01 1.051287e-01 -3.663347e+01 5.098140e-01 -1.036213e-01 8.540212e-01 7.759315e+02 +8.576362e-01 3.296027e-02 -5.131996e-01 3.116090e+02 2.697154e-02 9.936874e-01 1.088933e-01 -3.651134e+01 5.135491e-01 -1.072326e-01 8.513333e-01 7.770758e+02 +8.550246e-01 3.140544e-02 -5.176357e-01 3.109363e+02 2.840548e-02 9.938298e-01 1.072164e-01 -3.638533e+01 5.178090e-01 -1.063764e-01 8.488568e-01 7.782175e+02 +8.517185e-01 2.903983e-02 -5.231945e-01 3.102540e+02 2.921118e-02 9.942791e-01 1.027408e-01 -3.626014e+01 5.231849e-01 -1.027893e-01 8.459975e-01 7.793595e+02 +8.479832e-01 2.836533e-02 -5.292636e-01 3.095586e+02 2.926850e-02 9.945372e-01 1.001950e-01 -3.613653e+01 5.292144e-01 -1.004544e-01 8.425206e-01 7.805056e+02 +8.439651e-01 3.029846e-02 -5.355418e-01 3.088507e+02 2.821767e-02 9.945132e-01 1.007334e-01 -3.601512e+01 5.356554e-01 -1.001272e-01 8.384794e-01 7.816480e+02 +8.396537e-01 3.404299e-02 -5.420542e-01 3.081228e+02 2.530008e-02 9.944986e-01 1.016485e-01 -3.589492e+01 5.425326e-01 -9.906355e-02 8.341731e-01 7.827828e+02 +8.349052e-01 3.617884e-02 -5.492034e-01 3.073845e+02 2.425337e-02 9.944497e-01 1.023797e-01 -3.577474e+01 5.498591e-01 -9.879740e-02 8.293937e-01 7.839108e+02 +8.295679e-01 3.913105e-02 -5.570332e-01 3.066269e+02 2.269568e-02 9.943546e-01 1.036523e-01 -3.565184e+01 5.579445e-01 -9.862881e-02 8.239965e-01 7.850400e+02 +8.238121e-01 4.160687e-02 -5.653340e-01 3.058628e+02 2.243114e-02 9.941289e-01 1.058518e-01 -3.552667e+01 5.664190e-01 -9.988308e-02 8.180420e-01 7.861668e+02 +8.175770e-01 4.375513e-02 -5.741545e-01 3.050858e+02 2.193328e-02 9.940187e-01 1.069844e-01 -3.539980e+01 5.754014e-01 -1.000610e-01 8.117271e-01 7.872901e+02 +8.110856e-01 4.195266e-02 -5.834212e-01 3.042983e+02 2.354506e-02 9.942745e-01 1.042292e-01 -3.527530e+01 5.844535e-01 -9.827546e-02 8.054539e-01 7.883978e+02 +8.039802e-01 4.043654e-02 -5.932796e-01 3.035007e+02 2.476620e-02 9.945427e-01 1.013475e-01 -3.514979e+01 5.941401e-01 -9.617464e-02 7.985912e-01 7.895031e+02 +7.964148e-01 4.231783e-02 -6.032684e-01 3.026736e+02 2.495838e-02 9.943988e-01 1.027039e-01 -3.502526e+01 6.042355e-01 -9.685151e-02 7.908977e-01 7.906036e+02 +7.887614e-01 4.706661e-02 -6.128950e-01 3.018301e+02 2.482285e-02 9.938122e-01 1.082643e-01 -3.489573e+01 6.141981e-01 -1.006085e-01 7.827123e-01 7.916936e+02 +7.811185e-01 5.172639e-02 -6.222365e-01 3.009708e+02 2.318197e-02 9.934728e-01 1.116885e-01 -3.476397e+01 6.239523e-01 -1.016666e-01 7.748209e-01 7.927766e+02 +7.736839e-01 5.325508e-02 -6.313297e-01 3.001061e+02 2.316909e-02 9.934164e-01 1.121918e-01 -3.462860e+01 6.331480e-01 -1.014283e-01 7.673564e-01 7.938477e+02 +7.664853e-01 5.364964e-02 -6.400173e-01 2.992297e+02 2.243628e-02 9.936602e-01 1.101636e-01 -3.449466e+01 6.418699e-01 -9.879835e-02 7.604221e-01 7.949018e+02 +7.598495e-01 5.462383e-02 -6.478002e-01 2.983461e+02 2.120722e-02 9.938506e-01 1.086789e-01 -3.436216e+01 6.497530e-01 -9.631765e-02 7.540184e-01 7.959487e+02 +7.538655e-01 5.647965e-02 -6.545968e-01 2.974504e+02 1.958705e-02 9.939237e-01 1.083147e-01 -3.423041e+01 6.567368e-01 -9.447633e-02 7.481784e-01 7.969851e+02 +7.486490e-01 5.923701e-02 -6.603148e-01 2.965447e+02 1.690066e-02 9.939712e-01 1.083310e-01 -3.410045e+01 6.627511e-01 -9.226161e-02 7.431344e-01 7.980192e+02 +7.442448e-01 6.151064e-02 -6.650686e-01 2.956324e+02 1.433282e-02 9.940501e-01 1.079765e-01 -3.396997e+01 6.677532e-01 -8.989324e-02 7.389349e-01 7.990468e+02 +7.405356e-01 6.190909e-02 -6.691595e-01 2.947108e+02 1.326630e-02 9.942067e-01 1.066631e-01 -3.383867e+01 6.718862e-01 -8.786506e-02 7.354241e-01 8.000761e+02 +7.370311e-01 5.934197e-02 -6.732486e-01 2.937857e+02 1.381368e-02 9.946072e-01 1.027898e-01 -3.370984e+01 6.757176e-01 -8.505927e-02 7.322366e-01 8.011045e+02 +7.333859e-01 5.673297e-02 -6.774412e-01 2.928544e+02 1.542188e-02 9.948667e-01 1.000115e-01 -3.358460e+01 6.796376e-01 -8.379446e-02 7.287463e-01 8.021310e+02 +7.292289e-01 5.670491e-02 -6.819163e-01 2.919173e+02 1.636329e-02 9.948303e-01 1.002240e-01 -3.346174e+01 6.840742e-01 -8.424458e-02 7.245310e-01 8.031509e+02 +7.248429e-01 5.995240e-02 -6.863006e-01 2.909727e+02 1.590061e-02 9.944849e-01 1.036677e-01 -3.333921e+01 6.887307e-01 -8.605537e-02 7.198919e-01 8.041639e+02 +7.200059e-01 6.024287e-02 -6.913483e-01 2.900219e+02 1.558134e-02 9.945704e-01 1.028923e-01 -3.321776e+01 6.937930e-01 -8.485520e-02 7.151578e-01 8.051675e+02 +7.145848e-01 5.603046e-02 -6.973014e-01 2.890667e+02 1.681318e-02 9.951237e-01 9.719138e-02 -3.309657e+01 6.993467e-01 -8.117532e-02 7.101582e-01 8.061657e+02 +7.086400e-01 5.298850e-02 -7.035778e-01 2.881065e+02 1.866511e-02 9.954191e-01 9.376734e-02 -3.297893e+01 7.053233e-01 -7.957962e-02 7.044047e-01 8.071562e+02 +7.020996e-01 5.390677e-02 -7.100354e-01 2.871266e+02 2.119279e-02 9.951068e-01 9.650568e-02 -3.286114e+01 7.117633e-01 -8.280421e-02 6.975216e-01 8.081466e+02 +6.950288e-01 5.593147e-02 -7.168031e-01 2.861351e+02 2.245349e-02 9.947947e-01 9.939433e-02 -3.274106e+01 7.186312e-01 -8.517664e-02 6.901551e-01 8.091326e+02 +6.876187e-01 5.941754e-02 -7.236368e-01 2.851335e+02 2.255369e-02 9.944171e-01 1.030823e-01 -3.261744e+01 7.257216e-01 -8.720199e-02 6.824396e-01 8.101061e+02 +6.802493e-01 6.273275e-02 -7.302914e-01 2.841190e+02 2.102304e-02 9.942511e-01 1.049896e-01 -3.249141e+01 7.326793e-01 -8.677204e-02 6.750197e-01 8.110633e+02 +6.727916e-01 6.400915e-02 -7.370579e-01 2.830982e+02 1.844117e-02 9.944898e-01 1.031988e-01 -3.236580e+01 7.396021e-01 -8.302351e-02 6.679039e-01 8.120104e+02 +6.652885e-01 6.289240e-02 -7.439327e-01 2.820697e+02 1.678510e-02 9.949336e-01 9.912282e-02 -3.224389e+01 7.463977e-01 -7.843224e-02 6.608622e-01 8.129414e+02 +6.576302e-01 6.258664e-02 -7.507367e-01 2.810418e+02 1.638808e-02 9.951186e-01 9.731567e-02 -3.212462e+01 7.531626e-01 -7.630084e-02 6.533943e-01 8.138603e+02 +6.497128e-01 6.503615e-02 -7.573927e-01 2.799942e+02 1.664299e-02 9.948778e-01 9.970546e-02 -3.200692e+01 7.599976e-01 -7.738517e-02 6.453024e-01 8.147737e+02 +6.413365e-01 6.652610e-02 -7.643703e-01 2.789370e+02 1.783142e-02 9.946725e-01 1.015315e-01 -3.188910e+01 7.670525e-01 -7.874562e-02 6.367334e-01 8.156634e+02 +6.328222e-01 6.672439e-02 -7.714169e-01 2.778693e+02 2.008465e-02 9.945303e-01 1.024990e-01 -3.176745e+01 7.740366e-01 -8.035726e-02 6.280207e-01 8.165459e+02 +6.242639e-01 6.921405e-02 -7.781414e-01 2.767989e+02 2.111099e-02 9.942090e-01 1.053691e-01 -3.164460e+01 7.809282e-01 -8.220544e-02 6.191876e-01 8.174152e+02 +6.158549e-01 6.956577e-02 -7.847824e-01 2.757221e+02 2.262440e-02 9.941218e-01 1.058767e-01 -3.152266e+01 7.875347e-01 -8.295992e-02 6.106608e-01 8.182667e+02 +6.075074e-01 6.675682e-02 -7.915039e-01 2.746468e+02 2.405297e-02 9.944590e-01 1.023359e-01 -3.140025e+01 7.939498e-01 -8.120783e-02 6.025355e-01 8.191056e+02 +5.990701e-01 6.674237e-02 -7.979101e-01 2.735615e+02 2.343645e-02 9.946313e-01 1.007935e-01 -3.127921e+01 8.003535e-01 -7.908252e-02 5.942896e-01 8.199278e+02 +5.908167e-01 6.892527e-02 -8.038563e-01 2.724742e+02 2.246110e-02 9.945528e-01 1.017846e-01 -3.116057e+01 8.064931e-01 -7.819153e-02 5.860502e-01 8.207391e+02 +5.823739e-01 7.146790e-02 -8.097735e-01 2.713861e+02 1.978402e-02 9.945869e-01 1.020072e-01 -3.104288e+01 8.126803e-01 -7.542690e-02 5.778074e-01 8.215312e+02 +5.740122e-01 7.523435e-02 -8.153832e-01 2.702930e+02 1.670498e-02 9.944871e-01 1.035200e-01 -3.092561e+01 8.186763e-01 -7.304267e-02 5.695909e-01 8.223062e+02 +5.660588e-01 7.716531e-02 -8.207454e-01 2.692081e+02 1.584478e-02 9.944070e-01 1.044207e-01 -3.080913e+01 8.242125e-01 -7.211278e-02 5.616701e-01 8.230650e+02 +5.582847e-01 7.998495e-02 -8.257849e-01 2.681168e+02 1.543636e-02 9.941681e-01 1.067304e-01 -3.068990e+01 8.295058e-01 -7.233307e-02 5.537942e-01 8.238137e+02 +5.512530e-01 8.414807e-02 -8.300839e-01 2.670320e+02 1.321349e-02 9.938957e-01 1.095292e-01 -3.056845e+01 8.342335e-01 -7.134657e-02 5.467761e-01 8.245404e+02 +5.459153e-01 8.488487e-02 -8.335293e-01 2.659492e+02 1.188139e-02 9.939701e-01 1.090055e-01 -3.044799e+01 8.377561e-01 -6.941123e-02 5.416149e-01 8.252592e+02 +5.414641e-01 8.324378e-02 -8.365926e-01 2.648671e+02 1.092969e-02 9.943049e-01 1.060107e-01 -3.032651e+01 8.406528e-01 -6.654466e-02 5.374705e-01 8.259705e+02 +5.369135e-01 8.307238e-02 -8.395373e-01 2.637813e+02 8.507860e-03 9.945563e-01 1.038526e-01 -3.020811e+01 8.435944e-01 -6.290253e-02 5.332839e-01 8.266733e+02 +5.326124e-01 8.556762e-02 -8.420227e-01 2.626998e+02 7.446793e-03 9.943639e-01 1.057592e-01 -3.009077e+01 8.463265e-01 -6.259900e-02 5.289733e-01 8.273685e+02 +5.284218e-01 9.062448e-02 -8.441313e-01 2.616116e+02 6.706462e-03 9.938098e-01 1.108919e-01 -2.997089e+01 8.489554e-01 -6.425884e-02 5.245430e-01 8.280603e+02 +5.244859e-01 9.251574e-02 -8.463779e-01 2.605383e+02 7.798138e-03 9.935152e-01 1.134314e-01 -2.984842e+01 8.513834e-01 -6.609332e-02 5.203632e-01 8.287383e+02 +5.209198e-01 9.235437e-02 -8.485949e-01 2.594729e+02 8.175455e-03 9.935445e-01 1.131482e-01 -2.972331e+01 8.535665e-01 -6.587874e-02 5.168019e-01 8.294067e+02 +5.167971e-01 9.272250e-02 -8.510719e-01 2.584122e+02 8.875329e-03 9.934838e-01 1.136274e-01 -2.959840e+01 8.560619e-01 -6.627582e-02 5.126065e-01 8.300646e+02 +5.123249e-01 9.260867e-02 -8.537838e-01 2.573593e+02 1.034675e-02 9.934309e-01 1.139647e-01 -2.947671e+01 8.587293e-01 -6.722082e-02 5.080012e-01 8.307114e+02 +5.074429e-01 9.223917e-02 -8.567344e-01 2.563131e+02 9.965454e-03 9.935594e-01 1.128728e-01 -2.935637e+01 8.616278e-01 -6.581423e-02 5.032554e-01 8.313437e+02 +5.027830e-01 9.104515e-02 -8.596046e-01 2.552708e+02 9.994137e-03 9.937590e-01 1.110997e-01 -2.923858e+01 8.643549e-01 -6.445004e-02 4.987351e-01 8.319645e+02 +4.985281e-01 8.966910e-02 -8.622235e-01 2.542289e+02 1.183690e-02 9.938388e-01 1.102008e-01 -2.912152e+01 8.667927e-01 -6.514420e-02 4.943951e-01 8.325822e+02 +4.945982e-01 9.125925e-02 -8.643173e-01 2.531929e+02 1.357111e-02 9.935398e-01 1.126692e-01 -2.900297e+01 8.690158e-01 -6.745573e-02 4.901645e-01 8.331879e+02 +4.907246e-01 9.446323e-02 -8.661790e-01 2.521654e+02 1.604946e-02 9.929571e-01 1.173820e-01 -2.888580e+01 8.711669e-01 -7.150392e-02 4.857524e-01 8.337855e+02 +4.868501e-01 9.695861e-02 -8.680876e-01 2.511463e+02 1.728661e-02 9.925560e-01 1.205556e-01 -2.876729e+01 8.733144e-01 -7.369879e-02 4.815499e-01 8.343710e+02 +4.832285e-01 9.490092e-02 -8.703356e-01 2.501457e+02 1.887631e-02 9.927472e-01 1.187291e-01 -2.864923e+01 8.752907e-01 -7.380201e-02 4.779323e-01 8.349433e+02 +4.795000e-01 9.206656e-02 -8.726990e-01 2.490355e+02 1.809968e-02 9.932321e-01 1.147272e-01 -2.855465e+01 8.773552e-01 -7.080723e-02 4.745884e-01 8.354654e+02 +4.758334e-01 8.996459e-02 -8.749223e-01 2.478952e+02 1.694989e-02 9.936323e-01 1.113894e-01 -2.847107e+01 8.793721e-01 -6.783261e-02 4.712785e-01 8.359631e+02 +4.724208e-01 8.994343e-02 -8.767718e-01 2.467560e+02 1.670932e-02 9.936866e-01 1.109404e-01 -2.839108e+01 8.812147e-01 -6.706080e-02 4.679353e-01 8.364503e+02 +4.696979e-01 9.189369e-02 -8.780316e-01 2.456766e+02 1.752595e-02 9.934012e-01 1.133436e-01 -2.830514e+01 8.826532e-01 -6.862555e-02 4.649879e-01 8.369415e+02 +4.674238e-01 9.465437e-02 -8.789514e-01 2.445919e+02 1.878523e-02 9.929634e-01 1.169223e-01 -2.820361e+01 8.838337e-01 -7.116353e-02 4.623565e-01 8.374299e+02 +4.657610e-01 9.703200e-02 -8.795746e-01 2.435571e+02 1.886118e-02 9.926557e-01 1.194943e-01 -2.808630e+01 8.847095e-01 -7.224559e-02 4.605101e-01 8.379185e+02 +4.646512e-01 9.834066e-02 -8.800161e-01 2.425264e+02 1.935559e-02 9.924486e-01 1.211247e-01 -2.796812e+01 8.852822e-01 -7.331394e-02 4.592390e-01 8.383951e+02 +4.637962e-01 9.668136e-02 -8.806508e-01 2.415525e+02 1.902935e-02 9.927112e-01 1.190057e-01 -2.785652e+01 8.857375e-01 -7.195256e-02 4.585758e-01 8.388677e+02 +4.631175e-01 9.378249e-02 -8.813212e-01 2.405805e+02 1.913583e-02 9.930961e-01 1.157321e-01 -2.774490e+01 8.860903e-01 -7.046236e-02 4.581255e-01 8.393266e+02 +4.625611e-01 9.376654e-02 -8.816151e-01 2.396492e+02 1.707502e-02 9.932649e-01 1.146002e-01 -2.763875e+01 8.864229e-01 -6.806318e-02 4.578446e-01 8.397823e+02 +4.625041e-01 9.706596e-02 -8.812878e-01 2.387202e+02 1.540046e-02 9.929596e-01 1.174479e-01 -2.753424e+01 8.864833e-01 -6.789234e-02 4.577530e-01 8.402275e+02 +4.624712e-01 9.962100e-02 -8.810199e-01 2.378291e+02 1.382838e-02 9.927364e-01 1.195122e-01 -2.743619e+01 8.865264e-01 -6.745401e-02 4.577343e-01 8.406671e+02 +4.625462e-01 9.950579e-02 -8.809936e-01 2.369542e+02 1.180525e-02 9.929025e-01 1.183437e-01 -2.734099e+01 8.865165e-01 -6.513977e-02 4.580886e-01 8.410952e+02 +4.629518e-01 9.587780e-02 -8.811828e-01 2.361140e+02 1.231848e-02 9.933407e-01 1.145531e-01 -2.724592e+01 8.862978e-01 -6.388737e-02 4.586878e-01 8.415167e+02 +4.632062e-01 9.443666e-02 -8.812048e-01 2.352886e+02 1.183100e-02 9.935590e-01 1.126964e-01 -2.715287e+01 8.861715e-01 -6.262718e-02 4.591054e-01 8.419323e+02 +4.641962e-01 9.636805e-02 -8.804744e-01 2.344774e+02 1.082282e-02 9.933723e-01 1.144307e-01 -2.706291e+01 8.856662e-01 -6.264749e-02 4.600767e-01 8.423392e+02 +4.659907e-01 1.001888e-01 -8.790989e-01 2.336903e+02 1.117817e-02 9.928223e-01 1.190749e-01 -2.697538e+01 8.847190e-01 -6.531451e-02 4.615260e-01 8.427429e+02 +4.683251e-01 9.844659e-02 -8.780546e-01 2.329269e+02 1.531862e-02 9.927192e-01 1.194731e-01 -2.689215e+01 8.834234e-01 -6.940283e-02 4.634072e-01 8.431405e+02 +4.701528e-01 9.327997e-02 -8.776419e-01 2.321936e+02 1.855434e-02 9.931348e-01 1.154947e-01 -2.681089e+01 8.823900e-01 -7.058419e-02 4.651943e-01 8.435287e+02 +4.715729e-01 8.827537e-02 -8.773976e-01 2.314726e+02 1.897166e-02 9.937309e-01 1.101764e-01 -2.672707e+01 8.816230e-01 -6.860186e-02 4.669418e-01 8.439045e+02 +4.729773e-01 8.590314e-02 -8.768769e-01 2.307758e+02 2.136119e-02 9.938251e-01 1.088820e-01 -2.664634e+01 8.808156e-01 -7.022981e-02 4.682217e-01 8.442762e+02 +4.729099e-01 8.735864e-02 -8.767695e-01 2.300934e+02 2.437816e-02 9.933947e-01 1.121279e-01 -2.657214e+01 8.807735e-01 -7.440039e-02 4.676565e-01 8.446393e+02 +4.710113e-01 8.843968e-02 -8.776827e-01 2.294323e+02 2.683798e-02 9.930642e-01 1.144688e-01 -2.650107e+01 8.817188e-01 -7.747130e-02 4.653709e-01 8.449890e+02 +4.664550e-01 8.606038e-02 -8.803484e-01 2.287884e+02 2.750337e-02 9.933634e-01 1.116811e-01 -2.643396e+01 8.841172e-01 -7.630676e-02 4.609924e-01 8.453182e+02 +4.588877e-01 8.304245e-02 -8.846051e-01 2.281646e+02 2.845025e-02 9.937387e-01 1.080459e-01 -2.636748e+01 8.880386e-01 -7.474816e-02 4.536518e-01 8.456333e+02 +4.491171e-01 7.964334e-02 -8.899162e-01 2.275476e+02 3.137626e-02 9.939989e-01 1.047930e-01 -2.630276e+01 8.929218e-01 -7.498656e-02 4.439230e-01 8.459295e+02 +4.356431e-01 7.769790e-02 -8.967598e-01 2.269412e+02 3.301583e-02 9.942178e-01 1.021809e-01 -2.623913e+01 8.995137e-01 -7.412167e-02 4.305588e-01 8.462152e+02 +4.190977e-01 7.833077e-02 -9.045560e-01 2.263397e+02 3.531154e-02 9.941116e-01 1.024464e-01 -2.617903e+01 9.072542e-01 -7.487631e-02 4.138639e-01 8.464875e+02 +3.988220e-01 8.138573e-02 -9.134098e-01 2.257346e+02 3.611513e-02 9.938873e-01 1.043253e-01 -2.612033e+01 9.163169e-01 -7.459512e-02 3.934449e-01 8.467158e+02 +3.746323e-01 8.446360e-02 -9.233182e-01 2.251385e+02 3.578317e-02 9.937829e-01 1.054285e-01 -2.606265e+01 9.264827e-01 -7.253615e-02 3.692808e-01 8.469498e+02 +3.494279e-01 8.744012e-02 -9.328743e-01 2.245598e+02 3.320755e-02 9.938546e-01 1.055945e-01 -2.600722e+01 9.363746e-01 -6.787613e-02 3.443769e-01 8.471486e+02 +3.220980e-01 8.766285e-02 -9.426389e-01 2.239772e+02 3.301213e-02 9.940580e-01 1.037249e-01 -2.595647e+01 9.461305e-01 -6.452808e-02 3.172901e-01 8.472958e+02 +2.908621e-01 8.693072e-02 -9.528076e-01 2.234159e+02 3.516830e-02 9.942193e-01 1.014448e-01 -2.590336e+01 9.561184e-01 -6.301505e-02 2.861235e-01 8.474606e+02 +2.553298e-01 8.540993e-02 -9.630742e-01 2.228629e+02 3.854195e-02 9.943997e-01 9.840626e-02 -2.584709e+01 9.660855e-01 -6.224479e-02 2.506080e-01 8.476111e+02 +2.152551e-01 8.206535e-02 -9.731036e-01 2.222901e+02 4.009302e-02 9.948800e-01 9.277061e-02 -2.580198e+01 9.757344e-01 -5.898399e-02 2.108627e-01 8.476609e+02 +1.707452e-01 7.961600e-02 -9.820934e-01 2.217286e+02 4.289091e-02 9.951847e-01 8.813424e-02 -2.575078e+01 9.843812e-01 -5.717136e-02 1.665082e-01 8.477623e+02 +1.212278e-01 8.088203e-02 -9.893240e-01 2.211600e+02 4.792574e-02 9.950354e-01 8.722161e-02 -2.570592e+01 9.914670e-01 -5.798775e-02 1.167496e-01 8.478532e+02 +6.765468e-02 8.517499e-02 -9.940665e-01 2.205503e+02 5.443821e-02 9.945499e-01 8.892141e-02 -2.565397e+01 9.962225e-01 -6.013113e-02 6.264917e-02 8.477832e+02 +9.692640e-03 8.933662e-02 -9.959544e-01 2.199659e+02 5.968649e-02 9.941735e-01 8.975777e-02 -2.560791e+01 9.981701e-01 -6.031499e-02 4.303975e-03 8.478177e+02 +-5.118510e-02 9.281061e-02 -9.943673e-01 2.193436e+02 6.120870e-02 9.940921e-01 8.963422e-02 -2.556375e+01 9.968117e-01 -5.627597e-02 -5.656352e-02 8.476509e+02 +-1.134958e-01 9.442541e-02 -9.890413e-01 2.187663e+02 6.475382e-02 9.940600e-01 8.747385e-02 -2.551769e+01 9.914260e-01 -5.411627e-02 -1.189360e-01 8.476082e+02 +-1.768602e-01 9.430564e-02 -9.797076e-01 2.181961e+02 7.117074e-02 9.940186e-01 8.283524e-02 -2.547179e+01 9.816594e-01 -5.507624e-02 -1.825141e-01 8.475362e+02 +-2.400965e-01 9.511200e-02 -9.660784e-01 2.176137e+02 7.475182e-02 9.940451e-01 7.928754e-02 -2.542777e+01 9.678666e-01 -5.317944e-02 -2.457765e-01 8.472288e+02 +-3.023077e-01 9.593480e-02 -9.483705e-01 2.170736e+02 7.771182e-02 9.940910e-01 7.578796e-02 -2.540113e+01 9.500373e-01 -5.078830e-02 -3.079766e-01 8.470592e+02 +-3.631631e-01 9.565621e-02 -9.268023e-01 2.165415e+02 7.970260e-02 9.942592e-01 7.138743e-02 -2.537445e+01 9.283103e-01 -4.794326e-02 -3.687023e-01 8.468580e+02 +-4.219301e-01 9.469607e-02 -9.016694e-01 2.159832e+02 8.382183e-02 9.943451e-01 6.520531e-02 -2.535892e+01 9.027452e-01 -4.806749e-02 -4.274817e-01 8.464590e+02 +-4.786789e-01 9.349206e-02 -8.729982e-01 2.154817e+02 8.688791e-02 9.944777e-01 5.885967e-02 -2.534052e+01 8.736801e-01 -4.767809e-02 -4.841588e-01 8.461876e+02 +-5.332411e-01 8.812964e-02 -8.413603e-01 2.150031e+02 8.521658e-02 9.950958e-01 5.022398e-02 -2.534013e+01 8.416603e-01 -4.491634e-02 -5.381361e-01 8.458716e+02 +-5.844969e-01 8.675236e-02 -8.067450e-01 2.144966e+02 8.908604e-02 9.951183e-01 4.246492e-02 -2.534781e+01 8.064905e-01 -4.704908e-02 -5.893719e-01 8.453767e+02 +-6.313768e-01 8.386294e-02 -7.709283e-01 2.140429e+02 8.916954e-02 9.953924e-01 3.525227e-02 -2.534359e+01 7.703325e-01 -4.648584e-02 -6.359456e-01 8.449932e+02 +-6.735453e-01 7.939266e-02 -7.348698e-01 2.135806e+02 8.730377e-02 9.958003e-01 2.756436e-02 -2.536321e+01 7.339720e-01 -4.559105e-02 -6.776478e-01 8.444615e+02 +-7.098840e-01 7.255862e-02 -7.005712e-01 2.131663e+02 8.416723e-02 9.962908e-01 1.790046e-02 -2.536512e+01 6.992715e-01 -4.625788e-02 -7.133579e-01 8.440156e+02 +-7.419182e-01 6.513161e-02 -6.673195e-01 2.127650e+02 8.075210e-02 9.967060e-01 7.501094e-03 -2.536924e+01 6.656098e-01 -4.832223e-02 -7.447338e-01 8.435395e+02 +-7.705730e-01 5.611895e-02 -6.348763e-01 2.123594e+02 7.467465e-02 9.972048e-01 -2.488936e-03 -2.538640e+01 6.329620e-01 -4.932706e-02 -7.726097e-01 8.429708e+02 +-7.958624e-01 4.810885e-02 -6.035633e-01 2.119896e+02 6.703888e-02 9.977109e-01 -8.872287e-03 -2.539528e+01 6.017548e-01 -4.752331e-02 -7.972657e-01 8.424430e+02 +-8.187606e-01 4.258458e-02 -5.725537e-01 2.116165e+02 5.982213e-02 9.981450e-01 -1.130795e-02 -2.541595e+01 5.710100e-01 -4.350988e-02 -8.197892e-01 8.418340e+02 +-8.400414e-01 3.782606e-02 -5.412021e-01 2.112731e+02 5.415896e-02 9.984302e-01 -1.428130e-02 -2.543285e+01 5.398123e-01 -4.130782e-02 -8.407712e-01 8.412617e+02 +-8.599461e-01 3.168816e-02 -5.094003e-01 2.109425e+02 4.897564e-02 9.985883e-01 -2.055943e-02 -2.545083e+01 5.080297e-01 -4.262819e-02 -8.602840e-01 8.406735e+02 +-8.785154e-01 2.399085e-02 -4.771114e-01 2.106138e+02 4.269568e-02 9.986844e-01 -2.839905e-02 -2.548253e+01 4.758023e-01 -4.531959e-02 -8.783838e-01 8.400101e+02 +-8.947145e-01 1.657646e-02 -4.463309e-01 2.103137e+02 3.652493e-02 9.986795e-01 -3.612747e-02 -2.549847e+01 4.451426e-01 -4.862596e-02 -8.941384e-01 8.393722e+02 +-9.082824e-01 8.520547e-03 -4.182708e-01 2.100152e+02 2.795180e-02 9.987945e-01 -4.035148e-02 -2.553640e+01 4.174228e-01 -4.834195e-02 -9.074256e-01 8.386687e+02 +-9.192372e-01 1.228605e-03 -3.937024e-01 2.097365e+02 1.737372e-02 9.991475e-01 -3.744709e-02 -2.556711e+01 3.933207e-01 -4.126282e-02 -9.184749e-01 8.379676e+02 +-9.281059e-01 -3.353154e-03 -3.723014e-01 2.094578e+02 9.614258e-03 9.994101e-01 -3.296850e-02 -2.561305e+01 3.721923e-01 -3.417765e-02 -9.275261e-01 8.372460e+02 +-9.357211e-01 -4.434195e-03 -3.527129e-01 2.091771e+02 7.165531e-03 9.994757e-01 -3.157470e-02 -2.566642e+01 3.526679e-01 -3.207248e-02 -9.351987e-01 8.364923e+02 +-9.422730e-01 -8.959924e-03 -3.347259e-01 2.089143e+02 3.430475e-03 9.993311e-01 -3.640701e-02 -2.570971e+01 3.348282e-01 -3.545360e-02 -9.416119e-01 8.357411e+02 +-9.474398e-01 -1.778843e-02 -3.194395e-01 2.086599e+02 -2.150660e-03 9.987846e-01 -4.923995e-02 -2.576100e+01 3.199271e-01 -4.596487e-02 -9.463265e-01 8.349662e+02 +-9.519033e-01 -2.567293e-02 -3.053212e-01 2.084201e+02 -5.691403e-03 9.977931e-01 -6.615525e-02 -2.580795e+01 3.063458e-01 -6.123568e-02 -9.499486e-01 8.342034e+02 +-9.559326e-01 -2.919050e-02 -2.921317e-01 2.081725e+02 -6.313257e-03 9.968586e-01 -7.894981e-02 -2.586526e+01 2.935186e-01 -7.362638e-02 -9.531138e-01 8.334173e+02 +-9.593097e-01 -3.029715e-02 -2.807261e-01 2.079281e+02 -8.128690e-03 9.967778e-01 -7.979875e-02 -2.593136e+01 2.822392e-01 -7.426976e-02 -9.564648e-01 8.325956e+02 +-9.620157e-01 -2.891078e-02 -2.714590e-01 2.076853e+02 -1.018621e-02 9.974855e-01 -7.013500e-02 -2.601299e+01 2.728041e-01 -6.470581e-02 -9.598911e-01 8.317566e+02 +-9.640630e-01 -2.720261e-02 -2.642777e-01 2.074460e+02 -1.116897e-02 9.980146e-01 -6.198408e-02 -2.608611e+01 2.654392e-01 -5.680483e-02 -9.624527e-01 8.309013e+02 +-9.652370e-01 -2.717191e-02 -2.599602e-01 2.072049e+02 -1.184785e-02 9.981079e-01 -6.033425e-02 -2.616388e+01 2.611077e-01 -5.515686e-02 -9.637325e-01 8.300402e+02 +-9.658041e-01 -2.932028e-02 -2.576097e-01 2.069664e+02 -1.375564e-02 9.979804e-01 -6.201555e-02 -2.623648e+01 2.589077e-01 -5.635127e-02 -9.642568e-01 8.291695e+02 +-9.660312e-01 -3.188272e-02 -2.564512e-01 2.067251e+02 -1.575717e-02 9.977809e-01 -6.469085e-02 -2.631266e+01 2.579446e-01 -5.845243e-02 -9.643898e-01 8.282900e+02 +-9.661648e-01 -3.412808e-02 -2.556577e-01 2.064825e+02 -1.723992e-02 9.975356e-01 -6.801035e-02 -2.638278e+01 2.573487e-01 -6.130168e-02 -9.643721e-01 8.274002e+02 +-9.662913e-01 -3.539722e-02 -2.550062e-01 2.062349e+02 -1.798764e-02 9.973649e-01 -7.028314e-02 -2.646209e+01 2.568221e-01 -6.332702e-02 -9.643817e-01 8.264996e+02 +-9.663983e-01 -3.649427e-02 -2.544455e-01 2.059867e+02 -1.931424e-02 9.973814e-01 -6.969450e-02 -2.654409e+01 2.563227e-01 -6.243821e-02 -9.645725e-01 8.255841e+02 +-9.663479e-01 -3.788350e-02 -2.544338e-01 2.057386e+02 -2.144310e-02 9.975170e-01 -6.708201e-02 -2.662216e+01 2.563434e-01 -5.936870e-02 -9.647608e-01 8.246565e+02 +-9.664379e-01 -3.846626e-02 -2.540045e-01 2.054913e+02 -2.242532e-02 9.975841e-01 -6.574943e-02 -2.670191e+01 2.559199e-01 -5.784659e-02 -9.649656e-01 8.237278e+02 +-9.665863e-01 -3.834413e-02 -2.534575e-01 2.052398e+02 -2.246768e-02 9.976166e-01 -6.524085e-02 -2.677715e+01 2.553550e-01 -5.736630e-02 -9.651439e-01 8.227870e+02 +-9.667122e-01 -3.767545e-02 -2.530776e-01 2.049850e+02 -2.196589e-02 9.976684e-01 -6.461619e-02 -2.685545e+01 2.549219e-01 -5.690617e-02 -9.652857e-01 8.218365e+02 +-9.667805e-01 -3.709577e-02 -2.529022e-01 2.047269e+02 -2.188752e-02 9.977932e-01 -6.268620e-02 -2.693453e+01 2.546695e-01 -5.506838e-02 -9.654589e-01 8.208729e+02 +-9.668906e-01 -3.642878e-02 -2.525779e-01 2.044700e+02 -2.166820e-02 9.979039e-01 -6.097778e-02 -2.701620e+01 2.542698e-01 -5.348592e-02 -9.656532e-01 8.199051e+02 +-9.669419e-01 -3.787740e-02 -2.521680e-01 2.042129e+02 -2.325723e-02 9.978845e-01 -6.070902e-02 -2.709167e+01 2.539341e-01 -5.283735e-02 -9.657772e-01 8.189292e+02 +-9.670793e-01 -3.970739e-02 -2.513585e-01 2.039601e+02 -2.487363e-02 9.977711e-01 -6.191995e-02 -2.716236e+01 2.532569e-01 -5.362928e-02 -9.659113e-01 8.179473e+02 +-9.671406e-01 -4.034254e-02 -2.510211e-01 2.037018e+02 -2.549875e-02 9.977436e-01 -6.210887e-02 -2.723152e+01 2.529603e-01 -5.366727e-02 -9.659870e-01 8.169553e+02 +-9.671464e-01 -4.287235e-02 -2.505791e-01 2.034466e+02 -2.792896e-02 9.976295e-01 -6.289159e-02 -2.730235e+01 2.526814e-01 -5.382695e-02 -9.660511e-01 8.159565e+02 +-9.670497e-01 -4.600234e-02 -2.503971e-01 2.031887e+02 -3.081481e-02 9.974585e-01 -6.424184e-02 -2.737368e+01 2.527160e-01 -5.440910e-02 -9.660094e-01 8.149445e+02 +-9.670654e-01 -4.677802e-02 -2.501926e-01 2.029251e+02 -3.171184e-02 9.974513e-01 -6.391623e-02 -2.745029e+01 2.525448e-01 -5.387710e-02 -9.660840e-01 8.139260e+02 +-9.670154e-01 -4.824324e-02 -2.501078e-01 2.026577e+02 -3.372447e-02 9.975052e-01 -6.201645e-02 -2.752998e+01 2.524757e-01 -5.153610e-02 -9.662298e-01 8.128921e+02 +-9.668842e-01 -4.951949e-02 -2.503653e-01 2.023877e+02 -3.525801e-02 9.975067e-01 -6.113309e-02 -2.760717e+01 2.527683e-01 -5.028123e-02 -9.662194e-01 8.118530e+02 +-9.668001e-01 -5.204928e-02 -2.501770e-01 2.021157e+02 -3.744321e-02 9.973238e-01 -6.279509e-02 -2.768522e+01 2.527759e-01 -5.134286e-02 -9.661616e-01 8.108079e+02 +-9.667250e-01 -5.321460e-02 -2.502218e-01 2.018378e+02 -3.818024e-02 9.971830e-01 -6.456231e-02 -2.776479e+01 2.529526e-01 -5.286046e-02 -9.660335e-01 8.097525e+02 +-9.665452e-01 -5.586260e-02 -2.503394e-01 2.015571e+02 -4.089153e-02 9.970721e-01 -6.461439e-02 -2.785432e+01 2.532160e-01 -5.221595e-02 -9.659995e-01 8.086850e+02 +-9.663323e-01 -5.869741e-02 -2.505126e-01 2.012769e+02 -4.376221e-02 9.969393e-01 -6.478284e-02 -2.794180e+01 2.535484e-01 -5.163875e-02 -9.659433e-01 8.076122e+02 +-9.662157e-01 -5.990763e-02 -2.506757e-01 2.009921e+02 -4.541318e-02 9.969660e-01 -6.321690e-02 -2.802522e+01 2.537023e-01 -4.969717e-02 -9.660048e-01 8.065324e+02 +-9.661162e-01 -5.952750e-02 -2.511495e-01 2.007070e+02 -4.609191e-02 9.971904e-01 -5.904893e-02 -2.810229e+01 2.539589e-01 -4.547215e-02 -9.661455e-01 8.054467e+02 +-9.659664e-01 -5.900522e-02 -2.518479e-01 2.004212e+02 -4.687135e-02 9.974449e-01 -5.391470e-02 -2.817193e+01 2.543857e-01 -4.027533e-02 -9.662638e-01 8.043574e+02 +-9.661130e-01 -5.682407e-02 -2.517870e-01 2.001304e+02 -4.494571e-02 9.975993e-01 -5.268347e-02 -2.824071e+01 2.541762e-01 -3.958144e-02 -9.663476e-01 8.032651e+02 +-9.662625e-01 -5.536313e-02 -2.515387e-01 1.998376e+02 -4.362394e-02 9.976931e-01 -5.201280e-02 -2.830726e+01 2.538380e-01 -3.928490e-02 -9.664486e-01 8.021693e+02 +-9.664335e-01 -5.467159e-02 -2.510327e-01 1.995455e+02 -4.250308e-02 9.976550e-01 -5.364633e-02 -2.837282e+01 2.533769e-01 -4.117593e-02 -9.664909e-01 8.010711e+02 +-9.664257e-01 -5.536582e-02 -2.509105e-01 1.992540e+02 -4.371517e-02 9.977015e-01 -5.177578e-02 -2.844030e+01 2.532004e-01 -3.906884e-02 -9.666246e-01 7.999674e+02 +-9.663970e-01 -5.510712e-02 -2.510780e-01 1.989591e+02 -4.422549e-02 9.978298e-01 -4.878225e-02 -2.851641e+01 2.532214e-01 -3.603896e-02 -9.667368e-01 7.988530e+02 +-9.663478e-01 -5.561367e-02 -2.511556e-01 1.986660e+02 -4.535727e-02 9.978904e-01 -4.644712e-02 -2.858949e+01 2.532089e-01 -3.349233e-02 -9.668316e-01 7.977403e+02 +-9.664498e-01 -5.561038e-02 -2.507637e-01 1.983733e+02 -4.513914e-02 9.978592e-01 -4.732193e-02 -2.865630e+01 2.528584e-01 -3.441500e-02 -9.668910e-01 7.966275e+02 +-9.666698e-01 -5.505863e-02 -2.500361e-01 1.980783e+02 -4.409461e-02 9.978128e-01 -4.924600e-02 -2.872084e+01 2.522007e-01 -3.657937e-02 -9.669833e-01 7.955120e+02 +-9.668476e-01 -5.540961e-02 -2.492700e-01 1.977872e+02 -4.428300e-02 9.977655e-01 -5.002963e-02 -2.878505e+01 2.514851e-01 -3.733260e-02 -9.671408e-01 7.943923e+02 +-9.669873e-01 -5.431118e-02 -2.489699e-01 1.974954e+02 -4.367328e-02 9.978893e-01 -4.805816e-02 -2.884839e+01 2.510544e-01 -3.559829e-02 -9.673181e-01 7.932647e+02 +-9.670996e-01 -5.414112e-02 -2.485703e-01 1.972081e+02 -4.421233e-02 9.979919e-01 -4.535809e-02 -2.891275e+01 2.505269e-01 -3.287591e-02 -9.675512e-01 7.921342e+02 +-9.671613e-01 -5.381874e-02 -2.484000e-01 1.969198e+02 -4.423626e-02 9.980515e-01 -4.400272e-02 -2.897405e+01 2.502842e-01 -3.156943e-02 -9.676575e-01 7.910033e+02 +-9.669970e-01 -5.403432e-02 -2.489922e-01 1.966298e+02 -4.466447e-02 9.980705e-01 -4.313250e-02 -2.903373e+01 2.508424e-01 -3.058789e-02 -9.675445e-01 7.898685e+02 +-9.665820e-01 -5.418160e-02 -2.505667e-01 1.963315e+02 -4.491023e-02 9.980833e-01 -4.257678e-02 -2.909872e+01 2.523933e-01 -2.990093e-02 -9.671626e-01 7.887273e+02 +-9.659901e-01 -5.416869e-02 -2.528420e-01 1.960240e+02 -4.464173e-02 9.980655e-01 -4.326989e-02 -2.917101e+01 2.546967e-01 -3.051097e-02 -9.665395e-01 7.875825e+02 +-9.653476e-01 -5.419734e-02 -2.552777e-01 1.957126e+02 -4.395406e-02 9.979893e-01 -4.566566e-02 -2.924379e+01 2.572394e-01 -3.286273e-02 -9.657887e-01 7.864424e+02 +-9.646793e-01 -5.301558e-02 -2.580374e-01 1.953938e+02 -4.261810e-02 9.980445e-01 -4.572636e-02 -2.931503e+01 2.599570e-01 -3.311420e-02 -9.650522e-01 7.852964e+02 +-9.638356e-01 -5.119623e-02 -2.615337e-01 1.950718e+02 -4.139592e-02 9.982236e-01 -4.284887e-02 -2.938898e+01 2.632628e-01 -3.047283e-02 -9.642427e-01 7.841424e+02 +-9.627197e-01 -4.945535e-02 -2.659418e-01 1.947428e+02 -4.040459e-02 9.984062e-01 -3.940050e-02 -2.946308e+01 2.674665e-01 -2.718636e-02 -9.631835e-01 7.829868e+02 +-9.614354e-01 -4.920312e-02 -2.705940e-01 1.944070e+02 -4.002873e-02 9.984244e-01 -3.932299e-02 -2.953850e+01 2.721025e-01 -2.697497e-02 -9.618901e-01 7.818322e+02 +-9.600782e-01 -4.878019e-02 -2.754458e-01 1.940672e+02 -3.925049e-02 9.984281e-01 -4.000778e-02 -2.960278e+01 2.769644e-01 -2.759920e-02 -9.604837e-01 7.806767e+02 +-9.585965e-01 -4.978253e-02 -2.803829e-01 1.937222e+02 -4.018061e-02 9.983957e-01 -3.989428e-02 -2.967427e+01 2.819191e-01 -2.697655e-02 -9.590588e-01 7.795183e+02 +-9.571323e-01 -5.048077e-02 -2.852185e-01 1.933721e+02 -4.097438e-02 9.983908e-01 -3.920375e-02 -2.974491e+01 2.867385e-01 -2.583652e-02 -9.576604e-01 7.783616e+02 +-9.556505e-01 -4.992276e-02 -2.902411e-01 1.930113e+02 -4.091651e-02 9.984765e-01 -3.702030e-02 -2.981711e+01 2.916470e-01 -2.350281e-02 -9.562372e-01 7.771971e+02 +-9.540428e-01 -4.867979e-02 -2.956902e-01 1.926417e+02 -4.045259e-02 9.986068e-01 -3.388163e-02 -2.988312e+01 2.969276e-01 -2.036309e-02 -9.546828e-01 7.760299e+02 +-9.524531e-01 -4.933090e-02 -3.006653e-01 1.922685e+02 -4.139749e-02 9.986073e-01 -3.270422e-02 -2.994573e+01 3.018599e-01 -1.870243e-02 -9.531688e-01 7.748627e+02 +-9.511705e-01 -4.630362e-02 -3.051733e-01 1.918856e+02 -3.837177e-02 9.987529e-01 -3.194177e-02 -3.000720e+01 3.062717e-01 -1.867203e-02 -9.517610e-01 7.736956e+02 +-9.501289e-01 -4.391434e-02 -3.087502e-01 1.914970e+02 -3.608482e-02 9.988670e-01 -3.102624e-02 -3.006735e+01 3.097628e-01 -1.833773e-02 -9.506370e-01 7.725243e+02 +-9.495472e-01 -4.123392e-02 -3.109020e-01 1.911045e+02 -3.312197e-02 9.989602e-01 -3.132876e-02 -3.013300e+01 3.118705e-01 -1.945044e-02 -9.499255e-01 7.713519e+02 +-9.493820e-01 -3.949445e-02 -3.116314e-01 1.907052e+02 -3.103885e-02 9.990042e-01 -3.204874e-02 -3.019767e+01 3.125869e-01 -2.075380e-02 -9.496624e-01 7.701736e+02 +-9.494224e-01 -3.657962e-02 -3.118639e-01 1.903024e+02 -2.779937e-02 9.990832e-01 -3.255502e-02 -3.026057e+01 3.127688e-01 -2.223884e-02 -9.495688e-01 7.689911e+02 +-9.495934e-01 -3.215362e-02 -3.118309e-01 1.899002e+02 -2.370096e-02 9.992427e-01 -3.085963e-02 -3.031634e+01 3.125870e-01 -2.191341e-02 -9.496363e-01 7.678032e+02 +-9.500113e-01 -2.778025e-02 -3.109773e-01 1.895038e+02 -2.009408e-02 9.994089e-01 -2.789341e-02 -3.037157e+01 3.115683e-01 -2.025024e-02 -9.500079e-01 7.666132e+02 +-9.509856e-01 -2.062636e-02 -3.085468e-01 1.890994e+02 -1.307589e-02 9.995628e-01 -2.651900e-02 -3.042015e+01 3.089588e-01 -2.118466e-02 -9.508394e-01 7.654178e+02 +-9.523621e-01 -1.499384e-02 -3.046009e-01 1.886974e+02 -7.415086e-03 9.996338e-01 -2.602257e-02 -3.046733e+01 3.048796e-01 -2.252426e-02 -9.521245e-01 7.642153e+02 +-9.540059e-01 -9.668108e-03 -2.996322e-01 1.882986e+02 -1.987481e-03 9.996618e-01 -2.592767e-02 -3.051427e+01 2.997815e-01 -2.413962e-02 -9.537024e-01 7.630054e+02 +-9.558804e-01 -6.475994e-03 -2.936850e-01 1.879090e+02 1.353920e-03 9.996492e-01 -2.644977e-02 -3.056520e+01 2.937532e-01 -2.568044e-02 -9.555362e-01 7.617935e+02 +-9.578102e-01 -3.693739e-03 -2.873780e-01 1.875255e+02 3.371082e-03 9.997042e-01 -2.408498e-02 -3.062286e+01 2.873820e-01 -2.403761e-02 -9.575143e-01 7.605731e+02 +-9.597266e-01 4.721277e-04 -2.809356e-01 1.871473e+02 6.294363e-03 9.997837e-01 -1.982246e-02 -3.068017e+01 2.808654e-01 -2.079244e-02 -9.595219e-01 7.593427e+02 +-9.615817e-01 3.794164e-03 -2.744928e-01 1.867785e+02 9.272910e-03 9.997828e-01 -1.866465e-02 -3.073561e+01 2.743624e-01 -2.049292e-02 -9.614079e-01 7.581093e+02 +-9.633049e-01 7.179661e-03 -2.683135e-01 1.864172e+02 1.229762e-02 9.997730e-01 -1.739873e-02 -3.078700e+01 2.681277e-01 -2.005989e-02 -9.631745e-01 7.568748e+02 +-9.649410e-01 1.059164e-02 -2.622531e-01 1.860641e+02 1.496076e-02 9.997805e-01 -1.466879e-02 -3.083726e+01 2.620401e-01 -1.807801e-02 -9.648876e-01 7.556365e+02 +-9.665527e-01 1.024116e-02 -2.562637e-01 1.857199e+02 1.443809e-02 9.997906e-01 -1.450128e-02 -3.087764e+01 2.560615e-01 -1.771620e-02 -9.664981e-01 7.543880e+02 +-9.681512e-01 7.684165e-03 -2.502486e-01 1.853911e+02 1.249153e-02 9.997666e-01 -1.762769e-02 -3.091944e+01 2.500547e-01 -2.019225e-02 -9.680211e-01 7.531402e+02 +-9.694845e-01 8.843264e-03 -2.449933e-01 1.850633e+02 1.399874e-02 9.997155e-01 -1.930994e-02 -3.096006e+01 2.447529e-01 -2.215028e-02 -9.693324e-01 7.518907e+02 +-9.709287e-01 7.095135e-03 -2.392637e-01 1.847426e+02 1.134607e-02 9.998012e-01 -1.639400e-02 -3.101194e+01 2.390998e-01 -1.863210e-02 -9.708162e-01 7.506348e+02 +-9.724450e-01 1.083179e-02 -2.328810e-01 1.844253e+02 1.450999e-02 9.997955e-01 -1.408696e-02 -3.106198e+01 2.326808e-01 -1.707789e-02 -9.724032e-01 7.493761e+02 +-9.737309e-01 1.503015e-02 -2.272054e-01 1.841130e+02 1.835409e-02 9.997531e-01 -1.252387e-02 -3.111749e+01 2.269611e-01 -1.636502e-02 -9.737663e-01 7.481178e+02 +-9.749143e-01 1.666869e-02 -2.219557e-01 1.838060e+02 1.975839e-02 9.997362e-01 -1.170697e-02 -3.117086e+01 2.217020e-01 -1.579878e-02 -9.749864e-01 7.468551e+02 +-9.759163e-01 1.740639e-02 -2.174501e-01 1.835058e+02 2.025211e-02 9.997358e-01 -1.086485e-02 -3.122351e+01 2.172036e-01 -1.500701e-02 -9.760109e-01 7.455860e+02 +-9.767171e-01 1.793115e-02 -2.137811e-01 1.832101e+02 2.071740e-02 9.997270e-01 -1.079969e-02 -3.128039e+01 2.135291e-01 -1.497723e-02 -9.768218e-01 7.443158e+02 +-9.773891e-01 1.833272e-02 -2.106528e-01 1.829187e+02 2.111503e-02 9.997169e-01 -1.096621e-02 -3.132766e+01 2.103921e-01 -1.516618e-02 -9.774994e-01 7.430397e+02 +-9.779844e-01 1.919816e-02 -2.077931e-01 1.826308e+02 2.176083e-02 9.997126e-01 -1.005370e-02 -3.137561e+01 2.075404e-01 -1.435410e-02 -9.781211e-01 7.417605e+02 +-9.785335e-01 1.926454e-02 -2.051854e-01 1.823477e+02 2.169261e-02 9.997187e-01 -9.590401e-03 -3.141709e+01 2.049429e-01 -1.383553e-02 -9.786761e-01 7.404783e+02 +-9.790299e-01 1.960979e-02 -2.027706e-01 1.820719e+02 2.252451e-02 9.996733e-01 -1.207655e-02 -3.145525e+01 2.024676e-01 -1.639061e-02 -9.791517e-01 7.391998e+02 +-9.795940e-01 1.661091e-02 -2.002993e-01 1.817996e+02 2.027815e-02 9.996619e-01 -1.627088e-02 -3.149723e+01 1.999613e-01 -2.000055e-02 -9.795996e-01 7.379206e+02 +-9.801280e-01 1.481826e-02 -1.978123e-01 1.815301e+02 1.891491e-02 9.996436e-01 -1.883623e-02 -3.154885e+01 1.974626e-01 -2.220351e-02 -9.800589e-01 7.366317e+02 +-9.806160e-01 1.333357e-02 -1.954855e-01 1.812640e+02 1.728972e-02 9.996785e-01 -1.854503e-02 -3.160107e+01 1.951754e-01 -2.156544e-02 -9.805312e-01 7.353420e+02 +-9.810571e-01 1.511639e-02 -1.931285e-01 1.809957e+02 1.861649e-02 9.996935e-01 -1.632111e-02 -3.165383e+01 1.928225e-01 -1.960731e-02 -9.810377e-01 7.340460e+02 +-9.815616e-01 1.468042e-02 -1.905819e-01 1.807345e+02 1.816053e-02 9.996985e-01 -1.652662e-02 -3.169967e+01 1.902818e-01 -1.968296e-02 -9.815321e-01 7.327523e+02 +-9.820479e-01 1.553395e-02 -1.879913e-01 1.804826e+02 1.956223e-02 9.996167e-01 -1.959151e-02 -3.173747e+01 1.876149e-01 -2.291732e-02 -9.819752e-01 7.314607e+02 +-9.825061e-01 1.471805e-02 -1.856479e-01 1.802351e+02 1.892597e-02 9.996021e-01 -2.091421e-02 -3.177991e+01 1.852662e-01 -2.406190e-02 -9.823937e-01 7.301651e+02 +-9.827957e-01 1.192395e-02 -1.843111e-01 1.799912e+02 1.595690e-02 9.996643e-01 -2.041336e-02 -3.182430e+01 1.840058e-01 -2.300319e-02 -9.826559e-01 7.288661e+02 +-9.829642e-01 9.390337e-03 -1.835573e-01 1.797543e+02 1.318262e-02 9.997239e-01 -1.945054e-02 -3.186500e+01 1.833239e-01 -2.153894e-02 -9.828165e-01 7.275669e+02 +-9.830973e-01 9.812751e-03 -1.828208e-01 1.795090e+02 1.341077e-02 9.997397e-01 -1.845460e-02 -3.191077e+01 1.825922e-01 -2.059443e-02 -9.829730e-01 7.262673e+02 +-9.832886e-01 1.012744e-02 -1.817717e-01 1.792692e+02 1.367193e-02 9.997398e-01 -1.825720e-02 -3.195101e+01 1.815395e-01 -2.043726e-02 -9.831712e-01 7.249646e+02 +-9.834846e-01 1.053268e-02 -1.806856e-01 1.790242e+02 1.402846e-02 9.997381e-01 -1.808027e-02 -3.199222e+01 1.804478e-01 -2.031640e-02 -9.833747e-01 7.236595e+02 +-9.838061e-01 1.091832e-02 -1.789035e-01 1.787826e+02 1.429559e-02 9.997429e-01 -1.759923e-02 -3.203392e+01 1.786654e-01 -1.987175e-02 -9.837091e-01 7.223580e+02 +-9.842602e-01 1.069021e-02 -1.764019e-01 1.785396e+02 1.386669e-02 9.997630e-01 -1.678413e-02 -3.208279e+01 1.761807e-01 -1.896606e-02 -9.841751e-01 7.210528e+02 +-9.847563e-01 1.061587e-02 -1.736157e-01 1.782976e+02 1.357913e-02 9.997815e-01 -1.588901e-02 -3.213658e+01 1.734091e-01 -1.800435e-02 -9.846852e-01 7.197448e+02 +-9.852291e-01 1.007208e-02 -1.709452e-01 1.780607e+02 1.301859e-02 9.997852e-01 -1.612429e-02 -3.218450e+01 1.707461e-01 -1.811158e-02 -9.851485e-01 7.184334e+02 +-9.856689e-01 8.806874e-03 -1.684619e-01 1.778260e+02 1.191612e-02 9.997766e-01 -1.745460e-02 -3.223300e+01 1.682706e-01 -1.921186e-02 -9.855536e-01 7.171226e+02 +-9.860964e-01 7.500613e-03 -1.660049e-01 1.775931e+02 1.083835e-02 9.997567e-01 -1.920942e-02 -3.228302e+01 1.658204e-01 -2.074155e-02 -9.859378e-01 7.158073e+02 +-9.864725e-01 5.970235e-03 -1.638186e-01 1.773621e+02 9.444919e-03 9.997464e-01 -2.043981e-02 -3.233414e+01 1.636551e-01 -2.171055e-02 -9.862786e-01 7.144854e+02 +-9.868285e-01 4.369429e-03 -1.617114e-01 1.771340e+02 7.737484e-03 9.997659e-01 -2.020361e-02 -3.238726e+01 1.615852e-01 -2.118873e-02 -9.866312e-01 7.131595e+02 +-9.871673e-01 4.202377e-03 -1.596347e-01 1.769077e+02 7.110896e-03 9.998189e-01 -1.765292e-02 -3.243938e+01 1.595316e-01 -1.856152e-02 -9.870183e-01 7.118236e+02 +-9.874560e-01 5.310436e-03 -1.578051e-01 1.766836e+02 7.389462e-03 9.998934e-01 -1.259078e-02 -3.248957e+01 1.577214e-01 -1.359894e-02 -9.873900e-01 7.104853e+02 +-9.877940e-01 7.878411e-03 -1.555669e-01 1.764560e+02 9.674607e-03 9.998949e-01 -1.079230e-02 -3.253641e+01 1.554655e-01 -1.216562e-02 -9.877663e-01 7.091527e+02 +-9.881225e-01 8.169274e-03 -1.534510e-01 1.762320e+02 1.150583e-02 9.997160e-01 -2.086793e-02 -3.259141e+01 1.532370e-01 -2.238565e-02 -9.879358e-01 7.078369e+02 +-9.883373e-01 1.037955e-02 -1.519267e-01 1.760121e+02 1.463675e-02 9.995301e-01 -2.692985e-02 -3.264929e+01 1.515758e-01 -2.883948e-02 -9.880248e-01 7.065239e+02 +-9.885960e-01 1.200101e-02 -1.501133e-01 1.757937e+02 1.557557e-02 9.996219e-01 -2.265933e-02 -3.271775e+01 1.497846e-01 -2.473901e-02 -9.884090e-01 7.052012e+02 +-9.888505e-01 1.456141e-02 -1.481984e-01 1.755780e+02 1.732425e-02 9.996990e-01 -1.736901e-02 -3.277900e+01 1.479009e-01 -1.974277e-02 -9.888051e-01 7.038842e+02 +-9.890694e-01 1.709143e-02 -1.464570e-01 1.753667e+02 1.970997e-02 9.996704e-01 -1.644658e-02 -3.283361e+01 1.461276e-01 -1.915347e-02 -9.890803e-01 7.025732e+02 +-9.893242e-01 1.746467e-02 -1.446811e-01 1.751624e+02 2.008143e-02 9.996597e-01 -1.664563e-02 -3.288151e+01 1.443411e-01 -1.937333e-02 -9.893383e-01 7.012664e+02 +-9.895879e-01 1.546535e-02 -1.430966e-01 1.749647e+02 1.787461e-02 9.997190e-01 -1.556626e-02 -3.293038e+01 1.428156e-01 -1.796197e-02 -9.895863e-01 6.999638e+02 +-9.898078e-01 1.322295e-02 -1.417949e-01 1.747716e+02 1.536213e-02 9.997839e-01 -1.400230e-02 -3.298050e+01 1.415791e-01 -1.603785e-02 -9.897970e-01 6.986640e+02 +-9.899742e-01 1.233589e-02 -1.407088e-01 1.745809e+02 1.451209e-02 9.997902e-01 -1.445029e-02 -3.302686e+01 1.405011e-01 -1.634739e-02 -9.899455e-01 6.973700e+02 +-9.902255e-01 1.015646e-02 -1.391058e-01 1.743935e+02 1.199454e-02 9.998514e-01 -1.238147e-02 -3.307277e+01 1.389593e-01 -1.392895e-02 -9.902001e-01 6.960784e+02 +-9.904369e-01 8.023741e-03 -1.377334e-01 1.742087e+02 9.269917e-03 9.999217e-01 -8.408607e-03 -3.311503e+01 1.376551e-01 -9.604968e-03 -9.904336e-01 6.947860e+02 +-9.906267e-01 6.074193e-03 -1.364623e-01 1.740253e+02 7.033032e-03 9.999538e-01 -6.545307e-03 -3.315472e+01 1.364163e-01 -7.443696e-03 -9.906236e-01 6.935084e+02 +-9.906860e-01 3.754727e-03 -1.361144e-01 1.738442e+02 5.421423e-03 9.999148e-01 -1.187612e-02 -3.319438e+01 1.360582e-01 -1.250344e-02 -9.906219e-01 6.922391e+02 +-9.907764e-01 2.763933e-03 -1.354788e-01 1.736645e+02 4.721809e-03 9.998890e-01 -1.413227e-02 -3.323557e+01 1.354247e-01 -1.464162e-02 -9.906794e-01 6.909714e+02 +-9.908465e-01 4.646129e-03 -1.349138e-01 1.734798e+02 6.637015e-03 9.998755e-01 -1.431064e-02 -3.327543e+01 1.348305e-01 -1.507507e-02 -9.907539e-01 6.897080e+02 +-9.908854e-01 5.583532e-03 -1.345920e-01 1.733014e+02 7.597316e-03 9.998667e-01 -1.445311e-02 -3.331362e+01 1.344933e-01 -1.534390e-02 -9.907956e-01 6.884457e+02 +-9.909079e-01 7.237295e-03 -1.343474e-01 1.731204e+02 9.180910e-03 9.998619e-01 -1.385313e-02 -3.335226e+01 1.342286e-01 -1.496060e-02 -9.908374e-01 6.871944e+02 +-9.909424e-01 7.903853e-03 -1.340553e-01 1.729460e+02 9.576467e-03 9.998841e-01 -1.183677e-02 -3.339068e+01 1.339462e-01 -1.301332e-02 -9.909031e-01 6.859439e+02 +-9.908865e-01 1.080758e-02 -1.342658e-01 1.727770e+02 1.216086e-02 9.998831e-01 -9.262960e-03 -3.341728e+01 1.341500e-01 -1.081132e-02 -9.909020e-01 6.846951e+02 +-9.908617e-01 1.155211e-02 -1.343866e-01 1.726098e+02 1.277116e-02 9.998847e-01 -8.212659e-03 -3.344108e+01 1.342763e-01 -9.853879e-03 -9.908949e-01 6.834525e+02 +-9.907918e-01 1.297015e-02 -1.347716e-01 1.724432e+02 1.446732e-02 9.998439e-01 -1.013543e-02 -3.346934e+01 1.346191e-01 -1.199188e-02 -9.908248e-01 6.822209e+02 +-9.907496e-01 1.199829e-02 -1.351717e-01 1.722700e+02 1.362229e-02 9.998456e-01 -1.109574e-02 -3.350639e+01 1.350177e-01 -1.283444e-02 -9.907600e-01 6.809874e+02 +-9.906805e-01 9.565703e-03 -1.358706e-01 1.721113e+02 1.088277e-02 9.999007e-01 -8.953976e-03 -3.353377e+01 1.357714e-01 -1.034917e-02 -9.906861e-01 6.797572e+02 +-9.906185e-01 7.241492e-03 -1.364649e-01 1.719473e+02 8.199755e-03 9.999455e-01 -6.461165e-03 -3.355913e+01 1.364106e-01 -7.519525e-03 -9.906238e-01 6.785274e+02 +-9.905566e-01 5.919849e-03 -1.369768e-01 1.717867e+02 6.628629e-03 9.999669e-01 -4.718828e-03 -3.357546e+01 1.369443e-01 -5.582232e-03 -9.905630e-01 6.772987e+02 +-9.904951e-01 5.183372e-03 -1.374505e-01 1.716201e+02 5.643125e-03 9.999797e-01 -2.955331e-03 -3.359577e+01 1.374324e-01 -3.702889e-03 -9.905042e-01 6.760754e+02 +-9.904627e-01 2.987066e-03 -1.377490e-01 1.714516e+02 3.368255e-03 9.999911e-01 -2.534194e-03 -3.362298e+01 1.377401e-01 -2.973996e-03 -9.904639e-01 6.748571e+02 +-9.904210e-01 9.911433e-04 -1.380770e-01 1.712832e+02 1.436431e-03 9.999941e-01 -3.125255e-03 -3.364736e+01 1.380731e-01 -3.293654e-03 -9.904165e-01 6.736413e+02 +-9.903654e-01 -1.110286e-03 -1.384745e-01 1.711165e+02 -6.259362e-04 9.999935e-01 -3.541195e-03 -3.367100e+01 1.384775e-01 -3.420399e-03 -9.903596e-01 6.724251e+02 +-9.902790e-01 -2.377064e-03 -1.390750e-01 1.709501e+02 -1.895397e-03 9.999917e-01 -3.595643e-03 -3.369393e+01 1.390824e-01 -3.297085e-03 -9.902753e-01 6.712113e+02 +-9.902230e-01 -1.324389e-03 -1.394872e-01 1.707763e+02 -7.379757e-04 9.999906e-01 -4.255643e-03 -3.372013e+01 1.394915e-01 -4.111095e-03 -9.902147e-01 6.700000e+02 +-9.902269e-01 -8.576278e-05 -1.394657e-01 1.705973e+02 5.201884e-04 9.999906e-01 -4.308284e-03 -3.375223e+01 1.394648e-01 -4.338724e-03 -9.902175e-01 6.687913e+02 +-9.902429e-01 1.688384e-03 -1.393421e-01 1.704170e+02 2.312960e-03 9.999880e-01 -4.320449e-03 -3.378272e+01 1.393331e-01 -4.600584e-03 -9.902348e-01 6.675831e+02 +-9.902324e-01 2.342544e-03 -1.394075e-01 1.702379e+02 3.063157e-03 9.999830e-01 -4.954714e-03 -3.381515e+01 1.393936e-01 -5.333342e-03 -9.902226e-01 6.663733e+02 +-9.902072e-01 1.609580e-04 -1.396059e-01 1.700617e+02 8.073099e-04 9.999892e-01 -4.573155e-03 -3.384461e+01 1.396036e-01 -4.641073e-03 -9.901965e-01 6.651583e+02 +-9.901624e-01 -2.486430e-03 -1.399010e-01 1.698820e+02 -2.117660e-03 9.999939e-01 -2.784682e-03 -3.388069e+01 1.399071e-01 -2.461022e-03 -9.901615e-01 6.639456e+02 +-9.901403e-01 -2.359037e-04 -1.400791e-01 1.696968e+02 3.082956e-04 9.999925e-01 -3.863170e-03 -3.391429e+01 1.400790e-01 -3.868263e-03 -9.901327e-01 6.627297e+02 +-9.901369e-01 2.295407e-03 -1.400845e-01 1.695085e+02 3.592758e-03 9.999529e-01 -9.008948e-03 -3.394643e+01 1.400572e-01 -9.423378e-03 -9.900985e-01 6.615157e+02 +-9.901331e-01 7.481302e-03 -1.399306e-01 1.693161e+02 8.933789e-03 9.999125e-01 -9.754712e-03 -3.397919e+01 1.398454e-01 -1.090857e-02 -9.901132e-01 6.602947e+02 +-9.901828e-01 1.234962e-02 -1.392323e-01 1.691173e+02 1.389812e-02 9.998518e-01 -1.015485e-02 -3.402283e+01 1.390862e-01 -1.199022e-02 -9.902076e-01 6.590770e+02 +-9.901530e-01 1.412372e-02 -1.392756e-01 1.689244e+02 1.596690e-02 9.997990e-01 -1.212544e-02 -3.406533e+01 1.390763e-01 -1.422984e-02 -9.901794e-01 6.578558e+02 +-9.900877e-01 1.537031e-02 -1.396072e-01 1.687341e+02 1.675548e-02 9.998213e-01 -8.751885e-03 -3.410374e+01 1.394477e-01 -1.100431e-02 -9.901682e-01 6.566285e+02 +-9.901026e-01 1.509289e-02 -1.395316e-01 1.685431e+02 1.579064e-02 9.998677e-01 -3.894815e-03 -3.414306e+01 1.394543e-01 -6.059557e-03 -9.902099e-01 6.553983e+02 +-9.901579e-01 1.825718e-02 -1.387588e-01 1.683536e+02 1.871132e-02 9.998230e-01 -1.968913e-03 -3.416717e+01 1.386982e-01 -4.545892e-03 -9.903242e-01 6.541647e+02 +-9.903759e-01 1.859914e-02 -1.371489e-01 1.681619e+02 1.880112e-02 9.998232e-01 -1.772848e-04 -3.419514e+01 1.371213e-01 -2.754129e-03 -9.905504e-01 6.529343e+02 +-9.906002e-01 1.842070e-02 -1.355436e-01 1.679763e+02 1.865048e-02 9.998260e-01 -4.253861e-04 -3.422234e+01 1.355122e-01 -2.949338e-03 -9.907712e-01 6.517032e+02 +-9.908026e-01 1.689267e-02 -1.342567e-01 1.677870e+02 1.716031e-02 9.998524e-01 -8.364138e-04 -3.425942e+01 1.342227e-01 -3.132605e-03 -9.909462e-01 6.504696e+02 +-9.910026e-01 1.479678e-02 -1.330225e-01 1.676043e+02 1.513919e-02 9.998842e-01 -1.562872e-03 -3.429350e+01 1.329840e-01 -3.562660e-03 -9.911117e-01 6.492352e+02 +-9.911435e-01 1.417840e-02 -1.320366e-01 1.674197e+02 1.447277e-02 9.998944e-01 -1.269931e-03 -3.432482e+01 1.320046e-01 -3.169617e-03 -9.912440e-01 6.479981e+02 +-9.912440e-01 1.497387e-02 -1.311914e-01 1.672417e+02 1.518616e-02 9.998845e-01 -6.177067e-04 -3.434881e+01 1.311670e-01 -2.604589e-03 -9.913568e-01 6.467600e+02 +-9.913171e-01 1.607337e-02 -1.305069e-01 1.670630e+02 1.609097e-02 9.998701e-01 9.197942e-04 -3.437278e+01 1.305048e-01 -1.188173e-03 -9.914469e-01 6.455194e+02 +-9.913651e-01 1.736514e-02 -1.299762e-01 1.668873e+02 1.716309e-02 9.998491e-01 2.674661e-03 -3.439170e+01 1.300030e-01 4.207741e-04 -9.915135e-01 6.442767e+02 +-9.913381e-01 1.824610e-02 -1.300611e-01 1.667117e+02 1.800148e-02 9.998333e-01 3.056397e-03 -3.441187e+01 1.300952e-01 6.886317e-04 -9.915012e-01 6.430336e+02 +-9.912700e-01 1.707634e-02 -1.307370e-01 1.665321e+02 1.706126e-02 9.998537e-01 1.235559e-03 -3.443682e+01 1.307390e-01 -1.005765e-03 -9.914163e-01 6.417925e+02 +-9.910654e-01 1.845543e-02 -1.320942e-01 1.663473e+02 1.846683e-02 9.998288e-01 1.138952e-03 -3.445970e+01 1.320926e-01 -1.310583e-03 -9.912365e-01 6.405489e+02 +-9.909289e-01 1.753084e-02 -1.332394e-01 1.661619e+02 1.720859e-02 9.998455e-01 3.569871e-03 -3.448246e+01 1.332814e-01 1.244627e-03 -9.910774e-01 6.392985e+02 +-9.907686e-01 1.793194e-02 -1.343727e-01 1.659752e+02 1.743679e-02 9.998361e-01 4.861009e-03 -3.449993e+01 1.344379e-01 2.473107e-03 -9.909189e-01 6.380473e+02 +-9.906534e-01 1.527250e-02 -1.355462e-01 1.657882e+02 1.473578e-02 9.998791e-01 4.962287e-03 -3.451962e+01 1.356056e-01 2.918530e-03 -9.907585e-01 6.367983e+02 +-9.904681e-01 1.152769e-02 -1.372596e-01 1.656033e+02 1.132870e-02 9.999333e-01 2.230949e-03 -3.454141e+01 1.372761e-01 6.547138e-04 -9.905325e-01 6.355472e+02 +-9.902993e-01 8.400119e-03 -1.386971e-01 1.654137e+02 8.572669e-03 9.999630e-01 -6.466613e-04 -3.456623e+01 1.386866e-01 -1.829391e-03 -9.903346e-01 6.342960e+02 +-9.901291e-01 7.124404e-03 -1.399778e-01 1.652219e+02 7.372314e-03 9.999720e-01 -1.252543e-03 -3.459151e+01 1.399649e-01 -2.272137e-03 -9.901538e-01 6.330395e+02 +-9.899865e-01 7.655197e-03 -1.409545e-01 1.650199e+02 7.694511e-03 9.999703e-01 2.661631e-04 -3.462651e+01 1.409524e-01 -8.210762e-04 -9.900160e-01 6.317811e+02 +-9.898574e-01 1.053451e-02 -1.416734e-01 1.648133e+02 1.023634e-02 9.999436e-01 2.833289e-03 -3.465903e+01 1.416953e-01 1.354337e-03 -9.899093e-01 6.305225e+02 +-9.897334e-01 1.243846e-02 -1.423836e-01 1.646102e+02 1.190707e-02 9.999186e-01 4.583643e-03 -3.468491e+01 1.424290e-01 2.841216e-03 -9.898009e-01 6.292592e+02 +-9.897022e-01 1.341145e-02 -1.425125e-01 1.644079e+02 1.274286e-02 9.999031e-01 5.603182e-03 -3.470532e+01 1.425738e-01 3.729466e-03 -9.897771e-01 6.279898e+02 +-9.896955e-01 1.444789e-02 -1.424579e-01 1.642043e+02 1.352273e-02 9.998807e-01 7.460429e-03 -3.472363e+01 1.425487e-01 5.457134e-03 -9.897727e-01 6.267180e+02 +-9.896542e-01 1.563680e-02 -1.426191e-01 1.639990e+02 1.432021e-02 9.998449e-01 1.025340e-02 -3.474059e+01 1.427573e-01 8.104980e-03 -9.897245e-01 6.254406e+02 +-9.896225e-01 1.731815e-02 -1.426448e-01 1.637951e+02 1.595901e-02 9.998157e-01 1.066682e-02 -3.475429e+01 1.428032e-01 8.279657e-03 -9.897164e-01 6.241657e+02 +-9.895957e-01 1.890682e-02 -1.426286e-01 1.635892e+02 1.780252e-02 9.998009e-01 9.014787e-03 -3.476832e+01 1.427706e-01 6.381846e-03 -9.897352e-01 6.228877e+02 +-9.895960e-01 2.146851e-02 -1.422633e-01 1.633893e+02 2.064699e-02 9.997605e-01 7.248543e-03 -3.478295e+01 1.423849e-01 4.235822e-03 -9.898023e-01 6.216121e+02 +-9.896072e-01 2.429865e-02 -1.417295e-01 1.631886e+02 2.350690e-02 9.996973e-01 7.258318e-03 -3.480074e+01 1.418630e-01 3.851264e-03 -9.898788e-01 6.203335e+02 +-9.896022e-01 2.732608e-02 -1.412122e-01 1.629870e+02 2.653835e-02 9.996199e-01 7.458948e-03 -3.481822e+01 1.413624e-01 3.633854e-03 -9.899512e-01 6.190512e+02 +-9.895857e-01 3.025080e-02 -1.407309e-01 1.627857e+02 2.938533e-02 9.995343e-01 8.224356e-03 -3.483490e+01 1.409142e-01 4.003282e-03 -9.900137e-01 6.177678e+02 +-9.895786e-01 3.244217e-02 -1.402917e-01 1.625859e+02 3.151605e-02 9.994643e-01 8.818757e-03 -3.485048e+01 1.405027e-01 4.305412e-03 -9.900709e-01 6.164858e+02 +-9.895741e-01 3.464903e-02 -1.397948e-01 1.623894e+02 3.392385e-02 9.993957e-01 7.567815e-03 -3.487137e+01 1.399725e-01 2.746537e-03 -9.901515e-01 6.151912e+02 +-9.895196e-01 3.667774e-02 -1.396628e-01 1.621962e+02 3.620248e-02 9.993268e-01 5.942903e-03 -3.488888e+01 1.397867e-01 8.244808e-04 -9.901812e-01 6.139209e+02 +-9.895043e-01 3.680907e-02 -1.397373e-01 1.620038e+02 3.639753e-02 9.993222e-01 5.500500e-03 -3.490716e+01 1.398450e-01 3.566790e-04 -9.901733e-01 6.126372e+02 +-9.895097e-01 3.614513e-02 -1.398719e-01 1.618113e+02 3.557340e-02 9.993453e-01 6.586402e-03 -3.492664e+01 1.400184e-01 1.541591e-03 -9.901476e-01 6.113502e+02 +-9.894501e-01 3.614251e-02 -1.402939e-01 1.616192e+02 3.540547e-02 9.993430e-01 7.746832e-03 -3.494660e+01 1.404817e-01 2.697932e-03 -9.900795e-01 6.100645e+02 +-9.893800e-01 3.501395e-02 -1.410721e-01 1.614040e+02 3.424561e-02 9.993824e-01 7.871301e-03 -3.498929e+01 1.412606e-01 2.956609e-03 -9.899680e-01 6.087961e+02 +-9.893196e-01 3.429689e-02 -1.416702e-01 1.611895e+02 3.347489e-02 9.994060e-01 8.182177e-03 -3.502270e+01 1.418667e-01 3.352396e-03 -9.898800e-01 6.075234e+02 +-9.892832e-01 3.332646e-02 -1.421554e-01 1.609692e+02 3.217277e-02 9.994281e-01 1.040713e-02 -3.505989e+01 1.424210e-01 5.722064e-03 -9.897896e-01 6.062530e+02 +-9.892717e-01 3.158457e-02 -1.426321e-01 1.607580e+02 3.035001e-02 9.994807e-01 1.082347e-02 -3.508687e+01 1.428999e-01 6.378467e-03 -9.897165e-01 6.049721e+02 +-9.892410e-01 2.856675e-02 -1.434793e-01 1.605500e+02 2.781893e-02 9.995869e-01 7.215962e-03 -3.512083e+01 1.436262e-01 3.146884e-03 -9.896269e-01 6.037014e+02 +-9.892131e-01 2.671643e-02 -1.440268e-01 1.603440e+02 2.611237e-02 9.996405e-01 6.083116e-03 -3.514818e+01 1.441375e-01 2.256619e-03 -9.895550e-01 6.024190e+02 +-9.891712e-01 2.687702e-02 -1.442844e-01 1.601336e+02 2.633912e-02 9.996371e-01 5.637323e-03 -3.517953e+01 1.443836e-01 1.775954e-03 -9.895201e-01 6.011353e+02 +-9.890872e-01 2.847160e-02 -1.445542e-01 1.599211e+02 2.850013e-02 9.995920e-01 1.873877e-03 -3.521042e+01 1.445486e-01 -2.266385e-03 -9.894950e-01 5.998524e+02 +-9.891155e-01 2.959250e-02 -1.441350e-01 1.597085e+02 2.996347e-02 9.995509e-01 -4.031817e-04 -3.523960e+01 1.440583e-01 -4.717574e-03 -9.895579e-01 5.985678e+02 +-9.891688e-01 3.114376e-02 -1.434410e-01 1.594958e+02 3.084833e-02 9.995149e-01 4.283720e-03 -3.528041e+01 1.435048e-01 -1.875910e-04 -9.896495e-01 5.972734e+02 +-9.892355e-01 3.189179e-02 -1.428152e-01 1.592760e+02 3.128757e-02 9.994894e-01 6.475113e-03 -3.533458e+01 1.429488e-01 1.937071e-03 -9.897281e-01 5.959715e+02 +-9.892531e-01 3.217070e-02 -1.426302e-01 1.590560e+02 3.138172e-02 9.994772e-01 7.778343e-03 -3.538523e+01 1.428058e-01 3.218771e-03 -9.897454e-01 5.946721e+02 +-9.893383e-01 3.129400e-02 -1.422341e-01 1.588403e+02 3.050832e-02 9.995048e-01 7.701863e-03 -3.542530e+01 1.424047e-01 3.280426e-03 -9.898030e-01 5.933660e+02 +-9.893677e-01 3.173206e-02 -1.419319e-01 1.586240e+02 3.092718e-02 9.994906e-01 7.873879e-03 -3.546968e+01 1.421094e-01 3.400611e-03 -9.898451e-01 5.920622e+02 +-9.894598e-01 3.039036e-02 -1.415832e-01 1.584180e+02 2.953638e-02 9.995306e-01 8.129816e-03 -3.550339e+01 1.417638e-01 3.862272e-03 -9.898929e-01 5.907562e+02 +-9.894191e-01 3.086796e-02 -1.417644e-01 1.582086e+02 3.006340e-02 9.995174e-01 7.814173e-03 -3.554247e+01 1.419372e-01 3.469573e-03 -9.898695e-01 5.894470e+02 +-9.894800e-01 2.872157e-02 -1.417906e-01 1.580013e+02 2.838158e-02 9.995874e-01 4.420137e-03 -3.557643e+01 1.418590e-01 3.493982e-04 -9.898868e-01 5.881377e+02 +-9.894630e-01 2.870598e-02 -1.419123e-01 1.577910e+02 2.890913e-02 9.995818e-01 6.304763e-04 -3.561069e+01 1.418710e-01 -3.478726e-03 -9.898790e-01 5.868299e+02 +-9.894693e-01 2.807420e-02 -1.419947e-01 1.575808e+02 2.818727e-02 9.996019e-01 1.215540e-03 -3.564336e+01 1.419723e-01 -2.799700e-03 -9.898666e-01 5.855154e+02 +-9.894370e-01 2.827249e-02 -1.421800e-01 1.573689e+02 2.798828e-02 9.996002e-01 3.998909e-03 -3.567613e+01 1.422362e-01 -2.270186e-05 -9.898327e-01 5.841943e+02 +-9.894492e-01 2.827246e-02 -1.420954e-01 1.571565e+02 2.790361e-02 9.996001e-01 4.588203e-03 -3.570596e+01 1.421683e-01 5.748207e-04 -9.898423e-01 5.828767e+02 +-9.894261e-01 2.868950e-02 -1.421722e-01 1.569429e+02 2.830346e-02 9.995881e-01 4.737365e-03 -3.573307e+01 1.422495e-01 6.633104e-04 -9.898306e-01 5.815584e+02 +-9.894567e-01 2.818467e-02 -1.420600e-01 1.567312e+02 2.775425e-02 9.996022e-01 5.010891e-03 -3.576023e+01 1.421448e-01 1.015293e-03 -9.898453e-01 5.802348e+02 +-9.894759e-01 2.746116e-02 -1.420683e-01 1.565222e+02 2.701661e-02 9.996222e-01 5.057534e-03 -3.578467e+01 1.421535e-01 1.166107e-03 -9.898439e-01 5.789130e+02 +-9.894743e-01 2.649337e-02 -1.422633e-01 1.563151e+02 2.587631e-02 9.996460e-01 6.186161e-03 -3.580915e+01 1.423768e-01 2.439800e-03 -9.898095e-01 5.775847e+02 +-9.894943e-01 2.606238e-02 -1.422037e-01 1.561060e+02 2.521333e-02 9.996519e-01 7.769646e-03 -3.583041e+01 1.423567e-01 4.102592e-03 -9.898069e-01 5.762572e+02 +-9.895325e-01 2.575901e-02 -1.419926e-01 1.558981e+02 2.485791e-02 9.996580e-01 8.116630e-03 -3.585115e+01 1.421532e-01 4.502031e-03 -9.898344e-01 5.749281e+02 +-9.895775e-01 2.507234e-02 -1.418019e-01 1.556931e+02 2.413002e-02 9.996738e-01 8.361289e-03 -3.586969e+01 1.419653e-01 4.852461e-03 -9.898597e-01 5.736022e+02 +-9.896689e-01 2.381033e-02 -1.413810e-01 1.554936e+02 2.292070e-02 9.997059e-01 7.917832e-03 -3.588441e+01 1.415279e-01 4.595483e-03 -9.899235e-01 5.722717e+02 +-9.897676e-01 2.135687e-02 -1.410817e-01 1.552930e+02 2.053615e-02 9.997626e-01 7.270926e-03 -3.590371e+01 1.412035e-01 4.299253e-03 -9.899712e-01 5.709394e+02 +-9.898449e-01 1.861005e-02 -1.409288e-01 1.550979e+02 1.774289e-02 9.998151e-01 7.407363e-03 -3.593006e+01 1.410406e-01 4.831657e-03 -9.899920e-01 5.696121e+02 +-9.898628e-01 1.616583e-02 -1.411040e-01 1.549006e+02 1.522467e-02 9.998541e-01 7.747100e-03 -3.595794e+01 1.412086e-01 5.520306e-03 -9.899644e-01 5.682830e+02 +-9.898333e-01 1.461382e-02 -1.414799e-01 1.546990e+02 1.373124e-02 9.998797e-01 7.212587e-03 -3.598424e+01 1.415682e-01 5.196567e-03 -9.899148e-01 5.669550e+02 +-9.898177e-01 1.343568e-02 -1.417059e-01 1.544946e+02 1.264068e-02 9.998989e-01 6.509001e-03 -3.600791e+01 1.417790e-01 4.651466e-03 -9.898873e-01 5.656317e+02 +-9.897754e-01 1.531810e-02 -1.418100e-01 1.542914e+02 1.432438e-02 9.998652e-01 8.025758e-03 -3.602675e+01 1.419138e-01 5.912359e-03 -9.898613e-01 5.642982e+02 +-9.896886e-01 1.792051e-02 -1.421105e-01 1.540917e+02 1.652289e-02 9.998029e-01 1.100879e-02 -3.604319e+01 1.422798e-01 8.547199e-03 -9.897895e-01 5.629643e+02 +-9.895629e-01 2.177468e-02 -1.424472e-01 1.538829e+02 2.023419e-02 9.997201e-01 1.225431e-02 -3.605732e+01 1.426741e-01 9.244106e-03 -9.897265e-01 5.616358e+02 +-9.894512e-01 2.515623e-02 -1.426658e-01 1.536849e+02 2.377037e-02 9.996523e-01 1.141041e-02 -3.606846e+01 1.429033e-01 7.898822e-03 -9.897051e-01 5.603082e+02 +-9.893240e-01 2.837350e-02 -1.429440e-01 1.534817e+02 2.731888e-02 9.995832e-01 9.335543e-03 -3.608014e+01 1.431493e-01 5.330807e-03 -9.896867e-01 5.589838e+02 +-9.892833e-01 2.838595e-02 -1.432234e-01 1.532754e+02 2.747625e-02 9.995878e-01 8.325935e-03 -3.609139e+01 1.434007e-01 4.301467e-03 -9.896553e-01 5.576617e+02 +-9.891867e-01 2.801666e-02 -1.439612e-01 1.530669e+02 2.703779e-02 9.995961e-01 8.751914e-03 -3.610579e+01 1.441482e-01 4.764887e-03 -9.895446e-01 5.563377e+02 +-9.891645e-01 2.490008e-02 -1.446846e-01 1.528621e+02 2.407938e-02 9.996825e-01 7.421109e-03 -3.612050e+01 1.448235e-01 3.856782e-03 -9.894499e-01 5.550162e+02 +-9.891403e-01 2.181469e-02 -1.453467e-01 1.526571e+02 2.125590e-02 9.997595e-01 5.396670e-03 -3.613785e+01 1.454294e-01 2.248591e-03 -9.893660e-01 5.536995e+02 +-9.890958e-01 1.855939e-02 -1.460997e-01 1.524519e+02 1.801347e-02 9.998249e-01 5.058916e-03 -3.615574e+01 1.461680e-01 2.371991e-03 -9.892569e-01 5.523778e+02 +-9.890226e-01 1.610433e-02 -1.468841e-01 1.522297e+02 1.532234e-02 9.998618e-01 6.453933e-03 -3.617512e+01 1.469677e-01 4.132480e-03 -9.891326e-01 5.510578e+02 +-9.889143e-01 1.509144e-02 -1.477186e-01 1.520070e+02 1.410253e-02 9.998706e-01 7.739785e-03 -3.619361e+01 1.478163e-01 5.570779e-03 -9.889991e-01 5.497361e+02 +-9.888462e-01 1.486770e-02 -1.481969e-01 1.517816e+02 1.378119e-02 9.998701e-01 8.355794e-03 -3.621094e+01 1.483018e-01 6.220267e-03 -9.889225e-01 5.484183e+02 +-9.888477e-01 1.551270e-02 -1.481205e-01 1.515568e+02 1.462116e-02 9.998678e-01 7.106107e-03 -3.622887e+01 1.482112e-01 4.861164e-03 -9.889437e-01 5.471003e+02 +-9.889139e-01 1.696409e-02 -1.475179e-01 1.513355e+02 1.618452e-02 9.998480e-01 6.483446e-03 -3.624426e+01 1.476054e-01 4.024065e-03 -9.890381e-01 5.457807e+02 +-9.890381e-01 1.707966e-02 -1.466695e-01 1.511231e+02 1.624732e-02 9.998444e-01 6.871223e-03 -3.626111e+01 1.467641e-01 4.412916e-03 -9.891616e-01 5.444675e+02 +-9.891123e-01 1.707504e-02 -1.461688e-01 1.509147e+02 1.612423e-02 9.998404e-01 7.687363e-03 -3.628456e+01 1.462767e-01 5.246808e-03 -9.892297e-01 5.431458e+02 +-9.892205e-01 1.679567e-02 -1.454676e-01 1.507023e+02 1.577951e-02 9.998424e-01 8.136612e-03 -3.631054e+01 1.455813e-01 5.753497e-03 -9.893295e-01 5.418300e+02 +-9.893164e-01 1.751741e-02 -1.447281e-01 1.504989e+02 1.651996e-02 9.998308e-01 8.090979e-03 -3.633671e+01 1.448454e-01 5.613637e-03 -9.894383e-01 5.405167e+02 +-9.894167e-01 1.767754e-02 -1.440212e-01 1.503028e+02 1.698730e-02 9.998376e-01 6.021044e-03 -3.635943e+01 1.441042e-01 3.510792e-03 -9.895562e-01 5.391902e+02 +-9.895127e-01 2.088679e-02 -1.429281e-01 1.501111e+02 2.022566e-02 9.997769e-01 6.077145e-03 -3.638092e+01 1.430232e-01 3.122597e-03 -9.897144e-01 5.378632e+02 +-9.896377e-01 2.278073e-02 -1.417685e-01 1.499274e+02 2.201541e-02 9.997333e-01 6.964738e-03 -3.640180e+01 1.418894e-01 3.771476e-03 -9.898753e-01 5.365334e+02 +-9.897121e-01 2.733818e-02 -1.404371e-01 1.497390e+02 2.656933e-02 9.996200e-01 7.347183e-03 -3.641925e+01 1.405845e-01 3.540280e-03 -9.900623e-01 5.352059e+02 +-9.898079e-01 2.796837e-02 -1.396360e-01 1.495658e+02 2.733205e-02 9.996054e-01 6.472998e-03 -3.643762e+01 1.397619e-01 2.590488e-03 -9.901817e-01 5.338780e+02 +-9.899198e-01 2.730970e-02 -1.389714e-01 1.493900e+02 2.712272e-02 9.996268e-01 3.239530e-03 -3.645568e+01 1.390080e-01 -5.624045e-04 -9.902910e-01 5.325525e+02 +-9.900610e-01 2.560378e-02 -1.382887e-01 1.492373e+02 2.556514e-02 9.996710e-01 2.055982e-03 -3.647314e+01 1.382959e-01 -1.499820e-03 -9.903898e-01 5.312173e+02 +-9.901479e-01 2.538756e-02 -1.377048e-01 1.490707e+02 2.522498e-02 9.996775e-01 2.925985e-03 -3.649414e+01 1.377346e-01 -5.764402e-04 -9.904689e-01 5.298864e+02 +-9.902720e-01 2.580938e-02 -1.367309e-01 1.489178e+02 2.548331e-02 9.996667e-01 4.134965e-03 -3.651605e+01 1.367920e-01 6.103862e-04 -9.905995e-01 5.285526e+02 +-9.903953e-01 2.581926e-02 -1.358327e-01 1.487465e+02 2.551535e-02 9.996665e-01 3.978238e-03 -3.654081e+01 1.358901e-01 4.742121e-04 -9.907237e-01 5.272240e+02 +-9.905290e-01 2.482172e-02 -1.350416e-01 1.485833e+02 2.447550e-02 9.996915e-01 4.223692e-03 -3.656521e+01 1.351047e-01 8.784809e-04 -9.908309e-01 5.258922e+02 +-9.906518e-01 2.259473e-02 -1.345309e-01 1.484166e+02 2.211673e-02 9.997426e-01 5.046782e-03 -3.659225e+01 1.346103e-01 2.024222e-03 -9.908965e-01 5.245616e+02 +-9.907610e-01 2.084877e-02 -1.340075e-01 1.482552e+02 2.019689e-02 9.997766e-01 6.222269e-03 -3.662280e+01 1.341073e-01 3.458247e-03 -9.909607e-01 5.232315e+02 +-9.908682e-01 1.789627e-02 -1.336415e-01 1.480981e+02 1.727698e-02 9.998339e-01 5.792347e-03 -3.665937e+01 1.337230e-01 3.430532e-03 -9.910128e-01 5.218996e+02 +-9.909207e-01 1.402886e-02 -1.337141e-01 1.479370e+02 1.378034e-02 9.999011e-01 2.783986e-03 -3.669287e+01 1.337400e-01 9.160851e-04 -9.910160e-01 5.205729e+02 +-9.908402e-01 1.247592e-02 -1.344621e-01 1.477813e+02 1.244741e-02 9.999220e-01 1.052740e-03 -3.672369e+01 1.344647e-01 -6.306056e-04 -9.909181e-01 5.192436e+02 +-9.907356e-01 1.084154e-02 -1.353718e-01 1.476152e+02 1.025655e-02 9.999348e-01 5.018104e-03 -3.675185e+01 1.354174e-01 3.583167e-03 -9.907821e-01 5.179060e+02 +-9.904870e-01 1.608944e-02 -1.366631e-01 1.474333e+02 1.519173e-02 9.998556e-01 7.609397e-03 -3.678077e+01 1.367658e-01 5.460860e-03 -9.905883e-01 5.165776e+02 +-9.904065e-01 1.648536e-02 -1.371981e-01 1.472478e+02 1.589963e-02 9.998592e-01 5.364137e-03 -3.680604e+01 1.372672e-01 3.131279e-03 -9.905291e-01 5.152502e+02 +-9.902494e-01 1.933657e-02 -1.379579e-01 1.470786e+02 1.924575e-02 9.998128e-01 1.992384e-03 -3.682222e+01 1.379706e-01 -6.821457e-04 -9.904360e-01 5.139248e+02 +-9.900981e-01 2.012919e-02 -1.389265e-01 1.469088e+02 1.981695e-02 9.997970e-01 3.630583e-03 -3.684045e+01 1.389714e-01 8.415348e-04 -9.902960e-01 5.125940e+02 +-9.898938e-01 2.061069e-02 -1.403053e-01 1.467361e+02 1.990936e-02 9.997813e-01 6.400626e-03 -3.685922e+01 1.404066e-01 3.542551e-03 -9.900875e-01 5.112597e+02 +-9.897705e-01 2.041724e-02 -1.412005e-01 1.465574e+02 1.979263e-02 9.997871e-01 5.826822e-03 -3.687345e+01 1.412894e-01 2.972489e-03 -9.899638e-01 5.099280e+02 +-9.896218e-01 2.120126e-02 -1.421243e-01 1.463705e+02 2.071960e-02 9.997735e-01 4.868285e-03 -3.689043e+01 1.421953e-01 1.873005e-03 -9.898368e-01 5.086073e+02 +-9.895002e-01 2.080302e-02 -1.430267e-01 1.461806e+02 2.019674e-02 9.997798e-01 5.689680e-03 -3.690734e+01 1.431136e-01 2.741267e-03 -9.897024e-01 5.072768e+02 +-9.893663e-01 1.895284e-02 -1.442054e-01 1.459908e+02 1.790779e-02 9.998031e-01 8.541667e-03 -3.692472e+01 1.443389e-01 5.868438e-03 -9.895109e-01 5.059474e+02 +-9.892472e-01 1.625619e-02 -1.453474e-01 1.458011e+02 1.490777e-02 9.998352e-01 1.036172e-02 -3.694071e+01 1.454919e-01 8.083492e-03 -9.893264e-01 5.046207e+02 +-9.890915e-01 1.367614e-02 -1.466662e-01 1.456051e+02 1.246398e-02 9.998802e-01 9.180645e-03 -3.696090e+01 1.467742e-01 7.252454e-03 -9.891434e-01 5.032985e+02 +-9.890117e-01 7.412294e-03 -1.476518e-01 1.454142e+02 6.796777e-03 9.999660e-01 4.672883e-03 -3.699136e+01 1.476814e-01 3.617981e-03 -9.890283e-01 5.019839e+02 +-9.888651e-01 4.661564e-03 -1.487417e-01 1.452222e+02 4.769768e-03 9.999885e-01 -3.706894e-04 -3.701873e+01 1.487383e-01 -1.076023e-03 -9.888760e-01 5.006689e+02 +-9.887266e-01 1.062241e-03 -1.497287e-01 1.450362e+02 1.123970e-03 9.999993e-01 -3.275931e-04 -3.705073e+01 1.497282e-01 -4.921884e-04 -9.887270e-01 4.993461e+02 +-9.885977e-01 -1.510089e-03 -1.505736e-01 1.448394e+02 -1.479113e-03 9.999988e-01 -3.176579e-04 -3.708251e+01 1.505739e-01 -9.131850e-05 -9.885987e-01 4.980232e+02 +-9.884821e-01 2.772805e-04 -1.513378e-01 1.446322e+02 4.923741e-04 9.999989e-01 -1.383754e-03 -3.711944e+01 1.513372e-01 -1.442328e-03 -9.884811e-01 4.967093e+02 +-9.884474e-01 2.892154e-03 -1.515371e-01 1.444285e+02 3.527065e-03 9.999861e-01 -3.921123e-03 -3.715595e+01 1.515236e-01 -4.410302e-03 -9.884437e-01 4.953908e+02 +-9.884848e-01 6.963640e-03 -1.511604e-01 1.442370e+02 7.835751e-03 9.999559e-01 -5.174494e-03 -3.719331e+01 1.511177e-01 -6.299360e-03 -9.884957e-01 4.940666e+02 +-9.884697e-01 1.316380e-02 -1.508458e-01 1.440382e+02 1.366591e-02 9.999040e-01 -2.292356e-03 -3.723224e+01 1.508011e-01 -4.327367e-03 -9.885546e-01 4.927343e+02 +-9.884697e-01 1.597739e-02 -1.505739e-01 1.438385e+02 1.598087e-02 9.998716e-01 1.187115e-03 -3.727609e+01 1.505736e-01 -1.232873e-03 -9.885980e-01 4.914146e+02 +-9.884543e-01 1.786660e-02 -1.504624e-01 1.436422e+02 1.816528e-02 9.998348e-01 -6.106626e-04 -3.731896e+01 1.504266e-01 -3.336800e-03 -9.886155e-01 4.900867e+02 +-9.884250e-01 1.464000e-02 -1.510024e-01 1.434585e+02 1.562783e-02 9.998635e-01 -5.357043e-03 -3.735422e+01 1.509033e-01 -7.654872e-03 -9.885188e-01 4.887606e+02 +-9.883920e-01 9.786322e-03 -1.516098e-01 1.432828e+02 1.133988e-02 9.998916e-01 -9.385777e-03 -3.739562e+01 1.515015e-01 -1.099606e-02 -9.883958e-01 4.874301e+02 +-9.883985e-01 7.265608e-03 -1.517093e-01 1.430936e+02 9.012648e-03 9.999007e-01 -1.083119e-02 -3.744017e+01 1.516155e-01 -1.207283e-02 -9.883658e-01 4.861006e+02 +-9.884641e-01 6.952625e-03 -1.512962e-01 1.429060e+02 8.664382e-03 9.999056e-01 -1.065758e-02 -3.748631e+01 1.512078e-01 -1.184552e-02 -9.884310e-01 4.847698e+02 +-9.885801e-01 7.641888e-03 -1.505029e-01 1.427088e+02 9.350996e-03 9.998995e-01 -1.065148e-02 -3.753118e+01 1.504063e-01 -1.193719e-02 -9.885521e-01 4.834425e+02 +-9.887594e-01 8.052690e-03 -1.492989e-01 1.425200e+02 9.689837e-03 9.999006e-01 -1.024132e-02 -3.757513e+01 1.492016e-01 -1.157288e-02 -9.887390e-01 4.821095e+02 +-9.889554e-01 7.505745e-03 -1.480237e-01 1.423295e+02 9.063445e-03 9.999104e-01 -9.851530e-03 -3.761820e+01 1.479365e-01 -1.108432e-02 -9.889347e-01 4.807796e+02 +-9.891311e-01 6.056063e-03 -1.469118e-01 1.421423e+02 7.544195e-03 9.999257e-01 -9.574285e-03 -3.766075e+01 1.468429e-01 -1.057855e-02 -9.891032e-01 4.794505e+02 +-9.892652e-01 4.500837e-03 -1.460621e-01 1.419536e+02 6.085667e-03 9.999273e-01 -1.040530e-02 -3.770401e+01 1.460046e-01 -1.118248e-02 -9.892207e-01 4.781200e+02 +-9.893713e-01 2.469803e-03 -1.453906e-01 1.417705e+02 4.228998e-03 9.999215e-01 -1.179190e-02 -3.774107e+01 1.453501e-01 -1.228142e-02 -9.893040e-01 4.767885e+02 +-9.894656e-01 2.014267e-04 -1.447681e-01 1.415915e+02 2.146838e-03 9.999095e-01 -1.328197e-02 -3.777811e+01 1.447523e-01 -1.345284e-02 -9.893764e-01 4.754542e+02 +-9.895241e-01 -1.434674e-03 -1.443610e-01 1.414092e+02 5.632007e-04 9.999046e-01 -1.379756e-02 -3.781888e+01 1.443670e-01 -1.373432e-02 -9.894288e-01 4.741207e+02 +-9.896031e-01 -3.489448e-03 -1.437830e-01 1.412299e+02 -1.672752e-03 9.999172e-01 -1.275388e-02 -3.785877e+01 1.438156e-01 -1.238077e-02 -9.895270e-01 4.727832e+02 +-9.896326e-01 -4.978814e-03 -1.435358e-01 1.410454e+02 -3.303298e-03 9.999236e-01 -1.190905e-02 -3.790188e+01 1.435841e-01 -1.131144e-02 -9.895734e-01 4.714476e+02 +-9.896408e-01 -7.388927e-03 -1.433759e-01 1.408662e+02 -5.638714e-03 9.999046e-01 -1.260960e-02 -3.794403e+01 1.434554e-01 -1.167052e-02 -9.895879e-01 4.701168e+02 +-9.896452e-01 -9.763442e-03 -1.432028e-01 1.406838e+02 -7.828657e-03 9.998704e-01 -1.406800e-02 -3.798848e+01 1.433216e-01 -1.280124e-02 -9.895933e-01 4.687861e+02 +-9.896865e-01 -1.057343e-02 -1.428600e-01 1.405054e+02 -8.623215e-03 9.998611e-01 -1.426347e-02 -3.803096e+01 1.429910e-01 -1.288444e-02 -9.896401e-01 4.674554e+02 +-9.897391e-01 -1.172907e-02 -1.424044e-01 1.403299e+02 -9.578747e-03 9.998296e-01 -1.577622e-02 -3.807021e+01 1.425652e-01 -1.425028e-02 -9.896828e-01 4.661290e+02 +-9.897902e-01 -1.350495e-02 -1.418914e-01 1.401531e+02 -1.097678e-02 9.997670e-01 -1.858528e-02 -3.810772e+01 1.421093e-01 -1.683801e-02 -9.897077e-01 4.648054e+02 +-9.898135e-01 -1.590797e-02 -1.414787e-01 1.399768e+02 -1.325915e-02 9.997191e-01 -1.964543e-02 -3.815253e+01 1.417515e-01 -1.756942e-02 -9.897463e-01 4.634873e+02 +-9.898150e-01 -1.824911e-02 -1.411855e-01 1.398029e+02 -1.578401e-02 9.997031e-01 -1.856023e-02 -3.819948e+01 1.414823e-01 -1.614272e-02 -9.898091e-01 4.621702e+02 +-9.897959e-01 -2.021324e-02 -1.410519e-01 1.396312e+02 -1.766552e-02 9.996578e-01 -1.929123e-02 -3.824579e+01 1.413935e-01 -1.660262e-02 -9.898142e-01 4.608614e+02 +-9.898625e-01 -2.132800e-02 -1.404191e-01 1.394572e+02 -1.876096e-02 9.996322e-01 -1.957978e-02 -3.829285e+01 1.407850e-01 -1.674689e-02 -9.898985e-01 4.595579e+02 +-9.899337e-01 -2.258126e-02 -1.397191e-01 1.392852e+02 -1.988461e-02 9.995886e-01 -2.066663e-02 -3.834326e+01 1.401283e-01 -1.768033e-02 -9.899754e-01 4.582594e+02 +-9.900199e-01 -2.207425e-02 -1.391886e-01 1.391113e+02 -1.926936e-02 9.995838e-01 -2.146733e-02 -3.839462e+01 1.396045e-01 -1.857101e-02 -9.900331e-01 4.569649e+02 +-9.901115e-01 -2.170054e-02 -1.385943e-01 1.389402e+02 -1.899122e-02 9.996024e-01 -2.084126e-02 -3.844393e+01 1.389915e-01 -1.800309e-02 -9.901299e-01 4.556713e+02 +-9.902170e-01 -2.149674e-02 -1.378701e-01 1.387674e+02 -1.897685e-02 9.996284e-01 -1.956586e-02 -3.849641e+01 1.382395e-01 -1.675810e-02 -9.902570e-01 4.543808e+02 +-9.903802e-01 -1.984853e-02 -1.369426e-01 1.386009e+02 -1.731748e-02 9.996569e-01 -1.964936e-02 -3.853840e+01 1.372856e-01 -1.708883e-02 -9.903840e-01 4.530896e+02 +-9.905411e-01 -1.952684e-02 -1.358200e-01 1.384296e+02 -1.661017e-02 9.996071e-01 -2.257476e-02 -3.859054e+01 1.362075e-01 -2.010523e-02 -9.904762e-01 4.518114e+02 +-9.907544e-01 -1.986211e-02 -1.342062e-01 1.382652e+02 -1.651366e-02 9.995251e-01 -2.601737e-02 -3.863673e+01 1.346592e-01 -2.356058e-02 -9.906118e-01 4.505371e+02 +-9.909842e-01 -1.778254e-02 -1.327935e-01 1.381021e+02 -1.451858e-02 9.995692e-01 -2.550721e-02 -3.867953e+01 1.331899e-01 -2.334926e-02 -9.908154e-01 4.492604e+02 +-9.911949e-01 -1.666766e-02 -1.313583e-01 1.379417e+02 -1.390015e-02 9.996623e-01 -2.195720e-02 -3.872791e+01 1.316799e-01 -1.993795e-02 -9.910917e-01 4.479831e+02 +-9.914602e-01 -1.559707e-02 -1.294740e-01 1.377819e+02 -1.277429e-02 9.996629e-01 -2.260381e-02 -3.877963e+01 1.297829e-01 -2.075683e-02 -9.913251e-01 4.467035e+02 +-9.917445e-01 -1.483499e-02 -1.273692e-01 1.376244e+02 -1.173365e-02 9.996169e-01 -2.506509e-02 -3.883459e+01 1.276923e-01 -2.336365e-02 -9.915386e-01 4.454404e+02 +-9.920028e-01 -1.493145e-02 -1.253303e-01 1.374746e+02 -1.184273e-02 9.996084e-01 -2.535355e-02 -3.888771e+01 1.256597e-01 -2.366653e-02 -9.917910e-01 4.441661e+02 +-9.922160e-01 -1.578859e-02 -1.235245e-01 1.373267e+02 -1.280119e-02 9.996069e-01 -2.494101e-02 -3.894477e+01 1.238697e-01 -2.316560e-02 -9.920280e-01 4.428900e+02 +-9.924324e-01 -1.646546e-02 -1.216836e-01 1.371814e+02 -1.362245e-02 9.996153e-01 -2.415910e-02 -3.899490e+01 1.220346e-01 -2.231864e-02 -9.922748e-01 4.416177e+02 +-9.926322e-01 -1.870153e-02 -1.197151e-01 1.370410e+02 -1.628782e-02 9.996445e-01 -2.110890e-02 -3.905025e+01 1.200673e-01 -1.900347e-02 -9.925838e-01 4.403381e+02 +-9.928354e-01 -2.056616e-02 -1.177076e-01 1.369051e+02 -1.855595e-02 9.996631e-01 -1.814857e-02 -3.910228e+01 1.180411e-01 -1.583436e-02 -9.928824e-01 4.390647e+02 +-9.929955e-01 -2.344252e-02 -1.158033e-01 1.367740e+02 -2.155891e-02 9.996145e-01 -1.749153e-02 -3.915010e+01 1.161687e-01 -1.487241e-02 -9.931181e-01 4.377872e+02 +-9.932197e-01 -2.535236e-02 -1.134543e-01 1.366461e+02 -2.315104e-02 9.995181e-01 -2.067857e-02 -3.919901e+01 1.139238e-01 -1.791177e-02 -9.933280e-01 4.365142e+02 +-9.935228e-01 -2.534966e-02 -1.107699e-01 1.365181e+02 -2.290488e-02 9.994664e-01 -2.328804e-02 -3.924495e+01 1.113011e-01 -2.060002e-02 -9.935731e-01 4.352373e+02 +-9.938398e-01 -2.457168e-02 -1.080685e-01 1.363912e+02 -2.222516e-02 9.994915e-01 -2.286448e-02 -3.928684e+01 1.085754e-01 -2.032178e-02 -9.938804e-01 4.339654e+02 +-9.941889e-01 -2.303180e-02 -1.051572e-01 1.362644e+02 -2.074498e-02 9.995250e-01 -2.278896e-02 -3.933188e+01 1.056322e-01 -2.047504e-02 -9.941944e-01 4.326922e+02 +-9.945031e-01 -2.230111e-02 -1.023048e-01 1.361432e+02 -1.991357e-02 9.995063e-01 -2.429977e-02 -3.938072e+01 1.027962e-01 -2.212894e-02 -9.944562e-01 4.314142e+02 +-9.947993e-01 -2.273008e-02 -9.928615e-02 1.360298e+02 -2.018601e-02 9.994435e-01 -2.655351e-02 -3.943242e+01 9.983446e-02 -2.441122e-02 -9.947045e-01 4.301404e+02 +-9.951314e-01 -2.450791e-02 -9.546170e-02 1.359258e+02 -2.195945e-02 9.993762e-01 -2.765594e-02 -3.948564e+01 9.607994e-02 -2.542500e-02 -9.950488e-01 4.288635e+02 +-9.954804e-01 -2.772214e-02 -9.083102e-02 1.358254e+02 -2.500217e-02 9.992082e-01 -3.094778e-02 -3.954136e+01 9.161704e-02 -2.853693e-02 -9.953853e-01 4.275922e+02 +-9.958169e-01 -3.010832e-02 -8.626886e-02 1.357266e+02 -2.767522e-02 9.991885e-01 -2.926234e-02 -3.960010e+01 8.707989e-02 -2.675241e-02 -9.958420e-01 4.263140e+02 +-9.960700e-01 -3.320997e-02 -8.210783e-02 1.356323e+02 -3.163163e-02 9.992904e-01 -2.044969e-02 -3.966444e+01 8.272869e-02 -1.777211e-02 -9.964136e-01 4.250231e+02 +-9.962749e-01 -3.655098e-02 -7.810498e-02 1.355432e+02 -3.517015e-02 9.992010e-01 -1.898261e-02 -3.972587e+01 7.873641e-02 -1.616493e-02 -9.967643e-01 4.237373e+02 +-9.966623e-01 -3.482630e-02 -7.383469e-02 1.354491e+02 -3.324397e-02 9.991928e-01 -2.255274e-02 -3.978588e+01 7.456051e-02 -2.002290e-02 -9.970154e-01 4.224548e+02 +-9.969776e-01 -3.465749e-02 -6.953201e-02 1.353585e+02 -3.274986e-02 9.990603e-01 -2.839042e-02 -3.985114e+01 7.045060e-02 -2.602744e-02 -9.971756e-01 4.211841e+02 +-9.972853e-01 -3.443056e-02 -6.508957e-02 1.352701e+02 -3.232483e-02 9.989281e-01 -3.313235e-02 -3.992522e+01 6.616056e-02 -3.093839e-02 -9.973292e-01 4.199081e+02 +-9.975705e-01 -3.362669e-02 -6.101187e-02 1.351884e+02 -3.172885e-02 9.989901e-01 -3.181280e-02 -4.000274e+01 6.202001e-02 -2.979966e-02 -9.976299e-01 4.186176e+02 +-9.977731e-01 -3.365362e-02 -5.758803e-02 1.351107e+02 -3.213298e-02 9.991153e-01 -2.713099e-02 -4.008164e+01 5.845013e-02 -2.522009e-02 -9.979717e-01 4.173250e+02 +-9.979483e-01 -3.388952e-02 -5.432035e-02 1.350359e+02 -3.268660e-02 9.992036e-01 -2.288256e-02 -4.015777e+01 5.505257e-02 -2.106006e-02 -9.982613e-01 4.160312e+02 +-9.981659e-01 -3.289015e-02 -5.082390e-02 1.349704e+02 -3.176216e-02 9.992343e-01 -2.284464e-02 -4.022041e+01 5.153635e-02 -2.118845e-02 -9.984463e-01 4.147415e+02 +-9.983467e-01 -3.291632e-02 -4.712158e-02 1.349129e+02 -3.178415e-02 9.991925e-01 -2.457752e-02 -4.027725e+01 4.789253e-02 -2.303916e-02 -9.985867e-01 4.134553e+02 +-9.985198e-01 -3.290336e-02 -4.330922e-02 1.348604e+02 -3.181997e-02 9.991690e-01 -2.547132e-02 -4.033625e+01 4.411132e-02 -2.405551e-02 -9.987369e-01 4.121672e+02 +-9.986687e-01 -3.292346e-02 -3.971183e-02 1.348092e+02 -3.191748e-02 9.991599e-01 -2.570563e-02 -4.039977e+01 4.052479e-02 -2.440390e-02 -9.988804e-01 4.108802e+02 +-9.987678e-01 -3.399490e-02 -3.615621e-02 1.347665e+02 -3.304133e-02 9.990985e-01 -2.665207e-02 -4.046812e+01 3.702965e-02 -2.542457e-02 -9.989906e-01 4.095954e+02 +-9.988065e-01 -3.636268e-02 -3.260948e-02 1.347296e+02 -3.546561e-02 9.989875e-01 -2.767822e-02 -4.053259e+01 3.358292e-02 -2.648867e-02 -9.990848e-01 4.083192e+02 +-9.988125e-01 -3.902856e-02 -2.916112e-02 1.347040e+02 -3.821760e-02 9.988807e-01 -2.786789e-02 -4.059131e+01 3.021612e-02 -2.672033e-02 -9.991861e-01 4.070461e+02 +-9.987669e-01 -4.229038e-02 -2.600402e-02 1.346779e+02 -4.158285e-02 9.987655e-01 -2.717257e-02 -4.065667e+01 2.712106e-02 -2.605773e-02 -9.992924e-01 4.057783e+02 +-9.986335e-01 -4.686355e-02 -2.313127e-02 1.346575e+02 -4.624595e-02 9.985772e-01 -2.654919e-02 -4.072310e+01 2.434254e-02 -2.544317e-02 -9.993798e-01 4.045156e+02 +-9.984842e-01 -5.120144e-02 -2.019415e-02 1.346428e+02 -5.064503e-02 9.983472e-01 -2.716399e-02 -4.078707e+01 2.155161e-02 -2.610007e-02 -9.994269e-01 4.032567e+02 +-9.984896e-01 -5.213734e-02 -1.732867e-02 1.346307e+02 -5.159634e-02 9.982075e-01 -3.032376e-02 -4.084851e+01 1.887861e-02 -2.938386e-02 -9.993899e-01 4.020090e+02 +-9.985724e-01 -5.140837e-02 -1.450273e-02 1.346228e+02 -5.089854e-02 9.981395e-01 -3.356889e-02 -4.090735e+01 1.620147e-02 -3.278279e-02 -9.993311e-01 4.007687e+02 +-9.987514e-01 -4.871881e-02 -1.105402e-02 1.346122e+02 -4.831418e-02 9.982425e-01 -3.431616e-02 -4.096407e+01 1.270643e-02 -3.373924e-02 -9.993498e-01 3.995327e+02 +-9.989693e-01 -4.478248e-02 -7.416628e-03 1.346026e+02 -4.451842e-02 9.984767e-01 -3.259296e-02 -4.102615e+01 8.864923e-03 -3.222918e-02 -9.994411e-01 3.983021e+02 +-9.990799e-01 -4.268478e-02 -4.166739e-03 1.345964e+02 -4.252768e-02 9.985687e-01 -3.243211e-02 -4.108453e+01 5.545132e-03 -3.222506e-02 -9.994652e-01 3.970796e+02 +-9.990888e-01 -4.266517e-02 -1.159432e-03 1.346004e+02 -4.260324e-02 9.985406e-01 -3.319127e-02 -4.114517e+01 2.573851e-03 -3.311163e-02 -9.994483e-01 3.958656e+02 +-9.990253e-01 -4.411011e-02 1.687880e-03 1.346097e+02 -4.414180e-02 9.984793e-01 -3.302423e-02 -4.120807e+01 -2.286110e-04 -3.306654e-02 -9.994531e-01 3.946601e+02 +-9.989705e-01 -4.515270e-02 4.395510e-03 1.346230e+02 -4.526712e-02 9.984982e-01 -3.085714e-02 -4.126979e+01 -2.995626e-03 -3.102434e-02 -9.995141e-01 3.934603e+02 +-9.989857e-01 -4.447763e-02 7.032118e-03 1.346335e+02 -4.466395e-02 9.985800e-01 -2.903455e-02 -4.132810e+01 -5.730745e-03 -2.931917e-02 -9.995536e-01 3.922676e+02 +-9.990457e-01 -4.266422e-02 9.354649e-03 1.346464e+02 -4.291500e-02 9.986726e-01 -2.848444e-02 -4.138698e+01 -8.126965e-03 -2.885870e-02 -9.995504e-01 3.910822e+02 +-9.990464e-01 -4.204100e-02 1.178434e-02 1.346647e+02 -4.237258e-02 9.986673e-01 -2.946303e-02 -4.144977e+01 -1.052998e-02 -2.993427e-02 -9.994963e-01 3.899037e+02 +-9.990585e-01 -4.093979e-02 1.435958e-02 1.346860e+02 -4.137376e-02 9.986517e-01 -3.135346e-02 -4.152012e+01 -1.305662e-02 -3.191804e-02 -9.994051e-01 3.887277e+02 +-9.990315e-01 -4.070468e-02 1.671250e-02 1.347122e+02 -4.122467e-02 9.986358e-01 -3.204762e-02 -4.158853e+01 -1.538521e-02 -3.270555e-02 -9.993466e-01 3.875583e+02 +-9.989479e-01 -4.183400e-02 1.879031e-02 1.347429e+02 -4.241622e-02 9.985958e-01 -3.173669e-02 -4.165899e+01 -1.743625e-02 -3.250031e-02 -9.993196e-01 3.863954e+02 +-9.988691e-01 -4.251690e-02 2.128265e-02 1.347770e+02 -4.318723e-02 9.985513e-01 -3.209603e-02 -4.172782e+01 -1.988719e-02 -3.297887e-02 -9.992581e-01 3.852386e+02 +-9.988239e-01 -4.222861e-02 2.382599e-02 1.348122e+02 -4.297033e-02 9.985787e-01 -3.152893e-02 -4.179540e+01 -2.246070e-02 -3.251566e-02 -9.992188e-01 3.840904e+02 +-9.988114e-01 -4.106020e-02 2.626490e-02 1.348491e+02 -4.181590e-02 9.987072e-01 -2.890078e-02 -4.186002e+01 -2.504428e-02 -2.996471e-02 -9.992371e-01 3.829455e+02 +-9.988299e-01 -3.891707e-02 2.871361e-02 1.348868e+02 -3.972612e-02 9.988135e-01 -2.816586e-02 -4.192533e+01 -2.758341e-02 -2.927357e-02 -9.991907e-01 3.818090e+02 +-9.988049e-01 -3.719207e-02 3.171191e-02 1.349285e+02 -3.818349e-02 9.987819e-01 -3.125308e-02 -4.198672e+01 -3.051091e-02 -3.242659e-02 -9.990083e-01 3.806844e+02 +-9.988505e-01 -3.325352e-02 3.452620e-02 1.349720e+02 -3.444494e-02 9.988107e-01 -3.450661e-02 -4.203830e+01 -3.333767e-02 -3.565619e-02 -9.988079e-01 3.795654e+02 +-9.988036e-01 -3.179741e-02 3.715446e-02 1.350210e+02 -3.303355e-02 9.989045e-01 -3.314435e-02 -4.208977e+01 -3.605985e-02 -3.433203e-02 -9.987597e-01 3.784539e+02 +-9.987208e-01 -3.097444e-02 3.996872e-02 1.350748e+02 -3.212926e-02 9.990749e-01 -2.858164e-02 -4.214031e+01 -3.904645e-02 -2.982924e-02 -9.987920e-01 3.773415e+02 +-9.985900e-01 -3.002133e-02 4.378189e-02 1.351318e+02 -3.120459e-02 9.991590e-01 -2.659806e-02 -4.219082e+01 -4.294656e-02 -2.792675e-02 -9.986869e-01 3.762447e+02 +-9.983973e-01 -3.051968e-02 4.766089e-02 1.351949e+02 -3.186749e-02 9.991059e-01 -2.778008e-02 -4.224163e+01 -4.677044e-02 -2.925438e-02 -9.984771e-01 3.751579e+02 +-9.981968e-01 -3.132185e-02 5.120672e-02 1.352628e+02 -3.293343e-02 9.989786e-01 -3.093722e-02 -4.229196e+01 -5.018541e-02 -3.256784e-02 -9.982087e-01 3.740859e+02 +-9.979418e-01 -3.285817e-02 5.506865e-02 1.353339e+02 -3.471131e-02 9.988511e-01 -3.303980e-02 -4.234697e+01 -5.391975e-02 -3.488329e-02 -9.979357e-01 3.730182e+02 +-9.976677e-01 -3.364979e-02 5.938756e-02 1.354040e+02 -3.564062e-02 9.988266e-01 -3.278804e-02 -4.241066e+01 -5.821456e-02 -3.482817e-02 -9.976963e-01 3.719591e+02 +-9.973708e-01 -3.305511e-02 6.449045e-02 1.354781e+02 -3.515919e-02 9.988766e-01 -3.176857e-02 -4.247425e+01 -6.336789e-02 -3.395246e-02 -9.974125e-01 3.709063e+02 +-9.970192e-01 -3.131187e-02 7.051488e-02 1.355565e+02 -3.349732e-02 9.989876e-01 -3.002638e-02 -4.253526e+01 -6.950331e-02 -3.229893e-02 -9.970587e-01 3.698612e+02 +-9.965750e-01 -2.828222e-02 7.770713e-02 1.356408e+02 -3.045395e-02 9.991739e-01 -2.690603e-02 -4.259402e+01 -7.688197e-02 -2.918036e-02 -9.966130e-01 3.688247e+02 +-9.959153e-01 -2.641617e-02 8.634248e-02 1.357337e+02 -2.857139e-02 9.993078e-01 -2.382139e-02 -4.265109e+01 -8.565345e-02 -2.619100e-02 -9.959806e-01 3.677918e+02 +-9.950236e-01 -2.505597e-02 9.643857e-02 1.358389e+02 -2.744048e-02 9.993476e-01 -2.347923e-02 -4.270492e+01 -9.578735e-02 -2.600870e-02 -9.950619e-01 3.667771e+02 +-9.938939e-01 -2.323086e-02 1.078669e-01 1.359528e+02 -2.605948e-02 9.993505e-01 -2.488804e-02 -4.275607e+01 -1.072186e-01 -2.754702e-02 -9.938537e-01 3.657691e+02 +-9.925083e-01 -2.236155e-02 1.201140e-01 1.360817e+02 -2.562355e-02 9.993417e-01 -2.568193e-02 -4.280692e+01 -1.194606e-01 -2.856727e-02 -9.924278e-01 3.647747e+02 +-9.907779e-01 -2.273296e-02 1.335758e-01 1.362257e+02 -2.648241e-02 9.993016e-01 -2.636031e-02 -4.285887e+01 -1.328833e-01 -2.965461e-02 -9.906879e-01 3.637919e+02 +-9.886976e-01 -2.203929e-02 1.482950e-01 1.363812e+02 -2.639532e-02 9.992740e-01 -2.747026e-02 -4.291143e+01 -1.475819e-01 -3.107406e-02 -9.885615e-01 3.628127e+02 +-9.861656e-01 -2.147542e-02 1.643661e-01 1.365524e+02 -2.639141e-02 9.992655e-01 -2.778346e-02 -4.296355e+01 -1.636487e-01 -3.173694e-02 -9.860080e-01 3.618493e+02 +-9.833273e-01 -2.075788e-02 1.806560e-01 1.367387e+02 -2.613278e-02 9.992823e-01 -2.742286e-02 -4.301361e+01 -1.799570e-01 -3.168668e-02 -9.831639e-01 3.608913e+02 +-9.802383e-01 -2.153407e-02 1.966450e-01 1.369304e+02 -2.742311e-02 9.992518e-01 -2.727367e-02 -4.304889e+01 -1.959105e-01 -3.212730e-02 -9.800953e-01 3.599464e+02 +-9.770346e-01 -2.140700e-02 2.120029e-01 1.371350e+02 -2.783413e-02 9.992375e-01 -2.737809e-02 -4.307963e+01 -2.112552e-01 -3.265025e-02 -9.768854e-01 3.590175e+02 +-9.736052e-01 -2.323869e-02 2.270529e-01 1.373590e+02 -3.052928e-02 9.991232e-01 -2.865041e-02 -4.311813e+01 -2.261880e-01 -3.482594e-02 -9.734609e-01 3.580810e+02 +-9.702920e-01 -2.422898e-02 2.407205e-01 1.375953e+02 -3.216251e-02 9.990594e-01 -2.908289e-02 -4.315233e+01 -2.397895e-01 -3.596106e-02 -9.701586e-01 3.571547e+02 +-9.670913e-01 -2.703674e-02 2.529890e-01 1.378494e+02 -3.553308e-02 9.989455e-01 -2.907444e-02 -4.319146e+01 -2.519361e-01 -3.710711e-02 -9.670321e-01 3.562281e+02 +-9.640404e-01 -3.012193e-02 2.640432e-01 1.381124e+02 -3.930398e-02 9.987899e-01 -2.956009e-02 -4.323185e+01 -2.628333e-01 -3.887507e-02 -9.640577e-01 3.553032e+02 +-9.611077e-01 -3.294715e-02 2.742018e-01 1.383888e+02 -4.258910e-02 9.986634e-01 -2.928354e-02 -4.327333e+01 -2.728705e-01 -3.982264e-02 -9.612262e-01 3.543803e+02 +-9.583115e-01 -3.517993e-02 2.835518e-01 1.386741e+02 -4.506384e-02 9.985801e-01 -2.840829e-02 -4.331579e+01 -2.821497e-01 -4.000192e-02 -9.585360e-01 3.534552e+02 +-9.555097e-01 -3.773355e-02 2.925363e-01 1.389662e+02 -4.769825e-02 9.984967e-01 -2.700288e-02 -4.335762e+01 -2.910776e-01 -3.975497e-02 -9.558730e-01 3.525348e+02 +-9.526000e-01 -3.949267e-02 3.016515e-01 1.392679e+02 -4.962571e-02 9.984294e-01 -2.599958e-02 -4.340005e+01 -3.001510e-01 -3.973687e-02 -9.530636e-01 3.516183e+02 +-9.494330e-01 -4.166113e-02 3.111937e-01 1.395763e+02 -5.168073e-02 9.983748e-01 -2.401710e-02 -4.344123e+01 -3.096873e-01 -3.888533e-02 -9.500429e-01 3.507073e+02 +-9.459009e-01 -4.218062e-02 3.217023e-01 1.398936e+02 -5.224014e-02 9.983766e-01 -2.269755e-02 -4.348337e+01 -3.202226e-01 -3.827540e-02 -9.465687e-01 3.498059e+02 +-9.419771e-01 -4.280918e-02 3.329362e-01 1.402185e+02 -5.294695e-02 9.983673e-01 -2.143214e-02 -4.352373e+01 -3.314751e-01 -3.781653e-02 -9.427057e-01 3.489157e+02 +-9.380827e-01 -4.376883e-02 3.436354e-01 1.405525e+02 -5.393073e-02 9.983430e-01 -2.006539e-02 -4.356256e+01 -3.421878e-01 -3.735549e-02 -9.388887e-01 3.480314e+02 +-9.341100e-01 -4.521089e-02 3.541111e-01 1.408960e+02 -5.502845e-02 9.983279e-01 -1.769879e-02 -4.359990e+01 -3.527187e-01 -3.601879e-02 -9.350358e-01 3.471572e+02 +-9.301217e-01 -4.552345e-02 3.644191e-01 1.412462e+02 -5.470387e-02 9.983914e-01 -1.490328e-02 -4.363662e+01 -3.631544e-01 -3.379700e-02 -9.311157e-01 3.462915e+02 +-9.257875e-01 -4.525567e-02 3.753259e-01 1.416036e+02 -5.398673e-02 9.984599e-01 -1.277361e-02 -4.367145e+01 -3.741697e-01 -3.208826e-02 -9.268049e-01 3.454288e+02 +-9.209888e-01 -4.508979e-02 3.869710e-01 1.419714e+02 -5.337835e-02 9.985171e-01 -1.069315e-02 -4.370268e+01 -3.859150e-01 -3.050414e-02 -9.220298e-01 3.445790e+02 +-9.156804e-01 -4.416023e-02 3.994739e-01 1.423460e+02 -5.157368e-02 9.986385e-01 -7.822551e-03 -4.373204e+01 -3.985845e-01 -2.776529e-02 -9.167112e-01 3.437338e+02 +-9.097740e-01 -4.290360e-02 4.128809e-01 1.427332e+02 -4.992335e-02 9.987336e-01 -6.223813e-03 -4.376025e+01 -4.120910e-01 -2.627465e-02 -9.107637e-01 3.429018e+02 +-9.033419e-01 -4.078687e-02 4.269777e-01 1.431305e+02 -4.859768e-02 9.987909e-01 -7.407327e-03 -4.378886e+01 -4.261594e-01 -2.744147e-02 -9.042318e-01 3.420845e+02 +-8.963805e-01 -3.741949e-02 4.417033e-01 1.435364e+02 -4.618390e-02 9.988915e-01 -9.101907e-03 -4.381474e+01 -4.408731e-01 -2.855835e-02 -8.971150e-01 3.412705e+02 +-8.887867e-01 -3.361418e-02 4.570868e-01 1.439568e+02 -4.296639e-02 9.990257e-01 -1.007801e-02 -4.384095e+01 -4.563027e-01 -2.859656e-02 -8.893649e-01 3.404686e+02 +-8.804717e-01 -3.103901e-02 4.730816e-01 1.443923e+02 -3.944690e-02 9.991907e-01 -7.859089e-03 -4.386832e+01 -4.724548e-01 -2.558130e-02 -8.809835e-01 3.396745e+02 +-8.712648e-01 -2.689703e-02 4.900758e-01 1.448357e+02 -3.406123e-02 9.994034e-01 -5.703959e-03 -4.389466e+01 -4.896300e-01 -2.166224e-02 -8.716611e-01 3.388817e+02 +-8.608393e-01 -2.343074e-02 5.083372e-01 1.453016e+02 -2.991629e-02 9.995418e-01 -4.589719e-03 -4.391913e+01 -5.079968e-01 -1.915857e-02 -8.611458e-01 3.381059e+02 +-8.498156e-01 -1.831528e-02 5.267618e-01 1.457774e+02 -2.447819e-02 9.996891e-01 -4.731497e-03 -4.394261e+01 -5.265114e-01 -1.691508e-02 -8.499997e-01 3.373321e+02 +-8.381986e-01 -1.460291e-02 5.451697e-01 1.462767e+02 -2.009968e-02 9.997895e-01 -4.122938e-03 -4.396579e+01 -5.449947e-01 -1.441358e-02 -8.383155e-01 3.365741e+02 +-8.263181e-01 -1.147028e-02 5.630869e-01 1.467945e+02 -1.570603e-02 9.998730e-01 -2.680509e-03 -4.398590e+01 -5.629847e-01 -1.105882e-02 -8.263933e-01 3.358250e+02 +-8.138252e-01 -1.200719e-02 5.809857e-01 1.473315e+02 -1.411222e-02 9.999000e-01 8.969181e-04 -4.400497e+01 -5.809383e-01 -7.469066e-03 -8.139132e-01 3.350739e+02 +-8.010310e-01 -1.087501e-02 5.985242e-01 1.478886e+02 -1.088894e-02 9.999342e-01 3.595356e-03 -4.402366e+01 -5.985239e-01 -3.637303e-03 -8.010966e-01 3.343415e+02 +-7.876181e-01 -8.560244e-03 6.161044e-01 1.484661e+02 -7.775000e-03 9.999619e-01 3.954169e-03 -4.404059e+01 -6.161147e-01 -1.675837e-03 -7.876546e-01 3.336147e+02 +-7.739078e-01 -6.061150e-03 6.332694e-01 1.490574e+02 -5.854750e-03 9.999799e-01 2.416010e-03 -4.405316e+01 -6.332713e-01 -1.837866e-03 -7.739277e-01 3.328931e+02 +-7.594121e-01 -4.392650e-03 6.505952e-01 1.496762e+02 -3.369916e-03 9.999903e-01 2.818105e-03 -4.406463e+01 -6.506012e-01 -5.234999e-05 -7.594195e-01 3.321825e+02 +-7.439020e-01 -3.156518e-03 6.682813e-01 1.503161e+02 6.254456e-05 9.999885e-01 4.792894e-03 -4.407741e+01 -6.682887e-01 3.607239e-03 -7.438932e-01 3.314768e+02 +-7.272593e-01 -1.986735e-03 6.863600e-01 1.509670e+02 3.570261e-03 9.999713e-01 6.677510e-03 -4.408767e+01 -6.863535e-01 7.306762e-03 -7.272313e-01 3.307720e+02 +-7.100664e-01 -5.202105e-04 7.041346e-01 1.516443e+02 8.007256e-03 9.999291e-01 8.813441e-03 -4.409067e+01 -7.040892e-01 1.189631e-02 -7.100118e-01 3.300879e+02 +-6.927017e-01 -1.281434e-03 7.212231e-01 1.523391e+02 1.053167e-02 9.998738e-01 1.189170e-02 -4.409280e+01 -7.211473e-01 1.583309e-02 -6.926007e-01 3.294124e+02 +-6.756426e-01 -1.543437e-03 7.372278e-01 1.530500e+02 1.104115e-02 9.998644e-01 1.221209e-02 -4.409609e+01 -7.371466e-01 1.639084e-02 -6.755339e-01 3.287628e+02 +-6.583589e-01 1.985936e-03 7.527016e-01 1.537753e+02 1.435410e-02 9.998478e-01 9.916952e-03 -4.409534e+01 -7.525673e-01 1.733326e-02 -6.582871e-01 3.281329e+02 +-6.406593e-01 2.566990e-03 7.678211e-01 1.545167e+02 1.417751e-02 9.998635e-01 8.486753e-03 -4.409622e+01 -7.676944e-01 1.632290e-02 -6.406081e-01 3.275124e+02 +-6.223735e-01 -4.276146e-04 7.827204e-01 1.552869e+02 1.372634e-02 9.998401e-01 1.146060e-02 -4.409799e+01 -7.826001e-01 1.787665e-02 -6.222680e-01 3.269134e+02 +-6.031933e-01 -3.749655e-03 7.975863e-01 1.560768e+02 1.332112e-02 9.998021e-01 1.477473e-02 -4.409909e+01 -7.974838e-01 1.953676e-02 -6.030239e-01 3.263296e+02 +-5.830076e-01 -6.221830e-03 8.124429e-01 1.568761e+02 1.345778e-02 9.997595e-01 1.731361e-02 -4.409889e+01 -8.123552e-01 2.102764e-02 -5.827837e-01 3.257539e+02 +-5.616841e-01 -7.984336e-03 8.273133e-01 1.576960e+02 1.258015e-02 9.997554e-01 1.818954e-02 -4.409794e+01 -8.272561e-01 2.062449e-02 -5.614462e-01 3.252107e+02 +-5.390019e-01 -8.837217e-03 8.422582e-01 1.585263e+02 1.050226e-02 9.997967e-01 1.721106e-02 -4.409811e+01 -8.422390e-01 1.812240e-02 -5.387995e-01 3.246792e+02 +-5.146880e-01 -1.061154e-02 8.573119e-01 1.593818e+02 1.320643e-02 9.997066e-01 2.030254e-02 -4.409252e+01 -8.572758e-01 2.177150e-02 -5.143969e-01 3.241753e+02 +-4.883259e-01 -1.694400e-02 8.724969e-01 1.602581e+02 1.451720e-02 9.995154e-01 2.753581e-02 -4.408359e+01 -8.725406e-01 2.611265e-02 -4.878432e-01 3.236964e+02 +-4.609807e-01 -2.412913e-02 8.870821e-01 1.611470e+02 1.600341e-02 9.992416e-01 3.549625e-02 -4.407601e+01 -8.872658e-01 3.055942e-02 -4.602450e-01 3.232249e+02 +-4.327368e-01 -2.316704e-02 9.012226e-01 1.620488e+02 2.056967e-02 9.991558e-01 3.556139e-02 -4.405969e+01 -9.012856e-01 3.392656e-02 -4.318949e-01 3.227972e+02 +-4.048483e-01 -2.217811e-02 9.141149e-01 1.629731e+02 2.318422e-02 9.991354e-01 3.450882e-02 -4.404114e+01 -9.140899e-01 3.516387e-02 -4.039841e-01 3.223953e+02 +-3.782904e-01 -2.382056e-02 9.253805e-01 1.639062e+02 2.348247e-02 9.991002e-01 3.531771e-02 -4.402247e+01 -9.253890e-01 3.509056e-02 -3.773906e-01 3.220068e+02 +-3.527553e-01 -2.739794e-02 9.353145e-01 1.648653e+02 2.394973e-02 9.989794e-01 3.829553e-02 -4.400358e+01 -9.354090e-01 3.590947e-02 -3.517391e-01 3.216553e+02 +-3.273991e-01 -3.146528e-02 9.443621e-01 1.658328e+02 2.431055e-02 9.988340e-01 4.170841e-02 -4.398417e+01 -9.445733e-01 3.661324e-02 -3.262524e-01 3.213146e+02 +-3.025365e-01 -3.431253e-02 9.525200e-01 1.668283e+02 2.447188e-02 9.987427e-01 4.375029e-02 -4.396075e+01 -9.528236e-01 3.654600e-02 -3.013164e-01 3.210086e+02 +-2.795922e-01 -3.574502e-02 9.594533e-01 1.678170e+02 2.421347e-02 9.987264e-01 4.426415e-02 -4.393771e+01 -9.598135e-01 3.560759e-02 -2.783705e-01 3.207267e+02 +-2.589373e-01 -3.672004e-02 9.651959e-01 1.688230e+02 2.441080e-02 9.987091e-01 4.454381e-02 -4.391142e+01 -9.655856e-01 3.509525e-02 -2.577067e-01 3.204555e+02 +-2.403943e-01 -3.703450e-02 9.699686e-01 1.698433e+02 2.388430e-02 9.987436e-01 4.405258e-02 -4.388523e+01 -9.703814e-01 3.375701e-02 -2.392078e-01 3.202085e+02 +-2.240015e-01 -3.787891e-02 9.738524e-01 1.708769e+02 2.369271e-02 9.987374e-01 4.429653e-02 -4.385777e+01 -9.743007e-01 3.299568e-02 -2.228212e-01 3.199754e+02 +-2.095902e-01 -3.929809e-02 9.769993e-01 1.719150e+02 2.386562e-02 9.986887e-01 4.529027e-02 -4.383045e+01 -9.774980e-01 3.280909e-02 -2.083775e-01 3.197518e+02 +-1.972237e-01 -4.041499e-02 9.795251e-01 1.729647e+02 2.398089e-02 9.986520e-01 4.603263e-02 -4.380359e+01 -9.800651e-01 3.256861e-02 -1.959887e-01 3.195440e+02 +-1.864278e-01 -4.161389e-02 9.815870e-01 1.740245e+02 2.320544e-02 9.986373e-01 4.674402e-02 -4.377490e+01 -9.821945e-01 3.149253e-02 -1.852081e-01 3.193438e+02 +-1.768201e-01 -4.301767e-02 9.833027e-01 1.750936e+02 2.360725e-02 9.985716e-01 4.793077e-02 -4.374400e+01 -9.839600e-01 3.168818e-02 -1.755520e-01 3.191544e+02 +-1.682262e-01 -4.406834e-02 9.847629e-01 1.761733e+02 2.433274e-02 9.985101e-01 4.884027e-02 -4.371247e+01 -9.854480e-01 3.217818e-02 -1.669032e-01 3.189709e+02 +-1.608271e-01 -4.471025e-02 9.859694e-01 1.772626e+02 2.528785e-02 9.984588e-01 4.940144e-02 -4.368085e+01 -9.866585e-01 3.287813e-02 -1.594486e-01 3.187935e+02 +-1.547817e-01 -4.556458e-02 9.868974e-01 1.783566e+02 2.665168e-02 9.983797e-01 5.027467e-02 -4.364646e+01 -9.875891e-01 3.408406e-02 -1.533165e-01 3.186215e+02 +-1.499764e-01 -4.696096e-02 9.875737e-01 1.794617e+02 2.761542e-02 9.982826e-01 5.166396e-02 -4.361079e+01 -9.883038e-01 3.502063e-02 -1.484220e-01 3.184532e+02 +-1.455032e-01 -4.795377e-02 9.881950e-01 1.805757e+02 2.780492e-02 9.982319e-01 5.253487e-02 -4.357374e+01 -9.889669e-01 3.512067e-02 -1.439126e-01 3.182896e+02 +-1.416900e-01 -4.896321e-02 9.886994e-01 1.816706e+02 2.889375e-02 9.981459e-01 5.357177e-02 -4.355945e+01 -9.894893e-01 3.615781e-02 -1.400126e-01 3.181078e+02 +-1.390042e-01 -5.162325e-02 9.889454e-01 1.827501e+02 2.804503e-02 9.980346e-01 5.603966e-02 -4.356492e+01 -9.898946e-01 3.552474e-02 -1.372832e-01 3.179207e+02 +-1.378724e-01 -5.560885e-02 9.888877e-01 1.838501e+02 2.644343e-02 9.978600e-01 5.980019e-02 -4.355704e+01 -9.900969e-01 3.439437e-02 -1.361068e-01 3.177434e+02 +-1.375634e-01 -6.014101e-02 9.886655e-01 1.849541e+02 2.477975e-02 9.976335e-01 6.413441e-02 -4.355989e+01 -9.901829e-01 3.332142e-02 -1.357476e-01 3.175521e+02 +-1.375237e-01 -6.433627e-02 9.884069e-01 1.860880e+02 2.405411e-02 9.973770e-01 6.826696e-02 -4.353774e+01 -9.902063e-01 3.316356e-02 -1.356154e-01 3.173674e+02 +-1.377477e-01 -6.841645e-02 9.881016e-01 1.872158e+02 2.462003e-02 9.970667e-01 7.246939e-02 -4.352112e+01 -9.901613e-01 3.430957e-02 -1.356593e-01 3.171864e+02 +-1.381366e-01 -6.994381e-02 9.879404e-01 1.883606e+02 2.323899e-02 9.969997e-01 7.383453e-02 -4.348922e+01 -9.901405e-01 3.315798e-02 -1.360967e-01 3.170146e+02 +-1.390610e-01 -6.826345e-02 9.879282e-01 1.895037e+02 2.236326e-02 9.971504e-01 7.204853e-02 -4.343871e+01 -9.900312e-01 3.211242e-02 -1.371381e-01 3.168468e+02 +-1.404952e-01 -6.622094e-02 9.878643e-01 1.906550e+02 2.296516e-02 9.972743e-01 7.011786e-02 -4.338584e+01 -9.898149e-01 3.253768e-02 -1.385914e-01 3.166745e+02 +-1.427993e-01 -6.827227e-02 9.873942e-01 1.918105e+02 2.275848e-02 9.971278e-01 7.223668e-02 -4.333407e+01 -9.894899e-01 3.278692e-02 -1.408353e-01 3.164986e+02 +-1.455334e-01 -7.302665e-02 9.866545e-01 1.929711e+02 2.333430e-02 9.967413e-01 7.721508e-02 -4.327987e+01 -9.890781e-01 3.426026e-02 -1.433551e-01 3.163191e+02 +-1.487068e-01 -7.924705e-02 9.857009e-01 1.941384e+02 2.411467e-02 9.961967e-01 8.372892e-02 -4.321953e+01 -9.885872e-01 3.622090e-02 -1.462302e-01 3.161375e+02 +-1.526002e-01 -8.540689e-02 9.845907e-01 1.953033e+02 2.527676e-02 9.955957e-01 9.027911e-02 -4.315280e+01 -9.879647e-01 3.866386e-02 -1.497692e-01 3.159563e+02 +-1.573797e-01 -9.012841e-02 9.834168e-01 1.964734e+02 2.730571e-02 9.950487e-01 9.556429e-02 -4.307134e+01 -9.871606e-01 4.189276e-02 -1.541394e-01 3.157666e+02 +-1.624061e-01 -9.294804e-02 9.823365e-01 1.976403e+02 2.892240e-02 9.946772e-01 9.889735e-02 -4.296330e+01 -9.863000e-01 4.447306e-02 -1.588534e-01 3.155727e+02 +-1.673173e-01 -9.409865e-02 9.814023e-01 1.988102e+02 2.999267e-02 9.944882e-01 1.004668e-01 -4.285777e+01 -9.854467e-01 4.624469e-02 -1.635728e-01 3.153705e+02 +-1.726316e-01 -9.413146e-02 9.804783e-01 1.999766e+02 3.267837e-02 9.943277e-01 1.012147e-01 -4.274528e+01 -9.844442e-01 4.951328e-02 -1.685763e-01 3.151627e+02 +-1.783870e-01 -9.477749e-02 9.793852e-01 2.011468e+02 3.363523e-02 9.941811e-01 1.023357e-01 -4.263770e+01 -9.833853e-01 5.119719e-02 -1.741611e-01 3.149464e+02 +-1.846217e-01 -9.796414e-02 9.779151e-01 2.023197e+02 3.255275e-02 9.938643e-01 1.057076e-01 -4.251577e+01 -9.822704e-01 5.134973e-02 -1.802999e-01 3.147277e+02 +-1.911922e-01 -1.034980e-01 9.760808e-01 2.035021e+02 3.122017e-02 9.932809e-01 1.114371e-01 -4.240747e+01 -9.810559e-01 5.177930e-02 -1.866763e-01 3.144993e+02 +-1.984621e-01 -1.070045e-01 9.742499e-01 2.046784e+02 3.052721e-02 9.928652e-01 1.152677e-01 -4.230052e+01 -9.796330e-01 5.261739e-02 -1.937796e-01 3.142653e+02 +-2.064388e-01 -1.077306e-01 9.725108e-01 2.058549e+02 3.072822e-02 9.927162e-01 1.164917e-01 -4.218974e+01 -9.779769e-01 5.393192e-02 -2.016247e-01 3.140186e+02 +-2.148690e-01 -1.095446e-01 9.704800e-01 2.070348e+02 2.921339e-02 9.925241e-01 1.185009e-01 -4.207716e+01 -9.762058e-01 5.381316e-02 -2.100625e-01 3.137609e+02 +-2.234243e-01 -1.137930e-01 9.680562e-01 2.082104e+02 2.877383e-02 9.919592e-01 1.232437e-01 -4.195644e+01 -9.742964e-01 5.539030e-02 -2.183536e-01 3.134913e+02 +-2.324153e-01 -1.146341e-01 9.658376e-01 2.093821e+02 2.955435e-02 9.917391e-01 1.248202e-01 -4.183493e+01 -9.721675e-01 5.755479e-02 -2.271073e-01 3.132100e+02 +-2.415825e-01 -1.154480e-01 9.634883e-01 2.105536e+02 2.929884e-02 9.915771e-01 1.261600e-01 -4.171473e+01 -9.699378e-01 5.870711e-02 -2.361651e-01 3.129230e+02 +-2.509588e-01 -1.150744e-01 9.611335e-01 2.117184e+02 2.974476e-02 9.915232e-01 1.264794e-01 -4.159416e+01 -9.675406e-01 6.032980e-02 -2.454086e-01 3.126202e+02 +-2.601730e-01 -1.121023e-01 9.590324e-01 2.128739e+02 2.754362e-02 9.919716e-01 1.234248e-01 -4.147765e+01 -9.651690e-01 5.852701e-02 -2.549965e-01 3.123135e+02 +-2.702696e-01 -1.057877e-01 9.569553e-01 2.140151e+02 2.934193e-02 9.925785e-01 1.180127e-01 -4.136396e+01 -9.623374e-01 5.997415e-02 -2.651598e-01 3.119900e+02 +-2.802952e-01 -1.013604e-01 9.545474e-01 2.151481e+02 2.987637e-02 9.930064e-01 1.142172e-01 -4.125440e+01 -9.594488e-01 6.053293e-02 -2.753067e-01 3.116602e+02 +-2.914919e-01 -1.011815e-01 9.512070e-01 2.162824e+02 3.149233e-02 9.928360e-01 1.152603e-01 -4.115052e+01 -9.560547e-01 6.355316e-02 -2.862172e-01 3.113158e+02 +-3.026705e-01 -1.035900e-01 9.474491e-01 2.174034e+02 3.087746e-02 9.924883e-01 1.183785e-01 -4.104650e+01 -9.525949e-01 6.508447e-02 -2.971983e-01 3.109605e+02 +-3.155431e-01 -1.033191e-01 9.432697e-01 2.185095e+02 2.985504e-02 9.924816e-01 1.186966e-01 -4.094070e+01 -9.484414e-01 6.561524e-02 -3.100861e-01 3.105933e+02 +-3.298194e-01 -1.020555e-01 9.385116e-01 2.196023e+02 2.935158e-02 9.925503e-01 1.182468e-01 -4.083233e+01 -9.435876e-01 6.654685e-02 -3.243668e-01 3.102118e+02 +-3.447573e-01 -1.010745e-01 9.332344e-01 2.206820e+02 2.694109e-02 9.927110e-01 1.174688e-01 -4.072771e+01 -9.383051e-01 6.564056e-02 -3.395213e-01 3.098151e+02 +-3.598615e-01 -1.008918e-01 9.275347e-01 2.217681e+02 2.561229e-02 9.926932e-01 1.179163e-01 -4.062208e+01 -9.326541e-01 6.618982e-02 -3.546480e-01 3.094011e+02 +-3.746452e-01 -9.895495e-02 9.218725e-01 2.228286e+02 2.580755e-02 9.927900e-01 1.170554e-01 -4.051468e+01 -9.268090e-01 6.764551e-02 -3.693902e-01 3.089695e+02 +-3.893409e-01 -9.786086e-02 9.158804e-01 2.238557e+02 2.460337e-02 9.928804e-01 1.165471e-01 -4.041093e+01 -9.207651e-01 6.791029e-02 -3.841612e-01 3.085359e+02 +-4.042867e-01 -9.855907e-02 9.093066e-01 2.248847e+02 2.148431e-02 9.928795e-01 1.171696e-01 -4.030750e+01 -9.143799e-01 6.690592e-02 -3.992904e-01 3.080855e+02 +-4.192497e-01 -9.931184e-02 9.024228e-01 2.258928e+02 1.797373e-02 9.928961e-01 1.176187e-01 -4.020641e+01 -9.076930e-01 6.553151e-02 -4.144864e-01 3.076185e+02 +-4.343836e-01 -9.917095e-02 8.952520e-01 2.268963e+02 1.516525e-02 9.929743e-01 1.173544e-01 -4.010589e+01 -9.006003e-01 6.455353e-02 -4.298278e-01 3.071407e+02 +-4.492223e-01 -9.830941e-02 8.879947e-01 2.278839e+02 1.308178e-02 9.930971e-01 1.165631e-01 -4.000630e+01 -8.933242e-01 6.397928e-02 -4.448353e-01 3.066456e+02 +-4.638446e-01 -9.673930e-02 8.806190e-01 2.288574e+02 1.230441e-02 9.932208e-01 1.155901e-01 -3.990822e+01 -8.858311e-01 6.445131e-02 -4.595097e-01 3.061326e+02 +-4.780866e-01 -9.476380e-02 8.731856e-01 2.298185e+02 1.304623e-02 9.932866e-01 1.149410e-01 -3.980854e+01 -8.782158e-01 6.634353e-02 -4.736407e-01 3.056050e+02 +-4.922198e-01 -9.217369e-02 8.655771e-01 2.307714e+02 1.376574e-02 9.934293e-01 1.136165e-01 -3.970910e+01 -8.703621e-01 6.783957e-02 -4.877166e-01 3.050612e+02 +-5.062757e-01 -8.870442e-02 8.577975e-01 2.317053e+02 1.553078e-02 9.935965e-01 1.119137e-01 -3.961775e+01 -8.622318e-01 6.998142e-02 -5.016561e-01 3.045100e+02 +-5.197307e-01 -8.506631e-02 8.500846e-01 2.326199e+02 1.770691e-02 9.937441e-01 1.102678e-01 -3.952931e+01 -8.541466e-01 7.236193e-02 -5.149731e-01 3.039494e+02 +-5.327994e-01 -8.255527e-02 8.422052e-01 2.335202e+02 1.906369e-02 9.938066e-01 1.094758e-01 -3.944018e+01 -8.460268e-01 7.438416e-02 -5.279257e-01 3.033730e+02 +-5.453755e-01 -8.097561e-02 8.342713e-01 2.344045e+02 1.938659e-02 9.938377e-01 1.091367e-01 -3.935649e+01 -8.379676e-01 7.569413e-02 -5.404449e-01 3.027950e+02 +-5.576821e-01 -7.819086e-02 8.263637e-01 2.352767e+02 1.883297e-02 9.941051e-01 1.067723e-01 -3.927819e+01 -8.298409e-01 7.510787e-02 -5.529220e-01 3.022127e+02 +-5.697988e-01 -7.434739e-02 8.184142e-01 2.361270e+02 1.852434e-02 9.944840e-01 1.032392e-01 -3.919904e+01 -8.215754e-01 7.398616e-02 -5.652786e-01 3.016181e+02 +-5.816418e-01 -7.146354e-02 8.102998e-01 2.369642e+02 1.673115e-02 9.948717e-01 9.975146e-02 -3.912250e+01 -8.132729e-01 7.157685e-02 -5.774633e-01 3.010224e+02 +-5.934756e-01 -6.699314e-02 8.020590e-01 2.377787e+02 1.659881e-02 9.952991e-01 9.541591e-02 -3.905310e+01 -8.046808e-01 6.994022e-02 -5.895737e-01 3.004161e+02 +-6.050968e-01 -6.156908e-02 7.937677e-01 2.385738e+02 1.923033e-02 9.955841e-01 9.188256e-02 -3.898243e+01 -7.959196e-01 7.086224e-02 -6.012407e-01 2.998073e+02 +-6.170213e-01 -6.182489e-02 7.845141e-01 2.393574e+02 1.885771e-02 9.954612e-01 9.328053e-02 -3.891533e+01 -7.867204e-01 7.235020e-02 -6.130549e-01 2.991916e+02 +-6.284532e-01 -6.555433e-02 7.750801e-01 2.401230e+02 1.656955e-02 9.950880e-01 9.759703e-02 -3.885000e+01 -7.776709e-01 7.417788e-02 -6.242801e-01 2.985732e+02 +-6.400213e-01 -6.623548e-02 7.654970e-01 2.408627e+02 1.461614e-02 9.950477e-01 9.831795e-02 -3.878528e+01 -7.682181e-01 7.411417e-02 -6.358835e-01 2.979579e+02 +-6.517461e-01 -6.148646e-02 7.559408e-01 2.415733e+02 1.317779e-02 9.956399e-01 9.234446e-02 -3.871917e+01 -7.583227e-01 7.014675e-02 -6.480942e-01 2.973480e+02 +-6.635329e-01 -5.902249e-02 7.458153e-01 2.422611e+02 1.041758e-02 9.960576e-01 8.809447e-02 -3.865762e+01 -7.480746e-01 6.622315e-02 -6.603021e-01 2.967405e+02 +-6.744863e-01 -6.115885e-02 7.357499e-01 2.429356e+02 5.976400e-03 9.960780e-01 8.827725e-02 -3.860033e+01 -7.382632e-01 6.393892e-02 -6.714754e-01 2.961342e+02 +-6.851333e-01 -6.328239e-02 7.256637e-01 2.435832e+02 4.210411e-03 9.958584e-01 9.082030e-02 -3.855149e+01 -7.284055e-01 6.527934e-02 -6.820292e-01 2.955313e+02 +-6.955929e-01 -6.204881e-02 7.157517e-01 2.441995e+02 4.508458e-03 9.958668e-01 9.071358e-02 -3.850165e+01 -7.184220e-01 6.632665e-02 -6.924381e-01 2.949278e+02 +-7.062876e-01 -6.031969e-02 7.053506e-01 2.447935e+02 3.943193e-03 9.960126e-01 8.912476e-02 -3.845039e+01 -7.079141e-01 6.572903e-02 -7.032334e-01 2.943368e+02 +-7.170632e-01 -5.992619e-02 6.944273e-01 2.453640e+02 2.138042e-03 9.961034e-01 8.816732e-02 -3.839951e+01 -6.970048e-01 6.470624e-02 -7.141409e-01 2.937453e+02 +-7.278749e-01 -5.951136e-02 6.831227e-01 2.459143e+02 5.658260e-04 9.961743e-01 8.738626e-02 -3.834988e+01 -6.857097e-01 6.399277e-02 -7.250565e-01 2.931637e+02 +-7.395348e-01 -5.867909e-02 6.705559e-01 2.464362e+02 1.894408e-03 9.960076e-01 8.924805e-02 -3.829872e+01 -6.731157e-01 6.727233e-02 -7.364710e-01 2.925841e+02 +-7.515933e-01 -5.593126e-02 6.572513e-01 2.469283e+02 5.779234e-03 9.958020e-01 9.135029e-02 -3.824858e+01 -6.596015e-01 7.245666e-02 -7.481148e-01 2.920034e+02 +-7.641861e-01 -5.239224e-02 6.428645e-01 2.473960e+02 1.089928e-02 9.955042e-01 9.408790e-02 -3.820375e+01 -6.449038e-01 7.890741e-02 -7.601794e-01 2.914320e+02 +-7.767234e-01 -4.827768e-02 6.279889e-01 2.478371e+02 1.558929e-02 9.952790e-01 9.579519e-02 -3.815982e+01 -6.296489e-01 8.419625e-02 -7.723038e-01 2.908725e+02 +-7.892667e-01 -4.330200e-02 6.125219e-01 2.482559e+02 1.804904e-02 9.954435e-01 9.362962e-02 -3.811868e+01 -6.137853e-01 8.495415e-02 -7.848887e-01 2.903133e+02 +-8.023166e-01 -3.569684e-02 5.958304e-01 2.486366e+02 2.162017e-02 9.958172e-01 8.877316e-02 -3.807932e+01 -5.965070e-01 8.410612e-02 -7.981889e-01 2.897809e+02 +-8.163343e-01 -2.626338e-02 5.769824e-01 2.489860e+02 2.644553e-02 9.962183e-01 8.276240e-02 -3.804160e+01 -5.769740e-01 8.282037e-02 -8.125525e-01 2.892398e+02 +-8.310368e-01 -1.751528e-02 5.559417e-01 2.493182e+02 3.090556e-02 9.965059e-01 7.759399e-02 -3.800127e+01 -5.553582e-01 8.166513e-02 -8.275917e-01 2.887123e+02 +-8.466177e-01 -1.281782e-02 5.320473e-01 2.496347e+02 3.276349e-02 9.965584e-01 7.614332e-02 -3.796205e+01 -5.311922e-01 8.189599e-02 -8.432839e-01 2.881897e+02 +-8.623777e-01 -7.365750e-03 5.062120e-01 2.499124e+02 3.686968e-02 9.963253e-01 7.730806e-02 -3.792588e+01 -5.049212e-01 8.533260e-02 -8.589370e-01 2.876536e+02 +-8.780631e-01 -7.251519e-04 4.785443e-01 2.501704e+02 4.171962e-02 9.960754e-01 7.805913e-02 -3.789307e+01 -4.767228e-01 8.850551e-02 -8.745868e-01 2.871376e+02 +-8.940811e-01 6.192965e-03 4.478623e-01 2.503893e+02 4.546597e-02 9.959944e-01 7.699264e-02 -3.786599e+01 -4.455915e-01 8.920014e-02 -8.907813e-01 2.866095e+02 +-9.103877e-01 1.192707e-02 4.135843e-01 2.505995e+02 4.657095e-02 9.961862e-01 7.378428e-02 -3.783317e+01 -4.111269e-01 8.643330e-02 -9.074711e-01 2.861073e+02 +-9.262720e-01 1.830692e-02 3.764108e-01 2.507893e+02 4.777551e-02 9.964649e-01 6.910246e-02 -3.780157e+01 -3.738151e-01 8.199088e-02 -9.238721e-01 2.856000e+02 +-9.413975e-01 2.562714e-02 3.363244e-01 2.509255e+02 5.009406e-02 9.966742e-01 6.427276e-02 -3.777223e+01 -3.335587e-01 7.735405e-02 -9.395503e-01 2.850610e+02 +-9.553537e-01 3.369912e-02 2.935368e-01 2.510583e+02 5.398284e-02 9.966601e-01 6.127384e-02 -3.774001e+01 -2.904915e-01 7.438412e-02 -9.539820e-01 2.845401e+02 +-9.675802e-01 3.998448e-02 2.493790e-01 2.511659e+02 5.625405e-02 9.967038e-01 5.845563e-02 -3.771289e+01 -2.462197e-01 7.058908e-02 -9.666400e-01 2.840197e+02 +-9.782400e-01 4.089160e-02 2.034073e-01 2.512315e+02 5.320868e-02 9.970423e-01 5.545617e-02 -3.769272e+01 -2.005380e-01 6.507247e-02 -9.775224e-01 2.834590e+02 +-9.873459e-01 4.029372e-02 1.533774e-01 2.513060e+02 4.906479e-02 9.973436e-01 5.383593e-02 -3.767245e+01 -1.508007e-01 6.068010e-02 -9.867000e-01 2.829253e+02 +-9.941401e-01 3.983166e-02 1.004938e-01 2.513141e+02 4.521376e-02 9.976303e-01 5.185906e-02 -3.764950e+01 -9.819006e-02 5.609886e-02 -9.935852e-01 2.823470e+02 +-9.980857e-01 4.236239e-02 4.506063e-02 2.513229e+02 4.464029e-02 9.977103e-01 5.080786e-02 -3.762635e+01 -4.280510e-02 5.272211e-02 -9.976913e-01 2.818086e+02 +-9.990693e-01 4.123316e-02 -1.267031e-02 2.513037e+02 4.050608e-02 9.977675e-01 5.309627e-02 -3.760705e+01 1.483135e-02 5.253362e-02 -9.985090e-01 2.812693e+02 +-9.966779e-01 3.932768e-02 -7.132060e-02 2.512086e+02 3.525553e-02 9.977237e-01 5.748361e-02 -3.758070e+01 7.341895e-02 5.477819e-02 -9.957956e-01 2.806859e+02 +-9.905802e-01 4.083089e-02 -1.307053e-01 2.511160e+02 3.309637e-02 9.976004e-01 6.081104e-02 -3.755538e+01 1.328746e-01 5.591233e-02 -9.895545e-01 2.801529e+02 +-9.806970e-01 4.191032e-02 -1.909896e-01 2.509393e+02 2.992683e-02 9.974231e-01 6.520344e-02 -3.752015e+01 1.932301e-01 5.822910e-02 -9.794240e-01 2.795660e+02 +-9.665624e-01 4.198459e-02 -2.529715e-01 2.507724e+02 2.492296e-02 9.972161e-01 7.027720e-02 -3.748851e+01 2.552178e-01 6.162248e-02 -9.649178e-01 2.790312e+02 +-9.481682e-01 4.280890e-02 -3.148724e-01 2.505694e+02 1.877367e-02 9.966998e-01 7.897499e-02 -3.745934e+01 3.172140e-01 6.897025e-02 -9.458426e-01 2.784912e+02 +-9.257387e-01 3.818528e-02 -3.762312e-01 2.502806e+02 6.473063e-03 9.963432e-01 8.519574e-02 -3.740607e+01 3.781086e-01 7.643361e-02 -9.226005e-01 2.778955e+02 +-8.990829e-01 3.660103e-02 -4.362458e-01 2.499999e+02 -2.751890e-03 9.960066e-01 8.923653e-02 -3.736150e+01 4.377699e-01 8.143152e-02 -8.953917e-01 2.773631e+02 +-8.694330e-01 3.593498e-02 -4.927424e-01 2.496317e+02 -1.162297e-02 9.955875e-01 9.311523e-02 -3.730655e+01 4.939142e-01 8.668457e-02 -8.651788e-01 2.767797e+02 +-8.372244e-01 3.777837e-02 -5.455531e-01 2.492687e+02 -1.804528e-02 9.951591e-01 9.660553e-02 -3.726082e+01 5.465617e-01 9.072515e-02 -8.324897e-01 2.762570e+02 +-8.033246e-01 3.814053e-02 -5.943189e-01 2.488626e+02 -2.363266e-02 9.951195e-01 9.580562e-02 -3.720878e+01 5.950723e-01 9.100833e-02 -7.985025e-01 2.757425e+02 +-7.695370e-01 3.412477e-02 -6.376899e-01 2.483907e+02 -3.186411e-02 9.952756e-01 9.171255e-02 -3.714195e+01 6.378068e-01 9.089560e-02 -7.648140e-01 2.751990e+02 +-7.374430e-01 3.168598e-02 -6.746658e-01 2.479135e+02 -3.831562e-02 9.953277e-01 8.862689e-02 -3.708194e+01 6.743217e-01 9.120750e-02 -7.327833e-01 2.746961e+02 +-7.074394e-01 3.446028e-02 -7.059334e-01 2.473914e+02 -3.882025e-02 9.954083e-01 8.749414e-02 -3.701735e+01 7.057071e-01 8.930130e-02 -7.028533e-01 2.741998e+02 +-6.795051e-01 3.920267e-02 -7.326227e-01 2.468170e+02 -3.762751e-02 9.953951e-01 8.816304e-02 -3.695794e+01 7.327052e-01 8.747399e-02 -6.749009e-01 2.736935e+02 +-6.547815e-01 4.228136e-02 -7.546347e-01 2.462257e+02 -3.798124e-02 9.953319e-01 8.872294e-02 -3.689801e+01 7.548633e-01 8.675609e-02 -6.501190e-01 2.732061e+02 +-6.344466e-01 4.470513e-02 -7.716729e-01 2.456041e+02 -3.720829e-02 9.954024e-01 8.825798e-02 -3.683564e+01 7.720706e-01 8.470759e-02 -6.298663e-01 2.727176e+02 +-6.191899e-01 4.905824e-02 -7.837074e-01 2.449546e+02 -2.989929e-02 9.958498e-01 8.596064e-02 -3.677493e+01 7.846719e-01 7.665825e-02 -6.151532e-01 2.722319e+02 +-6.093926e-01 5.471713e-02 -7.909784e-01 2.442874e+02 -2.173162e-02 9.960884e-01 8.564861e-02 -3.671138e+01 7.925707e-01 6.938286e-02 -6.058197e-01 2.717466e+02 +-6.041973e-01 5.782604e-02 -7.947338e-01 2.436067e+02 -1.600693e-02 9.962813e-01 8.466024e-02 -3.664658e+01 7.966740e-01 6.387272e-02 -6.010248e-01 2.712490e+02 +-6.022890e-01 6.095651e-02 -7.959475e-01 2.429094e+02 -1.292281e-02 9.962051e-01 8.607159e-02 -3.658241e+01 7.981735e-01 6.212584e-02 -5.992156e-01 2.707322e+02 +-6.021862e-01 6.263475e-02 -7.958949e-01 2.422014e+02 -1.070739e-02 9.961944e-01 8.649915e-02 -3.651890e+01 7.982839e-01 6.061054e-02 -5.992238e-01 2.702017e+02 +-6.040802e-01 6.468188e-02 -7.942943e-01 2.414832e+02 -7.448699e-03 9.961989e-01 8.678853e-02 -3.644894e+01 7.968887e-01 5.834369e-02 -6.013022e-01 2.696570e+02 +-6.074582e-01 6.702133e-02 -7.915192e-01 2.407521e+02 -4.669971e-03 9.961157e-01 8.792942e-02 -3.637609e+01 7.943379e-01 5.710982e-02 -6.047857e-01 2.690979e+02 +-6.122016e-01 7.012629e-02 -7.875859e-01 2.400101e+02 -2.438655e-03 9.958872e-01 9.056896e-02 -3.630161e+01 7.906979e-01 5.736711e-02 -6.095127e-01 2.685185e+02 +-6.175901e-01 7.225532e-02 -7.831741e-01 2.392559e+02 8.222797e-04 9.958298e-01 9.122643e-02 -3.622583e+01 7.864997e-01 5.569655e-02 -6.150740e-01 2.679313e+02 +-6.233538e-01 7.357791e-02 -7.784706e-01 2.384951e+02 3.508415e-03 9.958162e-01 9.131124e-02 -3.614684e+01 7.819321e-01 5.418800e-02 -6.210039e-01 2.673245e+02 +-6.291532e-01 7.567065e-02 -7.735892e-01 2.377242e+02 6.501802e-03 9.957274e-01 9.211183e-02 -3.606711e+01 7.772542e-01 5.292272e-02 -6.269570e-01 2.667011e+02 +-6.350736e-01 7.945914e-02 -7.683540e-01 2.369424e+02 9.377789e-03 9.954150e-01 9.518952e-02 -3.598622e+01 7.723947e-01 5.324688e-02 -6.329069e-01 2.660627e+02 +-6.410022e-01 8.112979e-02 -7.632393e-01 2.361565e+02 1.124696e-02 9.952840e-01 9.634969e-02 -3.590615e+01 7.674566e-01 5.317624e-02 -6.388916e-01 2.654104e+02 +-6.470861e-01 8.137344e-02 -7.580620e-01 2.353674e+02 1.350816e-02 9.953555e-01 9.531485e-02 -3.582458e+01 7.622972e-01 5.143689e-02 -6.451799e-01 2.647437e+02 +-6.534195e-01 8.226825e-02 -7.525125e-01 2.345734e+02 1.780987e-02 9.954726e-01 9.336522e-02 -3.573890e+01 7.567865e-01 4.760450e-02 -6.519263e-01 2.640609e+02 +-6.604073e-01 8.099582e-02 -7.465266e-01 2.337785e+02 1.690331e-02 9.955172e-01 9.305721e-02 -3.565438e+01 7.507173e-01 4.883689e-02 -6.588159e-01 2.633585e+02 +-6.672506e-01 7.975807e-02 -7.405507e-01 2.329872e+02 1.534864e-02 9.955114e-01 9.338820e-02 -3.557147e+01 7.446751e-01 5.094688e-02 -6.654797e-01 2.626401e+02 +-6.740329e-01 7.834312e-02 -7.345352e-01 2.321942e+02 1.438230e-02 9.955635e-01 9.298591e-02 -3.548874e+01 7.385613e-01 5.211126e-02 -6.721693e-01 2.619113e+02 +-6.805836e-01 7.616255e-02 -7.287011e-01 2.314089e+02 1.171551e-02 9.955864e-01 9.311505e-02 -3.540745e+01 7.325767e-01 5.483547e-02 -6.784720e-01 2.611680e+02 +-6.872311e-01 7.381889e-02 -7.226786e-01 2.306217e+02 8.694521e-03 9.955881e-01 9.342754e-02 -3.532646e+01 7.263868e-01 5.792296e-02 -6.848408e-01 2.604101e+02 +-6.936537e-01 7.499437e-02 -7.163941e-01 2.298286e+02 1.099787e-02 9.955521e-01 9.356875e-02 -3.524734e+01 7.202247e-01 5.702549e-02 -6.913931e-01 2.596435e+02 +-6.996975e-01 7.848426e-02 -7.101152e-01 2.290334e+02 1.438431e-02 9.952938e-01 9.582987e-02 -3.516634e+01 7.142944e-01 5.683740e-02 -6.975335e-01 2.588707e+02 +-7.057455e-01 8.108354e-02 -7.038103e-01 2.282396e+02 1.692868e-02 9.950754e-01 9.766399e-02 -3.508376e+01 7.082632e-01 5.701133e-02 -7.036426e-01 2.580817e+02 +-7.119183e-01 7.847857e-02 -6.978635e-01 2.274594e+02 1.805967e-02 9.954535e-01 9.352083e-02 -3.499945e+01 7.020300e-01 5.397600e-02 -7.100988e-01 2.572857e+02 +-7.174385e-01 7.799372e-02 -6.922421e-01 2.266778e+02 2.166833e-02 9.957303e-01 8.973023e-02 -3.491387e+01 6.962848e-01 4.937619e-02 -7.160652e-01 2.564797e+02 +-7.225982e-01 7.742835e-02 -6.869183e-01 2.258983e+02 2.135600e-02 9.957333e-01 8.977224e-02 -3.483448e+01 6.909383e-01 5.019943e-02 -7.211686e-01 2.556555e+02 +-7.276516e-01 7.950958e-02 -6.813233e-01 2.251177e+02 2.062462e-02 9.953464e-01 9.412866e-02 -3.475488e+01 6.856368e-01 5.444083e-02 -7.259052e-01 2.548183e+02 +-7.323628e-01 8.045363e-02 -6.761450e-01 2.243408e+02 2.128725e-02 9.952150e-01 9.536222e-02 -3.467447e+01 6.805818e-01 5.544646e-02 -7.305710e-01 2.539761e+02 +-7.364624e-01 8.202476e-02 -6.714872e-01 2.235626e+02 2.479546e-02 9.952278e-01 9.437619e-02 -3.458644e+01 6.760239e-01 5.285467e-02 -7.349816e-01 2.531292e+02 +-7.403968e-01 8.115300e-02 -6.672532e-01 2.227949e+02 2.277181e-02 9.951436e-01 9.576384e-02 -3.450313e+01 6.717842e-01 5.570867e-02 -7.386490e-01 2.522681e+02 +-7.442358e-01 7.919468e-02 -6.632054e-01 2.220315e+02 1.988364e-02 9.951326e-01 9.651778e-02 -3.442355e+01 6.676210e-01 5.864504e-02 -7.421879e-01 2.514046e+02 +-7.480457e-01 7.610823e-02 -6.592687e-01 2.212812e+02 1.612536e-02 9.951934e-01 9.659175e-02 -3.434865e+01 6.634513e-01 6.162409e-02 -7.456774e-01 2.505392e+02 +-7.516777e-01 7.337886e-02 -6.554359e-01 2.205399e+02 1.316978e-02 9.952632e-01 9.632043e-02 -3.427441e+01 6.593991e-01 6.376996e-02 -7.490835e-01 2.496841e+02 +-7.550209e-01 7.057319e-02 -6.518918e-01 2.198084e+02 9.508950e-03 9.952649e-01 9.673319e-02 -3.420947e+01 6.556318e-01 6.683676e-02 -7.521168e-01 2.488314e+02 +-7.585037e-01 6.993723e-02 -6.479050e-01 2.190863e+02 8.206736e-03 9.951708e-01 9.781474e-02 -3.414228e+01 6.516170e-01 6.887565e-02 -7.554147e-01 2.479881e+02 +-7.621654e-01 6.987471e-02 -6.436005e-01 2.183790e+02 7.091155e-03 9.949995e-01 9.962809e-02 -3.407002e+01 6.473436e-01 7.136920e-02 -7.588496e-01 2.471502e+02 +-7.658748e-01 7.413747e-02 -6.387015e-01 2.176823e+02 1.065352e-02 9.946573e-01 1.026804e-01 -3.399774e+01 6.429015e-01 7.183591e-02 -7.625727e-01 2.463218e+02 +-7.701252e-01 7.688049e-02 -6.332429e-01 2.169999e+02 1.267127e-02 9.943584e-01 1.053124e-01 -3.392299e+01 6.377669e-01 7.307971e-02 -7.667546e-01 2.455019e+02 +-7.745828e-01 7.911159e-02 -6.275054e-01 2.163319e+02 1.509575e-02 9.941761e-01 1.067050e-01 -3.384874e+01 6.322924e-01 7.317919e-02 -7.712659e-01 2.446886e+02 +-7.795618e-01 7.996331e-02 -6.211999e-01 2.156822e+02 1.664205e-02 9.941110e-01 1.070813e-01 -3.377237e+01 6.261041e-01 7.313847e-02 -7.763017e-01 2.438841e+02 +-7.840916e-01 8.205291e-02 -6.151973e-01 2.150569e+02 1.888693e-02 9.939177e-01 1.084933e-01 -3.369409e+01 6.203576e-01 7.344947e-02 -7.808722e-01 2.430892e+02 +-7.886737e-01 8.097657e-02 -6.094561e-01 2.144471e+02 1.700471e-02 9.937821e-01 1.100357e-01 -3.361758e+01 6.145768e-01 7.641862e-02 -7.851467e-01 2.422966e+02 +-7.928295e-01 7.791555e-02 -6.044424e-01 2.138628e+02 1.366010e-02 9.938166e-01 1.101903e-01 -3.354206e+01 6.092904e-01 7.910534e-02 -7.889914e-01 2.415165e+02 +-7.965788e-01 7.399894e-02 -5.999887e-01 2.132939e+02 1.045319e-02 9.940177e-01 1.087178e-01 -3.346134e+01 6.044444e-01 8.033052e-02 -7.925868e-01 2.407455e+02 +-7.993326e-01 7.032000e-02 -5.967601e-01 2.127389e+02 7.774152e-03 9.942559e-01 1.067463e-01 -3.338280e+01 6.008386e-01 8.068651e-02 -7.952877e-01 2.399863e+02 +-8.008920e-01 6.585233e-02 -5.951768e-01 2.121983e+02 3.544100e-03 9.944385e-01 1.052589e-01 -3.330906e+01 5.987983e-01 8.219165e-02 -7.966712e-01 2.392449e+02 +-8.012497e-01 6.247897e-02 -5.950591e-01 2.116726e+02 -9.060877e-04 9.944052e-01 1.056289e-01 -3.323394e+01 5.983294e-01 8.517427e-02 -7.967102e-01 2.385093e+02 +-8.003635e-01 6.147551e-02 -5.963549e-01 2.111551e+02 -2.767589e-03 9.943392e-01 1.062163e-01 -3.316424e+01 5.995087e-01 8.666208e-02 -7.956626e-01 2.378000e+02 +-7.978614e-01 5.853023e-02 -5.999930e-01 2.106457e+02 -6.161415e-03 9.944318e-01 1.052017e-01 -3.309995e+01 6.028095e-01 8.763318e-02 -7.930580e-01 2.371123e+02 +-7.929672e-01 5.389145e-02 -6.068762e-01 2.101466e+02 -1.145581e-02 9.945854e-01 1.032892e-01 -3.303479e+01 6.091566e-01 8.885718e-02 -7.880562e-01 2.364463e+02 +-7.853144e-01 5.221633e-02 -6.168913e-01 2.096455e+02 -1.514058e-02 9.945189e-01 1.034546e-01 -3.297092e+01 6.189120e-01 9.058448e-02 -7.802194e-01 2.358060e+02 +-7.753293e-01 5.203250e-02 -6.294101e-01 2.091496e+02 -1.868049e-02 9.942749e-01 1.052067e-01 -3.291263e+01 6.312808e-01 9.332750e-02 -7.699184e-01 2.351950e+02 +-7.633840e-01 5.220167e-02 -6.438322e-01 2.086497e+02 -2.174887e-02 9.940868e-01 1.063876e-01 -3.285735e+01 6.455787e-01 9.521719e-02 -7.577346e-01 2.346098e+02 +-7.486825e-01 5.309478e-02 -6.607992e-01 2.081538e+02 -2.287736e-02 9.941245e-01 1.057972e-01 -3.280360e+01 6.625339e-01 9.432584e-02 -7.430689e-01 2.340632e+02 +-7.310214e-01 5.302316e-02 -6.802914e-01 2.076452e+02 -2.487397e-02 9.942429e-01 1.042220e-01 -3.275344e+01 6.819010e-01 9.311004e-02 -7.254939e-01 2.335368e+02 +-7.093911e-01 5.276452e-02 -7.028373e-01 2.071416e+02 -2.691546e-02 9.944384e-01 1.018225e-01 -3.271018e+01 7.043009e-01 9.114917e-02 -7.040255e-01 2.330510e+02 +-6.852518e-01 4.715046e-02 -7.267784e-01 2.066426e+02 -3.354844e-02 9.947994e-01 9.617015e-02 -3.267160e+01 7.275331e-01 9.028304e-02 -6.801062e-01 2.325993e+02 +-6.574506e-01 4.373853e-02 -7.522272e-01 2.061160e+02 -3.708499e-02 9.952257e-01 9.028026e-02 -3.262857e+01 7.525845e-01 8.725113e-02 -6.526896e-01 2.321597e+02 +-6.257915e-01 4.058590e-02 -7.789338e-01 2.055996e+02 -4.104426e-02 9.955482e-01 8.484724e-02 -3.258472e+01 7.789097e-01 8.506743e-02 -6.213398e-01 2.317725e+02 +-5.893254e-01 4.039556e-02 -8.068852e-01 2.050507e+02 -4.485962e-02 9.955721e-01 8.260607e-02 -3.253572e+01 8.066493e-01 8.487841e-02 -5.849038e-01 2.313887e+02 +-5.485816e-01 3.783635e-02 -8.352405e-01 2.045209e+02 -5.757219e-02 9.948950e-01 8.288182e-02 -3.249607e+01 8.341125e-01 9.355405e-02 -5.436028e-01 2.310548e+02 +-5.045118e-01 3.809827e-02 -8.625639e-01 2.039495e+02 -6.577659e-02 9.944267e-01 8.239507e-02 -3.245216e+01 8.608956e-01 9.830578e-02 -4.991940e-01 2.307218e+02 +-4.586169e-01 3.898249e-02 -8.877787e-01 2.033860e+02 -7.194032e-02 9.941294e-01 8.081597e-02 -3.241036e+01 8.857173e-01 1.009306e-01 -4.531201e-01 2.304539e+02 +-4.112216e-01 4.249830e-02 -9.105442e-01 2.028028e+02 -7.751127e-02 9.936643e-01 8.138359e-02 -3.236715e+01 9.082339e-01 1.040441e-01 -4.053220e-01 2.302177e+02 +-3.620368e-01 4.656191e-02 -9.310002e-01 2.021762e+02 -8.284490e-02 9.931923e-01 8.188812e-02 -3.232072e+01 9.284751e-01 1.067751e-01 -3.557148e-01 2.299786e+02 +-3.101456e-01 4.841396e-02 -9.494556e-01 2.015688e+02 -8.975886e-02 9.927500e-01 7.994190e-02 -3.228250e+01 9.464423e-01 1.100157e-01 -3.035514e-01 2.298042e+02 +-2.567006e-01 5.012994e-02 -9.651901e-01 2.009188e+02 -9.628641e-02 9.923592e-01 7.714926e-02 -3.223724e+01 9.616827e-01 1.127389e-01 -2.499124e-01 2.296294e+02 +-2.012516e-01 5.260726e-02 -9.781259e-01 2.002886e+02 -9.830097e-02 9.924311e-01 7.360231e-02 -3.219845e+01 9.745946e-01 1.109633e-01 -1.945570e-01 2.295322e+02 +-1.451192e-01 5.742314e-02 -9.877465e-01 1.996526e+02 -1.023833e-01 9.920836e-01 7.271739e-02 -3.215678e+01 9.841026e-01 1.116814e-01 -1.380912e-01 2.294694e+02 +-8.832378e-02 6.182221e-02 -9.941715e-01 1.989753e+02 -1.005002e-01 9.924260e-01 7.064228e-02 -3.212082e+01 9.910088e-01 1.061539e-01 -8.144166e-02 2.294134e+02 +-3.109641e-02 6.520882e-02 -9.973870e-01 1.983304e+02 -9.981460e-02 9.926788e-01 6.801301e-02 -3.208499e+01 9.945200e-01 1.016687e-01 -2.435995e-02 2.294312e+02 +2.594687e-02 6.867085e-02 -9.973019e-01 1.976493e+02 -1.004786e-01 9.927647e-01 6.574428e-02 -3.205345e+01 9.946008e-01 9.850167e-02 3.265908e-02 2.294487e+02 +8.376288e-02 6.864517e-02 -9.941185e-01 1.970047e+02 -1.022053e-01 9.929550e-01 5.995317e-02 -3.202744e+01 9.912304e-01 9.658234e-02 9.018866e-02 2.295419e+02 +1.411765e-01 6.617667e-02 -9.877702e-01 1.963648e+02 -1.017064e-01 9.934534e-01 5.202111e-02 -3.200809e+01 9.847461e-01 9.311833e-02 1.469828e-01 2.296746e+02 +1.981225e-01 6.040004e-02 -9.783145e-01 1.956952e+02 -9.945967e-02 9.941867e-01 4.123799e-02 -3.198295e+01 9.751180e-01 8.913266e-02 2.029781e-01 2.298085e+02 +2.538642e-01 5.380154e-02 -9.657424e-01 1.950606e+02 -9.284659e-02 9.951966e-01 3.103590e-02 -3.196457e+01 9.627733e-01 8.178698e-02 2.576401e-01 2.300277e+02 +3.060522e-01 4.895868e-02 -9.507550e-01 1.943937e+02 -8.537993e-02 9.960640e-01 2.380768e-02 -3.195103e+01 9.481784e-01 7.388900e-02 3.090276e-01 2.302497e+02 +3.534471e-01 4.523152e-02 -9.343604e-01 1.937575e+02 -7.392672e-02 9.970570e-01 2.030183e-02 -3.194439e+01 9.325288e-01 6.189857e-02 3.557507e-01 2.305459e+02 +3.946541e-01 4.083221e-02 -9.179221e-01 1.931243e+02 -6.035189e-02 9.980067e-01 1.844677e-02 -3.194205e+01 9.168455e-01 4.811823e-02 3.963317e-01 2.308698e+02 +4.306055e-01 3.495192e-02 -9.018633e-01 1.924864e+02 -4.570583e-02 9.988122e-01 1.688640e-02 -3.193644e+01 9.013822e-01 3.394902e-02 4.316915e-01 2.312011e+02 +4.613883e-01 2.673002e-02 -8.867956e-01 1.918734e+02 -3.044686e-02 9.994343e-01 1.428410e-02 -3.192307e+01 8.866757e-01 2.040963e-02 4.619411e-01 2.315755e+02 +4.863755e-01 1.621544e-02 -8.735994e-01 1.912589e+02 -1.562333e-02 9.998293e-01 9.860207e-03 -3.190935e+01 8.736102e-01 8.852768e-03 4.865458e-01 2.319688e+02 +5.052553e-01 5.048852e-03 -8.629552e-01 1.906334e+02 -2.403707e-03 9.999872e-01 4.443225e-03 -3.190223e+01 8.629665e-01 -1.706673e-04 5.052610e-01 2.323684e+02 +5.178016e-01 -6.395816e-03 -8.554768e-01 1.900085e+02 1.031265e-02 9.999460e-01 -1.233886e-03 -3.189638e+01 8.554385e-01 -8.183323e-03 5.178396e-01 2.327869e+02 +5.247496e-01 -1.646208e-02 -8.510975e-01 1.893693e+02 2.050314e-02 9.997673e-01 -6.696346e-03 -3.189660e+01 8.510097e-01 -1.393625e-02 5.249650e-01 2.332119e+02 +5.285650e-01 -2.283178e-02 -8.485858e-01 1.887100e+02 2.602425e-02 9.996042e-01 -1.068511e-02 -3.189186e+01 8.484938e-01 -1.643603e-02 5.289500e-01 2.336426e+02 +5.291591e-01 -2.724993e-02 -8.480850e-01 1.880278e+02 2.819672e-02 9.994969e-01 -1.452174e-02 -3.189897e+01 8.480540e-01 -1.622890e-02 5.296612e-01 2.340756e+02 +5.270268e-01 -3.055275e-02 -8.492993e-01 1.873317e+02 2.830634e-02 9.994301e-01 -1.838827e-02 -3.191060e+01 8.493771e-01 -1.434944e-02 5.275913e-01 2.345103e+02 +5.227406e-01 -3.434924e-02 -8.517995e-01 1.866211e+02 2.925873e-02 9.993221e-01 -2.234239e-02 -3.192490e+01 8.519895e-01 -1.324329e-02 5.233912e-01 2.349484e+02 +5.158121e-01 -3.695498e-02 -8.559043e-01 1.858935e+02 3.033151e-02 9.992306e-01 -2.486398e-02 -3.194411e+01 8.561646e-01 -1.313573e-02 5.165361e-01 2.353903e+02 +5.072650e-01 -3.735267e-02 -8.609803e-01 1.851491e+02 3.106416e-02 9.992035e-01 -2.504722e-02 -3.196679e+01 8.612300e-01 -1.404005e-02 5.080213e-01 2.358307e+02 +4.974898e-01 -3.664188e-02 -8.666956e-01 1.843849e+02 3.154888e-02 9.992108e-01 -2.413502e-02 -3.199480e+01 8.668959e-01 -1.533635e-02 4.982532e-01 2.362697e+02 +4.869570e-01 -3.661239e-02 -8.726583e-01 1.836098e+02 3.182393e-02 9.992013e-01 -2.416325e-02 -3.202891e+01 8.728459e-01 -1.600494e-02 4.877332e-01 2.367058e+02 +4.753447e-01 -3.700603e-02 -8.790211e-01 1.828152e+02 3.168985e-02 9.991868e-01 -2.492812e-02 -3.206263e+01 8.792287e-01 -1.600659e-02 4.761308e-01 2.371397e+02 +4.629675e-01 -3.777119e-02 -8.855702e-01 1.820056e+02 3.315630e-02 9.991304e-01 -2.528095e-02 -3.209692e+01 8.857549e-01 -1.765796e-02 4.638172e-01 2.375759e+02 +4.496374e-01 -3.636467e-02 -8.924707e-01 1.811652e+02 3.315698e-02 9.991618e-01 -2.400704e-02 -3.212682e+01 8.925955e-01 -1.879716e-02 4.504662e-01 2.380051e+02 +4.362122e-01 -3.258017e-02 -8.992538e-01 1.802983e+02 3.131992e-02 9.992885e-01 -2.101171e-02 -3.215988e+01 8.992986e-01 -1.899898e-02 4.369223e-01 2.384233e+02 +4.223456e-01 -3.103716e-02 -9.059034e-01 1.794164e+02 3.422655e-02 9.992469e-01 -1.827828e-02 -3.219939e+01 9.057885e-01 -2.328619e-02 4.230898e-01 2.388406e+02 +4.079909e-01 -3.212393e-02 -9.124207e-01 1.785173e+02 3.805443e-02 9.991106e-01 -1.815994e-02 -3.224159e+01 9.121925e-01 -2.731255e-02 4.088505e-01 2.392540e+02 +3.933406e-01 -3.483567e-02 -9.187326e-01 1.775995e+02 3.830548e-02 9.990351e-01 -2.148063e-02 -3.229075e+01 9.185945e-01 -2.674328e-02 3.942955e-01 2.396502e+02 +3.784328e-01 -3.911570e-02 -9.248019e-01 1.766741e+02 3.840640e-02 9.989098e-01 -2.653414e-02 -3.233859e+01 9.248316e-01 -2.547692e-02 3.795225e-01 2.400344e+02 +3.632034e-01 -4.141969e-02 -9.307888e-01 1.757269e+02 3.794272e-02 9.988401e-01 -2.964231e-02 -3.239205e+01 9.309369e-01 -2.455047e-02 3.643537e-01 2.404070e+02 +3.494832e-01 -3.269253e-02 -9.363721e-01 1.747468e+02 3.092714e-02 9.992490e-01 -2.334485e-02 -3.243545e+01 9.364320e-01 -2.080067e-02 3.502318e-01 2.407619e+02 +3.360680e-01 -2.031241e-02 -9.416187e-01 1.737272e+02 2.277821e-02 9.996502e-01 -1.343461e-02 -3.247535e+01 9.415622e-01 -1.693344e-02 3.364131e-01 2.410980e+02 +3.233656e-01 -1.407435e-02 -9.461695e-01 1.727074e+02 1.666159e-02 9.998190e-01 -9.178081e-03 -3.250566e+01 9.461274e-01 -1.279681e-02 3.235416e-01 2.414212e+02 +3.106431e-01 -1.980662e-02 -9.503203e-01 1.716739e+02 1.689797e-02 9.997399e-01 -1.531298e-02 -3.252181e+01 9.503764e-01 -1.130161e-02 3.108970e-01 2.417336e+02 +2.981994e-01 -2.518881e-02 -9.541712e-01 1.706532e+02 2.093123e-02 9.995839e-01 -1.984617e-02 -3.254834e+01 9.542740e-01 -1.405385e-02 2.986026e-01 2.420498e+02 +2.854846e-01 -2.449153e-02 -9.580703e-01 1.696036e+02 2.778121e-02 9.994648e-01 -1.727150e-02 -3.258127e+01 9.579805e-01 -2.168560e-02 2.860122e-01 2.423576e+02 +2.731015e-01 -2.165281e-02 -9.617415e-01 1.685526e+02 3.211019e-02 9.993947e-01 -1.338235e-02 -3.261819e+01 9.614491e-01 -2.722696e-02 2.736315e-01 2.426576e+02 +2.610451e-01 -2.544999e-02 -9.649911e-01 1.674990e+02 3.414594e-02 9.992702e-01 -1.711704e-02 -3.265220e+01 9.647225e-01 -2.848220e-02 2.617236e-01 2.429380e+02 +2.505859e-01 -2.752202e-02 -9.677031e-01 1.664455e+02 3.452727e-02 9.992139e-01 -1.947740e-02 -3.268698e+01 9.674784e-01 -2.853138e-02 2.513392e-01 2.432090e+02 +2.420380e-01 -2.210803e-02 -9.700149e-01 1.653888e+02 2.899369e-02 9.994587e-01 -1.554460e-02 -3.272887e+01 9.698334e-01 -2.436191e-02 2.425480e-01 2.434680e+02 +2.350880e-01 -1.484903e-02 -9.718607e-01 1.643275e+02 2.336015e-02 9.996808e-01 -9.623391e-03 -3.276853e+01 9.716933e-01 -2.044046e-02 2.353598e-01 2.437202e+02 +2.293791e-01 -1.195482e-02 -9.732638e-01 1.632697e+02 2.236818e-02 9.997252e-01 -7.008108e-03 -3.280120e+01 9.730801e-01 -2.016262e-02 2.295834e-01 2.439752e+02 +2.247470e-01 -1.241834e-02 -9.743381e-01 1.621973e+02 2.383820e-02 9.996896e-01 -7.242790e-03 -3.282799e+01 9.741255e-01 -2.159866e-02 2.249732e-01 2.442249e+02 +2.206749e-01 -1.396965e-02 -9.752474e-01 1.611137e+02 2.572206e-02 9.996330e-01 -8.498672e-03 -3.285030e+01 9.750081e-01 -2.320992e-02 2.209532e-01 2.444687e+02 +2.161206e-01 -1.616092e-02 -9.762330e-01 1.600186e+02 2.911268e-02 9.995251e-01 -1.010148e-02 -3.286728e+01 9.759325e-01 -2.623761e-02 2.164884e-01 2.447101e+02 +2.113881e-01 -2.070276e-02 -9.771830e-01 1.589305e+02 3.237478e-02 9.993753e-01 -1.416949e-02 -3.288767e+01 9.768658e-01 -2.864081e-02 2.119262e-01 2.449462e+02 +2.068339e-01 -2.515078e-02 -9.780528e-01 1.578316e+02 3.540598e-02 9.992071e-01 -1.820727e-02 -3.290293e+01 9.777352e-01 -3.086303e-02 2.075604e-01 2.451737e+02 +2.027627e-01 -2.384333e-02 -9.789376e-01 1.567367e+02 3.516465e-02 9.992360e-01 -1.705423e-02 -3.292966e+01 9.785963e-01 -3.096602e-02 2.034462e-01 2.453974e+02 +1.988485e-01 -1.844916e-02 -9.798566e-01 1.556294e+02 3.493913e-02 9.993206e-01 -1.172522e-02 -3.295719e+01 9.794072e-01 -3.190378e-02 1.993580e-01 2.456163e+02 +1.949385e-01 -1.411557e-02 -9.807139e-01 1.545199e+02 3.427078e-02 9.993839e-01 -7.572216e-03 -3.297944e+01 9.802165e-01 -3.213370e-02 1.953021e-01 2.458290e+02 +1.912979e-01 -1.112755e-02 -9.814690e-01 1.534084e+02 3.251990e-02 9.994586e-01 -4.993056e-03 -3.300029e+01 9.809931e-01 -3.096210e-02 1.915562e-01 2.460361e+02 +1.876955e-01 -8.555429e-03 -9.821900e-01 1.522935e+02 2.979518e-02 9.995515e-01 -3.012826e-03 -3.301844e+01 9.817752e-01 -2.869903e-02 1.878662e-01 2.462357e+02 +1.845720e-01 -6.334339e-03 -9.827986e-01 1.511910e+02 2.615917e-02 9.996566e-01 -1.530232e-03 -3.304124e+01 9.824708e-01 -2.542675e-02 1.846744e-01 2.464348e+02 +1.815855e-01 -2.604813e-03 -9.833717e-01 1.500902e+02 2.290744e-02 9.997363e-01 1.581837e-03 -3.306866e+01 9.831083e-01 -2.281375e-02 1.815972e-01 2.466346e+02 +1.787037e-01 5.648776e-04 -9.839028e-01 1.489907e+02 2.191067e-02 9.997495e-01 4.553558e-03 -3.309563e+01 9.836589e-01 -2.237170e-02 1.786466e-01 2.468361e+02 +1.758028e-01 1.360079e-04 -9.844254e-01 1.478991e+02 2.211381e-02 9.997471e-01 4.087305e-03 -3.312266e+01 9.841770e-01 -2.248795e-02 1.757553e-01 2.470358e+02 +1.725515e-01 -4.170894e-03 -9.849917e-01 1.468063e+02 1.995369e-02 9.998006e-01 -7.380999e-04 -3.314537e+01 9.847983e-01 -1.952685e-02 1.726003e-01 2.472284e+02 +1.698284e-01 -8.445887e-03 -9.854375e-01 1.457083e+02 2.068662e-02 9.997735e-01 -5.003662e-03 -3.315880e+01 9.852565e-01 -1.953560e-02 1.699647e-01 2.474217e+02 +1.679863e-01 -8.402802e-03 -9.857535e-01 1.446084e+02 2.005477e-02 9.997858e-01 -5.104799e-03 -3.317843e+01 9.855853e-01 -1.891151e-02 1.681188e-01 2.476129e+02 +1.670351e-01 -4.822997e-03 -9.859392e-01 1.435050e+02 1.721397e-02 9.998499e-01 -1.974699e-03 -3.319916e+01 9.858006e-01 -1.664208e-02 1.670930e-01 2.478016e+02 +1.659730e-01 -3.724505e-03 -9.861233e-01 1.424066e+02 1.691287e-02 9.998565e-01 -9.297913e-04 -3.321988e+01 9.859852e-01 -1.652384e-02 1.660122e-01 2.479906e+02 +1.650599e-01 -4.534072e-03 -9.862732e-01 1.413072e+02 1.866810e-02 9.998246e-01 -1.472128e-03 -3.323481e+01 9.861068e-01 -1.816885e-02 1.651156e-01 2.481797e+02 +1.643794e-01 -4.894002e-03 -9.863851e-01 1.402093e+02 2.031502e-02 9.997924e-01 -1.575057e-03 -3.325023e+01 9.861879e-01 -1.977951e-02 1.644447e-01 2.483675e+02 +1.641613e-01 -5.674608e-03 -9.864172e-01 1.391141e+02 2.105932e-02 9.997757e-01 -2.246724e-03 -3.326812e+01 9.862086e-01 -2.040444e-02 1.642440e-01 2.485536e+02 +1.646615e-01 -6.264348e-03 -9.863303e-01 1.380219e+02 2.293607e-02 9.997337e-01 -2.520442e-03 -3.328502e+01 9.860834e-01 -2.220751e-02 1.647614e-01 2.487412e+02 +1.659384e-01 -5.867378e-03 -9.861187e-01 1.369351e+02 2.295670e-02 9.997343e-01 -2.085365e-03 -3.330383e+01 9.858688e-01 -2.229198e-02 1.660290e-01 2.489267e+02 +1.682636e-01 -4.658023e-03 -9.857311e-01 1.358528e+02 2.321519e-02 9.997302e-01 -7.613576e-04 -3.331909e+01 9.854686e-01 -2.275581e-02 1.683263e-01 2.491143e+02 +1.708704e-01 -3.293558e-03 -9.852880e-01 1.347750e+02 2.131373e-02 9.997728e-01 3.542905e-04 -3.333116e+01 9.850629e-01 -2.106069e-02 1.709017e-01 2.492989e+02 +1.743041e-01 -2.046620e-03 -9.846898e-01 1.337012e+02 2.003376e-02 9.997982e-01 1.468241e-03 -3.333817e+01 9.844880e-01 -1.998295e-02 1.743099e-01 2.494820e+02 +1.777569e-01 1.224949e-04 -9.840744e-01 1.326341e+02 1.784630e-02 9.998351e-01 3.348101e-03 -3.335015e+01 9.839125e-01 -1.815722e-02 1.777254e-01 2.496689e+02 +1.821331e-01 2.850264e-03 -9.832698e-01 1.315682e+02 1.501598e-02 9.998711e-01 5.679831e-03 -3.335955e+01 9.831592e-01 -1.579923e-02 1.820668e-01 2.498564e+02 +1.866905e-01 4.643254e-03 -9.824078e-01 1.305123e+02 1.340426e-02 9.998837e-01 7.273115e-03 -3.336209e+01 9.823273e-01 -1.452626e-02 1.866065e-01 2.500414e+02 +1.912524e-01 6.526555e-03 -9.815192e-01 1.294567e+02 1.257281e-02 9.998795e-01 9.098501e-03 -3.335105e+01 9.814603e-01 -1.408056e-02 1.911473e-01 2.502266e+02 +1.956725e-01 1.004532e-02 -9.806179e-01 1.284104e+02 1.137886e-02 9.998569e-01 1.251295e-02 -3.334557e+01 9.806032e-01 -1.360675e-02 1.955302e-01 2.504210e+02 +2.001598e-01 1.068436e-02 -9.797050e-01 1.273686e+02 1.369039e-02 9.998124e-01 1.370068e-02 -3.334343e+01 9.796676e-01 -1.615486e-02 1.999759e-01 2.506230e+02 +2.050181e-01 7.598969e-03 -9.787287e-01 1.263344e+02 1.680936e-02 9.997950e-01 1.128366e-02 -3.334204e+01 9.786138e-01 -1.876515e-02 2.048483e-01 2.508318e+02 +2.110741e-01 4.063879e-03 -9.774616e-01 1.253081e+02 1.807329e-02 9.998042e-01 8.059540e-03 -3.334191e+01 9.773029e-01 -1.936710e-02 2.109593e-01 2.510484e+02 +2.178037e-01 2.680516e-03 -9.759889e-01 1.242795e+02 2.069817e-02 9.997586e-01 7.364849e-03 -3.334192e+01 9.757730e-01 -2.180527e-02 2.176957e-01 2.512716e+02 +2.251397e-01 1.745107e-03 -9.743250e-01 1.232572e+02 2.350486e-02 9.996976e-01 7.221881e-03 -3.334480e+01 9.740429e-01 -2.452730e-02 2.250306e-01 2.515029e+02 +2.342045e-01 4.836892e-03 -9.721753e-01 1.222378e+02 2.565544e-02 9.996086e-01 1.115398e-02 -3.334581e+01 9.718487e-01 -2.755389e-02 2.339887e-01 2.517430e+02 +2.437271e-01 5.304769e-03 -9.698294e-01 1.212268e+02 2.835154e-02 9.995187e-01 1.259217e-02 -3.334926e+01 9.694293e-01 -3.056519e-02 2.434594e-01 2.519884e+02 +2.534444e-01 3.907713e-03 -9.673421e-01 1.202255e+02 3.132291e-02 9.994343e-01 1.224398e-02 -3.334801e+01 9.668427e-01 -3.340312e-02 2.531786e-01 2.522505e+02 +2.635366e-01 2.818770e-03 -9.646453e-01 1.192285e+02 3.308319e-02 9.993810e-01 1.195844e-02 -3.334424e+01 9.640819e-01 -3.506502e-02 2.632802e-01 2.525231e+02 +2.747798e-01 2.714402e-03 -9.615034e-01 1.182359e+02 3.364501e-02 9.993564e-01 1.243639e-02 -3.334059e+01 9.609183e-01 -3.576705e-02 2.745116e-01 2.527962e+02 +2.874346e-01 3.642434e-03 -9.577934e-01 1.172488e+02 3.351787e-02 9.993420e-01 1.385918e-02 -3.333589e+01 9.572136e-01 -3.608679e-02 2.871233e-01 2.530904e+02 +3.010854e-01 4.485430e-03 -9.535867e-01 1.162725e+02 3.066479e-02 9.994262e-01 1.438315e-02 -3.333201e+01 9.531040e-01 -3.357208e-02 3.007750e-01 2.533940e+02 +3.158363e-01 4.295594e-03 -9.488040e-01 1.152960e+02 2.904320e-02 9.994774e-01 1.419287e-02 -3.332309e+01 9.483690e-01 -3.203892e-02 3.155465e-01 2.537105e+02 +3.310450e-01 2.784386e-03 -9.436109e-01 1.143340e+02 2.877681e-02 9.995007e-01 1.304501e-02 -3.332087e+01 9.431760e-01 -3.147258e-02 3.307995e-01 2.540561e+02 +3.466682e-01 7.213559e-04 -9.379876e-01 1.133712e+02 2.322751e-02 9.996864e-01 9.353399e-03 -3.332071e+01 9.377002e-01 -2.502963e-02 3.465427e-01 2.544087e+02 +3.632375e-01 -5.027311e-03 -9.316831e-01 1.124109e+02 2.155468e-02 9.997631e-01 3.008908e-03 -3.331768e+01 9.314472e-01 -2.117507e-02 3.632598e-01 2.547936e+02 +3.808426e-01 -5.587755e-03 -9.246230e-01 1.114626e+02 1.966983e-02 9.998044e-01 2.059701e-03 -3.332362e+01 9.244306e-01 -1.897159e-02 3.808780e-01 2.552037e+02 +3.996770e-01 1.654111e-03 -9.166546e-01 1.105024e+02 1.664686e-02 9.998203e-01 9.062500e-03 -3.333115e+01 9.165048e-01 -1.888148e-02 3.995776e-01 2.556216e+02 +4.182608e-01 8.787528e-03 -9.082845e-01 1.095501e+02 1.668918e-02 9.997100e-01 1.735735e-02 -3.333322e+01 9.081736e-01 -2.241842e-02 4.179929e-01 2.560736e+02 +4.364633e-01 9.894673e-03 -8.996677e-01 1.086069e+02 2.061943e-02 9.995669e-01 2.099666e-02 -3.332646e+01 8.994857e-01 -2.771490e-02 4.360702e-01 2.565406e+02 +4.542667e-01 7.034499e-03 -8.908380e-01 1.076830e+02 2.488937e-02 9.994782e-01 2.058426e-02 -3.331673e+01 8.905180e-01 -3.152313e-02 4.538546e-01 2.570436e+02 +4.720871e-01 2.871999e-03 -8.815473e-01 1.067653e+02 2.901320e-02 9.994023e-01 1.879314e-02 -3.330709e+01 8.810743e-01 -3.444850e-02 4.717216e-01 2.575594e+02 +4.900454e-01 9.434963e-04 -8.716964e-01 1.058556e+02 3.160957e-02 9.993225e-01 1.885173e-02 -3.329527e+01 8.711236e-01 -3.679214e-02 4.896835e-01 2.580834e+02 +5.079449e-01 3.284211e-03 -8.613833e-01 1.049512e+02 3.233177e-02 9.992154e-01 2.287529e-02 -3.328522e+01 8.607825e-01 -3.946942e-02 5.074402e-01 2.586308e+02 +5.253216e-01 5.543755e-03 -8.508858e-01 1.040583e+02 3.337614e-02 9.990750e-01 2.711508e-02 -3.327387e+01 8.502489e-01 -4.264340e-02 5.246506e-01 2.591952e+02 +5.423605e-01 8.692702e-03 -8.401010e-01 1.031720e+02 3.312009e-02 9.989479e-01 3.171832e-02 -3.325679e+01 8.394928e-01 -4.502697e-02 5.415019e-01 2.597737e+02 +5.590272e-01 1.115388e-02 -8.290743e-01 1.023023e+02 3.249892e-02 9.988464e-01 3.535123e-02 -3.323865e+01 8.285121e-01 -4.670631e-02 5.580198e-01 2.603708e+02 +5.753758e-01 7.638426e-03 -8.178535e-01 1.014513e+02 3.448761e-02 9.988404e-01 3.359147e-02 -3.321958e+01 8.171617e-01 -4.753352e-02 5.744451e-01 2.609838e+02 +5.921089e-01 -1.562250e-03 -8.058565e-01 1.006161e+02 3.194537e-02 9.992576e-01 2.153491e-02 -3.320387e+01 8.052245e-01 -3.849439e-02 5.917191e-01 2.616091e+02 +6.082571e-01 -6.414684e-03 -7.937142e-01 9.978949e+01 3.329988e-02 9.992932e-01 1.744297e-02 -3.318844e+01 7.930413e-01 -3.704038e-02 6.080407e-01 2.622604e+02 +6.240740e-01 -1.260679e-03 -7.813643e-01 9.895890e+01 3.468905e-02 9.990574e-01 2.609416e-02 -3.317503e+01 7.805948e-01 -4.338946e-02 6.235294e-01 2.629300e+02 +6.392006e-01 5.456773e-03 -7.690207e-01 9.814497e+01 3.282537e-02 9.988699e-01 3.437177e-02 -3.315755e+01 7.683391e-01 -4.721384e-02 6.382991e-01 2.636220e+02 +6.538699e-01 4.864193e-03 -7.565914e-01 9.734396e+01 3.217270e-02 9.988961e-01 3.422664e-02 -3.314040e+01 7.559226e-01 -4.672135e-02 6.529916e-01 2.643294e+02 +6.677515e-01 -1.190620e-03 -7.443834e-01 9.656075e+01 3.113787e-02 9.991681e-01 2.633419e-02 -3.312374e+01 7.437327e-01 -4.076319e-02 6.672330e-01 2.650384e+02 +6.812054e-01 -1.323084e-03 -7.320912e-01 9.578101e+01 2.669882e-02 9.993780e-01 2.303692e-02 -3.311436e+01 7.316053e-01 -3.523884e-02 6.808170e-01 2.657700e+02 +6.940570e-01 2.392577e-03 -7.199161e-01 9.500346e+01 2.330706e-02 9.993956e-01 2.579128e-02 -3.310710e+01 7.195427e-01 -3.467973e-02 6.935817e-01 2.665268e+02 +7.068274e-01 7.820577e-03 -7.073429e-01 9.423329e+01 2.052181e-02 9.992913e-01 3.155530e-02 -3.309386e+01 7.070883e-01 -3.682010e-02 7.061659e-01 2.673024e+02 +7.194672e-01 1.192770e-02 -6.944241e-01 9.347254e+01 1.745932e-02 9.992259e-01 3.525206e-02 -3.307900e+01 6.943070e-01 -3.748686e-02 7.187019e-01 2.680890e+02 +7.317575e-01 1.311173e-02 -6.814390e-01 9.272549e+01 1.532767e-02 9.992455e-01 3.568622e-02 -3.305980e+01 6.813927e-01 -3.655852e-02 7.310044e-01 2.688736e+02 +7.437710e-01 1.121680e-02 -6.683404e-01 9.199266e+01 1.607710e-02 9.992697e-01 3.466241e-02 -3.303720e+01 6.682411e-01 -3.652586e-02 7.430475e-01 2.696825e+02 +7.555422e-01 1.051017e-02 -6.550158e-01 9.127349e+01 1.610560e-02 9.992710e-01 3.461134e-02 -3.301690e+01 6.549020e-01 -3.669974e-02 7.548221e-01 2.705090e+02 +7.670751e-01 8.522586e-03 -6.415008e-01 9.056458e+01 1.794694e-02 9.992354e-01 3.473530e-02 -3.299746e+01 6.413063e-01 -3.815754e-02 7.663356e-01 2.713522e+02 +7.783401e-01 6.166567e-03 -6.278127e-01 8.987216e+01 1.995953e-02 9.992033e-01 3.455960e-02 -3.297940e+01 6.275256e-01 -3.942996e-02 7.775968e-01 2.722153e+02 +7.895462e-01 3.653233e-03 -6.136803e-01 8.919168e+01 2.189976e-02 9.991776e-01 3.412379e-02 -3.295954e+01 6.133003e-01 -4.038175e-02 7.888168e-01 2.730963e+02 +8.003361e-01 2.191187e-03 -5.995476e-01 8.851989e+01 2.380468e-02 9.990886e-01 3.542826e-02 -3.293813e+01 5.990789e-01 -4.262654e-02 7.995545e-01 2.739892e+02 +8.108304e-01 -1.271411e-03 -5.852799e-01 8.786748e+01 2.649723e-02 9.990520e-01 3.453827e-02 -3.291994e+01 5.846811e-01 -4.351297e-02 8.100954e-01 2.749028e+02 +8.213320e-01 -6.800278e-03 -5.704100e-01 8.722827e+01 2.898035e-02 9.991351e-01 2.981731e-02 -3.290207e+01 5.697138e-01 -4.102057e-02 8.208187e-01 2.758275e+02 +8.315955e-01 -1.106314e-02 -5.552716e-01 8.660441e+01 3.074688e-02 9.991853e-01 2.614008e-02 -3.288580e+01 5.545300e-01 -3.881083e-02 8.312581e-01 2.767716e+02 +8.416495e-01 -1.222674e-02 -5.398858e-01 8.599060e+01 3.168584e-02 9.991393e-01 2.676890e-02 -3.287194e+01 5.390938e-01 -3.963675e-02 8.413125e-01 2.777350e+02 +8.514518e-01 -1.239353e-02 -5.242864e-01 8.539166e+01 3.348164e-02 9.989658e-01 3.076045e-02 -3.285801e+01 5.233629e-01 -4.374501e-02 8.509862e-01 2.787085e+02 +8.605819e-01 -1.147254e-02 -5.091830e-01 8.480830e+01 3.390791e-02 9.988188e-01 3.480386e-02 -3.284044e+01 5.081822e-01 -4.721689e-02 8.599543e-01 2.797008e+02 +8.692603e-01 -1.291976e-02 -4.941859e-01 8.424404e+01 3.429170e-02 9.988263e-01 3.420538e-02 -3.282354e+01 4.931639e-01 -4.667985e-02 8.686831e-01 2.807101e+02 +8.776453e-01 -1.851289e-02 -4.789531e-01 8.369527e+01 3.509180e-02 9.990539e-01 2.568681e-02 -3.280323e+01 4.780244e-01 -3.935123e-02 8.774646e-01 2.817138e+02 +8.856306e-01 -1.668085e-02 -4.640908e-01 8.315449e+01 3.085204e-02 9.992602e-01 2.295886e-02 -3.278853e+01 4.633645e-01 -3.465120e-02 8.854900e-01 2.827403e+02 +8.932722e-01 -9.868994e-03 -4.494079e-01 8.261910e+01 2.416210e-02 9.993678e-01 2.608003e-02 -3.277940e+01 4.488664e-01 -3.415520e-02 8.929458e-01 2.837770e+02 +9.006708e-01 3.476961e-04 -4.345021e-01 8.209467e+01 1.630595e-02 9.992682e-01 3.459991e-02 -3.276135e+01 4.341961e-01 -3.824809e-02 9.000060e-01 2.848344e+02 +9.076057e-01 1.693795e-02 -4.194819e-01 8.157233e+01 1.289274e-03 9.990686e-01 4.313018e-02 -3.273460e+01 4.198217e-01 -3.968601e-02 9.067385e-01 2.859039e+02 +9.142298e-01 2.001468e-02 -4.047015e-01 8.107969e+01 -2.676721e-03 9.990558e-01 4.336195e-02 -3.270630e+01 4.051872e-01 -3.855951e-02 9.134201e-01 2.869686e+02 +9.203108e-01 5.930360e-03 -3.911430e-01 8.062578e+01 3.778910e-03 9.997036e-01 2.404843e-02 -3.268885e+01 3.911697e-01 -2.361011e-02 9.200156e-01 2.880402e+02 +9.252448e-01 -1.401823e-02 -3.791115e-01 8.019704e+01 1.557974e-02 9.998781e-01 1.051279e-03 -3.268133e+01 3.790505e-01 -6.879144e-03 9.253503e-01 2.891224e+02 +9.297159e-01 -2.892638e-02 -3.671398e-01 7.978431e+01 3.058418e-02 9.995313e-01 -1.302574e-03 -3.268633e+01 3.670054e-01 -1.001764e-02 9.301648e-01 2.902333e+02 +9.342543e-01 -3.163156e-02 -3.552020e-01 7.937537e+01 3.894981e-02 9.991504e-01 1.346934e-02 -3.269566e+01 3.544741e-01 -2.641883e-02 9.346925e-01 2.913754e+02 +9.388596e-01 -2.738101e-02 -3.432098e-01 7.896809e+01 3.954465e-02 9.988115e-01 2.849105e-02 -3.269656e+01 3.420218e-01 -4.032120e-02 9.388265e-01 2.925165e+02 +9.433991e-01 -2.294606e-02 -3.308651e-01 7.856856e+01 3.657487e-02 9.987170e-01 3.502359e-02 -3.268227e+01 3.296369e-01 -4.514256e-02 9.430279e-01 2.936534e+02 +9.476254e-01 -1.895282e-02 -3.188211e-01 7.818276e+01 3.176878e-02 9.988806e-01 3.504565e-02 -3.266603e+01 3.178000e-01 -4.333869e-02 9.471667e-01 2.947903e+02 +9.516046e-01 -1.922604e-02 -3.067234e-01 7.781728e+01 3.076730e-02 9.989870e-01 3.283653e-02 -3.265395e+01 3.057813e-01 -4.068443e-02 9.512321e-01 2.959335e+02 +9.554499e-01 -1.988203e-02 -2.944832e-01 7.747147e+01 3.110164e-02 9.989558e-01 3.346468e-02 -3.264416e+01 2.935104e-01 -4.113272e-02 9.550705e-01 2.970910e+02 +9.592029e-01 -1.950905e-02 -2.820450e-01 7.713544e+01 3.134614e-02 9.988042e-01 3.751735e-02 -3.262785e+01 2.809757e-01 -4.482776e-02 9.586673e-01 2.982541e+02 +9.629342e-01 -1.934726e-02 -2.690419e-01 7.681324e+01 3.170715e-02 9.986281e-01 4.167075e-02 -3.260857e+01 2.678666e-01 -4.865673e-02 9.622265e-01 2.994210e+02 +9.665296e-01 -1.993785e-02 -2.557795e-01 7.650759e+01 3.247088e-02 9.984650e-01 4.486994e-02 -3.258084e+01 2.544923e-01 -5.167350e-02 9.656932e-01 3.005906e+02 +9.699802e-01 -2.141058e-02 -2.422395e-01 7.621526e+01 3.304873e-02 9.984811e-01 4.408260e-02 -3.255147e+01 2.409278e-01 -5.076494e-02 9.692144e-01 3.017618e+02 +9.732370e-01 -2.374685e-02 -2.285735e-01 7.594424e+01 3.404761e-02 9.985695e-01 4.122748e-02 -3.252254e+01 2.272674e-01 -4.790648e-02 9.726533e-01 3.029350e+02 +9.762924e-01 -2.457125e-02 -2.150567e-01 7.568435e+01 3.439105e-02 9.985239e-01 4.203884e-02 -3.249222e+01 2.137063e-01 -4.843822e-02 9.756963e-01 3.041185e+02 +9.792082e-01 -2.368722e-02 -2.014704e-01 7.543699e+01 3.320710e-02 9.984793e-01 4.400378e-02 -3.246419e+01 2.001217e-01 -4.977910e-02 9.785056e-01 3.053062e+02 +9.819990e-01 -2.366144e-02 -1.873982e-01 7.520729e+01 3.267032e-02 9.984467e-01 4.513133e-02 -3.243312e+01 1.860393e-01 -5.044127e-02 9.812466e-01 3.064961e+02 +9.845722e-01 -2.288683e-02 -1.734761e-01 7.499374e+01 3.099287e-02 9.985435e-01 4.416293e-02 -3.240139e+01 1.722127e-01 -4.885811e-02 9.838473e-01 3.076919e+02 +9.868951e-01 -2.326805e-02 -1.596767e-01 7.479507e+01 3.049040e-02 9.986127e-01 4.293085e-02 -3.236880e+01 1.584563e-01 -4.723684e-02 9.862354e-01 3.088857e+02 +9.889331e-01 -2.373603e-02 -1.464515e-01 7.461532e+01 3.026264e-02 9.986381e-01 4.249887e-02 -3.233698e+01 1.452433e-01 -4.646054e-02 9.883045e-01 3.100896e+02 +9.908071e-01 -2.302561e-02 -1.333086e-01 7.444854e+01 2.889089e-02 9.986900e-01 4.223172e-02 -3.230611e+01 1.321615e-01 -4.569488e-02 9.901743e-01 3.112977e+02 +9.925104e-01 -2.276430e-02 -1.200210e-01 7.429759e+01 2.801997e-02 9.987126e-01 4.228518e-02 -3.227489e+01 1.189039e-01 -4.533146e-02 9.918704e-01 3.125057e+02 +9.940183e-01 -2.165185e-02 -1.070466e-01 7.416166e+01 2.632565e-02 9.987520e-01 4.244267e-02 -3.224368e+01 1.059940e-01 -4.500685e-02 9.933476e-01 3.137206e+02 +9.952347e-01 -2.293165e-02 -9.477446e-02 7.404202e+01 2.700797e-02 9.987544e-01 4.195410e-02 -3.221264e+01 9.369433e-02 -4.431384e-02 9.946143e-01 3.149359e+02 +9.961530e-01 -2.520708e-02 -8.392812e-02 7.393962e+01 2.878322e-02 9.987165e-01 4.167569e-02 -3.218128e+01 8.276987e-02 -4.393108e-02 9.955999e-01 3.161541e+02 +9.968228e-01 -2.829147e-02 -7.445852e-02 7.385001e+01 3.139183e-02 9.986739e-01 4.080300e-02 -3.215088e+01 7.320540e-02 -4.301074e-02 9.963889e-01 3.173735e+02 +9.973333e-01 -3.163381e-02 -6.577050e-02 7.377159e+01 3.435601e-02 9.985814e-01 4.067859e-02 -3.212070e+01 6.439038e-02 -4.282971e-02 9.970052e-01 3.185948e+02 +9.977778e-01 -3.328149e-02 -5.772192e-02 7.371762e+01 3.566291e-02 9.985335e-01 4.072932e-02 -3.208526e+01 5.628174e-02 -4.269733e-02 9.975015e-01 3.198245e+02 +9.981200e-01 -3.596388e-02 -4.962968e-02 7.371580e+01 3.799337e-02 9.984539e-01 4.057365e-02 -3.205311e+01 4.809376e-02 -4.238296e-02 9.979432e-01 3.210462e+02 +9.984256e-01 -3.721879e-02 -4.196665e-02 7.371591e+01 3.891480e-02 9.984276e-01 4.034773e-02 -3.202698e+01 4.039896e-02 -4.191732e-02 9.983039e-01 3.222619e+02 +9.986535e-01 -3.892548e-02 -3.429431e-02 7.374032e+01 4.028794e-02 9.983881e-01 3.997612e-02 -3.200170e+01 3.268294e-02 -4.130393e-02 9.986119e-01 3.234741e+02 +9.988189e-01 -4.029456e-02 -2.715264e-02 7.375097e+01 4.135340e-02 9.983582e-01 3.963317e-02 -3.197569e+01 2.551106e-02 -4.070921e-02 9.988453e-01 3.246891e+02 +9.989977e-01 -3.986298e-02 -2.036272e-02 7.376942e+01 4.063967e-02 9.984018e-01 3.927062e-02 -3.195030e+01 1.876473e-02 -4.005878e-02 9.990211e-01 3.259077e+02 +9.990997e-01 -3.994237e-02 -1.430176e-02 7.377693e+01 4.047701e-02 9.984080e-01 3.928060e-02 -3.192415e+01 1.271003e-02 -3.982412e-02 9.991258e-01 3.271257e+02 +9.992014e-01 -3.895757e-02 -8.890904e-03 7.378378e+01 3.928288e-02 9.984295e-01 3.994148e-02 -3.189968e+01 7.320917e-03 -4.025883e-02 9.991624e-01 3.283466e+02 +9.992432e-01 -3.874007e-02 -3.519986e-03 7.381704e+01 3.885155e-02 9.984119e-01 4.079468e-02 -3.186569e+01 1.934007e-03 -4.090055e-02 9.991613e-01 3.295521e+02 +9.992603e-01 -3.843030e-02 1.452587e-03 7.387562e+01 3.834032e-02 9.984476e-01 4.040233e-02 -3.181425e+01 -3.003006e-03 -4.031674e-02 9.991824e-01 3.307608e+02 +9.992517e-01 -3.815370e-02 6.364873e-03 7.394362e+01 3.787223e-02 9.984954e-01 3.965669e-02 -3.176169e+01 -7.868345e-03 -3.938595e-02 9.991930e-01 3.319666e+02 +9.992444e-01 -3.737628e-02 1.066062e-02 7.400029e+01 3.693145e-02 9.985467e-01 3.924947e-02 -3.171745e+01 -1.211212e-02 -3.882610e-02 9.991725e-01 3.331735e+02 +9.992398e-01 -3.612391e-02 1.466314e-02 7.406242e+01 3.553253e-02 9.986164e-01 3.876462e-02 -3.169341e+01 -1.604318e-02 -3.821412e-02 9.991407e-01 3.343865e+02 +9.992331e-01 -3.453161e-02 1.846484e-02 7.411211e+01 3.380650e-02 9.986966e-01 3.823717e-02 -3.166869e+01 -1.976117e-02 -3.758361e-02 9.990980e-01 3.355975e+02 +9.992182e-01 -3.322045e-02 2.143315e-02 7.417250e+01 3.241874e-02 9.987993e-01 3.672668e-02 -3.164484e+01 -2.262749e-02 -3.600313e-02 9.990954e-01 3.368092e+02 +9.991993e-01 -3.222208e-02 2.371887e-02 7.422388e+01 3.138554e-02 9.989001e-01 3.483418e-02 -3.162065e+01 -2.481521e-02 -3.406185e-02 9.991115e-01 3.380199e+02 +9.991363e-01 -3.293814e-02 2.533503e-02 7.428610e+01 3.208201e-02 9.989241e-01 3.348753e-02 -3.159774e+01 -2.641079e-02 -3.264580e-02 9.991179e-01 3.392299e+02 +9.990190e-01 -3.548872e-02 2.649059e-02 7.434468e+01 3.459660e-02 9.988428e-01 3.340793e-02 -3.157463e+01 -2.764554e-02 -3.245867e-02 9.990906e-01 3.404422e+02 +9.987789e-01 -4.142060e-02 2.692677e-02 7.440549e+01 4.044831e-02 9.985435e-01 3.570290e-02 -3.154716e+01 -2.836639e-02 -3.457016e-02 9.989996e-01 3.416578e+02 +9.982862e-01 -5.237684e-02 2.610435e-02 7.445874e+01 5.140672e-02 9.980090e-01 3.654326e-02 -3.151174e+01 -2.796640e-02 -3.513869e-02 9.989910e-01 3.428783e+02 +9.976533e-01 -6.408220e-02 2.411419e-02 7.451443e+01 6.325132e-02 9.974260e-01 3.377175e-02 -3.147597e+01 -2.621629e-02 -3.216723e-02 9.991386e-01 3.440913e+02 +9.968033e-01 -7.687966e-02 2.174214e-02 7.457050e+01 7.617934e-02 9.965999e-01 3.138870e-02 -3.144179e+01 -2.408137e-02 -2.963205e-02 9.992707e-01 3.453052e+02 +9.963379e-01 -8.336510e-02 1.900438e-02 7.461953e+01 8.268172e-02 9.959861e-01 3.428457e-02 -3.140567e+01 -2.178623e-02 -3.258769e-02 9.992314e-01 3.465238e+02 +9.959902e-01 -8.779543e-02 1.718935e-02 7.466294e+01 8.716514e-02 9.955960e-01 3.450746e-02 -3.135378e+01 -2.014324e-02 -3.287077e-02 9.992565e-01 3.477467e+02 +9.962502e-01 -8.509403e-02 1.563862e-02 7.469240e+01 8.448313e-02 9.957644e-01 3.627427e-02 -3.131107e+01 -1.865910e-02 -3.481704e-02 9.992194e-01 3.489700e+02 +9.966584e-01 -8.030343e-02 1.494989e-02 7.471581e+01 7.970566e-02 9.961308e-01 3.701810e-02 -3.126742e+01 -1.786472e-02 -3.570280e-02 9.992027e-01 3.501885e+02 +9.971138e-01 -7.442187e-02 1.501815e-02 7.473607e+01 7.385109e-02 9.966361e-01 3.552997e-02 -3.123268e+01 -1.761184e-02 -3.431831e-02 9.992557e-01 3.514000e+02 +9.974569e-01 -6.960051e-02 1.534906e-02 7.474781e+01 6.908738e-02 9.971052e-01 3.175140e-02 -3.119085e+01 -1.751454e-02 -3.061022e-02 9.993779e-01 3.526040e+02 +9.976980e-01 -6.606021e-02 1.532503e-02 7.475759e+01 6.556808e-02 9.973771e-01 3.065587e-02 -3.115496e+01 -1.730997e-02 -2.958046e-02 9.994125e-01 3.538030e+02 +9.978270e-01 -6.411507e-02 1.518842e-02 7.476932e+01 6.360480e-02 9.974624e-01 3.198510e-02 -3.111941e+01 -1.720060e-02 -3.094953e-02 9.993729e-01 3.550007e+02 +9.979976e-01 -6.149193e-02 1.482248e-02 7.478390e+01 6.097551e-02 9.975908e-01 3.308375e-02 -3.108792e+01 -1.682115e-02 -3.211369e-02 9.993426e-01 3.561955e+02 +9.980723e-01 -6.041183e-02 1.422041e-02 7.480012e+01 5.991750e-02 9.976596e-01 3.294273e-02 -3.105504e+01 -1.617726e-02 -3.202717e-02 9.993560e-01 3.573900e+02 +9.983037e-01 -5.669412e-02 1.325077e-02 7.481447e+01 5.623663e-02 9.978829e-01 3.266653e-02 -3.102500e+01 -1.507471e-02 -3.186593e-02 9.993784e-01 3.585865e+02 +9.985494e-01 -5.256714e-02 1.165950e-02 7.480662e+01 5.216111e-02 9.981014e-01 3.275438e-02 -3.100320e+01 -1.335917e-02 -3.209868e-02 9.993954e-01 3.597808e+02 +9.988818e-01 -4.621671e-02 9.967035e-03 7.476995e+01 4.586083e-02 9.983898e-01 3.338547e-02 -3.099703e+01 -1.149395e-02 -3.289103e-02 9.993928e-01 3.609812e+02 +9.990870e-01 -4.188654e-02 8.415898e-03 7.474692e+01 4.159511e-02 9.986141e-01 3.224477e-02 -3.098688e+01 -9.754856e-03 -3.186527e-02 9.994445e-01 3.621780e+02 +9.991766e-01 -4.010586e-02 6.135367e-03 7.472073e+01 3.990908e-02 9.987708e-01 2.939497e-02 -3.097582e+01 -7.306736e-03 -2.912590e-02 9.995490e-01 3.633654e+02 +9.992429e-01 -3.877078e-02 3.259484e-03 7.470815e+01 3.866605e-02 9.988691e-01 2.766440e-02 -3.096059e+01 -4.328368e-03 -2.751741e-02 9.996119e-01 3.645514e+02 +9.991900e-01 -4.022192e-02 -1.235923e-03 7.468683e+01 4.024088e-02 9.987532e-01 2.954171e-02 -3.094761e+01 4.615773e-05 -2.956751e-02 9.995627e-01 3.657456e+02 +9.991506e-01 -4.064013e-02 -6.822447e-03 7.465868e+01 4.083083e-02 9.986963e-01 3.063353e-02 -3.093146e+01 5.568602e-03 -3.088607e-02 9.995073e-01 3.669440e+02 +9.990694e-01 -4.117445e-02 -1.285020e-02 7.460520e+01 4.153624e-02 9.987077e-01 2.928674e-02 -3.093605e+01 1.162773e-02 -2.979323e-02 9.994884e-01 3.681290e+02 +9.990082e-01 -4.015784e-02 -1.923583e-02 7.455574e+01 4.070079e-02 9.987585e-01 2.871909e-02 -3.093403e+01 1.805865e-02 -2.947352e-02 9.994024e-01 3.693170e+02 +9.988647e-01 -4.036901e-02 -2.529118e-02 7.449477e+01 4.113254e-02 9.986901e-01 3.043400e-02 -3.092270e+01 2.402946e-02 -3.143973e-02 9.992167e-01 3.705243e+02 +9.986372e-01 -4.154144e-02 -3.159392e-02 7.442845e+01 4.258362e-02 9.985457e-01 3.306188e-02 -3.091575e+01 3.017453e-02 -3.436219e-02 9.989538e-01 3.717321e+02 +9.983500e-01 -4.313574e-02 -3.790398e-02 7.436004e+01 4.448430e-02 9.983796e-01 3.548571e-02 -3.090434e+01 3.631186e-02 -3.711329e-02 9.986511e-01 3.729352e+02 +9.981175e-01 -4.243127e-02 -4.428460e-02 7.427897e+01 4.411410e-02 9.983133e-01 3.774099e-02 -3.089119e+01 4.260851e-02 -3.962351e-02 9.983058e-01 3.741414e+02 +9.978763e-01 -4.132605e-02 -5.035016e-02 7.419893e+01 4.316971e-02 9.984154e-01 3.609646e-02 -3.087490e+01 4.877865e-02 -3.819339e-02 9.980791e-01 3.753373e+02 +9.975269e-01 -4.270918e-02 -5.582204e-02 7.410945e+01 4.457741e-02 9.984718e-01 3.266183e-02 -3.085765e+01 5.434178e-02 -3.506944e-02 9.979063e-01 3.765339e+02 +9.972792e-01 -4.116621e-02 -6.115216e-02 7.402082e+01 4.311895e-02 9.985900e-01 3.096323e-02 -3.084199e+01 5.979129e-02 -3.351580e-02 9.976480e-01 3.777288e+02 +9.968782e-01 -4.243357e-02 -6.658257e-02 7.392128e+01 4.455810e-02 9.985333e-01 3.075372e-02 -3.084133e+01 6.517992e-02 -3.362450e-02 9.973068e-01 3.789305e+02 +9.963622e-01 -4.693607e-02 -7.112985e-02 7.382833e+01 4.957105e-02 9.981308e-01 3.574272e-02 -3.083649e+01 6.931927e-02 -3.913866e-02 9.968264e-01 3.801331e+02 +9.961485e-01 -4.450335e-02 -7.554877e-02 7.371659e+01 4.722878e-02 9.982819e-01 3.467944e-02 -3.083904e+01 7.387561e-02 -3.811394e-02 9.965388e-01 3.813320e+02 +9.959098e-01 -4.249079e-02 -7.973926e-02 7.360415e+01 4.500218e-02 9.985373e-01 2.996604e-02 -3.083267e+01 7.834934e-02 -3.343190e-02 9.963652e-01 3.825222e+02 +9.956835e-01 -3.912241e-02 -8.416634e-02 7.347645e+01 4.169767e-02 9.987076e-01 2.905951e-02 -3.083572e+01 8.292068e-02 -3.244361e-02 9.960278e-01 3.837166e+02 +9.956946e-01 -2.700210e-02 -8.867515e-02 7.333304e+01 2.982186e-02 9.990858e-01 3.062917e-02 -3.084221e+01 8.776702e-02 -3.314175e-02 9.955895e-01 3.849087e+02 +9.952845e-01 -2.637192e-02 -9.334502e-02 7.319698e+01 2.968207e-02 9.989723e-01 3.425232e-02 -3.083989e+01 9.234579e-02 -3.686147e-02 9.950444e-01 3.861010e+02 +9.944693e-01 -3.177664e-02 -1.001053e-01 7.306226e+01 3.604693e-02 9.985028e-01 4.114163e-02 -3.083562e+01 9.864806e-02 -4.452257e-02 9.941258e-01 3.872954e+02 +9.935780e-01 -3.559036e-02 -1.074069e-01 7.292248e+01 4.064434e-02 9.981491e-01 4.523768e-02 -3.082591e+01 1.055980e-01 -4.931263e-02 9.931854e-01 3.884844e+02 +9.923207e-01 -4.412173e-02 -1.155547e-01 7.278245e+01 4.906811e-02 9.979814e-01 4.031537e-02 -3.080462e+01 1.135427e-01 -4.567582e-02 9.924826e-01 3.896637e+02 +9.914930e-01 -4.533260e-02 -1.220106e-01 7.263564e+01 4.960931e-02 9.982481e-01 3.224387e-02 -3.078156e+01 1.203351e-01 -3.802243e-02 9.920049e-01 3.908392e+02 +9.910355e-01 -4.097222e-02 -1.271610e-01 7.247129e+01 4.464574e-02 9.986599e-01 2.617303e-02 -3.075931e+01 1.259182e-01 -3.161559e-02 9.915367e-01 3.920067e+02 +9.906378e-01 -3.466188e-02 -1.320429e-01 7.229969e+01 3.834028e-02 9.989414e-01 2.541705e-02 -3.074275e+01 1.310221e-01 -3.024164e-02 9.909180e-01 3.931832e+02 +9.900504e-01 -3.212188e-02 -1.369983e-01 7.212369e+01 3.633712e-02 9.989365e-01 2.837884e-02 -3.072456e+01 1.359410e-01 -3.307460e-02 9.901646e-01 3.943657e+02 +9.892631e-01 -3.293408e-02 -1.423865e-01 7.195058e+01 3.797841e-02 9.987383e-01 3.285496e-02 -3.070358e+01 1.411248e-01 -3.790981e-02 9.892656e-01 3.955495e+02 +9.883738e-01 -3.469193e-02 -1.480333e-01 7.177257e+01 4.048915e-02 9.985193e-01 3.632865e-02 -3.067844e+01 1.465538e-01 -4.190002e-02 9.883149e-01 3.967346e+02 +9.876167e-01 -3.276725e-02 -1.534266e-01 7.158557e+01 3.901605e-02 9.985197e-01 3.789530e-02 -3.065329e+01 1.519578e-01 -4.341212e-02 9.874331e-01 3.979105e+02 +9.868301e-01 -3.118630e-02 -1.587257e-01 7.139021e+01 3.748022e-02 9.986190e-01 3.681429e-02 -3.062796e+01 1.573584e-01 -4.227852e-02 9.866361e-01 3.990885e+02 +9.860593e-01 -2.973840e-02 -1.637157e-01 7.118796e+01 3.570975e-02 9.987954e-01 3.365192e-02 -3.060330e+01 1.625177e-01 -3.902903e-02 9.859334e-01 4.002612e+02 +9.852550e-01 -2.743238e-02 -1.688789e-01 7.097640e+01 3.347228e-02 9.988939e-01 3.302183e-02 -3.059615e+01 1.677863e-01 -3.818768e-02 9.850834e-01 4.014350e+02 +9.842648e-01 -2.659543e-02 -1.746872e-01 7.076022e+01 3.342669e-02 9.987824e-01 3.628008e-02 -3.058868e+01 1.735096e-01 -4.154841e-02 9.839553e-01 4.026112e+02 +9.832768e-01 -2.580847e-02 -1.802797e-01 7.054006e+01 3.357250e-02 9.986295e-01 4.014853e-02 -3.057455e+01 1.789965e-01 -4.552955e-02 9.827956e-01 4.037890e+02 +9.824505e-01 -2.379070e-02 -1.850005e-01 7.031185e+01 3.161111e-02 9.987219e-01 3.943801e-02 -3.056122e+01 1.838258e-01 -4.459396e-02 9.819467e-01 4.049597e+02 +9.817446e-01 -2.279430e-02 -1.888332e-01 7.007912e+01 3.015654e-02 9.988892e-01 3.620676e-02 -3.054205e+01 1.877981e-01 -4.124034e-02 9.813414e-01 4.061284e+02 +9.812784e-01 -2.116690e-02 -1.914281e-01 6.983762e+01 2.799167e-02 9.990627e-01 3.301790e-02 -3.052825e+01 1.905498e-01 -3.775813e-02 9.809511e-01 4.072854e+02 +9.808481e-01 -2.352674e-02 -1.933485e-01 6.960267e+01 3.012557e-02 9.990572e-01 3.125983e-02 -3.051387e+01 1.924308e-01 -3.648587e-02 9.806320e-01 4.084499e+02 +9.802877e-01 -2.763201e-02 -1.956338e-01 6.935747e+01 3.408845e-02 9.989770e-01 2.971231e-02 -3.049731e+01 1.946126e-01 -3.579546e-02 9.802268e-01 4.096121e+02 +9.795853e-01 -3.718708e-02 -1.975598e-01 6.912183e+01 4.383594e-02 9.986064e-01 2.938746e-02 -3.047855e+01 1.961916e-01 -3.744773e-02 9.798502e-01 4.107783e+02 +9.789412e-01 -4.235606e-02 -1.997004e-01 6.887914e+01 4.920201e-02 9.983548e-01 2.944154e-02 -3.046350e+01 1.981248e-01 -3.864719e-02 9.794145e-01 4.119482e+02 +9.787175e-01 -4.430550e-02 -2.003728e-01 6.863377e+01 5.094172e-02 9.983067e-01 2.808295e-02 -3.044778e+01 1.987893e-01 -3.769260e-02 9.793171e-01 4.131152e+02 +9.787142e-01 -4.288364e-02 -2.006980e-01 6.838450e+01 4.893750e-02 9.984814e-01 2.529822e-02 -3.043396e+01 1.993083e-01 -3.458137e-02 9.793264e-01 4.142791e+02 +9.791010e-01 -3.987394e-02 -1.994277e-01 6.813949e+01 4.652061e-02 9.985034e-01 2.875280e-02 -3.040852e+01 1.979827e-01 -3.742938e-02 9.794906e-01 4.154528e+02 +9.794816e-01 -3.538028e-02 -1.984037e-01 6.789875e+01 4.285343e-02 9.985196e-01 3.349855e-02 -3.037682e+01 1.969248e-01 -4.131349e-02 9.795477e-01 4.166292e+02 +9.795757e-01 -3.473856e-02 -1.980523e-01 6.766435e+01 4.236925e-02 9.985089e-01 3.442078e-02 -3.033950e+01 1.965613e-01 -4.210908e-02 9.795868e-01 4.178065e+02 +9.795860e-01 -3.637801e-02 -1.977068e-01 6.743258e+01 4.413757e-02 9.984128e-01 3.498249e-02 -3.030533e+01 1.961204e-01 -4.299464e-02 9.796367e-01 4.189811e+02 +9.797915e-01 -3.601706e-02 -1.967521e-01 6.719991e+01 4.441802e-02 9.982727e-01 3.845216e-02 -3.026813e+01 1.950273e-01 -4.641442e-02 9.796989e-01 4.201607e+02 +9.799978e-01 -3.499141e-02 -1.959080e-01 6.696538e+01 4.355903e-02 9.982659e-01 3.959522e-02 -3.023636e+01 1.941827e-01 -4.733678e-02 9.798225e-01 4.213359e+02 +9.801288e-01 -3.627232e-02 -1.950180e-01 6.673559e+01 4.335118e-02 9.985424e-01 3.215234e-02 -3.020369e+01 1.935674e-01 -3.996768e-02 9.802725e-01 4.225018e+02 +9.801546e-01 -3.938984e-02 -1.942819e-01 6.650714e+01 4.520366e-02 9.986502e-01 2.558084e-02 -3.017745e+01 1.930121e-01 -3.385543e-02 9.806121e-01 4.236708e+02 +9.801939e-01 -4.218085e-02 -1.934963e-01 6.626655e+01 4.848042e-02 9.984334e-01 2.793563e-02 -3.017356e+01 1.920148e-01 -3.676311e-02 9.807032e-01 4.248280e+02 +9.803336e-01 -4.269041e-02 -1.926752e-01 6.603179e+01 5.053853e-02 9.980730e-01 3.600080e-02 -3.017423e+01 1.907670e-01 -4.503031e-02 9.806019e-01 4.259911e+02 +9.805985e-01 -4.264834e-02 -1.913317e-01 6.579979e+01 5.119211e-02 9.978901e-01 3.993349e-02 -3.016547e+01 1.892249e-01 -4.895338e-02 9.807127e-01 4.271502e+02 +9.812252e-01 -4.079743e-02 -1.885013e-01 6.556635e+01 4.898053e-02 9.980397e-01 3.895713e-02 -3.015534e+01 1.865425e-01 -4.745860e-02 9.812999e-01 4.283048e+02 +9.821716e-01 -3.814074e-02 -1.840768e-01 6.533770e+01 4.410708e-02 9.986223e-01 2.842578e-02 -3.014835e+01 1.827390e-01 -3.603807e-02 9.825007e-01 4.294576e+02 +9.832754e-01 -3.441574e-02 -1.788440e-01 6.510785e+01 3.760793e-02 9.991875e-01 1.448842e-02 -3.014716e+01 1.782001e-01 -2.097205e-02 9.837707e-01 4.306061e+02 +9.842991e-01 -3.083988e-02 -1.737938e-01 6.488798e+01 3.402873e-02 9.993022e-01 1.539804e-02 -3.014778e+01 1.731977e-01 -2.107025e-02 9.846616e-01 4.317794e+02 +9.850587e-01 -3.121799e-02 -1.693663e-01 6.467815e+01 3.629745e-02 9.989768e-01 2.697742e-02 -3.015039e+01 1.683508e-01 -3.272189e-02 9.851838e-01 4.329715e+02 +9.857052e-01 -3.447514e-02 -1.649148e-01 6.447677e+01 4.086913e-02 9.985324e-01 3.553574e-02 -3.014403e+01 1.634476e-01 -4.176768e-02 9.856674e-01 4.341748e+02 +9.862814e-01 -3.936503e-02 -1.603106e-01 6.428274e+01 4.568649e-02 9.983091e-01 3.593809e-02 -3.013209e+01 1.586248e-01 -4.276909e-02 9.864121e-01 4.353733e+02 +9.869810e-01 -4.029749e-02 -1.557069e-01 6.409235e+01 4.581743e-02 9.984363e-01 3.202462e-02 -3.011582e+01 1.541729e-01 -3.874178e-02 9.872840e-01 4.365647e+02 +9.880026e-01 -3.865128e-02 -1.495228e-01 6.390223e+01 4.335623e-02 9.986578e-01 2.833456e-02 -3.010784e+01 1.482269e-01 -3.447736e-02 9.883522e-01 4.377586e+02 +9.892472e-01 -3.284436e-02 -1.425180e-01 6.371616e+01 3.714038e-02 9.989291e-01 2.758824e-02 -3.010404e+01 1.414592e-01 -3.258475e-02 9.894076e-01 4.389547e+02 +9.904658e-01 -3.155033e-02 -1.340978e-01 6.353882e+01 3.591107e-02 9.988978e-01 3.022513e-02 -3.010486e+01 1.329964e-01 -3.475255e-02 9.905070e-01 4.401657e+02 +9.915276e-01 -3.103383e-02 -1.261352e-01 6.337809e+01 3.571778e-02 9.987473e-01 3.504336e-02 -3.009689e+01 1.248897e-01 -3.925172e-02 9.913938e-01 4.413753e+02 +9.924736e-01 -3.155350e-02 -1.183246e-01 6.322958e+01 3.605171e-02 9.986988e-01 3.606959e-02 -3.008479e+01 1.170325e-01 -4.006390e-02 9.923196e-01 4.425806e+02 +9.933160e-01 -3.169518e-02 -1.109906e-01 6.308949e+01 3.566140e-02 9.987876e-01 3.393331e-02 -3.006970e+01 1.097805e-01 -3.766457e-02 9.932419e-01 4.437802e+02 +9.943511e-01 -2.623739e-02 -1.028469e-01 6.294899e+01 2.987576e-02 9.989753e-01 3.399706e-02 -3.006024e+01 1.018495e-01 -3.687764e-02 9.941160e-01 4.449870e+02 +9.953407e-01 -2.082018e-02 -9.414662e-02 6.281227e+01 2.426838e-02 9.990703e-01 3.563030e-02 -3.005780e+01 9.331725e-02 -3.774906e-02 9.949205e-01 4.461993e+02 +9.962083e-01 -1.444417e-02 -8.579346e-02 6.268770e+01 1.751829e-02 9.992272e-01 3.518753e-02 -3.004824e+01 8.521890e-02 -3.655705e-02 9.956913e-01 4.474056e+02 +9.968757e-01 -1.210000e-02 -7.805513e-02 6.257795e+01 1.480256e-02 9.993075e-01 3.413854e-02 -3.004032e+01 7.758799e-02 -3.518729e-02 9.963643e-01 4.486106e+02 +9.974248e-01 -1.037311e-02 -7.096651e-02 6.248171e+01 1.288322e-02 9.993041e-01 3.500451e-02 -3.002578e+01 7.055401e-02 -3.582863e-02 9.968642e-01 4.498148e+02 +9.979153e-01 -1.051342e-02 -6.367623e-02 6.239543e+01 1.274730e-02 9.993137e-01 3.477779e-02 -3.001580e+01 6.326689e-02 -3.551698e-02 9.973644e-01 4.510169e+02 +9.983180e-01 -8.269211e-03 -5.738439e-02 6.231589e+01 1.015780e-02 9.994136e-01 3.269793e-02 -3.000241e+01 5.708035e-02 -3.322582e-02 9.978165e-01 4.522126e+02 +9.986195e-01 -7.834385e-03 -5.194077e-02 6.224401e+01 9.518163e-03 9.994345e-01 3.224956e-02 -2.998907e+01 5.165874e-02 -3.269941e-02 9.981293e-01 4.534067e+02 +9.988397e-01 -6.836786e-03 -4.767104e-02 6.217991e+01 8.446138e-03 9.993983e-01 3.364024e-02 -2.997533e+01 4.741236e-02 -3.400383e-02 9.982964e-01 4.546003e+02 +9.990253e-01 -6.802692e-03 -4.361463e-02 6.212198e+01 8.331347e-03 9.993538e-01 3.496371e-02 -2.995908e+01 4.334860e-02 -3.529299e-02 9.984364e-01 4.557931e+02 +9.991865e-01 -5.380931e-03 -3.996766e-02 6.206608e+01 6.822454e-03 9.993278e-01 3.601885e-02 -2.994150e+01 3.974697e-02 -3.626222e-02 9.985515e-01 4.569925e+02 +9.993114e-01 -5.252536e-03 -3.673267e-02 6.201606e+01 6.588823e-03 9.993173e-01 3.635280e-02 -2.992133e+01 3.651664e-02 -3.656978e-02 9.986636e-01 4.581848e+02 +9.994013e-01 -4.545292e-03 -3.429966e-02 6.196869e+01 5.770503e-03 9.993456e-01 3.570674e-02 -2.990140e+01 3.411492e-02 -3.588328e-02 9.987735e-01 4.593792e+02 +9.994862e-01 -1.509180e-03 -3.201818e-02 6.192154e+01 2.578938e-03 9.994388e-01 3.339600e-02 -2.988192e+01 3.194981e-02 -3.346141e-02 9.989291e-01 4.605708e+02 +9.995556e-01 -2.664537e-04 -2.980864e-02 6.187891e+01 1.207915e-03 9.995008e-01 3.156995e-02 -2.986261e+01 2.978534e-02 -3.159192e-02 9.990569e-01 4.617627e+02 +9.996288e-01 4.559319e-04 -2.724242e-02 6.184077e+01 3.914896e-04 9.995164e-01 3.109327e-02 -2.984488e+01 2.724342e-02 -3.109239e-02 9.991451e-01 4.629558e+02 +9.996963e-01 -6.505631e-05 -2.464692e-02 6.180876e+01 7.917953e-04 9.995651e-01 2.947738e-02 -2.982930e+01 2.463428e-02 -2.948794e-02 9.992615e-01 4.641483e+02 +9.997446e-01 -2.402246e-03 -2.247365e-02 6.178226e+01 3.021351e-03 9.996157e-01 2.755474e-02 -2.981434e+01 2.239882e-02 -2.761559e-02 9.993676e-01 4.653398e+02 +9.997805e-01 -3.355473e-03 -2.068430e-02 6.175759e+01 3.922098e-03 9.996164e-01 2.741457e-02 -2.980003e+01 2.058437e-02 -2.748967e-02 9.994101e-01 4.665340e+02 +9.998192e-01 -4.229036e-03 -1.854338e-02 6.173523e+01 4.761814e-03 9.995743e-01 2.878205e-02 -2.978618e+01 1.841376e-02 -2.886514e-02 9.994136e-01 4.677279e+02 +9.998748e-01 -1.183801e-03 -1.578125e-02 6.171120e+01 1.645126e-03 9.995707e-01 2.925160e-02 -2.977108e+01 1.573984e-02 -2.927390e-02 9.994474e-01 4.689240e+02 +9.999317e-01 6.005286e-04 -1.167461e-02 6.169094e+01 -2.791702e-04 9.996215e-01 2.750842e-02 -2.975585e+01 1.168671e-02 -2.750328e-02 9.995533e-01 4.701183e+02 +9.999653e-01 3.041521e-03 -7.758734e-03 6.167460e+01 -2.847750e-03 9.996868e-01 2.486455e-02 -2.974208e+01 7.831929e-03 -2.484159e-02 9.996607e-01 4.713112e+02 +9.999919e-01 1.754739e-03 -3.630698e-03 6.166971e+01 -1.667566e-03 9.997135e-01 2.387534e-02 -2.972981e+01 3.671553e-03 -2.386909e-02 9.997083e-01 4.725060e+02 +9.999933e-01 -3.664260e-03 -1.679595e-04 6.167550e+01 3.667229e-03 9.997074e-01 2.390931e-02 -2.971754e+01 8.030031e-05 -2.390976e-02 9.997141e-01 4.736994e+02 +9.999790e-01 -5.853252e-03 2.787978e-03 6.168390e+01 5.786311e-03 9.997084e-01 2.344236e-02 -2.970659e+01 -2.924379e-03 -2.342573e-02 9.997212e-01 4.748978e+02 +9.999388e-01 -9.355645e-03 5.904189e-03 6.169553e+01 9.203176e-03 9.996364e-01 2.534329e-02 -2.969347e+01 -6.139145e-03 -2.528740e-02 9.996613e-01 4.760948e+02 +9.999389e-01 -6.060970e-03 9.248580e-03 6.170142e+01 5.827487e-03 9.996688e-01 2.506689e-02 -2.968265e+01 -9.397446e-03 -2.501146e-02 9.996429e-01 4.772901e+02 +9.999071e-01 -2.421830e-03 1.341799e-02 6.170979e+01 2.158860e-03 9.998060e-01 1.957830e-02 -2.967501e+01 -1.346280e-02 -1.954750e-02 9.997182e-01 4.784768e+02 +9.998430e-01 -4.502979e-03 1.713977e-02 6.172939e+01 4.299315e-03 9.999199e-01 1.190090e-02 -2.966784e+01 -1.719199e-02 -1.182534e-02 9.997822e-01 4.796669e+02 +9.997845e-01 -4.421317e-03 2.028751e-02 6.175418e+01 4.204550e-03 9.999337e-01 1.071500e-02 -2.966788e+01 -2.033354e-02 -1.062739e-02 9.997367e-01 4.808627e+02 +9.997072e-01 -7.462673e-03 2.302076e-02 6.178625e+01 7.076913e-03 9.998339e-01 1.679327e-02 -2.966606e+01 -2.314226e-02 -1.662543e-02 9.995939e-01 4.820660e+02 +9.996178e-01 -1.105758e-02 2.533899e-02 6.182287e+01 1.052580e-02 9.997235e-01 2.102464e-02 -2.965840e+01 -2.556446e-02 -2.074988e-02 9.994577e-01 4.832703e+02 +9.995134e-01 -1.453231e-02 2.760251e-02 6.185960e+01 1.396980e-02 9.996930e-01 2.046343e-02 -2.964756e+01 -2.789142e-02 -2.006786e-02 9.994094e-01 4.844727e+02 +9.995004e-01 -1.194063e-02 2.926610e-02 6.189087e+01 1.140114e-02 9.997632e-01 1.853207e-02 -2.963680e+01 -2.948045e-02 -1.818914e-02 9.993998e-01 4.856716e+02 +9.994818e-01 -1.089926e-02 3.028786e-02 6.192481e+01 1.037275e-02 9.997933e-01 1.748659e-02 -2.963187e+01 -3.047218e-02 -1.716335e-02 9.993882e-01 4.868781e+02 +9.993802e-01 -1.657732e-02 3.105558e-02 6.196853e+01 1.613730e-02 9.997665e-01 1.436629e-02 -2.962845e+01 -3.128649e-02 -1.385623e-02 9.994144e-01 4.880776e+02 +9.993676e-01 -1.758657e-02 3.090696e-02 6.200735e+01 1.726138e-02 9.997931e-01 1.075716e-02 -2.962550e+01 -3.108975e-02 -1.021686e-02 9.994643e-01 4.892780e+02 +9.991718e-01 -2.755671e-02 2.994028e-02 6.205655e+01 2.737187e-02 9.996037e-01 6.566180e-03 -2.962912e+01 -3.010936e-02 -5.741219e-03 9.995301e-01 4.904786e+02 +9.991300e-01 -3.132310e-02 2.753674e-02 6.209928e+01 3.122248e-02 9.995041e-01 4.076378e-03 -2.963476e+01 -2.765077e-02 -3.213065e-03 9.996124e-01 4.916884e+02 +9.989522e-01 -3.734008e-02 2.646303e-02 6.214208e+01 3.714546e-02 9.992793e-01 7.808270e-03 -2.964202e+01 -2.673552e-02 -6.817105e-03 9.996192e-01 4.929053e+02 +9.990471e-01 -3.542970e-02 2.548954e-02 6.217602e+01 3.522953e-02 9.993451e-01 8.259791e-03 -2.965110e+01 -2.576549e-02 -7.353933e-03 9.996409e-01 4.941179e+02 +9.989461e-01 -3.800721e-02 2.573494e-02 6.220936e+01 3.776627e-02 9.992387e-01 9.784677e-03 -2.965342e+01 -2.608723e-02 -8.802450e-03 9.996209e-01 4.953326e+02 +9.989992e-01 -3.695488e-02 2.519994e-02 6.223917e+01 3.663349e-02 9.992429e-01 1.309844e-02 -2.965527e+01 -2.566491e-02 -1.216217e-02 9.995966e-01 4.965489e+02 +9.991325e-01 -3.321567e-02 2.511975e-02 6.226669e+01 3.273252e-02 9.992757e-01 1.940672e-02 -2.965389e+01 -2.574616e-02 -1.856765e-02 9.994960e-01 4.977739e+02 +9.992635e-01 -2.882604e-02 2.532964e-02 6.229207e+01 2.832390e-02 9.993994e-01 1.996444e-02 -2.964820e+01 -2.588992e-02 -1.923230e-02 9.994797e-01 4.989961e+02 +9.992906e-01 -2.610919e-02 2.714216e-02 6.231305e+01 2.570828e-02 9.995567e-01 1.501623e-02 -2.968655e+01 -2.752219e-02 -1.430780e-02 9.995187e-01 5.002337e+02 +9.993163e-01 -2.220626e-02 2.956293e-02 6.233091e+01 2.189043e-02 9.997002e-01 1.096459e-02 -2.975460e+01 -2.979755e-02 -1.030994e-02 9.995027e-01 5.014844e+02 +9.994126e-01 -1.361399e-02 3.145247e-02 6.234645e+01 1.333602e-02 9.998703e-01 9.030759e-03 -2.980734e+01 -3.157134e-02 -8.606002e-03 9.994644e-01 5.027320e+02 +9.993343e-01 -1.293906e-02 3.411291e-02 6.237074e+01 1.264975e-02 9.998823e-01 8.683332e-03 -2.987199e+01 -3.422124e-02 -8.246029e-03 9.993802e-01 5.039952e+02 +9.992474e-01 -8.835551e-03 3.777197e-02 6.238360e+01 8.468650e-03 9.999155e-01 9.862593e-03 -2.996263e+01 -3.785592e-02 -9.535291e-03 9.992377e-01 5.052451e+02 +9.991003e-01 1.030701e-03 4.239733e-02 6.238900e+01 -1.459092e-03 9.999482e-01 1.007450e-02 -3.002263e+01 -4.238474e-02 -1.012730e-02 9.990500e-01 5.065041e+02 +9.988928e-01 1.190439e-03 4.702970e-02 6.242438e+01 -1.778320e-03 9.999208e-01 1.246035e-02 -3.004403e+01 -4.701114e-02 -1.253018e-02 9.988157e-01 5.077564e+02 +9.986204e-01 3.036648e-03 5.242345e-02 6.245682e+01 -3.717072e-03 9.999100e-01 1.288677e-02 -3.009300e+01 -5.237959e-02 -1.306385e-02 9.985417e-01 5.090163e+02 +9.983375e-01 -7.514748e-04 5.763536e-02 6.251183e+01 6.583982e-05 9.999292e-01 1.189706e-02 -3.012980e+01 -5.764022e-02 -1.187348e-02 9.982668e-01 5.102768e+02 +9.980719e-01 -6.566888e-03 6.172028e-02 6.257018e+01 5.966919e-03 9.999332e-01 9.900087e-03 -3.018947e+01 -6.178117e-02 -9.512717e-03 9.980443e-01 5.115396e+02 +9.977008e-01 -1.640189e-02 6.575807e-02 6.263966e+01 1.591078e-02 9.998415e-01 7.985263e-03 -3.021748e+01 -6.587862e-02 -6.920640e-03 9.978036e-01 5.128006e+02 +9.973772e-01 -2.232161e-02 6.885143e-02 6.271269e+01 2.143142e-02 9.996772e-01 1.364094e-02 -3.023074e+01 -6.913370e-02 -1.212958e-02 9.975336e-01 5.140754e+02 +9.970422e-01 -2.628314e-02 7.222324e-02 6.278682e+01 2.482228e-02 9.994702e-01 2.105076e-02 -3.023197e+01 -7.273825e-02 -1.919574e-02 9.971663e-01 5.153561e+02 +9.967795e-01 -2.916092e-02 7.470122e-02 6.286835e+01 2.734108e-02 9.993067e-01 2.526971e-02 -3.022795e+01 -7.538631e-02 -2.314591e-02 9.968857e-01 5.166381e+02 +9.966829e-01 -2.852740e-02 7.621999e-02 6.294582e+01 2.721451e-02 9.994637e-01 1.820882e-02 -3.022461e+01 -7.669856e-02 -1.607413e-02 9.969247e-01 5.179075e+02 +9.966175e-01 -2.951006e-02 7.669920e-02 6.302872e+01 2.864259e-02 9.995130e-01 1.238589e-02 -3.022487e+01 -7.702735e-02 -1.014712e-02 9.969773e-01 5.191774e+02 +9.965293e-01 -3.200949e-02 7.684318e-02 6.310640e+01 3.084173e-02 9.993908e-01 1.633604e-02 -3.023054e+01 -7.731926e-02 -1.390936e-02 9.969093e-01 5.204567e+02 +9.963841e-01 -3.673449e-02 7.661193e-02 6.319398e+01 3.519532e-02 9.991525e-01 2.134521e-02 -3.023592e+01 -7.733110e-02 -1.857165e-02 9.968324e-01 5.217318e+02 +9.962783e-01 -4.202481e-02 7.525616e-02 6.327909e+01 4.089170e-02 9.990267e-01 1.653558e-02 -3.024068e+01 -7.587782e-02 -1.339668e-02 9.970271e-01 5.229983e+02 +9.961968e-01 -4.790583e-02 7.278133e-02 6.336724e+01 4.752866e-02 9.988460e-01 6.906367e-03 -3.024702e+01 -7.302819e-02 -3.420900e-03 9.973240e-01 5.242594e+02 +9.960938e-01 -5.361448e-02 7.016215e-02 6.345143e+01 5.343537e-02 9.985615e-01 4.428716e-03 -3.026336e+01 -7.029866e-02 -6.622762e-04 9.975257e-01 5.255253e+02 +9.963414e-01 -5.193762e-02 6.787080e-02 6.352566e+01 5.115127e-02 9.986027e-01 1.327415e-02 -3.028439e+01 -6.846539e-02 -9.753906e-03 9.976058e-01 5.268025e+02 +9.966233e-01 -4.916936e-02 6.576088e-02 6.359357e+01 4.793049e-02 9.986446e-01 2.028695e-02 -3.029986e+01 -6.666924e-02 -1.706649e-02 9.976291e-01 5.280818e+02 +9.968020e-01 -4.784749e-02 6.400399e-02 6.366036e+01 4.648652e-02 9.986635e-01 2.258746e-02 -3.030737e+01 -6.499920e-02 -1.953990e-02 9.976939e-01 5.293629e+02 +9.968710e-01 -4.926046e-02 6.182020e-02 6.372753e+01 4.771610e-02 9.985169e-01 2.621486e-02 -3.030568e+01 -6.301987e-02 -2.318301e-02 9.977429e-01 5.306231e+02 +9.966609e-01 -5.580873e-02 5.960267e-02 6.380153e+01 5.440392e-02 9.982075e-01 2.493919e-02 -3.030507e+01 -6.088765e-02 -2.161329e-02 9.979105e-01 5.318882e+02 +9.961646e-01 -6.611063e-02 5.731950e-02 6.387822e+01 6.507160e-02 9.976839e-01 1.981007e-02 -3.030383e+01 -5.849640e-02 -1.600421e-02 9.981593e-01 5.331588e+02 +9.956357e-01 -7.526959e-02 5.517351e-02 6.395473e+01 7.451969e-02 9.970986e-01 1.552833e-02 -3.030880e+01 -5.618224e-02 -1.134905e-02 9.983560e-01 5.344059e+02 +9.954934e-01 -7.889110e-02 5.262295e-02 6.402454e+01 7.821112e-02 9.968260e-01 1.486147e-02 -3.030985e+01 -5.362836e-02 -1.067880e-02 9.985038e-01 5.356679e+02 +9.950531e-01 -8.531068e-02 5.090745e-02 6.409618e+01 8.458170e-02 9.962830e-01 1.631030e-02 -3.033016e+01 -5.210967e-02 -1.192377e-02 9.985701e-01 5.369330e+02 +9.951802e-01 -8.481464e-02 4.922281e-02 6.415405e+01 8.392095e-02 9.962726e-01 1.995114e-02 -3.033808e+01 -5.073148e-02 -1.572415e-02 9.985885e-01 5.381985e+02 +9.954134e-01 -8.335427e-02 4.695056e-02 6.420683e+01 8.209071e-02 9.962249e-01 2.823016e-02 -3.034295e+01 -4.912642e-02 -2.424647e-02 9.984982e-01 5.394675e+02 +9.957350e-01 -8.039099e-02 4.526682e-02 6.425876e+01 7.915941e-02 9.964580e-01 2.837525e-02 -3.034540e+01 -4.738760e-02 -2.467093e-02 9.985718e-01 5.407274e+02 +9.960934e-01 -7.611950e-02 4.476339e-02 6.430508e+01 7.525619e-02 9.969500e-01 2.066774e-02 -3.034649e+01 -4.620008e-02 -1.721828e-02 9.987837e-01 5.419798e+02 +9.967419e-01 -6.739694e-02 4.430833e-02 6.434471e+01 6.684941e-02 9.976686e-01 1.372684e-02 -3.035452e+01 -4.513018e-02 -1.072012e-02 9.989235e-01 5.432349e+02 +9.968296e-01 -6.695395e-02 4.298773e-02 6.438977e+01 6.659915e-02 9.977333e-01 9.634971e-03 -3.036664e+01 -4.353538e-02 -6.741477e-03 9.990291e-01 5.444832e+02 +9.968455e-01 -6.737065e-02 4.195695e-02 6.443713e+01 6.711381e-02 9.977171e-01 7.502147e-03 -3.038255e+01 -4.236659e-02 -4.662589e-03 9.990912e-01 5.457330e+02 +9.964308e-01 -7.411709e-02 4.040357e-02 6.449631e+01 7.351347e-02 9.971622e-01 1.622858e-02 -3.038692e+01 -4.149173e-02 -1.320045e-02 9.990516e-01 5.469969e+02 +9.960788e-01 -7.930288e-02 3.922016e-02 6.455740e+01 7.840069e-02 9.966322e-01 2.403232e-02 -3.038517e+01 -4.099390e-02 -2.086319e-02 9.989415e-01 5.482559e+02 +9.967127e-01 -7.119330e-02 3.867069e-02 6.459620e+01 7.032501e-02 9.972503e-01 2.336983e-02 -3.038170e+01 -4.022813e-02 -2.057348e-02 9.989786e-01 5.495045e+02 +9.972818e-01 -6.197001e-02 3.985953e-02 6.463193e+01 6.141065e-02 9.979982e-01 1.510915e-02 -3.037991e+01 -4.071605e-02 -1.262028e-02 9.990910e-01 5.507430e+02 +9.977003e-01 -5.306675e-02 4.216779e-02 6.466488e+01 5.275740e-02 9.985719e-01 8.416242e-03 -3.038529e+01 -4.255419e-02 -6.172223e-03 9.990750e-01 5.519809e+02 +9.981289e-01 -4.237519e-02 4.408173e-02 6.470090e+01 4.203795e-02 9.990794e-01 8.549950e-03 -3.039768e+01 -4.440345e-02 -6.680845e-03 9.989913e-01 5.532226e+02 +9.981101e-01 -4.214935e-02 4.471846e-02 6.474917e+01 4.173023e-02 9.990762e-01 1.026533e-02 -3.041057e+01 -4.510982e-02 -8.379820e-03 9.989468e-01 5.544627e+02 +9.980540e-01 -4.226070e-02 4.585192e-02 6.480354e+01 4.188610e-02 9.990809e-01 9.100510e-03 -3.042047e+01 -4.619437e-02 -7.162240e-03 9.989067e-01 5.556978e+02 +9.979097e-01 -4.349441e-02 4.779785e-02 6.485863e+01 4.303280e-02 9.990169e-01 1.064495e-02 -3.042894e+01 -4.821386e-02 -8.565822e-03 9.988003e-01 5.569316e+02 +9.978916e-01 -4.204860e-02 4.944034e-02 6.491461e+01 4.138871e-02 9.990408e-01 1.429663e-02 -3.044249e+01 -4.999407e-02 -1.222021e-02 9.986747e-01 5.581673e+02 +9.978759e-01 -3.950367e-02 5.179980e-02 6.497033e+01 3.853704e-02 9.990663e-01 1.952910e-02 -3.045613e+01 -5.252290e-02 -1.749140e-02 9.984665e-01 5.594073e+02 +9.977518e-01 -3.968279e-02 5.400734e-02 6.503012e+01 3.848255e-02 9.989925e-01 2.308548e-02 -3.046345e+01 -5.486903e-02 -2.095523e-02 9.982736e-01 5.606409e+02 +9.973374e-01 -4.686369e-02 5.587486e-02 6.510370e+01 4.570229e-02 9.987153e-01 2.188628e-02 -3.046897e+01 -5.682875e-02 -1.927439e-02 9.981978e-01 5.618672e+02 +9.969904e-01 -5.211672e-02 5.739416e-02 6.517697e+01 5.133922e-02 9.985695e-01 1.494000e-02 -3.048824e+01 -5.809068e-02 -1.194847e-02 9.982397e-01 5.630821e+02 +9.964989e-01 -5.934423e-02 5.889278e-02 6.525908e+01 5.892825e-02 9.982236e-01 8.776666e-03 -3.051182e+01 -5.930900e-02 -5.275489e-03 9.982257e-01 5.642984e+02 +9.962197e-01 -6.295331e-02 5.986051e-02 6.533596e+01 6.260587e-02 9.980089e-01 7.664043e-03 -3.052806e+01 -6.022379e-02 -3.887451e-03 9.981773e-01 5.655172e+02 +9.957946e-01 -6.811161e-02 6.126970e-02 6.541668e+01 6.735477e-02 9.976261e-01 1.433670e-02 -3.054385e+01 -6.210074e-02 -1.014960e-02 9.980182e-01 5.667457e+02 +9.957674e-01 -6.752673e-02 6.234981e-02 6.549146e+01 6.650431e-02 9.976177e-01 1.833278e-02 -3.055592e+01 -6.343922e-02 -1.410865e-02 9.978859e-01 5.679707e+02 +9.955715e-01 -6.996311e-02 6.279089e-02 6.556920e+01 6.882862e-02 9.974269e-01 2.005523e-02 -3.056114e+01 -6.403244e-02 -1.564460e-02 9.978251e-01 5.691902e+02 +9.953958e-01 -7.328906e-02 6.177328e-02 6.564974e+01 7.190476e-02 9.971143e-01 2.434529e-02 -3.056148e+01 -6.337926e-02 -1.979140e-02 9.977932e-01 5.704166e+02 +9.953439e-01 -7.533815e-02 6.012280e-02 6.572601e+01 7.385948e-02 9.969178e-01 2.645193e-02 -3.056718e+01 -6.193032e-02 -2.188813e-02 9.978404e-01 5.716394e+02 +9.954603e-01 -7.470280e-02 5.897789e-02 6.579425e+01 7.305935e-02 9.968897e-01 2.954988e-02 -3.056589e+01 -6.100190e-02 -2.510684e-02 9.978218e-01 5.728638e+02 +9.957441e-01 -7.126160e-02 5.844294e-02 6.585656e+01 6.975643e-02 9.971875e-01 2.740509e-02 -3.056486e+01 -6.023149e-02 -2.321168e-02 9.979145e-01 5.740847e+02 +9.957941e-01 -7.013010e-02 5.895730e-02 6.591963e+01 6.904553e-02 9.974082e-01 2.023860e-02 -3.055742e+01 -6.022383e-02 -1.608273e-02 9.980553e-01 5.753003e+02 +9.962643e-01 -6.326995e-02 5.877373e-02 6.597921e+01 6.232503e-02 9.978976e-01 1.777554e-02 -3.055140e+01 -5.977482e-02 -1.404606e-02 9.981130e-01 5.765219e+02 +9.960026e-01 -6.692919e-02 5.915533e-02 6.604778e+01 6.639065e-02 9.977328e-01 1.102515e-02 -3.055335e+01 -5.975911e-02 -7.053720e-03 9.981878e-01 5.777368e+02 +9.960214e-01 -6.623807e-02 5.961496e-02 6.611325e+01 6.631540e-02 9.977985e-01 6.825898e-04 -3.056374e+01 -5.952893e-02 3.273516e-03 9.982212e-01 5.789491e+02 +9.959568e-01 -6.755584e-02 5.921405e-02 6.618005e+01 6.751040e-02 9.977147e-01 2.770043e-03 -3.057954e+01 -5.926585e-02 1.238721e-03 9.982414e-01 5.801723e+02 +9.961406e-01 -6.641344e-02 5.738662e-02 6.624230e+01 6.604725e-02 9.977823e-01 8.256587e-03 -3.059281e+01 -5.780770e-02 -4.434492e-03 9.983178e-01 5.813969e+02 +9.960114e-01 -6.908446e-02 5.646801e-02 6.630713e+01 6.841440e-02 9.975627e-01 1.371691e-02 -3.059955e+01 -5.727800e-02 -9.798970e-03 9.983101e-01 5.826257e+02 +9.962739e-01 -6.641962e-02 5.501702e-02 6.636228e+01 6.547207e-02 9.976763e-01 1.885186e-02 -3.059891e+01 -5.614131e-02 -1.517954e-02 9.983074e-01 5.838530e+02 +9.960435e-01 -7.098532e-02 5.346557e-02 6.642176e+01 7.000353e-02 9.973458e-01 2.001958e-02 -3.059449e+01 -5.474475e-02 -1.619759e-02 9.983689e-01 5.850738e+02 +9.960437e-01 -7.279506e-02 5.097015e-02 6.647890e+01 7.206298e-02 9.972708e-01 1.605886e-02 -3.059282e+01 -5.200004e-02 -1.232226e-02 9.985710e-01 5.862920e+02 +9.958041e-01 -7.775929e-02 4.824598e-02 6.653835e+01 7.697015e-02 9.968708e-01 1.800719e-02 -3.059203e+01 -4.949523e-02 -1.421813e-02 9.986731e-01 5.875152e+02 +9.958612e-01 -7.905048e-02 4.484968e-02 6.659443e+01 7.818127e-02 9.967218e-01 2.081720e-02 -3.059249e+01 -4.634826e-02 -1.722463e-02 9.987768e-01 5.887373e+02 +9.959628e-01 -7.909028e-02 4.246123e-02 6.664304e+01 7.842170e-02 9.967720e-01 1.718974e-02 -3.059112e+01 -4.368371e-02 -1.379045e-02 9.989502e-01 5.899515e+02 +9.964181e-01 -7.408208e-02 4.077775e-02 6.668227e+01 7.348604e-02 9.971690e-01 1.592893e-02 -3.058838e+01 -4.184236e-02 -1.287527e-02 9.990412e-01 5.911689e+02 +9.968830e-01 -6.769539e-02 4.051769e-02 6.671479e+01 6.713076e-02 9.976293e-01 1.513925e-02 -3.059246e+01 -4.144649e-02 -1.237207e-02 9.990641e-01 5.923819e+02 +9.974588e-01 -5.843383e-02 4.076171e-02 6.674636e+01 5.791120e-02 9.982251e-01 1.388766e-02 -3.059512e+01 -4.150087e-02 -1.149181e-02 9.990723e-01 5.935962e+02 +9.977923e-01 -5.212760e-02 4.114964e-02 6.677760e+01 5.144620e-02 9.985233e-01 1.744870e-02 -3.059517e+01 -4.199843e-02 -1.529319e-02 9.990006e-01 5.948114e+02 +9.980087e-01 -4.761649e-02 4.136990e-02 6.681255e+01 4.692336e-02 9.987440e-01 1.756769e-02 -3.059663e+01 -4.215444e-02 -1.559149e-02 9.989894e-01 5.960203e+02 +9.981856e-01 -4.316603e-02 4.197849e-02 6.684767e+01 4.266046e-02 9.990068e-01 1.286622e-02 -3.060274e+01 -4.249217e-02 -1.105205e-02 9.990356e-01 5.972236e+02 +9.981551e-01 -4.296821e-02 4.289822e-02 6.689040e+01 4.265073e-02 9.990556e-01 8.289165e-03 -3.060873e+01 -4.321388e-02 -6.444230e-03 9.990450e-01 5.984203e+02 +9.981325e-01 -4.262240e-02 4.375933e-02 6.693507e+01 4.222641e-02 9.990587e-01 9.934729e-03 -3.061734e+01 -4.414158e-02 -8.068375e-03 9.989926e-01 5.996305e+02 +9.981013e-01 -4.267411e-02 4.441531e-02 6.698150e+01 4.204724e-02 9.990037e-01 1.495407e-02 -3.062533e+01 -4.500920e-02 -1.305813e-02 9.989012e-01 6.008367e+02 +9.980954e-01 -4.214055e-02 4.505373e-02 6.702669e+01 4.124279e-02 9.989352e-01 2.067413e-02 -3.062541e+01 -4.587698e-02 -1.877661e-02 9.987706e-01 6.020429e+02 +9.980251e-01 -4.331660e-02 4.549424e-02 6.707671e+01 4.225188e-02 9.988160e-01 2.411025e-02 -3.061967e+01 -4.648475e-02 -2.214042e-02 9.986735e-01 6.032469e+02 +9.981147e-01 -4.025108e-02 4.633457e-02 6.712270e+01 3.926509e-02 9.989867e-01 2.199712e-02 -3.061608e+01 -4.717302e-02 -2.013631e-02 9.986837e-01 6.044377e+02 +9.978854e-01 -4.407850e-02 4.776862e-02 6.717746e+01 4.369985e-02 9.990047e-01 8.942942e-03 -3.061759e+01 -4.811526e-02 -6.836549e-03 9.988183e-01 6.056229e+02 +9.978875e-01 -4.316341e-02 4.855548e-02 6.722857e+01 4.325324e-02 9.990638e-01 -8.001724e-04 -3.062692e+01 -4.847548e-02 2.898663e-03 9.988201e-01 6.068034e+02 +9.979174e-01 -4.167306e-02 4.923808e-02 6.727761e+01 4.156509e-02 9.991306e-01 3.215295e-03 -3.064073e+01 -4.932926e-02 -1.162013e-03 9.987818e-01 6.079964e+02 +9.980599e-01 -3.753676e-02 4.967434e-02 6.732302e+01 3.688486e-02 9.992218e-01 1.397615e-02 -3.065377e+01 -5.016030e-02 -1.211680e-02 9.986676e-01 6.091983e+02 +9.982416e-01 -3.058082e-02 5.078041e-02 6.736474e+01 2.940985e-02 9.992876e-01 2.364908e-02 -3.065802e+01 -5.146744e-02 -2.211404e-02 9.984297e-01 6.103967e+02 +9.983175e-01 -2.242085e-02 5.347497e-02 6.740452e+01 2.128126e-02 9.995361e-01 2.178585e-02 -3.065500e+01 -5.393862e-02 -2.061117e-02 9.983315e-01 6.115794e+02 +9.982478e-01 -1.791483e-02 5.639526e-02 6.745050e+01 1.700956e-02 9.997193e-01 1.649153e-02 -3.065237e+01 -5.667487e-02 -1.550337e-02 9.982723e-01 6.127580e+02 +9.980263e-01 -1.981089e-02 5.959090e-02 6.750965e+01 1.915546e-02 9.997498e-01 1.155024e-02 -3.065671e+01 -5.980480e-02 -1.038595e-02 9.981560e-01 6.139338e+02 +9.977422e-01 -2.379700e-02 6.280408e-02 6.757930e+01 2.317365e-02 9.996749e-01 1.063535e-02 -3.066677e+01 -6.303675e-02 -9.155934e-03 9.979692e-01 6.151119e+02 +9.973901e-01 -2.840921e-02 6.637797e-02 6.765357e+01 2.766105e-02 9.995433e-01 1.216341e-02 -3.067628e+01 -6.669321e-02 -1.029558e-02 9.977204e-01 6.162893e+02 +9.971861e-01 -2.822430e-02 6.945003e-02 6.772655e+01 2.721619e-02 9.995106e-01 1.541940e-02 -3.068256e+01 -6.985124e-02 -1.348585e-02 9.974662e-01 6.174688e+02 +9.968814e-01 -2.965116e-02 7.313286e-02 6.780166e+01 2.854014e-02 9.994615e-01 1.619049e-02 -3.068626e+01 -7.357355e-02 -1.405278e-02 9.971907e-01 6.186413e+02 +9.966293e-01 -2.841772e-02 7.695807e-02 6.787829e+01 2.712223e-02 9.994731e-01 1.782708e-02 -3.068959e+01 -7.742413e-02 -1.567971e-02 9.968749e-01 6.198137e+02 +9.962826e-01 -2.724135e-02 8.172501e-02 6.795771e+01 2.604648e-02 9.995382e-01 1.565149e-02 -3.069359e+01 -8.211363e-02 -1.346465e-02 9.965320e-01 6.209790e+02 +9.959017e-01 -2.886038e-02 8.571418e-02 6.805015e+01 2.759657e-02 9.994928e-01 1.589316e-02 -3.069814e+01 -8.612939e-02 -1.346261e-02 9.961929e-01 6.221454e+02 +9.952321e-01 -3.784053e-02 8.989606e-02 6.815401e+01 3.644231e-02 9.991887e-01 1.714508e-02 -3.069937e+01 -9.047190e-02 -1.378731e-02 9.958035e-01 6.233085e+02 +9.949037e-01 -3.738375e-02 9.364350e-02 6.825561e+01 3.559307e-02 9.991515e-01 2.072067e-02 -3.070047e+01 -9.433865e-02 -1.728201e-02 9.953901e-01 6.244726e+02 +9.948497e-01 -2.394161e-02 9.849378e-02 6.834121e+01 2.163275e-02 9.994671e-01 2.444334e-02 -3.069881e+01 -9.902650e-02 -2.218675e-02 9.948374e-01 6.256381e+02 +9.943778e-01 -1.801679e-02 1.043466e-01 6.843702e+01 1.524507e-02 9.995110e-01 2.729965e-02 -3.069499e+01 -1.047875e-01 -2.555539e-02 9.941662e-01 6.267996e+02 +9.938004e-01 -4.671232e-03 1.110812e-01 6.853133e+01 2.106194e-03 9.997287e-01 2.319770e-02 -3.069013e+01 -1.111594e-01 -2.281992e-02 9.935405e-01 6.279565e+02 +9.930595e-01 1.269801e-04 1.176137e-01 6.863837e+01 -2.766270e-03 9.997480e-01 2.227735e-02 -3.068335e+01 -1.175812e-01 -2.244808e-02 9.928095e-01 6.291094e+02 +9.925615e-01 -7.372202e-03 1.215210e-01 6.877141e+01 5.144285e-03 9.998131e-01 1.863716e-02 -3.068435e+01 -1.216356e-01 -1.787338e-02 9.924138e-01 6.302577e+02 +9.921583e-01 -1.603456e-02 1.239549e-01 6.891548e+01 1.363529e-02 9.997034e-01 2.018024e-02 -3.068382e+01 -1.242417e-01 -1.833183e-02 9.920826e-01 6.314072e+02 +9.917573e-01 -2.425506e-02 1.258144e-01 6.906335e+01 2.152397e-02 9.995032e-01 2.302163e-02 -3.068258e+01 -1.263103e-01 -2.012384e-02 9.917866e-01 6.325536e+02 +9.915012e-01 -2.507520e-02 1.276583e-01 6.920255e+01 2.280085e-02 9.995547e-01 1.924649e-02 -3.068222e+01 -1.280841e-01 -1.617220e-02 9.916314e-01 6.336952e+02 +9.913292e-01 -1.854369e-02 1.300867e-01 6.933306e+01 1.689258e-02 9.997623e-01 1.378447e-02 -3.068350e+01 -1.303114e-01 -1.146744e-02 9.914067e-01 6.348305e+02 +9.910683e-01 -1.611663e-02 1.323784e-01 6.946592e+01 1.500704e-02 9.998434e-01 9.375461e-03 -3.068713e+01 -1.325087e-01 -7.305113e-03 9.911549e-01 6.359645e+02 +9.909207e-01 -1.260955e-02 1.338555e-01 6.960067e+01 1.075832e-02 9.998363e-01 1.454436e-02 -3.069590e+01 -1.340170e-01 -1.297225e-02 9.908941e-01 6.371033e+02 +9.906301e-01 -1.344747e-02 1.359091e-01 6.974198e+01 1.085266e-02 9.997447e-01 1.981515e-02 -3.070234e+01 -1.361408e-01 -1.815450e-02 9.905231e-01 6.382350e+02 +9.903247e-01 -1.449392e-02 1.380111e-01 6.988598e+01 1.139450e-02 9.996654e-01 2.322141e-02 -3.070309e+01 -1.383015e-01 -2.142416e-02 9.901584e-01 6.393650e+02 +9.899971e-01 -1.929174e-02 1.397625e-01 7.003683e+01 1.559199e-02 9.994997e-01 2.751863e-02 -3.069846e+01 -1.402235e-01 -2.506418e-02 9.898025e-01 6.404887e+02 +9.896581e-01 -3.281737e-02 1.396423e-01 7.020030e+01 2.955547e-02 9.992411e-01 2.536953e-02 -3.069272e+01 -1.403689e-01 -2.097996e-02 9.898769e-01 6.415999e+02 +9.898806e-01 -3.523192e-02 1.374596e-01 7.035244e+01 3.332517e-02 9.993141e-01 1.614888e-02 -3.069237e+01 -1.379342e-01 -1.140459e-02 9.903757e-01 6.427042e+02 +9.899421e-01 -4.479974e-02 1.341925e-01 7.050627e+01 4.399743e-02 9.989916e-01 8.939840e-03 -3.069271e+01 -1.344577e-01 -2.945797e-03 9.909149e-01 6.438071e+02 +9.904272e-01 -4.431955e-02 1.307281e-01 7.064581e+01 4.295591e-02 9.989893e-01 1.323403e-02 -3.070085e+01 -1.311825e-01 -7.491795e-03 9.913299e-01 6.449198e+02 +9.908846e-01 -4.390489e-02 1.273584e-01 7.077454e+01 4.087372e-02 9.988176e-01 2.631820e-02 -3.070245e+01 -1.283634e-01 -2.087268e-02 9.915075e-01 6.460445e+02 +9.916551e-01 -3.771697e-02 1.232792e-01 7.089277e+01 3.366954e-02 9.988286e-01 3.475220e-02 -3.069577e+01 -1.244455e-01 -3.031143e-02 9.917633e-01 6.471615e+02 +9.919498e-01 -3.969492e-02 1.202498e-01 7.101533e+01 3.596708e-02 9.988075e-01 3.301506e-02 -3.068234e+01 -1.214170e-01 -2.842424e-02 9.921945e-01 6.482631e+02 +9.925923e-01 -3.212882e-02 1.171682e-01 7.112474e+01 2.968446e-02 9.993049e-01 2.254819e-02 -3.067423e+01 -1.178112e-01 -1.890309e-02 9.928560e-01 6.493557e+02 +9.929021e-01 -2.854551e-02 1.154588e-01 7.123277e+01 2.777676e-02 9.995800e-01 8.262022e-03 -3.067802e+01 -1.156462e-01 -4.996307e-03 9.932779e-01 6.504433e+02 +9.933266e-01 -2.329693e-02 1.129587e-01 7.133593e+01 2.280158e-02 9.997239e-01 5.675431e-03 -3.068719e+01 -1.130597e-01 -3.061919e-03 9.935834e-01 6.515385e+02 +9.935052e-01 -2.291920e-02 1.114553e-01 7.144314e+01 2.166553e-02 9.996878e-01 1.244652e-02 -3.069355e+01 -1.117058e-01 -9.950945e-03 9.936914e-01 6.526402e+02 +9.937890e-01 -2.286800e-02 1.089058e-01 7.158017e+01 2.108410e-02 9.996244e-01 1.750382e-02 -3.069384e+01 -1.092652e-01 -1.509892e-02 9.938979e-01 6.537205e+02 +9.938497e-01 -3.031570e-02 1.065070e-01 7.171438e+01 2.841764e-02 9.994099e-01 1.929407e-02 -3.068696e+01 -1.070290e-01 -1.614873e-02 9.941247e-01 6.547945e+02 +9.939173e-01 -3.674719e-02 1.038180e-01 7.184670e+01 3.513761e-02 9.992329e-01 1.729116e-02 -3.068175e+01 -1.043737e-01 -1.353806e-02 9.944459e-01 6.558676e+02 +9.943420e-01 -3.350616e-02 1.008040e-01 7.198816e+01 3.205349e-02 9.993581e-01 1.599661e-02 -3.067209e+01 -1.012753e-01 -1.267498e-02 9.947776e-01 6.569390e+02 +9.946609e-01 -3.463532e-02 9.721149e-02 7.211333e+01 3.315025e-02 9.993083e-01 1.685103e-02 -3.067279e+01 -9.772788e-02 -1.353847e-02 9.951210e-01 6.580225e+02 +9.949190e-01 -3.754032e-02 9.341838e-02 7.222320e+01 3.578310e-02 9.991510e-01 2.041531e-02 -3.067508e+01 -9.410546e-02 -1.696877e-02 9.954176e-01 6.591131e+02 +9.954241e-01 -3.255476e-02 8.983979e-02 7.230515e+01 3.069880e-02 9.992873e-01 2.196395e-02 -3.067904e+01 -9.049078e-02 -1.910546e-02 9.957140e-01 6.602041e+02 +9.958215e-01 -3.203365e-02 8.551933e-02 7.239612e+01 3.067200e-02 9.993817e-01 1.718923e-02 -3.067798e+01 -8.601708e-02 -1.449435e-02 9.961882e-01 6.612827e+02 +9.960623e-01 -3.357534e-02 8.205319e-02 7.249539e+01 3.282684e-02 9.994064e-01 1.045461e-02 -3.067699e+01 -8.235549e-02 -7.719897e-03 9.965731e-01 6.623478e+02 +9.961846e-01 -3.362492e-02 8.053333e-02 7.260412e+01 3.301874e-02 9.994155e-01 8.847418e-03 -3.067195e+01 -8.078375e-02 -6.154551e-03 9.967126e-01 6.634084e+02 +9.963076e-01 -3.176415e-02 7.976349e-02 7.270876e+01 3.079326e-02 9.994363e-01 1.337316e-02 -3.067073e+01 -8.014330e-02 -1.086760e-02 9.967241e-01 6.644825e+02 +9.964066e-01 -2.978375e-02 7.928993e-02 7.281643e+01 2.858642e-02 9.994601e-01 1.619349e-02 -3.066459e+01 -7.972942e-02 -1.386868e-02 9.967200e-01 6.655570e+02 +9.964430e-01 -3.037181e-02 7.860671e-02 7.291701e+01 2.895519e-02 9.993982e-01 1.909935e-02 -3.065735e+01 -7.913949e-02 -1.675534e-02 9.967227e-01 6.666350e+02 +9.964454e-01 -3.108450e-02 7.829659e-02 7.302467e+01 2.943901e-02 9.993226e-01 2.208371e-02 -3.064550e+01 -7.893000e-02 -1.970023e-02 9.966854e-01 6.677096e+02 +9.963507e-01 -2.885512e-02 8.032878e-02 7.313133e+01 2.703137e-02 9.993536e-01 2.369943e-02 -3.062878e+01 -8.096070e-02 -2.144154e-02 9.964866e-01 6.687818e+02 +9.961653e-01 -2.759931e-02 8.302477e-02 7.324255e+01 2.572219e-02 9.993906e-01 2.359466e-02 -3.061144e+01 -8.362536e-02 -2.136859e-02 9.962681e-01 6.698524e+02 +9.959523e-01 -2.581307e-02 8.609785e-02 7.336912e+01 2.440874e-02 9.995519e-01 1.732411e-02 -3.058910e+01 -8.650646e-02 -1.515244e-02 9.961360e-01 6.709151e+02 +9.954575e-01 -2.823410e-02 9.092408e-02 7.350776e+01 2.733028e-02 9.995640e-01 1.117050e-02 -3.057066e+01 -9.119983e-02 -8.634777e-03 9.957951e-01 6.719754e+02 +9.951716e-01 -2.152103e-02 9.576202e-02 7.363733e+01 2.025302e-02 9.996941e-01 1.419379e-02 -3.055182e+01 -9.603819e-02 -1.218578e-02 9.953030e-01 6.730501e+02 +9.945564e-01 -2.384254e-02 1.014360e-01 7.376470e+01 2.158848e-02 9.994963e-01 2.326168e-02 -3.053975e+01 -1.019395e-01 -2.094520e-02 9.945700e-01 6.741337e+02 +9.941230e-01 -1.796067e-02 1.067567e-01 7.389512e+01 1.495382e-02 9.994704e-01 2.889954e-02 -3.051697e+01 -1.072193e-01 -2.713327e-02 9.938650e-01 6.752151e+02 +9.934168e-01 -1.809381e-02 1.131186e-01 7.402771e+01 1.571423e-02 9.996368e-01 2.189260e-02 -3.049429e+01 -1.134736e-01 -1.997090e-02 9.933402e-01 6.762843e+02 +9.926153e-01 -2.070966e-02 1.195246e-01 7.417611e+01 1.950472e-02 9.997465e-01 1.124227e-02 -3.047687e+01 -1.197272e-01 -8.827949e-03 9.927675e-01 6.773528e+02 +9.920126e-01 -2.084930e-02 1.244041e-01 7.431470e+01 1.979351e-02 9.997568e-01 9.716892e-03 -3.047132e+01 -1.245764e-01 -7.176885e-03 9.921840e-01 6.784361e+02 +9.912901e-01 -2.438361e-02 1.294199e-01 7.445960e+01 2.207933e-02 9.995716e-01 1.920999e-02 -3.046835e+01 -1.298328e-01 -1.618517e-02 9.914037e-01 6.795268e+02 +9.905206e-01 -3.156870e-02 1.336876e-01 7.462024e+01 2.821759e-02 9.992401e-01 2.688809e-02 -3.045996e+01 -1.344348e-01 -2.286086e-02 9.906586e-01 6.806262e+02 +9.897398e-01 -3.834585e-02 1.376403e-01 7.478731e+01 3.536692e-02 9.990856e-01 2.402453e-02 -3.044583e+01 -1.384357e-01 -1.891011e-02 9.901908e-01 6.817337e+02 +9.892678e-01 -3.970252e-02 1.406168e-01 7.495066e+01 3.739312e-02 9.991194e-01 1.902871e-02 -3.043053e+01 -1.412484e-01 -1.356639e-02 9.898812e-01 6.828201e+02 +9.889327e-01 -3.987273e-02 1.429069e-01 7.512784e+01 3.802488e-02 9.991544e-01 1.563937e-02 -3.041800e+01 -1.434096e-01 -1.003227e-02 9.896125e-01 6.838891e+02 +9.886958e-01 -3.772092e-02 1.451134e-01 7.530940e+01 3.500886e-02 9.991621e-01 2.119865e-02 -3.040716e+01 -1.457915e-01 -1.587876e-02 9.891879e-01 6.849913e+02 +9.881607e-01 -3.816747e-02 1.485996e-01 7.548538e+01 3.479114e-02 9.990754e-01 2.525551e-02 -3.039717e+01 -1.494261e-01 -1.978655e-02 9.885748e-01 6.861010e+02 +9.877452e-01 -3.671122e-02 1.516966e-01 7.564806e+01 3.344314e-02 9.991514e-01 2.403990e-02 -3.037740e+01 -1.524504e-01 -1.867208e-02 9.881347e-01 6.872087e+02 +9.873479e-01 -3.518736e-02 1.546157e-01 7.581326e+01 3.253123e-02 9.992770e-01 1.967644e-02 -3.035625e+01 -1.551963e-01 -1.439765e-02 9.877787e-01 6.883208e+02 +9.869201e-01 -3.929546e-02 1.563478e-01 7.599700e+01 3.679070e-02 9.991445e-01 1.888331e-02 -3.033560e+01 -1.569561e-01 -1.288418e-02 9.875215e-01 6.894383e+02 +9.864442e-01 -4.136520e-02 1.587983e-01 7.619907e+01 3.871866e-02 9.990554e-01 1.972524e-02 -3.031868e+01 -1.594642e-01 -1.330939e-02 9.871139e-01 6.905573e+02 +9.857522e-01 -4.660292e-02 1.616195e-01 7.641859e+01 4.436827e-02 9.988635e-01 1.741031e-02 -3.030933e+01 -1.622472e-01 -9.991473e-03 9.866995e-01 6.916858e+02 +9.853495e-01 -4.577870e-02 1.642885e-01 7.662078e+01 4.461097e-02 9.989461e-01 1.079241e-02 -3.030568e+01 -1.646095e-01 -3.305223e-03 9.863532e-01 6.928179e+02 +9.848310e-01 -4.882772e-02 1.665046e-01 7.682174e+01 4.764377e-02 9.988027e-01 1.110001e-02 -3.030459e+01 -1.668472e-01 -2.998728e-03 9.859781e-01 6.939615e+02 +9.842247e-01 -5.687697e-02 1.675313e-01 7.704169e+01 5.403791e-02 9.983082e-01 2.146048e-02 -3.030243e+01 -1.684685e-01 -1.206889e-02 9.856331e-01 6.951175e+02 +9.837236e-01 -6.178794e-02 1.687313e-01 7.725575e+01 5.799628e-02 9.979431e-01 2.731294e-02 -3.029411e+01 -1.700718e-01 -1.708259e-02 9.852835e-01 6.962663e+02 +9.831450e-01 -6.740847e-02 1.699475e-01 7.746184e+01 6.395274e-02 9.976211e-01 2.573327e-02 -3.027642e+01 -1.712778e-01 -1.443093e-02 9.851170e-01 6.974114e+02 +9.831377e-01 -6.625870e-02 1.704408e-01 7.766386e+01 6.350026e-02 9.977482e-01 2.159115e-02 -3.025850e+01 -1.714876e-01 -1.040404e-02 9.851313e-01 6.985621e+02 +9.833823e-01 -6.255400e-02 1.704301e-01 7.786092e+01 6.015270e-02 9.980041e-01 1.922225e-02 -3.024818e+01 -1.712923e-01 -8.650995e-03 9.851822e-01 6.997202e+02 +9.835443e-01 -6.175930e-02 1.697835e-01 7.805963e+01 5.921778e-02 9.980447e-01 1.999750e-02 -3.024441e+01 -1.706866e-01 -9.614225e-03 9.852784e-01 7.008912e+02 +9.840561e-01 -5.658516e-02 1.686173e-01 7.825386e+01 5.320241e-02 9.982827e-01 2.451616e-02 -3.023438e+01 -1.697150e-01 -1.515442e-02 9.853766e-01 7.020702e+02 +9.843872e-01 -5.575931e-02 1.669517e-01 7.845696e+01 5.201139e-02 9.982884e-01 2.674143e-02 -3.021799e+01 -1.681570e-01 -1.764053e-02 9.856023e-01 7.032523e+02 +9.847845e-01 -5.282760e-02 1.655563e-01 7.865696e+01 4.840621e-02 9.983579e-01 3.063117e-02 -3.019708e+01 -1.669026e-01 -2.215114e-02 9.857245e-01 7.044443e+02 +9.849286e-01 -5.299298e-02 1.646435e-01 7.884823e+01 4.815196e-02 9.982861e-01 3.325921e-02 -3.017413e+01 -1.661239e-01 -2.483004e-02 9.857922e-01 7.056429e+02 +9.852332e-01 -4.975509e-02 1.638296e-01 7.904665e+01 4.512028e-02 9.984723e-01 3.189345e-02 -3.014933e+01 -1.651662e-01 -2.403044e-02 9.859729e-01 7.068383e+02 +9.851300e-01 -5.291389e-02 1.634596e-01 7.927193e+01 4.904985e-02 9.984152e-01 2.758824e-02 -3.012908e+01 -1.646603e-01 -1.916033e-02 9.861642e-01 7.080335e+02 +9.852632e-01 -5.340580e-02 1.624938e-01 7.950901e+01 5.079849e-02 9.985054e-01 2.016136e-02 -3.011228e+01 -1.633277e-01 -1.160981e-02 9.865035e-01 7.092270e+02 +9.852868e-01 -5.495766e-02 1.618321e-01 7.974896e+01 5.297489e-02 9.984588e-01 1.654493e-02 -3.010286e+01 -1.624920e-01 -7.728465e-03 9.866795e-01 7.104317e+02 +9.854617e-01 -5.369371e-02 1.611902e-01 7.996940e+01 5.137356e-02 9.985076e-01 1.853029e-02 -3.010127e+01 -1.619446e-01 -9.979969e-03 9.867493e-01 7.116483e+02 +9.856206e-01 -4.878916e-02 1.617769e-01 8.017534e+01 4.683634e-02 9.987766e-01 1.586520e-02 -3.010641e+01 -1.623530e-01 -8.060028e-03 9.866998e-01 7.128649e+02 +9.856145e-01 -4.477244e-02 1.629711e-01 8.037782e+01 4.360142e-02 9.989911e-01 1.075698e-02 -3.010432e+01 -1.632883e-01 -3.496463e-03 9.865721e-01 7.140878e+02 +9.854125e-01 -4.589456e-02 1.638780e-01 8.058343e+01 4.436331e-02 9.989309e-01 1.299347e-02 -3.010566e+01 -1.642991e-01 -5.533754e-03 9.863950e-01 7.153211e+02 +9.852527e-01 -4.722860e-02 1.644589e-01 8.079118e+01 4.497678e-02 9.988366e-01 1.739140e-02 -3.010568e+01 -1.650889e-01 -9.738092e-03 9.862306e-01 7.165585e+02 +9.849867e-01 -5.114261e-02 1.648809e-01 8.098499e+01 4.887608e-02 9.986466e-01 1.777712e-02 -3.011306e+01 -1.655669e-01 -9.451490e-03 9.861532e-01 7.177950e+02 +9.848056e-01 -5.296464e-02 1.653864e-01 8.118167e+01 5.008711e-02 9.985129e-01 2.152424e-02 -3.011026e+01 -1.662805e-01 -1.291347e-02 9.859939e-01 7.190340e+02 +9.843883e-01 -5.623394e-02 1.667855e-01 8.137299e+01 5.226423e-02 9.982379e-01 2.809927e-02 -3.010651e+01 -1.680718e-01 -1.894367e-02 9.855927e-01 7.202833e+02 +9.841192e-01 -5.483858e-02 1.688259e-01 8.156853e+01 5.012217e-02 9.982279e-01 3.207577e-02 -3.009543e+01 -1.702857e-01 -2.310446e-02 9.851238e-01 7.215241e+02 +9.836073e-01 -5.400168e-02 1.720479e-01 8.176499e+01 5.014356e-02 9.983852e-01 2.669557e-02 -3.008412e+01 -1.732117e-01 -1.763086e-02 9.847267e-01 7.227575e+02 +9.830679e-01 -5.379820e-02 1.751663e-01 8.197833e+01 5.098751e-02 9.984886e-01 2.051033e-02 -3.007151e+01 -1.760050e-01 -1.123176e-02 9.843251e-01 7.239939e+02 +9.824270e-01 -5.438235e-02 1.785491e-01 8.222695e+01 5.133339e-02 9.984467e-01 2.165551e-02 -3.005622e+01 -1.794494e-01 -1.210943e-02 9.836926e-01 7.252301e+02 +9.817754e-01 -5.497148e-02 1.819212e-01 8.247496e+01 5.167811e-02 9.984035e-01 2.279792e-02 -3.004097e+01 -1.828840e-01 -1.298109e-02 9.830487e-01 7.264633e+02 +9.811107e-01 -5.556768e-02 1.852948e-01 8.272327e+01 5.202291e-02 9.983588e-01 2.394166e-02 -3.002569e+01 -1.863211e-01 -1.384984e-02 9.823912e-01 7.276979e+02 +9.804337e-01 -5.617025e-02 1.886657e-01 8.297157e+01 5.236737e-02 9.983127e-01 2.508538e-02 -3.001041e+01 -1.897564e-01 -1.471462e-02 9.817209e-01 7.289325e+02 +9.797436e-01 -5.677991e-02 1.920381e-01 8.322018e+01 5.271192e-02 9.982652e-01 2.623047e-02 -2.999512e+01 -1.931943e-01 -1.557644e-02 9.810368e-01 7.301686e+02 +9.790421e-01 -5.739512e-02 1.954035e-01 8.346847e+01 5.305570e-02 9.982163e-01 2.737409e-02 -2.997984e+01 -1.966261e-01 -1.643311e-02 9.803408e-01 7.314031e+02 +9.783281e-01 -5.801677e-02 1.987669e-01 8.371681e+01 5.339921e-02 9.981659e-01 2.851793e-02 -2.996456e+01 -2.000568e-01 -1.728589e-02 9.796317e-01 7.326378e+02 +9.776016e-01 -5.864488e-02 2.021284e-01 8.396522e+01 5.374249e-02 9.981142e-01 2.966207e-02 -2.994927e+01 -2.034867e-01 -1.813480e-02 9.789097e-01 7.338729e+02 +9.768643e-01 -5.927803e-02 2.054806e-01 8.421315e+01 5.408476e-02 9.980611e-01 3.080400e-02 -2.993401e+01 -2.069082e-01 -1.897795e-02 9.781762e-01 7.351057e+02 +9.761138e-01 -5.991825e-02 2.088344e-01 8.446142e+01 5.442716e-02 9.980065e-01 3.194740e-02 -2.991873e+01 -2.103323e-01 -1.981803e-02 9.774290e-01 7.363400e+02 +9.753516e-01 -6.056413e-02 2.121824e-01 8.470947e+01 5.476892e-02 9.979506e-01 3.308981e-02 -2.990345e+01 -2.137516e-01 -2.065320e-02 9.766697e-01 7.375733e+02 +9.745768e-01 -6.121646e-02 2.155286e-01 8.495761e+01 5.511047e-02 9.978932e-01 3.423264e-02 -2.988818e+01 -2.171702e-01 -2.148445e-02 9.758972e-01 7.388071e+02 +9.737894e-01 -6.187531e-02 2.188737e-01 8.520589e+01 5.545187e-02 9.978344e-01 3.537605e-02 -2.987289e+01 -2.205886e-01 -2.231186e-02 9.751117e-01 7.400415e+02 +9.729896e-01 -6.254045e-02 2.222163e-01 8.545423e+01 5.579299e-02 9.977742e-01 3.651966e-02 -2.985760e+01 -2.240057e-01 -2.313513e-02 9.743132e-01 7.412762e+02 +9.721518e-01 -6.327814e-02 2.256476e-01 8.569604e+01 5.626310e-02 9.977155e-01 3.739157e-02 -2.984355e+01 -2.274982e-01 -2.365464e-02 9.734911e-01 7.425106e+02 +9.715196e-01 -6.346632e-02 2.283020e-01 8.598828e+01 5.566083e-02 9.976290e-01 4.047390e-02 -2.982041e+01 -2.303294e-01 -2.661370e-02 9.727487e-01 7.437348e+02 +9.708115e-01 -6.571377e-02 2.306661e-01 8.628516e+01 5.818475e-02 9.975320e-01 3.929998e-02 -2.979697e+01 -2.326794e-01 -2.473162e-02 9.722389e-01 7.449486e+02 +9.700838e-01 -6.908829e-02 2.327325e-01 8.658329e+01 6.182543e-02 9.973492e-01 3.836731e-02 -2.977100e+01 -2.347663e-01 -2.283072e-02 9.717836e-01 7.461609e+02 +9.693700e-01 -7.070207e-02 2.352086e-01 8.688112e+01 6.337288e-02 9.972437e-01 3.858462e-02 -2.974671e+01 -2.372883e-01 -2.249693e-02 9.711787e-01 7.473715e+02 +9.691672e-01 -6.619005e-02 2.373476e-01 8.717242e+01 5.809823e-02 9.974712e-01 4.093484e-02 -2.972196e+01 -2.394569e-01 -2.588322e-02 9.705619e-01 7.485865e+02 +9.685869e-01 -6.582699e-02 2.398048e-01 8.747063e+01 5.658976e-02 9.973733e-01 4.521173e-02 -2.969553e+01 -2.421510e-01 -3.022099e-02 9.697677e-01 7.498039e+02 +9.682121e-01 -6.252198e-02 2.421909e-01 8.777020e+01 5.224588e-02 9.974495e-01 4.862872e-02 -2.966277e+01 -2.446136e-01 -3.442943e-02 9.690091e-01 7.510193e+02 +9.679946e-01 -5.811508e-02 2.441498e-01 8.805889e+01 4.723331e-02 9.976218e-01 5.019579e-02 -2.963404e+01 -2.464863e-01 -3.705724e-02 9.684375e-01 7.522334e+02 +9.679682e-01 -5.434358e-02 2.451214e-01 8.835411e+01 4.232621e-02 9.976416e-01 5.403445e-02 -2.959655e+01 -2.474797e-01 -4.192856e-02 9.679854e-01 7.534504e+02 +9.673435e-01 -5.573585e-02 2.472654e-01 8.865914e+01 4.394086e-02 9.976288e-01 5.297061e-02 -2.955854e+01 -2.496315e-01 -4.037571e-02 9.674987e-01 7.546579e+02 +9.672052e-01 -4.591543e-02 2.498119e-01 8.895424e+01 3.665416e-02 9.984617e-01 4.160214e-02 -2.952377e+01 -2.513377e-01 -3.108116e-02 9.674002e-01 7.558539e+02 +9.665330e-01 -4.417537e-02 2.527104e-01 8.926279e+01 3.890148e-02 9.989091e-01 2.583046e-02 -2.950276e+01 -2.535758e-01 -1.513518e-02 9.671971e-01 7.570495e+02 +9.662370e-01 -4.071484e-02 2.544179e-01 8.956883e+01 3.676920e-02 9.991186e-01 2.024700e-02 -2.949034e+01 -2.550180e-01 -1.020866e-02 9.668824e-01 7.582563e+02 +9.655029e-01 -4.314651e-02 2.567929e-01 8.988631e+01 3.680047e-02 9.988880e-01 2.946957e-02 -2.947751e+01 -2.577788e-01 -1.900286e-02 9.660170e-01 7.594696e+02 +9.649408e-01 -4.705583e-02 2.582151e-01 9.020370e+01 3.632444e-02 9.982726e-01 4.617709e-02 -2.945364e+01 -2.599419e-01 -3.517863e-02 9.649832e-01 7.606976e+02 +9.641881e-01 -5.248817e-02 2.599738e-01 9.052950e+01 3.919394e-02 9.976576e-01 5.606296e-02 -2.942003e+01 -2.623075e-01 -4.386583e-02 9.639868e-01 7.619192e+02 +9.633498e-01 -5.595744e-02 2.623473e-01 9.085339e+01 4.605281e-02 9.979802e-01 4.375676e-02 -2.938493e+01 -2.642659e-01 -3.007123e-02 9.639809e-01 7.631075e+02 +9.628027e-01 -5.143825e-02 2.652642e-01 9.117230e+01 4.681931e-02 9.986219e-01 2.371075e-02 -2.935540e+01 -2.661183e-01 -1.040928e-02 9.638841e-01 7.642943e+02 +9.623121e-01 -4.968737e-02 2.673699e-01 9.150442e+01 4.495496e-02 9.987055e-01 2.379611e-02 -2.933518e+01 -2.682061e-01 -1.087968e-02 9.633001e-01 7.654954e+02 +9.617598e-01 -4.857961e-02 2.695520e-01 9.184195e+01 4.064349e-02 9.985623e-01 3.494872e-02 -2.931360e+01 -2.708622e-01 -2.265674e-02 9.623514e-01 7.667133e+02 +9.610036e-01 -4.599144e-02 2.726845e-01 9.218039e+01 3.652498e-02 9.985441e-01 3.969366e-02 -2.928465e+01 -2.741131e-01 -2.818595e-02 9.612843e-01 7.679242e+02 +9.602316e-01 -4.640211e-02 2.753221e-01 9.251836e+01 3.727623e-02 9.985711e-01 3.828972e-02 -2.925369e+01 -2.767054e-01 -2.650403e-02 9.605892e-01 7.691264e+02 +9.596433e-01 -4.587396e-02 2.774535e-01 9.285781e+01 3.839509e-02 9.987394e-01 3.233173e-02 -2.923287e+01 -2.785869e-01 -2.037407e-02 9.601948e-01 7.703229e+02 +9.590215e-01 -4.538942e-02 2.796741e-01 9.319719e+01 3.995593e-02 9.988861e-01 2.510160e-02 -2.921809e+01 -2.805019e-01 -1.289833e-02 9.597667e-01 7.715139e+02 +9.584267e-01 -4.284880e-02 2.821034e-01 9.354199e+01 3.871935e-02 9.990459e-01 2.019920e-02 -2.921080e+01 -2.826997e-01 -8.436590e-03 9.591713e-01 7.727034e+02 +9.575746e-01 -4.505630e-02 2.846416e-01 9.389043e+01 3.965882e-02 9.989079e-01 2.470060e-02 -2.920524e+01 -2.854437e-01 -1.236411e-02 9.583157e-01 7.739037e+02 +9.567581e-01 -4.917182e-02 2.866987e-01 9.425028e+01 4.093275e-02 9.985604e-01 3.466463e-02 -2.918863e+01 -2.879904e-01 -2.143030e-02 9.573934e-01 7.751048e+02 +9.559302e-01 -5.516472e-02 2.883650e-01 9.461527e+01 4.444787e-02 9.980604e-01 4.358598e-02 -2.916213e+01 -2.902100e-01 -2.884794e-02 9.565280e-01 7.763020e+02 +9.551709e-01 -5.972087e-02 2.899692e-01 9.497543e+01 4.938701e-02 9.978608e-01 4.283245e-02 -2.913472e+01 -2.919069e-01 -2.659160e-02 9.560770e-01 7.774825e+02 +9.543234e-01 -5.901408e-02 2.928895e-01 9.533213e+01 5.053332e-02 9.980572e-01 3.644480e-02 -2.911474e+01 -2.944712e-01 -1.997944e-02 9.554514e-01 7.786577e+02 +9.537486e-01 -5.234581e-02 2.960130e-01 9.568725e+01 4.555782e-02 9.985175e-01 2.978757e-02 -2.910482e+01 -2.971334e-01 -1.492415e-02 9.547193e-01 7.798332e+02 +9.530384e-01 -4.778726e-02 2.990557e-01 9.604379e+01 4.258129e-02 9.988070e-01 2.390409e-02 -2.910087e+01 -2.998412e-01 -1.004733e-02 9.539361e-01 7.810087e+02 +9.523615e-01 -4.686649e-02 3.013489e-01 9.640290e+01 4.106636e-02 9.988295e-01 2.555716e-02 -2.909844e+01 -3.021939e-01 -1.196435e-02 9.531713e-01 7.821877e+02 +9.518214e-01 -4.594247e-02 3.031919e-01 9.676459e+01 3.829270e-02 9.987815e-01 3.113106e-02 -2.909878e+01 -3.042527e-01 -1.802117e-02 9.524208e-01 7.833691e+02 +9.512802e-01 -4.625404e-02 3.048387e-01 9.712740e+01 3.762850e-02 9.987093e-01 3.411347e-02 -2.909039e+01 -3.060232e-01 -2.098084e-02 9.517928e-01 7.845469e+02 +9.504115e-01 -5.054976e-02 3.068595e-01 9.749835e+01 4.181348e-02 9.985128e-01 3.498206e-02 -2.908062e+01 -3.081714e-01 -2.041649e-02 9.511117e-01 7.857166e+02 +9.498979e-01 -5.061906e-02 3.084342e-01 9.785797e+01 4.169424e-02 9.985008e-01 3.546267e-02 -2.907268e+01 -3.097669e-01 -2.082598e-02 9.505844e-01 7.868877e+02 +9.491780e-01 -5.414233e-02 3.100481e-01 9.823208e+01 4.480252e-02 9.983040e-01 3.717150e-02 -2.905756e+01 -3.115348e-01 -2.139143e-02 9.499939e-01 7.880526e+02 +9.485568e-01 -5.454593e-02 3.118732e-01 9.860436e+01 4.701861e-02 9.983937e-01 3.161059e-02 -2.904575e+01 -3.130964e-01 -1.532060e-02 9.495977e-01 7.892081e+02 +9.479520e-01 -5.015738e-02 3.144380e-01 9.897770e+01 4.463799e-02 9.986970e-01 2.473414e-02 -2.903655e+01 -3.152689e-01 -9.410901e-03 9.489557e-01 7.903639e+02 +9.474896e-01 -4.602944e-02 3.164566e-01 9.934753e+01 4.055216e-02 9.988921e-01 2.387595e-02 -2.903372e+01 -3.172050e-01 -9.789218e-03 9.483064e-01 7.915233e+02 +9.466508e-01 -4.525559e-02 3.190678e-01 9.972448e+01 3.808288e-02 9.988627e-01 2.868650e-02 -2.902846e+01 -3.200031e-01 -1.500508e-02 9.472976e-01 7.926834e+02 +9.455377e-01 -4.707906e-02 3.220902e-01 1.001027e+02 3.797208e-02 9.986829e-01 3.450286e-02 -2.902026e+01 -3.232903e-01 -2.039332e-02 9.460800e-01 7.938424e+02 +9.447490e-01 -4.732633e-02 3.243603e-01 1.004902e+02 3.762330e-02 9.986388e-01 3.612446e-02 -2.900528e+01 -3.256284e-01 -2.192504e-02 9.452435e-01 7.949913e+02 +9.438244e-01 -5.114709e-02 3.264651e-01 1.008865e+02 4.233722e-02 9.985233e-01 3.403939e-02 -2.899090e+01 -3.277240e-01 -1.830558e-02 9.445961e-01 7.961389e+02 +9.430600e-01 -5.273740e-02 3.284153e-01 1.012817e+02 4.475367e-02 9.984909e-01 3.182685e-02 -2.897795e+01 -3.295981e-01 -1.531684e-02 9.439970e-01 7.972788e+02 +9.419895e-01 -5.525919e-02 3.310623e-01 1.016782e+02 4.767977e-02 9.983821e-01 3.097890e-02 -2.896522e+01 -3.322385e-01 -1.339682e-02 9.431002e-01 7.984198e+02 +9.412388e-01 -5.545279e-02 3.331584e-01 1.020757e+02 4.789402e-02 9.983754e-01 3.086519e-02 -2.895036e+01 -3.343287e-01 -1.309522e-02 9.423655e-01 7.995599e+02 +9.402979e-01 -5.744465e-02 3.354698e-01 1.024801e+02 4.850355e-02 9.982103e-01 3.497799e-02 -2.893212e+01 -3.368787e-01 -1.661825e-02 9.414013e-01 8.007012e+02 +9.395208e-01 -5.762621e-02 3.376092e-01 1.028857e+02 4.867947e-02 9.982040e-01 3.491417e-02 -2.890691e+01 -3.390148e-01 -1.636795e-02 9.406386e-01 8.018340e+02 +9.384742e-01 -5.686650e-02 3.406353e-01 1.032915e+02 5.008848e-02 9.983333e-01 2.866696e-02 -2.887859e+01 -3.416977e-01 -9.841294e-03 9.397583e-01 8.029571e+02 +9.373614e-01 -5.994271e-02 3.431625e-01 1.037068e+02 5.427824e-02 9.981847e-01 2.609719e-02 -2.885671e+01 -3.441039e-01 -5.836243e-03 9.389134e-01 8.040802e+02 +9.368732e-01 -5.897086e-02 3.446609e-01 1.041184e+02 5.260737e-02 9.982284e-01 2.779531e-02 -2.884004e+01 -3.456894e-01 -7.908973e-03 9.383156e-01 8.052058e+02 +9.361356e-01 -5.992735e-02 3.464953e-01 1.045370e+02 5.335947e-02 9.981693e-01 2.847354e-02 -2.882538e+01 -3.475673e-01 -8.166289e-03 9.376194e-01 8.063277e+02 +9.355697e-01 -5.630958e-02 3.486239e-01 1.049483e+02 4.961244e-02 9.983727e-01 2.811644e-02 -2.881242e+01 -3.496398e-01 -9.008807e-03 9.368408e-01 8.074492e+02 +9.346157e-01 -5.460614e-02 3.514423e-01 1.053600e+02 4.720615e-02 9.984466e-01 2.959721e-02 -2.879983e+01 -3.525125e-01 -1.107178e-02 9.357416e-01 8.085704e+02 +9.339018e-01 -5.420547e-02 3.533967e-01 1.057726e+02 4.579325e-02 9.984341e-01 3.212877e-02 -2.878198e+01 -3.545849e-01 -1.382193e-02 9.349216e-01 8.096876e+02 +9.332073e-01 -5.406993e-02 3.552474e-01 1.061924e+02 4.523992e-02 9.984269e-01 3.312244e-02 -2.876539e+01 -3.564794e-01 -1.483874e-02 9.341853e-01 8.107980e+02 +9.325527e-01 -5.520282e-02 3.567888e-01 1.066159e+02 4.595502e-02 9.983527e-01 3.435201e-02 -2.874789e+01 -3.580974e-01 -1.563882e-02 9.335532e-01 8.119090e+02 +9.318848e-01 -5.346011e-02 3.587936e-01 1.070415e+02 4.470917e-02 9.984664e-01 3.264923e-02 -2.872953e+01 -3.599887e-01 -1.438395e-02 9.328457e-01 8.130150e+02 +9.310076e-01 -5.156705e-02 3.613389e-01 1.074670e+02 4.405199e-02 9.986079e-01 2.901026e-02 -2.871716e+01 -3.623319e-01 -1.109107e-02 9.319831e-01 8.141171e+02 +9.304280e-01 -4.874143e-02 3.632191e-01 1.078939e+02 4.180250e-02 9.987625e-01 2.694490e-02 -2.870172e+01 -3.640829e-01 -9.886818e-03 9.313140e-01 8.152171e+02 +9.295862e-01 -5.131342e-02 3.650157e-01 1.083318e+02 4.416514e-02 9.986342e-01 2.791122e-02 -2.867857e+01 -3.659493e-01 -9.824919e-03 9.305828e-01 8.163082e+02 +9.290315e-01 -5.579576e-02 3.657695e-01 1.087750e+02 4.661358e-02 9.983378e-01 3.389439e-02 -2.865765e+01 -3.670527e-01 -1.443913e-02 9.300880e-01 8.174115e+02 +9.286017e-01 -5.919774e-02 3.663259e-01 1.092148e+02 4.714066e-02 9.980141e-01 4.178053e-02 -2.863824e+01 -3.680717e-01 -2.152863e-02 9.295481e-01 8.185110e+02 +9.286568e-01 -5.930871e-02 3.661682e-01 1.096470e+02 4.487758e-02 9.978479e-01 4.780648e-02 -2.860994e+01 -3.682155e-01 -2.796306e-02 9.293198e-01 8.196064e+02 +9.285357e-01 -5.700140e-02 3.668410e-01 1.100776e+02 4.387753e-02 9.980665e-01 4.402273e-02 -2.857205e+01 -3.686410e-01 -2.478060e-02 9.292414e-01 8.206898e+02 +9.284894e-01 -5.026356e-02 3.679418e-01 1.104992e+02 3.961660e-02 9.985503e-01 3.643813e-02 -2.853838e+01 -3.692399e-01 -1.925581e-02 9.291345e-01 8.217623e+02 +9.282696e-01 -4.637861e-02 3.690050e-01 1.109185e+02 3.544543e-02 9.987100e-01 3.635689e-02 -2.851472e+01 -3.702152e-01 -2.066945e-02 9.287160e-01 8.228422e+02 +9.282283e-01 -4.408145e-02 3.693901e-01 1.113370e+02 2.987792e-02 9.985808e-01 4.408715e-02 -2.848760e+01 -3.708093e-01 -2.988633e-02 9.282280e-01 8.239168e+02 +9.276094e-01 -4.422824e-02 3.709241e-01 1.117573e+02 2.650170e-02 9.982558e-01 5.275440e-02 -2.845602e+01 -3.726104e-01 -3.910536e-02 9.271635e-01 8.249869e+02 +9.265787e-01 -4.442082e-02 3.734686e-01 1.121747e+02 2.481597e-02 9.980576e-01 5.714161e-02 -2.841681e+01 -3.752814e-01 -4.367821e-02 9.258812e-01 8.260415e+02 +9.251689e-01 -4.776833e-02 3.765378e-01 1.125959e+02 2.639648e-02 9.977445e-01 6.171862e-02 -2.837441e+01 -3.786367e-01 -4.716087e-02 9.243430e-01 8.270827e+02 +9.242209e-01 -5.187661e-02 3.783181e-01 1.130156e+02 2.830066e-02 9.973098e-01 6.761769e-02 -2.833307e+01 -3.808081e-01 -5.178702e-02 9.232027e-01 8.281157e+02 +9.230866e-01 -5.909668e-02 3.800248e-01 1.134376e+02 3.390556e-02 9.967810e-01 7.264971e-02 -2.828076e+01 -3.830948e-01 -5.417701e-02 9.221188e-01 8.291377e+02 +9.220291e-01 -6.090418e-02 3.822998e-01 1.138625e+02 3.449127e-02 9.965435e-01 7.557345e-02 -2.822414e+01 -3.855811e-01 -5.649490e-02 9.209427e-01 8.301530e+02 +9.205447e-01 -6.164718e-02 3.857424e-01 1.142868e+02 3.426354e-02 9.964055e-01 7.747264e-02 -2.816168e+01 -3.891318e-01 -5.810011e-02 9.193480e-01 8.311635e+02 +9.190136e-01 -5.607672e-02 3.902172e-01 1.147059e+02 2.779740e-02 9.965853e-01 7.774914e-02 -2.810274e+01 -3.932446e-01 -6.060549e-02 9.174342e-01 8.321645e+02 +9.169432e-01 -4.402237e-02 3.965820e-01 1.151184e+02 1.547098e-02 9.970704e-01 7.490860e-02 -2.804773e+01 -3.987178e-01 -6.255141e-02 9.149379e-01 8.331665e+02 +9.140018e-01 -3.863417e-02 4.038666e-01 1.155396e+02 1.123549e-02 9.974842e-01 6.999273e-02 -2.799062e+01 -4.055546e-01 -5.943583e-02 9.121364e-01 8.341537e+02 +9.105329e-01 -3.205521e-02 4.121923e-01 1.159745e+02 3.038195e-03 9.974816e-01 7.086039e-02 -2.793343e+01 -4.134256e-01 -6.326838e-02 9.083371e-01 8.351417e+02 +9.063640e-01 -3.057357e-02 4.213901e-01 1.164235e+02 -1.024680e-03 9.972163e-01 7.455609e-02 -2.786826e+01 -4.224965e-01 -6.800674e-02 9.038095e-01 8.361289e+02 +9.020517e-01 -3.678339e-02 4.300579e-01 1.169004e+02 1.084576e-03 9.965521e-01 8.296143e-02 -2.779706e+01 -4.316267e-01 -7.436906e-02 8.989814e-01 8.371086e+02 +8.973942e-01 -4.214831e-02 4.392121e-01 1.173858e+02 2.233378e-03 9.958482e-01 9.100182e-02 -2.771964e+01 -4.412241e-01 -8.068356e-02 8.937624e-01 8.380750e+02 +8.928589e-01 -5.407906e-02 4.470777e-01 1.178954e+02 1.042511e-02 9.949795e-01 9.953396e-02 -2.763253e+01 -4.502159e-01 -8.420894e-02 8.889401e-01 8.390372e+02 +8.881066e-01 -6.301155e-02 4.552980e-01 1.184052e+02 1.661513e-02 9.943123e-01 1.051996e-01 -2.753887e+01 -4.593372e-01 -8.586358e-02 8.841022e-01 8.399868e+02 +8.825038e-01 -7.319465e-02 4.645747e-01 1.189258e+02 2.572942e-02 9.938496e-01 1.077075e-01 -2.745027e+01 -4.696010e-01 -8.309903e-02 8.789593e-01 8.409327e+02 +8.772394e-01 -7.647137e-02 4.739233e-01 1.194476e+02 2.600632e-02 9.933512e-01 1.121472e-01 -2.735742e+01 -4.793483e-01 -8.605493e-02 8.733955e-01 8.418851e+02 +8.711058e-01 -8.752610e-02 4.832327e-01 1.199831e+02 3.211518e-02 9.920361e-01 1.217909e-01 -2.725342e+01 -4.900442e-01 -9.057362e-02 8.669793e-01 8.428248e+02 +8.647244e-01 -1.030015e-01 4.915715e-01 1.205396e+02 4.143880e-02 9.900395e-01 1.345531e-01 -2.713858e+01 -5.005344e-01 -9.598115e-02 8.603795e-01 8.437655e+02 +8.590184e-01 -1.053734e-01 5.009829e-01 1.210886e+02 4.017401e-02 9.894450e-01 1.392283e-01 -2.701916e+01 -5.103659e-01 -9.947319e-02 8.541847e-01 8.447019e+02 +8.529017e-01 -1.020379e-01 5.120030e-01 1.216372e+02 4.091367e-02 9.907616e-01 1.292960e-01 -2.690638e+01 -5.204660e-01 -8.932888e-02 8.491969e-01 8.456108e+02 +8.483346e-01 -1.030705e-01 5.193312e-01 1.222546e+02 4.113589e-02 9.907346e-01 1.294328e-01 -2.678900e+01 -5.278600e-01 -8.843912e-02 8.447143e-01 8.464507e+02 +8.437020e-01 -1.040938e-01 5.266227e-01 1.228721e+02 4.135654e-02 9.907076e-01 1.295689e-01 -2.667158e+01 -5.352164e-01 -8.753827e-02 8.401669e-01 8.472907e+02 +8.390055e-01 -1.051076e-01 5.338748e-01 1.234896e+02 4.157554e-02 9.906807e-01 1.297046e-01 -2.655416e+01 -5.425324e-01 -8.662669e-02 8.355563e-01 8.481307e+02 +8.342448e-01 -1.061119e-01 5.410877e-01 1.241071e+02 4.179293e-02 9.906538e-01 1.298396e-01 -2.643673e+01 -5.498081e-01 -8.570436e-02 8.308825e-01 8.489708e+02 +8.294214e-01 -1.071063e-01 5.482595e-01 1.247244e+02 4.200867e-02 9.906271e-01 1.299740e-01 -2.631930e+01 -5.570417e-01 -8.477159e-02 8.261466e-01 8.498108e+02 +8.245345e-01 -1.080909e-01 5.553912e-01 1.253418e+02 4.222281e-02 9.906004e-01 1.301079e-01 -2.620186e+01 -5.642342e-01 -8.382824e-02 8.213480e-01 8.506508e+02 +8.195922e-01 -1.090642e-01 5.624711e-01 1.259583e+02 4.243502e-02 9.905738e-01 1.302409e-01 -2.608458e+01 -5.713737e-01 -8.287593e-02 8.164947e-01 8.514896e+02 +8.145805e-01 -1.100288e-01 5.695193e-01 1.265755e+02 4.264593e-02 9.905473e-01 1.303735e-01 -2.596713e+01 -5.784807e-01 -8.191199e-02 8.115728e-01 8.523296e+02 +8.095094e-01 -1.109828e-01 5.765218e-01 1.271925e+02 4.285513e-02 9.905210e-01 1.305053e-01 -2.584973e+01 -5.855407e-01 -8.093835e-02 8.065922e-01 8.531691e+02 +8.043760e-01 -1.119267e-01 5.834824e-01 1.278095e+02 4.306278e-02 9.904947e-01 1.306365e-01 -2.573231e+01 -5.925579e-01 -7.995450e-02 8.015500e-01 8.540088e+02 +7.991808e-01 -1.128603e-01 5.904005e-01 1.284266e+02 4.326885e-02 9.904684e-01 1.307671e-01 -2.561486e+01 -5.995314e-01 -7.896057e-02 7.964466e-01 8.548486e+02 +7.939272e-01 -1.137830e-01 5.972714e-01 1.290433e+02 4.347325e-02 9.904423e-01 1.308969e-01 -2.549747e+01 -6.064567e-01 -7.795724e-02 7.912856e-01 8.556880e+02 +7.886125e-01 -1.146953e-01 6.040988e-01 1.296601e+02 4.367610e-02 9.904164e-01 1.310260e-01 -2.538005e+01 -6.133373e-01 -7.694403e-02 7.860641e-01 8.565275e+02 +7.832381e-01 -1.155969e-01 6.108809e-01 1.302768e+02 4.387737e-02 9.903905e-01 1.311544e-01 -2.526263e+01 -6.201716e-01 -7.592123e-02 7.807836e-01 8.573670e+02 +7.778049e-01 -1.164877e-01 6.176166e-01 1.308934e+02 4.407705e-02 9.903647e-01 1.312820e-01 -2.514522e+01 -6.269584e-01 -7.488903e-02 7.754448e-01 8.582064e+02 +7.723123e-01 -1.173676e-01 6.243065e-01 1.315100e+02 4.427518e-02 9.903390e-01 1.314089e-01 -2.502779e+01 -6.336982e-01 -7.384739e-02 7.700474e-01 8.590457e+02 +7.667872e-01 -1.182973e-01 6.309066e-01 1.321274e+02 4.447461e-02 9.903005e-01 1.316318e-01 -2.491045e+01 -6.403588e-01 -7.287421e-02 7.646109e-01 8.598836e+02 +7.627736e-01 -1.220298e-01 6.350474e-01 1.327484e+02 4.468878e-02 9.896330e-01 1.364895e-01 -2.479544e+01 -6.451197e-01 -7.573109e-02 7.603192e-01 8.606092e+02 +7.583622e-01 -1.270013e-01 6.393415e-01 1.333721e+02 4.733149e-02 9.889755e-01 1.403112e-01 -2.468463e+01 -6.501127e-01 -7.614569e-02 7.560127e-01 8.613188e+02 +7.545088e-01 -1.314973e-01 6.429814e-01 1.339922e+02 5.222328e-02 9.886444e-01 1.409079e-01 -2.457601e+01 -6.542089e-01 -7.273761e-02 7.528080e-01 8.620148e+02 +7.504093e-01 -1.299029e-01 6.480827e-01 1.346039e+02 5.648026e-02 9.895132e-01 1.329419e-01 -2.446811e+01 -6.585559e-01 -6.315697e-02 7.498768e-01 8.626906e+02 +7.468482e-01 -1.268047e-01 6.527928e-01 1.352085e+02 5.677461e-02 9.902256e-01 1.273961e-01 -2.436063e+01 -6.625666e-01 -5.808349e-02 7.467475e-01 8.633663e+02 +7.430802e-01 -1.285718e-01 6.567352e-01 1.358146e+02 5.831727e-02 9.900779e-01 1.278471e-01 -2.425740e+01 -6.666565e-01 -5.670165e-02 7.432052e-01 8.640353e+02 +7.399549e-01 -1.305735e-01 6.598616e-01 1.364174e+02 5.700893e-02 9.896226e-01 1.318981e-01 -2.415595e+01 -6.702363e-01 -5.998063e-02 7.397199e-01 8.646962e+02 +7.372768e-01 -1.321612e-01 6.625378e-01 1.370123e+02 5.485132e-02 9.891515e-01 1.362742e-01 -2.405413e+01 -6.733604e-01 -6.413073e-02 7.365276e-01 8.653504e+02 +7.349802e-01 -1.353324e-01 6.644466e-01 1.376048e+02 5.685633e-02 9.887305e-01 1.384897e-01 -2.395009e+01 -6.757007e-01 -6.400920e-02 7.343918e-01 8.659883e+02 +7.335722e-01 -1.383962e-01 6.653709e-01 1.381876e+02 6.103612e-02 9.885056e-01 1.383154e-01 -2.385098e+01 -6.768652e-01 -6.085267e-02 7.335873e-01 8.666106e+02 +7.330702e-01 -1.360437e-01 6.664085e-01 1.387515e+02 6.095574e-02 9.889901e-01 1.348439e-01 -2.375646e+01 -6.774160e-01 -5.822858e-02 7.332918e-01 8.672268e+02 +7.330659e-01 -1.290374e-01 6.678052e-01 1.392982e+02 5.858665e-02 9.901691e-01 1.270146e-01 -2.366449e+01 -6.776297e-01 -5.398562e-02 7.334190e-01 8.678359e+02 +7.337944e-01 -1.234083e-01 6.680690e-01 1.398425e+02 6.088228e-02 9.913517e-01 1.162545e-01 -2.359159e+01 -6.766381e-01 -4.463330e-02 7.349616e-01 8.684357e+02 +7.341606e-01 -1.180754e-01 6.686303e-01 1.403827e+02 6.474172e-02 9.924497e-01 1.041729e-01 -2.352565e+01 -6.758822e-01 -3.319132e-02 7.362618e-01 8.690247e+02 +7.352396e-01 -1.123527e-01 6.684307e-01 1.409192e+02 6.476065e-02 9.932990e-01 9.572450e-02 -2.345190e+01 -6.747064e-01 -2.709244e-02 7.375888e-01 8.696093e+02 +7.366273e-01 -1.079114e-01 6.676342e-01 1.414481e+02 6.102375e-02 9.937666e-01 9.329509e-02 -2.337384e+01 -6.735402e-01 -2.798216e-02 7.386207e-01 8.701957e+02 +7.374570e-01 -1.089368e-01 6.665508e-01 1.419738e+02 5.857358e-02 9.935038e-01 9.756736e-02 -2.330517e+01 -6.728494e-01 -3.290946e-02 7.390471e-01 8.707743e+02 +7.376941e-01 -1.076244e-01 6.665016e-01 1.424860e+02 5.680645e-02 9.936061e-01 9.756992e-02 -2.324030e+01 -6.727410e-01 -3.411516e-02 7.390911e-01 8.713384e+02 +7.374171e-01 -1.008827e-01 6.678613e-01 1.429801e+02 5.172096e-02 9.943137e-01 9.308688e-02 -2.317648e+01 -6.734545e-01 -3.410142e-02 7.384416e-01 8.718904e+02 +7.366478e-01 -9.585265e-02 6.694493e-01 1.434648e+02 4.725918e-02 9.947808e-01 9.043106e-02 -2.311572e+01 -6.746233e-01 -3.497820e-02 7.373329e-01 8.724295e+02 +7.354178e-01 -9.228759e-02 6.713000e-01 1.439408e+02 4.349191e-02 9.950680e-01 8.915197e-02 -2.306146e+01 -6.762167e-01 -3.636782e-02 7.358045e-01 8.729540e+02 +7.326815e-01 -8.973178e-02 6.746303e-01 1.444058e+02 4.034514e-02 9.952533e-01 8.856069e-02 -2.300941e+01 -6.793748e-01 -3.766872e-02 7.328239e-01 8.734586e+02 +7.287033e-01 -8.584933e-02 6.794273e-01 1.448598e+02 3.538793e-02 9.955064e-01 8.783320e-02 -2.296315e+01 -6.839146e-01 -3.996081e-02 7.284668e-01 8.739469e+02 +7.231290e-01 -8.118611e-02 6.859251e-01 1.453001e+02 3.015694e-02 9.958322e-01 8.607411e-02 -2.291557e+01 -6.900543e-01 -4.155728e-02 7.225635e-01 8.744129e+02 +7.161789e-01 -7.721328e-02 6.936325e-01 1.457300e+02 2.560304e-02 9.960989e-01 8.444776e-02 -2.287378e+01 -6.974470e-01 -4.272060e-02 7.153618e-01 8.748517e+02 +7.078132e-01 -7.411996e-02 7.025004e-01 1.461488e+02 2.139288e-02 9.962730e-01 8.356090e-02 -2.283382e+01 -7.060757e-01 -4.411699e-02 7.067607e-01 8.752692e+02 +6.978310e-01 -7.463096e-02 7.123638e-01 1.465590e+02 2.066134e-02 9.962404e-01 8.413154e-02 -2.279581e+01 -7.159644e-01 -4.399120e-02 6.967494e-01 8.756616e+02 +6.872465e-01 -7.388013e-02 7.226577e-01 1.469554e+02 1.983332e-02 9.963522e-01 8.299954e-02 -2.276350e+01 -7.261535e-01 -4.270844e-02 6.862047e-01 8.760151e+02 +6.667962e-01 -7.014438e-02 7.419317e-01 1.473034e+02 1.824450e-02 9.967986e-01 7.784338e-02 -2.275154e+01 -7.450168e-01 -3.836949e-02 6.659412e-01 8.762168e+02 +6.458084e-01 -6.620639e-02 7.606236e-01 1.476508e+02 1.663935e-02 9.972170e-01 7.267237e-02 -2.273955e+01 -7.633182e-01 -3.427614e-02 6.451127e-01 8.764184e+02 +6.243218e-01 -6.208163e-02 7.786965e-01 1.479968e+02 1.502012e-02 9.976067e-01 6.749185e-02 -2.272760e+01 -7.810228e-01 -3.044052e-02 6.237601e-01 8.766195e+02 +6.023560e-01 -5.778230e-02 7.961335e-01 1.483416e+02 1.338744e-02 9.979675e-01 6.230219e-02 -2.271571e+01 -7.981153e-01 -2.686991e-02 6.019053e-01 8.768200e+02 +5.799003e-01 -5.331466e-02 8.129411e-01 1.486855e+02 1.173960e-02 9.982996e-01 5.709664e-02 -2.270377e+01 -8.146028e-01 -2.356676e-02 5.795401e-01 8.770206e+02 +5.569587e-01 -4.868787e-02 8.291119e-01 1.490289e+02 1.007609e-02 9.986029e-01 5.187223e-02 -2.269176e+01 -8.304791e-01 -2.053648e-02 5.566711e-01 8.772216e+02 +5.335452e-01 -4.391321e-02 8.446308e-01 1.493718e+02 8.397165e-03 9.988770e-01 4.662822e-02 -2.267965e+01 -8.457298e-01 -1.778576e-02 5.333148e-01 8.774231e+02 +5.097325e-01 -3.901431e-02 8.594479e-01 1.497132e+02 6.707407e-03 9.991211e-01 4.137661e-02 -2.266764e+01 -8.603068e-01 -1.532634e-02 5.095462e-01 8.776239e+02 +4.853833e-01 -3.397145e-02 8.736412e-01 1.500556e+02 4.995831e-03 9.993363e-01 3.608347e-02 -2.265522e+01 -8.742871e-01 -1.314975e-02 4.852309e-01 8.778275e+02 +4.608259e-01 -2.886192e-02 8.870211e-01 1.503940e+02 3.285657e-03 9.995197e-01 3.081543e-02 -2.264338e+01 -8.874844e-01 -1.128610e-02 4.606994e-01 8.780270e+02 +4.358320e-01 -2.364713e-02 8.997174e-01 1.507325e+02 1.559222e-03 9.996731e-01 2.551895e-02 -2.263133e+01 -9.000267e-01 -9.719117e-03 4.357264e-01 8.782279e+02 +4.104564e-01 -1.834758e-02 9.116956e-01 1.510705e+02 -1.803058e-04 9.997959e-01 2.020174e-02 -2.261919e+01 -9.118802e-01 -8.456322e-03 4.103693e-01 8.784294e+02 +3.847732e-01 -1.298787e-02 9.229198e-01 1.514070e+02 -1.928513e-03 9.998875e-01 1.487501e-02 -2.260713e+01 -9.230091e-01 -7.503371e-03 3.847049e-01 8.786305e+02 +3.587780e-01 -7.576216e-03 9.333922e-01 1.517426e+02 -3.686628e-03 9.999477e-01 9.533505e-03 -2.259507e+01 -9.334156e-01 -6.861483e-03 3.587313e-01 8.788317e+02 +3.325198e-01 -2.132018e-03 9.430939e-01 1.520767e+02 -5.452096e-03 9.999764e-01 4.182928e-03 -2.258310e+01 -9.430805e-01 -6.532747e-03 3.325003e-01 8.790324e+02 +3.059857e-01 3.348414e-03 9.520302e-01 1.524100e+02 -7.236741e-03 9.999731e-01 -1.191127e-03 -2.257098e+01 -9.520086e-01 -6.525130e-03 3.060017e-01 8.792333e+02 +2.679835e-01 7.414380e-03 9.633950e-01 1.528081e+02 -6.089512e-03 9.999634e-01 -6.001925e-03 -2.256937e+01 -9.634042e-01 -4.258191e-03 2.680189e-01 8.793420e+02 +2.289849e-01 1.143980e-02 9.733628e-01 1.532073e+02 -4.933162e-03 9.999317e-01 -1.059153e-02 -2.257547e+01 -9.734174e-01 -2.376458e-03 2.290257e-01 8.793676e+02 +1.889167e-01 1.611032e-02 9.818610e-01 1.536330e+02 -8.953348e-04 9.998678e-01 -1.623351e-02 -2.257850e+01 -9.819927e-01 2.187684e-03 1.889062e-01 8.794463e+02 +1.479723e-01 2.303901e-02 9.887231e-01 1.540687e+02 -1.129613e-03 9.997319e-01 -2.312648e-02 -2.258200e+01 -9.889908e-01 2.305200e-03 1.479586e-01 8.795169e+02 +1.052109e-01 3.109898e-02 9.939636e-01 1.545000e+02 -4.747805e-03 9.995152e-01 -3.077013e-02 -2.260424e+01 -9.944386e-01 -1.481794e-03 1.053076e-01 8.794960e+02 +6.040175e-02 3.945020e-02 9.973943e-01 1.549580e+02 -1.024669e-02 9.991905e-01 -3.890072e-02 -2.261158e+01 -9.981215e-01 -7.870322e-03 6.075708e-02 8.795423e+02 +1.476744e-02 4.629830e-02 9.988185e-01 1.554133e+02 -1.503631e-02 9.988247e-01 -4.607629e-02 -2.263535e+01 -9.997778e-01 -1.433811e-02 1.544624e-02 8.794794e+02 +-3.156074e-02 5.150249e-02 9.981741e-01 1.558986e+02 -1.412210e-02 9.985489e-01 -5.196836e-02 -2.264924e+01 -9.994020e-01 -1.573647e-02 -3.078761e-02 8.794743e+02 +-7.795507e-02 5.403515e-02 9.954915e-01 1.563974e+02 -8.228069e-03 9.984612e-01 -5.484068e-02 -2.267322e+01 -9.969229e-01 -1.246608e-02 -7.739050e-02 8.794265e+02 +-1.229291e-01 5.557208e-02 9.908583e-01 1.568887e+02 -3.816645e-03 9.983971e-01 -5.646841e-02 -2.270308e+01 -9.924081e-01 -1.072337e-02 -1.225199e-01 8.792723e+02 +-1.637402e-01 5.694397e-02 9.848587e-01 1.574131e+02 -3.499170e-03 9.982928e-01 -5.830251e-02 -2.273891e+01 -9.864972e-01 -1.299265e-02 -1.632614e-01 8.791841e+02 +-2.026970e-01 5.697139e-02 9.775829e-01 1.579481e+02 -3.970611e-03 9.982501e-01 -5.899913e-02 -2.277576e+01 -9.792334e-01 -1.584055e-02 -2.021161e-01 8.790762e+02 +-2.401689e-01 5.824595e-02 9.689821e-01 1.584781e+02 -4.104930e-03 9.981284e-01 -6.101539e-02 -2.281826e+01 -9.707224e-01 -1.863160e-02 -2.394803e-01 8.788819e+02 +-2.759842e-01 5.836296e-02 9.593886e-01 1.590258e+02 -2.932955e-03 9.980990e-01 -6.156157e-02 -2.286018e+01 -9.611577e-01 -1.980386e-02 -2.752883e-01 8.787221e+02 +-3.089319e-01 5.729502e-02 9.493569e-01 1.595731e+02 -3.666078e-03 9.981046e-01 -6.143002e-02 -2.290343e+01 -9.510771e-01 -2.245810e-02 -3.081363e-01 8.784925e+02 +-3.391856e-01 5.804958e-02 9.389267e-01 1.601349e+02 -2.179807e-03 9.980431e-01 -6.249194e-02 -2.294200e+01 -9.407169e-01 -2.324304e-02 -3.383953e-01 8.782875e+02 +-3.662008e-01 5.827750e-02 9.287092e-01 1.607031e+02 1.740860e-03 9.980781e-01 -6.194405e-02 -2.298254e+01 -9.305342e-01 -2.106721e-02 -3.655984e-01 8.780510e+02 +-3.896682e-01 5.851764e-02 9.190943e-01 1.612742e+02 8.348148e-03 9.981627e-01 -6.001248e-02 -2.302182e+01 -9.209174e-01 -1.571222e-02 -3.894408e-01 8.777660e+02 +-4.098458e-01 5.849829e-02 9.102771e-01 1.618601e+02 1.160565e-02 9.981950e-01 -5.892292e-02 -2.306375e+01 -9.120810e-01 -1.358495e-02 -4.097849e-01 8.774891e+02 +-4.267913e-01 5.854598e-02 9.024531e-01 1.624561e+02 1.248104e-02 9.981885e-01 -5.885419e-02 -2.310742e+01 -9.042640e-01 -1.385491e-02 -4.267489e-01 8.771987e+02 +-4.410092e-01 5.852179e-02 8.955926e-01 1.630590e+02 1.225786e-02 9.981715e-01 -5.918871e-02 -2.315226e+01 -8.974188e-01 -1.512472e-02 -4.409202e-01 8.768867e+02 +-4.519582e-01 6.144640e-02 8.899203e-01 1.636725e+02 1.643955e-02 9.980290e-01 -6.056196e-02 -2.319267e+01 -8.918876e-01 -1.274159e-02 -4.520776e-01 8.765626e+02 +-4.591910e-01 6.287051e-02 8.861100e-01 1.642982e+02 1.925885e-02 9.979625e-01 -6.082646e-02 -2.323390e+01 -8.881287e-01 -1.086550e-02 -4.594662e-01 8.762260e+02 +-4.642699e-01 6.065814e-02 8.836142e-01 1.649395e+02 1.991401e-02 9.981147e-01 -5.805510e-02 -2.327799e+01 -8.854698e-01 -9.356933e-03 -4.646025e-01 8.758813e+02 +-4.671713e-01 5.832734e-02 8.822409e-01 1.655941e+02 2.067429e-02 9.982695e-01 -5.505071e-02 -2.332424e+01 -8.839250e-01 -7.478413e-03 -4.675687e-01 8.755300e+02 +-4.685991e-01 5.804809e-02 8.815018e-01 1.662561e+02 2.298456e-02 9.983021e-01 -5.352116e-02 -2.336992e+01 -8.831119e-01 -4.819035e-03 -4.691376e-01 8.751692e+02 +-4.702641e-01 5.815190e-02 8.806078e-01 1.669350e+02 2.246013e-02 9.982921e-01 -5.392912e-02 -2.341419e+01 -8.822398e-01 -5.582370e-03 -4.707670e-01 8.748046e+02 +-4.706656e-01 5.965717e-02 8.802926e-01 1.676240e+02 2.076818e-02 9.981841e-01 -5.654255e-02 -2.345857e+01 -8.820672e-01 -8.330556e-03 -4.710499e-01 8.744371e+02 +-4.702221e-01 6.120805e-02 8.804231e-01 1.683233e+02 2.044962e-02 9.980799e-01 -5.846585e-02 -2.350416e+01 -8.823112e-01 -9.487616e-03 -4.705708e-01 8.740629e+02 +-4.695378e-01 6.036224e-02 8.808466e-01 1.690399e+02 2.059966e-02 9.981376e-01 -5.741921e-02 -2.355077e+01 -8.826720e-01 -8.815348e-03 -4.699068e-01 8.736783e+02 +-4.693007e-01 5.771564e-02 8.811503e-01 1.697700e+02 1.999064e-02 9.983004e-01 -5.474201e-02 -2.359866e+01 -8.828121e-01 -8.075714e-03 -4.696568e-01 8.732899e+02 +-4.688827e-01 5.489742e-02 8.815528e-01 1.705133e+02 1.858687e-02 9.984589e-01 -5.229155e-02 -2.365020e+01 -8.830648e-01 -8.133298e-03 -4.691805e-01 8.728964e+02 +-4.675096e-01 5.446001e-02 8.823089e-01 1.712665e+02 1.782145e-02 9.984783e-01 -5.218745e-02 -2.370000e+01 -8.838083e-01 -8.674110e-03 -4.677687e-01 8.724988e+02 +-4.663452e-01 5.689806e-02 8.827711e-01 1.720356e+02 1.709752e-02 9.983226e-01 -5.531364e-02 -2.374831e+01 -8.844376e-01 -1.070205e-02 -4.665357e-01 8.720941e+02 +-4.644754e-01 6.043942e-02 8.835212e-01 1.727995e+02 1.770749e-02 9.981027e-01 -5.896867e-02 -2.379832e+01 -8.854089e-01 -1.174456e-02 -4.646644e-01 8.716924e+02 +-4.623201e-01 6.207301e-02 8.845378e-01 1.735874e+02 1.884408e-02 9.980092e-01 -6.018675e-02 -2.385208e+01 -8.865128e-01 -1.115724e-02 -4.625694e-01 8.712788e+02 +-4.600505e-01 6.347059e-02 8.856213e-01 1.743853e+02 1.967865e-02 9.979256e-01 -6.129681e-02 -2.391005e+01 -8.876746e-01 -1.077180e-02 -4.603451e-01 8.708623e+02 +-4.579535e-01 6.230487e-02 8.867901e-01 1.751972e+02 1.970367e-02 9.980073e-01 -5.994356e-02 -2.396924e+01 -8.887577e-01 -9.978348e-03 -4.582685e-01 8.704437e+02 +-4.556318e-01 6.184540e-02 8.880174e-01 1.760214e+02 2.173682e-02 9.980591e-01 -5.835628e-02 -2.402615e+01 -8.899029e-01 -7.286306e-03 -4.560918e-01 8.700181e+02 +-4.540239e-01 6.065449e-02 8.889226e-01 1.768546e+02 2.323564e-02 9.981469e-01 -5.623951e-02 -2.408480e+01 -8.906864e-01 -4.879404e-03 -4.545919e-01 8.695892e+02 +-4.532779e-01 6.248650e-02 8.891764e-01 1.776988e+02 2.326640e-02 9.980294e-01 -5.827553e-02 -2.414778e+01 -8.910655e-01 -5.727078e-03 -4.538385e-01 8.691578e+02 +-4.531064e-01 6.723613e-02 8.889173e-01 1.785463e+02 2.295537e-02 9.977010e-01 -6.376335e-02 -2.420939e+01 -8.911608e-01 -8.486158e-03 -4.536081e-01 8.687250e+02 +-4.535308e-01 6.875972e-02 8.885843e-01 1.794010e+02 2.283445e-02 9.975886e-01 -6.553999e-02 -2.427106e+01 -8.909480e-01 -9.434073e-03 -4.540072e-01 8.682881e+02 +-4.550747e-01 6.315683e-02 8.882107e-01 1.802639e+02 2.188983e-02 9.979735e-01 -5.974635e-02 -2.433783e+01 -8.901841e-01 -7.746270e-03 -4.555350e-01 8.678469e+02 +-4.571056e-01 5.708684e-02 8.875785e-01 1.811219e+02 1.975504e-02 9.983435e-01 -5.403708e-02 -2.440550e+01 -8.891930e-01 -7.166504e-03 -4.574761e-01 8.674077e+02 +-4.594199e-01 5.590960e-02 8.864579e-01 1.819755e+02 1.706093e-02 9.983883e-01 -5.412708e-02 -2.446836e+01 -8.880553e-01 -9.743261e-03 -4.596333e-01 8.669697e+02 +-4.619130e-01 5.657198e-02 8.851192e-01 1.828274e+02 1.538119e-02 9.983245e-01 -5.578055e-02 -2.453003e+01 -8.867918e-01 -1.215157e-02 -4.620092e-01 8.665285e+02 +-4.643783e-01 5.547457e-02 8.838979e-01 1.836836e+02 1.208984e-02 9.983404e-01 -5.630543e-02 -2.459228e+01 -8.855544e-01 -1.546083e-02 -4.642782e-01 8.660841e+02 +-4.672042e-01 5.275792e-02 8.825740e-01 1.845367e+02 9.133162e-03 9.984528e-01 -5.485008e-02 -2.465486e+01 -8.841022e-01 -1.756550e-02 -4.669632e-01 8.656395e+02 +-4.698580e-01 5.238526e-02 8.811863e-01 1.853861e+02 8.156724e-03 9.984526e-01 -5.500733e-02 -2.472099e+01 -8.827043e-01 -1.865804e-02 -4.695582e-01 8.651902e+02 +-4.725008e-01 5.410007e-02 8.796682e-01 1.862304e+02 7.955387e-03 9.983353e-01 -5.712505e-02 -2.478460e+01 -8.812943e-01 -1.999353e-02 -4.721446e-01 8.647384e+02 +-4.746154e-01 5.934769e-02 8.781903e-01 1.870624e+02 1.133490e-02 9.980536e-01 -6.132210e-02 -2.484870e+01 -8.801203e-01 -1.915022e-02 -4.743643e-01 8.642847e+02 +-4.762095e-01 6.029578e-02 8.772622e-01 1.878976e+02 1.361164e-02 9.980322e-01 -6.120764e-02 -2.491615e+01 -8.792264e-01 -1.720669e-02 -4.760932e-01 8.638267e+02 +-4.779425e-01 5.892477e-02 8.764125e-01 1.887277e+02 1.531337e-02 9.981547e-01 -5.875902e-02 -2.498378e+01 -8.782576e-01 -1.466260e-02 -4.779628e-01 8.633715e+02 +-4.795118e-01 5.827167e-02 8.755986e-01 1.895389e+02 1.638128e-02 9.982133e-01 -5.746075e-02 -2.505379e+01 -8.773825e-01 -1.320968e-02 -4.796096e-01 8.629248e+02 +-4.810001e-01 6.271563e-02 8.744746e-01 1.903413e+02 1.819232e-02 9.979373e-01 -6.156358e-02 -2.512322e+01 -8.765318e-01 -1.370337e-02 -4.811488e-01 8.624818e+02 +-4.822168e-01 6.759649e-02 8.734402e-01 1.911304e+02 1.747595e-02 9.975625e-01 -6.755419e-02 -2.519237e+01 -8.758775e-01 -1.731157e-02 -4.822227e-01 8.620462e+02 +-4.834420e-01 6.859493e-02 8.726847e-01 1.919189e+02 1.719461e-02 9.974768e-01 -6.887857e-02 -2.526187e+01 -8.752075e-01 -1.829332e-02 -4.834017e-01 8.616113e+02 +-4.840116e-01 6.698694e-02 8.724939e-01 1.926988e+02 1.863930e-02 9.976286e-01 -6.625430e-02 -2.533441e+01 -8.748630e-01 -1.580518e-02 -4.841124e-01 8.611751e+02 +-4.838938e-01 6.829011e-02 8.724582e-01 1.934585e+02 2.144374e-02 9.975766e-01 -6.619015e-02 -2.540716e+01 -8.748640e-01 -1.332023e-02 -4.841854e-01 8.607418e+02 +-4.835341e-01 7.177632e-02 8.723778e-01 1.942069e+02 2.440275e-02 9.973503e-01 -6.853291e-02 -2.547652e+01 -8.749853e-01 -1.184958e-02 -4.840044e-01 8.603157e+02 +-4.821202e-01 7.278640e-02 8.730763e-01 1.949466e+02 2.403598e-02 9.972667e-01 -6.986701e-02 -2.554590e+01 -8.757753e-01 -1.269906e-02 -4.825519e-01 8.599035e+02 +-4.801224e-01 7.186791e-02 8.742525e-01 1.956623e+02 2.509219e-02 9.973555e-01 -6.820747e-02 -2.558773e+01 -8.768425e-01 -1.081102e-02 -4.806561e-01 8.594374e+02 +-4.759713e-01 7.253498e-02 8.764645e-01 1.963433e+02 2.842796e-02 9.973411e-01 -6.710054e-02 -2.562325e+01 -8.790012e-01 -7.021833e-03 -4.767677e-01 8.589564e+02 +-4.693449e-01 7.307709e-02 8.799859e-01 1.970334e+02 3.173411e-02 9.973218e-01 -6.589554e-02 -2.568177e+01 -8.824445e-01 -3.002168e-03 -4.704069e-01 8.585554e+02 +-4.610995e-01 7.602700e-02 8.840855e-01 1.977093e+02 3.425352e-02 9.971052e-01 -6.788105e-02 -2.574733e+01 -8.866871e-01 -1.016881e-03 -4.623688e-01 8.582185e+02 +-4.521195e-01 7.932937e-02 8.884227e-01 1.983684e+02 3.658645e-02 9.968482e-01 -7.039206e-02 -2.580673e+01 -8.912067e-01 6.786010e-04 -4.535969e-01 8.578882e+02 +-4.428842e-01 8.243222e-02 8.927814e-01 1.990101e+02 3.783274e-02 9.965958e-01 -7.324985e-02 -2.585750e+01 -8.957802e-01 1.335157e-03 -4.444951e-01 8.575636e+02 +-4.323508e-01 8.588999e-02 8.976056e-01 1.996347e+02 3.955954e-02 9.963014e-01 -7.627931e-02 -2.591402e+01 -9.008373e-01 2.529438e-03 -4.341494e-01 8.572339e+02 +-4.198097e-01 8.753627e-02 9.033810e-01 2.002750e+02 4.238728e-02 9.961430e-01 -7.682701e-02 -2.597327e+01 -9.066218e-01 6.039140e-03 -4.219009e-01 8.569191e+02 +-4.041150e-01 8.723840e-02 9.105386e-01 2.009206e+02 4.498705e-02 9.961325e-01 -7.547300e-02 -2.602563e+01 -9.136012e-01 1.046267e-02 -4.064767e-01 8.566230e+02 +-3.855631e-01 8.676803e-02 9.185926e-01 2.015549e+02 4.691473e-02 9.961243e-01 -7.439986e-02 -2.607835e+01 -9.214879e-01 1.440968e-02 -3.881395e-01 8.563285e+02 +-3.632305e-01 8.524988e-02 9.277910e-01 2.021936e+02 4.634014e-02 9.962257e-01 -7.339582e-02 -2.613275e+01 -9.305462e-01 1.633436e-02 -3.658100e-01 8.560858e+02 +-3.372307e-01 8.403930e-02 9.376636e-01 2.028305e+02 4.352588e-02 9.963343e-01 -7.364368e-02 -2.617684e+01 -9.404153e-01 1.597772e-02 -3.396523e-01 8.558726e+02 +-3.079351e-01 8.539877e-02 9.475669e-01 2.034522e+02 3.995305e-02 9.962455e-01 -7.680218e-02 -2.622427e+01 -9.505681e-01 1.420810e-02 -3.101908e-01 8.556462e+02 +-2.740677e-01 8.860397e-02 9.576201e-01 2.040735e+02 3.722507e-02 9.959780e-01 -8.149937e-02 -2.628857e+01 -9.609897e-01 1.331113e-02 -2.762636e-01 8.554964e+02 +-2.348453e-01 9.056742e-02 9.678044e-01 2.047018e+02 3.298692e-02 9.958190e-01 -8.518451e-02 -2.635080e+01 -9.714728e-01 1.191969e-02 -2.368510e-01 8.553915e+02 +-1.911706e-01 9.099730e-02 9.773297e-01 2.053169e+02 2.757977e-02 9.957982e-01 -8.732215e-02 -2.640320e+01 -9.811692e-01 1.026110e-02 -1.928770e-01 8.552209e+02 +-1.432276e-01 8.676774e-02 9.858789e-01 2.059604e+02 2.095055e-02 9.961920e-01 -8.463174e-02 -2.645393e+01 -9.894680e-01 8.533106e-03 -1.445000e-01 8.551839e+02 +-9.065823e-02 7.782979e-02 9.928362e-01 2.066127e+02 1.570881e-02 9.969292e-01 -7.671625e-02 -2.650217e+01 -9.957581e-01 8.641307e-03 -9.160244e-02 8.551955e+02 +-3.549290e-02 6.934650e-02 9.969611e-01 2.072381e+02 9.996149e-03 9.975643e-01 -6.903260e-02 -2.656711e+01 -9.993199e-01 7.515600e-03 -3.609964e-02 8.551249e+02 +1.906682e-02 6.550491e-02 9.976701e-01 2.078643e+02 1.898530e-03 9.978473e-01 -6.555284e-02 -2.662736e+01 -9.998164e-01 3.143986e-03 1.890141e-02 8.552021e+02 +7.526562e-02 6.480997e-02 9.950552e-01 2.084618e+02 -3.885597e-03 9.978971e-01 -6.470118e-02 -2.668167e+01 -9.971559e-01 1.003387e-03 7.535917e-02 8.551786e+02 +1.345511e-01 6.683711e-02 9.886500e-01 2.090847e+02 -2.801629e-03 9.977443e-01 -6.707065e-02 -2.673636e+01 -9.909027e-01 6.254591e-03 1.344348e-01 8.553300e+02 +1.947051e-01 6.784978e-02 9.785123e-01 2.097137e+02 -2.388552e-03 9.976345e-01 -6.870044e-02 -2.680561e+01 -9.808589e-01 1.103910e-02 1.944066e-01 8.555291e+02 +2.532099e-01 6.668637e-02 9.651102e-01 2.102934e+02 -7.952272e-03 9.977311e-01 -6.685400e-02 -2.686298e+01 -9.673786e-01 9.253274e-03 2.531657e-01 8.556164e+02 +3.112310e-01 6.632017e-02 9.480174e-01 2.109016e+02 -1.668897e-02 9.977895e-01 -6.432314e-02 -2.692138e+01 -9.501877e-01 4.197919e-03 3.116499e-01 8.559032e+02 +3.696336e-01 6.471383e-02 9.269214e-01 2.114992e+02 -1.964690e-02 9.978930e-01 -6.183409e-02 -2.695577e+01 -9.289698e-01 4.644824e-03 3.701262e-01 8.562207e+02 +4.271154e-01 6.133064e-02 9.021148e-01 2.120622e+02 -2.163259e-02 9.981045e-01 -5.761438e-02 -2.699596e+01 -9.039383e-01 5.092902e-03 4.276325e-01 8.564102e+02 +4.828169e-01 5.665486e-02 8.738868e-01 2.126481e+02 -2.333799e-02 9.983831e-01 -5.183199e-02 -2.703595e+01 -8.754102e-01 4.630601e-03 4.833584e-01 8.568136e+02 +5.351987e-01 5.322046e-02 8.430480e-01 2.131881e+02 -2.844089e-02 9.985828e-01 -4.498381e-02 -2.709403e+01 -8.442473e-01 9.823291e-05 5.359538e-01 8.571077e+02 +5.843730e-01 4.930446e-02 8.099860e-01 2.137447e+02 -2.975829e-02 9.987831e-01 -3.932726e-02 -2.714565e+01 -8.109393e-01 -1.122006e-03 5.851291e-01 8.575884e+02 +6.294249e-01 4.805128e-02 7.755743e-01 2.142832e+02 -3.333019e-02 9.988371e-01 -3.483426e-02 -2.719267e+01 -7.763462e-01 -3.924495e-03 6.302944e-01 8.580977e+02 +6.701115e-01 4.650830e-02 7.408020e-01 2.147844e+02 -3.485677e-02 9.989057e-01 -3.118174e-02 -2.723500e+01 -7.414416e-01 -4.926725e-03 6.709993e-01 8.585220e+02 +7.065455e-01 4.713430e-02 7.060963e-01 2.152884e+02 -3.722461e-02 9.988734e-01 -2.942988e-02 -2.726329e+01 -7.066879e-01 -5.490616e-03 7.075040e-01 8.590793e+02 +7.385369e-01 4.879987e-02 6.724447e-01 2.157765e+02 -3.989049e-02 9.987926e-01 -2.867203e-02 -2.728911e+01 -6.730320e-01 -5.648799e-03 7.395917e-01 8.596545e+02 +7.660794e-01 5.281870e-02 6.405721e-01 2.162271e+02 -4.498312e-02 9.985799e-01 -2.854177e-02 -2.730382e+01 -6.411699e-01 -6.949666e-03 7.673674e-01 8.601905e+02 +7.895156e-01 5.372758e-02 6.113744e-01 2.166900e+02 -4.619162e-02 9.985373e-01 -2.810061e-02 -2.732953e+01 -6.119898e-01 -6.054506e-03 7.908424e-01 8.608193e+02 +8.097591e-01 5.183224e-02 5.844687e-01 2.171337e+02 -4.575080e-02 9.986356e-01 -2.517570e-02 -2.736080e+01 -5.849762e-01 -6.353660e-03 8.110255e-01 8.614303e+02 +8.273997e-01 4.200055e-02 5.600409e-01 2.175892e+02 -3.756408e-02 9.991053e-01 -1.943155e-02 -2.738187e+01 -5.603559e-01 -4.959765e-03 8.282370e-01 8.621004e+02 +8.437152e-01 3.248447e-02 5.358074e-01 2.180301e+02 -2.738906e-02 9.994722e-01 -1.746665e-02 -2.740239e+01 -5.360919e-01 6.161687e-05 8.441595e-01 8.627888e+02 +8.591325e-01 2.255630e-02 5.112559e-01 2.184557e+02 -1.580989e-02 9.997211e-01 -1.753959e-02 -2.743434e+01 -5.115089e-01 6.985927e-03 8.592495e-01 8.634635e+02 +8.734727e-01 1.527206e-02 4.866336e-01 2.188702e+02 -5.206343e-03 9.997437e-01 -2.203002e-02 -2.745432e+01 -4.868453e-01 1.670904e-02 8.733283e-01 8.641941e+02 +8.867465e-01 8.338984e-03 4.621809e-01 2.192716e+02 4.594434e-03 9.996289e-01 -2.685094e-02 -2.748777e+01 -4.622332e-01 2.593343e-02 8.863790e-01 8.649214e+02 +8.974752e-01 -9.372490e-04 4.410640e-01 2.196631e+02 1.558019e-02 9.994410e-01 -2.957872e-02 -2.751579e+01 -4.407897e-01 3.341802e-02 8.969880e-01 8.656970e+02 +9.062987e-01 -4.074021e-03 4.226183e-01 2.200365e+02 1.899738e-02 9.993355e-01 -3.110605e-02 -2.755388e+01 -4.222107e-01 3.622000e-02 9.057738e-01 8.664915e+02 +9.132197e-01 -4.452067e-03 4.074433e-01 2.203930e+02 1.942886e-02 9.992787e-01 -3.262776e-02 -2.759950e+01 -4.070041e-01 3.771247e-02 9.126474e-01 8.672941e+02 +9.183022e-01 -1.835016e-03 3.958760e-01 2.207438e+02 1.748375e-02 9.992015e-01 -3.592492e-02 -2.765157e+01 -3.954939e-01 3.991132e-02 9.176010e-01 8.681197e+02 +9.214778e-01 1.158563e-03 3.884295e-01 2.210925e+02 1.526972e-02 9.991145e-01 -3.920465e-02 -2.770703e+01 -3.881309e-01 4.205742e-02 9.206440e-01 8.689551e+02 +9.229401e-01 2.483275e-03 3.849356e-01 2.214434e+02 1.344934e-02 9.991606e-01 -3.869251e-02 -2.775971e+01 -3.847086e-01 4.088799e-02 9.221320e-01 8.698074e+02 +9.236941e-01 2.433102e-03 3.831231e-01 2.217984e+02 1.160010e-02 9.993438e-01 -3.431390e-02 -2.781630e+01 -3.829551e-01 3.613981e-02 9.230597e-01 8.706745e+02 +9.241346e-01 -2.074189e-04 3.820671e-01 2.221592e+02 1.283792e-02 9.994520e-01 -3.050945e-02 -2.786440e+01 -3.818514e-01 3.309978e-02 9.236308e-01 8.715512e+02 +9.245983e-01 -6.856957e-04 3.809430e-01 2.225220e+02 1.307477e-02 9.994663e-01 -2.993515e-02 -2.791271e+01 -3.807191e-01 3.265872e-02 9.241138e-01 8.724342e+02 +9.249299e-01 -2.677806e-03 3.801284e-01 2.228901e+02 1.518170e-02 9.994376e-01 -2.989966e-02 -2.795230e+01 -3.798345e-01 3.342608e-02 9.244503e-01 8.733288e+02 +9.255392e-01 -4.423852e-03 3.786261e-01 2.232613e+02 1.716012e-02 9.993944e-01 -3.027046e-02 -2.799306e+01 -3.782628e-01 3.451376e-02 9.250545e-01 8.742334e+02 +9.261443e-01 -6.703700e-03 3.771099e-01 2.236385e+02 1.956432e-02 9.993499e-01 -3.028305e-02 -2.802593e+01 -3.766617e-01 3.542436e-02 9.256733e-01 8.751475e+02 +9.268363e-01 -9.609540e-03 3.753428e-01 2.240215e+02 2.211595e-02 9.993339e-01 -2.902605e-02 -2.805337e+01 -3.748139e-01 3.520345e-02 9.264314e-01 8.760689e+02 +9.278752e-01 -1.244286e-02 3.726835e-01 2.244021e+02 2.408916e-02 9.993556e-01 -2.660941e-02 -2.808341e+01 -3.721122e-01 3.366783e-02 9.275769e-01 8.770035e+02 +9.290559e-01 -1.504123e-02 3.696336e-01 2.247827e+02 2.582016e-02 9.993729e-01 -2.423094e-02 -2.811404e+01 -3.690373e-01 3.205588e-02 9.288615e-01 8.779434e+02 +9.302207e-01 -1.837242e-02 3.665407e-01 2.251634e+02 2.933502e-02 9.992727e-01 -2.436014e-02 -2.814324e+01 -3.658265e-01 3.341278e-02 9.300830e-01 8.788849e+02 +9.315499e-01 -1.943563e-02 3.630938e-01 2.255381e+02 3.041354e-02 9.992360e-01 -2.454172e-02 -2.817325e+01 -3.623394e-01 3.390479e-02 9.314293e-01 8.798352e+02 +9.328707e-01 -2.159535e-02 3.595635e-01 2.259105e+02 3.151972e-02 9.992662e-01 -2.176059e-02 -2.820368e+01 -3.588297e-01 3.163315e-02 9.328668e-01 8.807886e+02 +9.342057e-01 -2.575422e-02 3.558040e-01 2.262824e+02 3.439606e-02 9.992465e-01 -1.798229e-02 -2.823428e+01 -3.550728e-01 2.903741e-02 9.343875e-01 8.817517e+02 +9.355202e-01 -2.814178e-02 3.521507e-01 2.266474e+02 3.516235e-02 9.992897e-01 -1.355472e-02 -2.826192e+01 -3.515190e-01 2.506315e-02 9.358451e-01 8.827142e+02 +9.368249e-01 -3.135897e-02 3.483903e-01 2.270088e+02 3.763267e-02 9.992283e-01 -1.125303e-02 -2.828771e+01 -3.477686e-01 2.365297e-02 9.372819e-01 8.836773e+02 +9.381658e-01 -3.240870e-02 3.446659e-01 2.273658e+02 3.799553e-02 9.992331e-01 -9.464968e-03 -2.831085e+01 -3.440948e-01 2.197547e-02 9.386776e-01 8.846411e+02 +9.393271e-01 -3.151516e-02 3.415721e-01 2.277130e+02 3.614698e-02 9.993205e-01 -7.202264e-03 -2.833191e+01 -3.411130e-01 1.911208e-02 9.398279e-01 8.856055e+02 +9.403387e-01 -2.874245e-02 3.390236e-01 2.280553e+02 3.235871e-02 9.994637e-01 -5.017685e-03 -2.835279e+01 -3.386975e-01 1.568869e-02 9.407644e-01 8.865737e+02 +9.411017e-01 -2.567936e-02 3.371472e-01 2.283935e+02 2.925966e-02 9.995565e-01 -5.541609e-03 -2.837401e+01 -3.368554e-01 1.508003e-02 9.414356e-01 8.875383e+02 +9.415961e-01 -2.160411e-02 3.360507e-01 2.287298e+02 2.616064e-02 9.996169e-01 -9.037069e-03 -2.839480e+01 -3.357267e-01 1.730056e-02 9.418005e-01 8.884988e+02 +9.419713e-01 -1.896387e-02 3.351573e-01 2.290646e+02 2.417255e-02 9.996431e-01 -1.137598e-02 -2.841698e+01 -3.348219e-01 1.881745e-02 9.420934e-01 8.894566e+02 +9.421049e-01 -1.964395e-02 3.347425e-01 2.294016e+02 2.503415e-02 9.996170e-01 -1.179524e-02 -2.844122e+01 -3.343826e-01 1.949235e-02 9.422358e-01 8.904100e+02 +9.422552e-01 -2.036019e-02 3.342765e-01 2.297404e+02 2.582471e-02 9.995955e-01 -1.191084e-02 -2.846821e+01 -3.338987e-01 1.985564e-02 9.423997e-01 8.913647e+02 +9.420329e-01 -2.082600e-02 3.348737e-01 2.300753e+02 2.645147e-02 9.995751e-01 -1.224642e-02 -2.849457e+01 -3.344764e-01 2.039443e-02 9.421834e-01 8.923085e+02 +9.415423e-01 -2.367177e-02 3.360622e-01 2.304153e+02 2.922757e-02 9.995068e-01 -1.148267e-02 -2.852095e+01 -3.356246e-01 2.063370e-02 9.417698e-01 8.932517e+02 +9.405243e-01 -2.675129e-02 3.386715e-01 2.307564e+02 3.184608e-02 9.994477e-01 -9.494451e-03 -2.854616e+01 -3.382305e-01 1.971512e-02 9.408567e-01 8.941903e+02 +9.390567e-01 -3.036671e-02 3.424185e-01 2.311005e+02 3.456796e-02 9.993833e-01 -6.171655e-03 -2.856942e+01 -3.420199e-01 1.763224e-02 9.395272e-01 8.951251e+02 +9.372507e-01 -3.502225e-02 3.468929e-01 2.314478e+02 3.815711e-02 9.992693e-01 -2.208510e-03 -2.858853e+01 -3.465620e-01 1.530635e-02 9.379021e-01 8.960518e+02 +9.350885e-01 -3.674704e-02 3.525042e-01 2.317980e+02 3.891490e-02 9.992421e-01 9.370766e-04 -2.860523e+01 -3.522715e-01 1.284141e-02 9.358097e-01 8.969756e+02 +9.324177e-01 -3.586228e-02 3.595987e-01 2.321485e+02 3.706863e-02 9.993064e-01 3.542724e-03 -2.861858e+01 -3.594764e-01 1.002653e-02 9.331003e-01 8.978905e+02 +9.290180e-01 -3.374694e-02 3.684926e-01 2.325013e+02 3.436530e-02 9.993974e-01 4.886449e-03 -2.863224e+01 -3.684354e-01 8.123759e-03 9.296178e-01 8.987921e+02 +9.247365e-01 -3.015720e-02 3.794115e-01 2.328622e+02 3.079653e-02 9.995160e-01 4.385576e-03 -2.864285e+01 -3.793601e-01 7.629053e-03 9.252176e-01 8.996893e+02 +9.196295e-01 -2.360797e-02 3.920770e-01 2.332270e+02 2.425211e-02 9.997004e-01 3.310437e-03 -2.865639e+01 -3.920377e-01 6.464317e-03 9.199264e-01 9.005720e+02 +9.134010e-01 -1.983604e-02 4.065775e-01 2.336085e+02 2.044328e-02 9.997869e-01 2.850389e-03 -2.866714e+01 -4.065474e-01 5.708229e-03 9.136118e-01 9.014496e+02 +9.061717e-01 -1.814015e-02 4.225209e-01 2.340064e+02 1.866664e-02 9.998216e-01 2.891543e-03 -2.867863e+01 -4.224980e-01 5.266808e-03 9.063485e-01 9.023144e+02 +8.979136e-01 -1.694033e-02 4.398458e-01 2.344140e+02 1.760006e-02 9.998418e-01 2.578908e-03 -2.869104e+01 -4.398199e-01 5.425673e-03 8.980696e-01 9.031468e+02 +8.885672e-01 -1.759998e-02 4.584088e-01 2.348462e+02 1.929333e-02 9.998134e-01 9.888023e-04 -2.870737e+01 -4.583406e-01 7.965614e-03 8.887409e-01 9.039872e+02 +8.784418e-01 -1.745438e-02 4.775306e-01 2.352840e+02 2.093370e-02 9.997789e-01 -1.965351e-03 -2.872095e+01 -4.773907e-01 1.172293e-02 8.786129e-01 9.047798e+02 +8.673089e-01 -1.897162e-02 4.974087e-01 2.357475e+02 2.453253e-02 9.996882e-01 -4.647240e-03 -2.873780e+01 -4.971654e-01 1.623328e-02 8.675038e-01 9.055805e+02 +8.554135e-01 -2.034714e-02 5.175459e-01 2.362275e+02 2.779563e-02 9.995915e-01 -6.642749e-03 -2.875713e+01 -5.171994e-01 2.006781e-02 8.556296e-01 9.063653e+02 +8.423827e-01 -2.345681e-02 5.383691e-01 2.367173e+02 3.259964e-02 9.994406e-01 -7.462681e-03 -2.877307e+01 -5.378929e-01 2.383707e-02 8.426761e-01 9.071065e+02 +8.280469e-01 -2.534001e-02 5.600860e-01 2.372319e+02 3.511494e-02 9.993608e-01 -6.700770e-03 -2.879315e+01 -5.595582e-01 2.521593e-02 8.284073e-01 9.078621e+02 +8.125434e-01 -2.658402e-02 5.822943e-01 2.377621e+02 3.609413e-02 9.993371e-01 -4.742690e-03 -2.881347e+01 -5.817822e-01 2.487104e-02 8.129642e-01 9.086005e+02 +7.960581e-01 -2.850451e-02 6.045486e-01 2.382978e+02 3.783292e-02 9.992804e-01 -2.701515e-03 -2.882982e+01 -6.040365e-01 2.502240e-02 7.965636e-01 9.092827e+02 +7.789933e-01 -2.786017e-02 6.264131e-01 2.388587e+02 3.921892e-02 9.992212e-01 -4.330678e-03 -2.884725e+01 -6.258046e-01 2.794081e-02 7.794792e-01 9.099768e+02 +7.614207e-01 -2.558371e-02 6.477531e-01 2.394299e+02 3.982597e-02 9.991796e-01 -7.350946e-03 -2.887580e+01 -6.470335e-01 3.139455e-02 7.618149e-01 9.106212e+02 +7.431643e-01 -2.191362e-02 6.687500e-01 2.400262e+02 3.947689e-02 9.991585e-01 -1.112917e-02 -2.890125e+01 -6.679434e-01 3.467096e-02 7.434040e-01 9.112798e+02 +7.237332e-01 -1.879823e-02 6.898239e-01 2.406369e+02 3.858296e-02 9.991675e-01 -1.325148e-02 -2.892817e+01 -6.890005e-01 3.620598e-02 7.238559e-01 9.119206e+02 +7.032605e-01 -1.682514e-02 7.107332e-01 2.412545e+02 3.767494e-02 9.991971e-01 -1.362490e-02 -2.895765e+01 -7.099333e-01 3.635867e-02 7.033297e-01 9.125050e+02 +6.822340e-01 -1.717687e-02 7.309322e-01 2.418998e+02 3.816869e-02 9.991975e-01 -1.214461e-02 -2.898464e+01 -7.301369e-01 3.618418e-02 6.823420e-01 9.131079e+02 +6.607297e-01 -1.644734e-02 7.504437e-01 2.425844e+02 3.781012e-02 9.992200e-01 -1.139027e-02 -2.902137e+01 -7.496710e-01 3.590025e-02 6.608362e-01 9.136917e+02 +6.384427e-01 -1.317302e-02 7.695567e-01 2.432615e+02 3.634636e-02 9.992540e-01 -1.304891e-02 -2.905781e+01 -7.688107e-01 3.630155e-02 6.384452e-01 9.142148e+02 +6.149579e-01 -9.046740e-03 7.885081e-01 2.439692e+02 3.534735e-02 9.992453e-01 -1.610284e-02 -2.909300e+01 -7.877673e-01 3.777423e-02 6.148135e-01 9.147535e+02 +5.899904e-01 -5.977484e-03 8.073882e-01 2.446697e+02 3.532142e-02 9.992063e-01 -1.841315e-02 -2.912353e+01 -8.066373e-01 3.938167e-02 5.897332e-01 9.152244e+02 +5.632699e-01 -3.368184e-03 8.262661e-01 2.454028e+02 3.158968e-02 9.993484e-01 -1.746112e-02 -2.915461e+01 -8.256689e-01 3.593680e-02 5.630092e-01 9.157243e+02 +5.350364e-01 -1.740776e-03 8.448272e-01 2.461672e+02 2.846456e-02 9.994672e-01 -1.596744e-02 -2.919388e+01 -8.443493e-01 3.259079e-02 5.348009e-01 9.162007e+02 +5.060491e-01 4.179243e-04 8.625046e-01 2.469334e+02 2.542369e-02 9.995581e-01 -1.540093e-02 -2.923502e+01 -8.621299e-01 2.972167e-02 5.058148e-01 9.166041e+02 +4.764897e-01 3.212332e-03 8.791742e-01 2.477185e+02 2.338118e-02 9.995933e-01 -1.632432e-02 -2.926519e+01 -8.788691e-01 2.833450e-02 4.762208e-01 9.170278e+02 +4.465402e-01 4.724214e-03 8.947511e-01 2.485193e+02 2.368879e-02 9.995731e-01 -1.709995e-02 -2.929617e+01 -8.944499e-01 2.883138e-02 4.462377e-01 9.174259e+02 +4.161544e-01 4.637151e-03 9.092822e-01 2.493220e+02 2.283430e-02 9.996183e-01 -1.554850e-02 -2.932604e+01 -9.090072e-01 2.723339e-02 4.158896e-01 9.177483e+02 +3.854684e-01 4.988678e-03 9.227076e-01 2.501464e+02 2.082422e-02 9.996836e-01 -1.410434e-02 -2.935286e+01 -9.224860e-01 2.465143e-02 3.852425e-01 9.180980e+02 +3.546776e-01 6.387774e-03 9.349669e-01 2.509705e+02 1.870533e-02 9.997280e-01 -1.392606e-02 -2.938239e+01 -9.348015e-01 2.242812e-02 3.544616e-01 9.183729e+02 +3.233611e-01 8.614199e-03 9.462365e-01 2.518184e+02 1.453754e-02 9.997953e-01 -1.406975e-02 -2.940627e+01 -9.461639e-01 1.830555e-02 3.231697e-01 9.186739e+02 +2.910676e-01 1.237820e-02 9.566224e-01 2.526815e+02 7.508170e-03 9.998559e-01 -1.522210e-02 -2.942831e+01 -9.566730e-01 1.161314e-02 2.909327e-01 9.189547e+02 +2.583350e-01 1.509292e-02 9.659375e-01 2.535402e+02 4.937758e-04 9.998757e-01 -1.575527e-02 -2.945537e+01 -9.660552e-01 4.547090e-03 2.582954e-01 9.191597e+02 +2.258801e-01 1.677124e-02 9.740108e-01 2.544348e+02 -1.818368e-03 9.998573e-01 -1.679460e-02 -2.947797e+01 -9.741534e-01 2.022451e-03 2.258783e-01 9.193826e+02 +1.948461e-01 2.115323e-02 9.806057e-01 2.553403e+02 -9.979402e-04 9.997711e-01 -2.136837e-02 -2.950179e+01 -9.808333e-01 3.184954e-03 1.948226e-01 9.195708e+02 +1.653822e-01 2.613989e-02 9.858831e-01 2.562404e+02 2.379319e-03 9.996352e-01 -2.690365e-02 -2.953080e+01 -9.862266e-01 6.795112e-03 1.652597e-01 9.196880e+02 +1.387678e-01 2.845808e-02 9.899160e-01 2.571682e+02 1.159154e-02 9.994719e-01 -3.035771e-02 -2.955866e+01 -9.902571e-01 1.568732e-02 1.383646e-01 9.198094e+02 +1.138229e-01 2.705926e-02 9.931325e-01 2.581093e+02 1.772920e-02 9.994145e-01 -2.926237e-02 -2.959241e+01 -9.933428e-01 2.093816e-02 1.132766e-01 9.199079e+02 +8.985275e-02 2.204813e-02 9.957110e-01 2.590645e+02 2.130437e-02 9.994836e-01 -2.405418e-02 -2.961945e+01 -9.957271e-01 2.337432e-02 8.933663e-02 9.199658e+02 +6.736309e-02 1.716602e-02 9.975809e-01 2.600380e+02 2.264245e-02 9.995682e-01 -1.872918e-02 -2.964823e+01 -9.974715e-01 2.384932e-02 6.694531e-02 9.200311e+02 +4.545873e-02 1.256405e-02 9.988872e-01 2.610170e+02 2.098748e-02 9.996882e-01 -1.352926e-02 -2.967105e+01 -9.987457e-01 2.157914e-02 4.518086e-02 9.200595e+02 +2.455290e-02 1.416835e-02 9.995982e-01 2.620048e+02 1.819940e-02 9.997275e-01 -1.461722e-02 -2.969244e+01 -9.995328e-01 1.855098e-02 2.428836e-02 9.200927e+02 +6.287240e-03 1.971762e-02 9.997858e-01 2.630006e+02 1.689712e-02 9.996607e-01 -1.982142e-02 -2.971423e+01 -9.998374e-01 1.701812e-02 5.951937e-03 9.201033e+02 +-9.574375e-03 2.644106e-02 9.996046e-01 2.640065e+02 1.692308e-02 9.995114e-01 -2.627651e-02 -2.973996e+01 -9.998109e-01 1.666480e-02 -1.001716e-02 9.200844e+02 +-2.437759e-02 2.638459e-02 9.993546e-01 2.650328e+02 1.807246e-02 9.994999e-01 -2.594759e-02 -2.974852e+01 -9.995394e-01 1.742825e-02 -2.484223e-02 9.200812e+02 +-3.821504e-02 2.346891e-02 9.989939e-01 2.660871e+02 1.839135e-02 9.995713e-01 -2.277895e-02 -2.972738e+01 -9.991002e-01 1.750234e-02 -3.863028e-02 9.200985e+02 +-4.984019e-02 2.467588e-02 9.984524e-01 2.671451e+02 2.035855e-02 9.995121e-01 -2.368583e-02 -2.970123e+01 -9.985496e-01 1.914653e-02 -5.031823e-02 9.201003e+02 +-5.902886e-02 2.713169e-02 9.978875e-01 2.682101e+02 2.228049e-02 9.994173e-01 -2.585532e-02 -2.969291e+01 -9.980076e-01 2.070721e-02 -5.959897e-02 9.200784e+02 +-6.686210e-02 2.685720e-02 9.974007e-01 2.693092e+02 2.347088e-02 9.994034e-01 -2.533773e-02 -2.966530e+01 -9.974861e-01 2.171573e-02 -6.745256e-02 9.200426e+02 +-7.366837e-02 2.378577e-02 9.969991e-01 2.703940e+02 2.407088e-02 9.994667e-01 -2.206605e-02 -2.965194e+01 -9.969922e-01 2.237307e-02 -7.420162e-02 9.199889e+02 +-8.032450e-02 2.131647e-02 9.965408e-01 2.714953e+02 2.346640e-02 9.995346e-01 -1.948905e-02 -2.964393e+01 -9.964925e-01 2.181977e-02 -8.078733e-02 9.199273e+02 +-8.712160e-02 2.188261e-02 9.959573e-01 2.725986e+02 2.074089e-02 9.995818e-01 -2.014793e-02 -2.963329e+01 -9.959817e-01 1.890171e-02 -8.753903e-02 9.198611e+02 +-9.409551e-02 2.320177e-02 9.952928e-01 2.737036e+02 1.894277e-02 9.995891e-01 -2.151107e-02 -2.963285e+01 -9.953829e-01 1.682950e-02 -9.449635e-02 9.197827e+02 +-1.012813e-01 2.140776e-02 9.946275e-01 2.748200e+02 1.749198e-02 9.996522e-01 -1.973474e-02 -2.962906e+01 -9.947040e-01 1.539923e-02 -1.016205e-01 9.196981e+02 +-1.090590e-01 1.708549e-02 9.938885e-01 2.759456e+02 1.466709e-02 9.997711e-01 -1.557721e-02 -2.963490e+01 -9.939270e-01 1.287861e-02 -1.092846e-01 9.195944e+02 +-1.166636e-01 1.440803e-02 9.930670e-01 2.770891e+02 1.317294e-02 9.998292e-01 -1.295861e-02 -2.966932e+01 -9.930841e-01 1.156981e-02 -1.168334e-01 9.194705e+02 +-1.239310e-01 1.515305e-02 9.921752e-01 2.782293e+02 1.123779e-02 9.998407e-01 -1.386643e-02 -2.970192e+01 -9.922272e-01 9.431374e-03 -1.240815e-01 9.193363e+02 +-1.313305e-01 1.676737e-02 9.911969e-01 2.793873e+02 8.406696e-03 9.998398e-01 -1.579972e-02 -2.975665e+01 -9.913029e-01 6.257700e-03 -1.314504e-01 9.191942e+02 +-1.388910e-01 1.774691e-02 9.901487e-01 2.805341e+02 6.047365e-03 9.998359e-01 -1.707227e-02 -2.980451e+01 -9.902892e-01 3.616601e-03 -1.389756e-01 9.190420e+02 +-1.458913e-01 1.852082e-02 9.891273e-01 2.816747e+02 2.917534e-03 9.998284e-01 -1.829087e-02 -2.985197e+01 -9.892963e-01 2.173295e-04 -1.459203e-01 9.188854e+02 +-1.524805e-01 1.774956e-02 9.881471e-01 2.828234e+02 5.827731e-04 9.998401e-01 -1.786968e-02 -2.989668e+01 -9.883063e-01 -2.148915e-03 -1.524665e-01 9.187165e+02 +-1.587534e-01 1.586985e-02 9.871907e-01 2.839812e+02 -2.510799e-03 9.998611e-01 -1.647731e-02 -2.994188e+01 -9.873150e-01 -5.094469e-03 -1.586915e-01 9.185396e+02 +-1.649299e-01 1.735862e-02 9.861526e-01 2.851336e+02 -5.124822e-03 9.998165e-01 -1.845625e-02 -2.997129e+01 -9.862919e-01 -8.097846e-03 -1.648107e-01 9.183458e+02 +-1.712797e-01 2.002969e-02 9.850189e-01 2.862924e+02 -8.069967e-03 9.997312e-01 -2.173211e-02 -2.999429e+01 -9.851894e-01 -1.167134e-02 -1.710720e-01 9.181481e+02 +-1.776059e-01 2.140155e-02 9.838690e-01 2.874531e+02 -1.000660e-02 9.996725e-01 -2.355169e-02 -3.003317e+01 -9.840508e-01 -1.402810e-02 -1.773335e-01 9.179431e+02 +-1.839934e-01 2.068942e-02 9.827097e-01 2.886226e+02 -1.165114e-02 9.996623e-01 -2.322779e-02 -3.007548e+01 -9.828584e-01 -1.572344e-02 -1.836902e-01 9.177286e+02 +-1.904993e-01 1.884584e-02 9.815064e-01 2.897936e+02 -1.367351e-02 9.996678e-01 -2.184843e-02 -3.010686e+01 -9.815921e-01 -1.758275e-02 -1.901783e-01 9.175006e+02 +-1.970041e-01 1.929650e-02 9.802128e-01 2.909672e+02 -1.037110e-02 9.997093e-01 -2.176471e-02 -3.013207e+01 -9.803478e-01 -1.445362e-02 -1.967467e-01 9.172606e+02 +-2.034989e-01 2.071048e-02 9.788561e-01 2.921328e+02 -9.378509e-03 9.996891e-01 -2.310101e-02 -3.015823e+01 -9.790302e-01 -1.388124e-02 -2.032414e-01 9.170137e+02 +-2.102108e-01 2.040133e-02 9.774432e-01 2.932954e+02 -6.498839e-03 9.997310e-01 -2.226419e-02 -3.019791e+01 -9.776344e-01 -1.103242e-02 -2.100216e-01 9.167630e+02 +-2.165603e-01 1.819931e-02 9.760996e-01 2.944562e+02 -3.070932e-03 9.998086e-01 -1.932270e-02 -3.024305e+01 -9.762644e-01 -7.182068e-03 -2.164630e-01 9.165001e+02 +-2.235656e-01 1.625290e-02 9.745534e-01 2.956173e+02 -3.768008e-03 9.998391e-01 -1.753900e-02 -3.027211e+01 -9.746816e-01 -7.593243e-03 -2.234683e-01 9.162382e+02 +-2.313652e-01 1.315551e-02 9.727781e-01 2.967783e+02 -4.916076e-03 9.998800e-01 -1.469127e-02 -3.030356e+01 -9.728545e-01 -8.181302e-03 -2.312727e-01 9.159619e+02 +-2.394146e-01 1.007106e-02 9.708652e-01 2.979346e+02 -5.634636e-03 9.999149e-01 -1.176191e-02 -3.033702e+01 -9.709010e-01 -8.286446e-03 -2.393374e-01 9.156702e+02 +-2.475129e-01 1.009771e-02 9.688320e-01 2.990909e+02 -1.399813e-03 9.999409e-01 -1.077957e-02 -3.036956e+01 -9.688835e-01 -4.024269e-03 -2.474841e-01 9.153582e+02 +-2.549742e-01 1.201814e-02 9.668732e-01 3.002415e+02 -2.781940e-03 9.999095e-01 -1.316242e-02 -3.039752e+01 -9.669438e-01 -6.045862e-03 -2.549177e-01 9.150273e+02 +-2.622335e-01 1.620341e-02 9.648684e-01 3.013882e+02 3.956743e-03 9.998686e-01 -1.571582e-02 -3.041367e+01 -9.649963e-01 -3.034812e-04 -2.622631e-01 9.146933e+02 +-2.696196e-01 1.646186e-02 9.628262e-01 3.025331e+02 4.879641e-03 9.998644e-01 -1.572868e-02 -3.043606e+01 -9.629545e-01 4.574821e-04 -2.696633e-01 9.143535e+02 +-2.774709e-01 1.278908e-02 9.606490e-01 3.036781e+02 2.299653e-03 9.999173e-01 -1.264764e-02 -3.046419e+01 -9.607313e-01 -1.300195e-03 -2.774773e-01 9.140105e+02 +-2.847186e-01 1.150131e-02 9.585422e-01 3.048145e+02 2.660463e-03 9.999336e-01 -1.120771e-02 -3.049293e+01 -9.586074e-01 -6.408818e-04 -2.847303e-01 9.136540e+02 +-2.917743e-01 1.282737e-02 9.564012e-01 3.059432e+02 2.373585e-03 9.999167e-01 -1.268689e-02 -3.052592e+01 -9.564842e-01 -1.431613e-03 -2.917804e-01 9.133099e+02 +-2.988049e-01 1.648296e-02 9.541719e-01 3.070676e+02 2.463041e-03 9.998608e-01 -1.650091e-02 -3.055552e+01 -9.543110e-01 -2.580390e-03 -2.988039e-01 9.129496e+02 +-3.050099e-01 2.128846e-02 9.521113e-01 3.081920e+02 2.475037e-03 9.997644e-01 -2.156108e-02 -3.058728e+01 -9.523459e-01 -4.219833e-03 -3.049907e-01 9.125755e+02 +-3.105812e-01 2.694828e-02 9.501648e-01 3.093117e+02 5.010566e-03 9.996306e-01 -2.671342e-02 -3.062584e+01 -9.505336e-01 -3.535824e-03 -3.106014e-01 9.121914e+02 +-3.144296e-01 3.188904e-02 9.487451e-01 3.104309e+02 9.512298e-03 9.994912e-01 -3.044219e-02 -3.067322e+01 -9.492331e-01 -5.471820e-04 -3.145729e-01 9.118108e+02 +-3.168359e-01 3.377215e-02 9.478789e-01 3.115537e+02 1.405409e-02 9.994233e-01 -3.091095e-02 -3.071832e+01 -9.483762e-01 3.527875e-03 -3.171278e-01 9.114294e+02 +-3.188806e-01 3.343788e-02 9.472049e-01 3.126799e+02 1.642520e-02 9.994223e-01 -2.975164e-02 -3.076545e+01 -9.476525e-01 6.070803e-03 -3.192456e-01 9.110454e+02 +-3.208149e-01 3.333389e-02 9.465552e-01 3.138058e+02 1.863398e-02 9.994092e-01 -2.887961e-02 -3.081711e+01 -9.469586e-01 8.373078e-03 -3.212464e-01 9.106612e+02 +-3.227568e-01 3.160946e-02 9.459540e-01 3.149323e+02 1.740528e-02 9.994714e-01 -2.745914e-02 -3.086952e+01 -9.463219e-01 7.601964e-03 -3.231363e-01 9.102802e+02 +-3.246089e-01 2.923215e-02 9.453965e-01 3.160617e+02 1.428300e-02 9.995598e-01 -2.600274e-02 -3.091626e+01 -9.457404e-01 5.062369e-03 -3.248835e-01 9.099024e+02 +-3.261209e-01 2.522201e-02 9.449916e-01 3.171944e+02 1.155089e-02 9.996757e-01 -2.269528e-02 -3.095587e+01 -9.452575e-01 3.514087e-03 -3.263064e-01 9.095240e+02 +-3.273430e-01 2.288092e-02 9.446285e-01 3.183261e+02 8.958947e-03 9.997370e-01 -2.111122e-02 -3.098385e+01 -9.448631e-01 1.552263e-03 -3.274619e-01 9.091410e+02 +-3.285687e-01 2.602954e-02 9.441214e-01 3.194504e+02 7.740482e-03 9.996608e-01 -2.486697e-02 -3.101749e+01 -9.444483e-01 -8.625582e-04 -3.286587e-01 9.087534e+02 +-3.295623e-01 3.303165e-02 9.435559e-01 3.205729e+02 9.129826e-03 9.994525e-01 -3.179963e-02 -3.105351e+01 -9.440896e-01 -1.865462e-03 -3.296835e-01 9.083597e+02 +-3.306594e-01 3.459115e-02 9.431160e-01 3.216999e+02 9.314754e-03 9.993990e-01 -3.338969e-02 -3.108298e+01 -9.437042e-01 -2.255725e-03 -3.307828e-01 9.079620e+02 +-3.312917e-01 3.154673e-02 9.430009e-01 3.228400e+02 1.046407e-02 9.995023e-01 -2.976072e-02 -3.112491e+01 -9.434703e-01 8.143675e-06 -3.314569e-01 9.075604e+02 +-3.320399e-01 2.811471e-02 9.428463e-01 3.239777e+02 1.131631e-02 9.996025e-01 -2.582190e-02 -3.116282e+01 -9.431974e-01 2.095635e-03 -3.322261e-01 9.071583e+02 +-3.325924e-01 2.775748e-02 9.426621e-01 3.251098e+02 1.267022e-02 9.996080e-01 -2.496397e-02 -3.119152e+01 -9.429855e-01 3.640912e-03 -3.328137e-01 9.067568e+02 +-3.333917e-01 2.842111e-02 9.423600e-01 3.262494e+02 1.226845e-02 9.995916e-01 -2.580683e-02 -3.122475e+01 -9.427085e-01 2.957512e-03 -3.336042e-01 9.063560e+02 +-3.340368e-01 3.118125e-02 9.420442e-01 3.273899e+02 1.276392e-02 9.995106e-01 -2.855745e-02 -3.126156e+01 -9.424736e-01 2.484933e-03 -3.342713e-01 9.059547e+02 +-3.344589e-01 3.416750e-02 9.417908e-01 3.285359e+02 1.370159e-02 9.994132e-01 -3.139215e-02 -3.131228e+01 -9.423107e-01 2.404640e-03 -3.347308e-01 9.055491e+02 +-3.347478e-01 3.606933e-02 9.416172e-01 3.296911e+02 1.494605e-02 9.993447e-01 -3.296727e-02 -3.137146e+01 -9.421892e-01 3.037735e-03 -3.350675e-01 9.051398e+02 +-3.351056e-01 3.668826e-02 9.414660e-01 3.308539e+02 1.550904e-02 9.993209e-01 -3.342254e-02 -3.142076e+01 -9.420529e-01 3.401148e-03 -3.354470e-01 9.047296e+02 +-3.358416e-01 3.683404e-02 9.411980e-01 3.320217e+02 1.500552e-02 9.993175e-01 -3.375425e-02 -3.147830e+01 -9.417989e-01 2.787087e-03 -3.361650e-01 9.043176e+02 +-3.364296e-01 3.964300e-02 9.408738e-01 3.331954e+02 1.669700e-02 9.992076e-01 -3.613049e-02 -3.153896e+01 -9.415605e-01 3.554402e-03 -3.368249e-01 9.039006e+02 +-3.373019e-01 4.219488e-02 9.404505e-01 3.343713e+02 1.779263e-02 9.991023e-01 -3.844490e-02 -3.160791e+01 -9.412283e-01 3.765550e-03 -3.377498e-01 9.034799e+02 +-3.379475e-01 4.360633e-02 9.401543e-01 3.355586e+02 2.040103e-02 9.990308e-01 -3.900381e-02 -3.167944e+01 -9.409438e-01 5.998873e-03 -3.385095e-01 9.030525e+02 +-3.387231e-01 4.344784e-02 9.398824e-01 3.367546e+02 2.136951e-02 9.990308e-01 -3.848076e-02 -3.175596e+01 -9.406434e-01 7.050501e-03 -3.393232e-01 9.026253e+02 +-3.399808e-01 4.327232e-02 9.394363e-01 3.379564e+02 2.228622e-02 9.990310e-01 -3.795203e-02 -3.182664e+01 -9.401682e-01 8.033514e-03 -3.406157e-01 9.021944e+02 +-3.420599e-01 4.067608e-02 9.387974e-01 3.391676e+02 2.114424e-02 9.991429e-01 -3.558662e-02 -3.189245e+01 -9.394402e-01 7.677391e-03 -3.426268e-01 9.017610e+02 +-3.443026e-01 3.808229e-02 9.380861e-01 3.403841e+02 1.634021e-02 9.992687e-01 -3.456876e-02 -3.196584e+01 -9.387165e-01 3.426408e-03 -3.446731e-01 9.013284e+02 +-3.465523e-01 3.982348e-02 9.371850e-01 3.416053e+02 1.883438e-02 9.991924e-01 -3.549378e-02 -3.203414e+01 -9.378415e-01 5.350840e-03 -3.470224e-01 9.008811e+02 +-3.485262e-01 4.087116e-02 9.364075e-01 3.428315e+02 1.952228e-02 9.991486e-01 -3.634352e-02 -3.210650e+01 -9.370957e-01 5.614139e-03 -3.490274e-01 9.004297e+02 +-3.499804e-01 4.105299e-02 9.358570e-01 3.440646e+02 2.266599e-02 9.991178e-01 -3.535169e-02 -3.217090e+01 -9.364827e-01 8.839724e-03 -3.506022e-01 8.999690e+02 +-3.517736e-01 3.653674e-02 9.353718e-01 3.453027e+02 2.385318e-02 9.992634e-01 -3.006176e-02 -3.224042e+01 -9.357811e-01 1.173665e-02 -3.523860e-01 8.995073e+02 +-3.543089e-01 3.227769e-02 9.345712e-01 3.465415e+02 2.158068e-02 9.994202e-01 -2.633588e-02 -3.230325e+01 -9.348794e-01 1.083764e-02 -3.548000e-01 8.990477e+02 +-3.568269e-01 2.941503e-02 9.337073e-01 3.477697e+02 1.886693e-02 9.995272e-01 -2.427838e-02 -3.236607e+01 -9.339799e-01 8.953011e-03 -3.572132e-01 8.985909e+02 +-3.587589e-01 2.538884e-02 9.330849e-01 3.489917e+02 1.432620e-02 9.996620e-01 -2.169215e-02 -3.242436e+01 -9.333203e-01 5.585304e-03 -3.590014e-01 8.981360e+02 +-3.608031e-01 2.357501e-02 9.323440e-01 3.502027e+02 1.397265e-02 9.997049e-01 -1.987109e-02 -3.248002e+01 -9.325373e-01 5.857760e-03 -3.610260e-01 8.976767e+02 +-3.626075e-01 2.363853e-02 9.316422e-01 3.514017e+02 1.259601e-02 9.997112e-01 -2.046312e-02 -3.253613e+01 -9.318568e-01 4.314888e-03 -3.628005e-01 8.972205e+02 +-3.645521e-01 2.260860e-02 9.309085e-01 3.526013e+02 1.209003e-02 9.997358e-01 -1.954563e-02 -3.259069e+01 -9.311045e-01 4.129312e-03 -3.647291e-01 8.967602e+02 +-3.660794e-01 2.059146e-02 9.303558e-01 3.537902e+02 1.166625e-02 9.997781e-01 -1.753751e-02 -3.264553e+01 -9.305105e-01 4.433640e-03 -3.662383e-01 8.963012e+02 +-3.678183e-01 1.821361e-02 9.297193e-01 3.549752e+02 1.075908e-02 9.998246e-01 -1.533048e-02 -3.269059e+01 -9.298354e-01 4.364085e-03 -3.679497e-01 8.958411e+02 +-3.695336e-01 1.813820e-02 9.290403e-01 3.561527e+02 9.582937e-03 9.998307e-01 -1.570860e-02 -3.273285e+01 -9.291679e-01 3.098077e-03 -3.696449e-01 8.953824e+02 +-3.712987e-01 1.919902e-02 9.283150e-01 3.573199e+02 8.619159e-03 9.998144e-01 -1.723034e-02 -3.277211e+01 -9.284735e-01 1.603691e-03 -3.713952e-01 8.949248e+02 +-3.731669e-01 1.833985e-02 9.275830e-01 3.584850e+02 8.399501e-03 9.998304e-01 -1.638918e-02 -3.282062e+01 -9.277262e-01 1.675330e-03 -3.732576e-01 8.944636e+02 +-3.746477e-01 1.543649e-02 9.270388e-01 3.596445e+02 7.926078e-03 9.998782e-01 -1.344618e-02 -3.286501e+01 -9.271333e-01 2.310200e-03 -3.747244e-01 8.940019e+02 +-3.762200e-01 1.014901e-02 9.264748e-01 3.607996e+02 7.152676e-03 9.999420e-01 -8.049278e-03 -3.290830e+01 -9.265027e-01 3.598471e-03 -3.762707e-01 8.935399e+02 +-3.777565e-01 5.142649e-03 9.258907e-01 3.619495e+02 4.441357e-03 9.999831e-01 -3.742146e-03 -3.294403e+01 -9.258943e-01 2.698588e-03 -3.777729e-01 8.930843e+02 +-3.790032e-01 1.698251e-03 9.253938e-01 3.630880e+02 -4.801646e-04 9.999978e-01 -2.031824e-03 -3.298266e+01 -9.253952e-01 -1.214412e-03 -3.790016e-01 8.926328e+02 +-3.802761e-01 -4.059127e-04 9.248729e-01 3.642187e+02 -6.900195e-03 9.999733e-01 -2.398258e-03 -3.301508e+01 -9.248472e-01 -7.293805e-03 -3.802687e-01 8.921827e+02 +-3.812929e-01 1.293732e-03 9.244534e-01 3.653362e+02 -8.702870e-03 9.999497e-01 -4.988911e-03 -3.304519e+01 -9.244133e-01 -9.947635e-03 -3.812624e-01 8.917327e+02 +-3.817995e-01 1.830328e-03 9.242434e-01 3.664456e+02 -1.065694e-02 9.999228e-01 -6.382527e-03 -3.307701e+01 -9.241837e-01 -1.228645e-02 -3.817505e-01 8.912839e+02 +-3.818034e-01 3.292781e-03 9.242377e-01 3.675398e+02 -8.157980e-03 9.999427e-01 -6.932571e-03 -3.310546e+01 -9.242075e-01 -1.018679e-02 -3.817547e-01 8.908352e+02 +-3.815777e-01 2.319953e-03 9.243339e-01 3.686192e+02 -5.458079e-03 9.999737e-01 -4.762976e-03 -3.314341e+01 -9.243206e-01 -6.862534e-03 -3.815550e-01 8.903894e+02 +-3.814218e-01 1.393676e-03 9.244001e-01 3.696836e+02 -4.176710e-03 9.999860e-01 -3.231016e-03 -3.317438e+01 -9.243916e-01 -5.093333e-03 -3.814106e-01 8.899536e+02 +-3.812337e-01 6.572888e-04 9.244785e-01 3.707284e+02 -4.263330e-03 9.999878e-01 -2.469081e-03 -3.321332e+01 -9.244688e-01 -4.882656e-03 -3.812262e-01 8.895285e+02 +-3.811070e-01 7.448449e-04 9.245307e-01 3.717495e+02 -3.892469e-03 9.999895e-01 -2.410186e-03 -3.324493e+01 -9.245227e-01 -4.517248e-03 -3.811001e-01 8.891121e+02 +-3.810703e-01 2.567710e-05 9.245461e-01 3.727512e+02 -3.987151e-03 9.999906e-01 -1.671164e-03 -3.327694e+01 -9.245374e-01 -4.323138e-03 -3.810666e-01 8.887050e+02 +-3.808950e-01 -8.151910e-04 9.246180e-01 3.737293e+02 -4.730972e-03 9.999882e-01 -1.067282e-03 -3.331230e+01 -9.246062e-01 -4.780866e-03 -3.808943e-01 8.883081e+02 +-3.806372e-01 -7.616299e-04 9.247242e-01 3.746818e+02 -3.805824e-03 9.999925e-01 -7.429457e-04 -3.335458e+01 -9.247166e-01 -3.802132e-03 -3.806372e-01 8.879189e+02 +-3.802916e-01 -6.377533e-04 9.248665e-01 3.756087e+02 -3.258463e-03 9.999945e-01 -6.502805e-04 -3.339421e+01 -9.248609e-01 -3.260942e-03 -3.802915e-01 8.875421e+02 +-3.800989e-01 -8.580695e-04 9.249455e-01 3.765121e+02 -1.935522e-03 9.999981e-01 1.323017e-04 -3.343473e+01 -9.249438e-01 -1.739967e-03 -3.800998e-01 8.871761e+02 +-3.797589e-01 -3.281080e-03 9.250797e-01 3.773892e+02 -3.155111e-03 9.999925e-01 2.251556e-03 -3.348001e+01 -9.250801e-01 -2.063683e-03 -3.797663e-01 8.868245e+02 +-3.795351e-01 -5.230845e-03 9.251626e-01 3.782437e+02 -3.659019e-03 9.999847e-01 4.152819e-03 -3.352285e+01 -9.251701e-01 -1.809050e-03 -3.795484e-01 8.864819e+02 +-3.792451e-01 -5.789121e-03 9.252782e-01 3.790715e+02 -4.674948e-03 9.999796e-01 4.340367e-03 -3.357429e+01 -9.252844e-01 -2.679567e-03 -3.792644e-01 8.861540e+02 +-3.790921e-01 -3.577892e-03 9.253521e-01 3.798749e+02 -5.673857e-03 9.999827e-01 1.542019e-03 -3.361052e+01 -9.253415e-01 -4.665750e-03 -3.791058e-01 8.858370e+02 +-3.787219e-01 2.616155e-04 9.255105e-01 3.806591e+02 -5.758637e-03 9.999799e-01 -2.639126e-03 -3.364992e+01 -9.254926e-01 -6.329175e-03 -3.787128e-01 8.855285e+02 +-3.782233e-01 3.162290e-03 9.257090e-01 3.814238e+02 -4.761241e-03 9.999743e-01 -5.361326e-03 -3.368425e+01 -9.257021e-01 -6.435304e-03 -3.781985e-01 8.852262e+02 +-3.777506e-01 4.249994e-03 9.258977e-01 3.821779e+02 -3.905657e-03 9.999732e-01 -6.183460e-03 -3.372946e+01 -9.258991e-01 -5.952046e-03 -3.777238e-01 8.849316e+02 +-3.772227e-01 4.156996e-03 9.261133e-01 3.829087e+02 -2.403105e-03 9.999821e-01 -5.467402e-03 -3.376924e+01 -9.261194e-01 -4.287978e-03 -3.772059e-01 8.846462e+02 +-3.767610e-01 2.884346e-03 9.263061e-01 3.836246e+02 -1.340056e-03 9.999924e-01 -3.658847e-03 -3.381270e+01 -9.263095e-01 -2.619815e-03 -3.767542e-01 8.843696e+02 +-3.764193e-01 3.191880e-03 9.264439e-01 3.843281e+02 -1.511514e-03 9.999906e-01 -4.059414e-03 -3.385197e+01 -9.264481e-01 -2.928377e-03 -3.764109e-01 8.841003e+02 +-3.762690e-01 3.800343e-03 9.265027e-01 3.850230e+02 -2.073035e-03 9.999856e-01 -4.943659e-03 -3.389257e+01 -9.265081e-01 -3.780820e-03 -3.762557e-01 8.838358e+02 +-3.760495e-01 3.699712e-03 9.265922e-01 3.857170e+02 -3.301452e-03 9.999803e-01 -5.332610e-03 -3.393399e+01 -9.265936e-01 -5.064427e-03 -3.760299e-01 8.835726e+02 +-3.758114e-01 2.930817e-03 9.266916e-01 3.864007e+02 -4.246477e-03 9.999790e-01 -4.884729e-03 -3.396847e+01 -9.266864e-01 -5.770913e-03 -3.757911e-01 8.833112e+02 +-3.756290e-01 3.202828e-03 9.267646e-01 3.870719e+02 -4.678896e-03 9.999747e-01 -5.352258e-03 -3.400555e+01 -9.267583e-01 -6.346701e-03 -3.756045e-01 8.830518e+02 +-3.752781e-01 4.214126e-03 9.269027e-01 3.877313e+02 -5.310223e-03 9.999635e-01 -6.696269e-03 -3.402855e+01 -9.268970e-01 -7.435024e-03 -3.752420e-01 8.827947e+02 +-3.747185e-01 5.481973e-03 9.271224e-01 3.883769e+02 -5.748227e-03 9.999495e-01 -8.235882e-03 -3.405628e+01 -9.271208e-01 -8.415449e-03 -3.746681e-01 8.825368e+02 +-3.743170e-01 5.617275e-03 9.272838e-01 3.890212e+02 -5.822491e-03 9.999477e-01 -8.407831e-03 -3.408036e+01 -9.272825e-01 -8.546297e-03 -3.742647e-01 8.822817e+02 +-3.738619e-01 6.452250e-03 9.274620e-01 3.896619e+02 -6.309190e-03 9.999350e-01 -9.499692e-03 -3.411381e+01 -9.274629e-01 -9.403108e-03 -3.737969e-01 8.820273e+02 +-3.736568e-01 8.221225e-03 9.275306e-01 3.903090e+02 -7.102214e-03 9.999060e-01 -1.172387e-02 -3.414840e+01 -9.275398e-01 -1.096823e-02 -3.735633e-01 8.817748e+02 +-3.736999e-01 9.050648e-03 9.275055e-01 3.909634e+02 -8.394025e-03 9.998784e-01 -1.313890e-02 -3.418086e+01 -9.275117e-01 -1.269551e-02 -3.735785e-01 8.815181e+02 +-3.737629e-01 8.160164e-03 9.274884e-01 3.916309e+02 -1.038777e-02 9.998617e-01 -1.298302e-02 -3.421087e+01 -9.274661e-01 -1.448711e-02 -3.736264e-01 8.812563e+02 +-3.746819e-01 7.883362e-03 9.271200e-01 3.923061e+02 -1.149010e-02 9.998476e-01 -1.314533e-02 -3.424791e+01 -9.270822e-01 -1.557802e-02 -3.745341e-01 8.809937e+02 +-3.752990e-01 9.862308e-03 9.268514e-01 3.929898e+02 -1.170669e-02 9.998132e-01 -1.537893e-02 -3.428720e+01 -9.268298e-01 -1.662206e-02 -3.751134e-01 8.807229e+02 +-3.759784e-01 1.231096e-02 9.265467e-01 3.936814e+02 -1.175699e-02 9.997679e-01 -1.805466e-02 -3.431398e+01 -9.265538e-01 -1.768156e-02 -3.757463e-01 8.804466e+02 +-3.764731e-01 1.653351e-02 9.262800e-01 3.943777e+02 -1.007723e-02 9.997085e-01 -2.193992e-02 -3.434049e+01 -9.263727e-01 -1.759413e-02 -3.761968e-01 8.801621e+02 +-3.768000e-01 1.599157e-02 9.261566e-01 3.950921e+02 -8.974041e-03 9.997410e-01 -2.091315e-02 -3.436893e+01 -9.262511e-01 -1.619144e-02 -3.765589e-01 8.798713e+02 +-3.773023e-01 1.497046e-02 9.259692e-01 3.958150e+02 -4.720727e-03 9.998252e-01 -1.808806e-02 -3.439985e+01 -9.260781e-01 -1.119592e-02 -3.771657e-01 8.795680e+02 +-3.776535e-01 1.451011e-02 9.258333e-01 3.965502e+02 -2.125199e-03 9.998610e-01 -1.653720e-02 -3.442657e+01 -9.259445e-01 -8.212912e-03 -3.775701e-01 8.792622e+02 +-3.773584e-01 1.175297e-02 9.259928e-01 3.972968e+02 -3.861038e-03 9.998908e-01 -1.426436e-02 -3.444906e+01 -9.260592e-01 -8.958069e-03 -3.772718e-01 8.789516e+02 +-3.769034e-01 9.408073e-03 9.262048e-01 3.980643e+02 -4.575011e-03 9.999173e-01 -1.201855e-02 -3.447001e+01 -9.262413e-01 -8.767230e-03 -3.768291e-01 8.786381e+02 +-3.758769e-01 7.588343e-03 9.266386e-01 3.988423e+02 -3.590336e-03 9.999470e-01 -9.645047e-03 -3.449434e+01 -9.266626e-01 -6.952296e-03 -3.758297e-01 8.783149e+02 +-3.751117e-01 7.229020e-03 9.269514e-01 3.996344e+02 -4.700672e-03 9.999419e-01 -9.700491e-03 -3.451644e+01 -9.269677e-01 -7.996064e-03 -3.750559e-01 8.779936e+02 +-3.743271e-01 8.904666e-03 9.272540e-01 4.004392e+02 -5.943169e-03 9.999103e-01 -1.200163e-02 -3.454044e+01 -9.272777e-01 -1.000336e-02 -3.742406e-01 8.776693e+02 +-3.729427e-01 1.066376e-02 9.277931e-01 4.012596e+02 -5.624874e-03 9.998896e-01 -1.375343e-02 -3.456392e+01 -9.278373e-01 -1.034796e-02 -3.728415e-01 8.773390e+02 +-3.710389e-01 1.147454e-02 9.285465e-01 4.020930e+02 -4.743189e-03 9.998872e-01 -1.425147e-02 -3.459034e+01 -9.286052e-01 -9.692123e-03 -3.709425e-01 8.770045e+02 +-3.693071e-01 1.231952e-02 9.292258e-01 4.029343e+02 -3.202020e-03 9.998893e-01 -1.452897e-02 -3.461987e+01 -9.293019e-01 -8.341051e-03 -3.692268e-01 8.766650e+02 +-3.674568e-01 1.178282e-02 9.299660e-01 4.037898e+02 -3.084816e-03 9.998988e-01 -1.388779e-02 -3.465174e+01 -9.300355e-01 -7.971936e-03 -3.673832e-01 8.763251e+02 +-3.660349e-01 1.201284e-02 9.305236e-01 4.046577e+02 -2.499748e-03 9.999004e-01 -1.389180e-02 -3.468585e+01 -9.305977e-01 -7.410961e-03 -3.659684e-01 8.759815e+02 +-3.649717e-01 1.347679e-02 9.309211e-01 4.055404e+02 -2.461389e-03 9.998777e-01 -1.544007e-02 -3.471630e+01 -9.310153e-01 -7.926549e-03 -3.648938e-01 8.756358e+02 +-3.643275e-01 1.583903e-02 9.311362e-01 4.064359e+02 -4.101775e-03 9.998183e-01 -1.861227e-02 -3.474853e+01 -9.312618e-01 -1.060027e-02 -3.641964e-01 8.752911e+02 +-3.636340e-01 1.698039e-02 9.313872e-01 4.073465e+02 -2.035019e-03 9.998170e-01 -1.902248e-02 -3.477707e+01 -9.315396e-01 -8.812614e-03 -3.635329e-01 8.749371e+02 +-3.625770e-01 1.329937e-02 9.318589e-01 4.082742e+02 -1.619555e-03 9.998876e-01 -1.490043e-02 -3.481322e+01 -9.319524e-01 -6.911752e-03 -3.625147e-01 8.745757e+02 +-3.621962e-01 9.682505e-03 9.320516e-01 4.092170e+02 -8.971585e-04 9.999419e-01 -1.073642e-02 -3.485012e+01 -9.321014e-01 -4.724890e-03 -3.621664e-01 8.742145e+02 +-3.615923e-01 8.862103e-03 9.322942e-01 4.101710e+02 -1.742329e-03 9.999466e-01 -1.018096e-02 -3.488211e+01 -9.323346e-01 -5.305722e-03 -3.615575e-01 8.738516e+02 +-3.613194e-01 1.039225e-02 9.323842e-01 4.111347e+02 -1.379990e-03 9.999308e-01 -1.167990e-02 -3.490972e+01 -9.324411e-01 -5.506858e-03 -3.612800e-01 8.734844e+02 +-3.615316e-01 8.017634e-03 9.323254e-01 4.121181e+02 -1.410556e-03 9.999572e-01 -9.146225e-03 -3.493283e+01 -9.323587e-01 -4.621749e-03 -3.615048e-01 8.731113e+02 +-3.616886e-01 4.944559e-03 9.322859e-01 4.131164e+02 -5.582648e-04 9.999846e-01 -5.520203e-03 -3.495003e+01 -9.322988e-01 -2.517059e-03 -3.616802e-01 8.727301e+02 +-3.625007e-01 6.395616e-03 9.319616e-01 4.141113e+02 7.603881e-04 9.999781e-01 -6.566624e-03 -3.497235e+01 -9.319832e-01 -1.671756e-03 -3.624976e-01 8.723465e+02 +-3.635344e-01 1.187226e-02 9.315052e-01 4.151187e+02 -3.274596e-04 9.999171e-01 -1.287199e-02 -3.499737e+01 -9.315807e-01 -4.984443e-03 -3.635003e-01 8.719598e+02 +-3.653242e-01 1.513487e-02 9.307573e-01 4.161399e+02 -1.886303e-03 9.998537e-01 -1.699882e-02 -3.502075e+01 -9.308784e-01 -7.965772e-03 -3.652422e-01 8.715680e+02 +-3.672145e-01 1.280156e-02 9.300482e-01 4.171787e+02 -6.227449e-03 9.998490e-01 -1.622115e-02 -3.505081e+01 -9.301154e-01 -1.174847e-02 -3.670793e-01 8.711715e+02 +-3.694318e-01 8.954953e-03 9.292147e-01 4.182181e+02 -1.028712e-02 9.998529e-01 -1.372560e-02 -3.508130e+01 -9.292009e-01 -1.462961e-02 -3.692853e-01 8.707710e+02 +-3.718708e-01 5.472868e-03 9.282684e-01 4.192661e+02 -1.288509e-02 9.998558e-01 -1.105680e-02 -3.511286e+01 -9.281950e-01 -1.607252e-02 -3.717466e-01 8.703606e+02 +-3.748009e-01 1.837584e-03 9.271035e-01 4.203230e+02 -1.669461e-02 9.998225e-01 -8.730872e-03 -3.514204e+01 -9.269549e-01 -1.874997e-02 -3.747037e-01 8.699449e+02 +-3.782443e-01 1.157693e-03 9.257051e-01 4.213931e+02 -2.116366e-02 9.997270e-01 -9.897771e-03 -3.516933e+01 -9.254638e-01 -2.333508e-02 -3.781165e-01 8.695203e+02 +-3.818028e-01 3.298660e-03 9.242380e-01 4.224622e+02 -2.243199e-02 9.996660e-01 -1.283453e-02 -3.518515e+01 -9.239715e-01 -2.563276e-02 -3.816012e-01 8.690862e+02 +-3.856835e-01 2.522751e-03 9.226277e-01 4.235413e+02 -2.510908e-02 9.995972e-01 -1.322949e-02 -3.519724e+01 -9.222894e-01 -2.826873e-02 -3.854648e-01 8.686449e+02 +-3.897452e-01 2.021263e-03 9.209206e-01 4.246273e+02 -2.704291e-02 9.995412e-01 -1.363873e-02 -3.521290e+01 -9.205256e-01 -3.021999e-02 -3.895117e-01 8.681932e+02 +-3.937889e-01 3.373884e-03 9.191947e-01 4.257157e+02 -2.741657e-02 9.995052e-01 -1.541410e-02 -3.523346e+01 -9.187919e-01 -3.127106e-02 -3.935016e-01 8.677333e+02 +-3.980330e-01 4.962941e-03 9.173577e-01 4.268104e+02 -2.552408e-02 9.995383e-01 -1.648221e-02 -3.526314e+01 -9.170159e-01 -2.997517e-02 -3.977225e-01 8.672566e+02 +-4.023492e-01 1.155546e-03 9.154856e-01 4.279148e+02 -2.474021e-02 9.996202e-01 -1.213489e-02 -3.529594e+01 -9.151519e-01 -2.753177e-02 -4.021678e-01 8.667719e+02 +-4.071523e-01 -3.267652e-03 9.133545e-01 4.290245e+02 -2.201309e-02 9.997382e-01 -6.236231e-03 -3.532626e+01 -9.130950e-01 -2.264485e-02 -4.071176e-01 8.662750e+02 +-4.118665e-01 -7.346759e-03 9.112146e-01 4.301372e+02 -1.913254e-02 9.998168e-01 -5.867404e-04 -3.534794e+01 -9.110433e-01 -1.767551e-02 -4.119316e-01 8.657692e+02 +-4.169279e-01 -7.787041e-03 9.089062e-01 4.312478e+02 -1.553326e-02 9.998783e-01 1.441114e-03 -3.536411e+01 -9.088068e-01 -1.351744e-02 -4.169981e-01 8.652545e+02 +-4.217283e-01 -5.774114e-03 9.067039e-01 4.323571e+02 -1.486659e-02 9.998893e-01 -5.472463e-04 -3.537785e+01 -9.066003e-01 -1.371038e-02 -4.217674e-01 8.647378e+02 +-4.267192e-01 -2.734917e-04 9.043841e-01 4.334568e+02 -1.236129e-02 9.999083e-01 -5.530105e-03 -3.539550e+01 -9.042996e-01 -1.353916e-02 -4.266834e-01 8.642141e+02 +-4.317808e-01 2.862636e-03 9.019741e-01 4.345524e+02 -1.317192e-02 9.998683e-01 -9.478815e-03 -3.542296e+01 -9.018824e-01 -1.597350e-02 -4.316861e-01 8.636904e+02 +-4.370554e-01 -1.498343e-03 8.994334e-01 4.356468e+02 -1.267463e-02 9.999096e-01 -4.493180e-03 -3.545241e+01 -8.993453e-01 -1.336376e-02 -4.370348e-01 8.631550e+02 +-4.422257e-01 -8.108067e-03 8.968672e-01 4.367333e+02 -1.388508e-02 9.999012e-01 2.193103e-03 -3.548107e+01 -8.967963e-01 -1.148323e-02 -4.422945e-01 8.626218e+02 +-4.475035e-01 -6.347323e-03 8.942597e-01 4.378075e+02 -1.070636e-02 9.999411e-01 1.739774e-03 -3.550255e+01 -8.942180e-01 -8.795712e-03 -4.475451e-01 8.620816e+02 +-4.517765e-01 -3.937102e-04 8.921311e-01 4.388668e+02 -8.716244e-03 9.999541e-01 -3.972631e-03 -3.552257e+01 -8.920886e-01 -9.570774e-03 -4.517591e-01 8.615394e+02 +-4.564523e-01 2.911724e-03 8.897432e-01 4.399202e+02 -4.099125e-03 9.999771e-01 -5.375393e-03 -3.554693e+01 -8.897384e-01 -6.100781e-03 -4.564298e-01 8.609919e+02 +-4.608030e-01 2.100042e-03 8.875000e-01 4.409666e+02 -1.496450e-03 9.999939e-01 -3.143217e-03 -3.558688e+01 -8.875012e-01 -2.776505e-03 -4.607970e-01 8.604442e+02 +-4.654368e-01 1.714404e-03 8.850795e-01 4.420044e+02 -1.708758e-04 9.999979e-01 -2.026868e-03 -3.562680e+01 -8.850811e-01 -1.094620e-03 -4.654355e-01 8.599014e+02 +-4.689735e-01 3.122992e-03 8.832067e-01 4.430296e+02 1.913955e-03 9.999950e-01 -2.519670e-03 -3.566927e+01 -8.832101e-01 5.087568e-04 -4.689771e-01 8.593608e+02 +-4.711488e-01 4.685090e-03 8.820413e-01 4.440492e+02 4.284382e-03 9.999862e-01 -3.023045e-03 -3.570445e+01 -8.820433e-01 2.354695e-03 -4.711624e-01 8.588167e+02 +-4.719651e-01 5.103173e-03 8.816025e-01 4.450606e+02 7.527090e-03 9.999701e-01 -1.758733e-03 -3.574222e+01 -8.815851e-01 5.805837e-03 -4.719894e-01 8.582739e+02 +-4.717916e-01 5.579644e-03 8.816925e-01 4.460651e+02 1.083350e-02 9.999412e-01 -5.309887e-04 -3.577386e+01 -8.816435e-01 9.301296e-03 -4.718242e-01 8.577324e+02 +-4.710367e-01 6.971113e-03 8.820861e-01 4.470690e+02 1.279714e-02 9.999175e-01 -1.068630e-03 -3.580112e+01 -8.820208e-01 1.078481e-02 -4.710870e-01 8.571937e+02 +-4.697088e-01 1.002273e-02 8.827645e-01 4.480654e+02 1.700529e-02 9.998527e-01 -2.303812e-03 -3.583171e+01 -8.826576e-01 1.392954e-02 -4.698100e-01 8.566608e+02 +-4.678115e-01 9.901607e-03 8.837728e-01 4.490568e+02 1.764628e-02 9.998425e-01 -1.861249e-03 -3.586067e+01 -8.836520e-01 1.472459e-02 -4.679125e-01 8.561371e+02 +-4.657058e-01 9.902170e-03 8.848843e-01 4.500371e+02 2.151882e-02 9.997684e-01 1.373661e-04 -3.589702e+01 -8.846779e-01 1.910563e-02 -4.658110e-01 8.556071e+02 +-4.626049e-01 1.069209e-02 8.865001e-01 4.510113e+02 2.338074e-02 9.997266e-01 1.431117e-04 -3.593332e+01 -8.862562e-01 2.079323e-02 -4.627284e-01 8.550947e+02 +-4.591039e-01 1.307752e-02 8.882864e-01 4.519826e+02 2.704485e-02 9.996339e-01 -7.388909e-04 -3.597612e+01 -8.879708e-01 2.368434e-02 -4.592895e-01 8.545852e+02 +-4.546083e-01 1.470893e-02 8.905701e-01 4.529446e+02 3.209422e-02 9.994848e-01 -1.247134e-04 -3.601551e+01 -8.901130e-01 2.852545e-02 -4.548461e-01 8.540811e+02 +-4.502233e-01 1.609746e-02 8.927709e-01 4.539000e+02 3.660841e-02 9.993296e-01 4.427681e-04 -3.605542e+01 -8.921652e-01 3.288226e-02 -4.505108e-01 8.535924e+02 +-4.460086e-01 1.414081e-02 8.949170e-01 4.548464e+02 3.638804e-02 9.993350e-01 2.344308e-03 -3.608688e+01 -8.942887e-01 3.360985e-02 -4.462265e-01 8.531150e+02 +-4.420860e-01 1.335567e-02 8.968733e-01 4.557776e+02 3.638803e-02 9.993330e-01 3.054913e-03 -3.612438e+01 -8.962343e-01 3.398598e-02 -4.422771e-01 8.526544e+02 +-4.380933e-01 1.316485e-02 8.988331e-01 4.566932e+02 3.496819e-02 9.993855e-01 2.405964e-03 -3.615564e+01 -8.982491e-01 3.248460e-02 -4.382844e-01 8.522134e+02 +-4.345630e-01 1.541970e-02 9.005095e-01 4.575914e+02 3.152468e-02 9.995011e-01 -1.901765e-03 -3.618379e+01 -9.000895e-01 2.756182e-02 -4.348323e-01 8.517911e+02 +-4.313530e-01 1.606694e-02 9.020402e-01 4.584676e+02 2.818842e-02 9.995932e-01 -4.324927e-03 -3.621273e+01 -9.017427e-01 2.356151e-02 -4.316305e-01 8.513834e+02 +-4.281553e-01 1.763224e-02 9.035332e-01 4.593265e+02 2.740479e-02 9.996031e-01 -6.520787e-03 -3.624474e+01 -9.032895e-01 2.196922e-02 -4.284685e-01 8.509819e+02 +-4.251786e-01 1.937938e-02 9.049020e-01 4.601660e+02 2.790057e-02 9.995762e-01 -8.297529e-03 -3.627543e+01 -9.046793e-01 2.171934e-02 -4.255391e-01 8.505879e+02 +-4.224728e-01 2.487569e-02 9.060342e-01 4.609907e+02 3.055751e-02 9.994459e-01 -1.319178e-02 -3.630577e+01 -9.058603e-01 2.211298e-02 -4.229988e-01 8.501982e+02 +-4.200771e-01 2.742573e-02 9.070739e-01 4.618099e+02 2.950068e-02 9.994276e-01 -1.655596e-02 -3.633824e+01 -9.070087e-01 1.980451e-02 -4.206457e-01 8.498174e+02 +-4.178936e-01 3.019873e-02 9.079940e-01 4.626215e+02 2.900202e-02 9.993814e-01 -1.989033e-02 -3.637089e+01 -9.080329e-01 1.802162e-02 -4.185108e-01 8.494425e+02 +-4.159327e-01 3.274306e-02 9.088058e-01 4.634268e+02 2.977224e-02 9.993062e-01 -2.237783e-02 -3.640784e+01 -9.089079e-01 1.774951e-02 -4.166189e-01 8.490703e+02 +-4.146488e-01 3.580441e-02 9.092769e-01 4.642211e+02 2.950820e-02 9.992292e-01 -2.589012e-02 -3.645457e+01 -9.095029e-01 1.609582e-02 -4.153857e-01 8.487058e+02 +-4.137036e-01 3.855975e-02 9.095947e-01 4.650098e+02 2.969520e-02 9.991426e-01 -2.884986e-02 -3.649821e+01 -9.099272e-01 1.507530e-02 -4.144939e-01 8.483447e+02 +-4.124686e-01 4.049030e-02 9.100716e-01 4.657876e+02 3.058182e-02 9.990641e-01 -3.058922e-02 -3.654257e+01 -9.104583e-01 1.521454e-02 -4.133208e-01 8.479909e+02 +-4.112686e-01 4.208828e-02 9.105420e-01 4.665613e+02 3.142286e-02 9.989943e-01 -3.198394e-02 -3.658119e+01 -9.109724e-01 1.545784e-02 -4.121775e-01 8.476383e+02 +-4.102305e-01 4.136291e-02 9.110434e-01 4.673267e+02 3.021686e-02 9.990389e-01 -3.175182e-02 -3.661983e+01 -9.114811e-01 1.450330e-02 -4.110860e-01 8.472940e+02 +-4.093763e-01 4.131850e-02 9.114296e-01 4.680949e+02 2.892882e-02 9.990595e-01 -3.229748e-02 -3.665050e+01 -9.119068e-01 1.314475e-02 -4.101866e-01 8.469506e+02 +-4.088302e-01 4.360703e-02 9.115681e-01 4.688560e+02 2.941547e-02 9.989684e-01 -3.459547e-02 -3.668291e+01 -9.121362e-01 1.267052e-02 -4.096912e-01 8.466084e+02 +-4.087387e-01 4.686348e-02 9.114475e-01 4.696104e+02 2.604892e-02 9.988729e-01 -3.967697e-02 -3.671866e+01 -9.122796e-01 7.524709e-03 -4.094987e-01 8.462723e+02 +-4.089116e-01 4.891932e-02 9.112619e-01 4.703668e+02 2.028756e-02 9.988027e-01 -4.451512e-02 -3.676026e+01 -9.123485e-01 2.845328e-04 -4.094144e-01 8.459373e+02 +-4.091252e-01 4.782860e-02 9.112240e-01 4.711392e+02 1.594570e-02 9.988476e-01 -4.526846e-02 -3.679832e+01 -9.123389e-01 -3.990364e-03 -4.094163e-01 8.455989e+02 +-4.094205e-01 4.594747e-02 9.111881e-01 4.719211e+02 1.524453e-02 9.989361e-01 -4.352249e-02 -3.684140e+01 -9.122184e-01 -3.928366e-03 -4.096853e-01 8.452475e+02 +-4.103572e-01 4.756565e-02 9.106836e-01 4.727081e+02 1.217504e-02 9.988355e-01 -4.668379e-02 -3.688644e+01 -9.118436e-01 -8.069422e-03 -4.104584e-01 8.448976e+02 +-4.116076e-01 4.808773e-02 9.100917e-01 4.735073e+02 8.311853e-03 9.987635e-01 -4.901381e-02 -3.692790e+01 -9.113233e-01 -1.260991e-02 -4.114983e-01 8.445445e+02 +-4.123321e-01 4.894285e-02 9.097180e-01 4.743115e+02 1.204190e-02 9.987615e-01 -4.827539e-02 -3.697960e+01 -9.109540e-01 -8.950765e-03 -4.124108e-01 8.441758e+02 +-4.130749e-01 5.057174e-02 9.092919e-01 4.751217e+02 1.485159e-02 9.986983e-01 -4.879742e-02 -3.703548e+01 -9.105759e-01 -6.652560e-03 -4.132882e-01 8.438004e+02 +-4.144160e-01 5.496516e-02 9.084263e-01 4.759394e+02 5.876766e-03 9.983153e-01 -5.772307e-02 -3.709510e+01 -9.100686e-01 -1.858275e-02 -4.140408e-01 8.434408e+02 +-4.149137e-01 6.125003e-02 9.077969e-01 4.767566e+02 1.401631e-03 9.977734e-01 -6.668024e-02 -3.716007e+01 -9.098597e-01 -2.639414e-02 -4.140756e-01 8.430683e+02 +-4.147696e-01 6.274888e-02 9.077603e-01 4.775875e+02 6.230380e-05 9.976213e-01 -6.893207e-02 -3.723000e+01 -9.099264e-01 -2.853437e-02 -4.137869e-01 8.426838e+02 +-4.161081e-01 5.509935e-02 9.076443e-01 4.784327e+02 -5.371908e-03 9.979961e-01 -6.304699e-02 -3.730379e+01 -9.092993e-01 -3.111014e-02 -4.149782e-01 8.423034e+02 +-4.170570e-01 4.937705e-02 9.075381e-01 4.792848e+02 -1.046090e-02 9.981962e-01 -5.911685e-02 -3.737326e+01 -9.088201e-01 -3.414876e-02 -4.157882e-01 8.419248e+02 +-4.166161e-01 4.902576e-02 9.077596e-01 4.801524e+02 -9.555108e-03 9.982534e-01 -5.829843e-02 -3.743370e+01 -9.090323e-01 -3.296180e-02 -4.154200e-01 8.415323e+02 +-4.150905e-01 5.052643e-02 9.083760e-01 4.810243e+02 -8.278747e-03 9.982055e-01 -5.930606e-02 -3.749411e+01 -9.097424e-01 -3.213759e-02 -4.139273e-01 8.411365e+02 +-4.136572e-01 5.703541e-02 9.086445e-01 4.818915e+02 -5.612688e-03 9.978570e-01 -6.519043e-02 -3.756059e+01 -9.104154e-01 -3.206643e-02 -4.124506e-01 8.407380e+02 +-4.126487e-01 6.614177e-02 9.084857e-01 4.827663e+02 -1.948342e-03 9.972939e-01 -7.349238e-02 -3.761879e+01 -9.108881e-01 -3.209658e-02 -4.114032e-01 8.403395e+02 +-4.126851e-01 7.221131e-02 9.080069e-01 4.836520e+02 -2.888927e-03 9.967438e-01 -8.058134e-02 -3.769111e+01 -9.108692e-01 -3.587788e-02 -4.111327e-01 8.399439e+02 +-4.122976e-01 7.592886e-02 9.078797e-01 4.845462e+02 -5.766567e-03 9.962835e-01 -8.594115e-02 -3.777050e+01 -9.110309e-01 -4.066867e-02 -4.103274e-01 8.395491e+02 +-4.115117e-01 7.979591e-02 9.079046e-01 4.854451e+02 -3.378902e-03 9.960194e-01 -8.907186e-02 -3.785733e+01 -9.113982e-01 -3.972183e-02 -4.096040e-01 8.391432e+02 +-4.100270e-01 8.279314e-02 9.083079e-01 4.863507e+02 8.588059e-04 9.959060e-01 -9.039014e-02 -3.794448e+01 -9.120729e-01 -3.628234e-02 -4.084195e-01 8.387309e+02 +-4.086715e-01 8.810119e-02 9.084194e-01 4.872645e+02 6.842621e-03 9.955978e-01 -9.347774e-02 -3.802906e+01 -9.126559e-01 -3.198572e-02 -4.074753e-01 8.383150e+02 +-4.073160e-01 9.158161e-02 9.086839e-01 4.881883e+02 1.005426e-02 9.953489e-01 -9.580935e-02 -3.812219e+01 -9.132319e-01 -2.988854e-02 -4.063423e-01 8.378914e+02 +-4.066355e-01 9.465216e-02 9.086741e-01 4.891135e+02 1.294884e-02 9.951158e-01 -9.786172e-02 -3.822457e+01 -9.134987e-01 -2.802777e-02 -4.058750e-01 8.374686e+02 +-4.061946e-01 9.704613e-02 9.086188e-01 4.900457e+02 1.463298e-02 9.949078e-01 -9.972073e-02 -3.833058e+01 -9.136694e-01 -2.721022e-02 -4.055462e-01 8.370458e+02 +-4.060453e-01 9.873239e-02 9.085038e-01 4.909875e+02 1.603105e-02 9.947631e-01 -1.009418e-01 -3.843586e+01 -9.137123e-01 -2.642268e-02 -4.055017e-01 8.366230e+02 +-4.060355e-01 1.009455e-01 9.082650e-01 4.919319e+02 1.859832e-02 9.945874e-01 -1.022252e-01 -3.854151e+01 -9.136680e-01 -2.461483e-02 -4.057152e-01 8.361927e+02 +-4.061872e-01 1.036436e-01 9.078932e-01 4.928702e+02 1.968602e-02 9.943088e-01 -1.047012e-01 -3.865404e+01 -9.135778e-01 -2.465549e-02 -4.059159e-01 8.357698e+02 +-4.063939e-01 1.062693e-01 9.074971e-01 4.938031e+02 2.085081e-02 9.940333e-01 -1.070654e-01 -3.877482e+01 -9.134600e-01 -2.458868e-02 -4.061848e-01 8.353511e+02 +-4.066292e-01 1.066002e-01 9.073528e-01 4.947373e+02 2.337969e-02 9.940582e-01 -1.063092e-01 -3.890374e+01 -9.132940e-01 -2.201480e-02 -4.067053e-01 8.349337e+02 +-4.075753e-01 1.033480e-01 9.073046e-01 4.956823e+02 1.970268e-02 9.943390e-01 -1.044111e-01 -3.903371e+01 -9.129590e-01 -2.467903e-02 -4.073043e-01 8.345172e+02 +-4.081030e-01 1.020476e-01 9.072146e-01 4.966247e+02 1.891214e-02 9.944648e-01 -1.033544e-01 -3.916656e+01 -9.127400e-01 -2.502187e-02 -4.077739e-01 8.340944e+02 +-4.082556e-01 1.025469e-01 9.070896e-01 4.975726e+02 1.771390e-02 9.943732e-01 -1.044419e-01 -3.929864e+01 -9.126958e-01 -2.657087e-02 -4.077749e-01 8.336675e+02 +-4.087961e-01 1.026922e-01 9.068297e-01 4.985220e+02 1.714946e-02 9.943379e-01 -1.048710e-01 -3.942995e+01 -9.124646e-01 -2.731922e-02 -4.082426e-01 8.332390e+02 +-4.093970e-01 1.034626e-01 9.064710e-01 4.994743e+02 1.511163e-02 9.941819e-01 -1.066488e-01 -3.956347e+01 -9.122312e-01 -2.996344e-02 -4.085785e-01 8.328096e+02 +-4.088698e-01 1.034120e-01 9.067147e-01 5.004320e+02 1.634225e-02 9.942293e-01 -1.060239e-01 -3.969309e+01 -9.124463e-01 -2.853221e-02 -4.082003e-01 8.323764e+02 +-4.080420e-01 1.037916e-01 9.070441e-01 5.013918e+02 1.881257e-02 9.942616e-01 -1.053087e-01 -3.982399e+01 -9.127693e-01 -2.590655e-02 -4.076531e-01 8.319407e+02 +-4.069726e-01 1.053141e-01 9.073491e-01 5.023585e+02 2.151043e-02 9.941609e-01 -1.057421e-01 -3.995296e+01 -9.131870e-01 -2.351667e-02 -4.068615e-01 8.315026e+02 +-4.056392e-01 1.056216e-01 9.079102e-01 5.033276e+02 2.306938e-02 9.941676e-01 -1.053494e-01 -4.008260e+01 -9.137421e-01 -2.178891e-02 -4.057100e-01 8.310761e+02 +-4.043136e-01 1.046805e-01 9.086102e-01 5.043189e+02 2.247172e-02 9.942658e-01 -1.045494e-01 -4.021815e+01 -9.143443e-01 -2.185272e-02 -4.043475e-01 8.306487e+02 +-4.030578e-01 1.060600e-01 9.090081e-01 5.052868e+02 2.332642e-02 9.941299e-01 -1.056487e-01 -4.035723e+01 -9.148772e-01 -2.137864e-02 -4.031658e-01 8.302367e+02 +-4.016480e-01 1.090123e-01 9.092828e-01 5.062685e+02 2.549639e-02 9.938361e-01 -1.078870e-01 -4.049533e+01 -9.154391e-01 -2.014918e-02 -4.019517e-01 8.298102e+02 +-4.005122e-01 1.106165e-01 9.095900e-01 5.072564e+02 2.683540e-02 9.936766e-01 -1.090262e-01 -4.063241e+01 -9.158984e-01 -1.925712e-02 -4.009480e-01 8.293811e+02 +-3.992521e-01 1.095505e-01 9.102728e-01 5.082480e+02 2.892376e-02 9.938466e-01 -1.069224e-01 -4.076660e+01 -9.163848e-01 -1.636046e-02 -3.999639e-01 8.289483e+02 +-3.983420e-01 1.077193e-01 9.108898e-01 5.092465e+02 3.048444e-02 9.940862e-01 -1.042267e-01 -4.090159e+01 -9.167302e-01 -1.374991e-02 -3.992700e-01 8.285163e+02 +-3.979337e-01 1.086501e-01 9.109577e-01 5.102457e+02 2.845343e-02 9.939462e-01 -1.061189e-01 -4.103406e+01 -9.169728e-01 -1.630841e-02 -3.986161e-01 8.280895e+02 +-3.976562e-01 1.118723e-01 9.106889e-01 5.112441e+02 2.965784e-02 9.935876e-01 -1.091057e-01 -4.116504e+01 -9.170550e-01 -1.637747e-02 -3.984241e-01 8.276581e+02 +-3.973695e-01 1.110507e-01 9.109145e-01 5.122486e+02 3.050125e-02 9.937005e-01 -1.078376e-01 -4.129447e+01 -9.171516e-01 -1.506735e-02 -3.982535e-01 8.272219e+02 +-3.972092e-01 1.100611e-01 9.111045e-01 5.132537e+02 3.263493e-02 9.938487e-01 -1.058289e-01 -4.143062e+01 -9.171476e-01 -1.230239e-02 -3.983576e-01 8.267856e+02 +-3.962758e-01 1.075357e-01 9.118123e-01 5.142671e+02 3.256534e-02 9.941386e-01 -1.030920e-01 -4.156093e+01 -9.175538e-01 -1.115939e-02 -3.974549e-01 8.263471e+02 +-3.951265e-01 1.056725e-01 9.125286e-01 5.152806e+02 3.470014e-02 9.943696e-01 -1.001246e-01 -4.168144e+01 -9.179711e-01 -7.897033e-03 -3.965686e-01 8.259060e+02 +-3.945832e-01 1.004341e-01 9.133549e-01 5.163072e+02 3.354799e-02 9.949204e-01 -9.491002e-02 -4.180005e+01 -9.182475e-01 -6.808685e-03 -3.959482e-01 8.254663e+02 +-3.950170e-01 1.003272e-01 9.131791e-01 5.173278e+02 2.984789e-02 9.948956e-01 -9.639372e-02 -4.191679e+01 -9.181888e-01 -1.082069e-02 -3.959952e-01 8.250315e+02 +-3.949628e-01 1.037904e-01 9.128154e-01 5.183500e+02 2.582843e-02 9.944595e-01 -1.018980e-01 -4.203463e+01 -9.183339e-01 -1.666934e-02 -3.954552e-01 8.246007e+02 +-3.944371e-01 1.058561e-01 9.128055e-01 5.193719e+02 2.615356e-02 9.942336e-01 -1.039978e-01 -4.215528e+01 -9.185506e-01 -1.714747e-02 -3.949311e-01 8.241630e+02 +-3.938718e-01 1.042740e-01 9.132316e-01 5.203885e+02 2.787970e-02 9.944425e-01 -1.015224e-01 -4.227847e+01 -9.187424e-01 -1.452619e-02 -3.945899e-01 8.237191e+02 +-3.934250e-01 1.026984e-01 9.136027e-01 5.214013e+02 2.763103e-02 9.946131e-01 -9.990607e-02 -4.240380e+01 -9.189414e-01 -1.406176e-02 -3.941433e-01 8.232803e+02 +-3.924279e-01 1.046903e-01 9.138054e-01 5.223985e+02 2.909201e-02 9.944170e-01 -1.014323e-01 -4.252347e+01 -9.193225e-01 -1.322041e-02 -3.932826e-01 8.228467e+02 +-3.913512e-01 1.035320e-01 9.143989e-01 5.233891e+02 2.943660e-02 9.945510e-01 -1.000087e-01 -4.264586e+01 -9.197704e-01 -1.222173e-02 -3.922663e-01 8.224203e+02 +-3.907066e-01 9.825496e-02 9.152565e-01 5.243714e+02 2.785579e-02 9.950937e-01 -9.493456e-02 -4.277344e+01 -9.200937e-01 -1.159637e-02 -3.915266e-01 8.220038e+02 +-3.894231e-01 9.673061e-02 9.159655e-01 5.253332e+02 2.701998e-02 9.952417e-01 -9.361504e-02 -4.289700e+01 -9.206625e-01 -1.170649e-02 -3.901838e-01 8.215964e+02 +-3.876830e-01 9.799003e-02 9.165696e-01 5.262834e+02 2.763543e-02 9.951223e-01 -9.469908e-02 -4.301391e+01 -9.213784e-01 -1.138343e-02 -3.885000e-01 8.211904e+02 +-3.856188e-01 9.810669e-02 9.174275e-01 5.272192e+02 2.841184e-02 9.951219e-01 -9.447285e-02 -4.312443e+01 -9.222206e-01 -1.036470e-02 -3.865251e-01 8.207925e+02 +-3.832429e-01 9.683721e-02 9.185573e-01 5.281450e+02 2.981461e-02 9.952676e-01 -9.248494e-02 -4.323518e+01 -9.231663e-01 -8.057764e-03 -3.843163e-01 8.204022e+02 +-3.809470e-01 9.546465e-02 9.196554e-01 5.290570e+02 3.041727e-02 9.954110e-01 -9.072878e-02 -4.334280e+01 -9.240964e-01 -6.589448e-03 -3.821025e-01 8.200236e+02 +-3.787345e-01 9.562582e-02 9.205520e-01 5.299509e+02 3.140829e-02 9.954029e-01 -9.047923e-02 -4.344686e+01 -9.249722e-01 -5.354637e-03 -3.799968e-01 8.196542e+02 +-3.767869e-01 9.630441e-02 9.212802e-01 5.308449e+02 3.158169e-02 9.953381e-01 -9.112961e-02 -4.354929e+01 -9.257614e-01 -5.240864e-03 -3.780718e-01 8.192852e+02 +-3.752038e-01 9.595975e-02 9.219620e-01 5.317048e+02 3.068211e-02 9.953677e-01 -9.111353e-02 -4.364315e+01 -9.264344e-01 -5.898407e-03 -3.764100e-01 8.189340e+02 +-3.738949e-01 9.464000e-02 9.226299e-01 5.325599e+02 2.913874e-02 9.954878e-01 -9.030507e-02 -4.373915e+01 -9.270132e-01 -6.880336e-03 -3.749655e-01 8.185871e+02 +-3.729637e-01 9.248412e-02 9.232252e-01 5.333996e+02 2.938075e-02 9.956981e-01 -8.787490e-02 -4.383482e+01 -9.273806e-01 -5.649098e-03 -3.740765e-01 8.182461e+02 +-3.729544e-01 8.755125e-02 9.237098e-01 5.342265e+02 2.634388e-02 9.961360e-01 -8.377946e-02 -4.392728e+01 -9.274756e-01 -6.911820e-03 -3.738197e-01 8.179164e+02 +-3.741076e-01 8.280922e-02 9.236808e-01 5.350463e+02 2.078680e-02 9.965039e-01 -8.091889e-02 -4.401613e+01 -9.271523e-01 -1.107201e-02 -3.745210e-01 8.175910e+02 +-3.765159e-01 7.873850e-02 9.230580e-01 5.358564e+02 1.512154e-02 9.967711e-01 -7.885830e-02 -4.410260e+01 -9.262867e-01 -1.573335e-02 -3.764908e-01 8.172702e+02 +-3.801216e-01 7.581628e-02 9.218240e-01 5.366567e+02 1.105777e-02 9.969361e-01 -7.743419e-02 -4.418142e+01 -9.248704e-01 -1.924109e-02 -3.797952e-01 8.169466e+02 +-3.851652e-01 7.339467e-02 9.199245e-01 5.374500e+02 6.925968e-03 9.970342e-01 -7.664691e-02 -4.425863e+01 -9.228216e-01 -2.315035e-02 -3.845312e-01 8.166194e+02 +-3.923949e-01 7.161976e-02 9.170043e-01 5.382400e+02 3.196569e-03 9.970641e-01 -7.650475e-02 -4.433053e+01 -9.197913e-01 -2.708880e-02 -3.914717e-01 8.162897e+02 +-4.013949e-01 7.032417e-02 9.132014e-01 5.390235e+02 3.766344e-04 9.970605e-01 -7.661650e-02 -4.440262e+01 -9.159050e-01 -3.040953e-02 -4.002415e-01 8.159529e+02 +-4.123335e-01 6.824851e-02 9.084731e-01 5.397944e+02 -1.975532e-03 9.971207e-01 -7.580477e-02 -4.447246e+01 -9.110308e-01 -3.305156e-02 -4.110114e-01 8.156002e+02 +-4.247789e-01 6.497317e-02 9.029626e-01 5.405635e+02 -2.477128e-03 9.973340e-01 -7.292904e-02 -4.454548e+01 -9.052937e-01 -3.321546e-02 -4.234854e-01 8.152416e+02 +-4.381713e-01 5.947077e-02 8.969221e-01 5.413173e+02 -3.930260e-03 9.976727e-01 -6.807113e-02 -4.461358e+01 -8.988828e-01 -3.335195e-02 -4.369178e-01 8.148663e+02 +-4.524316e-01 5.335628e-02 8.902016e-01 5.420709e+02 -4.792446e-03 9.980487e-01 -6.225605e-02 -4.468302e+01 -8.917862e-01 -3.243284e-02 -4.512930e-01 8.144885e+02 +-4.672739e-01 5.021798e-02 8.826853e-01 5.428107e+02 -4.263526e-03 9.982459e-01 -5.904951e-02 -4.475087e+01 -8.841023e-01 -3.135564e-02 -4.662401e-01 8.141006e+02 +-4.825847e-01 4.762956e-02 8.745533e-01 5.435320e+02 -4.622073e-03 9.983678e-01 -5.692321e-02 -4.481550e+01 -8.758371e-01 -3.151252e-02 -4.815769e-01 8.136886e+02 +-4.987794e-01 4.062225e-02 8.657765e-01 5.442603e+02 -8.457556e-03 9.986254e-01 -5.172798e-02 -4.487684e+01 -8.666877e-01 -3.312320e-02 -4.977502e-01 8.132810e+02 +-5.161261e-01 3.052183e-02 8.559686e-01 5.449837e+02 -1.161095e-02 9.990237e-01 -4.262394e-02 -4.493698e+01 -8.564339e-01 -3.193793e-02 -5.152678e-01 8.128590e+02 +-5.351522e-01 2.038107e-02 8.445098e-01 5.456869e+02 -1.477102e-02 9.993303e-01 -3.347762e-02 -4.499113e+01 -8.446265e-01 -3.038989e-02 -5.344927e-01 8.123968e+02 +-5.569374e-01 1.300339e-02 8.304527e-01 5.463933e+02 -2.269260e-02 9.992659e-01 -3.086534e-02 -4.504379e+01 -8.302444e-01 -3.603519e-02 -5.562334e-01 8.119513e+02 +-5.808182e-01 1.147126e-02 8.139525e-01 5.470620e+02 -3.025985e-02 9.989054e-01 -3.567060e-02 -4.508733e+01 -8.134707e-01 -4.534821e-02 -5.798352e-01 8.114549e+02 +-6.064237e-01 1.155589e-02 7.950577e-01 5.477347e+02 -3.406586e-02 9.985987e-01 -4.049775e-02 -4.512763e+01 -7.944116e-01 -5.164311e-02 -6.051802e-01 8.109718e+02 +-6.330736e-01 9.021761e-03 7.740391e-01 5.483955e+02 -3.680080e-02 9.984507e-01 -4.173615e-02 -4.517569e+01 -7.732163e-01 -5.490730e-02 -6.317607e-01 8.104670e+02 +-6.604878e-01 1.223452e-03 7.508359e-01 5.490080e+02 -4.310628e-02 9.982875e-01 -3.954597e-02 -4.522002e+01 -7.495984e-01 -5.848536e-02 -6.593039e-01 8.098892e+02 +-6.878496e-01 -3.307758e-03 7.258457e-01 5.496294e+02 -4.585175e-02 9.981904e-01 -3.890268e-02 -4.526859e+01 -7.244035e-01 -6.004048e-02 -6.867565e-01 8.093394e+02 +-7.139450e-01 -2.601752e-03 7.001970e-01 5.501853e+02 -4.332729e-02 9.982409e-01 -4.046881e-02 -4.532000e+01 -6.988600e-01 -5.923013e-02 -7.128018e-01 8.087116e+02 +-7.391975e-01 -4.112693e-03 6.734763e-01 5.507590e+02 -4.555611e-02 9.979964e-01 -4.390729e-02 -4.536428e+01 -6.719462e-01 -6.313710e-02 -7.379037e-01 8.081170e+02 +-7.636230e-01 -7.149496e-03 6.456228e-01 5.512976e+02 -4.759079e-02 9.978419e-01 -4.523905e-02 -4.545519e+01 -6.439061e-01 -6.527126e-02 -7.623152e-01 8.075021e+02 +-7.868619e-01 -1.137169e-02 6.170244e-01 5.517808e+02 -4.823537e-02 9.979047e-01 -4.312102e-02 -4.555422e+01 -6.152412e-01 -6.369268e-02 -7.857617e-01 8.068063e+02 +-8.093274e-01 -1.719485e-02 5.871061e-01 5.522920e+02 -5.089002e-02 9.978653e-01 -4.092710e-02 -4.565947e+01 -5.851490e-01 -6.300125e-02 -8.084747e-01 8.061451e+02 +-8.312012e-01 -1.896639e-02 5.556482e-01 5.527799e+02 -5.215954e-02 9.976702e-01 -4.397183e-02 -4.576338e+01 -5.535197e-01 -6.553178e-02 -8.302539e-01 8.054651e+02 +-8.522994e-01 -2.134198e-02 5.226188e-01 5.532070e+02 -5.395104e-02 9.974249e-01 -4.725322e-02 -4.584676e+01 -5.202645e-01 -6.846971e-02 -8.512559e-01 8.046955e+02 +-8.721784e-01 -2.368420e-02 4.886144e-01 5.536468e+02 -5.355474e-02 9.974465e-01 -4.724699e-02 -4.594647e+01 -4.862477e-01 -6.737541e-02 -8.712196e-01 8.039547e+02 +-8.905898e-01 -2.900147e-02 4.538820e-01 5.540254e+02 -5.464154e-02 9.975591e-01 -4.347501e-02 -4.603236e+01 -4.515133e-01 -6.351920e-02 -8.900006e-01 8.031229e+02 +-9.075563e-01 -3.030412e-02 4.188356e-01 5.544123e+02 -5.181687e-02 9.978519e-01 -4.008187e-02 -4.613149e+01 -4.167213e-01 -5.807929e-02 -9.071770e-01 8.023241e+02 +-9.227244e-01 -3.038542e-02 3.842609e-01 5.547689e+02 -4.874870e-02 9.980827e-01 -3.813675e-02 -4.621018e+01 -3.823653e-01 -5.392192e-02 -9.224365e-01 8.014978e+02 +-9.361692e-01 -2.629865e-02 3.505649e-01 5.550538e+02 -4.288144e-02 9.982941e-01 -3.962319e-02 -4.629431e+01 -3.489248e-01 -5.212673e-02 -9.356998e-01 8.006038e+02 +-9.477369e-01 -2.143851e-02 3.183319e-01 5.553448e+02 -3.632838e-02 9.985021e-01 -4.091123e-02 -4.636143e+01 -3.169780e-01 -5.033756e-02 -9.470961e-01 7.997299e+02 +-9.572331e-01 -1.645053e-02 2.888500e-01 5.556075e+02 -2.974996e-02 9.986866e-01 -4.171273e-02 -4.642904e+01 -2.877844e-01 -4.852207e-02 -9.564652e-01 7.988300e+02 +-9.644914e-01 -1.238216e-02 2.638239e-01 5.558338e+02 -2.446235e-02 9.987947e-01 -4.255301e-02 -4.650416e+01 -2.629790e-01 -4.749575e-02 -9.636317e-01 7.978907e+02 +-9.695010e-01 -6.839881e-03 2.449919e-01 5.560593e+02 -1.856209e-02 9.987886e-01 -4.557039e-02 -4.657189e+01 -2.443834e-01 -4.872809e-02 -9.684535e-01 7.969544e+02 +-9.729057e-01 -2.875739e-03 2.311847e-01 5.562718e+02 -1.467080e-02 9.986754e-01 -4.931719e-02 -4.664851e+01 -2.307366e-01 -5.137262e-02 -9.716591e-01 7.959998e+02 +-9.751899e-01 5.397334e-04 2.213697e-01 5.564862e+02 -1.124258e-02 9.985858e-01 -5.196117e-02 -4.672274e+01 -2.210846e-01 -5.316076e-02 -9.738046e-01 7.950317e+02 +-9.768749e-01 2.334190e-03 2.137991e-01 5.566964e+02 -9.226034e-03 9.985489e-01 -5.305677e-02 -4.680351e+01 -2.136127e-01 -5.380234e-02 -9.754357e-01 7.940501e+02 +-9.782298e-01 4.837132e-03 2.074682e-01 5.569014e+02 -6.475127e-03 9.985301e-01 -5.381158e-02 -4.687803e+01 -2.074236e-01 -5.398347e-02 -9.767605e-01 7.930530e+02 +-9.790033e-01 7.430559e-03 2.037093e-01 5.571031e+02 -4.059484e-03 9.984265e-01 -5.592836e-02 -4.695231e+01 -2.038043e-01 -5.558099e-02 -9.774326e-01 7.920437e+02 +-9.794355e-01 1.166470e-02 2.014203e-01 5.573030e+02 8.102800e-05 9.983499e-01 -5.742270e-02 -4.702622e+01 -2.017577e-01 -5.622550e-02 -9.778202e-01 7.910267e+02 +-9.796718e-01 1.632745e-02 1.999416e-01 5.575033e+02 5.053557e-03 9.983746e-01 -5.676708e-02 -4.710128e+01 -2.005435e-01 -5.460268e-02 -9.781619e-01 7.899915e+02 +-9.798796e-01 1.943941e-02 1.986410e-01 5.577069e+02 8.209680e-03 9.983289e-01 -5.720086e-02 -4.717769e+01 -1.994210e-01 -5.441917e-02 -9.784016e-01 7.889509e+02 +-9.800160e-01 2.259807e-02 1.976309e-01 5.579114e+02 1.168247e-02 9.983498e-01 -5.622489e-02 -4.725449e+01 -1.985754e-01 -5.279247e-02 -9.786627e-01 7.878992e+02 +-9.799616e-01 2.840070e-02 1.971517e-01 5.581104e+02 1.816049e-02 9.983997e-01 -5.355612e-02 -4.732950e+01 -1.983572e-01 -4.890256e-02 -9.789090e-01 7.868320e+02 +-9.798716e-01 3.149198e-02 1.971294e-01 5.583141e+02 2.198891e-02 9.984964e-01 -5.021238e-02 -4.740374e+01 -1.984143e-01 -4.486702e-02 -9.790907e-01 7.857574e+02 +-9.798074e-01 3.365962e-02 1.970904e-01 5.585226e+02 2.440396e-02 9.984905e-01 -4.920405e-02 -4.747529e+01 -1.984491e-01 -4.340070e-02 -9.791498e-01 7.846707e+02 +-9.796381e-01 3.350999e-02 1.979556e-01 5.587371e+02 2.405322e-02 9.984602e-01 -4.998575e-02 -4.754593e+01 -1.993258e-01 -4.420646e-02 -9.789356e-01 7.835824e+02 +-9.795488e-01 3.008764e-02 1.989446e-01 5.589630e+02 2.082084e-02 9.986057e-01 -4.850934e-02 -4.761747e+01 -2.001267e-01 -4.337506e-02 -9.788094e-01 7.824802e+02 +-9.794153e-01 2.666515e-02 2.000866e-01 5.591956e+02 1.780410e-02 9.987848e-01 -4.595584e-02 -4.769143e+01 -2.010689e-01 -4.144748e-02 -9.786998e-01 7.813705e+02 +-9.791521e-01 2.406370e-02 2.016984e-01 5.594306e+02 1.490880e-02 9.987936e-01 -4.678618e-02 -4.776660e+01 -2.025809e-01 -4.280370e-02 -9.783295e-01 7.802551e+02 +-9.788250e-01 2.490523e-02 2.031781e-01 5.596643e+02 1.479322e-02 9.985820e-01 -5.113720e-02 -4.784007e+01 -2.041636e-01 -4.704871e-02 -9.778055e-01 7.791323e+02 +-9.785307e-01 2.604792e-02 2.044485e-01 5.599003e+02 1.527441e-02 9.984188e-01 -5.409805e-02 -4.791547e+01 -2.055343e-01 -4.981376e-02 -9.773813e-01 7.779998e+02 +-9.782177e-01 2.673995e-02 2.058522e-01 5.601395e+02 1.597430e-02 9.984248e-01 -5.378373e-02 -4.799562e+01 -2.069661e-01 -4.932384e-02 -9.771039e-01 7.768552e+02 +-9.778473e-01 2.646690e-02 2.076399e-01 5.603835e+02 1.588694e-02 9.984968e-01 -5.245682e-02 -4.807710e+01 -2.087161e-01 -4.799598e-02 -9.767978e-01 7.757025e+02 +-9.774245e-01 2.743974e-02 2.094959e-01 5.606290e+02 1.684921e-02 9.984960e-01 -5.217122e-02 -4.815784e+01 -2.106124e-01 -4.746358e-02 -9.764167e-01 7.745416e+02 +-9.771173e-01 2.289380e-02 2.114656e-01 5.608847e+02 1.220605e-02 9.985876e-01 -5.170928e-02 -4.823660e+01 -2.123508e-01 -4.794486e-02 -9.760166e-01 7.733720e+02 +-9.768402e-01 2.073092e-02 2.129635e-01 5.611437e+02 1.029319e-02 9.986959e-01 -5.000430e-02 -4.831491e+01 -2.137224e-01 -4.665413e-02 -9.757797e-01 7.721901e+02 +-9.767080e-01 1.641803e-02 2.139437e-01 5.614101e+02 5.319982e-03 9.986148e-01 -5.234660e-02 -4.838960e+01 -2.145068e-01 -4.998915e-02 -9.754424e-01 7.710072e+02 +-9.765127e-01 1.619769e-02 2.148503e-01 5.616832e+02 4.052709e-03 9.983746e-01 -5.684818e-02 -4.845644e+01 -2.154219e-01 -5.464224e-02 -9.749910e-01 7.698148e+02 +-9.761787e-01 1.941801e-02 2.160974e-01 5.619557e+02 6.540313e-03 9.981680e-01 -6.014850e-02 -4.853302e+01 -2.168695e-01 -5.730233e-02 -9.745173e-01 7.686062e+02 +-9.758088e-01 2.190703e-02 2.175254e-01 5.622330e+02 9.204643e-03 9.982015e-01 -5.923755e-02 -4.861152e+01 -2.184319e-01 -5.580227e-02 -9.742554e-01 7.673846e+02 +-9.755144e-01 2.312535e-02 2.187166e-01 5.625097e+02 1.128199e-02 9.984091e-01 -5.524421e-02 -4.869401e+01 -2.196461e-01 -5.142396e-02 -9.742233e-01 7.661571e+02 +-9.752963e-01 2.215299e-02 2.197873e-01 5.627943e+02 1.114424e-02 9.986261e-01 -5.120235e-02 -4.877224e+01 -2.206196e-01 -4.748809e-02 -9.742031e-01 7.649214e+02 +-9.753417e-01 2.066887e-02 2.197305e-01 5.630798e+02 9.989699e-03 9.987191e-01 -4.960184e-02 -4.884902e+01 -2.204742e-01 -4.618370e-02 -9.742988e-01 7.636830e+02 +-9.752896e-01 1.892784e-02 2.201183e-01 5.633765e+02 8.302810e-03 9.987596e-01 -4.909510e-02 -4.893044e+01 -2.207745e-01 -4.605433e-02 -9.742369e-01 7.624392e+02 +-9.750926e-01 1.878477e-02 2.210013e-01 5.636656e+02 8.288732e-03 9.987972e-01 -4.832506e-02 -4.899987e+01 -2.216433e-01 -4.528958e-02 -9.740755e-01 7.611946e+02 +-9.749412e-01 2.057278e-02 2.215095e-01 5.639484e+02 1.067222e-02 9.988936e-01 -4.580047e-02 -4.905898e+01 -2.222067e-01 -4.228876e-02 -9.740820e-01 7.599433e+02 +-9.747965e-01 2.085032e-02 2.221195e-01 5.642314e+02 1.160256e-02 9.990138e-01 -4.285818e-02 -4.912595e+01 -2.227940e-01 -3.920085e-02 -9.740770e-01 7.586884e+02 +-9.748018e-01 2.115647e-02 2.220673e-01 5.645120e+02 1.212856e-02 9.990465e-01 -4.193937e-02 -4.919738e+01 -2.227428e-01 -3.818921e-02 -9.741289e-01 7.574394e+02 +-9.748399e-01 2.221163e-02 2.217971e-01 5.647951e+02 1.305964e-02 9.990049e-01 -4.264472e-02 -4.926618e+01 -2.225236e-01 -3.867517e-02 -9.741598e-01 7.561858e+02 +-9.749593e-01 2.273532e-02 2.212183e-01 5.650775e+02 1.357267e-02 9.989892e-01 -4.285156e-02 -4.933810e+01 -2.219689e-01 -3.877600e-02 -9.742824e-01 7.549375e+02 +-9.750501e-01 2.242400e-02 2.208497e-01 5.653605e+02 1.292446e-02 9.989317e-01 -4.436527e-02 -4.941209e+01 -2.216086e-01 -4.040399e-02 -9.742982e-01 7.536919e+02 +-9.751237e-01 2.311849e-02 2.204525e-01 5.656411e+02 1.305467e-02 9.988096e-01 -4.699906e-02 -4.948947e+01 -2.212766e-01 -4.295195e-02 -9.742647e-01 7.524487e+02 +-9.751356e-01 2.347757e-02 2.203621e-01 5.659217e+02 1.310694e-02 9.987417e-01 -4.840665e-02 -4.956704e+01 -2.212213e-01 -4.431476e-02 -9.742162e-01 7.512065e+02 +-9.750367e-01 2.419971e-02 2.207214e-01 5.662023e+02 1.387797e-02 9.987415e-01 -4.819532e-02 -4.964844e+01 -2.216099e-01 -4.392903e-02 -9.741454e-01 7.499557e+02 +-9.748831e-01 2.433443e-02 2.213838e-01 5.664794e+02 1.402740e-02 9.987483e-01 -4.801121e-02 -4.973274e+01 -2.222750e-01 -4.369987e-02 -9.740041e-01 7.487045e+02 +-9.746685e-01 2.517246e-02 2.222337e-01 5.667572e+02 1.458178e-02 9.986840e-01 -4.916872e-02 -4.981941e+01 -2.231789e-01 -4.468263e-02 -9.737528e-01 7.474570e+02 +-9.745230e-01 2.406582e-02 2.229931e-01 5.670387e+02 1.341605e-02 9.987012e-01 -4.915098e-02 -4.990607e+01 -2.238864e-01 -4.490707e-02 -9.735801e-01 7.462100e+02 +-9.744719e-01 2.154933e-02 2.234731e-01 5.673269e+02 1.124441e-02 9.988182e-01 -4.728313e-02 -4.998504e+01 -2.242280e-01 -4.356325e-02 -9.735625e-01 7.449582e+02 +-9.743757e-01 1.926587e-02 2.241001e-01 5.676176e+02 9.279896e-03 9.989199e-01 -4.552860e-02 -5.006576e+01 -2.247352e-01 -4.228233e-02 -9.735020e-01 7.437074e+02 +-9.743078e-01 1.570893e-02 2.246724e-01 5.679140e+02 5.909025e-03 9.990041e-01 -4.422475e-02 -5.014650e+01 -2.251434e-01 -4.176092e-02 -9.734302e-01 7.424554e+02 +-9.741837e-01 9.362670e-03 2.255629e-01 5.682093e+02 -3.181063e-04 9.990817e-01 -4.284382e-02 -5.022282e+01 -2.257569e-01 -4.180949e-02 -9.732860e-01 7.412052e+02 +-9.741122e-01 3.342621e-04 2.260650e-01 5.685123e+02 -8.992439e-03 9.991501e-01 -4.022573e-02 -5.029612e+01 -2.258863e-01 -4.121724e-02 -9.732813e-01 7.399531e+02 +-9.742461e-01 -3.846535e-03 2.254545e-01 5.688098e+02 -1.316632e-02 9.991189e-01 -3.984883e-02 -5.036970e+01 -2.251026e-01 -4.179097e-02 -9.734384e-01 7.387002e+02 +-9.743867e-01 -3.588732e-03 2.248506e-01 5.691001e+02 -1.386529e-02 9.989290e-01 -4.414163e-02 -5.044813e+01 -2.244513e-01 -4.612862e-02 -9.733928e-01 7.374491e+02 +-9.742547e-01 3.308084e-03 2.254260e-01 5.693818e+02 -8.417983e-03 9.986613e-01 -5.103637e-02 -5.053035e+01 -2.252930e-01 -5.162005e-02 -9.729226e-01 7.362000e+02 +-9.738706e-01 1.304953e-02 2.267284e-01 5.696516e+02 9.668158e-05 9.983715e-01 -5.704683e-02 -5.061196e+01 -2.271036e-01 -5.553430e-02 -9.722859e-01 7.349488e+02 +-9.737991e-01 1.850210e-02 2.266563e-01 5.699278e+02 5.951684e-03 9.984169e-01 -5.593085e-02 -5.069980e+01 -2.273323e-01 -5.311641e-02 -9.723675e-01 7.336930e+02 +-9.739308e-01 1.829420e-02 2.261066e-01 5.702128e+02 7.231839e-03 9.987401e-01 -4.965734e-02 -5.078631e+01 -2.267302e-01 -4.672764e-02 -9.728360e-01 7.324290e+02 +-9.741530e-01 1.458501e-02 2.254181e-01 5.705044e+02 4.767123e-03 9.990185e-01 -4.403730e-02 -5.086285e+01 -2.258391e-01 -4.182446e-02 -9.732663e-01 7.311650e+02 +-9.743142e-01 1.064408e-02 2.249414e-01 5.707956e+02 2.171268e-03 9.992799e-01 -3.788065e-02 -5.093516e+01 -2.251827e-01 -3.641924e-02 -9.736356e-01 7.299029e+02 +-9.745978e-01 5.186660e-03 2.239024e-01 5.710894e+02 -2.407125e-03 9.994315e-01 -3.362939e-02 -5.100207e+01 -2.239495e-01 -3.331408e-02 -9.740312e-01 7.286428e+02 +-9.749168e-01 -7.068809e-05 2.225697e-01 5.713817e+02 -7.978917e-03 9.993682e-01 -3.463249e-02 -5.106803e+01 -2.224267e-01 -3.553966e-02 -9.743014e-01 7.273909e+02 +-9.751820e-01 -3.496111e-03 2.213773e-01 5.716696e+02 -1.231566e-02 9.991838e-01 -3.847169e-02 -5.113441e+01 -2.210621e-01 -4.024330e-02 -9.744290e-01 7.261412e+02 +-9.753003e-01 -3.529105e-03 2.208553e-01 5.719528e+02 -1.264750e-02 9.991242e-01 -3.988632e-02 -5.120365e+01 -2.205210e-01 -4.169440e-02 -9.744906e-01 7.248915e+02 +-9.753999e-01 -2.749353e-03 2.204259e-01 5.722312e+02 -1.242587e-02 9.990181e-01 -4.252470e-02 -5.127912e+01 -2.200925e-01 -4.421756e-02 -9.744763e-01 7.236458e+02 +-9.754852e-01 1.303521e-03 2.200614e-01 5.725052e+02 -8.961202e-03 9.989177e-01 -4.564016e-02 -5.135814e+01 -2.198827e-01 -4.649331e-02 -9.744177e-01 7.224010e+02 +-9.755262e-01 3.979796e-03 2.198472e-01 5.727784e+02 -6.450565e-03 9.988879e-01 -4.670550e-02 -5.143676e+01 -2.197886e-01 -4.698057e-02 -9.744156e-01 7.211549e+02 +-9.755677e-01 3.795443e-03 2.196666e-01 5.730541e+02 -6.012745e-03 9.990150e-01 -4.396459e-02 -5.151895e+01 -2.196171e-01 -4.421123e-02 -9.745838e-01 7.199048e+02 +-9.756234e-01 1.934313e-03 2.194432e-01 5.733308e+02 -7.703985e-03 9.990429e-01 -4.305743e-02 -5.160099e+01 -2.193164e-01 -4.369841e-02 -9.746746e-01 7.186567e+02 +-9.757150e-01 3.973536e-04 2.190438e-01 5.736081e+02 -9.595562e-03 9.989608e-01 -4.455493e-02 -5.168296e+01 -2.188339e-01 -4.557476e-02 -9.746972e-01 7.174109e+02 +-9.758430e-01 -1.988753e-03 2.184643e-01 5.738897e+02 -1.201434e-02 9.989339e-01 -4.457244e-02 -5.176922e+01 -2.181427e-01 -4.612040e-02 -9.748264e-01 7.161631e+02 +-9.759704e-01 -4.153108e-03 2.178639e-01 5.741690e+02 -1.393636e-02 9.989611e-01 -4.338805e-02 -5.185530e+01 -2.174573e-01 -4.538167e-02 -9.750142e-01 7.149094e+02 +-9.761308e-01 -5.026570e-03 2.171257e-01 5.744450e+02 -1.411554e-02 9.990867e-01 -4.032983e-02 -5.193821e+01 -2.167246e-01 -4.243202e-02 -9.753101e-01 7.136582e+02 +-9.764637e-01 -6.016111e-03 2.155979e-01 5.747186e+02 -1.475262e-02 9.991328e-01 -3.893594e-02 -5.201912e+01 -2.151767e-01 -4.120016e-02 -9.757056e-01 7.124048e+02 +-9.769865e-01 -7.057707e-03 2.131848e-01 5.749914e+02 -1.570426e-02 9.991200e-01 -3.889285e-02 -5.209567e+01 -2.127226e-01 -4.134568e-02 -9.762374e-01 7.111544e+02 +-9.776648e-01 -9.652705e-03 2.099487e-01 5.752614e+02 -1.783547e-02 9.991517e-01 -3.711668e-02 -5.217166e+01 -2.094124e-01 -4.003220e-02 -9.770076e-01 7.098992e+02 +-9.786387e-01 -1.256481e-02 2.052034e-01 5.755271e+02 -1.975786e-02 9.992586e-01 -3.304195e-02 -5.224381e+01 -2.046361e-01 -3.639050e-02 -9.781614e-01 7.086396e+02 +-9.797568e-01 -1.463602e-02 1.996560e-01 5.757835e+02 -2.106279e-02 9.993248e-01 -3.010315e-02 -5.231398e+01 -1.990806e-01 -3.369908e-02 -9.794035e-01 7.073813e+02 +-9.809114e-01 -1.167587e-02 1.941043e-01 5.760302e+02 -1.883576e-02 9.992069e-01 -3.508222e-02 -5.238191e+01 -1.935408e-01 -3.806865e-02 -9.803533e-01 7.061243e+02 +-9.819351e-01 -2.821727e-03 1.891974e-01 5.762613e+02 -1.158644e-02 9.989091e-01 -4.523581e-02 -5.245526e+01 -1.888633e-01 -4.661074e-02 -9.808965e-01 7.048698e+02 +-9.828692e-01 4.636607e-03 1.842466e-01 5.764840e+02 -4.800259e-03 9.987004e-01 -5.073970e-02 -5.253647e+01 -1.842424e-01 -5.075491e-02 -9.815694e-01 7.036084e+02 +-9.837615e-01 7.763823e-03 1.793130e-01 5.767076e+02 -1.298436e-03 9.987299e-01 -5.036626e-02 -5.262161e+01 -1.794762e-01 -4.978120e-02 -9.825019e-01 7.023401e+02 +-9.846913e-01 1.202040e-02 1.738926e-01 5.769307e+02 3.409356e-03 9.987567e-01 -4.973356e-02 -5.269890e+01 -1.742742e-01 -4.837933e-02 -9.835079e-01 7.010643e+02 +-9.854258e-01 1.291161e-02 1.696155e-01 5.771514e+02 4.876230e-03 9.988495e-01 -4.770553e-02 -5.277842e+01 -1.700363e-01 -4.618316e-02 -9.843549e-01 6.997889e+02 +-9.859745e-01 1.579189e-02 1.661475e-01 5.773664e+02 7.947700e-03 9.988266e-01 -4.777165e-02 -5.285693e+01 -1.667070e-01 -4.578113e-02 -9.849430e-01 6.985100e+02 +-9.863947e-01 1.854610e-02 1.633453e-01 5.775759e+02 1.050731e-02 9.986969e-01 -4.994079e-02 -5.293843e+01 -1.640586e-01 -4.754500e-02 -9.853041e-01 6.972347e+02 +-9.868830e-01 2.083618e-02 1.600869e-01 5.777834e+02 1.267856e-02 9.985764e-01 -5.181105e-02 -5.302031e+01 -1.609385e-01 -4.910176e-02 -9.857422e-01 6.959489e+02 +-9.874033e-01 2.114319e-02 1.568047e-01 5.779887e+02 1.324339e-02 9.985978e-01 -5.125474e-02 -5.310570e+01 -1.576685e-01 -4.853247e-02 -9.862987e-01 6.946637e+02 +-9.879148e-01 2.093648e-02 1.535777e-01 5.781924e+02 1.316902e-02 9.985902e-01 -5.142090e-02 -5.319316e+01 -1.544377e-01 -4.877698e-02 -9.867977e-01 6.933753e+02 +-9.883663e-01 2.195637e-02 1.504996e-01 5.783913e+02 1.413889e-02 9.985040e-01 -5.281826e-02 -5.328070e+01 -1.514342e-01 -5.007588e-02 -9.871980e-01 6.920861e+02 +-9.888390e-01 2.219982e-02 1.473248e-01 5.785861e+02 1.461956e-02 9.985224e-01 -5.233769e-02 -5.336771e+01 -1.482690e-01 -4.959972e-02 -9.877024e-01 6.907953e+02 +-9.892759e-01 2.180363e-02 1.444227e-01 5.787785e+02 1.463217e-02 9.986151e-01 -5.053358e-02 -5.345656e+01 -1.453245e-01 -4.787842e-02 -9.882248e-01 6.894960e+02 +-9.897181e-01 2.042581e-02 1.415660e-01 5.789688e+02 1.373039e-02 9.987476e-01 -4.811197e-02 -5.354336e+01 -1.423714e-01 -4.567352e-02 -9.887589e-01 6.881965e+02 +-9.901635e-01 1.712136e-02 1.388636e-01 5.791589e+02 1.070001e-02 9.988442e-01 -4.685765e-02 -5.362774e+01 -1.395053e-01 -4.491088e-02 -9.892023e-01 6.868968e+02 +-9.906107e-01 1.492627e-02 1.358961e-01 5.793459e+02 8.881985e-03 9.989486e-01 -4.497547e-02 -5.370991e+01 -1.364246e-01 -4.334614e-02 -9.897016e-01 6.855918e+02 +-9.910625e-01 1.399787e-02 1.326622e-01 5.795269e+02 8.414846e-03 9.990588e-01 -4.255218e-02 -5.378984e+01 -1.331329e-01 -4.105553e-02 -9.902474e-01 6.842839e+02 +-9.914344e-01 1.447453e-02 1.298016e-01 5.797018e+02 9.138749e-03 9.990921e-01 -4.160911e-02 -5.386895e+01 -1.302860e-01 -4.006647e-02 -9.906665e-01 6.829734e+02 +-9.917153e-01 1.657458e-02 1.273816e-01 5.798573e+02 1.127586e-02 9.990453e-01 -4.220642e-02 -5.393214e+01 -1.279596e-01 -4.042040e-02 -9.909553e-01 6.816654e+02 +-9.919846e-01 1.893013e-02 1.249332e-01 5.800121e+02 1.366533e-02 9.989874e-01 -4.286429e-02 -5.400142e+01 -1.256182e-01 -4.081346e-02 -9.912387e-01 6.803526e+02 +-9.922855e-01 1.972301e-02 1.223948e-01 5.801587e+02 1.444110e-02 9.989318e-01 -4.389294e-02 -5.407581e+01 -1.231297e-01 -4.178680e-02 -9.915104e-01 6.790390e+02 +-9.926366e-01 1.863659e-02 1.196884e-01 5.803106e+02 1.362824e-02 9.990023e-01 -4.252810e-02 -5.414946e+01 -1.203615e-01 -4.058380e-02 -9.919002e-01 6.777205e+02 +-9.929750e-01 1.818083e-02 1.169198e-01 5.804626e+02 1.364286e-02 9.991265e-01 -3.949665e-02 -5.421613e+01 -1.175358e-01 -3.762406e-02 -9.923556e-01 6.763937e+02 +-9.933129e-01 1.803959e-02 1.140354e-01 5.806121e+02 1.377868e-02 9.991811e-01 -3.804330e-02 -5.428474e+01 -1.146283e-01 -3.621764e-02 -9.927480e-01 6.750686e+02 +-9.936844e-01 1.619554e-02 1.110368e-01 5.807588e+02 1.212190e-02 9.992319e-01 -3.726487e-02 -5.435176e+01 -1.115550e-01 -3.568354e-02 -9.931173e-01 6.737464e+02 +-9.940528e-01 1.630974e-02 1.076710e-01 5.808961e+02 1.233519e-02 9.992213e-01 -3.747728e-02 -5.441768e+01 -1.081984e-01 -3.592624e-02 -9.934799e-01 6.724301e+02 +-9.944841e-01 1.479066e-02 1.038401e-01 5.810295e+02 1.080159e-02 9.991857e-01 -3.887341e-02 -5.448917e+01 -1.043305e-01 -3.753734e-02 -9.938340e-01 6.711113e+02 +-9.949193e-01 1.318408e-02 9.980939e-02 5.811550e+02 9.186086e-03 9.991409e-01 -4.041052e-02 -5.456017e+01 -1.002564e-01 -3.928834e-02 -9.941856e-01 6.697962e+02 +-9.953131e-01 1.185109e-02 9.597673e-02 5.812783e+02 8.203466e-03 9.992322e-01 -3.831125e-02 -5.463224e+01 -9.635706e-02 -3.734433e-02 -9.946460e-01 6.684817e+02 +-9.957164e-01 1.013247e-02 9.190327e-02 5.813941e+02 6.978176e-03 9.993776e-01 -3.457864e-02 -5.470458e+01 -9.219643e-02 -3.378919e-02 -9.951673e-01 6.671702e+02 +-9.961224e-01 7.332424e-03 8.767310e-02 5.815107e+02 4.472891e-03 9.994530e-01 -3.276804e-02 -5.477092e+01 -8.786541e-02 -3.224882e-02 -9.956102e-01 6.658657e+02 +-9.965032e-01 5.351953e-03 8.338406e-02 5.816192e+02 2.911065e-03 9.995644e-01 -2.936707e-02 -5.483605e+01 -8.350491e-02 -2.902164e-02 -9.960846e-01 6.645621e+02 +-9.968199e-01 3.967958e-03 7.958884e-02 5.817240e+02 1.838399e-03 9.996388e-01 -2.681257e-02 -5.489990e+01 -7.966647e-02 -2.658098e-02 -9.964671e-01 6.632638e+02 +-9.971404e-01 2.918365e-03 7.551594e-02 5.818229e+02 1.052836e-03 9.996935e-01 -2.473192e-02 -5.496282e+01 -7.556497e-02 -2.458168e-02 -9.968378e-01 6.619697e+02 +-9.974245e-01 1.372970e-03 7.171140e-02 5.819172e+02 -2.917151e-04 9.997308e-01 -2.319816e-02 -5.502102e+01 -7.172394e-02 -2.315933e-02 -9.971556e-01 6.606790e+02 +-9.976784e-01 2.236965e-03 6.806460e-02 5.820018e+02 6.946662e-04 9.997426e-01 -2.267470e-02 -5.507699e+01 -6.809780e-02 -2.257478e-02 -9.974232e-01 6.593959e+02 +-9.979124e-01 2.884668e-03 6.451827e-02 5.820779e+02 1.288186e-03 9.996923e-01 -2.477270e-02 -5.513496e+01 -6.456987e-02 -2.463787e-02 -9.976089e-01 6.581129e+02 +-9.981079e-01 5.554122e-03 6.123578e-02 5.821493e+02 3.839129e-03 9.995980e-01 -2.808870e-02 -5.519276e+01 -6.136717e-02 -2.780046e-02 -9.977280e-01 6.568330e+02 +-9.982659e-01 8.992831e-03 5.817483e-02 5.822133e+02 7.221556e-03 9.995060e-01 -3.058651e-02 -5.525226e+01 -5.842115e-02 -3.011336e-02 -9.978377e-01 6.555567e+02 +-9.984037e-01 1.347010e-02 5.485172e-02 5.822739e+02 1.190858e-02 9.995172e-01 -2.869620e-02 -5.531196e+01 -5.521178e-02 -2.799717e-02 -9.980820e-01 6.542749e+02 +-9.985258e-01 1.658631e-02 5.168331e-02 5.823294e+02 1.535931e-02 9.995928e-01 -2.404833e-02 -5.537085e+01 -5.206113e-02 -2.321905e-02 -9.983739e-01 6.529873e+02 +-9.986358e-01 1.820519e-02 4.894152e-02 5.823839e+02 1.711160e-02 9.995965e-01 -2.267194e-02 -5.542548e+01 -4.933452e-02 -2.180354e-02 -9.985442e-01 6.517066e+02 +-9.987661e-01 1.766883e-02 4.641336e-02 5.824379e+02 1.664020e-02 9.996093e-01 -2.245633e-02 -5.547586e+01 -4.679200e-02 -2.165629e-02 -9.986698e-01 6.504271e+02 +-9.989809e-01 1.358605e-02 4.304347e-02 5.824951e+02 1.258535e-02 9.996461e-01 -2.343509e-02 -5.552931e+01 -4.334663e-02 -2.286948e-02 -9.987983e-01 6.491456e+02 +-9.991679e-01 8.596362e-03 3.987042e-02 5.825503e+02 7.698277e-03 9.997144e-01 -2.262443e-02 -5.558048e+01 -4.005351e-02 -2.229866e-02 -9.989486e-01 6.478594e+02 +-9.993024e-01 5.655518e-03 3.691567e-02 5.825998e+02 4.926828e-03 9.997918e-01 -1.980075e-02 -5.562979e+01 -3.701996e-02 -1.960506e-02 -9.991221e-01 6.465772e+02 +-9.994150e-01 1.838125e-03 3.415099e-02 5.826527e+02 1.257823e-03 9.998546e-01 -1.700622e-02 -5.567942e+01 -3.417729e-02 -1.695331e-02 -9.992719e-01 6.452828e+02 +-9.994967e-01 -3.014380e-03 3.158009e-02 5.827037e+02 -3.519286e-03 9.998667e-01 -1.594501e-02 -5.572573e+01 -3.152782e-02 -1.604812e-02 -9.993740e-01 6.439897e+02 +-9.995358e-01 -8.681073e-03 2.920302e-02 5.827539e+02 -9.151620e-03 9.998298e-01 -1.601835e-02 -5.577029e+01 -2.905899e-02 -1.627817e-02 -9.994451e-01 6.426938e+02 +-9.995750e-01 -1.118194e-02 2.692451e-02 5.827985e+02 -1.169041e-02 9.997548e-01 -1.880276e-02 -5.581740e+01 -2.670766e-02 -1.910952e-02 -9.994606e-01 6.413994e+02 +-9.996577e-01 -7.257669e-03 2.513810e-02 5.828301e+02 -7.926838e-03 9.996141e-01 -2.662349e-02 -5.586795e+01 -2.493517e-02 -2.681363e-02 -9.993294e-01 6.401093e+02 +-9.997034e-01 1.558710e-03 2.430410e-02 5.828514e+02 7.413583e-04 9.994349e-01 -3.360339e-02 -5.592478e+01 -2.434275e-02 -3.357540e-02 -9.991396e-01 6.388134e+02 +-9.996507e-01 1.018073e-02 2.439017e-02 5.828648e+02 9.364330e-03 9.993996e-01 -3.335638e-02 -5.598772e+01 -2.471512e-02 -3.311632e-02 -9.991458e-01 6.375087e+02 +-9.995538e-01 1.714377e-02 2.446239e-02 5.828765e+02 1.647158e-02 9.994882e-01 -2.742088e-02 -5.605039e+01 -2.491996e-02 -2.700570e-02 -9.993246e-01 6.362015e+02 +-9.995351e-01 1.856603e-02 2.418742e-02 5.828988e+02 1.798671e-02 9.995512e-01 -2.395296e-02 -5.610708e+01 -2.462128e-02 -2.350676e-02 -9.994204e-01 6.348900e+02 +-9.995778e-01 1.633861e-02 2.402700e-02 5.829259e+02 1.584964e-02 9.996662e-01 -2.040273e-02 -5.615728e+01 -2.435233e-02 -2.001329e-02 -9.995030e-01 6.335792e+02 +-9.995859e-01 1.512601e-02 2.448184e-02 5.829545e+02 1.467311e-02 9.997198e-01 -1.857526e-02 -5.620544e+01 -2.475595e-02 -1.820834e-02 -9.995276e-01 6.322647e+02 +-9.995627e-01 1.542143e-02 2.523177e-02 5.829824e+02 1.501722e-02 9.997571e-01 -1.613195e-02 -5.625063e+01 -2.547442e-02 -1.574598e-02 -9.995514e-01 6.309495e+02 +-9.995242e-01 1.579167e-02 2.649569e-02 5.830123e+02 1.539270e-02 9.997660e-01 -1.519516e-02 -5.629631e+01 -2.672945e-02 -1.478009e-02 -9.995334e-01 6.296335e+02 +-9.994437e-01 1.809155e-02 2.801827e-02 5.830417e+02 1.766990e-02 9.997279e-01 -1.522466e-02 -5.634074e+01 -2.828609e-02 -1.472111e-02 -9.994914e-01 6.283207e+02 +-9.993830e-01 1.872260e-02 2.971934e-02 5.830731e+02 1.833212e-02 9.997427e-01 -1.335782e-02 -5.638326e+01 -2.996178e-02 -1.280475e-02 -9.994690e-01 6.270034e+02 +-9.993343e-01 1.855189e-02 3.141519e-02 5.831099e+02 1.825289e-02 9.997856e-01 -9.778215e-03 -5.642371e+01 -3.158986e-02 -9.198284e-03 -9.994585e-01 6.256856e+02 +-9.992962e-01 1.763739e-02 3.310674e-02 5.831495e+02 1.736002e-02 9.998119e-01 -8.647005e-03 -5.646227e+01 -3.325302e-02 -8.066183e-03 -9.994144e-01 6.243745e+02 +-9.992498e-01 1.736636e-02 3.461549e-02 5.831921e+02 1.709616e-02 9.998211e-01 -8.086864e-03 -5.649914e+01 -3.474974e-02 -7.489003e-03 -9.993679e-01 6.230616e+02 +-9.992398e-01 1.523168e-02 3.588838e-02 5.832365e+02 1.500478e-02 9.998657e-01 -6.583761e-03 -5.653482e+01 -3.598384e-02 -6.040257e-03 -9.993341e-01 6.217574e+02 +-9.992142e-01 1.401827e-02 3.707526e-02 5.832833e+02 1.380497e-02 9.998867e-01 -6.003027e-03 -5.656748e+01 -3.715521e-02 -5.486484e-03 -9.992944e-01 6.204479e+02 +-9.991748e-01 1.404648e-02 3.811120e-02 5.833289e+02 1.381164e-02 9.998840e-01 -6.418653e-03 -5.659970e+01 -3.819694e-02 -5.886976e-03 -9.992528e-01 6.191430e+02 +-9.991477e-01 1.349257e-02 3.901036e-02 5.833780e+02 1.325381e-02 9.998918e-01 -6.372667e-03 -5.663237e+01 -3.909212e-02 -5.850197e-03 -9.992184e-01 6.178360e+02 +-9.991101e-01 1.326468e-02 4.004027e-02 5.834272e+02 1.301389e-02 9.998940e-01 -6.518051e-03 -5.666570e+01 -4.012249e-02 -5.991169e-03 -9.991768e-01 6.165298e+02 +-9.990630e-01 1.428799e-02 4.085489e-02 5.834753e+02 1.393885e-02 9.998639e-01 -8.818310e-03 -5.669953e+01 -4.097532e-02 -8.240574e-03 -9.991261e-01 6.152237e+02 +-9.990163e-01 1.593477e-02 4.138370e-02 5.835233e+02 1.549511e-02 9.998203e-01 -1.092345e-02 -5.673457e+01 -4.155032e-02 -1.027146e-02 -9.990836e-01 6.139137e+02 +-9.990094e-01 1.532332e-02 4.177839e-02 5.835745e+02 1.484005e-02 9.998196e-01 -1.185349e-02 -5.677132e+01 -4.195249e-02 -1.122176e-02 -9.990565e-01 6.126002e+02 +-9.989824e-01 1.581809e-02 4.223785e-02 5.836259e+02 1.551234e-02 9.998511e-01 -7.557059e-03 -5.680666e+01 -4.235110e-02 -6.894159e-03 -9.990789e-01 6.112822e+02 +-9.990137e-01 1.281548e-02 4.251329e-02 5.836519e+02 1.261546e-02 9.999080e-01 -4.969970e-03 -5.684437e+01 -4.257307e-02 -4.428741e-03 -9.990835e-01 6.099677e+02 +-9.990221e-01 1.265774e-02 4.236391e-02 5.836883e+02 1.235066e-02 9.998956e-01 -7.502742e-03 -5.687854e+01 -4.245445e-02 -6.972180e-03 -9.990740e-01 6.086546e+02 +-9.990534e-01 9.330903e-03 4.248906e-02 5.837207e+02 8.900640e-03 9.999073e-01 -1.030460e-02 -5.691512e+01 -4.258127e-02 -9.916664e-03 -9.990437e-01 6.073411e+02 +-9.990636e-01 7.026051e-03 4.269180e-02 5.837632e+02 6.552173e-03 9.999155e-01 -1.123001e-02 -5.695394e+01 -4.276709e-02 -1.093976e-02 -9.990251e-01 6.060287e+02 +-9.990698e-01 6.223888e-03 4.267243e-02 5.837967e+02 5.732527e-03 9.999159e-01 -1.162764e-02 -5.700158e+01 -4.274121e-02 -1.137220e-02 -9.990214e-01 6.047151e+02 +-9.990676e-01 6.434313e-03 4.269190e-02 5.838345e+02 6.095325e-03 9.999489e-01 -8.065979e-03 -5.704896e+01 -4.274162e-02 -7.798235e-03 -9.990557e-01 6.033963e+02 +-9.990570e-01 7.577318e-03 4.275265e-02 5.838675e+02 7.387815e-03 9.999622e-01 -4.589018e-03 -5.709234e+01 -4.278580e-02 -4.268840e-03 -9.990751e-01 6.020824e+02 +-9.990210e-01 9.777881e-03 4.314642e-02 5.839031e+02 9.665380e-03 9.999493e-01 -2.815486e-03 -5.713130e+01 -4.317176e-02 -2.395701e-03 -9.990647e-01 6.007678e+02 +-9.989710e-01 1.240304e-02 4.362462e-02 5.839343e+02 1.227128e-02 9.999193e-01 -3.287141e-03 -5.716886e+01 -4.366187e-02 -2.748427e-03 -9.990425e-01 5.994620e+02 +-9.989377e-01 1.398914e-02 4.390697e-02 5.839633e+02 1.381438e-02 9.998954e-01 -4.281502e-03 -5.720655e+01 -4.396227e-02 -3.670404e-03 -9.990264e-01 5.981604e+02 +-9.989461e-01 1.280961e-02 4.407516e-02 5.840005e+02 1.256553e-02 9.999041e-01 -5.810663e-03 -5.724510e+01 -4.414537e-02 -5.250709e-03 -9.990113e-01 5.968627e+02 +-9.989720e-01 1.153395e-02 4.384048e-02 5.840365e+02 1.132883e-02 9.999237e-01 -4.924560e-03 -5.728251e+01 -4.389393e-02 -4.422834e-03 -9.990264e-01 5.955628e+02 +-9.989974e-01 9.327851e-03 4.378554e-02 5.840812e+02 9.200076e-03 9.999528e-01 -3.119011e-03 -5.731299e+01 -4.381256e-02 -2.713052e-03 -9.990360e-01 5.942707e+02 +-9.989870e-01 1.027568e-02 4.381236e-02 5.841204e+02 1.023734e-02 9.999470e-01 -1.099537e-03 -5.733890e+01 -4.382133e-02 -6.499003e-04 -9.990391e-01 5.929811e+02 +-9.989707e-01 1.143781e-02 4.389530e-02 5.841622e+02 1.145821e-02 9.999343e-01 2.128306e-04 -5.736590e+01 -4.388998e-02 7.155739e-04 -9.990361e-01 5.916892e+02 +-9.989594e-01 1.100266e-02 4.426133e-02 5.841928e+02 1.092182e-02 9.999382e-01 -2.067985e-03 -5.734259e+01 -4.428134e-02 -1.582417e-03 -9.990178e-01 5.904060e+02 +-9.989310e-01 1.274412e-02 4.443580e-02 5.842084e+02 1.246210e-02 9.999004e-01 -6.618140e-03 -5.723955e+01 -4.451572e-02 -6.057299e-03 -9.989903e-01 5.891391e+02 +-9.989144e-01 1.235989e-02 4.491516e-02 5.842273e+02 1.196463e-02 9.998874e-01 -9.058532e-03 -5.713610e+01 -4.502207e-02 -8.511301e-03 -9.989497e-01 5.878679e+02 +-9.988106e-01 1.460302e-02 4.652073e-02 5.842544e+02 1.427942e-02 9.998715e-01 -7.281047e-03 -5.707801e+01 -4.662108e-02 -6.608096e-03 -9.988907e-01 5.865860e+02 +-9.986174e-01 1.780236e-02 4.946163e-02 5.842856e+02 1.761056e-02 9.998356e-01 -4.311146e-03 -5.703130e+01 -4.953024e-02 -3.434137e-03 -9.987667e-01 5.853034e+02 +-9.983035e-01 2.183540e-02 5.397553e-02 5.843176e+02 2.175538e-02 9.997612e-01 -2.069814e-03 -5.697620e+01 -5.400783e-02 -8.920433e-04 -9.985401e-01 5.840245e+02 +-9.978830e-01 2.457129e-02 6.021514e-02 5.843651e+02 2.441612e-02 9.996964e-01 -3.311634e-03 -5.693540e+01 -6.027823e-02 -1.834402e-03 -9.981799e-01 5.827438e+02 +-9.973471e-01 2.721490e-02 6.751396e-02 5.844210e+02 2.694740e-02 9.996250e-01 -4.870026e-03 -5.689262e+01 -6.762118e-02 -3.037779e-03 -9.977064e-01 5.814685e+02 +-9.967782e-01 2.519748e-02 7.614706e-02 5.844990e+02 2.503231e-02 9.996817e-01 -3.123072e-03 -5.687459e+01 -7.620151e-02 -1.206872e-03 -9.970917e-01 5.801927e+02 +-9.960521e-01 2.403506e-02 8.545574e-02 5.845877e+02 2.387773e-02 9.997108e-01 -2.863008e-03 -5.685192e+01 -8.549983e-02 -8.112152e-04 -9.963378e-01 5.789252e+02 +-9.952199e-01 2.327743e-02 9.484477e-02 5.846894e+02 2.311235e-02 9.997288e-01 -2.838912e-03 -5.684742e+01 -9.488513e-02 -6.332546e-04 -9.954880e-01 5.776583e+02 +-9.943028e-01 2.161930e-02 1.043773e-01 5.848080e+02 2.150737e-02 9.997663e-01 -2.198034e-03 -5.683127e+01 -1.044005e-01 5.937107e-05 -9.945353e-01 5.763972e+02 +-9.932254e-01 1.963833e-02 1.145323e-01 5.849417e+02 1.959332e-02 9.998069e-01 -1.518890e-03 -5.683299e+01 -1.145400e-01 7.354693e-04 -9.934183e-01 5.751404e+02 +-9.919219e-01 1.978181e-02 1.252982e-01 5.850812e+02 1.967017e-02 9.998042e-01 -2.128354e-03 -5.683312e+01 -1.253158e-01 3.534778e-04 -9.921168e-01 5.738848e+02 +-9.904755e-01 2.069387e-02 1.361252e-01 5.852385e+02 2.032960e-02 9.997850e-01 -4.065846e-03 -5.684281e+01 -1.361800e-01 -1.259750e-03 -9.906832e-01 5.726363e+02 +-9.889387e-01 1.982592e-02 1.469940e-01 5.854119e+02 1.944454e-02 9.998028e-01 -4.031221e-03 -5.685440e+01 -1.470449e-01 -1.128399e-03 -9.891291e-01 5.713919e+02 +-9.873020e-01 1.950194e-02 1.576532e-01 5.855953e+02 1.947361e-02 9.998089e-01 -1.724612e-03 -5.686525e+01 -1.576567e-01 1.367365e-03 -9.874930e-01 5.701446e+02 +-9.856542e-01 1.738602e-02 1.678799e-01 5.857968e+02 1.802548e-02 9.998349e-01 2.285752e-03 -5.687837e+01 -1.678124e-01 5.279076e-03 -9.858048e-01 5.689013e+02 +-9.841553e-01 1.416210e-02 1.767422e-01 5.860092e+02 1.538927e-02 9.998660e-01 5.574359e-03 -5.688789e+01 -1.766395e-01 8.205968e-03 -9.842413e-01 5.676627e+02 +-9.828701e-01 1.139700e-02 1.839470e-01 5.862356e+02 1.290292e-02 9.998923e-01 6.991788e-03 -5.689675e+01 -1.838475e-01 9.245472e-03 -9.829113e-01 5.664320e+02 +-9.816315e-01 9.916840e-03 1.905290e-01 5.864805e+02 1.175807e-02 9.998944e-01 8.535642e-03 -5.689947e+01 -1.904243e-01 1.061911e-02 -9.816444e-01 5.651937e+02 +-9.804586e-01 5.012174e-03 1.966620e-01 5.867296e+02 6.975584e-03 9.999325e-01 9.292220e-03 -5.690622e+01 -1.966021e-01 1.048247e-02 -9.804273e-01 5.639625e+02 +-9.795941e-01 1.514497e-03 2.009807e-01 5.869882e+02 3.486056e-03 9.999492e-01 9.456086e-03 -5.690853e+01 -2.009562e-01 9.963754e-03 -9.795495e-01 5.627329e+02 +-9.789686e-01 -2.834116e-03 2.039914e-01 5.872485e+02 -9.252032e-04 9.999549e-01 9.452533e-03 -5.691498e+01 -2.040089e-01 9.064998e-03 -9.789270e-01 5.615076e+02 +-9.786089e-01 -4.773728e-03 2.056743e-01 5.875098e+02 -3.058646e-03 9.999578e-01 8.655922e-03 -5.692120e+01 -2.057069e-01 7.841676e-03 -9.785822e-01 5.602830e+02 +-9.781789e-01 -5.815476e-03 2.076830e-01 5.877712e+02 -4.494720e-03 9.999665e-01 6.830765e-03 -5.692924e+01 -2.077158e-01 5.748233e-03 -9.781723e-01 5.590597e+02 +-9.778502e-01 -3.367268e-03 2.092789e-01 5.880299e+02 -2.168279e-03 9.999799e-01 5.958267e-03 -5.693772e+01 -2.092947e-01 5.372517e-03 -9.778378e-01 5.578365e+02 +-9.774180e-01 -3.035064e-03 2.112932e-01 5.882952e+02 -2.084717e-03 9.999867e-01 4.720339e-03 -5.695006e+01 -2.113047e-01 4.173258e-03 -9.774113e-01 5.566134e+02 +-9.770305e-01 -1.648769e-03 2.130934e-01 5.885634e+02 -1.157404e-03 9.999964e-01 2.430559e-03 -5.696469e+01 -2.130966e-01 2.128095e-03 -9.770288e-01 5.553925e+02 +-9.766217e-01 -2.399070e-03 2.149522e-01 5.888386e+02 -2.419885e-03 9.999970e-01 1.662844e-04 -5.698049e+01 -2.149520e-01 -3.577623e-04 -9.766245e-01 5.541716e+02 +-9.763341e-01 -4.014091e-03 2.162306e-01 5.891165e+02 -4.131464e-03 9.999914e-01 -9.083179e-05 -5.699936e+01 -2.162284e-01 -9.820305e-04 -9.763423e-01 5.529469e+02 +-9.760249e-01 -5.653812e-03 2.175859e-01 5.893975e+02 -5.763746e-03 9.999834e-01 1.293777e-04 -5.701924e+01 -2.175830e-01 -1.127833e-03 -9.760411e-01 5.517258e+02 +-9.757452e-01 -5.912822e-03 2.188295e-01 5.896737e+02 -6.265916e-03 9.999799e-01 -9.196319e-04 -5.704214e+01 -2.188196e-01 -2.268493e-03 -9.757626e-01 5.505094e+02 +-9.754510e-01 -5.752056e-03 2.201416e-01 5.899542e+02 -6.234917e-03 9.999794e-01 -1.498697e-03 -5.706040e+01 -2.201284e-01 -2.834469e-03 -9.754667e-01 5.492938e+02 +-9.752603e-01 -6.552833e-03 2.209627e-01 5.902332e+02 -6.697303e-03 9.999775e-01 9.532839e-05 -5.707661e+01 -2.209584e-01 -1.386884e-03 -9.752822e-01 5.480819e+02 +-9.753505e-01 -7.873201e-03 2.205210e-01 5.905161e+02 -7.195851e-03 9.999666e-01 3.874702e-03 -5.708806e+01 -2.205441e-01 2.192356e-03 -9.753745e-01 5.468665e+02 +-9.755496e-01 -1.007547e-02 2.195483e-01 5.907951e+02 -8.765349e-03 9.999375e-01 6.940605e-03 -5.710133e+01 -2.196045e-01 4.846486e-03 -9.755769e-01 5.456598e+02 +-9.758773e-01 -1.062487e-02 2.180610e-01 5.910716e+02 -9.330458e-03 9.999322e-01 6.964837e-03 -5.711153e+01 -2.181202e-01 4.762217e-03 -9.759102e-01 5.444589e+02 +-9.762884e-01 -1.249608e-02 2.161133e-01 5.913435e+02 -1.128293e-02 9.999129e-01 6.846361e-03 -5.712285e+01 -2.161800e-01 4.245631e-03 -9.763442e-01 5.432619e+02 +-9.769613e-01 -1.574082e-02 2.128354e-01 5.916132e+02 -1.451850e-02 9.998679e-01 7.304829e-03 -5.713452e+01 -2.129222e-01 4.046485e-03 -9.770607e-01 5.420720e+02 +-9.779197e-01 -1.922240e-02 2.080954e-01 5.918794e+02 -1.838291e-02 9.998132e-01 5.967414e-03 -5.714718e+01 -2.081712e-01 2.010252e-03 -9.780903e-01 5.408795e+02 +-9.790925e-01 -1.874039e-02 2.025508e-01 5.921322e+02 -1.882101e-02 9.998217e-01 1.528166e-03 -5.716388e+01 -2.025433e-01 -2.315995e-03 -9.792705e-01 5.396986e+02 +-9.802436e-01 -1.715764e-02 1.970486e-01 5.923759e+02 -1.834382e-02 9.998229e-01 -4.195994e-03 -5.718322e+01 -1.969417e-01 -7.727719e-03 -9.803847e-01 5.385219e+02 +-9.813708e-01 -1.382530e-02 1.916253e-01 5.926046e+02 -1.501090e-02 9.998761e-01 -4.736764e-03 -5.720841e+01 -1.915361e-01 -7.524988e-03 -9.814567e-01 5.373442e+02 +-9.823932e-01 -1.051912e-02 1.865291e-01 5.928280e+02 -1.077437e-02 9.999419e-01 -3.547226e-04 -5.723035e+01 -1.865146e-01 -2.358211e-03 -9.824493e-01 5.361626e+02 +-9.834396e-01 -7.912678e-03 1.810637e-01 5.930421e+02 -7.391689e-03 9.999664e-01 3.551922e-03 -5.725050e+01 -1.810857e-01 2.154734e-03 -9.834649e-01 5.349857e+02 +-9.843286e-01 -7.528153e-03 1.761836e-01 5.932538e+02 -6.733872e-03 9.999643e-01 5.105664e-03 -5.726930e+01 -1.762157e-01 3.839253e-03 -9.843440e-01 5.338175e+02 +-9.850578e-01 -8.183768e-03 1.720297e-01 5.934600e+02 -7.249511e-03 9.999553e-01 6.058301e-03 -5.728599e+01 -1.720716e-01 4.720645e-03 -9.850731e-01 5.326590e+02 +-9.856639e-01 -5.330854e-03 1.686365e-01 5.936559e+02 -4.273042e-03 9.999688e-01 6.634960e-03 -5.730332e+01 -1.686666e-01 5.819250e-03 -9.856559e-01 5.315138e+02 +-9.859864e-01 -3.044508e-03 1.667983e-01 5.938472e+02 -1.841337e-03 9.999711e-01 7.367456e-03 -5.731799e+01 -1.668159e-01 6.957079e-03 -9.859635e-01 5.303850e+02 +-9.860953e-01 3.918180e-04 1.661809e-01 5.940317e+02 2.281077e-03 9.999349e-01 1.117793e-02 -5.733174e+01 -1.661656e-01 1.140157e-02 -9.860319e-01 5.292772e+02 +-9.859723e-01 3.072386e-03 1.668812e-01 5.942114e+02 5.872259e-03 9.998501e-01 1.628673e-02 -5.734537e+01 -1.668062e-01 1.703823e-02 -9.858424e-01 5.281891e+02 +-9.857730e-01 6.792191e-03 1.679453e-01 5.943846e+02 1.030302e-02 9.997460e-01 2.004204e-02 -5.735502e+01 -1.677665e-01 2.148724e-02 -9.855925e-01 5.271252e+02 +-9.854818e-01 8.303762e-03 1.695783e-01 5.945545e+02 1.207750e-02 9.997016e-01 2.123420e-02 -5.736569e+01 -1.693513e-01 2.297400e-02 -9.852879e-01 5.260810e+02 +-9.850268e-01 1.062590e-02 1.720737e-01 5.947239e+02 1.392454e-02 9.997415e-01 1.797417e-02 -5.737909e+01 -1.718382e-01 2.010108e-02 -9.849200e-01 5.250582e+02 +-9.843759e-01 1.264947e-02 1.756251e-01 5.948999e+02 1.550108e-02 9.997692e-01 1.487448e-02 -5.738726e+01 -1.753964e-01 1.736446e-02 -9.843447e-01 5.240585e+02 +-9.835561e-01 1.594092e-02 1.798980e-01 5.950758e+02 1.924585e-02 9.996763e-01 1.664057e-02 -5.739299e+01 -1.795745e-01 1.982922e-02 -9.835445e-01 5.230726e+02 +-9.826247e-01 1.661949e-02 1.848580e-01 5.952565e+02 2.102233e-02 9.995395e-01 2.188285e-02 -5.740229e+01 -1.844092e-01 2.538877e-02 -9.825215e-01 5.221078e+02 +-9.816377e-01 1.817328e-02 1.898876e-01 5.954367e+02 2.282400e-02 9.994900e-01 2.233360e-02 -5.740937e+01 -1.893849e-01 2.625749e-02 -9.815517e-01 5.211719e+02 +-9.806383e-01 2.014908e-02 1.947884e-01 5.956173e+02 2.433817e-02 9.995206e-01 1.913617e-02 -5.741358e+01 -1.943094e-01 2.350645e-02 -9.806585e-01 5.202551e+02 +-9.796858e-01 2.185974e-02 1.993440e-01 5.957985e+02 2.560568e-02 9.995403e-01 1.623234e-02 -5.741994e+01 -1.988975e-01 2.100692e-02 -9.797951e-01 5.193643e+02 +-9.788487e-01 2.177521e-02 2.034238e-01 5.959819e+02 2.551131e-02 9.995502e-01 1.576162e-02 -5.742711e+01 -2.029891e-01 2.061784e-02 -9.789639e-01 5.184899e+02 +-9.781180e-01 2.104228e-02 2.069843e-01 5.961664e+02 2.523337e-02 9.995261e-01 1.762885e-02 -5.743522e+01 -2.065152e-01 2.246600e-02 -9.781854e-01 5.176268e+02 +-9.776064e-01 1.998686e-02 2.094905e-01 5.963493e+02 2.441984e-02 9.995288e-01 1.859526e-02 -5.744441e+01 -2.090202e-01 2.329457e-02 -9.776338e-01 5.167825e+02 +-9.773053e-01 1.904513e-02 2.109779e-01 5.965306e+02 2.355810e-02 9.995438e-01 1.889772e-02 -5.745057e+01 -2.105217e-01 2.343907e-02 -9.773081e-01 5.159525e+02 +-9.773201e-01 1.957920e-02 2.108604e-01 5.967048e+02 2.386752e-02 9.995564e-01 1.781120e-02 -5.745673e+01 -2.104181e-01 2.243996e-02 -9.773538e-01 5.151432e+02 +-9.777329e-01 1.914362e-02 2.089784e-01 5.968743e+02 2.316315e-02 9.995904e-01 1.680359e-02 -5.746330e+01 -2.085711e-01 2.127002e-02 -9.777758e-01 5.143530e+02 +-9.786759e-01 1.680325e-02 2.047223e-01 5.970371e+02 2.053179e-02 9.996595e-01 1.610198e-02 -5.747102e+01 -2.043820e-01 1.996193e-02 -9.786876e-01 5.135825e+02 +-9.801810e-01 1.292795e-02 1.976821e-01 5.971949e+02 1.636288e-02 9.997420e-01 1.575237e-02 -5.747826e+01 -1.974274e-01 1.867482e-02 -9.801396e-01 5.128335e+02 +-9.822100e-01 9.616294e-03 1.875394e-01 5.973348e+02 1.313851e-02 9.997597e-01 1.754718e-02 -5.748381e+01 -1.873256e-01 1.969901e-02 -9.821003e-01 5.120969e+02 +-9.847817e-01 7.712473e-03 1.736251e-01 5.974620e+02 1.127907e-02 9.997449e-01 1.956460e-02 -5.749007e+01 -1.734299e-01 2.122519e-02 -9.846174e-01 5.113852e+02 +-9.877035e-01 3.887758e-03 1.562904e-01 5.975762e+02 7.201321e-03 9.997610e-01 2.064063e-02 -5.749824e+01 -1.561728e-01 2.151231e-02 -9.874954e-01 5.106943e+02 +-9.907853e-01 1.092593e-03 1.354379e-01 5.976591e+02 3.812333e-03 9.997962e-01 1.982328e-02 -5.750419e+01 -1.353886e-01 2.015695e-02 -9.905875e-01 5.100024e+02 +-9.938081e-01 -1.506041e-03 1.111000e-01 5.977348e+02 5.657982e-04 9.998266e-01 1.861446e-02 -5.751111e+01 -1.111088e-01 1.856206e-02 -9.936348e-01 5.093307e+02 +-9.964714e-01 -2.848726e-03 8.388569e-02 5.977866e+02 -1.321306e-03 9.998324e-01 1.825814e-02 -5.752252e+01 -8.392364e-02 1.808287e-02 -9.963080e-01 5.086679e+02 +-9.985306e-01 -2.878657e-03 5.411518e-02 5.977876e+02 -1.851931e-03 9.998175e-01 1.901340e-02 -5.753434e+01 -5.416004e-02 1.888524e-02 -9.983536e-01 5.079842e+02 +-9.997470e-01 -2.889365e-03 2.231018e-02 5.977964e+02 -2.451033e-03 9.998039e-01 1.964920e-02 -5.754502e+01 -2.236258e-02 1.958954e-02 -9.995579e-01 5.073280e+02 +-9.999315e-01 -2.899758e-03 -1.133919e-02 5.977475e+02 -3.113287e-03 9.998173e-01 1.885978e-02 -5.755639e+01 1.128243e-02 1.889379e-02 -9.997578e-01 5.066495e+02 +-9.988989e-01 -1.198715e-03 -4.689964e-02 5.977084e+02 -2.042200e-03 9.998369e-01 1.794130e-02 -5.756445e+01 4.687048e-02 1.801733e-02 -9.987384e-01 5.060070e+02 +-9.965003e-01 1.280946e-03 -8.357982e-02 5.976442e+02 -3.786344e-04 9.998031e-01 1.983746e-02 -5.757229e+01 8.358877e-02 1.979968e-02 -9.963036e-01 5.053681e+02 +-9.927477e-01 5.335567e-03 -1.200982e-01 5.975146e+02 2.363033e-03 9.996876e-01 2.487975e-02 -5.757232e+01 1.201935e-01 2.441552e-02 -9.924502e-01 5.046977e+02 +-9.876604e-01 7.556415e-03 -1.564286e-01 5.974026e+02 2.549090e-03 9.994786e-01 3.218625e-02 -5.757722e+01 1.565902e-01 3.139033e-02 -9.871646e-01 5.040652e+02 +-9.809877e-01 9.181863e-03 -1.938526e-01 5.972261e+02 1.836764e-03 9.992747e-01 3.803597e-02 -5.758064e+01 1.940612e-01 3.695675e-02 -9.802930e-01 5.034050e+02 +-9.724148e-01 1.134857e-02 -2.329822e-01 5.970705e+02 2.654162e-03 9.992894e-01 3.759760e-02 -5.758387e+01 2.332433e-01 3.594209e-02 -9.717539e-01 5.028000e+02 +-9.616930e-01 1.125044e-02 -2.738979e-01 5.968945e+02 2.559039e-03 9.994824e-01 3.206894e-02 -5.757975e+01 2.741169e-01 3.013955e-02 -9.612239e-01 5.022121e+02 +-9.485179e-01 6.907489e-03 -3.166482e-01 5.966372e+02 -9.730825e-04 9.996939e-01 2.472261e-02 -5.757401e+01 3.167220e-01 2.375796e-02 -9.482208e-01 5.015798e+02 +-9.330614e-01 7.131232e-03 -3.596466e-01 5.964024e+02 -9.906386e-04 9.997487e-01 2.239358e-02 -5.756562e+01 3.597159e-01 2.125086e-02 -9.328198e-01 5.009983e+02 +-9.155889e-01 1.118782e-02 -4.019601e-01 5.960701e+02 8.305209e-04 9.996633e-01 2.593204e-02 -5.756044e+01 4.021149e-01 2.340925e-02 -9.152899e-01 5.003668e+02 +-8.957505e-01 1.733940e-02 -4.442190e-01 5.957679e+02 4.021542e-03 9.995142e-01 3.090524e-02 -5.755399e+01 4.445390e-01 2.589693e-02 -8.953850e-01 4.997929e+02 +-8.734036e-01 2.090377e-02 -4.865484e-01 5.954389e+02 4.718876e-03 9.993947e-01 3.446655e-02 -5.754715e+01 4.869743e-01 2.780724e-02 -8.729735e-01 4.992287e+02 +-8.484927e-01 2.374114e-02 -5.286743e-01 5.949970e+02 3.971658e-03 9.992507e-01 3.849901e-02 -5.752233e+01 5.291922e-01 3.056641e-02 -8.479512e-01 4.986087e+02 +-8.209914e-01 2.588749e-02 -5.703534e-01 5.945957e+02 2.271495e-03 9.991117e-01 4.207852e-02 -5.750248e+01 5.709360e-01 3.325055e-02 -8.203209e-01 4.980616e+02 +-7.911174e-01 2.735982e-02 -6.110522e-01 5.941625e+02 -2.294516e-03 9.988593e-01 4.769455e-02 -5.748294e+01 6.116601e-01 3.913405e-02 -7.901521e-01 4.975267e+02 +-7.585157e-01 2.851306e-02 -6.510307e-01 5.936223e+02 -8.061105e-03 9.985553e-01 5.312554e-02 -5.745140e+01 6.516049e-01 4.554458e-02 -7.571900e-01 4.969417e+02 +-7.236768e-01 3.135261e-02 -6.894266e-01 5.931209e+02 -1.152675e-02 9.982791e-01 5.749750e-02 -5.742377e+01 6.900428e-01 4.955645e-02 -7.220699e-01 4.964426e+02 +-6.866671e-01 3.258269e-02 -7.262415e-01 5.925137e+02 -1.616316e-02 9.980639e-01 6.006036e-02 -5.738893e+01 7.267923e-01 5.297983e-02 -6.848109e-01 4.959008e+02 +-6.491069e-01 3.143192e-02 -7.600476e-01 5.919449e+02 -2.143710e-02 9.979933e-01 5.958026e-02 -5.736083e+01 7.603950e-01 5.496717e-02 -6.471305e-01 4.954387e+02 +-6.118485e-01 3.019872e-02 -7.903983e-01 5.913334e+02 -2.573302e-02 9.979820e-01 5.804985e-02 -5.732995e+01 7.905562e-01 5.585705e-02 -6.098367e-01 4.949977e+02 +-5.757144e-01 2.974854e-02 -8.171096e-01 5.906356e+02 -2.746956e-02 9.980701e-01 5.569114e-02 -5.729492e+01 8.171893e-01 5.450782e-02 -5.737861e-01 4.945325e+02 +-5.416773e-01 3.094485e-02 -8.400168e-01 5.899621e+02 -2.881615e-02 9.980512e-01 5.534842e-02 -5.726452e+01 8.400924e-01 5.418702e-02 -5.397299e-01 4.941303e+02 +-5.100733e-01 3.207734e-02 -8.595326e-01 5.892581e+02 -2.979564e-02 9.980456e-01 5.492825e-02 -5.723436e+01 8.596147e-01 5.362776e-02 -5.081206e-01 4.937394e+02 +-4.817683e-01 3.526339e-02 -8.755889e-01 5.885005e+02 -2.877486e-02 9.980145e-01 5.602653e-02 -5.720531e+01 8.758260e-01 5.218675e-02 -4.797970e-01 4.933430e+02 +-4.566686e-01 3.998147e-02 -8.887381e-01 5.877458e+02 -2.617246e-02 9.979534e-01 5.834317e-02 -5.716979e+01 8.892518e-01 4.990396e-02 -4.546875e-01 4.929815e+02 +-4.353120e-01 4.415679e-02 -8.991961e-01 5.869612e+02 -2.345127e-02 9.979013e-01 6.035696e-02 -5.713958e+01 8.999741e-01 4.736140e-02 -4.333629e-01 4.926199e+02 +-4.183526e-01 4.690295e-02 -9.070729e-01 5.861789e+02 -2.040691e-02 9.979283e-01 6.101282e-02 -5.711329e+01 9.080554e-01 4.403542e-02 -4.165287e-01 4.922789e+02 +-4.060017e-01 4.649867e-02 -9.126887e-01 5.853822e+02 -1.402121e-02 9.982702e-01 5.709601e-02 -5.709011e+01 9.137647e-01 3.597808e-02 -4.046474e-01 4.919482e+02 +-3.980127e-01 4.613780e-02 -9.162190e-01 5.845678e+02 -6.440337e-03 9.985693e-01 5.308244e-02 -5.706651e+01 9.173573e-01 2.702825e-02 -3.971461e-01 4.916170e+02 +-3.937583e-01 4.704036e-02 -9.180096e-01 5.837385e+02 -2.256795e-03 9.986372e-01 5.213986e-02 -5.704651e+01 9.192112e-01 2.260226e-02 -3.931155e-01 4.912790e+02 +-3.918280e-01 4.968324e-02 -9.186960e-01 5.828926e+02 1.091726e-03 9.985652e-01 5.353697e-02 -5.702391e+01 9.200378e-01 1.997432e-02 -3.913201e-01 4.909324e+02 +-3.909385e-01 5.212047e-02 -9.189399e-01 5.820363e+02 2.122993e-03 9.984438e-01 5.572662e-02 -5.700065e+01 9.204143e-01 1.983478e-02 -3.904408e-01 4.905790e+02 +-3.909911e-01 5.325280e-02 -9.188526e-01 5.811668e+02 2.163593e-03 9.983752e-01 5.694095e-02 -5.697246e+01 9.203919e-01 2.027538e-02 -3.904710e-01 4.902156e+02 +-3.922576e-01 5.376084e-02 -9.182831e-01 5.802860e+02 3.566149e-03 9.983720e-01 5.692633e-02 -5.694229e+01 9.198485e-01 1.905505e-02 -3.918107e-01 4.898487e+02 +-3.943894e-01 5.317879e-02 -9.174034e-01 5.793935e+02 3.435178e-03 9.984025e-01 5.639727e-02 -5.691002e+01 9.189370e-01 1.909105e-02 -3.939420e-01 4.894720e+02 +-3.970907e-01 5.235522e-02 -9.162849e-01 5.784908e+02 1.858384e-03 9.984154e-01 5.624268e-02 -5.687662e+01 9.177775e-01 2.063064e-02 -3.965587e-01 4.890837e+02 +-4.007161e-01 5.195277e-02 -9.147282e-01 5.775774e+02 6.669488e-04 9.984073e-01 5.641324e-02 -5.684317e+01 9.162020e-01 2.199561e-02 -4.001124e-01 4.886874e+02 +-4.048836e-01 5.140078e-02 -9.129224e-01 5.766535e+02 -6.088563e-04 9.984033e-01 5.648371e-02 -5.680785e+01 9.143680e-01 2.342516e-02 -4.042058e-01 4.882810e+02 +-4.100275e-01 5.119325e-02 -9.106354e-01 5.757235e+02 -4.340183e-03 9.983027e-01 5.807590e-02 -5.677069e+01 9.120628e-01 2.776504e-02 -4.091093e-01 4.878615e+02 +-4.153112e-01 4.777494e-02 -9.084240e-01 5.747887e+02 -7.335298e-03 9.984116e-01 5.586103e-02 -5.673551e+01 9.096498e-01 2.986327e-02 -4.143011e-01 4.874340e+02 +-4.205778e-01 4.562933e-02 -9.061083e-01 5.738487e+02 -1.035879e-02 9.984278e-01 5.508644e-02 -5.669876e+01 9.071973e-01 3.255432e-02 -4.194439e-01 4.869978e+02 +-4.256089e-01 4.460806e-02 -9.038071e-01 5.729046e+02 -1.195551e-02 9.984198e-01 5.490769e-02 -5.666137e+01 9.048282e-01 3.417468e-02 -4.244030e-01 4.865547e+02 +-4.308244e-01 4.794928e-02 -9.011611e-01 5.719510e+02 -1.310132e-02 9.981498e-01 5.937334e-02 -5.661919e+01 9.023407e-01 3.738588e-02 -4.293991e-01 4.861060e+02 +-4.361367e-01 5.059503e-02 -8.984570e-01 5.709989e+02 -1.282320e-02 9.979673e-01 6.242354e-02 -5.657601e+01 8.997890e-01 3.874628e-02 -4.346014e-01 4.856517e+02 +-4.412340e-01 5.249848e-02 -8.958552e-01 5.700422e+02 -1.105670e-02 9.978935e-01 6.392383e-02 -5.652948e+01 8.973239e-01 3.811057e-02 -4.397241e-01 4.851909e+02 +-4.462521e-01 5.326674e-02 -8.933206e-01 5.690852e+02 -9.798141e-03 9.978763e-01 6.439578e-02 -5.648104e+01 8.948536e-01 3.748963e-02 -4.447825e-01 4.847230e+02 +-4.506605e-01 5.386227e-02 -8.910691e-01 5.681257e+02 -9.911928e-03 9.978146e-01 6.532769e-02 -5.643410e+01 8.926404e-01 3.827282e-02 -4.491417e-01 4.842450e+02 +-4.546768e-01 5.159069e-02 -8.891611e-01 5.671692e+02 -1.198724e-02 9.978761e-01 6.402827e-02 -5.638616e+01 8.905758e-01 3.977075e-02 -4.530926e-01 4.837602e+02 +-4.574042e-01 5.023521e-02 -8.878389e-01 5.662105e+02 -1.243046e-02 9.979443e-01 6.286918e-02 -5.633920e+01 8.891720e-01 3.979287e-02 -4.558394e-01 4.832708e+02 +-4.590286e-01 4.795168e-02 -8.871265e-01 5.652494e+02 -1.353836e-02 9.980488e-01 6.095255e-02 -5.629346e+01 8.883183e-01 3.998919e-02 -4.574837e-01 4.827780e+02 +-4.597360e-01 4.683105e-02 -8.868200e-01 5.642805e+02 -1.382386e-02 9.981102e-01 5.987447e-02 -5.624918e+01 8.879480e-01 3.978572e-02 -4.582197e-01 4.822803e+02 +-4.611548e-01 4.592008e-02 -8.861307e-01 5.633096e+02 -1.570587e-02 9.980811e-01 5.989501e-02 -5.620508e+01 8.871807e-01 4.153832e-02 -4.595486e-01 4.817797e+02 +-4.622355e-01 4.745531e-02 -8.854865e-01 5.623336e+02 -1.830236e-02 9.978437e-01 6.303089e-02 -5.616118e+01 8.865683e-01 4.534160e-02 -4.603702e-01 4.812731e+02 +-4.625977e-01 5.104414e-02 -8.850977e-01 5.613504e+02 -1.410380e-02 9.977911e-01 6.491463e-02 -5.611437e+01 8.864561e-01 4.251260e-02 -4.608560e-01 4.807696e+02 +-4.630351e-01 4.591812e-02 -8.851497e-01 5.603735e+02 -1.218174e-02 9.982331e-01 5.815691e-02 -5.606999e+01 8.862562e-01 3.771136e-02 -4.616576e-01 4.802672e+02 +-4.636467e-01 4.046416e-02 -8.850957e-01 5.593954e+02 -9.329265e-03 9.986782e-01 5.054388e-02 -5.602939e+01 8.859710e-01 3.169180e-02 -4.626563e-01 4.797638e+02 +-4.646779e-01 4.115106e-02 -8.845231e-01 5.584058e+02 -1.708147e-03 9.988760e-01 4.736853e-02 -5.599325e+01 8.854781e-01 2.352200e-02 -4.640853e-01 4.792616e+02 +-4.648484e-01 4.626014e-02 -8.841810e-01 5.574008e+02 2.292846e-03 9.986936e-01 5.104599e-02 -5.595910e+01 8.853873e-01 2.170136e-02 -4.643472e-01 4.787560e+02 +-4.643834e-01 5.164319e-02 -8.841273e-01 5.563868e+02 5.882513e-03 9.984562e-01 5.523157e-02 -5.592674e+01 8.856147e-01 2.044773e-02 -4.639702e-01 4.782510e+02 +-4.644030e-01 5.574619e-02 -8.838678e-01 5.553768e+02 9.452899e-03 9.982721e-01 5.799502e-02 -5.589144e+01 8.855735e-01 1.857795e-02 -4.641274e-01 4.777433e+02 +-4.641275e-01 5.821813e-02 -8.838531e-01 5.543611e+02 1.474917e-02 9.982073e-01 5.800543e-02 -5.586631e+01 8.856456e-01 1.388581e-02 -4.641541e-01 4.772389e+02 +-4.644611e-01 5.852666e-02 -8.836575e-01 5.533596e+02 1.789332e-02 9.982303e-01 5.671015e-02 -5.583986e+01 8.854127e-01 1.052809e-02 -4.646864e-01 4.767336e+02 +-4.644855e-01 5.860056e-02 -8.836398e-01 5.523488e+02 2.403001e-02 9.982748e-01 5.357148e-02 -5.581568e+01 8.852546e-01 3.649314e-03 -4.650923e-01 4.762299e+02 +-4.653581e-01 5.891454e-02 -8.831596e-01 5.513373e+02 2.270402e-02 9.982486e-01 5.462871e-02 -5.578740e+01 8.848312e-01 5.370642e-03 -4.658807e-01 4.757112e+02 +-4.656624e-01 6.342127e-02 -8.826870e-01 5.503221e+02 2.136183e-02 9.979436e-01 6.043305e-02 -5.575760e+01 8.847045e-01 9.285589e-03 -4.660596e-01 4.751873e+02 +-4.658356e-01 6.303284e-02 -8.826234e-01 5.493094e+02 1.646537e-02 9.979044e-01 6.257550e-02 -5.572315e+01 8.847181e-01 1.461718e-02 -4.658972e-01 4.746572e+02 +-4.661395e-01 6.046973e-02 -8.826423e-01 5.482975e+02 1.326796e-02 9.980270e-01 6.136770e-02 -5.568614e+01 8.846117e-01 1.689505e-02 -4.660221e-01 4.741272e+02 +-4.667702e-01 5.748082e-02 -8.825087e-01 5.472868e+02 1.074323e-02 9.981804e-01 5.933270e-02 -5.564858e+01 8.843133e-01 1.821375e-02 -4.665384e-01 4.735995e+02 +-4.673474e-01 5.650471e-02 -8.822662e-01 5.462681e+02 9.297198e-03 9.982143e-01 5.900578e-02 -5.561029e+01 8.840249e-01 1.937359e-02 -4.670381e-01 4.730671e+02 +-4.680662e-01 5.612491e-02 -8.819093e-01 5.452490e+02 7.704401e-03 9.982023e-01 5.943678e-02 -5.557344e+01 8.836598e-01 2.102577e-02 -4.676572e-01 4.725347e+02 +-4.686516e-01 5.469866e-02 -8.816881e-01 5.442279e+02 5.727284e-03 9.982483e-01 5.888562e-02 -5.553718e+01 8.833645e-01 2.254716e-02 -4.681439e-01 4.719982e+02 +-4.691788e-01 5.207882e-02 -8.815663e-01 5.432057e+02 3.337085e-03 9.983570e-01 5.720225e-02 -5.550071e+01 8.830969e-01 2.389622e-02 -4.685817e-01 4.714604e+02 +-4.693446e-01 5.262604e-02 -8.814455e-01 5.421814e+02 2.758764e-03 9.983049e-01 5.813410e-02 -5.546126e+01 8.830108e-01 2.485322e-02 -4.686942e-01 4.709217e+02 +-4.698411e-01 5.525725e-02 -8.810199e-01 5.411525e+02 3.863853e-03 9.981581e-01 6.054357e-02 -5.542122e+01 8.827425e-01 2.504173e-02 -4.691892e-01 4.703833e+02 +-4.704465e-01 5.775402e-02 -8.805366e-01 5.401234e+02 5.011830e-03 9.980147e-01 6.278169e-02 -5.537967e+01 8.824143e-01 2.512233e-02 -4.698019e-01 4.698449e+02 +-4.711820e-01 5.864779e-02 -8.800841e-01 5.390960e+02 6.638301e-03 9.979945e-01 6.295119e-02 -5.533705e+01 8.820110e-01 2.381920e-02 -4.706264e-01 4.693077e+02 +-4.714812e-01 5.906902e-02 -8.798956e-01 5.380717e+02 7.191990e-03 9.979786e-01 6.314242e-02 -5.529340e+01 8.818467e-01 2.344227e-02 -4.709530e-01 4.687694e+02 +-4.716453e-01 5.792173e-02 -8.798840e-01 5.370558e+02 4.622404e-03 9.979890e-01 6.321870e-02 -5.525010e+01 8.817762e-01 2.574963e-02 -4.709645e-01 4.682279e+02 +-4.721821e-01 5.548954e-02 -8.797528e-01 5.360477e+02 1.972449e-03 9.980807e-01 6.189432e-02 -5.520803e+01 8.814988e-01 2.749012e-02 -4.713853e-01 4.676881e+02 +-4.726635e-01 5.374737e-02 -8.796025e-01 5.350430e+02 2.241037e-04 9.981456e-01 6.087044e-02 -5.516699e+01 8.812429e-01 2.857411e-02 -4.717990e-01 4.671520e+02 +-4.730768e-01 5.492399e-02 -8.793076e-01 5.340393e+02 1.916701e-03 9.981167e-01 6.131394e-02 -5.512741e+01 8.810191e-01 2.732083e-02 -4.722911e-01 4.666205e+02 +-4.736117e-01 5.477061e-02 -8.790291e-01 5.330436e+02 5.177142e-04 9.980816e-01 6.190962e-02 -5.508869e+01 8.807336e-01 2.886603e-02 -4.727315e-01 4.660919e+02 +-4.744913e-01 5.530633e-02 -8.785211e-01 5.320528e+02 3.273890e-03 9.981282e-01 6.106785e-02 -5.504663e+01 8.802541e-01 2.609998e-02 -4.737842e-01 4.655660e+02 +-4.754397e-01 5.379576e-02 -8.781020e-01 5.310701e+02 2.882033e-03 9.982185e-01 5.959410e-02 -5.501050e+01 8.797435e-01 2.580268e-02 -4.747477e-01 4.650419e+02 +-4.759358e-01 5.289743e-02 -8.778878e-01 5.301003e+02 2.923787e-03 9.982792e-01 5.856657e-02 -5.497429e+01 8.794751e-01 2.530717e-02 -4.752714e-01 4.645212e+02 +-4.765916e-01 5.202845e-02 -8.775839e-01 5.291365e+02 3.614854e-03 9.983547e-01 5.722535e-02 -5.494041e+01 8.791174e-01 2.410078e-02 -4.759955e-01 4.640055e+02 +-4.774095e-01 5.169833e-02 -8.771588e-01 5.281898e+02 4.911652e-03 9.984090e-01 5.617139e-02 -5.490705e+01 8.786672e-01 2.250846e-02 -4.769039e-01 4.634964e+02 +-4.789936e-01 5.315324e-02 -8.762077e-01 5.272495e+02 6.552694e-03 9.983537e-01 5.698083e-02 -5.487442e+01 8.777939e-01 2.155193e-02 -4.785533e-01 4.629895e+02 +-4.806468e-01 5.655615e-02 -8.750887e-01 5.263163e+02 9.316571e-03 9.981911e-01 5.939498e-02 -5.484179e+01 8.768648e-01 2.039518e-02 -4.803042e-01 4.624871e+02 +-4.828000e-01 5.906081e-02 -8.737368e-01 5.253925e+02 1.081784e-02 9.980493e-01 6.148621e-02 -5.480893e+01 8.756638e-01 2.023360e-02 -4.824971e-01 4.619853e+02 +-4.850524e-01 5.988717e-02 -8.724321e-01 5.244788e+02 9.933212e-03 9.979652e-01 6.298163e-02 -5.477520e+01 8.744286e-01 2.188334e-02 -4.846603e-01 4.614821e+02 +-4.875553e-01 6.031138e-02 -8.710065e-01 5.235821e+02 9.086538e-03 9.979077e-01 6.401216e-02 -5.473789e+01 8.730448e-01 2.329504e-02 -4.870832e-01 4.609821e+02 +-4.905317e-01 6.002951e-02 -8.693533e-01 5.226964e+02 7.125338e-03 9.978674e-01 6.488305e-02 -5.470039e+01 8.713942e-01 2.563276e-02 -4.899133e-01 4.604827e+02 +-4.935649e-01 5.981635e-02 -8.676496e-01 5.218283e+02 5.852375e-03 9.978378e-01 6.546249e-02 -5.466386e+01 8.696893e-01 2.723217e-02 -4.928477e-01 4.599893e+02 +-4.966558e-01 5.955747e-02 -8.659018e-01 5.209738e+02 4.730860e-03 9.978139e-01 6.591702e-02 -5.462781e+01 8.679347e-01 2.864161e-02 -4.958517e-01 4.595017e+02 +-4.997760e-01 5.941192e-02 -8.641147e-01 5.201386e+02 2.103476e-03 9.977250e-01 6.738169e-02 -5.459214e+01 8.661521e-01 3.185810e-02 -4.987640e-01 4.590182e+02 +-5.032244e-01 5.924406e-02 -8.621226e-01 5.193212e+02 1.596650e-04 9.976535e-01 6.846440e-02 -5.455743e+01 8.641557e-01 3.431531e-02 -5.020530e-01 4.585400e+02 +-5.069733e-01 5.758313e-02 -8.600363e-01 5.185298e+02 -1.234406e-03 9.977165e-01 6.752909e-02 -5.452269e+01 8.619609e-01 3.529708e-02 -5.057445e-01 4.580704e+02 +-5.108620e-01 5.516863e-02 -8.578907e-01 5.177561e+02 -2.110476e-03 9.978552e-01 6.542614e-02 -5.449036e+01 8.596601e-01 3.523429e-02 -5.096498e-01 4.576093e+02 +-5.146577e-01 5.286183e-02 -8.557646e-01 5.170004e+02 -1.916379e-03 9.980241e-01 6.280193e-02 -5.445995e+01 8.573936e-01 3.396147e-02 -5.135395e-01 4.571563e+02 +-5.181906e-01 5.023112e-02 -8.537889e-01 5.162621e+02 -2.341005e-03 9.981867e-01 6.014735e-02 -5.443283e+01 8.552619e-01 3.316651e-02 -5.171333e-01 4.567106e+02 +-5.209859e-01 4.853698e-02 -8.521842e-01 5.155446e+02 -9.581799e-04 9.983480e-01 5.744769e-02 -5.440617e+01 8.535647e-01 3.074598e-02 -5.200787e-01 4.562723e+02 +-5.233235e-01 4.714249e-02 -8.508291e-01 5.148396e+02 -3.427463e-04 9.984568e-01 5.553303e-02 -5.438199e+01 8.521340e-01 2.935335e-02 -5.224997e-01 4.558390e+02 +-5.246415e-01 4.572576e-02 -8.500944e-01 5.141478e+02 -3.668052e-04 9.985442e-01 5.393712e-02 -5.436090e+01 8.513232e-01 2.860947e-02 -5.238609e-01 4.554135e+02 +-5.250461e-01 4.530003e-02 -8.498674e-01 5.134685e+02 -1.394663e-03 9.985353e-01 5.408603e-02 -5.433992e+01 8.510726e-01 2.958294e-02 -5.242138e-01 4.549934e+02 +-5.237258e-01 4.713154e-02 -8.505821e-01 5.127986e+02 -3.107440e-03 9.983560e-01 5.723317e-02 -5.431844e+01 8.518812e-01 3.261762e-02 -5.227183e-01 4.545834e+02 +-5.201920e-01 4.553368e-02 -8.528347e-01 5.121532e+02 -7.831145e-03 9.982814e-01 5.807589e-02 -5.429782e+01 8.540134e-01 3.688929e-02 -5.189414e-01 4.541791e+02 +-5.133647e-01 4.130235e-02 -8.571761e-01 5.115150e+02 -1.152821e-02 9.984191e-01 5.501232e-02 -5.428119e+01 8.580931e-01 3.812309e-02 -5.120769e-01 4.537920e+02 +-5.036542e-01 3.411558e-02 -8.632315e-01 5.108952e+02 -1.671400e-02 9.986481e-01 4.921918e-02 -5.426260e+01 8.637436e-01 3.921750e-02 -5.024031e-01 4.534253e+02 +-4.904766e-01 2.787724e-02 -8.710084e-01 5.102806e+02 -2.157980e-02 9.987932e-01 4.411897e-02 -5.424603e+01 8.711871e-01 4.043551e-02 -4.892830e-01 4.530812e+02 +-4.740748e-01 2.817972e-02 -8.800335e-01 5.096470e+02 -2.396411e-02 9.987045e-01 4.488920e-02 -5.423588e+01 8.801583e-01 4.237005e-02 -4.727853e-01 4.527527e+02 +-4.544000e-01 3.090887e-02 -8.902614e-01 5.090269e+02 -2.218263e-02 9.986953e-01 4.599587e-02 -5.423059e+01 8.905215e-01 4.064886e-02 -4.531214e-01 4.524649e+02 +-4.307608e-01 2.964870e-02 -9.019790e-01 5.084015e+02 -2.115248e-02 9.988539e-01 4.293491e-02 -5.422383e+01 9.022182e-01 3.757376e-02 -4.296399e-01 4.521870e+02 +-4.037402e-01 2.640453e-02 -9.144926e-01 5.078164e+02 -2.188989e-02 9.990184e-01 3.850928e-02 -5.421615e+01 9.146118e-01 3.556588e-02 -4.027658e-01 4.519527e+02 +-3.738767e-01 2.405137e-02 -9.271666e-01 5.072383e+02 -2.170981e-02 9.991628e-01 3.467342e-02 -5.420980e+01 9.272243e-01 3.309219e-02 -3.730415e-01 4.517400e+02 +-3.407527e-01 2.163461e-02 -9.399040e-01 5.066218e+02 -1.964736e-02 9.993530e-01 3.012596e-02 -5.420820e+01 9.399476e-01 2.873214e-02 -3.401071e-01 4.515254e+02 +-3.037996e-01 2.212488e-02 -9.524790e-01 5.060247e+02 -1.398562e-02 9.995190e-01 2.767837e-02 -5.420798e+01 9.526333e-01 2.172969e-02 -3.033441e-01 4.513751e+02 +-2.634767e-01 2.353231e-02 -9.643787e-01 5.053762e+02 -7.896431e-03 9.996163e-01 2.654954e-02 -5.421478e+01 9.646334e-01 1.461034e-02 -2.631898e-01 4.512124e+02 +-2.196774e-01 2.464287e-02 -9.752613e-01 5.047705e+02 -4.224286e-03 9.996475e-01 2.621059e-02 -5.421728e+01 9.755634e-01 9.877661e-03 -2.194959e-01 4.511202e+02 +-1.736531e-01 2.624409e-02 -9.844572e-01 5.041644e+02 -4.161399e-03 9.996164e-01 2.738227e-02 -5.421923e+01 9.847981e-01 8.851738e-03 -1.734772e-01 4.510573e+02 +-1.260738e-01 2.852986e-02 -9.916106e-01 5.034958e+02 -2.691026e-03 9.995728e-01 2.910109e-02 -5.422262e+01 9.920172e-01 6.337340e-03 -1.259432e-01 4.509745e+02 +-7.858565e-02 3.099185e-02 -9.964255e-01 5.028841e+02 1.419208e-03 9.995191e-01 3.097614e-02 -5.422104e+01 9.969063e-01 1.020151e-03 -7.859184e-02 4.509786e+02 +-3.057823e-02 3.177066e-02 -9.990274e-01 5.022134e+02 1.162951e-03 9.994951e-01 3.174995e-02 -5.422056e+01 9.995317e-01 -1.909574e-04 -3.059974e-02 4.509555e+02 +1.988326e-02 2.859986e-02 -9.993932e-01 5.016111e+02 -3.169096e-03 9.995875e-01 2.854238e-02 -5.422969e+01 9.997972e-01 2.599662e-03 1.996569e-02 4.510130e+02 +7.207943e-02 2.199539e-02 -9.971564e-01 5.010205e+02 -6.468931e-03 9.997461e-01 2.158491e-02 -5.423775e+01 9.973779e-01 4.894711e-03 7.220341e-02 4.511092e+02 +1.258395e-01 1.441308e-02 -9.919459e-01 5.003600e+02 -5.075653e-03 9.998907e-01 1.388462e-02 -5.423696e+01 9.920376e-01 3.287545e-03 1.258988e-01 4.511746e+02 +1.801292e-01 9.600740e-03 -9.835961e-01 4.997749e+02 -3.275706e-03 9.999527e-01 9.160507e-03 -5.424473e+01 9.836375e-01 1.571901e-03 1.801521e-01 4.513479e+02 +2.339820e-01 5.913903e-03 -9.722230e-01 4.991140e+02 -3.932033e-03 9.999791e-01 5.136432e-03 -5.425071e+01 9.722329e-01 2.620985e-03 2.340003e-01 4.514798e+02 +2.883173e-01 7.004745e-03 -9.575093e-01 4.985324e+02 -6.703376e-03 9.999635e-01 5.296861e-03 -5.426422e+01 9.575114e-01 4.891373e-03 2.883537e-01 4.517174e+02 +3.412516e-01 7.273872e-03 -9.399439e-01 4.979576e+02 -3.956200e-03 9.999723e-01 6.302093e-03 -5.427796e+01 9.399636e-01 1.568011e-03 3.412709e-01 4.519937e+02 +3.935005e-01 5.239119e-03 -9.193095e-01 4.973157e+02 8.143036e-04 9.999814e-01 6.047423e-03 -5.429176e+01 9.193240e-01 -3.128256e-03 3.934889e-01 4.522437e+02 +4.459533e-01 3.171590e-03 -8.950507e-01 4.967624e+02 1.164225e-03 9.999908e-01 4.123513e-03 -5.430411e+01 8.950555e-01 -2.880929e-03 4.459454e-01 4.525949e+02 +4.977396e-01 2.007074e-03 -8.673242e-01 4.962202e+02 -1.862227e-04 9.999975e-01 2.207226e-03 -5.431646e+01 8.673265e-01 -9.371035e-04 4.977387e-01 4.529808e+02 +5.473559e-01 1.083673e-03 -8.368993e-01 4.956048e+02 1.085697e-03 9.999974e-01 2.004941e-03 -5.433061e+01 8.368992e-01 -2.006030e-03 5.473532e-01 4.533349e+02 +5.951645e-01 2.662346e-03 -8.035996e-01 4.950852e+02 1.700813e-03 9.999881e-01 4.572651e-03 -5.433977e+01 8.036021e-01 -4.088247e-03 5.951528e-01 4.538031e+02 +6.409718e-01 6.070557e-03 -7.675404e-01 4.944943e+02 2.119755e-03 9.999509e-01 9.678922e-03 -5.435583e+01 7.675615e-01 -7.830909e-03 6.409274e-01 4.542406e+02 +6.835658e-01 1.155432e-02 -7.297975e-01 4.939964e+02 1.501158e-03 9.998503e-01 1.723593e-02 -5.435649e+01 7.298873e-01 -1.287743e-02 6.834461e-01 4.547908e+02 +7.223215e-01 1.498795e-02 -6.913950e-01 4.935128e+02 9.935379e-04 9.997416e-01 2.271022e-02 -5.436026e+01 6.915567e-01 -1.709100e-02 7.221199e-01 4.553708e+02 +7.568249e-01 1.506388e-02 -6.534441e-01 4.929869e+02 7.040674e-04 9.997150e-01 2.386194e-02 -5.433964e+01 6.536173e-01 -1.851937e-02 7.565985e-01 4.559041e+02 +7.865760e-01 1.211941e-02 -6.173746e-01 4.925558e+02 1.987079e-03 9.997525e-01 2.215738e-02 -5.428850e+01 6.174903e-01 -1.865523e-02 7.863571e-01 4.565298e+02 +8.117965e-01 7.722264e-03 -5.838895e-01 4.921402e+02 5.063472e-03 9.997818e-01 2.026255e-02 -5.422644e+01 5.839185e-01 -1.940557e-02 8.115802e-01 4.571920e+02 +8.328182e-01 3.442791e-03 -5.535360e-01 4.917091e+02 1.020494e-02 9.997152e-01 2.157163e-02 -5.416405e+01 5.534526e-01 -2.361404e-02 8.325458e-01 4.578575e+02 +8.497080e-01 1.375852e-03 -5.272519e-01 4.913021e+02 1.384569e-02 9.995935e-01 2.492184e-02 -5.411771e+01 5.270718e-01 -2.847645e-02 8.493434e-01 4.585826e+02 +8.626570e-01 -9.456874e-04 -5.057885e-01 4.908998e+02 1.723834e-02 9.994722e-01 2.753243e-02 -5.406626e+01 5.054955e-01 -3.246999e-02 8.622180e-01 4.593290e+02 +8.723247e-01 -4.856434e-03 -4.889030e-01 4.904933e+02 2.207323e-02 9.993223e-01 2.945755e-02 -5.401707e+01 4.884285e-01 -3.648821e-02 8.718406e-01 4.600924e+02 +8.787284e-01 -8.946290e-03 -4.772383e-01 4.901048e+02 2.629955e-02 9.992130e-01 2.969357e-02 -5.394651e+01 4.765971e-01 -3.864373e-02 8.782721e-01 4.608811e+02 +8.826987e-01 -1.264800e-02 -4.697691e-01 4.896971e+02 2.946955e-02 9.991601e-01 2.847219e-02 -5.389998e+01 4.690144e-01 -3.897624e-02 8.823300e-01 4.616890e+02 +8.846094e-01 -1.557019e-02 -4.660728e-01 4.892825e+02 3.211016e-02 9.991040e-01 2.756802e-02 -5.384422e+01 4.652260e-01 -3.935259e-02 8.843167e-01 4.625258e+02 +8.851769e-01 -1.841638e-02 -4.648901e-01 4.888622e+02 3.487084e-02 9.990319e-01 2.681990e-02 -5.380343e+01 4.639461e-01 -3.995146e-02 8.849620e-01 4.633612e+02 +8.850749e-01 -1.899431e-02 -4.650609e-01 4.884362e+02 3.558506e-02 9.990040e-01 2.692131e-02 -5.374632e+01 4.640863e-01 -4.037659e-02 8.848692e-01 4.642169e+02 +8.845572e-01 -1.890613e-02 -4.660484e-01 4.879918e+02 3.611902e-02 9.989543e-01 2.802923e-02 -5.369577e+01 4.650311e-01 -4.162666e-02 8.843151e-01 4.650954e+02 +8.839247e-01 -1.688753e-02 -4.673242e-01 4.875327e+02 3.575919e-02 9.988625e-01 3.154151e-02 -5.364709e+01 4.662600e-01 -4.459144e-02 8.835231e-01 4.659928e+02 +8.834472e-01 -1.657660e-02 -4.682375e-01 4.870653e+02 3.748771e-02 9.986707e-01 3.537487e-02 -5.359536e+01 4.670287e-01 -4.880496e-02 8.828942e-01 4.669100e+02 +8.829098e-01 -1.666782e-02 -4.692467e-01 4.865825e+02 3.819473e-02 9.986073e-01 3.639427e-02 -5.355100e+01 4.679866e-01 -5.005560e-02 8.823168e-01 4.678437e+02 +8.823546e-01 -1.904364e-02 -4.701997e-01 4.860945e+02 3.974133e-02 9.986269e-01 3.413115e-02 -5.350137e+01 4.689041e-01 -4.880213e-02 8.818998e-01 4.687888e+02 +8.816335e-01 -1.992650e-02 -4.715140e-01 4.855895e+02 4.055011e-02 9.986118e-01 3.361827e-02 -5.345898e+01 4.701895e-01 -4.875892e-02 8.812175e-01 4.697530e+02 +8.809781e-01 -2.093750e-02 -4.726936e-01 4.850767e+02 4.263949e-02 9.984687e-01 3.524273e-02 -5.341533e+01 4.712318e-01 -5.120348e-02 8.805218e-01 4.707340e+02 +8.801993e-01 -2.202262e-02 -4.740932e-01 4.845502e+02 4.424478e-02 9.983802e-01 3.576782e-02 -5.337974e+01 4.725375e-01 -5.245894e-02 8.797478e-01 4.717318e+02 +8.793789e-01 -1.981137e-02 -4.757103e-01 4.840097e+02 4.239848e-02 9.984229e-01 3.679592e-02 -5.334011e+01 4.742311e-01 -5.252694e-02 8.788320e-01 4.727403e+02 +8.783949e-01 -1.764118e-02 -4.776100e-01 4.834526e+02 4.232496e-02 9.982635e-01 4.096957e-02 -5.329980e+01 4.760579e-01 -5.620228e-02 8.776161e-01 4.737652e+02 +8.775226e-01 -1.457749e-02 -4.793137e-01 4.828859e+02 4.052034e-02 9.982171e-01 4.382519e-02 -5.325909e+01 4.778203e-01 -5.787954e-02 8.765487e-01 4.747990e+02 +8.770628e-01 -1.521551e-02 -4.801348e-01 4.823142e+02 3.906188e-02 9.984473e-01 3.971350e-02 -5.321779e+01 4.787850e-01 -5.358619e-02 8.762952e-01 4.758370e+02 +8.766377e-01 -1.607647e-02 -4.808825e-01 4.817370e+02 3.776082e-02 9.986578e-01 3.545078e-02 -5.318050e+01 4.796671e-01 -4.923600e-02 8.760680e-01 4.768845e+02 +8.761274e-01 -1.712177e-02 -4.817756e-01 4.811563e+02 3.859987e-02 9.986519e-01 3.470435e-02 -5.314701e+01 4.805319e-01 -4.900190e-02 8.756071e-01 4.779436e+02 +8.754367e-01 -1.608727e-02 -4.830651e-01 4.805673e+02 3.988636e-02 9.984415e-01 3.903361e-02 -5.311581e+01 4.816843e-01 -5.343915e-02 8.747139e-01 4.790181e+02 +8.748775e-01 -1.455872e-02 -4.841256e-01 4.799719e+02 4.141040e-02 9.981365e-01 4.481778e-02 -5.308087e+01 4.825709e-01 -5.925788e-02 8.738500e-01 4.800995e+02 +8.743365e-01 -1.364106e-02 -4.851285e-01 4.793725e+02 4.358377e-02 9.977729e-01 5.049424e-02 -5.303981e+01 4.833593e-01 -6.529267e-02 8.729837e-01 4.811883e+02 +8.736986e-01 -1.268001e-02 -4.863024e-01 4.787668e+02 4.454033e-02 9.975464e-01 5.401152e-02 -5.299406e+01 4.844243e-01 -6.884984e-02 8.721197e-01 4.822825e+02 +8.731712e-01 -1.179521e-02 -4.872709e-01 4.781646e+02 3.941388e-02 9.981420e-01 4.646650e-02 -5.294844e+01 4.858174e-01 -5.977844e-02 8.720137e-01 4.833569e+02 +8.730213e-01 -1.675214e-02 -4.873943e-01 4.775811e+02 3.498812e-02 9.989859e-01 2.833482e-02 -5.289721e+01 4.864253e-01 -4.178990e-02 8.727221e-01 4.844108e+02 +8.731372e-01 -1.505248e-02 -4.872421e-01 4.769772e+02 2.863425e-02 9.993810e-01 2.043843e-02 -5.286461e+01 4.866328e-01 -3.179736e-02 8.730277e-01 4.854842e+02 +8.729365e-01 -7.370921e-03 -4.877782e-01 4.763678e+02 2.504886e-02 9.992441e-01 2.972808e-02 -5.283789e+01 4.871904e-01 -3.816901e-02 8.724612e-01 4.865748e+02 +8.722991e-01 -1.049144e-03 -4.889715e-01 4.757546e+02 2.468770e-02 9.988168e-01 4.189847e-02 -5.280952e+01 4.883490e-01 -4.861957e-02 8.712929e-01 4.876775e+02 +8.716977e-01 -3.273714e-04 -4.900439e-01 4.751498e+02 2.672135e-02 9.985437e-01 4.686528e-02 -5.276867e+01 4.893149e-01 -5.394698e-02 8.704370e-01 4.887702e+02 +8.711984e-01 -8.102421e-04 -4.909306e-01 4.745478e+02 2.678304e-02 9.985878e-01 4.588070e-02 -5.271660e+01 4.902001e-01 -5.311979e-02 8.699897e-01 4.898530e+02 +8.709412e-01 -1.792605e-03 -4.913840e-01 4.739391e+02 2.565451e-02 9.987954e-01 4.182701e-02 -5.267180e+01 4.907171e-01 -4.903507e-02 8.699380e-01 4.909376e+02 +8.704173e-01 -7.343659e-04 -4.923143e-01 4.733266e+02 2.265542e-02 9.989992e-01 3.856487e-02 -5.263029e+01 4.917932e-01 -4.472111e-02 8.695627e-01 4.920204e+02 +8.699449e-01 1.293615e-03 -4.931474e-01 4.727052e+02 2.025231e-02 9.990592e-01 3.834714e-02 -5.259415e+01 4.927330e-01 -4.334726e-02 8.691002e-01 4.931141e+02 +8.695719e-01 3.071932e-03 -4.937969e-01 4.720942e+02 1.904670e-02 9.990278e-01 3.975606e-02 -5.254890e+01 4.934389e-01 -4.397594e-02 8.686680e-01 4.942044e+02 +8.692171e-01 4.653376e-03 -4.944088e-01 4.714756e+02 1.857177e-02 9.989427e-01 4.205295e-02 -5.250615e+01 4.940818e-01 -4.573518e-02 8.682116e-01 4.953028e+02 +8.685658e-01 7.337013e-03 -4.955196e-01 4.708398e+02 1.707649e-02 9.988535e-01 4.472206e-02 -5.245846e+01 4.952796e-01 -4.730578e-02 8.674446e-01 4.964056e+02 +8.679666e-01 7.554153e-03 -4.965651e-01 4.702041e+02 1.718929e-02 9.988282e-01 4.524086e-02 -5.241498e+01 4.963250e-01 -4.780315e-02 8.668196e-01 4.975109e+02 +8.674558e-01 5.210897e-03 -4.974870e-01 4.695682e+02 1.877255e-02 9.988902e-01 4.319605e-02 -5.237000e+01 4.971600e-01 -4.680975e-02 8.663952e-01 4.986173e+02 +8.668224e-01 5.050491e-03 -4.985916e-01 4.689261e+02 1.828298e-02 9.989543e-01 4.190464e-02 -5.232872e+01 4.982818e-01 -4.543961e-02 8.658235e-01 4.997289e+02 +8.663542e-01 2.536338e-03 -4.994237e-01 4.682925e+02 1.994807e-02 9.990134e-01 3.967760e-02 -5.228625e+01 4.990315e-01 -4.433738e-02 8.654488e-01 5.008414e+02 +8.660039e-01 1.907662e-03 -5.000337e-01 4.676513e+02 1.988419e-02 9.990704e-01 3.824877e-02 -5.224882e+01 4.996418e-01 -4.306634e-02 8.651608e-01 5.019589e+02 +8.659665e-01 3.518426e-03 -5.000897e-01 4.670052e+02 1.839420e-02 9.990745e-01 3.888089e-02 -5.221407e+01 4.997636e-01 -4.286828e-02 8.651003e-01 5.030793e+02 +8.662678e-01 4.763119e-03 -4.995574e-01 4.663594e+02 1.814142e-02 9.989951e-01 4.098361e-02 -5.217756e+01 4.992505e-01 -4.456545e-02 8.653108e-01 5.042031e+02 +8.667670e-01 7.597708e-03 -4.986556e-01 4.657080e+02 1.582899e-02 9.989610e-01 4.273464e-02 -5.214248e+01 4.984621e-01 -4.493418e-02 8.657461e-01 5.053344e+02 +8.674817e-01 7.797323e-03 -4.974080e-01 4.650617e+02 1.486531e-02 9.990243e-01 4.158577e-02 -5.210666e+01 4.972470e-01 -4.346901e-02 8.665194e-01 5.064635e+02 +8.682727e-01 8.191358e-03 -4.960197e-01 4.644142e+02 1.352517e-02 9.991011e-01 4.017487e-02 -5.207124e+01 4.959029e-01 -4.159148e-02 8.673813e-01 5.075945e+02 +8.692938e-01 8.433864e-03 -4.942238e-01 4.637691e+02 1.399854e-02 9.990333e-01 4.167050e-02 -5.203577e+01 4.940975e-01 -4.314230e-02 8.683354e-01 5.087315e+02 +8.702104e-01 8.210968e-03 -4.926120e-01 4.631261e+02 1.468912e-02 9.989842e-01 4.259995e-02 -5.200111e+01 4.924614e-01 -4.430694e-02 8.692057e-01 5.098703e+02 +8.711815e-01 5.745595e-03 -4.909276e-01 4.624862e+02 1.756426e-02 9.989267e-01 4.285985e-02 -5.196450e+01 4.906469e-01 -4.596147e-02 8.701454e-01 5.110142e+02 +8.717097e-01 4.350537e-03 -4.900035e-01 4.618452e+02 1.911980e-02 9.988971e-01 4.288267e-02 -5.192861e+01 4.896496e-01 -4.675000e-02 8.706650e-01 5.121619e+02 +8.722680e-01 2.623549e-03 -4.890212e-01 4.612153e+02 2.170325e-02 9.987926e-01 4.407054e-02 -5.188806e+01 4.885464e-01 -4.905465e-02 8.711578e-01 5.133146e+02 +8.727436e-01 2.009242e-03 -4.881749e-01 4.605788e+02 2.269676e-02 9.987431e-01 4.468721e-02 -5.184691e+01 4.876511e-01 -5.008045e-02 8.716010e-01 5.144672e+02 +8.730637e-01 2.786404e-03 -4.875982e-01 4.599196e+02 2.211409e-02 9.987285e-01 4.530344e-02 -5.180613e+01 4.871044e-01 -5.033557e-02 8.718919e-01 5.156214e+02 +8.732638e-01 3.563006e-03 -4.872348e-01 4.592594e+02 2.090610e-02 9.987784e-01 4.477347e-02 -5.176542e+01 4.867991e-01 -4.928522e-02 8.721224e-01 5.167792e+02 +8.734756e-01 -1.033288e-03 -4.868669e-01 4.586025e+02 2.213575e-02 9.990479e-01 3.759289e-02 -5.172938e+01 4.863645e-01 -4.361363e-02 8.726668e-01 5.179398e+02 +8.733725e-01 -3.968756e-03 -4.870368e-01 4.579390e+02 2.447764e-02 9.990608e-01 3.575308e-02 -5.169839e+01 4.864375e-01 -4.314726e-02 8.726493e-01 5.191129e+02 +8.728208e-01 -4.799002e-03 -4.880173e-01 4.572796e+02 2.806567e-02 9.987904e-01 4.037378e-02 -5.167178e+01 4.872332e-01 -4.893560e-02 8.718997e-01 5.202829e+02 +8.718514e-01 -8.921283e-03 -4.896893e-01 4.566139e+02 3.270019e-02 9.986634e-01 4.002608e-02 -5.164489e+01 4.886777e-01 -5.090971e-02 8.709777e-01 5.214527e+02 +8.706708e-01 -1.400567e-02 -4.916668e-01 4.559534e+02 3.721010e-02 9.986056e-01 3.744734e-02 -5.161589e+01 4.904567e-01 -5.089926e-02 8.699778e-01 5.226205e+02 +8.696734e-01 -1.633789e-02 -4.933572e-01 4.552843e+02 3.925629e-02 9.985757e-01 3.613109e-02 -5.159071e+01 4.920642e-01 -5.078960e-02 8.690760e-01 5.237878e+02 +8.690979e-01 -1.579018e-02 -4.943880e-01 4.546151e+02 3.910348e-02 9.985555e-01 3.684834e-02 -5.156653e+01 4.930920e-01 -5.135710e-02 8.684599e-01 5.249522e+02 +8.690319e-01 -1.395440e-02 -4.945593e-01 4.539351e+02 3.829169e-02 9.985009e-01 3.911203e-02 -5.153879e+01 4.932721e-01 -5.292710e-02 8.682633e-01 5.261171e+02 +8.694534e-01 -1.220475e-02 -4.938643e-01 4.532597e+02 3.625706e-02 9.985752e-01 3.915341e-02 -5.151016e+01 4.926827e-01 -5.194812e-02 8.686570e-01 5.272768e+02 +8.701202e-01 -1.340723e-02 -4.926572e-01 4.525886e+02 3.645347e-02 9.986425e-01 3.720612e-02 -5.148071e+01 4.914896e-01 -5.033285e-02 8.694277e-01 5.284412e+02 +8.708662e-01 -1.194535e-02 -4.913751e-01 4.519289e+02 3.528205e-02 9.986450e-01 3.825343e-02 -5.144300e+01 4.902523e-01 -5.065032e-02 8.701075e-01 5.296143e+02 +8.716719e-01 -8.204591e-03 -4.900213e-01 4.512717e+02 3.401685e-02 9.984613e-01 4.379313e-02 -5.140415e+01 4.889080e-01 -5.484221e-02 8.706097e-01 5.307931e+02 +8.726853e-01 -5.465825e-03 -4.882526e-01 4.506173e+02 3.113001e-02 9.985259e-01 4.446250e-02 -5.136186e+01 4.872898e-01 -5.400106e-02 8.715690e-01 5.319679e+02 +8.736838e-01 -5.717545e-03 -4.864606e-01 4.499645e+02 2.787167e-02 9.988768e-01 3.831739e-02 -5.132120e+01 4.856952e-01 -4.703574e-02 8.728618e-01 5.331346e+02 +8.743668e-01 -6.129182e-03 -4.852270e-01 4.493102e+02 2.714295e-02 9.989725e-01 3.629230e-02 -5.128301e+01 4.845060e-01 -4.490326e-02 8.736347e-01 5.343178e+02 +8.746438e-01 -5.018339e-03 -4.847403e-01 4.486611e+02 2.811037e-02 9.987888e-01 4.038100e-02 -5.124870e+01 4.839506e-01 -4.894520e-02 8.737254e-01 5.354974e+02 +8.748442e-01 -3.777038e-03 -4.843897e-01 4.480105e+02 3.030308e-02 9.984377e-01 4.694430e-02 -5.120821e+01 4.834556e-01 -5.574744e-02 8.735919e-01 5.366873e+02 +8.749171e-01 -4.604399e-03 -4.842508e-01 4.473618e+02 3.291627e-02 9.982076e-01 4.998001e-02 -5.116403e+01 4.831527e-01 -5.966808e-02 8.735005e-01 5.378721e+02 +8.750321e-01 -6.540546e-03 -4.840209e-01 4.467096e+02 3.389332e-02 9.982825e-01 4.778395e-02 -5.111940e+01 4.828770e-01 -5.821755e-02 8.737508e-01 5.390567e+02 +8.750733e-01 -8.296741e-03 -4.839194e-01 4.460541e+02 3.317208e-02 9.985300e-01 4.286552e-02 -5.108251e+01 4.828523e-01 -5.356307e-02 8.740621e-01 5.402360e+02 +8.750183e-01 -8.605486e-03 -4.840134e-01 4.453943e+02 3.275161e-02 9.986034e-01 4.145504e-02 -5.104877e+01 4.829806e-01 -5.212612e-02 8.740781e-01 5.414219e+02 +8.749662e-01 -6.311026e-03 -4.841429e-01 4.447219e+02 3.145343e-02 9.985438e-01 4.382766e-02 -5.102500e+01 4.831613e-01 -5.357567e-02 8.738906e-01 5.426128e+02 +8.748295e-01 -6.058432e-03 -4.843932e-01 4.440561e+02 3.258364e-02 9.983932e-01 4.635993e-02 -5.099564e+01 4.833340e-01 -5.634031e-02 8.736211e-01 5.438079e+02 +8.746727e-01 -6.648738e-03 -4.846685e-01 4.433873e+02 3.452304e-02 9.982210e-01 4.860941e-02 -5.096885e+01 4.834831e-01 -5.924954e-02 8.733462e-01 5.450152e+02 +8.744047e-01 -1.083108e-02 -4.850765e-01 4.427218e+02 3.913000e-02 9.980685e-01 4.825074e-02 -5.094161e+01 4.836169e-01 -6.117170e-02 8.731395e-01 5.462148e+02 +8.739887e-01 -1.414350e-02 -4.857405e-01 4.420493e+02 4.204194e-02 9.980292e-01 4.658570e-02 -5.092215e+01 4.841242e-01 -6.113683e-02 8.728608e-01 5.474178e+02 +8.735769e-01 -1.727436e-02 -4.863796e-01 4.413819e+02 4.525186e-02 9.979236e-01 4.583350e-02 -5.089574e+01 4.845779e-01 -6.204866e-02 8.725446e-01 5.486179e+02 +8.729819e-01 -1.815551e-02 -4.874146e-01 4.407082e+02 4.674049e-02 9.978220e-01 4.654688e-02 -5.087524e+01 4.855079e-01 -6.341657e-02 8.719291e-01 5.498222e+02 +8.723302e-01 -2.012954e-02 -4.885026e-01 4.400378e+02 4.990184e-02 9.975999e-01 4.800312e-02 -5.084550e+01 4.863638e-01 -6.625173e-02 8.712410e-01 5.510285e+02 +8.716471e-01 -2.270580e-02 -4.896078e-01 4.393679e+02 5.273961e-02 9.974716e-01 4.763391e-02 -5.081432e+01 4.872883e-01 -6.734167e-02 8.706406e-01 5.522344e+02 +8.709314e-01 -2.587511e-02 -4.907230e-01 4.387015e+02 5.488981e-02 9.974859e-01 4.482202e-02 -5.078350e+01 4.883295e-01 -6.597258e-02 8.701620e-01 5.534325e+02 +8.703045e-01 -2.798749e-02 -4.917183e-01 4.380252e+02 5.608583e-02 9.975214e-01 4.249106e-02 -5.076100e+01 4.893102e-01 -6.455857e-02 8.697169e-01 5.546346e+02 +8.700063e-01 -2.812326e-02 -4.922379e-01 4.373475e+02 5.540151e-02 9.976252e-01 4.092164e-02 -5.074030e+01 4.899181e-01 -6.287279e-02 8.694982e-01 5.558322e+02 +8.698049e-01 -2.676736e-02 -4.926692e-01 4.366616e+02 5.423406e-02 9.976636e-01 4.154558e-02 -5.072552e+01 4.904061e-01 -6.285598e-02 8.692243e-01 5.570347e+02 +8.695925e-01 -2.511320e-02 -4.931312e-01 4.359778e+02 5.349264e-02 9.976192e-01 4.352470e-02 -5.071985e+01 4.908640e-01 -6.422762e-02 8.688655e-01 5.582375e+02 +8.694231e-01 -2.327601e-02 -4.935198e-01 4.352940e+02 5.201264e-02 9.976510e-01 4.457703e-02 -5.070482e+01 4.913229e-01 -6.442555e-02 8.685914e-01 5.594394e+02 +8.693718e-01 -2.226685e-02 -4.936567e-01 4.346097e+02 5.300747e-02 9.974224e-01 4.836101e-02 -5.068832e+01 4.913074e-01 -6.821117e-02 8.683111e-01 5.606462e+02 +8.693384e-01 -2.110200e-02 -4.937667e-01 4.339195e+02 5.407387e-02 9.971511e-01 5.258881e-02 -5.066223e+01 4.912503e-01 -7.241733e-02 8.680027e-01 5.618550e+02 +8.689403e-01 -2.404756e-02 -4.943324e-01 4.332238e+02 5.652788e-02 9.971048e-01 5.085933e-02 -5.063791e+01 4.916781e-01 -7.213727e-02 8.677838e-01 5.630631e+02 +8.685761e-01 -2.800023e-02 -4.947642e-01 4.325327e+02 5.716129e-02 9.973992e-01 4.390276e-02 -5.061057e+01 4.922481e-01 -6.641423e-02 8.679176e-01 5.642651e+02 +8.685269e-01 -2.956496e-02 -4.947596e-01 4.318430e+02 5.650947e-02 9.976170e-01 3.958585e-02 -5.057943e+01 4.924102e-01 -6.233996e-02 8.681278e-01 5.654701e+02 +8.686365e-01 -2.683153e-02 -4.947230e-01 4.311495e+02 5.709775e-02 9.973007e-01 4.616338e-02 -5.054788e+01 4.921489e-01 -6.834675e-02 8.678237e-01 5.666842e+02 +8.685931e-01 -2.383269e-02 -4.949526e-01 4.304526e+02 5.649684e-02 9.970924e-01 5.113494e-02 -5.051190e+01 4.922947e-01 -7.237870e-02 8.674140e-01 5.679021e+02 +8.682452e-01 -2.989544e-02 -4.952339e-01 4.297678e+02 5.935961e-02 9.972723e-01 4.386777e-02 -5.046789e+01 4.925715e-01 -6.748485e-02 8.676514e-01 5.691083e+02 +8.680927e-01 -3.292625e-02 -4.953089e-01 4.290756e+02 5.742665e-02 9.977596e-01 3.432035e-02 -5.044003e+01 4.930692e-01 -5.823717e-02 8.680387e-01 5.703119e+02 +8.683908e-01 -3.189376e-02 -4.948538e-01 4.283732e+02 5.482079e-02 9.979871e-01 3.188075e-02 -5.042652e+01 4.928409e-01 -5.481321e-02 8.683912e-01 5.715291e+02 +8.687469e-01 -2.373665e-02 -4.946872e-01 4.276678e+02 4.992426e-02 9.979601e-01 3.978942e-02 -5.041213e+01 4.927336e-01 -5.926381e-02 8.681597e-01 5.727476e+02 +8.689307e-01 -1.931001e-02 -4.945570e-01 4.269489e+02 4.888215e-02 9.977014e-01 4.693003e-02 -5.038686e+01 4.925139e-01 -6.495393e-02 8.678772e-01 5.739785e+02 +8.687929e-01 -2.030799e-02 -4.947590e-01 4.262418e+02 5.091209e-02 9.975269e-01 4.845650e-02 -5.035325e+01 4.925514e-01 -6.728786e-02 8.676782e-01 5.752054e+02 +8.685441e-01 -2.617275e-02 -4.949204e-01 4.255378e+02 5.655254e-02 9.973160e-01 4.650419e-02 -5.031989e+01 4.923748e-01 -6.837993e-02 8.676930e-01 5.764352e+02 +8.682184e-01 -3.121446e-02 -4.951996e-01 4.248396e+02 6.092362e-02 9.971739e-01 4.395956e-02 -5.028640e+01 4.924279e-01 -6.833583e-02 8.676663e-01 5.776603e+02 +8.680261e-01 -3.391048e-02 -4.953592e-01 4.241408e+02 6.303812e-02 9.971183e-01 4.220366e-02 -5.026059e+01 4.925006e-01 -6.786038e-02 8.676624e-01 5.788791e+02 +8.680078e-01 -3.242008e-02 -4.954911e-01 4.234364e+02 6.120905e-02 9.972419e-01 4.197707e-02 -5.023673e+01 4.927635e-01 -6.676495e-02 8.675981e-01 5.801009e+02 +8.683690e-01 -2.766259e-02 -4.951466e-01 4.227282e+02 5.549951e-02 9.975917e-01 4.159998e-02 -5.021640e+01 4.928033e-01 -6.360451e-02 8.678129e-01 5.813211e+02 +8.689513e-01 -2.284548e-02 -4.943702e-01 4.220216e+02 4.990757e-02 9.978867e-01 4.160858e-02 -5.019484e+01 4.923748e-01 -6.082862e-02 8.682550e-01 5.825432e+02 +8.693116e-01 -2.019108e-02 -4.938520e-01 4.213185e+02 4.785420e-02 9.979094e-01 4.343677e-02 -5.016794e+01 4.919425e-01 -6.139296e-02 8.684603e-01 5.837677e+02 +8.694119e-01 -1.871226e-02 -4.937337e-01 4.206202e+02 4.835092e-02 9.977085e-01 4.732811e-02 -5.013181e+01 4.917166e-01 -6.502008e-02 8.683243e-01 5.849938e+02 +8.691958e-01 -2.166440e-02 -4.939933e-01 4.199191e+02 5.252475e-02 9.974326e-01 4.867579e-02 -5.009065e+01 4.916705e-01 -6.825565e-02 8.681021e-01 5.862247e+02 +8.690524e-01 -2.527604e-02 -4.940740e-01 4.192199e+02 5.546701e-02 9.973753e-01 4.653967e-02 -5.004716e+01 4.916008e-01 -6.785021e-02 8.681733e-01 5.874491e+02 +8.691217e-01 -2.830751e-02 -4.937877e-01 4.185191e+02 5.831524e-02 9.972621e-01 4.547102e-02 -5.000599e+01 4.911486e-01 -6.831518e-02 8.683928e-01 5.886777e+02 +8.691730e-01 -2.802528e-02 -4.937134e-01 4.178126e+02 5.871513e-02 9.971789e-01 4.676272e-02 -4.996618e+01 4.910100e-01 -6.963333e-02 8.683664e-01 5.899105e+02 +8.692773e-01 -2.818589e-02 -4.935206e-01 4.171204e+02 5.812370e-02 9.972755e-01 4.542161e-02 -4.992758e+01 4.908958e-01 -6.816920e-02 8.685472e-01 5.911346e+02 +8.694486e-01 -2.935590e-02 -4.931506e-01 4.164298e+02 5.722938e-02 9.974973e-01 4.151992e-02 -4.988676e+01 4.906975e-01 -6.432212e-02 8.689526e-01 5.923700e+02 +8.697467e-01 -2.863013e-02 -4.926674e-01 4.157242e+02 5.651182e-02 9.975267e-01 4.179623e-02 -4.984746e+01 4.902522e-01 -6.419364e-02 8.692134e-01 5.935957e+02 +8.698581e-01 -2.771573e-02 -4.925230e-01 4.150052e+02 5.764350e-02 9.972914e-01 4.568518e-02 -4.981034e+01 4.899227e-01 -6.813035e-02 8.690995e-01 5.948325e+02 +8.696246e-01 -2.916740e-02 -4.928512e-01 4.142946e+02 6.102161e-02 9.969491e-01 4.867083e-02 -4.976385e+01 4.899280e-01 -7.239991e-02 8.687513e-01 5.960781e+02 +8.693196e-01 -3.265943e-02 -4.931703e-01 4.135918e+02 6.422398e-02 9.968188e-01 4.719593e-02 -4.971593e+01 4.900600e-01 -7.270169e-02 8.686516e-01 5.973085e+02 +8.691980e-01 -3.329554e-02 -4.933419e-01 4.128885e+02 6.176937e-02 9.972262e-01 4.152622e-02 -4.966429e+01 4.905908e-01 -6.656791e-02 8.688436e-01 5.985414e+02 +8.693610e-01 -3.159039e-02 -4.931670e-01 4.121767e+02 5.790472e-02 9.975920e-01 3.817323e-02 -4.961870e+01 4.907735e-01 -6.174299e-02 8.690967e-01 5.997800e+02 +8.695597e-01 -2.675926e-02 -4.931024e-01 4.114673e+02 5.420171e-02 9.976697e-01 4.144112e-02 -4.957445e+01 4.908444e-01 -6.276251e-02 8.689836e-01 6.010127e+02 +8.694386e-01 -2.333719e-02 -4.934896e-01 4.107555e+02 5.539478e-02 9.971897e-01 5.043825e-02 -4.952793e+01 4.909256e-01 -7.118969e-02 8.682880e-01 6.022616e+02 +8.690184e-01 -2.544558e-02 -4.941252e-01 4.100519e+02 6.130940e-02 9.965179e-01 5.650797e-02 -4.946831e+01 4.909667e-01 -7.940096e-02 8.675524e-01 6.035126e+02 +8.683699e-01 -3.062487e-02 -4.949707e-01 4.093515e+02 6.720690e-02 9.961509e-01 5.627295e-02 -4.940925e+01 4.913421e-01 -8.213116e-02 8.670855e-01 6.047568e+02 +8.677981e-01 -3.595530e-02 -4.956144e-01 4.086488e+02 7.039372e-02 9.962155e-01 5.098379e-02 -4.935138e+01 4.919056e-01 -7.913176e-02 8.670449e-01 6.059990e+02 +8.678455e-01 -3.644178e-02 -4.954960e-01 4.079372e+02 6.762871e-02 9.966885e-01 4.514702e-02 -4.930529e+01 4.922099e-01 -7.269037e-02 8.674361e-01 6.072374e+02 +8.682309e-01 -3.347257e-02 -4.950300e-01 4.072176e+02 6.217454e-02 9.971971e-01 4.161990e-02 -4.926501e+01 4.922494e-01 -6.691393e-02 8.678784e-01 6.084775e+02 +8.686643e-01 -2.901037e-02 -4.945511e-01 4.064993e+02 5.852553e-02 9.973026e-01 4.429657e-02 -4.922812e+01 4.919320e-01 -6.742270e-02 8.680190e-01 6.097203e+02 +8.687985e-01 -2.476036e-02 -4.945464e-01 4.057805e+02 5.669306e-02 9.971552e-01 4.967161e-02 -4.918610e+01 4.919097e-01 -7.119195e-02 8.677307e-01 6.109706e+02 +8.687696e-01 -2.230833e-02 -4.947139e-01 4.050636e+02 5.457123e-02 9.972135e-01 5.086506e-02 -4.914054e+01 4.922006e-01 -7.118714e-02 8.675661e-01 6.122170e+02 +8.689272e-01 -2.219517e-02 -4.944421e-01 4.043499e+02 5.217007e-02 9.975361e-01 4.690441e-02 -4.909676e+01 4.921827e-01 -6.655158e-02 8.679441e-01 6.134579e+02 +8.695661e-01 -1.959505e-02 -4.934277e-01 4.036350e+02 4.703353e-02 9.979563e-01 4.325610e-02 -4.905752e+01 4.915716e-01 -6.082167e-02 8.687105e-01 6.146904e+02 +8.698694e-01 -1.574609e-02 -4.930308e-01 4.029223e+02 4.375050e-02 9.980142e-01 4.531643e-02 -4.902251e+01 4.913381e-01 -6.098970e-02 8.688308e-01 6.159245e+02 +8.698189e-01 -1.567384e-02 -4.931222e-01 4.022195e+02 4.577614e-02 9.977477e-01 4.903129e-02 -4.898679e+01 4.912430e-01 -6.522156e-02 8.685772e-01 6.171589e+02 +8.695670e-01 -1.777478e-02 -4.934951e-01 4.015240e+02 4.856833e-02 9.975851e-01 4.964903e-02 -4.894889e+01 4.914209e-01 -6.714137e-02 8.683303e-01 6.183840e+02 +8.693806e-01 -1.985413e-02 -4.937441e-01 4.008334e+02 5.106549e-02 9.974525e-01 4.980675e-02 -4.890969e+01 4.914974e-01 -6.851429e-02 8.681797e-01 6.196007e+02 +8.693608e-01 -1.862684e-02 -4.938269e-01 4.001444e+02 5.014155e-02 9.974570e-01 5.064857e-02 -4.887174e+01 4.916276e-01 -6.879311e-02 8.680839e-01 6.208041e+02 +8.695492e-01 -1.439368e-02 -4.936366e-01 3.994535e+02 4.745873e-02 9.973843e-01 5.451715e-02 -4.883192e+01 4.915607e-01 -7.083270e-02 8.679578e-01 6.220037e+02 +8.699190e-01 -9.421412e-03 -4.931046e-01 3.987675e+02 4.487871e-02 9.971817e-01 6.012108e-02 -4.878751e+01 4.911484e-01 -7.443036e-02 8.678901e-01 6.231945e+02 +8.701461e-01 -7.644176e-03 -4.927347e-01 3.980883e+02 4.291997e-02 9.972557e-01 6.032342e-02 -4.874092e+01 4.909213e-01 -7.363832e-02 8.680861e-01 6.243760e+02 +8.700574e-01 -1.341796e-02 -4.927678e-01 3.974201e+02 4.448177e-02 9.976884e-01 5.137259e-02 -4.869741e+01 4.909394e-01 -6.661627e-02 8.686430e-01 6.255465e+02 +8.698176e-01 -1.834642e-02 -4.930322e-01 3.967581e+02 4.491472e-02 9.981034e-01 4.209864e-02 -4.865995e+01 4.913247e-01 -5.876253e-02 8.689919e-01 6.267067e+02 +8.698414e-01 -1.977737e-02 -4.929350e-01 3.960940e+02 4.561806e-02 9.981396e-01 4.045138e-02 -4.862996e+01 4.912179e-01 -5.767300e-02 8.691253e-01 6.278721e+02 +8.699222e-01 -1.744657e-02 -4.928804e-01 3.954251e+02 4.460343e-02 9.980618e-01 4.339544e-02 -4.860221e+01 4.911679e-01 -5.973479e-02 8.690142e-01 6.290399e+02 +8.699810e-01 -1.725284e-02 -4.927834e-01 3.947620e+02 4.585896e-02 9.978871e-01 4.602433e-02 -4.856954e+01 4.909481e-01 -6.263881e-02 8.689340e-01 6.302025e+02 +8.699250e-01 -1.306802e-02 -4.930110e-01 3.940961e+02 4.420786e-02 9.976909e-01 5.156005e-02 -4.853288e+01 4.911988e-01 -6.664832e-02 8.684939e-01 6.313639e+02 +8.700674e-01 -8.496748e-03 -4.928595e-01 3.934288e+02 4.351683e-02 9.972716e-01 5.962959e-02 -4.848850e+01 4.910081e-01 -7.332944e-02 8.680632e-01 6.325285e+02 +8.702009e-01 -3.460455e-03 -4.926850e-01 3.927607e+02 4.201432e-02 9.968541e-01 6.720589e-02 -4.843649e+01 4.909025e-01 -7.918243e-02 8.676087e-01 6.336905e+02 +8.702795e-01 -1.883054e-04 -4.925583e-01 3.920962e+02 3.840893e-02 9.969809e-01 6.748189e-02 -4.837947e+01 4.910585e-01 -7.764673e-02 8.676592e-01 6.348411e+02 +8.702443e-01 -2.731380e-03 -4.926129e-01 3.914379e+02 3.711419e-02 9.975061e-01 6.003467e-02 -4.832449e+01 4.912203e-01 -7.052774e-02 8.681753e-01 6.359867e+02 +8.703126e-01 -5.143414e-03 -4.924729e-01 3.907834e+02 3.380343e-02 9.982112e-01 4.931304e-02 -4.827643e+01 4.913383e-01 -5.956502e-02 8.689296e-01 6.371196e+02 +8.704538e-01 -4.278541e-03 -4.922315e-01 3.901222e+02 3.083026e-02 9.984729e-01 4.584085e-02 -4.823561e+01 4.912837e-01 -5.507795e-02 8.692564e-01 6.382660e+02 +8.703800e-01 1.227384e-03 -4.923791e-01 3.894579e+02 2.834806e-02 9.982132e-01 5.259926e-02 -4.819688e+01 4.915638e-01 -5.973932e-02 8.687900e-01 6.394199e+02 +8.704326e-01 5.673868e-03 -4.922550e-01 3.887972e+02 2.781946e-02 9.977687e-01 6.069248e-02 -4.815019e+01 4.915009e-01 -6.652297e-02 8.683325e-01 6.405725e+02 +8.704619e-01 8.598505e-03 -4.921608e-01 3.881382e+02 2.639964e-02 9.975929e-01 6.412067e-02 -4.809696e+01 4.915275e-01 -6.880745e-02 8.681395e-01 6.417192e+02 +8.703716e-01 9.763056e-03 -4.922987e-01 3.874833e+02 2.316627e-02 9.978843e-01 6.074700e-02 -4.804319e+01 4.918502e-01 -6.427717e-02 8.683039e-01 6.428613e+02 +8.703119e-01 8.405432e-03 -4.924292e-01 3.868330e+02 2.269585e-02 9.981076e-01 5.714932e-02 -4.799230e+01 4.919777e-01 -6.091382e-02 8.684741e-01 6.440194e+02 +8.702599e-01 9.292245e-03 -4.925052e-01 3.861900e+02 2.201068e-02 9.980899e-01 5.772428e-02 -4.794469e+01 4.921009e-01 -6.107549e-02 8.683930e-01 6.451820e+02 +8.699736e-01 8.269539e-03 -4.930291e-01 3.855505e+02 2.552675e-02 9.977634e-01 6.177859e-02 -4.789466e+01 4.924372e-01 -6.633116e-02 8.678166e-01 6.463363e+02 +8.693433e-01 4.387999e-03 -4.941893e-01 3.849223e+02 3.134136e-02 9.974582e-01 6.399014e-02 -4.783613e+01 4.932140e-01 -7.111795e-02 8.669960e-01 6.474845e+02 +8.688013e-01 2.770271e-04 -4.951609e-01 3.842894e+02 3.704245e-02 9.971613e-01 6.555197e-02 -4.777691e+01 4.937734e-01 -7.529360e-02 8.663247e-01 6.486269e+02 +8.681957e-01 -3.013531e-03 -4.962129e-01 3.836585e+02 4.038417e-02 9.970936e-01 6.460250e-02 -4.771843e+01 4.945760e-01 -7.612674e-02 8.657940e-01 6.497588e+02 +8.677282e-01 -4.806133e-03 -4.970159e-01 3.830236e+02 4.237970e-02 9.970272e-01 6.434847e-02 -4.766127e+01 4.952290e-01 -7.690035e-02 8.653522e-01 6.508834e+02 +8.672817e-01 -5.430961e-03 -4.977882e-01 3.823884e+02 4.411524e-02 9.968449e-01 6.598490e-02 -4.760395e+01 4.958593e-01 -7.918752e-02 8.647848e-01 6.520056e+02 +8.667400e-01 -5.647560e-03 -4.987284e-01 3.817488e+02 4.466319e-02 9.967974e-01 6.633250e-02 -4.754772e+01 4.967566e-01 -7.976781e-02 8.642164e-01 6.531252e+02 +8.660638e-01 -8.601044e-03 -4.998596e-01 3.811112e+02 4.682303e-02 9.968525e-01 6.397346e-02 -4.749167e+01 4.977361e-01 -7.881002e-02 8.637405e-01 6.542415e+02 +8.655217e-01 -1.217709e-02 -5.007235e-01 3.804737e+02 4.880268e-02 9.969979e-01 6.011150e-02 -4.743664e+01 4.984883e-01 -7.646444e-02 8.635175e-01 6.553567e+02 +8.650922e-01 -1.245444e-02 -5.014583e-01 3.798269e+02 4.625974e-02 9.974123e-01 5.503293e-02 -4.738702e+01 4.994753e-01 -7.080587e-02 8.634297e-01 6.564706e+02 +8.646477e-01 -9.229873e-03 -5.022939e-01 3.791756e+02 4.119884e-02 9.977662e-01 5.258521e-02 -4.734086e+01 5.006865e-01 -6.616159e-02 8.630965e-01 6.575813e+02 +8.645497e-01 -4.313383e-03 -5.025288e-01 3.785039e+02 3.821627e-02 9.976319e-01 5.718418e-02 -4.730158e+01 5.010921e-01 -6.864333e-02 8.626672e-01 6.587014e+02 +8.645629e-01 4.441227e-04 -5.025244e-01 3.778247e+02 3.555967e-02 9.974387e-01 6.205978e-02 -4.726164e+01 5.012649e-01 -7.152417e-02 8.623327e-01 6.598283e+02 +8.643812e-01 -2.755823e-03 -5.028297e-01 3.771619e+02 3.814660e-02 9.974627e-01 6.010857e-02 -4.721396e+01 5.013881e-01 -7.113794e-02 8.622930e-01 6.609492e+02 +8.636790e-01 -8.072405e-03 -5.039777e-01 3.764948e+02 4.298289e-02 9.974091e-01 5.768494e-02 -4.715466e+01 5.022063e-01 -7.148367e-02 8.617881e-01 6.620620e+02 +8.632681e-01 -1.203513e-02 -5.046023e-01 3.758262e+02 4.754936e-02 9.972089e-01 5.756278e-02 -4.710010e+01 5.025011e-01 -7.368561e-02 8.614308e-01 6.631605e+02 +8.631148e-01 -1.099402e-02 -5.048881e-01 3.751551e+02 4.727649e-02 9.971315e-01 5.910727e-02 -4.704329e+01 5.027900e-01 -7.488568e-02 8.611587e-01 6.642593e+02 +8.631122e-01 -1.058887e-02 -5.049012e-01 3.744990e+02 4.700786e-02 9.971240e-01 5.944655e-02 -4.697592e+01 5.028196e-01 -7.504335e-02 8.611276e-01 6.653732e+02 +8.629418e-01 -9.318566e-03 -5.052175e-01 3.738337e+02 4.641156e-02 9.970653e-01 6.088320e-02 -4.690733e+01 5.031675e-01 -7.598657e-02 8.608417e-01 6.664941e+02 +8.627946e-01 -6.720818e-03 -5.055100e-01 3.731648e+02 4.680309e-02 9.966793e-01 6.663162e-02 -4.683431e+01 5.033835e-01 -8.114881e-02 8.602440e-01 6.676213e+02 +8.627015e-01 -5.330735e-03 -5.056855e-01 3.724951e+02 4.950402e-02 9.960322e-01 7.395429e-02 -4.675934e+01 5.032847e-01 -8.883392e-02 8.595423e-01 6.687590e+02 +8.624670e-01 -8.544872e-03 -5.060413e-01 3.718326e+02 5.549448e-02 9.954254e-01 7.777306e-02 -4.667555e+01 5.030617e-01 -9.515917e-02 8.589957e-01 6.698938e+02 +8.620407e-01 -1.681962e-02 -5.065600e-01 3.711676e+02 6.462008e-02 9.949400e-01 7.693191e-02 -4.659142e+01 5.027028e-01 -9.905236e-02 8.587656e-01 6.710400e+02 +8.614690e-01 -2.307498e-02 -5.072858e-01 3.705035e+02 7.135950e-02 9.945554e-01 7.594268e-02 -4.650545e+01 5.027714e-01 -1.016219e-01 8.584252e-01 6.721827e+02 +8.610684e-01 -2.627941e-02 -5.078097e-01 3.698304e+02 7.412080e-02 9.944837e-01 7.421801e-02 -4.642668e+01 5.030581e-01 -1.015460e-01 8.582662e-01 6.733302e+02 +8.612967e-01 -2.794162e-02 -5.073336e-01 3.691522e+02 7.377964e-02 9.947818e-01 7.046711e-02 -4.634942e+01 5.027173e-01 -9.812396e-02 8.588637e-01 6.744742e+02 +8.619303e-01 -2.915506e-02 -5.061879e-01 3.684705e+02 7.326781e-02 9.950289e-01 6.744850e-02 -4.627731e+01 5.017050e-01 -9.522316e-02 8.597817e-01 6.756252e+02 +8.625071e-01 -2.755272e-02 -5.052944e-01 3.677865e+02 7.142469e-02 9.951489e-01 6.765411e-02 -4.620856e+01 5.009791e-01 -9.444262e-02 8.602909e-01 6.767785e+02 +8.627091e-01 -3.006590e-02 -5.048061e-01 3.671072e+02 7.655642e-02 9.944909e-01 7.160304e-02 -4.613390e+01 4.998722e-01 -1.004187e-01 8.602580e-01 6.779476e+02 +8.630583e-01 -2.843625e-02 -5.043033e-01 3.664232e+02 7.978918e-02 9.935538e-01 8.052647e-02 -4.605412e+01 4.987625e-01 -1.097370e-01 8.597637e-01 6.791248e+02 +8.635640e-01 -2.689850e-02 -5.035214e-01 3.657394e+02 8.207765e-02 9.927568e-01 8.773336e-02 -4.596538e+01 4.975143e-01 -1.170912e-01 8.595167e-01 6.802997e+02 +8.639896e-01 -2.769276e-02 -5.027477e-01 3.650548e+02 8.352133e-02 9.925359e-01 8.886266e-02 -4.587123e+01 4.965342e-01 -1.187665e-01 8.598536e-01 6.814757e+02 +8.645628e-01 -2.926522e-02 -5.016721e-01 3.643707e+02 8.349314e-02 9.927927e-01 8.597401e-02 -4.577698e+01 4.955403e-01 -1.162161e-01 8.607750e-01 6.826496e+02 +8.652700e-01 -2.786159e-02 -5.005313e-01 3.636807e+02 7.924379e-02 9.935027e-01 8.168663e-02 -4.568742e+01 4.950032e-01 -1.103450e-01 8.618559e-01 6.838227e+02 +8.660520e-01 -2.522672e-02 -4.993172e-01 3.629885e+02 7.303044e-02 9.943968e-01 7.642992e-02 -4.560501e+01 4.945914e-01 -1.026576e-01 8.630415e-01 6.849967e+02 +8.669428e-01 -2.163844e-02 -4.979378e-01 3.622951e+02 6.772951e-02 9.949043e-01 7.468689e-02 -4.552513e+01 4.937843e-01 -9.847432e-02 8.639906e-01 6.861759e+02 +8.678306e-01 -1.604995e-02 -4.966010e-01 3.616018e+02 6.317890e-02 9.949297e-01 7.825198e-02 -4.544747e+01 4.928271e-01 -9.928414e-02 8.644443e-01 6.873612e+02 +8.684018e-01 -1.303772e-02 -4.956899e-01 3.609118e+02 6.019159e-02 9.950336e-01 7.927842e-02 -4.536648e+01 4.921945e-01 -9.868186e-02 8.648736e-01 6.885479e+02 +8.685190e-01 -1.175021e-02 -4.955167e-01 3.602271e+02 6.085193e-02 9.946839e-01 8.307149e-02 -4.527938e+01 4.919063e-01 -1.023023e-01 8.646169e-01 6.897359e+02 +8.685616e-01 -1.145740e-02 -4.954489e-01 3.595419e+02 6.378180e-02 9.940027e-01 8.882800e-02 -4.519008e+01 4.914598e-01 -1.087532e-01 8.640833e-01 6.909338e+02 +8.682625e-01 -1.420609e-02 -4.959018e-01 3.588611e+02 6.485712e-02 9.942615e-01 8.507419e-02 -4.510158e+01 4.918474e-01 -1.060295e-01 8.642012e-01 6.921201e+02 +8.677169e-01 -1.913026e-02 -4.966905e-01 3.581823e+02 6.406754e-02 9.952282e-01 7.359414e-02 -4.501690e+01 4.929125e-01 -9.568060e-02 8.648019e-01 6.932975e+02 +8.677907e-01 -1.950958e-02 -4.965468e-01 3.574968e+02 6.154934e-02 9.957546e-01 6.844306e-02 -4.494145e+01 4.931035e-01 -8.995636e-02 8.653073e-01 6.944789e+02 +8.680103e-01 -1.078221e-02 -4.964292e-01 3.568021e+02 5.538317e-02 9.956283e-01 7.521331e-02 -4.486999e+01 4.934480e-01 -9.277973e-02 8.648126e-01 6.956645e+02 +8.680916e-01 -2.476691e-03 -4.963980e-01 3.561097e+02 5.233061e-02 9.948720e-01 8.655104e-02 -4.478982e+01 4.936381e-01 -1.011110e-01 8.637696e-01 6.968509e+02 +8.677187e-01 -1.686109e-03 -4.970528e-01 3.554312e+02 5.480659e-02 9.942213e-01 9.230477e-02 -4.469867e+01 4.940248e-01 -1.073363e-01 8.627968e-01 6.980274e+02 +8.672708e-01 -5.404107e-03 -4.978074e-01 3.547576e+02 5.761480e-02 9.943117e-01 8.958136e-02 -4.460540e+01 4.944916e-01 -1.063724e-01 8.626488e-01 6.991973e+02 +8.668719e-01 -8.446140e-03 -4.984595e-01 3.540858e+02 5.668350e-02 9.950423e-01 8.171791e-02 -4.451807e+01 4.952980e-01 -9.909337e-02 8.630529e-01 7.003574e+02 +8.667687e-01 -6.950069e-03 -4.986621e-01 3.534050e+02 5.422937e-02 9.952873e-01 8.038911e-02 -4.443555e+01 4.957533e-01 -9.672087e-02 8.630606e-01 7.015245e+02 +8.668100e-01 -1.573100e-03 -4.986361e-01 3.527203e+02 5.086299e-02 9.950580e-01 8.527907e-02 -4.435254e+01 4.960377e-01 -9.928285e-02 8.626062e-01 7.026937e+02 +8.666498e-01 1.591572e-03 -4.989145e-01 3.520383e+02 4.893834e-02 9.949014e-01 8.818316e-02 -4.426268e+01 4.965111e-01 -1.008399e-01 8.621531e-01 7.038597e+02 +8.662137e-01 1.476991e-03 -4.996716e-01 3.513600e+02 5.071615e-02 9.945714e-01 9.085966e-02 -4.416760e+01 4.970933e-01 -1.040453e-01 8.614364e-01 7.050283e+02 +8.658908e-01 6.771950e-05 -5.002332e-01 3.506831e+02 5.166854e-02 9.946393e-01 8.957157e-02 -4.407528e+01 4.975576e-01 -1.034055e-01 8.612454e-01 7.061919e+02 +8.656030e-01 -5.743733e-03 -5.006981e-01 3.500088e+02 5.469123e-02 9.950364e-01 8.313527e-02 -4.398567e+01 4.977352e-01 -9.934591e-02 8.616205e-01 7.073537e+02 +8.651644e-01 -9.752908e-03 -5.013935e-01 3.493354e+02 5.767823e-02 9.951112e-01 8.016841e-02 -4.390104e+01 4.981604e-01 -9.827832e-02 8.614972e-01 7.085182e+02 +8.646832e-01 -1.020490e-02 -5.022140e-01 3.486565e+02 5.939648e-02 9.948567e-01 8.205014e-02 -4.381776e+01 4.987936e-01 -1.007771e-01 8.608419e-01 7.096888e+02 +8.643013e-01 -1.317626e-02 -5.028020e-01 3.479827e+02 6.350223e-02 9.945162e-01 8.309643e-02 -4.373339e+01 4.989498e-01 -1.037494e-01 8.603982e-01 7.108555e+02 +8.640897e-01 -1.541255e-02 -5.031019e-01 3.473056e+02 6.493268e-02 9.945923e-01 8.105408e-02 -4.364794e+01 4.991320e-01 -1.027057e-01 8.604177e-01 7.120161e+02 +8.639202e-01 -1.292025e-02 -5.034631e-01 3.466249e+02 5.983901e-02 9.952229e-01 7.714091e-02 -4.356871e+01 5.000613e-01 -9.677030e-02 8.605662e-01 7.131669e+02 +8.638607e-01 -1.064538e-02 -5.036183e-01 3.459420e+02 5.620631e-02 9.955705e-01 7.536701e-02 -4.349246e+01 5.005852e-01 -9.341310e-02 8.606326e-01 7.143209e+02 +8.643058e-01 -4.238697e-03 -5.029490e-01 3.452576e+02 5.084970e-02 9.955774e-01 7.899358e-02 -4.341812e+01 5.003897e-01 -9.384939e-02 8.606987e-01 7.154719e+02 +8.645452e-01 -7.419562e-04 -5.025546e-01 3.445755e+02 4.819651e-02 9.955120e-01 8.144276e-02 -4.333937e+01 5.002386e-01 -9.463230e-02 8.607008e-01 7.166248e+02 +8.644546e-01 -4.026846e-03 -5.026949e-01 3.439062e+02 5.207349e-02 9.953059e-01 8.157477e-02 -4.325647e+01 5.000067e-01 -9.669473e-02 8.606064e-01 7.177792e+02 +8.641155e-01 -6.349504e-03 -5.032535e-01 3.432369e+02 5.464052e-02 9.951937e-01 8.126467e-02 -4.317426e+01 5.003187e-01 -9.772008e-02 8.603092e-01 7.189300e+02 +8.641298e-01 -7.440789e-03 -5.032141e-01 3.425679e+02 5.653470e-02 9.949970e-01 8.237002e-02 -4.308882e+01 5.000836e-01 -9.962742e-02 8.602271e-01 7.200774e+02 +8.645259e-01 -7.164107e-04 -5.025879e-01 3.418896e+02 5.174458e-02 9.948117e-01 8.759031e-02 -4.300512e+01 4.999175e-01 -1.017303e-01 8.600775e-01 7.212267e+02 +8.649876e-01 4.014243e-04 -5.017932e-01 3.412156e+02 5.136082e-02 9.946768e-01 8.933113e-02 -4.291836e+01 4.991579e-01 -1.030428e-01 8.603624e-01 7.223728e+02 +8.651048e-01 -5.398274e-04 -5.015910e-01 3.405490e+02 5.114385e-02 9.948825e-01 8.713818e-02 -4.282699e+01 4.989770e-01 -1.010369e-01 8.607051e-01 7.235100e+02 +8.650750e-01 -2.989206e-03 -5.016338e-01 3.398820e+02 5.187113e-02 9.951549e-01 8.352248e-02 -4.274090e+01 4.989536e-01 -9.827349e-02 8.610386e-01 7.246548e+02 +8.654115e-01 -2.302623e-03 -5.010566e-01 3.392149e+02 5.245516e-02 9.949109e-01 8.602700e-02 -4.265276e+01 4.983085e-01 -1.007317e-01 8.611281e-01 7.258005e+02 +8.660032e-01 7.847953e-04 -5.000380e-01 3.385403e+02 5.071992e-02 9.947034e-01 8.940171e-02 -4.256217e+01 4.974596e-01 -1.027840e-01 8.613764e-01 7.269515e+02 +8.667215e-01 2.840460e-03 -4.987844e-01 3.378687e+02 5.029720e-02 9.943890e-01 9.306261e-02 -4.246757e+01 4.962501e-01 -1.057468e-01 8.617154e-01 7.281034e+02 +8.672675e-01 5.066967e-03 -4.978168e-01 3.371980e+02 5.013092e-02 9.939768e-01 9.745225e-02 -4.236934e+01 4.953121e-01 -1.094732e-01 8.617897e-01 7.292586e+02 +8.679395e-01 2.371922e-03 -4.966643e-01 3.365329e+02 5.370704e-02 9.936767e-01 9.860057e-02 -4.226537e+01 4.937576e-01 -1.122537e-01 8.623238e-01 7.304159e+02 +8.686587e-01 2.946644e-03 -4.954023e-01 3.358662e+02 5.320069e-02 9.936449e-01 9.919445e-02 -4.215609e+01 4.925462e-01 -1.125218e-01 8.629814e-01 7.315718e+02 +8.694973e-01 1.207967e-03 -4.939362e-01 3.352025e+02 5.534674e-02 9.934611e-01 9.985885e-02 -4.204402e+01 4.908270e-01 -1.141647e-01 8.637448e-01 7.327369e+02 +8.700937e-01 2.748242e-03 -4.928788e-01 3.345591e+02 5.336819e-02 9.935800e-01 9.975257e-02 -4.192455e+01 4.899886e-01 -1.130981e-01 8.643610e-01 7.339132e+02 +8.707774e-01 5.644361e-03 -4.916452e-01 3.339675e+02 4.875169e-02 9.940154e-01 9.775841e-02 -4.178921e+01 4.892546e-01 -1.090943e-01 8.652909e-01 7.351052e+02 +8.715611e-01 8.205918e-03 -4.902183e-01 3.333794e+02 4.670227e-02 9.939239e-01 9.966976e-02 -4.164739e+01 4.880576e-01 -1.097626e-01 8.658821e-01 7.363067e+02 +8.722134e-01 9.683662e-03 -4.890298e-01 3.327660e+02 4.527064e-02 9.939142e-01 1.004241e-01 -4.151637e+01 4.870262e-01 -1.097299e-01 8.664668e-01 7.375068e+02 +8.727002e-01 8.527510e-03 -4.881820e-01 3.321306e+02 4.552883e-02 9.940698e-01 9.875407e-02 -4.140414e+01 4.861291e-01 -1.084090e-01 8.671366e-01 7.387070e+02 +8.730022e-01 6.283846e-03 -4.876758e-01 3.314603e+02 4.725793e-02 9.941220e-01 9.740730e-02 -4.130393e+01 4.854213e-01 -1.080833e-01 8.675736e-01 7.399035e+02 +8.732228e-01 5.798747e-03 -4.872868e-01 3.307887e+02 4.926962e-02 9.937550e-01 1.001174e-01 -4.120590e+01 4.848243e-01 -1.114332e-01 8.674837e-01 7.411077e+02 +8.734090e-01 5.835121e-03 -4.869526e-01 3.301090e+02 5.082191e-02 9.933760e-01 1.030589e-01 -4.110036e+01 4.843284e-01 -1.147604e-01 8.673269e-01 7.423257e+02 +8.734985e-01 4.329916e-03 -4.868076e-01 3.294307e+02 5.176147e-02 9.934661e-01 1.017141e-01 -4.099339e+01 4.840672e-01 -1.140450e-01 8.675670e-01 7.435388e+02 +8.733868e-01 3.696688e-03 -4.870133e-01 3.287436e+02 5.202293e-02 9.935419e-01 1.008370e-01 -4.088247e+01 4.842408e-01 -1.134055e-01 8.675540e-01 7.447653e+02 +8.733417e-01 5.005920e-03 -4.870824e-01 3.280526e+02 5.023914e-02 9.936889e-01 1.002916e-01 -4.077320e+01 4.845104e-01 -1.120594e-01 8.675784e-01 7.459933e+02 +8.733468e-01 6.904036e-03 -4.870500e-01 3.273565e+02 4.760167e-02 9.939038e-01 9.944505e-02 -4.066330e+01 4.847674e-01 -1.100344e-01 8.676940e-01 7.472256e+02 +8.734038e-01 9.881137e-03 -4.868965e-01 3.266576e+02 4.412784e-02 9.940755e-01 9.933121e-02 -4.055324e+01 4.849934e-01 -1.082419e-01 8.677932e-01 7.484610e+02 +8.734959e-01 1.314269e-02 -4.866541e-01 3.259603e+02 4.066371e-02 9.941726e-01 9.983617e-02 -4.044479e+01 4.851303e-01 -1.069956e-01 8.678712e-01 7.496947e+02 +8.734533e-01 1.395645e-02 -4.867080e-01 3.252660e+02 3.945897e-02 9.942724e-01 9.932461e-02 -4.033481e+01 4.853065e-01 -1.059604e-01 8.678997e-01 7.509292e+02 +8.732898e-01 1.062222e-02 -4.870854e-01 3.245791e+02 4.534176e-02 9.936513e-01 1.029620e-01 -4.022165e+01 4.850867e-01 -1.120009e-01 8.672639e-01 7.521686e+02 +8.722081e-01 1.554015e-02 -4.888881e-01 3.238824e+02 4.187729e-02 9.934529e-01 1.062904e-01 -4.010899e+01 4.873391e-01 -1.131806e-01 8.658468e-01 7.534009e+02 +8.712599e-01 1.226771e-02 -4.906687e-01 3.231960e+02 4.471774e-02 9.935459e-01 1.042441e-01 -3.999412e+01 4.887807e-01 -1.127653e-01 8.650881e-01 7.546225e+02 +8.704783e-01 1.068763e-02 -4.920909e-01 3.225029e+02 4.313614e-02 9.942610e-01 9.789934e-02 -3.988511e+01 4.903131e-01 -1.064461e-01 8.650215e-01 7.558379e+02 +8.696031e-01 8.576992e-03 -4.936770e-01 3.218104e+02 4.149447e-02 9.950426e-01 9.037932e-02 -3.978289e+01 4.920048e-01 -9.907898e-02 8.649361e-01 7.570464e+02 +8.682872e-01 6.257598e-03 -4.960224e-01 3.211126e+02 4.432062e-02 9.949429e-01 9.013502e-02 -3.969944e+01 4.940779e-01 -1.002471e-01 8.636188e-01 7.582359e+02 +8.670860e-01 7.798926e-03 -4.980974e-01 3.204070e+02 4.593712e-02 9.943654e-01 9.553636e-02 -3.962143e+01 4.960359e-01 -1.057194e-01 8.618420e-01 7.594366e+02 +8.660262e-01 1.555319e-02 -4.997568e-01 3.196885e+02 4.290037e-02 9.935187e-01 1.052616e-01 -3.954703e+01 4.981549e-01 -1.125991e-01 8.597459e-01 7.606640e+02 +8.653111e-01 2.447261e-02 -5.006375e-01 3.189726e+02 3.564102e-02 9.932750e-01 1.101568e-01 -3.946109e+01 4.999665e-01 -1.131631e-01 8.586195e-01 7.618740e+02 +8.646651e-01 2.924382e-02 -5.014970e-01 3.182784e+02 2.851758e-02 9.938367e-01 1.071228e-01 -3.934753e+01 5.015387e-01 -1.069268e-01 8.585019e-01 7.630947e+02 +8.637285e-01 2.947169e-02 -5.030949e-01 3.175957e+02 2.487026e-02 9.945794e-01 1.009612e-01 -3.921785e+01 5.033434e-01 -9.971519e-02 8.583136e-01 7.642885e+02 +8.625824e-01 2.904848e-02 -5.050821e-01 3.169176e+02 2.408797e-02 9.948599e-01 9.835435e-02 -3.909332e+01 5.053429e-01 -9.700511e-02 8.574488e-01 7.654846e+02 +8.615015e-01 2.865320e-02 -5.069459e-01 3.162279e+02 2.483425e-02 9.948338e-01 9.843244e-02 -3.897840e+01 5.071473e-01 -9.738930e-02 8.563392e-01 7.666799e+02 +8.605549e-01 2.980739e-02 -5.084848e-01 3.155547e+02 2.463820e-02 9.946817e-01 1.000057e-01 -3.885350e+01 5.087614e-01 -9.858855e-02 8.552438e-01 7.678927e+02 +8.595795e-01 3.032298e-02 -5.101017e-01 3.148742e+02 2.593290e-02 9.943629e-01 1.028098e-01 -3.872868e+01 5.103437e-01 -1.016016e-01 8.539475e-01 7.691077e+02 +8.584203e-01 2.993106e-02 -5.120730e-01 3.142031e+02 2.669402e-02 9.943367e-01 1.028686e-01 -3.860085e+01 5.122519e-01 -1.019738e-01 8.527598e-01 7.703210e+02 +8.574059e-01 2.937468e-02 -5.138019e-01 3.135146e+02 2.766440e-02 9.942955e-01 1.030100e-01 -3.847775e+01 5.138968e-01 -1.025354e-01 8.517021e-01 7.715262e+02 +8.563048e-01 2.986497e-02 -5.156067e-01 3.128335e+02 2.722467e-02 9.943286e-01 1.028074e-01 -3.836443e+01 5.157528e-01 -1.020717e-01 8.506352e-01 7.727283e+02 +8.550536e-01 2.985072e-02 -5.176798e-01 3.121436e+02 2.691250e-02 9.944414e-01 1.017935e-01 -3.825942e+01 5.178408e-01 -1.009709e-01 8.494973e-01 7.739286e+02 +8.533867e-01 3.090769e-02 -5.203614e-01 3.114507e+02 2.706814e-02 9.942665e-01 1.034475e-01 -3.815310e+01 5.205752e-01 -1.023659e-01 8.476571e-01 7.751196e+02 +8.511593e-01 3.286851e-02 -5.238774e-01 3.107590e+02 2.817896e-02 9.937372e-01 1.081311e-01 -3.804414e+01 5.241506e-01 -1.067991e-01 8.449024e-01 7.763019e+02 +8.483633e-01 3.443700e-02 -5.282933e-01 3.100572e+02 2.951484e-02 9.932537e-01 1.121422e-01 -3.793151e+01 5.285911e-01 -1.107298e-01 8.416236e-01 7.774737e+02 +8.454953e-01 3.342246e-02 -5.329359e-01 3.093573e+02 3.044059e-02 9.933994e-01 1.105935e-01 -3.781722e+01 5.331145e-01 -1.097291e-01 8.388971e-01 7.786294e+02 +8.424879e-01 3.214647e-02 -5.377554e-01 3.086458e+02 3.001340e-02 9.938667e-01 1.064336e-01 -3.770154e+01 5.378786e-01 -1.058089e-01 8.363558e-01 7.797743e+02 +8.394424e-01 3.238449e-02 -5.424830e-01 3.079283e+02 2.821826e-02 9.942789e-01 1.030204e-01 -3.759073e+01 5.427156e-01 -1.017876e-01 8.337259e-01 7.809165e+02 +8.362545e-01 3.449082e-02 -5.472558e-01 3.071949e+02 2.542469e-02 9.945075e-01 1.015300e-01 -3.748176e+01 5.477518e-01 -9.881873e-02 8.307844e-01 7.820505e+02 +8.327272e-01 3.715940e-02 -5.524352e-01 3.064553e+02 2.316858e-02 9.945329e-01 1.018207e-01 -3.737301e+01 5.531986e-01 -9.758799e-02 8.273136e-01 7.831857e+02 +8.287722e-01 3.947296e-02 -5.581922e-01 3.057013e+02 2.182591e-02 9.944697e-01 1.027305e-01 -3.726206e+01 5.591603e-01 -9.732324e-02 8.233273e-01 7.843202e+02 +8.244487e-01 4.307659e-02 -5.642950e-01 3.049374e+02 1.992035e-02 9.942723e-01 1.050039e-01 -3.714843e+01 5.655861e-01 -9.781125e-02 8.188683e-01 7.854482e+02 +8.200395e-01 4.550402e-02 -5.704951e-01 3.041637e+02 1.949417e-02 9.940347e-01 1.073078e-01 -3.703348e+01 5.719748e-01 -9.911794e-02 8.142606e-01 7.865725e+02 +8.155784e-01 4.795427e-02 -5.766561e-01 3.033812e+02 1.788440e-02 9.939950e-01 1.079542e-01 -3.691860e+01 5.783701e-01 -9.835822e-02 8.098231e-01 7.876885e+02 +8.111037e-01 4.593762e-02 -5.830957e-01 3.025924e+02 1.910382e-02 9.942985e-01 1.049071e-01 -3.680181e+01 5.845903e-01 -9.622989e-02 8.056015e-01 7.887994e+02 +8.065723e-01 4.546261e-02 -5.893848e-01 3.017926e+02 1.871950e-02 9.945738e-01 1.023348e-01 -3.668578e+01 5.908391e-01 -9.357336e-02 8.013446e-01 7.899059e+02 +8.018279e-01 4.800500e-02 -5.956237e-01 3.009793e+02 1.779647e-02 9.944073e-01 1.041030e-01 -3.656946e+01 5.972900e-01 -9.407270e-02 7.964891e-01 7.910086e+02 +7.970952e-01 5.266416e-02 -6.015528e-01 3.001538e+02 1.693810e-02 9.938477e-01 1.094525e-01 -3.645179e+01 6.036161e-01 -9.743317e-02 7.912991e-01 7.921110e+02 +7.921442e-01 5.573799e-02 -6.077836e-01 2.993209e+02 1.608099e-02 9.935695e-01 1.120761e-01 -3.632865e+01 6.101221e-01 -9.855421e-02 7.861540e-01 7.932037e+02 +7.872484e-01 5.626157e-02 -6.140640e-01 2.984792e+02 1.624065e-02 9.935917e-01 1.118555e-01 -3.620437e+01 6.164221e-01 -9.803088e-02 7.812898e-01 7.942879e+02 +7.820624e-01 5.572938e-02 -6.207034e-01 2.976240e+02 1.639765e-02 9.938086e-01 1.098888e-01 -3.607127e+01 6.229844e-01 -9.611792e-02 7.763065e-01 7.953748e+02 +7.766308e-01 5.516329e-02 -6.275362e-01 2.967361e+02 1.711402e-02 9.939434e-01 1.085522e-01 -3.592834e+01 6.297236e-01 -9.504466e-02 7.709829e-01 7.964414e+02 +7.707182e-01 5.512427e-02 -6.347873e-01 2.958274e+02 1.788644e-02 9.939863e-01 1.080333e-01 -3.578757e+01 6.369251e-01 -9.461732e-02 7.650973e-01 7.974878e+02 +7.642545e-01 5.659218e-02 -6.424270e-01 2.949270e+02 1.765572e-02 9.939330e-01 1.085607e-01 -3.565796e+01 6.446731e-01 -9.431047e-02 7.586185e-01 7.985393e+02 +7.577078e-01 5.715893e-02 -6.500860e-01 2.940369e+02 1.784351e-02 9.939698e-01 1.081925e-01 -3.554030e+01 6.523500e-01 -9.357808e-02 7.521187e-01 7.995900e+02 +7.510247e-01 5.500613e-02 -6.579789e-01 2.931249e+02 1.929225e-02 9.942703e-01 1.051400e-01 -3.541910e+01 6.599922e-01 -9.165663e-02 7.456603e-01 8.006365e+02 +7.444474e-01 5.248282e-02 -6.656153e-01 2.921858e+02 2.110740e-02 9.945577e-01 1.020267e-01 -3.529449e+01 6.673474e-01 -9.000291e-02 7.392880e-01 8.016785e+02 +7.377981e-01 5.085459e-02 -6.731031e-01 2.912150e+02 2.204975e-02 9.948102e-01 9.932941e-02 -3.519650e+01 6.746612e-01 -8.812679e-02 7.328478e-01 8.026984e+02 +7.311497e-01 5.245118e-02 -6.801978e-01 2.902181e+02 2.207571e-02 9.946989e-01 1.004322e-01 -3.512078e+01 6.818598e-01 -8.844683e-02 7.261159e-01 8.037172e+02 +7.244548e-01 5.684523e-02 -6.869745e-01 2.891922e+02 1.999595e-02 9.944415e-01 1.033742e-01 -3.508692e+01 6.890322e-01 -8.862662e-02 7.192912e-01 8.046957e+02 +7.178359e-01 5.701010e-02 -6.938743e-01 2.881764e+02 1.971047e-02 9.945780e-01 1.021077e-01 -3.502570e+01 6.959333e-01 -8.697312e-02 7.128201e-01 8.056775e+02 +7.112231e-01 5.416949e-02 -7.008762e-01 2.871608e+02 1.997201e-02 9.950670e-01 9.717385e-02 -3.497845e+01 7.026826e-01 -8.311017e-02 7.066327e-01 8.066491e+02 +7.045860e-01 5.310447e-02 -7.076288e-01 2.861513e+02 2.159391e-02 9.951296e-01 9.618122e-02 -3.490584e+01 7.092899e-01 -8.304840e-02 7.000076e-01 8.076240e+02 +6.978262e-01 5.603074e-02 -7.140723e-01 2.851251e+02 2.265839e-02 9.947098e-01 1.001943e-01 -3.484532e+01 7.159087e-01 -8.609790e-02 6.928650e-01 8.085921e+02 +6.909176e-01 5.877103e-02 -7.205407e-01 2.841028e+02 2.315736e-02 9.943794e-01 1.033121e-01 -3.476325e+01 7.225625e-01 -8.806592e-02 6.856732e-01 8.095491e+02 +6.840591e-01 6.279206e-02 -7.267189e-01 2.830650e+02 2.198286e-02 9.940606e-01 1.065841e-01 -3.470230e+01 7.290952e-01 -8.888519e-02 6.786159e-01 8.104763e+02 +6.772438e-01 6.497481e-02 -7.328842e-01 2.820410e+02 1.998466e-02 9.941010e-01 1.066008e-01 -3.461047e+01 7.354872e-01 -8.684113e-02 6.719502e-01 8.113975e+02 +6.704007e-01 6.537772e-02 -7.391135e-01 2.810203e+02 1.736940e-02 9.944550e-01 1.037184e-01 -3.450613e+01 7.417960e-01 -8.237082e-02 6.655477e-01 8.123070e+02 +6.636342e-01 6.404614e-02 -7.453106e-01 2.800071e+02 1.607716e-02 9.948769e-01 9.980723e-02 -3.439317e+01 7.478845e-01 -7.821795e-02 6.592046e-01 8.132137e+02 +6.565722e-01 6.511220e-02 -7.514475e-01 2.789848e+02 1.547959e-02 9.948939e-01 9.973180e-02 -3.428074e+01 7.541043e-01 -7.711321e-02 6.522118e-01 8.141203e+02 +6.494329e-01 6.706123e-02 -7.574561e-01 2.779650e+02 1.653922e-02 9.946223e-01 1.022392e-01 -3.415341e+01 7.602390e-01 -7.892522e-02 6.448313e-01 8.150193e+02 +6.417835e-01 6.731640e-02 -7.639257e-01 2.769422e+02 1.792379e-02 9.945512e-01 1.026969e-01 -3.402858e+01 7.666764e-01 -7.960161e-02 6.370799e-01 8.159043e+02 +6.339036e-01 6.653308e-02 -7.705450e-01 2.759117e+02 1.990353e-02 9.945596e-01 1.022498e-01 -3.389906e+01 7.731559e-01 -8.015304e-02 6.291306e-01 8.167816e+02 +6.257237e-01 6.752687e-02 -7.771165e-01 2.748659e+02 2.177977e-02 9.943451e-01 1.039396e-01 -3.377735e+01 7.797407e-01 -8.196284e-02 6.207145e-01 8.176378e+02 +6.177432e-01 6.676870e-02 -7.835403e-01 2.738115e+02 2.433440e-02 9.942887e-01 1.039127e-01 -3.365174e+01 7.860033e-01 -8.325832e-02 6.125902e-01 8.184936e+02 +6.092726e-01 6.413262e-02 -7.903632e-01 2.727490e+02 2.590576e-02 9.945821e-01 1.006738e-01 -3.353182e+01 7.925376e-01 -8.181271e-02 6.043102e-01 8.193300e+02 +6.006628e-01 6.463900e-02 -7.968852e-01 2.716853e+02 2.583926e-02 9.946361e-01 1.001562e-01 -3.338937e+01 7.990848e-01 -8.075100e-02 5.957707e-01 8.201503e+02 +5.922802e-01 6.719607e-02 -8.029252e-01 2.706056e+02 2.379621e-02 9.946228e-01 1.007924e-01 -3.325497e+01 8.053806e-01 -7.880391e-02 5.874963e-01 8.209605e+02 +5.840000e-01 7.071516e-02 -8.086677e-01 2.695213e+02 1.881071e-02 9.947519e-01 1.005722e-01 -3.311932e+01 8.115357e-01 -7.394577e-02 5.796048e-01 8.217504e+02 +5.765823e-01 7.495122e-02 -8.135941e-01 2.684226e+02 1.494941e-02 9.946489e-01 1.022251e-01 -3.298643e+01 8.169023e-01 -7.110390e-02 5.723764e-01 8.225316e+02 +5.694316e-01 7.816219e-02 -8.183143e-01 2.673212e+02 1.249555e-02 9.945313e-01 1.036889e-01 -3.286207e+01 8.219437e-01 -6.926901e-02 5.653409e-01 8.233037e+02 +5.623115e-01 8.091944e-02 -8.229568e-01 2.662171e+02 1.387109e-02 9.941375e-01 1.072291e-01 -3.273080e+01 8.268092e-01 -7.171145e-02 5.578924e-01 8.240664e+02 +5.550363e-01 8.206640e-02 -8.277680e-01 2.651100e+02 1.515508e-02 9.939585e-01 1.087046e-01 -3.260506e+01 8.316881e-01 -7.287990e-02 5.504393e-01 8.248197e+02 +5.478581e-01 8.032834e-02 -8.327058e-01 2.640052e+02 1.723443e-02 9.940843e-01 1.072350e-01 -3.247739e+01 8.363937e-01 -7.310073e-02 5.432327e-01 8.255678e+02 +5.407677e-01 7.800800e-02 -8.375471e-01 2.628942e+02 1.709386e-02 9.944659e-01 1.036600e-01 -3.235083e+01 8.409983e-01 -7.037286e-02 5.364415e-01 8.262994e+02 +5.336609e-01 7.855517e-02 -8.420423e-01 2.617821e+02 1.516499e-02 9.946276e-01 1.024012e-01 -3.220685e+01 8.455625e-01 -6.741704e-02 5.296025e-01 8.270232e+02 +5.267739e-01 8.282691e-02 -8.459604e-01 2.606579e+02 1.318496e-02 9.943251e-01 1.055633e-01 -3.206464e+01 8.499032e-01 -6.676193e-02 5.226924e-01 8.277350e+02 +5.202480e-01 8.943401e-02 -8.493195e-01 2.595274e+02 1.203537e-02 9.936350e-01 1.120028e-01 -3.191153e+01 8.539304e-01 -6.849108e-02 5.158602e-01 8.284391e+02 +5.138481e-01 9.089885e-02 -8.530520e-01 2.583986e+02 1.224842e-02 9.934919e-01 1.132418e-01 -3.177911e+01 8.577937e-01 -6.863758e-02 5.093905e-01 8.291318e+02 +5.076554e-01 8.975228e-02 -8.568726e-01 2.572730e+02 1.335048e-02 9.936202e-01 1.119853e-01 -3.163159e+01 8.614567e-01 -6.828958e-02 5.032184e-01 8.298139e+02 +5.017697e-01 8.981161e-02 -8.603261e-01 2.561399e+02 1.347492e-02 9.936629e-01 1.115900e-01 -3.149114e+01 8.648962e-01 -6.758529e-02 4.973798e-01 8.304879e+02 +4.969170e-01 9.005065e-02 -8.631132e-01 2.550005e+02 1.300675e-02 9.937168e-01 1.111652e-01 -3.135612e+01 8.677006e-01 -6.646614e-02 4.926235e-01 8.311554e+02 +4.929034e-01 9.031364e-02 -8.653842e-01 2.538618e+02 1.071888e-02 9.938925e-01 1.098303e-01 -3.120256e+01 8.700180e-01 -6.341167e-02 4.889249e-01 8.318092e+02 +4.897915e-01 8.904410e-02 -8.672805e-01 2.527223e+02 1.139710e-02 9.940317e-01 1.084942e-01 -3.106118e+01 8.717651e-01 -6.302398e-02 4.858534e-01 8.324599e+02 +4.870771e-01 8.959855e-02 -8.687508e-01 2.515874e+02 1.253985e-02 9.939036e-01 1.095368e-01 -3.090128e+01 8.732689e-01 -6.424688e-02 4.829841e-01 8.331105e+02 +4.849267e-01 9.226615e-02 -8.696741e-01 2.504468e+02 1.475680e-02 9.934144e-01 1.136224e-01 -3.076004e+01 8.744303e-01 -6.793214e-02 4.803716e-01 8.337613e+02 +4.823702e-01 9.552117e-02 -8.707438e-01 2.493107e+02 1.644891e-02 9.928736e-01 1.180312e-01 -3.061022e+01 8.758130e-01 -7.125750e-02 4.773614e-01 8.344069e+02 +4.800480e-01 9.419358e-02 -8.721706e-01 2.481833e+02 1.800646e-02 9.929511e-01 1.171486e-01 -3.046151e+01 8.770574e-01 -7.194165e-02 4.749681e-01 8.350364e+02 +4.777305e-01 9.074231e-02 -8.738075e-01 2.470528e+02 1.777943e-02 9.934487e-01 1.128871e-01 -3.033941e+01 8.783265e-01 -6.946541e-02 4.729873e-01 8.356528e+02 +4.754938e-01 8.824955e-02 -8.752815e-01 2.459272e+02 1.592178e-02 9.939294e-01 1.088616e-01 -3.022284e+01 8.795749e-01 -6.569905e-02 4.712022e-01 8.362623e+02 +4.737394e-01 8.792619e-02 -8.762648e-01 2.448018e+02 1.645474e-02 9.939460e-01 1.086306e-01 -3.010763e+01 8.805113e-01 -6.588128e-02 4.694245e-01 8.368704e+02 +4.722997e-01 8.984408e-02 -8.768472e-01 2.436772e+02 1.659205e-02 9.937092e-01 1.107551e-01 -2.999503e+01 8.812818e-01 -6.685829e-02 4.678378e-01 8.374768e+02 +4.709273e-01 9.145219e-02 -8.774190e-01 2.425518e+02 1.781569e-02 9.934233e-01 1.131052e-01 -2.987888e+01 8.819921e-01 -6.889612e-02 4.662008e-01 8.380835e+02 +4.696267e-01 9.229100e-02 -8.780280e-01 2.414220e+02 1.996918e-02 9.931563e-01 1.150732e-01 -2.975900e+01 8.826392e-01 -7.157492e-02 4.645697e-01 8.386913e+02 +4.684876e-01 9.038500e-02 -8.788344e-01 2.402955e+02 2.048371e-02 9.933742e-01 1.130844e-01 -2.963889e+01 8.832326e-01 -7.098043e-02 4.635320e-01 8.392943e+02 +4.678204e-01 8.729741e-02 -8.795018e-01 2.391695e+02 2.012381e-02 9.937999e-01 1.093466e-01 -2.951900e+01 8.835944e-01 -6.885346e-02 4.631630e-01 8.398934e+02 +4.671448e-01 8.762385e-02 -8.798283e-01 2.380371e+02 1.748118e-02 9.939675e-01 1.082728e-01 -2.940177e+01 8.840080e-01 -6.595952e-02 4.627950e-01 8.404921e+02 +4.673284e-01 9.062265e-02 -8.794269e-01 2.369065e+02 1.525271e-02 9.937580e-01 1.105095e-01 -2.928595e+01 8.839522e-01 -6.505785e-02 4.630291e-01 8.410897e+02 +4.674455e-01 9.112719e-02 -8.793126e-01 2.357714e+02 1.226886e-02 9.939082e-01 1.095255e-01 -2.917122e+01 8.839367e-01 -6.198533e-02 4.634799e-01 8.416892e+02 +4.680467e-01 8.760614e-02 -8.793506e-01 2.346430e+02 1.261649e-02 9.943101e-01 1.057744e-01 -2.905623e+01 8.836136e-01 -6.060166e-02 4.642782e-01 8.422902e+02 +4.682944e-01 8.814849e-02 -8.791645e-01 2.335102e+02 1.259928e-02 9.942438e-01 1.063979e-01 -2.894204e+01 8.834826e-01 -6.090237e-02 4.644882e-01 8.428963e+02 +4.689047e-01 9.051015e-02 -8.785991e-01 2.323767e+02 1.624263e-02 9.936838e-01 1.110344e-01 -2.882747e+01 8.830994e-01 -6.633530e-02 4.644729e-01 8.435070e+02 +4.688679e-01 8.706597e-02 -8.789667e-01 2.312523e+02 2.141782e-02 9.937165e-01 1.098574e-01 -2.871339e+01 8.830085e-01 -7.033417e-02 4.640570e-01 8.441176e+02 +4.680455e-01 8.069285e-02 -8.800126e-01 2.301312e+02 2.520594e-02 9.941981e-01 1.045692e-01 -2.859830e+01 8.833448e-01 -7.112467e-02 4.632959e-01 8.447230e+02 +4.672717e-01 7.966182e-02 -8.805176e-01 2.290054e+02 2.805515e-02 9.940948e-01 1.048256e-01 -2.848731e+01 8.836685e-01 -7.368507e-02 4.622774e-01 8.453298e+02 +4.668450e-01 7.938244e-02 -8.807691e-01 2.278866e+02 2.658276e-02 9.942532e-01 1.037006e-01 -2.838165e+01 8.839395e-01 -7.182537e-02 4.620519e-01 8.459249e+02 +4.662266e-01 7.761026e-02 -8.812545e-01 2.267693e+02 2.351526e-02 9.947052e-01 1.000424e-01 -2.827878e+01 8.843527e-01 -6.736533e-02 4.619330e-01 8.465145e+02 +4.653516e-01 7.611236e-02 -8.818474e-01 2.256529e+02 2.094906e-02 9.950698e-01 9.693945e-02 -2.817805e+01 8.848780e-01 -6.358478e-02 4.614628e-01 8.471034e+02 +4.643647e-01 7.771519e-02 -8.822278e-01 2.245308e+02 1.727449e-02 9.951582e-01 9.675571e-02 -2.804682e+01 8.854756e-01 -6.016995e-02 4.607738e-01 8.476875e+02 +4.637049e-01 7.966747e-02 -8.824007e-01 2.234083e+02 1.220677e-02 9.952800e-01 9.627349e-02 -2.794030e+01 8.859056e-01 -5.541373e-02 4.605437e-01 8.482680e+02 +4.629503e-01 7.758892e-02 -8.829819e-01 2.222792e+02 6.643505e-03 9.958298e-01 9.098825e-02 -2.788023e+01 8.863593e-01 -4.798912e-02 4.605042e-01 8.488493e+02 +4.618726e-01 7.405260e-02 -8.838495e-01 2.211604e+02 1.592971e-04 9.965015e-01 8.357431e-02 -2.780349e+01 8.869462e-01 -3.874147e-02 4.602450e-01 8.494195e+02 +4.606881e-01 7.160192e-02 -8.846692e-01 2.200263e+02 -3.887140e-03 9.968938e-01 7.866077e-02 -2.777803e+01 8.875535e-01 -3.279924e-02 4.595354e-01 8.499912e+02 +4.590813e-01 7.310584e-02 -8.853813e-01 2.189000e+02 -6.148033e-03 9.968460e-01 7.912165e-02 -2.774859e+01 8.883730e-01 -3.087990e-02 4.580827e-01 8.505745e+02 +4.571688e-01 7.458844e-02 -8.862467e-01 2.177749e+02 -9.463094e-03 9.968286e-01 7.901374e-02 -2.770502e+01 8.893296e-01 -2.773597e-02 4.564248e-01 8.511493e+02 +4.552962e-01 7.355883e-02 -8.872962e-01 2.166526e+02 -7.994772e-03 9.968788e-01 7.854115e-02 -2.765011e+01 8.903041e-01 -2.866575e-02 4.544632e-01 8.517280e+02 +4.529609e-01 7.563968e-02 -8.883159e-01 2.155309e+02 -6.474830e-03 9.966472e-01 8.156248e-02 -2.759260e+01 8.915068e-01 -3.119291e-02 4.519319e-01 8.523051e+02 +4.500870e-01 8.171961e-02 -8.892377e-01 2.143998e+02 -9.382502e-03 9.961817e-01 8.679867e-02 -2.752866e+01 8.929354e-01 -3.072367e-02 4.491351e-01 8.528759e+02 +4.470737e-01 8.772209e-02 -8.901854e-01 2.132699e+02 -1.192984e-02 9.956759e-01 9.212605e-02 -2.745525e+01 8.944175e-01 -3.056736e-02 4.461870e-01 8.534423e+02 +4.450200e-01 9.270946e-02 -8.907088e-01 2.121399e+02 -1.368922e-02 9.952148e-01 9.674752e-02 -2.737385e+01 8.954160e-01 -3.086146e-02 4.441595e-01 8.540045e+02 +4.433646e-01 9.279123e-02 -8.915255e-01 2.110138e+02 -1.285155e-02 9.951830e-01 9.718886e-02 -2.728425e+01 8.962492e-01 -3.163260e-02 4.424213e-01 8.545662e+02 +4.415802e-01 9.879131e-02 -8.917664e-01 2.098806e+02 -1.044902e-02 9.944184e-01 1.049892e-01 -2.717937e+01 8.971609e-01 -3.704304e-02 4.401477e-01 8.551392e+02 +4.405046e-01 1.031505e-01 -8.918048e-01 2.087476e+02 -2.617003e-03 9.935205e-01 1.136228e-01 -2.704707e+01 8.977465e-01 -4.771749e-02 4.379202e-01 8.557206e+02 +4.399561e-01 1.034323e-01 -8.920429e-01 2.076159e+02 4.691261e-03 9.930665e-01 1.174597e-01 -2.689467e+01 8.980070e-01 -5.586192e-02 4.364204e-01 8.563049e+02 +4.398156e-01 1.059541e-01 -8.918161e-01 2.064688e+02 9.928429e-03 9.923819e-01 1.227984e-01 -2.676220e+01 8.980332e-01 -6.286298e-02 4.354131e-01 8.568850e+02 +4.402197e-01 1.084372e-01 -8.913182e-01 2.053149e+02 1.656743e-02 9.915307e-01 1.288117e-01 -2.663589e+01 8.977372e-01 -7.147226e-02 4.346948e-01 8.574662e+02 +4.407315e-01 1.052136e-01 -8.914516e-01 2.041657e+02 2.061101e-02 9.916590e-01 1.272306e-01 -2.651103e+01 8.974023e-01 -7.444823e-02 4.348867e-01 8.580438e+02 +4.416378e-01 9.617067e-02 -8.920243e-01 2.030103e+02 2.463427e-02 9.925638e-01 1.192064e-01 -2.639947e+01 8.968552e-01 -7.462038e-02 4.359846e-01 8.586205e+02 +4.427970e-01 8.942048e-02 -8.921518e-01 2.018494e+02 2.895889e-02 9.930691e-01 1.139085e-01 -2.629677e+01 8.961541e-01 -7.627404e-02 4.371385e-01 8.592014e+02 +4.441031e-01 9.142217e-02 -8.912993e-01 2.006761e+02 2.845299e-02 9.928399e-01 1.160145e-01 -2.619949e+01 8.955238e-01 -7.688251e-02 4.383220e-01 8.597836e+02 +4.459206e-01 9.170827e-02 -8.903620e-01 1.995027e+02 2.888268e-02 9.927449e-01 1.167192e-01 -2.611085e+01 8.946064e-01 -7.776350e-02 4.400366e-01 8.603633e+02 +4.476086e-01 8.690402e-02 -8.899968e-01 1.983356e+02 2.834914e-02 9.933872e-01 1.112573e-01 -2.601671e+01 8.937801e-01 -7.503036e-02 4.421850e-01 8.609411e+02 +4.496381e-01 8.201180e-02 -8.894379e-01 1.971693e+02 2.799567e-02 9.939927e-01 1.058051e-01 -2.592028e+01 8.927720e-01 -7.247439e-02 4.446410e-01 8.615200e+02 +4.514475e-01 8.365999e-02 -8.883672e-01 1.960025e+02 2.819219e-02 9.937606e-01 1.079118e-01 -2.581449e+01 8.918522e-01 -7.376151e-02 4.462722e-01 8.621073e+02 +4.537753e-01 8.897965e-02 -8.866626e-01 1.948332e+02 2.936807e-02 9.929685e-01 1.146778e-01 -2.570951e+01 8.906320e-01 -7.807750e-02 4.479714e-01 8.626996e+02 +4.565074e-01 8.466925e-02 -8.856817e-01 1.936771e+02 3.317954e-02 9.931491e-01 1.120447e-01 -2.562088e+01 8.891007e-01 -8.053571e-02 4.505706e-01 8.632970e+02 +4.585310e-01 7.764750e-02 -8.852798e-01 1.925266e+02 3.191799e-02 9.940939e-01 1.037235e-01 -2.554052e+01 8.881050e-01 -7.581676e-02 4.533445e-01 8.638934e+02 +4.605412e-01 7.390237e-02 -8.845566e-01 1.913745e+02 2.904172e-02 9.947400e-01 9.822839e-02 -2.545651e+01 8.871631e-01 -7.092724e-02 4.559725e-01 8.644903e+02 +4.633890e-01 6.977854e-02 -8.834034e-01 1.902234e+02 3.003447e-02 9.950855e-01 9.435470e-02 -2.539073e+01 8.856458e-01 -7.025547e-02 4.590159e-01 8.650885e+02 +4.658295e-01 6.837298e-02 -8.822291e-01 1.890702e+02 2.966510e-02 9.952432e-01 9.279521e-02 -2.533300e+01 8.843771e-01 -6.939813e-02 4.615853e-01 8.656869e+02 +4.672686e-01 6.905287e-02 -8.814147e-01 1.879176e+02 3.248303e-02 9.949312e-01 9.516653e-02 -2.526992e+01 8.835184e-01 -7.309933e-02 4.626571e-01 8.662947e+02 +4.679684e-01 6.854294e-02 -8.810831e-01 1.867657e+02 3.621727e-02 9.946627e-01 9.661478e-02 -2.518576e+01 8.830027e-01 -7.712307e-02 4.629882e-01 8.669090e+02 +4.688875e-01 6.183702e-02 -8.810907e-01 1.856228e+02 4.074233e-02 9.949702e-01 9.151110e-02 -2.509305e+01 8.823177e-01 -7.880608e-02 4.640097e-01 8.675261e+02 +4.690683e-01 5.487183e-02 -8.814557e-01 1.844833e+02 4.056691e-02 9.956758e-01 8.356996e-02 -2.501530e+01 8.822297e-01 -7.495793e-02 4.648140e-01 8.681352e+02 +4.691182e-01 5.166633e-02 -8.816228e-01 1.833368e+02 3.957223e-02 9.960547e-01 7.942915e-02 -2.494059e+01 8.822483e-01 -7.214942e-02 4.652228e-01 8.687467e+02 +4.697000e-01 5.450801e-02 -8.811418e-01 1.821885e+02 3.943313e-02 9.958006e-01 8.262106e-02 -2.487165e+01 8.819449e-01 -7.355328e-02 4.655781e-01 8.693629e+02 +4.705498e-01 6.107481e-02 -8.802572e-01 1.810396e+02 3.865653e-02 9.952170e-01 8.971527e-02 -2.480006e+01 8.815262e-01 -7.624318e-02 4.659382e-01 8.699856e+02 +4.708307e-01 6.396689e-02 -8.799016e-01 1.798955e+02 3.557900e-02 9.951798e-01 9.138551e-02 -2.474444e+01 8.815059e-01 -7.433309e-02 4.662852e-01 8.705981e+02 +4.714509e-01 6.388077e-02 -8.795757e-01 1.787508e+02 3.286004e-02 9.954080e-01 8.990623e-02 -2.467574e+01 8.812799e-01 -7.128925e-02 4.671868e-01 8.712106e+02 +4.726605e-01 6.125541e-02 -8.791131e-01 1.776082e+02 3.065726e-02 9.958344e-01 8.587147e-02 -2.460608e+01 8.807112e-01 -6.753923e-02 4.688136e-01 8.718229e+02 +4.743365e-01 6.216450e-02 -8.781461e-01 1.764647e+02 2.553004e-02 9.961128e-01 8.430567e-02 -2.453128e+01 8.799733e-01 -6.240835e-02 4.709056e-01 8.724338e+02 +4.763931e-01 6.485341e-02 -8.768373e-01 1.753145e+02 2.354643e-02 9.959771e-01 8.645832e-02 -2.447182e+01 8.789170e-01 -6.183452e-02 4.729495e-01 8.730514e+02 +4.789998e-01 6.665546e-02 -8.752807e-01 1.741651e+02 2.231199e-02 9.958662e-01 8.804875e-02 -2.442101e+01 8.775314e-01 -6.170458e-02 4.755325e-01 8.736717e+02 +4.827771e-01 6.368191e-02 -8.734248e-01 1.730207e+02 2.536441e-02 9.959173e-01 8.663286e-02 -2.435832e+01 8.753758e-01 -6.397826e-02 4.791908e-01 8.743033e+02 +4.862813e-01 6.070127e-02 -8.716914e-01 1.718785e+02 2.749323e-02 9.960274e-01 8.469693e-02 -2.429749e+01 8.733696e-01 -6.515213e-02 4.826806e-01 8.749380e+02 +4.904497e-01 5.752448e-02 -8.695689e-01 1.707408e+02 3.098954e-02 9.960367e-01 8.336926e-02 -2.422720e+01 8.709183e-01 -6.783595e-02 4.867232e-01 8.755816e+02 +4.958615e-01 5.747415e-02 -8.664977e-01 1.696028e+02 3.260648e-02 9.958716e-01 8.471480e-02 -2.414804e+01 8.677892e-01 -7.026022e-02 4.919403e-01 8.762303e+02 +5.025147e-01 5.836641e-02 -8.625963e-01 1.684640e+02 3.040144e-02 9.959087e-01 8.509751e-02 -2.406926e+01 8.640339e-01 -6.898690e-02 4.986843e-01 8.768820e+02 +5.104575e-01 5.527113e-02 -8.581249e-01 1.673361e+02 2.919552e-02 9.962428e-01 8.153422e-02 -2.398635e+01 8.594072e-01 -6.667314e-02 5.069259e-01 8.775418e+02 +5.191576e-01 5.537776e-02 -8.528826e-01 1.662104e+02 2.620215e-02 9.963983e-01 8.064575e-02 -2.389129e+01 8.542768e-01 -6.421519e-02 5.158367e-01 8.782120e+02 +5.285881e-01 5.927928e-02 -8.468062e-01 1.650935e+02 2.371361e-02 9.961382e-01 8.453540e-02 -2.379523e+01 8.485472e-01 -6.476522e-02 5.251410e-01 8.788987e+02 +5.384362e-01 6.203470e-02 -8.403798e-01 1.639838e+02 2.312562e-02 9.958231e-01 8.832585e-02 -2.370807e+01 8.423489e-01 -6.699212e-02 5.347526e-01 8.796035e+02 +5.486158e-01 5.860385e-02 -8.340182e-01 1.628865e+02 2.273649e-02 9.961257e-01 8.495067e-02 -2.361724e+01 8.357653e-01 -6.556791e-02 5.451578e-01 8.803099e+02 +5.587696e-01 5.676895e-02 -8.273777e-01 1.617937e+02 2.150580e-02 9.963270e-01 8.288503e-02 -2.352713e+01 8.290440e-01 -6.410704e-02 5.554963e-01 8.810396e+02 +5.685771e-01 5.909037e-02 -8.205050e-01 1.607043e+02 2.078419e-02 9.960665e-01 8.613642e-02 -2.343814e+01 8.223673e-01 -6.602872e-02 5.651124e-01 8.817881e+02 +5.785237e-01 5.936731e-02 -8.135022e-01 1.596216e+02 1.995279e-02 9.960192e-01 8.687641e-02 -2.334654e+01 8.154215e-01 -6.649169e-02 5.750362e-01 8.825441e+02 +5.884559e-01 5.292516e-02 -8.067953e-01 1.585536e+02 1.803624e-02 9.967477e-01 7.854108e-02 -2.326540e+01 8.083281e-01 -6.076950e-02 5.855874e-01 8.833156e+02 +5.984053e-01 4.450058e-02 -7.999568e-01 1.574873e+02 1.516795e-02 9.976481e-01 6.684424e-02 -2.320575e+01 8.010499e-01 -5.213364e-02 5.963229e-01 8.840921e+02 +6.085789e-01 4.397101e-02 -7.922742e-01 1.564212e+02 1.383864e-02 9.977234e-01 6.600344e-02 -2.315398e+01 7.933727e-01 -5.113228e-02 6.065848e-01 8.848995e+02 +6.190955e-01 4.408265e-02 -7.840776e-01 1.553693e+02 1.731768e-02 9.974141e-01 6.975070e-02 -2.310589e+01 7.851248e-01 -5.676073e-02 6.167311e-01 8.857270e+02 +6.290702e-01 4.004710e-02 -7.763163e-01 1.543328e+02 1.993882e-02 9.975122e-01 6.761470e-02 -2.304537e+01 7.770927e-01 -5.801321e-02 6.267067e-01 8.865594e+02 +6.384635e-01 3.594832e-02 -7.688122e-01 1.533098e+02 2.582165e-02 9.973458e-01 6.807786e-02 -2.296431e+01 7.692189e-01 -6.331721e-02 6.358405e-01 8.874128e+02 +6.473739e-01 4.589716e-02 -7.607894e-01 1.522790e+02 2.004854e-02 9.968143e-01 7.719594e-02 -2.288383e+01 7.619088e-01 -6.522734e-02 6.443913e-01 8.882770e+02 +6.564095e-01 5.587301e-02 -7.523329e-01 1.512530e+02 1.445191e-02 9.961393e-01 8.658890e-02 -2.280046e+01 7.542663e-01 -6.771041e-02 6.530678e-01 8.891419e+02 +6.645412e-01 5.385532e-02 -7.453085e-01 1.502514e+02 1.103881e-02 9.965831e-01 8.185478e-02 -2.271493e+01 7.471701e-01 -6.262317e-02 6.616760e-01 8.900158e+02 +6.708590e-01 4.699270e-02 -7.400946e-01 1.492592e+02 9.054779e-03 9.973968e-01 7.153795e-02 -2.263174e+01 7.415296e-01 -5.469326e-02 6.686870e-01 8.908973e+02 +6.756712e-01 4.426735e-02 -7.358729e-01 1.482741e+02 1.312714e-02 9.973148e-01 7.204793e-02 -2.255797e+01 7.370862e-01 -5.834060e-02 6.732757e-01 8.918040e+02 +6.786414e-01 4.780922e-02 -7.329121e-01 1.472850e+02 1.434453e-02 9.968261e-01 7.830717e-02 -2.248397e+01 7.343297e-01 -6.365575e-02 6.758016e-01 8.927182e+02 +6.808430e-01 5.195868e-02 -7.305841e-01 1.462981e+02 1.527574e-02 9.962562e-01 8.508883e-02 -2.239893e+01 7.322700e-01 -6.909233e-02 6.775004e-01 8.936330e+02 +6.825261e-01 5.944328e-02 -7.284399e-01 1.453080e+02 1.089196e-02 9.957490e-01 9.146210e-02 -2.230888e+01 7.307801e-01 -7.035939e-02 6.789771e-01 8.945454e+02 +6.844906e-01 6.322405e-02 -7.262750e-01 1.443221e+02 8.859579e-03 9.954373e-01 9.500518e-02 -2.221252e+01 7.289678e-01 -7.146463e-02 6.808074e-01 8.954598e+02 +6.857834e-01 6.273271e-02 -7.250971e-01 1.433415e+02 9.294496e-03 9.954422e-01 9.491255e-02 -2.211403e+01 7.277463e-01 -7.182884e-02 6.820746e-01 8.963779e+02 +6.865008e-01 5.906108e-02 -7.247265e-01 1.423664e+02 1.333952e-02 9.955051e-01 9.376392e-02 -2.201495e+01 7.270067e-01 -7.403649e-02 6.826271e-01 8.973018e+02 +6.859555e-01 5.382360e-02 -7.256502e-01 1.413921e+02 1.973717e-02 9.955172e-01 9.249793e-02 -2.191794e+01 7.273758e-01 -7.777172e-02 6.818181e-01 8.982279e+02 +6.845442e-01 4.679719e-02 -7.274678e-01 1.404196e+02 2.619642e-02 9.957135e-01 8.870386e-02 -2.183585e+01 7.285005e-01 -7.977874e-02 6.803839e-01 8.991490e+02 +6.823373e-01 4.527858e-02 -7.296339e-01 1.394306e+02 2.626180e-02 9.959175e-01 8.636268e-02 -2.177458e+01 7.305656e-01 -7.808996e-02 6.783626e-01 9.000629e+02 +6.805577e-01 4.568531e-02 -7.312688e-01 1.384313e+02 2.744609e-02 9.957641e-01 8.775219e-02 -2.172117e+01 7.321802e-01 -7.979088e-02 6.764210e-01 9.009750e+02 +6.787374e-01 4.604152e-02 -7.329364e-01 1.374288e+02 2.523419e-02 9.959812e-01 8.593362e-02 -2.165937e+01 7.339474e-01 -7.682140e-02 6.748478e-01 9.018834e+02 +6.769672e-01 4.691305e-02 -7.345166e-01 1.364274e+02 2.477451e-02 9.959486e-01 8.644397e-02 -2.159545e+01 7.355961e-01 -7.671701e-02 6.730623e-01 9.027898e+02 +6.751821e-01 4.687216e-02 -7.361605e-01 1.354302e+02 2.594018e-02 9.958531e-01 8.719857e-02 -2.154869e+01 7.371949e-01 -7.797103e-02 6.711663e-01 9.036871e+02 +6.734055e-01 4.568306e-02 -7.378605e-01 1.344306e+02 2.742817e-02 9.958578e-01 8.668863e-02 -2.149490e+01 7.387643e-01 -7.861474e-02 6.693631e-01 9.045854e+02 +6.718144e-01 4.227098e-02 -7.395125e-01 1.334322e+02 3.135732e-02 9.958523e-01 8.541026e-02 -2.144197e+01 7.400555e-01 -8.056895e-02 6.677023e-01 9.054804e+02 +6.702506e-01 3.871319e-02 -7.411245e-01 1.324336e+02 3.609475e-02 9.957561e-01 8.465706e-02 -2.137904e+01 7.412566e-01 -8.349213e-02 6.660087e-01 9.063774e+02 +6.687138e-01 3.599634e-02 -7.426481e-01 1.314305e+02 3.779599e-02 9.958903e-01 8.230427e-02 -2.132109e+01 7.425587e-01 -8.310710e-02 6.646050e-01 9.072689e+02 +6.679305e-01 3.385601e-02 -7.434532e-01 1.304232e+02 3.980278e-02 9.959099e-01 8.111207e-02 -2.125372e+01 7.431585e-01 -8.376871e-02 6.638510e-01 9.081650e+02 +6.675993e-01 3.515427e-02 -7.436904e-01 1.294123e+02 3.924437e-02 9.958344e-01 8.230220e-02 -2.119143e+01 7.434857e-01 -8.413053e-02 6.634387e-01 9.090564e+02 +6.675320e-01 3.992668e-02 -7.435099e-01 1.284000e+02 3.499229e-02 9.957757e-01 8.488993e-02 -2.112285e+01 7.437584e-01 -8.268384e-02 6.633150e-01 9.099427e+02 +6.680782e-01 4.391652e-02 -7.427940e-01 1.273858e+02 3.313362e-02 9.955108e-01 8.865880e-02 -2.104828e+01 7.433530e-01 -8.384245e-02 6.636239e-01 9.108329e+02 +6.698628e-01 4.843929e-02 -7.409032e-01 1.263765e+02 2.980228e-02 9.953113e-01 9.201691e-02 -2.096874e+01 7.418866e-01 -8.371929e-02 6.652784e-01 9.117211e+02 +6.723517e-01 4.198672e-02 -7.390402e-01 1.253871e+02 2.998878e-02 9.960254e-01 8.386939e-02 -2.089602e+01 7.396241e-01 -7.855262e-02 6.684202e-01 9.126057e+02 +6.740479e-01 3.058240e-02 -7.380543e-01 1.244085e+02 3.527661e-02 9.966699e-01 7.351584e-02 -2.083099e+01 7.378448e-01 -7.558924e-02 6.707244e-01 9.134963e+02 +6.759954e-01 2.789004e-02 -7.363779e-01 1.234262e+02 4.118290e-02 9.962919e-01 7.554012e-02 -2.076716e+01 7.357542e-01 -8.139093e-02 6.723401e-01 9.144012e+02 +6.784164e-01 2.585583e-02 -7.342225e-01 1.224460e+02 5.179065e-02 9.952111e-01 8.290080e-02 -2.070084e+01 7.328498e-01 -9.426710e-02 6.738284e-01 9.153117e+02 +6.808971e-01 2.896301e-02 -7.318062e-01 1.214574e+02 5.181616e-02 9.948086e-01 8.758347e-02 -2.062162e+01 7.305437e-01 -9.755469e-02 6.758615e-01 9.162210e+02 diff --git a/tools/Ground-Truth/dataset/poses/03.txt b/tools/Ground-Truth/dataset/poses/03.txt new file mode 100644 index 0000000..ed66b8a --- /dev/null +++ b/tools/Ground-Truth/dataset/poses/03.txt @@ -0,0 +1,801 @@ +1.000000e+00 -1.822835e-10 5.241111e-10 -5.551115e-17 -1.822835e-10 9.999999e-01 -5.072855e-10 -3.330669e-16 5.241111e-10 -5.072855e-10 9.999999e-01 2.220446e-16 +9.999986e-01 7.122128e-04 1.533514e-03 -1.101102e-02 -7.055720e-04 9.999903e-01 -4.327036e-03 -1.712164e-02 -1.536580e-03 4.325946e-03 9.999894e-01 9.617130e-01 +9.999968e-01 -1.383964e-03 2.129266e-03 -1.699529e-02 1.395070e-03 9.999853e-01 -5.223267e-03 -3.304158e-02 -2.122006e-03 5.226219e-03 9.999840e-01 1.924885e+00 +9.999935e-01 -2.875213e-03 2.196984e-03 -3.106702e-02 2.877221e-03 9.999954e-01 -9.111935e-04 -6.341853e-02 -2.194353e-03 9.175076e-04 9.999971e-01 2.888054e+00 +9.999894e-01 -4.378258e-03 1.426928e-03 -4.462738e-02 4.370282e-03 9.999750e-01 5.546374e-03 -9.503621e-02 -1.451175e-03 -5.540079e-03 9.999835e-01 3.848312e+00 +9.999613e-01 -8.800744e-03 4.930361e-05 -5.337242e-02 8.800421e-03 9.999503e-01 4.659577e-03 -1.222173e-01 -9.030788e-05 -4.658963e-03 9.999891e-01 4.806551e+00 +9.999329e-01 -1.154122e-02 -9.928825e-04 -6.458549e-02 1.154281e-02 9.999320e-01 1.608232e-03 -1.448705e-01 9.742552e-04 -1.619585e-03 9.999981e-01 5.738958e+00 +9.999251e-01 -1.210851e-02 -1.791951e-03 -7.542792e-02 1.210590e-02 9.999256e-01 -1.463266e-03 -1.535673e-01 1.809537e-03 1.441462e-03 9.999973e-01 6.676395e+00 +9.999307e-01 -1.148261e-02 -2.596193e-03 -8.936429e-02 1.147713e-02 9.999318e-01 -2.115606e-03 -1.678814e-01 2.620310e-03 2.085662e-03 9.999943e-01 7.606157e+00 +9.999351e-01 -1.082459e-02 -3.547008e-03 -1.013034e-01 1.082533e-02 9.999413e-01 1.915052e-04 -1.791661e-01 3.544728e-03 -2.298913e-04 9.999936e-01 8.535486e+00 +9.999332e-01 -1.074628e-02 -4.252912e-03 -1.141317e-01 1.075959e-02 9.999372e-01 3.119014e-03 -1.865848e-01 4.219129e-03 -3.164566e-03 9.999860e-01 9.465868e+00 +9.999267e-01 -1.090491e-02 -5.254531e-03 -1.275574e-01 1.092822e-02 9.999304e-01 4.428359e-03 -1.916301e-01 5.205877e-03 -4.485457e-03 9.999763e-01 1.038892e+01 +9.999051e-01 -1.246298e-02 -5.868031e-03 -1.421945e-01 1.249287e-02 9.999090e-01 5.084305e-03 -1.997185e-01 5.804133e-03 -5.157132e-03 9.999698e-01 1.133952e+01 +9.998969e-01 -1.263069e-02 -6.826217e-03 -1.548813e-01 1.266478e-02 9.999074e-01 4.973288e-03 -2.155601e-01 6.762771e-03 -5.059228e-03 9.999643e-01 1.222345e+01 +9.998890e-01 -1.287236e-02 -7.500847e-03 -1.693123e-01 1.289812e-02 9.999110e-01 3.394724e-03 -2.354858e-01 7.456483e-03 -3.491094e-03 9.999660e-01 1.313325e+01 +9.998699e-01 -1.336574e-02 -9.034486e-03 -1.849063e-01 1.337692e-02 9.999098e-01 1.177817e-03 -2.602522e-01 9.017931e-03 -1.298518e-03 9.999584e-01 1.404136e+01 +9.998368e-01 -1.468699e-02 -1.051998e-02 -1.992846e-01 1.468671e-02 9.998921e-01 -1.034110e-04 -2.760574e-01 1.052037e-02 -5.111081e-05 9.999446e-01 1.494552e+01 +9.998231e-01 -1.432671e-02 -1.218625e-02 -2.169483e-01 1.431971e-02 9.998972e-01 -6.616172e-04 -2.851106e-01 1.219448e-02 4.869955e-04 9.999255e-01 1.584627e+01 +9.998220e-01 -1.304143e-02 -1.363681e-02 -2.367130e-01 1.302122e-02 9.999139e-01 -1.569338e-03 -2.933610e-01 1.365611e-02 1.391489e-03 9.999057e-01 1.674309e+01 +9.998148e-01 -1.159649e-02 -1.536125e-02 -2.548521e-01 1.157275e-02 9.999316e-01 -1.633665e-03 -2.982439e-01 1.537915e-02 1.455589e-03 9.998806e-01 1.763484e+01 +9.997832e-01 -1.213664e-02 -1.691845e-02 -2.730779e-01 1.212689e-02 9.999262e-01 -6.787551e-04 -3.044055e-01 1.692545e-02 4.734386e-04 9.998566e-01 1.852684e+01 +9.997674e-01 -1.148423e-02 -1.825599e-02 -2.937433e-01 1.149904e-02 9.999336e-01 7.061475e-04 -3.138402e-01 1.824668e-02 -9.159104e-04 9.998330e-01 1.941419e+01 +9.997407e-01 -1.132286e-02 -1.975877e-02 -3.146034e-01 1.134559e-02 9.999350e-01 1.038627e-03 -3.236882e-01 1.974573e-02 -1.262534e-03 9.998042e-01 2.029478e+01 +9.996913e-01 -1.246784e-02 -2.149326e-02 -3.335669e-01 1.249154e-02 9.999214e-01 9.685078e-04 -3.220398e-01 2.147950e-02 -1.236693e-03 9.997685e-01 2.116890e+01 +9.996529e-01 -1.268780e-02 -2.308809e-02 -3.517749e-01 1.269885e-02 9.999192e-01 3.318073e-04 -3.205089e-01 2.308202e-02 -6.248852e-04 9.997333e-01 2.203793e+01 +9.996297e-01 -1.261378e-02 -2.411198e-02 -3.725490e-01 1.263650e-02 9.999198e-01 7.899130e-04 -3.172185e-01 2.410009e-02 -1.094312e-03 9.997089e-01 2.290089e+01 +9.996068e-01 -1.236724e-02 -2.516463e-02 -3.933684e-01 1.244026e-02 9.999188e-01 2.747129e-03 -3.159266e-01 2.512862e-02 -3.059103e-03 9.996795e-01 2.375773e+01 +9.995692e-01 -1.363816e-02 -2.598840e-02 -4.121035e-01 1.378817e-02 9.998892e-01 5.601313e-03 -3.140241e-01 2.590913e-02 -5.957232e-03 9.996465e-01 2.461543e+01 +9.995560e-01 -1.327670e-02 -2.667519e-02 -4.280328e-01 1.346665e-02 9.998851e-01 6.953738e-03 -3.057383e-01 2.657980e-02 -7.309876e-03 9.996199e-01 2.544218e+01 +9.995413e-01 -1.282492e-02 -2.743674e-02 -4.474023e-01 1.298763e-02 9.998990e-01 5.760451e-03 -2.988492e-01 2.736009e-02 -6.114147e-03 9.996069e-01 2.626621e+01 +9.995372e-01 -1.142993e-02 -2.819322e-02 -4.690774e-01 1.151922e-02 9.999291e-01 3.006464e-03 -2.930490e-01 2.815686e-02 -3.329837e-03 9.995979e-01 2.708037e+01 +9.995206e-01 -1.092301e-02 -2.896974e-02 -4.916230e-01 1.096822e-02 9.999388e-01 1.401950e-03 -2.934051e-01 2.895266e-02 -1.719025e-03 9.995792e-01 2.787697e+01 +9.995005e-01 -1.020425e-02 -2.990979e-02 -5.147234e-01 1.023690e-02 9.999471e-01 9.386493e-04 -2.982767e-01 2.989864e-02 -1.244365e-03 9.995521e-01 2.866957e+01 +9.994551e-01 -1.042435e-02 -3.131936e-02 -5.377287e-01 1.044602e-02 9.999452e-01 5.283531e-04 -3.030386e-01 3.131214e-02 -8.552288e-04 9.995092e-01 2.945471e+01 +9.993980e-01 -1.012000e-02 -3.318482e-02 -5.610502e-01 1.012245e-02 9.999487e-01 -9.415537e-05 -3.024561e-01 3.318408e-02 -2.418140e-04 9.994492e-01 3.022665e+01 +9.993348e-01 -1.013992e-02 -3.503166e-02 -5.837097e-01 1.012933e-02 9.999485e-01 -4.799930e-04 -2.893166e-01 3.503473e-02 1.248256e-04 9.993860e-01 3.099325e+01 +9.992572e-01 -1.045439e-02 -3.709050e-02 -6.098827e-01 1.048559e-02 9.999447e-01 6.466132e-04 -2.849460e-01 3.708169e-02 -1.035049e-03 9.993116e-01 3.175331e+01 +9.991826e-01 -1.044167e-02 -3.905299e-02 -6.373473e-01 1.057814e-02 9.999386e-01 3.289435e-03 -2.859582e-01 3.901625e-02 -3.699855e-03 9.992317e-01 3.249745e+01 +9.991166e-01 -9.676451e-03 -4.089457e-02 -6.694970e-01 9.870613e-03 9.999409e-01 4.548579e-03 -2.913155e-01 4.084814e-02 -4.948216e-03 9.991530e-01 3.323490e+01 +9.990483e-01 -8.212274e-03 -4.283877e-02 -7.070281e-01 8.425612e-03 9.999529e-01 4.801790e-03 -2.980989e-01 4.279733e-02 -5.158163e-03 9.990704e-01 3.396228e+01 +9.989871e-01 -5.570437e-03 -4.465125e-02 -7.475972e-01 5.752148e-03 9.999756e-01 3.942093e-03 -3.011809e-01 4.462821e-02 -4.194941e-03 9.989948e-01 3.470353e+01 +9.989142e-01 -4.076822e-03 -4.640854e-02 -7.861231e-01 4.225973e-03 9.999861e-01 3.116198e-03 -3.012987e-01 4.639521e-02 -3.308936e-03 9.989176e-01 3.539317e+01 +9.988447e-01 -3.602322e-03 -4.792024e-02 -8.225011e-01 3.824192e-03 9.999823e-01 4.539097e-03 -2.935002e-01 4.790305e-02 -4.717109e-03 9.988408e-01 3.608573e+01 +9.987977e-01 -2.421920e-03 -4.896157e-02 -8.579745e-01 2.724895e-03 9.999775e-01 6.122217e-03 -2.845601e-01 4.894565e-02 -6.248272e-03 9.987818e-01 3.677338e+01 +9.988038e-01 6.059604e-04 -4.889413e-02 -8.979841e-01 -2.707568e-04 9.999763e-01 6.862041e-03 -2.829222e-01 4.889714e-02 -6.840594e-03 9.987803e-01 3.744921e+01 +9.988488e-01 3.748494e-03 -4.782370e-02 -9.356939e-01 -3.523552e-03 9.999823e-01 4.787030e-03 -2.753503e-01 4.784081e-02 -4.613010e-03 9.988443e-01 3.811124e+01 +9.989248e-01 5.352123e-03 -4.605101e-02 -9.662440e-01 -5.291339e-03 9.999849e-01 1.441747e-03 -2.643952e-01 4.605804e-02 -1.196526e-03 9.989380e-01 3.876355e+01 +9.990194e-01 5.712810e-03 -4.390410e-02 -9.940685e-01 -5.743068e-03 9.999833e-01 -5.630376e-04 -2.590333e-01 4.390016e-02 8.146287e-04 9.990355e-01 3.940063e+01 +9.991414e-01 6.928143e-03 -4.084787e-02 -1.022967e+00 -6.919997e-03 9.999759e-01 3.408663e-04 -2.546909e-01 4.084925e-02 -5.790746e-05 9.991653e-01 4.003748e+01 +9.992324e-01 1.197639e-02 -3.729938e-02 -1.054571e+00 -1.185276e-02 9.999234e-01 3.533972e-03 -2.561416e-01 3.733886e-02 -3.089159e-03 9.992978e-01 4.068683e+01 +9.993048e-01 1.641604e-02 -3.347332e-02 -1.082779e+00 -1.618094e-02 9.998425e-01 7.282552e-03 -2.559993e-01 3.358760e-02 -6.735859e-03 9.994130e-01 4.129211e+01 +9.993476e-01 2.131604e-02 -2.915361e-02 -1.107347e+00 -2.108763e-02 9.997446e-01 8.120116e-03 -2.542439e-01 2.931926e-02 -7.500038e-03 9.995419e-01 4.189089e+01 +9.994044e-01 2.501999e-02 -2.376615e-02 -1.127463e+00 -2.483055e-02 9.996577e-01 8.233076e-03 -2.504927e-01 2.396401e-02 -7.638046e-03 9.996836e-01 4.247569e+01 +9.994265e-01 2.870924e-02 -1.795791e-02 -1.143225e+00 -2.852866e-02 9.995405e-01 1.023293e-02 -2.472759e-01 1.824345e-02 -9.714743e-03 9.997863e-01 4.304425e+01 +9.993683e-01 3.372431e-02 -1.120755e-02 -1.156523e+00 -3.359318e-02 9.993671e-01 1.169024e-02 -2.461265e-01 1.159470e-02 -1.130636e-02 9.998688e-01 4.359239e+01 +9.993066e-01 3.700958e-02 -4.072654e-03 -1.163695e+00 -3.696271e-02 9.992556e-01 1.103952e-02 -2.463307e-01 4.478192e-03 -1.088133e-02 9.999307e-01 4.411947e+01 +9.991739e-01 4.050788e-02 3.260896e-03 -1.165311e+00 -4.054268e-02 9.991124e-01 1.142537e-02 -2.460311e-01 -2.795184e-03 -1.154814e-02 9.999293e-01 4.462705e+01 +9.989309e-01 4.494697e-02 1.081107e-02 -1.165281e+00 -4.506496e-02 9.989242e-01 1.092935e-02 -2.401569e-01 -1.030820e-02 -1.140486e-02 9.998818e-01 4.511047e+01 +9.986110e-01 4.932216e-02 1.853237e-02 -1.162119e+00 -4.947620e-02 9.987436e-01 7.946644e-03 -2.348502e-01 -1.811714e-02 -8.852517e-03 9.997966e-01 4.557447e+01 +9.983445e-01 5.105621e-02 2.648756e-02 -1.153911e+00 -5.119570e-02 9.986779e-01 4.614266e-03 -2.368661e-01 -2.621696e-02 -5.962677e-03 9.996384e-01 4.601395e+01 +9.980778e-01 5.151562e-02 3.445099e-02 -1.139704e+00 -5.171685e-02 9.986493e-01 4.974724e-03 -2.380301e-01 -3.414819e-02 -6.746859e-03 9.993939e-01 4.643562e+01 +9.978050e-01 5.099690e-02 4.224351e-02 -1.119110e+00 -5.130814e-02 9.986628e-01 6.315813e-03 -2.395256e-01 -4.186495e-02 -8.469386e-03 9.990873e-01 4.683267e+01 +9.973383e-01 5.274012e-02 5.034723e-02 -1.098158e+00 -5.316651e-02 9.985599e-01 7.166379e-03 -2.391747e-01 -4.989678e-02 -9.824091e-03 9.987060e-01 4.720456e+01 +9.966453e-01 5.618538e-02 5.950962e-02 -1.077742e+00 -5.670529e-02 9.983658e-01 7.082538e-03 -2.387525e-01 -5.901444e-02 -1.043329e-02 9.982025e-01 4.756732e+01 +9.958318e-01 6.082299e-02 6.796721e-02 -1.059487e+00 -6.141123e-02 9.980907e-01 6.596949e-03 -2.404154e-01 -6.743621e-02 -1.074340e-02 9.976657e-01 4.787840e+01 +9.949463e-01 6.439773e-02 7.703781e-02 -1.036133e+00 -6.510727e-02 9.978555e-01 6.731622e-03 -2.443984e-01 -7.643911e-02 -1.171332e-02 9.970054e-01 4.817664e+01 +9.942173e-01 6.384319e-02 8.634873e-02 -1.006263e+00 -6.469375e-02 9.978799e-01 7.085063e-03 -2.532706e-01 -8.571335e-02 -1.263031e-02 9.962397e-01 4.845088e+01 +9.932966e-01 6.279192e-02 9.705214e-02 -9.730963e-01 -6.358338e-02 9.979635e-01 5.080641e-03 -2.607772e-01 -9.653549e-02 -1.121749e-02 9.952663e-01 4.871656e+01 +9.921379e-01 6.152264e-02 1.089836e-01 -9.369557e-01 -6.192852e-02 9.980805e-01 3.401550e-04 -2.675893e-01 -1.087535e-01 -7.086672e-03 9.940434e-01 4.897559e+01 +9.905372e-01 6.248717e-02 1.221940e-01 -8.977462e-01 -6.247046e-02 9.980388e-01 -3.971708e-03 -2.734425e-01 -1.222026e-01 -3.699392e-03 9.924982e-01 4.923239e+01 +9.883707e-01 6.431657e-02 1.377925e-01 -8.567415e-01 -6.411000e-02 9.979251e-01 -5.941497e-03 -2.805680e-01 -1.378888e-01 -2.961478e-03 9.904432e-01 4.948708e+01 +9.857258e-01 6.628680e-02 1.547602e-01 -8.084309e-01 -6.596478e-02 9.977957e-01 -7.220978e-03 -2.860922e-01 -1.548977e-01 -3.090816e-03 9.879256e-01 4.974970e+01 +9.830186e-01 6.669167e-02 1.709583e-01 -7.577117e-01 -6.621707e-02 9.977691e-01 -8.483377e-03 -2.915714e-01 -1.711427e-01 -2.981041e-03 9.852417e-01 4.998615e+01 +9.797322e-01 6.595410e-02 1.891427e-01 -6.971579e-01 -6.530127e-02 9.978185e-01 -9.688392e-03 -2.967619e-01 -1.893691e-01 -2.859233e-03 9.819017e-01 5.023058e+01 +9.757277e-01 6.503198e-02 2.091083e-01 -6.296551e-01 -6.433369e-02 9.978768e-01 -1.014671e-02 -3.022908e-01 -2.093242e-01 -3.552285e-03 9.778398e-01 5.047733e+01 +9.713025e-01 6.551318e-02 2.286472e-01 -5.626253e-01 -6.460929e-02 9.978449e-01 -1.144496e-02 -3.067843e-01 -2.289043e-01 -3.656217e-03 9.734420e-01 5.070727e+01 +9.659140e-01 6.760924e-02 2.498781e-01 -4.889211e-01 -6.623732e-02 9.977069e-01 -1.390550e-02 -3.117062e-01 -2.502453e-01 -3.119744e-03 9.681774e-01 5.094530e+01 +9.596674e-01 6.892286e-02 2.725584e-01 -4.074937e-01 -6.707060e-02 9.976179e-01 -1.611853e-02 -3.179085e-01 -2.730201e-01 -2.812227e-03 9.620042e-01 5.118149e+01 +9.522731e-01 7.018360e-02 2.970693e-01 -3.172192e-01 -6.815286e-02 9.975265e-01 -1.720102e-02 -3.255041e-01 -2.975418e-01 -3.866058e-03 9.547009e-01 5.142020e+01 +9.436113e-01 7.308946e-02 3.228865e-01 -2.212449e-01 -7.102643e-02 9.973086e-01 -1.818419e-02 -3.340796e-01 -3.233466e-01 -5.774668e-03 9.462629e-01 5.165930e+01 +9.334129e-01 7.549648e-02 3.507715e-01 -1.147140e-01 -7.333123e-02 9.971174e-01 -1.947297e-02 -3.439537e-01 -3.512306e-01 -7.546181e-03 9.362585e-01 5.190075e+01 +9.222742e-01 7.613570e-02 3.789639e-01 2.735872e-04 -7.373827e-02 9.970594e-01 -2.085934e-02 -3.544958e-01 -3.794378e-01 -8.706115e-03 9.251762e-01 5.212982e+01 +9.095902e-01 7.427774e-02 4.088135e-01 1.309526e-01 -7.108895e-02 9.972044e-01 -2.301366e-02 -3.642721e-01 -4.093801e-01 -8.129124e-03 9.123277e-01 5.235595e+01 +8.944222e-01 7.169632e-02 4.414392e-01 2.760316e-01 -6.712497e-02 9.974060e-01 -2.598839e-02 -3.733939e-01 -4.421575e-01 -6.387003e-03 8.969146e-01 5.258045e+01 +8.771443e-01 7.145361e-02 4.748814e-01 4.279778e-01 -6.473981e-02 9.974359e-01 -3.050080e-02 -3.824345e-01 -4.758432e-01 -3.990132e-03 8.795210e-01 5.280031e+01 +8.575413e-01 7.341493e-02 5.091494e-01 5.907911e-01 -6.409369e-02 9.972996e-01 -3.585139e-02 -3.919068e-01 -5.104066e-01 -1.889215e-03 8.599311e-01 5.301901e+01 +8.354269e-01 7.568777e-02 5.443649e-01 7.701079e-01 -6.394528e-02 9.971310e-01 -4.050415e-02 -4.025973e-01 -5.458689e-01 -9.713071e-04 8.378700e-01 5.324411e+01 +8.104782e-01 7.887974e-02 5.804335e-01 9.652370e-01 -6.518263e-02 9.968824e-01 -4.445771e-02 -4.147601e-01 -5.821309e-01 -1.802183e-03 8.130930e-01 5.347280e+01 +7.831650e-01 8.302927e-02 6.162457e-01 1.172293e+00 -6.828228e-02 9.965350e-01 -4.748968e-02 -4.302534e-01 -6.180536e-01 -4.886408e-03 7.861208e-01 5.369477e+01 +7.530585e-01 8.748648e-02 6.521111e-01 1.401712e+00 -7.188324e-02 9.961272e-01 -5.062849e-02 -4.467404e-01 -6.540151e-01 -8.749646e-03 7.564309e-01 5.392680e+01 +7.198925e-01 8.857767e-02 6.884102e-01 1.658262e+00 -7.134170e-02 9.960132e-01 -5.355265e-02 -4.647131e-01 -6.904094e-01 -1.056021e-02 7.233418e-01 5.415343e+01 +6.834437e-01 8.631703e-02 7.248820e-01 1.946080e+00 -6.813306e-02 9.961927e-01 -5.438583e-02 -4.776399e-01 -7.268168e-01 -1.221878e-02 6.867227e-01 5.436895e+01 +6.444403e-01 8.503336e-02 7.599118e-01 2.269729e+00 -6.511601e-02 9.962903e-01 -5.626252e-02 -4.777691e-01 -7.618770e-01 -1.322459e-02 6.475867e-01 5.458519e+01 +6.014973e-01 8.478487e-02 7.943629e-01 2.612681e+00 -6.309072e-02 9.962879e-01 -5.856425e-02 -4.832195e-01 -7.963797e-01 -1.489068e-02 6.046137e-01 5.478988e+01 +5.561716e-01 8.472528e-02 8.267374e-01 2.973763e+00 -5.939500e-02 9.962982e-01 -6.214531e-02 -4.792758e-01 -8.289424e-01 -1.454061e-02 5.591450e-01 5.498383e+01 +5.082200e-01 8.368613e-02 8.571517e-01 3.359263e+00 -5.674312e-02 9.963588e-01 -6.363336e-02 -4.860892e-01 -8.593560e-01 -1.629772e-02 5.111180e-01 5.516957e+01 +4.595568e-01 8.166095e-02 8.843862e-01 3.766145e+00 -5.479782e-02 9.964739e-01 -6.353594e-02 -4.913921e-01 -8.864563e-01 -1.926406e-02 4.624112e-01 5.533541e+01 +4.095444e-01 7.979453e-02 9.087938e-01 4.198361e+00 -5.480553e-02 9.965202e-01 -6.279926e-02 -5.166196e-01 -9.106425e-01 -2.408784e-02 4.124924e-01 5.548396e+01 +3.597340e-01 7.961125e-02 9.296523e-01 4.641416e+00 -5.780824e-02 9.963408e-01 -6.295296e-02 -5.396177e-01 -9.312624e-01 -3.109524e-02 3.630199e-01 5.561845e+01 +3.103427e-01 8.045242e-02 9.472142e-01 5.103719e+00 -5.497858e-02 9.962635e-01 -6.660545e-02 -5.645924e-01 -9.490336e-01 -3.140597e-02 3.136062e-01 5.572143e+01 +2.636126e-01 7.622494e-02 9.616122e-01 5.585536e+00 -4.431946e-02 9.967773e-01 -6.686285e-02 -5.957735e-01 -9.636100e-01 -2.499224e-02 2.661413e-01 5.580227e+01 +2.200748e-01 7.093645e-02 9.729003e-01 6.088519e+00 -3.059900e-02 9.973636e-01 -6.579850e-02 -6.266796e-01 -9.750030e-01 -1.528919e-02 2.216651e-01 5.585617e+01 +1.770423e-01 6.939967e-02 9.817533e-01 6.612372e+00 -2.180620e-02 9.975425e-01 -6.658344e-02 -6.532414e-01 -9.839617e-01 -9.620226e-03 1.781206e-01 5.590280e+01 +1.394343e-01 7.225282e-02 9.875917e-01 7.126377e+00 -1.775361e-02 9.973565e-01 -7.046066e-02 -6.821309e-01 -9.900722e-01 -7.708693e-03 1.403484e-01 5.593790e+01 +1.074817e-01 7.204208e-02 9.915934e-01 7.658631e+00 -8.852841e-03 9.974009e-01 -7.150444e-02 -7.242890e-01 -9.941677e-01 -1.093003e-03 1.078401e-01 5.595413e+01 +7.852152e-02 7.027376e-02 9.944324e-01 8.209580e+00 -2.181921e-03 9.975220e-01 -7.031982e-02 -7.737852e-01 -9.969101e-01 3.351844e-03 7.848028e-02 5.597135e+01 +5.379933e-02 6.807411e-02 9.962286e-01 8.774944e+00 4.677949e-03 9.976453e-01 -6.842356e-02 -8.137508e-01 -9.985408e-01 8.341445e-03 5.335421e-02 5.597751e+01 +3.425250e-02 6.829690e-02 9.970768e-01 9.351661e+00 1.011661e-02 9.975874e-01 -6.867942e-02 -8.573790e-01 -9.993620e-01 1.243947e-02 3.347893e-02 5.598323e+01 +1.874635e-02 7.007914e-02 9.973652e-01 9.933246e+00 1.331628e-02 9.974345e-01 -7.033431e-02 -9.020616e-01 -9.997356e-01 1.459970e-02 1.776507e-02 5.598182e+01 +5.284248e-03 6.962217e-02 9.975594e-01 1.053767e+01 1.391943e-02 9.974715e-01 -6.968979e-02 -9.473740e-01 -9.998892e-01 1.425371e-02 4.301785e-03 5.597984e+01 +-6.190262e-03 7.029766e-02 9.975068e-01 1.113754e+01 1.431476e-02 9.974299e-01 -7.020342e-02 -9.965387e-01 -9.998784e-01 1.384449e-02 -7.180648e-03 5.597900e+01 +-1.479860e-02 7.371512e-02 9.971695e-01 1.175501e+01 1.910705e-02 9.971174e-01 -7.342773e-02 -1.055254e+00 -9.997080e-01 1.796633e-02 -1.616442e-02 5.596304e+01 +-2.122260e-02 7.564821e-02 9.969086e-01 1.238276e+01 2.370387e-02 9.968910e-01 -7.514227e-02 -1.117194e+00 -9.994938e-01 2.203587e-02 -2.294978e-02 5.592954e+01 +-2.590903e-02 7.474963e-02 9.968656e-01 1.302027e+01 2.392123e-02 9.969612e-01 -7.413508e-02 -1.167977e+00 -9.993781e-01 2.192548e-02 -2.761840e-02 5.590304e+01 +-2.969905e-02 7.235375e-02 9.969367e-01 1.367308e+01 2.153551e-02 9.971914e-01 -7.173070e-02 -1.217524e+00 -9.993269e-01 1.933920e-02 -3.117381e-02 5.588330e+01 +-3.224636e-02 6.482052e-02 9.973757e-01 1.433357e+01 1.930001e-02 9.977490e-01 -6.422080e-02 -1.269538e+00 -9.992936e-01 1.717847e-02 -3.342481e-02 5.585852e+01 +-3.357981e-02 5.896572e-02 9.976950e-01 1.501321e+01 2.069200e-02 9.980850e-01 -5.829234e-02 -1.317429e+00 -9.992219e-01 1.868685e-02 -3.473562e-02 5.582149e+01 +-3.403686e-02 5.685168e-02 9.978022e-01 1.569798e+01 2.332191e-02 9.981540e-01 -5.607618e-02 -1.366117e+00 -9.991485e-01 2.136199e-02 -3.529992e-02 5.577901e+01 +-3.372396e-02 5.922088e-02 9.976750e-01 1.638718e+01 2.647752e-02 9.979454e-01 -5.834194e-02 -1.417061e+00 -9.990804e-01 2.444843e-02 -3.522269e-02 5.574074e+01 +-3.305902e-02 6.730529e-02 9.971845e-01 1.708252e+01 2.770655e-02 9.974081e-01 -6.640186e-02 -1.462354e+00 -9.990693e-01 2.543336e-02 -3.483813e-02 5.570318e+01 +-3.087265e-02 7.512682e-02 9.966959e-01 1.778472e+01 2.832330e-02 9.968365e-01 -7.426013e-02 -1.502437e+00 -9.991220e-01 2.593711e-02 -3.290283e-02 5.567210e+01 +-2.869260e-02 7.658907e-02 9.966497e-01 1.850468e+01 2.970433e-02 9.966852e-01 -7.573665e-02 -1.545746e+00 -9.991469e-01 2.743173e-02 -3.087252e-02 5.564300e+01 +-2.666061e-02 7.158414e-02 9.970781e-01 1.924155e+01 2.859289e-02 9.970792e-01 -7.081969e-02 -1.593908e+00 -9.992356e-01 2.662124e-02 -2.862953e-02 5.561503e+01 +-2.419601e-02 6.403547e-02 9.976542e-01 1.997824e+01 2.815724e-02 9.975941e-01 -6.334873e-02 -1.647724e+00 -9.993107e-01 2.655840e-02 -2.594085e-02 5.559027e+01 +-2.154982e-02 6.329704e-02 9.977620e-01 2.071281e+01 2.585577e-02 9.976952e-01 -6.273439e-02 -1.696725e+00 -9.994334e-01 2.444598e-02 -2.313674e-02 5.556904e+01 +-1.813135e-02 6.898441e-02 9.974529e-01 2.143850e+01 3.389740e-02 9.970858e-01 -6.834286e-02 -1.741686e+00 -9.992609e-01 3.257190e-02 -2.041691e-02 5.553688e+01 +-1.465585e-02 7.434465e-02 9.971248e-01 2.216714e+01 3.594039e-02 9.966267e-01 -7.377927e-02 -1.787932e+00 -9.992465e-01 3.475575e-02 -1.727839e-02 5.551011e+01 +-1.252203e-02 7.473476e-02 9.971247e-01 2.290332e+01 2.917558e-02 9.968057e-01 -7.434447e-02 -1.839076e+00 -9.994959e-01 2.816074e-02 -1.466246e-02 5.550537e+01 +-9.302733e-03 7.218496e-02 9.973478e-01 2.363216e+01 2.558215e-02 9.970817e-01 -7.192709e-02 -1.895775e+00 -9.996295e-01 2.484517e-02 -1.112223e-02 5.550164e+01 +-4.586658e-03 6.657880e-02 9.977705e-01 2.437331e+01 2.924907e-02 9.973631e-01 -6.641717e-02 -1.955801e+00 -9.995617e-01 2.887922e-02 -6.521932e-03 5.548454e+01 +-1.251911e-03 6.911428e-02 9.976079e-01 2.511164e+01 3.420447e-02 9.970279e-01 -6.903119e-02 -2.008471e+00 -9.994141e-01 3.403622e-02 -3.612208e-03 5.546362e+01 +1.859530e-03 7.309744e-02 9.973230e-01 2.583505e+01 3.365647e-02 9.967551e-01 -7.311859e-02 -2.059391e+00 -9.994318e-01 3.370233e-02 -6.067061e-04 5.546181e+01 +5.331076e-03 7.446070e-02 9.972096e-01 2.656806e+01 3.017783e-02 9.967576e-01 -7.458830e-02 -2.113697e+00 -9.995304e-01 3.049125e-02 3.066728e-03 5.547262e+01 +9.153452e-03 7.318056e-02 9.972766e-01 2.730492e+01 2.911682e-02 9.968760e-01 -7.341842e-02 -2.167614e+00 -9.995341e-01 2.970955e-02 6.994071e-03 5.548963e+01 +1.307642e-02 7.048501e-02 9.974270e-01 2.804413e+01 3.351330e-02 9.969210e-01 -7.088863e-02 -2.226546e+00 -9.993528e-01 3.435404e-02 1.067398e-02 5.549768e+01 +1.709323e-02 7.022556e-02 9.973846e-01 2.877765e+01 3.809348e-02 9.967604e-01 -7.083447e-02 -2.288673e+00 -9.991280e-01 3.920463e-02 1.436272e-02 5.551027e+01 +2.071775e-02 7.126874e-02 9.972419e-01 2.951232e+01 4.090596e-02 9.965603e-01 -7.206987e-02 -2.343893e+00 -9.989482e-01 4.228625e-02 1.773117e-02 5.552232e+01 +2.346026e-02 7.155827e-02 9.971604e-01 3.024630e+01 4.104867e-02 9.965248e-01 -7.247843e-02 -2.395401e+00 -9.988817e-01 4.263246e-02 2.044136e-02 5.553620e+01 +2.700453e-02 7.039721e-02 9.971534e-01 3.098559e+01 4.270772e-02 9.965251e-01 -7.150946e-02 -2.445222e+00 -9.987226e-01 4.451722e-02 2.390419e-02 5.554859e+01 +3.070906e-02 6.867484e-02 9.971663e-01 3.172630e+01 4.416618e-02 9.965691e-01 -6.999389e-02 -2.496112e+00 -9.985521e-01 4.619046e-02 2.757060e-02 5.556188e+01 +3.356629e-02 6.985875e-02 9.969919e-01 3.246495e+01 4.308927e-02 9.965254e-01 -7.127678e-02 -2.537443e+00 -9.985072e-01 4.535214e-02 3.043949e-02 5.558466e+01 +3.662308e-02 7.125285e-02 9.967856e-01 3.320740e+01 4.027483e-02 9.965392e-01 -7.271499e-02 -2.578228e+00 -9.985173e-01 4.280842e-02 3.362664e-02 5.561348e+01 +3.950202e-02 7.135192e-02 9.966686e-01 3.395101e+01 4.213026e-02 9.964412e-01 -7.300545e-02 -2.620601e+00 -9.983310e-01 4.487376e-02 3.635537e-02 5.563975e+01 +4.226827e-02 7.092015e-02 9.965860e-01 3.469841e+01 3.944885e-02 9.965811e-01 -7.259297e-02 -2.667716e+00 -9.983272e-01 4.238254e-02 3.932604e-02 5.567316e+01 +4.429263e-02 7.181466e-02 9.964340e-01 3.544252e+01 3.837120e-02 9.965546e-01 -7.352900e-02 -2.711893e+00 -9.982815e-01 4.149115e-02 4.138441e-02 5.570930e+01 +4.741274e-02 7.133303e-02 9.963250e-01 3.619785e+01 3.453945e-02 9.967332e-01 -7.300592e-02 -2.761384e+00 -9.982781e-01 3.787392e-02 4.479405e-02 5.574855e+01 +5.077075e-02 7.342347e-02 9.960076e-01 3.695093e+01 3.333449e-02 9.966135e-01 -7.516735e-02 -2.812393e+00 -9.981539e-01 3.701770e-02 4.815128e-02 5.578704e+01 +5.397584e-02 7.769258e-02 9.955151e-01 3.770474e+01 3.235073e-02 9.963090e-01 -7.950858e-02 -2.867554e+00 -9.980181e-01 3.649717e-02 5.126320e-02 5.582660e+01 +5.735005e-02 7.908020e-02 9.952171e-01 3.846575e+01 3.198206e-02 9.962007e-01 -8.100135e-02 -2.922992e+00 -9.978418e-01 3.647452e-02 5.460300e-02 5.586855e+01 +6.039293e-02 8.181733e-02 9.948158e-01 3.923007e+01 2.627180e-02 9.961594e-01 -8.352275e-02 -2.973413e+00 -9.978289e-01 3.117978e-02 5.801150e-02 5.592107e+01 +6.297842e-02 8.056066e-02 9.947580e-01 4.000220e+01 2.229850e-02 9.963743e-01 -8.210329e-02 -3.024315e+00 -9.977658e-01 2.735234e-02 6.095370e-02 5.597631e+01 +6.664603e-02 8.105877e-02 9.944786e-01 4.077830e+01 2.445742e-02 9.962624e-01 -8.284322e-02 -3.080932e+00 -9.974769e-01 2.984355e-02 6.441445e-02 5.602494e+01 +7.069430e-02 8.200656e-02 9.941213e-01 4.155550e+01 2.387540e-02 9.961901e-01 -8.387508e-02 -3.135919e+00 -9.972123e-01 2.966452e-02 6.846702e-02 5.607788e+01 +7.416550e-02 8.302010e-02 9.937842e-01 4.233951e+01 1.936530e-02 9.962209e-01 -8.466889e-02 -3.188774e+00 -9.970579e-01 2.552443e-02 7.227750e-02 5.614130e+01 +7.831116e-02 8.192870e-02 9.935567e-01 4.313031e+01 1.900906e-02 9.963134e-01 -8.365431e-02 -3.244326e+00 -9.967478e-01 2.543764e-02 7.646507e-02 5.620333e+01 +8.332298e-02 8.026167e-02 9.932850e-01 4.393795e+01 1.886995e-02 9.964454e-01 -8.209998e-02 -3.297181e+00 -9.963440e-01 2.558405e-02 8.151226e-02 5.626972e+01 +8.814603e-02 8.493966e-02 9.924794e-01 4.471372e+01 1.544655e-02 9.961213e-01 -8.662324e-02 -3.352539e+00 -9.959878e-01 2.296587e-02 8.649212e-02 5.634391e+01 +9.421985e-02 9.422725e-02 9.910821e-01 4.550440e+01 1.386091e-02 9.952900e-01 -9.594507e-02 -3.402580e+00 -9.954550e-01 2.277722e-02 9.247000e-02 5.642297e+01 +1.017001e-01 9.855422e-02 9.899212e-01 4.630756e+01 1.204009e-02 9.948858e-01 -1.002854e-01 -3.461241e+00 -9.947423e-01 2.211777e-02 9.999338e-02 5.650810e+01 +1.088845e-01 1.009468e-01 9.889154e-01 4.712224e+01 8.008224e-03 9.947089e-01 -1.024200e-01 -3.525277e+00 -9.940222e-01 1.907140e-02 1.075000e-01 5.660533e+01 +1.158008e-01 9.873063e-02 9.883533e-01 4.791411e+01 4.086353e-03 9.949918e-01 -9.987257e-02 -3.592468e+00 -9.932641e-01 1.560408e-02 1.148174e-01 5.670663e+01 +1.234522e-01 9.684397e-02 9.876136e-01 4.872687e+01 3.804221e-03 9.951731e-01 -9.806079e-02 -3.662244e+00 -9.923433e-01 1.586291e-02 1.224879e-01 5.681192e+01 +1.306562e-01 9.388208e-02 9.869726e-01 4.954068e+01 3.680756e-03 9.954536e-01 -9.517607e-02 -3.727642e+00 -9.914209e-01 1.606814e-02 1.297166e-01 5.692162e+01 +1.381181e-01 8.777174e-02 9.865188e-01 5.035682e+01 1.418947e-03 9.960468e-01 -8.881813e-02 -3.792894e+00 -9.904148e-01 1.366721e-02 1.374476e-01 5.704097e+01 +1.452465e-01 8.101518e-02 9.860729e-01 5.116788e+01 -7.262737e-04 9.966503e-01 -8.177725e-02 -3.850124e+00 -9.893953e-01 1.116169e-02 1.448188e-01 5.716787e+01 +1.529056e-01 7.734363e-02 9.852095e-01 5.198907e+01 -1.273776e-03 9.969472e-01 -7.806743e-02 -3.912550e+00 -9.882400e-01 1.068200e-02 1.525373e-01 5.729726e+01 +1.599738e-01 8.035847e-02 9.838449e-01 5.277379e+01 -1.057041e-03 9.966942e-01 -8.123612e-02 -3.968025e+00 -9.871207e-01 1.195568e-02 1.595299e-01 5.742490e+01 +1.656985e-01 8.616732e-02 9.824047e-01 5.356153e+01 -9.232977e-04 9.961885e-01 -8.722059e-02 -4.023164e+00 -9.861761e-01 1.354526e-02 1.651465e-01 5.756033e+01 +1.708588e-01 9.069896e-02 9.811120e-01 5.434318e+01 -1.860034e-03 9.957820e-01 -9.173122e-02 -4.082523e+00 -9.852938e-01 1.384818e-02 1.703068e-01 5.769851e+01 +1.755626e-01 9.300269e-02 9.800654e-01 5.510439e+01 -3.992120e-03 9.955867e-01 -9.376047e-02 -4.143701e+00 -9.844602e-01 1.254829e-02 1.751591e-01 5.783752e+01 +1.809517e-01 9.250328e-02 9.791320e-01 5.587053e+01 -5.855985e-03 9.956505e-01 -9.298165e-02 -4.204409e+00 -9.834746e-01 1.109141e-02 1.807064e-01 5.797950e+01 +1.863508e-01 8.909315e-02 9.784353e-01 5.664546e+01 -2.180078e-03 9.959149e-01 -9.026959e-02 -4.262120e+00 -9.824809e-01 1.468874e-02 1.857838e-01 5.812033e+01 +1.908189e-01 8.315480e-02 9.780968e-01 5.738911e+01 -1.183557e-03 9.964242e-01 -8.448206e-02 -4.318314e+00 -9.816246e-01 1.496313e-02 1.902350e-01 5.826251e+01 +1.938017e-01 7.570595e-02 9.781152e-01 5.813668e+01 -3.606712e-03 9.970662e-01 -7.645814e-02 -4.369152e+00 -9.810341e-01 1.128994e-02 1.935062e-01 5.841357e+01 +1.969010e-01 7.301812e-02 9.777005e-01 5.887601e+01 -6.793476e-03 9.973004e-01 -7.311378e-02 -4.420802e+00 -9.803999e-01 7.754189e-03 1.968655e-01 5.856727e+01 +2.000843e-01 7.342233e-02 9.770237e-01 5.959961e+01 -8.462431e-03 9.972804e-01 -7.321160e-02 -4.467621e+00 -9.797422e-01 6.380489e-03 2.001614e-01 5.871611e+01 +2.021928e-01 7.573447e-02 9.764129e-01 6.031245e+01 -1.049868e-02 9.971157e-01 -7.516624e-02 -4.516372e+00 -9.792895e-01 4.947024e-03 2.024047e-01 5.886609e+01 +2.034632e-01 7.984969e-02 9.758210e-01 6.101319e+01 -1.476313e-02 9.968056e-01 -7.848865e-02 -4.564529e+00 -9.789713e-01 1.563375e-03 2.039921e-01 5.902108e+01 +2.054345e-01 8.430510e-02 9.750329e-01 6.170436e+01 -1.627995e-02 9.964393e-01 -8.272590e-02 -4.614787e+00 -9.785355e-01 1.121269e-03 2.060755e-01 5.917238e+01 +2.074464e-01 8.946661e-02 9.741466e-01 6.238199e+01 -1.684370e-02 9.959881e-01 -8.788567e-02 -4.657586e+00 -9.781014e-01 1.823331e-03 2.081211e-01 5.932091e+01 +2.090407e-01 9.129393e-02 9.736361e-01 6.305593e+01 -1.639693e-02 9.958199e-01 -8.985360e-02 -4.706379e+00 -9.777695e-01 2.818410e-03 2.096638e-01 5.946843e+01 +2.101708e-01 9.099554e-02 9.734207e-01 6.372231e+01 -1.864042e-02 9.958511e-01 -8.906770e-02 -4.758759e+00 -9.774870e-01 5.744598e-04 2.109950e-01 5.961689e+01 +2.108260e-01 8.823281e-02 9.735334e-01 6.438160e+01 -1.866586e-02 9.960998e-01 -8.623582e-02 -4.814707e+00 -9.773454e-01 8.912483e-06 2.116507e-01 5.976019e+01 +2.112869e-01 8.541374e-02 9.736849e-01 6.503281e+01 -1.865394e-02 9.963453e-01 -8.335373e-02 -4.867829e+00 -9.772461e-01 -5.515137e-04 2.121080e-01 5.990218e+01 +2.110651e-01 8.443186e-02 9.738186e-01 6.567175e+01 -1.792305e-02 9.964292e-01 -8.250762e-02 -4.913385e+00 -9.773077e-01 -3.931829e-05 2.118247e-01 6.003522e+01 +2.095206e-01 8.372355e-02 9.742132e-01 6.630099e+01 -1.785350e-02 9.964889e-01 -8.179825e-02 -4.965400e+00 -9.776413e-01 -2.547066e-04 2.102797e-01 6.016765e+01 +2.077765e-01 8.441024e-02 9.745274e-01 6.692208e+01 -1.912970e-02 9.964298e-01 -8.222878e-02 -5.018319e+00 -9.779893e-01 -1.557212e-03 2.086494e-01 6.029836e+01 +2.053680e-01 8.784886e-02 9.747340e-01 6.754573e+01 -2.015721e-02 9.961316e-01 -8.553041e-02 -5.076711e+00 -9.784773e-01 -2.082714e-03 2.063443e-01 6.043224e+01 +2.031289e-01 9.132170e-02 9.748840e-01 6.812018e+01 -1.842777e-02 9.958213e-01 -8.944337e-02 -5.130339e+00 -9.789786e-01 2.035992e-04 2.039630e-01 6.055436e+01 +2.013967e-01 9.173994e-02 9.752041e-01 6.872472e+01 -1.608471e-02 9.957798e-01 -9.035379e-02 -5.182058e+00 -9.793777e-01 2.511083e-03 2.020224e-01 6.067792e+01 +1.991932e-01 9.078018e-02 9.757463e-01 6.930307e+01 -1.683966e-02 9.958700e-01 -8.921471e-02 -5.231855e+00 -9.798156e-01 1.339723e-03 1.998992e-01 6.080309e+01 +1.965663e-01 8.799307e-02 9.765341e-01 6.988288e+01 -1.711964e-02 9.961210e-01 -8.631201e-02 -5.285896e+00 -9.803411e-01 2.481145e-04 1.973102e-01 6.091928e+01 +1.945332e-01 8.356130e-02 9.773301e-01 7.044995e+01 -1.685792e-02 9.965024e-01 -8.184504e-02 -5.342758e+00 -9.807511e-01 -5.541834e-04 1.952615e-01 6.103300e+01 +1.926949e-01 8.257239e-02 9.777782e-01 7.100066e+01 -1.386283e-02 9.965827e-01 -8.142841e-02 -5.393054e+00 -9.811608e-01 2.136068e-03 1.931811e-01 6.114039e+01 +1.909839e-01 8.458246e-02 9.779421e-01 7.154538e+01 -9.556653e-03 9.963935e-01 -8.431200e-02 -5.440828e+00 -9.815467e-01 6.756381e-03 1.911035e-01 6.124382e+01 +1.886273e-01 8.635003e-02 9.782450e-01 7.208654e+01 -5.731549e-03 9.962065e-01 -8.683035e-02 -5.485365e+00 -9.820321e-01 1.077171e-02 1.884067e-01 6.134673e+01 +1.869668e-01 8.883578e-02 9.783412e-01 7.262287e+01 -6.447483e-03 9.959922e-01 -8.920640e-02 -5.532216e+00 -9.823451e-01 1.037080e-02 1.867903e-01 6.145078e+01 +1.856976e-01 9.117689e-02 9.783675e-01 7.315814e+01 -6.598439e-03 9.957788e-01 -9.154711e-02 -5.583135e+00 -9.825848e-01 1.054438e-02 1.855154e-01 6.155451e+01 +1.845375e-01 8.926813e-02 9.787630e-01 7.370114e+01 -4.887309e-03 9.959375e-01 -8.991310e-02 -5.630170e+00 -9.828134e-01 1.180882e-02 1.842241e-01 6.165701e+01 +1.853966e-01 8.748296e-02 9.787618e-01 7.424267e+01 1.400607e-03 9.960047e-01 -8.928947e-02 -5.676448e+00 -9.826628e-01 1.792482e-02 1.845333e-01 6.174950e+01 +1.879927e-01 8.647239e-02 9.783563e-01 7.478759e+01 6.455634e-03 9.959864e-01 -8.927110e-02 -5.720800e+00 -9.821493e-01 2.309822e-02 1.866799e-01 6.184178e+01 +1.900022e-01 8.543021e-02 9.780597e-01 7.533524e+01 8.831326e-03 9.960179e-01 -8.871443e-02 -5.768173e+00 -9.817440e-01 2.549349e-02 1.884911e-01 6.194475e+01 +1.934204e-01 8.506894e-02 9.774209e-01 7.588674e+01 5.714224e-03 9.961193e-01 -8.782713e-02 -5.817062e+00 -9.810994e-01 2.257276e-02 1.921837e-01 6.205821e+01 +1.989535e-01 8.554309e-02 9.762683e-01 7.643447e+01 5.154324e-03 9.960779e-01 -8.832928e-02 -5.862448e+00 -9.799954e-01 2.260541e-02 1.977323e-01 6.217121e+01 +2.058044e-01 8.467054e-02 9.749232e-01 7.699260e+01 6.227646e-03 9.961163e-01 -8.782578e-02 -5.912287e+00 -9.785734e-01 2.414640e-02 2.044778e-01 6.229135e+01 +2.140796e-01 8.394021e-02 9.732029e-01 7.756843e+01 5.760599e-03 9.961751e-01 -8.718880e-02 -5.961148e+00 -9.767993e-01 2.427156e-02 2.127772e-01 6.242394e+01 +2.221289e-01 8.323105e-02 9.714583e-01 7.812868e+01 5.261109e-03 9.962330e-01 -8.655665e-02 -6.008758e+00 -9.750032e-01 2.433767e-02 2.208542e-01 6.255305e+01 +2.310045e-01 8.248163e-02 9.694501e-01 7.869259e+01 1.415855e-03 9.963705e-01 -8.510943e-02 -6.059871e+00 -9.729517e-01 2.103326e-02 2.300493e-01 6.269195e+01 +2.409914e-01 8.249252e-02 9.670150e-01 7.928502e+01 -1.509138e-04 9.963842e-01 -8.496031e-02 -6.107865e+00 -9.705273e-01 2.032877e-02 2.401325e-01 6.284580e+01 +2.504059e-01 8.572786e-02 9.643378e-01 7.985086e+01 -4.511346e-03 9.961643e-01 -8.738574e-02 -6.150779e+00 -9.681305e-01 1.753144e-02 2.498322e-01 6.300502e+01 +2.600305e-01 8.867053e-02 9.615204e-01 8.045340e+01 -8.288988e-03 9.959430e-01 -8.960332e-02 -6.192815e+00 -9.655649e-01 1.532956e-02 2.597105e-01 6.317985e+01 +2.707708e-01 9.062972e-02 9.583680e-01 8.104837e+01 -1.252273e-02 9.958056e-01 -9.063200e-02 -6.239009e+00 -9.625624e-01 1.253911e-02 2.707700e-01 6.335684e+01 +2.810514e-01 9.255691e-02 9.552189e-01 8.165468e+01 -1.440018e-02 9.956330e-01 -9.223596e-02 -6.285674e+00 -9.595847e-01 1.216772e-02 2.811569e-01 6.354111e+01 +2.908657e-01 9.326445e-02 9.522073e-01 8.226579e+01 -1.695222e-02 9.955836e-01 -9.233468e-02 -6.324963e+00 -9.566137e-01 1.071496e-02 2.911622e-01 6.374049e+01 +3.012086e-01 9.423417e-02 9.488905e-01 8.289509e+01 -1.847524e-02 9.954948e-01 -9.299781e-02 -6.371173e+00 -9.533793e-01 1.048075e-02 3.015926e-01 6.394808e+01 +3.114761e-01 9.499952e-02 9.454933e-01 8.353476e+01 -2.182553e-02 9.954428e-01 -9.282824e-02 -6.414738e+00 -9.500033e-01 8.277883e-03 3.121301e-01 6.416680e+01 +3.221019e-01 8.973348e-02 9.424426e-01 8.419403e+01 -2.158695e-02 9.959350e-01 -8.744886e-02 -6.458457e+00 -9.464589e-01 7.822978e-03 3.227297e-01 6.439981e+01 +3.329780e-01 8.181771e-02 9.393782e-01 8.486139e+01 -1.796666e-02 9.965980e-01 -8.043286e-02 -6.498607e+00 -9.427634e-01 9.904888e-03 3.333152e-01 6.463735e+01 +3.440230e-01 7.757898e-02 9.357508e-01 8.553876e+01 -1.656435e-02 9.969272e-01 -7.656109e-02 -6.545009e+00 -9.388151e-01 1.083867e-02 3.442509e-01 6.488814e+01 +3.540944e-01 7.458960e-02 9.322303e-01 8.622445e+01 -1.650619e-02 9.971574e-01 -7.351492e-02 -6.585584e+00 -9.350641e-01 1.064365e-02 3.543190e-01 6.515377e+01 +3.632093e-01 7.047665e-02 9.290382e-01 8.692746e+01 -1.006274e-02 9.973735e-01 -7.172652e-02 -6.605047e+00 -9.316533e-01 1.670306e-02 3.629645e-01 6.542840e+01 +3.724555e-01 6.671889e-02 9.256486e-01 8.763165e+01 -3.810859e-03 9.975139e-01 -7.036543e-02 -6.624344e+00 -9.280423e-01 2.268047e-02 3.717838e-01 6.570333e+01 +3.795424e-01 5.699201e-02 9.234172e-01 8.835787e+01 5.138607e-03 9.979555e-01 -6.370449e-02 -6.646336e+00 -9.251601e-01 2.892363e-02 3.784736e-01 6.599341e+01 +3.868597e-01 5.286436e-02 9.206220e-01 8.907692e+01 1.153572e-02 9.979998e-01 -6.215508e-02 -6.684073e+00 -9.220665e-01 3.466532e-02 3.854760e-01 6.628897e+01 +3.941549e-01 5.312216e-02 9.175074e-01 8.979244e+01 1.280626e-02 9.979136e-01 -6.327904e-02 -6.725361e+00 -9.189548e-01 3.669158e-02 3.926523e-01 6.659944e+01 +4.017997e-01 5.915111e-02 9.138151e-01 9.050245e+01 1.551673e-02 9.973284e-01 -7.137956e-02 -6.763694e+00 -9.155961e-01 4.285970e-02 3.998084e-01 6.690709e+01 +4.091353e-01 6.372032e-02 9.102461e-01 9.121810e+01 1.973855e-02 9.967072e-01 -7.864494e-02 -6.813377e+00 -9.122603e-01 5.014335e-02 4.065303e-01 6.722868e+01 +4.144271e-01 6.513043e-02 9.077489e-01 9.192183e+01 1.705387e-02 9.967049e-01 -7.929882e-02 -6.870738e+00 -9.099228e-01 4.834421e-02 4.119508e-01 6.755932e+01 +4.188452e-01 6.732450e-02 9.055584e-01 9.260904e+01 9.204078e-03 9.968817e-01 -7.837115e-02 -6.914272e+00 -9.080110e-01 4.116020e-02 4.169195e-01 6.790371e+01 +4.227454e-01 7.070038e-02 9.034864e-01 9.328887e+01 3.057782e-03 9.968352e-01 -7.943595e-02 -6.975179e+00 -9.062434e-01 3.634384e-02 4.211913e-01 6.824748e+01 +4.270382e-01 7.405487e-02 9.011959e-01 9.396130e+01 2.044972e-03 9.965590e-01 -8.286027e-02 -7.034880e+00 -9.042313e-01 3.722741e-02 4.254173e-01 6.858083e+01 +4.311862e-01 7.836336e-02 8.988534e-01 9.463312e+01 -1.013917e-03 9.962626e-01 -8.636927e-02 -7.110019e+00 -9.022624e-01 3.632986e-02 4.296541e-01 6.892013e+01 +4.345564e-01 8.123113e-02 8.969739e-01 9.527546e+01 -4.290526e-03 9.960997e-01 -8.812948e-02 -7.183014e+00 -9.006345e-01 3.444873e-02 4.332100e-01 6.924820e+01 +4.385578e-01 7.953606e-02 8.951765e-01 9.592749e+01 -5.482144e-03 9.962942e-01 -8.583457e-02 -7.259679e+00 -8.986863e-01 3.273593e-02 4.373687e-01 6.958240e+01 +4.428542e-01 7.591396e-02 8.933740e-01 9.658342e+01 -4.416793e-03 9.965817e-01 -8.249455e-02 -7.329268e+00 -8.965828e-01 3.258720e-02 4.416757e-01 6.991299e+01 +4.462005e-01 7.354328e-02 8.919061e-01 9.720647e+01 -4.875929e-03 9.968026e-01 -7.975336e-02 -7.398532e+00 -8.949198e-01 3.123711e-02 4.451324e-01 7.023613e+01 +4.498128e-01 7.264084e-02 8.901638e-01 9.784561e+01 -6.223303e-03 9.969176e-01 -7.820765e-02 -7.469536e+00 -8.931012e-01 2.963904e-02 4.488783e-01 7.056975e+01 +4.531344e-01 7.464556e-02 8.883114e-01 9.843505e+01 -7.837986e-03 9.967830e-01 -7.976232e-02 -7.533159e+00 -8.914078e-01 2.918048e-02 4.522618e-01 7.088389e+01 +4.559167e-01 7.493501e-02 8.868622e-01 9.903309e+01 -6.874789e-03 9.967160e-01 -8.068289e-02 -7.592121e+00 -8.899959e-01 3.068768e-02 4.549346e-01 7.119793e+01 +4.580361e-01 7.309423e-02 8.859233e-01 9.962790e+01 -4.849071e-03 9.968042e-01 -7.973557e-02 -7.650212e+00 -8.889204e-01 3.222586e-02 4.569267e-01 7.150888e+01 +4.597856e-01 7.210194e-02 8.850980e-01 1.002122e+02 -2.867504e-03 9.968137e-01 -7.971295e-02 -7.709739e+00 -8.880254e-01 3.411284e-02 4.585273e-01 7.181621e+01 +4.615821e-01 7.190767e-02 8.841782e-01 1.007869e+02 -4.291855e-03 9.968785e-01 -7.883272e-02 -7.766662e+00 -8.870872e-01 3.259300e-02 4.604499e-01 7.212549e+01 +4.635939e-01 7.154756e-02 8.831543e-01 1.013530e+02 -3.114287e-03 9.968598e-01 -7.912450e-02 -7.823540e+00 -8.860423e-01 3.393123e-02 4.623610e-01 7.243265e+01 +4.662232e-01 7.370896e-02 8.815911e-01 1.019055e+02 -3.435783e-03 9.966663e-01 -8.151331e-02 -7.883340e+00 -8.846605e-01 3.497443e-02 4.649221e-01 7.273582e+01 +4.693305e-01 7.307267e-02 8.799938e-01 1.024447e+02 -1.109730e-03 9.966180e-01 -8.216504e-02 -7.943074e+00 -8.830219e-01 3.758600e-02 4.678244e-01 7.303236e+01 +4.724365e-01 7.237662e-02 8.783879e-01 1.029830e+02 1.234127e-03 9.965672e-01 -8.277804e-02 -8.002376e+00 -8.813639e-01 4.019140e-02 4.707254e-01 7.332849e+01 +4.756810e-01 7.068726e-02 8.767729e-01 1.035115e+02 4.050499e-03 9.965791e-01 -8.254384e-02 -8.053690e+00 -8.796086e-01 4.281590e-02 4.737675e-01 7.362090e+01 +4.791236e-01 6.975479e-02 8.749712e-01 1.040361e+02 5.530276e-03 9.965775e-01 -8.247786e-02 -8.096619e+00 -8.777300e-01 4.435591e-02 4.770981e-01 7.390981e+01 +4.823176e-01 6.935246e-02 8.732467e-01 1.045505e+02 6.467138e-03 9.965520e-01 -8.271724e-02 -8.139292e+00 -8.759726e-01 4.554338e-02 4.802060e-01 7.419588e+01 +4.857257e-01 6.865676e-02 8.714107e-01 1.050601e+02 7.159909e-03 9.965646e-01 -8.250835e-02 -8.181955e+00 -8.740820e-01 4.631564e-02 4.835655e-01 7.448234e+01 +4.891732e-01 6.814586e-02 8.695203e-01 1.055640e+02 8.817026e-03 9.965056e-01 -8.305820e-02 -8.223750e+00 -8.721421e-01 4.829642e-02 4.868630e-01 7.476626e+01 +4.930605e-01 6.945168e-02 8.672184e-01 1.060641e+02 8.412663e-03 9.963812e-01 -8.457882e-02 -8.265059e+00 -8.699544e-01 4.899808e-02 4.906919e-01 7.505403e+01 +4.974064e-01 6.960041e-02 8.647211e-01 1.065650e+02 1.039377e-02 9.962267e-01 -8.616388e-02 -8.308372e+00 -8.674554e-01 5.184617e-02 4.948061e-01 7.534311e+01 +5.021425e-01 7.305369e-02 8.616936e-01 1.070595e+02 8.009040e-03 9.959898e-01 -8.910641e-02 -8.363102e+00 -8.647478e-01 5.164545e-02 4.995438e-01 7.563421e+01 +5.075846e-01 7.889659e-02 8.579820e-01 1.075403e+02 4.700685e-03 9.955302e-01 -9.432592e-02 -8.418748e+00 -8.615891e-01 5.191148e-02 5.049449e-01 7.592569e+01 +5.133730e-01 8.591861e-02 8.538536e-01 1.080289e+02 -7.217714e-04 9.950183e-01 -9.968929e-02 -8.475876e+00 -8.581653e-01 5.056150e-02 5.108775e-01 7.622883e+01 +5.194125e-01 9.210111e-02 8.495457e-01 1.085079e+02 -5.748399e-03 9.945287e-01 -1.043045e-01 -8.530283e+00 -8.545043e-01 4.929352e-02 5.171001e-01 7.653231e+01 +5.258177e-01 9.648418e-02 8.451073e-01 1.089938e+02 -8.786758e-03 9.941089e-01 -1.080284e-01 -8.586122e+00 -8.505519e-01 4.937747e-02 5.235679e-01 7.684080e+01 +5.311767e-01 9.671565e-02 8.417228e-01 1.094846e+02 -1.339558e-02 9.942978e-01 -1.057934e-01 -8.642339e+00 -8.471552e-01 4.491963e-02 5.294434e-01 7.716092e+01 +5.364891e-01 9.552072e-02 8.384838e-01 1.099856e+02 -1.985535e-02 9.947271e-01 -1.006160e-01 -8.706456e+00 -8.436737e-01 3.733100e-02 5.355569e-01 7.748994e+01 +5.422377e-01 9.312728e-02 8.350482e-01 1.104964e+02 -2.597826e-02 9.952217e-01 -9.412141e-02 -8.763095e+00 -8.398235e-01 2.934307e-02 5.420659e-01 7.782451e+01 +5.479617e-01 9.099474e-02 8.315395e-01 1.110125e+02 -3.224469e-02 9.956247e-01 -8.770211e-02 -8.817849e+00 -8.358818e-01 2.124465e-02 5.484982e-01 7.817109e+01 +5.540927e-01 8.923672e-02 8.276582e-01 1.115367e+02 -3.493499e-02 9.958545e-01 -8.398345e-02 -8.867411e+00 -8.317217e-01 1.762038e-02 5.549131e-01 7.851965e+01 +5.605101e-01 9.286252e-02 8.229246e-01 1.120557e+02 -3.948982e-02 9.955598e-01 -8.544618e-02 -8.915374e+00 -8.272056e-01 1.539630e-02 5.616884e-01 7.887613e+01 +5.664510e-01 9.677166e-02 8.183938e-01 1.125829e+02 -4.325482e-02 9.952038e-01 -8.773993e-02 -8.963221e+00 -8.229595e-01 1.430088e-02 5.679200e-01 7.924678e+01 +5.725560e-01 1.001365e-01 8.137274e-01 1.131161e+02 -4.600950e-02 9.948734e-01 -9.005489e-02 -9.011645e+00 -8.185737e-01 1.412227e-02 5.742279e-01 7.962766e+01 +5.788717e-01 1.020245e-01 8.090108e-01 1.136686e+02 -4.805454e-02 9.946856e-01 -9.105551e-02 -9.057118e+00 -8.140015e-01 1.383281e-02 5.806981e-01 8.001888e+01 +5.851199e-01 1.029632e-01 8.043838e-01 1.142286e+02 -5.131706e-02 9.946201e-01 -8.998518e-02 -9.105368e+00 -8.093215e-01 1.137351e-02 5.872557e-01 8.042589e+01 +5.912435e-01 1.049190e-01 7.996393e-01 1.147933e+02 -5.726240e-02 9.944606e-01 -8.814198e-02 -9.158005e+00 -8.044577e-01 6.324097e-03 5.939762e-01 8.084871e+01 +5.984116e-01 1.026552e-01 7.945850e-01 1.153671e+02 -5.766808e-02 9.947039e-01 -8.507872e-02 -9.217043e+00 -7.991107e-01 5.089903e-03 6.011623e-01 8.128451e+01 +6.059710e-01 1.007245e-01 7.890841e-01 1.159476e+02 -5.766546e-02 9.949036e-01 -8.271315e-02 -9.273702e+00 -7.933939e-01 4.618868e-03 6.086910e-01 8.172926e+01 +6.134904e-01 1.008717e-01 7.832333e-01 1.165301e+02 -5.858763e-02 9.948889e-01 -8.224017e-02 -9.317811e+00 -7.875259e-01 4.565763e-03 6.162646e-01 8.218891e+01 +6.209422e-01 1.032880e-01 7.770214e-01 1.171091e+02 -6.351949e-02 9.946507e-01 -8.145667e-02 -9.366338e+00 -7.812785e-01 1.223868e-03 6.241813e-01 8.266397e+01 +6.287839e-01 1.038119e-01 7.706191e-01 1.177001e+02 -6.392980e-02 9.945945e-01 -8.182087e-02 -9.410224e+00 -7.749477e-01 2.182111e-03 6.320216e-01 8.315109e+01 +6.355250e-01 1.046068e-01 7.649610e-01 1.182986e+02 -6.565811e-02 9.945124e-01 -8.144912e-02 -9.457628e+00 -7.692835e-01 1.537052e-03 6.389057e-01 8.365236e+01 +6.407217e-01 1.032479e-01 7.607993e-01 1.189071e+02 -6.562197e-02 9.946549e-01 -7.971966e-02 -9.501459e+00 -7.649638e-01 1.152959e-03 6.440723e-01 8.416417e+01 +6.444287e-01 1.017978e-01 7.578580e-01 1.195230e+02 -6.480563e-02 9.948039e-01 -7.851900e-02 -9.549903e+00 -7.619133e-01 1.486427e-03 6.476773e-01 8.468521e+01 +6.482741e-01 9.914096e-02 7.549249e-01 1.201636e+02 -6.092667e-02 9.950617e-01 -7.835775e-02 -9.590647e+00 -7.589655e-01 4.802234e-03 6.511131e-01 8.522386e+01 +6.517854e-01 9.553642e-02 7.523619e-01 1.207812e+02 -5.554669e-02 9.953831e-01 -7.827461e-02 -9.635230e+00 -7.563665e-01 9.227034e-03 6.540829e-01 8.574376e+01 +6.557828e-01 8.869963e-02 7.497207e-01 1.214334e+02 -4.780545e-02 9.959598e-01 -7.601670e-02 -9.682937e+00 -7.534345e-01 1.400970e-02 6.573737e-01 8.629266e+01 +6.594618e-01 8.305565e-02 7.471357e-01 1.220849e+02 -4.218349e-02 9.964003e-01 -7.353186e-02 -9.728697e+00 -7.505536e-01 1.697466e-02 6.605915e-01 8.685165e+01 +6.630555e-01 7.736600e-02 7.445615e-01 1.227300e+02 -3.652420e-02 9.968037e-01 -7.105009e-02 -9.773963e+00 -7.476787e-01 1.991564e-02 6.637620e-01 8.740500e+01 +6.663679e-01 7.623736e-02 7.417153e-01 1.233777e+02 -3.632067e-02 9.968970e-01 -6.983526e-02 -9.820354e+00 -7.447380e-01 1.959638e-02 6.670692e-01 8.797821e+01 +6.693976e-01 7.789532e-02 7.388092e-01 1.240203e+02 -3.713224e-02 9.967529e-01 -7.144763e-02 -9.868055e+00 -7.419758e-01 2.039322e-02 6.701164e-01 8.855484e+01 +6.726330e-01 8.244028e-02 7.353695e-01 1.246768e+02 -4.296094e-02 9.964489e-01 -7.241340e-02 -9.916275e+00 -7.387281e-01 1.711548e-02 6.737862e-01 8.916047e+01 +6.752168e-01 8.584468e-02 7.326069e-01 1.253111e+02 -4.843845e-02 9.962211e-01 -7.209029e-02 -9.964397e+00 -7.360272e-01 1.319023e-02 6.768235e-01 8.975362e+01 +6.781317e-01 8.261678e-02 7.302820e-01 1.259636e+02 -4.941746e-02 9.965384e-01 -6.684989e-02 -1.001373e+01 -7.332771e-01 9.244349e-03 6.798670e-01 9.035993e+01 +6.816128e-01 7.975910e-02 7.273530e-01 1.266190e+02 -5.207611e-02 9.968084e-01 -6.050544e-02 -1.005780e+01 -7.298576e-01 3.363564e-03 6.835909e-01 9.097676e+01 +6.851176e-01 7.449807e-02 7.246129e-01 1.272756e+02 -5.171768e-02 9.972208e-01 -5.362636e-02 -1.010087e+01 -7.265943e-01 -7.349427e-04 6.870664e-01 9.159686e+01 +6.897845e-01 7.018655e-02 7.206047e-01 1.279271e+02 -4.896896e-02 9.975336e-01 -5.028476e-02 -1.014276e+01 -7.223569e-01 -6.016191e-04 6.915202e-01 9.221818e+01 +6.945548e-01 6.746366e-02 7.162696e-01 1.285815e+02 -4.338405e-02 9.977092e-01 -5.190300e-02 -1.018420e+01 -7.181305e-01 4.974799e-03 6.958906e-01 9.284078e+01 +7.000786e-01 6.446784e-02 7.111496e-01 1.292245e+02 -3.261729e-02 9.977637e-01 -5.834077e-02 -1.023342e+01 -7.133204e-01 1.764735e-02 7.006158e-01 9.346390e+01 +7.055871e-01 6.626764e-02 7.055178e-01 1.298788e+02 -2.683090e-02 9.974021e-01 -6.685014e-02 -1.028691e+01 -7.081151e-01 2.823891e-02 7.055321e-01 9.410638e+01 +7.112766e-01 6.627078e-02 6.997812e-01 1.305065e+02 -2.419601e-02 9.972640e-01 -6.984958e-02 -1.034070e+01 -7.024957e-01 3.275046e-02 7.109340e-01 9.474426e+01 +7.170970e-01 6.227613e-02 6.941855e-01 1.311491e+02 -2.167839e-02 9.975111e-01 -6.709393e-02 -1.039963e+01 -6.966362e-01 3.306402e-02 7.166622e-01 9.540323e+01 +7.231076e-01 5.587894e-02 6.884714e-01 1.317916e+02 -1.710974e-02 9.978655e-01 -6.302005e-02 -1.045600e+01 -6.905235e-01 3.379071e-02 7.225202e-01 9.607042e+01 +7.284913e-01 5.352637e-02 6.829607e-01 1.324272e+02 -1.289581e-02 9.978376e-01 -6.444902e-02 -1.050523e+01 -6.849337e-01 3.814321e-02 7.276063e-01 9.674200e+01 +7.331185e-01 5.473772e-02 6.778946e-01 1.330590e+02 -1.046941e-02 9.975460e-01 -6.922623e-02 -1.055248e+01 -6.800204e-01 4.365387e-02 7.318924e-01 9.741926e+01 +7.367498e-01 5.740409e-02 6.737244e-01 1.336847e+02 -1.154373e-02 9.973123e-01 -7.235151e-02 -1.060432e+01 -6.760670e-01 4.552765e-02 7.354323e-01 9.810439e+01 +7.399405e-01 5.339135e-02 6.705501e-01 1.343191e+02 -9.169455e-03 9.975529e-01 -6.931005e-02 -1.066004e+01 -6.726099e-01 4.513673e-02 7.386194e-01 9.879631e+01 +7.423894e-01 4.822207e-02 6.682309e-01 1.349539e+02 -5.940312e-03 9.978408e-01 -6.540843e-02 -1.071551e+01 -6.699423e-01 4.458902e-02 7.410729e-01 9.948856e+01 +7.438086e-01 4.422238e-02 6.669281e-01 1.356011e+02 -2.810458e-03 9.980069e-01 -6.304099e-02 -1.077139e+01 -6.683868e-01 4.501605e-02 7.424504e-01 1.001963e+02 +7.444086e-01 3.981831e-02 6.665360e-01 1.362215e+02 6.075426e-04 9.981795e-01 -6.030895e-02 -1.081998e+01 -6.677241e-01 4.529944e-02 7.430292e-01 1.008793e+02 +7.446767e-01 3.886854e-02 6.662926e-01 1.368528e+02 5.034860e-04 9.982697e-01 -5.879734e-02 -1.086978e+01 -6.674252e-01 4.412047e-02 7.433687e-01 1.015789e+02 +7.445003e-01 3.908607e-02 6.664769e-01 1.374843e+02 -7.060651e-04 9.983302e-01 -5.775915e-02 -1.091832e+01 -6.676217e-01 4.253113e-02 7.432848e-01 1.022803e+02 +7.439725e-01 4.142014e-02 6.669253e-01 1.381207e+02 -2.359997e-03 9.982335e-01 -5.936379e-02 -1.096869e+01 -6.682062e-01 4.259108e-02 7.427560e-01 1.029852e+02 +7.425831e-01 4.566012e-02 6.681957e-01 1.387684e+02 -6.204824e-03 9.980995e-01 -6.130802e-02 -1.101807e+01 -6.697253e-01 4.138025e-02 7.414551e-01 1.037008e+02 +7.406677e-01 4.907649e-02 6.700767e-01 1.393904e+02 -9.656987e-03 9.980032e-01 -6.241955e-02 -1.106529e+01 -6.718021e-01 3.976121e-02 7.396627e-01 1.043827e+02 +7.386300e-01 5.214625e-02 6.720911e-01 1.400213e+02 -1.406987e-02 9.979789e-01 -6.196844e-02 -1.111507e+01 -6.739643e-01 3.631551e-02 7.378708e-01 1.050727e+02 +7.361989e-01 5.306085e-02 6.746819e-01 1.406686e+02 -1.596371e-02 9.980058e-01 -6.106964e-02 -1.116410e+01 -6.765770e-01 3.418896e-02 7.355777e-01 1.057715e+02 +7.338585e-01 5.302817e-02 6.772294e-01 1.413096e+02 -1.676349e-02 9.980585e-01 -5.998439e-02 -1.121534e+01 -6.790956e-01 3.266732e-02 7.333226e-01 1.064570e+02 +7.313859e-01 5.166595e-02 6.800038e-01 1.419472e+02 -1.795340e-02 9.982391e-01 -5.653516e-02 -1.126171e+01 -6.817275e-01 2.914063e-02 7.310256e-01 1.071334e+02 +7.287605e-01 4.794310e-02 6.830882e-01 1.425933e+02 -1.422739e-02 9.983907e-01 -5.489421e-02 -1.130940e+01 -6.846209e-01 3.028616e-02 7.282698e-01 1.078056e+02 +7.258265e-01 5.210861e-02 6.859013e-01 1.432295e+02 -1.519369e-02 9.980978e-01 -5.974841e-02 -1.135965e+01 -6.877101e-01 3.294560e-02 7.252375e-01 1.084648e+02 +7.223039e-01 6.290068e-02 6.887093e-01 1.438589e+02 -2.003347e-02 9.973403e-01 -7.007765e-02 -1.141070e+01 -6.912856e-01 3.682011e-02 7.216429e-01 1.091244e+02 +7.189310e-01 6.814252e-02 6.917331e-01 1.444994e+02 -2.214004e-02 9.969229e-01 -7.519618e-02 -1.146260e+01 -6.947288e-01 3.874586e-02 7.182274e-01 1.097839e+02 +7.151980e-01 6.636784e-02 6.957637e-01 1.451538e+02 -2.496307e-02 9.972717e-01 -6.946792e-02 -1.152141e+01 -6.984760e-01 3.231491e-02 7.149034e-01 1.104492e+02 +7.115688e-01 6.459830e-02 6.996405e-01 1.457899e+02 -2.769090e-02 9.975692e-01 -6.394329e-02 -1.157854e+01 -7.020706e-01 2.612637e-02 7.116279e-01 1.110957e+02 +7.079977e-01 6.419717e-02 7.032908e-01 1.464484e+02 -2.918610e-02 9.976687e-01 -6.168690e-02 -1.163357e+01 -7.056114e-01 2.314786e-02 7.082208e-01 1.117540e+02 +7.047570e-01 6.385359e-02 7.065694e-01 1.470826e+02 -2.882029e-02 9.976960e-01 -6.141674e-02 -1.168264e+01 -7.088632e-01 2.292033e-02 7.049734e-01 1.123782e+02 +7.017347e-01 6.235181e-02 7.097046e-01 1.477333e+02 -2.673815e-02 9.977659e-01 -6.122186e-02 -1.173221e+01 -7.119365e-01 2.398531e-02 7.018341e-01 1.130076e+02 +6.988853e-01 6.118800e-02 7.126116e-01 1.483963e+02 -2.290297e-02 9.977374e-01 -6.320838e-02 -1.178416e+01 -7.148670e-01 2.785448e-02 6.987054e-01 1.136394e+02 +6.954869e-01 6.096418e-02 7.159478e-01 1.490522e+02 -1.943465e-02 9.976256e-01 -6.607031e-02 -1.183500e+01 -7.182760e-01 3.203684e-02 6.950203e-01 1.142503e+02 +6.916046e-01 6.120012e-02 7.196788e-01 1.497073e+02 -1.661558e-02 9.974881e-01 -6.885709e-02 -1.188352e+01 -7.220853e-01 3.566398e-02 6.908842e-01 1.148427e+02 +6.876071e-01 6.194504e-02 7.234357e-01 1.503763e+02 -1.668900e-02 9.974392e-01 -6.954446e-02 -1.192783e+01 -7.258912e-01 3.574584e-02 6.868801e-01 1.154384e+02 +6.834020e-01 6.347575e-02 7.272775e-01 1.510476e+02 -1.859951e-02 9.974033e-01 -6.957454e-02 -1.197578e+01 -7.298054e-01 3.402036e-02 6.828080e-01 1.160372e+02 +6.782384e-01 6.333601e-02 7.321074e-01 1.517272e+02 -1.839537e-02 9.974298e-01 -6.924776e-02 -1.202409e+01 -7.346117e-01 3.349909e-02 6.776602e-01 1.166342e+02 +6.725802e-01 6.631303e-02 7.370471e-01 1.524041e+02 -2.058202e-02 9.972679e-01 -7.094364e-02 -1.207204e+01 -7.397380e-01 3.254536e-02 6.721075e-01 1.172224e+02 +6.661776e-01 7.294586e-02 7.422171e-01 1.530860e+02 -2.514374e-02 9.968361e-01 -7.540231e-02 -1.212501e+01 -7.453692e-01 3.156921e-02 6.659040e-01 1.178158e+02 +6.599246e-01 7.911778e-02 7.471545e-01 1.537739e+02 -2.713381e-02 9.963010e-01 -8.153451e-02 -1.217933e+01 -7.508417e-01 3.353347e-02 6.596303e-01 1.183992e+02 +6.534586e-01 8.079660e-02 7.526378e-01 1.544786e+02 -2.689334e-02 9.961374e-01 -8.358715e-02 -1.223831e+01 -7.564844e-01 3.437979e-02 6.531075e-01 1.189893e+02 +6.469446e-01 7.608418e-02 7.587317e-01 1.551890e+02 -2.810513e-02 9.967128e-01 -7.598421e-02 -1.229900e+01 -7.620189e-01 2.783331e-02 6.469563e-01 1.195662e+02 +6.397512e-01 7.181624e-02 7.652194e-01 1.559127e+02 -3.418701e-02 9.972984e-01 -6.501541e-02 -1.236503e+01 -7.678214e-01 1.543313e-02 6.404781e-01 1.201520e+02 +6.324319e-01 6.652044e-02 7.717544e-01 1.566454e+02 -3.339659e-02 9.977209e-01 -5.862978e-02 -1.242646e+01 -7.738957e-01 1.130537e-02 6.332121e-01 1.207245e+02 +6.251650e-01 6.886405e-02 7.774487e-01 1.573838e+02 -3.787701e-02 9.976031e-01 -5.790688e-02 -1.247643e+01 -7.795731e-01 6.753918e-03 6.262749e-01 1.212983e+02 +6.172113e-01 6.988319e-02 7.836877e-01 1.581338e+02 -3.599040e-02 9.975127e-01 -6.060540e-02 -1.252578e+01 -7.859739e-01 9.201094e-03 6.181912e-01 1.218681e+02 +6.108586e-01 7.059566e-02 7.885860e-01 1.589058e+02 -3.062857e-02 9.973783e-01 -6.556148e-02 -1.258374e+01 -7.911471e-01 1.589552e-02 6.114194e-01 1.224322e+02 +6.038259e-01 7.815156e-02 7.932758e-01 1.596460e+02 -2.993338e-02 9.967033e-01 -7.540806e-02 -1.263933e+01 -7.965541e-01 2.178790e-02 6.041746e-01 1.229716e+02 +5.963776e-01 7.929639e-02 7.987777e-01 1.604008e+02 -2.527590e-02 9.964702e-01 -8.005047e-02 -1.270216e+01 -8.023060e-01 2.755048e-02 5.962768e-01 1.235094e+02 +5.891790e-01 7.493142e-02 8.045206e-01 1.611947e+02 -2.269531e-02 9.968324e-01 -7.622240e-02 -1.277762e+01 -8.076838e-01 2.664978e-02 5.890133e-01 1.240636e+02 +5.822744e-01 6.889034e-02 8.100682e-01 1.619638e+02 -1.852015e-02 9.972687e-01 -7.149816e-02 -1.285193e+01 -8.127814e-01 2.662895e-02 5.819599e-01 1.245828e+02 +5.757273e-01 6.846542e-02 8.147702e-01 1.627291e+02 -1.710626e-02 9.972784e-01 -7.171416e-02 -1.291940e+01 -8.174629e-01 2.735012e-02 5.753316e-01 1.250909e+02 +5.691041e-01 6.805338e-02 8.194444e-01 1.634987e+02 -1.568329e-02 9.972862e-01 -7.193080e-02 -1.298726e+01 -8.221159e-01 2.808453e-02 5.686270e-01 1.256019e+02 +5.624434e-01 6.760840e-02 8.240670e-01 1.642698e+02 -1.422680e-02 9.972951e-01 -7.211036e-02 -1.305527e+01 -8.267134e-01 2.883416e-02 5.618839e-01 1.261138e+02 +5.573815e-01 6.199015e-02 8.279390e-01 1.650417e+02 -9.673814e-03 9.976259e-01 -6.818255e-02 -1.312226e+01 -8.302002e-01 2.999436e-02 5.566579e-01 1.266042e+02 +5.523929e-01 5.872647e-02 8.315126e-01 1.658008e+02 -9.085324e-03 9.978801e-01 -6.444078e-02 -1.318289e+01 -8.335344e-01 2.804206e-02 5.517555e-01 1.270920e+02 +5.479447e-01 5.798755e-02 8.345022e-01 1.665531e+02 -1.051015e-02 9.979929e-01 -6.244704e-02 -1.323954e+01 -8.364486e-01 2.544678e-02 5.474544e-01 1.275770e+02 +5.433404e-01 6.094574e-02 8.372973e-01 1.672915e+02 -1.101350e-02 9.977929e-01 -6.548111e-02 -1.329978e+01 -8.394403e-01 2.635695e-02 5.428124e-01 1.280524e+02 +5.395125e-01 6.452462e-02 8.395015e-01 1.680469e+02 -1.026839e-02 9.974892e-01 -7.006861e-02 -1.336429e+01 -8.419150e-01 2.918255e-02 5.388205e-01 1.285271e+02 +5.365350e-01 6.953514e-02 8.410083e-01 1.687640e+02 -1.024792e-02 9.970627e-01 -7.590002e-02 -1.342431e+01 -8.438159e-01 3.210442e-02 5.356716e-01 1.289792e+02 +5.330025e-01 7.208680e-02 8.430372e-01 1.694764e+02 -1.306140e-02 9.969463e-01 -7.698940e-02 -1.348459e+01 -8.460129e-01 3.002430e-02 5.323164e-01 1.294289e+02 +5.302807e-01 6.709643e-02 8.451629e-01 1.701931e+02 -1.291596e-02 9.973871e-01 -7.107748e-02 -1.354899e+01 -8.477238e-01 2.677492e-02 5.297618e-01 1.298817e+02 +5.280669e-01 5.862653e-02 8.471766e-01 1.709121e+02 -9.759284e-03 9.979671e-01 -6.297838e-02 -1.361181e+01 -8.491468e-01 2.498895e-02 5.275655e-01 1.303215e+02 +5.255471e-01 5.374601e-02 8.490651e-01 1.716213e+02 -5.432773e-03 9.981941e-01 -5.982320e-02 -1.367121e+01 -8.507472e-01 2.682712e-02 5.248900e-01 1.307525e+02 +5.230206e-01 5.247386e-02 8.507032e-01 1.723205e+02 4.771035e-04 9.980848e-01 -6.185813e-02 -1.372813e+01 -8.523200e-01 3.275894e-02 5.219938e-01 1.311750e+02 +5.207817e-01 5.561492e-02 8.518763e-01 1.730101e+02 1.812765e-03 9.978013e-01 -6.624989e-02 -1.378410e+01 -8.536880e-01 3.604597e-02 5.195358e-01 1.315931e+02 +5.186716e-01 6.233329e-02 8.526982e-01 1.736861e+02 -2.165016e-04 9.973482e-01 -7.277570e-02 -1.384508e+01 -8.549736e-01 3.756207e-02 5.173097e-01 1.320073e+02 +5.163968e-01 7.099758e-02 8.534012e-01 1.743545e+02 -2.460570e-03 9.966761e-01 -8.142826e-02 -1.390627e+01 -8.563459e-01 3.994943e-02 5.148550e-01 1.324182e+02 +5.142678e-01 7.224068e-02 8.545816e-01 1.750350e+02 1.884135e-03 9.963484e-01 -8.535855e-02 -1.396378e+01 -8.576276e-01 4.550729e-02 5.122538e-01 1.328270e+02 +5.116812e-01 6.617294e-02 8.566232e-01 1.756897e+02 8.975473e-04 9.969878e-01 -7.755205e-02 -1.401825e+01 -8.591749e-01 4.045078e-02 5.100806e-01 1.332184e+02 +5.080308e-01 5.800036e-02 8.593838e-01 1.763532e+02 -7.050528e-03 9.979768e-01 -6.318613e-02 -1.407865e+01 -8.613101e-01 2.604138e-02 5.074118e-01 1.336308e+02 +5.045411e-01 5.525444e-02 8.616177e-01 1.770072e+02 -1.538348e-02 9.983669e-01 -5.501584e-02 -1.413400e+01 -8.632506e-01 1.450307e-02 5.045671e-01 1.340303e+02 +5.023265e-01 5.713914e-02 8.627880e-01 1.776520e+02 -1.616384e-02 9.982603e-01 -5.670016e-02 -1.418089e+01 -8.645270e-01 1.453602e-02 5.023762e-01 1.344121e+02 +5.000701e-01 6.042140e-02 8.638744e-01 1.782937e+02 -1.266980e-02 9.979666e-01 -6.246598e-02 -1.422293e+01 -8.658923e-01 2.029225e-02 4.998188e-01 1.347778e+02 +4.975661e-01 6.193002e-02 8.652124e-01 1.789314e+02 -1.167629e-02 9.978358e-01 -6.470813e-02 -1.426465e+01 -8.673475e-01 2.209409e-02 4.972124e-01 1.351404e+02 +4.949234e-01 6.121024e-02 8.667780e-01 1.795573e+02 -1.208720e-02 9.979042e-01 -6.356844e-02 -1.431261e+01 -8.688526e-01 2.098458e-02 4.946260e-01 1.355048e+02 +4.921297e-01 6.017400e-02 8.684396e-01 1.801748e+02 -1.296951e-02 9.980041e-01 -6.180192e-02 -1.436322e+01 -8.704253e-01 1.915132e-02 4.919279e-01 1.358638e+02 +4.896008e-01 5.986967e-02 8.698888e-01 1.807795e+02 -1.280694e-02 9.980260e-01 -6.148051e-02 -1.441258e+01 -8.718527e-01 1.896030e-02 4.894011e-01 1.362166e+02 +4.866699e-01 6.023619e-02 8.715067e-01 1.813913e+02 -1.112561e-02 9.979663e-01 -6.276395e-02 -1.445852e+01 -8.735151e-01 2.084928e-02 4.863503e-01 1.365576e+02 +4.828026e-01 6.205743e-02 8.735276e-01 1.819903e+02 -1.022615e-02 9.978174e-01 -6.523525e-02 -1.450312e+01 -8.756695e-01 2.256292e-02 4.823834e-01 1.368908e+02 +4.784604e-01 6.412302e-02 8.757647e-01 1.825812e+02 -1.039562e-02 9.976738e-01 -6.736967e-02 -1.454745e+01 -8.780476e-01 2.312960e-02 4.780140e-01 1.372138e+02 +4.736855e-01 6.600436e-02 8.782171e-01 1.831665e+02 -1.039294e-02 9.975370e-01 -6.936647e-02 -1.459096e+01 -8.806328e-01 2.373063e-02 4.732048e-01 1.375326e+02 +4.685024e-01 6.864257e-02 8.807914e-01 1.837467e+02 -1.075481e-02 9.973462e-01 -7.200543e-02 -1.463103e+01 -8.833968e-01 2.426197e-02 4.679973e-01 1.378441e+02 +4.626633e-01 7.179588e-02 8.836221e-01 1.843283e+02 -9.424215e-03 9.970572e-01 -7.607820e-02 -1.467151e+01 -8.864840e-01 2.687114e-02 4.619784e-01 1.381496e+02 +4.562691e-01 7.465751e-02 8.867044e-01 1.849104e+02 -7.607239e-03 9.967650e-01 -8.000982e-02 -1.471237e+01 -8.898093e-01 2.976063e-02 4.553610e-01 1.384500e+02 +4.496326e-01 7.711009e-02 8.898789e-01 1.855029e+02 -9.350031e-03 9.966184e-01 -8.163501e-02 -1.475510e+01 -8.931647e-01 2.838536e-02 4.488331e-01 1.387526e+02 +4.427020e-01 7.909464e-02 8.931735e-01 1.860967e+02 -1.379913e-02 9.965849e-01 -8.141266e-02 -1.479763e+01 -8.965626e-01 2.371653e-02 4.422816e-01 1.390562e+02 +4.359586e-01 8.053965e-02 8.963556e-01 1.867023e+02 -1.739722e-02 9.965556e-01 -8.108142e-02 -1.484501e+01 -8.997986e-01 1.975405e-02 4.358582e-01 1.393564e+02 +4.295368e-01 8.152935e-02 8.993614e-01 1.873167e+02 -1.777900e-02 9.964866e-01 -8.184272e-02 -1.489366e+01 -9.028744e-01 1.916471e-02 4.294772e-01 1.396500e+02 +4.225271e-01 8.476602e-02 9.023777e-01 1.879390e+02 -1.879476e-02 9.962223e-01 -8.478104e-02 -1.494259e+01 -9.061555e-01 1.886231e-02 4.225240e-01 1.399420e+02 +4.148052e-01 9.003995e-02 9.054443e-01 1.885640e+02 -2.199096e-02 9.957932e-01 -8.894995e-02 -1.499292e+01 -9.096445e-01 1.698531e-02 4.150403e-01 1.402354e+02 +4.070557e-01 9.379638e-02 9.085746e-01 1.891978e+02 -2.398002e-02 9.954680e-01 -9.202339e-02 -1.503908e+01 -9.130885e-01 1.567100e-02 4.074601e-01 1.405266e+02 +3.997251e-01 9.636593e-02 9.115554e-01 1.898399e+02 -2.556744e-02 9.952436e-01 -9.400157e-02 -1.508795e+01 -9.162784e-01 1.426864e-02 4.002877e-01 1.408155e+02 +3.922288e-01 9.906575e-02 9.145176e-01 1.904965e+02 -2.595899e-02 9.949799e-01 -9.664833e-02 -1.514579e+01 -9.195014e-01 1.416831e-02 3.928315e-01 1.410981e+02 +3.847916e-01 1.008805e-01 9.174739e-01 1.911667e+02 -2.733209e-02 9.948186e-01 -9.792178e-02 -1.520551e+01 -9.225988e-01 1.260299e-02 3.855551e-01 1.413810e+02 +3.777429e-01 1.015973e-01 9.203196e-01 1.918455e+02 -2.382205e-02 9.946991e-01 -1.000306e-01 -1.526383e+01 -9.256041e-01 1.586195e-02 3.781608e-01 1.416544e+02 +3.707676e-01 1.006210e-01 9.232587e-01 1.925394e+02 -2.164634e-02 9.947797e-01 -9.972289e-02 -1.532526e+01 -9.284734e-01 1.698885e-02 3.710102e-01 1.419287e+02 +3.633030e-01 9.808784e-02 9.264932e-01 1.932450e+02 -2.057046e-02 9.950445e-01 -9.727916e-02 -1.538822e+01 -9.314440e-01 1.628341e-02 3.635203e-01 1.422045e+02 +3.558825e-01 9.574795e-02 9.296127e-01 1.939627e+02 -2.182126e-02 9.953177e-01 -9.416162e-02 -1.545199e+01 -9.342759e-01 1.322515e-02 3.563055e-01 1.424808e+02 +3.492649e-01 9.144873e-02 9.325508e-01 1.946963e+02 -2.109748e-02 9.957413e-01 -8.974384e-02 -1.551367e+01 -9.367865e-01 1.166989e-02 3.497068e-01 1.427543e+02 +3.436377e-01 8.776456e-02 9.349922e-01 1.954600e+02 -1.751161e-02 9.960491e-01 -8.705974e-02 -1.557305e+01 -9.389391e-01 1.354378e-02 3.438169e-01 1.430263e+02 +3.382361e-01 8.240972e-02 9.374459e-01 1.962138e+02 -1.692004e-02 9.965297e-01 -8.149887e-02 -1.562684e+01 -9.409092e-01 1.170424e-02 3.384567e-01 1.432937e+02 +3.326918e-01 7.692879e-02 9.398925e-01 1.969859e+02 -1.629127e-02 9.969872e-01 -7.583532e-02 -1.568196e+01 -9.428949e-01 9.917743e-03 3.329428e-01 1.435675e+02 +3.280429e-01 7.676251e-02 9.415387e-01 1.977721e+02 -1.147022e-02 9.969431e-01 -7.728322e-02 -1.574033e+01 -9.445932e-01 1.455255e-02 3.279206e-01 1.438336e+02 +3.230512e-01 8.427881e-02 9.426213e-01 1.985592e+02 -9.109144e-03 9.962575e-01 -8.595254e-02 -1.579846e+01 -9.463377e-01 1.918059e-02 3.226099e-01 1.440967e+02 +3.186931e-01 9.624264e-02 9.429591e-01 1.993386e+02 -3.649873e-03 9.949489e-01 -1.003154e-01 -1.585428e+01 -9.478510e-01 2.852814e-02 3.174346e-01 1.443500e+02 +3.148095e-01 1.023328e-01 9.436222e-01 2.001451e+02 2.326605e-03 9.940847e-01 -1.085816e-01 -1.592437e+01 -9.491521e-01 3.637793e-02 3.127092e-01 1.446074e+02 +3.107911e-01 9.763496e-02 9.454502e-01 2.009751e+02 8.425803e-03 9.943879e-01 -1.054584e-01 -1.600532e+01 -9.504409e-01 4.074171e-02 3.082243e-01 1.448679e+02 +3.062511e-01 8.904936e-02 9.477765e-01 2.018244e+02 1.522725e-02 9.950294e-01 -9.840939e-02 -1.608857e+01 -9.518290e-01 4.457001e-02 3.033729e-01 1.451297e+02 +3.014416e-01 8.371634e-02 9.498023e-01 2.026924e+02 1.738545e-02 9.954898e-01 -9.326097e-02 -1.617598e+01 -9.533262e-01 4.462547e-02 2.986266e-01 1.453976e+02 +2.966921e-01 9.037361e-02 9.506873e-01 2.035316e+02 1.415046e-02 9.949866e-01 -9.900089e-02 -1.626124e+01 -9.548684e-01 4.282544e-02 2.939259e-01 1.456544e+02 +2.920486e-01 9.973348e-02 9.511891e-01 2.043673e+02 1.011548e-02 9.941702e-01 -1.073459e-01 -1.633869e+01 -9.563500e-01 4.097195e-02 2.893371e-01 1.459080e+02 +2.868469e-01 1.037087e-01 9.523462e-01 2.052495e+02 6.313512e-03 9.938965e-01 -1.101351e-01 -1.642655e+01 -9.579557e-01 3.760455e-02 2.844414e-01 1.461719e+02 +2.812924e-01 9.863609e-02 9.545394e-01 2.061048e+02 3.084065e-03 9.946053e-01 -1.036851e-01 -1.651609e+01 -9.596172e-01 3.210968e-02 2.794707e-01 1.464228e+02 +2.756989e-01 9.513302e-02 9.565248e-01 2.069819e+02 5.180705e-04 9.950756e-01 -9.911651e-02 -1.660980e+01 -9.612439e-01 2.782186e-02 2.742920e-01 1.466776e+02 +2.701798e-01 9.681046e-02 9.579303e-01 2.078609e+02 -6.002559e-04 9.949487e-01 -1.003823e-01 -1.669858e+01 -9.628097e-01 2.654627e-02 2.688731e-01 1.469260e+02 +2.651747e-01 1.011309e-01 9.588820e-01 2.087471e+02 -1.566681e-03 9.945281e-01 -1.044571e-01 -1.678439e+01 -9.641991e-01 2.619712e-02 2.638821e-01 1.471708e+02 +2.606053e-01 1.013878e-01 9.601069e-01 2.096440e+02 1.688637e-03 9.944210e-01 -1.054698e-01 -1.687390e+01 -9.654440e-01 2.910725e-02 2.589801e-01 1.474068e+02 +2.566684e-01 1.005347e-01 9.612565e-01 2.105492e+02 5.486179e-03 9.944076e-01 -1.054667e-01 -1.696319e+01 -9.664840e-01 3.234359e-02 2.546814e-01 1.476436e+02 +2.528181e-01 9.892462e-02 9.624431e-01 2.114620e+02 7.020823e-03 9.945453e-01 -1.040685e-01 -1.705443e+01 -9.674884e-01 3.306754e-02 2.507445e-01 1.478807e+02 +2.493833e-01 9.838460e-02 9.633942e-01 2.123811e+02 9.511728e-03 9.945290e-01 -1.040264e-01 -1.714388e+01 -9.683582e-01 3.510598e-02 2.470831e-01 1.481148e+02 +2.466281e-01 9.726272e-02 9.642170e-01 2.133004e+02 9.659479e-03 9.946547e-01 -1.028038e-01 -1.723376e+01 -9.690621e-01 3.466812e-02 2.443703e-01 1.483482e+02 +2.437899e-01 9.602031e-02 9.650629e-01 2.142272e+02 8.511665e-03 9.948364e-01 -1.011329e-01 -1.732239e+01 -9.697908e-01 3.286945e-02 2.417138e-01 1.485829e+02 +2.412380e-01 9.416597e-02 9.658866e-01 2.151568e+02 8.599209e-03 9.950347e-01 -9.915541e-02 -1.741109e+01 -9.704279e-01 3.222591e-02 2.392304e-01 1.488145e+02 +2.384371e-01 9.451012e-02 9.665482e-01 2.160841e+02 4.124666e-03 9.951458e-01 -9.832395e-02 -1.750032e+01 -9.711492e-01 2.743076e-02 2.368899e-01 1.490489e+02 +2.367007e-01 9.694294e-02 9.667340e-01 2.170093e+02 2.825041e-03 9.949367e-01 -1.004628e-01 -1.758912e+01 -9.715785e-01 2.651067e-02 2.352284e-01 1.492778e+02 +2.348880e-01 9.796276e-02 9.670733e-01 2.179343e+02 2.215985e-03 9.948519e-01 -1.013149e-01 -1.767768e+01 -9.720199e-01 2.594068e-02 2.334617e-01 1.495044e+02 +2.328840e-01 9.866896e-02 9.674861e-01 2.188603e+02 2.613904e-03 9.947726e-01 -1.020810e-01 -1.776862e+01 -9.725010e-01 2.630194e-02 2.314087e-01 1.497262e+02 +2.315539e-01 9.596294e-02 9.680773e-01 2.197937e+02 2.582563e-03 9.950586e-01 -9.925526e-02 -1.785886e+01 -9.728187e-01 2.548306e-02 2.301619e-01 1.499499e+02 +2.304690e-01 9.379991e-02 9.685481e-01 2.207197e+02 5.176530e-03 9.952108e-01 -9.761387e-02 -1.794623e+01 -9.730659e-01 2.751068e-02 2.288797e-01 1.501656e+02 +2.288692e-01 8.945903e-02 9.693378e-01 2.216448e+02 5.952827e-03 9.956211e-01 -9.329021e-02 -1.803413e+01 -9.734390e-01 2.712155e-02 2.273345e-01 1.503821e+02 +2.271951e-01 9.333935e-02 9.693658e-01 2.225742e+02 5.126221e-03 9.952677e-01 -9.703490e-02 -1.812038e+01 -9.738358e-01 2.701503e-02 2.256415e-01 1.506004e+02 +2.252583e-01 9.769402e-02 9.693887e-01 2.235075e+02 4.753492e-03 9.948380e-01 -1.013634e-01 -1.820847e+01 -9.742875e-01 2.744092e-02 2.236312e-01 1.508144e+02 +2.234058e-01 1.020275e-01 9.693710e-01 2.244121e+02 4.420208e-03 9.943903e-01 -1.056795e-01 -1.829363e+01 -9.747155e-01 2.789423e-02 2.217015e-01 1.510218e+02 +2.206324e-01 1.024896e-01 9.699572e-01 2.253277e+02 3.208701e-03 9.943821e-01 -1.058003e-01 -1.838635e+01 -9.753518e-01 2.645528e-02 2.190641e-01 1.512317e+02 +2.177265e-01 9.880990e-02 9.709952e-01 2.262731e+02 1.781073e-03 9.948202e-01 -1.016338e-01 -1.848080e+01 -9.760082e-01 2.385777e-02 2.164227e-01 1.514464e+02 +2.146834e-01 9.265815e-02 9.722784e-01 2.271676e+02 2.290800e-03 9.954391e-01 -9.537119e-02 -1.856752e+01 -9.766811e-01 2.270190e-02 2.134919e-01 1.516432e+02 +2.109988e-01 8.885442e-02 9.734394e-01 2.281038e+02 3.055129e-03 9.957950e-01 -9.155725e-02 -1.865508e+01 -9.774816e-01 2.229244e-02 2.098401e-01 1.518450e+02 +2.070110e-01 8.963300e-02 9.742239e-01 2.290056e+02 1.722539e-03 9.957593e-01 -9.198038e-02 -1.873661e+01 -9.783371e-01 2.071908e-02 2.059787e-01 1.520382e+02 +2.028161e-01 9.132666e-02 9.749487e-01 2.299189e+02 1.864635e-03 9.956034e-01 -9.364937e-02 -1.881652e+01 -9.792151e-01 2.081152e-02 2.017541e-01 1.522303e+02 +1.989953e-01 9.142692e-02 9.757263e-01 2.308378e+02 1.895294e-03 9.956009e-01 -9.367575e-02 -1.889376e+01 -9.799986e-01 2.049032e-02 1.979466e-01 1.524181e+02 +1.946759e-01 9.085693e-02 9.766505e-01 2.317587e+02 1.971537e-03 9.956623e-01 -9.301859e-02 -1.896992e+01 -9.808657e-01 2.003397e-02 1.936523e-01 1.526032e+02 +1.906832e-01 8.970677e-02 9.775441e-01 2.326895e+02 2.738799e-03 9.957632e-01 -9.191294e-02 -1.904112e+01 -9.816478e-01 2.020354e-02 1.896296e-01 1.527858e+02 +1.867244e-01 8.935452e-02 9.783402e-01 2.336155e+02 1.846353e-03 9.958213e-01 -9.130353e-02 -1.911494e+01 -9.824106e-01 1.885495e-02 1.857791e-01 1.529646e+02 +1.825907e-01 9.018021e-02 9.790444e-01 2.345305e+02 2.826323e-04 9.957797e-01 -9.177443e-02 -1.918701e+01 -9.831890e-01 1.703386e-02 1.817946e-01 1.531401e+02 +1.785548e-01 9.099055e-02 9.797136e-01 2.354493e+02 -2.091990e-03 9.957476e-01 -9.209846e-02 -1.926118e+01 -9.839278e-01 1.439507e-02 1.779859e-01 1.533132e+02 +1.743611e-01 9.053696e-02 9.805106e-01 2.363787e+02 -4.315816e-03 9.958247e-01 -9.118355e-02 -1.933366e+01 -9.846724e-01 1.166716e-02 1.740238e-01 1.534780e+02 +1.705743e-01 9.158339e-02 9.810794e-01 2.372897e+02 -8.781858e-03 9.957729e-01 -9.142819e-02 -1.941011e+01 -9.853057e-01 6.979593e-03 1.706575e-01 1.536418e+02 +1.667417e-01 9.616093e-02 9.813002e-01 2.381998e+02 -1.347371e-02 9.953622e-01 -9.524949e-02 -1.949555e+01 -9.859086e-01 2.660306e-03 1.672640e-01 1.538032e+02 +1.633438e-01 1.017604e-01 9.813070e-01 2.391054e+02 -1.609225e-02 9.948087e-01 -1.004819e-01 -1.957930e+01 -9.864380e-01 6.216606e-04 1.641334e-01 1.539590e+02 +1.598319e-01 1.034678e-01 9.817067e-01 2.400191e+02 -1.762164e-02 9.946322e-01 -1.019611e-01 -1.966444e+01 -9.869870e-01 -1.002646e-03 1.607972e-01 1.541100e+02 +1.564371e-01 1.008394e-01 9.825267e-01 2.409342e+02 -1.912174e-02 9.948972e-01 -9.906450e-02 -1.975257e+01 -9.875028e-01 -3.290260e-03 1.575671e-01 1.542564e+02 +1.531232e-01 9.702814e-02 9.834321e-01 2.418500e+02 -1.863667e-02 9.952745e-01 -9.529479e-02 -1.983999e+01 -9.880314e-01 -3.736056e-03 1.542079e-01 1.543982e+02 +1.500900e-01 9.410238e-02 9.841837e-01 2.427628e+02 -1.809626e-02 9.955547e-01 -9.242991e-02 -1.992378e+01 -9.885068e-01 -3.937243e-03 1.511257e-01 1.545354e+02 +1.468285e-01 9.306468e-02 9.847742e-01 2.436688e+02 -1.671571e-02 9.956554e-01 -9.160072e-02 -2.000434e+01 -9.890208e-01 -3.011608e-03 1.477462e-01 1.546684e+02 +1.433841e-01 9.318567e-02 9.852702e-01 2.445757e+02 -1.605087e-02 9.956451e-01 -9.183109e-02 -2.008388e+01 -9.895370e-01 -2.647326e-03 1.442554e-01 1.547979e+02 +1.391890e-01 9.508455e-02 9.856902e-01 2.454743e+02 -1.670129e-02 9.954632e-01 -9.366894e-02 -2.016399e+01 -9.901250e-01 -3.424617e-03 1.401456e-01 1.549236e+02 +1.344071e-01 9.756237e-02 9.861116e-01 2.463684e+02 -1.701631e-02 9.952219e-01 -9.614439e-02 -2.024532e+01 -9.907801e-01 -3.857497e-03 1.354250e-01 1.550412e+02 +1.295849e-01 9.341149e-02 9.871585e-01 2.472733e+02 -7.631354e-03 9.956171e-01 -9.321015e-02 -2.032350e+01 -9.915390e-01 4.545266e-03 1.297298e-01 1.551446e+02 +1.253781e-01 8.789818e-02 9.882075e-01 2.481739e+02 -7.045965e-03 9.961212e-01 -8.770814e-02 -2.040379e+01 -9.920840e-01 4.033802e-03 1.255111e-01 1.552524e+02 +1.198622e-01 8.884159e-02 9.888074e-01 2.490698e+02 -7.117082e-03 9.960392e-01 -8.862864e-02 -2.048204e+01 -9.927651e-01 3.585797e-03 1.200197e-01 1.553582e+02 +1.158805e-01 1.016851e-01 9.880444e-01 2.499549e+02 -3.982113e-03 9.947854e-01 -1.019118e-01 -2.055749e+01 -9.932552e-01 7.875084e-03 1.156811e-01 1.554527e+02 +1.104988e-01 1.151812e-01 9.871794e-01 2.508345e+02 -2.010936e-03 9.932857e-01 -1.156686e-01 -2.063460e+01 -9.938743e-01 1.079609e-02 1.099885e-01 1.555425e+02 +1.047395e-01 1.180202e-01 9.874719e-01 2.517259e+02 -4.262840e-03 9.929775e-01 -1.182261e-01 -2.071972e+01 -9.944906e-01 8.173507e-03 1.045071e-01 1.556328e+02 +9.917196e-02 1.118108e-01 9.887685e-01 2.526209e+02 -8.700271e-03 9.937264e-01 -1.114988e-01 -2.080615e+01 -9.950323e-01 2.454999e-03 9.952258e-02 1.557215e+02 +9.406476e-02 1.050531e-01 9.900078e-01 2.535136e+02 -1.083401e-02 9.944661e-01 -1.044968e-01 -2.089449e+01 -9.955072e-01 -8.962934e-04 9.468236e-02 1.558057e+02 +8.875950e-02 1.013125e-01 9.908872e-01 2.544024e+02 -1.243372e-02 9.948488e-01 -1.006038e-01 -2.098217e+01 -9.959755e-01 -3.390874e-03 8.956197e-02 1.558813e+02 +8.239821e-02 1.009633e-01 9.914720e-01 2.552821e+02 -1.617835e-02 9.948595e-01 -9.996378e-02 -2.106516e+01 -9.964682e-01 -7.803544e-03 8.360806e-02 1.559558e+02 +7.516193e-02 9.907144e-02 9.922376e-01 2.561621e+02 -2.012641e-02 9.950002e-01 -9.782273e-02 -2.114494e+01 -9.969682e-01 -1.261764e-02 7.678010e-02 1.560255e+02 +6.775378e-02 9.475242e-02 9.931924e-01 2.570428e+02 -2.362694e-02 9.953532e-01 -9.334679e-02 -2.122381e+01 -9.974223e-01 -1.714150e-02 6.967765e-02 1.560897e+02 +6.045093e-02 9.080372e-02 9.940323e-01 2.579199e+02 -2.544022e-02 9.956702e-01 -8.940624e-02 -2.130232e+01 -9.978470e-01 -1.988371e-02 6.249926e-02 1.561451e+02 +5.393239e-02 9.298377e-02 9.942058e-01 2.587907e+02 -2.106591e-02 9.955392e-01 -9.196574e-02 -2.137550e+01 -9.983224e-01 -1.598391e-02 5.565060e-02 1.561854e+02 +4.757742e-02 9.690533e-02 9.941557e-01 2.596601e+02 -1.894279e-02 9.951914e-01 -9.609975e-02 -2.144205e+01 -9.986880e-01 -1.425990e-02 4.918430e-02 1.562240e+02 +4.087781e-02 9.896300e-02 9.942511e-01 2.605270e+02 -1.649453e-02 9.950140e-01 -9.836080e-02 -2.151116e+01 -9.990280e-01 -1.237893e-02 4.230634e-02 1.562580e+02 +3.443742e-02 9.744229e-02 9.946451e-01 2.613989e+02 -1.652403e-02 9.951549e-01 -9.692014e-02 -2.158418e+01 -9.992703e-01 -1.309787e-02 3.588071e-02 1.562883e+02 +2.816779e-02 9.417738e-02 9.951568e-01 2.622717e+02 -1.736072e-02 9.954477e-01 -9.371354e-02 -2.165347e+01 -9.994525e-01 -1.463693e-02 2.967455e-02 1.563158e+02 +2.220778e-02 9.332828e-02 9.953876e-01 2.631403e+02 -1.454025e-02 9.955580e-01 -9.301987e-02 -2.172636e+01 -9.996477e-01 -1.240742e-02 2.346615e-02 1.563324e+02 +1.710884e-02 9.546598e-02 9.952856e-01 2.640060e+02 -1.239199e-02 9.953751e-01 -9.526156e-02 -2.179663e+01 -9.997769e-01 -1.070376e-02 1.821273e-02 1.563451e+02 +1.239196e-02 9.919173e-02 9.949911e-01 2.648657e+02 -1.273930e-02 9.950024e-01 -9.903421e-02 -2.186707e+01 -9.998421e-01 -1.144826e-02 1.359367e-02 1.563569e+02 +8.943048e-03 1.006318e-01 9.948835e-01 2.657295e+02 -1.000260e-02 9.948825e-01 -1.005418e-01 -2.194115e+01 -9.999100e-01 -9.052275e-03 9.903861e-03 1.563616e+02 +6.660461e-03 9.944125e-02 9.950211e-01 2.665945e+02 -4.772361e-03 9.950350e-01 -9.941072e-02 -2.201710e+01 -9.999665e-01 -4.086480e-03 7.101961e-03 1.563599e+02 +4.848032e-03 9.689815e-02 9.952824e-01 2.674594e+02 -2.860987e-03 9.952914e-01 -9.688511e-02 -2.209328e+01 -9.999842e-01 -2.377790e-03 5.102428e-03 1.563596e+02 +2.995586e-03 9.526225e-02 9.954476e-01 2.683206e+02 -8.155678e-04 9.954520e-01 -9.526023e-02 -2.216749e+01 -9.999952e-01 -5.264969e-04 3.059654e-03 1.563531e+02 +1.306964e-03 9.412386e-02 9.955596e-01 2.691826e+02 1.142220e-03 9.955596e-01 -9.412539e-02 -2.224240e+01 -9.999985e-01 1.260164e-03 1.193650e-03 1.563491e+02 +3.884868e-04 9.592333e-02 9.953886e-01 2.700395e+02 3.445441e-03 9.953826e-01 -9.592412e-02 -2.231694e+01 -9.999940e-01 3.466815e-03 5.619441e-05 1.563437e+02 +-1.476633e-04 9.735673e-02 9.952495e-01 2.708934e+02 5.270039e-03 9.952357e-01 -9.735462e-02 -2.239231e+01 -9.999861e-01 5.230625e-03 -6.600340e-04 1.563409e+02 +4.131730e-04 9.896354e-02 9.950909e-01 2.717439e+02 8.805307e-03 9.950520e-01 -9.896335e-02 -2.246937e+01 -9.999612e-01 8.802966e-03 -4.602761e-04 1.563340e+02 +1.492866e-03 9.988379e-02 9.949979e-01 2.725882e+02 1.065649e-02 9.949409e-01 -9.989408e-02 -2.255275e+01 -9.999421e-01 1.075231e-02 4.209030e-04 1.563300e+02 +2.918794e-03 1.000762e-01 9.949754e-01 2.734367e+02 1.201711e-02 9.949043e-01 -1.001044e-01 -2.263729e+01 -9.999236e-01 1.224891e-02 1.701293e-03 1.563283e+02 +4.793049e-03 9.980382e-02 9.949955e-01 2.742406e+02 1.397223e-02 9.949031e-01 -9.986188e-02 -2.271743e+01 -9.998909e-01 1.438095e-02 3.374137e-03 1.563276e+02 +7.215725e-03 9.861120e-02 9.950998e-01 2.750562e+02 1.484922e-02 9.950054e-01 -9.870955e-02 -2.279801e+01 -9.998637e-01 1.548871e-02 5.715386e-03 1.563301e+02 +9.870523e-03 9.634341e-02 9.952991e-01 2.758616e+02 1.563907e-02 9.952110e-01 -9.648999e-02 -2.287783e+01 -9.998290e-01 1.651795e-02 8.316532e-03 1.563361e+02 +1.298051e-02 9.328545e-02 9.955547e-01 2.766656e+02 1.561146e-02 9.954983e-01 -9.348373e-02 -2.295477e+01 -9.997939e-01 1.675553e-02 1.146576e-02 1.563455e+02 +1.635965e-02 9.038495e-02 9.957724e-01 2.774484e+02 1.476380e-02 9.957753e-01 -9.062779e-02 -2.302961e+01 -9.997572e-01 1.618401e-02 1.495611e-02 1.563596e+02 +1.989448e-02 8.828070e-02 9.958969e-01 2.782238e+02 1.298542e-02 9.959872e-01 -8.854813e-02 -2.310166e+01 -9.997178e-01 1.469376e-02 1.866829e-02 1.563778e+02 +2.360367e-02 8.872324e-02 9.957765e-01 2.789862e+02 8.346178e-03 9.960018e-01 -8.894116e-02 -2.317205e+01 -9.996866e-01 1.041026e-02 2.276880e-02 1.564029e+02 +2.734546e-02 9.000245e-02 9.955660e-01 2.797382e+02 5.628650e-03 9.959088e-01 -9.018806e-02 -2.323843e+01 -9.996102e-01 8.069923e-03 2.672699e-02 1.564295e+02 +3.148095e-02 9.015983e-02 9.954295e-01 2.804806e+02 5.682488e-03 9.958909e-01 -9.038135e-02 -2.330168e+01 -9.994882e-01 8.501804e-03 3.083926e-02 1.564550e+02 +3.510286e-02 8.734102e-02 9.955597e-01 2.812202e+02 4.614952e-03 9.961489e-01 -8.755545e-02 -2.336731e+01 -9.993731e-01 7.667904e-03 3.456460e-02 1.564848e+02 +3.826068e-02 8.410351e-02 9.957221e-01 2.819382e+02 2.804072e-03 9.964388e-01 -8.427180e-02 -2.343189e+01 -9.992639e-01 6.016370e-03 3.788859e-02 1.565202e+02 +4.196265e-02 8.211682e-02 9.957388e-01 2.826515e+02 -7.378172e-04 9.966189e-01 -8.215833e-02 -2.349597e+01 -9.991189e-01 2.712906e-03 4.188136e-02 1.565600e+02 +4.598351e-02 8.363717e-02 9.954347e-01 2.833383e+02 1.450858e-03 9.964821e-01 -8.379222e-02 -2.355164e+01 -9.989412e-01 5.297292e-03 4.570040e-02 1.565937e+02 +4.981478e-02 8.490538e-02 9.951429e-01 2.840121e+02 9.564078e-04 9.963754e-01 -8.505843e-02 -2.361050e+01 -9.987580e-01 5.188927e-03 4.955302e-02 1.566340e+02 +5.315016e-02 8.696359e-02 9.947926e-01 2.846753e+02 3.544211e-04 9.961990e-01 -8.710549e-02 -2.366960e+01 -9.985865e-01 4.982244e-03 5.291732e-02 1.566761e+02 +5.619304e-02 8.942614e-02 9.944069e-01 2.853276e+02 -6.545837e-04 9.959837e-01 -8.953096e-02 -2.372680e+01 -9.984197e-01 4.380092e-03 5.602589e-02 1.567166e+02 +5.922029e-02 8.988187e-02 9.941901e-01 2.859670e+02 -4.209716e-03 9.959517e-01 -8.979039e-02 -2.378128e+01 -9.982361e-01 1.132152e-03 5.935893e-02 1.567616e+02 +6.238687e-02 9.037044e-02 9.939522e-01 2.865937e+02 -6.356971e-03 9.959079e-01 -9.014927e-02 -2.383446e+01 -9.980318e-01 -6.943966e-04 6.270606e-02 1.568069e+02 +6.586665e-02 9.151821e-02 9.936226e-01 2.872092e+02 -7.837117e-03 9.958017e-01 -9.119942e-02 -2.389017e+01 -9.977977e-01 -1.780139e-03 6.630736e-02 1.568523e+02 +6.883180e-02 8.959867e-02 9.935965e-01 2.878108e+02 -9.041925e-03 9.959738e-01 -8.918668e-02 -2.394344e+01 -9.975873e-01 -2.845148e-03 6.936481e-02 1.568983e+02 +7.240766e-02 9.171733e-02 9.931490e-01 2.884106e+02 -9.505547e-03 9.957810e-01 -9.126739e-02 -2.399582e+01 -9.973299e-01 -2.831968e-03 7.297399e-02 1.569431e+02 +7.498782e-02 9.437462e-02 9.927085e-01 2.889746e+02 -1.271679e-02 9.955209e-01 -9.368141e-02 -2.404626e+01 -9.971034e-01 -5.599100e-03 7.585209e-02 1.569918e+02 +7.748816e-02 9.419449e-02 9.925335e-01 2.895493e+02 -1.441353e-02 9.955286e-01 -9.335347e-02 -2.410169e+01 -9.968891e-01 -7.072121e-03 7.849936e-02 1.570416e+02 +8.078990e-02 9.339951e-02 9.923454e-01 2.901099e+02 -1.566925e-02 9.955958e-01 -9.242978e-02 -2.415117e+01 -9.966080e-01 -8.081919e-03 8.189758e-02 1.570886e+02 +8.371397e-02 9.363229e-02 9.920810e-01 2.906604e+02 -1.686057e-02 9.955663e-01 -9.253851e-02 -2.419669e+01 -9.963472e-01 -8.980292e-03 8.492150e-02 1.571342e+02 +8.663261e-02 9.365735e-02 9.918281e-01 2.911990e+02 -1.710046e-02 9.955642e-01 -9.251650e-02 -2.424004e+01 -9.960936e-01 -8.945774e-03 8.784991e-02 1.571804e+02 +8.964866e-02 9.529768e-02 9.914037e-01 2.917281e+02 -1.806414e-02 9.954036e-01 -9.404872e-02 -2.428194e+01 -9.958097e-01 -9.477513e-03 9.095807e-02 1.572288e+02 +9.215738e-02 9.591684e-02 9.911139e-01 2.922488e+02 -1.891062e-02 9.953388e-01 -9.456734e-02 -2.432193e+01 -9.955649e-01 -1.002750e-02 9.354166e-02 1.572772e+02 +9.465993e-02 9.701353e-02 9.907713e-01 2.927596e+02 -1.786123e-02 9.952455e-01 -9.574516e-02 -2.436116e+01 -9.953495e-01 -8.633167e-03 9.594266e-02 1.573242e+02 +9.679969e-02 9.870160e-02 9.903977e-01 2.932587e+02 -1.898933e-02 9.950727e-01 -9.731153e-02 -2.440494e+01 -9.951228e-01 -9.387263e-03 9.819701e-02 1.573722e+02 +9.834348e-02 9.989360e-02 9.901261e-01 2.937527e+02 -1.992185e-02 9.949473e-01 -9.840131e-02 -2.444767e+01 -9.949531e-01 -1.004802e-02 9.983664e-02 1.574213e+02 +9.976809e-02 1.014255e-01 9.898278e-01 2.942374e+02 -2.065299e-02 9.947878e-01 -9.985206e-02 -2.449148e+01 -9.947964e-01 -1.048085e-02 1.013428e-01 1.574678e+02 +1.007501e-01 1.026575e-01 9.896013e-01 2.947246e+02 -2.120281e-02 9.946580e-01 -1.010234e-01 -2.453746e+01 -9.946858e-01 -1.080421e-02 1.023885e-01 1.575174e+02 +1.008718e-01 1.031887e-01 9.895336e-01 2.952096e+02 -2.039731e-02 9.946121e-01 -1.016390e-01 -2.458496e+01 -9.946904e-01 -9.931315e-03 1.024331e-01 1.575670e+02 +1.002965e-01 1.036965e-01 9.895390e-01 2.957020e+02 -2.090760e-02 9.945540e-01 -1.021029e-01 -2.463307e+01 -9.947379e-01 -1.044832e-02 1.019183e-01 1.576170e+02 +9.926632e-02 1.029983e-01 9.897158e-01 2.961993e+02 -2.246840e-02 9.946068e-01 -1.012538e-01 -2.467824e+01 -9.948072e-01 -1.218624e-02 1.010452e-01 1.576689e+02 +9.780866e-02 1.018172e-01 9.899831e-01 2.967013e+02 -2.305459e-02 9.947176e-01 -1.000264e-01 -2.472333e+01 -9.949382e-01 -1.304020e-02 9.963935e-02 1.577197e+02 +9.593365e-02 1.025233e-01 9.900937e-01 2.972090e+02 -2.124570e-02 9.946657e-01 -1.009382e-01 -2.477055e+01 -9.951610e-01 -1.135187e-02 9.760010e-02 1.577654e+02 +9.405200e-02 1.058972e-01 9.899191e-01 2.977199e+02 -1.840470e-02 9.943417e-01 -1.046217e-01 -2.482169e+01 -9.953972e-01 -8.379288e-03 9.546883e-02 1.578091e+02 +9.260036e-02 1.091591e-01 9.897016e-01 2.982403e+02 -1.321807e-02 9.940196e-01 -1.083986e-01 -2.487488e+01 -9.956157e-01 -3.044198e-03 9.348944e-02 1.578477e+02 +9.036216e-02 1.143786e-01 9.893190e-01 2.987679e+02 -1.039326e-02 9.934372e-01 -1.139055e-01 -2.492374e+01 -9.958548e-01 1.048919e-05 9.095790e-02 1.578894e+02 +8.787483e-02 1.180023e-01 9.891174e-01 2.993114e+02 -1.130602e-02 9.930129e-01 -1.174626e-01 -2.496956e+01 -9.960674e-01 -8.609784e-04 8.859498e-02 1.579364e+02 +8.575183e-02 1.181163e-01 9.892901e-01 2.998664e+02 -1.111031e-02 9.929993e-01 -1.175962e-01 -2.502054e+01 -9.962546e-01 -9.072382e-04 8.646381e-02 1.579801e+02 +8.426795e-02 1.151518e-01 9.897671e-01 3.004328e+02 -6.534590e-03 9.933426e-01 -1.150114e-01 -2.508500e+01 -9.964217e-01 3.224053e-03 8.445941e-02 1.580169e+02 +8.343147e-02 1.088990e-01 9.905453e-01 3.010133e+02 2.473078e-03 9.939852e-01 -1.094855e-01 -2.515046e+01 -9.965105e-01 1.158423e-02 8.266033e-02 1.580468e+02 +8.139896e-02 1.087770e-01 9.907278e-01 3.015988e+02 3.792299e-03 9.939854e-01 -1.094462e-01 -2.521321e+01 -9.966744e-01 1.266594e-02 8.049687e-02 1.580882e+02 +7.827110e-02 1.124281e-01 9.905723e-01 3.021893e+02 -6.016215e-04 9.936257e-01 -1.127271e-01 -2.527483e+01 -9.969320e-01 8.227323e-03 7.783981e-02 1.581416e+02 +7.616432e-02 1.140868e-01 9.905468e-01 3.027896e+02 -3.335015e-03 9.934561e-01 -1.141654e-01 -2.533868e+01 -9.970897e-01 5.391842e-03 7.604638e-02 1.581930e+02 +7.521955e-02 1.120311e-01 9.908536e-01 3.034095e+02 1.847027e-03 9.936513e-01 -1.124876e-01 -2.540269e+01 -9.971653e-01 1.029140e-02 7.453508e-02 1.582314e+02 +7.426643e-02 1.111381e-01 9.910261e-01 3.040385e+02 6.830937e-03 9.936904e-01 -1.119489e-01 -2.546722e+01 -9.972151e-01 1.508367e-02 7.303866e-02 1.582678e+02 +7.250130e-02 1.104748e-01 9.912309e-01 3.046811e+02 7.489698e-03 9.937581e-01 -1.113043e-01 -2.553204e+01 -9.973402e-01 1.549372e-02 7.122133e-02 1.583096e+02 +6.983813e-02 1.121359e-01 9.912356e-01 3.053328e+02 3.889924e-03 9.936236e-01 -1.126801e-01 -2.559815e+01 -9.975508e-01 1.172520e-02 6.895661e-02 1.583588e+02 +6.772387e-02 1.131934e-01 9.912621e-01 3.059952e+02 1.301164e-03 9.935323e-01 -1.135416e-01 -2.566221e+01 -9.977033e-01 8.979264e-03 6.713857e-02 1.584057e+02 +6.629428e-02 1.175675e-01 9.908495e-01 3.066661e+02 1.256886e-03 9.930235e-01 -1.179096e-01 -2.572467e+01 -9.977994e-01 9.062113e-03 6.568401e-02 1.584467e+02 +6.452438e-02 1.190950e-01 9.907839e-01 3.073491e+02 2.360926e-03 9.928319e-01 -1.194949e-01 -2.579503e+01 -9.979134e-01 1.004950e-02 6.378068e-02 1.584838e+02 +6.256863e-02 1.180965e-01 9.910289e-01 3.080487e+02 -1.239109e-03 9.929829e-01 -1.182511e-01 -2.586821e+01 -9.980399e-01 6.170813e-03 6.227591e-02 1.585319e+02 +6.062733e-02 1.170197e-01 9.912772e-01 3.087476e+02 -4.908244e-03 9.931270e-01 -1.169379e-01 -2.594126e+01 -9.981484e-01 2.224202e-03 6.078500e-02 1.585802e+02 +5.847112e-02 1.188269e-01 9.911918e-01 3.094569e+02 -5.443540e-03 9.929137e-01 -1.187122e-01 -2.601685e+01 -9.982743e-01 1.545642e-03 5.870361e-02 1.586244e+02 +5.713243e-02 1.229182e-01 9.907708e-01 3.101745e+02 -2.094116e-03 9.924044e-01 -1.230001e-01 -2.609606e+01 -9.983644e-01 4.952504e-03 5.695588e-02 1.586611e+02 +5.565177e-02 1.291976e-01 9.900559e-01 3.108972e+02 -5.022675e-04 9.915961e-01 -1.293704e-01 -2.617480e+01 -9.984501e-01 6.702417e-03 5.524897e-02 1.586982e+02 +5.430244e-02 1.332636e-01 9.895918e-01 3.116329e+02 -4.975636e-04 9.910575e-01 -1.334337e-01 -2.625448e+01 -9.985244e-01 6.753389e-03 5.388315e-02 1.587386e+02 +5.391789e-02 1.304135e-01 9.899924e-01 3.123814e+02 3.792934e-03 9.914007e-01 -1.308056e-01 -2.634091e+01 -9.985382e-01 1.080773e-02 5.295959e-02 1.587711e+02 +5.332015e-02 1.240819e-01 9.908383e-01 3.131397e+02 8.682950e-03 9.921547e-01 -1.247140e-01 -2.643175e+01 -9.985398e-01 1.525316e-02 5.182444e-02 1.588018e+02 +5.222614e-02 1.214984e-01 9.912166e-01 3.139052e+02 1.168147e-02 9.924290e-01 -1.222625e-01 -2.652053e+01 -9.985670e-01 1.796416e-02 5.041146e-02 1.588338e+02 +5.113628e-02 1.227066e-01 9.911246e-01 3.146762e+02 1.394691e-02 9.922385e-01 -1.235641e-01 -2.660789e+01 -9.985943e-01 2.014173e-02 4.902800e-02 1.588676e+02 +5.044464e-02 1.246398e-01 9.909188e-01 3.154536e+02 1.463580e-02 9.919832e-01 -1.255188e-01 -2.669381e+01 -9.986196e-01 2.083464e-02 4.821603e-02 1.589033e+02 +4.997089e-02 1.255290e-01 9.908306e-01 3.162406e+02 1.586639e-02 9.918450e-01 -1.264577e-01 -2.678025e+01 -9.986247e-01 2.204011e-02 4.757169e-02 1.589387e+02 +5.009590e-02 1.245794e-01 9.909441e-01 3.170373e+02 1.627108e-02 9.919564e-01 -1.255293e-01 -2.687072e+01 -9.986119e-01 2.241222e-02 4.766591e-02 1.589755e+02 +5.096456e-02 1.227630e-01 9.911265e-01 3.178436e+02 1.686391e-02 9.921689e-01 -1.237593e-01 -2.696318e+01 -9.985581e-01 2.302160e-02 4.849518e-02 1.590134e+02 +5.201746e-02 1.218305e-01 9.911868e-01 3.186531e+02 1.741029e-02 9.922691e-01 -1.228772e-01 -2.705549e+01 -9.984944e-01 2.364860e-02 4.949421e-02 1.590532e+02 +5.328914e-02 1.204013e-01 9.912939e-01 3.194779e+02 1.732402e-02 9.924436e-01 -1.214722e-01 -2.714548e+01 -9.984289e-01 2.364634e-02 5.080063e-02 1.590967e+02 +5.454453e-02 1.189726e-01 9.913981e-01 3.203018e+02 1.721411e-02 9.926166e-01 -1.200659e-01 -2.723538e+01 -9.983630e-01 2.361497e-02 5.209380e-02 1.591401e+02 +5.657803e-02 1.175706e-01 9.914514e-01 3.211391e+02 1.830567e-02 9.927530e-01 -1.187696e-01 -2.732655e+01 -9.982304e-01 2.486893e-02 5.401580e-02 1.591855e+02 +5.867949e-02 1.161298e-01 9.914991e-01 3.219833e+02 1.971585e-02 9.928820e-01 -1.174586e-01 -2.741810e+01 -9.980822e-01 2.644065e-02 5.597221e-02 1.592317e+02 +6.060118e-02 1.157836e-01 9.914240e-01 3.228344e+02 2.023431e-02 9.929029e-01 -1.171931e-01 -2.750858e+01 -9.979570e-01 2.716282e-02 5.782829e-02 1.592816e+02 +6.327043e-02 1.161945e-01 9.912091e-01 3.236909e+02 2.143224e-02 9.928118e-01 -1.177504e-01 -2.759901e+01 -9.977663e-01 2.869394e-02 6.032533e-02 1.593323e+02 +6.625425e-02 1.150114e-01 9.911521e-01 3.245567e+02 2.284912e-02 9.928994e-01 -1.167416e-01 -2.768936e+01 -9.975412e-01 3.038158e-02 6.315589e-02 1.593854e+02 +6.917695e-02 1.139790e-01 9.910717e-01 3.254350e+02 2.437491e-02 9.929619e-01 -1.158978e-01 -2.778207e+01 -9.973066e-01 3.217473e-02 6.591185e-02 1.594432e+02 +7.209766e-02 1.129565e-01 9.909806e-01 3.263133e+02 2.588720e-02 9.930197e-01 -1.150723e-01 -2.787480e+01 -9.970616e-01 3.395015e-02 6.867027e-02 1.595010e+02 +7.513682e-02 1.134846e-01 9.906945e-01 3.271990e+02 2.631868e-02 9.929311e-01 -1.157369e-01 -2.796791e+01 -9.968259e-01 3.476987e-02 7.161892e-02 1.595617e+02 +7.817080e-02 1.142752e-01 9.903688e-01 3.280932e+02 2.733506e-02 9.927895e-01 -1.167121e-01 -2.806283e+01 -9.965652e-01 3.619527e-02 7.448343e-02 1.596224e+02 +8.109190e-02 1.153438e-01 9.900100e-01 3.289883e+02 2.664118e-02 9.926755e-01 -1.178366e-01 -2.815786e+01 -9.963506e-01 3.593062e-02 7.742504e-02 1.596885e+02 +8.374685e-02 1.164910e-01 9.896546e-01 3.298880e+02 2.376216e-02 9.926276e-01 -1.188518e-01 -2.825775e+01 -9.962037e-01 3.346978e-02 8.036135e-02 1.597631e+02 +8.618878e-02 1.176635e-01 9.893061e-01 3.307890e+02 2.209679e-02 9.925312e-01 -1.199722e-01 -2.835861e+01 -9.960338e-01 3.220074e-02 8.294507e-02 1.598373e+02 +8.819552e-02 1.181846e-01 9.890671e-01 3.316970e+02 1.969879e-02 9.925353e-01 -1.203556e-01 -2.845992e+01 -9.959084e-01 3.009824e-02 8.520907e-02 1.599145e+02 +8.981929e-02 1.165213e-01 9.891183e-01 3.326065e+02 1.925512e-02 9.927437e-01 -1.186969e-01 -2.856250e+01 -9.957720e-01 2.970687e-02 8.692391e-02 1.599925e+02 +9.163701e-02 1.140286e-01 9.892421e-01 3.335180e+02 1.945100e-02 9.930275e-01 -1.162667e-01 -2.866639e+01 -9.956025e-01 2.989608e-02 8.878009e-02 1.600736e+02 +9.289593e-02 1.112317e-01 9.894431e-01 3.344313e+02 1.934819e-02 9.933509e-01 -1.134876e-01 -2.877189e+01 -9.954879e-01 2.968646e-02 9.012612e-02 1.601589e+02 +9.403856e-02 1.116727e-01 9.892855e-01 3.353462e+02 2.084473e-02 9.932503e-01 -1.141017e-01 -2.887348e+01 -9.953503e-01 3.135134e-02 9.107604e-02 1.602423e+02 +9.493406e-02 1.127651e-01 9.890760e-01 3.362589e+02 2.205986e-02 9.930811e-01 -1.153392e-01 -2.897212e+01 -9.952391e-01 3.276848e-02 9.178964e-02 1.603277e+02 +9.558836e-02 1.128985e-01 9.889978e-01 3.371754e+02 2.178626e-02 9.930720e-01 -1.154693e-01 -2.907108e+01 -9.951825e-01 3.258408e-02 9.246648e-02 1.604126e+02 +9.556615e-02 1.107103e-01 9.892473e-01 3.380878e+02 1.895328e-02 9.934133e-01 -1.130075e-01 -2.917312e+01 -9.952427e-01 2.954916e-02 9.283836e-02 1.605022e+02 +9.555729e-02 1.087423e-01 9.894664e-01 3.389981e+02 1.608639e-02 9.937166e-01 -1.107630e-01 -2.927516e+01 -9.952940e-01 2.650114e-02 9.320760e-02 1.605872e+02 +9.578047e-02 1.101647e-01 9.892875e-01 3.399061e+02 1.446065e-02 9.935979e-01 -1.120448e-01 -2.937509e+01 -9.952975e-01 2.503743e-02 9.357421e-02 1.606703e+02 +9.584067e-02 1.117738e-01 9.891011e-01 3.408083e+02 1.424895e-02 9.934194e-01 -1.136425e-01 -2.947693e+01 -9.952947e-01 2.498522e-02 9.361733e-02 1.607513e+02 +9.609138e-02 1.119879e-01 9.890526e-01 3.417122e+02 1.386504e-02 9.934037e-01 -1.138276e-01 -2.957782e+01 -9.952760e-01 2.465110e-02 9.390482e-02 1.608345e+02 +9.604387e-02 1.127033e-01 9.889759e-01 3.426161e+02 1.237417e-02 9.933571e-01 -1.144043e-01 -2.968020e+01 -9.953002e-01 2.322558e-02 9.401125e-02 1.609116e+02 +9.618510e-02 1.131048e-01 9.889164e-01 3.435205e+02 1.283903e-02 9.932992e-01 -1.148548e-01 -2.978018e+01 -9.952807e-01 2.374405e-02 9.408843e-02 1.609891e+02 +9.651481e-02 1.128235e-01 9.889164e-01 3.444236e+02 1.238225e-02 9.933418e-01 -1.145368e-01 -2.987756e+01 -9.952546e-01 2.329951e-02 9.447518e-02 1.610668e+02 +9.676099e-02 1.117265e-01 9.890169e-01 3.453276e+02 1.349316e-02 9.934410e-01 -1.135464e-01 -2.997769e+01 -9.952162e-01 2.433182e-02 9.461879e-02 1.611449e+02 +9.704748e-02 1.119951e-01 9.889584e-01 3.462235e+02 1.235480e-02 9.934366e-01 -1.137146e-01 -3.007709e+01 -9.952031e-01 2.325410e-02 9.502684e-02 1.612272e+02 +9.709422e-02 1.154493e-01 9.885565e-01 3.471167e+02 1.227950e-02 9.930349e-01 -1.171784e-01 -3.017753e+01 -9.951995e-01 2.351632e-02 9.500029e-02 1.613076e+02 +9.833792e-02 1.159032e-01 9.883805e-01 3.480099e+02 1.569985e-02 9.928901e-01 -1.179941e-01 -3.027574e+01 -9.950293e-01 2.712072e-02 9.581908e-02 1.613912e+02 +9.958608e-02 1.127523e-01 9.886199e-01 3.489065e+02 1.834286e-02 9.931821e-01 -1.151203e-01 -3.037548e+01 -9.948599e-01 2.959849e-02 9.683891e-02 1.614741e+02 +1.015405e-01 1.105410e-01 9.886709e-01 3.498059e+02 2.064777e-02 9.933592e-01 -1.131858e-01 -3.047413e+01 -9.946171e-01 3.190678e-02 9.858377e-02 1.615564e+02 +1.045667e-01 1.136308e-01 9.880049e-01 3.506977e+02 2.476749e-02 9.928455e-01 -1.168088e-01 -3.056953e+01 -9.942095e-01 3.668470e-02 1.010042e-01 1.616370e+02 +1.076221e-01 1.166956e-01 9.873193e-01 3.515901e+02 2.888635e-02 9.923010e-01 -1.204332e-01 -3.066501e+01 -9.937722e-01 4.148131e-02 1.034226e-01 1.617177e+02 +1.107003e-01 1.198682e-01 9.865986e-01 3.524825e+02 3.306623e-02 9.917062e-01 -1.241990e-01 -3.076035e+01 -9.933036e-01 4.637195e-02 1.058186e-01 1.617983e+02 +1.139344e-01 1.182988e-01 9.864199e-01 3.533785e+02 3.497157e-02 9.917924e-01 -1.229824e-01 -3.086050e+01 -9.928726e-01 4.850858e-02 1.088622e-01 1.618840e+02 +1.172720e-01 1.189627e-01 9.859488e-01 3.542731e+02 3.631767e-02 9.916214e-01 -1.239669e-01 -3.096097e+01 -9.924356e-01 5.034520e-02 1.119690e-01 1.619694e+02 +1.204753e-01 1.198291e-01 9.854575e-01 3.551700e+02 3.678917e-02 9.914671e-01 -1.250575e-01 -3.105569e+01 -9.920344e-01 5.132049e-02 1.150389e-01 1.620527e+02 +1.239344e-01 1.210330e-01 9.848813e-01 3.560658e+02 3.688766e-02 9.912853e-01 -1.264618e-01 -3.114982e+01 -9.916046e-01 5.200293e-02 1.183897e-01 1.621440e+02 +1.277618e-01 1.160830e-01 9.849881e-01 3.569660e+02 3.613260e-02 9.919228e-01 -1.215871e-01 -3.124424e+01 -9.911465e-01 5.112436e-02 1.225355e-01 1.622399e+02 +1.318728e-01 1.125377e-01 9.848577e-01 3.578634e+02 3.352562e-02 9.924598e-01 -1.178955e-01 -3.134268e+01 -9.906996e-01 4.856516e-02 1.271055e-01 1.623464e+02 +1.365953e-01 1.115372e-01 9.843277e-01 3.587644e+02 3.175280e-02 9.926376e-01 -1.168852e-01 -3.143232e+01 -9.901179e-01 4.722112e-02 1.320481e-01 1.624482e+02 +1.413442e-01 1.105499e-01 9.837685e-01 3.596666e+02 2.997660e-02 9.928115e-01 -1.158730e-01 -3.152203e+01 -9.895066e-01 4.586800e-02 1.370142e-01 1.625502e+02 +1.466974e-01 1.095166e-01 9.831001e-01 3.605743e+02 2.815798e-02 9.929871e-01 -1.148197e-01 -3.160985e+01 -9.887806e-01 4.452585e-02 1.425848e-01 1.626543e+02 +1.529007e-01 1.095949e-01 9.821457e-01 3.614763e+02 2.681702e-02 9.930055e-01 -1.149816e-01 -3.169958e+01 -9.878777e-01 4.391898e-02 1.488922e-01 1.627695e+02 +1.599654e-01 1.106391e-01 9.809026e-01 3.623757e+02 2.478776e-02 9.929353e-01 -1.160387e-01 -3.179176e+01 -9.868114e-01 4.287654e-02 1.560928e-01 1.628963e+02 +1.685298e-01 1.116793e-01 9.793494e-01 3.632722e+02 2.252629e-02 9.928649e-01 -1.170969e-01 -3.188456e+01 -9.854392e-01 4.179542e-02 1.648116e-01 1.630348e+02 +1.770761e-01 1.127470e-01 9.777178e-01 3.641687e+02 2.026468e-02 9.927883e-01 -1.181550e-01 -3.197736e+01 -9.839885e-01 4.073556e-02 1.735143e-01 1.631733e+02 +1.864249e-01 1.131781e-01 9.759284e-01 3.650628e+02 1.850031e-02 9.927620e-01 -1.186643e-01 -3.207264e+01 -9.822950e-01 4.017695e-02 1.829817e-01 1.633230e+02 +1.956206e-01 1.130345e-01 9.741435e-01 3.659547e+02 1.678754e-02 9.928036e-01 -1.185709e-01 -3.216864e+01 -9.805360e-01 3.954838e-02 1.923152e-01 1.634848e+02 +2.048510e-01 1.131498e-01 9.722310e-01 3.668412e+02 1.487984e-02 9.928208e-01 -1.186813e-01 -3.226554e+01 -9.786801e-01 3.877862e-02 2.016967e-01 1.636594e+02 +2.135395e-01 1.128075e-01 9.703995e-01 3.677270e+02 1.273175e-02 9.929051e-01 -1.182255e-01 -3.236548e+01 -9.768515e-01 3.760068e-02 2.105882e-01 1.638508e+02 +2.217370e-01 1.125311e-01 9.685914e-01 3.686005e+02 1.125072e-02 9.929572e-01 -1.179376e-01 -3.246696e+01 -9.750416e-01 3.704847e-02 2.189093e-01 1.640490e+02 +2.285522e-01 1.122576e-01 9.670377e-01 3.694767e+02 9.226360e-03 9.930351e-01 -1.174561e-01 -3.256385e+01 -9.734880e-01 3.576708e-02 2.259246e-01 1.642602e+02 +2.343612e-01 1.124992e-01 9.656182e-01 3.703486e+02 7.947360e-03 9.930266e-01 -1.176213e-01 -3.265824e+01 -9.721171e-01 3.523999e-02 2.318328e-01 1.644754e+02 +2.394172e-01 1.132440e-01 9.642899e-01 3.712200e+02 6.456768e-03 9.929670e-01 -1.182149e-01 -3.275253e+01 -9.708953e-01 3.452888e-02 2.370022e-01 1.646956e+02 +2.439934e-01 1.128580e-01 9.631875e-01 3.720932e+02 5.688206e-03 9.930216e-01 -1.177947e-01 -3.284871e+01 -9.697602e-01 3.421993e-02 2.416487e-01 1.649156e+02 +2.485591e-01 1.130185e-01 9.620005e-01 3.729644e+02 4.561648e-03 9.930218e-01 -1.178416e-01 -3.294965e+01 -9.686060e-01 3.367890e-02 2.463090e-01 1.651387e+02 +2.529698e-01 1.126934e-01 9.608883e-01 3.738419e+02 4.461847e-03 9.930463e-01 -1.176395e-01 -3.304904e+01 -9.674639e-01 3.404658e-02 2.507079e-01 1.653620e+02 +2.574499e-01 1.130131e-01 9.596601e-01 3.747198e+02 4.280739e-03 9.929939e-01 -1.180870e-01 -3.314733e+01 -9.662822e-01 3.450954e-02 2.551624e-01 1.655911e+02 +2.616512e-01 1.127596e-01 9.585529e-01 3.755998e+02 3.889417e-03 9.930206e-01 -1.178760e-01 -3.324711e+01 -9.651547e-01 3.457059e-02 2.593865e-01 1.658267e+02 +2.661828e-01 1.111869e-01 9.574884e-01 3.764772e+02 3.666615e-03 9.932010e-01 -1.163533e-01 -3.334844e+01 -9.639156e-01 3.448199e-02 2.639654e-01 1.660669e+02 +2.705843e-01 1.097161e-01 9.564237e-01 3.773568e+02 2.307585e-03 9.934076e-01 -1.146116e-01 -3.345186e+01 -9.626935e-01 3.321912e-02 2.685473e-01 1.663146e+02 +2.752357e-01 1.072420e-01 9.553765e-01 3.782299e+02 2.690412e-03 9.936689e-01 -1.123155e-01 -3.355204e+01 -9.613731e-01 3.348357e-02 2.732046e-01 1.665661e+02 +2.797899e-01 1.051832e-01 9.542819e-01 3.790956e+02 2.531317e-03 9.938960e-01 -1.102918e-01 -3.365147e+01 -9.600580e-01 3.327410e-02 2.778158e-01 1.668284e+02 +2.840759e-01 1.045043e-01 9.530895e-01 3.799484e+02 1.742747e-03 9.939843e-01 -1.095077e-01 -3.375068e+01 -9.588003e-01 3.276950e-02 2.821848e-01 1.670928e+02 +2.883694e-01 1.039393e-01 9.518611e-01 3.808018e+02 9.181531e-04 9.940604e-01 -1.088254e-01 -3.385006e+01 -9.575188e-01 3.225586e-02 2.865611e-01 1.673575e+02 +2.929533e-01 1.074307e-01 9.500720e-01 3.816460e+02 -1.215826e-03 9.937085e-01 -1.119901e-01 -3.394947e+01 -9.561260e-01 3.165274e-02 2.912408e-01 1.676218e+02 +2.972749e-01 1.107134e-01 9.483512e-01 3.824797e+02 -3.855091e-03 9.933854e-01 -1.147624e-01 -3.405166e+01 -9.547842e-01 3.046000e-02 2.957353e-01 1.678984e+02 +3.013338e-01 1.109379e-01 9.470431e-01 3.833184e+02 -5.334055e-03 9.933893e-01 -1.146698e-01 -3.415042e+01 -9.535038e-01 2.950229e-02 2.999335e-01 1.681718e+02 +3.045009e-01 1.068686e-01 9.464978e-01 3.841565e+02 -7.518452e-03 9.939247e-01 -1.098048e-01 -3.424855e+01 -9.524824e-01 2.631946e-02 3.034545e-01 1.684494e+02 +3.067000e-01 1.042673e-01 9.460779e-01 3.849855e+02 -1.092571e-02 9.943017e-01 -1.060402e-01 -3.434893e+01 -9.517436e-01 2.218595e-02 3.060915e-01 1.687309e+02 +3.080226e-01 1.058548e-01 9.454717e-01 3.858082e+02 -1.552208e-02 9.942176e-01 -1.062555e-01 -3.444909e+01 -9.512524e-01 1.805340e-02 3.078846e-01 1.690139e+02 +3.087888e-01 1.109555e-01 9.446366e-01 3.866213e+02 -1.770889e-02 9.936708e-01 -1.109262e-01 -3.454404e+01 -9.509658e-01 1.752430e-02 3.087993e-01 1.692932e+02 +3.095370e-01 1.160975e-01 9.437733e-01 3.874349e+02 -1.989768e-02 9.930920e-01 -1.156385e-01 -3.463900e+01 -9.506792e-01 1.701548e-02 3.097088e-01 1.695726e+02 +3.099305e-01 1.164118e-01 9.436054e-01 3.882465e+02 -2.175266e-02 9.930842e-01 -1.153712e-01 -3.473778e+01 -9.505104e-01 1.523112e-02 3.103193e-01 1.698564e+02 +3.099903e-01 1.123501e-01 9.440780e-01 3.890518e+02 -2.463686e-02 9.936090e-01 -1.101550e-01 -3.483651e+01 -9.504205e-01 1.088786e-02 3.107771e-01 1.701379e+02 +3.100776e-01 1.082620e-01 9.445269e-01 3.898585e+02 -2.754216e-02 9.941010e-01 -1.049024e-01 -3.493537e+01 -9.503123e-01 6.513568e-03 3.112302e-01 1.704198e+02 +3.100444e-01 1.064960e-01 9.447386e-01 3.906508e+02 -2.875904e-02 9.943022e-01 -1.026450e-01 -3.503121e+01 -9.502870e-01 4.654721e-03 3.113405e-01 1.706950e+02 +3.097147e-01 1.061799e-01 9.448823e-01 3.914405e+02 -2.816812e-02 9.943336e-01 -1.025039e-01 -3.512143e+01 -9.504122e-01 5.131422e-03 3.109507e-01 1.709678e+02 +3.091957e-01 1.072735e-01 9.449287e-01 3.922273e+02 -2.789587e-02 9.942130e-01 -1.037406e-01 -3.521056e+01 -9.505892e-01 5.716521e-03 3.103989e-01 1.712375e+02 +3.087797e-01 1.082195e-01 9.449569e-01 3.930148e+02 -2.807721e-02 9.941101e-01 -1.046741e-01 -3.529819e+01 -9.507191e-01 5.789476e-03 3.099995e-01 1.715035e+02 +3.086937e-01 1.038425e-01 9.454759e-01 3.938158e+02 -2.176814e-02 9.945335e-01 -1.021234e-01 -3.537808e+01 -9.509124e-01 1.094358e-02 3.092667e-01 1.717624e+02 +3.087881e-01 1.026505e-01 9.455753e-01 3.946157e+02 -2.064637e-02 9.946482e-01 -1.012355e-01 -3.545946e+01 -9.509068e-01 1.173761e-02 3.092548e-01 1.720196e+02 +3.080547e-01 1.044962e-01 9.456123e-01 3.954044e+02 -2.125178e-02 9.944573e-01 -1.029707e-01 -3.554302e+01 -9.511313e-01 1.162466e-02 3.085680e-01 1.722841e+02 +3.079967e-01 1.097057e-01 9.450410e-01 3.961902e+02 -1.930875e-02 9.938455e-01 -1.090784e-01 -3.562299e+01 -9.511915e-01 1.534821e-02 3.082194e-01 1.725390e+02 +3.081961e-01 1.146509e-01 9.443888e-01 3.969791e+02 -1.709520e-02 9.932183e-01 -1.150000e-01 -3.570992e+01 -9.511693e-01 1.929803e-02 3.080660e-01 1.727964e+02 +3.071199e-01 1.123495e-01 9.450158e-01 3.977804e+02 -1.939441e-02 9.935396e-01 -1.118154e-01 -3.579994e+01 -9.514732e-01 1.601270e-02 3.073147e-01 1.730637e+02 +3.069887e-01 1.090161e-01 9.454487e-01 3.985862e+02 -1.889642e-02 9.939201e-01 -1.084695e-01 -3.589106e+01 -9.515256e-01 1.543331e-02 3.071822e-01 1.733316e+02 +3.066595e-01 1.093771e-01 9.455139e-01 3.993940e+02 -1.962407e-02 9.938908e-01 -1.086087e-01 -3.598738e+01 -9.516170e-01 1.475104e-02 3.069324e-01 1.736026e+02 +3.065987e-01 1.107902e-01 9.453690e-01 4.002054e+02 -1.973965e-02 9.937293e-01 -1.100558e-01 -3.608162e+01 -9.516342e-01 1.508171e-02 3.068631e-01 1.738740e+02 +3.070320e-01 1.138787e-01 9.448613e-01 4.010420e+02 -1.766371e-02 9.933259e-01 -1.139801e-01 -3.617291e+01 -9.515353e-01 1.830578e-02 3.069944e-01 1.741460e+02 +3.071754e-01 1.148930e-01 9.446919e-01 4.018570e+02 -1.707675e-02 9.931909e-01 -1.152388e-01 -3.626143e+01 -9.514997e-01 1.926626e-02 3.070458e-01 1.744114e+02 +3.072435e-01 1.132316e-01 9.448703e-01 4.027259e+02 -1.704133e-02 9.933912e-01 -1.135049e-01 -3.635992e+01 -9.514784e-01 1.877180e-02 3.071426e-01 1.746994e+02 +3.076335e-01 1.102631e-01 9.450945e-01 4.035400e+02 -1.612796e-02 9.937244e-01 -1.106870e-01 -3.645650e+01 -9.513683e-01 1.880856e-02 3.074812e-01 1.749704e+02 +3.081225e-01 1.099155e-01 9.449756e-01 4.043866e+02 -1.344742e-02 9.937071e-01 -1.111991e-01 -3.655987e+01 -9.512517e-01 2.155545e-02 3.076616e-01 1.752516e+02 +3.090515e-01 1.099925e-01 9.446633e-01 4.052387e+02 -8.981753e-03 9.935827e-01 -1.127501e-01 -3.665818e+01 -9.510029e-01 2.636084e-02 3.080562e-01 1.755298e+02 +3.099970e-01 1.098248e-01 9.443729e-01 4.060994e+02 -4.999210e-03 9.934802e-01 -1.138946e-01 -3.676127e+01 -9.507244e-01 3.058587e-02 3.085249e-01 1.758119e+02 +3.112264e-01 1.071204e-01 9.442792e-01 4.069522e+02 -2.457199e-03 9.937143e-01 -1.119185e-01 -3.686062e+01 -9.503326e-01 3.251172e-02 3.095334e-01 1.760920e+02 +3.130370e-01 1.064513e-01 9.437562e-01 4.078104e+02 3.684987e-03 9.935550e-01 -1.132907e-01 -3.696060e+01 -9.497338e-01 3.894190e-02 3.106272e-01 1.763696e+02 +3.145753e-01 1.046328e-01 9.434480e-01 4.086653e+02 7.761287e-03 9.935894e-01 -1.127816e-01 -3.705716e+01 -9.492008e-01 4.280068e-02 3.117466e-01 1.766545e+02 +3.147561e-01 1.020186e-01 9.436740e-01 4.095217e+02 5.657862e-03 9.939877e-01 -1.093451e-01 -3.714867e+01 -9.491557e-01 3.975620e-02 3.122865e-01 1.769473e+02 +3.147916e-01 9.585197e-02 9.443085e-01 4.103808e+02 2.725348e-03 9.947924e-01 -1.018849e-01 -3.723727e+01 -9.491569e-01 3.464606e-02 3.128911e-01 1.772463e+02 +3.157271e-01 9.375545e-02 9.442066e-01 4.112375e+02 3.742762e-03 9.949755e-01 -1.000481e-01 -3.732340e+01 -9.488427e-01 3.512183e-02 3.137898e-01 1.775323e+02 +3.162079e-01 9.345226e-02 9.440758e-01 4.120933e+02 3.873713e-03 9.950008e-01 -9.979071e-02 -3.740675e+01 -9.486820e-01 3.521168e-02 3.142651e-01 1.778160e+02 +3.166015e-01 9.692250e-02 9.435939e-01 4.129441e+02 4.488751e-03 9.946018e-01 -1.036680e-01 -3.749169e+01 -9.485480e-01 3.705698e-02 3.144574e-01 1.780918e+02 +3.175786e-01 9.840383e-02 9.431121e-01 4.138009e+02 5.871184e-03 9.943775e-01 -1.057299e-01 -3.757270e+01 -9.482138e-01 3.911472e-02 3.152152e-01 1.783624e+02 +3.184832e-01 9.679597e-02 9.429734e-01 4.146582e+02 7.814923e-03 9.944708e-01 -1.047216e-01 -3.766188e+01 -9.478963e-01 4.072133e-02 3.159658e-01 1.786362e+02 +3.191689e-01 9.344832e-02 9.430793e-01 4.155021e+02 9.577672e-03 9.947576e-01 -1.018105e-01 -3.774912e+01 -9.476495e-01 4.152723e-02 3.166007e-01 1.789073e+02 +3.192730e-01 9.231668e-02 9.431555e-01 4.163431e+02 9.134190e-03 9.948977e-01 -1.004733e-01 -3.783262e+01 -9.476188e-01 4.069338e-02 3.168008e-01 1.791783e+02 +3.189147e-01 9.299196e-02 9.432104e-01 4.171677e+02 7.689091e-03 9.948884e-01 -1.006868e-01 -3.791664e+01 -9.477523e-01 3.936291e-02 3.165695e-01 1.794502e+02 +3.186001e-01 9.339868e-02 9.432765e-01 4.179870e+02 7.158151e-03 9.948682e-01 -1.009248e-01 -3.800097e+01 -9.478622e-01 3.890676e-02 3.162966e-01 1.797220e+02 +3.181704e-01 9.085054e-02 9.436703e-01 4.187969e+02 8.749774e-03 9.950738e-01 -9.874945e-02 -3.808222e+01 -9.479932e-01 3.967604e-02 3.158081e-01 1.799864e+02 +3.172940e-01 8.815438e-02 9.442210e-01 4.196091e+02 9.535326e-03 9.953231e-01 -9.612962e-02 -3.815827e+01 -9.482793e-01 3.950479e-02 3.149694e-01 1.802456e+02 +3.162635e-01 8.641041e-02 9.447277e-01 4.204007e+02 9.263240e-03 9.955142e-01 -9.415669e-02 -3.823307e+01 -9.486262e-01 3.852955e-02 3.140443e-01 1.804990e+02 +3.151552e-01 8.608907e-02 9.451274e-01 4.211854e+02 1.034592e-02 9.955063e-01 -9.412783e-02 -3.830596e+01 -9.489838e-01 3.944308e-02 3.128483e-01 1.807477e+02 +3.141182e-01 8.772990e-02 9.453217e-01 4.219594e+02 1.226682e-02 9.952631e-01 -9.644080e-02 -3.837484e+01 -9.493047e-01 4.188989e-02 3.115541e-01 1.809889e+02 +3.127525e-01 9.238385e-02 9.453311e-01 4.227235e+02 1.166195e-02 9.948101e-01 -1.010775e-01 -3.844427e+01 -9.497631e-01 4.263663e-02 3.100520e-01 1.812296e+02 +3.113861e-01 9.733007e-02 9.452859e-01 4.234737e+02 1.036535e-02 9.943339e-01 -1.057947e-01 -3.852223e+01 -9.502270e-01 4.274121e-02 3.086129e-01 1.814720e+02 +3.099927e-01 1.023837e-01 9.452100e-01 4.242251e+02 9.030405e-03 9.938227e-01 -1.106110e-01 -3.860018e+01 -9.506961e-01 4.282423e-02 3.071532e-01 1.817147e+02 +3.091029e-01 1.030592e-01 9.454280e-01 4.249706e+02 9.261700e-03 9.937376e-01 -1.113534e-01 -3.868180e+01 -9.509835e-01 4.317592e-02 3.062127e-01 1.819531e+02 +3.075501e-01 9.898596e-02 9.463692e-01 4.257139e+02 8.422945e-03 9.942521e-01 -1.067316e-01 -3.876538e+01 -9.514947e-01 4.079652e-02 3.049485e-01 1.821916e+02 +3.064270e-01 9.419666e-02 9.472219e-01 4.264553e+02 8.217497e-03 9.947928e-01 -1.015857e-01 -3.884576e+01 -9.518587e-01 3.891240e-02 3.040573e-01 1.824274e+02 +3.058018e-01 9.277511e-02 9.475642e-01 4.271913e+02 9.999996e-03 9.948731e-01 -1.006343e-01 -3.891860e+01 -9.520427e-01 4.024980e-02 3.033063e-01 1.826547e+02 +3.052762e-01 9.325665e-02 9.476864e-01 4.279167e+02 1.177946e-02 9.947471e-01 -1.016821e-01 -3.898930e+01 -9.521910e-01 4.220436e-02 3.025741e-01 1.828782e+02 +3.050925e-01 9.545886e-02 9.475263e-01 4.286390e+02 1.185970e-02 9.945054e-01 -1.040105e-01 -3.906082e+01 -9.522489e-01 4.297018e-02 3.022840e-01 1.831044e+02 +3.049568e-01 9.658127e-02 9.474562e-01 4.293649e+02 1.199425e-02 9.943761e-01 -1.052248e-01 -3.913224e+01 -9.522907e-01 4.345302e-02 3.020833e-01 1.833307e+02 +3.050456e-01 9.657228e-02 9.474285e-01 4.300878e+02 1.380955e-02 9.942919e-01 -1.057954e-01 -3.920176e+01 -9.522377e-01 4.535598e-02 3.019707e-01 1.835566e+02 +3.052745e-01 9.748485e-02 9.472613e-01 4.308055e+02 1.498041e-02 9.941314e-01 -1.071361e-01 -3.926661e+01 -9.521466e-01 4.689628e-02 3.020226e-01 1.837827e+02 +3.051579e-01 9.762278e-02 9.472847e-01 4.315424e+02 1.541821e-02 9.940948e-01 -1.074136e-01 -3.932909e+01 -9.521770e-01 4.738354e-02 3.018507e-01 1.840151e+02 +3.053275e-01 1.002741e-01 9.469530e-01 4.322521e+02 1.451625e-02 9.938345e-01 -1.099189e-01 -3.938552e+01 -9.521368e-01 4.730747e-02 3.019894e-01 1.842421e+02 +3.054465e-01 9.994590e-02 9.469494e-01 4.329778e+02 1.539454e-02 9.938278e-01 -1.098594e-01 -3.944566e+01 -9.520848e-01 4.813400e-02 3.020227e-01 1.844755e+02 +3.058577e-01 9.861570e-02 9.469561e-01 4.337097e+02 1.521502e-02 9.939878e-01 -1.084279e-01 -3.951541e+01 -9.519557e-01 4.757145e-02 3.025184e-01 1.847061e+02 +3.068410e-01 9.687451e-02 9.468177e-01 4.344438e+02 1.626394e-02 9.941274e-01 -1.069858e-01 -3.958607e+01 -9.516218e-01 4.822662e-02 3.034635e-01 1.849369e+02 +3.082757e-01 9.496456e-02 9.465451e-01 4.351772e+02 1.641353e-02 9.943257e-01 -1.051039e-01 -3.965560e+01 -9.511555e-01 4.793712e-02 3.049678e-01 1.851676e+02 +3.098890e-01 9.297063e-02 9.462162e-01 4.358944e+02 1.698318e-02 9.945075e-01 -1.032776e-01 -3.972678e+01 -9.506211e-01 4.807433e-02 3.066080e-01 1.853968e+02 +3.115098e-01 9.165976e-02 9.458118e-01 4.365933e+02 1.686657e-02 9.946467e-01 -1.019476e-01 -3.980189e+01 -9.500933e-01 4.771026e-02 3.082962e-01 1.856247e+02 +3.133710e-01 9.253911e-02 9.451111e-01 4.372950e+02 1.523776e-02 9.946225e-01 -1.024393e-01 -3.987998e+01 -9.495086e-01 4.650289e-02 3.102757e-01 1.858583e+02 +3.152042e-01 9.389248e-02 9.443677e-01 4.379870e+02 1.372652e-02 9.945386e-01 -1.034622e-01 -3.996184e+01 -9.489246e-01 4.557459e-02 3.121939e-01 1.860948e+02 +3.172397e-01 9.467480e-02 9.436077e-01 4.386578e+02 1.331582e-02 9.944615e-01 -1.042539e-01 -4.003698e+01 -9.482519e-01 4.563837e-02 3.142220e-01 1.863220e+02 +3.190373e-01 9.454291e-02 9.430147e-01 4.393183e+02 1.207221e-02 9.945257e-01 -1.037915e-01 -4.011521e+01 -9.476653e-01 4.449761e-02 3.161495e-01 1.865498e+02 +3.202231e-01 9.348292e-02 9.427184e-01 4.399765e+02 1.073958e-02 9.946970e-01 -1.022853e-01 -4.019335e+01 -9.472813e-01 4.287852e-02 3.175210e-01 1.867754e+02 +3.212630e-01 9.210563e-02 9.425001e-01 4.406294e+02 9.453147e-03 9.948973e-01 -1.004484e-01 -4.026688e+01 -9.469429e-01 4.117993e-02 3.187530e-01 1.869990e+02 +3.223719e-01 9.208473e-02 9.421235e-01 4.412583e+02 9.156853e-03 9.949072e-01 -1.003772e-01 -4.033301e+01 -9.465688e-01 4.098566e-02 3.198869e-01 1.872107e+02 +3.234843e-01 9.206304e-02 9.417442e-01 4.418895e+02 8.865716e-03 9.949170e-01 -1.003065e-01 -4.039940e+01 -9.461920e-01 4.079679e-02 3.210238e-01 1.874232e+02 +3.245771e-01 9.190703e-02 9.413834e-01 4.425242e+02 9.259575e-03 9.949115e-01 -1.003256e-01 -4.046910e+01 -9.458140e-01 4.128018e-02 3.220744e-01 1.876386e+02 +3.258291e-01 9.143753e-02 9.409965e-01 4.431116e+02 9.863533e-03 9.949291e-01 -1.000936e-01 -4.053170e+01 -9.453773e-01 4.189494e-02 3.232750e-01 1.878378e+02 +3.271229e-01 9.074787e-02 9.406143e-01 4.437097e+02 1.127691e-02 9.949325e-01 -9.991018e-02 -4.058993e+01 -9.449145e-01 4.329012e-02 3.244419e-01 1.880413e+02 +3.282855e-01 9.107567e-02 9.401775e-01 4.443114e+02 1.097192e-02 9.949059e-01 -1.002084e-01 -4.065105e+01 -9.445149e-01 4.321250e-02 3.256139e-01 1.882466e+02 +3.293295e-01 9.156653e-02 9.397646e-01 4.448710e+02 1.006165e-02 9.948898e-01 -1.004637e-01 -4.071269e+01 -9.441615e-01 4.254123e-02 3.267252e-01 1.884403e+02 +3.303751e-01 9.181241e-02 9.393735e-01 4.454493e+02 9.319676e-03 9.948917e-01 -1.005164e-01 -4.077681e+01 -9.438038e-01 4.196275e-02 3.278317e-01 1.886415e+02 +3.313686e-01 9.191269e-02 9.390137e-01 4.459827e+02 9.118132e-03 9.948852e-01 -1.005992e-01 -4.083615e+01 -9.434573e-01 4.189747e-02 3.288356e-01 1.888272e+02 +3.322889e-01 9.199614e-02 9.386803e-01 4.465258e+02 8.942019e-03 9.948797e-01 -1.006695e-01 -4.089361e+01 -9.431353e-01 4.184503e-02 3.297648e-01 1.890156e+02 +3.329485e-01 9.155826e-02 9.384894e-01 4.470563e+02 7.737753e-03 9.949759e-01 -9.981419e-02 -4.094722e+01 -9.429133e-01 4.049477e-02 3.305672e-01 1.892012e+02 +3.335041e-01 9.066370e-02 9.383789e-01 4.475777e+02 6.513945e-03 9.951195e-01 -9.846092e-02 -4.100285e+01 -9.427262e-01 3.894966e-02 3.312858e-01 1.893847e+02 +3.342198e-01 8.978541e-02 9.382087e-01 4.480907e+02 5.909832e-03 9.952328e-01 -9.734784e-02 -4.105680e+01 -9.424767e-01 3.808022e-02 3.320959e-01 1.895643e+02 +3.349541e-01 8.934939e-02 9.379884e-01 4.485905e+02 6.882468e-03 9.952351e-01 -9.726024e-02 -4.111097e+01 -9.422093e-01 3.903338e-02 3.327431e-01 1.897399e+02 +3.356351e-01 9.044704e-02 9.376397e-01 4.490822e+02 7.375546e-03 9.950968e-01 -9.862964e-02 -4.116507e+01 -9.419632e-01 4.001917e-02 3.333223e-01 1.899127e+02 +3.360799e-01 9.352981e-02 9.371779e-01 4.495511e+02 6.060934e-03 9.948215e-01 -1.014561e-01 -4.122241e+01 -9.418140e-01 3.977753e-02 3.337726e-01 1.900814e+02 +3.366296e-01 9.647984e-02 9.366814e-01 4.500150e+02 4.601294e-03 9.945567e-01 -1.040948e-01 -4.127840e+01 -9.416259e-01 3.935131e-02 3.343533e-01 1.902493e+02 +3.375830e-01 9.840790e-02 9.361375e-01 4.504737e+02 4.365595e-03 9.943457e-01 -1.061011e-01 -4.133399e+01 -9.412857e-01 3.990473e-02 3.352446e-01 1.904150e+02 +3.384125e-01 9.896722e-02 9.357790e-01 4.509162e+02 6.088911e-03 9.942028e-01 -1.073481e-01 -4.138482e+01 -9.409782e-01 4.202580e-02 3.358481e-01 1.905699e+02 +3.390005e-01 9.878143e-02 9.355858e-01 4.513527e+02 7.171518e-03 9.941720e-01 -1.075657e-01 -4.143116e+01 -9.407589e-01 4.317438e-02 3.363164e-01 1.907215e+02 +3.383185e-01 9.730497e-02 9.359873e-01 4.517763e+02 6.980390e-03 9.943527e-01 -1.058957e-01 -4.147778e+01 -9.410058e-01 4.236003e-02 3.357286e-01 1.908714e+02 +3.371164e-01 9.616336e-02 9.365389e-01 4.521892e+02 5.380338e-03 9.945567e-01 -1.040573e-01 -4.152320e+01 -9.414476e-01 4.011831e-02 3.347639e-01 1.910192e+02 +3.358107e-01 9.538026e-02 9.370878e-01 4.525961e+02 5.171137e-03 9.946582e-01 -1.030931e-01 -4.157027e+01 -9.419153e-01 3.946558e-02 3.335237e-01 1.911612e+02 +3.345526e-01 9.479137e-02 9.375975e-01 4.529753e+02 5.306256e-03 9.947229e-01 -1.024602e-01 -4.161612e+01 -9.423622e-01 3.925343e-02 3.322841e-01 1.912926e+02 +3.334111e-01 9.435379e-02 9.380481e-01 4.533477e+02 5.763486e-03 9.947567e-01 -1.021064e-01 -4.166274e+01 -9.427640e-01 3.944982e-02 3.311191e-01 1.914237e+02 +3.324680e-01 9.403196e-02 9.384151e-01 4.537102e+02 5.425047e-03 9.948100e-01 -1.016049e-01 -4.170389e+01 -9.430989e-01 3.887133e-02 3.302324e-01 1.915502e+02 +3.315140e-01 9.318319e-02 9.388372e-01 4.540561e+02 5.913669e-03 9.948856e-01 -1.008344e-01 -4.174707e+01 -9.434318e-01 3.897998e-02 3.292674e-01 1.916725e+02 +3.305591e-01 9.233410e-02 9.392577e-01 4.544021e+02 6.400617e-03 9.949605e-01 -1.000626e-01 -4.179023e+01 -9.437636e-01 3.908843e-02 3.283023e-01 1.917949e+02 +3.295672e-01 9.155844e-02 9.396821e-01 4.547312e+02 7.027224e-03 9.950212e-01 -9.941506e-02 -4.183460e+01 -9.441060e-01 3.936729e-02 3.272829e-01 1.919114e+02 +3.284433e-01 9.134146e-02 9.400966e-01 4.550471e+02 6.353516e-03 9.950767e-01 -9.890318e-02 -4.187896e+01 -9.445024e-01 3.845699e-02 3.262459e-01 1.920290e+02 +3.273781e-01 9.152950e-02 9.404498e-01 4.553537e+02 4.757571e-03 9.951249e-01 -9.850694e-02 -4.191510e+01 -9.448815e-01 3.672326e-02 3.253466e-01 1.921421e+02 +3.263618e-01 9.168611e-02 9.407877e-01 4.556532e+02 3.667488e-03 9.951543e-01 -9.825678e-02 -4.194952e+01 -9.452379e-01 3.551758e-02 3.244441e-01 1.922468e+02 +3.251982e-01 9.168213e-02 9.411909e-01 4.559458e+02 4.177548e-03 9.951400e-01 -9.838078e-02 -4.197617e+01 -9.456367e-01 3.592511e-02 3.232347e-01 1.923442e+02 +3.242734e-01 9.227498e-02 9.414520e-01 4.562262e+02 5.260350e-03 9.950396e-01 -9.933918e-02 -4.200704e+01 -9.459488e-01 3.716541e-02 3.221795e-01 1.924409e+02 +3.237164e-01 9.346848e-02 9.415260e-01 4.565053e+02 5.988966e-03 9.948861e-01 -1.008249e-01 -4.203355e+01 -9.461352e-01 3.827742e-02 3.215012e-01 1.925337e+02 +3.233885e-01 9.389593e-02 9.415962e-01 4.567802e+02 6.139755e-03 9.948355e-01 -1.013137e-01 -4.206007e+01 -9.462464e-01 3.854483e-02 3.211418e-01 1.926304e+02 +3.235829e-01 9.347280e-02 9.415715e-01 4.570499e+02 5.497834e-03 9.949059e-01 -1.006569e-01 -4.208984e+01 -9.461839e-01 3.774745e-02 3.214206e-01 1.927285e+02 +3.238729e-01 9.308561e-02 9.415101e-01 4.573193e+02 4.811580e-03 9.949731e-01 -1.000266e-01 -4.211960e+01 -9.460884e-01 3.692604e-02 3.217969e-01 1.928262e+02 +3.248344e-01 9.294999e-02 9.411922e-01 4.575849e+02 3.824537e-03 9.950215e-01 -9.958603e-02 -4.214874e+01 -9.457632e-01 3.594859e-02 3.228618e-01 1.929215e+02 +3.260310e-01 9.299330e-02 9.407741e-01 4.578478e+02 2.494010e-03 9.950619e-01 -9.922386e-02 -4.217833e+01 -9.453558e-01 3.469635e-02 3.241891e-01 1.930158e+02 +3.278277e-01 9.331689e-02 9.401175e-01 4.581099e+02 1.083880e-03 9.950719e-01 -9.914968e-02 -4.220107e+01 -9.447369e-01 3.352298e-02 3.261110e-01 1.931115e+02 +3.306440e-01 9.344245e-02 9.391182e-01 4.583727e+02 7.158041e-04 9.950611e-01 -9.926083e-02 -4.222298e+01 -9.437553e-01 3.349222e-02 3.289441e-01 1.932069e+02 +3.349602e-01 9.345845e-02 9.375858e-01 4.586339e+02 9.102231e-04 9.950360e-01 -9.951029e-02 -4.224587e+01 -9.422319e-01 3.418539e-02 3.332124e-01 1.933069e+02 +3.407326e-01 9.321062e-02 9.355281e-01 4.588966e+02 1.050943e-03 9.950347e-01 -9.952230e-02 -4.227315e+01 -9.401597e-01 3.489367e-02 3.389428e-01 1.934109e+02 +3.481868e-01 9.394209e-02 9.327061e-01 4.591567e+02 -4.346563e-05 9.949676e-01 -1.001968e-01 -4.230207e+01 -9.374252e-01 3.484667e-02 3.464386e-01 1.935220e+02 +3.576679e-01 9.485041e-02 9.290193e-01 4.594284e+02 -2.034053e-03 9.949052e-01 -1.007941e-01 -4.232982e+01 -9.338467e-01 3.416113e-02 3.560385e-01 1.936404e+02 +3.680307e-01 9.578386e-02 9.248669e-01 4.596977e+02 -3.340707e-03 9.948096e-01 -1.016981e-01 -4.235796e+01 -9.298077e-01 3.433831e-02 3.664404e-01 1.937601e+02 +3.798081e-01 9.587525e-02 9.200835e-01 4.599699e+02 -3.471510e-03 9.947553e-01 -1.022233e-01 -4.238822e+01 -9.250588e-01 3.563113e-02 3.781489e-01 1.938837e+02 +3.940225e-01 9.609928e-02 9.140629e-01 4.602494e+02 -5.525148e-03 9.947484e-01 -1.022004e-01 -4.241641e+01 -9.190842e-01 3.521892e-02 3.924842e-01 1.940183e+02 +4.098683e-01 9.768578e-02 9.068987e-01 4.605317e+02 -8.864805e-03 9.946284e-01 -1.031291e-01 -4.244519e+01 -9.121016e-01 3.422987e-02 4.085327e-01 1.941659e+02 +4.271757e-01 9.941432e-02 8.986866e-01 4.608164e+02 -1.282180e-02 9.945030e-01 -1.039191e-01 -4.246997e+01 -9.040778e-01 3.286893e-02 4.261022e-01 1.943198e+02 +4.457413e-01 1.009795e-01 8.894480e-01 4.610905e+02 -1.430944e-02 9.942938e-01 -1.057117e-01 -4.249464e+01 -8.950475e-01 3.439255e-02 4.446428e-01 1.944719e+02 +4.644901e-01 1.032963e-01 8.795332e-01 4.613703e+02 -1.634703e-02 9.940047e-01 -1.081073e-01 -4.252156e+01 -8.854275e-01 3.583701e-02 4.633940e-01 1.946318e+02 +4.837386e-01 1.042873e-01 8.689770e-01 4.616462e+02 -1.786057e-02 9.938449e-01 -1.093303e-01 -4.255214e+01 -8.750303e-01 3.736686e-02 4.826238e-01 1.947973e+02 +5.027649e-01 1.070389e-01 8.577704e-01 4.619028e+02 -2.395649e-02 9.936479e-01 -1.099531e-01 -4.258029e+01 -8.640912e-01 3.473140e-02 5.021356e-01 1.949670e+02 +5.167028e-01 1.113386e-01 8.488945e-01 4.621586e+02 -2.877736e-02 9.932065e-01 -1.127501e-01 -4.260070e+01 -8.556811e-01 3.382933e-02 5.163966e-01 1.951399e+02 +5.209580e-01 1.164952e-01 8.455954e-01 4.624096e+02 -3.605008e-02 9.927619e-01 -1.145600e-01 -4.262020e+01 -8.528207e-01 2.919716e-02 5.213869e-01 1.953093e+02 +5.200352e-01 1.182342e-01 8.459220e-01 4.626558e+02 -3.851893e-02 9.926117e-01 -1.150572e-01 -4.264180e+01 -8.532759e-01 2.724978e-02 5.207472e-01 1.954678e+02 +5.154653e-01 1.193647e-01 8.485561e-01 4.628996e+02 -3.958114e-02 9.925103e-01 -1.155705e-01 -4.266193e+01 -8.559959e-01 2.598575e-02 5.163292e-01 1.956128e+02 +5.061351e-01 1.197342e-01 8.541024e-01 4.631354e+02 -3.898857e-02 9.924803e-01 -1.160287e-01 -4.268335e+01 -8.615725e-01 2.542595e-02 5.069973e-01 1.957438e+02 +4.931571e-01 1.191426e-01 8.617430e-01 4.633755e+02 -3.562090e-02 9.925120e-01 -1.168374e-01 -4.269452e+01 -8.692107e-01 2.692314e-02 4.937083e-01 1.958647e+02 +4.790758e-01 1.181278e-01 8.697885e-01 4.635862e+02 -3.110378e-02 9.925654e-01 -1.176706e-01 -4.270011e+01 -8.772223e-01 2.931940e-02 4.791882e-01 1.959620e+02 +4.611439e-01 1.167452e-01 8.796117e-01 4.638526e+02 -2.574568e-02 9.926499e-01 -1.182507e-01 -4.271946e+01 -8.869518e-01 3.188439e-02 4.607602e-01 1.960754e+02 +4.413199e-01 1.162526e-01 8.897876e-01 4.641011e+02 -2.260178e-02 9.926981e-01 -1.184879e-01 -4.273706e+01 -8.970652e-01 3.218029e-02 4.407249e-01 1.961766e+02 +4.206924e-01 1.164545e-01 8.996978e-01 4.643543e+02 -2.079159e-02 9.927039e-01 -1.187709e-01 -4.275047e+01 -9.069651e-01 3.125987e-02 4.200442e-01 1.962736e+02 +3.998922e-01 1.164892e-01 9.091294e-01 4.646036e+02 -1.972033e-02 9.927545e-01 -1.185301e-01 -4.276345e+01 -9.163500e-01 2.947094e-02 3.992920e-01 1.963641e+02 +3.799271e-01 1.156615e-01 9.177569e-01 4.648704e+02 -1.755105e-02 9.928747e-01 -1.178626e-01 -4.278446e+01 -9.248499e-01 2.867161e-02 3.792500e-01 1.964577e+02 +3.617435e-01 1.145253e-01 9.252165e-01 4.651394e+02 -1.269053e-02 9.929388e-01 -1.179463e-01 -4.281190e+01 -9.321913e-01 3.092482e-02 3.606425e-01 1.965508e+02 +3.455695e-01 1.131318e-01 9.315486e-01 4.654025e+02 -6.932431e-03 9.929868e-01 -1.180215e-01 -4.283862e+01 -9.383676e-01 3.432674e-02 3.439302e-01 1.966346e+02 +3.305536e-01 1.123499e-01 9.370761e-01 4.656751e+02 -3.202771e-03 9.930170e-01 -1.179272e-01 -4.287317e+01 -9.437818e-01 3.598000e-02 3.286052e-01 1.967174e+02 +3.167368e-01 1.124309e-01 9.418264e-01 4.659486e+02 -3.066268e-03 9.930661e-01 -1.175165e-01 -4.290391e+01 -9.485085e-01 3.433392e-02 3.148854e-01 1.967998e+02 +3.069734e-01 1.105617e-01 9.452742e-01 4.662106e+02 -1.743759e-03 9.932929e-01 -1.156118e-01 -4.293432e+01 -9.517165e-01 3.384141e-02 3.051073e-01 1.968705e+02 +2.977034e-01 1.074260e-01 9.485948e-01 4.664742e+02 8.995351e-05 9.936453e-01 -1.125561e-01 -4.297107e+01 -9.546584e-01 3.359366e-02 2.958019e-01 1.969409e+02 +2.914654e-01 1.063192e-01 9.506545e-01 4.667140e+02 1.581234e-03 9.937492e-01 -1.116236e-01 -4.300329e+01 -9.565801e-01 3.403763e-02 2.894754e-01 1.970063e+02 +2.894986e-01 1.064076e-01 9.512454e-01 4.669526e+02 2.845079e-03 9.937015e-01 -1.120227e-01 -4.303319e+01 -9.571742e-01 3.513678e-02 2.873725e-01 1.970727e+02 +2.923063e-01 1.068445e-01 9.503374e-01 4.671914e+02 2.919385e-03 9.936349e-01 -1.126103e-01 -4.305471e+01 -9.563203e-01 3.569110e-02 2.901338e-01 1.971423e+02 +2.989503e-01 1.058601e-01 9.483787e-01 4.674097e+02 4.103635e-03 9.936760e-01 -1.122098e-01 -4.307618e+01 -9.542599e-01 3.743695e-02 2.966253e-01 1.972090e+02 +3.088265e-01 1.042761e-01 9.453849e-01 4.676176e+02 5.628783e-03 9.937540e-01 -1.114500e-01 -4.309856e+01 -9.511018e-01 3.974006e-02 3.063106e-01 1.972758e+02 +3.210372e-01 1.035137e-01 9.413925e-01 4.678226e+02 3.645640e-03 9.938664e-01 -1.105269e-01 -4.312385e+01 -9.470596e-01 3.891521e-02 3.186908e-01 1.973493e+02 +3.343143e-01 1.056401e-01 9.365223e-01 4.680046e+02 -2.449517e-03 9.937921e-01 -1.112257e-01 -4.315132e+01 -9.424585e-01 3.489031e-02 3.324976e-01 1.974270e+02 +3.473590e-01 1.079323e-01 9.315000e-01 4.681669e+02 -7.735704e-03 9.936499e-01 -1.122489e-01 -4.318329e+01 -9.377004e-01 3.178484e-02 3.459881e-01 1.974971e+02 +3.611940e-01 1.078870e-01 9.262284e-01 4.683295e+02 -1.159096e-02 9.937271e-01 -1.112293e-01 -4.320345e+01 -9.324187e-01 2.943946e-02 3.601788e-01 1.975723e+02 +3.757864e-01 1.058797e-01 9.206378e-01 4.684910e+02 -1.372735e-02 9.939785e-01 -1.087112e-01 -4.322371e+01 -9.266046e-01 2.821426e-02 3.749771e-01 1.976433e+02 +3.910737e-01 1.044648e-01 9.144115e-01 4.686283e+02 -8.488632e-03 9.939046e-01 -1.099160e-01 -4.324139e+01 -9.203203e-01 3.522313e-02 3.895767e-01 1.976916e+02 +4.060707e-01 1.027888e-01 9.080423e-01 4.687634e+02 -3.285678e-03 9.938117e-01 -1.110284e-01 -4.325910e+01 -9.138358e-01 4.210186e-02 4.038956e-01 1.977388e+02 +4.222470e-01 1.055119e-01 9.003192e-01 4.688842e+02 6.376888e-04 9.931678e-01 -1.166923e-01 -4.327329e+01 -9.064806e-01 4.984707e-02 4.192948e-01 1.977883e+02 +4.374772e-01 1.079245e-01 8.927295e-01 4.689924e+02 -2.493033e-03 9.929133e-01 -1.188143e-01 -4.328474e+01 -8.992261e-01 4.975294e-02 4.346459e-01 1.978525e+02 +4.505978e-01 1.096455e-01 8.859681e-01 4.690948e+02 -1.140323e-02 9.930547e-01 -1.170987e-01 -4.329185e+01 -8.926543e-01 4.266150e-02 4.487186e-01 1.979181e+02 +4.642500e-01 1.097715e-01 8.788754e-01 4.692040e+02 -1.799657e-02 9.932543e-01 -1.145511e-01 -4.329579e+01 -8.855214e-01 3.736361e-02 4.630938e-01 1.979843e+02 +4.765987e-01 1.091034e-01 8.723245e-01 4.692991e+02 -2.074711e-02 9.933885e-01 -1.129098e-01 -4.329833e+01 -8.788761e-01 3.571447e-02 4.757113e-01 1.980352e+02 +4.884469e-01 1.080321e-01 8.658802e-01 4.693867e+02 -2.129129e-02 9.934865e-01 -1.119425e-01 -4.330684e+01 -8.723339e-01 3.624227e-02 4.875656e-01 1.980824e+02 +5.003428e-01 1.074614e-01 8.591327e-01 4.694730e+02 -2.225667e-02 9.935363e-01 -1.113110e-01 -4.331315e+01 -8.655413e-01 3.657220e-02 4.995005e-01 1.981348e+02 +5.114245e-01 1.071765e-01 8.526184e-01 4.695559e+02 -2.313426e-02 9.935493e-01 -1.110153e-01 -4.331632e+01 -8.590168e-01 3.705126e-02 5.106049e-01 1.981810e+02 +5.218632e-01 1.058312e-01 8.464387e-01 4.696341e+02 -2.313388e-02 9.936649e-01 -1.099762e-01 -4.331351e+01 -8.527155e-01 3.781110e-02 5.210054e-01 1.982243e+02 +5.312143e-01 1.036979e-01 8.408674e-01 4.697087e+02 -2.277776e-02 9.938706e-01 -1.081769e-01 -4.332229e+01 -8.469313e-01 3.831202e-02 5.303203e-01 1.982622e+02 +5.384552e-01 1.041962e-01 8.361872e-01 4.697717e+02 -2.538041e-02 9.938807e-01 -1.075027e-01 -4.333560e+01 -8.422718e-01 3.666260e-02 5.378048e-01 1.983029e+02 +5.454831e-01 1.083810e-01 8.310846e-01 4.698181e+02 -3.248860e-02 9.935926e-01 -1.082496e-01 -4.334418e+01 -8.374919e-01 3.204756e-02 5.455091e-01 1.983492e+02 +5.539267e-01 1.152745e-01 8.245465e-01 4.698578e+02 -4.248517e-02 9.929918e-01 -1.102824e-01 -4.334935e+01 -8.314808e-01 2.605739e-02 5.549421e-01 1.984001e+02 +5.594288e-01 1.199751e-01 8.201496e-01 4.698944e+02 -4.893292e-02 9.925237e-01 -1.118133e-01 -4.335196e+01 -8.274328e-01 2.241926e-02 5.611170e-01 1.984424e+02 +5.642626e-01 1.190064e-01 8.169731e-01 4.699367e+02 -4.897448e-02 9.926386e-01 -1.107697e-01 -4.335745e+01 -8.241416e-01 2.249237e-02 5.659371e-01 1.984781e+02 +5.709020e-01 1.138916e-01 8.130803e-01 4.699846e+02 -4.444896e-02 9.931667e-01 -1.079074e-01 -4.336013e+01 -8.198142e-01 2.546394e-02 5.720632e-01 1.985051e+02 +5.760968e-01 1.089937e-01 8.100819e-01 4.700301e+02 -3.997483e-02 9.936406e-01 -1.052624e-01 -4.336564e+01 -8.164034e-01 2.825845e-02 5.767902e-01 1.985343e+02 +5.798753e-01 1.073130e-01 8.076066e-01 4.700664e+02 -3.962307e-02 9.938286e-01 -1.036078e-01 -4.337479e+01 -8.137412e-01 2.807974e-02 5.805487e-01 1.985661e+02 +5.847946e-01 1.090136e-01 8.038228e-01 4.700932e+02 -4.394039e-02 9.937308e-01 -1.028014e-01 -4.338690e+01 -8.099905e-01 2.479739e-02 5.859186e-01 1.986001e+02 +5.889091e-01 1.121413e-01 8.003813e-01 4.701173e+02 -4.938056e-02 9.934691e-01 -1.028614e-01 -4.338980e+01 -8.066893e-01 2.105272e-02 5.906007e-01 1.986341e+02 +5.916659e-01 1.148511e-01 7.979603e-01 4.701424e+02 -5.333305e-02 9.932080e-01 -1.034083e-01 -4.339187e+01 -8.044172e-01 1.862552e-02 5.937727e-01 1.986644e+02 diff --git a/tools/Ground-Truth/dataset/poses/04.txt b/tools/Ground-Truth/dataset/poses/04.txt new file mode 100644 index 0000000..f1b8924 --- /dev/null +++ b/tools/Ground-Truth/dataset/poses/04.txt @@ -0,0 +1,271 @@ +1.000000e+00 1.197625e-11 1.704638e-10 -5.551115e-17 1.197625e-11 1.000000e+00 3.562503e-10 0.000000e+00 1.704638e-10 3.562503e-10 1.000000e+00 2.220446e-16 +9.999996e-01 -9.035185e-04 -2.101169e-04 1.289128e-03 9.037964e-04 9.999987e-01 1.325646e-03 -1.821616e-02 2.089193e-04 -1.325834e-03 9.999991e-01 1.310643e+00 +9.999985e-01 -1.646347e-03 -5.538205e-04 4.448326e-04 1.647375e-03 9.999969e-01 1.859719e-03 -4.203318e-02 5.507574e-04 -1.860627e-03 9.999981e-01 2.625299e+00 +9.999939e-01 -3.413454e-03 -7.312197e-04 2.037581e-03 3.413847e-03 9.999940e-01 5.361920e-04 -6.302801e-02 7.293855e-04 -5.386841e-04 9.999996e-01 3.941730e+00 +9.999932e-01 -3.635348e-03 -6.434003e-04 2.777892e-03 3.635872e-03 9.999930e-01 8.141188e-04 -8.483761e-02 6.404366e-04 -8.164517e-04 9.999995e-01 5.261017e+00 +9.999922e-01 -3.925219e-03 -5.162240e-04 4.157928e-03 3.926062e-03 9.999909e-01 1.640787e-03 -1.014678e-01 5.097792e-04 -1.642800e-03 9.999985e-01 6.581638e+00 +9.999848e-01 -5.504052e-03 -4.169862e-04 7.571022e-03 5.505158e-03 9.999812e-01 2.694454e-03 -1.165874e-01 4.021483e-04 -2.696707e-03 9.999963e-01 7.908775e+00 +9.999864e-01 -5.184552e-03 -5.975596e-04 8.323818e-03 5.186662e-03 9.999801e-01 3.583038e-03 -1.328035e-01 5.789716e-04 -3.586087e-03 9.999934e-01 9.238962e+00 +9.999889e-01 -4.630870e-03 -8.604706e-04 7.728339e-03 4.632472e-03 9.999875e-01 1.867105e-03 -1.497649e-01 8.518139e-04 -1.871070e-03 9.999979e-01 1.056963e+01 +9.999977e-01 -1.900807e-03 -9.601046e-04 6.780918e-03 1.900055e-03 9.999979e-01 -7.842219e-04 -1.634547e-01 9.615936e-04 7.823964e-04 9.999992e-01 1.190426e+01 +9.999986e-01 1.543588e-03 -6.218670e-04 3.419395e-03 -1.544659e-03 9.999973e-01 -1.724973e-03 -1.767480e-01 6.192031e-04 1.725931e-03 9.999983e-01 1.324208e+01 +9.999920e-01 3.962554e-03 -5.304797e-04 -1.862182e-03 -3.963388e-03 9.999909e-01 -1.579139e-03 -1.959202e-01 5.242178e-04 1.581229e-03 9.999986e-01 1.458048e+01 +9.999865e-01 5.189813e-03 -3.869434e-04 -5.851755e-03 -5.190150e-03 9.999861e-01 -8.728856e-04 -2.177602e-01 3.824083e-04 8.748826e-04 9.999996e-01 1.593066e+01 +9.999955e-01 2.993090e-03 2.876761e-05 -4.267715e-03 -2.993137e-03 9.999939e-01 1.769063e-03 -2.364140e-01 -2.347214e-05 -1.769141e-03 9.999984e-01 1.728222e+01 +9.999996e-01 -8.993856e-04 2.524904e-04 4.827890e-04 8.983692e-04 9.999916e-01 3.998216e-03 -2.537475e-01 -2.560839e-04 -3.997986e-03 9.999920e-01 1.863469e+01 +9.999934e-01 -3.638641e-03 -3.959215e-05 5.006086e-03 3.638708e-03 9.999917e-01 1.831392e-03 -2.699101e-01 3.292839e-05 -1.831523e-03 9.999983e-01 1.998670e+01 +9.999869e-01 -5.119262e-03 -2.320356e-04 4.134686e-03 5.119134e-03 9.999867e-01 -5.539281e-04 -2.931092e-01 2.348686e-04 5.527336e-04 9.999998e-01 2.134127e+01 +9.999959e-01 -2.848774e-03 4.262615e-04 -7.654745e-04 2.849650e-03 9.999938e-01 -2.066802e-03 -3.222297e-01 -4.203707e-04 2.068008e-03 9.999978e-01 2.270575e+01 +9.999992e-01 1.424853e-04 1.245425e-03 -7.369324e-03 -1.415313e-04 9.999997e-01 -7.660729e-04 -3.468119e-01 -1.245534e-03 7.658967e-04 9.999989e-01 2.407210e+01 +9.999971e-01 1.440634e-03 1.942058e-03 -9.719264e-03 -1.451156e-03 9.999842e-01 5.427244e-03 -3.687424e-01 -1.934208e-03 -5.430044e-03 9.999834e-01 2.544868e+01 +9.999966e-01 -1.050891e-03 2.369238e-03 -5.061181e-03 1.037930e-03 9.999845e-01 5.465290e-03 -3.871399e-01 -2.374945e-03 -5.462811e-03 9.999823e-01 2.682030e+01 +9.999839e-01 -5.339007e-03 1.951315e-03 1.962273e-03 5.331392e-03 9.999782e-01 3.887907e-03 -4.099385e-01 -1.972030e-03 -3.877439e-03 9.999905e-01 2.819472e+01 +9.999804e-01 -5.933229e-03 1.984892e-03 5.281593e-03 5.930623e-03 9.999815e-01 1.317193e-03 -4.328977e-01 -1.992671e-03 -1.305395e-03 9.999972e-01 2.957012e+01 +9.999781e-01 -6.177289e-03 2.396696e-03 7.939024e-03 6.179643e-03 9.999804e-01 -9.754601e-04 -4.591179e-01 -2.390623e-03 9.902499e-04 9.999967e-01 3.094984e+01 +9.999909e-01 -2.864263e-03 3.173275e-03 6.827076e-03 2.868672e-03 9.999949e-01 -1.385713e-03 -4.850133e-01 -3.169290e-03 1.394804e-03 9.999940e-01 3.233531e+01 +9.999918e-01 -1.916604e-03 3.569832e-03 8.305167e-03 1.929098e-03 9.999920e-01 -3.499497e-03 -5.122367e-01 -3.563096e-03 3.506355e-03 9.999875e-01 3.371780e+01 +9.999934e-01 -1.021449e-03 3.498427e-03 1.017340e-02 1.035312e-03 9.999916e-01 -3.963092e-03 -5.431160e-01 -3.494350e-03 3.966688e-03 9.999860e-01 3.511083e+01 +9.999937e-01 -9.562966e-04 3.408962e-03 1.211940e-02 9.619574e-04 9.999981e-01 -1.659242e-03 -5.746233e-01 -3.407369e-03 1.662511e-03 9.999928e-01 3.650789e+01 +9.999955e-01 -1.889567e-04 2.986144e-03 1.511478e-02 1.891381e-04 1.000000e+00 -6.045352e-05 -5.999006e-01 -2.986132e-03 6.101873e-05 9.999955e-01 3.790589e+01 +9.999925e-01 2.514536e-03 2.962671e-03 1.696851e-02 -2.513425e-03 9.999967e-01 -3.789502e-04 -6.238526e-01 -2.963614e-03 3.715016e-04 9.999955e-01 3.930156e+01 +9.999824e-01 5.051551e-03 3.101410e-03 1.942949e-02 -5.049835e-03 9.999871e-01 -5.613031e-04 -6.437120e-01 -3.104205e-03 5.456323e-04 9.999950e-01 4.070437e+01 +9.999692e-01 7.203652e-03 3.111047e-03 1.916344e-02 -7.203531e-03 9.999740e-01 -5.033623e-05 -6.707246e-01 -3.111328e-03 2.792485e-05 9.999952e-01 4.211100e+01 +9.999615e-01 8.308311e-03 2.843621e-03 2.134431e-02 -8.308996e-03 9.999654e-01 2.285387e-04 -6.941320e-01 -2.841624e-03 -2.521567e-04 9.999959e-01 4.351858e+01 +9.999707e-01 7.259716e-03 2.412259e-03 2.622364e-02 -7.259297e-03 9.999736e-01 -1.830541e-04 -7.178581e-01 -2.413524e-03 1.655381e-04 9.999971e-01 4.492821e+01 +9.999779e-01 6.426238e-03 1.720933e-03 3.086036e-02 -6.424858e-03 9.999790e-01 -8.074730e-04 -7.390250e-01 -1.726085e-03 7.963989e-04 9.999982e-01 4.634127e+01 +9.999829e-01 5.800169e-03 7.616191e-04 3.408031e-02 -5.800122e-03 9.999832e-01 -6.598169e-05 -7.610315e-01 -7.619887e-04 6.156377e-05 9.999997e-01 4.775704e+01 +9.999819e-01 6.010565e-03 -2.411952e-04 3.359221e-02 -6.010374e-03 9.999816e-01 7.926521e-04 -7.839856e-01 2.459554e-04 -7.911873e-04 9.999997e-01 4.917963e+01 +9.999771e-01 6.648910e-03 -1.303817e-03 3.175532e-02 -6.647540e-03 9.999773e-01 1.052800e-03 -8.056350e-01 1.310788e-03 -1.044108e-03 9.999986e-01 5.060218e+01 +9.999749e-01 6.638251e-03 -2.479480e-03 2.895795e-02 -6.636601e-03 9.999777e-01 6.739965e-04 -8.265408e-01 2.483900e-03 -6.575234e-04 9.999967e-01 5.202831e+01 +9.999699e-01 6.882776e-03 -3.588301e-03 2.536977e-02 -6.875797e-03 9.999744e-01 1.954123e-03 -8.453836e-01 3.601659e-03 -1.929391e-03 9.999917e-01 5.345716e+01 +9.999753e-01 5.497092e-03 -4.387406e-03 2.082938e-02 -5.484306e-03 9.999807e-01 2.921095e-03 -8.668316e-01 4.403379e-03 -2.896960e-03 9.999861e-01 5.488464e+01 +9.999794e-01 4.003115e-03 -5.028578e-03 1.680870e-02 -3.988904e-03 9.999880e-01 2.833038e-03 -8.868800e-01 5.039859e-03 -2.812920e-03 9.999834e-01 5.631660e+01 +9.999825e-01 1.719377e-03 -5.654443e-03 1.322910e-02 -1.705846e-03 9.999956e-01 2.396848e-03 -9.072442e-01 5.658540e-03 -2.387160e-03 9.999812e-01 5.774550e+01 +9.999835e-01 3.749396e-04 -5.730769e-03 1.007535e-02 -3.587007e-04 9.999959e-01 2.834406e-03 -9.249469e-01 5.731809e-03 -2.832302e-03 9.999796e-01 5.917365e+01 +9.999856e-01 -8.364906e-04 -5.300789e-03 6.524255e-03 8.549023e-04 9.999936e-01 3.472042e-03 -9.446035e-01 5.297852e-03 -3.476522e-03 9.999799e-01 6.060318e+01 +9.999862e-01 -1.858791e-03 -4.917931e-03 2.764210e-03 1.878972e-03 9.999898e-01 4.102186e-03 -9.647484e-01 4.910257e-03 -4.111369e-03 9.999795e-01 6.202795e+01 +9.999827e-01 -3.792549e-03 -4.488790e-03 -1.308243e-03 3.809033e-03 9.999860e-01 3.669129e-03 -9.878100e-01 4.474812e-03 -3.686163e-03 9.999832e-01 6.345198e+01 +9.999780e-01 -5.296196e-03 -4.008198e-03 -2.873604e-03 5.307526e-03 9.999819e-01 2.820928e-03 -1.008175e+00 3.993186e-03 -2.842138e-03 9.999880e-01 6.487187e+01 +9.999807e-01 -5.220464e-03 -3.359595e-03 -5.953934e-03 5.228046e-03 9.999838e-01 2.251723e-03 -1.029700e+00 3.347786e-03 -2.269242e-03 9.999918e-01 6.628940e+01 +9.999907e-01 -3.482462e-03 -2.553135e-03 -1.002031e-02 3.488378e-03 9.999912e-01 2.316104e-03 -1.050203e+00 2.545047e-03 -2.324987e-03 9.999941e-01 6.770311e+01 +9.999977e-01 -6.481361e-04 -2.068772e-03 -1.936440e-02 6.556852e-04 9.999931e-01 3.650429e-03 -1.076075e+00 2.066392e-03 -3.651776e-03 9.999912e-01 6.911593e+01 +9.999946e-01 3.012865e-03 -1.287971e-03 -2.702275e-02 -3.006442e-03 9.999832e-01 4.960905e-03 -1.097831e+00 1.302897e-03 -4.957004e-03 9.999869e-01 7.053000e+01 +9.999777e-01 6.659933e-03 -5.287413e-04 -3.513442e-02 -6.656920e-03 9.999626e-01 5.510824e-03 -1.118231e+00 5.654236e-04 -5.507180e-03 9.999847e-01 7.193978e+01 +9.999378e-01 1.115147e-02 1.358833e-04 -4.214650e-02 -1.115202e-02 9.999247e-01 5.112813e-03 -1.135987e+00 -7.885743e-05 -5.114008e-03 9.999869e-01 7.333986e+01 +9.998986e-01 1.421691e-02 8.503240e-04 -4.677589e-02 -1.422070e-02 9.998882e-01 4.621051e-03 -1.153311e+00 -7.845315e-04 -4.632673e-03 9.999890e-01 7.474245e+01 +9.998649e-01 1.636598e-02 1.544958e-03 -5.327678e-02 -1.637256e-02 9.998565e-01 4.344501e-03 -1.177226e+00 -1.473634e-03 -4.369207e-03 9.999894e-01 7.614450e+01 +9.998598e-01 1.663766e-02 1.883621e-03 -5.458511e-02 -1.664595e-02 9.998514e-01 4.472345e-03 -1.197942e+00 -1.808931e-03 -4.503071e-03 9.999882e-01 7.754079e+01 +9.998793e-01 1.540192e-02 2.040510e-03 -5.287325e-02 -1.541125e-02 9.998705e-01 4.635585e-03 -1.218035e+00 -1.968848e-03 -4.666470e-03 9.999872e-01 7.893496e+01 +9.998967e-01 1.423630e-02 1.959369e-03 -4.954250e-02 -1.424345e-02 9.998917e-01 3.684603e-03 -1.236655e+00 -1.906701e-03 -3.712129e-03 9.999913e-01 8.032545e+01 +9.999076e-01 1.348987e-02 1.677215e-03 -4.883212e-02 -1.349578e-02 9.999026e-01 3.560725e-03 -1.258287e+00 -1.629018e-03 -3.583030e-03 9.999923e-01 8.171095e+01 +9.999074e-01 1.353416e-02 1.448463e-03 -4.838807e-02 -1.353963e-02 9.999010e-01 3.833191e-03 -1.278676e+00 -1.396440e-03 -3.852447e-03 9.999916e-01 8.309721e+01 +9.999140e-01 1.308010e-02 9.085344e-04 -5.269073e-02 -1.308305e-02 9.999089e-01 3.317811e-03 -1.300031e+00 -8.650540e-04 -3.329411e-03 9.999941e-01 8.448367e+01 +9.999097e-01 1.343478e-02 1.870473e-04 -6.072004e-02 -1.343539e-02 9.999029e-01 3.681202e-03 -1.320245e+00 -1.375727e-04 -3.683382e-03 9.999932e-01 8.586562e+01 +9.999145e-01 1.305409e-02 -7.454492e-04 -7.518042e-02 -1.305069e-02 9.999051e-01 4.397269e-03 -1.343695e+00 8.027813e-04 -4.387163e-03 9.999901e-01 8.725015e+01 +9.999385e-01 1.093064e-02 -1.877975e-03 -8.437620e-02 -1.092024e-02 9.999254e-01 5.458590e-03 -1.362982e+00 1.937501e-03 -5.437745e-03 9.999833e-01 8.862909e+01 +9.999566e-01 8.790731e-03 -3.086647e-03 -9.813229e-02 -8.771544e-03 9.999424e-01 6.176185e-03 -1.382640e+00 3.140763e-03 -6.148840e-03 9.999762e-01 9.000634e+01 +9.999700e-01 6.803260e-03 -3.711637e-03 -1.110475e-01 -6.779632e-03 9.999569e-01 6.342125e-03 -1.399781e+00 3.754624e-03 -6.316769e-03 9.999730e-01 9.137524e+01 +9.999761e-01 5.509752e-03 -4.188780e-03 -1.283351e-01 -5.485989e-03 9.999689e-01 5.663659e-03 -1.418059e+00 4.219856e-03 -5.640542e-03 9.999752e-01 9.274128e+01 +9.999809e-01 4.282217e-03 -4.468492e-03 -1.454603e-01 -4.259218e-03 9.999777e-01 5.143990e-03 -1.435964e+00 4.490421e-03 -5.124857e-03 9.999768e-01 9.410339e+01 +9.999772e-01 4.941455e-03 -4.604768e-03 -1.697048e-01 -4.919521e-03 9.999765e-01 4.762664e-03 -1.456190e+00 4.628195e-03 -4.739901e-03 9.999781e-01 9.546076e+01 +9.999787e-01 4.738575e-03 -4.487410e-03 -1.913409e-01 -4.720319e-03 9.999805e-01 4.070437e-03 -1.476213e+00 4.506611e-03 -4.049167e-03 9.999817e-01 9.681382e+01 +9.999761e-01 5.462031e-03 -4.246260e-03 -2.120314e-01 -5.447632e-03 9.999794e-01 3.395396e-03 -1.496478e+00 4.264719e-03 -3.372181e-03 9.999852e-01 9.816545e+01 +9.999676e-01 7.060840e-03 -3.876949e-03 -2.344056e-01 -7.047185e-03 9.999689e-01 3.524911e-03 -1.517683e+00 3.901718e-03 -3.497473e-03 9.999863e-01 9.951513e+01 +9.999651e-01 7.529260e-03 -3.627207e-03 -2.485715e-01 -7.511447e-03 9.999598e-01 4.900143e-03 -1.534999e+00 3.663956e-03 -4.872725e-03 9.999814e-01 1.008603e+02 +9.999550e-01 8.833811e-03 -3.458298e-03 -2.694021e-01 -8.811343e-03 9.999403e-01 6.459623e-03 -1.556018e+00 3.515155e-03 -6.428858e-03 9.999732e-01 1.022054e+02 +9.999597e-01 8.302254e-03 -3.413289e-03 -2.867601e-01 -8.284616e-03 9.999524e-01 5.149958e-03 -1.575247e+00 3.455884e-03 -5.121471e-03 9.999809e-01 1.035459e+02 +9.999610e-01 8.173871e-03 -3.338205e-03 -3.053256e-01 -8.165524e-03 9.999635e-01 2.507096e-03 -1.596046e+00 3.358576e-03 -2.479739e-03 9.999913e-01 1.048845e+02 +9.999651e-01 7.633274e-03 -3.387356e-03 -3.153955e-01 -7.628806e-03 9.999700e-01 1.330447e-03 -1.613299e+00 3.397411e-03 -1.304558e-03 9.999934e-01 1.062208e+02 +9.999796e-01 5.504928e-03 -3.239048e-03 -3.343086e-01 -5.496405e-03 9.999814e-01 2.634819e-03 -1.638432e+00 3.253493e-03 -2.616961e-03 9.999913e-01 1.075653e+02 +9.999916e-01 3.142105e-03 -2.625883e-03 -3.508131e-01 -3.129622e-03 9.999838e-01 4.744784e-03 -1.661275e+00 2.640749e-03 -4.736525e-03 9.999853e-01 1.089064e+02 +9.999973e-01 1.561465e-03 -1.709519e-03 -3.737761e-01 -1.552202e-03 9.999842e-01 5.406523e-03 -1.686739e+00 1.717934e-03 -5.403854e-03 9.999839e-01 1.102446e+02 +9.999993e-01 6.761649e-04 -1.000188e-03 -3.943149e-01 -6.721988e-04 9.999919e-01 3.960469e-03 -1.710102e+00 1.002858e-03 -3.959792e-03 9.999917e-01 1.115766e+02 +9.999966e-01 2.581200e-03 -3.337541e-04 -4.137129e-01 -2.580678e-03 9.999954e-01 1.556832e-03 -1.733997e+00 3.377714e-04 -1.555964e-03 9.999987e-01 1.129050e+02 +9.999895e-01 4.532670e-03 7.482827e-04 -4.219683e-01 -4.532188e-03 9.999895e-01 -6.455749e-04 -1.753986e+00 -7.512008e-04 6.421774e-04 9.999995e-01 1.142286e+02 +9.999690e-01 7.570197e-03 2.161282e-03 -4.295899e-01 -7.568322e-03 9.999710e-01 -8.754176e-04 -1.775004e+00 -2.167846e-03 8.590337e-04 9.999973e-01 1.155601e+02 +9.999531e-01 8.996724e-03 3.596945e-03 -4.334779e-01 -9.001425e-03 9.999586e-01 1.292099e-03 -1.794230e+00 -3.585171e-03 -1.324415e-03 9.999927e-01 1.168930e+02 +9.999479e-01 9.079888e-03 4.667313e-03 -4.334151e-01 -9.097321e-03 9.999516e-01 3.727156e-03 -1.811794e+00 -4.633246e-03 -3.769420e-03 9.999822e-01 1.182274e+02 +9.999525e-01 8.077879e-03 5.449540e-03 -4.306137e-01 -8.102033e-03 9.999574e-01 4.424713e-03 -1.825847e+00 -5.413565e-03 -4.468654e-03 9.999754e-01 1.195613e+02 +9.999422e-01 8.587162e-03 6.468939e-03 -4.334146e-01 -8.611020e-03 9.999562e-01 3.668979e-03 -1.846322e+00 -6.437149e-03 -3.724469e-03 9.999724e-01 1.209045e+02 +9.999167e-01 1.035031e-02 7.709247e-03 -4.472932e-01 -1.037511e-02 9.999411e-01 3.183679e-03 -1.880929e+00 -7.675841e-03 -3.263396e-03 9.999652e-01 1.222684e+02 +9.998842e-01 1.238024e-02 8.849720e-03 -4.560744e-01 -1.240543e-02 9.999191e-01 2.797299e-03 -1.910030e+00 -8.814373e-03 -2.906759e-03 9.999569e-01 1.236242e+02 +9.998641e-01 1.313728e-02 9.963119e-03 -4.622549e-01 -1.315502e-02 9.999120e-01 1.716443e-03 -1.940325e+00 -9.939693e-03 -1.847274e-03 9.999489e-01 1.249835e+02 +9.998377e-01 1.423201e-02 1.105094e-02 -4.641329e-01 -1.424547e-02 9.998979e-01 1.139845e-03 -1.966295e+00 -1.103359e-02 -1.297085e-03 9.999383e-01 1.263371e+02 +9.998388e-01 1.339481e-02 1.195754e-02 -4.708495e-01 -1.340614e-02 9.999097e-01 8.676732e-04 -2.006026e+00 -1.194484e-02 -1.027837e-03 9.999281e-01 1.276925e+02 +9.998362e-01 1.286455e-02 1.272995e-02 -4.718094e-01 -1.288658e-02 9.999156e-01 1.649653e-03 -2.038343e+00 -1.270765e-02 -1.813427e-03 9.999176e-01 1.290496e+02 +9.998371e-01 1.188958e-02 1.357740e-02 -4.742800e-01 -1.193361e-02 9.999238e-01 3.166744e-03 -2.073189e+00 -1.353872e-02 -3.328255e-03 9.999028e-01 1.304070e+02 +9.998441e-01 1.089170e-02 1.389623e-02 -4.701254e-01 -1.093766e-02 9.999349e-01 3.235384e-03 -2.099489e+00 -1.386008e-02 -3.386870e-03 9.998982e-01 1.317557e+02 +9.998649e-01 8.812545e-03 1.387257e-02 -4.656937e-01 -8.863631e-03 9.999541e-01 3.625222e-03 -2.127702e+00 -1.383999e-02 -3.747692e-03 9.998972e-01 1.331097e+02 +9.998827e-01 7.142773e-03 1.354834e-02 -4.651028e-01 -7.199653e-03 9.999654e-01 4.154062e-03 -2.162932e+00 -1.351820e-02 -4.251117e-03 9.998996e-01 1.344614e+02 +9.998996e-01 5.636614e-03 1.300499e-02 -4.661197e-01 -5.686390e-03 9.999766e-01 3.793553e-03 -2.198388e+00 -1.298330e-02 -3.867122e-03 9.999082e-01 1.358146e+02 +9.999228e-01 4.048643e-03 1.174935e-02 -4.644953e-01 -4.092637e-03 9.999847e-01 3.722651e-03 -2.226309e+00 -1.173410e-02 -3.770448e-03 9.999241e-01 1.371606e+02 +9.999391e-01 2.791727e-03 1.067837e-02 -4.645723e-01 -2.842435e-03 9.999847e-01 4.736388e-03 -2.254854e+00 -1.066498e-02 -4.766451e-03 9.999318e-01 1.385124e+02 +9.999526e-01 1.228059e-03 9.656581e-03 -4.641807e-01 -1.276893e-03 9.999864e-01 5.052512e-03 -2.281749e+00 -9.650245e-03 -5.064602e-03 9.999406e-01 1.398626e+02 +9.999650e-01 4.853852e-04 8.355191e-03 -4.674418e-01 -5.268857e-04 9.999875e-01 4.965534e-03 -2.314866e+00 -8.352676e-03 -4.969760e-03 9.999528e-01 1.412129e+02 +9.999748e-01 2.292746e-04 7.102144e-03 -4.704574e-01 -2.612741e-04 9.999898e-01 4.505001e-03 -2.341886e+00 -7.101039e-03 -4.506741e-03 9.999646e-01 1.425622e+02 +9.999816e-01 -1.461826e-04 6.061113e-03 -4.747020e-01 1.219015e-04 9.999919e-01 4.006239e-03 -2.367455e+00 -6.061650e-03 -4.005425e-03 9.999736e-01 1.439099e+02 +9.999856e-01 -1.774247e-03 5.074856e-03 -4.789013e-01 1.762936e-03 9.999959e-01 2.232536e-03 -2.395024e+00 -5.078797e-03 -2.223556e-03 9.999846e-01 1.452578e+02 +9.999656e-01 -7.298614e-03 3.947404e-03 -4.813925e-01 7.295542e-03 9.999730e-01 7.925721e-04 -2.426593e+00 -3.953082e-03 -7.637455e-04 9.999919e-01 1.466011e+02 +9.998967e-01 -1.409568e-02 2.802842e-03 -4.844150e-01 1.408553e-02 9.998943e-01 3.608253e-03 -2.462969e+00 -2.853406e-03 -3.568400e-03 9.999896e-01 1.479538e+02 +9.997630e-01 -2.173080e-02 1.320181e-03 -4.832843e-01 2.172460e-02 9.997536e-01 4.543876e-03 -2.489366e+00 -1.418598e-03 -4.514118e-03 9.999888e-01 1.493030e+02 +9.996862e-01 -2.504947e-02 1.332437e-04 -4.887986e-01 2.504914e-02 9.996840e-01 2.113372e-03 -2.518617e+00 -1.861401e-04 -2.109370e-03 9.999978e-01 1.506481e+02 +9.996841e-01 -2.513252e-02 3.807422e-04 -4.979854e-01 2.513320e-02 9.996823e-01 -1.884703e-03 -2.545628e+00 -3.332535e-04 1.893677e-03 9.999982e-01 1.519917e+02 +9.997662e-01 -2.158749e-02 1.248822e-03 -5.139897e-01 2.159192e-02 9.997602e-01 -3.645129e-03 -2.581792e+00 -1.169833e-03 3.671241e-03 9.999926e-01 1.533373e+02 +9.997705e-01 -2.133187e-02 2.001939e-03 -5.203405e-01 2.133904e-02 9.997657e-01 -3.630061e-03 -2.611885e+00 -1.924034e-03 3.671947e-03 9.999914e-01 1.546843e+02 +9.997071e-01 -2.405938e-02 2.609289e-03 -5.188374e-01 2.406072e-02 9.997104e-01 -4.795238e-04 -2.641449e+00 -2.596996e-03 5.421654e-04 9.999965e-01 1.560329e+02 +9.995597e-01 -2.951217e-02 3.081805e-03 -5.104870e-01 2.950365e-02 9.995608e-01 2.776577e-03 -2.666163e+00 -3.162394e-03 -2.684429e-03 9.999914e-01 1.573829e+02 +9.994284e-01 -3.366699e-02 3.070718e-03 -4.996047e-01 3.365623e-02 9.994273e-01 3.494311e-03 -2.689150e+00 -3.186602e-03 -3.388964e-03 9.999892e-01 1.587319e+02 +9.993665e-01 -3.546242e-02 3.006804e-03 -4.908894e-01 3.545071e-02 9.993639e-01 3.864764e-03 -2.711383e+00 -3.141945e-03 -3.755721e-03 9.999880e-01 1.600786e+02 +9.994176e-01 -3.391111e-02 3.821913e-03 -4.848759e-01 3.389483e-02 9.994163e-01 4.248695e-03 -2.736780e+00 -3.963760e-03 -4.116675e-03 9.999837e-01 1.614290e+02 +9.995379e-01 -2.997704e-02 5.043696e-03 -4.836516e-01 2.995749e-02 9.995435e-01 3.909706e-03 -2.760604e+00 -5.158595e-03 -3.756801e-03 9.999796e-01 1.627788e+02 +9.996297e-01 -2.654347e-02 5.992326e-03 -4.767803e-01 2.653482e-02 9.996467e-01 1.518786e-03 -2.787254e+00 -6.030523e-03 -1.359217e-03 9.999809e-01 1.641295e+02 +9.996963e-01 -2.370307e-02 6.750227e-03 -4.687840e-01 2.369904e-02 9.997189e-01 6.776078e-04 -2.810667e+00 -6.764391e-03 -5.174273e-04 9.999770e-01 1.654807e+02 +9.997390e-01 -2.170098e-02 7.145421e-03 -4.599264e-01 2.168704e-02 9.997627e-01 2.022974e-03 -2.835558e+00 -7.187626e-03 -1.867482e-03 9.999724e-01 1.668390e+02 +9.997748e-01 -2.006189e-02 6.919389e-03 -4.494840e-01 2.004972e-02 9.997973e-01 1.825343e-03 -2.861986e+00 -6.954607e-03 -1.686199e-03 9.999744e-01 1.682000e+02 +9.998149e-01 -1.813299e-02 6.434412e-03 -4.424438e-01 1.813719e-02 9.998353e-01 -5.943430e-04 -2.886560e+00 -6.422575e-03 7.109357e-04 9.999791e-01 1.695602e+02 +9.998753e-01 -1.463466e-02 5.933089e-03 -4.389717e-01 1.465566e-02 9.998864e-01 -3.510450e-03 -2.914240e+00 -5.881041e-03 3.596966e-03 9.999762e-01 1.709198e+02 +9.999362e-01 -9.733294e-03 5.740251e-03 -4.111543e-01 9.761015e-03 9.999407e-01 -4.820709e-03 -2.932731e+00 -5.692989e-03 4.876432e-03 9.999719e-01 1.722841e+02 +9.999686e-01 -5.143146e-03 6.037007e-03 -3.881120e-01 5.167231e-03 9.999787e-01 -3.980535e-03 -2.960771e+00 -6.016406e-03 4.011605e-03 9.999739e-01 1.736528e+02 +9.999768e-01 -1.828108e-03 6.567234e-03 -3.779301e-01 1.838035e-03 9.999972e-01 -1.505773e-03 -2.986448e+00 -6.564463e-03 1.517810e-03 9.999773e-01 1.750291e+02 +9.999765e-01 -1.477610e-03 6.696021e-03 -3.588782e-01 1.474495e-03 9.999988e-01 4.701385e-04 -3.008539e+00 -6.696708e-03 -4.602534e-04 9.999775e-01 1.764086e+02 +9.999731e-01 -4.339593e-03 5.909490e-03 -3.405308e-01 4.328926e-03 9.999890e-01 1.816912e-03 -3.013913e+00 -5.917309e-03 -1.791280e-03 9.999809e-01 1.777852e+02 +9.999673e-01 -6.892799e-03 4.231974e-03 -3.214042e-01 6.885778e-03 9.999749e-01 1.671888e-03 -3.022953e+00 -4.243392e-03 -1.642692e-03 9.999897e-01 1.791607e+02 +9.999709e-01 -7.309297e-03 2.170147e-03 -3.136545e-01 7.314585e-03 9.999703e-01 -2.437950e-03 -3.041123e+00 -2.152263e-03 2.453753e-03 9.999947e-01 1.805420e+02 +9.999803e-01 -6.249158e-03 6.762724e-04 -3.089995e-01 6.253708e-03 9.999563e-01 -6.947885e-03 -3.062100e+00 -6.328241e-04 6.951976e-03 9.999756e-01 1.819214e+02 +9.999989e-01 -1.472010e-03 7.625144e-05 -3.140564e-01 1.472565e-03 9.999679e-01 -7.868715e-03 -3.088158e+00 -6.466581e-05 7.868819e-03 9.999690e-01 1.833098e+02 +9.999966e-01 2.593231e-03 -4.985571e-05 -3.186558e-01 -2.593500e-03 9.999756e-01 -6.476319e-03 -3.114466e+00 3.306026e-05 6.476426e-03 9.999790e-01 1.847039e+02 +9.999907e-01 4.303533e-03 2.334260e-04 -3.141305e-01 -4.302714e-03 9.999849e-01 -3.405586e-03 -3.137555e+00 -2.480782e-04 3.404550e-03 9.999942e-01 1.860994e+02 +9.999868e-01 5.091028e-03 6.512883e-04 -3.087277e-01 -5.090224e-03 9.999863e-01 -1.231497e-03 -3.164478e+00 -6.575487e-04 1.228166e-03 9.999990e-01 1.874988e+02 +9.999898e-01 4.448722e-03 7.330863e-04 -3.089327e-01 -4.448418e-03 9.999900e-01 -4.171905e-04 -3.193945e+00 -7.349346e-04 4.139258e-04 9.999997e-01 1.889003e+02 +9.999954e-01 2.954010e-03 6.755492e-04 -3.070211e-01 -2.954257e-03 9.999955e-01 3.634327e-04 -3.221858e+00 -6.744723e-04 -3.654260e-04 9.999997e-01 1.903048e+02 +9.999997e-01 3.667254e-04 6.633030e-04 -3.030042e-01 -3.672563e-04 9.999996e-01 8.003941e-04 -3.250530e+00 -6.630089e-04 -8.006366e-04 9.999995e-01 1.917128e+02 +9.999968e-01 -2.296786e-03 1.039530e-03 -3.007558e-01 2.295944e-03 9.999970e-01 8.102725e-04 -3.281162e+00 -1.041387e-03 -8.078824e-04 9.999991e-01 1.931213e+02 +9.999851e-01 -5.294323e-03 1.369557e-03 -2.979338e-01 5.291893e-03 9.999844e-01 1.772738e-03 -3.314135e+00 -1.378920e-03 -1.765463e-03 9.999975e-01 1.945397e+02 +9.999546e-01 -9.368607e-03 1.771587e-03 -2.945301e-01 9.362221e-03 9.999497e-01 3.580279e-03 -3.344375e+00 -1.805040e-03 -3.563529e-03 9.999920e-01 1.959592e+02 +9.999160e-01 -1.280487e-02 1.997357e-03 -2.955048e-01 1.279759e-02 9.999115e-01 3.617325e-03 -3.384557e+00 -2.043500e-03 -3.591458e-03 9.999915e-01 1.973809e+02 +9.999376e-01 -1.094347e-02 2.233356e-03 -2.998637e-01 1.094485e-02 9.999399e-01 -6.040287e-04 -3.419365e+00 -2.226612e-03 6.284354e-04 9.999973e-01 1.988011e+02 +9.999866e-01 -4.404760e-03 2.705777e-03 -3.150034e-01 4.421524e-03 9.999709e-01 -6.220738e-03 -3.471363e+00 -2.678297e-03 6.232618e-03 9.999770e-01 2.002242e+02 +9.999803e-01 4.937679e-03 3.867005e-03 -3.321987e-01 -4.911558e-03 9.999652e-01 -6.735801e-03 -3.515079e+00 -3.900129e-03 6.716675e-03 9.999698e-01 2.016573e+02 +9.998989e-01 1.319129e-02 5.303121e-03 -3.485808e-01 -1.317803e-02 9.999099e-01 -2.527297e-03 -3.555576e+00 -5.335981e-03 2.457157e-03 9.999828e-01 2.030948e+02 +9.998740e-01 1.466149e-02 6.089232e-03 -3.518432e-01 -1.466092e-02 9.998925e-01 -1.386890e-04 -3.580327e+00 -6.090611e-03 4.939844e-05 9.999815e-01 2.045325e+02 +9.999049e-01 1.262628e-02 5.556508e-03 -3.481359e-01 -1.262551e-02 9.999203e-01 -1.752367e-04 -3.604083e+00 -5.558278e-03 1.050669e-04 9.999846e-01 2.059704e+02 +9.999449e-01 9.535333e-03 4.390272e-03 -3.438313e-01 -9.534934e-03 9.999545e-01 -1.122394e-04 -3.628674e+00 -4.391142e-03 7.037296e-05 9.999904e-01 2.074183e+02 +9.999698e-01 7.056709e-03 3.265357e-03 -3.421980e-01 -7.056163e-03 9.999751e-01 -1.791660e-04 -3.650886e+00 -3.266540e-03 1.561204e-04 9.999947e-01 2.088679e+02 +9.999687e-01 7.421207e-03 2.746368e-03 -3.429638e-01 -7.418335e-03 9.999719e-01 -1.054972e-03 -3.674360e+00 -2.754120e-03 1.034566e-03 9.999957e-01 2.103232e+02 +9.999572e-01 8.865968e-03 2.639868e-03 -3.479510e-01 -8.863573e-03 9.999603e-01 -9.180181e-04 -3.708945e+00 -2.647902e-03 8.945807e-04 9.999961e-01 2.117849e+02 +9.999457e-01 1.011607e-02 2.524498e-03 -3.533161e-01 -1.011626e-02 9.999488e-01 6.078905e-05 -3.741769e+00 -2.523753e-03 -8.632351e-05 9.999968e-01 2.132453e+02 +9.999520e-01 9.528196e-03 2.287637e-03 -3.575809e-01 -9.528055e-03 9.999546e-01 -7.338614e-05 -3.778065e+00 -2.288232e-03 5.158657e-05 9.999974e-01 2.147142e+02 +9.999567e-01 9.109499e-03 1.882098e-03 -3.574839e-01 -9.106736e-03 9.999574e-01 -1.472665e-03 -3.809987e+00 -1.895433e-03 1.455462e-03 9.999972e-01 2.161864e+02 +9.999636e-01 8.359215e-03 1.687676e-03 -3.559812e-01 -8.356573e-03 9.999638e-01 -1.567357e-03 -3.837087e+00 -1.700717e-03 1.553197e-03 9.999974e-01 2.176615e+02 +9.999613e-01 8.710909e-03 1.240726e-03 -3.604882e-01 -8.709396e-03 9.999613e-01 -1.221145e-03 -3.867619e+00 -1.251315e-03 1.210292e-03 9.999985e-01 2.191419e+02 +9.999614e-01 8.743635e-03 8.939218e-04 -3.669047e-01 -8.742048e-03 9.999602e-01 -1.766652e-03 -3.899694e+00 -9.093329e-04 1.758769e-03 9.999980e-01 2.206192e+02 +9.999611e-01 8.794205e-03 6.937191e-04 -3.711882e-01 -8.792778e-03 9.999592e-01 -2.036552e-03 -3.933170e+00 -7.116004e-04 2.030374e-03 9.999977e-01 2.221053e+02 +9.999510e-01 9.892701e-03 3.480351e-04 -3.755068e-01 -9.891997e-03 9.999491e-01 -1.976626e-03 -3.961696e+00 -3.675712e-04 1.973087e-03 9.999980e-01 2.235894e+02 +9.999545e-01 9.535271e-03 3.060761e-06 -3.771503e-01 -9.535239e-03 9.999517e-01 -2.380069e-03 -3.990503e+00 -2.575488e-05 2.379932e-03 9.999972e-01 2.250789e+02 +9.999496e-01 1.003812e-02 -2.604534e-04 -3.787707e-01 -1.003868e-02 9.999470e-01 -2.264917e-03 -4.017067e+00 2.377044e-04 2.267418e-03 9.999974e-01 2.265691e+02 +9.999586e-01 9.094606e-03 -3.650914e-04 -3.785266e-01 -9.095365e-03 9.999563e-01 -2.127619e-03 -4.048136e+00 3.457260e-04 2.130852e-03 9.999977e-01 2.280602e+02 +9.999692e-01 7.840322e-03 -2.576861e-04 -3.786614e-01 -7.841006e-03 9.999654e-01 -2.764804e-03 -4.075078e+00 2.360006e-04 2.766740e-03 9.999962e-01 2.295511e+02 +9.999775e-01 6.708944e-03 -8.900665e-05 -3.766086e-01 -6.709141e-03 9.999746e-01 -2.414917e-03 -4.099044e+00 7.280319e-05 2.415460e-03 9.999971e-01 2.310454e+02 +9.999869e-01 5.120322e-03 1.128453e-04 -3.745701e-01 -5.120128e-03 9.999855e-01 -1.666319e-03 -4.124994e+00 -1.213754e-04 1.665719e-03 9.999986e-01 2.325421e+02 +9.999877e-01 4.961834e-03 1.048822e-04 -3.739626e-01 -4.961702e-03 9.999869e-01 -1.231555e-03 -4.153624e+00 -1.109912e-04 1.231020e-03 9.999992e-01 2.340378e+02 +9.999858e-01 5.337975e-03 2.022159e-05 -3.764692e-01 -5.337943e-03 9.999848e-01 -1.389784e-03 -4.186333e+00 -2.763958e-05 1.389656e-03 9.999990e-01 2.355390e+02 +9.999818e-01 6.028187e-03 2.363445e-04 -3.784077e-01 -6.027547e-03 9.999784e-01 -2.625311e-03 -4.220226e+00 -2.521649e-04 2.623838e-03 9.999965e-01 2.370446e+02 +9.999731e-01 7.300761e-03 7.680277e-04 -3.814943e-01 -7.299344e-03 9.999717e-01 -1.833168e-03 -4.253315e+00 -7.813891e-04 1.827513e-03 9.999980e-01 2.385499e+02 +9.999700e-01 7.615056e-03 1.421637e-03 -3.829065e-01 -7.615902e-03 9.999708e-01 5.892762e-04 -4.285388e+00 -1.417108e-03 -6.000848e-04 9.999988e-01 2.400603e+02 +9.999712e-01 7.345183e-03 1.934962e-03 -3.820924e-01 -7.347076e-03 9.999725e-01 9.725281e-04 -4.315103e+00 -1.927765e-03 -9.867155e-04 9.999977e-01 2.415712e+02 +9.999683e-01 7.596371e-03 2.404236e-03 -3.818797e-01 -7.594896e-03 9.999709e-01 -6.227482e-04 -4.347138e+00 -2.408896e-03 6.044691e-04 9.999969e-01 2.430873e+02 +9.999670e-01 7.564991e-03 2.950398e-03 -3.796393e-01 -7.559141e-03 9.999694e-01 -1.989576e-03 -4.377646e+00 -2.965359e-03 1.967208e-03 9.999937e-01 2.446020e+02 +9.999578e-01 8.594224e-03 3.260437e-03 -3.770780e-01 -8.589250e-03 9.999619e-01 -1.537157e-03 -4.404696e+00 -3.273523e-03 1.509088e-03 9.999935e-01 2.461231e+02 +9.999617e-01 8.101687e-03 3.326840e-03 -3.721572e-01 -8.099747e-03 9.999670e-01 -5.968841e-04 -4.432022e+00 -3.331566e-03 5.699152e-04 9.999943e-01 2.476477e+02 +9.999620e-01 8.179632e-03 3.022564e-03 -3.683885e-01 -8.180107e-03 9.999665e-01 1.440039e-04 -4.458219e+00 -3.021285e-03 -1.687226e-04 9.999954e-01 2.491682e+02 +9.999599e-01 8.505824e-03 2.798118e-03 -3.658944e-01 -8.507187e-03 9.999637e-01 4.745749e-04 -4.487063e+00 -2.793979e-03 -4.983592e-04 9.999960e-01 2.506964e+02 +9.999463e-01 9.971468e-03 2.839532e-03 -3.629857e-01 -9.973122e-03 9.999501e-01 5.680798e-04 -4.511301e+00 -2.833726e-03 -5.963674e-04 9.999958e-01 2.522241e+02 +9.999354e-01 1.095121e-02 3.044268e-03 -3.598899e-01 -1.095307e-02 9.999398e-01 5.963360e-04 -4.535745e+00 -3.037554e-03 -6.296408e-04 9.999952e-01 2.537570e+02 +9.999290e-01 1.155157e-02 2.931934e-03 -3.565283e-01 -1.155344e-02 9.999330e-01 6.206596e-04 -4.558441e+00 -2.924568e-03 -6.544886e-04 9.999955e-01 2.552885e+02 +9.999459e-01 9.972903e-03 2.944504e-03 -3.518994e-01 -9.975714e-03 9.999498e-01 9.406382e-04 -4.584940e+00 -2.934975e-03 -9.699600e-04 9.999952e-01 2.568230e+02 +9.999600e-01 8.473834e-03 2.849624e-03 -3.474488e-01 -8.479116e-03 9.999623e-01 1.846164e-03 -4.611578e+00 -2.833873e-03 -1.870251e-03 9.999942e-01 2.583612e+02 +9.999798e-01 5.649029e-03 2.911618e-03 -3.407995e-01 -5.657374e-03 9.999799e-01 2.865668e-03 -4.637604e+00 -2.895371e-03 -2.882081e-03 9.999917e-01 2.599003e+02 +9.999882e-01 4.111334e-03 2.589962e-03 -3.346776e-01 -4.116750e-03 9.999893e-01 2.088632e-03 -4.662237e+00 -2.581348e-03 -2.099269e-03 9.999945e-01 2.614352e+02 +9.999932e-01 2.887471e-03 2.307492e-03 -3.291338e-01 -2.889040e-03 9.999956e-01 6.765815e-04 -4.686551e+00 -2.305528e-03 -6.832424e-04 9.999971e-01 2.629731e+02 +9.999954e-01 9.355651e-04 2.883662e-03 -3.253738e-01 -9.427296e-04 9.999964e-01 2.484078e-03 -4.715745e+00 -2.881328e-03 -2.486784e-03 9.999928e-01 2.645113e+02 +9.999945e-01 -1.234139e-04 3.329163e-03 -3.249046e-01 1.067289e-04 9.999874e-01 5.011498e-03 -4.748173e+00 -3.329740e-03 -5.011114e-03 9.999819e-01 2.660572e+02 +9.999919e-01 -2.066105e-03 3.459414e-03 -3.208179e-01 2.052234e-03 9.999898e-01 4.008459e-03 -4.788372e+00 -3.467660e-03 -4.001325e-03 9.999860e-01 2.675981e+02 +9.999887e-01 -2.908690e-03 3.750876e-03 -3.173943e-01 2.899428e-03 9.999927e-01 2.472455e-03 -4.824679e+00 -3.758040e-03 -2.461551e-03 9.999899e-01 2.691377e+02 +9.999885e-01 -1.938031e-03 4.395994e-03 -3.166024e-01 1.927536e-03 9.999953e-01 2.390467e-03 -4.866052e+00 -4.400606e-03 -2.381965e-03 9.999875e-01 2.706771e+02 +9.999849e-01 -4.661324e-04 5.479803e-03 -3.155943e-01 4.509532e-04 9.999960e-01 2.770953e-03 -4.906588e+00 -5.481073e-03 -2.768439e-03 9.999812e-01 2.722185e+02 +9.999785e-01 1.232933e-03 6.440203e-03 -3.140401e-01 -1.248098e-03 9.999964e-01 2.351180e-03 -4.950219e+00 -6.437281e-03 -2.359167e-03 9.999765e-01 2.737649e+02 +9.999697e-01 2.424589e-03 7.402642e-03 -3.112309e-01 -2.441393e-03 9.999944e-01 2.261700e-03 -4.987626e+00 -7.397117e-03 -2.279703e-03 9.999701e-01 2.753072e+02 +9.999614e-01 3.182729e-03 8.193149e-03 -3.114206e-01 -3.198390e-03 9.999931e-01 1.899045e-03 -5.039836e+00 -8.187048e-03 -1.925175e-03 9.999646e-01 2.768535e+02 +9.999530e-01 3.540242e-03 9.029623e-03 -3.062026e-01 -3.552063e-03 9.999928e-01 1.293327e-03 -5.082755e+00 -9.024980e-03 -1.325339e-03 9.999584e-01 2.783952e+02 +9.999461e-01 3.002326e-03 9.935417e-03 -3.011292e-01 -3.010760e-03 9.999951e-01 8.339534e-04 -5.134136e+00 -9.932865e-03 -8.638208e-04 9.999503e-01 2.799451e+02 +9.999391e-01 2.412082e-03 1.077454e-02 -2.897536e-01 -2.422969e-03 9.999965e-01 9.974198e-04 -5.172038e+00 -1.077210e-02 -1.023464e-03 9.999415e-01 2.814958e+02 +9.999325e-01 1.490615e-03 1.152157e-02 -2.764899e-01 -1.517343e-03 9.999962e-01 2.311413e-03 -5.210037e+00 -1.151808e-02 -2.328738e-03 9.999310e-01 2.830498e+02 +9.999296e-01 6.994984e-05 1.186441e-02 -2.599233e-01 -1.024084e-04 9.999962e-01 2.735204e-03 -5.241690e+00 -1.186417e-02 -2.736226e-03 9.999259e-01 2.846005e+02 +9.999287e-01 -5.783054e-04 1.192680e-02 -2.447296e-01 5.738058e-04 9.999997e-01 3.807036e-04 -5.277598e+00 -1.192702e-02 -3.738321e-04 9.999288e-01 2.861454e+02 +9.999319e-01 -1.492295e-03 1.157237e-02 -2.301583e-01 1.517665e-03 9.999964e-01 -2.183831e-03 -5.316244e+00 -1.156907e-02 2.201245e-03 9.999307e-01 2.876999e+02 +9.999418e-01 -1.171813e-03 1.072948e-02 -2.170805e-01 1.198557e-03 9.999962e-01 -2.486478e-03 -5.355148e+00 -1.072652e-02 2.499193e-03 9.999394e-01 2.892536e+02 +9.999459e-01 -2.783388e-03 1.002137e-02 -2.045251e-01 2.801633e-03 9.999944e-01 -1.806982e-03 -5.390475e+00 -1.001629e-02 1.834961e-03 9.999482e-01 2.908103e+02 +9.999558e-01 -2.681787e-03 9.007871e-03 -1.926927e-01 2.703689e-03 9.999934e-01 -2.419995e-03 -5.424878e+00 -9.001322e-03 2.444243e-03 9.999565e-01 2.923692e+02 +9.999614e-01 -2.412034e-03 8.447233e-03 -1.828271e-01 2.434845e-03 9.999934e-01 -2.691088e-03 -5.462578e+00 -8.440686e-03 2.711552e-03 9.999607e-01 2.939316e+02 +9.999673e-01 -2.373487e-03 7.737565e-03 -1.753107e-01 2.390449e-03 9.999947e-01 -2.183543e-03 -5.502144e+00 -7.732342e-03 2.201968e-03 9.999677e-01 2.955007e+02 +9.999723e-01 -2.819612e-03 6.887209e-03 -1.681708e-01 2.832591e-03 9.999942e-01 -1.875372e-03 -5.542654e+00 -6.881881e-03 1.894829e-03 9.999745e-01 2.970723e+02 +9.999769e-01 -3.466837e-03 5.851379e-03 -1.571664e-01 3.473314e-03 9.999933e-01 -1.096977e-03 -5.573209e+00 -5.847537e-03 1.117276e-03 9.999823e-01 2.986502e+02 +9.999842e-01 -1.884748e-03 5.291489e-03 -1.498301e-01 1.882308e-03 9.999981e-01 4.661426e-04 -5.605662e+00 -5.292358e-03 -4.561742e-04 9.999859e-01 3.002367e+02 +9.999815e-01 -1.358135e-03 5.923153e-03 -1.436567e-01 1.352001e-03 9.999985e-01 1.039545e-03 -5.638056e+00 -5.924556e-03 -1.031517e-03 9.999819e-01 3.018211e+02 +9.999759e-01 -7.817355e-04 6.894868e-03 -1.362308e-01 7.782359e-04 9.999995e-01 5.102687e-04 -5.674045e+00 -6.895264e-03 -5.048898e-04 9.999761e-01 3.034130e+02 +9.999714e-01 -2.066171e-03 7.276388e-03 -1.245796e-01 2.065775e-03 9.999978e-01 6.192163e-05 -5.704927e+00 -7.276500e-03 -4.688778e-05 9.999735e-01 3.050095e+02 +9.999651e-01 -3.784307e-03 7.453066e-03 -1.113075e-01 3.790433e-03 9.999925e-01 -8.078684e-04 -5.740563e+00 -7.449952e-03 8.360910e-04 9.999719e-01 3.066086e+02 +9.999552e-01 -5.428677e-03 7.758261e-03 -1.009905e-01 5.450080e-03 9.999814e-01 -2.740138e-03 -5.775938e+00 -7.743241e-03 2.782299e-03 9.999662e-01 3.082116e+02 +9.999537e-01 -5.687325e-03 7.763489e-03 -9.649990e-02 5.716383e-03 9.999767e-01 -3.725647e-03 -5.821106e+00 -7.742119e-03 3.769853e-03 9.999629e-01 3.098189e+02 +9.999708e-01 -5.147094e-03 5.644397e-03 -9.324941e-02 5.173322e-03 9.999758e-01 -4.641742e-03 -5.863046e+00 -5.620369e-03 4.670807e-03 9.999733e-01 3.114331e+02 +9.999850e-01 -4.221316e-03 3.496670e-03 -9.658434e-02 4.236103e-03 9.999820e-01 -4.231981e-03 -5.907766e+00 -3.478743e-03 4.246730e-03 9.999849e-01 3.130445e+02 +9.999922e-01 -2.484768e-03 3.084130e-03 -1.065230e-01 2.488109e-03 9.999963e-01 -1.079636e-03 -5.952029e+00 -3.081436e-03 1.087301e-03 9.999947e-01 3.146682e+02 +9.999867e-01 -3.716961e-03 3.583983e-03 -1.079811e-01 3.709068e-03 9.999907e-01 2.206630e-03 -5.990688e+00 -3.592151e-03 -2.193306e-03 9.999912e-01 3.162953e+02 +9.999815e-01 -4.767094e-03 3.790247e-03 -1.086696e-01 4.755540e-03 9.999840e-01 3.051853e-03 -6.032426e+00 -3.804734e-03 -3.033771e-03 9.999882e-01 3.179241e+02 +9.999725e-01 -6.194818e-03 4.072383e-03 -1.058419e-01 6.187770e-03 9.999793e-01 1.741229e-03 -6.068362e+00 -4.083086e-03 -1.715981e-03 9.999902e-01 3.195525e+02 +9.999660e-01 -6.964861e-03 4.412163e-03 -1.039698e-01 6.957070e-03 9.999742e-01 1.779038e-03 -6.106845e+00 -4.424440e-03 -1.748280e-03 9.999887e-01 3.211823e+02 +9.999660e-01 -6.841180e-03 4.609291e-03 -1.009179e-01 6.831105e-03 9.999742e-01 2.198320e-03 -6.143404e+00 -4.624211e-03 -2.166758e-03 9.999870e-01 3.228139e+02 +9.999627e-01 -6.976154e-03 5.098733e-03 -9.883113e-02 6.966045e-03 9.999737e-01 1.998024e-03 -6.185282e+00 -5.112538e-03 -1.962430e-03 9.999850e-01 3.244397e+02 +9.999691e-01 -5.531858e-03 5.582557e-03 -9.648438e-02 5.524152e-03 9.999837e-01 1.395066e-03 -6.224088e+00 -5.590184e-03 -1.364183e-03 9.999835e-01 3.260682e+02 +9.999692e-01 -4.739913e-03 6.254823e-03 -9.411052e-02 4.736022e-03 9.999886e-01 6.369864e-04 -6.268819e+00 -6.257771e-03 -6.073430e-04 9.999802e-01 3.276976e+02 +9.999576e-01 -5.867213e-03 7.096038e-03 -8.496956e-02 5.850059e-03 9.999799e-01 2.435870e-03 -6.305428e+00 -7.110188e-03 -2.394254e-03 9.999719e-01 3.293242e+02 +9.999510e-01 -6.766778e-03 7.224057e-03 -7.442718e-02 6.741273e-03 9.999710e-01 3.549352e-03 -6.342113e+00 -7.247865e-03 -3.500477e-03 9.999676e-01 3.309508e+02 +9.999441e-01 -7.988538e-03 6.922601e-03 -6.421231e-02 7.974252e-03 9.999660e-01 2.089082e-03 -6.372244e+00 -6.939054e-03 -2.033762e-03 9.999739e-01 3.325694e+02 +9.999502e-01 -7.183819e-03 6.934729e-03 -5.844895e-02 7.168776e-03 9.999719e-01 2.191934e-03 -6.413497e+00 -6.950281e-03 -2.142110e-03 9.999736e-01 3.341893e+02 +9.999652e-01 -4.787434e-03 6.833316e-03 -5.434961e-02 4.781851e-03 9.999882e-01 8.332573e-04 -6.450780e+00 -6.837225e-03 -8.005516e-04 9.999763e-01 3.358024e+02 +9.999750e-01 -3.571959e-03 6.109299e-03 -4.949748e-02 3.593288e-03 9.999875e-01 -3.483711e-03 -6.492551e+00 -6.096779e-03 3.505576e-03 9.999753e-01 3.374097e+02 +9.999843e-01 -1.994183e-03 5.234120e-03 -4.548042e-02 2.006544e-03 9.999952e-01 -2.357182e-03 -6.532188e+00 -5.229394e-03 2.367648e-03 9.999835e-01 3.390211e+02 +9.999894e-01 -1.462301e-03 4.362284e-03 -4.257007e-02 1.457657e-03 9.999983e-01 1.067779e-03 -6.571397e+00 -4.363838e-03 -1.061409e-03 9.999899e-01 3.406287e+02 +9.999945e-01 -2.826640e-04 3.299426e-03 -3.930296e-02 2.684306e-04 9.999906e-01 4.313590e-03 -6.601811e+00 -3.300614e-03 -4.312679e-03 9.999853e-01 3.422462e+02 +9.999978e-01 2.062417e-04 2.091700e-03 -3.681003e-02 -2.126335e-04 9.999953e-01 3.056043e-03 -6.628918e+00 -2.091059e-03 -3.056480e-03 9.999932e-01 3.438528e+02 +9.999999e-01 -4.441106e-04 2.716568e-04 -3.514659e-02 4.438341e-04 9.999994e-01 1.017490e-03 -6.652782e+00 -2.721082e-04 -1.017369e-03 9.999995e-01 3.454525e+02 +9.999977e-01 -1.439658e-03 -1.625805e-03 -3.454790e-02 1.443853e-03 9.999956e-01 2.581640e-03 -6.677644e+00 1.622082e-03 -2.583980e-03 9.999954e-01 3.470554e+02 +9.999919e-01 -3.062606e-03 -2.625489e-03 -3.707175e-02 3.071647e-03 9.999893e-01 3.446059e-03 -6.708152e+00 2.614908e-03 -3.454094e-03 9.999906e-01 3.486551e+02 +9.999897e-01 -3.341987e-03 -3.057511e-03 -4.156332e-02 3.349607e-03 9.999913e-01 2.490201e-03 -6.737239e+00 3.049163e-03 -2.500416e-03 9.999922e-01 3.502532e+02 +9.999866e-01 -4.006270e-03 -3.273666e-03 -5.261018e-02 4.011489e-03 9.999907e-01 1.588782e-03 -6.773059e+00 3.267271e-03 -1.601892e-03 9.999934e-01 3.518478e+02 +9.999863e-01 -4.071348e-03 -3.294287e-03 -6.277075e-02 4.076787e-03 9.999903e-01 1.645910e-03 -6.805862e+00 3.287555e-03 -1.659316e-03 9.999932e-01 3.534464e+02 +9.999843e-01 -4.565924e-03 -3.263315e-03 -7.506606e-02 4.570743e-03 9.999884e-01 1.470618e-03 -6.843564e+00 3.256563e-03 -1.485510e-03 9.999936e-01 3.550379e+02 +9.999810e-01 -5.215829e-03 -3.293599e-03 -8.570356e-02 5.218715e-03 9.999860e-01 8.679440e-04 -6.882552e+00 3.289027e-03 -8.851150e-04 9.999942e-01 3.566308e+02 +9.999796e-01 -5.401737e-03 -3.418004e-03 -9.729989e-02 5.402475e-03 9.999854e-01 2.062371e-04 -6.921763e+00 3.416841e-03 -2.246978e-04 9.999941e-01 3.582218e+02 +9.999770e-01 -5.897304e-03 -3.345777e-03 -1.091014e-01 5.899221e-03 9.999824e-01 5.628509e-04 -6.958715e+00 3.342400e-03 -5.825747e-04 9.999943e-01 3.598125e+02 +9.999797e-01 -5.468744e-03 -3.269773e-03 -1.223014e-01 5.467336e-03 9.999849e-01 -4.395206e-04 -6.995935e+00 3.272128e-03 4.216354e-04 9.999946e-01 3.614037e+02 +9.999705e-01 -6.990990e-03 -3.199392e-03 -1.322206e-01 6.985695e-03 9.999742e-01 -1.663812e-03 -7.034017e+00 3.210942e-03 1.641413e-03 9.999935e-01 3.629890e+02 +9.999604e-01 -8.343867e-03 -3.084171e-03 -1.419952e-01 8.343344e-03 9.999652e-01 -1.830997e-04 -7.072717e+00 3.085592e-03 1.573608e-04 9.999952e-01 3.645867e+02 +9.999448e-01 -1.000719e-02 -3.215683e-03 -1.552999e-01 1.001035e-02 9.999494e-01 9.681153e-04 -7.112398e+00 3.205833e-03 -1.000251e-03 9.999944e-01 3.661838e+02 +9.999393e-01 -1.055761e-02 -3.163105e-03 -1.668615e-01 1.055852e-02 9.999442e-01 2.692067e-04 -7.146884e+00 3.160086e-03 -3.025873e-04 9.999950e-01 3.677811e+02 +9.999515e-01 -9.444498e-03 -2.786077e-03 -1.858911e-01 9.442854e-03 9.999552e-01 -6.033254e-04 -7.188290e+00 2.791651e-03 5.769883e-04 9.999959e-01 3.693866e+02 +9.999697e-01 -7.434945e-03 -2.307470e-03 -2.029185e-01 7.436476e-03 9.999721e-01 6.546484e-04 -7.225081e+00 2.302539e-03 -6.717872e-04 9.999971e-01 3.709753e+02 +9.999798e-01 -6.100116e-03 -1.805530e-03 -2.229981e-01 6.101847e-03 9.999809e-01 9.540591e-04 -7.268840e+00 1.799676e-03 -9.650559e-04 9.999979e-01 3.726154e+02 +9.999827e-01 -5.698435e-03 -1.435322e-03 -2.378134e-01 5.699452e-03 9.999835e-01 7.046586e-04 -7.306808e+00 1.431283e-03 -7.128262e-04 9.999987e-01 3.742253e+02 +9.999820e-01 -5.879431e-03 -1.199967e-03 -2.519893e-01 5.879326e-03 9.999827e-01 -9.211550e-05 -7.344936e+00 1.200488e-03 8.505955e-05 9.999993e-01 3.757811e+02 +9.999832e-01 -5.717950e-03 -9.178671e-04 -2.625878e-01 5.717644e-03 9.999836e-01 -3.368161e-04 -7.379336e+00 9.197784e-04 3.315630e-04 9.999995e-01 3.773873e+02 +9.999855e-01 -5.335829e-03 -6.929259e-04 -2.704012e-01 5.335561e-03 9.999857e-01 -3.900621e-04 -7.414418e+00 6.949976e-04 3.863599e-04 9.999997e-01 3.789929e+02 +9.999912e-01 -4.183305e-03 -3.813569e-04 -2.783585e-01 4.183203e-03 9.999912e-01 -2.705875e-04 -7.448411e+00 3.824859e-04 2.689904e-04 9.999999e-01 3.806071e+02 +9.999958e-01 -2.891363e-03 -5.685947e-05 -2.877925e-01 2.891389e-03 9.999957e-01 4.518743e-04 -7.485057e+00 5.555304e-05 -4.520360e-04 9.999999e-01 3.822202e+02 +9.999985e-01 -1.738505e-03 2.114522e-04 -2.960866e-01 1.738539e-03 9.999985e-01 -1.625976e-04 -7.522079e+00 -2.111689e-04 1.629656e-04 1.000000e+00 3.838408e+02 +9.999995e-01 -8.743833e-04 4.812968e-04 -3.039652e-01 8.747432e-04 9.999993e-01 -7.476725e-04 -7.558709e+00 -4.806424e-04 7.480937e-04 9.999996e-01 3.854512e+02 +9.999997e-01 -1.279523e-04 8.073792e-04 -3.110174e-01 1.284791e-04 9.999998e-01 -6.525093e-04 -7.596748e+00 -8.072952e-04 6.526134e-04 9.999995e-01 3.870678e+02 +9.999988e-01 1.116543e-03 1.060919e-03 -3.164538e-01 -1.116826e-03 9.999993e-01 2.659665e-04 -7.631598e+00 -1.060621e-03 -2.671503e-04 9.999994e-01 3.886857e+02 +9.999964e-01 2.241238e-03 1.452395e-03 -3.206582e-01 -2.242667e-03 9.999970e-01 9.825513e-04 -7.664429e+00 -1.450189e-03 -9.858042e-04 9.999985e-01 3.903059e+02 +9.999941e-01 2.903367e-03 1.839558e-03 -3.238003e-01 -2.903950e-03 9.999957e-01 3.144580e-04 -7.696195e+00 -1.838637e-03 -3.197974e-04 9.999983e-01 3.919359e+02 +9.999935e-01 2.925452e-03 2.091742e-03 -3.237896e-01 -2.926418e-03 9.999956e-01 4.584597e-04 -7.731691e+00 -2.090391e-03 -4.645773e-04 9.999977e-01 3.935579e+02 diff --git a/tools/Ground-Truth/dataset/poses/05.txt b/tools/Ground-Truth/dataset/poses/05.txt new file mode 100644 index 0000000..d6ab56e --- /dev/null +++ b/tools/Ground-Truth/dataset/poses/05.txt @@ -0,0 +1,2761 @@ +1.000000e+00 1.197625e-11 1.704638e-10 1.110223e-16 1.197625e-11 1.000000e+00 3.562503e-10 0.000000e+00 1.704638e-10 3.562503e-10 1.000000e+00 2.220446e-16 +9.999968e-01 -1.958988e-03 -1.630129e-03 3.499723e-03 1.957401e-03 9.999976e-01 -9.745057e-04 -9.789328e-03 1.632035e-03 9.713123e-04 9.999982e-01 5.653511e-01 +9.999931e-01 -2.475044e-03 -2.755837e-03 1.173954e-03 2.468662e-03 9.999942e-01 -2.316828e-03 -2.241474e-02 2.761556e-03 2.310009e-03 9.999935e-01 1.127607e+00 +9.999863e-01 -2.528164e-03 -4.580897e-03 -7.831705e-03 2.512020e-03 9.999906e-01 -3.526615e-03 -4.141091e-02 4.589771e-03 3.515059e-03 9.999833e-01 1.689225e+00 +9.999675e-01 -4.648687e-03 -6.595320e-03 -1.508128e-02 4.612815e-03 9.999745e-01 -5.443974e-03 -5.922720e-02 6.620460e-03 5.413373e-03 9.999634e-01 2.251296e+00 +9.999413e-01 -7.134576e-03 -8.152763e-03 -2.040073e-02 7.072901e-03 9.999463e-01 -7.569121e-03 -7.423248e-02 8.206328e-03 7.511012e-03 9.999381e-01 2.816072e+00 +9.999200e-01 -8.311338e-03 -9.539068e-03 -2.969353e-02 8.230327e-03 9.999300e-01 -8.500812e-03 -9.078265e-02 9.609054e-03 8.421622e-03 9.999184e-01 3.390281e+00 +9.999041e-01 -8.525348e-03 -1.091073e-02 -4.152744e-02 8.441127e-03 9.999344e-01 -7.742225e-03 -1.098544e-01 1.097602e-02 7.649383e-03 9.999105e-01 3.969489e+00 +9.998884e-01 -8.811524e-03 -1.206613e-02 -5.593704e-02 8.715868e-03 9.999303e-01 -7.957589e-03 -1.348021e-01 1.213540e-02 7.851533e-03 9.998955e-01 4.556204e+00 +9.998780e-01 -8.278892e-03 -1.324786e-02 -7.008098e-02 8.141373e-03 9.999127e-01 -1.040105e-02 -1.575514e-01 1.333281e-02 1.029192e-02 9.998582e-01 5.150463e+00 +9.998748e-01 -6.580037e-03 -1.439059e-02 -8.798198e-02 6.374276e-03 9.998774e-01 -1.429781e-02 -1.803479e-01 1.448291e-02 1.420429e-02 9.997942e-01 5.751285e+00 +9.998652e-01 -5.082827e-03 -1.561247e-02 -1.054713e-01 4.800847e-03 9.998256e-01 -1.804597e-02 -1.996581e-01 1.570147e-02 1.796859e-02 9.997153e-01 6.363942e+00 +9.998522e-01 -3.623834e-03 -1.680538e-02 -1.238576e-01 3.306955e-03 9.998169e-01 -1.884543e-02 -2.187844e-01 1.687060e-02 1.878706e-02 9.996812e-01 6.989627e+00 +9.998394e-01 -1.112536e-03 -1.788542e-02 -1.444743e-01 8.907687e-04 9.999227e-01 -1.240253e-02 -2.366165e-01 1.789783e-02 1.238460e-02 9.997631e-01 7.637602e+00 +9.998258e-01 -8.672136e-05 -1.866531e-02 -1.645124e-01 5.358731e-05 9.999984e-01 -1.775663e-03 -2.542635e-01 1.866543e-02 1.774354e-03 9.998242e-01 8.302111e+00 +9.998120e-01 1.004604e-03 -1.936675e-02 -1.844755e-01 -8.989153e-04 9.999846e-01 5.465141e-03 -2.738044e-01 1.937194e-02 -5.446702e-03 9.997975e-01 8.978383e+00 +9.997817e-01 3.389970e-03 -2.061746e-02 -2.077191e-01 -3.275843e-03 9.999791e-01 5.566728e-03 -2.924369e-01 2.063590e-02 -5.497971e-03 9.997719e-01 9.661917e+00 +9.997543e-01 5.555763e-03 -2.145926e-02 -2.329992e-01 -5.595211e-03 9.999827e-01 -1.778629e-03 -3.035717e-01 2.144901e-02 1.898261e-03 9.997682e-01 1.035368e+01 +9.997369e-01 4.812930e-03 -2.242765e-02 -2.537940e-01 -5.013394e-03 9.999479e-01 -8.890577e-03 -3.091782e-01 2.238369e-02 9.000675e-03 9.997089e-01 1.106423e+01 +9.997145e-01 2.620743e-03 -2.375049e-02 -2.701280e-01 -2.819209e-03 9.999613e-01 -8.326642e-03 -3.152238e-01 2.372775e-02 8.391221e-03 9.996832e-01 1.179839e+01 +9.997063e-01 1.893748e-03 -2.416094e-02 -2.821162e-01 -1.858131e-03 9.999971e-01 1.496504e-03 -3.207015e-01 2.416371e-02 -1.451169e-03 9.997070e-01 1.255870e+01 +9.996966e-01 1.625146e-03 -2.457882e-02 -2.962122e-01 -1.393167e-03 9.999543e-01 9.452361e-03 -3.252216e-01 2.459306e-02 -9.415248e-03 9.996532e-01 1.333520e+01 +9.996863e-01 7.583641e-04 -2.503532e-02 -3.128296e-01 -4.521018e-04 9.999250e-01 1.223661e-02 -3.292075e-01 2.504272e-02 -1.222145e-02 9.996117e-01 1.412399e+01 +9.996792e-01 -1.382699e-03 -2.529212e-02 -3.270868e-01 1.667549e-03 9.999354e-01 1.124476e-02 -3.300205e-01 2.527494e-02 -1.128333e-02 9.996169e-01 1.492763e+01 +9.996851e-01 -2.198699e-03 -2.499779e-02 -3.451203e-01 2.413900e-03 9.999602e-01 8.581850e-03 -3.298600e-01 2.497793e-02 -8.639487e-03 9.996507e-01 1.574882e+01 +9.997041e-01 5.747479e-05 -2.432655e-02 -3.585571e-01 6.660546e-05 9.999870e-01 5.099768e-03 -3.310784e-01 2.432653e-02 -5.099877e-03 9.996911e-01 1.658175e+01 +9.997240e-01 -2.636624e-03 -2.334610e-02 -3.661096e-01 2.632565e-03 9.999965e-01 -2.046126e-04 -3.374209e-01 2.334656e-02 1.430967e-04 9.997274e-01 1.742810e+01 +9.997263e-01 -5.544119e-03 -2.272786e-02 -3.686442e-01 5.399776e-03 9.999649e-01 -6.407463e-03 -3.506532e-01 2.276259e-02 6.282984e-03 9.997212e-01 1.828806e+01 +9.997553e-01 -5.085930e-03 -2.153036e-02 -3.812873e-01 4.819452e-03 9.999113e-01 -1.241078e-02 -3.643232e-01 2.159157e-02 1.230397e-02 9.996912e-01 1.916967e+01 +9.997662e-01 -3.838836e-03 -2.127843e-02 -3.931436e-01 3.555293e-03 9.999046e-01 -1.334729e-02 -3.836280e-01 2.132764e-02 1.326852e-02 9.996845e-01 2.007060e+01 +9.997622e-01 -3.422674e-03 -2.153588e-02 -4.065575e-01 3.148129e-03 9.999135e-01 -1.276932e-02 -4.078809e-01 2.157773e-02 1.269848e-02 9.996865e-01 2.099062e+01 +9.997668e-01 -2.204438e-03 -2.148374e-02 -4.196580e-01 1.910245e-03 9.999042e-01 -1.370467e-02 -4.350658e-01 2.151189e-02 1.366044e-02 9.996753e-01 2.192489e+01 +9.997726e-01 4.687529e-04 -2.131795e-02 -4.375606e-01 -8.075310e-04 9.998735e-01 -1.588585e-02 -4.631430e-01 2.130781e-02 1.589945e-02 9.996465e-01 2.287774e+01 +9.997643e-01 4.013694e-03 -2.133588e-02 -4.507315e-01 -4.371519e-03 9.998501e-01 -1.675089e-02 -4.913797e-01 2.126545e-02 1.684021e-02 9.996320e-01 2.384921e+01 +9.997576e-01 5.791203e-03 -2.123996e-02 -4.686400e-01 -6.143965e-03 9.998436e-01 -1.658089e-02 -5.208191e-01 2.114062e-02 1.670737e-02 9.996369e-01 2.482497e+01 +9.997475e-01 6.655410e-03 -2.146389e-02 -4.870736e-01 -7.009523e-03 9.998398e-01 -1.646518e-02 -5.504866e-01 2.135087e-02 1.661147e-02 9.996340e-01 2.580752e+01 +9.997432e-01 6.684038e-03 -2.165237e-02 -5.055765e-01 -7.043805e-03 9.998377e-01 -1.658208e-02 -5.806979e-01 2.153803e-02 1.673033e-02 9.996280e-01 2.679489e+01 +9.997300e-01 7.470019e-03 -2.200512e-02 -5.258752e-01 -7.810435e-03 9.998505e-01 -1.542467e-02 -6.123111e-01 2.188661e-02 1.559237e-02 9.996389e-01 2.779590e+01 +9.997180e-01 8.169161e-03 -2.229874e-02 -5.464848e-01 -8.471998e-03 9.998727e-01 -1.352028e-02 -6.430976e-01 2.218546e-02 1.370538e-02 9.996599e-01 2.880310e+01 +9.997048e-01 8.828655e-03 -2.263483e-02 -5.679163e-01 -9.107452e-03 9.998835e-01 -1.224376e-02 -6.738450e-01 2.252410e-02 1.244629e-02 9.996688e-01 2.981730e+01 +9.997049e-01 8.689446e-03 -2.268546e-02 -5.884758e-01 -8.985541e-03 9.998753e-01 -1.298294e-02 -7.048065e-01 2.256982e-02 1.318295e-02 9.996584e-01 3.083820e+01 +9.996909e-01 9.758370e-03 -2.286542e-02 -6.113853e-01 -1.008382e-02 9.998488e-01 -1.416135e-02 -7.344817e-01 2.272378e-02 1.438754e-02 9.996383e-01 3.186663e+01 +9.996851e-01 9.563056e-03 -2.320037e-02 -6.341856e-01 -9.875840e-03 9.998614e-01 -1.340487e-02 -7.658540e-01 2.306896e-02 1.362977e-02 9.996410e-01 3.290250e+01 +9.996756e-01 8.859609e-03 -2.387811e-02 -6.562571e-01 -9.116721e-03 9.999014e-01 -1.068035e-02 -7.960953e-01 2.378114e-02 1.089458e-02 9.996578e-01 3.394945e+01 +9.996656e-01 9.103416e-03 -2.420489e-02 -6.799668e-01 -9.280078e-03 9.999310e-01 -7.196274e-03 -8.250696e-01 2.413772e-02 7.418490e-03 9.996811e-01 3.500439e+01 +9.996516e-01 9.284323e-03 -2.470700e-02 -7.046294e-01 -9.400963e-03 9.999452e-01 -4.608864e-03 -8.521280e-01 2.466286e-02 4.839528e-03 9.996841e-01 3.606726e+01 +9.996390e-01 9.218534e-03 -2.523677e-02 -7.318157e-01 -9.321934e-03 9.999486e-01 -3.982562e-03 -8.792448e-01 2.519876e-02 4.216380e-03 9.996736e-01 3.712992e+01 +9.996343e-01 8.640360e-03 -2.562662e-02 -7.509456e-01 -8.785442e-03 9.999460e-01 -5.554152e-03 -8.999454e-01 2.557725e-02 5.777261e-03 9.996562e-01 3.820156e+01 +9.996235e-01 8.853187e-03 -2.597288e-02 -7.637420e-01 -9.008680e-03 9.999421e-01 -5.875766e-03 -9.173898e-01 2.591936e-02 6.107535e-03 9.996454e-01 3.927699e+01 +9.996113e-01 8.636784e-03 -2.650763e-02 -7.861115e-01 -8.772323e-03 9.999490e-01 -5.001110e-03 -9.426008e-01 2.646309e-02 5.231700e-03 9.996361e-01 4.035358e+01 +9.995911e-01 8.601039e-03 -2.727063e-02 -8.119808e-01 -8.683288e-03 9.999581e-01 -2.898948e-03 -9.707248e-01 2.724456e-02 3.134561e-03 9.996239e-01 4.143101e+01 +9.995744e-01 8.727969e-03 -2.783667e-02 -8.405589e-01 -8.747257e-03 9.999616e-01 -5.711173e-04 -9.983507e-01 2.783061e-02 8.143693e-04 9.996123e-01 4.250646e+01 +9.995472e-01 1.022000e-02 -2.830096e-02 -8.709114e-01 -1.022405e-02 9.999477e-01 1.828267e-06 -1.026979e+00 2.829950e-02 2.875237e-04 9.995995e-01 4.358049e+01 +9.995279e-01 1.094395e-02 -2.871053e-02 -9.059963e-01 -1.106491e-02 9.999305e-01 -4.057536e-03 -1.047970e+00 2.866413e-02 4.373300e-03 9.995795e-01 4.464539e+01 +9.995085e-01 1.235171e-02 -2.881189e-02 -9.448054e-01 -1.260322e-02 9.998839e-01 -8.564026e-03 -1.065232e+00 2.870277e-02 8.922939e-03 9.995482e-01 4.570729e+01 +9.994940e-01 1.312039e-02 -2.897767e-02 -9.815092e-01 -1.338944e-02 9.998688e-01 -9.110188e-03 -1.088166e+00 2.885435e-02 9.493571e-03 9.995386e-01 4.677981e+01 +9.994989e-01 1.324264e-02 -2.875026e-02 -1.015604e+00 -1.343042e-02 9.998896e-01 -6.348082e-03 -1.110851e+00 2.866302e-02 6.731028e-03 9.995665e-01 4.785820e+01 +9.994919e-01 1.417720e-02 -2.854922e-02 -1.050114e+00 -1.429880e-02 9.998895e-01 -4.059449e-03 -1.131381e+00 2.848852e-02 4.465605e-03 9.995842e-01 4.893463e+01 +9.995220e-01 1.204172e-02 -2.847356e-02 -1.079496e+00 -1.212515e-02 9.999227e-01 -2.758982e-03 -1.149441e+00 2.843813e-02 3.102909e-03 9.995907e-01 5.001065e+01 +9.995195e-01 1.300679e-02 -2.813588e-02 -1.112505e+00 -1.308056e-02 9.999114e-01 -2.439357e-03 -1.168837e+00 2.810166e-02 2.806218e-03 9.996011e-01 5.108922e+01 +9.995571e-01 1.082090e-02 -2.772132e-02 -1.142897e+00 -1.097231e-02 9.999256e-01 -5.315486e-03 -1.184929e+00 2.766174e-02 5.617298e-03 9.996016e-01 5.215954e+01 +9.995465e-01 1.194244e-02 -2.764414e-02 -1.177502e+00 -1.216294e-02 9.998954e-01 -7.821636e-03 -1.200275e+00 2.754784e-02 8.154322e-03 9.995872e-01 5.323263e+01 +9.995598e-01 1.097808e-02 -2.756386e-02 -1.210486e+00 -1.125243e-02 9.998885e-01 -9.817640e-03 -1.221230e+00 2.745301e-02 1.012348e-02 9.995718e-01 5.430647e+01 +9.995747e-01 9.582319e-03 -2.754407e-02 -1.248790e+00 -9.938401e-03 9.998684e-01 -1.281994e-02 -1.244310e+00 2.741761e-02 1.308823e-02 9.995384e-01 5.537246e+01 +9.995931e-01 7.889461e-03 -2.741337e-02 -1.282228e+00 -8.313639e-03 9.998469e-01 -1.539395e-02 -1.272192e+00 2.728772e-02 1.561559e-02 9.995057e-01 5.644378e+01 +9.996076e-01 6.482936e-03 -2.724986e-02 -1.319412e+00 -6.848565e-03 9.998875e-01 -1.334574e-02 -1.300079e+00 2.716028e-02 1.352712e-02 9.995396e-01 5.751446e+01 +9.996159e-01 5.272756e-03 -2.720940e-02 -1.352181e+00 -5.472263e-03 9.999586e-01 -7.262988e-03 -1.322688e+00 2.716998e-02 7.409094e-03 9.996034e-01 5.860062e+01 +9.996289e-01 4.177682e-03 -2.691985e-02 -1.387176e+00 -4.211062e-03 9.999904e-01 -1.183339e-03 -1.339024e+00 2.691465e-02 1.296261e-03 9.996369e-01 5.968580e+01 +9.996383e-01 2.508970e-03 -2.677796e-02 -1.418009e+00 -2.506310e-03 9.999968e-01 1.329272e-04 -1.354327e+00 2.677822e-02 -6.576443e-05 9.996414e-01 6.076851e+01 +9.996473e-01 -6.622685e-04 -2.654826e-02 -1.444555e+00 5.799434e-04 9.999950e-01 -3.108548e-03 -1.364859e+00 2.655019e-02 3.092056e-03 9.996427e-01 6.184743e+01 +9.996453e-01 -2.548634e-03 -2.651046e-02 -1.469495e+00 2.379543e-03 9.999766e-01 -6.407902e-03 -1.377471e+00 2.652617e-02 6.342545e-03 9.996280e-01 6.292513e+01 +9.996473e-01 -5.710145e-04 -2.655199e-02 -1.499917e+00 3.004754e-04 9.999480e-01 -1.019191e-02 -1.395800e+00 2.655643e-02 1.018033e-02 9.995955e-01 6.400399e+01 +9.996482e-01 -1.301741e-03 -2.649102e-02 -1.528092e+00 9.079193e-04 9.998890e-01 -1.487284e-02 -1.415207e+00 2.650744e-02 1.484356e-02 9.995384e-01 6.508527e+01 +9.996614e-01 1.995361e-03 -2.594344e-02 -1.558768e+00 -2.403038e-03 9.998740e-01 -1.569239e-02 -1.436238e+00 2.590886e-02 1.574942e-02 9.995402e-01 6.616971e+01 +9.996658e-01 6.847933e-03 -2.492658e-02 -1.593317e+00 -7.147739e-03 9.999029e-01 -1.195833e-02 -1.460636e+00 2.484228e-02 1.213250e-02 9.996178e-01 6.726138e+01 +9.996582e-01 8.312834e-03 -2.478541e-02 -1.623511e+00 -8.549643e-03 9.999186e-01 -9.463685e-03 -1.483749e+00 2.470473e-02 9.672356e-03 9.996480e-01 6.834968e+01 +9.996600e-01 7.575555e-03 -2.494941e-02 -1.649241e+00 -7.807005e-03 9.999272e-01 -9.192408e-03 -1.501927e+00 2.487796e-02 9.384062e-03 9.996465e-01 6.943492e+01 +9.996743e-01 6.096033e-03 -2.478355e-02 -1.673162e+00 -6.302831e-03 9.999459e-01 -8.274537e-03 -1.522851e+00 2.473177e-02 8.428047e-03 9.996586e-01 7.052233e+01 +9.996733e-01 4.970250e-03 -2.507073e-02 -1.697570e+00 -5.144801e-03 9.999629e-01 -6.902635e-03 -1.542287e+00 2.503550e-02 7.029363e-03 9.996619e-01 7.160597e+01 +9.996724e-01 3.394724e-03 -2.536873e-02 -1.724041e+00 -3.524391e-03 9.999809e-01 -5.068311e-03 -1.566430e+00 2.535104e-02 5.156060e-03 9.996653e-01 7.268959e+01 +9.996575e-01 2.220552e-03 -2.607526e-02 -1.754602e+00 -2.302257e-03 9.999925e-01 -3.103834e-03 -1.593458e+00 2.606817e-02 3.162804e-03 9.996552e-01 7.376891e+01 +9.996433e-01 1.479137e-03 -2.666623e-02 -1.784427e+00 -1.590559e-03 9.999901e-01 -4.157630e-03 -1.618953e+00 2.665981e-02 4.198561e-03 9.996358e-01 7.484293e+01 +9.996291e-01 1.607274e-03 -2.718639e-02 -1.818016e+00 -1.826344e-03 9.999660e-01 -8.035150e-03 -1.644073e+00 2.717256e-02 8.081821e-03 9.995981e-01 7.591173e+01 +9.996101e-01 2.133806e-03 -2.783910e-02 -1.852271e+00 -2.424651e-03 9.999428e-01 -1.041780e-02 -1.670698e+00 2.781528e-02 1.048123e-02 9.995581e-01 7.698007e+01 +9.995891e-01 4.233092e-03 -2.834910e-02 -1.892754e+00 -4.483809e-03 9.999513e-01 -8.786135e-03 -1.702097e+00 2.831053e-02 8.909636e-03 9.995595e-01 7.804464e+01 +9.995678e-01 5.278628e-03 -2.892128e-02 -1.931694e+00 -5.415869e-03 9.999744e-01 -4.669015e-03 -1.731655e+00 2.889590e-02 4.823631e-03 9.995708e-01 7.911497e+01 +9.995411e-01 6.853246e-03 -2.950637e-02 -1.971601e+00 -6.869005e-03 9.999763e-01 -4.326932e-04 -1.759353e+00 2.950271e-02 6.351747e-04 9.995645e-01 8.018037e+01 +9.995209e-01 7.994852e-03 -2.990165e-02 -2.009246e+00 -7.977963e-03 9.999679e-01 6.841464e-04 -1.780033e+00 2.990617e-02 -4.452634e-04 9.995526e-01 8.124100e+01 +9.995060e-01 7.795793e-03 -3.044809e-02 -2.046091e+00 -7.848921e-03 9.999679e-01 -1.625703e-03 -1.798450e+00 3.043444e-02 1.863885e-03 9.995350e-01 8.229562e+01 +9.994882e-01 7.555003e-03 -3.108412e-02 -2.082196e+00 -7.642022e-03 9.999672e-01 -2.681568e-03 -1.819154e+00 3.106284e-02 2.917741e-03 9.995132e-01 8.334260e+01 +9.994752e-01 7.225519e-03 -3.157600e-02 -2.118145e+00 -7.306479e-03 9.999703e-01 -2.449280e-03 -1.836350e+00 3.155737e-02 2.678705e-03 9.994984e-01 8.438146e+01 +9.994607e-01 5.955976e-03 -3.229184e-02 -2.152257e+00 -6.031653e-03 9.999793e-01 -2.246562e-03 -1.854735e+00 3.227779e-02 2.440124e-03 9.994760e-01 8.540636e+01 +9.994472e-01 4.547048e-03 -3.293428e-02 -2.187213e+00 -4.572446e-03 9.999893e-01 -6.958514e-04 -1.871238e+00 3.293077e-02 8.460575e-04 9.994573e-01 8.641716e+01 +9.994314e-01 4.756684e-03 -3.338168e-02 -2.224921e+00 -4.695592e-03 9.999871e-01 1.908273e-03 -1.889129e+00 3.339033e-02 -1.750440e-03 9.994409e-01 8.741070e+01 +9.994019e-01 4.012762e-03 -3.434629e-02 -2.262425e+00 -3.902838e-03 9.999870e-01 3.266921e-03 -1.907770e+00 3.435896e-02 -3.130918e-03 9.994047e-01 8.838264e+01 +9.993338e-01 2.999186e-03 -3.637303e-02 -2.303693e+00 -2.880714e-03 9.999904e-01 3.309115e-03 -1.929486e+00 3.638260e-02 -3.202128e-03 9.993328e-01 8.933531e+01 +9.992113e-01 2.138299e-03 -3.965073e-02 -2.344772e+00 -2.031068e-03 9.999941e-01 2.744488e-03 -1.950966e+00 3.965637e-02 -2.661789e-03 9.992098e-01 9.026556e+01 +9.990684e-01 2.186699e-03 -4.309936e-02 -2.390135e+00 -2.107826e-03 9.999960e-01 1.875411e-03 -1.972736e+00 4.310329e-02 -1.782817e-03 9.990690e-01 9.117072e+01 +9.989307e-01 1.832805e-03 -4.619660e-02 -2.434745e+00 -1.755145e-03 9.999970e-01 1.721603e-03 -1.993637e+00 4.619962e-02 -1.638679e-03 9.989309e-01 9.205518e+01 +9.987771e-01 2.904739e-03 -4.935412e-02 -2.486719e+00 -2.745233e-03 9.999908e-01 3.299346e-03 -2.021957e+00 4.936326e-02 -3.159822e-03 9.987759e-01 9.291577e+01 +9.986194e-01 3.941519e-03 -5.238126e-02 -2.538278e+00 -3.724414e-03 9.999840e-01 4.241689e-03 -2.044394e+00 5.239715e-02 -4.040742e-03 9.986182e-01 9.375397e+01 +9.984574e-01 4.910923e-03 -5.530497e-02 -2.594376e+00 -4.595720e-03 9.999724e-01 5.825129e-03 -2.066115e+00 5.533206e-02 -5.561975e-03 9.984525e-01 9.456706e+01 +9.982947e-01 6.427526e-03 -5.802030e-02 -2.649588e+00 -6.047890e-03 9.999591e-01 6.716404e-03 -2.083333e+00 5.806110e-02 -6.354048e-03 9.982928e-01 9.535206e+01 +9.981360e-01 8.546321e-03 -6.042826e-02 -2.709824e+00 -8.117173e-03 9.999401e-01 7.343723e-03 -2.104835e+00 6.048741e-02 -6.839525e-03 9.981455e-01 9.611060e+01 +9.979505e-01 1.045330e-02 -6.313131e-02 -2.769310e+00 -1.006763e-02 9.999287e-01 6.424076e-03 -2.127247e+00 6.319396e-02 -5.775324e-03 9.979846e-01 9.683647e+01 +9.977683e-01 1.184201e-02 -6.571358e-02 -2.827593e+00 -1.166772e-02 9.999273e-01 3.035422e-03 -2.149905e+00 6.574475e-02 -2.261919e-03 9.978339e-01 9.753308e+01 +9.975717e-01 1.414368e-02 -6.819605e-02 -2.885302e+00 -1.423255e-02 9.998984e-01 -8.174607e-04 -2.169614e+00 6.817756e-02 1.786080e-03 9.976716e-01 9.819683e+01 +9.973874e-01 1.616254e-02 -7.040771e-02 -2.940577e+00 -1.644917e-02 9.998586e-01 -3.493045e-03 -2.192789e+00 7.034131e-02 4.642067e-03 9.975122e-01 9.883274e+01 +9.972886e-01 1.777342e-02 -7.141100e-02 -2.992555e+00 -1.815495e-02 9.998241e-01 -4.697178e-03 -2.217650e+00 7.131496e-02 5.980905e-03 9.974359e-01 9.943737e+01 +9.972983e-01 2.031185e-02 -7.059445e-02 -3.043655e+00 -2.065599e-02 9.997780e-01 -4.148050e-03 -2.242127e+00 7.049453e-02 5.595041e-03 9.974965e-01 1.000200e+02 +9.974082e-01 2.401071e-02 -6.782548e-02 -3.092267e+00 -2.423148e-02 9.997034e-01 -2.434004e-03 -2.268333e+00 6.774693e-02 4.071208e-03 9.976942e-01 1.005818e+02 +9.976861e-01 2.685736e-02 -6.245978e-02 -3.132396e+00 -2.695920e-02 9.996362e-01 -7.880321e-04 -2.291455e+00 6.241590e-02 2.470075e-03 9.980472e-01 1.011196e+02 +9.980865e-01 2.769474e-02 -5.528438e-02 -3.162399e+00 -2.768287e-02 9.996162e-01 9.807221e-04 -2.311035e+00 5.529033e-02 5.515859e-04 9.984702e-01 1.016363e+02 +9.985724e-01 2.754334e-02 -4.576698e-02 -3.182492e+00 -2.741437e-02 9.996182e-01 3.443627e-03 -2.327168e+00 4.584436e-02 -2.184037e-03 9.989462e-01 1.021306e+02 +9.990500e-01 2.711620e-02 -3.411624e-02 -3.196722e+00 -2.696659e-02 9.996246e-01 4.838232e-03 -2.349063e+00 3.423463e-02 -3.913635e-03 9.994062e-01 1.026043e+02 +9.994365e-01 2.634999e-02 -2.079597e-02 -3.201967e+00 -2.625239e-02 9.996431e-01 4.952734e-03 -2.369031e+00 2.091905e-02 -4.403998e-03 9.997715e-01 1.030549e+02 +9.996431e-01 2.606407e-02 -5.856808e-03 -3.198184e+00 -2.603947e-02 9.996519e-01 4.238673e-03 -2.391847e+00 5.965247e-03 -4.084651e-03 9.999739e-01 1.034865e+02 +9.996254e-01 2.465666e-02 1.187615e-02 -3.182672e+00 -2.467518e-02 9.996945e-01 1.414920e-03 -2.410045e+00 -1.183763e-02 -1.707435e-03 9.999285e-01 1.039074e+02 +9.991757e-01 2.397217e-02 3.276205e-02 -3.156876e+00 -2.388296e-02 9.997099e-01 -3.111873e-03 -2.432590e+00 -3.282714e-02 2.326853e-03 9.994583e-01 1.043189e+02 +9.981466e-01 2.187542e-02 5.678845e-02 -3.116159e+00 -2.145346e-02 9.997376e-01 -8.029551e-03 -2.449486e+00 -5.694920e-02 6.796359e-03 9.983540e-01 1.047190e+02 +9.962910e-01 1.953501e-02 8.380147e-02 -3.061832e+00 -1.869541e-02 9.997670e-01 -1.079205e-02 -2.472039e+00 -8.399277e-02 9.185320e-03 9.964240e-01 1.051162e+02 +9.934054e-01 1.685322e-02 1.134096e-01 -2.993908e+00 -1.558580e-02 9.998059e-01 -1.205311e-02 -2.487673e+00 -1.135907e-01 1.020604e-02 9.934752e-01 1.054984e+02 +9.892475e-01 1.437845e-02 1.455423e-01 -2.911418e+00 -1.252083e-02 9.998281e-01 -1.367150e-02 -2.507487e+00 -1.457139e-01 1.170218e-02 9.892576e-01 1.058778e+02 +9.834416e-01 1.169323e-02 1.808479e-01 -2.813888e+00 -9.043005e-03 9.998394e-01 -1.547206e-02 -2.526594e+00 -1.809998e-01 1.358045e-02 9.833894e-01 1.062405e+02 +9.756821e-01 8.224854e-03 2.190361e-01 -2.699437e+00 -4.860504e-03 9.998618e-01 -1.589424e-02 -2.548585e+00 -2.191366e-01 1.444310e-02 9.755873e-01 1.066027e+02 +9.659042e-01 5.639536e-03 2.588384e-01 -2.570785e+00 -1.392872e-03 9.998614e-01 -1.658708e-02 -2.565421e+00 -2.588961e-01 1.566100e-02 9.657782e-01 1.069444e+02 +9.538763e-01 5.989151e-03 3.001401e-01 -2.431748e+00 -7.529466e-04 9.998455e-01 -1.755850e-02 -2.585374e+00 -3.001989e-01 1.652264e-02 9.537335e-01 1.072854e+02 +9.389078e-01 8.082927e-03 3.440738e-01 -2.279365e+00 -2.030353e-03 9.998368e-01 -1.794759e-02 -2.601080e+00 -3.441628e-01 1.615254e-02 9.387711e-01 1.076167e+02 +9.213636e-01 7.841691e-03 3.886227e-01 -2.109387e+00 -1.344341e-03 9.998548e-01 -1.698801e-02 -2.615943e+00 -3.886995e-01 1.512969e-02 9.212404e-01 1.079269e+02 +9.015120e-01 6.907630e-03 4.326990e-01 -1.921488e+00 -1.279666e-04 9.998768e-01 -1.569548e-02 -2.628863e+00 -4.327542e-01 1.409428e-02 9.014018e-01 1.082346e+02 +8.787762e-01 5.396942e-03 4.772036e-01 -1.720225e+00 2.468528e-03 9.998712e-01 -1.585389e-02 -2.641910e+00 -4.772278e-01 1.511000e-02 8.786497e-01 1.085153e+02 +8.539851e-01 5.486594e-03 5.202685e-01 -1.506750e+00 4.312303e-03 9.998354e-01 -1.762231e-02 -2.655967e+00 -5.202796e-01 1.729274e-02 8.538209e-01 1.087943e+02 +8.268621e-01 7.076746e-03 5.623602e-01 -1.282825e+00 5.372216e-03 9.997758e-01 -2.048019e-02 -2.670469e+00 -5.623791e-01 1.995541e-02 8.266387e-01 1.090496e+02 +7.967129e-01 1.146739e-02 6.042492e-01 -1.047012e+00 4.228660e-03 9.996897e-01 -2.454758e-02 -2.682863e+00 -6.043433e-01 2.211254e-02 7.964172e-01 1.093104e+02 +7.634311e-01 1.721087e-02 6.456600e-01 -7.972273e-01 1.533558e-03 9.995938e-01 -2.845871e-02 -2.691906e+00 -6.458875e-01 2.271642e-02 7.630946e-01 1.095491e+02 +7.266640e-01 2.200542e-02 6.866405e-01 -5.307156e-01 -1.000028e-03 9.995197e-01 -3.097424e-02 -2.699185e+00 -6.869924e-01 2.182120e-02 7.263370e-01 1.097910e+02 +6.876532e-01 2.243150e-02 7.256927e-01 -2.466359e-01 7.842081e-04 9.994991e-01 -3.163809e-02 -2.712112e+00 -7.260389e-01 2.232512e-02 6.872911e-01 1.100156e+02 +6.472283e-01 1.957918e-02 7.620447e-01 5.578371e-02 5.453654e-03 9.995256e-01 -3.031273e-02 -2.723636e+00 -7.622767e-01 2.377518e-02 6.468145e-01 1.102064e+02 +6.035009e-01 1.731669e-02 7.971742e-01 3.744581e-01 6.707206e-03 9.996185e-01 -2.679201e-02 -2.732922e+00 -7.973341e-01 2.151581e-02 6.031545e-01 1.104040e+02 +5.574795e-01 1.558425e-02 8.300444e-01 7.051086e-01 7.847757e-03 9.996802e-01 -2.403995e-02 -2.741477e+00 -8.301537e-01 1.991576e-02 5.571789e-01 1.105684e+02 +5.100162e-01 1.318785e-02 8.600637e-01 1.049532e+00 9.403782e-03 9.997372e-01 -2.090598e-02 -2.753607e+00 -8.601135e-01 1.875023e-02 5.097581e-01 1.107304e+02 +4.596811e-01 8.542107e-03 8.880429e-01 1.408134e+00 1.226402e-02 9.997973e-01 -1.596535e-02 -2.764267e+00 -8.879994e-01 1.822994e-02 4.594832e-01 1.108567e+02 +4.082059e-01 8.234297e-03 9.128527e-01 1.774099e+00 9.891073e-03 9.998607e-01 -1.344220e-02 -2.777327e+00 -9.128363e-01 1.451627e-02 4.080676e-01 1.109879e+02 +3.572424e-01 1.240740e-02 9.339293e-01 2.148919e+00 6.274944e-03 9.998573e-01 -1.568353e-02 -2.788461e+00 -9.339906e-01 1.146317e-02 3.571136e-01 1.111029e+02 +3.067219e-01 1.787320e-02 9.516313e-01 2.533142e+00 5.747217e-03 9.997706e-01 -2.062973e-02 -2.796272e+00 -9.517819e-01 1.179682e-02 3.065488e-01 1.111851e+02 +2.598207e-01 2.006224e-02 9.654484e-01 2.934626e+00 7.048719e-03 9.997181e-01 -2.267132e-02 -2.806532e+00 -9.656312e-01 1.269565e-02 2.596061e-01 1.112656e+02 +2.179078e-01 1.961097e-02 9.757723e-01 3.350702e+00 1.357173e-02 9.996405e-01 -2.312150e-02 -2.818457e+00 -9.758750e-01 1.828127e-02 2.175633e-01 1.113182e+02 +1.822823e-01 1.918248e-02 9.830591e-01 3.783818e+00 2.177190e-02 9.994858e-01 -2.354004e-02 -2.829807e+00 -9.830052e-01 2.569399e-02 1.817710e-01 1.113644e+02 +1.513859e-01 2.092434e-02 9.882532e-01 4.227266e+00 2.705725e-02 9.993136e-01 -2.530330e-02 -2.840259e+00 -9.881044e-01 3.056997e-02 1.507159e-01 1.114023e+02 +1.229001e-01 1.931907e-02 9.922310e-01 4.690755e+00 2.545091e-02 9.994203e-01 -2.261146e-02 -2.856964e+00 -9.920927e-01 2.803212e-02 1.223372e-01 1.114470e+02 +9.696370e-02 1.560921e-02 9.951655e-01 5.173439e+00 1.880566e-02 9.996698e-01 -1.751219e-02 -2.871679e+00 -9.951103e-01 2.041278e-02 9.663814e-02 1.114895e+02 +7.261944e-02 1.214445e-02 9.972858e-01 5.672652e+00 1.372028e-02 9.998191e-01 -1.317437e-02 -2.886056e+00 -9.972654e-01 1.463975e-02 7.243968e-02 1.115178e+02 +4.961925e-02 8.990929e-03 9.987277e-01 6.192944e+00 1.713408e-02 9.998046e-01 -9.851892e-03 -2.902144e+00 -9.986213e-01 1.760112e-02 4.945550e-02 1.115272e+02 +2.913822e-02 9.131699e-03 9.995337e-01 6.728517e+00 2.461286e-02 9.996485e-01 -9.850263e-03 -2.917163e+00 -9.992724e-01 2.488840e-02 2.890322e-02 1.115183e+02 +1.095538e-02 1.122155e-02 9.998770e-01 7.282318e+00 2.994530e-02 9.994848e-01 -1.154526e-02 -2.930539e+00 -9.994915e-01 3.006809e-02 1.061370e-02 1.115004e+02 +-3.553242e-03 1.690927e-02 9.998507e-01 7.855335e+00 3.158021e-02 9.993602e-01 -1.678875e-02 -2.935743e+00 -9.994949e-01 3.151583e-02 -4.084969e-03 1.114905e+02 +-1.522981e-02 2.191925e-02 9.996437e-01 8.447661e+00 2.859550e-02 9.993603e-01 -2.147739e-02 -2.943016e+00 -9.994751e-01 2.825821e-02 -1.584686e-02 1.114822e+02 +-2.198079e-02 2.258082e-02 9.995033e-01 9.065751e+00 3.081249e-02 9.992852e-01 -2.189828e-02 -2.953427e+00 -9.992835e-01 3.031583e-02 -2.266085e-02 1.114624e+02 +-2.491485e-02 1.845120e-02 9.995193e-01 9.708447e+00 3.655336e-02 9.991778e-01 -1.753375e-02 -2.966443e+00 -9.990211e-01 3.609893e-02 -2.556882e-02 1.114331e+02 +-2.478790e-02 1.739682e-02 9.995413e-01 1.036534e+01 3.920624e-02 9.990962e-01 -1.641679e-02 -2.980253e+00 -9.989237e-01 3.878131e-02 -2.544756e-02 1.114116e+02 +-2.312930e-02 1.652093e-02 9.995959e-01 1.104173e+01 3.862182e-02 9.991318e-01 -1.561960e-02 -2.993917e+00 -9.989862e-01 3.824493e-02 -2.374729e-02 1.113977e+02 +-2.174809e-02 1.639419e-02 9.996290e-01 1.173050e+01 3.415289e-02 9.992941e-01 -1.564567e-02 -3.009754e+00 -9.991800e-01 3.379994e-02 -2.229265e-02 1.113912e+02 +-2.066774e-02 1.829032e-02 9.996191e-01 1.244057e+01 3.375051e-02 9.992755e-01 -1.758623e-02 -3.020980e+00 -9.992166e-01 3.337418e-02 -2.127008e-02 1.113766e+02 +-1.993655e-02 1.883647e-02 9.996238e-01 1.316355e+01 3.319336e-02 9.992838e-01 -1.816806e-02 -3.034345e+00 -9.992501e-01 3.281866e-02 -2.054752e-02 1.113612e+02 +-1.940800e-02 1.845005e-02 9.996414e-01 1.390220e+01 3.300790e-02 9.992965e-01 -1.780284e-02 -3.051223e+00 -9.992667e-01 3.265054e-02 -2.000334e-02 1.113451e+02 +-1.875443e-02 1.703650e-02 9.996789e-01 1.465827e+01 3.161099e-02 9.993650e-01 -1.643812e-02 -3.072877e+00 -9.993243e-01 3.129255e-02 -1.928107e-02 1.113363e+02 +-1.820959e-02 1.570494e-02 9.997108e-01 1.542377e+01 3.246256e-02 9.993587e-01 -1.510811e-02 -3.095311e+00 -9.993071e-01 3.217805e-02 -1.870774e-02 1.113240e+02 +-1.880614e-02 1.351924e-02 9.997317e-01 1.620084e+01 3.332321e-02 9.993615e-01 -1.288739e-02 -3.118178e+00 -9.992677e-01 3.307190e-02 -1.924464e-02 1.113091e+02 +-2.016064e-02 1.196133e-02 9.997252e-01 1.698099e+01 3.120717e-02 9.994487e-01 -1.132870e-02 -3.141006e+00 -9.993096e-01 3.097020e-02 -2.052281e-02 1.112943e+02 +-2.180273e-02 1.095057e-02 9.997023e-01 1.776747e+01 2.961032e-02 9.995084e-01 -1.030268e-02 -3.160636e+00 -9.993237e-01 2.937688e-02 -2.211626e-02 1.112760e+02 +-2.322968e-02 8.366561e-03 9.996951e-01 1.856541e+01 3.187309e-02 9.994628e-01 -7.623995e-03 -3.176463e+00 -9.992220e-01 3.168626e-02 -2.348387e-02 1.112519e+02 +-2.447946e-02 7.293772e-03 9.996737e-01 1.937151e+01 3.473776e-02 9.993757e-01 -6.440963e-03 -3.193647e+00 -9.990966e-01 3.456875e-02 -2.471755e-02 1.112251e+02 +-2.654199e-02 5.000474e-03 9.996352e-01 2.018791e+01 3.034893e-02 9.995305e-01 -4.194140e-03 -3.214056e+00 -9.991869e-01 3.022653e-02 -2.668129e-02 1.112066e+02 +-2.742417e-02 9.939064e-03 9.995745e-01 2.100565e+01 2.777439e-02 9.995721e-01 -9.177032e-03 -3.232298e+00 -9.992380e-01 2.751089e-02 -2.768849e-02 1.111890e+02 +-2.804745e-02 1.509420e-02 9.994926e-01 2.182752e+01 2.924817e-02 9.994702e-01 -1.427311e-02 -3.250815e+00 -9.991786e-01 2.883300e-02 -2.847408e-02 1.111686e+02 +-2.877537e-02 1.693819e-02 9.994424e-01 2.265838e+01 2.997996e-02 9.994212e-01 -1.607467e-02 -3.273148e+00 -9.991363e-01 2.950068e-02 -2.926652e-02 1.111497e+02 +-2.984141e-02 1.484383e-02 9.994444e-01 2.349682e+01 2.643242e-02 9.995517e-01 -1.405621e-02 -3.298255e+00 -9.992051e-01 2.599827e-02 -3.022040e-02 1.111374e+02 +-3.061397e-02 1.071316e-02 9.994739e-01 2.433823e+01 2.329981e-02 9.996785e-01 -1.000168e-02 -3.326366e+00 -9.992597e-01 2.298136e-02 -3.085374e-02 1.111280e+02 +-3.056497e-02 4.928690e-03 9.995206e-01 2.518208e+01 2.158534e-02 9.997579e-01 -4.269793e-03 -3.350402e+00 -9.992997e-01 2.144448e-02 -3.066396e-02 1.111110e+02 +-3.049090e-02 -5.349902e-04 9.995349e-01 2.602725e+01 1.837372e-02 9.998306e-01 1.095637e-03 -3.370419e+00 -9.993662e-01 1.839858e-02 -3.047590e-02 1.110993e+02 +-3.037824e-02 -1.870939e-03 9.995367e-01 2.686546e+01 1.530089e-02 9.998802e-01 2.336608e-03 -3.392421e+00 -9.994214e-01 1.536478e-02 -3.034597e-02 1.110866e+02 +-2.940461e-02 3.384421e-03 9.995618e-01 2.769648e+01 1.770798e-02 9.998391e-01 -2.864439e-03 -3.417654e+00 -9.994108e-01 1.761599e-02 -2.945981e-02 1.110665e+02 +-2.823685e-02 1.516988e-02 9.994861e-01 2.851752e+01 2.033913e-02 9.996865e-01 -1.459832e-02 -3.439638e+00 -9.993944e-01 1.991646e-02 -2.853654e-02 1.110417e+02 +-2.765042e-02 2.203755e-02 9.993747e-01 2.934025e+01 2.260636e-02 9.995150e-01 -2.141519e-02 -3.464646e+00 -9.993620e-01 2.200008e-02 -2.813520e-02 1.110185e+02 +-2.636109e-02 1.615497e-02 9.995219e-01 3.017178e+01 2.380199e-02 9.995961e-01 -1.552843e-02 -3.494748e+00 -9.993691e-01 2.338126e-02 -2.673496e-02 1.109962e+02 +-2.511623e-02 7.842711e-03 9.996538e-01 3.100291e+01 2.644169e-02 9.996246e-01 -7.178141e-03 -3.524637e+00 -9.993348e-01 2.625224e-02 -2.531418e-02 1.109727e+02 +-2.452145e-02 5.048207e-03 9.996865e-01 3.182438e+01 2.812594e-02 9.995949e-01 -4.357843e-03 -3.550386e+00 -9.993036e-01 2.801026e-02 -2.465351e-02 1.109495e+02 +-2.448426e-02 5.625083e-03 9.996844e-01 3.263728e+01 2.725401e-02 9.996162e-01 -4.957200e-03 -3.574008e+00 -9.993287e-01 2.712402e-02 -2.462818e-02 1.109310e+02 +-2.520882e-02 6.438168e-03 9.996615e-01 3.344955e+01 2.428460e-02 9.996881e-01 -5.825950e-03 -3.597380e+00 -9.993872e-01 2.412951e-02 -2.535731e-02 1.109148e+02 +-2.711108e-02 6.831514e-03 9.996091e-01 3.425559e+01 2.235531e-02 9.997307e-01 -6.226037e-03 -3.619497e+00 -9.993825e-01 2.217777e-02 -2.725650e-02 1.108957e+02 +-2.907136e-02 6.272478e-03 9.995576e-01 3.505969e+01 2.164930e-02 9.997497e-01 -5.644034e-03 -3.643377e+00 -9.993429e-01 2.147564e-02 -2.919988e-02 1.108735e+02 +-3.118245e-02 7.053685e-03 9.994888e-01 3.585953e+01 2.094508e-02 9.997601e-01 -6.402152e-03 -3.668997e+00 -9.992943e-01 2.073473e-02 -3.132271e-02 1.108521e+02 +-3.323136e-02 7.280968e-03 9.994211e-01 3.665572e+01 1.909226e-02 9.997956e-01 -6.648872e-03 -3.692321e+00 -9.992653e-01 1.886025e-02 -3.336358e-02 1.108323e+02 +-3.528758e-02 6.548349e-03 9.993557e-01 3.745030e+01 1.702129e-02 9.998374e-01 -5.950483e-03 -3.713275e+00 -9.992323e-01 1.680034e-02 -3.539330e-02 1.108119e+02 +-3.732820e-02 4.989269e-03 9.992906e-01 3.824062e+01 1.747571e-02 9.998378e-01 -4.339207e-03 -3.739393e+00 -9.991503e-01 1.730133e-02 -3.740934e-02 1.107877e+02 +-3.931675e-02 4.742139e-03 9.992155e-01 3.902353e+01 1.720543e-02 9.998437e-01 -4.068132e-03 -3.764360e+00 -9.990787e-01 1.703198e-02 -3.939220e-02 1.107603e+02 +-4.114167e-02 5.913874e-03 9.991358e-01 3.980437e+01 1.695435e-02 9.998426e-01 -5.219929e-03 -3.788915e+00 -9.990095e-01 1.672494e-02 -4.123546e-02 1.107309e+02 +-4.213293e-02 6.779929e-03 9.990890e-01 4.057553e+01 1.752921e-02 9.998280e-01 -6.045719e-03 -3.811300e+00 -9.989583e-01 1.725851e-02 -4.224453e-02 1.106977e+02 +-4.335089e-02 5.462525e-03 9.990450e-01 4.134827e+01 1.953435e-02 9.997985e-01 -4.619010e-03 -3.834868e+00 -9.988689e-01 1.931545e-02 -4.344886e-02 1.106618e+02 +-4.474975e-02 4.542984e-03 9.989879e-01 4.211586e+01 1.966984e-02 9.997998e-01 -3.665569e-03 -3.860486e+00 -9.988046e-01 1.948589e-02 -4.483016e-02 1.106260e+02 +-4.613078e-02 3.792299e-03 9.989282e-01 4.287606e+01 1.865418e-02 9.998217e-01 -2.934241e-03 -3.885455e+00 -9.987613e-01 1.849882e-02 -4.619330e-02 1.105935e+02 +-4.752738e-02 2.697713e-03 9.988663e-01 4.362563e+01 1.682637e-02 9.998566e-01 -1.899772e-03 -3.908535e+00 -9.987282e-01 1.671699e-02 -4.756596e-02 1.105634e+02 +-4.844212e-02 1.858945e-03 9.988242e-01 4.435901e+01 1.563944e-02 9.998771e-01 -1.102409e-03 -3.927506e+00 -9.987036e-01 1.556764e-02 -4.846524e-02 1.105329e+02 +-4.930024e-02 1.121100e-03 9.987834e-01 4.507372e+01 1.575283e-02 9.998758e-01 -3.447660e-04 -3.947128e+00 -9.986598e-01 1.571667e-02 -4.931179e-02 1.105025e+02 +-4.963267e-02 3.439404e-03 9.987616e-01 4.577870e+01 1.594992e-02 9.998693e-01 -2.650604e-03 -3.968246e+00 -9.986402e-01 1.579861e-02 -4.968105e-02 1.104722e+02 +-4.971655e-02 6.537549e-03 9.987420e-01 4.647919e+01 1.624219e-02 9.998516e-01 -5.736295e-03 -3.990288e+00 -9.986313e-01 1.593657e-02 -4.981536e-02 1.104407e+02 +-4.991082e-02 8.104079e-03 9.987208e-01 4.717652e+01 1.435816e-02 9.998695e-01 -7.395860e-03 -4.011755e+00 -9.986505e-01 1.397065e-02 -5.002068e-02 1.104123e+02 +-5.013018e-02 8.979031e-03 9.987023e-01 4.787113e+01 1.465636e-02 9.998585e-01 -8.253750e-03 -4.034285e+00 -9.986352e-01 1.422358e-02 -5.025469e-02 1.103817e+02 +-5.019960e-02 8.863095e-03 9.986999e-01 4.856561e+01 1.583562e-02 9.998420e-01 -8.077259e-03 -4.055339e+00 -9.986137e-01 1.540955e-02 -5.033203e-02 1.103479e+02 +-5.048020e-02 7.914478e-03 9.986937e-01 4.925400e+01 1.685096e-02 9.998330e-01 -7.071760e-03 -4.074607e+00 -9.985829e-01 1.647196e-02 -5.060514e-02 1.103152e+02 +-5.087475e-02 8.507834e-03 9.986688e-01 4.993953e+01 1.311497e-02 9.998832e-01 -7.850075e-03 -4.093812e+00 -9.986190e-01 1.269814e-02 -5.098039e-02 1.102891e+02 +-5.083338e-02 8.201674e-03 9.986735e-01 5.062365e+01 1.021682e-02 9.999182e-01 -7.691857e-03 -4.114385e+00 -9.986549e-01 9.812257e-03 -5.091302e-02 1.102629e+02 +-5.069705e-02 6.789371e-03 9.986910e-01 5.129886e+01 1.208748e-02 9.999078e-01 -6.184045e-03 -4.131756e+00 -9.986410e-01 1.175814e-02 -5.077445e-02 1.102291e+02 +-5.159813e-02 6.404684e-03 9.986474e-01 5.197172e+01 1.276125e-02 9.999020e-01 -5.753386e-03 -4.148661e+00 -9.985864e-01 1.244713e-02 -5.167481e-02 1.101946e+02 +-5.487974e-02 5.891529e-03 9.984756e-01 5.264111e+01 9.889219e-03 9.999367e-01 -5.356609e-03 -4.167844e+00 -9.984440e-01 9.580171e-03 -5.493453e-02 1.101638e+02 +-6.012039e-02 5.456290e-03 9.981762e-01 5.330677e+01 5.756207e-03 9.999703e-01 -5.119404e-03 -4.188031e+00 -9.981746e-01 5.437925e-03 -6.015001e-02 1.101320e+02 +-6.594365e-02 8.719935e-03 9.977852e-01 5.396640e+01 8.774153e-03 9.999282e-01 -8.158784e-03 -4.204714e+00 -9.977848e-01 8.216697e-03 -6.601543e-02 1.100844e+02 +-7.232000e-02 1.209615e-02 9.973081e-01 5.462746e+01 1.154160e-02 9.998696e-01 -1.129028e-02 -4.221113e+00 -9.973147e-01 1.069401e-02 -7.245018e-02 1.100294e+02 +-7.976551e-02 1.367826e-02 9.967198e-01 5.529672e+01 1.069626e-02 9.998600e-01 -1.286536e-02 -4.239741e+00 -9.967563e-01 9.634955e-03 -7.990066e-02 1.099758e+02 +-8.610102e-02 1.289271e-02 9.962030e-01 5.596874e+01 7.212257e-03 9.998981e-01 -1.231719e-02 -4.259740e+00 -9.962603e-01 6.124346e-03 -8.618523e-02 1.099227e+02 +-9.151917e-02 1.184083e-02 9.957329e-01 5.664512e+01 5.857237e-03 9.999184e-01 -1.135226e-02 -4.283061e+00 -9.957861e-01 4.793291e-03 -9.158106e-02 1.098596e+02 +-9.601658e-02 1.227851e-02 9.953040e-01 5.732460e+01 4.243196e-03 9.999199e-01 -1.192612e-02 -4.305330e+00 -9.953707e-01 3.078162e-03 -9.606099e-02 1.097920e+02 +-9.999902e-02 1.143901e-02 9.949218e-01 5.801252e+01 1.729848e-03 9.999344e-01 -1.132278e-02 -4.323997e+00 -9.949861e-01 5.887941e-04 -1.000122e-01 1.097249e+02 +-1.027987e-01 8.949224e-03 9.946619e-01 5.870923e+01 2.193170e-03 9.999591e-01 -8.770224e-03 -4.342226e+00 -9.946998e-01 1.279893e-03 -1.028142e-01 1.096525e+02 +-1.045341e-01 5.579471e-03 9.945056e-01 5.941860e+01 3.960115e-03 9.999786e-01 -5.193927e-03 -4.360434e+00 -9.945134e-01 3.395412e-03 -1.045540e-01 1.095755e+02 +-1.063441e-01 1.341655e-03 9.943285e-01 6.014241e+01 2.969012e-03 9.999950e-01 -1.031768e-03 -4.377079e+00 -9.943250e-01 2.842448e-03 -1.063475e-01 1.095029e+02 +-1.078470e-01 1.980980e-03 9.941655e-01 6.086806e+01 2.647993e-03 9.999950e-01 -1.705346e-03 -4.390954e+00 -9.941640e-01 2.448625e-03 -1.078517e-01 1.094297e+02 +-1.085763e-01 5.064896e-03 9.940752e-01 6.159653e+01 4.061801e-03 9.999809e-01 -4.651347e-03 -4.404393e+00 -9.940799e-01 3.532707e-03 -1.085948e-01 1.093511e+02 +-1.087612e-01 9.316179e-03 9.940242e-01 6.232941e+01 9.639908e-03 9.999189e-01 -8.316680e-03 -4.420348e+00 -9.940212e-01 8.677766e-03 -1.088422e-01 1.092651e+02 +-1.093263e-01 1.353913e-02 9.939137e-01 6.306998e+01 1.724616e-02 9.997825e-01 -1.172207e-02 -4.438119e+00 -9.938563e-01 1.585966e-02 -1.095361e-01 1.091742e+02 +-1.100410e-01 1.596005e-02 9.937989e-01 6.381462e+01 1.875611e-02 9.997263e-01 -1.397843e-02 -4.456517e+00 -9.937501e-01 1.710159e-02 -1.103102e-01 1.090910e+02 +-1.106278e-01 1.354003e-02 9.937697e-01 6.456343e+01 1.662791e-02 9.997924e-01 -1.177106e-02 -4.476878e+00 -9.937228e-01 1.522211e-02 -1.108300e-01 1.090137e+02 +-1.104470e-01 7.719378e-03 9.938520e-01 6.531557e+01 1.572797e-02 9.998582e-01 -6.018181e-03 -4.499677e+00 -9.937576e-01 1.496658e-02 -1.105528e-01 1.089344e+02 +-1.105493e-01 6.344343e-03 9.938504e-01 6.605966e+01 1.848372e-02 9.998198e-01 -4.326448e-03 -4.579860e+00 -9.936988e-01 1.789176e-02 -1.106467e-01 1.088574e+02 +-1.115464e-01 5.771519e-03 9.937424e-01 6.680584e+01 1.874394e-02 9.998174e-01 -3.702821e-03 -4.708747e+00 -9.935825e-01 1.821361e-02 -1.116343e-01 1.087907e+02 +-1.133140e-01 6.359768e-03 9.935389e-01 6.754618e+01 1.731402e-02 9.998403e-01 -4.425430e-03 -4.789634e+00 -9.934084e-01 1.670068e-02 -1.134060e-01 1.087201e+02 +-1.155968e-01 7.492320e-03 9.932679e-01 6.828567e+01 1.688045e-02 9.998419e-01 -5.577361e-03 -4.884585e+00 -9.931528e-01 1.612208e-02 -1.157050e-01 1.086478e+02 +-1.177661e-01 7.254734e-03 9.930148e-01 6.902479e+01 1.758561e-02 9.998317e-01 -5.218985e-03 -4.946543e+00 -9.928857e-01 1.684815e-02 -1.178739e-01 1.085668e+02 +-1.195878e-01 7.408337e-03 9.927960e-01 6.977011e+01 1.837544e-02 9.998174e-01 -5.247313e-03 -5.019805e+00 -9.926536e-01 1.761554e-02 -1.197021e-01 1.084826e+02 +-1.216743e-01 7.133093e-03 9.925444e-01 7.051938e+01 1.797497e-02 9.998260e-01 -4.981908e-03 -5.072470e+00 -9.924073e-01 1.723478e-02 -1.217814e-01 1.083983e+02 +-1.234095e-01 7.376899e-03 9.923284e-01 7.127406e+01 1.559289e-02 9.998633e-01 -5.493731e-03 -5.125756e+00 -9.922333e-01 1.479529e-02 -1.235077e-01 1.083160e+02 +-1.246446e-01 8.735687e-03 9.921630e-01 7.202772e+01 1.595162e-02 9.998496e-01 -6.799383e-03 -5.169640e+00 -9.920733e-01 1.497909e-02 -1.247652e-01 1.082285e+02 +-1.253808e-01 8.769852e-03 9.920699e-01 7.278695e+01 1.435901e-02 9.998722e-01 -7.024095e-03 -5.215003e+00 -9.920048e-01 1.336445e-02 -1.254907e-01 1.081439e+02 +-1.267926e-01 9.328478e-03 9.918854e-01 7.355163e+01 1.435415e-02 9.998683e-01 -7.568673e-03 -5.250965e+00 -9.918254e-01 1.327801e-02 -1.269098e-01 1.080563e+02 +-1.278121e-01 7.724363e-03 9.917683e-01 7.432302e+01 1.476541e-02 9.998736e-01 -5.884635e-03 -5.288827e+00 -9.916885e-01 1.389173e-02 -1.279100e-01 1.079665e+02 +-1.289397e-01 5.671148e-03 9.916362e-01 7.509805e+01 1.260751e-02 9.999122e-01 -4.079163e-03 -5.322302e+00 -9.915723e-01 1.197609e-02 -1.289999e-01 1.078742e+02 +-1.306425e-01 3.493916e-03 9.914234e-01 7.587891e+01 9.506667e-03 9.999522e-01 -2.271259e-03 -5.352632e+00 -9.913840e-01 9.128405e-03 -1.306695e-01 1.077830e+02 +-1.326642e-01 2.681364e-03 9.911574e-01 7.666362e+01 1.026652e-02 9.999464e-01 -1.330995e-03 -5.383553e+00 -9.911079e-01 9.999156e-03 -1.326846e-01 1.076848e+02 +-1.344690e-01 3.147963e-03 9.909128e-01 7.745431e+01 1.159636e-02 9.999315e-01 -1.602968e-03 -5.407645e+00 -9.908500e-01 1.127543e-02 -1.344963e-01 1.075825e+02 +-1.366917e-01 4.086094e-03 9.906052e-01 7.824938e+01 1.100964e-02 9.999360e-01 -2.605389e-03 -5.427471e+00 -9.905525e-01 1.055006e-02 -1.367279e-01 1.074828e+02 +-1.383602e-01 7.756543e-03 9.903516e-01 7.904660e+01 1.180350e-02 9.999112e-01 -6.182375e-03 -5.449247e+00 -9.903117e-01 1.083422e-02 -1.384395e-01 1.073781e+02 +-1.385896e-01 1.198577e-02 9.902774e-01 7.984877e+01 1.431669e-02 9.998465e-01 -1.009797e-02 -5.474046e+00 -9.902464e-01 1.277801e-02 -1.387399e-01 1.072685e+02 +-1.397558e-01 1.572527e-02 9.900611e-01 8.065616e+01 1.567534e-02 9.997837e-01 -1.366699e-02 -5.497261e+00 -9.900620e-01 1.360950e-02 -1.399720e-01 1.071591e+02 +-1.394963e-01 1.663944e-02 9.900828e-01 8.147409e+01 1.722002e-02 9.997483e-01 -1.437570e-02 -5.523123e+00 -9.900729e-01 1.504388e-02 -1.397477e-01 1.070489e+02 +-1.390177e-01 1.633615e-02 9.901551e-01 8.229746e+01 2.133374e-02 9.996813e-01 -1.349807e-02 -5.550477e+00 -9.900601e-01 1.924724e-02 -1.393219e-01 1.069330e+02 +-1.388048e-01 1.447101e-02 9.902140e-01 8.312845e+01 2.165159e-02 9.996985e-01 -1.157458e-02 -5.578164e+00 -9.900831e-01 1.983309e-02 -1.390763e-01 1.068232e+02 +-1.381253e-01 1.301215e-02 9.903293e-01 8.396282e+01 2.122319e-02 9.997230e-01 -1.017550e-02 -5.600569e+00 -9.901874e-01 1.961245e-02 -1.383632e-01 1.067162e+02 +-1.364016e-01 1.076811e-02 9.905951e-01 8.480162e+01 1.993126e-02 9.997683e-01 -8.123363e-03 -5.624186e+00 -9.904531e-01 1.863576e-02 -1.365847e-01 1.066094e+02 +-1.347013e-01 7.330803e-03 9.908591e-01 8.565017e+01 2.069307e-02 9.997753e-01 -4.583676e-03 -5.645151e+00 -9.906702e-01 1.988649e-02 -1.348228e-01 1.064988e+02 +-1.329181e-01 3.962549e-03 9.911191e-01 8.649919e+01 2.109774e-02 9.997767e-01 -1.167768e-03 -5.665219e+00 -9.909025e-01 2.075515e-02 -1.329721e-01 1.063903e+02 +-1.311869e-01 3.194230e-03 9.913525e-01 8.734879e+01 1.948757e-02 9.998099e-01 -6.426705e-04 -5.689906e+00 -9.911661e-01 1.923473e-02 -1.312243e-01 1.062858e+02 +-1.297945e-01 7.040084e-03 9.915159e-01 8.819557e+01 2.040016e-02 9.997821e-01 -4.428295e-03 -5.717941e+00 -9.913311e-01 1.965231e-02 -1.299099e-01 1.061799e+02 +-1.276834e-01 1.337617e-02 9.917248e-01 8.904327e+01 2.072071e-02 9.997268e-01 -1.081634e-02 -5.742522e+00 -9.915985e-01 1.916817e-02 -1.279257e-01 1.060757e+02 +-1.261059e-01 1.693562e-02 9.918722e-01 8.989495e+01 1.946295e-02 9.997040e-01 -1.459484e-02 -5.767415e+00 -9.918259e-01 1.746426e-02 -1.263982e-01 1.059776e+02 +-1.243722e-01 1.491375e-02 9.921235e-01 9.075627e+01 1.760024e-02 9.997629e-01 -1.282223e-02 -5.799013e+00 -9.920796e-01 1.586688e-02 -1.246052e-01 1.058789e+02 +-1.234953e-01 1.196673e-02 9.922730e-01 9.162156e+01 1.793269e-02 9.997909e-01 -9.825554e-03 -5.830094e+00 -9.921832e-01 1.658070e-02 -1.236840e-01 1.057772e+02 +-1.228619e-01 1.031533e-02 9.923702e-01 9.248727e+01 1.866495e-02 9.997931e-01 -8.081658e-03 -5.857296e+00 -9.922483e-01 1.752960e-02 -1.230290e-01 1.056748e+02 +-1.221479e-01 1.038791e-02 9.924575e-01 9.334712e+01 1.873840e-02 9.997911e-01 -8.158425e-03 -5.883872e+00 -9.923350e-01 1.760053e-02 -1.223170e-01 1.055741e+02 +-1.217251e-01 9.881780e-03 9.925146e-01 9.421112e+01 1.754070e-02 9.998157e-01 -7.803231e-03 -5.910917e+00 -9.924089e-01 1.645954e-02 -1.218760e-01 1.054745e+02 +-1.209477e-01 8.898539e-03 9.926190e-01 9.507445e+01 2.017227e-02 9.997753e-01 -6.504768e-03 -5.936408e+00 -9.924539e-01 1.923664e-02 -1.211000e-01 1.053717e+02 +-1.198438e-01 7.271893e-03 9.927661e-01 9.593646e+01 2.234193e-02 9.997397e-01 -4.625927e-03 -5.961976e+00 -9.925414e-01 2.162592e-02 -1.199751e-01 1.052677e+02 +-1.190352e-01 8.848992e-03 9.928506e-01 9.679086e+01 2.516260e-02 9.996660e-01 -5.892938e-03 -5.986691e+00 -9.925712e-01 2.428123e-02 -1.192181e-01 1.051663e+02 +-1.183018e-01 1.141515e-02 9.929121e-01 9.764589e+01 2.579424e-02 9.996318e-01 -8.419119e-03 -6.012871e+00 -9.926426e-01 2.461541e-02 -1.185527e-01 1.050653e+02 +-1.174633e-01 1.238153e-02 9.930000e-01 9.849885e+01 2.292434e-02 9.996896e-01 -9.753196e-03 -6.038151e+00 -9.928126e-01 2.161822e-02 -1.177107e-01 1.049697e+02 +-1.171821e-01 9.006918e-03 9.930696e-01 9.935201e+01 1.820885e-02 9.998102e-01 -6.919417e-03 -6.066471e+00 -9.929435e-01 1.727182e-02 -1.173239e-01 1.048776e+02 +-1.172208e-01 5.690447e-03 9.930896e-01 1.002020e+02 1.305697e-02 9.999060e-01 -4.188312e-03 -6.095973e+00 -9.930201e-01 1.247578e-02 -1.172840e-01 1.047876e+02 +-1.183671e-01 6.041275e-03 9.929515e-01 1.010431e+02 9.720484e-03 9.999406e-01 -4.925050e-03 -6.123256e+00 -9.929224e-01 9.069002e-03 -1.184188e-01 1.046963e+02 +-1.197342e-01 1.068369e-02 9.927485e-01 1.018778e+02 6.446464e-03 9.999294e-01 -9.983472e-03 -6.148741e+00 -9.927851e-01 5.204352e-03 -1.197946e-01 1.046056e+02 +-1.204827e-01 1.352048e-02 9.926233e-01 1.027081e+02 5.467535e-03 9.999011e-01 -1.295597e-02 -6.174259e+00 -9.927004e-01 3.866230e-03 -1.205447e-01 1.045111e+02 +-1.209697e-01 1.392892e-02 9.925585e-01 1.035359e+02 6.373522e-03 9.998918e-01 -1.325505e-02 -6.203992e+00 -9.926358e-01 4.722631e-03 -1.210454e-01 1.044140e+02 +-1.214188e-01 1.298786e-02 9.925164e-01 1.043613e+02 7.534352e-03 9.998976e-01 -1.216274e-02 -6.235915e+00 -9.925728e-01 6.001179e-03 -1.215042e-01 1.043147e+02 +-1.220013e-01 1.359193e-02 9.924369e-01 1.051785e+02 8.617162e-03 9.998830e-01 -1.263459e-02 -6.267117e+00 -9.924926e-01 7.010550e-03 -1.221041e-01 1.042165e+02 +-1.225016e-01 1.645980e-02 9.923318e-01 1.059907e+02 9.949292e-03 9.998326e-01 -1.535600e-02 -6.298760e+00 -9.924185e-01 7.991859e-03 -1.226449e-01 1.041174e+02 +-1.231222e-01 1.819136e-02 9.922248e-01 1.067982e+02 9.661891e-03 9.998065e-01 -1.713145e-02 -6.331199e+00 -9.923445e-01 7.477501e-03 -1.232742e-01 1.040206e+02 +-1.243020e-01 1.823554e-02 9.920768e-01 1.076027e+02 7.972666e-03 9.998172e-01 -1.737889e-02 -6.362544e+00 -9.922124e-01 5.749264e-03 -1.244246e-01 1.039256e+02 +-1.264559e-01 1.749424e-02 9.918179e-01 1.084014e+02 6.222075e-03 9.998388e-01 -1.684242e-02 -6.396279e+00 -9.919528e-01 4.041340e-03 -1.265443e-01 1.038301e+02 +-1.296089e-01 1.774251e-02 9.914064e-01 1.091918e+02 5.753134e-03 9.998365e-01 -1.714126e-02 -6.429851e+00 -9.915485e-01 3.482031e-03 -1.296898e-01 1.037315e+02 +-1.327292e-01 2.076343e-02 9.909348e-01 1.099770e+02 5.471096e-03 9.997806e-01 -2.021597e-02 -6.461637e+00 -9.911373e-01 2.738246e-03 -1.328137e-01 1.036312e+02 +-1.362271e-01 2.224775e-02 9.904278e-01 1.107566e+02 4.321779e-03 9.997516e-01 -2.186276e-02 -6.493157e+00 -9.906682e-01 1.302107e-03 -1.362894e-01 1.035305e+02 +-1.393824e-01 2.211545e-02 9.899916e-01 1.115346e+02 4.017233e-03 9.997550e-01 -2.176797e-02 -6.526005e+00 -9.902305e-01 9.429535e-04 -1.394371e-01 1.034269e+02 +-1.422740e-01 2.044221e-02 9.896162e-01 1.123078e+02 5.216391e-03 9.997883e-01 -1.990239e-02 -6.558137e+00 -9.898136e-01 2.330629e-03 -1.423506e-01 1.033200e+02 +-1.448094e-01 2.128516e-02 9.892306e-01 1.130783e+02 7.013069e-03 9.997655e-01 -2.048523e-02 -6.588770e+00 -9.894347e-01 3.971085e-03 -1.449247e-01 1.032107e+02 +-1.469150e-01 2.569409e-02 9.888153e-01 1.138417e+02 2.553576e-03 9.996691e-01 -2.559672e-02 -6.625419e+00 -9.891459e-01 -1.235529e-03 -1.469320e-01 1.031087e+02 +-1.488051e-01 3.176362e-02 9.883563e-01 1.145994e+02 -4.000436e-04 9.994819e-01 -3.218142e-02 -6.664413e+00 -9.888665e-01 -5.184145e-03 -1.487153e-01 1.030043e+02 +-1.513491e-01 3.616220e-02 9.878187e-01 1.153566e+02 3.780690e-03 9.993444e-01 -3.600489e-02 -6.698886e+00 -9.884732e-01 -1.714672e-03 -1.513866e-01 1.028870e+02 +-1.540003e-01 3.424775e-02 9.874771e-01 1.161173e+02 6.069612e-03 9.994130e-01 -3.371515e-02 -6.732518e+00 -9.880522e-01 8.014589e-04 -1.541177e-01 1.027662e+02 +-1.575348e-01 2.612263e-02 9.871679e-01 1.168832e+02 4.681739e-03 9.996586e-01 -2.570605e-02 -6.772644e+00 -9.875024e-01 5.720647e-04 -1.576033e-01 1.026502e+02 +-1.597956e-01 2.329694e-02 9.868752e-01 1.176391e+02 3.079438e-03 9.997284e-01 -2.310175e-02 -6.812258e+00 -9.871453e-01 -6.525398e-04 -1.598240e-01 1.025331e+02 +-1.613565e-01 2.713452e-02 9.865231e-01 1.183859e+02 3.127759e-03 9.996310e-01 -2.698349e-02 -6.848109e+00 -9.868913e-01 -1.268356e-03 -1.613818e-01 1.024110e+02 +-1.639985e-01 3.001508e-02 9.860038e-01 1.191312e+02 4.911652e-04 9.995393e-01 -3.034543e-02 -6.880154e+00 -9.864605e-01 -4.492314e-03 -1.639377e-01 1.022948e+02 +-1.665879e-01 3.260343e-02 9.854874e-01 1.198732e+02 -3.815779e-04 9.994510e-01 -3.312991e-02 -6.916674e+00 -9.860266e-01 -5.895083e-03 -1.664840e-01 1.021780e+02 +-1.685537e-01 3.619051e-02 9.850279e-01 1.206114e+02 3.086699e-03 9.993402e-01 -3.618819e-02 -6.955093e+00 -9.856877e-01 -3.059169e-03 -1.685542e-01 1.020532e+02 +-1.703598e-01 4.083782e-02 9.845353e-01 1.213457e+02 3.882035e-03 9.991609e-01 -4.077276e-02 -6.993951e+00 -9.853743e-01 -3.124038e-03 -1.703753e-01 1.019311e+02 +-1.734488e-01 4.368725e-02 9.838734e-01 1.220792e+02 3.064934e-03 9.990347e-01 -4.382015e-02 -7.031609e+00 -9.848381e-01 -4.585048e-03 -1.734153e-01 1.018119e+02 +-1.756325e-01 4.109592e-02 9.835976e-01 1.228130e+02 3.401261e-03 9.991476e-01 -4.113830e-02 -7.073884e+00 -9.844500e-01 -3.879751e-03 -1.756226e-01 1.016844e+02 +-1.795086e-01 3.730601e-02 9.830488e-01 1.235470e+02 7.378010e-03 9.993036e-01 -3.657563e-02 -7.116066e+00 -9.837288e-01 6.872995e-04 -1.796589e-01 1.015468e+02 +-1.849296e-01 3.586086e-02 9.820973e-01 1.242726e+02 1.000076e-02 9.993509e-01 -3.460773e-02 -7.157447e+00 -9.827009e-01 3.421729e-03 -1.851682e-01 1.014077e+02 +-1.911026e-01 3.472870e-02 9.809555e-01 1.249966e+02 8.903726e-03 9.993941e-01 -3.364693e-02 -7.198722e+00 -9.815297e-01 2.304139e-03 -1.912961e-01 1.012695e+02 +-1.993640e-01 3.441734e-02 9.793209e-01 1.257124e+02 7.623401e-03 9.994072e-01 -3.357135e-02 -7.237820e+00 -9.798959e-01 7.728352e-04 -1.995082e-01 1.011264e+02 +-2.097442e-01 3.490405e-02 9.771331e-01 1.264247e+02 6.731302e-03 9.993905e-01 -3.425422e-02 -7.277349e+00 -9.777332e-01 -6.072494e-04 -2.098513e-01 1.009752e+02 +-2.215235e-01 3.605602e-02 9.744882e-01 1.271315e+02 7.392757e-03 9.993496e-01 -3.529536e-02 -7.316019e+00 -9.751270e-01 -6.146005e-04 -2.216460e-01 1.008115e+02 +-2.338325e-01 3.646334e-02 9.715929e-01 1.278368e+02 8.066085e-03 9.993349e-01 -3.556323e-02 -7.354262e+00 -9.722435e-01 -4.788901e-04 -2.339711e-01 1.006400e+02 +-2.455518e-01 3.680717e-02 9.686844e-01 1.285371e+02 1.095265e-02 9.993204e-01 -3.519487e-02 -7.391647e+00 -9.693216e-01 1.967497e-03 -2.457881e-01 1.004561e+02 +-2.566142e-01 3.679370e-02 9.658133e-01 1.292346e+02 1.413778e-02 9.993111e-01 -3.431348e-02 -7.428905e+00 -9.664105e-01 4.849127e-03 -2.569576e-01 1.002649e+02 +-2.668005e-01 3.681275e-02 9.630484e-01 1.299272e+02 1.816236e-02 9.992848e-01 -3.316625e-02 -7.464456e+00 -9.635807e-01 8.642454e-03 -2.672783e-01 1.000660e+02 +-2.756318e-01 3.765500e-02 9.605255e-01 1.306177e+02 2.381571e-02 9.991932e-01 -3.233675e-02 -7.501316e+00 -9.609683e-01 1.396256e-02 -2.763062e-01 9.985681e+01 +-2.832348e-01 3.770564e-02 9.583091e-01 1.313037e+02 2.916264e-02 9.991034e-01 -3.069152e-02 -7.535702e+00 -9.586071e-01 1.925391e-02 -2.840805e-01 9.964198e+01 +-2.897949e-01 3.761505e-02 9.563493e-01 1.319861e+02 2.949442e-02 9.991038e-01 -3.035922e-02 -7.571493e+00 -9.566342e-01 1.940902e-02 -2.906446e-01 9.943215e+01 +-2.944851e-01 3.618860e-02 9.549706e-01 1.326678e+02 3.289240e-02 9.990745e-01 -2.771687e-02 -7.602966e+00 -9.550899e-01 2.324906e-02 -2.954029e-01 9.921607e+01 +-2.966293e-01 3.359043e-02 9.544017e-01 1.333449e+02 3.923959e-02 9.989659e-01 -2.296317e-02 -7.633871e+00 -9.541862e-01 3.063878e-02 -2.976407e-01 9.899266e+01 +-2.975246e-01 3.271849e-02 9.541533e-01 1.340170e+02 4.590603e-02 9.987468e-01 -1.993319e-02 -7.665957e+00 -9.536099e-01 3.787077e-02 -2.986538e-01 9.876779e+01 +-2.985891e-01 2.994413e-02 9.539119e-01 1.346874e+02 4.720854e-02 9.987475e-01 -1.657458e-02 -7.696836e+00 -9.532135e-01 4.008379e-02 -2.996287e-01 9.855353e+01 +-2.983373e-01 3.542957e-02 9.538027e-01 1.353466e+02 5.060939e-02 9.984922e-01 -2.125964e-02 -7.725113e+00 -9.531178e-01 4.192883e-02 -2.996805e-01 9.834062e+01 +-2.968336e-01 3.904998e-02 9.541304e-01 1.360050e+02 5.058688e-02 9.984036e-01 -2.512421e-02 -7.752705e+00 -9.535884e-01 4.080876e-02 -2.983351e-01 9.813493e+01 +-2.961325e-01 3.945679e-02 9.543315e-01 1.366601e+02 5.251239e-02 9.983078e-01 -2.498022e-02 -7.781433e+00 -9.537023e-01 4.271677e-02 -2.977033e-01 9.792651e+01 +-2.943028e-01 3.805680e-02 9.549542e-01 1.373158e+02 5.415976e-02 9.982652e-01 -2.309160e-02 -7.809641e+00 -9.541764e-01 4.492415e-02 -2.958534e-01 9.771838e+01 +-2.923629e-01 3.448849e-02 9.556853e-01 1.379665e+02 5.560800e-02 9.982716e-01 -1.901377e-02 -7.844579e+00 -9.546893e-01 4.758482e-02 -2.937755e-01 9.751185e+01 +-2.908038e-01 3.523570e-02 9.561337e-01 1.386074e+02 5.699889e-02 9.981848e-01 -1.944944e-02 -7.876691e+00 -9.550834e-01 4.884258e-02 -2.922843e-01 9.731435e+01 +-2.884384e-01 3.795384e-02 9.567459e-01 1.392425e+02 5.803494e-02 9.980700e-01 -2.209688e-02 -7.904561e+00 -9.557381e-01 4.915109e-02 -2.900843e-01 9.711981e+01 +-2.841890e-01 3.956027e-02 9.579518e-01 1.398731e+02 5.961113e-02 9.979443e-01 -2.352743e-02 -7.934720e+00 -9.569134e-01 5.041834e-02 -2.859630e-01 9.692653e+01 +-2.788728e-01 3.891345e-02 9.595393e-01 1.405034e+02 6.114570e-02 9.978707e-01 -2.269708e-02 -7.965446e+00 -9.583795e-01 5.234209e-02 -2.806584e-01 9.673888e+01 +-2.732552e-01 3.696237e-02 9.612312e-01 1.411304e+02 6.246963e-02 9.978340e-01 -2.061125e-02 -7.997921e+00 -9.599110e-01 5.441561e-02 -2.749723e-01 9.655453e+01 +-2.684718e-01 3.498844e-02 9.626519e-01 1.417523e+02 6.244183e-02 9.978705e-01 -1.885424e-02 -8.029376e+00 -9.612616e-01 5.504790e-02 -2.700849e-01 9.637711e+01 +-2.643665e-01 3.405038e-02 9.638210e-01 1.423690e+02 6.234759e-02 9.978894e-01 -1.815265e-02 -8.060370e+00 -9.624049e-01 5.529295e-02 -2.659315e-01 9.620436e+01 +-2.604320e-01 3.275240e-02 9.649365e-01 1.429830e+02 6.330765e-02 9.978529e-01 -1.678322e-02 -8.087196e+00 -9.634144e-01 5.671696e-02 -2.619463e-01 9.603450e+01 +-2.565355e-01 3.089812e-02 9.660408e-01 1.435939e+02 6.596060e-02 9.977184e-01 -1.439525e-02 -8.112439e+00 -9.642815e-01 6.002772e-02 -2.579883e-01 9.586352e+01 +-2.524266e-01 3.007468e-02 9.671485e-01 1.442021e+02 6.925467e-02 9.975150e-01 -1.294344e-02 -8.136308e+00 -9.651345e-01 6.371227e-02 -2.538821e-01 9.569564e+01 +-2.491217e-01 2.804319e-02 9.680661e-01 1.448014e+02 6.736837e-02 9.976611e-01 -1.156397e-02 -8.165921e+00 -9.661263e-01 6.233618e-02 -2.504283e-01 9.553897e+01 +-2.455375e-01 2.857835e-02 9.689657e-01 1.453935e+02 6.436852e-02 9.978399e-01 -1.311887e-02 -8.194245e+00 -9.672477e-01 5.914970e-02 -2.468467e-01 9.539074e+01 +-2.408650e-01 3.192500e-02 9.700334e-01 1.459803e+02 6.519589e-02 9.977336e-01 -1.664814e-02 -8.221656e+00 -9.683665e-01 5.923223e-02 -2.424005e-01 9.524410e+01 +-2.351403e-01 3.558922e-02 9.713096e-01 1.465647e+02 6.756376e-02 9.975106e-01 -2.019302e-02 -8.246532e+00 -9.696104e-01 6.087712e-02 -2.369595e-01 9.509910e+01 +-2.285944e-01 3.660572e-02 9.728333e-01 1.471435e+02 6.685380e-02 9.975240e-01 -2.182562e-02 -8.273094e+00 -9.712236e-01 6.004838e-02 -2.304757e-01 9.496498e+01 +-2.202235e-01 3.475298e-02 9.748301e-01 1.477253e+02 6.348447e-02 9.977570e-01 -2.122859e-02 -8.301809e+00 -9.733814e-01 5.721153e-02 -2.219359e-01 9.484161e+01 +-2.097253e-01 3.283610e-02 9.772088e-01 1.483017e+02 6.249012e-02 9.978428e-01 -2.011803e-02 -8.330790e+00 -9.757614e-01 5.684662e-02 -2.113248e-01 9.471843e+01 +-1.971660e-01 3.170632e-02 9.798573e-01 1.488778e+02 6.374538e-02 9.977764e-01 -1.945937e-02 -8.357320e+00 -9.782955e-01 5.862464e-02 -1.987487e-01 9.460227e+01 +-1.839779e-01 3.008949e-02 9.824697e-01 1.494512e+02 6.353833e-02 9.978049e-01 -1.866093e-02 -8.384287e+00 -9.808746e-01 5.899128e-02 -1.854859e-01 9.449786e+01 +-1.686128e-01 2.947232e-02 9.852416e-01 1.500216e+02 6.281771e-02 9.978422e-01 -1.909873e-02 -8.411951e+00 -9.836787e-01 5.867032e-02 -1.701004e-01 9.440439e+01 +-1.502165e-01 2.848254e-02 9.882427e-01 1.505932e+02 6.198793e-02 9.978895e-01 -1.933820e-02 -8.438291e+00 -9.867079e-01 5.835419e-02 -1.516650e-01 9.432475e+01 +-1.292397e-01 2.755995e-02 9.912303e-01 1.511604e+02 6.132119e-02 9.979226e-01 -1.975078e-02 -8.463908e+00 -9.897155e-01 5.823082e-02 -1.306613e-01 9.425103e+01 +-1.069882e-01 2.734453e-02 9.938842e-01 1.517288e+02 5.816595e-02 9.980818e-01 -2.119866e-02 -8.491499e+00 -9.925575e-01 5.554220e-02 -1.083735e-01 9.419972e+01 +-8.495579e-02 2.813820e-02 9.959873e-01 1.522939e+02 5.238013e-02 9.983450e-01 -2.373690e-02 -8.522593e+00 -9.950070e-01 5.015334e-02 -8.628908e-02 9.416541e+01 +-6.359000e-02 2.925630e-02 9.975472e-01 1.528539e+02 4.649933e-02 9.985714e-01 -2.632219e-02 -8.551506e+00 -9.968923e-01 4.471144e-02 -6.485956e-02 9.414214e+01 +-4.405511e-02 3.007958e-02 9.985762e-01 1.534149e+02 4.018528e-02 9.987910e-01 -2.831317e-02 -8.579884e+00 -9.982206e-01 3.888071e-02 -4.521060e-02 9.413044e+01 +-2.829096e-02 2.964958e-02 9.991599e-01 1.539729e+02 3.328137e-02 9.990337e-01 -2.870349e-02 -8.607328e+00 -9.990456e-01 3.244136e-02 -2.925040e-02 9.412758e+01 +-1.839191e-02 2.782557e-02 9.994436e-01 1.545327e+02 2.475617e-02 9.993188e-01 -2.736654e-02 -8.635876e+00 -9.995244e-01 2.423906e-02 -1.906824e-02 9.413268e+01 +-1.508953e-02 2.533972e-02 9.995650e-01 1.550895e+02 1.662867e-02 9.995469e-01 -2.508824e-02 -8.663502e+00 -9.997479e-01 1.624286e-02 -1.550407e-02 9.413926e+01 +-2.109399e-02 2.189851e-02 9.995376e-01 1.556469e+02 9.131974e-03 9.997226e-01 -2.170985e-02 -8.688323e+00 -9.997358e-01 8.669800e-03 -2.128812e-02 9.413797e+01 +-3.339952e-02 1.870088e-02 9.992671e-01 1.561965e+02 6.110325e-03 9.998100e-01 -1.850682e-02 -8.709648e+00 -9.994234e-01 5.487725e-03 -3.350745e-02 9.412065e+01 +-4.679940e-02 1.637794e-02 9.987700e-01 1.567425e+02 5.577396e-03 9.998543e-01 -1.613439e-02 -8.727615e+00 -9.988888e-01 4.815454e-03 -4.688393e-02 9.409311e+01 +-5.946910e-02 1.519122e-02 9.981145e-01 1.572847e+02 8.193505e-03 9.998579e-01 -1.472958e-02 -8.747148e+00 -9.981966e-01 7.302098e-03 -5.958512e-02 9.405245e+01 +-7.151987e-02 1.443012e-02 9.973348e-01 1.578214e+02 9.621680e-03 9.998588e-01 -1.377666e-02 -8.765511e+00 -9.973928e-01 8.610728e-03 -7.164862e-02 9.400733e+01 +-8.537735e-02 1.386193e-02 9.962522e-01 1.583533e+02 6.951610e-03 9.998871e-01 -1.331677e-02 -8.782045e+00 -9.963245e-01 5.788603e-03 -8.546408e-02 9.396008e+01 +-1.016683e-01 1.235219e-02 9.947417e-01 1.588792e+02 2.286106e-03 9.999231e-01 -1.218288e-02 -8.797332e+00 -9.948158e-01 1.035469e-03 -1.016887e-01 9.390679e+01 +-1.188025e-01 1.165166e-02 9.928495e-01 1.594012e+02 2.750125e-03 9.999311e-01 -1.140570e-02 -8.813298e+00 -9.929141e-01 1.375433e-03 -1.188264e-01 9.383820e+01 +-1.342507e-01 1.100316e-02 9.908863e-01 1.599158e+02 5.077193e-03 9.999328e-01 -1.041573e-02 -8.829814e+00 -9.909344e-01 3.632599e-03 -1.342976e-01 9.375723e+01 +-1.486364e-01 9.184546e-03 9.888493e-01 1.604306e+02 6.744987e-03 9.999430e-01 -8.273736e-03 -8.846036e+00 -9.888690e-01 5.439995e-03 -1.486898e-01 9.366924e+01 +-1.629326e-01 7.570467e-03 9.866081e-01 1.609386e+02 6.761994e-03 9.999556e-01 -6.556186e-03 -8.861136e+00 -9.866141e-01 5.603219e-03 -1.629766e-01 9.357816e+01 +-1.764608e-01 6.683653e-03 9.842850e-01 1.614350e+02 4.967473e-03 9.999702e-01 -5.899608e-03 -8.875534e+00 -9.842952e-01 3.848357e-03 -1.764888e-01 9.348522e+01 +-1.889989e-01 6.360769e-03 9.819567e-01 1.619306e+02 5.137210e-03 9.999717e-01 -5.488702e-03 -8.890957e+00 -9.819639e-01 4.007156e-03 -1.890262e-01 9.338617e+01 +-1.998227e-01 6.697966e-03 9.798092e-01 1.624176e+02 8.616462e-03 9.999500e-01 -5.078409e-03 -8.905283e+00 -9.797942e-01 7.427703e-03 -1.998704e-01 9.327627e+01 +-2.099177e-01 1.021626e-02 9.776657e-01 1.628990e+02 1.352771e-02 9.998800e-01 -7.543823e-03 -8.919301e+00 -9.776255e-01 1.164199e-02 -2.100308e-01 9.316096e+01 +-2.174003e-01 1.130058e-02 9.760171e-01 1.633789e+02 1.394518e-02 9.998669e-01 -8.470543e-03 -8.934349e+00 -9.759830e-01 1.176923e-02 -2.175289e-01 9.304986e+01 +-2.223591e-01 1.113624e-02 9.749012e-01 1.638542e+02 1.540583e-02 9.998500e-01 -7.907419e-03 -8.947930e+00 -9.748431e-01 1.326087e-02 -2.224974e-01 9.293874e+01 +-2.255958e-01 9.868399e-03 9.741710e-01 1.643316e+02 1.447832e-02 9.998722e-01 -6.775912e-03 -8.963049e+00 -9.741134e-01 1.257573e-02 -2.257099e-01 9.283529e+01 +-2.279943e-01 9.086305e-03 9.736201e-01 1.648060e+02 1.515764e-02 9.998684e-01 -5.781784e-03 -8.978427e+00 -9.735445e-01 1.343956e-02 -2.281020e-01 9.272888e+01 +-2.282584e-01 7.916889e-03 9.735684e-01 1.652777e+02 1.707519e-02 9.998457e-01 -4.127207e-03 -8.997595e+00 -9.734509e-01 1.568179e-02 -2.283583e-01 9.262255e+01 +-2.293559e-01 9.113780e-03 9.732999e-01 1.657438e+02 1.912253e-02 9.998053e-01 -4.855798e-03 -9.013537e+00 -9.731548e-01 1.749824e-02 -2.294855e-01 9.251318e+01 +-2.325795e-01 8.553571e-03 9.725398e-01 1.662092e+02 1.689019e-02 9.998460e-01 -4.754508e-03 -9.030668e+00 -9.724307e-01 1.532057e-02 -2.326882e-01 9.241197e+01 +-2.350495e-01 1.202891e-02 9.719089e-01 1.666749e+02 1.713075e-02 9.998193e-01 -8.231399e-03 -9.042484e+00 -9.718325e-01 1.471474e-02 -2.352131e-01 9.229964e+01 +-2.388826e-01 1.377125e-02 9.709508e-01 1.671492e+02 1.685226e-02 9.998076e-01 -1.003439e-02 -9.050522e+00 -9.709022e-01 1.396567e-02 -2.390687e-01 9.218701e+01 +-2.443866e-01 1.294450e-02 9.695914e-01 1.676334e+02 1.572711e-02 9.998323e-01 -9.384196e-03 -9.058955e+00 -9.695504e-01 1.295549e-02 -2.445492e-01 9.206950e+01 +-2.497555e-01 1.147022e-02 9.682410e-01 1.681253e+02 1.481258e-02 9.998581e-01 -8.023911e-03 -9.068787e+00 -9.681957e-01 1.233813e-02 -2.498900e-01 9.194609e+01 +-2.553035e-01 1.222543e-02 9.667836e-01 1.686218e+02 1.759326e-02 9.998132e-01 -7.997165e-03 -9.082588e+00 -9.667009e-01 1.496716e-02 -2.554709e-01 9.181029e+01 +-2.607071e-01 1.292790e-02 9.653314e-01 1.691260e+02 1.988029e-02 9.997702e-01 -8.020047e-03 -9.096027e+00 -9.652133e-01 1.710018e-02 -2.609042e-01 9.166843e+01 +-2.665264e-01 1.431077e-02 9.637214e-01 1.696389e+02 1.961510e-02 9.997632e-01 -9.421237e-03 -9.107717e+00 -9.636280e-01 1.639248e-02 -2.667440e-01 9.152630e+01 +-2.721956e-01 1.590901e-02 9.621104e-01 1.701579e+02 1.869499e-02 9.997620e-01 -1.124251e-02 -9.119045e+00 -9.620604e-01 1.492647e-02 -2.724282e-01 9.138115e+01 +-2.775093e-01 1.743581e-02 9.605647e-01 1.706832e+02 2.029199e-02 9.997186e-01 -1.228412e-02 -9.132048e+00 -9.605087e-01 1.608281e-02 -2.777850e-01 9.122588e+01 +-2.827266e-01 1.816067e-02 9.590286e-01 1.712141e+02 2.443884e-02 9.996325e-01 -1.172488e-02 -9.147581e+00 -9.588892e-01 2.012261e-02 -2.830665e-01 9.106242e+01 +-2.873398e-01 1.919299e-02 9.576364e-01 1.717484e+02 2.829411e-02 9.995330e-01 -1.154301e-02 -9.163386e+00 -9.574107e-01 2.377870e-02 -2.877487e-01 9.089653e+01 +-2.913773e-01 1.809110e-02 9.564371e-01 1.722902e+02 2.640005e-02 9.995924e-01 -1.086466e-02 -9.178977e+00 -9.562439e-01 2.208427e-02 -2.917361e-01 9.073483e+01 +-2.953670e-01 1.606871e-02 9.552487e-01 1.728366e+02 2.678467e-02 9.996048e-01 -8.532921e-03 -9.193889e+00 -9.550084e-01 2.306567e-02 -2.956807e-01 9.056912e+01 +-2.981976e-01 1.237120e-02 9.544240e-01 1.733868e+02 2.689337e-02 9.996279e-01 -4.554645e-03 -9.207509e+00 -9.541252e-01 2.430948e-02 -2.984194e-01 9.039703e+01 +-3.008942e-01 1.085365e-02 9.535957e-01 1.739327e+02 3.075536e-02 9.995255e-01 -1.671982e-03 -9.221710e+00 -9.531615e-01 2.882508e-02 -3.010853e-01 9.021585e+01 +-3.027064e-01 9.524578e-03 9.530363e-01 1.744808e+02 3.359430e-02 9.994353e-01 6.820323e-04 -9.235795e+00 -9.524916e-01 3.222303e-02 -3.028554e-01 9.003523e+01 +-3.041964e-01 8.054749e-03 9.525753e-01 1.750292e+02 3.182098e-02 9.994921e-01 1.710272e-03 -9.249796e+00 -9.520778e-01 3.083213e-02 -3.042982e-01 8.986252e+01 +-3.044141e-01 9.350867e-03 9.524939e-01 1.755740e+02 3.255291e-02 9.994698e-01 5.917600e-04 -9.260605e+00 -9.519834e-01 3.118658e-02 -3.045571e-01 8.968772e+01 +-3.037054e-01 1.132475e-02 9.526987e-01 1.761157e+02 3.320492e-02 9.994477e-01 -1.295251e-03 -9.273390e+00 -9.521872e-01 3.124090e-02 -3.039137e-01 8.951351e+01 +-3.027890e-01 1.161052e-02 9.529869e-01 1.766580e+02 3.493632e-02 9.993889e-01 -1.075670e-03 -9.286728e+00 -9.524171e-01 3.296814e-02 -3.030097e-01 8.934095e+01 +-3.006426e-01 1.210122e-02 9.536601e-01 1.771976e+02 3.430652e-02 9.994096e-01 -1.866579e-03 -9.302397e+00 -9.531197e-01 3.215558e-02 -3.008802e-01 8.917394e+01 +-2.982840e-01 1.151335e-02 9.544077e-01 1.777366e+02 3.409918e-02 9.994174e-01 -1.399209e-03 -9.318006e+00 -9.538679e-01 3.212715e-02 -2.985029e-01 8.900902e+01 +-2.955264e-01 1.169623e-02 9.552630e-01 1.782718e+02 3.482970e-02 9.993922e-01 -1.461413e-03 -9.333326e+00 -9.546995e-01 3.283963e-02 -2.957541e-01 8.884611e+01 +-2.928886e-01 1.371698e-02 9.560481e-01 1.787972e+02 3.655161e-02 9.993268e-01 -3.140221e-03 -9.347847e+00 -9.554477e-01 3.402535e-02 -2.931929e-01 8.868987e+01 +-2.894218e-01 1.599879e-02 9.570679e-01 1.793156e+02 3.706865e-02 9.992976e-01 -5.494994e-03 -9.362912e+00 -9.564837e-01 3.388684e-02 -2.898116e-01 8.853955e+01 +-2.856569e-01 1.651431e-02 9.581897e-01 1.798254e+02 3.729241e-02 9.992857e-01 -6.104944e-03 -9.377338e+00 -9.576061e-01 3.398928e-02 -2.860687e-01 8.839451e+01 +-2.820015e-01 1.652123e-02 9.592717e-01 1.803224e+02 3.760260e-02 9.992738e-01 -6.155974e-03 -9.391387e+00 -9.586768e-01 3.433510e-02 -2.824180e-01 8.825564e+01 +-2.779321e-01 1.526490e-02 9.604794e-01 1.808080e+02 3.684002e-02 9.993075e-01 -5.221680e-03 -9.404618e+00 -9.598941e-01 3.393280e-02 -2.783020e-01 8.812317e+01 +-2.733511e-01 1.248095e-02 9.618333e-01 1.812821e+02 3.703569e-02 9.993109e-01 -2.441812e-03 -9.417670e+00 -9.612011e-01 3.495468e-02 -2.736250e-01 8.799373e+01 +-2.678315e-01 8.359336e-03 9.634295e-01 1.817427e+02 3.866401e-02 9.992501e-01 2.078373e-03 -9.430540e+00 -9.626897e-01 3.780669e-02 -2.679539e-01 8.786857e+01 +-2.609832e-01 5.114162e-03 9.653298e-01 1.821857e+02 4.013209e-02 9.991789e-01 5.556475e-03 -9.443133e+00 -9.645088e-01 4.019084e-02 -2.609741e-01 8.775348e+01 +-2.523614e-01 3.381868e-03 9.676271e-01 1.826121e+02 4.032383e-02 9.991619e-01 7.024543e-03 -9.454580e+00 -9.667925e-01 4.079115e-02 -2.522863e-01 8.765091e+01 +-2.414348e-01 2.284986e-03 9.704143e-01 1.830265e+02 3.975206e-02 9.991811e-01 7.537411e-03 -9.464732e+00 -9.696025e-01 4.039575e-02 -2.413280e-01 8.756152e+01 +-2.281587e-01 2.614680e-03 9.736204e-01 1.834324e+02 3.891153e-02 9.992219e-01 6.435111e-03 -9.474451e+00 -9.728461e-01 3.935328e-02 -2.280830e-01 8.748204e+01 +-2.125689e-01 3.764842e-03 9.771388e-01 1.838335e+02 3.735659e-02 9.992928e-01 4.276428e-03 -9.483133e+00 -9.764318e-01 3.741160e-02 -2.125592e-01 8.740983e+01 +-1.939324e-01 7.455503e-03 9.809865e-01 1.842319e+02 3.766994e-02 9.992902e-01 -1.476012e-04 -9.493001e+00 -9.802914e-01 3.692507e-02 -1.940756e-01 8.734855e+01 +-1.717367e-01 1.097173e-02 9.850818e-01 1.846231e+02 3.901595e-02 9.992292e-01 -4.327365e-03 -9.502342e+00 -9.843700e-01 3.769073e-02 -1.720324e-01 8.729367e+01 +-1.462333e-01 1.117612e-02 9.891870e-01 1.850197e+02 3.900861e-02 9.992236e-01 -5.522814e-03 -9.513352e+00 -9.884808e-01 3.777918e-02 -1.465557e-01 8.725612e+01 +-1.181119e-01 8.604454e-03 9.929630e-01 1.854134e+02 3.571887e-02 9.993521e-01 -4.411101e-03 -9.524231e+00 -9.923577e-01 3.494651e-02 -1.183428e-01 8.723365e+01 +-8.789429e-02 6.290422e-03 9.961099e-01 1.858039e+02 3.127301e-02 9.995045e-01 -3.552410e-03 -9.535840e+00 -9.956388e-01 3.083911e-02 -8.804746e-02 8.723155e+01 +-5.616419e-02 5.016196e-03 9.984089e-01 1.861937e+02 2.635121e-02 9.996465e-01 -3.540066e-03 -9.547399e+00 -9.980738e-01 2.611045e-02 -5.627652e-02 8.724422e+01 +-2.493841e-02 2.806688e-03 9.996850e-01 1.865698e+02 2.098765e-02 9.997771e-01 -2.283387e-03 -9.559758e+00 -9.994687e-01 2.092409e-02 -2.499176e-02 8.726331e+01 +5.721284e-03 -1.150342e-03 9.999830e-01 1.869520e+02 1.662550e-02 9.998612e-01 1.055078e-03 -9.574536e+00 -9.998455e-01 1.661917e-02 5.739613e-03 8.729783e+01 +3.700005e-02 -5.197322e-03 9.993017e-01 1.873319e+02 1.381041e-02 9.998936e-01 4.689056e-03 -9.588216e+00 -9.992199e-01 1.362726e-02 3.706789e-02 8.734029e+01 +6.861960e-02 -8.516294e-03 9.976065e-01 1.876973e+02 1.440293e-02 9.998678e-01 7.544902e-03 -9.601021e+00 -9.975390e-01 1.385073e-02 6.873318e-02 8.738579e+01 +1.011490e-01 -1.028528e-02 9.948181e-01 1.880686e+02 1.356385e-02 9.998679e-01 8.958372e-03 -9.611487e+00 -9.947789e-01 1.258743e-02 1.012751e-01 8.745192e+01 +1.351236e-01 -1.098431e-02 9.907678e-01 1.884238e+02 1.319666e-02 9.998698e-01 9.285428e-03 -9.620615e+00 -9.907409e-01 1.182014e-02 1.352510e-01 8.752595e+01 +1.704443e-01 -1.005290e-02 9.853160e-01 1.887883e+02 1.251008e-02 9.998894e-01 8.037535e-03 -9.627618e+00 -9.852879e-01 1.095643e-02 1.705512e-01 8.761924e+01 +2.076712e-01 -7.456692e-03 9.781702e-01 1.891549e+02 1.222124e-02 9.999127e-01 5.027795e-03 -9.633802e+00 -9.781224e-01 1.091032e-02 2.077442e-01 8.772864e+01 +2.463376e-01 -5.020139e-03 9.691711e-01 1.895095e+02 1.343054e-02 9.999082e-01 1.765663e-03 -9.639227e+00 -9.690911e-01 1.258154e-02 2.463824e-01 8.784616e+01 +2.869700e-01 -3.937609e-03 9.579315e-01 1.898823e+02 1.275367e-02 9.999186e-01 2.895475e-04 -9.645668e+00 -9.578547e-01 1.213405e-02 2.869969e-01 8.799264e+01 +3.289804e-01 1.435245e-04 9.443367e-01 1.902336e+02 7.240976e-03 9.999702e-01 -2.674536e-03 -9.651550e+00 -9.443090e-01 7.717786e-03 3.289696e-01 8.815725e+01 +3.721213e-01 5.771503e-03 9.281661e-01 1.906013e+02 1.364474e-03 9.999762e-01 -6.765080e-03 -9.662356e+00 -9.281831e-01 3.783886e-03 3.721046e-01 8.835376e+01 +4.161375e-01 9.994793e-03 9.092468e-01 1.909490e+02 -1.116839e-03 9.999444e-01 -1.048063e-02 -9.672989e+00 -9.093011e-01 3.345899e-03 4.161255e-01 8.855409e+01 +4.594585e-01 1.130725e-02 8.881272e-01 1.913201e+02 8.704227e-04 9.999127e-01 -1.318076e-02 -9.684160e+00 -8.881988e-01 6.829056e-03 4.594086e-01 8.878162e+01 +5.023124e-01 1.247096e-02 8.645963e-01 1.916933e+02 4.312122e-03 9.998474e-01 -1.692708e-02 -9.694072e+00 -8.646755e-01 1.223092e-02 5.021820e-01 8.903226e+01 +5.448941e-01 1.132756e-02 8.384283e-01 1.920423e+02 9.140241e-03 9.997691e-01 -1.944759e-02 -9.704866e+00 -8.384551e-01 1.826031e-02 5.446648e-01 8.929218e+01 +5.851963e-01 1.051044e-02 8.108236e-01 1.924105e+02 8.094829e-03 9.997904e-01 -1.880224e-02 -9.719824e+00 -8.108513e-01 1.756648e-02 5.849885e-01 8.960055e+01 +6.241385e-01 1.187157e-02 7.812235e-01 1.927478e+02 1.752189e-03 9.998608e-01 -1.659387e-02 -9.734985e+00 -7.813118e-01 1.172572e-02 6.240308e-01 8.992948e+01 +6.619290e-01 1.362857e-02 7.494426e-01 1.931030e+02 -3.337605e-03 9.998783e-01 -1.523486e-02 -9.753497e+00 -7.495591e-01 7.583050e-03 6.618940e-01 9.029644e+01 +6.976322e-01 1.360725e-02 7.163268e-01 1.934542e+02 -4.660140e-03 9.998846e-01 -1.445516e-02 -9.771782e+00 -7.164409e-01 6.746199e-03 6.976152e-01 9.068449e+01 +7.309139e-01 1.324663e-02 6.823412e-01 1.937797e+02 -4.234771e-03 9.998804e-01 -1.487496e-02 -9.788979e+00 -6.824566e-01 7.982752e-03 7.308825e-01 9.108783e+01 +7.618590e-01 1.254854e-02 6.476213e-01 1.941207e+02 -3.911125e-03 9.998832e-01 -1.477307e-02 -9.805979e+00 -6.477311e-01 8.722066e-03 7.618191e-01 9.152895e+01 +7.897710e-01 1.072756e-02 6.133080e-01 1.944379e+02 -2.361531e-03 9.998928e-01 -1.444845e-02 -9.823861e+00 -6.133973e-01 9.962618e-03 7.897117e-01 9.198893e+01 +8.142510e-01 1.064909e-02 5.804153e-01 1.947637e+02 -3.160408e-03 9.998982e-01 -1.391183e-02 -9.843068e+00 -5.805044e-01 9.493374e-03 8.142018e-01 9.248548e+01 +8.358761e-01 1.096908e-02 5.488086e-01 1.950720e+02 -4.730695e-03 9.999071e-01 -1.278003e-02 -9.861770e+00 -5.488979e-01 8.086276e-03 8.358503e-01 9.300739e+01 +8.539778e-01 1.076167e-02 5.201981e-01 1.953781e+02 -5.811760e-03 9.999210e-01 -1.114519e-02 -9.878410e+00 -5.202770e-01 6.494480e-03 8.539729e-01 9.354895e+01 +8.694597e-01 9.517999e-03 4.939122e-01 1.956839e+02 -6.036330e-03 9.999444e-01 -8.643494e-03 -9.896652e+00 -4.939670e-01 4.533751e-03 8.694688e-01 9.412166e+01 +8.824760e-01 8.530372e-03 4.702801e-01 1.959764e+02 -7.021209e-03 9.999630e-01 -4.963022e-03 -9.912797e+00 -4.703050e-01 1.077812e-03 8.825033e-01 9.471148e+01 +8.929201e-01 6.551292e-03 4.501676e-01 1.962715e+02 -6.486757e-03 9.999775e-01 -1.686020e-03 -9.928192e+00 -4.501685e-01 -1.414647e-03 8.929425e-01 9.532711e+01 +9.015920e-01 3.695464e-03 4.325716e-01 1.965617e+02 -4.113073e-03 9.999915e-01 2.977397e-05 -9.940191e+00 -4.325678e-01 -1.806043e-03 9.015996e-01 9.595704e+01 +9.093690e-01 1.215774e-04 4.159903e-01 1.968516e+02 -3.065167e-04 9.999999e-01 3.777946e-04 -9.951735e+00 -4.159902e-01 -4.710632e-04 9.093690e-01 9.660743e+01 +9.167775e-01 -4.268977e-03 3.993755e-01 1.971374e+02 4.415593e-03 9.999901e-01 5.529107e-04 -9.961056e+00 -3.993740e-01 1.256583e-03 9.167873e-01 9.727740e+01 +9.237788e-01 -6.958991e-03 3.828633e-01 1.974182e+02 7.193970e-03 9.999738e-01 8.179753e-04 -9.970244e+00 -3.828589e-01 1.998678e-03 9.238047e-01 9.797014e+01 +9.304654e-01 -7.380189e-03 3.663055e-01 1.976899e+02 7.971659e-03 9.999682e-01 -1.020921e-04 -9.982069e+00 -3.662931e-01 3.015055e-03 9.304946e-01 9.868228e+01 +9.365780e-01 -6.943546e-03 3.503904e-01 1.979499e+02 7.585451e-03 9.999711e-01 -4.595440e-04 -9.992522e+00 -3.503771e-01 3.088267e-03 9.366036e-01 9.941105e+01 +9.415907e-01 -6.089185e-03 3.367045e-01 1.982071e+02 6.659661e-03 9.999777e-01 -5.394187e-04 -1.000261e+01 -3.366937e-01 2.750248e-03 9.416102e-01 1.001604e+02 +9.448573e-01 -3.593169e-03 3.274625e-01 1.984618e+02 3.568112e-03 9.999934e-01 6.772963e-04 -1.001358e+01 -3.274628e-01 5.284742e-04 9.448639e-01 1.009262e+02 +9.462461e-01 -7.863739e-04 3.234465e-01 1.987161e+02 5.581754e-05 9.999974e-01 2.267932e-03 -1.002705e+01 -3.234474e-01 -2.127968e-03 9.462438e-01 1.017027e+02 +9.468438e-01 1.394494e-03 3.216908e-01 1.989723e+02 -2.530612e-03 9.999919e-01 3.113582e-03 -1.003702e+01 -3.216839e-01 -3.762150e-03 9.468397e-01 1.024872e+02 +9.470758e-01 -6.111221e-04 3.210094e-01 1.992416e+02 -4.424794e-04 9.999947e-01 3.209191e-03 -1.004701e+01 -3.210097e-01 -3.181387e-03 9.470706e-01 1.032840e+02 +9.471344e-01 -2.676734e-03 3.208259e-01 1.995168e+02 1.771992e-03 9.999936e-01 3.111974e-03 -1.005960e+01 -3.208322e-01 -2.378956e-03 9.471331e-01 1.040925e+02 +9.470930e-01 -4.665788e-03 3.209254e-01 1.997985e+02 4.296629e-03 9.999890e-01 1.858471e-03 -1.007261e+01 -3.209306e-01 -3.812475e-04 9.471027e-01 1.049137e+02 +9.470100e-01 -5.571899e-03 3.211557e-01 2.000827e+02 5.777165e-03 9.999832e-01 3.137822e-04 -1.008525e+01 -3.211521e-01 1.558214e-03 9.470264e-01 1.057448e+02 +9.468298e-01 -5.244674e-03 3.216922e-01 2.003710e+02 5.463629e-03 9.999850e-01 2.221683e-04 -1.009936e+01 -3.216886e-01 1.547251e-03 9.468443e-01 1.065908e+02 +9.465238e-01 -6.084819e-03 3.225766e-01 2.006612e+02 5.676107e-03 9.999814e-01 2.207652e-03 -1.011259e+01 -3.225840e-01 -2.586164e-04 9.465408e-01 1.074441e+02 +9.462337e-01 -7.406948e-03 3.233991e-01 2.009553e+02 6.070072e-03 9.999683e-01 5.142278e-03 -1.012353e+01 -3.234270e-01 -2.902740e-03 9.462487e-01 1.083065e+02 +9.459411e-01 -9.756188e-03 3.241917e-01 2.012524e+02 8.069194e-03 9.999460e-01 6.547610e-03 -1.013595e+01 -3.242381e-01 -3.577688e-03 9.459688e-01 1.091695e+02 +9.457563e-01 -1.044029e-02 3.247091e-01 2.015498e+02 8.732001e-03 9.999393e-01 6.717734e-03 -1.015022e+01 -3.247595e-01 -3.517979e-03 9.457901e-01 1.100320e+02 +9.455920e-01 -1.164613e-02 3.251463e-01 2.018479e+02 1.051688e-02 9.999310e-01 5.230403e-03 -1.016319e+01 -3.251848e-01 -1.526301e-03 9.456493e-01 1.108930e+02 +9.454582e-01 -1.315883e-02 3.254775e-01 2.021510e+02 1.170991e-02 9.999109e-01 6.410366e-03 -1.017328e+01 -3.255329e-01 -2.249420e-03 9.455281e-01 1.117544e+02 +9.452739e-01 -1.622617e-02 3.258741e-01 2.024544e+02 1.368912e-02 9.998555e-01 1.007710e-02 -1.018181e+01 -3.259906e-01 -5.064695e-03 9.453595e-01 1.126206e+02 +9.451402e-01 -1.753480e-02 3.261940e-01 2.027572e+02 1.436581e-02 9.998233e-01 1.212163e-02 -1.018895e+01 -3.263490e-01 -6.770596e-03 9.452251e-01 1.134866e+02 +9.450547e-01 -1.937291e-02 3.263378e-01 2.030592e+02 1.626594e-02 9.997927e-01 1.224709e-02 -1.019560e+01 -3.265075e-01 -6.265976e-03 9.451739e-01 1.143505e+02 +9.450754e-01 -2.137724e-02 3.261527e-01 2.033642e+02 1.885876e-02 9.997629e-01 1.088212e-02 -1.020405e+01 -3.263080e-01 -4.133585e-03 9.452545e-01 1.152141e+02 +9.451789e-01 -2.090529e-02 3.258831e-01 2.036649e+02 1.889839e-02 9.997779e-01 9.323263e-03 -1.021469e+01 -3.260057e-01 -2.653484e-03 9.453641e-01 1.160817e+02 +9.452466e-01 -2.188025e-02 3.256226e-01 2.039839e+02 2.036065e-02 9.997601e-01 8.074303e-03 -1.022705e+01 -3.257212e-01 -1.002320e-03 9.454654e-01 1.170004e+02 +9.455962e-01 -2.169907e-02 3.246182e-01 2.042664e+02 2.040224e-02 9.997645e-01 7.398483e-03 -1.023876e+01 -3.247023e-01 -3.730381e-04 9.458162e-01 1.178202e+02 +9.459325e-01 -2.215724e-02 3.236058e-01 2.045630e+02 2.080123e-02 9.997543e-01 7.648940e-03 -1.024981e+01 -3.236958e-01 -5.039831e-04 9.461611e-01 1.186904e+02 +9.463680e-01 -2.176183e-02 3.223570e-01 2.048576e+02 2.003989e-02 9.997617e-01 8.659779e-03 -1.026236e+01 -3.224686e-01 -1.735340e-03 9.465786e-01 1.195620e+02 +9.467465e-01 -2.079036e-02 3.213080e-01 2.051510e+02 1.886296e-02 9.997805e-01 9.110771e-03 -1.027452e+01 -3.214269e-01 -2.564770e-03 9.469309e-01 1.204368e+02 +9.472075e-01 -2.147983e-02 3.199008e-01 2.054446e+02 1.960843e-02 9.997666e-01 9.070210e-03 -1.028626e+01 -3.200210e-01 -2.318617e-03 9.474076e-01 1.213088e+02 +9.476693e-01 -2.076045e-02 3.185780e-01 2.057350e+02 1.893696e-02 9.997817e-01 8.820288e-03 -1.029698e+01 -3.186916e-01 -2.325817e-03 9.478556e-01 1.221791e+02 +9.481717e-01 -2.035745e-02 3.171057e-01 2.060233e+02 1.848911e-02 9.997894e-01 8.900244e-03 -1.030650e+01 -3.172201e-01 -2.575956e-03 9.483484e-01 1.230494e+02 +9.486462e-01 -2.164856e-02 3.155974e-01 2.063117e+02 1.949854e-02 9.997602e-01 9.968890e-03 -1.031639e+01 -3.157375e-01 -3.303262e-03 9.488408e-01 1.239201e+02 +9.491044e-01 -2.315876e-02 3.141090e-01 2.065986e+02 2.071826e-02 9.997236e-01 1.110625e-02 -1.032682e+01 -3.142794e-01 -4.033201e-03 9.493220e-01 1.247903e+02 +9.496334e-01 -2.326308e-02 3.124984e-01 2.068814e+02 2.063080e-02 9.997184e-01 1.172752e-02 -1.033631e+01 -3.126833e-01 -4.689753e-03 9.498459e-01 1.256572e+02 +9.501803e-01 -2.421423e-02 3.107589e-01 2.071621e+02 2.160455e-02 9.996965e-01 1.183770e-02 -1.034503e+01 -3.109513e-01 -4.534141e-03 9.504151e-01 1.265197e+02 +9.507385e-01 -2.583853e-02 3.089153e-01 2.074409e+02 2.323812e-02 9.996568e-01 1.209489e-02 -1.035411e+01 -3.091218e-01 -4.320471e-03 9.510127e-01 1.273774e+02 +9.513396e-01 -2.565774e-02 3.070742e-01 2.077118e+02 2.318796e-02 9.996628e-01 1.168925e-02 -1.036189e+01 -3.072706e-01 -4.000018e-03 9.516138e-01 1.282265e+02 +9.518425e-01 -2.561209e-02 3.055158e-01 2.079796e+02 2.335919e-02 9.996663e-01 1.102815e-02 -1.037139e+01 -3.056963e-01 -3.360460e-03 9.521232e-01 1.290715e+02 +9.524510e-01 -2.696448e-02 3.034962e-01 2.082428e+02 2.439398e-02 9.996272e-01 1.225838e-02 -1.037829e+01 -3.037136e-01 -4.272026e-03 9.527538e-01 1.299084e+02 +9.532619e-01 -2.835641e-02 3.008117e-01 2.085020e+02 2.484380e-02 9.995712e-01 1.549676e-02 -1.038629e+01 -3.011222e-01 -7.299167e-03 9.535576e-01 1.307359e+02 +9.539256e-01 -2.825327e-02 2.987102e-01 2.087512e+02 2.360383e-02 9.995377e-01 1.916210e-02 -1.039206e+01 -2.991136e-01 -1.122851e-02 9.541515e-01 1.315533e+02 +9.546204e-01 -2.937478e-02 2.963732e-01 2.089973e+02 2.539425e-02 9.995283e-01 1.727234e-02 -1.040122e+01 -2.967407e-01 -8.962354e-03 9.549160e-01 1.323500e+02 +9.553926e-01 -2.785741e-02 2.940220e-01 2.092395e+02 2.525886e-02 9.996011e-01 1.263231e-02 -1.041143e+01 -2.942567e-01 -4.642151e-03 9.557152e-01 1.331441e+02 +9.561008e-01 -2.578688e-02 2.919013e-01 2.094650e+02 2.425597e-02 9.996665e-01 8.863042e-03 -1.041970e+01 -2.920325e-01 -1.393610e-03 9.564074e-01 1.338990e+02 +9.568478e-01 -2.443805e-02 2.895601e-01 2.096873e+02 2.311132e-02 9.997009e-01 8.000881e-03 -1.042934e+01 -2.896691e-01 -9.635099e-04 9.571264e-01 1.346536e+02 +9.576129e-01 -2.429349e-02 2.870321e-01 2.099047e+02 2.259253e-02 9.997021e-01 9.237176e-03 -1.044065e+01 -2.871710e-01 -2.360858e-03 9.578764e-01 1.353898e+02 +9.585068e-01 -2.571452e-02 2.839077e-01 2.101152e+02 2.312469e-02 9.996548e-01 1.247052e-02 -1.045188e+01 -2.841304e-01 -5.387798e-03 9.587705e-01 1.361105e+02 +9.597674e-01 -2.700709e-02 2.794945e-01 2.103158e+02 2.366400e-02 9.996024e-01 1.532919e-02 -1.046160e+01 -2.797974e-01 -8.098499e-03 9.600249e-01 1.368126e+02 +9.610421e-01 -2.715056e-02 2.750654e-01 2.105053e+02 2.312805e-02 9.995730e-01 1.785736e-02 -1.047044e+01 -2.754328e-01 -1.079994e-02 9.612597e-01 1.374929e+02 +9.621319e-01 -2.648051e-02 2.712951e-01 2.106841e+02 2.252796e-02 9.995900e-01 1.767372e-02 -1.047955e+01 -2.716519e-01 -1.089272e-02 9.623339e-01 1.381496e+02 +9.631592e-01 -2.464764e-02 2.678001e-01 2.108534e+02 2.098898e-02 9.996432e-01 1.651649e-02 -1.048458e+01 -2.681117e-01 -1.028715e-02 9.633329e-01 1.387810e+02 +9.639973e-01 -2.351207e-02 2.648706e-01 2.110151e+02 2.033123e-02 9.996845e-01 1.474460e-02 -1.048927e+01 -2.651338e-01 -8.828609e-03 9.641712e-01 1.393870e+02 +9.645338e-01 -2.034610e-02 2.631742e-01 2.111681e+02 1.792356e-02 9.997720e-01 1.160292e-02 -1.050014e+01 -2.633503e-01 -6.474385e-03 9.646786e-01 1.399688e+02 +9.646023e-01 -1.900929e-02 2.630228e-01 2.113149e+02 1.666555e-02 9.997990e-01 1.113912e-02 -1.051272e+01 -2.631817e-01 -6.361403e-03 9.647253e-01 1.405281e+02 +9.650836e-01 -1.770651e-02 2.613429e-01 2.114559e+02 1.566651e-02 9.998284e-01 9.887358e-03 -1.052308e+01 -2.614731e-01 -5.447796e-03 9.651954e-01 1.410618e+02 +9.654480e-01 -1.684652e-02 2.600507e-01 2.115916e+02 1.560779e-02 9.998549e-01 6.827781e-03 -1.053223e+01 -2.601280e-01 -2.533051e-03 9.655708e-01 1.415766e+02 +9.655507e-01 -1.720282e-02 2.596458e-01 2.117240e+02 1.663960e-02 9.998520e-01 4.367124e-03 -1.054209e+01 -2.596825e-01 1.037222e-04 9.656941e-01 1.420720e+02 +9.657705e-01 -1.584837e-02 2.589134e-01 2.118477e+02 1.502164e-02 9.998738e-01 5.171295e-03 -1.055376e+01 -2.589627e-01 -1.104981e-03 9.658867e-01 1.425540e+02 +9.662313e-01 -1.510924e-02 2.572329e-01 2.119678e+02 1.398285e-02 9.998829e-01 6.207640e-03 -1.056314e+01 -2.572966e-01 -2.401168e-03 9.663295e-01 1.430234e+02 +9.669570e-01 -1.573718e-02 2.544533e-01 2.120878e+02 1.460740e-02 9.998733e-01 6.329116e-03 -1.057460e+01 -2.545206e-01 -2.403082e-03 9.670644e-01 1.434896e+02 +9.680014e-01 -1.677594e-02 2.503835e-01 2.122023e+02 1.591921e-02 9.998584e-01 5.446622e-03 -1.058625e+01 -2.504395e-01 -1.286428e-03 9.681314e-01 1.439404e+02 +9.696504e-01 -1.921327e-02 2.437395e-01 2.123145e+02 1.846732e-02 9.998152e-01 5.345366e-03 -1.059882e+01 -2.437972e-01 -6.819207e-04 9.698260e-01 1.443957e+02 +9.720990e-01 -2.152384e-02 2.335812e-01 2.124189e+02 2.071537e-02 9.997679e-01 5.914256e-03 -1.060855e+01 -2.336543e-01 -9.105213e-04 9.723193e-01 1.448487e+02 +9.752358e-01 -2.265833e-02 2.200040e-01 2.125094e+02 2.203306e-02 9.997432e-01 5.295786e-03 -1.061759e+01 -2.200675e-01 -3.172787e-04 9.754846e-01 1.452960e+02 +9.790615e-01 -2.228738e-02 2.023412e-01 2.125874e+02 2.202750e-02 9.997511e-01 3.536390e-03 -1.062654e+01 -2.023697e-01 9.947278e-04 9.793087e-01 1.457394e+02 +9.833171e-01 -2.087448e-02 1.806981e-01 2.126445e+02 2.078427e-02 9.997811e-01 2.392836e-03 -1.063536e+01 -1.807085e-01 1.402761e-03 9.835357e-01 1.461708e+02 +9.877583e-01 -1.945549e-02 1.547739e-01 2.126931e+02 1.932468e-02 9.998105e-01 2.349823e-03 -1.064334e+01 -1.547903e-01 6.698988e-04 9.879471e-01 1.466087e+02 +9.919455e-01 -1.882870e-02 1.252586e-01 2.127280e+02 1.857962e-02 9.998224e-01 3.156605e-03 -1.065085e+01 -1.252958e-01 -8.039227e-04 9.921191e-01 1.470442e+02 +9.955991e-01 -1.865026e-02 9.184060e-02 2.127352e+02 1.830054e-02 9.998217e-01 4.648667e-03 -1.065946e+01 -9.191093e-02 -2.947475e-03 9.957629e-01 1.474670e+02 +9.983197e-01 -1.673693e-02 5.547705e-02 2.127355e+02 1.640384e-02 9.998446e-01 6.454090e-03 -1.067006e+01 -5.557645e-02 -5.533207e-03 9.984391e-01 1.478973e+02 +9.997523e-01 -1.437397e-02 1.699009e-02 2.126979e+02 1.424094e-02 9.998672e-01 7.925501e-03 -1.068017e+01 -1.710175e-02 -7.681581e-03 9.998243e-01 1.483090e+02 +9.996516e-01 -8.985728e-03 -2.481857e-02 2.126554e+02 9.218636e-03 9.999144e-01 9.285880e-03 -1.069138e+01 2.473301e-02 -9.511435e-03 9.996489e-01 1.487277e+02 +9.976280e-01 -3.647617e-03 -6.873937e-02 2.125937e+02 4.344898e-03 9.999406e-01 9.997040e-03 -1.070164e+01 6.869883e-02 -1.027199e-02 9.975846e-01 1.491398e+02 +9.934967e-01 2.097570e-03 -1.138419e-01 2.124911e+02 -8.649740e-04 9.999405e-01 1.087558e-02 -1.070606e+01 1.138579e-01 -1.070638e-02 9.934394e-01 1.495284e+02 +9.868753e-01 5.395208e-03 -1.613940e-01 2.123948e+02 -3.154838e-03 9.998951e-01 1.413443e-02 -1.071183e+01 1.614534e-01 -1.343974e-02 9.867888e-01 1.499312e+02 +9.775257e-01 8.567655e-03 -2.106421e-01 2.122529e+02 -4.920269e-03 9.998288e-01 1.783357e-02 -1.071523e+01 2.107589e-01 -1.639636e-02 9.774006e-01 1.503050e+02 +9.651599e-01 9.699883e-03 -2.614808e-01 2.121199e+02 -4.264328e-03 9.997630e-01 2.134699e-02 -1.072424e+01 2.616259e-01 -1.948821e-02 9.649726e-01 1.506883e+02 +9.495228e-01 1.114838e-02 -3.134998e-01 2.119677e+02 -3.434785e-03 9.996779e-01 2.514638e-02 -1.073122e+01 3.136792e-01 -2.280025e-02 9.492553e-01 1.510609e+02 +9.311353e-01 1.438286e-02 -3.643903e-01 2.117649e+02 -3.806033e-03 9.995508e-01 2.972767e-02 -1.073621e+01 3.646542e-01 -2.629359e-02 9.307717e-01 1.513980e+02 +9.093124e-01 1.925245e-02 -4.156686e-01 2.115709e+02 -6.305387e-03 9.994519e-01 3.249785e-02 -1.074053e+01 4.160665e-01 -2.692973e-02 9.089354e-01 1.517398e+02 +8.839085e-01 2.242167e-02 -4.671221e-01 2.113278e+02 -7.529744e-03 9.994028e-01 3.372283e-02 -1.074127e+01 4.675993e-01 -2.629058e-02 8.835495e-01 1.520414e+02 +8.555144e-01 2.658640e-02 -5.170960e-01 2.110997e+02 -9.972995e-03 9.993417e-01 3.488108e-02 -1.073972e+01 5.176830e-01 -2.468427e-02 8.552164e-01 1.523511e+02 +8.241967e-01 2.923266e-02 -5.655487e-01 2.108585e+02 -1.090278e-02 9.993008e-01 3.576385e-02 -1.073777e+01 5.661988e-01 -2.331039e-02 8.239391e-01 1.526461e+02 +7.895156e-01 2.932858e-02 -6.130294e-01 2.105705e+02 -8.149408e-03 9.992704e-01 3.731160e-02 -1.073280e+01 6.136765e-01 -2.446225e-02 7.891786e-01 1.529003e+02 +7.520053e-01 2.945536e-02 -6.584985e-01 2.103042e+02 -3.710001e-03 9.991744e-01 4.045735e-02 -1.072730e+01 6.591466e-01 -2.798111e-02 7.514938e-01 1.531666e+02 +7.121610e-01 3.111440e-02 -7.013263e-01 2.099863e+02 -1.310403e-03 9.990745e-01 4.299339e-02 -1.072114e+01 7.020150e-01 -2.969919e-02 7.115427e-01 1.533864e+02 +6.702861e-01 3.320291e-02 -7.413596e-01 2.096902e+02 7.692885e-04 9.989669e-01 4.543579e-02 -1.071643e+01 7.421024e-01 -3.102529e-02 6.695682e-01 1.536096e+02 +6.259801e-01 3.531032e-02 -7.790392e-01 2.093840e+02 3.713906e-03 9.988280e-01 4.825659e-02 -1.071065e+01 7.798302e-01 -3.310093e-02 6.251153e-01 1.538164e+02 +5.802604e-01 3.883756e-02 -8.135045e-01 2.090364e+02 3.722631e-03 9.987254e-01 5.033551e-02 -1.070316e+01 8.144225e-01 -3.223607e-02 5.793762e-01 1.539758e+02 +5.335327e-01 4.226918e-02 -8.447226e-01 2.087097e+02 1.691732e-04 9.987450e-01 5.008319e-02 -1.069694e+01 8.457795e-01 -2.686392e-02 5.328559e-01 1.541279e+02 +4.852255e-01 4.509424e-02 -8.732255e-01 2.083451e+02 -4.942772e-03 9.987947e-01 4.883222e-02 -1.068954e+01 8.743751e-01 -1.937847e-02 4.848635e-01 1.542375e+02 +4.363238e-01 4.454308e-02 -8.986865e-01 2.080039e+02 -5.873801e-03 9.988936e-01 4.665801e-02 -1.067917e+01 8.997706e-01 -1.507929e-02 4.361027e-01 1.543570e+02 +3.884891e-01 4.438723e-02 -9.203836e-01 2.076286e+02 -6.108480e-03 9.989412e-01 4.559748e-02 -1.067050e+01 9.214331e-01 -1.209197e-02 3.883489e-01 1.544466e+02 +3.427629e-01 4.356315e-02 -9.384113e-01 2.072698e+02 -7.491775e-03 9.990192e-01 4.364028e-02 -1.066114e+01 9.393921e-01 -7.927895e-03 3.427531e-01 1.545375e+02 +3.003227e-01 4.350679e-02 -9.528449e-01 2.069028e+02 -1.030613e-02 9.990489e-01 4.236813e-02 -1.065159e+01 9.537820e-01 -2.903958e-03 3.004854e-01 1.546115e+02 +2.615204e-01 4.361803e-02 -9.642119e-01 2.065143e+02 -1.322078e-02 9.990465e-01 4.160802e-02 -1.064196e+01 9.651074e-01 1.866294e-03 2.618478e-01 1.546636e+02 +2.273625e-01 4.115985e-02 -9.729399e-01 2.061374e+02 -9.893025e-03 9.991524e-01 3.995691e-02 -1.062867e+01 9.737600e-01 5.406198e-04 2.275770e-01 1.547274e+02 +1.967036e-01 3.928852e-02 -9.796755e-01 2.057432e+02 -1.601211e-03 9.992083e-01 3.975036e-02 -1.061058e+01 9.804617e-01 -6.250366e-03 1.966107e-01 1.547862e+02 +1.720887e-01 4.054493e-02 -9.842467e-01 2.053426e+02 4.017264e-03 9.991154e-01 4.185983e-02 -1.059434e+01 9.850733e-01 -1.115757e-02 1.717736e-01 1.548398e+02 +1.487242e-01 4.321597e-02 -9.879339e-01 2.049245e+02 1.404692e-04 9.990437e-01 4.372311e-02 -1.057990e+01 9.888787e-01 -6.641455e-03 1.485759e-01 1.548689e+02 +1.286706e-01 4.630769e-02 -9.906056e-01 2.044976e+02 -4.163915e-03 9.989256e-01 4.615578e-02 -1.056644e+01 9.916787e-01 -1.814092e-03 1.287252e-01 1.548951e+02 +1.135065e-01 4.984355e-02 -9.922862e-01 2.040547e+02 -8.838367e-03 9.987519e-01 4.915734e-02 -1.055371e+01 9.934980e-01 3.190514e-03 1.138054e-01 1.549164e+02 +9.940841e-02 4.912094e-02 -9.938335e-01 2.036024e+02 -6.824822e-03 9.987909e-01 4.868332e-02 -1.054074e+01 9.950233e-01 1.943209e-03 9.962347e-02 1.549481e+02 +8.333831e-02 4.396560e-02 -9.955510e-01 2.031364e+02 -2.155443e-03 9.990319e-01 4.393890e-02 -1.052573e+01 9.965190e-01 -1.515936e-03 8.335239e-02 1.549817e+02 +6.673896e-02 3.819249e-02 -9.970392e-01 2.026532e+02 1.977425e-03 9.992601e-01 3.840994e-02 -1.050710e+01 9.977685e-01 -4.535005e-03 6.661406e-02 1.550030e+02 +4.831609e-02 3.494883e-02 -9.982205e-01 2.021496e+02 6.972296e-03 9.993515e-01 3.532591e-02 -1.048725e+01 9.988078e-01 -8.666693e-03 4.804109e-02 1.550197e+02 +3.174231e-02 3.605394e-02 -9.988456e-01 2.016203e+02 8.932202e-03 9.992990e-01 3.635418e-02 -1.047117e+01 9.994562e-01 -1.007585e-02 3.139802e-02 1.550193e+02 +1.682063e-02 3.992350e-02 -9.990611e-01 2.010710e+02 4.879640e-03 9.991873e-01 4.001071e-02 -1.045869e+01 9.998466e-01 -5.548059e-03 1.661215e-02 1.550048e+02 +2.424119e-03 4.287470e-02 -9.990775e-01 2.005036e+02 -7.236538e-04 9.990802e-01 4.287307e-02 -1.044543e+01 9.999968e-01 6.190608e-04 2.452918e-03 1.549800e+02 +-9.615556e-03 4.359373e-02 -9.990031e-01 1.999196e+02 -3.748668e-03 9.990406e-01 4.363147e-02 -1.042741e+01 9.999468e-01 4.164475e-03 -9.442911e-03 1.549573e+02 +-1.795706e-02 4.358338e-02 -9.988884e-01 1.993179e+02 -5.062727e-03 9.990327e-01 4.368070e-02 -1.040597e+01 9.998260e-01 5.841479e-03 -1.771903e-02 1.549342e+02 +-2.299777e-02 4.403534e-02 -9.987652e-01 1.986968e+02 -6.269082e-03 9.990034e-01 4.419021e-02 -1.038401e+01 9.997159e-01 7.277620e-03 -2.269879e-02 1.549104e+02 +-2.663710e-02 4.488889e-02 -9.986368e-01 1.980566e+02 -8.108913e-03 9.989487e-01 4.511921e-02 -1.036129e+01 9.996123e-01 9.299707e-03 -2.624510e-02 1.548848e+02 +-2.923419e-02 4.497119e-02 -9.985604e-01 1.974010e+02 -1.080477e-02 9.989148e-01 4.530349e-02 -1.033952e+01 9.995142e-01 1.211362e-02 -2.871656e-02 1.548572e+02 +-3.039146e-02 4.433836e-02 -9.985542e-01 1.967229e+02 -1.507589e-02 9.988817e-01 4.481176e-02 -1.031726e+01 9.994244e-01 1.641599e-02 -2.968903e-02 1.548260e+02 +-2.908443e-02 4.385709e-02 -9.986143e-01 1.960291e+02 -2.108697e-02 9.987877e-01 4.447887e-02 -1.029442e+01 9.993545e-01 2.235139e-02 -2.812436e-02 1.547958e+02 +-2.348681e-02 4.360132e-02 -9.987729e-01 1.953169e+02 -2.654297e-02 9.986691e-01 4.422097e-02 -1.027036e+01 9.993718e-01 2.754901e-02 -2.229824e-02 1.547720e+02 +-1.522407e-02 4.377078e-02 -9.989256e-01 1.945862e+02 -3.164927e-02 9.985197e-01 4.423535e-02 -1.024608e+01 9.993831e-01 3.228870e-02 -1.381622e-02 1.547538e+02 +-5.858202e-03 4.485157e-02 -9.989765e-01 1.938374e+02 -3.412570e-02 9.984028e-01 4.502594e-02 -1.022125e+01 9.994004e-01 3.435454e-02 -4.318252e-03 1.547492e+02 +3.878805e-03 4.513481e-02 -9.989734e-01 1.930705e+02 -3.648714e-02 9.983220e-01 4.496372e-02 -1.019609e+01 9.993266e-01 3.627528e-02 5.519139e-03 1.547502e+02 +1.383842e-02 4.465359e-02 -9.989067e-01 1.922854e+02 -3.879257e-02 9.982742e-01 4.408791e-02 -1.016949e+01 9.991515e-01 3.814005e-02 1.554677e-02 1.547603e+02 +2.369696e-02 4.473729e-02 -9.987177e-01 1.914848e+02 -4.174097e-02 9.981713e-01 4.372242e-02 -1.014317e+01 9.988474e-01 4.065135e-02 2.552100e-02 1.547788e+02 +3.451007e-02 4.433566e-02 -9.984204e-01 1.906688e+02 -4.393261e-02 9.981171e-01 4.280369e-02 -1.011899e+01 9.984383e-01 4.238606e-02 3.639288e-02 1.548086e+02 +4.516900e-02 4.502404e-02 -9.979642e-01 1.898354e+02 -4.626673e-02 9.980061e-01 4.293185e-02 -1.009564e+01 9.979074e-01 4.423335e-02 4.716206e-02 1.548506e+02 +5.635231e-02 4.632214e-02 -9.973358e-01 1.889847e+02 -4.784802e-02 9.979006e-01 4.364484e-02 -1.007065e+01 9.972638e-01 4.526105e-02 5.845043e-02 1.549028e+02 +6.711431e-02 4.828677e-02 -9.965762e-01 1.881234e+02 -4.952499e-02 9.977582e-01 4.500880e-02 -1.004573e+01 9.965154e-01 4.633468e-02 6.935526e-02 1.549664e+02 +7.719468e-02 5.074095e-02 -9.957240e-01 1.872537e+02 -4.998538e-02 9.976451e-01 4.696368e-02 -1.002182e+01 9.957623e-01 4.614629e-02 7.954920e-02 1.550405e+02 +8.608571e-02 5.250198e-02 -9.949034e-01 1.863819e+02 -5.027566e-02 9.975671e-01 4.829237e-02 -9.996545e+00 9.950184e-01 4.586213e-02 8.851585e-02 1.551219e+02 +9.487550e-02 5.362492e-02 -9.940437e-01 1.855055e+02 -5.072049e-02 9.975115e-01 4.897104e-02 -9.969487e+00 9.941962e-01 4.577223e-02 9.735930e-02 1.552099e+02 +1.028275e-01 5.426425e-02 -9.932179e-01 1.846297e+02 -5.088965e-02 9.974902e-01 4.922909e-02 -9.942539e+00 9.933966e-01 4.548241e-02 1.053309e-01 1.553026e+02 +1.088472e-01 5.434670e-02 -9.925718e-01 1.837535e+02 -4.992696e-02 9.975430e-01 4.914383e-02 -9.916425e+00 9.928039e-01 4.420692e-02 1.112932e-01 1.554011e+02 +1.129783e-01 5.357656e-02 -9.921519e-01 1.828772e+02 -4.747501e-02 9.976957e-01 4.846987e-02 -9.890135e+00 9.924626e-01 4.162637e-02 1.152616e-01 1.555026e+02 +1.153174e-01 5.330065e-02 -9.918976e-01 1.819987e+02 -4.680629e-02 9.977417e-01 4.817303e-02 -9.863521e+00 9.922253e-01 4.087185e-02 1.175518e-01 1.556041e+02 +1.167074e-01 5.288580e-02 -9.917572e-01 1.811142e+02 -4.680625e-02 9.977645e-01 4.769812e-02 -9.837804e+00 9.920628e-01 4.085371e-02 1.189219e-01 1.557048e+02 +1.174405e-01 5.264707e-02 -9.916834e-01 1.802294e+02 -4.726025e-02 9.977586e-01 4.737279e-02 -9.813133e+00 9.919548e-01 4.130372e-02 1.196654e-01 1.558063e+02 +1.182326e-01 5.209188e-02 -9.916186e-01 1.793401e+02 -4.759769e-02 9.977724e-01 4.674000e-02 -9.787337e+00 9.918445e-01 4.167255e-02 1.204487e-01 1.559061e+02 +1.191336e-01 5.173203e-02 -9.915296e-01 1.784501e+02 -4.836926e-02 9.977584e-01 4.624539e-02 -9.762228e+00 9.916994e-01 4.245017e-02 1.213688e-01 1.560078e+02 +1.199691e-01 5.187047e-02 -9.914216e-01 1.775583e+02 -4.894964e-02 9.977286e-01 4.627720e-02 -9.737717e+00 9.915702e-01 4.297789e-02 1.222356e-01 1.561110e+02 +1.203778e-01 5.249348e-02 -9.913393e-01 1.766648e+02 -4.940130e-02 9.976805e-01 4.683050e-02 -9.715049e+00 9.914982e-01 4.333609e-02 1.226918e-01 1.562176e+02 +1.204497e-01 5.246437e-02 -9.913321e-01 1.757731e+02 -4.922305e-02 9.976898e-01 4.682011e-02 -9.692884e+00 9.914984e-01 4.315692e-02 1.227539e-01 1.563244e+02 +1.200903e-01 5.280178e-02 -9.913578e-01 1.748806e+02 -5.052448e-02 9.976156e-01 4.701470e-02 -9.670040e+00 9.914765e-01 4.444183e-02 1.224717e-01 1.564284e+02 +1.195021e-01 5.253171e-02 -9.914432e-01 1.739870e+02 -5.146507e-02 9.975844e-01 4.665386e-02 -9.647095e+00 9.914992e-01 4.544946e-02 1.219170e-01 1.565318e+02 +1.188705e-01 5.084968e-02 -9.916068e-01 1.730979e+02 -4.985424e-02 9.977337e-01 4.518753e-02 -9.626476e+00 9.916574e-01 4.406434e-02 1.211362e-01 1.566392e+02 +1.178390e-01 4.912536e-02 -9.918168e-01 1.722109e+02 -5.055325e-02 9.977773e-01 4.341430e-02 -9.605476e+00 9.917451e-01 4.502367e-02 1.200605e-01 1.567456e+02 +1.174350e-01 5.033417e-02 -9.918041e-01 1.713197e+02 -5.191961e-02 9.976600e-01 4.448380e-02 -9.581146e+00 9.917225e-01 4.627013e-02 1.197736e-01 1.568486e+02 +1.163484e-01 5.402290e-02 -9.917381e-01 1.704234e+02 -5.230853e-02 9.974671e-01 4.819827e-02 -9.556695e+00 9.918301e-01 4.626857e-02 1.188796e-01 1.569534e+02 +1.156863e-01 5.704174e-02 -9.916466e-01 1.695318e+02 -5.196830e-02 9.973299e-01 5.130601e-02 -9.529498e+00 9.919254e-01 4.559878e-02 1.183417e-01 1.570576e+02 +1.153604e-01 5.647471e-02 -9.917170e-01 1.686411e+02 -5.234415e-02 9.973409e-01 5.070611e-02 -9.502013e+00 9.919436e-01 4.606110e-02 1.180098e-01 1.571610e+02 +1.151248e-01 5.538674e-02 -9.918057e-01 1.677494e+02 -5.298148e-02 9.973655e-01 4.954736e-02 -9.474824e+00 9.919371e-01 4.684320e-02 1.177560e-01 1.572640e+02 +1.151284e-01 5.497893e-02 -9.918280e-01 1.668573e+02 -5.360526e-02 9.973561e-01 4.906304e-02 -9.448053e+00 9.919032e-01 4.751864e-02 1.177712e-01 1.573675e+02 +1.160916e-01 5.536972e-02 -9.916940e-01 1.659654e+02 -5.349116e-02 9.973445e-01 4.942334e-02 -9.422279e+00 9.917971e-01 4.730922e-02 1.187451e-01 1.574718e+02 +1.176222e-01 5.640333e-02 -9.914553e-01 1.650767e+02 -5.434787e-02 9.972550e-01 5.028568e-02 -9.397373e+00 9.915702e-01 4.796877e-02 1.203648e-01 1.575771e+02 +1.196906e-01 5.679254e-02 -9.911855e-01 1.641664e+02 -5.441762e-02 9.972370e-01 5.056809e-02 -9.371821e+00 9.913188e-01 4.788542e-02 1.224504e-01 1.576877e+02 +1.210250e-01 5.667571e-02 -9.910302e-01 1.633046e+02 -5.480342e-02 9.972275e-01 5.033753e-02 -9.348969e+00 9.911355e-01 4.821974e-02 1.237954e-01 1.577946e+02 +1.222386e-01 5.556377e-02 -9.909442e-01 1.624228e+02 -5.439476e-02 9.973061e-01 4.921061e-02 -9.324889e+00 9.910091e-01 4.788673e-02 1.249317e-01 1.579057e+02 +1.231576e-01 5.453317e-02 -9.908876e-01 1.615439e+02 -5.393051e-02 9.973813e-01 4.818753e-02 -9.300010e+00 9.909207e-01 4.750441e-02 1.257761e-01 1.580151e+02 +1.236705e-01 5.404299e-02 -9.908506e-01 1.606685e+02 -5.431237e-02 9.973878e-01 4.762070e-02 -9.278466e+00 9.908359e-01 4.792616e-02 1.262827e-01 1.581268e+02 +1.244199e-01 5.398807e-02 -9.907598e-01 1.597910e+02 -5.491397e-02 9.973629e-01 4.745179e-02 -9.257473e+00 9.907089e-01 4.850260e-02 1.270565e-01 1.582372e+02 +1.249301e-01 5.439531e-02 -9.906733e-01 1.589175e+02 -5.504095e-02 9.973383e-01 4.782027e-02 -9.235883e+00 9.906377e-01 4.855340e-02 1.275916e-01 1.583483e+02 +1.258218e-01 5.453306e-02 -9.905529e-01 1.580452e+02 -5.431113e-02 9.973692e-01 4.800964e-02 -9.214242e+00 9.905651e-01 4.775739e-02 1.284525e-01 1.584607e+02 +1.264550e-01 5.538453e-02 -9.904250e-01 1.571734e+02 -5.399235e-02 9.973443e-01 4.887786e-02 -9.192396e+00 9.905019e-01 4.729451e-02 1.291096e-01 1.585732e+02 +1.272171e-01 5.604167e-02 -9.902904e-01 1.563070e+02 -5.390587e-02 9.973176e-01 4.951438e-02 -9.171456e+00 9.904090e-01 4.708339e-02 1.298968e-01 1.586857e+02 +1.274709e-01 5.600094e-02 -9.902601e-01 1.554350e+02 -5.378301e-02 9.973261e-01 4.947735e-02 -9.149972e+00 9.903831e-01 4.695225e-02 1.301419e-01 1.587993e+02 +1.279066e-01 5.415161e-02 -9.903068e-01 1.545698e+02 -5.281066e-02 9.974636e-01 4.772202e-02 -9.127752e+00 9.903792e-01 4.619478e-02 1.304420e-01 1.589136e+02 +1.283165e-01 5.143404e-02 -9.903986e-01 1.537017e+02 -5.201878e-02 9.976285e-01 4.506995e-02 -9.106746e+00 9.903681e-01 4.573610e-02 1.306877e-01 1.590295e+02 +1.290623e-01 5.014324e-02 -9.903679e-01 1.528296e+02 -5.229986e-02 9.976749e-01 4.369763e-02 -9.085915e+00 9.902564e-01 4.615638e-02 1.313847e-01 1.591441e+02 +1.297961e-01 4.996317e-02 -9.902811e-01 1.519539e+02 -5.315399e-02 9.976441e-01 4.336778e-02 -9.065684e+00 9.901150e-01 4.700841e-02 1.321461e-01 1.592594e+02 +1.307966e-01 5.061392e-02 -9.901164e-01 1.510745e+02 -5.250371e-02 9.976481e-01 4.406309e-02 -9.046829e+00 9.900180e-01 4.622148e-02 1.331464e-01 1.593794e+02 +1.318124e-01 5.121070e-02 -9.899510e-01 1.501896e+02 -5.178285e-02 9.976568e-01 4.471443e-02 -9.027227e+00 9.899212e-01 4.536856e-02 1.341554e-01 1.595007e+02 +1.326047e-01 5.118815e-02 -9.898463e-01 1.493011e+02 -5.203396e-02 9.976479e-01 4.462089e-02 -9.007556e+00 9.898023e-01 4.558868e-02 1.349563e-01 1.596223e+02 +1.337511e-01 5.140473e-02 -9.896808e-01 1.484176e+02 -5.158016e-02 9.976613e-01 4.484842e-02 -8.986304e+00 9.896718e-01 4.504937e-02 1.360898e-01 1.597440e+02 +1.348950e-01 5.232784e-02 -9.894772e-01 1.475233e+02 -4.783155e-02 9.977842e-01 4.624631e-02 -8.965435e+00 9.897048e-01 4.108982e-02 1.370991e-01 1.598738e+02 +1.361915e-01 5.454363e-02 -9.891799e-01 1.466258e+02 -4.464320e-02 9.978068e-01 4.887281e-02 -8.943302e+00 9.896762e-01 3.750410e-02 1.383278e-01 1.600060e+02 +1.367944e-01 5.481989e-02 -9.890814e-01 1.457261e+02 -4.737547e-02 9.976871e-01 4.874463e-02 -8.923891e+00 9.894660e-01 4.019020e-02 1.390751e-01 1.601315e+02 +1.378601e-01 5.257475e-02 -9.890553e-01 1.448243e+02 -4.774314e-02 9.977821e-01 4.638394e-02 -8.900537e+00 9.893004e-01 4.082611e-02 1.400644e-01 1.602572e+02 +1.380414e-01 4.711243e-02 -9.893053e-01 1.439222e+02 -4.510216e-02 9.981308e-01 4.123946e-02 -8.876788e+00 9.893990e-01 3.892704e-02 1.399083e-01 1.603908e+02 +1.386085e-01 4.654881e-02 -9.892527e-01 1.430067e+02 -4.656055e-02 9.980965e-01 4.044116e-02 -8.855379e+00 9.892522e-01 4.045465e-02 1.405120e-01 1.605168e+02 +1.379032e-01 4.753439e-02 -9.893044e-01 1.420900e+02 -4.849546e-02 9.979737e-01 4.119097e-02 -8.834610e+00 9.892578e-01 4.229641e-02 1.399290e-01 1.606400e+02 +1.362331e-01 4.833489e-02 -9.894970e-01 1.411690e+02 -4.800227e-02 9.979579e-01 4.213929e-02 -8.814338e+00 9.895132e-01 4.175734e-02 1.382750e-01 1.607675e+02 +1.331051e-01 4.874556e-02 -9.899025e-01 1.402449e+02 -4.644304e-02 9.979993e-01 4.289942e-02 -8.793788e+00 9.900132e-01 4.026395e-02 1.351027e-01 1.608945e+02 +1.293836e-01 4.863915e-02 -9.904010e-01 1.393164e+02 -4.448916e-02 9.980752e-01 4.320409e-02 -8.774450e+00 9.905961e-01 3.847221e-02 1.312984e-01 1.610191e+02 +1.247807e-01 4.865803e-02 -9.909905e-01 1.383734e+02 -4.436900e-02 9.980712e-01 4.341898e-02 -8.753301e+00 9.911918e-01 3.855141e-02 1.266989e-01 1.611378e+02 +1.198669e-01 4.877589e-02 -9.915910e-01 1.374412e+02 -4.454392e-02 9.980508e-01 4.370903e-02 -8.730564e+00 9.917902e-01 3.893008e-02 1.218060e-01 1.612492e+02 +1.145289e-01 4.987410e-02 -9.921672e-01 1.364973e+02 -4.493080e-02 9.979770e-01 4.497966e-02 -8.707212e+00 9.924034e-01 3.942739e-02 1.165381e-01 1.613585e+02 +1.092920e-01 5.122664e-02 -9.926888e-01 1.355474e+02 -4.561868e-02 9.978774e-01 4.647193e-02 -8.684384e+00 9.929624e-01 4.020613e-02 1.113969e-01 1.614635e+02 +1.046883e-01 5.152951e-02 -9.931692e-01 1.345952e+02 -4.735251e-02 9.977823e-01 4.677752e-02 -8.660506e+00 9.933772e-01 4.213200e-02 1.068961e-01 1.615602e+02 +1.013755e-01 4.949116e-02 -9.936164e-01 1.336359e+02 -4.809516e-02 9.978378e-01 4.479444e-02 -8.637170e+00 9.936850e-01 4.324708e-02 1.035366e-01 1.616556e+02 +9.975755e-02 4.581154e-02 -9.939566e-01 1.326768e+02 -4.879872e-02 9.979627e-01 4.109855e-02 -8.614007e+00 9.938145e-01 4.440392e-02 1.017899e-01 1.617489e+02 +9.892700e-02 4.291852e-02 -9.941687e-01 1.317112e+02 -4.957940e-02 9.980412e-01 3.815219e-02 -8.590858e+00 9.938588e-01 4.551600e-02 1.008611e-01 1.618406e+02 +9.805729e-02 4.211299e-02 -9.942893e-01 1.307412e+02 -4.735797e-02 9.981698e-01 3.760689e-02 -8.568927e+00 9.940533e-01 4.339989e-02 9.987221e-02 1.619362e+02 +9.723005e-02 4.276273e-02 -9.943428e-01 1.297673e+02 -4.361861e-02 9.982996e-01 3.866774e-02 -8.548312e+00 9.943057e-01 3.961218e-02 9.892998e-02 1.620340e+02 +9.644718e-02 4.473701e-02 -9.943322e-01 1.287890e+02 -4.116053e-02 9.983141e-01 4.092373e-02 -8.526577e+00 9.944867e-01 3.698026e-02 9.812598e-02 1.621294e+02 +9.564847e-02 4.818611e-02 -9.942482e-01 1.277888e+02 -3.961264e-02 9.982207e-01 4.456785e-02 -8.502345e+00 9.946267e-01 3.512195e-02 9.738706e-02 1.622242e+02 +9.464611e-02 5.147184e-02 -9.941794e-01 1.268239e+02 -3.948759e-02 9.980706e-01 4.791408e-02 -8.478331e+00 9.947276e-01 3.472287e-02 9.649600e-02 1.623139e+02 +9.411041e-02 5.315597e-02 -9.941417e-01 1.258470e+02 -3.947577e-02 9.979875e-01 4.962464e-02 -8.451643e+00 9.947788e-01 3.457431e-02 9.601939e-02 1.624025e+02 +9.360058e-02 5.409412e-02 -9.941392e-01 1.248698e+02 -4.118395e-02 9.978786e-01 5.042003e-02 -8.423223e+00 9.947577e-01 3.622323e-02 9.562983e-02 1.624891e+02 +9.322914e-02 5.469456e-02 -9.941412e-01 1.238955e+02 -4.172502e-02 9.978274e-01 5.098446e-02 -8.393223e+00 9.947700e-01 3.672733e-02 9.530873e-02 1.625755e+02 +9.247072e-02 5.476779e-02 -9.942080e-01 1.229228e+02 -4.247659e-02 9.977942e-01 5.101463e-02 -8.364074e+00 9.948090e-01 3.751321e-02 9.459310e-02 1.626628e+02 +9.215138e-02 5.377365e-02 -9.942920e-01 1.219517e+02 -4.307784e-02 9.978211e-01 4.997206e-02 -8.334383e+00 9.948128e-01 3.822695e-02 9.426705e-02 1.627476e+02 +9.151376e-02 5.226603e-02 -9.944312e-01 1.209827e+02 -4.374182e-02 9.978687e-01 4.842132e-02 -8.305096e+00 9.948427e-01 3.906702e-02 9.360493e-02 1.628330e+02 +9.098484e-02 5.140950e-02 -9.945244e-01 1.200115e+02 -4.505996e-02 9.978563e-01 4.745940e-02 -8.276030e+00 9.948324e-01 4.049515e-02 9.310630e-02 1.629170e+02 +9.056420e-02 5.088671e-02 -9.945897e-01 1.190400e+02 -4.675063e-02 9.978099e-01 4.679452e-02 -8.247097e+00 9.947927e-01 4.225979e-02 9.274485e-02 1.629982e+02 +9.025995e-02 5.037285e-02 -9.946435e-01 1.180676e+02 -4.549213e-02 9.978861e-01 4.640885e-02 -8.217188e+00 9.948787e-01 4.105959e-02 9.236072e-02 1.630817e+02 +8.968942e-02 5.025682e-02 -9.947010e-01 1.170962e+02 -4.633494e-02 9.978552e-01 4.623831e-02 -8.190686e+00 9.948914e-01 4.194232e-02 9.182571e-02 1.631649e+02 +9.010488e-02 4.989201e-02 -9.946818e-01 1.161257e+02 -4.644646e-02 9.978682e-01 4.584442e-02 -8.164620e+00 9.948487e-01 4.206864e-02 9.223011e-02 1.632477e+02 +9.001551e-02 5.098531e-02 -9.946344e-01 1.151532e+02 -4.649350e-02 9.978151e-01 4.694065e-02 -8.137410e+00 9.948546e-01 4.201865e-02 9.218932e-02 1.633320e+02 +9.070459e-02 4.948941e-02 -9.946474e-01 1.141834e+02 -4.654619e-02 9.978836e-01 4.540577e-02 -8.112159e+00 9.947895e-01 4.217853e-02 9.281617e-02 1.634176e+02 +9.088773e-02 4.959217e-02 -9.946256e-01 1.132135e+02 -4.709518e-02 9.978559e-01 4.544975e-02 -8.088498e+00 9.947470e-01 4.271124e-02 9.302841e-02 1.635036e+02 +9.080935e-02 5.100057e-02 -9.945615e-01 1.122414e+02 -4.692298e-02 9.977977e-01 4.688219e-02 -8.064935e+00 9.947623e-01 4.241045e-02 9.300246e-02 1.635907e+02 +9.063070e-02 5.213529e-02 -9.945190e-01 1.112713e+02 -4.773771e-02 9.977082e-01 4.795215e-02 -8.039749e+00 9.947398e-01 4.313012e-02 9.291181e-02 1.636764e+02 +9.097282e-02 5.078062e-02 -9.945578e-01 1.102992e+02 -4.790950e-02 9.977658e-01 4.656212e-02 -8.016223e+00 9.947003e-01 4.341288e-02 9.320244e-02 1.637618e+02 +9.098417e-02 5.026671e-02 -9.945829e-01 1.093298e+02 -4.906158e-02 9.977387e-01 4.593808e-02 -7.988739e+00 9.946431e-01 4.461617e-02 9.324460e-02 1.638452e+02 +9.102953e-02 5.058643e-02 -9.945625e-01 1.083600e+02 -4.909452e-02 9.977225e-01 4.625369e-02 -7.961322e+00 9.946373e-01 4.461712e-02 9.330573e-02 1.639300e+02 +9.069197e-02 5.348940e-02 -9.944415e-01 1.073860e+02 -4.972321e-02 9.975543e-01 4.912214e-02 -7.933978e+00 9.946369e-01 4.499184e-02 9.312983e-02 1.640146e+02 +9.082970e-02 5.479972e-02 -9.943575e-01 1.064168e+02 -4.887934e-02 9.975267e-01 5.050950e-02 -7.906372e+00 9.946662e-01 4.401577e-02 9.328363e-02 1.641013e+02 +9.025062e-02 5.498735e-02 -9.943999e-01 1.054447e+02 -5.022363e-02 9.974554e-01 5.059808e-02 -7.880923e+00 9.946519e-01 4.537586e-02 9.278264e-02 1.641854e+02 +8.999326e-02 5.413655e-02 -9.944699e-01 1.044776e+02 -5.024308e-02 9.974969e-01 4.975466e-02 -7.853605e+00 9.946743e-01 4.548765e-02 9.248799e-02 1.642692e+02 +8.931996e-02 5.413197e-02 -9.945309e-01 1.035089e+02 -5.085234e-02 9.974675e-01 4.972472e-02 -7.826026e+00 9.947040e-01 4.613281e-02 9.184650e-02 1.643528e+02 +8.901285e-02 5.526693e-02 -9.944960e-01 1.025407e+02 -5.219497e-02 9.973463e-01 5.075361e-02 -7.799256e+00 9.946620e-01 4.738996e-02 9.166130e-02 1.644349e+02 +8.838057e-02 5.619845e-02 -9.945002e-01 1.015720e+02 -5.566163e-02 9.971257e-01 5.140022e-02 -7.770766e+00 9.945304e-01 5.081271e-02 9.125464e-02 1.645137e+02 +8.818061e-02 5.302397e-02 -9.946922e-01 1.006078e+02 -5.733784e-02 9.971967e-01 4.807442e-02 -7.743516e+00 9.944529e-01 5.279427e-02 9.097369e-02 1.645939e+02 +8.855687e-02 4.913822e-02 -9.948583e-01 9.964440e+01 -6.047186e-02 9.972053e-01 4.387128e-02 -7.716144e+00 9.942338e-01 5.627582e-02 9.128086e-02 1.646724e+02 +9.068580e-02 4.670770e-02 -9.947836e-01 9.868013e+01 -6.413058e-02 9.971001e-01 4.097025e-02 -7.691555e+00 9.938126e-01 6.008062e-02 9.341821e-02 1.647519e+02 +9.265692e-02 4.806584e-02 -9.945372e-01 9.771624e+01 -6.603983e-02 9.969314e-01 4.202890e-02 -7.668411e+00 9.935057e-01 6.178480e-02 9.554686e-02 1.648360e+02 +9.506144e-02 5.119850e-02 -9.941539e-01 9.674473e+01 -6.492759e-02 9.968689e-01 4.512993e-02 -7.645451e+00 9.933518e-01 6.025790e-02 9.808799e-02 1.649281e+02 +9.721106e-02 5.299063e-02 -9.938521e-01 9.577946e+01 -6.351830e-02 9.968762e-01 4.693900e-02 -7.621151e+00 9.932349e-01 5.856480e-02 1.002733e-01 1.650250e+02 +9.943451e-02 5.454678e-02 -9.935479e-01 9.481342e+01 -6.219738e-02 9.968845e-01 4.850525e-02 -7.595478e+00 9.930983e-01 5.697297e-02 1.025174e-01 1.651226e+02 +1.016564e-01 5.575781e-02 -9.932558e-01 9.384929e+01 -6.138350e-02 9.968771e-01 4.967872e-02 -7.567909e+00 9.929240e-01 5.591935e-02 1.047616e-01 1.652231e+02 +1.041815e-01 5.688816e-02 -9.929300e-01 9.288647e+01 -6.081904e-02 9.968587e-01 5.073193e-02 -7.539571e+00 9.926970e-01 5.510371e-02 1.073141e-01 1.653259e+02 +1.061034e-01 5.692616e-02 -9.927243e-01 9.191835e+01 -6.274834e-02 9.967534e-01 5.045061e-02 -7.510417e+00 9.923733e-01 5.693881e-02 1.093309e-01 1.654274e+02 +1.082547e-01 5.678987e-02 -9.924998e-01 9.095214e+01 -6.350731e-02 9.967228e-01 5.010460e-02 -7.480226e+00 9.920926e-01 5.760692e-02 1.115065e-01 1.655302e+02 +1.098515e-01 5.476449e-02 -9.924381e-01 8.997192e+01 -6.419284e-02 9.967873e-01 4.789909e-02 -7.451480e+00 9.918730e-01 5.844563e-02 1.130140e-01 1.656374e+02 +1.117552e-01 5.092152e-02 -9.924302e-01 8.902823e+01 -6.366019e-02 9.970017e-01 4.398747e-02 -7.424901e+00 9.916946e-01 5.826246e-02 1.146618e-01 1.657432e+02 +1.126116e-01 4.839162e-02 -9.924600e-01 8.806538e+01 -6.409094e-02 9.970872e-01 4.134503e-02 -7.399685e+00 9.915700e-01 5.895176e-02 1.153851e-01 1.658512e+02 +1.133351e-01 4.766750e-02 -9.924127e-01 8.709607e+01 -6.367389e-02 9.971436e-01 4.062309e-02 -7.380274e+00 9.915144e-01 5.858675e-02 1.160465e-01 1.659632e+02 +1.134882e-01 4.941651e-02 -9.923096e-01 8.612617e+01 -6.318024e-02 9.970998e-01 4.242929e-02 -7.361033e+00 9.915285e-01 5.787913e-02 1.162812e-01 1.660746e+02 +1.139765e-01 5.146586e-02 -9.921495e-01 8.515047e+01 -5.993470e-02 9.971945e-01 4.484238e-02 -7.341209e+00 9.916740e-01 5.435320e-02 1.167414e-01 1.661916e+02 +1.136868e-01 5.135253e-02 -9.921886e-01 8.418412e+01 -5.764645e-02 9.973217e-01 4.501298e-02 -7.317668e+00 9.918429e-01 5.207877e-02 1.163426e-01 1.663055e+02 +1.131856e-01 5.055762e-02 -9.922867e-01 8.321610e+01 -5.677313e-02 9.974019e-01 4.434240e-02 -7.293431e+00 9.919505e-01 5.131629e-02 1.157619e-01 1.664184e+02 +1.119347e-01 5.125816e-02 -9.923927e-01 8.224261e+01 -5.568172e-02 9.974232e-01 4.523751e-02 -7.267431e+00 9.921543e-01 5.019448e-02 1.145004e-01 1.665315e+02 +1.109191e-01 5.441103e-02 -9.923388e-01 8.126555e+01 -5.365575e-02 9.973717e-01 4.868961e-02 -7.240322e+00 9.923800e-01 4.784408e-02 1.135470e-01 1.666460e+02 +1.100869e-01 5.942134e-02 -9.921441e-01 8.028691e+01 -5.519025e-02 9.970366e-01 5.359054e-02 -7.211469e+00 9.923885e-01 4.885706e-02 1.130402e-01 1.667540e+02 +1.106046e-01 6.112154e-02 -9.919832e-01 7.931183e+01 -5.530860e-02 9.969389e-01 5.526008e-02 -7.181974e+00 9.923244e-01 4.875318e-02 1.136466e-01 1.668626e+02 +1.111544e-01 5.623192e-02 -9.922110e-01 7.833892e+01 -5.463148e-02 9.972340e-01 5.039641e-02 -7.153796e+00 9.923004e-01 4.860417e-02 1.139190e-01 1.669738e+02 +1.120495e-01 4.888660e-02 -9.924994e-01 7.736723e+01 -5.274679e-02 9.976736e-01 4.318657e-02 -7.127829e+00 9.923017e-01 4.751212e-02 1.143674e-01 1.670870e+02 +1.126959e-01 4.490989e-02 -9.926141e-01 7.639326e+01 -5.138845e-02 9.979046e-01 3.931491e-02 -7.104477e+00 9.922998e-01 4.657826e-02 1.147676e-01 1.672019e+02 +1.133072e-01 4.754658e-02 -9.924217e-01 7.540969e+01 -5.015329e-02 9.978546e-01 4.208076e-02 -7.083141e+00 9.922934e-01 4.500516e-02 1.154487e-01 1.673142e+02 +1.129118e-01 5.261815e-02 -9.922108e-01 7.442483e+01 -4.968523e-02 9.976465e-01 4.725233e-02 -7.061818e+00 9.923620e-01 4.396287e-02 1.152604e-01 1.674265e+02 +1.118953e-01 5.419679e-02 -9.922410e-01 7.343870e+01 -4.883268e-02 9.976051e-01 4.898292e-02 -7.037860e+00 9.925195e-01 4.297282e-02 1.142740e-01 1.675389e+02 +1.105890e-01 5.380875e-02 -9.924085e-01 7.245612e+01 -4.852186e-02 9.976349e-01 4.868510e-02 -7.009383e+00 9.926811e-01 4.276946e-02 1.129384e-01 1.676483e+02 +1.091027e-01 5.397384e-02 -9.925641e-01 7.147256e+01 -4.851606e-02 9.976239e-01 4.891611e-02 -6.982627e+00 9.928458e-01 4.281841e-02 1.114620e-01 1.677550e+02 +1.068224e-01 5.456378e-02 -9.927798e-01 7.048515e+01 -4.744759e-02 9.976352e-01 4.972533e-02 -6.956324e+00 9.931454e-01 4.179322e-02 1.091588e-01 1.678634e+02 +1.035536e-01 5.489837e-02 -9.931076e-01 6.949760e+01 -4.528329e-02 9.977004e-01 5.043048e-02 -6.928865e+00 9.935925e-01 3.974892e-02 1.058014e-01 1.679681e+02 +1.002521e-01 5.520621e-02 -9.934293e-01 6.850825e+01 -4.321653e-02 9.977588e-01 5.108561e-02 -6.902407e+00 9.940231e-01 3.781113e-02 1.024133e-01 1.680701e+02 +9.720146e-02 5.393726e-02 -9.938021e-01 6.751984e+01 -4.200995e-02 9.978628e-01 5.004877e-02 -6.876903e+00 9.943777e-01 3.688476e-02 9.925963e-02 1.681677e+02 +9.444052e-02 5.308277e-02 -9.941143e-01 6.652966e+01 -4.175556e-02 9.979099e-01 4.931869e-02 -6.849228e+00 9.946545e-01 3.685211e-02 9.645963e-02 1.682622e+02 +9.218087e-02 5.278076e-02 -9.943424e-01 6.553633e+01 -4.171846e-02 9.979220e-01 4.910325e-02 -6.822546e+00 9.948680e-01 3.695605e-02 9.419126e-02 1.683543e+02 +9.016400e-02 5.260268e-02 -9.945368e-01 6.454085e+01 -4.300995e-02 9.978782e-01 4.888018e-02 -6.796390e+00 9.949978e-01 3.836774e-02 9.223513e-02 1.684419e+02 +8.838344e-02 5.185421e-02 -9.947359e-01 6.354367e+01 -4.261793e-02 9.979264e-01 4.823389e-02 -6.768485e+00 9.951744e-01 3.813050e-02 9.041010e-02 1.685295e+02 +8.614914e-02 5.368951e-02 -9.948345e-01 6.254205e+01 -4.363177e-02 9.977921e-01 5.007079e-02 -6.740162e+00 9.953264e-01 3.909283e-02 8.830151e-02 1.686151e+02 +8.487163e-02 5.571687e-02 -9.948329e-01 6.154040e+01 -4.496258e-02 9.976324e-01 5.203780e-02 -6.714259e+00 9.953769e-01 4.031371e-02 8.717586e-02 1.686972e+02 +8.382030e-02 5.575487e-02 -9.949199e-01 6.053894e+01 -4.647351e-02 9.975658e-01 5.198785e-02 -6.686894e+00 9.953966e-01 4.187977e-02 8.620739e-02 1.687777e+02 +8.353113e-02 5.489677e-02 -9.949919e-01 5.953933e+01 -4.689459e-02 9.975917e-01 5.110335e-02 -6.658607e+00 9.954012e-01 4.239101e-02 8.590433e-02 1.688593e+02 +8.336753e-02 5.411814e-02 -9.950483e-01 5.853719e+01 -4.698183e-02 9.976274e-01 5.032217e-02 -6.630508e+00 9.954108e-01 4.255395e-02 8.571230e-02 1.689414e+02 +8.279885e-02 5.347158e-02 -9.951307e-01 5.753603e+01 -4.723969e-02 9.976475e-01 4.967630e-02 -6.604353e+00 9.954460e-01 4.289652e-02 8.513005e-02 1.690211e+02 +8.230406e-02 5.319369e-02 -9.951866e-01 5.653409e+01 -4.585416e-02 9.977191e-01 4.953683e-02 -6.576718e+00 9.955519e-01 4.155636e-02 8.455549e-02 1.691030e+02 +8.110063e-02 5.442569e-02 -9.952188e-01 5.553393e+01 -4.576313e-02 9.976583e-01 5.082986e-02 -6.548982e+00 9.956548e-01 4.142200e-02 8.340140e-02 1.691850e+02 +7.992681e-02 5.546805e-02 -9.952562e-01 5.453419e+01 -4.540825e-02 9.976166e-01 5.195298e-02 -6.521493e+00 9.957660e-01 4.104040e-02 8.225503e-02 1.692648e+02 +7.838363e-02 5.594360e-02 -9.953523e-01 5.353630e+01 -4.488628e-02 9.976097e-01 5.253571e-02 -6.494630e+00 9.959123e-01 4.055972e-02 8.070737e-02 1.693432e+02 +7.712824e-02 5.490713e-02 -9.955081e-01 5.254333e+01 -4.327253e-02 9.977259e-01 5.167687e-02 -6.467507e+00 9.960817e-01 3.909241e-02 7.932881e-02 1.694202e+02 +7.571156e-02 5.420676e-02 -9.956552e-01 5.154988e+01 -4.330526e-02 9.977578e-01 5.102823e-02 -6.441651e+00 9.961890e-01 3.925368e-02 7.788924e-02 1.694950e+02 +7.421353e-02 5.420251e-02 -9.957682e-01 5.056160e+01 -4.300168e-02 9.977670e-01 5.110646e-02 -6.413829e+00 9.963148e-01 3.902692e-02 7.637861e-02 1.695670e+02 +7.243793e-02 5.331380e-02 -9.959470e-01 4.957187e+01 -4.150333e-02 9.978665e-01 5.039792e-02 -6.389179e+00 9.965091e-01 3.768439e-02 7.449608e-02 1.696402e+02 +7.019359e-02 5.041907e-02 -9.962584e-01 4.858770e+01 -4.125677e-02 9.980140e-01 4.760109e-02 -6.365828e+00 9.966799e-01 3.776110e-02 7.213432e-02 1.697083e+02 +6.800837e-02 4.523318e-02 -9.966588e-01 4.761182e+01 -3.866073e-02 9.983408e-01 4.267146e-02 -6.344237e+00 9.969354e-01 3.562954e-02 6.964428e-02 1.697763e+02 +6.548812e-02 4.304444e-02 -9.969245e-01 4.663550e+01 -3.859644e-02 9.984308e-01 4.057408e-02 -6.324209e+00 9.971067e-01 3.582061e-02 6.704672e-02 1.698396e+02 +6.365355e-02 4.287461e-02 -9.970506e-01 4.566087e+01 -3.788466e-02 9.984604e-01 4.051662e-02 -6.305321e+00 9.972527e-01 3.519390e-02 6.517984e-02 1.699006e+02 +6.091850e-02 4.731922e-02 -9.970205e-01 4.468182e+01 -3.681538e-02 9.983025e-01 4.513064e-02 -6.287617e+00 9.974636e-01 3.395640e-02 6.255717e-02 1.699586e+02 +5.890474e-02 4.949878e-02 -9.970356e-01 4.371013e+01 -3.546363e-02 9.982432e-01 4.746356e-02 -6.268908e+00 9.976335e-01 3.256267e-02 6.055667e-02 1.700171e+02 +5.783970e-02 5.111024e-02 -9.970167e-01 4.274416e+01 -3.637571e-02 9.981333e-01 4.905724e-02 -6.249479e+00 9.976630e-01 3.342973e-02 5.959091e-02 1.700723e+02 +5.757792e-02 5.061736e-02 -9.970570e-01 4.178176e+01 -3.737531e-02 9.981230e-01 4.851315e-02 -6.228328e+00 9.976412e-01 3.447203e-02 5.936169e-02 1.701248e+02 +5.771386e-02 5.059196e-02 -9.970504e-01 4.082336e+01 -3.817192e-02 9.980966e-01 4.843549e-02 -6.202703e+00 9.976032e-01 3.526392e-02 5.953520e-02 1.701766e+02 +5.786598e-02 5.157459e-02 -9.969913e-01 3.986470e+01 -3.943703e-02 9.980032e-01 4.933801e-02 -6.175146e+00 9.975451e-01 3.646338e-02 5.978439e-02 1.702280e+02 +5.800658e-02 5.504314e-02 -9.967976e-01 3.890723e+01 -4.140682e-02 9.977523e-01 5.268629e-02 -6.146854e+00 9.974572e-01 3.821806e-02 6.015537e-02 1.702780e+02 +5.789332e-02 5.620071e-02 -9.967396e-01 3.795304e+01 -4.210314e-02 9.976633e-01 5.380735e-02 -6.116530e+00 9.974346e-01 3.885078e-02 6.012427e-02 1.703283e+02 +5.788577e-02 5.519813e-02 -9.967961e-01 3.700423e+01 -4.236087e-02 9.977068e-01 5.278860e-02 -6.084618e+00 9.974241e-01 3.916944e-02 6.009127e-02 1.703775e+02 +5.741449e-02 5.457212e-02 -9.968578e-01 3.606880e+01 -4.273685e-02 9.977239e-01 5.215810e-02 -6.054520e+00 9.974353e-01 3.960793e-02 5.961606e-02 1.704262e+02 +5.593824e-02 5.456659e-02 -9.969420e-01 3.513286e+01 -4.319133e-02 9.977030e-01 5.218479e-02 -6.023869e+00 9.974996e-01 4.014012e-02 5.816655e-02 1.704735e+02 +5.412318e-02 5.573722e-02 -9.969774e-01 3.420793e+01 -4.435678e-02 9.975895e-01 5.336345e-02 -5.994786e+00 9.975486e-01 4.133450e-02 5.646504e-02 1.705188e+02 +5.246166e-02 5.692426e-02 -9.969992e-01 3.329000e+01 -4.489274e-02 9.974991e-01 5.459058e-02 -5.964224e+00 9.976134e-01 4.189410e-02 5.488595e-02 1.705614e+02 +5.065391e-02 5.773827e-02 -9.970459e-01 3.238526e+01 -4.559514e-02 9.974202e-01 5.544354e-02 -5.934340e+00 9.976750e-01 4.265201e-02 5.315582e-02 1.706028e+02 +4.869586e-02 5.731991e-02 -9.971675e-01 3.148447e+01 -4.668680e-02 9.973913e-01 5.505288e-02 -5.904040e+00 9.977220e-01 4.387371e-02 5.124491e-02 1.706422e+02 +4.645898e-02 5.683115e-02 -9.973022e-01 3.058176e+01 -4.671814e-02 9.974114e-01 5.466104e-02 -5.872975e+00 9.978272e-01 4.405261e-02 4.899377e-02 1.706794e+02 +4.400409e-02 5.631493e-02 -9.974428e-01 2.970436e+01 -4.699707e-02 9.974213e-01 5.424036e-02 -5.841817e+00 9.979253e-01 4.449009e-02 4.653726e-02 1.707134e+02 +4.208114e-02 5.593677e-02 -9.975471e-01 2.882594e+01 -4.705233e-02 9.974347e-01 5.394559e-02 -5.812160e+00 9.980057e-01 4.466682e-02 4.460515e-02 1.707461e+02 +4.047260e-02 5.586884e-02 -9.976175e-01 2.795477e+01 -4.724367e-02 9.974258e-01 5.394149e-02 -5.782162e+00 9.980632e-01 4.494795e-02 4.300787e-02 1.707773e+02 +3.908881e-02 5.602373e-02 -9.976640e-01 2.709342e+01 -4.713165e-02 9.974191e-01 5.416336e-02 -5.753892e+00 9.981236e-01 4.490437e-02 4.162842e-02 1.708071e+02 +3.758059e-02 5.625856e-02 -9.977087e-01 2.624437e+01 -4.771097e-02 9.973764e-01 5.444271e-02 -5.725102e+00 9.981540e-01 4.555566e-02 4.016614e-02 1.708337e+02 +3.608180e-02 5.745935e-02 -9.976956e-01 2.540547e+01 -4.825849e-02 9.972811e-01 5.569022e-02 -5.695381e+00 9.981830e-01 4.613788e-02 3.875661e-02 1.708574e+02 +3.524163e-02 5.809231e-02 -9.976890e-01 2.458317e+01 -4.977686e-02 9.971720e-01 5.630394e-02 -5.666829e+00 9.981384e-01 4.767758e-02 3.803362e-02 1.708773e+02 +3.543049e-02 5.854111e-02 -9.976560e-01 2.377585e+01 -5.129047e-02 9.970737e-01 5.668543e-02 -5.638788e+00 9.980551e-01 4.916185e-02 3.832941e-02 1.708968e+02 +3.686562e-02 5.810791e-02 -9.976294e-01 2.298624e+01 -5.261516e-02 9.970362e-01 5.612907e-02 -5.610987e+00 9.979342e-01 5.042119e-02 3.981371e-02 1.709164e+02 +3.921312e-02 5.679216e-02 -9.976156e-01 2.220933e+01 -5.394901e-02 9.970476e-01 5.463927e-02 -5.584114e+00 9.977735e-01 5.167780e-02 4.216123e-02 1.709378e+02 +4.211040e-02 5.584768e-02 -9.975509e-01 2.144560e+01 -5.394437e-02 9.971072e-01 5.354566e-02 -5.559904e+00 9.976556e-01 5.155742e-02 4.500126e-02 1.709645e+02 +4.475473e-02 5.500375e-02 -9.974826e-01 2.069094e+01 -5.474365e-02 9.971178e-01 5.252743e-02 -5.536829e+00 9.974970e-01 5.225498e-02 4.763685e-02 1.709942e+02 +4.765837e-02 5.461661e-02 -9.973694e-01 1.994428e+01 -5.387815e-02 9.971909e-01 5.203233e-02 -5.515388e+00 9.974096e-01 5.125663e-02 5.046714e-02 1.710278e+02 +5.043237e-02 5.374455e-02 -9.972803e-01 1.920611e+01 -5.317505e-02 9.972792e-01 5.105544e-02 -5.494749e+00 9.973109e-01 5.045558e-02 5.315303e-02 1.710651e+02 +5.298732e-02 5.342684e-02 -9.971649e-01 1.847268e+01 -5.267936e-02 9.973268e-01 5.063625e-02 -5.472781e+00 9.972047e-01 4.984693e-02 5.566017e-02 1.711029e+02 +5.582100e-02 5.224370e-02 -9.970730e-01 1.774801e+01 -5.240799e-02 9.974067e-01 4.932715e-02 -5.451042e+00 9.970644e-01 4.950109e-02 5.841424e-02 1.711422e+02 +5.813500e-02 5.217133e-02 -9.969446e-01 1.702821e+01 -5.206672e-02 9.974328e-01 4.916072e-02 -5.430247e+00 9.969501e-01 4.904967e-02 6.070215e-02 1.711833e+02 +6.019500e-02 5.333519e-02 -9.967607e-01 1.631412e+01 -5.081970e-02 9.974402e-01 5.030253e-02 -5.408170e+00 9.968922e-01 4.762712e-02 6.275139e-02 1.712284e+02 +6.178304e-02 5.446574e-02 -9.966024e-01 1.560676e+01 -4.972252e-02 9.974381e-01 5.142894e-02 -5.386891e+00 9.968503e-01 4.637615e-02 6.433293e-02 1.712731e+02 +6.293180e-02 5.498065e-02 -9.965022e-01 1.489954e+01 -5.005529e-02 9.973986e-01 5.186900e-02 -5.366543e+00 9.967618e-01 4.661599e-02 6.552016e-02 1.713168e+02 +6.419123e-02 5.448434e-02 -9.964492e-01 1.422320e+01 -4.891363e-02 9.974801e-01 5.138971e-02 -5.347370e+00 9.967382e-01 4.544118e-02 6.669450e-02 1.713599e+02 +6.546924e-02 5.435605e-02 -9.963730e-01 1.354546e+01 -4.877465e-02 9.974960e-01 5.121247e-02 -5.327205e+00 9.966619e-01 4.524490e-02 6.795651e-02 1.714036e+02 +6.668679e-02 5.451153e-02 -9.962838e-01 1.287576e+01 -4.895698e-02 9.974826e-01 5.130017e-02 -5.307366e+00 9.965722e-01 4.535400e-02 6.918763e-02 1.714470e+02 +6.827265e-02 5.516068e-02 -9.961406e-01 1.221623e+01 -4.864904e-02 9.974666e-01 5.189985e-02 -5.289372e+00 9.964799e-01 4.491794e-02 7.078321e-02 1.714921e+02 +6.999007e-02 5.701908e-02 -9.959168e-01 1.156807e+01 -4.823867e-02 9.973905e-01 5.371340e-02 -5.273013e+00 9.963807e-01 4.428229e-02 7.255796e-02 1.715402e+02 +7.214937e-02 5.832535e-02 -9.956870e-01 1.093393e+01 -4.759737e-02 9.973526e-01 5.497394e-02 -5.255371e+00 9.962575e-01 4.342574e-02 7.473451e-02 1.715884e+02 +7.487500e-02 5.830263e-02 -9.954871e-01 1.031366e+01 -4.701719e-02 9.973855e-01 5.487745e-02 -5.238926e+00 9.960839e-01 4.269605e-02 7.742047e-02 1.716384e+02 +7.757817e-02 5.850369e-02 -9.952683e-01 9.709170e+00 -4.708538e-02 9.973779e-01 5.495755e-02 -5.222309e+00 9.958738e-01 4.259908e-02 8.012943e-02 1.716873e+02 +8.073868e-02 5.865069e-02 -9.950082e-01 9.120530e+00 -4.712102e-02 9.973757e-01 5.496668e-02 -5.204828e+00 9.956209e-01 4.244786e-02 8.329048e-02 1.717402e+02 +8.430579e-02 5.853112e-02 -9.947194e-01 8.551464e+00 -4.529484e-02 9.974665e-01 5.485389e-02 -5.188571e+00 9.954100e-01 4.043115e-02 8.674336e-02 1.717957e+02 +8.769143e-02 5.889985e-02 -9.944048e-01 7.998637e+00 -4.342748e-02 9.975274e-01 5.525517e-02 -5.175534e+00 9.952006e-01 3.833909e-02 9.003248e-02 1.718537e+02 +9.172422e-02 6.049456e-02 -9.939452e-01 7.461749e+00 -4.347633e-02 9.974444e-01 5.669542e-02 -5.161644e+00 9.948349e-01 3.801275e-02 9.411989e-02 1.719086e+02 +9.661879e-02 6.137221e-02 -9.934275e-01 6.938515e+00 -4.414769e-02 9.973791e-01 5.732263e-02 -5.148935e+00 9.943419e-01 3.831908e-02 9.907500e-02 1.719658e+02 +1.023099e-01 6.166268e-02 -9.928396e-01 6.432635e+00 -4.377380e-02 9.973891e-01 5.743446e-02 -5.135935e+00 9.937890e-01 3.758425e-02 1.047420e-01 1.720241e+02 +1.089841e-01 6.111423e-02 -9.921630e-01 5.941199e+00 -4.263808e-02 9.974771e-01 5.675800e-02 -5.122506e+00 9.931287e-01 3.611821e-02 1.113149e-01 1.720898e+02 +1.169274e-01 6.057407e-02 -9.912914e-01 5.461638e+00 -4.132223e-02 9.975706e-01 5.608363e-02 -5.108901e+00 9.922805e-01 3.440465e-02 1.191464e-01 1.721564e+02 +1.262524e-01 5.909773e-02 -9.902362e-01 4.995356e+00 -4.064851e-02 9.976936e-01 5.436023e-02 -5.097142e+00 9.911650e-01 3.338851e-02 1.283635e-01 1.722277e+02 +1.368663e-01 5.647881e-02 -9.889781e-01 4.541988e+00 -4.066335e-02 9.978521e-01 5.135813e-02 -5.086635e+00 9.897546e-01 3.318597e-02 1.388690e-01 1.722989e+02 +1.483073e-01 5.463267e-02 -9.874311e-01 4.101101e+00 -4.132657e-02 9.979431e-01 4.900724e-02 -5.078800e+00 9.880775e-01 3.353901e-02 1.502600e-01 1.723765e+02 +1.609493e-01 5.355798e-02 -9.855084e-01 3.674361e+00 -4.047478e-02 9.980447e-01 4.762910e-02 -5.068751e+00 9.861324e-01 3.222236e-02 1.628024e-01 1.724608e+02 +1.741381e-01 5.230879e-02 -9.833309e-01 3.262747e+00 -3.862625e-02 9.981824e-01 4.625852e-02 -5.058377e+00 9.839634e-01 2.992701e-02 1.758420e-01 1.725489e+02 +1.881524e-01 5.069556e-02 -9.808306e-01 2.864576e+00 -3.628761e-02 9.983439e-01 4.463973e-02 -5.050116e+00 9.814693e-01 2.719292e-02 1.896804e-01 1.726439e+02 +2.027713e-01 4.931927e-02 -9.779833e-01 2.475555e+00 -3.600769e-02 9.984309e-01 4.288475e-02 -5.044008e+00 9.785639e-01 2.651912e-02 2.042290e-01 1.727387e+02 +2.188958e-01 4.962084e-02 -9.744857e-01 2.100150e+00 -3.584792e-02 9.984408e-01 4.278824e-02 -5.038510e+00 9.750896e-01 2.556712e-02 2.203333e-01 1.728401e+02 +2.367568e-01 5.087957e-02 -9.702358e-01 1.737145e+00 -3.595746e-02 9.984025e-01 4.358233e-02 -5.033886e+00 9.709034e-01 2.456880e-02 2.382081e-01 1.729439e+02 +2.565280e-01 5.027894e-02 -9.652281e-01 1.394096e+00 -3.388556e-02 9.985000e-01 4.300635e-02 -5.030678e+00 9.659427e-01 2.167496e-02 2.578469e-01 1.730607e+02 +2.778254e-01 4.679540e-02 -9.594911e-01 1.066699e+00 -3.073780e-02 9.987344e-01 3.980907e-02 -5.029479e+00 9.601397e-01 1.843268e-02 2.789121e-01 1.731860e+02 +3.001504e-01 4.201991e-02 -9.529659e-01 7.490336e-01 -2.732319e-02 9.989981e-01 3.544382e-02 -5.026746e+00 9.535005e-01 1.539959e-02 3.009978e-01 1.733127e+02 +3.225095e-01 3.856940e-02 -9.457801e-01 4.352868e-01 -2.543680e-02 9.991618e-01 3.207244e-02 -5.023796e+00 9.462244e-01 1.371396e-02 3.232203e-01 1.734488e+02 +3.459339e-01 3.816217e-02 -9.374825e-01 1.244878e-01 -2.545913e-02 9.991864e-01 3.127948e-02 -5.020538e+00 9.379134e-01 1.304686e-02 3.466240e-01 1.735851e+02 +3.727942e-01 3.920693e-02 -9.270854e-01 -1.940023e-01 -2.427276e-02 9.991771e-01 3.249531e-02 -5.015397e+00 9.275966e-01 1.038886e-02 3.734391e-01 1.737434e+02 +3.990570e-01 4.191117e-02 -9.159678e-01 -4.819953e-01 -2.310408e-02 9.990972e-01 3.564919e-02 -5.010263e+00 9.166350e-01 6.936536e-03 3.996650e-01 1.739051e+02 +4.276772e-01 4.525584e-02 -9.027979e-01 -7.744074e-01 -2.459891e-02 9.989587e-01 3.842314e-02 -5.005880e+00 9.035968e-01 5.775152e-03 4.283451e-01 1.740816e+02 +4.568425e-01 4.567010e-02 -8.883744e-01 -1.056277e+00 -2.419818e-02 9.989496e-01 3.891082e-02 -5.004071e+00 8.892184e-01 3.720932e-03 4.574678e-01 1.742600e+02 +4.863599e-01 4.409116e-02 -8.726454e-01 -1.324858e+00 -2.227971e-02 9.990271e-01 3.805935e-02 -5.006267e+00 8.734745e-01 9.317462e-04 4.868691e-01 1.744569e+02 +5.169949e-01 4.155228e-02 -8.549794e-01 -1.580990e+00 -2.092947e-02 9.991361e-01 3.590258e-02 -5.013190e+00 8.557326e-01 -6.671821e-04 5.174179e-01 1.746662e+02 +5.483961e-01 3.838887e-02 -8.353370e-01 -1.827053e+00 -2.038283e-02 9.992625e-01 3.254100e-02 -5.016426e+00 8.359703e-01 -8.188259e-04 5.487742e-01 1.748661e+02 +5.800242e-01 3.440062e-02 -8.138726e-01 -2.065394e+00 -2.135248e-02 9.994066e-01 2.702545e-02 -5.020977e+00 8.143194e-01 1.702786e-03 5.804146e-01 1.750917e+02 +6.118833e-01 2.898209e-02 -7.904169e-01 -2.298974e+00 -2.230108e-02 9.995633e-01 1.938696e-02 -5.020260e+00 7.906336e-01 5.764602e-03 6.122624e-01 1.753083e+02 +6.438658e-01 2.625421e-02 -7.646879e-01 -2.533159e+00 -2.636547e-02 9.995789e-01 1.211912e-02 -5.021905e+00 7.646841e-01 1.235827e-02 6.442869e-01 1.755567e+02 +6.750462e-01 2.340756e-02 -7.374040e-01 -2.762100e+00 -2.682441e-02 9.996144e-01 7.174931e-03 -5.019984e+00 7.372877e-01 1.493702e-02 6.754138e-01 1.758085e+02 +7.059129e-01 2.010396e-02 -7.080132e-01 -2.984000e+00 -2.313954e-02 9.997181e-01 5.315989e-03 -5.021561e+00 7.079206e-01 1.263048e-02 7.061792e-01 1.761020e+02 +7.359936e-01 1.679065e-02 -6.767802e-01 -3.197645e+00 -1.723848e-02 9.998330e-01 6.058743e-03 -5.027380e+00 6.767690e-01 7.207467e-03 7.361602e-01 1.764144e+02 +7.651932e-01 1.636950e-02 -6.435925e-01 -3.408457e+00 -1.525951e-02 9.998570e-01 7.288299e-03 -5.035163e+00 6.436198e-01 4.243949e-03 7.653336e-01 1.767201e+02 +7.931081e-01 1.697889e-02 -6.088441e-01 -3.613633e+00 -1.572486e-02 9.998490e-01 7.398971e-03 -5.041623e+00 6.088778e-01 3.705804e-03 7.932554e-01 1.770559e+02 +8.196019e-01 1.628017e-02 -5.727021e-01 -3.809310e+00 -1.536331e-02 9.998612e-01 6.436351e-03 -5.049114e+00 5.727275e-01 3.523358e-03 8.197383e-01 1.773923e+02 +8.445118e-01 1.511006e-02 -5.353238e-01 -3.994755e+00 -1.420518e-02 9.998822e-01 5.813003e-03 -5.059470e+00 5.353486e-01 2.695225e-03 8.446269e-01 1.777639e+02 +8.674333e-01 1.406022e-02 -4.973548e-01 -4.172515e+00 -1.394673e-02 9.998949e-01 3.942639e-03 -5.069239e+00 4.973580e-01 3.516497e-03 8.675383e-01 1.781345e+02 +8.879012e-01 1.304774e-02 -4.598491e-01 -4.341951e+00 -1.514047e-02 9.998850e-01 -8.633173e-04 -5.077813e+00 4.597850e-01 7.728871e-03 8.879967e-01 1.785380e+02 +9.069298e-01 1.303923e-02 -4.210800e-01 -4.506015e+00 -1.670855e-02 9.998477e-01 -5.025739e-03 -5.085500e+00 4.209504e-01 1.159363e-02 9.070096e-01 1.789515e+02 +9.238324e-01 1.559732e-02 -3.824794e-01 -4.658887e+00 -1.961452e-02 9.997858e-01 -6.605700e-03 -5.093131e+00 3.822944e-01 1.360471e-02 9.239404e-01 1.793984e+02 +9.390440e-01 1.898508e-02 -3.432725e-01 -4.802666e+00 -2.273743e-02 9.997176e-01 -6.909158e-03 -5.103184e+00 3.430444e-01 1.429314e-02 9.392104e-01 1.798726e+02 +9.531963e-01 2.100738e-02 -3.016216e-01 -4.930925e+00 -2.425866e-02 9.996809e-01 -7.037227e-03 -5.118399e+00 3.013775e-01 1.402479e-02 9.534018e-01 1.803670e+02 +9.653074e-01 2.050261e-02 -2.603099e-01 -5.037119e+00 -2.301586e-02 9.997132e-01 -6.610011e-03 -5.132442e+00 2.600997e-01 1.237195e-02 9.655025e-01 1.808790e+02 +9.753302e-01 2.255942e-02 -2.195953e-01 -5.132379e+00 -2.448329e-02 9.996819e-01 -6.043104e-03 -5.148414e+00 2.193892e-01 1.127044e-02 9.755723e-01 1.813966e+02 +9.833107e-01 2.330433e-02 -1.804356e-01 -5.212692e+00 -2.545109e-02 9.996300e-01 -9.591319e-03 -5.159578e+00 1.801454e-01 1.402353e-02 9.835400e-01 1.819529e+02 +9.892527e-01 2.280164e-02 -1.444271e-01 -5.273350e+00 -2.534147e-02 9.995544e-01 -1.577010e-02 -5.167765e+00 1.440031e-01 1.926061e-02 9.893898e-01 1.825240e+02 +9.935798e-01 2.054114e-02 -1.112533e-01 -5.319340e+00 -2.258486e-02 9.995980e-01 -1.714083e-02 -5.180870e+00 1.108565e-01 1.954342e-02 9.936443e-01 1.831051e+02 +9.964030e-01 1.871693e-02 -8.264782e-02 -5.351521e+00 -2.021265e-02 9.996460e-01 -1.729789e-02 -5.198453e+00 8.229481e-02 1.890620e-02 9.964287e-01 1.837146e+02 +9.981732e-01 1.614988e-02 -5.821879e-02 -5.374392e+00 -1.725040e-02 9.996809e-01 -1.845024e-02 -5.217370e+00 5.790225e-02 1.942083e-02 9.981333e-01 1.843315e+02 +9.991252e-01 1.173249e-02 -4.013878e-02 -5.386215e+00 -1.251382e-02 9.997360e-01 -1.927011e-02 -5.239606e+00 3.990209e-02 1.975554e-02 9.990083e-01 1.849722e+02 +9.995994e-01 8.430127e-03 -2.701699e-02 -5.392321e+00 -8.964415e-03 9.997654e-01 -1.971619e-02 -5.261747e+00 2.684444e-02 1.995048e-02 9.994405e-01 1.856255e+02 +9.998640e-01 6.271695e-03 -1.525371e-02 -5.394182e+00 -6.570313e-03 9.997862e-01 -1.960594e-02 -5.283043e+00 1.512749e-02 1.970349e-02 9.996914e-01 1.862935e+02 +9.999733e-01 3.881571e-03 -6.199658e-03 -5.392487e+00 -3.997804e-03 9.998144e-01 -1.884706e-02 -5.306439e+00 6.125352e-03 1.887134e-02 9.998032e-01 1.869806e+02 +9.999992e-01 1.204301e-03 -3.079879e-04 -5.387940e+00 -1.209419e-03 9.998514e-01 -1.719764e-02 -5.330977e+00 2.872314e-04 1.719800e-02 9.998521e-01 1.876829e+02 +9.999950e-01 -1.059369e-03 2.990562e-03 -5.380740e+00 1.109956e-03 9.998554e-01 -1.696481e-02 -5.355984e+00 -2.972157e-03 1.696804e-02 9.998516e-01 1.884002e+02 +9.999821e-01 -4.759329e-03 3.632076e-03 -5.373899e+00 4.822227e-03 9.998350e-01 -1.750921e-02 -5.378798e+00 -3.548145e-03 1.752641e-02 9.998401e-01 1.891282e+02 +9.999739e-01 -6.753497e-03 2.557785e-03 -5.372151e+00 6.796866e-03 9.998265e-01 -1.734416e-02 -5.400566e+00 -2.440207e-03 1.736109e-02 9.998463e-01 1.898719e+02 +9.999816e-01 -6.054259e-03 3.093587e-04 -5.376082e+00 6.058572e-03 9.998430e-01 -1.664754e-02 -5.423205e+00 -2.085212e-04 1.664910e-02 9.998614e-01 1.906327e+02 +9.999850e-01 -4.794839e-03 -2.667404e-03 -5.383511e+00 4.752790e-03 9.998677e-01 -1.555358e-02 -5.448214e+00 2.741628e-03 1.554067e-02 9.998755e-01 1.914074e+02 +9.999568e-01 -7.272713e-03 -5.796759e-03 -5.386586e+00 7.178335e-03 9.998440e-01 -1.613937e-02 -5.475289e+00 5.913233e-03 1.609706e-02 9.998530e-01 1.921934e+02 +9.999173e-01 -9.407388e-03 -8.768298e-03 -5.388556e+00 9.240851e-03 9.997797e-01 -1.884405e-02 -5.503892e+00 8.943641e-03 1.876146e-02 9.997840e-01 1.929838e+02 +9.999075e-01 -8.183848e-03 -1.086111e-02 -5.397395e+00 7.948261e-03 9.997359e-01 -2.155975e-02 -5.530975e+00 1.103469e-02 2.147143e-02 9.997086e-01 1.937820e+02 +9.998986e-01 -6.621636e-03 -1.260828e-02 -5.406023e+00 6.335015e-03 9.997236e-01 -2.263872e-02 -5.557396e+00 1.275470e-02 2.255654e-02 9.996642e-01 1.945852e+02 +9.998738e-01 -7.069049e-03 -1.422653e-02 -5.414875e+00 6.795976e-03 9.997935e-01 -1.915242e-02 -5.584706e+00 1.435899e-02 1.905332e-02 9.997154e-01 1.953954e+02 +9.998662e-01 -6.933941e-03 -1.481947e-02 -5.425124e+00 6.734354e-03 9.998865e-01 -1.347575e-02 -5.615779e+00 1.491123e-02 1.337415e-02 9.997994e-01 1.962071e+02 +9.998681e-01 -4.756510e-03 -1.553228e-02 -5.440439e+00 4.594362e-03 9.999347e-01 -1.045854e-02 -5.644544e+00 1.558102e-02 1.038580e-02 9.998247e-01 1.970176e+02 +9.998676e-01 -3.513851e-03 -1.588671e-02 -5.450700e+00 3.341933e-03 9.999357e-01 -1.083522e-02 -5.671587e+00 1.592376e-02 1.078069e-02 9.998151e-01 1.978279e+02 +9.998657e-01 -7.525534e-04 -1.637318e-02 -5.463791e+00 5.378513e-04 9.999138e-01 -1.311350e-02 -5.697731e+00 1.638164e-02 1.310293e-02 9.997800e-01 1.986388e+02 +9.998562e-01 1.107699e-03 -1.692076e-02 -5.475977e+00 -1.357370e-03 9.998903e-01 -1.475090e-02 -5.721685e+00 1.690257e-02 1.477175e-02 9.997480e-01 1.994565e+02 +9.998435e-01 2.434521e-03 -1.752467e-02 -5.489710e+00 -2.691777e-03 9.998887e-01 -1.467106e-02 -5.746165e+00 1.748700e-02 1.471593e-02 9.997388e-01 2.002799e+02 +9.998362e-01 2.231574e-03 -1.796355e-02 -5.502826e+00 -2.461515e-03 9.999152e-01 -1.278849e-02 -5.772032e+00 1.793349e-02 1.283061e-02 9.997569e-01 2.011081e+02 +9.998298e-01 1.612409e-03 -1.838033e-02 -5.514842e+00 -1.820111e-03 9.999346e-01 -1.128905e-02 -5.797070e+00 1.836093e-02 1.132058e-02 9.997673e-01 2.019342e+02 +9.998040e-01 1.540550e-03 -1.973770e-02 -5.530315e+00 -1.750155e-03 9.999422e-01 -1.060663e-02 -5.821917e+00 1.972022e-02 1.063910e-02 9.997489e-01 2.027596e+02 +9.997665e-01 1.211167e-03 -2.157669e-02 -5.546064e+00 -1.414409e-03 9.999547e-01 -9.406703e-03 -5.847719e+00 2.156432e-02 9.435023e-03 9.997230e-01 2.035844e+02 +9.997258e-01 -7.497970e-04 -2.340625e-02 -5.560062e+00 5.578209e-04 9.999661e-01 -8.207378e-03 -5.875323e+00 2.341162e-02 8.192070e-03 9.996924e-01 2.044067e+02 +9.996831e-01 -1.729434e-03 -2.511272e-02 -5.574640e+00 1.568256e-03 9.999780e-01 -6.436466e-03 -5.904682e+00 2.512330e-02 6.395043e-03 9.996639e-01 2.052297e+02 +9.996473e-01 -1.397277e-03 -2.651990e-02 -5.595924e+00 1.287144e-03 9.999905e-01 -4.169471e-03 -5.931834e+00 2.652547e-02 4.133865e-03 9.996396e-01 2.060488e+02 +9.995962e-01 -1.251767e-03 -2.838667e-02 -5.616804e+00 1.158281e-03 9.999938e-01 -3.309499e-03 -5.960396e+00 2.839064e-02 3.275283e-03 9.995915e-01 2.068636e+02 +9.995341e-01 -2.577919e-03 -3.041298e-02 -5.638403e+00 2.461743e-03 9.999895e-01 -3.856798e-03 -5.984917e+00 3.042261e-02 3.780133e-03 9.995300e-01 2.076764e+02 +9.994773e-01 -3.004838e-03 -3.218924e-02 -5.663364e+00 2.900528e-03 9.999904e-01 -3.286756e-03 -6.010137e+00 3.219881e-02 3.191672e-03 9.994764e-01 2.084877e+02 +9.994259e-01 -1.886876e-03 -3.382741e-02 -5.692115e+00 1.788130e-03 9.999940e-01 -2.949148e-03 -6.032806e+00 3.383278e-02 2.886968e-03 9.994233e-01 2.092941e+02 +9.993857e-01 -2.258554e-03 -3.497271e-02 -5.719704e+00 2.098839e-03 9.999872e-01 -4.602896e-03 -6.058511e+00 3.498266e-02 4.526667e-03 9.993777e-01 2.100950e+02 +9.993329e-01 -2.313309e-03 -3.644815e-02 -5.746621e+00 2.022964e-03 9.999659e-01 -8.000854e-03 -6.085702e+00 3.646542e-02 7.921782e-03 9.993035e-01 2.108881e+02 +9.993183e-01 -1.518766e-03 -3.688692e-02 -5.775682e+00 1.151910e-03 9.999497e-01 -9.964643e-03 -6.110646e+00 3.690020e-02 9.915359e-03 9.992698e-01 2.116782e+02 +9.993235e-01 9.648325e-05 -3.677582e-02 -5.807043e+00 -4.056208e-04 9.999646e-01 -8.398633e-03 -6.136861e+00 3.677371e-02 8.407868e-03 9.992883e-01 2.124599e+02 +9.993372e-01 1.575280e-03 -3.637026e-02 -5.836098e+00 -1.729393e-03 9.999896e-01 -4.206233e-03 -6.163417e+00 3.636326e-02 4.266343e-03 9.993295e-01 2.132324e+02 +9.993654e-01 5.140906e-04 -3.561767e-02 -5.860771e+00 -6.054338e-04 9.999965e-01 -2.553805e-03 -6.187611e+00 3.561624e-02 2.573749e-03 9.993622e-01 2.139901e+02 +9.993757e-01 -4.287961e-04 -3.532795e-02 -5.885490e+00 3.312989e-04 9.999961e-01 -2.765587e-03 -6.210951e+00 3.532900e-02 2.752156e-03 9.993720e-01 2.147321e+02 +9.993775e-01 1.054298e-03 -3.526259e-02 -5.912330e+00 -1.213851e-03 9.999891e-01 -4.503614e-03 -6.234236e+00 3.525746e-02 4.543614e-03 9.993679e-01 2.154543e+02 +9.993550e-01 2.339040e-03 -3.583582e-02 -5.940900e+00 -2.587183e-03 9.999730e-01 -6.879616e-03 -6.258073e+00 3.581876e-02 6.967892e-03 9.993340e-01 2.161593e+02 +9.992983e-01 3.559158e-03 -3.728601e-02 -5.970022e+00 -3.836434e-03 9.999655e-01 -7.367539e-03 -6.279269e+00 3.725851e-02 7.505414e-03 9.992775e-01 2.168473e+02 +9.992477e-01 3.192129e-03 -3.864985e-02 -5.996305e+00 -3.426945e-03 9.999760e-01 -6.010719e-03 -6.299130e+00 3.862974e-02 6.138648e-03 9.992347e-01 2.175160e+02 +9.991684e-01 2.778936e-03 -4.067947e-02 -6.023283e+00 -2.961530e-03 9.999858e-01 -4.429027e-03 -6.319943e+00 4.066659e-02 4.545817e-03 9.991624e-01 2.181694e+02 +9.990597e-01 3.726701e-03 -4.319524e-02 -6.053756e+00 -3.735056e-03 9.999930e-01 -1.126907e-04 -6.341411e+00 4.319452e-02 2.739222e-04 9.990667e-01 2.188036e+02 +9.989175e-01 3.294398e-03 -4.640034e-02 -6.084272e+00 -3.386144e-03 9.999924e-01 -1.898801e-03 -6.361896e+00 4.639374e-02 2.053864e-03 9.989211e-01 2.194120e+02 +9.987749e-01 3.221400e-03 -4.937899e-02 -6.114588e+00 -3.414353e-03 9.999868e-01 -3.823739e-03 -6.382430e+00 4.936603e-02 3.987652e-03 9.987728e-01 2.200006e+02 +9.986301e-01 2.657253e-03 -5.225863e-02 -6.145730e+00 -2.871338e-03 9.999878e-01 -4.021980e-03 -6.399955e+00 5.224731e-02 4.166522e-03 9.986255e-01 2.205667e+02 +9.984705e-01 3.049348e-03 -5.520395e-02 -6.178103e+00 -3.291518e-03 9.999853e-01 -4.296436e-03 -6.417342e+00 5.519004e-02 4.471569e-03 9.984659e-01 2.211145e+02 +9.983342e-01 2.712696e-03 -5.763223e-02 -6.209081e+00 -2.962519e-03 9.999866e-01 -4.249765e-03 -6.433514e+00 5.761993e-02 4.413422e-03 9.983288e-01 2.216411e+02 +9.982741e-01 3.146344e-03 -5.864252e-02 -6.239666e+00 -3.403201e-03 9.999850e-01 -4.280670e-03 -6.450142e+00 5.862818e-02 4.472854e-03 9.982699e-01 2.221470e+02 +9.983637e-01 4.164692e-03 -5.703133e-02 -6.267700e+00 -4.391932e-03 9.999829e-01 -3.859697e-03 -6.466547e+00 5.701428e-02 4.103859e-03 9.983649e-01 2.226311e+02 +9.985621e-01 4.805887e-03 -5.339142e-02 -6.290085e+00 -5.031177e-03 9.999790e-01 -4.085962e-03 -6.480811e+00 5.337067e-02 4.348709e-03 9.985653e-01 2.230947e+02 +9.988733e-01 5.715830e-03 -4.711204e-02 -6.308435e+00 -5.916812e-03 9.999740e-01 -4.127670e-03 -6.492847e+00 4.708723e-02 4.401772e-03 9.988811e-01 2.235450e+02 +9.992492e-01 6.108434e-03 -3.825765e-02 -6.319855e+00 -6.305379e-03 9.999674e-01 -5.029281e-03 -6.503769e+00 3.822568e-02 5.266734e-03 9.992553e-01 2.239880e+02 +9.996261e-01 7.222803e-03 -2.637389e-02 -6.323739e+00 -7.378092e-03 9.999560e-01 -5.795380e-03 -6.516463e+00 2.633087e-02 5.987801e-03 9.996354e-01 2.244270e+02 +9.999002e-01 9.405535e-03 -1.054559e-02 -6.319417e+00 -9.470762e-03 9.999362e-01 -6.152322e-03 -6.533002e+00 1.048705e-02 6.251582e-03 9.999255e-01 2.248666e+02 +9.999251e-01 9.737424e-03 7.416027e-03 -6.304389e+00 -9.692387e-03 9.999345e-01 -6.085106e-03 -6.549425e+00 -7.474794e-03 6.012771e-03 9.999540e-01 2.252989e+02 +9.995929e-01 7.713466e-03 2.746768e-02 -6.274326e+00 -7.533312e-03 9.999494e-01 -6.656274e-03 -6.565498e+00 -2.751763e-02 6.446641e-03 9.996005e-01 2.257323e+02 +9.987205e-01 7.694413e-03 4.998102e-02 -6.236169e+00 -7.204369e-03 9.999242e-01 -9.977390e-03 -6.583319e+00 -5.005401e-02 9.604542e-03 9.987003e-01 2.261516e+02 +9.970770e-01 9.919845e-03 7.575654e-02 -6.190860e+00 -8.813711e-03 9.998498e-01 -1.492160e-02 -6.600756e+00 -7.589318e-02 1.421028e-02 9.970147e-01 2.265688e+02 +9.943564e-01 1.196295e-02 1.054144e-01 -6.132258e+00 -1.005446e-02 9.997761e-01 -1.861749e-02 -6.618486e+00 -1.056136e-01 1.745254e-02 9.942541e-01 2.269850e+02 +9.903613e-01 1.159904e-02 1.380216e-01 -6.055339e+00 -8.825498e-03 9.997470e-01 -2.069007e-02 -6.633282e+00 -1.382267e-01 1.927253e-02 9.902131e-01 2.273826e+02 +9.848996e-01 9.735628e-03 1.728527e-01 -5.959133e+00 -6.268523e-03 9.997683e-01 -2.059273e-02 -6.650140e+00 -1.730132e-01 1.919823e-02 9.847324e-01 2.277868e+02 +9.778350e-01 4.975564e-03 2.093179e-01 -5.842543e+00 -7.181557e-04 9.997914e-01 -2.041053e-02 -6.664783e+00 -2.093758e-01 1.980781e-02 9.776346e-01 2.281672e+02 +9.690343e-01 -2.293725e-03 2.469157e-01 -5.705406e+00 7.302014e-03 9.997857e-01 -1.936964e-02 -6.678846e+00 -2.468184e-01 2.057282e-02 9.688434e-01 2.285521e+02 +9.585253e-01 -8.380910e-03 2.848843e-01 -5.557346e+00 1.436855e-02 9.997175e-01 -1.893426e-02 -6.689134e+00 -2.846452e-01 2.224234e-02 9.583749e-01 2.289096e+02 +9.461325e-01 -1.580062e-02 3.233939e-01 -5.392446e+00 2.217590e-02 9.996254e-01 -1.603816e-02 -6.706019e+00 -3.230194e-01 2.234577e-02 9.461285e-01 2.292783e+02 +9.317321e-01 -2.044521e-02 3.625703e-01 -5.215271e+00 2.695410e-02 9.995534e-01 -1.290208e-02 -6.722386e+00 -3.621446e-01 2.179404e-02 9.318671e-01 2.296207e+02 +9.151334e-01 -1.980153e-02 4.026646e-01 -5.034004e+00 2.717180e-02 9.995514e-01 -1.259901e-02 -6.739810e+00 -4.022344e-01 2.247089e-02 9.152609e-01 2.299627e+02 +8.962972e-01 -1.590963e-02 4.431684e-01 -4.842747e+00 2.487939e-02 9.995862e-01 -1.443308e-02 -6.754313e+00 -4.427555e-01 2.396208e-02 8.963222e-01 2.302757e+02 +8.751766e-01 -9.686530e-03 4.837066e-01 -4.639218e+00 2.138561e-02 9.995968e-01 -1.867570e-02 -6.765090e+00 -4.833307e-01 2.668890e-02 8.750309e-01 2.305991e+02 +8.514087e-01 -7.020569e-03 5.244559e-01 -4.412698e+00 2.367511e-02 9.994056e-01 -2.505606e-02 -6.769151e+00 -5.239683e-01 3.374949e-02 8.510689e-01 2.309131e+02 +8.258672e-01 -8.221376e-03 5.638047e-01 -4.162700e+00 2.904803e-02 9.991863e-01 -2.797977e-02 -6.774005e+00 -5.631160e-01 3.948498e-02 8.254340e-01 2.311927e+02 +7.981035e-01 -1.126572e-02 6.024150e-01 -3.894204e+00 3.645269e-02 9.988965e-01 -2.961368e-02 -6.779934e+00 -6.014167e-01 4.559442e-02 7.976335e-01 2.314860e+02 +7.682926e-01 -9.167882e-03 6.400332e-01 -3.617048e+00 3.947514e-02 9.986728e-01 -3.308069e-02 -6.788129e+00 -6.388805e-01 5.068104e-02 7.676348e-01 2.317428e+02 +7.345317e-01 4.667377e-04 6.785743e-01 -3.339169e+00 3.108228e-02 9.989270e-01 -3.433250e-02 -6.795933e+00 -6.778622e-01 4.630993e-02 7.337290e-01 2.320322e+02 +6.984955e-01 1.258017e-02 7.155038e-01 -3.051125e+00 1.408269e-02 9.994102e-01 -3.131982e-02 -6.818114e+00 -7.154759e-01 3.195297e-02 6.979064e-01 2.322922e+02 +6.625626e-01 1.694674e-02 7.488148e-01 -2.738112e+00 6.632107e-03 9.995721e-01 -2.848993e-02 -6.839842e+00 -7.489772e-01 2.384257e-02 6.621666e-01 2.325583e+02 +6.239315e-01 1.438844e-02 7.813466e-01 -2.397566e+00 1.138131e-02 9.995571e-01 -2.749514e-02 -6.858248e+00 -7.813962e-01 2.604782e-02 6.234914e-01 2.327950e+02 +5.829205e-01 1.340639e-02 8.124186e-01 -2.039294e+00 2.108744e-02 9.992774e-01 -3.162041e-02 -6.866185e+00 -8.122555e-01 3.556401e-02 5.822166e-01 2.329743e+02 +5.398147e-01 1.429386e-02 8.416625e-01 -1.663556e+00 2.833651e-02 9.989806e-01 -3.513969e-02 -6.872959e+00 -8.413068e-01 4.281869e-02 5.388594e-01 2.331743e+02 +4.939656e-01 1.987853e-02 8.692542e-01 -1.278517e+00 2.408659e-02 9.990421e-01 -3.653413e-02 -6.884328e+00 -8.691478e-01 3.898397e-02 4.930136e-01 2.333450e+02 +4.470718e-01 2.738507e-02 8.940788e-01 -8.747580e-01 1.358667e-02 9.992080e-01 -3.739895e-02 -6.899401e+00 -8.943949e-01 2.886756e-02 4.463456e-01 2.335417e+02 +3.989222e-01 2.734975e-02 9.165768e-01 -4.359517e-01 5.899116e-03 9.994579e-01 -3.239032e-02 -6.921993e+00 -9.169658e-01 1.832821e-02 3.985446e-01 2.337034e+02 +3.541510e-01 2.417983e-02 9.348756e-01 2.398074e-03 2.934527e-03 9.996320e-01 -2.696638e-02 -6.948447e+00 -9.351837e-01 1.229358e-02 3.539498e-01 2.338494e+02 +3.099683e-01 2.152458e-02 9.505032e-01 4.703487e-01 5.845726e-03 9.996816e-01 -2.454460e-02 -6.970534e+00 -9.507289e-01 1.316443e-02 3.097438e-01 2.339807e+02 +2.695044e-01 2.329231e-02 9.627174e-01 9.528231e-01 1.069455e-02 9.995734e-01 -2.717786e-02 -6.986025e+00 -9.629398e-01 1.762038e-02 2.691403e-01 2.340717e+02 +2.323884e-01 2.503989e-02 9.723007e-01 1.451824e+00 1.651327e-02 9.994229e-01 -2.968520e-02 -6.997554e+00 -9.724829e-01 2.295436e-02 2.318408e-01 2.341673e+02 +1.985050e-01 2.814951e-02 9.796955e-01 1.968174e+00 1.730718e-02 9.993309e-01 -3.222046e-02 -7.010695e+00 -9.799471e-01 2.335169e-02 1.978850e-01 2.342460e+02 +1.692025e-01 2.765065e-02 9.851933e-01 2.504059e+00 1.758485e-02 9.993625e-01 -3.106846e-02 -7.027529e+00 -9.854244e-01 2.258133e-02 1.686084e-01 2.343265e+02 +1.421873e-01 2.179806e-02 9.895997e-01 3.063341e+00 1.872301e-02 9.995194e-01 -2.470673e-02 -7.050404e+00 -9.896627e-01 2.204126e-02 1.417109e-01 2.343947e+02 +1.158573e-01 1.914685e-02 9.930813e-01 3.633148e+00 1.575043e-02 9.996530e-01 -2.111107e-02 -7.071477e+00 -9.931410e-01 1.808732e-02 1.155155e-01 2.344468e+02 +8.958020e-02 1.800668e-02 9.958168e-01 4.219494e+00 1.562049e-02 9.996882e-01 -1.948186e-02 -7.090984e+00 -9.958571e-01 1.730033e-02 8.927099e-02 2.344924e+02 +6.563363e-02 2.004910e-02 9.976423e-01 4.818404e+00 1.136514e-02 9.997182e-01 -2.083852e-02 -7.109578e+00 -9.977791e-01 1.270605e-02 6.538727e-02 2.345217e+02 +4.419906e-02 2.301062e-02 9.987577e-01 5.432449e+00 1.520433e-02 9.996034e-01 -2.370297e-02 -7.126868e+00 -9.989071e-01 1.623309e-02 4.383167e-02 2.345364e+02 +2.421135e-02 2.362745e-02 9.994276e-01 6.068743e+00 2.122245e-02 9.994832e-01 -2.414289e-02 -7.144350e+00 -9.994816e-01 2.179483e-02 2.369740e-02 2.345358e+02 +5.946476e-03 2.161416e-02 9.997487e-01 6.718857e+00 2.284085e-02 9.995026e-01 -2.174470e-02 -7.163757e+00 -9.997215e-01 2.296441e-02 5.449831e-03 2.345295e+02 +-1.019614e-02 1.738479e-02 9.997969e-01 7.389986e+00 2.132028e-02 9.996253e-01 -1.716439e-02 -7.187767e+00 -9.997207e-01 2.114094e-02 -1.056297e-02 2.345223e+02 +-2.499359e-02 1.391890e-02 9.995907e-01 8.074205e+00 1.858722e-02 9.997367e-01 -1.345619e-02 -7.215715e+00 -9.995148e-01 1.824329e-02 -2.524572e-02 2.345065e+02 +-3.558532e-02 1.235990e-02 9.992902e-01 8.771869e+00 2.061880e-02 9.997197e-01 -1.163097e-02 -7.240419e+00 -9.991540e-01 2.019027e-02 -3.583019e-02 2.344769e+02 +-4.263985e-02 1.519762e-02 9.989749e-01 9.482224e+00 2.590498e-02 9.995649e-01 -1.410088e-02 -7.257341e+00 -9.987546e-01 2.527716e-02 -4.301499e-02 2.344371e+02 +-4.731971e-02 1.762077e-02 9.987243e-01 1.020631e+01 3.197400e-02 9.993587e-01 -1.611704e-02 -7.273022e+00 -9.983680e-01 3.117055e-02 -4.785277e-02 2.343929e+02 +-5.073158e-02 1.613994e-02 9.985819e-01 1.095005e+01 3.262043e-02 9.993627e-01 -1.449533e-02 -7.292063e+00 -9.981795e-01 3.183879e-02 -5.122574e-02 2.343535e+02 +-5.331793e-02 1.209160e-02 9.985044e-01 1.171401e+01 2.966212e-02 9.995046e-01 -1.051983e-02 -7.311668e+00 -9.981370e-01 2.905686e-02 -5.365018e-02 2.343193e+02 +-5.482371e-02 1.179747e-02 9.984263e-01 1.249258e+01 2.955924e-02 9.995111e-01 -1.018719e-02 -7.328580e+00 -9.980585e-01 2.895422e-02 -5.514563e-02 2.342816e+02 +-5.557469e-02 1.203357e-02 9.983820e-01 1.328369e+01 2.857944e-02 9.995368e-01 -1.045663e-02 -7.344725e+00 -9.980455e-01 2.795207e-02 -5.589287e-02 2.342426e+02 +-5.693097e-02 1.173637e-02 9.983091e-01 1.407990e+01 3.080050e-02 9.994756e-01 -9.993618e-03 -7.360661e+00 -9.979029e-01 3.017947e-02 -5.726260e-02 2.341974e+02 +-5.716337e-02 8.209780e-03 9.983311e-01 1.488697e+01 3.247495e-02 9.994523e-01 -6.359525e-03 -7.375631e+00 -9.978366e-01 3.205722e-02 -5.739868e-02 2.341568e+02 +-5.562187e-02 4.874672e-03 9.984400e-01 1.569818e+01 3.418244e-02 9.994112e-01 -2.975156e-03 -7.394681e+00 -9.978666e-01 3.396362e-02 -5.575575e-02 2.341141e+02 +-5.219978e-02 4.086526e-03 9.986283e-01 1.650141e+01 3.456220e-02 9.993999e-01 -2.283071e-03 -7.411421e+00 -9.980384e-01 3.439560e-02 -5.230970e-02 2.340796e+02 +-4.844880e-02 5.933848e-03 9.988080e-01 1.730472e+01 3.595923e-02 9.993444e-01 -4.192779e-03 -7.426529e+00 -9.981782e-01 3.571322e-02 -4.863041e-02 2.340441e+02 +-4.487461e-02 7.065474e-03 9.989676e-01 1.810984e+01 3.706315e-02 9.992983e-01 -5.402904e-03 -7.441340e+00 -9.983049e-01 3.678243e-02 -4.510499e-02 2.340112e+02 +-4.181571e-02 5.961244e-03 9.991075e-01 1.891815e+01 3.756988e-02 9.992843e-01 -4.389890e-03 -7.456706e+00 -9.984188e-01 3.735278e-02 -4.200975e-02 2.339809e+02 +-3.840414e-02 4.714784e-03 9.992512e-01 1.972619e+01 3.660650e-02 9.993243e-01 -3.308239e-03 -7.473759e+00 -9.985916e-01 3.645203e-02 -3.855078e-02 2.339563e+02 +-3.506421e-02 4.273576e-03 9.993759e-01 2.053893e+01 3.655845e-02 9.993270e-01 -2.990678e-03 -7.495794e+00 -9.987162e-01 3.643076e-02 -3.519685e-02 2.339370e+02 +-3.182745e-02 7.446965e-03 9.994656e-01 2.135033e+01 3.624649e-02 9.993230e-01 -6.291658e-03 -7.515353e+00 -9.988360e-01 3.602686e-02 -3.207583e-02 2.339198e+02 +-2.906579e-02 1.065204e-02 9.995207e-01 2.216683e+01 3.454583e-02 9.993565e-01 -9.645714e-03 -7.536610e+00 -9.989804e-01 3.424890e-02 -2.941507e-02 2.339078e+02 +-2.670246e-02 9.548447e-03 9.995978e-01 2.300035e+01 3.315758e-02 9.994126e-01 -8.660938e-03 -7.557271e+00 -9.990934e-01 3.291297e-02 -2.700339e-02 2.338961e+02 +-2.471834e-02 5.542178e-03 9.996791e-01 2.381188e+01 2.849220e-02 9.995823e-01 -4.837140e-03 -7.581613e+00 -9.992884e-01 2.836348e-02 -2.486592e-02 2.338935e+02 +-2.286889e-02 3.820065e-03 9.997312e-01 2.463455e+01 2.522832e-02 9.996764e-01 -3.242762e-03 -7.606651e+00 -9.994201e-01 2.514737e-02 -2.295786e-02 2.338935e+02 +-2.102783e-02 4.746191e-03 9.997676e-01 2.545451e+01 2.281354e-02 9.997306e-01 -4.266189e-03 -7.630553e+00 -9.995186e-01 2.271852e-02 -2.113044e-02 2.338957e+02 +-1.965604e-02 7.482003e-03 9.997788e-01 2.627665e+01 2.080155e-02 9.997586e-01 -7.072890e-03 -7.652572e+00 -9.995904e-01 2.065792e-02 -1.980694e-02 2.338929e+02 +-1.888952e-02 7.960594e-03 9.997899e-01 2.710127e+01 1.979172e-02 9.997753e-01 -7.586549e-03 -7.676497e+00 -9.996257e-01 1.964425e-02 -1.904284e-02 2.338931e+02 +-1.843748e-02 7.820395e-03 9.997994e-01 2.792772e+01 1.890730e-02 9.997933e-01 -7.471680e-03 -7.699905e+00 -9.996513e-01 1.876574e-02 -1.858153e-02 2.338893e+02 +-1.840914e-02 5.999397e-03 9.998125e-01 2.875467e+01 1.846378e-02 9.998135e-01 -5.659442e-03 -7.724217e+00 -9.996601e-01 1.835613e-02 -1.851648e-02 2.338876e+02 +-1.866305e-02 4.869763e-03 9.998140e-01 2.958258e+01 1.946827e-02 9.998003e-01 -4.506296e-03 -7.746246e+00 -9.996363e-01 1.938054e-02 -1.875413e-02 2.338801e+02 +-1.897752e-02 4.590858e-03 9.998094e-01 3.040790e+01 1.999865e-02 9.997911e-01 -4.211182e-03 -7.769147e+00 -9.996199e-01 1.991491e-02 -1.906537e-02 2.338720e+02 +-1.952091e-02 4.617156e-03 9.997988e-01 3.123452e+01 2.014428e-02 9.997881e-01 -4.223798e-03 -7.791107e+00 -9.996065e-01 2.005777e-02 -1.960979e-02 2.338629e+02 +-2.012350e-02 4.646293e-03 9.997867e-01 3.205872e+01 1.912472e-02 9.998080e-01 -4.261458e-03 -7.814556e+00 -9.996146e-01 1.903488e-02 -2.020850e-02 2.338600e+02 +-2.094960e-02 4.015235e-03 9.997725e-01 3.288214e+01 1.753227e-02 9.998396e-01 -3.648131e-03 -7.838979e+00 -9.996268e-01 1.745185e-02 -2.101664e-02 2.338536e+02 +-2.267060e-02 3.712942e-03 9.997361e-01 3.370381e+01 1.434620e-02 9.998913e-01 -3.388200e-03 -7.865063e+00 -9.996401e-01 1.426560e-02 -2.272141e-02 2.338490e+02 +-2.509875e-02 3.249237e-03 9.996797e-01 3.452269e+01 1.123365e-02 9.999325e-01 -2.968022e-03 -7.886547e+00 -9.996219e-01 1.115555e-02 -2.513355e-02 2.338418e+02 +-2.737750e-02 3.149077e-03 9.996202e-01 3.533850e+01 1.101351e-02 9.999353e-01 -2.848437e-03 -7.906483e+00 -9.995645e-01 1.093134e-02 -2.741041e-02 2.338290e+02 +-2.911193e-02 1.121462e-03 9.995755e-01 3.615344e+01 8.342005e-03 9.999648e-01 -8.789474e-04 -7.926435e+00 -9.995414e-01 8.312872e-03 -2.912026e-02 2.338183e+02 +-3.137564e-02 -2.686326e-03 9.995040e-01 3.696860e+01 6.137281e-03 9.999770e-01 2.880251e-03 -7.943983e+00 -9.994889e-01 6.224603e-03 -3.135844e-02 2.338051e+02 +-3.300818e-02 -6.835498e-03 9.994317e-01 3.777952e+01 4.242899e-03 9.999666e-01 6.979285e-03 -7.960457e+00 -9.994461e-01 4.470858e-03 -3.297807e-02 2.337905e+02 +-3.405891e-02 -7.765861e-03 9.993896e-01 3.858529e+01 4.184896e-03 9.999599e-01 7.912911e-03 -7.975262e+00 -9.994111e-01 4.451844e-03 -3.402505e-02 2.337716e+02 +-3.478255e-02 -4.933663e-03 9.993827e-01 3.938380e+01 5.879459e-03 9.999695e-01 5.141186e-03 -7.989265e+00 -9.993776e-01 6.054650e-03 -3.475248e-02 2.337509e+02 +-3.472437e-02 -4.254351e-04 9.993968e-01 4.017940e+01 7.265240e-03 9.999734e-01 6.781101e-04 -8.002997e+00 -9.993706e-01 7.284402e-03 -3.472035e-02 2.337275e+02 +-3.475871e-02 2.624533e-03 9.993923e-01 4.097136e+01 8.062994e-03 9.999647e-01 -2.345610e-03 -8.016094e+00 -9.993632e-01 7.976560e-03 -3.477865e-02 2.337072e+02 +-3.461962e-02 3.533732e-03 9.993943e-01 4.176276e+01 9.101295e-03 9.999534e-01 -3.220439e-03 -8.032476e+00 -9.993592e-01 8.984289e-03 -3.465017e-02 2.336841e+02 +-3.507683e-02 3.113238e-03 9.993798e-01 4.255230e+01 9.421422e-03 9.999517e-01 -2.784345e-03 -8.051914e+00 -9.993402e-01 9.317909e-03 -3.510447e-02 2.336624e+02 +-3.650033e-02 3.085961e-03 9.993289e-01 4.333725e+01 7.033552e-03 9.999712e-01 -2.831050e-03 -8.071871e+00 -9.993089e-01 6.925494e-03 -3.652098e-02 2.336432e+02 +-3.789971e-02 2.178566e-03 9.992792e-01 4.412374e+01 5.503761e-03 9.999829e-01 -1.971363e-03 -8.089941e+00 -9.992664e-01 5.425076e-03 -3.791105e-02 2.336220e+02 +-3.922051e-02 -3.472849e-04 9.992305e-01 4.490784e+01 5.528209e-03 9.999845e-01 5.645296e-04 -8.106085e+00 -9.992153e-01 5.546093e-03 -3.921799e-02 2.335956e+02 +-4.113239e-02 -3.229853e-03 9.991485e-01 4.568975e+01 4.681533e-03 9.999832e-01 3.425275e-03 -8.121634e+00 -9.991428e-01 4.818434e-03 -4.111658e-02 2.335712e+02 +-4.282268e-02 -3.637060e-03 9.990761e-01 4.645838e+01 3.053179e-03 9.999882e-01 3.771244e-03 -8.138474e+00 -9.990781e-01 3.211850e-03 -4.281108e-02 2.335470e+02 +-4.369602e-02 -2.052301e-03 9.990427e-01 4.722694e+01 2.747073e-03 9.999938e-01 2.174403e-03 -8.156788e+00 -9.990411e-01 2.839454e-03 -4.369012e-02 2.335206e+02 +-4.374438e-02 -1.063387e-04 9.990427e-01 4.799397e+01 4.259850e-03 9.999909e-01 2.929590e-04 -8.171387e+00 -9.990337e-01 4.268585e-03 -4.374353e-02 2.334904e+02 +-4.337364e-02 5.219146e-04 9.990588e-01 4.875855e+01 5.510897e-03 9.999847e-01 -2.831492e-04 -8.185292e+00 -9.990438e-01 5.493426e-03 -4.337586e-02 2.334615e+02 +-4.305998e-02 -1.446482e-03 9.990714e-01 4.952284e+01 6.127629e-03 9.999797e-01 1.711894e-03 -8.200392e+00 -9.990537e-01 6.195650e-03 -4.305025e-02 2.334346e+02 +-4.221467e-02 -3.668174e-03 9.991018e-01 5.028441e+01 4.639059e-03 9.999817e-01 3.867414e-03 -8.215913e+00 -9.990978e-01 4.798151e-03 -4.219688e-02 2.334114e+02 +-4.184736e-02 -5.304669e-03 9.991099e-01 5.104523e+01 2.399971e-03 9.999825e-01 5.409821e-03 -8.230410e+00 -9.991212e-01 2.624219e-03 -4.183390e-02 2.333900e+02 +-4.117135e-02 -6.926194e-03 9.991281e-01 5.180314e+01 1.390749e-04 9.999759e-01 6.937800e-03 -8.242981e+00 -9.991521e-01 4.245902e-04 -4.116939e-02 2.333702e+02 +-4.093814e-02 -6.354799e-03 9.991415e-01 5.255700e+01 2.329477e-03 9.999764e-01 6.455554e-03 -8.256877e+00 -9.991590e-01 2.591752e-03 -4.092238e-02 2.333458e+02 +-4.098513e-02 -4.764507e-03 9.991484e-01 5.330415e+01 2.505695e-03 9.999850e-01 4.871278e-03 -8.270946e+00 -9.991566e-01 2.703208e-03 -4.097257e-02 2.333232e+02 +-4.125394e-02 -1.149348e-03 9.991480e-01 5.404995e+01 -7.141005e-04 9.999991e-01 1.120839e-03 -8.287043e+00 -9.991485e-01 -6.672549e-04 -4.125473e-02 2.333065e+02 +-4.218901e-02 -1.208645e-03 9.991089e-01 5.479568e+01 -1.819187e-04 9.999992e-01 1.202037e-03 -8.300063e+00 -9.991097e-01 -1.310458e-04 -4.218920e-02 2.332829e+02 +-4.181931e-02 -4.940942e-03 9.991130e-01 5.555026e+01 3.507281e-03 9.999809e-01 5.092034e-03 -8.313353e+00 -9.991191e-01 3.717113e-03 -4.180118e-02 2.332521e+02 +-4.209890e-02 -4.380737e-03 9.991038e-01 5.628059e+01 3.570136e-03 9.999833e-01 4.535025e-03 -8.333448e+00 -9.991071e-01 3.757854e-03 -4.208256e-02 2.332265e+02 +-4.332336e-02 1.412766e-03 9.990601e-01 5.700822e+01 -3.911855e-04 9.999989e-01 -1.431060e-03 -8.356835e+00 -9.990611e-01 -4.528181e-04 -4.332277e-02 2.332101e+02 +-4.201463e-02 1.458477e-02 9.990105e-01 5.772320e+01 2.619593e-03 9.998916e-01 -1.448747e-02 -8.374695e+00 -9.991136e-01 2.008313e-03 -4.204829e-02 2.331815e+02 +-4.092549e-02 2.304770e-02 9.988963e-01 5.844558e+01 9.246933e-03 9.996998e-01 -2.268739e-02 -8.393154e+00 -9.991194e-01 8.308231e-03 -4.112633e-02 2.331479e+02 +-4.031672e-02 1.799011e-02 9.990250e-01 5.917375e+01 1.007023e-02 9.997944e-01 -1.759758e-02 -8.417118e+00 -9.991362e-01 9.350930e-03 -4.048960e-02 2.331230e+02 +-3.897424e-02 1.089824e-02 9.991808e-01 5.990016e+01 7.323981e-03 9.999168e-01 -1.062060e-02 -8.446187e+00 -9.992134e-01 6.904048e-03 -3.905082e-02 2.331051e+02 +-3.682983e-02 6.030319e-03 9.993033e-01 6.061997e+01 6.819557e-03 9.999600e-01 -5.782948e-03 -8.472225e+00 -9.992983e-01 6.601818e-03 -3.686948e-02 2.330867e+02 +-3.456610e-02 3.341035e-03 9.993968e-01 6.133366e+01 7.265927e-03 9.999688e-01 -3.091646e-03 -8.492901e+00 -9.993760e-01 7.154675e-03 -3.458930e-02 2.330660e+02 +-3.284083e-02 4.228014e-03 9.994516e-01 6.204381e+01 8.694569e-03 9.999544e-01 -3.944452e-03 -8.508656e+00 -9.994228e-01 8.560258e-03 -3.287609e-02 2.330459e+02 +-3.223228e-02 2.166832e-03 9.994780e-01 6.275048e+01 3.006781e-03 9.999933e-01 -2.070988e-03 -8.529158e+00 -9.994759e-01 2.938456e-03 -3.223858e-02 2.330375e+02 +-3.255792e-02 1.899272e-03 9.994680e-01 6.345444e+01 -2.740876e-03 9.999942e-01 -1.989561e-03 -8.550909e+00 -9.994661e-01 -2.804195e-03 -3.255253e-02 2.330304e+02 +-3.326082e-02 3.087109e-03 9.994419e-01 6.415215e+01 -4.861042e-03 9.999829e-01 -3.250557e-03 -8.569264e+00 -9.994349e-01 -4.966446e-03 -3.324524e-02 2.330168e+02 +-3.436509e-02 4.339766e-03 9.993999e-01 6.484629e+01 -5.077220e-03 9.999769e-01 -4.516859e-03 -8.585121e+00 -9.993965e-01 -5.229397e-03 -3.434226e-02 2.329980e+02 +-3.601904e-02 3.729812e-03 9.993441e-01 6.553951e+01 -6.595968e-03 9.999703e-01 -3.969890e-03 -8.602196e+00 -9.993294e-01 -6.734634e-03 -3.599337e-02 2.329801e+02 +-3.754280e-02 2.894307e-03 9.992908e-01 6.622642e+01 -7.900669e-03 9.999637e-01 -3.193083e-03 -8.623042e+00 -9.992638e-01 -8.014944e-03 -3.751857e-02 2.329604e+02 +-3.875001e-02 1.470126e-03 9.992478e-01 6.690794e+01 -5.934652e-03 9.999809e-01 -1.701350e-03 -8.643205e+00 -9.992313e-01 -5.996117e-03 -3.874055e-02 2.329343e+02 +-3.998073e-02 9.585825e-04 9.992000e-01 6.758526e+01 -3.847767e-03 9.999920e-01 -1.113306e-03 -8.661826e+00 -9.991931e-01 -3.889201e-03 -3.997672e-02 2.329080e+02 +-4.076697e-02 6.998023e-04 9.991684e-01 6.825907e+01 -3.421588e-03 9.999938e-01 -8.399880e-04 -8.679047e+00 -9.991629e-01 -3.452988e-03 -4.076433e-02 2.328857e+02 +-4.032050e-02 -9.469451e-04 9.991863e-01 6.892746e+01 -5.503522e-03 9.999846e-01 7.256127e-04 -8.698405e+00 -9.991717e-01 -5.469788e-03 -4.032509e-02 2.328669e+02 +-3.916459e-02 1.753057e-04 9.992327e-01 6.958553e+01 -6.155117e-03 9.999809e-01 -4.166883e-04 -8.717003e+00 -9.992138e-01 -6.166715e-03 -3.916277e-02 2.328486e+02 +-3.818047e-02 2.310323e-03 9.992682e-01 7.023807e+01 -7.410553e-03 9.999691e-01 -2.595093e-03 -8.735734e+00 -9.992434e-01 -7.504212e-03 -3.816217e-02 2.328315e+02 +-3.767457e-02 4.790516e-03 9.992786e-01 7.088774e+01 -8.554095e-03 9.999503e-01 -5.116246e-03 -8.754378e+00 -9.992535e-01 -8.740677e-03 -3.763172e-02 2.328149e+02 +-3.729143e-02 6.807008e-03 9.992812e-01 7.153628e+01 -7.893643e-03 9.999436e-01 -7.106102e-03 -8.773914e+00 -9.992733e-01 -8.152967e-03 -3.723560e-02 2.327959e+02 +-3.695688e-02 7.476490e-03 9.992889e-01 7.218216e+01 -6.639654e-03 9.999481e-01 -7.726982e-03 -8.792420e+00 -9.992948e-01 -6.920498e-03 -3.690532e-02 2.327771e+02 +-3.666985e-02 6.354584e-03 9.993072e-01 7.282575e+01 -7.283406e-03 9.999515e-01 -6.625952e-03 -8.810303e+00 -9.993009e-01 -7.521334e-03 -3.662179e-02 2.327583e+02 +-3.649896e-02 4.454759e-03 9.993237e-01 7.346820e+01 -1.021781e-02 9.999361e-01 -4.830686e-03 -8.829783e+00 -9.992815e-01 -1.038721e-02 -3.645112e-02 2.327460e+02 +-3.666118e-02 3.431551e-03 9.993218e-01 7.410352e+01 -1.052285e-02 9.999373e-01 -3.819711e-03 -8.848198e+00 -9.992724e-01 -1.065575e-02 -3.662277e-02 2.327265e+02 +-3.729919e-02 2.207241e-03 9.993017e-01 7.473793e+01 -7.881240e-03 9.999658e-01 -2.502881e-03 -8.865707e+00 -9.992731e-01 -7.969093e-03 -3.728053e-02 2.326990e+02 +-3.951987e-02 2.372875e-03 9.992160e-01 7.536658e+01 -4.746085e-03 9.999854e-01 -2.562418e-03 -8.882142e+00 -9.992075e-01 -4.843632e-03 -3.950804e-02 2.326701e+02 +-4.266662e-02 2.094509e-03 9.990872e-01 7.599352e+01 -6.480500e-03 9.999762e-01 -2.373131e-03 -8.898239e+00 -9.990684e-01 -6.575839e-03 -4.265203e-02 2.326467e+02 +-4.570610e-02 1.055254e-03 9.989544e-01 7.661837e+01 -8.487487e-03 9.999629e-01 -1.444659e-03 -8.915326e+00 -9.989189e-01 -8.544642e-03 -4.569545e-02 2.326222e+02 +-4.772390e-02 -9.212337e-05 9.988605e-01 7.723931e+01 -9.193602e-03 9.999577e-01 -3.470341e-04 -8.932340e+00 -9.988183e-01 -9.199689e-03 -4.772273e-02 2.325912e+02 +-5.083635e-02 2.080344e-03 9.987048e-01 7.786175e+01 -5.229920e-03 9.999835e-01 -2.349227e-03 -8.949571e+00 -9.986933e-01 -5.342574e-03 -5.082464e-02 2.325529e+02 +-5.593615e-02 5.553875e-03 9.984189e-01 7.848781e+01 -4.408803e-03 9.999734e-01 -5.809529e-03 -8.967541e+00 -9.984246e-01 -4.726796e-03 -5.591018e-02 2.325132e+02 +-6.277273e-02 8.808304e-03 9.979890e-01 7.912104e+01 -5.260056e-03 9.999442e-01 -9.156420e-03 -8.984140e+00 -9.980140e-01 -5.824252e-03 -6.272290e-02 2.324728e+02 +-6.913062e-02 1.037532e-02 9.975536e-01 7.976355e+01 -7.468608e-03 9.999125e-01 -1.091743e-02 -8.999635e+00 -9.975797e-01 -8.205067e-03 -6.904708e-02 2.324266e+02 +-7.420279e-02 1.018691e-02 9.971911e-01 8.041542e+01 -8.841432e-03 9.999018e-01 -1.087251e-02 -9.017553e+00 -9.972040e-01 -9.623369e-03 -7.410544e-02 2.323765e+02 +-7.946204e-02 8.410530e-03 9.968024e-01 8.107854e+01 -7.517007e-03 9.999309e-01 -9.036165e-03 -9.038271e+00 -9.968096e-01 -8.211004e-03 -7.939333e-02 2.323187e+02 +-8.559686e-02 8.945825e-03 9.962897e-01 8.174583e+01 -5.101080e-03 9.999426e-01 -9.416894e-03 -9.058866e+00 -9.963168e-01 -5.888210e-03 -8.554632e-02 2.322541e+02 +-9.161605e-02 1.048782e-02 9.957392e-01 8.242306e+01 -4.298566e-03 9.999310e-01 -1.092748e-02 -9.077863e+00 -9.957852e-01 -5.281384e-03 -9.156465e-02 2.321877e+02 +-9.761804e-02 8.977368e-03 9.951834e-01 8.311157e+01 -7.126142e-03 9.999274e-01 -9.719175e-03 -9.094322e+00 -9.951985e-01 -8.040586e-03 -9.754698e-02 2.321232e+02 +-1.036850e-01 6.464582e-03 9.945892e-01 8.381265e+01 -8.269881e-03 9.999387e-01 -7.361484e-03 -9.110651e+00 -9.945758e-01 -8.988410e-03 -1.036251e-01 2.320523e+02 +-1.084863e-01 3.945084e-03 9.940901e-01 8.452437e+01 -6.415483e-03 9.999685e-01 -4.668547e-03 -9.131071e+00 -9.940773e-01 -6.884042e-03 -1.084576e-01 2.319697e+02 +-1.138401e-01 3.259548e-03 9.934937e-01 8.524313e+01 -3.241357e-03 9.999881e-01 -3.652273e-03 -9.151732e+00 -9.934938e-01 -3.636044e-03 -1.138282e-01 2.318821e+02 +-1.198343e-01 7.097867e-03 9.927685e-01 8.596960e+01 -3.634233e-03 9.999646e-01 -7.587999e-03 -9.169400e+00 -9.927873e-01 -4.517255e-03 -1.198042e-01 2.317951e+02 +-1.250637e-01 1.078915e-02 9.920900e-01 8.670912e+01 -9.102972e-04 9.999392e-01 -1.098927e-02 -9.185711e+00 -9.921483e-01 -2.277458e-03 -1.250463e-01 2.316996e+02 +-1.292015e-01 1.264000e-02 9.915378e-01 8.746635e+01 1.166412e-03 9.999200e-01 -1.259488e-02 -9.205175e+00 -9.916177e-01 -4.707373e-04 -1.292059e-01 2.315979e+02 +-1.337579e-01 1.135575e-02 9.909490e-01 8.823768e+01 3.543556e-03 9.999334e-01 -1.098040e-02 -9.224469e+00 -9.910077e-01 2.042764e-03 -1.337893e-01 2.314913e+02 +-1.378633e-01 8.609634e-03 9.904138e-01 8.902413e+01 4.808010e-03 9.999562e-01 -8.023327e-03 -9.243456e+00 -9.904396e-01 3.655795e-03 -1.378986e-01 2.313804e+02 +-1.409821e-01 5.537585e-03 9.899966e-01 8.982554e+01 6.951358e-03 9.999652e-01 -4.603430e-03 -9.260364e+00 -9.899878e-01 6.232816e-03 -1.410157e-01 2.312641e+02 +-1.430513e-01 2.919271e-03 9.897110e-01 9.063846e+01 9.705499e-03 9.999517e-01 -1.546664e-03 -9.276414e+00 -9.896677e-01 9.384383e-03 -1.430727e-01 2.311442e+02 +-1.443116e-01 1.059615e-03 9.895317e-01 9.146784e+01 1.177095e-02 9.999305e-01 6.458992e-04 -9.287228e+00 -9.894623e-01 1.174093e-02 -1.443140e-01 2.310212e+02 +-1.448436e-01 1.727039e-03 9.894530e-01 9.230825e+01 1.322910e-02 9.999124e-01 1.912766e-04 -9.296007e+00 -9.893662e-01 1.311727e-02 -1.448538e-01 2.308986e+02 +-1.445945e-01 3.433885e-03 9.894850e-01 9.317072e+01 1.458455e-02 9.998927e-01 -1.338753e-03 -9.305704e+00 -9.893835e-01 1.423761e-02 -1.446291e-01 2.307753e+02 +-1.440332e-01 6.772587e-03 9.895497e-01 9.402458e+01 1.840738e-02 9.998219e-01 -4.163623e-03 -9.317283e+00 -9.894017e-01 1.761531e-02 -1.441322e-01 2.306492e+02 +-1.427025e-01 9.837388e-03 9.897167e-01 9.490089e+01 2.207342e-02 9.997335e-01 -6.754297e-03 -9.331083e+00 -9.895195e-01 2.088257e-02 -1.428816e-01 2.305196e+02 +-1.412419e-01 8.292963e-03 9.899404e-01 9.579771e+01 2.625057e-02 9.996447e-01 -4.628906e-03 -9.347969e+00 -9.896271e-01 2.533270e-02 -1.414094e-01 2.303902e+02 +-1.380868e-01 8.474364e-03 9.903839e-01 9.670430e+01 3.149618e-02 9.994952e-01 -4.160898e-03 -9.366932e+00 -9.899192e-01 3.061874e-02 -1.382840e-01 2.302580e+02 +-1.339354e-01 7.300073e-03 9.909632e-01 9.762407e+01 3.372804e-02 9.994271e-01 -2.803854e-03 -9.385303e+00 -9.904160e-01 3.304770e-02 -1.341049e-01 2.301321e+02 +-1.293188e-01 7.361107e-03 9.915757e-01 9.855625e+01 3.810591e-02 9.992707e-01 -2.448559e-03 -9.401196e+00 -9.908707e-01 3.746825e-02 -1.295050e-01 2.300076e+02 +-1.242514e-01 4.529151e-03 9.922404e-01 9.950026e+01 3.823302e-02 9.992688e-01 2.264175e-04 -9.418213e+00 -9.915139e-01 3.796448e-02 -1.243337e-01 2.298901e+02 +-1.197067e-01 4.770042e-03 9.927978e-01 1.004553e+02 3.810689e-02 9.992736e-01 -2.064188e-04 -9.438641e+00 -9.920777e-01 3.780771e-02 -1.198015e-01 2.297784e+02 +-1.148310e-01 6.928139e-03 9.933609e-01 1.014183e+02 3.721841e-02 9.993036e-01 -2.667200e-03 -9.459846e+00 -9.926876e-01 3.666503e-02 -1.150089e-01 2.296734e+02 +-1.094995e-01 7.361847e-03 9.939596e-01 1.023908e+02 3.870145e-02 9.992459e-01 -3.137462e-03 -9.479255e+00 -9.932332e-01 3.812412e-02 -1.097019e-01 2.295693e+02 +-1.044507e-01 5.094370e-03 9.945170e-01 1.033774e+02 3.925374e-02 9.992288e-01 -9.958260e-04 -9.498730e+00 -9.937551e-01 3.893449e-02 -1.045701e-01 2.294684e+02 +-9.962372e-02 3.279232e-03 9.950198e-01 1.043691e+02 3.706142e-02 9.993129e-01 4.172918e-04 -9.519498e+00 -9.943348e-01 3.691841e-02 -9.967680e-02 2.293758e+02 +-9.612528e-02 8.725084e-03 9.953310e-01 1.053585e+02 3.672910e-02 9.993116e-01 -5.212827e-03 -9.541908e+00 -9.946914e-01 3.605652e-02 -9.637958e-02 2.292851e+02 +-9.379883e-02 1.672981e-02 9.954506e-01 1.063476e+02 3.646666e-02 9.992456e-01 -1.335743e-02 -9.567125e+00 -9.949231e-01 3.504784e-02 -9.433815e-02 2.291934e+02 +-9.252587e-02 2.011209e-02 9.955071e-01 1.073411e+02 3.634357e-02 9.991980e-01 -1.680877e-02 -9.597529e+00 -9.950468e-01 3.462503e-02 -9.318261e-02 2.291046e+02 +-9.125092e-02 1.628833e-02 9.956947e-01 1.083449e+02 3.766226e-02 9.992073e-01 -1.289422e-02 -9.627979e+00 -9.951155e-01 3.632349e-02 -9.179205e-02 2.290131e+02 +-8.995892e-02 1.050218e-02 9.958901e-01 1.093502e+02 3.872597e-02 9.992250e-01 -7.039232e-03 -9.658610e+00 -9.951923e-01 3.793356e-02 -9.029592e-02 2.289209e+02 +-8.890276e-02 6.316409e-03 9.960203e-01 1.103582e+02 4.256526e-02 9.990904e-01 -2.536595e-03 -9.680900e+00 -9.951304e-01 4.217034e-02 -8.909076e-02 2.288255e+02 +-8.790119e-02 4.358736e-03 9.961196e-01 1.113632e+02 4.307801e-02 9.990715e-01 -5.702992e-04 -9.702182e+00 -9.951973e-01 4.286071e-02 -8.800734e-02 2.287349e+02 +-8.737969e-02 1.508968e-03 9.961739e-01 1.123674e+02 4.250254e-02 9.990939e-01 2.214728e-03 -9.722311e+00 -9.952680e-01 4.253344e-02 -8.736465e-02 2.286496e+02 +-8.652747e-02 2.070692e-03 9.962473e-01 1.133663e+02 4.199139e-02 9.991167e-01 1.570435e-03 -9.744343e+00 -9.953641e-01 4.196969e-02 -8.653799e-02 2.285643e+02 +-8.543239e-02 5.714662e-03 9.963276e-01 1.143732e+02 4.252757e-02 9.990931e-01 -2.083906e-03 -9.766560e+00 -9.954360e-01 4.219334e-02 -8.559794e-02 2.284776e+02 +-8.441906e-02 8.454301e-03 9.963945e-01 1.153718e+02 4.191627e-02 9.991090e-01 -4.926003e-03 -9.790871e+00 -9.955483e-01 4.134928e-02 -8.469822e-02 2.283939e+02 +-8.344511e-02 7.908014e-03 9.964810e-01 1.163595e+02 4.241745e-02 9.990904e-01 -4.376699e-03 -9.815331e+00 -9.956092e-01 4.190296e-02 -8.370465e-02 2.283111e+02 +-8.230024e-02 5.805802e-03 9.965907e-01 1.173600e+02 4.209976e-02 9.991106e-01 -2.343814e-03 -9.839630e+00 -9.957180e-01 4.176332e-02 -8.247148e-02 2.282294e+02 +-8.065774e-02 7.021810e-03 9.967171e-01 1.183545e+02 4.016329e-02 9.991859e-01 -3.789058e-03 -9.866258e+00 -9.959324e-01 3.972581e-02 -8.087410e-02 2.281529e+02 +-7.873163e-02 1.074468e-02 9.968379e-01 1.193481e+02 3.951913e-02 9.991895e-01 -7.648763e-03 -9.895039e+00 -9.961123e-01 3.879195e-02 -7.909244e-02 2.280769e+02 +-7.617908e-02 1.187984e-02 9.970234e-01 1.203394e+02 3.995875e-02 9.991621e-01 -8.852222e-03 -9.921926e+00 -9.962932e-01 3.916545e-02 -7.658996e-02 2.280013e+02 +-7.380519e-02 8.500908e-03 9.972364e-01 1.213310e+02 3.899497e-02 9.992235e-01 -5.631846e-03 -9.952263e+00 -9.965100e-01 3.847153e-02 -7.407937e-02 2.279304e+02 +-7.098914e-02 3.462669e-03 9.974711e-01 1.223225e+02 3.767310e-02 9.992898e-01 -7.878253e-04 -9.981524e+00 -9.967654e-01 3.752189e-02 -7.106918e-02 2.278627e+02 +-6.810392e-02 1.546646e-03 9.976770e-01 1.233094e+02 3.739879e-02 9.992999e-01 1.003769e-03 -1.000839e+01 -9.969771e-01 3.738027e-02 -6.811408e-02 2.277969e+02 +-6.556643e-02 2.516881e-03 9.978450e-01 1.242889e+02 3.765749e-02 9.992907e-01 -4.613181e-05 -1.003651e+01 -9.971374e-01 3.757331e-02 -6.561471e-02 2.277341e+02 +-6.345894e-02 2.862451e-03 9.979803e-01 1.252664e+02 3.480613e-02 9.993938e-01 -6.532801e-04 -1.006533e+01 -9.973773e-01 3.469437e-02 -6.352010e-02 2.276775e+02 +-6.197934e-02 1.553349e-03 9.980762e-01 1.262412e+02 3.146680e-02 9.995047e-01 3.984746e-04 -1.008969e+01 -9.975813e-01 3.143096e-02 -6.199752e-02 2.276231e+02 +-6.029257e-02 -1.735153e-03 9.981792e-01 1.272171e+02 2.545965e-02 9.996705e-01 3.275570e-03 -1.011480e+01 -9.978560e-01 2.561078e-02 -6.022852e-02 2.275743e+02 +-5.952081e-02 -3.120677e-03 9.982222e-01 1.281919e+02 2.023235e-02 9.997859e-01 4.331953e-03 -1.013924e+01 -9.980220e-01 2.045422e-02 -5.944493e-02 2.275274e+02 +-5.975680e-02 -1.370499e-03 9.982120e-01 1.291516e+02 1.913284e-02 9.998138e-01 2.518059e-03 -1.015923e+01 -9.980296e-01 1.924909e-02 -5.971945e-02 2.274775e+02 +-6.025686e-02 2.749259e-03 9.981791e-01 1.301103e+02 1.837293e-02 9.998298e-01 -1.644695e-03 -1.018069e+01 -9.980138e-01 1.824036e-02 -6.029712e-02 2.274262e+02 +-6.047745e-02 5.645852e-03 9.981536e-01 1.310641e+02 1.637532e-02 9.998550e-01 -4.663311e-03 -1.020427e+01 -9.980353e-01 1.606306e-02 -6.056113e-02 2.273755e+02 +-6.035500e-02 9.979127e-03 9.981271e-01 1.320126e+02 1.757244e-02 9.998057e-01 -8.933340e-03 -1.022966e+01 -9.980223e-01 1.700035e-02 -6.051863e-02 2.273189e+02 +-6.033335e-02 1.044954e-02 9.981236e-01 1.329615e+02 1.985643e-02 9.997599e-01 -9.266417e-03 -1.025553e+01 -9.979808e-01 1.926009e-02 -6.052636e-02 2.272603e+02 +-6.132929e-02 6.755258e-03 9.980947e-01 1.339101e+02 1.859530e-02 9.998112e-01 -5.624267e-03 -1.028445e+01 -9.979444e-01 1.821494e-02 -6.144333e-02 2.272067e+02 +-6.281870e-02 2.519633e-03 9.980218e-01 1.348544e+02 1.634037e-02 9.998653e-01 -1.495776e-03 -1.031177e+01 -9.978912e-01 1.621408e-02 -6.285141e-02 2.271547e+02 +-6.452497e-02 8.372498e-04 9.979157e-01 1.357962e+02 1.503531e-02 9.998869e-01 1.332717e-04 -1.033504e+01 -9.978029e-01 1.501257e-02 -6.453026e-02 2.270991e+02 +-6.692908e-02 1.001239e-03 9.977572e-01 1.367249e+02 1.233586e-02 9.999239e-01 -1.759330e-04 -1.035734e+01 -9.976815e-01 1.229641e-02 -6.693634e-02 2.270431e+02 +-7.022700e-02 1.127710e-03 9.975304e-01 1.376583e+02 9.917745e-03 9.999507e-01 -4.322319e-04 -1.038023e+01 -9.974818e-01 9.862894e-03 -7.023473e-02 2.269841e+02 +-7.408221e-02 3.253345e-04 9.972521e-01 1.385896e+02 9.146019e-03 9.999581e-01 3.532032e-04 -1.040365e+01 -9.972102e-01 9.147048e-03 -7.408209e-02 2.269194e+02 +-7.822093e-02 -3.513016e-04 9.969360e-01 1.395167e+02 8.502354e-03 9.999633e-01 1.019471e-03 -1.042594e+01 -9.968998e-01 8.556043e-03 -7.821508e-02 2.268515e+02 +-8.254961e-02 -3.502554e-04 9.965869e-01 1.404416e+02 7.026403e-03 9.999749e-01 9.334558e-04 -1.044654e+01 -9.965622e-01 7.079475e-03 -8.254508e-02 2.267807e+02 +-8.653361e-02 -5.716766e-04 9.962488e-01 1.413630e+02 6.149779e-03 9.999805e-01 1.107981e-03 -1.046923e+01 -9.962300e-01 6.222584e-03 -8.652841e-02 2.267033e+02 +-9.048954e-02 2.393773e-03 9.958945e-01 1.422853e+02 3.877552e-03 9.999904e-01 -2.051298e-03 -1.049189e+01 -9.958899e-01 3.676009e-03 -9.049796e-02 2.266240e+02 +-9.550733e-02 3.613998e-03 9.954222e-01 1.432093e+02 6.382112e-03 9.999751e-01 -3.018191e-03 -1.051060e+01 -9.954083e-01 6.064633e-03 -9.552802e-02 2.265354e+02 +-1.010635e-01 4.024431e-03 9.948718e-01 1.441328e+02 6.709572e-03 9.999718e-01 -3.363477e-03 -1.053087e+01 -9.948574e-01 6.335236e-03 -1.010877e-01 2.264414e+02 +-1.086870e-01 2.339011e-03 9.940733e-01 1.450560e+02 4.982844e-03 9.999859e-01 -1.808129e-03 -1.055141e+01 -9.940636e-01 4.756789e-03 -1.086971e-01 2.263459e+02 +-1.167711e-01 2.192708e-03 9.931564e-01 1.459774e+02 6.384690e-03 9.999785e-01 -1.457089e-03 -1.056725e+01 -9.931384e-01 6.170847e-03 -1.167826e-01 2.262383e+02 +-1.255390e-01 -1.143552e-03 9.920880e-01 1.469019e+02 5.647805e-03 9.999823e-01 1.867323e-03 -1.058219e+01 -9.920726e-01 5.837538e-03 -1.255304e-01 2.261230e+02 +-1.349414e-01 -3.571686e-03 9.908471e-01 1.478255e+02 7.005015e-03 9.999650e-01 4.558549e-03 -1.059738e+01 -9.908288e-01 7.556033e-03 -1.349117e-01 2.259958e+02 +-1.439673e-01 -4.695814e-03 9.895713e-01 1.487460e+02 5.434883e-03 9.999699e-01 5.535847e-03 -1.061100e+01 -9.895676e-01 6.175183e-03 -1.439375e-01 2.258626e+02 +-1.533494e-01 -4.419221e-03 9.881621e-01 1.496645e+02 5.238523e-03 9.999723e-01 5.284983e-03 -1.062270e+01 -9.881582e-01 5.986956e-03 -1.533220e-01 2.257211e+02 +-1.622481e-01 -4.941499e-03 9.867376e-01 1.505869e+02 5.786273e-03 9.999655e-01 5.959169e-03 -1.063323e+01 -9.867331e-01 6.676394e-03 -1.622139e-01 2.255676e+02 +-1.717698e-01 -4.779615e-03 9.851255e-01 1.515186e+02 7.826022e-03 9.999500e-01 6.216109e-03 -1.064535e+01 -9.851061e-01 8.777351e-03 -1.717238e-01 2.254025e+02 +-1.813011e-01 -2.603815e-03 9.834242e-01 1.524257e+02 9.687043e-03 9.999432e-01 4.433423e-03 -1.066009e+01 -9.833800e-01 1.033025e-02 -1.812655e-01 2.252314e+02 +-1.916981e-01 -7.517766e-04 9.814536e-01 1.533451e+02 1.024169e-02 9.999437e-01 2.766348e-03 -1.067316e+01 -9.814005e-01 1.058204e-02 -1.916796e-01 2.250522e+02 +-2.023395e-01 -7.009710e-04 9.793152e-01 1.542658e+02 1.253151e-02 9.999160e-01 3.304889e-03 -1.068772e+01 -9.792353e-01 1.294101e-02 -2.023137e-01 2.248589e+02 +-2.129368e-01 -2.203256e-03 9.770635e-01 1.551864e+02 1.624361e-02 9.998512e-01 5.794698e-03 -1.070466e+01 -9.769310e-01 1.710494e-02 -2.128693e-01 2.246507e+02 +-2.231721e-01 3.193609e-04 9.747790e-01 1.561038e+02 1.941032e-02 9.998031e-01 4.116358e-03 -1.072135e+01 -9.745858e-01 1.983942e-02 -2.231344e-01 2.244349e+02 +-2.320722e-01 3.673355e-03 9.726916e-01 1.570179e+02 2.427891e-02 9.997032e-01 2.017280e-03 -1.073555e+01 -9.723955e-01 2.408404e-02 -2.320925e-01 2.242081e+02 +-2.382600e-01 3.622420e-03 9.711946e-01 1.579367e+02 2.890518e-02 9.995765e-01 3.362926e-03 -1.075193e+01 -9.707712e-01 2.887380e-02 -2.382638e-01 2.239740e+02 +-2.427553e-01 2.741881e-03 9.700837e-01 1.588530e+02 3.425096e-02 9.993967e-01 5.746279e-03 -1.077320e+01 -9.694827e-01 3.462122e-02 -2.427028e-01 2.237355e+02 +-2.453586e-01 5.236526e-03 9.694182e-01 1.597703e+02 3.949192e-02 9.992093e-01 4.597901e-03 -1.079330e+01 -9.686277e-01 3.941231e-02 -2.453714e-01 2.234945e+02 +-2.457961e-01 8.928513e-03 9.692804e-01 1.606852e+02 4.360560e-02 9.990471e-01 1.855061e-03 -1.081601e+01 -9.683403e-01 4.272201e-02 -2.459512e-01 2.232561e+02 +-2.439192e-01 1.156004e-02 9.697266e-01 1.616029e+02 4.939384e-02 9.987792e-01 5.178485e-04 -1.083727e+01 -9.685369e-01 4.802483e-02 -2.441924e-01 2.230164e+02 +-2.400202e-01 1.398803e-02 9.706671e-01 1.625194e+02 5.280297e-02 9.986040e-01 -1.333854e-03 -1.086223e+01 -9.693308e-01 5.093394e-02 -2.404238e-01 2.227822e+02 +-2.346143e-01 1.341811e-02 9.719959e-01 1.634387e+02 5.764253e-02 9.983373e-01 1.316476e-04 -1.088198e+01 -9.703780e-01 5.605918e-02 -2.349977e-01 2.225541e+02 +-2.277846e-01 9.073331e-03 9.736693e-01 1.643660e+02 6.254682e-02 9.980278e-01 5.332158e-03 -1.089993e+01 -9.717006e-01 6.211449e-02 -2.279029e-01 2.223278e+02 +-2.217996e-01 3.980529e-03 9.750841e-01 1.652927e+02 6.559633e-02 9.977873e-01 1.084780e-02 -1.091476e+01 -9.728834e-01 6.636796e-02 -2.215700e-01 2.221110e+02 +-2.163968e-01 3.733776e-03 9.762984e-01 1.662142e+02 6.853557e-02 9.975838e-01 1.137574e-02 -1.092693e+01 -9.738970e-01 6.937282e-02 -2.161298e-01 2.219004e+02 +-2.110339e-01 6.423035e-03 9.774576e-01 1.671352e+02 7.006995e-02 9.975052e-01 8.573379e-03 -1.093836e+01 -9.749641e-01 7.029967e-02 -2.109575e-01 2.217008e+02 +-2.050684e-01 1.183871e-02 9.786760e-01 1.680517e+02 7.195326e-02 9.974034e-01 3.011575e-03 -1.095267e+01 -9.760993e-01 7.103649e-02 -2.053877e-01 2.215070e+02 +-1.991695e-01 1.658688e-02 9.798247e-01 1.689709e+02 7.339198e-02 9.973012e-01 -1.964306e-03 -1.097205e+01 -9.772130e-01 7.152003e-02 -1.998494e-01 2.213197e+02 +-1.931735e-01 1.673628e-02 9.810219e-01 1.698914e+02 7.221663e-02 9.973850e-01 -2.795238e-03 -1.099329e+01 -9.785034e-01 7.030611e-02 -1.938770e-01 2.211419e+02 +-1.866583e-01 1.258596e-02 9.823443e-01 1.708133e+02 6.911260e-02 9.976088e-01 3.507641e-04 -1.101589e+01 -9.799909e-01 6.795782e-02 -1.870818e-01 2.209732e+02 +-1.797312e-01 8.275080e-03 9.836809e-01 1.717375e+02 6.911333e-02 9.975998e-01 4.235720e-03 -1.103652e+01 -9.812849e-01 6.874674e-02 -1.798717e-01 2.208078e+02 +-1.730367e-01 7.777356e-03 9.848847e-01 1.726522e+02 7.090002e-02 9.974729e-01 4.579822e-03 -1.105613e+01 -9.823602e-01 7.062081e-02 -1.731508e-01 2.206457e+02 +-1.674789e-01 7.779084e-03 9.858450e-01 1.735653e+02 7.024651e-02 9.975214e-01 4.062503e-03 -1.107512e+01 -9.833699e-01 6.993253e-02 -1.676102e-01 2.204910e+02 +-1.638150e-01 1.006908e-02 9.864397e-01 1.744703e+02 6.859394e-02 9.976439e-01 1.207728e-03 -1.109703e+01 -9.841034e-01 6.786162e-02 -1.641197e-01 2.203408e+02 +-1.616754e-01 1.303766e-02 9.867578e-01 1.753649e+02 6.917753e-02 9.976026e-01 -1.846551e-03 -1.111947e+01 -9.844164e-01 6.796292e-02 -1.621898e-01 2.201910e+02 +-1.607790e-01 1.449856e-02 9.868839e-01 1.762458e+02 7.021590e-02 9.975266e-01 -3.215639e-03 -1.114170e+01 -9.844897e-01 6.877792e-02 -1.613993e-01 2.200431e+02 +-1.603253e-01 1.213456e-02 9.869896e-01 1.771194e+02 7.122593e-02 9.974599e-01 -6.934486e-04 -1.116612e+01 -9.844911e-01 7.018806e-02 -1.607824e-01 2.199007e+02 +-1.598169e-01 4.695880e-03 9.871355e-01 1.779794e+02 7.235457e-02 9.973546e-01 6.969685e-03 -1.118985e+01 -9.844915e-01 7.253762e-02 -1.597339e-01 2.197649e+02 +-1.591877e-01 -1.093232e-03 9.872477e-01 1.788188e+02 7.207093e-02 9.973183e-01 1.272538e-02 -1.121198e+01 -9.846142e-01 7.317757e-02 -1.586820e-01 2.196337e+02 +-1.587621e-01 -2.267047e-03 9.873142e-01 1.796396e+02 7.245810e-02 9.972740e-01 1.394132e-02 -1.123160e+01 -9.846545e-01 7.375225e-02 -1.581651e-01 2.195057e+02 +-1.579933e-01 2.416846e-03 9.874372e-01 1.804494e+02 7.495607e-02 9.971411e-01 9.552626e-03 -1.124667e+01 -9.845912e-01 7.552365e-02 -1.577228e-01 2.193761e+02 +-1.574196e-01 8.236555e-03 9.874974e-01 1.812572e+02 7.509265e-02 9.971698e-01 3.653479e-03 -1.126154e+01 -9.846727e-01 7.472891e-02 -1.575925e-01 2.192516e+02 +-1.575490e-01 1.124368e-02 9.874471e-01 1.820653e+02 7.291240e-02 9.973383e-01 2.770013e-04 -1.128050e+01 -9.848158e-01 7.204077e-02 -1.579495e-01 2.191312e+02 +-1.574562e-01 1.250802e-02 9.874467e-01 1.828723e+02 7.209926e-02 9.973968e-01 -1.137263e-03 -1.130022e+01 -9.848905e-01 7.101509e-02 -1.579482e-01 2.190097e+02 +-1.581125e-01 1.108663e-02 9.873588e-01 1.836794e+02 7.194000e-02 9.974089e-01 3.207550e-04 -1.131936e+01 -9.847970e-01 7.108130e-02 -1.585004e-01 2.188840e+02 +-1.593380e-01 8.626123e-03 9.871864e-01 1.844826e+02 7.304035e-02 9.973242e-01 3.074451e-03 -1.134108e+01 -9.845184e-01 7.259430e-02 -1.595417e-01 2.187569e+02 +-1.608905e-01 4.846644e-03 9.869603e-01 1.852857e+02 7.415549e-02 9.972207e-01 7.191508e-03 -1.136073e+01 -9.841825e-01 7.434556e-02 -1.608027e-01 2.186289e+02 +-1.626032e-01 1.024440e-04 9.866915e-01 1.860869e+02 7.601747e-02 9.970291e-01 1.242388e-02 -1.137570e+01 -9.837589e-01 7.702594e-02 -1.621279e-01 2.184976e+02 +-1.639173e-01 -1.854051e-03 9.864723e-01 1.868829e+02 7.922589e-02 9.967432e-01 1.503793e-02 -1.139179e+01 -9.832876e-01 8.061910e-02 -1.632366e-01 2.183633e+02 +-1.652841e-01 2.453532e-05 9.862460e-01 1.876728e+02 8.161830e-02 9.965701e-01 1.365355e-02 -1.140426e+01 -9.828630e-01 8.275242e-02 -1.647192e-01 2.182293e+02 +-1.657198e-01 6.984890e-03 9.861481e-01 1.884547e+02 8.198711e-02 9.966107e-01 6.718735e-03 -1.141601e+01 -9.827589e-01 8.196484e-02 -1.657308e-01 2.181002e+02 +-1.642526e-01 1.337722e-02 9.863276e-01 1.892377e+02 8.321528e-02 9.965315e-01 3.421824e-04 -1.142994e+01 -9.829020e-01 8.213372e-02 -1.647961e-01 2.179708e+02 +-1.619148e-01 1.561670e-02 9.866811e-01 1.900209e+02 8.585411e-02 9.963063e-01 -1.680353e-03 -1.144459e+01 -9.830629e-01 8.443854e-02 -1.626575e-01 2.178414e+02 +-1.589322e-01 1.323546e-02 9.872008e-01 1.908040e+02 8.510510e-02 9.963719e-01 3.428749e-04 -1.146339e+01 -9.836146e-01 8.407030e-02 -1.594819e-01 2.177163e+02 +-1.549074e-01 7.995837e-03 9.878966e-01 1.915816e+02 8.298957e-02 9.965381e-01 4.947417e-03 -1.148657e+01 -9.844371e-01 8.275149e-02 -1.550347e-01 2.176003e+02 +-1.500013e-01 5.241408e-03 9.886719e-01 1.923608e+02 8.264790e-02 9.965524e-01 7.256151e-03 -1.150395e+01 -9.852253e-01 8.280007e-02 -1.499174e-01 2.174857e+02 +-1.455304e-01 4.562017e-03 9.893433e-01 1.931408e+02 8.153630e-02 9.966429e-01 7.398140e-03 -1.151807e+01 -9.859882e-01 8.174402e-02 -1.454138e-01 2.173735e+02 +-1.418266e-01 4.438278e-03 9.898815e-01 1.939054e+02 8.007283e-02 9.967644e-01 7.003400e-03 -1.153475e+01 -9.866477e-01 8.025587e-02 -1.417231e-01 2.172664e+02 +-1.379147e-01 6.847184e-03 9.904204e-01 1.946686e+02 8.046909e-02 9.967477e-01 4.314277e-03 -1.155407e+01 -9.871699e-01 8.029322e-02 -1.380171e-01 2.171590e+02 +-1.343538e-01 9.001815e-03 9.908925e-01 1.954321e+02 8.138024e-02 9.966811e-01 1.979831e-03 -1.157048e+01 -9.875861e-01 8.090505e-02 -1.346405e-01 2.170546e+02 +-1.313695e-01 8.734777e-03 9.912950e-01 1.961951e+02 8.162234e-02 9.966612e-01 2.034777e-03 -1.158471e+01 -9.879676e-01 8.117911e-02 -1.316438e-01 2.169536e+02 +-1.293324e-01 4.050152e-03 9.915930e-01 1.969615e+02 8.154912e-02 9.966477e-01 6.565563e-03 -1.159784e+01 -9.882423e-01 8.171266e-02 -1.292292e-01 2.168558e+02 +-1.273979e-01 -5.824738e-04 9.918515e-01 1.977276e+02 8.146804e-02 9.966147e-01 1.104939e-02 -1.161171e+01 -9.885003e-01 8.221185e-02 -1.269192e-01 2.167592e+02 +-1.260624e-01 -1.425563e-03 9.920213e-01 1.984849e+02 7.941080e-02 9.967753e-01 1.152362e-02 -1.162654e+01 -9.888389e-01 8.022989e-02 -1.255426e-01 2.166672e+02 +-1.255904e-01 1.957659e-03 9.920802e-01 1.992330e+02 7.804835e-02 9.969181e-01 7.913163e-03 -1.163796e+01 -9.890074e-01 7.842402e-02 -1.253561e-01 2.165762e+02 +-1.249940e-01 6.746429e-03 9.921345e-01 1.999721e+02 7.676182e-02 9.970452e-01 2.891003e-03 -1.164907e+01 -9.891836e-01 7.651939e-02 -1.251425e-01 2.164856e+02 +-1.249128e-01 8.396010e-03 9.921322e-01 2.006974e+02 7.123544e-02 9.974594e-01 5.276818e-04 -1.166486e+01 -9.896072e-01 7.074087e-02 -1.251935e-01 2.164030e+02 +-1.253396e-01 7.122799e-03 9.920883e-01 2.014066e+02 6.748152e-02 9.977196e-01 1.362326e-03 -1.168188e+01 -9.898163e-01 6.711836e-02 -1.255345e-01 2.163207e+02 +-1.255463e-01 3.166278e-03 9.920827e-01 2.020987e+02 6.558058e-02 9.978341e-01 5.114467e-03 -1.169715e+01 -9.899179e-01 6.570345e-02 -1.254820e-01 2.162379e+02 +-1.258074e-01 -1.167550e-03 9.920540e-01 2.027701e+02 6.581015e-02 9.977867e-01 9.520011e-03 -1.171008e+01 -9.898695e-01 6.648490e-02 -1.254521e-01 2.161534e+02 +-1.263023e-01 -4.678568e-03 9.919808e-01 2.034203e+02 6.539827e-02 9.977741e-01 1.303261e-02 -1.172600e+01 -9.898338e-01 6.651986e-02 -1.257152e-01 2.160723e+02 +-1.265476e-01 -4.535748e-03 9.919501e-01 2.040424e+02 6.357314e-02 9.978967e-01 1.267325e-02 -1.174179e+01 -9.899213e-01 6.466514e-02 -1.259931e-01 2.159963e+02 +-1.262749e-01 -2.484053e-03 9.919922e-01 2.046388e+02 6.146035e-02 9.980561e-01 1.032279e-02 -1.175712e+01 -9.900896e-01 6.227168e-02 -1.258768e-01 2.159254e+02 +-1.257443e-01 1.397185e-03 9.920617e-01 2.052063e+02 6.235390e-02 9.980329e-01 6.497789e-03 -1.176977e+01 -9.901012e-01 6.267596e-02 -1.255841e-01 2.158497e+02 +-1.250196e-01 4.560881e-03 9.921438e-01 2.057498e+02 6.377571e-02 9.979583e-01 3.448734e-03 -1.178029e+01 -9.901024e-01 6.370582e-02 -1.250552e-01 2.157751e+02 +-1.239631e-01 5.877891e-03 9.922694e-01 2.062678e+02 6.352432e-02 9.979782e-01 2.024305e-03 -1.179068e+01 -9.902514e-01 6.328416e-02 -1.240858e-01 2.157039e+02 +-1.230730e-01 5.995201e-03 9.923795e-01 2.067643e+02 6.126993e-02 9.981200e-01 1.568695e-03 -1.180386e+01 -9.905045e-01 6.099607e-02 -1.232090e-01 2.156424e+02 +-1.226938e-01 5.385538e-03 9.924299e-01 2.072412e+02 5.868947e-02 9.982746e-01 1.838501e-03 -1.181841e+01 -9.907077e-01 5.847075e-02 -1.227982e-01 2.155834e+02 +-1.228948e-01 7.265338e-03 9.923931e-01 2.077037e+02 5.839788e-02 9.982934e-01 -7.673533e-05 -1.183177e+01 -9.907001e-01 5.794421e-02 -1.231093e-01 2.155193e+02 +-1.246385e-01 9.725456e-03 9.921545e-01 2.081634e+02 5.864887e-02 9.982757e-01 -2.417751e-03 -1.184447e+01 -9.904674e-01 5.788739e-02 -1.249940e-01 2.154469e+02 +-1.280538e-01 1.205802e-02 9.916939e-01 2.086133e+02 5.807919e-02 9.983012e-01 -4.638813e-03 -1.185974e+01 -9.900652e-01 5.700275e-02 -1.285366e-01 2.153795e+02 +-1.324406e-01 1.402128e-02 9.910918e-01 2.090598e+02 5.728552e-02 9.983369e-01 -6.468670e-03 -1.187441e+01 -9.895342e-01 5.591848e-02 -1.330235e-01 2.153094e+02 +-1.373036e-01 1.461844e-02 9.904211e-01 2.095000e+02 5.728440e-02 9.983348e-01 -6.793832e-03 -1.188921e+01 -9.888712e-01 5.580285e-02 -1.379123e-01 2.152430e+02 +-1.422973e-01 1.433411e-02 9.897201e-01 2.099461e+02 5.820215e-02 9.982862e-01 -6.090146e-03 -1.190078e+01 -9.881114e-01 5.673722e-02 -1.428878e-01 2.151654e+02 +-1.472620e-01 1.442430e-02 9.889923e-01 2.103502e+02 5.979156e-02 9.981948e-01 -5.655492e-03 -1.191239e+01 -9.872887e-01 5.830054e-02 -1.478587e-01 2.150913e+02 +-1.525840e-01 1.420982e-02 9.881883e-01 2.107510e+02 6.130418e-02 9.981071e-01 -4.886616e-03 -1.192429e+01 -9.863873e-01 5.983444e-02 -1.531663e-01 2.150166e+02 +-1.574848e-01 1.246525e-02 9.874427e-01 2.111322e+02 6.260964e-02 9.980346e-01 -2.613507e-03 -1.193502e+01 -9.855347e-01 6.141183e-02 -1.579558e-01 2.149432e+02 +-1.618337e-01 1.131137e-02 9.867532e-01 2.114907e+02 6.330111e-02 9.979939e-01 -1.058450e-03 -1.194531e+01 -9.847857e-01 6.229126e-02 -1.622251e-01 2.148750e+02 +-1.659169e-01 1.149618e-02 9.860727e-01 2.118248e+02 6.273494e-02 9.980296e-01 -1.079784e-03 -1.195308e+01 -9.841423e-01 6.168205e-02 -1.663112e-01 2.148092e+02 +-1.699844e-01 1.387986e-02 9.853490e-01 2.121366e+02 6.229972e-02 9.980520e-01 -3.311362e-03 -1.195979e+01 -9.834755e-01 6.082407e-02 -1.705180e-01 2.147448e+02 +-1.736840e-01 1.640657e-02 9.846647e-01 2.124472e+02 6.256633e-02 9.980251e-01 -5.593179e-03 -1.196560e+01 -9.828120e-01 6.063540e-02 -1.743675e-01 2.146767e+02 +-1.774167e-01 1.760772e-02 9.839783e-01 2.127554e+02 6.402838e-02 9.979281e-01 -6.312683e-03 -1.197156e+01 -9.820508e-01 6.188255e-02 -1.781766e-01 2.146076e+02 +-1.817133e-01 1.684144e-02 9.832073e-01 2.130625e+02 6.589720e-02 9.978143e-01 -4.912736e-03 -1.197601e+01 -9.811411e-01 6.389789e-02 -1.824259e-01 2.145346e+02 +-1.870768e-01 1.533974e-02 9.822255e-01 2.133651e+02 6.651997e-02 9.977808e-01 -2.913145e-03 -1.198122e+01 -9.800905e-01 6.479261e-02 -1.876821e-01 2.144625e+02 +-1.925935e-01 1.516670e-02 9.811614e-01 2.136645e+02 6.706206e-02 9.977462e-01 -2.259369e-03 -1.198387e+01 -9.789844e-01 6.536356e-02 -1.931765e-01 2.143873e+02 +-1.976465e-01 1.548005e-02 9.801511e-01 2.139593e+02 6.735828e-02 9.977265e-01 -2.174901e-03 -1.198790e+01 -9.779564e-01 6.559142e-02 -1.982399e-01 2.143144e+02 +-2.033506e-01 1.588860e-02 9.789770e-01 2.142535e+02 6.626177e-02 9.977993e-01 -2.430368e-03 -1.199133e+01 -9.768613e-01 6.437452e-02 -2.039559e-01 2.142396e+02 +-2.099843e-01 1.573130e-02 9.775782e-01 2.145405e+02 6.470205e-02 9.979023e-01 -2.160331e-03 -1.199660e+01 -9.755615e-01 6.279766e-02 -2.105617e-01 2.141671e+02 +-2.176390e-01 1.630868e-02 9.758931e-01 2.148240e+02 6.428828e-02 9.979286e-01 -2.339669e-03 -1.200048e+01 -9.739098e-01 6.222927e-02 -2.182366e-01 2.140888e+02 +-2.261592e-01 1.923465e-02 9.739004e-01 2.151087e+02 6.456007e-02 9.979027e-01 -4.716563e-03 -1.200452e+01 -9.719486e-01 6.180837e-02 -2.269266e-01 2.140092e+02 +-2.365380e-01 2.178275e-02 9.713780e-01 2.153958e+02 6.420290e-02 9.979141e-01 -6.743919e-03 -1.200829e+01 -9.694988e-01 6.077008e-02 -2.374431e-01 2.139238e+02 +-2.497179e-01 2.242394e-02 9.680589e-01 2.156879e+02 6.304978e-02 9.979868e-01 -6.853047e-03 -1.201206e+01 -9.662638e-01 5.932456e-02 -2.506290e-01 2.138347e+02 +-2.642260e-01 2.385360e-02 9.641658e-01 2.159779e+02 6.127067e-02 9.980899e-01 -7.901901e-03 -1.201719e+01 -9.625126e-01 5.698718e-02 -2.651828e-01 2.137362e+02 +-2.787501e-01 2.516667e-02 9.600339e-01 2.162742e+02 6.085829e-02 9.981102e-01 -8.494353e-03 -1.202125e+01 -9.584335e-01 5.605820e-02 -2.797549e-01 2.136330e+02 +-2.934133e-01 2.517444e-02 9.556542e-01 2.165750e+02 5.921836e-02 9.982121e-01 -8.113801e-03 -1.202540e+01 -9.541498e-01 5.421156e-02 -2.943795e-01 2.135266e+02 +-3.094498e-01 2.394164e-02 9.506143e-01 2.168779e+02 5.590271e-02 9.984120e-01 -6.947667e-03 -1.202996e+01 -9.492712e-01 5.099195e-02 -3.102968e-01 2.134128e+02 +-3.266804e-01 2.435808e-02 9.448209e-01 2.171847e+02 5.403130e-02 9.985143e-01 -7.060528e-03 -1.203598e+01 -9.435892e-01 4.874336e-02 -3.275112e-01 2.132943e+02 +-3.450266e-01 2.570099e-02 9.382410e-01 2.174909e+02 5.476335e-02 9.984733e-01 -7.212381e-03 -1.204201e+01 -9.369940e-01 4.889274e-02 -3.459073e-01 2.131576e+02 +-3.644988e-01 2.773359e-02 9.307908e-01 2.178077e+02 5.524271e-02 9.984399e-01 -8.116146e-03 -1.204893e+01 -9.295638e-01 4.846106e-02 -3.654623e-01 2.130160e+02 +-3.855047e-01 2.936807e-02 9.222384e-01 2.181257e+02 5.395823e-02 9.985004e-01 -9.241528e-03 -1.205635e+01 -9.211268e-01 4.619969e-02 -3.865113e-01 2.128606e+02 +-4.082826e-01 2.880593e-02 9.124009e-01 2.184573e+02 5.028626e-02 9.986940e-01 -9.028172e-03 -1.206367e+01 -9.114695e-01 4.219518e-02 -4.091980e-01 2.127009e+02 +-4.324458e-01 2.807722e-02 9.012226e-01 2.187890e+02 4.625260e-02 9.988899e-01 -8.926004e-03 -1.206999e+01 -9.004728e-01 3.782386e-02 -4.332644e-01 2.125208e+02 +-4.578166e-01 2.710274e-02 8.886334e-01 2.191324e+02 4.233923e-02 9.990658e-01 -8.658047e-03 -1.207317e+01 -8.880379e-01 3.366025e-02 -4.585364e-01 2.123331e+02 +-4.839728e-01 2.667367e-02 8.746764e-01 2.194807e+02 4.111448e-02 9.991246e-01 -7.719467e-03 -1.207767e+01 -8.741167e-01 3.222585e-02 -4.846458e-01 2.121252e+02 +-5.108352e-01 2.623673e-02 8.592782e-01 2.198185e+02 4.112431e-02 9.991356e-01 -6.058948e-03 -1.208217e+01 -8.586945e-01 3.224209e-02 -5.114726e-01 2.118886e+02 +-5.387793e-01 2.511835e-02 8.420724e-01 2.201707e+02 4.168522e-02 9.991259e-01 -3.131878e-03 -1.208752e+01 -8.414150e-01 3.341458e-02 -5.393554e-01 2.116444e+02 +-5.669378e-01 2.350174e-02 8.234252e-01 2.205117e+02 4.130794e-02 9.991464e-01 -7.609616e-05 -1.208923e+01 -8.227243e-01 3.397085e-02 -5.674247e-01 2.113709e+02 +-5.951077e-01 2.229455e-02 8.033366e-01 2.208656e+02 4.035051e-02 9.991832e-01 2.161666e-03 -1.209145e+01 -8.026324e-01 3.370146e-02 -5.955212e-01 2.110919e+02 +-6.235672e-01 2.193810e-02 7.814619e-01 2.212072e+02 3.975472e-02 9.992027e-01 3.671480e-03 -1.209207e+01 -7.807583e-01 3.335620e-02 -6.239422e-01 2.107785e+02 +-6.512370e-01 2.279329e-02 7.585320e-01 2.215508e+02 4.028302e-02 9.991779e-01 4.560423e-03 -1.209106e+01 -7.578045e-01 3.352587e-02 -6.516198e-01 2.104591e+02 +-6.790634e-01 2.218743e-02 7.337443e-01 2.218948e+02 4.056179e-02 9.991501e-01 7.326033e-03 -1.209078e+01 -7.329582e-01 3.473681e-02 -6.793863e-01 2.101168e+02 +-7.060656e-01 2.048919e-02 7.078500e-01 2.222202e+02 3.933543e-02 9.991728e-01 1.031452e-02 -1.208807e+01 -7.070531e-01 3.512630e-02 -7.062875e-01 2.097415e+02 +-7.323964e-01 1.891729e-02 6.806156e-01 2.225556e+02 3.745327e-02 9.992198e-01 1.252997e-02 -1.208726e+01 -6.798476e-01 3.466818e-02 -7.325335e-01 2.093633e+02 +-7.580937e-01 1.747620e-02 6.519115e-01 2.228726e+02 3.475301e-02 9.993030e-01 1.362455e-02 -1.208810e+01 -6.512190e-01 3.298456e-02 -7.581727e-01 2.089519e+02 +-7.823726e-01 1.723669e-02 6.225721e-01 2.231839e+02 3.375364e-02 9.993213e-01 1.474997e-02 -1.208800e+01 -6.218954e-01 3.255405e-02 -7.824234e-01 2.085357e+02 +-8.057083e-01 1.762032e-02 5.920504e-01 2.234744e+02 3.345723e-02 9.993154e-01 1.579004e-02 -1.208533e+01 -5.913669e-01 3.253053e-02 -8.057463e-01 2.080826e+02 +-8.272890e-01 1.948526e-02 5.614385e-01 2.237671e+02 3.420057e-02 9.992914e-01 1.571371e-02 -1.208074e+01 -5.607346e-01 3.220129e-02 -8.273692e-01 2.076241e+02 +-8.470536e-01 2.094060e-02 5.310948e-01 2.240514e+02 3.450544e-02 9.992822e-01 1.563259e-02 -1.207787e+01 -5.303862e-01 3.156729e-02 -8.471682e-01 2.071482e+02 +-8.652121e-01 2.106417e-02 5.009633e-01 2.243128e+02 3.395461e-02 9.992851e-01 1.662561e-02 -1.207612e+01 -5.002550e-01 3.139469e-02 -8.653088e-01 2.066411e+02 +-8.822165e-01 2.238904e-02 4.703113e-01 2.245725e+02 3.470998e-02 9.992435e-01 1.754073e-02 -1.207543e+01 -4.695628e-01 3.179921e-02 -8.823262e-01 2.061282e+02 +-8.986426e-01 2.086032e-02 4.381853e-01 2.248081e+02 3.232806e-02 9.993018e-01 1.872633e-02 -1.207187e+01 -4.374888e-01 3.099395e-02 -8.986896e-01 2.055859e+02 +-9.141780e-01 1.775824e-02 4.049238e-01 2.250448e+02 2.894846e-02 9.993490e-01 2.152838e-02 -1.206587e+01 -4.042779e-01 3.140269e-02 -9.140970e-01 2.050382e+02 +-9.286175e-01 1.701723e-02 3.706481e-01 2.252468e+02 2.876075e-02 9.992434e-01 2.617947e-02 -1.205579e+01 -3.699222e-01 3.497082e-02 -9.284043e-01 2.044540e+02 +-9.419550e-01 2.000498e-02 3.351425e-01 2.254378e+02 3.254740e-02 9.989626e-01 3.184896e-02 -1.204557e+01 -3.341577e-01 4.090830e-02 -9.416290e-01 2.038655e+02 +-9.542141e-01 2.065144e-02 2.984108e-01 2.256107e+02 3.330975e-02 9.987452e-01 3.739507e-02 -1.203450e+01 -2.972641e-01 4.562288e-02 -9.537047e-01 2.032602e+02 +-9.652761e-01 1.743748e-02 2.606491e-01 2.257529e+02 2.895948e-02 9.987626e-01 4.042976e-02 -1.202083e+01 -2.596216e-01 4.657414e-02 -9.645867e-01 2.026310e+02 +-9.749673e-01 1.665826e-02 2.217234e-01 2.258861e+02 2.641480e-02 9.988053e-01 4.111069e-02 -1.200689e+01 -2.207737e-01 4.593835e-02 -9.742426e-01 2.020049e+02 +-9.828727e-01 2.217488e-02 1.829469e-01 2.259699e+02 3.008988e-02 9.987222e-01 4.060177e-02 -1.198955e+01 -1.818128e-01 4.541121e-02 -9.822840e-01 2.013502e+02 +-9.891158e-01 2.936621e-02 1.441791e-01 2.260407e+02 3.550609e-02 9.985607e-01 4.019778e-02 -1.196853e+01 -1.427912e-01 4.487949e-02 -9.887348e-01 2.006996e+02 +-9.940102e-01 3.302946e-02 1.041770e-01 2.260923e+02 3.713007e-02 9.986001e-01 3.767074e-02 -1.195161e+01 -1.027869e-01 4.131319e-02 -9.938451e-01 2.000449e+02 +-9.973738e-01 3.298350e-02 6.447985e-02 2.261101e+02 3.526459e-02 9.987801e-01 3.456420e-02 -1.193962e+01 -6.326114e-02 3.674727e-02 -9.973203e-01 1.993672e+02 +-9.989634e-01 3.496914e-02 2.914356e-02 2.261143e+02 3.584977e-02 9.988989e-01 3.026256e-02 -1.192670e+01 -2.805322e-02 3.127597e-02 -9.991170e-01 1.986957e+02 +-9.992049e-01 3.966190e-02 -4.060367e-03 2.260837e+02 3.954454e-02 9.988855e-01 2.576577e-02 -1.191415e+01 5.077761e-03 2.558471e-02 -9.996598e-01 1.980015e+02 +-9.984876e-01 4.255609e-02 -3.480703e-02 2.260430e+02 4.166066e-02 9.987919e-01 2.605917e-02 -1.190302e+01 3.587396e-02 2.456967e-02 -9.990543e-01 1.973050e+02 +-9.969664e-01 4.461685e-02 -6.377540e-02 2.259758e+02 4.281251e-02 9.986509e-01 2.938497e-02 -1.189556e+01 6.500043e-02 2.656544e-02 -9.975316e-01 1.965914e+02 +-9.948896e-01 4.481946e-02 -9.047610e-02 2.259002e+02 4.199369e-02 9.985761e-01 3.289894e-02 -1.188846e+01 9.182178e-02 2.893138e-02 -9.953551e-01 1.958784e+02 +-9.924414e-01 4.503783e-02 -1.141564e-01 2.258077e+02 4.128788e-02 9.985339e-01 3.500474e-02 -1.187719e+01 1.155656e-01 3.002687e-02 -9.928459e-01 1.951598e+02 +-9.897238e-01 4.505728e-02 -1.357081e-01 2.256941e+02 4.045743e-02 9.985156e-01 3.646601e-02 -1.186231e+01 1.371497e-01 3.060087e-02 -9.900776e-01 1.944314e+02 +-9.868303e-01 4.439071e-02 -1.555491e-01 2.255712e+02 3.879338e-02 9.984922e-01 3.883862e-02 -1.184665e+01 1.570387e-01 3.229285e-02 -9.870644e-01 1.936998e+02 +-9.836355e-01 4.280878e-02 -1.750105e-01 2.254300e+02 3.592803e-02 9.984588e-01 4.229882e-02 -1.182904e+01 1.765516e-01 3.531883e-02 -9.836575e-01 1.929569e+02 +-9.798782e-01 4.244340e-02 -1.950316e-01 2.252770e+02 3.379403e-02 9.983010e-01 4.746548e-02 -1.180870e+01 1.967149e-01 3.991948e-02 -9.796478e-01 1.922149e+02 +-9.757752e-01 4.172989e-02 -2.147587e-01 2.251045e+02 3.104220e-02 9.981171e-01 5.290180e-02 -1.178565e+01 2.165619e-01 4.495368e-02 -9.752334e-01 1.914635e+02 +-9.714128e-01 3.969679e-02 -2.340541e-01 2.249166e+02 2.689130e-02 9.979744e-01 5.765267e-02 -1.175865e+01 2.358686e-01 4.971051e-02 -9.705127e-01 1.907076e+02 +-9.668772e-01 3.593075e-02 -2.527005e-01 2.247173e+02 2.124352e-02 9.979353e-01 6.061210e-02 -1.172910e+01 2.543566e-01 5.323620e-02 -9.656442e-01 1.899483e+02 +-9.624765e-01 3.292240e-02 -2.693604e-01 2.245024e+02 1.748761e-02 9.980749e-01 5.950250e-02 -1.169540e+01 2.708009e-01 5.255929e-02 -9.611995e-01 1.891896e+02 +-9.582210e-01 3.325158e-02 -2.840897e-01 2.242705e+02 1.863298e-02 9.983667e-01 5.400679e-02 -1.166511e+01 2.854215e-01 4.645699e-02 -9.572755e-01 1.884324e+02 +-9.545382e-01 2.981249e-02 -2.965939e-01 2.240295e+02 1.683468e-02 9.987896e-01 4.621497e-02 -1.163646e+01 2.976128e-01 3.912089e-02 -9.538848e-01 1.876707e+02 +-9.508700e-01 2.643557e-02 -3.084598e-01 2.237793e+02 1.461640e-02 9.990700e-01 4.056510e-02 -1.160574e+01 3.092453e-01 3.406356e-02 -9.503721e-01 1.868993e+02 +-9.477117e-01 2.865819e-02 -3.178383e-01 2.235149e+02 1.629568e-02 9.990061e-01 4.148685e-02 -1.158024e+01 3.187114e-01 3.413818e-02 -9.472369e-01 1.861219e+02 +-9.453445e-01 3.344807e-02 -3.243531e-01 2.232362e+02 1.932895e-02 9.987240e-01 4.665560e-02 -1.155902e+01 3.254998e-01 3.783620e-02 -9.447848e-01 1.853368e+02 +-9.429512e-01 3.939422e-02 -3.305921e-01 2.229496e+02 2.513315e-02 9.985643e-01 4.730404e-02 -1.153402e+01 3.319809e-01 3.629658e-02 -9.425875e-01 1.845560e+02 +-9.412202e-01 4.205782e-02 -3.351652e-01 2.226604e+02 2.837479e-02 9.985558e-01 4.561978e-02 -1.150979e+01 3.365999e-01 3.342801e-02 -9.410543e-01 1.837711e+02 +-9.398620e-01 4.118545e-02 -3.390622e-01 2.223723e+02 2.745395e-02 9.986007e-01 4.519792e-02 -1.148881e+01 3.404493e-01 3.317121e-02 -9.396776e-01 1.829813e+02 +-9.386170e-01 4.217391e-02 -3.423733e-01 2.220811e+02 2.866157e-02 9.986011e-01 4.443305e-02 -1.146666e+01 3.437683e-01 3.189266e-02 -9.385128e-01 1.821890e+02 +-9.376895e-01 4.373792e-02 -3.447105e-01 2.217831e+02 3.062448e-02 9.985883e-01 4.339857e-02 -1.144548e+01 3.461221e-01 3.013780e-02 -9.377053e-01 1.813910e+02 +-9.373188e-01 4.524603e-02 -3.455231e-01 2.214798e+02 3.225755e-02 9.985433e-01 4.325190e-02 -1.142358e+01 3.469768e-01 2.939509e-02 -9.374130e-01 1.805785e+02 +-9.375507e-01 4.715142e-02 -3.446380e-01 2.211898e+02 3.424916e-02 9.984691e-01 4.343377e-02 -1.140287e+01 3.461584e-01 2.891780e-02 -9.377303e-01 1.797993e+02 +-9.381494e-01 4.990494e-02 -3.426152e-01 2.208919e+02 3.683851e-02 9.983280e-01 4.454411e-02 -1.138373e+01 3.442653e-01 2.916759e-02 -9.384192e-01 1.789986e+02 +-9.391323e-01 5.341684e-02 -3.393777e-01 2.205956e+02 4.051014e-02 9.981649e-01 4.500725e-02 -1.136477e+01 3.411591e-01 2.851952e-02 -9.395729e-01 1.781970e+02 +-9.406534e-01 5.599016e-02 -3.347181e-01 2.203067e+02 4.317313e-02 9.980256e-01 4.561655e-02 -1.134462e+01 3.366114e-01 2.845853e-02 -9.412135e-01 1.773974e+02 +-9.426576e-01 5.794684e-02 -3.286927e-01 2.200214e+02 4.496701e-02 9.978841e-01 4.696106e-02 -1.132466e+01 3.307184e-01 2.948787e-02 -9.432687e-01 1.765874e+02 +-9.446961e-01 5.861738e-02 -3.226660e-01 2.197506e+02 4.547675e-02 9.978057e-01 4.812118e-02 -1.130546e+01 3.247787e-01 3.078608e-02 -9.452888e-01 1.757955e+02 +-9.467331e-01 5.862919e-02 -3.166370e-01 2.194829e+02 4.565422e-02 9.977914e-01 4.824881e-02 -1.128613e+01 3.187665e-01 3.122293e-02 -9.473189e-01 1.749962e+02 +-9.488231e-01 5.842654e-02 -3.103564e-01 2.192235e+02 4.565183e-02 9.977903e-01 4.827336e-02 -1.126642e+01 3.124911e-01 3.163454e-02 -9.493938e-01 1.742003e+02 +-9.508229e-01 5.899619e-02 -3.040646e-01 2.189685e+02 4.658043e-02 9.977638e-01 4.793242e-02 -1.124698e+01 3.062125e-01 3.141178e-02 -9.514448e-01 1.734080e+02 +-9.527442e-01 5.959994e-02 -2.978696e-01 2.187207e+02 4.737621e-02 9.977185e-01 4.809682e-02 -1.122758e+01 3.000566e-01 3.171203e-02 -9.533941e-01 1.726173e+02 +-9.545699e-01 5.899450e-02 -2.920890e-01 2.184822e+02 4.679123e-02 9.977218e-01 4.859690e-02 -1.120904e+01 2.942906e-01 3.272193e-02 -9.551557e-01 1.718348e+02 +-9.562503e-01 5.833727e-02 -2.866743e-01 2.182539e+02 4.603930e-02 9.977144e-01 4.945982e-02 -1.119054e+01 2.889045e-01 3.409767e-02 -9.567505e-01 1.710653e+02 +-9.576445e-01 5.820169e-02 -2.820098e-01 2.180324e+02 4.566688e-02 9.976629e-01 5.082466e-02 -1.117233e+01 2.843088e-01 3.579345e-02 -9.580644e-01 1.703090e+02 +-9.588005e-01 5.794791e-02 -2.781071e-01 2.178185e+02 4.522640e-02 9.976251e-01 5.194835e-02 -1.115639e+01 2.804570e-01 3.723032e-02 -9.591443e-01 1.695687e+02 +-9.595093e-01 5.699205e-02 -2.758509e-01 2.176115e+02 4.413862e-02 9.976404e-01 5.258699e-02 -1.114118e+01 2.781971e-01 3.828202e-02 -9.597608e-01 1.688446e+02 +-9.599059e-01 5.533234e-02 -2.748071e-01 2.174089e+02 4.262562e-02 9.977368e-01 5.200212e-02 -1.112669e+01 2.770625e-01 3.820332e-02 -9.600921e-01 1.681319e+02 +-9.600353e-01 5.447790e-02 -2.745257e-01 2.172166e+02 4.194700e-02 9.978011e-01 5.131587e-02 -1.111161e+01 2.767176e-01 3.774951e-02 -9.602095e-01 1.674588e+02 +-9.600545e-01 5.324109e-02 -2.747011e-01 2.170264e+02 4.085278e-02 9.978817e-01 5.062750e-02 -1.109583e+01 2.768147e-01 3.738285e-02 -9.601959e-01 1.667924e+02 +-9.599440e-01 5.324544e-02 -2.750863e-01 2.168358e+02 4.090325e-02 9.978904e-01 5.041437e-02 -1.108063e+01 2.771903e-01 3.714304e-02 -9.600968e-01 1.661328e+02 +-9.595572e-01 5.272948e-02 -2.765315e-01 2.166507e+02 4.013873e-02 9.978917e-01 5.099934e-02 -1.106602e+01 2.786377e-01 3.783716e-02 -9.596507e-01 1.654916e+02 +-9.588181e-01 5.233133e-02 -2.791584e-01 2.164731e+02 3.950177e-02 9.978970e-01 5.139121e-02 -1.105175e+01 2.812607e-01 3.824757e-02 -9.588689e-01 1.648836e+02 +-9.578782e-01 5.175742e-02 -2.824721e-01 2.162926e+02 3.884911e-02 9.979370e-01 5.111280e-02 -1.103735e+01 2.845349e-01 3.798604e-02 -9.579128e-01 1.642771e+02 +-9.567285e-01 5.184636e-02 -2.863261e-01 2.161108e+02 3.885110e-02 9.979485e-01 5.088626e-02 -1.102316e+01 2.883770e-01 3.756025e-02 -9.567800e-01 1.636828e+02 +-9.552714e-01 5.101220e-02 -2.912975e-01 2.159375e+02 3.778027e-02 9.979902e-01 5.087337e-02 -1.101053e+01 2.933073e-01 3.759257e-02 -9.552788e-01 1.631241e+02 +-9.532391e-01 5.037771e-02 -2.979888e-01 2.157571e+02 3.696701e-02 9.980410e-01 5.047383e-02 -1.099750e+01 2.999478e-01 3.709787e-02 -9.532340e-01 1.625601e+02 +-9.508266e-01 4.959487e-02 -3.057272e-01 2.155778e+02 3.609514e-02 9.981139e-01 4.965580e-02 -1.098606e+01 3.076133e-01 3.617878e-02 -9.508234e-01 1.620174e+02 +-9.475675e-01 4.877258e-02 -3.158117e-01 2.153925e+02 3.484348e-02 9.981608e-01 4.960660e-02 -1.097373e+01 3.176503e-01 3.600162e-02 -9.475242e-01 1.614786e+02 +-9.432170e-01 4.847617e-02 -3.286210e-01 2.151984e+02 3.385172e-02 9.981712e-01 5.008204e-02 -1.096038e+01 3.304479e-01 3.611384e-02 -9.431331e-01 1.609456e+02 +-9.375491e-01 4.830866e-02 -3.444821e-01 2.149994e+02 3.287374e-02 9.981823e-01 5.051096e-02 -1.094702e+01 3.462961e-01 3.603209e-02 -9.374331e-01 1.604300e+02 +-9.303330e-01 4.863359e-02 -3.634766e-01 2.147873e+02 3.228265e-02 9.981804e-01 5.092899e-02 -1.093349e+01 3.652921e-01 3.564693e-02 -9.302102e-01 1.599232e+02 +-9.215539e-01 4.962608e-02 -3.850659e-01 2.145696e+02 3.234686e-02 9.981631e-01 5.122647e-02 -1.092001e+01 3.869007e-01 3.475227e-02 -9.214663e-01 1.594398e+02 +-9.111594e-01 4.976293e-02 -4.090381e-01 2.143448e+02 3.173449e-02 9.982071e-01 5.074967e-02 -1.090714e+01 4.108302e-01 3.326042e-02 -9.111050e-01 1.589757e+02 +-8.982504e-01 4.760904e-02 -4.368977e-01 2.141013e+02 2.843177e-02 9.983277e-01 5.033349e-02 -1.089345e+01 4.385635e-01 3.279029e-02 -8.981018e-01 1.585183e+02 +-8.817741e-01 4.595791e-02 -4.694276e-01 2.138540e+02 2.572017e-02 9.984460e-01 4.943708e-02 -1.088161e+01 4.709702e-01 3.151857e-02 -8.815859e-01 1.580883e+02 +-8.621716e-01 4.335129e-02 -5.047581e-01 2.135738e+02 2.220786e-02 9.986084e-01 4.783279e-02 -1.087084e+01 5.061294e-01 3.003047e-02 -8.619346e-01 1.576626e+02 +-8.397277e-01 4.311798e-02 -5.412931e-01 2.132918e+02 2.179037e-02 9.987152e-01 4.575085e-02 -1.085991e+01 5.425704e-01 2.662328e-02 -8.395884e-01 1.572717e+02 +-8.145692e-01 4.373207e-02 -5.784156e-01 2.129713e+02 2.248101e-02 9.987849e-01 4.385533e-02 -1.084970e+01 5.796307e-01 2.271984e-02 -8.145625e-01 1.568845e+02 +-7.863499e-01 4.224668e-02 -6.163352e-01 2.126605e+02 2.118610e-02 9.989163e-01 4.144047e-02 -1.083876e+01 6.174180e-01 1.952897e-02 -7.863928e-01 1.565327e+02 +-7.553562e-01 4.348517e-02 -6.538701e-01 2.123070e+02 2.182181e-02 9.989116e-01 4.122320e-02 -1.082575e+01 6.549511e-01 1.686957e-02 -7.554830e-01 1.561823e+02 +-7.212335e-01 4.353665e-02 -6.913225e-01 2.119646e+02 2.034414e-02 9.989237e-01 4.168378e-02 -1.081490e+01 6.923932e-01 1.599938e-02 -7.213430e-01 1.558733e+02 +-6.835074e-01 4.348991e-02 -7.286469e-01 2.115825e+02 1.665099e-02 9.988927e-01 4.400032e-02 -1.080102e+01 7.297537e-01 1.794185e-02 -6.834747e-01 1.555602e+02 +-6.436357e-01 4.226311e-02 -7.641642e-01 2.112195e+02 1.089417e-02 9.988789e-01 4.606846e-02 -1.079193e+01 7.652545e-01 2.132638e-02 -6.433745e-01 1.552895e+02 +-6.023902e-01 4.177740e-02 -7.971077e-01 2.108436e+02 8.042909e-03 9.988963e-01 4.627522e-02 -1.077893e+01 7.981612e-01 2.146467e-02 -6.020614e-01 1.550445e+02 +-5.597492e-01 4.289535e-02 -8.275511e-01 2.104266e+02 7.495051e-03 9.988805e-01 4.670647e-02 -1.076398e+01 8.286282e-01 1.994137e-02 -5.594441e-01 1.548054e+02 +-5.151950e-01 4.434371e-02 -8.559251e-01 2.100255e+02 6.641985e-03 9.988372e-01 4.774979e-02 -1.074672e+01 8.570473e-01 1.891541e-02 -5.148905e-01 1.546096e+02 +-4.689686e-01 4.340219e-02 -8.821478e-01 2.095871e+02 3.212522e-03 9.988690e-01 4.743712e-02 -1.072901e+01 8.832090e-01 1.941260e-02 -4.685776e-01 1.544097e+02 +-4.222465e-01 4.281324e-02 -9.054694e-01 2.091630e+02 -3.623447e-03 9.987963e-01 4.891574e-02 -1.071710e+01 9.064738e-01 2.393542e-02 -4.215831e-01 1.542462e+02 +-3.749831e-01 4.390183e-02 -9.259915e-01 2.086989e+02 -8.449389e-03 9.986746e-01 5.076941e-02 -1.070231e+01 9.269932e-01 2.686173e-02 -3.741152e-01 1.540845e+02 +-3.270680e-01 4.450868e-02 -9.439520e-01 2.082485e+02 -1.035076e-02 9.986615e-01 5.067474e-02 -1.068657e+01 9.449441e-01 2.634471e-02 -3.261696e-01 1.539687e+02 +-2.796248e-01 4.394132e-02 -9.591033e-01 2.077642e+02 -1.128388e-02 9.987327e-01 4.904675e-02 -1.066963e+01 9.600431e-01 2.453710e-02 -2.787746e-01 1.538571e+02 +-2.339564e-01 4.347363e-02 -9.712746e-01 2.072894e+02 -1.343987e-02 9.987597e-01 4.794120e-02 -1.065218e+01 9.721542e-01 2.426995e-02 -2.330820e-01 1.537789e+02 +-1.909335e-01 4.491247e-02 -9.805749e-01 2.067991e+02 -1.689547e-02 9.986544e-01 4.903038e-02 -1.063405e+01 9.814576e-01 2.592882e-02 -1.899178e-01 1.537135e+02 +-1.513912e-01 4.795038e-02 -9.873102e-01 2.062808e+02 -1.813049e-02 9.985200e-01 5.127489e-02 -1.061406e+01 9.883077e-01 2.566298e-02 -1.502978e-01 1.536523e+02 +-1.162496e-01 5.172583e-02 -9.918722e-01 2.057617e+02 -1.729861e-02 9.983860e-01 5.409297e-02 -1.059467e+01 9.930694e-01 2.344629e-02 -1.151672e-01 1.536205e+02 +-8.477699e-02 5.522029e-02 -9.948686e-01 2.052140e+02 -1.776410e-02 9.982207e-01 5.692012e-02 -1.057389e+01 9.962416e-01 2.249846e-02 -8.364521e-02 1.535906e+02 +-5.721415e-02 5.609202e-02 -9.967849e-01 2.046780e+02 -2.081550e-02 9.981363e-01 5.736287e-02 -1.055334e+01 9.981449e-01 2.403054e-02 -5.593993e-02 1.535732e+02 +-3.171835e-02 5.314658e-02 -9.980828e-01 2.041091e+02 -2.390719e-02 9.982592e-01 5.391574e-02 -1.053316e+01 9.992109e-01 2.557148e-02 -3.039255e-02 1.535631e+02 +-1.080875e-02 4.941725e-02 -9.987197e-01 2.035572e+02 -2.637715e-02 9.984164e-01 4.968773e-02 -1.051461e+01 9.995937e-01 2.688044e-02 -9.488148e-03 1.535661e+02 +7.657214e-03 4.656911e-02 -9.988857e-01 2.029763e+02 -2.895917e-02 9.985063e-01 4.632944e-02 -1.049273e+01 9.995513e-01 2.857214e-02 8.994382e-03 1.535762e+02 +2.345413e-02 4.422907e-02 -9.987460e-01 2.023792e+02 -3.232032e-02 9.985322e-01 4.346062e-02 -1.046874e+01 9.992024e-01 3.126045e-02 2.484920e-02 1.535895e+02 +3.691838e-02 4.444772e-02 -9.983293e-01 2.017590e+02 -3.379095e-02 9.984946e-01 4.320549e-02 -1.044835e+01 9.987469e-01 3.213942e-02 3.836474e-02 1.536159e+02 +4.923569e-02 4.659450e-02 -9.976997e-01 2.011404e+02 -3.486727e-02 9.983825e-01 4.490573e-02 -1.043205e+01 9.981784e-01 3.257610e-02 5.078067e-02 1.536497e+02 +6.193689e-02 4.921678e-02 -9.968658e-01 2.004970e+02 -3.593747e-02 9.982457e-01 4.705207e-02 -1.041478e+01 9.974329e-01 3.291057e-02 6.359696e-02 1.536902e+02 +7.375757e-02 4.948310e-02 -9.960478e-01 1.998419e+02 -3.792849e-02 9.981848e-01 4.678066e-02 -1.039426e+01 9.965547e-01 3.432816e-02 7.550051e-02 1.537382e+02 +8.434373e-02 4.907301e-02 -9.952276e-01 1.991758e+02 -3.851230e-02 9.982008e-01 4.595578e-02 -1.037368e+01 9.956922e-01 3.445242e-02 8.608190e-02 1.537951e+02 +9.249367e-02 4.845774e-02 -9.945334e-01 1.984946e+02 -3.705460e-02 9.982907e-01 4.519467e-02 -1.035316e+01 9.950236e-01 3.267182e-02 9.413116e-02 1.538610e+02 +9.753973e-02 4.792520e-02 -9.940770e-01 1.978021e+02 -3.571033e-02 9.983652e-01 4.462802e-02 -1.033193e+01 9.945908e-01 3.114581e-02 9.909171e-02 1.539313e+02 +1.004019e-01 4.725112e-02 -9.938243e-01 1.970940e+02 -3.575087e-02 9.983979e-01 4.385683e-02 -1.031021e+01 9.943045e-01 3.112677e-02 1.019303e-01 1.540011e+02 +1.012807e-01 4.680683e-02 -9.937562e-01 1.963718e+02 -3.661813e-02 9.983911e-01 4.329314e-02 -1.028919e+01 9.941838e-01 3.200473e-02 1.028317e-01 1.540703e+02 +1.001150e-01 4.716687e-02 -9.938573e-01 1.956353e+02 -3.744672e-02 9.983467e-01 4.360779e-02 -1.026720e+01 9.942710e-01 3.285090e-02 1.017157e-01 1.541380e+02 +9.948408e-02 4.757583e-02 -9.939011e-01 1.948844e+02 -3.912302e-02 9.982709e-01 4.386902e-02 -1.024476e+01 9.942698e-01 3.452015e-02 1.011734e-01 1.542055e+02 +9.971122e-02 4.789038e-02 -9.938632e-01 1.941238e+02 -4.140170e-02 9.981757e-01 4.394448e-02 -1.022356e+01 9.941547e-01 3.676586e-02 1.015121e-01 1.542759e+02 +1.001521e-01 4.840970e-02 -9.937938e-01 1.933471e+02 -4.332757e-02 9.980804e-01 4.425208e-02 -1.020129e+01 9.940283e-01 3.862673e-02 1.020573e-01 1.543500e+02 +1.014657e-01 4.773146e-02 -9.936933e-01 1.925603e+02 -4.435022e-02 9.980723e-01 4.341322e-02 -1.017859e+01 9.938500e-01 3.966556e-02 1.033870e-01 1.544275e+02 +1.028760e-01 4.777847e-02 -9.935460e-01 1.917608e+02 -4.538744e-02 9.980308e-01 4.329455e-02 -1.015494e+01 9.936582e-01 4.064054e-02 1.048419e-01 1.545075e+02 +1.047168e-01 4.802052e-02 -9.933420e-01 1.909486e+02 -4.601516e-02 9.979977e-01 4.339474e-02 -1.013145e+01 9.934370e-01 4.116464e-02 1.067168e-01 1.545913e+02 +1.061111e-01 4.838311e-02 -9.931765e-01 1.901242e+02 -4.641109e-02 9.979679e-01 4.365797e-02 -1.010762e+01 9.932706e-01 4.146181e-02 1.081410e-01 1.546772e+02 +1.076027e-01 4.895052e-02 -9.929882e-01 1.892881e+02 -4.684230e-02 9.979275e-01 4.411808e-02 -1.008385e+01 9.930899e-01 4.176663e-02 1.096726e-01 1.547653e+02 +1.093468e-01 4.938877e-02 -9.927759e-01 1.884398e+02 -4.759648e-02 9.978793e-01 4.440027e-02 -1.005818e+01 9.928635e-01 4.239761e-02 1.114657e-01 1.548549e+02 +1.113155e-01 5.022020e-02 -9.925154e-01 1.875775e+02 -4.894422e-02 9.977874e-01 4.499763e-02 -1.003214e+01 9.925792e-01 4.356895e-02 1.135272e-01 1.549465e+02 +1.139566e-01 5.039395e-02 -9.922068e-01 1.867075e+02 -4.940661e-02 9.977644e-01 4.500181e-02 -1.000590e+01 9.922565e-01 4.389331e-02 1.161917e-01 1.550433e+02 +1.168476e-01 5.030162e-02 -9.918752e-01 1.858227e+02 -4.973688e-02 9.977597e-01 4.474082e-02 -9.979757e+00 9.919037e-01 4.410491e-02 1.190877e-01 1.551454e+02 +1.203451e-01 5.040567e-02 -9.914516e-01 1.849290e+02 -5.045436e-02 9.977300e-01 4.460058e-02 -9.953655e+00 9.914492e-01 4.465559e-02 1.226151e-01 1.552508e+02 +1.234753e-01 5.041033e-02 -9.910664e-01 1.840267e+02 -5.065338e-02 9.977271e-01 4.443832e-02 -9.928465e+00 9.910541e-01 4.471382e-02 1.257482e-01 1.553613e+02 +1.262713e-01 5.048667e-02 -9.907102e-01 1.831159e+02 -4.963205e-02 9.977748e-01 4.452083e-02 -9.903037e+00 9.907534e-01 4.354926e-02 1.284961e-01 1.554765e+02 +1.275000e-01 5.020822e-02 -9.905669e-01 1.821983e+02 -4.822518e-02 9.978505e-01 4.437015e-02 -9.877148e+00 9.906655e-01 4.211307e-02 1.296472e-01 1.555946e+02 +1.278957e-01 5.032910e-02 -9.905098e-01 1.812721e+02 -4.754442e-02 9.978745e-01 4.456434e-02 -9.849830e+00 9.906474e-01 4.139362e-02 1.300167e-01 1.557116e+02 +1.273017e-01 5.035574e-02 -9.905849e-01 1.803399e+02 -4.712118e-02 9.978898e-01 4.467147e-02 -9.823217e+00 9.907441e-01 4.099077e-02 1.294059e-01 1.558283e+02 +1.266819e-01 5.036912e-02 -9.906637e-01 1.794023e+02 -4.672217e-02 9.979045e-01 4.476264e-02 -9.797071e+00 9.908425e-01 4.061534e-02 1.287698e-01 1.559448e+02 +1.259409e-01 5.043708e-02 -9.907547e-01 1.784610e+02 -4.726866e-02 9.978774e-01 4.479108e-02 -9.770554e+00 9.909110e-01 4.119061e-02 1.280577e-01 1.560594e+02 +1.253999e-01 5.101310e-02 -9.907939e-01 1.775173e+02 -4.815228e-02 9.978131e-01 4.528012e-02 -9.743997e+00 9.909371e-01 4.203086e-02 1.275820e-01 1.561736e+02 +1.244313e-01 5.188639e-02 -9.908706e-01 1.765700e+02 -4.918953e-02 9.977264e-01 4.606829e-02 -9.716532e+00 9.910082e-01 4.300812e-02 1.267007e-01 1.562872e+02 +1.237624e-01 5.230734e-02 -9.909323e-01 1.756244e+02 -4.952038e-02 9.976910e-01 4.647928e-02 -9.690185e+00 9.910755e-01 4.331895e-02 1.260669e-01 1.564009e+02 +1.229357e-01 5.288888e-02 -9.910043e-01 1.746794e+02 -5.127243e-02 9.975838e-01 4.687961e-02 -9.663278e+00 9.910893e-01 4.504802e-02 1.253504e-01 1.565118e+02 +1.226784e-01 5.266367e-02 -9.910482e-01 1.737345e+02 -5.208893e-02 9.975564e-01 4.656161e-02 -9.637423e+00 9.910786e-01 4.591053e-02 1.251219e-01 1.566236e+02 +1.223071e-01 5.042939e-02 -9.912103e-01 1.727944e+02 -5.044366e-02 9.977334e-01 4.453695e-02 -9.613592e+00 9.912096e-01 4.455309e-02 1.245737e-01 1.567353e+02 +1.220713e-01 4.956831e-02 -9.912828e-01 1.718464e+02 -5.235617e-02 9.976831e-01 4.344098e-02 -9.588544e+00 9.911395e-01 4.659687e-02 1.243837e-01 1.568455e+02 +1.228904e-01 5.195213e-02 -9.910595e-01 1.709010e+02 -5.419644e-02 9.974899e-01 4.556893e-02 -9.562791e+00 9.909393e-01 4.811190e-02 1.253976e-01 1.569540e+02 +1.233681e-01 5.691729e-02 -9.907274e-01 1.699560e+02 -5.400526e-02 9.972594e-01 5.056769e-02 -9.537515e+00 9.908904e-01 4.726604e-02 1.261039e-01 1.570682e+02 +1.240320e-01 5.813002e-02 -9.905740e-01 1.690164e+02 -5.319169e-02 9.972367e-01 5.186077e-02 -9.509588e+00 9.908515e-01 4.625791e-02 1.267813e-01 1.571816e+02 +1.247423e-01 5.742187e-02 -9.905261e-01 1.680815e+02 -5.334011e-02 9.972683e-01 5.109532e-02 -9.480848e+00 9.907544e-01 4.646102e-02 1.274645e-01 1.572953e+02 +1.250678e-01 5.655480e-02 -9.905350e-01 1.671484e+02 -5.337183e-02 9.973119e-01 5.020286e-02 -9.453661e+00 9.907116e-01 4.658790e-02 1.277500e-01 1.574095e+02 +1.254128e-01 5.630195e-02 -9.905058e-01 1.662163e+02 -5.295771e-02 9.973449e-01 4.998548e-02 -9.427194e+00 9.906903e-01 4.618610e-02 1.280614e-01 1.575251e+02 +1.259144e-01 5.642326e-02 -9.904352e-01 1.652849e+02 -5.280264e-02 9.973472e-01 5.010421e-02 -9.400975e+00 9.906349e-01 4.598875e-02 1.285597e-01 1.576409e+02 +1.263191e-01 5.687770e-02 -9.903577e-01 1.643575e+02 -5.329890e-02 9.973019e-01 5.047831e-02 -9.372849e+00 9.905568e-01 4.640859e-02 1.290099e-01 1.577557e+02 +1.267393e-01 5.680565e-02 -9.903082e-01 1.634313e+02 -5.352124e-02 9.972962e-01 5.035688e-02 -9.345571e+00 9.904911e-01 4.662032e-02 1.294369e-01 1.578717e+02 +1.270315e-01 5.568284e-02 -9.903345e-01 1.625074e+02 -5.390255e-02 9.973352e-01 4.916233e-02 -9.319175e+00 9.904330e-01 4.713639e-02 1.296944e-01 1.579875e+02 +1.269934e-01 5.447091e-02 -9.904068e-01 1.615861e+02 -5.318727e-02 9.974284e-01 4.803724e-02 -9.292716e+00 9.904766e-01 4.657661e-02 1.295640e-01 1.581039e+02 +1.265192e-01 5.388234e-02 -9.904996e-01 1.606649e+02 -5.345071e-02 9.974433e-01 4.743267e-02 -9.266246e+00 9.905231e-01 4.694176e-02 1.290758e-01 1.582192e+02 +1.263730e-01 5.363781e-02 -9.905316e-01 1.597474e+02 -5.364133e-02 9.974456e-01 4.716860e-02 -9.240598e+00 9.905314e-01 4.717260e-02 1.289274e-01 1.583334e+02 +1.260842e-01 5.380056e-02 -9.905596e-01 1.588262e+02 -5.397413e-02 9.974213e-01 4.730311e-02 -9.215462e+00 9.905502e-01 4.750040e-02 1.286629e-01 1.584484e+02 +1.263294e-01 5.374468e-02 -9.905313e-01 1.579056e+02 -5.341800e-02 9.974510e-01 4.730737e-02 -9.190463e+00 9.905491e-01 4.693589e-02 1.288784e-01 1.585646e+02 +1.263656e-01 5.471250e-02 -9.904738e-01 1.569846e+02 -5.347771e-02 9.974016e-01 4.827246e-02 -9.164900e+00 9.905412e-01 4.686829e-02 1.289631e-01 1.586806e+02 +1.264333e-01 5.530417e-02 -9.904322e-01 1.560604e+02 -5.347379e-02 9.973729e-01 4.886556e-02 -9.140166e+00 9.905328e-01 4.678393e-02 1.290585e-01 1.587970e+02 +1.266898e-01 5.500310e-02 -9.904162e-01 1.551393e+02 -5.380505e-02 9.973726e-01 4.850693e-02 -9.115867e+00 9.904821e-01 4.714406e-02 1.293164e-01 1.589131e+02 +1.283536e-01 5.358145e-02 -9.902799e-01 1.542162e+02 -5.337682e-02 9.974653e-01 4.705189e-02 -9.090525e+00 9.902910e-01 4.681871e-02 1.308883e-01 1.590321e+02 +1.306341e-01 5.207113e-02 -9.900623e-01 1.532941e+02 -5.413318e-02 9.975047e-01 4.531995e-02 -9.066771e+00 9.899517e-01 4.767488e-02 1.331269e-01 1.591524e+02 +1.331386e-01 5.135633e-02 -9.897659e-01 1.523682e+02 -5.433089e-02 9.975331e-01 4.445103e-02 -9.042943e+00 9.896072e-01 4.785671e-02 1.356004e-01 1.592745e+02 +1.350751e-01 5.164936e-02 -9.894883e-01 1.514395e+02 -5.389961e-02 9.975448e-01 4.471207e-02 -9.019547e+00 9.893683e-01 4.729354e-02 1.375273e-01 1.593998e+02 +1.372202e-01 5.229809e-02 -9.891590e-01 1.505097e+02 -5.258275e-02 9.975818e-01 4.544893e-02 -8.996322e+00 9.891439e-01 4.577618e-02 1.396383e-01 1.595288e+02 +1.390657e-01 5.233483e-02 -9.888993e-01 1.495750e+02 -5.222302e-02 9.976006e-01 4.545139e-02 -8.974320e+00 9.889052e-01 4.532257e-02 1.414651e-01 1.596596e+02 +1.407442e-01 5.246468e-02 -9.886549e-01 1.486405e+02 -5.175246e-02 9.976195e-01 4.557298e-02 -8.950701e+00 9.886925e-01 4.475119e-02 1.431243e-01 1.597926e+02 +1.416215e-01 5.247161e-02 -9.885292e-01 1.477026e+02 -4.884568e-02 9.977482e-01 4.596310e-02 -8.925186e+00 9.887151e-01 4.177602e-02 1.438656e-01 1.599296e+02 +1.423187e-01 5.475913e-02 -9.883050e-01 1.467596e+02 -4.329386e-02 9.978574e-01 4.905398e-02 -8.897821e+00 9.888737e-01 3.580624e-02 1.443845e-01 1.600724e+02 +1.419490e-01 5.548381e-02 -9.883178e-01 1.458138e+02 -4.541788e-02 9.977414e-01 4.948964e-02 -8.873649e+00 9.888315e-01 3.786229e-02 1.441484e-01 1.602064e+02 +1.420415e-01 5.364591e-02 -9.884059e-01 1.448680e+02 -4.597660e-02 9.978102e-01 4.754915e-02 -8.847955e+00 9.887924e-01 3.868959e-02 1.441969e-01 1.603400e+02 +1.407854e-01 4.765972e-02 -9.888923e-01 1.439212e+02 -4.322897e-02 9.981839e-01 4.195318e-02 -8.822190e+00 9.890959e-01 3.684240e-02 1.425900e-01 1.604786e+02 +1.396641e-01 4.670739e-02 -9.890967e-01 1.429636e+02 -4.431085e-02 9.981810e-01 4.087952e-02 -8.798621e+00 9.892070e-01 3.811831e-02 1.414797e-01 1.606103e+02 +1.374422e-01 4.726901e-02 -9.893812e-01 1.420006e+02 -4.639915e-02 9.980714e-01 4.123855e-02 -8.777652e+00 9.894225e-01 4.023853e-02 1.393704e-01 1.607393e+02 +1.344706e-01 4.810825e-02 -9.897491e-01 1.410308e+02 -4.601090e-02 9.980466e-01 4.226038e-02 -8.756280e+00 9.898488e-01 3.985646e-02 1.364215e-01 1.608691e+02 +1.300187e-01 4.832619e-02 -9.903331e-01 1.400570e+02 -4.445396e-02 9.980912e-01 4.286852e-02 -8.733447e+00 9.905145e-01 3.845052e-02 1.319188e-01 1.609971e+02 +1.248943e-01 4.826542e-02 -9.909954e-01 1.390743e+02 -4.240836e-02 9.981629e-01 4.326983e-02 -8.708487e+00 9.912633e-01 3.662233e-02 1.267118e-01 1.611209e+02 +1.194921e-01 4.830138e-02 -9.916595e-01 1.380862e+02 -4.279220e-02 9.981382e-01 4.346062e-02 -8.682182e+00 9.919126e-01 3.724209e-02 1.213365e-01 1.612368e+02 +1.144482e-01 4.854149e-02 -9.922426e-01 1.370922e+02 -4.348590e-02 9.980929e-01 4.381191e-02 -8.657386e+00 9.924770e-01 3.813436e-02 1.163408e-01 1.613479e+02 +1.092936e-01 4.995155e-02 -9.927536e-01 1.360806e+02 -4.465643e-02 9.979749e-01 4.529799e-02 -8.631530e+00 9.930059e-01 3.938204e-02 1.113029e-01 1.614547e+02 +1.048231e-01 5.124421e-02 -9.931697e-01 1.350773e+02 -4.595857e-02 9.978542e-01 4.663527e-02 -8.603418e+00 9.934284e-01 4.075620e-02 1.069533e-01 1.615535e+02 +1.007483e-01 5.056303e-02 -9.936263e-01 1.340592e+02 -4.724852e-02 9.978240e-01 4.598592e-02 -8.574292e+00 9.937894e-01 4.231437e-02 1.029181e-01 1.616494e+02 +9.785650e-02 4.736967e-02 -9.940725e-01 1.330445e+02 -4.696081e-02 9.979737e-01 4.293275e-02 -8.547327e+00 9.940920e-01 4.248120e-02 9.988273e-02 1.617452e+02 +9.563679e-02 4.363838e-02 -9.944593e-01 1.320245e+02 -4.786487e-02 9.980845e-01 3.919433e-02 -8.524129e+00 9.942649e-01 4.385124e-02 9.754235e-02 1.618395e+02 +9.431008e-02 4.184760e-02 -9.946629e-01 1.309936e+02 -4.677465e-02 9.981990e-01 3.756139e-02 -8.502804e+00 9.944435e-01 4.298259e-02 9.609764e-02 1.619354e+02 +9.298430e-02 4.198922e-02 -9.947818e-01 1.299554e+02 -4.421219e-02 9.982990e-01 3.800509e-02 -8.483625e+00 9.946855e-01 4.044760e-02 9.468257e-02 1.620346e+02 +9.246214e-02 4.315501e-02 -9.947806e-01 1.289108e+02 -4.176912e-02 9.983490e-01 3.942750e-02 -8.463790e+00 9.948398e-01 3.790556e-02 9.411204e-02 1.621343e+02 +9.213294e-02 4.600333e-02 -9.946835e-01 1.278589e+02 -4.023036e-02 9.982885e-01 4.244372e-02 -8.441519e+00 9.949337e-01 3.610600e-02 9.382599e-02 1.622337e+02 +9.177952e-02 4.965796e-02 -9.945404e-01 1.268069e+02 -3.942415e-02 9.981539e-01 4.620021e-02 -8.416782e+00 9.949987e-01 3.496868e-02 9.356782e-02 1.623308e+02 +9.130294e-02 5.137790e-02 -9.944969e-01 1.257441e+02 -3.935723e-02 9.980741e-01 4.794940e-02 -8.389991e+00 9.950451e-01 3.476272e-02 9.314919e-02 1.624270e+02 +9.073127e-02 5.204663e-02 -9.945144e-01 1.246838e+02 -4.088358e-02 9.979862e-01 4.849845e-02 -8.360019e+00 9.950359e-01 3.625899e-02 9.267641e-02 1.625201e+02 +9.024189e-02 5.305791e-02 -9.945055e-01 1.236206e+02 -4.158939e-02 9.979095e-01 4.946569e-02 -8.329073e+00 9.950511e-01 3.689700e-02 9.225989e-02 1.626137e+02 +8.973410e-02 5.342104e-02 -9.945320e-01 1.225559e+02 -4.311824e-02 9.978326e-01 4.970790e-02 -8.298898e+00 9.950320e-01 3.842198e-02 9.184304e-02 1.627066e+02 +8.995780e-02 5.280626e-02 -9.945446e-01 1.214921e+02 -4.404847e-02 9.978272e-01 4.899633e-02 -8.268737e+00 9.949711e-01 3.940056e-02 9.208838e-02 1.627987e+02 +9.005473e-02 5.155388e-02 -9.946016e-01 1.204282e+02 -4.542374e-02 9.978327e-01 4.760854e-02 -8.239076e+00 9.949004e-01 4.089114e-02 9.220133e-02 1.628917e+02 +9.069168e-02 5.100355e-02 -9.945721e-01 1.193613e+02 -4.667630e-02 9.978078e-01 4.691324e-02 -8.210211e+00 9.947846e-01 4.216830e-02 9.287353e-02 1.629858e+02 +9.129817e-02 5.049914e-02 -9.945423e-01 1.182974e+02 -4.671878e-02 9.978309e-01 4.637738e-02 -8.182331e+00 9.947271e-01 4.222963e-02 9.345939e-02 1.630820e+02 +9.172991e-02 5.053843e-02 -9.945006e-01 1.172327e+02 -4.671197e-02 9.978302e-01 4.639907e-02 -8.154696e+00 9.946877e-01 4.219890e-02 9.389163e-02 1.631800e+02 +9.237238e-02 5.050306e-02 -9.944429e-01 1.161672e+02 -4.676253e-02 9.978310e-01 4.633143e-02 -8.128439e+00 9.946259e-01 4.222292e-02 9.453367e-02 1.632780e+02 +9.245599e-02 5.089538e-02 -9.944152e-01 1.151034e+02 -4.601083e-02 9.978444e-01 4.679304e-02 -8.101282e+00 9.946532e-01 4.142756e-02 9.459843e-02 1.633778e+02 +9.299006e-02 4.985239e-02 -9.944182e-01 1.140407e+02 -4.608437e-02 9.978908e-01 4.571705e-02 -8.072285e+00 9.946000e-01 4.157590e-02 9.509135e-02 1.634755e+02 +9.336966e-02 5.048937e-02 -9.943505e-01 1.129758e+02 -4.659198e-02 9.978408e-01 4.629161e-02 -8.042769e+00 9.945408e-01 4.200652e-02 9.552046e-02 1.635739e+02 +9.345763e-02 5.178683e-02 -9.942755e-01 1.119131e+02 -4.638641e-02 9.977883e-01 4.760969e-02 -8.015027e+00 9.945421e-01 4.167138e-02 9.565315e-02 1.636726e+02 +9.341358e-02 5.222291e-02 -9.942568e-01 1.108478e+02 -4.718136e-02 9.977337e-01 4.797270e-02 -7.987136e+00 9.945089e-01 4.242909e-02 9.566583e-02 1.637710e+02 +9.330696e-02 5.120099e-02 -9.943200e-01 1.097863e+02 -4.737628e-02 9.977739e-01 4.693307e-02 -7.960902e+00 9.945096e-01 4.272799e-02 9.552497e-02 1.638695e+02 +9.282502e-02 5.058085e-02 -9.943968e-01 1.087235e+02 -4.783480e-02 9.977822e-01 4.628778e-02 -7.932991e+00 9.945328e-01 4.327011e-02 9.503868e-02 1.639668e+02 +9.199095e-02 5.247703e-02 -9.943761e-01 1.076588e+02 -4.831630e-02 9.976693e-01 4.818104e-02 -7.905228e+00 9.945870e-01 4.361235e-02 9.431205e-02 1.640632e+02 +9.160984e-02 5.476418e-02 -9.942879e-01 1.065969e+02 -4.827822e-02 9.975567e-01 5.049606e-02 -7.876778e+00 9.946240e-01 4.337652e-02 9.402993e-02 1.641598e+02 +9.100643e-02 5.542605e-02 -9.943067e-01 1.055315e+02 -4.942975e-02 9.974706e-01 5.107825e-02 -7.848110e+00 9.946228e-01 4.449988e-02 9.351594e-02 1.642537e+02 +9.082692e-02 5.463806e-02 -9.943667e-01 1.044681e+02 -5.006605e-02 9.974817e-01 5.023613e-02 -7.819734e+00 9.946074e-01 4.522121e-02 9.333371e-02 1.643486e+02 +9.083917e-02 5.418997e-02 -9.943901e-01 1.034075e+02 -5.059283e-02 9.974801e-01 4.973664e-02 -7.790909e+00 9.945796e-01 4.579097e-02 9.335189e-02 1.644442e+02 +9.193206e-02 5.614195e-02 -9.941813e-01 1.023435e+02 -5.382435e-02 9.972299e-01 5.133697e-02 -7.761236e+00 9.943096e-01 4.879165e-02 9.469920e-02 1.645375e+02 +9.389641e-02 5.585586e-02 -9.940139e-01 1.012822e+02 -5.822699e-02 9.970240e-01 5.052479e-02 -7.734094e+00 9.938778e-01 5.313434e-02 9.686929e-02 1.646297e+02 +9.618327e-02 5.273932e-02 -9.939654e-01 1.002218e+02 -5.982218e-02 9.970964e-01 4.711664e-02 -7.707646e+00 9.935644e-01 5.492934e-02 9.905898e-02 1.647278e+02 +9.957027e-02 4.795344e-02 -9.938743e-01 9.916164e+01 -6.384172e-02 9.970879e-01 4.171258e-02 -7.683873e+00 9.929804e-01 5.929730e-02 1.023417e-01 1.648259e+02 +1.031570e-01 4.563701e-02 -9.936176e-01 9.809918e+01 -6.608813e-02 9.970539e-01 3.893361e-02 -7.662549e+00 9.924672e-01 6.165005e-02 1.058691e-01 1.649294e+02 +1.067455e-01 4.888621e-02 -9.930838e-01 9.703028e+01 -6.623694e-02 9.969214e-01 4.195540e-02 -7.643365e+00 9.920777e-01 6.130028e-02 1.096549e-01 1.650432e+02 +1.101696e-01 5.189540e-02 -9.925570e-01 9.595955e+01 -6.382085e-02 9.969444e-01 4.504096e-02 -7.620633e+00 9.918617e-01 5.838368e-02 1.131450e-01 1.651647e+02 +1.133369e-01 5.408013e-02 -9.920837e-01 9.489103e+01 -6.264680e-02 9.969196e-01 4.718691e-02 -7.597134e+00 9.915796e-01 5.680284e-02 1.163758e-01 1.652874e+02 +1.168930e-01 5.560950e-02 -9.915864e-01 9.381889e+01 -6.102214e-02 9.969468e-01 4.871655e-02 -7.571147e+00 9.912681e-01 5.481410e-02 1.199295e-01 1.654159e+02 +1.203524e-01 5.666828e-02 -9.911125e-01 9.274689e+01 -6.031606e-02 9.969424e-01 4.967735e-02 -7.546440e+00 9.908972e-01 5.380121e-02 1.234024e-01 1.655475e+02 +1.232347e-01 5.713858e-02 -9.907312e-01 9.167543e+01 -6.140380e-02 9.968671e-01 4.985460e-02 -7.518616e+00 9.904761e-01 5.469085e-02 1.263571e-01 1.656801e+02 +1.256953e-01 5.648039e-02 -9.904598e-01 9.059994e+01 -6.056468e-02 9.969527e-01 4.916464e-02 -7.489494e+00 9.902185e-01 5.380711e-02 1.287330e-01 1.658168e+02 +1.276885e-01 5.316740e-02 -9.903882e-01 8.952646e+01 -6.006937e-02 9.971436e-01 4.578545e-02 -7.463326e+00 9.899936e-01 5.364571e-02 1.305175e-01 1.659560e+02 +1.297312e-01 4.934365e-02 -9.903206e-01 8.845420e+01 -5.873886e-02 9.973894e-01 4.200113e-02 -7.437899e+00 9.898079e-01 5.272144e-02 1.322910e-01 1.660963e+02 +1.307576e-01 4.797751e-02 -9.902528e-01 8.737709e+01 -5.775093e-02 9.975009e-01 4.070299e-02 -7.414075e+00 9.897309e-01 5.186579e-02 1.332016e-01 1.662382e+02 +1.310039e-01 4.822964e-02 -9.902080e-01 8.629789e+01 -5.590863e-02 9.975858e-01 4.119232e-02 -7.391608e+00 9.898042e-01 4.996482e-02 1.333841e-01 1.663815e+02 +1.308390e-01 5.023524e-02 -9.901301e-01 8.521041e+01 -5.196201e-02 9.976901e-01 4.375239e-02 -7.368608e+00 9.900410e-01 4.572462e-02 1.331471e-01 1.665279e+02 +1.301935e-01 5.012963e-02 -9.902205e-01 8.412290e+01 -4.862168e-02 9.978422e-01 4.412275e-02 -7.345510e+00 9.902957e-01 4.240168e-02 1.323499e-01 1.666739e+02 +1.296342e-01 4.954566e-02 -9.903233e-01 8.303361e+01 -4.664775e-02 9.979497e-01 4.382099e-02 -7.320591e+00 9.904640e-01 4.051565e-02 1.316796e-01 1.668171e+02 +1.282816e-01 5.024529e-02 -9.904641e-01 8.194406e+01 -4.414281e-02 9.980152e-01 4.491114e-02 -7.293090e+00 9.907549e-01 3.796060e-02 1.302449e-01 1.669600e+02 +1.265446e-01 5.438578e-02 -9.904689e-01 8.084055e+01 -4.141756e-02 9.979148e-01 4.950305e-02 -7.261076e+00 9.910959e-01 3.475846e-02 1.285332e-01 1.671025e+02 +1.242457e-01 5.909282e-02 -9.904903e-01 7.973697e+01 -4.131280e-02 9.976675e-01 5.433881e-02 -7.227048e+00 9.913911e-01 3.416856e-02 1.263972e-01 1.672388e+02 +1.214012e-01 5.755162e-02 -9.909337e-01 7.863341e+01 -3.874987e-02 9.978315e-01 5.320493e-02 -7.191115e+00 9.918469e-01 3.193941e-02 1.233680e-01 1.673734e+02 +1.179264e-01 4.943599e-02 -9.917910e-01 7.753438e+01 -3.731999e-02 9.982751e-01 4.532176e-02 -7.157274e+00 9.923208e-01 3.166899e-02 1.195679e-01 1.675036e+02 +1.145747e-01 4.302380e-02 -9.924825e-01 7.642718e+01 -3.594316e-02 9.985871e-01 3.913907e-02 -7.125179e+00 9.927642e-01 3.118861e-02 1.159593e-01 1.676295e+02 +1.111380e-01 4.407895e-02 -9.928269e-01 7.530977e+01 -3.578735e-02 9.985454e-01 4.032678e-02 -7.097765e+00 9.931604e-01 3.104880e-02 1.125539e-01 1.677515e+02 +1.079476e-01 4.891668e-02 -9.929524e-01 7.417840e+01 -3.517042e-02 9.983514e-01 4.535916e-02 -7.069079e+00 9.935343e-01 3.002614e-02 1.094900e-01 1.678713e+02 +1.047190e-01 5.060110e-02 -9.932137e-01 7.305032e+01 -3.581342e-02 9.982488e-01 4.708166e-02 -7.037583e+00 9.938568e-01 3.064003e-02 1.063479e-01 1.679864e+02 +1.020028e-01 5.063064e-02 -9.934948e-01 7.191850e+01 -3.739944e-02 9.981931e-01 4.703026e-02 -7.003965e+00 9.940809e-01 3.235893e-02 1.037121e-01 1.680969e+02 +9.958313e-02 5.171041e-02 -9.936847e-01 7.078102e+01 -3.866284e-02 9.980956e-01 4.806533e-02 -6.971223e+00 9.942779e-01 3.363217e-02 1.013928e-01 1.682062e+02 +9.761616e-02 5.355269e-02 -9.937823e-01 6.964086e+01 -3.829796e-02 9.980137e-01 5.001883e-02 -6.938403e+00 9.944870e-01 3.317719e-02 9.947322e-02 1.683154e+02 +9.570258e-02 5.403422e-02 -9.939423e-01 6.849609e+01 -3.692392e-02 9.980310e-01 5.070126e-02 -6.904209e+00 9.947249e-01 3.184800e-02 9.750930e-02 1.684244e+02 +9.369140e-02 5.248042e-02 -9.942171e-01 6.734864e+01 -3.501531e-02 9.981656e-01 4.938915e-02 -6.870182e+00 9.949854e-01 3.018548e-02 9.535716e-02 1.685330e+02 +9.164190e-02 5.111850e-02 -9.944791e-01 6.619437e+01 -3.386589e-02 9.982638e-01 4.819229e-02 -6.835201e+00 9.952160e-01 2.926249e-02 9.321397e-02 1.686371e+02 +8.952336e-02 5.056587e-02 -9.947003e-01 6.503963e+01 -3.390629e-02 9.982862e-01 4.769660e-02 -6.801731e+00 9.954075e-01 2.945664e-02 9.108444e-02 1.687381e+02 +8.742620e-02 5.026994e-02 -9.949018e-01 6.387740e+01 -3.462145e-02 9.982759e-01 4.739811e-02 -6.767235e+00 9.955692e-01 3.030110e-02 8.901589e-02 1.688352e+02 +8.505502e-02 5.182365e-02 -9.950276e-01 6.271033e+01 -3.478191e-02 9.981922e-01 4.901532e-02 -6.732019e+00 9.957690e-01 3.043996e-02 8.670379e-02 1.689315e+02 +8.229342e-02 5.552726e-02 -9.950600e-01 6.154170e+01 -3.512348e-02 9.979879e-01 5.278588e-02 -6.696180e+00 9.959891e-01 3.060604e-02 8.407815e-02 1.690232e+02 +7.931965e-02 5.584538e-02 -9.952837e-01 6.037571e+01 -3.570266e-02 9.979481e-01 5.314956e-02 -6.659304e+00 9.962097e-01 3.131847e-02 8.115073e-02 1.691131e+02 +7.663835e-02 5.491694e-02 -9.955454e-01 5.921443e+01 -3.631887e-02 9.979731e-01 5.225500e-02 -6.621591e+00 9.963973e-01 3.215235e-02 7.847753e-02 1.691996e+02 +7.482343e-02 5.471044e-02 -9.956948e-01 5.805159e+01 -3.690667e-02 9.979616e-01 5.206159e-02 -6.585898e+00 9.965136e-01 3.285235e-02 7.669009e-02 1.692840e+02 +7.331485e-02 5.454013e-02 -9.958164e-01 5.689176e+01 -3.779726e-02 9.979381e-01 5.187361e-02 -6.551290e+00 9.965924e-01 3.383602e-02 7.522515e-02 1.693656e+02 +7.175939e-02 5.455297e-02 -9.959290e-01 5.573464e+01 -3.776921e-02 9.979356e-01 5.194152e-02 -6.517709e+00 9.967066e-01 3.388816e-02 7.367168e-02 1.694468e+02 +7.014483e-02 5.526427e-02 -9.960048e-01 5.457773e+01 -3.868223e-02 9.978639e-01 5.264319e-02 -6.484729e+00 9.967866e-01 3.483504e-02 7.213274e-02 1.695247e+02 +6.876069e-02 5.601098e-02 -9.960596e-01 5.342406e+01 -3.825727e-02 9.978363e-01 5.346990e-02 -6.451831e+00 9.968994e-01 3.442989e-02 7.075475e-02 1.696041e+02 +6.788744e-02 5.535910e-02 -9.961559e-01 5.227198e+01 -3.721840e-02 9.979049e-01 5.291990e-02 -6.419650e+00 9.969986e-01 3.348273e-02 6.980559e-02 1.696819e+02 +6.668189e-02 5.428922e-02 -9.962962e-01 5.112484e+01 -3.821987e-02 9.979248e-01 5.181993e-02 -6.387439e+00 9.970420e-01 3.462286e-02 6.861844e-02 1.697562e+02 +6.556135e-02 5.369363e-02 -9.964029e-01 4.997639e+01 -3.719948e-02 9.979886e-01 5.133144e-02 -6.354550e+00 9.971549e-01 3.370030e-02 6.742686e-02 1.698313e+02 +6.428504e-02 5.168373e-02 -9.965923e-01 4.883352e+01 -3.796777e-02 9.980615e-01 4.931084e-02 -6.324190e+00 9.972091e-01 3.466843e-02 6.612275e-02 1.699034e+02 +6.378249e-02 4.683523e-02 -9.968642e-01 4.769988e+01 -3.594333e-02 9.983578e-01 4.460565e-02 -6.297182e+00 9.973164e-01 3.298555e-02 6.536116e-02 1.699755e+02 +6.248296e-02 4.389177e-02 -9.970804e-01 4.656422e+01 -3.553109e-02 9.984970e-01 4.172756e-02 -6.272495e+00 9.974134e-01 3.282009e-02 6.394857e-02 1.700463e+02 +6.155443e-02 4.360457e-02 -9.971508e-01 4.543186e+01 -3.409010e-02 9.985542e-01 4.156156e-02 -6.250107e+00 9.975214e-01 3.143467e-02 6.295192e-02 1.701164e+02 +5.979951e-02 4.844629e-02 -9.970341e-01 4.429936e+01 -3.195249e-02 9.984026e-01 4.659637e-02 -6.226617e+00 9.976989e-01 2.907128e-02 6.125197e-02 1.701873e+02 +5.847737e-02 5.025798e-02 -9.970228e-01 4.317387e+01 -3.084696e-02 9.983460e-01 4.851546e-02 -6.202174e+00 9.978121e-01 2.791807e-02 5.993096e-02 1.702539e+02 +5.710160e-02 5.172366e-02 -9.970276e-01 4.205161e+01 -3.086545e-02 9.982711e-01 5.002046e-02 -6.174770e+00 9.978912e-01 2.791746e-02 5.859935e-02 1.703153e+02 +5.571362e-02 5.203692e-02 -9.970898e-01 4.094509e+01 -3.192121e-02 9.982232e-01 5.031245e-02 -6.147108e+00 9.979364e-01 2.902523e-02 5.727572e-02 1.703738e+02 +5.455351e-02 5.309891e-02 -9.970980e-01 3.983916e+01 -3.298317e-02 9.981359e-01 5.134961e-02 -6.117455e+00 9.979660e-01 3.008615e-02 5.620319e-02 1.704305e+02 +5.312200e-02 5.641953e-02 -9.969929e-01 3.874245e+01 -3.639476e-02 9.978487e-01 5.452878e-02 -6.088215e+00 9.979246e-01 3.338864e-02 5.506110e-02 1.704827e+02 +5.195736e-02 5.754698e-02 -9.969898e-01 3.766296e+01 -3.781275e-02 9.977357e-01 5.561947e-02 -6.057652e+00 9.979332e-01 3.480909e-02 5.401573e-02 1.705334e+02 +5.087432e-02 5.709580e-02 -9.970716e-01 3.659221e+01 -3.888075e-02 9.977208e-01 5.514915e-02 -6.026683e+00 9.979480e-01 3.596121e-02 5.297830e-02 1.705825e+02 +4.982437e-02 5.711482e-02 -9.971236e-01 3.553534e+01 -4.023535e-02 9.976679e-01 5.513553e-02 -5.996165e+00 9.979473e-01 3.737251e-02 5.200621e-02 1.706297e+02 +4.833475e-02 5.768322e-02 -9.971642e-01 3.449412e+01 -4.167267e-02 9.975782e-01 5.568722e-02 -5.965499e+00 9.979615e-01 3.886286e-02 5.062151e-02 1.706738e+02 +4.654474e-02 5.854169e-02 -9.971993e-01 3.346274e+01 -4.264783e-02 9.974874e-01 5.656802e-02 -5.935626e+00 9.980054e-01 3.989544e-02 4.892448e-02 1.707175e+02 +4.453633e-02 5.962024e-02 -9.972271e-01 3.246088e+01 -4.293138e-02 9.974096e-01 5.771384e-02 -5.905360e+00 9.980849e-01 4.024197e-02 4.698055e-02 1.707583e+02 +4.273252e-02 6.003956e-02 -9.972809e-01 3.146543e+01 -4.417114e-02 9.973302e-01 5.814985e-02 -5.875136e+00 9.981097e-01 4.156614e-02 4.527045e-02 1.707951e+02 +4.110748e-02 5.999665e-02 -9.973518e-01 3.048833e+01 -4.473342e-02 9.973051e-01 5.815010e-02 -5.845567e+00 9.981529e-01 4.222454e-02 4.368056e-02 1.708291e+02 +3.911370e-02 5.939368e-02 -9.974680e-01 2.952698e+01 -4.554089e-02 9.973006e-01 5.759793e-02 -5.815888e+00 9.981965e-01 4.317271e-02 4.171296e-02 1.708627e+02 +3.721009e-02 5.880801e-02 -9.975756e-01 2.857775e+01 -4.550466e-02 9.973311e-01 5.709626e-02 -5.787166e+00 9.982709e-01 4.326978e-02 3.978682e-02 1.708950e+02 +3.538692e-02 5.835357e-02 -9.976686e-01 2.765026e+01 -4.537798e-02 9.973580e-01 5.672588e-02 -5.760157e+00 9.983430e-01 4.326483e-02 3.794140e-02 1.709265e+02 +3.385785e-02 5.807907e-02 -9.977377e-01 2.673632e+01 -4.580615e-02 9.973511e-01 5.650217e-02 -5.734750e+00 9.983764e-01 4.378948e-02 3.642854e-02 1.709550e+02 +3.285308e-02 5.872234e-02 -9.977336e-01 2.583869e+01 -4.736218e-02 9.972424e-01 5.713392e-02 -5.709218e+00 9.983374e-01 4.537780e-02 3.554371e-02 1.709809e+02 +3.275709e-02 5.921482e-02 -9.977076e-01 2.496030e+01 -4.875553e-02 9.971496e-01 5.758095e-02 -5.685086e+00 9.982735e-01 4.675758e-02 3.555077e-02 1.710072e+02 +3.347069e-02 5.889310e-02 -9.977030e-01 2.409664e+01 -5.122721e-02 9.970512e-01 5.713609e-02 -5.661564e+00 9.981260e-01 4.919715e-02 3.638893e-02 1.710324e+02 +3.614948e-02 5.837431e-02 -9.976400e-01 2.325295e+01 -5.279407e-02 9.970100e-01 5.642447e-02 -5.641612e+00 9.979509e-01 5.062976e-02 3.912322e-02 1.710614e+02 +4.020123e-02 5.717992e-02 -9.975542e-01 2.241755e+01 -5.446173e-02 9.970025e-01 5.495352e-02 -5.619879e+00 9.977063e-01 5.211932e-02 4.319485e-02 1.710938e+02 +4.577637e-02 5.651786e-02 -9.973516e-01 2.159952e+01 -5.509678e-02 9.970213e-01 5.397033e-02 -5.600759e+00 9.974312e-01 5.248029e-02 4.875397e-02 1.711323e+02 +5.256416e-02 5.593832e-02 -9.970496e-01 2.079122e+01 -5.718776e-02 9.969600e-01 5.291839e-02 -5.580908e+00 9.969788e-01 5.423742e-02 5.560335e-02 1.711744e+02 +6.071134e-02 5.603308e-02 -9.965814e-01 2.002074e+01 -5.739221e-02 9.969672e-01 5.255848e-02 -5.563485e+00 9.965041e-01 5.400510e-02 6.374308e-02 1.712401e+02 +6.769746e-02 5.630921e-02 -9.961156e-01 1.931659e+01 -5.470380e-02 9.971137e-01 5.264789e-02 -5.549652e+00 9.962051e-01 5.092717e-02 7.058239e-02 1.713446e+02 +7.469073e-02 5.654437e-02 -9.956023e-01 1.861169e+01 -5.201030e-02 9.972531e-01 5.273629e-02 -5.535798e+00 9.958495e-01 4.784266e-02 7.742646e-02 1.714492e+02 +8.168416e-02 5.673823e-02 -9.950419e-01 1.790668e+01 -4.931423e-02 9.973854e-01 5.282361e-02 -5.521934e+00 9.954375e-01 4.475487e-02 8.426860e-02 1.715538e+02 +8.867532e-02 5.689069e-02 -9.944346e-01 1.720176e+01 -4.661634e-02 9.975106e-01 5.290983e-02 -5.508066e+00 9.949692e-01 4.166510e-02 9.110661e-02 1.716584e+02 +9.565362e-02 5.700162e-02 -9.937812e-01 1.649795e+01 -4.392054e-02 9.976284e-01 5.299486e-02 -5.494212e+00 9.944453e-01 3.857825e-02 9.793032e-02 1.717627e+02 +1.026291e-01 5.707125e-02 -9.930811e-01 1.579417e+01 -4.122276e-02 9.977391e-01 5.307882e-02 -5.480351e+00 9.938652e-01 3.549011e-02 1.047497e-01 1.718671e+02 +1.096072e-01 5.709955e-02 -9.923335e-01 1.508984e+01 -3.852072e-02 9.978426e-01 5.316180e-02 -5.466472e+00 9.932283e-01 3.239848e-02 1.115703e-01 1.719715e+02 +1.165755e-01 5.708648e-02 -9.915398e-01 1.438616e+01 -3.581905e-02 9.979389e-01 5.324366e-02 -5.452598e+00 9.925357e-01 2.930911e-02 1.183800e-01 1.720758e+02 +1.235353e-01 5.703212e-02 -9.906999e-01 1.368293e+01 -3.311708e-02 9.980279e-01 5.332445e-02 -5.438726e+00 9.917875e-01 2.622163e-02 1.251804e-01 1.721799e+02 +1.304837e-01 5.693657e-02 -9.898142e-01 1.298042e+01 -3.041573e-02 9.981096e-01 5.340416e-02 -5.424859e+00 9.909838e-01 2.313755e-02 1.319688e-01 1.722840e+02 +1.374345e-01 5.679961e-02 -9.888809e-01 1.227716e+01 -2.770946e-02 9.981842e-01 5.348293e-02 -5.410970e+00 9.901232e-01 2.005095e-02 1.387589e-01 1.723881e+02 +1.443711e-01 5.662159e-02 -9.879023e-01 1.157479e+01 -2.500456e-02 9.982515e-01 5.356062e-02 -5.397090e+00 9.892077e-01 1.696946e-02 1.455345e-01 1.724921e+02 +1.513018e-01 5.640235e-02 -9.868771e-01 1.087241e+01 -2.229760e-02 9.983115e-01 5.363733e-02 -5.383201e+00 9.882361e-01 1.388956e-02 1.523040e-01 1.725960e+02 +1.582240e-01 5.614198e-02 -9.858059e-01 1.017025e+01 -1.958945e-02 9.983642e-01 5.371305e-02 -5.369307e+00 9.872089e-01 1.081270e-02 1.590650e-01 1.726999e+02 +1.678550e-01 5.557054e-02 -9.842442e-01 9.442106e+00 -1.678890e-02 9.984262e-01 5.350806e-02 -5.355689e+00 9.856688e-01 7.542788e-03 1.685238e-01 1.728058e+02 +1.644072e-01 5.627268e-02 -9.847861e-01 8.838192e+00 -1.441109e-02 9.984018e-01 5.464483e-02 -5.340640e+00 9.862873e-01 5.207841e-03 1.649554e-01 1.729076e+02 +1.602748e-01 5.668891e-02 -9.854432e-01 8.251533e+00 -1.219796e-02 9.983869e-01 5.544963e-02 -5.327136e+00 9.869971e-01 3.133217e-03 1.607078e-01 1.730023e+02 +1.559035e-01 5.750915e-02 -9.860967e-01 7.682227e+00 -9.671340e-03 9.983447e-01 5.669441e-02 -5.313490e+00 9.877250e-01 6.980249e-04 1.562016e-01 1.730935e+02 +1.514312e-01 5.879348e-02 -9.867177e-01 7.132350e+00 -7.743005e-03 9.982694e-01 5.829349e-02 -5.302335e+00 9.884375e-01 -1.187289e-03 1.516244e-01 1.731770e+02 +1.470903e-01 5.932298e-02 -9.873425e-01 6.605054e+00 -5.901521e-03 9.982347e-01 5.909825e-02 -5.290740e+00 9.891055e-01 -2.865955e-03 1.471808e-01 1.732539e+02 +1.424242e-01 5.940185e-02 -9.880216e-01 6.095177e+00 -4.962078e-03 9.982278e-01 5.930020e-02 -5.276949e+00 9.897933e-01 -3.543136e-03 1.424665e-01 1.733230e+02 +1.378247e-01 5.920784e-02 -9.886854e-01 5.611287e+00 -4.315251e-03 9.982381e-01 5.917837e-02 -5.263627e+00 9.904473e-01 -3.889808e-03 1.378373e-01 1.733874e+02 +1.336522e-01 5.771869e-02 -9.893460e-01 5.150884e+00 -3.528036e-03 9.983239e-01 5.776587e-02 -5.252069e+00 9.910220e-01 -4.230084e-03 1.336319e-01 1.734464e+02 +1.294784e-01 5.537462e-02 -9.900348e-01 4.717735e+00 -3.721820e-03 9.984595e-01 5.535910e-02 -5.242680e+00 9.915753e-01 -3.483070e-03 1.294850e-01 1.734989e+02 +1.254016e-01 5.336216e-02 -9.906699e-01 4.309371e+00 -4.719002e-03 9.985732e-01 5.319054e-02 -5.233773e+00 9.920949e-01 -1.995203e-03 1.254745e-01 1.735445e+02 +1.213571e-01 5.228134e-02 -9.912311e-01 3.925632e+00 -5.109158e-03 9.986316e-01 5.204617e-02 -5.223780e+00 9.925958e-01 -1.251811e-03 1.214581e-01 1.735834e+02 +1.178478e-01 5.140332e-02 -9.917003e-01 3.568804e+00 -4.941005e-03 9.986773e-01 5.117781e-02 -5.214912e+00 9.930194e-01 -1.131192e-03 1.179459e-01 1.736202e+02 +1.147456e-01 5.014571e-02 -9.921284e-01 3.237420e+00 -5.445882e-03 9.987418e-01 4.985014e-02 -5.206743e+00 9.933800e-01 -3.170653e-04 1.148743e-01 1.736519e+02 +1.117142e-01 4.942317e-02 -9.925106e-01 2.929190e+00 -6.177276e-03 9.987777e-01 4.903997e-02 -5.200240e+00 9.937212e-01 6.525532e-04 1.118830e-01 1.736803e+02 +1.087120e-01 4.920781e-02 -9.928546e-01 2.641612e+00 -7.790670e-03 9.987855e-01 4.864874e-02 -5.195601e+00 9.940428e-01 2.446303e-03 1.089634e-01 1.737054e+02 +1.063078e-01 4.937517e-02 -9.931066e-01 2.375838e+00 -9.341319e-03 9.987718e-01 4.865689e-02 -5.192040e+00 9.942894e-01 4.104324e-03 1.066384e-01 1.737296e+02 +1.037963e-01 4.897444e-02 -9.933921e-01 2.130640e+00 -9.840876e-03 9.987886e-01 4.821227e-02 -5.188621e+00 9.945499e-01 4.771597e-03 1.041525e-01 1.737531e+02 +1.016003e-01 4.831348e-02 -9.936514e-01 1.899632e+00 -9.693821e-03 9.988207e-01 4.757364e-02 -5.186109e+00 9.947781e-01 4.798787e-03 1.019488e-01 1.737763e+02 +9.971754e-02 4.676162e-02 -9.939164e-01 1.679549e+00 -9.449490e-03 9.988945e-01 4.604780e-02 -5.183851e+00 9.949709e-01 4.800233e-03 1.000492e-01 1.737991e+02 +9.755992e-02 4.451779e-02 -9.942335e-01 1.465756e+00 -9.787771e-03 9.989936e-01 4.377052e-02 -5.181795e+00 9.951816e-01 5.461085e-03 9.789747e-02 1.738189e+02 +9.567819e-02 4.300650e-02 -9.944828e-01 1.258618e+00 -9.495462e-03 9.990602e-01 4.229091e-02 -5.179715e+00 9.953671e-01 5.396759e-03 9.599665e-02 1.738391e+02 +9.380379e-02 4.254270e-02 -9.946813e-01 1.056923e+00 -8.588526e-03 9.990840e-01 4.192107e-02 -5.178565e+00 9.955537e-01 4.610494e-03 9.408325e-02 1.738596e+02 +9.180630e-02 4.140556e-02 -9.949156e-01 8.596177e-01 -7.747839e-03 9.991346e-01 4.086622e-02 -5.177557e+00 9.957468e-01 3.956673e-03 9.204766e-02 1.738793e+02 +8.964802e-02 3.956255e-02 -9.951874e-01 6.630867e-01 -8.380303e-03 9.992053e-01 3.896737e-02 -5.175312e+00 9.959383e-01 4.846627e-03 8.990833e-02 1.738951e+02 +8.756390e-02 3.830922e-02 -9.954220e-01 4.652170e-01 -9.321546e-03 9.992480e-01 3.763649e-02 -5.169903e+00 9.961153e-01 5.983277e-03 8.785515e-02 1.739093e+02 +8.550485e-02 3.850399e-02 -9.955935e-01 2.667551e-01 -9.108521e-03 9.992414e-01 3.786281e-02 -5.164967e+00 9.962962e-01 5.830933e-03 8.579071e-02 1.739252e+02 +8.358815e-02 3.912330e-02 -9.957321e-01 6.863829e-02 -7.394709e-03 9.992258e-01 3.863982e-02 -5.160977e+00 9.964730e-01 4.133322e-03 8.381274e-02 1.739441e+02 +8.164541e-02 3.952867e-02 -9.958772e-01 -1.280297e-01 -5.881578e-03 9.992149e-01 3.917897e-02 -5.158165e+00 9.966441e-01 2.658550e-03 8.181381e-02 1.739624e+02 +7.957411e-02 3.997896e-02 -9.960269e-01 -3.247859e-01 -4.953341e-03 9.991989e-01 3.971056e-02 -5.154852e+00 9.968167e-01 1.773732e-03 7.970840e-02 1.739782e+02 +7.728217e-02 4.047508e-02 -9.961873e-01 -5.227320e-01 -4.544781e-03 9.991795e-01 4.024409e-02 -5.147631e+00 9.969989e-01 1.417306e-03 7.740271e-02 1.739917e+02 +7.479722e-02 4.089563e-02 -9.963598e-01 -7.202299e-01 -4.692259e-03 9.991621e-01 4.065841e-02 -5.142031e+00 9.971878e-01 1.634046e-03 7.492644e-02 1.740033e+02 +7.237150e-02 4.160935e-02 -9.965094e-01 -9.175144e-01 -5.979377e-03 9.991295e-01 4.128452e-02 -5.136067e+00 9.973599e-01 2.970686e-03 7.255730e-02 1.740126e+02 +6.943028e-02 4.183027e-02 -9.967094e-01 -1.118271e+00 -9.638814e-03 9.991020e-01 4.125926e-02 -5.131393e+00 9.975403e-01 6.742458e-03 6.977112e-02 1.740188e+02 +6.619844e-02 3.799900e-02 -9.970826e-01 -1.330594e+00 -1.375232e-02 9.992144e-01 3.716721e-02 -5.124737e+00 9.977117e-01 1.125179e-02 6.666901e-02 1.740238e+02 +6.296457e-02 3.347512e-02 -9.974542e-01 -1.559395e+00 -1.602838e-02 9.993423e-01 3.252670e-02 -5.120339e+00 9.978871e-01 1.393955e-02 6.345972e-02 1.740325e+02 +5.971183e-02 3.114948e-02 -9.977295e-01 -1.809787e+00 -1.664160e-02 9.994051e-01 3.020584e-02 -5.114207e+00 9.980770e-01 1.480017e-02 6.019469e-02 1.740434e+02 +5.616226e-02 3.130754e-02 -9.979307e-01 -2.080426e+00 -1.725221e-02 9.993894e-01 3.038238e-02 -5.109835e+00 9.982726e-01 1.551017e-02 5.666809e-02 1.740552e+02 +5.249161e-02 3.113252e-02 -9.981359e-01 -2.369588e+00 -1.736092e-02 9.993913e-01 3.025868e-02 -5.104338e+00 9.984705e-01 1.574023e-02 5.300015e-02 1.740678e+02 +4.882708e-02 2.958876e-02 -9.983689e-01 -2.673890e+00 -1.675079e-02 9.994448e-01 2.880143e-02 -5.098500e+00 9.986668e-01 1.531718e-02 4.929561e-02 1.740820e+02 +4.541782e-02 2.745822e-02 -9.985906e-01 -2.997577e+00 -1.652581e-02 9.995060e-01 2.673177e-02 -5.089512e+00 9.988314e-01 1.528842e-02 4.584916e-02 1.740946e+02 +4.248984e-02 2.506957e-02 -9.987823e-01 -3.339694e+00 -1.853442e-02 9.995329e-01 2.429994e-02 -5.081152e+00 9.989250e-01 1.747935e-02 4.293464e-02 1.741046e+02 +4.064887e-02 2.315191e-02 -9.989052e-01 -3.708094e+00 -2.172741e-02 9.995156e-01 2.228190e-02 -5.070678e+00 9.989373e-01 2.079789e-02 4.113221e-02 1.741128e+02 +4.084734e-02 2.136928e-02 -9.989368e-01 -4.098643e+00 -2.576149e-02 9.994614e-01 2.032710e-02 -5.061584e+00 9.988333e-01 2.490380e-02 4.137585e-02 1.741207e+02 +4.168056e-02 2.108907e-02 -9.989084e-01 -4.512924e+00 -2.912763e-02 9.993779e-01 1.988361e-02 -5.054777e+00 9.987064e-01 2.826708e-02 4.226890e-02 1.741316e+02 +4.265705e-02 2.320017e-02 -9.988204e-01 -4.953445e+00 -3.028000e-02 9.993011e-01 2.191817e-02 -5.048170e+00 9.986308e-01 2.930932e-02 4.332974e-02 1.741479e+02 +4.357429e-02 2.713487e-02 -9.986816e-01 -5.416520e+00 -2.969292e-02 9.992246e-01 2.585408e-02 -5.038620e+00 9.986089e-01 2.852720e-02 4.434622e-02 1.741680e+02 +4.470928e-02 3.229237e-02 -9.984780e-01 -5.904319e+00 -3.097181e-02 9.990417e-01 3.092378e-02 -5.026226e+00 9.985199e-01 2.954209e-02 4.566660e-02 1.741874e+02 +4.636357e-02 3.671219e-02 -9.982498e-01 -6.410143e+00 -3.328429e-02 9.988263e-01 3.518752e-02 -5.010688e+00 9.983700e-01 3.159461e-02 4.753110e-02 1.742043e+02 +4.694403e-02 4.227241e-02 -9.980026e-01 -6.936037e+00 -3.277020e-02 9.986315e-01 4.075761e-02 -4.995569e+00 9.983599e-01 3.079142e-02 4.826506e-02 1.742283e+02 +4.754141e-02 4.752781e-02 -9.977379e-01 -7.478197e+00 -2.571871e-02 9.985944e-01 4.634315e-02 -4.980210e+00 9.985381e-01 2.345731e-02 4.869694e-02 1.742632e+02 +4.873112e-02 4.739810e-02 -9.976867e-01 -8.034194e+00 -1.585092e-02 9.987843e-01 4.667604e-02 -4.963354e+00 9.986862e-01 1.353968e-02 4.942319e-02 1.743031e+02 +4.876975e-02 4.603159e-02 -9.977488e-01 -8.609358e+00 -9.108030e-03 9.989164e-01 4.564027e-02 -4.943192e+00 9.987686e-01 6.861663e-03 4.913617e-02 1.743404e+02 +4.712329e-02 4.437370e-02 -9.979030e-01 -9.205893e+00 -1.060441e-02 9.989787e-01 4.392079e-02 -4.919748e+00 9.988328e-01 8.512478e-03 4.754572e-02 1.743635e+02 +4.594391e-02 4.240758e-02 -9.980434e-01 -9.824702e+00 -1.355701e-02 9.990329e-01 4.182555e-02 -4.895504e+00 9.988521e-01 1.160886e-02 4.647440e-02 1.743826e+02 +4.402943e-02 4.243316e-02 -9.981287e-01 -1.046398e+01 -9.152766e-03 9.990727e-01 4.206956e-02 -4.868631e+00 9.989883e-01 7.283341e-03 4.437699e-02 1.744130e+02 +4.122416e-02 4.624954e-02 -9.980789e-01 -1.112470e+01 -8.564781e-05 9.989282e-01 4.628537e-02 -4.841195e+00 9.991500e-01 -1.822588e-03 4.118394e-02 1.744515e+02 +3.863112e-02 4.751964e-02 -9.981230e-01 -1.180349e+01 2.760929e-03 9.988597e-01 4.766158e-02 -4.813690e+00 9.992498e-01 -4.596962e-03 3.845587e-02 1.744789e+02 +3.622467e-02 4.568595e-02 -9.982988e-01 -1.249423e+01 1.010142e-03 9.989523e-01 4.575252e-02 -4.794972e+00 9.993432e-01 -2.665789e-03 3.614057e-02 1.744950e+02 +3.269816e-02 3.699546e-02 -9.987803e-01 -1.320023e+01 -2.524526e-03 9.993145e-01 3.693261e-02 -4.777646e+00 9.994621e-01 1.313822e-03 3.276915e-02 1.745107e+02 +3.075309e-02 2.590013e-02 -9.991914e-01 -1.391906e+01 -4.485341e-03 9.996577e-01 2.577417e-02 -4.756739e+00 9.995170e-01 3.689082e-03 3.085874e-02 1.745275e+02 +3.044179e-02 1.999842e-02 -9.993364e-01 -1.466259e+01 -6.913657e-03 9.997801e-01 1.979670e-02 -4.737636e+00 9.995127e-01 6.306425e-03 3.057336e-02 1.745442e+02 +2.937959e-02 2.382640e-02 -9.992843e-01 -1.543104e+01 -4.559240e-03 9.997086e-01 2.370248e-02 -4.723469e+00 9.995580e-01 3.859611e-03 2.947966e-02 1.745678e+02 +2.852303e-02 3.076663e-02 -9.991195e-01 -1.622230e+01 -2.767724e-03 9.995248e-01 3.070010e-02 -4.710841e+00 9.995893e-01 1.889631e-03 2.859463e-02 1.745912e+02 +2.774086e-02 3.654470e-02 -9.989469e-01 -1.702851e+01 -2.245853e-03 9.993312e-01 3.649640e-02 -4.696235e+00 9.996127e-01 1.231051e-03 2.780439e-02 1.746127e+02 +2.612532e-02 3.399131e-02 -9.990806e-01 -1.784141e+01 -5.419776e-03 9.994118e-01 3.386087e-02 -4.678436e+00 9.996440e-01 4.530171e-03 2.629418e-02 1.746282e+02 +2.510668e-02 2.985506e-02 -9.992389e-01 -1.867406e+01 -8.047020e-03 9.995276e-01 2.966150e-02 -4.659978e+00 9.996524e-01 7.296196e-03 2.533506e-02 1.746415e+02 +2.394480e-02 2.644220e-02 -9.993635e-01 -1.951549e+01 -7.779460e-03 9.996248e-01 2.626273e-02 -4.643082e+00 9.996830e-01 7.145656e-03 2.414152e-02 1.746569e+02 +2.316508e-02 2.750533e-02 -9.993532e-01 -2.038192e+01 -8.421416e-03 9.995913e-01 2.731668e-02 -4.629105e+00 9.996962e-01 7.783179e-03 2.338725e-02 1.746705e+02 +2.261650e-02 3.207984e-02 -9.992294e-01 -2.126296e+01 -1.045922e-02 9.994379e-01 3.184981e-02 -4.615818e+00 9.996895e-01 9.730829e-03 2.293932e-02 1.746811e+02 +2.174708e-02 3.565069e-02 -9.991276e-01 -2.215315e+01 -1.064328e-02 9.993156e-01 3.542575e-02 -4.599401e+00 9.997069e-01 9.863590e-03 2.211164e-02 1.746945e+02 +2.111917e-02 3.728059e-02 -9.990816e-01 -2.305412e+01 -9.541193e-03 9.992665e-01 3.708581e-02 -4.580094e+00 9.997315e-01 8.749211e-03 2.145938e-02 1.747108e+02 +2.077065e-02 3.996125e-02 -9.989853e-01 -2.396755e+01 -1.038214e-02 9.991556e-01 3.975221e-02 -4.560584e+00 9.997304e-01 9.545929e-03 2.116800e-02 1.747231e+02 +2.108223e-02 4.071708e-02 -9.989483e-01 -2.489170e+01 -9.987631e-03 9.991290e-01 4.051368e-02 -4.540819e+00 9.997279e-01 9.123010e-03 2.147054e-02 1.747368e+02 +2.197904e-02 3.832236e-02 -9.990237e-01 -2.582517e+01 -1.200682e-02 9.992031e-01 3.806510e-02 -4.522439e+00 9.996864e-01 1.115847e-02 2.242166e-02 1.747521e+02 +2.362595e-02 3.575806e-02 -9.990811e-01 -2.677027e+01 -1.267589e-02 9.992905e-01 3.546581e-02 -4.501933e+00 9.996405e-01 1.182633e-02 2.406245e-02 1.747678e+02 +2.505914e-02 3.494184e-02 -9.990751e-01 -2.772847e+01 -1.326893e-02 9.993125e-01 3.461734e-02 -4.479683e+00 9.995979e-01 1.238918e-02 2.550555e-02 1.747877e+02 +2.680752e-02 3.756858e-02 -9.989344e-01 -2.869788e+01 -1.295330e-02 9.992227e-01 3.723182e-02 -4.458410e+00 9.995567e-01 1.194141e-02 2.727333e-02 1.748119e+02 +2.870076e-02 3.889089e-02 -9.988312e-01 -2.968056e+01 -1.302835e-02 9.991725e-01 3.852983e-02 -4.437364e+00 9.995032e-01 1.190729e-02 2.918370e-02 1.748403e+02 +3.049470e-02 4.004975e-02 -9.987322e-01 -3.066883e+01 -1.307021e-02 9.991275e-01 3.966653e-02 -4.414338e+00 9.994495e-01 1.184402e-02 3.099155e-02 1.748694e+02 +3.195026e-02 3.970961e-02 -9.987003e-01 -3.166430e+01 -1.233768e-02 9.991500e-01 3.933280e-02 -4.389732e+00 9.994133e-01 1.106496e-02 3.241303e-02 1.749013e+02 +3.310467e-02 3.975758e-02 -9.986608e-01 -3.266632e+01 -1.113711e-02 9.991611e-01 3.940832e-02 -4.365966e+00 9.993899e-01 9.817602e-03 3.351969e-02 1.749346e+02 +3.372018e-02 3.916399e-02 -9.986637e-01 -3.367114e+01 -1.001341e-02 9.991950e-01 3.884673e-02 -4.343190e+00 9.993812e-01 8.690108e-03 3.408520e-02 1.749701e+02 +3.368258e-02 3.854813e-02 -9.986889e-01 -3.468647e+01 -9.467255e-03 9.992233e-01 3.824947e-02 -4.321067e+00 9.993878e-01 8.166504e-03 3.402136e-02 1.750048e+02 +3.342323e-02 3.845845e-02 -9.987011e-01 -3.570777e+01 -9.654451e-03 9.992251e-01 3.815554e-02 -4.299213e+00 9.993947e-01 8.366632e-03 3.376863e-02 1.750396e+02 +3.283526e-02 4.017233e-02 -9.986531e-01 -3.673469e+01 -8.467469e-03 9.991672e-01 3.991462e-02 -4.276039e+00 9.994249e-01 7.145460e-03 3.314808e-02 1.750748e+02 +3.177846e-02 4.061714e-02 -9.986693e-01 -3.776504e+01 -1.167395e-02 9.991209e-01 4.026404e-02 -4.256725e+00 9.994268e-01 1.037888e-02 3.222468e-02 1.751053e+02 +3.104251e-02 3.919953e-02 -9.987491e-01 -3.880365e+01 -1.382125e-02 9.991519e-01 3.878577e-02 -4.234575e+00 9.994225e-01 1.259995e-02 3.155797e-02 1.751336e+02 +3.023219e-02 3.661676e-02 -9.988720e-01 -3.984361e+01 -1.342788e-02 9.992534e-01 3.622434e-02 -4.212951e+00 9.994527e-01 1.231760e-02 3.070131e-02 1.751657e+02 +2.965356e-02 3.752536e-02 -9.988556e-01 -4.089475e+01 -1.472322e-02 9.992030e-01 3.710133e-02 -4.191574e+00 9.994518e-01 1.360619e-02 3.018242e-02 1.751957e+02 +2.914151e-02 4.077818e-02 -9.987432e-01 -4.194839e+01 -1.734835e-02 9.990376e-01 4.028403e-02 -4.169419e+00 9.994248e-01 1.615261e-02 2.982090e-02 1.752215e+02 +2.866815e-02 4.197664e-02 -9.987072e-01 -4.300116e+01 -1.738466e-02 9.989877e-01 4.148941e-02 -4.148064e+00 9.994378e-01 1.617276e-02 2.936888e-02 1.752525e+02 +2.893629e-02 4.201429e-02 -9.986979e-01 -4.406189e+01 -1.470047e-02 9.990261e-01 4.160218e-02 -4.119551e+00 9.994732e-01 1.347752e-02 2.952574e-02 1.752855e+02 +2.925195e-02 4.363017e-02 -9.986194e-01 -4.512250e+01 -1.381052e-02 9.989692e-01 4.324092e-02 -4.093854e+00 9.994767e-01 1.252658e-02 2.982435e-02 1.753188e+02 +2.971507e-02 4.552394e-02 -9.985212e-01 -4.618491e+01 -1.321181e-02 9.988929e-01 4.514773e-02 -4.070273e+00 9.994711e-01 1.185070e-02 3.028363e-02 1.753517e+02 +2.974324e-02 4.483819e-02 -9.985514e-01 -4.724820e+01 -1.272301e-02 9.989294e-01 4.447621e-02 -4.044487e+00 9.994766e-01 1.138172e-02 3.028187e-02 1.753850e+02 +2.939511e-02 4.495536e-02 -9.985564e-01 -4.830951e+01 -1.431165e-02 9.989046e-01 4.454975e-02 -4.018245e+00 9.994654e-01 1.298145e-02 3.000630e-02 1.754145e+02 +2.951419e-02 4.330502e-02 -9.986258e-01 -4.937440e+01 -1.641797e-02 9.989473e-01 4.283374e-02 -3.993183e+00 9.994296e-01 1.513120e-02 3.019410e-02 1.754431e+02 +2.968646e-02 4.067632e-02 -9.987313e-01 -5.043287e+01 -1.867141e-02 9.990199e-01 4.013309e-02 -3.971419e+00 9.993849e-01 1.745631e-02 3.041685e-02 1.754697e+02 +2.954366e-02 3.937763e-02 -9.987875e-01 -5.149310e+01 -2.201678e-02 9.990069e-01 3.873505e-02 -3.950335e+00 9.993210e-01 2.084571e-02 3.038129e-02 1.754987e+02 +2.923623e-02 4.304215e-02 -9.986454e-01 -5.255744e+01 -2.526006e-02 9.987852e-01 4.230868e-02 -3.927044e+00 9.992533e-01 2.398890e-02 3.028796e-02 1.755260e+02 +2.872337e-02 5.084768e-02 -9.982933e-01 -5.362657e+01 -2.496244e-02 9.984304e-01 5.013644e-02 -3.898270e+00 9.992757e-01 2.347974e-02 2.994757e-02 1.755580e+02 +2.838374e-02 5.856674e-02 -9.978799e-01 -5.469552e+01 -2.533761e-02 9.980035e-01 5.785331e-02 -3.863223e+00 9.992760e-01 2.364180e-02 2.981101e-02 1.755883e+02 +2.813393e-02 5.820132e-02 -9.979083e-01 -5.575759e+01 -2.739037e-02 9.979735e-01 5.743292e-02 -3.825657e+00 9.992289e-01 2.571727e-02 2.967107e-02 1.756160e+02 +2.801621e-02 5.168679e-02 -9.982703e-01 -5.681305e+01 -2.855798e-02 9.982960e-01 5.088666e-02 -3.789591e+00 9.991995e-01 2.708293e-02 2.944455e-02 1.756433e+02 +2.808693e-02 4.375236e-02 -9.986475e-01 -5.786797e+01 -2.867877e-02 9.986656e-01 4.294658e-02 -3.758663e+00 9.991940e-01 2.743374e-02 2.930422e-02 1.756732e+02 +2.898446e-02 3.870965e-02 -9.988300e-01 -5.892586e+01 -2.930420e-02 9.988533e-01 3.786020e-02 -3.729483e+00 9.991503e-01 2.817256e-02 3.008558e-02 1.757029e+02 +2.955093e-02 3.922163e-02 -9.987935e-01 -5.999213e+01 -2.753874e-02 9.988825e-01 3.841036e-02 -3.703519e+00 9.991839e-01 2.637045e-02 3.059802e-02 1.757368e+02 +2.989303e-02 4.086024e-02 -9.987176e-01 -6.106094e+01 -2.738710e-02 9.988225e-01 4.004480e-02 -3.679222e+00 9.991779e-01 2.615492e-02 3.097688e-02 1.757688e+02 +3.020727e-02 4.204794e-02 -9.986588e-01 -6.213007e+01 -2.378123e-02 9.988622e-01 4.133718e-02 -3.651678e+00 9.992607e-01 2.250065e-02 3.117286e-02 1.758047e+02 +2.992935e-02 4.251124e-02 -9.986476e-01 -6.319684e+01 -2.246806e-02 9.988713e-01 4.184741e-02 -3.624933e+00 9.992995e-01 2.118521e-02 3.085071e-02 1.758393e+02 +2.958721e-02 4.197146e-02 -9.986806e-01 -6.426316e+01 -2.027899e-02 9.989376e-01 4.138148e-02 -3.600963e+00 9.993565e-01 1.902787e-02 3.040692e-02 1.758739e+02 +2.880503e-02 3.902520e-02 -9.988229e-01 -6.532808e+01 -1.947704e-02 9.990698e-01 3.847316e-02 -3.578166e+00 9.993953e-01 1.834589e-02 2.953833e-02 1.759073e+02 +2.781304e-02 3.772083e-02 -9.989012e-01 -6.639425e+01 -1.854531e-02 9.991352e-01 3.721331e-02 -3.558276e+00 9.994411e-01 1.748992e-02 2.848854e-02 1.759388e+02 +2.682258e-02 4.018433e-02 -9.988322e-01 -6.746594e+01 -1.688506e-02 9.990673e-01 3.974037e-02 -3.537339e+00 9.994976e-01 1.579941e-02 2.747608e-02 1.759716e+02 +2.580966e-02 4.463398e-02 -9.986699e-01 -6.853766e+01 -1.512458e-02 9.989058e-01 4.425365e-02 -3.512966e+00 9.995525e-01 1.396229e-02 2.645649e-02 1.760031e+02 +2.514307e-02 4.778646e-02 -9.985411e-01 -6.961315e+01 -1.535658e-02 9.987574e-01 4.741015e-02 -3.488117e+00 9.995659e-01 1.414214e-02 2.584567e-02 1.760308e+02 +2.452755e-02 4.569910e-02 -9.986541e-01 -7.068082e+01 -1.484367e-02 9.988611e-01 4.534401e-02 -3.460593e+00 9.995890e-01 1.371151e-02 2.517796e-02 1.760582e+02 +2.366204e-02 4.040400e-02 -9.989032e-01 -7.174923e+01 -1.749389e-02 9.990467e-01 3.999542e-02 -3.434708e+00 9.995670e-01 1.652833e-02 2.434631e-02 1.760809e+02 +2.309466e-02 3.712162e-02 -9.990438e-01 -7.281964e+01 -1.952479e-02 9.991365e-01 3.667373e-02 -3.412173e+00 9.995426e-01 1.865915e-02 2.379951e-02 1.761026e+02 +2.253329e-02 3.819285e-02 -9.990163e-01 -7.389568e+01 -2.067590e-02 9.990741e-01 3.772872e-02 -3.390842e+00 9.995323e-01 1.980541e-02 2.330210e-02 1.761241e+02 +2.206374e-02 4.334170e-02 -9.988166e-01 -7.497650e+01 -2.082123e-02 9.988631e-01 4.288379e-02 -3.367524e+00 9.995398e-01 1.985041e-02 2.294109e-02 1.761459e+02 +2.141856e-02 4.742704e-02 -9.986450e-01 -7.605764e+01 -2.065329e-02 9.986820e-01 4.698584e-02 -3.344669e+00 9.995573e-01 1.961894e-02 2.236986e-02 1.761714e+02 +2.046055e-02 4.598428e-02 -9.987326e-01 -7.713401e+01 -2.028795e-02 9.987551e-01 4.556970e-02 -3.318655e+00 9.995848e-01 1.932986e-02 2.136801e-02 1.761965e+02 +1.945399e-02 4.341934e-02 -9.988675e-01 -7.820879e+01 -2.132799e-02 9.988472e-01 4.300309e-02 -3.293468e+00 9.995833e-01 2.046726e-02 2.035762e-02 1.762180e+02 +1.801232e-02 4.228241e-02 -9.989433e-01 -7.928739e+01 -2.450020e-02 9.988240e-01 4.183560e-02 -3.271490e+00 9.995376e-01 2.372075e-02 1.902707e-02 1.762341e+02 +1.622458e-02 4.220138e-02 -9.989774e-01 -8.036695e+01 -2.918046e-02 9.987033e-01 4.171589e-02 -3.250868e+00 9.994425e-01 2.847380e-02 1.743500e-02 1.762443e+02 +1.434862e-02 4.221213e-02 -9.990056e-01 -8.144707e+01 -2.897747e-02 9.987064e-01 4.178330e-02 -3.230620e+00 9.994771e-01 2.834912e-02 1.555326e-02 1.762579e+02 +1.141212e-02 3.956921e-02 -9.991516e-01 -8.252764e+01 -2.890573e-02 9.988122e-01 3.922563e-02 -3.208247e+00 9.995170e-01 2.843356e-02 1.254234e-02 1.762700e+02 +8.365985e-03 4.015016e-02 -9.991586e-01 -8.360948e+01 -2.804854e-02 9.988098e-01 3.990130e-02 -3.186890e+00 9.995716e-01 2.769112e-02 9.482183e-03 1.762796e+02 +5.627318e-03 3.876020e-02 -9.992327e-01 -8.469218e+01 -2.281284e-02 9.989934e-01 3.862245e-02 -3.168462e+00 9.997239e-01 2.257799e-02 6.505886e-03 1.762906e+02 +3.707893e-03 3.581891e-02 -9.993514e-01 -8.577305e+01 -2.202257e-02 9.991188e-01 3.572888e-02 -3.153257e+00 9.997506e-01 2.187580e-02 4.493452e-03 1.762928e+02 +1.486301e-03 3.060748e-02 -9.995304e-01 -8.685268e+01 -2.180213e-02 9.992949e-01 3.056786e-02 -3.138841e+00 9.997612e-01 2.174646e-02 2.152563e-03 1.762926e+02 +-7.824610e-04 2.978333e-02 -9.995561e-01 -8.793679e+01 -2.239296e-02 9.993052e-01 2.979339e-02 -3.126815e+00 9.997490e-01 2.240633e-02 -1.149784e-04 1.762887e+02 +-3.113029e-03 3.217743e-02 -9.994773e-01 -8.902466e+01 -2.362341e-02 9.992008e-01 3.224212e-02 -3.116234e+00 9.997161e-01 2.371144e-02 -2.350398e-03 1.762831e+02 +-5.156991e-03 3.713198e-02 -9.992970e-01 -9.011810e+01 -2.411255e-02 9.990152e-01 3.724595e-02 -3.102292e+00 9.996960e-01 2.428768e-02 -4.256563e-03 1.762705e+02 +-7.358941e-03 4.174064e-02 -9.991014e-01 -9.121129e+01 -2.401336e-02 9.988329e-01 4.190631e-02 -3.083165e+00 9.996846e-01 2.430017e-02 -6.348018e-03 1.762584e+02 +-9.527283e-03 4.363077e-02 -9.990023e-01 -9.230254e+01 -2.487439e-02 9.987281e-01 4.385603e-02 -3.064897e+00 9.996452e-01 2.526740e-02 -8.429875e-03 1.762410e+02 +-1.199915e-02 3.940000e-02 -9.991515e-01 -9.339307e+01 -2.297177e-02 9.989488e-01 3.966790e-02 -3.043695e+00 9.996641e-01 2.342826e-02 -1.108144e-02 1.762245e+02 +-1.444282e-02 3.413126e-02 -9.993130e-01 -9.448444e+01 -2.172744e-02 9.991705e-01 3.444043e-02 -3.024598e+00 9.996596e-01 2.220993e-02 -1.368925e-02 1.762048e+02 +-1.700235e-02 3.175556e-02 -9.993510e-01 -9.557350e+01 -2.167062e-02 9.992490e-01 3.212102e-02 -3.010653e+00 9.996206e-01 2.220268e-02 -1.630142e-02 1.761812e+02 +-1.960864e-02 3.165188e-02 -9.993066e-01 -9.665901e+01 -2.125146e-02 9.992597e-01 3.206741e-02 -2.997553e+00 9.995819e-01 2.186553e-02 -1.892148e-02 1.761540e+02 +-2.228841e-02 3.473255e-02 -9.991481e-01 -9.775700e+01 -2.160766e-02 9.991461e-01 3.521450e-02 -2.983233e+00 9.995181e-01 2.237412e-02 -2.151889e-02 1.761216e+02 +-2.481058e-02 3.685876e-02 -9.990124e-01 -9.885399e+01 -2.302309e-02 9.990339e-01 3.743135e-02 -2.968686e+00 9.994271e-01 2.392905e-02 -2.393800e-02 1.760869e+02 +-2.737084e-02 3.697018e-02 -9.989414e-01 -9.994875e+01 -2.363943e-02 9.990124e-01 3.762054e-02 -2.950607e+00 9.993458e-01 2.464411e-02 -2.646985e-02 1.760474e+02 +-2.975559e-02 3.651931e-02 -9.988898e-01 -1.010452e+02 -2.358126e-02 9.990285e-01 3.722684e-02 -2.930300e+00 9.992790e-01 2.466279e-02 -2.886551e-02 1.760044e+02 +-3.224418e-02 3.659215e-02 -9.988099e-01 -1.021429e+02 -2.270272e-02 9.990449e-01 3.733367e-02 -2.911418e+00 9.992222e-01 2.387950e-02 -3.138265e-02 1.759586e+02 +-3.498567e-02 3.591744e-02 -9.987422e-01 -1.032400e+02 -2.157114e-02 9.990940e-01 3.668573e-02 -2.893548e+00 9.991550e-01 2.282748e-02 -3.417919e-02 1.759128e+02 +-3.763537e-02 3.402385e-02 -9.987121e-01 -1.043390e+02 -2.009134e-02 9.991924e-01 3.479734e-02 -2.874527e+00 9.990896e-01 2.137508e-02 -3.692139e-02 1.758621e+02 +-4.000094e-02 3.268299e-02 -9.986650e-01 -1.054372e+02 -1.973858e-02 9.992440e-01 3.349257e-02 -2.858445e+00 9.990047e-01 2.105196e-02 -3.932558e-02 1.758098e+02 +-4.182228e-02 3.404618e-02 -9.985448e-01 -1.065395e+02 -1.924572e-02 9.992063e-01 3.487482e-02 -2.840079e+00 9.989397e-01 2.067626e-02 -4.113384e-02 1.757519e+02 +-4.376356e-02 3.329194e-02 -9.984870e-01 -1.076403e+02 -1.926921e-02 9.992305e-01 3.416130e-02 -2.824004e+00 9.988561e-01 2.073507e-02 -4.308838e-02 1.756946e+02 +-4.539533e-02 3.181375e-02 -9.984624e-01 -1.087404e+02 -1.667322e-02 9.993294e-01 3.259944e-02 -2.806967e+00 9.988300e-01 1.812745e-02 -4.483445e-02 1.756373e+02 +-4.745340e-02 3.228211e-02 -9.983516e-01 -1.098435e+02 -1.415754e-02 9.993555e-01 3.298751e-02 -2.790175e+00 9.987732e-01 1.569958e-02 -4.696578e-02 1.755812e+02 +-4.889021e-02 3.578810e-02 -9.981628e-01 -1.109486e+02 -1.372364e-02 9.992394e-01 3.649890e-02 -2.774611e+00 9.987099e-01 1.548287e-02 -4.836188e-02 1.755205e+02 +-5.078529e-02 3.906369e-02 -9.979453e-01 -1.120575e+02 -1.265637e-02 9.991293e-01 3.975413e-02 -2.755965e+00 9.986294e-01 1.464929e-02 -5.024667e-02 1.754596e+02 +-5.201110e-02 3.662954e-02 -9.979745e-01 -1.131625e+02 -1.283302e-02 9.992200e-01 3.734409e-02 -2.735063e+00 9.985641e-01 1.474934e-02 -5.150047e-02 1.753930e+02 +-5.362789e-02 3.406089e-02 -9.979799e-01 -1.142677e+02 -1.348695e-02 9.993022e-01 3.483077e-02 -2.717301e+00 9.984699e-01 1.532760e-02 -5.313109e-02 1.753260e+02 +-5.480229e-02 3.443276e-02 -9.979033e-01 -1.153758e+02 -1.300562e-02 9.992958e-01 3.519505e-02 -2.700498e+00 9.984126e-01 1.490713e-02 -5.431588e-02 1.752594e+02 +-5.610228e-02 3.402934e-02 -9.978449e-01 -1.164880e+02 -1.171680e-02 9.993277e-01 3.473868e-02 -2.685105e+00 9.983563e-01 1.364047e-02 -5.566584e-02 1.751917e+02 +-5.733181e-02 3.252728e-02 -9.978251e-01 -1.175985e+02 -1.073083e-02 9.993913e-01 3.319490e-02 -2.671202e+00 9.982975e-01 1.261062e-02 -5.694786e-02 1.751231e+02 +-5.843893e-02 3.192871e-02 -9.977802e-01 -1.187098e+02 -9.276938e-03 9.994278e-01 3.252478e-02 -2.658124e+00 9.982479e-01 1.115706e-02 -5.810929e-02 1.750547e+02 +-5.866785e-02 3.540085e-02 -9.976497e-01 -1.198273e+02 -8.394657e-03 9.993182e-01 3.595372e-02 -2.641605e+00 9.982423e-01 1.048426e-02 -5.833067e-02 1.749853e+02 +-5.855056e-02 3.715713e-02 -9.975927e-01 -1.209426e+02 -2.918769e-03 9.992964e-01 3.739191e-02 -2.627680e+00 9.982802e-01 5.101063e-03 -5.840091e-02 1.749232e+02 +-5.842735e-02 3.692965e-02 -9.976083e-01 -1.220620e+02 -2.188062e-03 9.993084e-01 3.712074e-02 -2.613523e+00 9.982893e-01 4.351698e-03 -5.830613e-02 1.748566e+02 +-5.868674e-02 3.231319e-02 -9.977533e-01 -1.231757e+02 -3.990105e-03 9.994604e-01 3.260318e-02 -2.600324e+00 9.982685e-01 5.894517e-03 -5.852614e-02 1.747877e+02 +-5.839753e-02 3.098951e-02 -9.978123e-01 -1.242939e+02 -3.740325e-03 9.995042e-01 3.126098e-02 -2.585573e+00 9.982864e-01 5.557710e-03 -5.825267e-02 1.747188e+02 +-5.795067e-02 2.846674e-02 -9.979135e-01 -1.254127e+02 -5.766669e-03 9.995671e-01 2.884880e-02 -2.577424e+00 9.983028e-01 7.426447e-03 -5.776143e-02 1.746490e+02 +-5.781771e-02 3.011989e-02 -9.978727e-01 -1.265349e+02 -1.013318e-02 9.994755e-01 3.075540e-02 -2.568074e+00 9.982758e-01 1.188983e-02 -5.748217e-02 1.745741e+02 +-5.824212e-02 3.310312e-02 -9.977535e-01 -1.276630e+02 -9.839092e-03 9.993825e-01 3.373151e-02 -2.557687e+00 9.982540e-01 1.178158e-02 -5.788045e-02 1.745059e+02 +-5.865335e-02 3.538032e-02 -9.976512e-01 -1.287911e+02 -8.679976e-03 9.993159e-01 3.594967e-02 -2.542800e+00 9.982407e-01 1.076816e-02 -5.830613e-02 1.744380e+02 +-5.907139e-02 3.702467e-02 -9.975669e-01 -1.299195e+02 -1.013998e-02 9.992381e-01 3.768715e-02 -2.526566e+00 9.982023e-01 1.234154e-02 -5.865095e-02 1.743664e+02 +-5.986866e-02 3.732799e-02 -9.975081e-01 -1.310489e+02 -1.017307e-02 9.992258e-01 3.800285e-02 -2.508856e+00 9.981545e-01 1.242290e-02 -5.944257e-02 1.742953e+02 +-6.059960e-02 3.553654e-02 -9.975294e-01 -1.321800e+02 -1.106783e-02 9.992807e-01 3.627130e-02 -2.492033e+00 9.981008e-01 1.323851e-02 -6.016269e-02 1.742224e+02 +-6.111935e-02 3.345604e-02 -9.975696e-01 -1.333093e+02 -1.154937e-02 9.993475e-01 3.422329e-02 -2.476347e+00 9.980637e-01 1.361300e-02 -6.069307e-02 1.741484e+02 +-6.149238e-02 3.291457e-02 -9.975647e-01 -1.344431e+02 -1.400889e-02 9.993292e-01 3.383635e-02 -2.462008e+00 9.980093e-01 1.605545e-02 -6.099003e-02 1.740725e+02 +-6.168455e-02 3.309413e-02 -9.975469e-01 -1.355747e+02 -1.607906e-02 9.992875e-01 3.414615e-02 -2.450133e+00 9.979662e-01 1.814591e-02 -6.110847e-02 1.739964e+02 +-6.172552e-02 3.348454e-02 -9.975313e-01 -1.367100e+02 -1.576635e-02 9.992797e-01 3.451883e-02 -2.437846e+00 9.979687e-01 1.785813e-02 -6.115313e-02 1.739239e+02 +-6.174860e-02 3.450283e-02 -9.974952e-01 -1.378472e+02 -1.673207e-02 9.992261e-01 3.559849e-02 -2.423048e+00 9.979515e-01 1.888832e-02 -6.112351e-02 1.738482e+02 +-6.148574e-02 3.511175e-02 -9.974902e-01 -1.389823e+02 -1.597492e-02 9.992184e-01 3.615729e-02 -2.408265e+00 9.979801e-01 1.815799e-02 -6.087677e-02 1.737749e+02 +-6.097099e-02 3.390718e-02 -9.975634e-01 -1.401220e+02 -1.348635e-02 9.993036e-01 3.479062e-02 -2.390520e+00 9.980485e-01 1.557471e-02 -6.047125e-02 1.737057e+02 +-6.081493e-02 3.456855e-02 -9.975503e-01 -1.412620e+02 -1.293050e-02 9.992889e-01 3.541711e-02 -2.374200e+00 9.980653e-01 1.505271e-02 -6.032469e-02 1.736350e+02 +-6.107731e-02 3.419085e-02 -9.975473e-01 -1.423995e+02 -1.177548e-02 9.993189e-01 3.497256e-02 -2.361339e+00 9.980636e-01 1.388263e-02 -6.063309e-02 1.735660e+02 +-6.136920e-02 3.028261e-02 -9.976556e-01 -1.435357e+02 -1.168100e-02 9.994494e-01 3.105561e-02 -2.348108e+00 9.980468e-01 1.355948e-02 -6.098168e-02 1.734921e+02 +-6.143343e-02 2.913140e-02 -9.976860e-01 -1.446753e+02 -1.267703e-02 9.994706e-01 2.996411e-02 -2.334856e+00 9.980307e-01 1.448850e-02 -6.103161e-02 1.734155e+02 +-6.124630e-02 3.259628e-02 -9.975903e-01 -1.458162e+02 -1.408536e-02 9.993388e-01 3.351819e-02 -2.322625e+00 9.980233e-01 1.610428e-02 -6.074667e-02 1.733376e+02 +-6.125731e-02 3.485684e-02 -9.975132e-01 -1.469598e+02 -1.494265e-02 9.992460e-01 3.583503e-02 -2.307135e+00 9.980102e-01 1.710064e-02 -6.069027e-02 1.732599e+02 +-6.137916e-02 3.483460e-02 -9.975065e-01 -1.480934e+02 -1.147291e-02 9.993001e-01 3.560320e-02 -2.289416e+00 9.980486e-01 1.362960e-02 -6.093654e-02 1.731890e+02 +-6.204761e-02 3.440576e-02 -9.974800e-01 -1.492316e+02 -8.486128e-03 9.993513e-01 3.499820e-02 -2.271249e+00 9.980371e-01 1.063630e-02 -6.171539e-02 1.731167e+02 +-6.267929e-02 3.514146e-02 -9.974148e-01 -1.503676e+02 -5.554016e-03 9.993521e-01 3.555875e-02 -2.254789e+00 9.980183e-01 7.768458e-03 -6.244350e-02 1.730442e+02 +-6.322791e-02 3.571699e-02 -9.973598e-01 -1.515066e+02 -4.693736e-03 9.993377e-01 3.608539e-02 -2.238994e+00 9.979881e-01 6.962950e-03 -6.301838e-02 1.729673e+02 +-6.355021e-02 3.415361e-02 -9.973940e-01 -1.526375e+02 -5.348532e-03 9.993882e-01 3.456269e-02 -2.223484e+00 9.979643e-01 7.531063e-03 -6.332866e-02 1.728880e+02 +-6.374121e-02 3.294226e-02 -9.974226e-01 -1.537672e+02 -5.418887e-03 9.994289e-01 3.335483e-02 -2.206655e+00 9.979518e-01 7.531001e-03 -6.352629e-02 1.728079e+02 +-6.377776e-02 3.503603e-02 -9.973489e-01 -1.549018e+02 -5.251290e-03 9.993579e-01 3.544242e-02 -2.189866e+00 9.979503e-01 7.497810e-03 -6.355283e-02 1.727283e+02 +-6.390332e-02 4.029374e-02 -9.971423e-01 -1.560426e+02 -5.049594e-03 9.991587e-01 4.069884e-02 -2.170747e+00 9.979434e-01 7.635958e-03 -6.364609e-02 1.726488e+02 +-6.381654e-02 4.469153e-02 -9.969604e-01 -1.571702e+02 -3.975762e-03 9.989774e-01 4.503645e-02 -2.146778e+00 9.979538e-01 6.837751e-03 -6.357360e-02 1.725710e+02 +-6.375519e-02 4.177957e-02 -9.970906e-01 -1.582929e+02 -1.328570e-03 9.991188e-01 4.194952e-02 -2.124401e+00 9.979647e-01 3.999208e-03 -6.364350e-02 1.724947e+02 +-6.336285e-02 3.111700e-02 -9.975053e-01 -1.594032e+02 -4.744351e-03 9.994931e-01 3.148039e-02 -2.104432e+00 9.979793e-01 6.727206e-03 -6.318310e-02 1.724115e+02 +-6.267042e-02 2.169556e-02 -9.977984e-01 -1.605142e+02 -5.769169e-03 9.997391e-01 2.210012e-02 -2.092754e+00 9.980176e-01 7.141495e-03 -6.252891e-02 1.723299e+02 +-6.237427e-02 2.439110e-02 -9.977547e-01 -1.616322e+02 -5.300567e-03 9.996791e-01 2.476951e-02 -2.083280e+00 9.980388e-01 6.833649e-03 -6.222497e-02 1.722504e+02 +-6.209179e-02 3.389053e-02 -9.974949e-01 -1.627528e+02 -4.609212e-03 9.994029e-01 3.424228e-02 -2.069616e+00 9.980598e-01 6.723833e-03 -6.189851e-02 1.721736e+02 +-6.146157e-02 4.142570e-02 -9.972494e-01 -1.638691e+02 -2.192075e-03 9.991303e-01 4.163894e-02 -2.048595e+00 9.981071e-01 4.745244e-03 -6.131730e-02 1.720977e+02 +-6.177511e-02 4.499955e-02 -9.970751e-01 -1.649749e+02 -2.546991e-03 9.989727e-01 4.524301e-02 -2.021386e+00 9.980869e-01 5.334437e-03 -6.159704e-02 1.720226e+02 +-6.175680e-02 4.292880e-02 -9.971676e-01 -1.660744e+02 -3.562195e-03 9.990587e-01 4.323084e-02 -1.995178e+00 9.980849e-01 6.221907e-03 -6.154575e-02 1.719453e+02 +-6.127776e-02 3.417076e-02 -9.975356e-01 -1.671580e+02 1.313529e-03 9.994157e-01 3.415448e-02 -1.975524e+00 9.981199e-01 7.826218e-04 -6.128684e-02 1.718752e+02 +-6.139673e-02 2.505276e-02 -9.977990e-01 -1.682360e+02 3.955343e-03 9.996832e-01 2.485670e-02 -1.961720e+00 9.981056e-01 -2.420512e-03 -6.147637e-02 1.718032e+02 +-6.314417e-02 2.453378e-02 -9.977028e-01 -1.693203e+02 7.270956e-03 9.996825e-01 2.412229e-02 -1.950410e+00 9.979780e-01 -5.731066e-03 -6.330251e-02 1.717341e+02 +-6.451881e-02 3.980966e-02 -9.971221e-01 -1.704137e+02 9.962817e-03 9.991798e-01 3.924718e-02 -1.929903e+00 9.978668e-01 -7.401958e-03 -6.486251e-02 1.716631e+02 +-6.426604e-02 5.539471e-02 -9.963941e-01 -1.715024e+02 1.583390e-02 9.983890e-01 5.448436e-02 -1.904604e+00 9.978072e-01 -1.227530e-02 -6.503962e-02 1.715970e+02 +-6.423052e-02 5.921716e-02 -9.961766e-01 -1.725710e+02 1.383558e-02 9.981947e-01 5.844506e-02 -1.869883e+00 9.978392e-01 -1.002872e-02 -6.493387e-02 1.715208e+02 +-6.379791e-02 5.426786e-02 -9.964862e-01 -1.736221e+02 1.137167e-02 9.984951e-01 5.364922e-02 -1.834797e+00 9.978981e-01 -7.908996e-03 -6.431901e-02 1.714424e+02 +-6.407316e-02 4.205668e-02 -9.970586e-01 -1.746683e+02 5.372183e-03 9.991116e-01 4.179806e-02 -1.814384e+00 9.979308e-01 -2.678243e-03 -6.424218e-02 1.713599e+02 +-6.445810e-02 3.036693e-02 -9.974583e-01 -1.756844e+02 4.381188e-03 9.995358e-01 3.014707e-02 -1.801522e+00 9.979108e-01 -2.426825e-03 -6.456122e-02 1.712844e+02 +-6.524662e-02 2.666030e-02 -9.975129e-01 -1.767136e+02 2.179671e-03 9.996444e-01 2.657471e-02 -1.792166e+00 9.978668e-01 -4.403355e-04 -6.528153e-02 1.712081e+02 +-6.525414e-02 3.362614e-02 -9.973019e-01 -1.777464e+02 1.474938e-03 9.994342e-01 3.360153e-02 -1.781877e+00 9.978676e-01 7.216845e-04 -6.526682e-02 1.711325e+02 +-6.574498e-02 4.373505e-02 -9.968775e-01 -1.787763e+02 -4.957698e-04 9.990374e-01 4.386251e-02 -1.764893e+00 9.978364e-01 3.377965e-03 -6.566001e-02 1.710553e+02 +-6.606710e-02 5.084245e-02 -9.965190e-01 -1.797942e+02 -2.206107e-03 9.986911e-01 5.109955e-02 -1.742396e+00 9.978128e-01 5.574430e-03 -6.586846e-02 1.709774e+02 +-6.668060e-02 5.224813e-02 -9.964054e-01 -1.808032e+02 -2.323724e-03 9.986172e-01 5.251963e-02 -1.714755e+00 9.977717e-01 5.817415e-03 -6.646698e-02 1.709033e+02 +-6.783664e-02 4.909307e-02 -9.964878e-01 -1.818002e+02 -1.958704e-03 9.987801e-01 4.933936e-02 -1.689522e+00 9.976946e-01 5.298845e-03 -6.765773e-02 1.708323e+02 +-6.808804e-02 4.854158e-02 -9.964977e-01 -1.827927e+02 3.462228e-04 9.988167e-01 4.863090e-02 -1.662413e+00 9.976793e-01 2.966176e-03 -6.802428e-02 1.707604e+02 +-6.833077e-02 4.656962e-02 -9.965752e-01 -1.837787e+02 8.938258e-04 9.989124e-01 4.661756e-02 -1.641427e+00 9.976624e-01 2.294653e-03 -6.829808e-02 1.706878e+02 +-6.809468e-02 4.040283e-02 -9.968604e-01 -1.847507e+02 1.196172e-03 9.991822e-01 4.041524e-02 -1.619494e+00 9.976782e-01 1.559650e-03 -6.808732e-02 1.706164e+02 +-6.757525e-02 3.811522e-02 -9.969858e-01 -1.857280e+02 1.762718e-03 9.992730e-01 3.808319e-02 -1.592277e+00 9.977127e-01 8.160808e-04 -6.759331e-02 1.705457e+02 +-6.615375e-02 4.116272e-02 -9.969600e-01 -1.867015e+02 1.494044e-03 9.991517e-01 4.115409e-02 -1.571123e+00 9.978084e-01 1.232999e-03 -6.615912e-02 1.704758e+02 +-6.432803e-02 4.090515e-02 -9.970901e-01 -1.876684e+02 -3.893034e-04 9.991584e-01 4.101513e-02 -1.551350e+00 9.979288e-01 3.026597e-03 -6.425797e-02 1.704036e+02 +-6.304502e-02 3.521438e-02 -9.973892e-01 -1.886198e+02 -1.684294e-03 9.993721e-01 3.539086e-02 -1.529735e+00 9.980093e-01 3.911118e-03 -6.294613e-02 1.703337e+02 +-6.202656e-02 3.280361e-02 -9.975353e-01 -1.895660e+02 -2.633601e-03 9.994509e-01 3.303037e-02 -1.512504e+00 9.980711e-01 4.675874e-03 -6.190611e-02 1.702680e+02 +-6.185129e-02 3.488018e-02 -9.974757e-01 -1.905132e+02 -4.661865e-03 9.993681e-01 3.523544e-02 -1.500652e+00 9.980745e-01 6.829457e-03 -6.164960e-02 1.702009e+02 +-6.249916e-02 3.741214e-02 -9.973435e-01 -1.914543e+02 -4.560040e-03 9.992760e-01 3.777040e-02 -1.486176e+00 9.980346e-01 6.908548e-03 -6.228332e-02 1.701353e+02 +-6.344699e-02 3.899656e-02 -9.972230e-01 -1.923913e+02 -4.300400e-03 9.992163e-01 3.934813e-02 -1.471672e+00 9.979760e-01 6.784982e-03 -6.322956e-02 1.700706e+02 +-6.466099e-02 3.921885e-02 -9.971363e-01 -1.933147e+02 -4.488047e-03 9.992059e-01 3.959129e-02 -1.458562e+00 9.978972e-01 7.035210e-03 -6.443363e-02 1.700043e+02 +-6.722641e-02 3.595706e-02 -9.970896e-01 -1.942342e+02 -8.037352e-03 9.992984e-01 3.657862e-02 -1.444659e+00 9.977054e-01 1.047301e-02 -6.689025e-02 1.699311e+02 +-7.070778e-02 3.510501e-02 -9.968791e-01 -1.951499e+02 -9.519771e-03 9.993112e-01 3.586589e-02 -1.429746e+00 9.974517e-01 1.202606e-02 -7.032489e-02 1.698581e+02 +-7.449689e-02 3.604625e-02 -9.965695e-01 -1.960637e+02 -8.232547e-03 9.992902e-01 3.676007e-02 -1.416638e+00 9.971873e-01 1.094282e-02 -7.414725e-02 1.697845e+02 +-7.845880e-02 3.900495e-02 -9.961540e-01 -1.969720e+02 -1.278812e-02 9.991127e-01 4.012802e-02 -1.404095e+00 9.968354e-01 1.588733e-02 -7.789038e-02 1.697012e+02 +-8.236188e-02 4.154199e-02 -9.957363e-01 -1.978760e+02 -8.303073e-03 9.990676e-01 4.236777e-02 -1.386589e+00 9.965679e-01 1.175716e-02 -8.194015e-02 1.696264e+02 +-8.755517e-02 4.312229e-02 -9.952259e-01 -1.987775e+02 -3.700292e-03 9.990416e-01 4.361317e-02 -1.369749e+00 9.961528e-01 7.501187e-03 -8.731170e-02 1.695500e+02 +-9.268481e-02 4.147627e-02 -9.948312e-01 -1.996695e+02 -4.652537e-03 9.991031e-01 4.208784e-02 -1.357670e+00 9.956847e-01 8.529395e-03 -9.240871e-02 1.694621e+02 +-9.867177e-02 3.507159e-02 -9.945018e-01 -2.005524e+02 -1.994211e-03 9.993698e-01 3.544113e-02 -1.343237e+00 9.951181e-01 5.480289e-03 -9.853964e-02 1.693725e+02 +-1.053136e-01 3.243368e-02 -9.939100e-01 -2.014348e+02 -7.821558e-05 9.994677e-01 3.262334e-02 -1.329844e+00 9.944391e-01 3.513426e-03 -1.052550e-01 1.692791e+02 +-1.115776e-01 3.551064e-02 -9.931210e-01 -2.023167e+02 1.525780e-03 9.993663e-01 3.556253e-02 -1.318833e+00 9.937546e-01 2.452700e-03 -1.115610e-01 1.691756e+02 +-1.183273e-01 4.122516e-02 -9.921185e-01 -2.031990e+02 1.031276e-03 9.991423e-01 4.139403e-02 -1.305680e+00 9.929741e-01 3.874901e-03 -1.182684e-01 1.690637e+02 +-1.254256e-01 4.456852e-02 -9.911014e-01 -2.040712e+02 2.541191e-04 9.989918e-01 4.489120e-02 -1.291408e+00 9.921030e-01 5.378652e-03 -1.253105e-01 1.689457e+02 +-1.321418e-01 4.360546e-02 -9.902712e-01 -2.049337e+02 2.108059e-03 9.990420e-01 4.371038e-02 -1.276326e+00 9.912286e-01 3.688422e-03 -1.321071e-01 1.688277e+02 +-1.381249e-01 3.937800e-02 -9.896317e-01 -2.057870e+02 1.715958e-03 9.992173e-01 3.951993e-02 -1.260867e+00 9.904134e-01 3.760521e-03 -1.380843e-01 1.687030e+02 +-1.425603e-01 3.566718e-02 -9.891433e-01 -2.066345e+02 -2.027978e-03 9.993379e-01 3.632708e-02 -1.248153e+00 9.897841e-01 7.184762e-03 -1.423936e-01 1.685696e+02 +-1.455240e-01 3.442686e-02 -9.887555e-01 -2.074800e+02 -7.120597e-03 9.993320e-01 3.584313e-02 -1.236530e+00 9.893291e-01 1.225657e-02 -1.451816e-01 1.684309e+02 +-1.468710e-01 3.710426e-02 -9.884595e-01 -2.083261e+02 -1.317219e-02 9.991342e-01 3.946218e-02 -1.224133e+00 9.890680e-01 1.881603e-02 -1.462551e-01 1.682904e+02 +-1.466390e-01 3.925953e-02 -9.884107e-01 -2.091657e+02 -1.786905e-02 9.989439e-01 4.232894e-02 -1.212351e+00 9.890287e-01 2.386903e-02 -1.457826e-01 1.681525e+02 +-1.462577e-01 3.954300e-02 -9.884559e-01 -2.100005e+02 -2.213494e-02 9.988198e-01 4.323283e-02 -1.198274e+00 9.889989e-01 2.820254e-02 -1.452098e-01 1.680172e+02 +-1.454836e-01 3.988785e-02 -9.885563e-01 -2.108240e+02 -2.445371e-02 9.987367e-01 4.389744e-02 -1.182468e+00 9.890585e-01 3.056022e-02 -1.443244e-01 1.678817e+02 +-1.441592e-01 4.244126e-02 -9.886439e-01 -2.116465e+02 -2.414682e-02 9.986314e-01 4.639099e-02 -1.165081e+00 9.892599e-01 3.056030e-02 -1.429371e-01 1.677511e+02 +-1.426488e-01 4.481344e-02 -9.887583e-01 -2.124586e+02 -2.851815e-02 9.983736e-01 4.936357e-02 -1.152062e+00 9.893625e-01 3.523921e-02 -1.411388e-01 1.676175e+02 +-1.397832e-01 4.098848e-02 -9.893334e-01 -2.132583e+02 -3.307703e-02 9.983919e-01 4.603725e-02 -1.135705e+00 9.896295e-01 3.915944e-02 -1.382026e-01 1.674882e+02 +-1.350038e-01 3.821510e-02 -9.901079e-01 -2.140407e+02 -3.751304e-02 9.983424e-01 4.364794e-02 -1.119039e+00 9.901348e-01 4.303459e-02 -1.333464e-01 1.673660e+02 +-1.268159e-01 3.869688e-02 -9.911712e-01 -2.148181e+02 -4.266281e-02 9.981013e-01 4.442597e-02 -1.100554e+00 9.910084e-01 4.792006e-02 -1.249242e-01 1.672539e+02 +-1.149497e-01 3.932478e-02 -9.925926e-01 -2.155840e+02 -4.704459e-02 9.978794e-01 4.498236e-02 -1.086661e+00 9.922567e-01 5.186682e-02 -1.128559e-01 1.671555e+02 +-1.023351e-01 4.008816e-02 -9.939419e-01 -2.163418e+02 -5.069774e-02 9.976789e-01 4.545867e-02 -1.074794e+00 9.934573e-01 5.504262e-02 -1.000652e-01 1.670689e+02 +-8.935849e-02 3.999105e-02 -9.951963e-01 -2.170893e+02 -5.061207e-02 9.977204e-01 4.463694e-02 -1.057950e+00 9.947128e-01 5.435763e-02 -8.713076e-02 1.670045e+02 +-7.723207e-02 3.977904e-02 -9.962193e-01 -2.178256e+02 -4.957812e-02 9.978143e-01 4.368629e-02 -1.043016e+00 9.957797e-01 5.276466e-02 -7.509110e-02 1.669510e+02 +-6.469787e-02 4.133544e-02 -9.970484e-01 -2.185566e+02 -4.848176e-02 9.978316e-01 4.451387e-02 -1.029719e+00 9.967265e-01 5.121861e-02 -6.255356e-02 1.669062e+02 +-5.224894e-02 4.162708e-02 -9.977661e-01 -2.192715e+02 -4.963255e-02 9.977878e-01 4.422705e-02 -1.016114e+00 9.974000e-01 5.183248e-02 -5.006729e-02 1.668699e+02 +-3.972110e-02 4.339658e-02 -9.982680e-01 -2.199767e+02 -5.146058e-02 9.976417e-01 4.541699e-02 -1.002754e+00 9.978848e-01 5.317545e-02 -3.739422e-02 1.668401e+02 +-2.524443e-02 4.467702e-02 -9.986825e-01 -2.206711e+02 -5.227240e-02 9.975752e-01 4.594883e-02 -9.893425e-01 9.983138e-01 5.336348e-02 -2.284784e-02 1.668244e+02 +-1.077680e-02 4.581944e-02 -9.988916e-01 -2.213566e+02 -5.218004e-02 9.975628e-01 4.632146e-02 -9.764641e-01 9.985796e-01 5.262139e-02 -8.359676e-03 1.668185e+02 +3.838491e-03 4.511591e-02 -9.989744e-01 -2.220306e+02 -5.207961e-02 9.976350e-01 4.485532e-02 -9.644893e-01 9.986356e-01 5.185401e-02 6.179035e-03 1.668264e+02 +1.842316e-02 4.525044e-02 -9.988058e-01 -2.226959e+02 -5.238063e-02 9.976471e-01 4.423179e-02 -9.525063e-01 9.984573e-01 5.150318e-02 2.075006e-02 1.668429e+02 +3.310923e-02 4.532266e-02 -9.984236e-01 -2.233488e+02 -5.051561e-02 9.977703e-01 4.361784e-02 -9.394063e-01 9.981743e-01 4.899182e-02 3.532491e-02 1.668730e+02 +4.787665e-02 4.450572e-02 -9.978612e-01 -2.239890e+02 -4.937464e-02 9.978910e-01 4.213810e-02 -9.272047e-01 9.976322e-01 4.725160e-02 4.997313e-02 1.669129e+02 +6.276100e-02 4.485028e-02 -9.970203e-01 -2.246154e+02 -4.730588e-02 9.980006e-01 4.191655e-02 -9.172341e-01 9.969069e-01 4.453420e-02 6.475720e-02 1.669629e+02 +7.798611e-02 4.157849e-02 -9.960870e-01 -2.252279e+02 -4.579204e-02 9.982248e-01 3.808256e-02 -9.093818e-01 9.959023e-01 4.264294e-02 7.975164e-02 1.670217e+02 +9.198595e-02 3.965608e-02 -9.949703e-01 -2.258246e+02 -4.450612e-02 9.983718e-01 3.567703e-02 -9.044080e-01 9.947652e-01 4.100048e-02 9.360113e-02 1.670879e+02 +1.064057e-01 3.880531e-02 -9.935653e-01 -2.264105e+02 -4.509063e-02 9.983985e-01 3.416512e-02 -8.990499e-01 9.932999e-01 4.116512e-02 1.079850e-01 1.671581e+02 +1.207057e-01 3.899810e-02 -9.919220e-01 -2.269870e+02 -4.287477e-02 9.985004e-01 3.403938e-02 -8.920368e-01 9.917621e-01 3.841968e-02 1.221967e-01 1.672400e+02 +1.335185e-01 3.966343e-02 -9.902523e-01 -2.275501e+02 -4.182533e-02 9.985341e-01 3.435573e-02 -8.863660e-01 9.901634e-01 3.683050e-02 1.349817e-01 1.673258e+02 +1.467149e-01 4.131578e-02 -9.883156e-01 -2.281067e+02 -3.949475e-02 9.985753e-01 3.588172e-02 -8.824469e-01 9.883901e-01 3.376890e-02 1.481376e-01 1.674196e+02 +1.589716e-01 4.303954e-02 -9.863446e-01 -2.286480e+02 -3.900762e-02 9.985430e-01 3.728489e-02 -8.786592e-01 9.865123e-01 3.254772e-02 1.604188e-01 1.675134e+02 +1.694420e-01 4.305862e-02 -9.845991e-01 -2.291782e+02 -3.996121e-02 9.985237e-01 3.679056e-02 -8.725095e-01 9.847297e-01 3.311190e-02 1.709125e-01 1.676088e+02 +1.778078e-01 4.237469e-02 -9.831525e-01 -2.296917e+02 -3.766681e-02 9.986334e-01 3.622972e-02 -8.650222e-01 9.833441e-01 3.059029e-02 1.791609e-01 1.677123e+02 +1.836921e-01 4.159786e-02 -9.821032e-01 -2.301975e+02 -3.411037e-02 9.987722e-01 3.592391e-02 -8.589438e-01 9.823919e-01 2.690096e-02 1.848855e-01 1.678180e+02 +1.865967e-01 4.122511e-02 -9.815713e-01 -2.306927e+02 -3.073121e-02 9.988752e-01 3.610987e-02 -8.530861e-01 9.819559e-01 2.342689e-02 1.876537e-01 1.679201e+02 +1.871248e-01 4.173788e-02 -9.814490e-01 -2.311791e+02 -2.810528e-02 9.989154e-01 3.712207e-02 -8.469939e-01 9.819340e-01 2.063744e-02 1.880949e-01 1.680181e+02 +1.857564e-01 4.283901e-02 -9.816615e-01 -2.316567e+02 -2.684239e-02 9.988975e-01 3.851190e-02 -8.401956e-01 9.822292e-01 1.919631e-02 1.867015e-01 1.681067e+02 +1.826595e-01 4.259623e-02 -9.822530e-01 -2.321216e+02 -2.600551e-02 9.989208e-01 3.848307e-02 -8.314175e-01 9.828323e-01 1.851469e-02 1.835701e-01 1.681921e+02 +1.771110e-01 4.269653e-02 -9.832643e-01 -2.325785e+02 -2.470218e-02 9.989366e-01 3.892759e-02 -8.239308e-01 9.838809e-01 1.739427e-02 1.779774e-01 1.682729e+02 +1.683966e-01 4.320891e-02 -9.847718e-01 -2.330235e+02 -2.318129e-02 9.989361e-01 3.986639e-02 -8.165832e-01 9.854467e-01 1.611491e-02 1.692191e-01 1.683457e+02 +1.569916e-01 4.371258e-02 -9.866321e-01 -2.334536e+02 -2.030339e-02 9.989517e-01 4.102776e-02 -8.087981e-01 9.873913e-01 1.359096e-02 1.577145e-01 1.684090e+02 +1.419476e-01 4.351335e-02 -9.889173e-01 -2.338713e+02 -1.847351e-02 9.989758e-01 4.130429e-02 -8.008611e-01 9.897018e-01 1.240573e-02 1.426061e-01 1.684619e+02 +1.243006e-01 4.278724e-02 -9.913216e-01 -2.342770e+02 -1.692981e-02 9.990158e-01 4.099654e-02 -7.921932e-01 9.921002e-01 1.168699e-02 1.249026e-01 1.685029e+02 +1.046616e-01 4.316524e-02 -9.935707e-01 -2.346695e+02 -1.685171e-02 9.989911e-01 4.162560e-02 -7.834473e-01 9.943651e-01 1.238677e-02 1.052834e-01 1.685283e+02 +8.325448e-02 4.343030e-02 -9.955815e-01 -2.350558e+02 -1.552426e-02 9.989851e-01 4.228059e-02 -7.754885e-01 9.964074e-01 1.193562e-02 8.384422e-02 1.685472e+02 +5.895824e-02 4.458473e-02 -9.972643e-01 -2.354232e+02 -1.303508e-02 9.989513e-01 4.388953e-02 -7.681360e-01 9.981754e-01 1.041178e-02 5.947758e-02 1.685506e+02 +3.132618e-02 4.599371e-02 -9.984504e-01 -2.357868e+02 -9.785060e-03 9.989069e-01 4.570774e-02 -7.590617e-01 9.994613e-01 8.338050e-03 3.174199e-02 1.685480e+02 +4.331022e-04 4.683679e-02 -9.989024e-01 -2.361394e+02 -9.021342e-03 9.988621e-01 4.683100e-02 -7.514887e-01 9.999592e-01 8.991160e-03 8.551421e-04 1.685281e+02 +-3.264386e-02 4.727134e-02 -9.983485e-01 -2.364725e+02 -9.942351e-03 9.988161e-01 4.761859e-02 -7.440649e-01 9.994176e-01 1.148039e-02 -3.213522e-02 1.684838e+02 +-6.742825e-02 4.674732e-02 -9.966284e-01 -2.368095e+02 -1.374214e-02 9.987635e-01 4.777723e-02 -7.372334e-01 9.976295e-01 1.691734e-02 -6.670247e-02 1.684318e+02 +-1.040575e-01 4.391516e-02 -9.936013e-01 -2.371197e+02 -1.592770e-02 9.988230e-01 4.581403e-02 -7.320402e-01 9.944438e-01 2.059308e-02 -1.032356e-01 1.683570e+02 +-1.416794e-01 3.913772e-02 -9.891386e-01 -2.374375e+02 -1.752389e-02 9.989624e-01 4.203647e-02 -7.269099e-01 9.897575e-01 2.328926e-02 -1.408466e-01 1.682840e+02 +-1.782391e-01 3.621659e-02 -9.833205e-01 -2.377491e+02 -1.642691e-02 9.990736e-01 3.977439e-02 -7.226217e-01 9.838501e-01 2.324227e-02 -1.774791e-01 1.682022e+02 +-2.145271e-01 3.542458e-02 -9.760754e-01 -2.380425e+02 -1.658342e-02 9.990659e-01 3.990378e-02 -7.168135e-01 9.765773e-01 2.474711e-02 -2.137393e-01 1.680989e+02 +-2.497961e-01 3.504947e-02 -9.676639e-01 -2.383427e+02 -1.582805e-02 9.990633e-01 4.027270e-02 -7.097837e-01 9.681691e-01 2.537620e-02 -2.490074e-01 1.679966e+02 +-2.848140e-01 3.422801e-02 -9.579715e-01 -2.386225e+02 -1.680192e-02 9.990305e-01 4.069042e-02 -7.024117e-01 9.584356e-01 2.768496e-02 -2.839628e-01 1.678710e+02 +-3.188608e-01 3.278289e-02 -9.472344e-01 -2.389050e+02 -2.109960e-02 9.989084e-01 4.167390e-02 -6.952770e-01 9.475667e-01 3.327444e-02 -3.178210e-01 1.677408e+02 +-3.522833e-01 2.905325e-02 -9.354423e-01 -2.391742e+02 -2.463242e-02 9.988839e-01 4.030011e-02 -6.900319e-01 9.355692e-01 3.723926e-02 -3.511745e-01 1.675987e+02 +-3.845996e-01 2.554970e-02 -9.227298e-01 -2.394235e+02 -3.025352e-02 9.987309e-01 4.026398e-02 -6.865426e-01 9.225876e-01 4.340133e-02 -3.833386e-01 1.674391e+02 +-4.153771e-01 2.406857e-02 -9.093308e-01 -2.396802e+02 -3.377024e-02 9.985527e-01 4.185620e-02 -6.821689e-01 9.090223e-01 4.809442e-02 -4.139631e-01 1.672813e+02 +-4.451012e-01 2.491126e-02 -8.951337e-01 -2.399216e+02 -3.798914e-02 9.981877e-01 4.666916e-02 -6.712409e-01 8.946741e-01 5.477786e-02 -4.433483e-01 1.671106e+02 +-4.729541e-01 2.801298e-02 -8.806416e-01 -2.401679e+02 -3.514166e-02 9.980994e-01 5.062234e-02 -6.646506e-01 8.803860e-01 5.488924e-02 -4.710708e-01 1.669481e+02 +-5.008219e-01 2.718529e-02 -8.651233e-01 -2.403930e+02 -3.480937e-02 9.980654e-01 5.151405e-02 -6.596450e-01 8.648501e-01 5.591376e-02 -4.989068e-01 1.667739e+02 +-5.267244e-01 2.311278e-02 -8.497218e-01 -2.406151e+02 -3.657635e-02 9.980882e-01 4.982131e-02 -6.509621e-01 8.492488e-01 5.732181e-02 -5.248721e-01 1.665946e+02 +-5.509240e-01 2.098228e-02 -8.342916e-01 -2.408365e+02 -3.981575e-02 9.978847e-01 5.138894e-02 -6.382377e-01 8.336051e-01 6.152934e-02 -5.489233e-01 1.664063e+02 +-5.721898e-01 2.023391e-02 -8.198715e-01 -2.410523e+02 -4.345029e-02 9.975436e-01 5.494278e-02 -6.232756e-01 8.189694e-01 6.706135e-02 -5.699052e-01 1.662067e+02 +-5.899386e-01 1.738297e-02 -8.072610e-01 -2.412710e+02 -4.775707e-02 9.972668e-01 5.637483e-02 -6.105303e-01 8.060346e-01 7.181010e-02 -5.874960e-01 1.660074e+02 +-6.059590e-01 1.288568e-02 -7.953915e-01 -2.414840e+02 -5.058646e-02 9.972209e-01 5.469407e-02 -5.996050e-01 7.938859e-01 7.337839e-02 -6.036231e-01 1.658021e+02 +-6.224363e-01 9.221787e-03 -7.826161e-01 -2.416990e+02 -4.948567e-02 9.974662e-01 5.111076e-02 -5.934784e-01 7.811045e-01 7.054146e-02 -6.204028e-01 1.656070e+02 +-6.370833e-01 1.272931e-02 -7.706898e-01 -2.419169e+02 -4.248438e-02 9.977638e-01 5.159914e-02 -5.908746e-01 7.696233e-01 6.561522e-02 -6.351178e-01 1.654069e+02 +-6.497454e-01 1.416655e-02 -7.600199e-01 -2.421335e+02 -3.844607e-02 9.979343e-01 5.146897e-02 -5.857004e-01 7.591791e-01 6.266150e-02 -6.478585e-01 1.652046e+02 +-6.626020e-01 1.319860e-02 -7.488553e-01 -2.423443e+02 -3.539845e-02 9.981755e-01 4.891413e-02 -5.766151e-01 7.481347e-01 5.891891e-02 -6.609259e-01 1.649981e+02 +-6.761111e-01 1.130384e-02 -7.367129e-01 -2.425519e+02 -3.230628e-02 9.984659e-01 4.496885e-02 -5.665866e-01 7.360911e-01 5.420439e-02 -6.747087e-01 1.647805e+02 +-6.892120e-01 8.997305e-03 -7.245039e-01 -2.427607e+02 -2.789619e-02 9.988520e-01 3.894164e-02 -5.509374e-01 7.240226e-01 4.704994e-02 -6.881698e-01 1.645648e+02 +-7.019191e-01 7.730166e-03 -7.122147e-01 -2.429631e+02 -2.516982e-02 9.990473e-01 3.564934e-02 -5.365056e-01 7.118118e-01 4.294927e-02 -7.010558e-01 1.643340e+02 +-7.156098e-01 7.914738e-03 -6.984554e-01 -2.431681e+02 -2.383779e-02 9.990766e-01 3.574457e-02 -5.242799e-01 6.980934e-01 4.222879e-02 -7.147604e-01 1.640969e+02 +-7.305536e-01 1.025615e-02 -6.827784e-01 -2.433732e+02 -2.310808e-02 9.989432e-01 3.973032e-02 -5.147036e-01 6.824643e-01 4.480282e-02 -7.295445e-01 1.638464e+02 +-7.467400e-01 1.464673e-02 -6.649548e-01 -2.435713e+02 -1.970770e-02 9.988313e-01 4.413255e-02 -5.052227e-01 6.648241e-01 4.606027e-02 -7.455786e-01 1.635855e+02 +-7.639199e-01 1.819794e-02 -6.450544e-01 -2.437699e+02 -1.671437e-02 9.987089e-01 4.796944e-02 -4.953107e-01 6.450946e-01 4.742648e-02 -7.626295e-01 1.633199e+02 +-7.810886e-01 2.106209e-02 -6.240648e-01 -2.439566e+02 -1.216580e-02 9.987279e-01 4.893383e-02 -4.851314e-01 6.243017e-01 4.581390e-02 -7.798388e-01 1.630411e+02 +-7.982605e-01 2.076333e-02 -6.019544e-01 -2.441465e+02 -1.142031e-02 9.987042e-01 4.959316e-02 -4.736289e-01 6.022042e-01 4.646276e-02 -7.969890e-01 1.627476e+02 +-8.145691e-01 2.087240e-02 -5.796909e-01 -2.443120e+02 -1.156410e-02 9.985694e-01 5.220421e-02 -4.621895e-01 5.799513e-01 4.922753e-02 -8.131625e-01 1.624453e+02 +-8.317049e-01 2.056880e-02 -5.548369e-01 -2.444907e+02 -1.077602e-02 9.985273e-01 5.317055e-02 -4.514481e-01 5.551134e-01 5.020113e-02 -8.302584e-01 1.621322e+02 +-8.488480e-01 2.152329e-02 -5.281987e-01 -2.446683e+02 -7.748388e-03 9.985569e-01 5.314182e-02 -4.380076e-01 5.285803e-01 4.920201e-02 -8.474563e-01 1.618087e+02 +-8.652322e-01 2.333295e-02 -5.008281e-01 -2.448258e+02 -2.785036e-03 9.986774e-01 5.133859e-02 -4.217408e-01 5.013636e-01 4.581462e-02 -8.640229e-01 1.614675e+02 +-8.811917e-01 2.271911e-02 -4.722129e-01 -2.449879e+02 -2.787337e-04 9.988195e-01 4.857537e-02 -4.025791e-01 4.727591e-01 4.293583e-02 -8.801451e-01 1.611168e+02 +-8.966966e-01 1.872205e-02 -4.422496e-01 -2.451278e+02 -1.681708e-03 9.989538e-01 4.569921e-02 -3.823338e-01 4.426426e-01 4.172206e-02 -8.957270e-01 1.607348e+02 +-9.110805e-01 1.281455e-02 -4.120294e-01 -2.452706e+02 -5.494158e-03 9.990504e-01 4.322025e-02 -3.612924e-01 4.121920e-01 4.164087e-02 -9.101449e-01 1.603393e+02 +-9.247890e-01 1.281865e-02 -3.802643e-01 -2.454187e+02 -4.504215e-03 9.989934e-01 4.463001e-02 -3.462077e-01 3.804537e-01 4.298613e-02 -9.238004e-01 1.599254e+02 +-9.361599e-01 1.925877e-02 -3.510467e-01 -2.455572e+02 2.633426e-03 9.988546e-01 4.777544e-02 -3.306834e-01 3.515647e-01 4.380099e-02 -9.351384e-01 1.594835e+02 +-9.456587e-01 2.163544e-02 -3.244404e-01 -2.456960e+02 6.388138e-03 9.988275e-01 4.798749e-02 -3.150386e-01 3.250983e-01 4.330721e-02 -9.446881e-01 1.590286e+02 +-9.535644e-01 1.931224e-02 -3.005695e-01 -2.458151e+02 5.187275e-03 9.988472e-01 4.772139e-02 -3.006187e-01 3.011446e-01 4.394627e-02 -9.525653e-01 1.585517e+02 +-9.590928e-01 1.518608e-02 -2.826842e-01 -2.459384e+02 1.432652e-03 9.988077e-01 4.879629e-02 -2.852335e-01 2.830882e-01 4.639517e-02 -9.579711e-01 1.580533e+02 +-9.626791e-01 1.257305e-02 -2.703532e-01 -2.460638e+02 -1.014967e-03 9.987456e-01 5.006184e-02 -2.685615e-01 2.706435e-01 4.846788e-02 -9.614588e-01 1.575327e+02 +-9.654141e-01 1.444609e-02 -2.603209e-01 -2.462000e+02 1.357840e-03 9.987288e-01 5.038726e-02 -2.480926e-01 2.607179e-01 4.829109e-02 -9.642065e-01 1.569917e+02 +-9.684038e-01 2.068822e-02 -2.485277e-01 -2.463426e+02 8.244952e-03 9.986643e-01 5.100499e-02 -2.290965e-01 2.492510e-01 4.734432e-02 -9.672810e-01 1.564306e+02 +-9.716600e-01 2.780707e-02 -2.347416e-01 -2.464823e+02 1.624702e-02 9.985646e-01 5.103735e-02 -2.083879e-01 2.358238e-01 4.577710e-02 -9.707171e-01 1.558415e+02 +-9.752005e-01 2.885452e-02 -2.194344e-01 -2.466139e+02 1.883493e-02 9.986880e-01 4.761716e-02 -1.903707e-01 2.205205e-01 4.230324e-02 -9.744646e-01 1.552300e+02 +-9.785339e-01 3.043508e-02 -2.038261e-01 -2.467355e+02 2.173692e-02 9.987604e-01 4.477863e-02 -1.659753e-01 2.049363e-01 3.938685e-02 -9.779825e-01 1.545891e+02 +-9.817011e-01 3.006991e-02 -1.880391e-01 -2.468530e+02 2.193836e-02 9.987380e-01 4.517713e-02 -1.389029e-01 1.891602e-01 4.022516e-02 -9.811220e-01 1.539159e+02 +-9.844346e-01 3.463595e-02 -1.723047e-01 -2.469677e+02 2.698214e-02 9.985507e-01 4.656645e-02 -1.088720e-01 1.736679e-01 4.119247e-02 -9.839424e-01 1.532143e+02 +-9.870513e-01 3.572799e-02 -1.563754e-01 -2.470750e+02 2.818112e-02 9.983407e-01 5.021579e-02 -8.501331e-02 1.579101e-01 4.515872e-02 -9.864204e-01 1.524803e+02 +-9.891321e-01 3.828588e-02 -1.419574e-01 -2.471762e+02 3.123618e-02 9.981812e-01 5.156156e-02 -5.578414e-02 1.436733e-01 4.656698e-02 -9.885290e-01 1.517237e+02 +-9.908804e-01 3.770228e-02 -1.293619e-01 -2.472670e+02 3.158082e-02 9.982969e-01 4.905055e-02 -2.502766e-02 1.309909e-01 4.451787e-02 -9.903835e-01 1.509436e+02 +-9.922654e-01 3.736249e-02 -1.183783e-01 -2.473551e+02 3.209594e-02 9.984216e-01 4.608818e-02 6.672745e-03 1.199134e-01 4.193224e-02 -9.918984e-01 1.501413e+02 +-9.931855e-01 3.823828e-02 -1.100927e-01 -2.474407e+02 3.341139e-02 9.984118e-01 4.536046e-02 3.865681e-02 1.116523e-01 4.137300e-02 -9.928857e-01 1.493093e+02 +-9.939423e-01 3.667675e-02 -1.036028e-01 -2.475215e+02 3.209384e-02 9.984458e-01 4.556186e-02 7.181150e-02 1.051128e-01 4.196084e-02 -9.935747e-01 1.484519e+02 +-9.944582e-01 3.633528e-02 -9.865456e-02 -2.476008e+02 3.184340e-02 9.983998e-01 4.673100e-02 1.027961e-01 1.001947e-01 4.333052e-02 -9.940239e-01 1.475729e+02 +-9.947880e-01 3.658585e-02 -9.517481e-02 -2.476815e+02 3.218414e-02 9.983583e-01 4.738021e-02 1.344629e-01 9.675201e-02 4.407014e-02 -9.943324e-01 1.466712e+02 +-9.950117e-01 3.694281e-02 -9.266555e-02 -2.477634e+02 3.277014e-02 9.983966e-01 4.615429e-02 1.704041e-01 9.422205e-02 4.288739e-02 -9.946270e-01 1.457494e+02 +-9.951810e-01 3.715531e-02 -9.074284e-02 -2.478453e+02 3.308913e-02 9.983973e-01 4.591114e-02 2.055884e-01 9.230326e-02 4.268729e-02 -9.948155e-01 1.448041e+02 +-9.952948e-01 3.822499e-02 -8.903458e-02 -2.479304e+02 3.415448e-02 9.983201e-01 4.680221e-02 2.420599e-01 9.067403e-02 4.354106e-02 -9.949283e-01 1.438343e+02 +-9.953519e-01 4.061038e-02 -8.732336e-02 -2.480180e+02 3.653484e-02 9.981897e-01 4.777477e-02 2.815153e-01 8.910543e-02 4.436236e-02 -9.950338e-01 1.428411e+02 +-9.954207e-01 4.263928e-02 -8.555473e-02 -2.481048e+02 3.849378e-02 9.980304e-01 4.953330e-02 3.208857e-01 8.749828e-02 4.601314e-02 -9.951014e-01 1.418238e+02 +-9.954230e-01 4.632187e-02 -8.359044e-02 -2.481925e+02 4.212876e-02 9.977969e-01 5.124863e-02 3.629577e-01 8.578023e-02 4.749250e-02 -9.951815e-01 1.407837e+02 +-9.955640e-01 4.624479e-02 -8.193771e-02 -2.482772e+02 4.228750e-02 9.978839e-01 4.939160e-02 4.036542e-01 8.404843e-02 4.570755e-02 -9.954128e-01 1.397205e+02 +-9.956572e-01 4.684216e-02 -8.045281e-02 -2.483614e+02 4.324306e-02 9.980091e-01 4.591095e-02 4.450745e-01 8.244321e-02 4.223253e-02 -9.957005e-01 1.386355e+02 +-9.958494e-01 4.567988e-02 -7.872301e-02 -2.484434e+02 4.242403e-02 9.981933e-01 4.254695e-02 4.856777e-01 8.052432e-02 3.903060e-02 -9.959882e-01 1.375273e+02 +-9.960865e-01 4.301062e-02 -7.721207e-02 -2.485231e+02 3.976544e-02 9.982796e-01 4.308684e-02 5.232463e-01 7.893243e-02 3.984785e-02 -9.960832e-01 1.363895e+02 +-9.962636e-01 4.144093e-02 -7.577243e-02 -2.486041e+02 3.811096e-02 9.982652e-01 4.487774e-02 5.595817e-01 7.750076e-02 4.182229e-02 -9.961147e-01 1.352321e+02 +-9.963170e-01 4.280713e-02 -7.429648e-02 -2.486891e+02 3.918374e-02 9.980022e-01 4.956091e-02 5.985779e-01 7.626961e-02 4.646716e-02 -9.960039e-01 1.340542e+02 +-9.963797e-01 4.442764e-02 -7.248225e-02 -2.487732e+02 4.049385e-02 9.976721e-01 5.486837e-02 6.419872e-01 7.475119e-02 5.173464e-02 -9.958593e-01 1.328705e+02 +-9.963861e-01 4.753209e-02 -7.039473e-02 -2.488563e+02 4.321834e-02 9.971657e-01 6.158458e-02 6.871201e-01 7.312246e-02 5.831967e-02 -9.956164e-01 1.316857e+02 +-9.964200e-01 5.000603e-02 -6.816583e-02 -2.489393e+02 4.582748e-02 9.970517e-01 6.154404e-02 7.334063e-01 7.104243e-02 5.819983e-02 -9.957740e-01 1.305080e+02 +-9.965426e-01 5.002963e-02 -6.633117e-02 -2.490158e+02 4.612876e-02 9.971862e-01 5.909129e-02 7.775391e-01 6.910085e-02 5.582720e-02 -9.960464e-01 1.293357e+02 +-9.967358e-01 4.903146e-02 -6.413737e-02 -2.490873e+02 4.545071e-02 9.973875e-01 5.614573e-02 8.166562e-01 6.672273e-02 5.304736e-02 -9.963604e-01 1.281648e+02 +-9.969816e-01 4.728149e-02 -6.158091e-02 -2.491564e+02 4.388195e-02 9.974976e-01 5.543428e-02 8.564476e-01 6.404782e-02 5.256466e-02 -9.965615e-01 1.269897e+02 +-9.972970e-01 4.405498e-02 -5.880405e-02 -2.492184e+02 4.075614e-02 9.975892e-01 5.616650e-02 8.958454e-01 6.113670e-02 5.361805e-02 -9.966882e-01 1.258149e+02 +-9.974979e-01 4.202018e-02 -5.685282e-02 -2.492779e+02 3.882715e-02 9.976672e-01 5.614787e-02 9.397070e-01 5.907954e-02 5.379994e-02 -9.968025e-01 1.246419e+02 +-9.976028e-01 4.235843e-02 -5.472111e-02 -2.493389e+02 3.920966e-02 9.975817e-01 5.738806e-02 9.865670e-01 5.701964e-02 5.510488e-02 -9.968512e-01 1.234622e+02 +-9.977659e-01 4.207682e-02 -5.189176e-02 -2.493978e+02 3.904520e-02 9.975461e-01 5.811352e-02 1.029505e+00 5.420966e-02 5.595756e-02 -9.969604e-01 1.222863e+02 +-9.978219e-01 4.383164e-02 -4.929744e-02 -2.494573e+02 4.096901e-02 9.974957e-01 5.765239e-02 1.073562e+00 5.170099e-02 5.550714e-02 -9.971188e-01 1.211090e+02 +-9.979111e-01 4.473115e-02 -4.661131e-02 -2.495133e+02 4.200202e-02 9.974343e-01 5.797149e-02 1.116077e+00 4.908485e-02 5.589261e-02 -9.972295e-01 1.199316e+02 +-9.980054e-01 4.450690e-02 -4.477122e-02 -2.495652e+02 4.185246e-02 9.974053e-01 5.857464e-02 1.158347e+00 4.726203e-02 5.658401e-02 -9.972786e-01 1.187550e+02 +-9.981337e-01 4.343324e-02 -4.292575e-02 -2.496122e+02 4.086466e-02 9.974209e-01 5.900523e-02 1.200686e+00 4.537783e-02 5.714096e-02 -9.973343e-01 1.175798e+02 +-9.983154e-01 4.076694e-02 -4.128419e-02 -2.496546e+02 3.826023e-02 9.974775e-01 5.978919e-02 1.243901e+00 4.361748e-02 5.810892e-02 -9.973570e-01 1.164065e+02 +-9.984331e-01 3.917344e-02 -3.995902e-02 -2.496974e+02 3.676840e-02 9.975661e-01 5.924381e-02 1.287102e+00 4.218255e-02 5.768175e-02 -9.974435e-01 1.152382e+02 +-9.985366e-01 3.750363e-02 -3.896385e-02 -2.497381e+02 3.513976e-02 9.975990e-01 5.967742e-02 1.332002e+00 4.110842e-02 5.822090e-02 -9.974570e-01 1.140680e+02 +-9.985874e-01 3.654748e-02 -3.856937e-02 -2.497789e+02 3.420879e-02 9.976332e-01 5.964661e-02 1.374204e+00 4.065802e-02 5.824293e-02 -9.974742e-01 1.129055e+02 +-9.986145e-01 3.660660e-02 -3.780269e-02 -2.498202e+02 3.437333e-02 9.977172e-01 5.812685e-02 1.417276e+00 3.984423e-02 5.674690e-02 -9.975932e-01 1.117419e+02 +-9.986412e-01 3.664945e-02 -3.704866e-02 -2.498613e+02 3.450625e-02 9.977822e-01 5.692030e-02 1.459159e+00 3.905260e-02 5.556454e-02 -9.976911e-01 1.105835e+02 +-9.986607e-01 3.718119e-02 -3.597858e-02 -2.499023e+02 3.505884e-02 9.977052e-01 5.792334e-02 1.500434e+00 3.804968e-02 5.658439e-02 -9.976725e-01 1.094248e+02 +-9.986366e-01 3.887567e-02 -3.483603e-02 -2.499433e+02 3.675386e-02 9.975450e-01 5.960761e-02 1.543852e+00 3.706780e-02 5.824597e-02 -9.976139e-01 1.082684e+02 +-9.987069e-01 3.813140e-02 -3.362235e-02 -2.499793e+02 3.603329e-02 9.974906e-01 6.094264e-02 1.587680e+00 3.586181e-02 5.965230e-02 -9.975748e-01 1.071143e+02 +-9.987567e-01 3.793125e-02 -3.234772e-02 -2.500131e+02 3.594905e-02 9.975627e-01 5.980206e-02 1.631849e+00 3.453725e-02 5.856483e-02 -9.976860e-01 1.059629e+02 +-9.988647e-01 3.661872e-02 -3.047113e-02 -2.500448e+02 3.476972e-02 9.976437e-01 5.914485e-02 1.676822e+00 3.256514e-02 5.801822e-02 -9.977843e-01 1.048150e+02 +-9.989707e-01 3.510952e-02 -2.872128e-02 -2.500737e+02 3.335842e-02 9.976809e-01 5.932994e-02 1.718794e+00 3.073772e-02 5.831077e-02 -9.978252e-01 1.036695e+02 +-9.990533e-01 3.427910e-02 -2.678409e-02 -2.501003e+02 3.261095e-02 9.976405e-01 6.041482e-02 1.761959e+00 2.879186e-02 5.948417e-02 -9.978140e-01 1.025248e+02 +-9.991035e-01 3.417001e-02 -2.499072e-02 -2.501253e+02 3.262430e-02 9.976745e-01 5.984246e-02 1.804161e+00 2.697743e-02 5.897350e-02 -9.978950e-01 1.013868e+02 +-9.991768e-01 3.326016e-02 -2.322579e-02 -2.501481e+02 3.188977e-02 9.978607e-01 5.707044e-02 1.843847e+00 2.507428e-02 5.628279e-02 -9.981000e-01 1.002511e+02 +-9.992411e-01 3.218067e-02 -2.194545e-02 -2.501691e+02 3.095213e-02 9.980506e-01 5.419378e-02 1.882550e+00 2.364666e-02 5.347339e-02 -9.982893e-01 9.911866e+01 +-9.992511e-01 3.229989e-02 -2.130739e-02 -2.501893e+02 3.109961e-02 9.980324e-01 5.444286e-02 1.922280e+00 2.302397e-02 5.373942e-02 -9.982895e-01 9.798601e+01 +-9.993234e-01 3.040074e-02 -2.070319e-02 -2.502072e+02 2.917290e-02 9.979348e-01 5.722811e-02 1.959653e+00 2.240021e-02 5.658541e-02 -9.981465e-01 9.685531e+01 +-9.993459e-01 2.993064e-02 -2.029688e-02 -2.502252e+02 2.867074e-02 9.978012e-01 5.975566e-02 1.999499e+00 2.204078e-02 5.913464e-02 -9.980067e-01 9.572318e+01 +-9.993471e-01 3.018569e-02 -1.985297e-02 -2.502440e+02 2.895747e-02 9.978089e-01 5.948754e-02 2.039049e+00 2.160515e-02 5.887380e-02 -9.980316e-01 9.459878e+01 +-9.993164e-01 3.084021e-02 -2.038784e-02 -2.502640e+02 2.963243e-02 9.979285e-01 5.710112e-02 2.077975e+00 2.210662e-02 5.645794e-02 -9.981602e-01 9.348269e+01 +-9.993238e-01 2.974620e-02 -2.161236e-02 -2.502833e+02 2.854147e-02 9.981296e-01 5.406204e-02 2.114060e+00 2.318007e-02 5.340863e-02 -9.983037e-01 9.236877e+01 +-9.993226e-01 2.801972e-02 -2.385821e-02 -2.503056e+02 2.674484e-02 9.982797e-01 5.217491e-02 2.147887e+00 2.527909e-02 5.150148e-02 -9.983529e-01 9.125917e+01 +-9.992890e-01 2.571774e-02 -2.757078e-02 -2.503296e+02 2.419338e-02 9.982334e-01 5.426538e-02 2.179142e+00 2.891766e-02 5.355976e-02 -9.981459e-01 9.014576e+01 +-9.991364e-01 2.654568e-02 -3.196470e-02 -2.503622e+02 2.476427e-02 9.981851e-01 5.489276e-02 2.212074e+00 3.336385e-02 5.405376e-02 -9.979805e-01 8.903749e+01 +-9.989565e-01 2.783805e-02 -3.620806e-02 -2.504001e+02 2.587715e-02 9.982302e-01 5.354203e-02 2.245753e+00 3.763449e-02 5.254919e-02 -9.979089e-01 8.793668e+01 +-9.987007e-01 3.206676e-02 -3.960635e-02 -2.504481e+02 3.000829e-02 9.982211e-01 5.151771e-02 2.278946e+00 4.118791e-02 5.026225e-02 -9.978864e-01 8.683995e+01 +-9.985020e-01 3.463499e-02 -4.235889e-02 -2.504984e+02 3.233966e-02 9.980321e-01 5.372244e-02 2.312027e+00 4.413621e-02 5.227208e-02 -9.976571e-01 8.574277e+01 +-9.982744e-01 3.767069e-02 -4.504523e-02 -2.505497e+02 3.505918e-02 9.977341e-01 5.742359e-02 2.348702e+00 4.710636e-02 5.574525e-02 -9.973332e-01 8.464524e+01 +-9.982811e-01 3.509747e-02 -4.693733e-02 -2.505976e+02 3.211248e-02 9.975028e-01 6.290410e-02 2.388874e+00 4.902789e-02 6.128869e-02 -9.969152e-01 8.354718e+01 +-9.983679e-01 2.956492e-02 -4.886257e-02 -2.506416e+02 2.614550e-02 9.972604e-01 6.919635e-02 2.434553e+00 5.077449e-02 6.780587e-02 -9.964057e-01 8.244945e+01 +-9.983218e-01 2.760321e-02 -5.090910e-02 -2.506902e+02 2.388696e-02 9.971030e-01 7.221459e-02 2.482656e+00 5.275497e-02 7.087732e-02 -9.960890e-01 8.135667e+01 +-9.983847e-01 2.134345e-02 -5.265355e-02 -2.507343e+02 1.779534e-02 9.975971e-01 6.695797e-02 2.530906e+00 5.395614e-02 6.591282e-02 -9.963655e-01 8.027234e+01 +-9.983719e-01 2.006332e-02 -5.339536e-02 -2.507859e+02 1.692092e-02 9.981342e-01 5.866659e-02 2.575919e+00 5.447278e-02 5.766757e-02 -9.968486e-01 7.918868e+01 +-9.983051e-01 2.349088e-02 -5.324590e-02 -2.508470e+02 2.066062e-02 9.983756e-01 5.309575e-02 2.617494e+00 5.440668e-02 5.190565e-02 -9.971689e-01 7.810380e+01 +-9.982931e-01 2.497009e-02 -5.279638e-02 -2.509057e+02 2.209730e-02 9.982794e-01 5.431356e-02 2.659920e+00 5.406176e-02 5.305418e-02 -9.971272e-01 7.701311e+01 +-9.982397e-01 2.720195e-02 -5.270323e-02 -2.509642e+02 2.418806e-02 9.980809e-01 5.700370e-02 2.700125e+00 5.415270e-02 5.562855e-02 -9.969819e-01 7.591871e+01 +-9.982433e-01 2.741717e-02 -5.252353e-02 -2.510203e+02 2.419230e-02 9.978396e-01 6.108024e-02 2.742240e+00 5.408471e-02 5.970227e-02 -9.967500e-01 7.482449e+01 +-9.982544e-01 2.675915e-02 -5.265167e-02 -2.510737e+02 2.335164e-02 9.976572e-01 6.430190e-02 2.790144e+00 5.424898e-02 6.296014e-02 -9.965406e-01 7.372705e+01 +-9.982709e-01 2.419851e-02 -5.356836e-02 -2.511257e+02 2.060173e-02 9.975599e-01 6.670656e-02 2.836662e+00 5.505185e-02 6.548761e-02 -9.963336e-01 7.263674e+01 +-9.982172e-01 2.470888e-02 -5.433163e-02 -2.511812e+02 2.105558e-02 9.975432e-01 6.681475e-02 2.887503e+00 5.584907e-02 6.555164e-02 -9.962850e-01 7.154963e+01 +-9.982103e-01 2.442303e-02 -5.458601e-02 -2.512376e+02 2.090243e-02 9.977205e-01 6.416197e-02 2.935570e+00 5.602861e-02 6.290616e-02 -9.964455e-01 7.046480e+01 +-9.981981e-01 2.598324e-02 -5.408792e-02 -2.512974e+02 2.253371e-02 9.977314e-01 6.343753e-02 2.982870e+00 5.561353e-02 6.210441e-02 -9.965190e-01 6.938060e+01 +-9.982368e-01 2.636999e-02 -5.317789e-02 -2.513532e+02 2.301159e-02 9.977604e-01 6.280666e-02 3.027809e+00 5.471501e-02 6.147220e-02 -9.966080e-01 6.829941e+01 +-9.982953e-01 2.657529e-02 -5.196456e-02 -2.514065e+02 2.328434e-02 9.977455e-01 6.294179e-02 3.073084e+00 5.352011e-02 6.162452e-02 -9.966635e-01 6.722089e+01 +-9.983900e-01 2.650940e-02 -5.014610e-02 -2.514574e+02 2.329017e-02 9.976955e-01 6.372683e-02 3.116928e+00 5.171990e-02 6.245631e-02 -9.967067e-01 6.614286e+01 +-9.984976e-01 2.557010e-02 -4.846367e-02 -2.515044e+02 2.240049e-02 9.976433e-01 6.485314e-02 3.160878e+00 5.000776e-02 6.367009e-02 -9.967173e-01 6.506813e+01 +-9.986112e-01 2.458381e-02 -4.659714e-02 -2.515491e+02 2.151071e-02 9.976310e-01 6.534205e-02 3.206256e+00 4.809312e-02 6.424896e-02 -9.967744e-01 6.399155e+01 +-9.987089e-01 2.414189e-02 -4.469491e-02 -2.515927e+02 2.119564e-02 9.976432e-01 6.525864e-02 3.251783e+00 4.616504e-02 6.422704e-02 -9.968669e-01 6.292070e+01 +-9.987908e-01 2.419292e-02 -4.279737e-02 -2.516351e+02 2.138283e-02 9.976599e-01 6.494194e-02 3.296922e+00 4.426836e-02 6.394828e-02 -9.969709e-01 6.185252e+01 +-9.988869e-01 2.357923e-02 -4.085301e-02 -2.516749e+02 2.092134e-02 9.977107e-01 6.430879e-02 3.342394e+00 4.227584e-02 6.338250e-02 -9.970935e-01 6.078690e+01 +-9.989742e-01 2.312560e-02 -3.893263e-02 -2.517122e+02 2.060369e-02 9.977387e-01 6.397615e-02 3.385498e+00 4.032408e-02 6.310836e-02 -9.971917e-01 5.972549e+01 +-9.990730e-01 2.153233e-02 -3.727566e-02 -2.517477e+02 1.912391e-02 9.977792e-01 6.380427e-02 3.426715e+00 3.856673e-02 6.303226e-02 -9.972660e-01 5.866186e+01 +-9.991444e-01 2.052454e-02 -3.590577e-02 -2.517821e+02 1.822556e-02 9.978329e-01 6.322408e-02 3.465372e+00 3.712561e-02 6.251557e-02 -9.973533e-01 5.760151e+01 +-9.992158e-01 1.907805e-02 -3.469731e-02 -2.518135e+02 1.684229e-02 9.978317e-01 6.362506e-02 3.507027e+00 3.583592e-02 6.299077e-02 -9.973705e-01 5.654650e+01 +-9.992598e-01 1.849572e-02 -3.373237e-02 -2.518453e+02 1.630330e-02 9.978071e-01 6.414997e-02 3.548046e+00 3.484490e-02 6.355252e-02 -9.973700e-01 5.548984e+01 +-9.993051e-01 1.737036e-02 -3.297802e-02 -2.518762e+02 1.521640e-02 9.978030e-01 6.447903e-02 3.588934e+00 3.402559e-02 6.393240e-02 -9.973740e-01 5.443875e+01 +-9.993229e-01 1.670983e-02 -3.277895e-02 -2.519056e+02 1.455785e-02 9.977904e-01 6.482580e-02 3.632120e+00 3.378976e-02 6.430471e-02 -9.973581e-01 5.338734e+01 +-9.993309e-01 1.581326e-02 -3.298123e-02 -2.519359e+02 1.366376e-02 9.978299e-01 6.441035e-02 3.673762e+00 3.392820e-02 6.391659e-02 -9.973783e-01 5.234366e+01 +-9.993259e-01 1.484518e-02 -3.357639e-02 -2.519668e+02 1.267922e-02 9.978805e-01 6.382604e-02 3.715463e+00 3.445274e-02 6.335729e-02 -9.973961e-01 5.129772e+01 +-9.993242e-01 1.389487e-02 -3.402958e-02 -2.519987e+02 1.173796e-02 9.979581e-01 6.278326e-02 3.756318e+00 3.483246e-02 6.234138e-02 -9.974469e-01 5.025774e+01 +-9.992998e-01 1.252929e-02 -3.525535e-02 -2.520309e+02 1.030294e-02 9.979831e-01 6.263756e-02 3.796550e+00 3.596905e-02 6.223046e-02 -9.974135e-01 4.922008e+01 +-9.992351e-01 1.138962e-02 -3.741102e-02 -2.520653e+02 9.024539e-03 9.979859e-01 6.279048e-02 3.837981e+00 3.805083e-02 6.240482e-02 -9.973253e-01 4.818245e+01 +-9.991319e-01 9.908488e-03 -4.046323e-02 -2.521023e+02 7.320663e-03 9.979480e-01 6.360975e-02 3.879003e+00 4.101047e-02 6.325830e-02 -9.971542e-01 4.714700e+01 +-9.989945e-01 1.035811e-02 -4.362110e-02 -2.521440e+02 7.508857e-03 9.978581e-01 6.498301e-02 3.921326e+00 4.420078e-02 6.459011e-02 -9.969325e-01 4.611671e+01 +-9.988630e-01 1.017353e-02 -4.657527e-02 -2.521878e+02 7.130408e-03 9.978569e-01 6.504395e-02 3.963638e+00 4.713718e-02 6.463788e-02 -9.967949e-01 4.509288e+01 +-9.987200e-01 1.057051e-02 -4.946445e-02 -2.522349e+02 7.378018e-03 9.979043e-01 6.428435e-02 4.004914e+00 5.004031e-02 6.383710e-02 -9.967050e-01 4.406300e+01 +-9.985902e-01 1.073584e-02 -5.198386e-02 -2.522851e+02 7.407541e-03 9.979352e-01 6.380030e-02 4.046284e+00 5.256147e-02 6.332528e-02 -9.966079e-01 4.303916e+01 +-9.984639e-01 1.100505e-02 -5.430177e-02 -2.523375e+02 7.543684e-03 9.979507e-01 6.354133e-02 4.086177e+00 5.488977e-02 6.303408e-02 -9.965008e-01 4.201855e+01 +-9.983671e-01 1.076647e-02 -5.610067e-02 -2.523910e+02 7.205016e-03 9.979683e-01 6.330321e-02 4.125653e+00 5.666824e-02 6.279563e-02 -9.964163e-01 4.100164e+01 +-9.982757e-01 1.142510e-02 -5.757705e-02 -2.524478e+02 7.775771e-03 9.979698e-01 6.321177e-02 4.164157e+00 5.818236e-02 6.265506e-02 -9.963379e-01 3.998803e+01 +-9.981907e-01 1.131946e-02 -5.905266e-02 -2.525055e+02 7.523969e-03 9.979148e-01 6.410397e-02 4.203496e+00 5.965516e-02 6.354367e-02 -9.961945e-01 3.897320e+01 +-9.981095e-01 1.135855e-02 -6.040300e-02 -2.525653e+02 7.481318e-03 9.979197e-01 6.403247e-02 4.241031e+00 6.100466e-02 6.345951e-02 -9.961181e-01 3.796223e+01 +-9.980473e-01 1.160400e-02 -6.137527e-02 -2.526254e+02 7.698257e-03 9.979524e-01 6.349509e-02 4.278741e+00 6.198641e-02 6.289861e-02 -9.960931e-01 3.695639e+01 +-9.979633e-01 1.218420e-02 -6.261635e-02 -2.526885e+02 8.240594e-03 9.979885e-01 6.285726e-02 4.313927e+00 6.325627e-02 6.221324e-02 -9.960563e-01 3.595330e+01 +-9.979011e-01 1.241453e-02 -6.355480e-02 -2.527498e+02 8.446128e-03 9.980197e-01 6.233285e-02 4.352801e+00 6.420277e-02 6.166522e-02 -9.960298e-01 3.495497e+01 +-9.978697e-01 1.239268e-02 -6.405007e-02 -2.528107e+02 8.333787e-03 9.979627e-01 6.325373e-02 4.392094e+00 6.470347e-02 6.258520e-02 -9.959400e-01 3.395482e+01 +-9.979258e-01 1.379798e-02 -6.287803e-02 -2.528716e+02 9.722960e-03 9.978600e-01 6.465954e-02 4.430341e+00 6.363564e-02 6.391405e-02 -9.959245e-01 3.295905e+01 +-9.980599e-01 1.542313e-02 -6.032010e-02 -2.529301e+02 1.148562e-02 9.978134e-01 6.508741e-02 4.468067e+00 6.119206e-02 6.426832e-02 -9.960548e-01 3.196578e+01 +-9.983029e-01 1.687207e-02 -5.573735e-02 -2.529844e+02 1.327236e-02 9.978401e-01 6.433392e-02 4.504925e+00 5.670242e-02 6.348496e-02 -9.963707e-01 3.097807e+01 +-9.986385e-01 1.723316e-02 -4.923533e-02 -2.530304e+02 1.404830e-02 9.978307e-01 6.431589e-02 4.541451e+00 5.023689e-02 6.353664e-02 -9.967143e-01 2.999395e+01 +-9.989971e-01 1.798514e-02 -4.100360e-02 -2.530691e+02 1.533086e-02 9.978223e-01 6.415284e-02 4.577433e+00 4.206810e-02 6.345987e-02 -9.970974e-01 2.900968e+01 +-9.993331e-01 1.816843e-02 -3.167317e-02 -2.530976e+02 1.609515e-02 9.977861e-01 6.452789e-02 4.612032e+00 3.277542e-02 6.397506e-02 -9.974131e-01 2.802895e+01 +-9.996024e-01 1.799587e-02 -2.170874e-02 -2.531145e+02 1.654970e-02 9.977447e-01 6.505102e-02 4.646341e+00 2.283043e-02 6.466587e-02 -9.976458e-01 2.704982e+01 +-9.997838e-01 1.747124e-02 -1.127698e-02 -2.531216e+02 1.669241e-02 9.976925e-01 6.581024e-02 4.680418e+00 1.240075e-02 6.560776e-02 -9.977684e-01 2.607376e+01 +-9.998508e-01 1.726499e-02 -4.939165e-04 -2.531163e+02 1.719378e-02 9.976313e-01 6.660400e-02 4.716997e+00 1.642664e-03 6.658556e-02 -9.977794e-01 2.510115e+01 +-9.997983e-01 1.698413e-02 1.071812e-02 -2.531022e+02 1.766215e-02 9.976166e-01 6.670201e-02 4.753821e+00 -9.559699e-03 6.687785e-02 -9.977154e-01 2.413040e+01 +-9.995801e-01 1.860430e-02 2.221497e-02 -2.530788e+02 2.000301e-02 9.977175e-01 6.449524e-02 4.788928e+00 -2.096438e-02 6.491251e-02 -9.976707e-01 2.316709e+01 +-9.992336e-01 1.890839e-02 3.427470e-02 -2.530411e+02 2.097467e-02 9.979195e-01 6.096428e-02 4.823440e+00 -3.305066e-02 6.163645e-02 -9.975513e-01 2.220336e+01 +-9.986510e-01 2.034033e-02 4.777513e-02 -2.529925e+02 2.321455e-02 9.979044e-01 6.039796e-02 4.860664e+00 -4.644650e-02 6.142555e-02 -9.970304e-01 2.124133e+01 +-9.977434e-01 2.184416e-02 6.348967e-02 -2.529274e+02 2.583485e-02 9.976961e-01 6.273011e-02 4.897579e+00 -6.197311e-02 6.422879e-02 -9.960090e-01 2.028205e+01 +-9.964414e-01 2.315605e-02 8.104520e-02 -2.528481e+02 2.833530e-02 9.975890e-01 6.335024e-02 4.933245e+00 -7.938287e-02 6.542123e-02 -9.946951e-01 1.932422e+01 +-9.947052e-01 2.448950e-02 9.980920e-02 -2.527503e+02 3.069810e-02 9.976563e-01 6.115108e-02 4.970231e+00 -9.807773e-02 6.389124e-02 -9.931257e-01 1.837471e+01 +-9.925035e-01 2.483698e-02 1.196662e-01 -2.526280e+02 3.200961e-02 9.977803e-01 5.839399e-02 5.006666e+00 -1.179502e-01 6.178670e-02 -9.910954e-01 1.742620e+01 +-9.899051e-01 2.385039e-02 1.397109e-01 -2.524880e+02 3.220588e-02 9.978055e-01 5.785303e-02 5.042073e+00 -1.380245e-01 6.176851e-02 -9.885008e-01 1.648091e+01 +-9.868566e-01 2.187640e-02 1.601106e-01 -2.523224e+02 3.152586e-02 9.978200e-01 5.797734e-02 5.079397e+00 -1.584932e-01 6.226294e-02 -9.853950e-01 1.553465e+01 +-9.833505e-01 2.050474e-02 1.805585e-01 -2.521417e+02 3.150694e-02 9.978030e-01 5.827844e-02 5.115032e+00 -1.789668e-01 6.299697e-02 -9.818362e-01 1.459081e+01 +-9.791979e-01 2.108515e-02 2.018091e-01 -2.519437e+02 3.331722e-02 9.977947e-01 5.740817e-02 5.150790e+00 -2.001536e-01 6.293767e-02 -9.777410e-01 1.365046e+01 +-9.744768e-01 2.039614e-02 2.235599e-01 -2.517170e+02 3.390114e-02 9.978133e-01 5.673792e-02 5.186491e+00 -2.219138e-01 6.286871e-02 -9.730374e-01 1.271269e+01 +-9.691245e-01 2.099491e-02 2.456763e-01 -2.514760e+02 3.542951e-02 9.978859e-01 5.448255e-02 5.219589e+00 -2.440131e-01 6.150456e-02 -9.678196e-01 1.177835e+01 +-9.631492e-01 2.039227e-02 2.681937e-01 -2.512062e+02 3.568539e-02 9.979951e-01 5.227178e-02 5.249930e+00 -2.665900e-01 5.991611e-02 -9.619459e-01 1.084625e+01 +-9.566009e-01 2.010437e-02 2.907070e-01 -2.509196e+02 3.605198e-02 9.981180e-01 4.960599e-02 5.281337e+00 -2.891626e-01 5.793369e-02 -9.555253e-01 9.917723e+00 +-9.494964e-01 1.959261e-02 3.131658e-01 -2.506095e+02 3.667924e-02 9.981367e-01 4.876232e-02 5.310708e+00 -3.116269e-01 5.778632e-02 -9.484458e-01 8.989691e+00 +-9.418590e-01 1.833820e-02 3.355075e-01 -2.502693e+02 3.690306e-02 9.981147e-01 4.904165e-02 5.338465e+00 -3.339756e-01 5.857156e-02 -9.407602e-01 8.064427e+00 +-9.336462e-01 1.745826e-02 3.577708e-01 -2.499109e+02 3.765520e-02 9.980609e-01 4.956305e-02 5.369207e+00 -3.562118e-01 5.974628e-02 -9.324932e-01 7.145792e+00 +-9.247223e-01 1.703902e-02 3.802610e-01 -2.495229e+02 3.921164e-02 9.979470e-01 5.063846e-02 5.400639e+00 -3.786175e-01 6.173716e-02 -9.234919e-01 6.226439e+00 +-9.152499e-01 1.882191e-02 4.024466e-01 -2.491194e+02 4.278611e-02 9.978001e-01 5.063892e-02 5.433542e+00 -4.006082e-01 6.356638e-02 -9.140418e-01 5.314832e+00 +-9.051100e-01 1.952570e-02 4.247290e-01 -2.486906e+02 4.411226e-02 9.978665e-01 4.813044e-02 5.465713e+00 -4.228831e-01 6.229908e-02 -9.040402e-01 4.411448e+00 +-8.944732e-01 1.898156e-02 4.467185e-01 -2.482273e+02 4.464792e-02 9.978967e-01 4.699765e-02 5.501097e+00 -4.448869e-01 6.198318e-02 -8.934393e-01 3.510403e+00 +-8.838282e-01 1.679176e-02 4.675101e-01 -2.477460e+02 4.415324e-02 9.978887e-01 4.763012e-02 5.534324e+00 -4.657232e-01 6.273892e-02 -8.827036e-01 2.616861e+00 +-8.735763e-01 1.398805e-02 4.864861e-01 -2.472381e+02 4.311398e-02 9.978812e-01 4.872685e-02 5.564578e+00 -4.847738e-01 6.354096e-02 -8.723285e-01 1.732723e+00 +-8.629723e-01 1.391656e-02 5.050595e-01 -2.467137e+02 4.214382e-02 9.981197e-01 4.450674e-02 5.598240e+00 -5.034905e-01 5.969321e-02 -8.619362e-01 8.535689e-01 +-8.521251e-01 1.496797e-02 5.231241e-01 -2.461661e+02 4.226897e-02 9.982936e-01 4.028873e-02 5.631630e+00 -5.216285e-01 5.644294e-02 -8.513037e-01 -1.796892e-02 +-8.414981e-01 1.365244e-02 5.400876e-01 -2.456007e+02 4.115391e-02 9.983959e-01 3.888329e-02 5.655536e+00 -5.386904e-01 5.494692e-02 -8.407101e-01 -8.863481e-01 +-8.316057e-01 1.158771e-02 5.552457e-01 -2.450122e+02 3.969992e-02 9.984649e-01 3.862209e-02 5.677791e+00 -5.539458e-01 5.416155e-02 -8.307891e-01 -1.755502e+00 +-8.228409e-01 1.081267e-02 5.681689e-01 -2.444063e+02 3.910908e-02 9.985259e-01 3.763635e-02 5.699836e+00 -5.669245e-01 5.318928e-02 -8.220508e-01 -2.619939e+00 +-8.157178e-01 7.751243e-03 5.783982e-01 -2.437822e+02 3.567093e-02 9.986812e-01 3.692333e-02 5.721996e+00 -5.773492e-01 5.075101e-02 -8.149185e-01 -3.482793e+00 +-8.099022e-01 3.832618e-03 5.865524e-01 -2.431481e+02 3.237472e-02 9.987464e-01 3.817653e-02 5.744050e+00 -5.856709e-01 4.990872e-02 -8.090110e-01 -4.341979e+00 +-8.055043e-01 3.096002e-03 5.925818e-01 -2.425070e+02 3.085268e-02 9.988492e-01 3.671986e-02 5.765582e+00 -5.917863e-01 4.786073e-02 -8.046729e-01 -5.201607e+00 +-8.022902e-01 2.481123e-03 5.969291e-01 -2.418568e+02 2.965385e-02 9.989223e-01 3.570363e-02 5.784410e+00 -5.961972e-01 4.634590e-02 -8.014992e-01 -6.066389e+00 +-7.996766e-01 2.884095e-03 6.004240e-01 -2.412026e+02 2.990594e-02 9.989386e-01 3.503198e-02 5.801983e+00 -5.996857e-01 4.597049e-02 -7.989141e-01 -6.934215e+00 +-7.978448e-01 4.405808e-03 6.028468e-01 -2.405437e+02 3.003379e-02 9.990221e-01 3.244737e-02 5.816429e+00 -6.021144e-01 4.399373e-02 -7.971969e-01 -7.805212e+00 +-7.964391e-01 4.930061e-03 6.046987e-01 -2.398756e+02 2.940854e-02 9.990993e-01 3.058794e-02 5.831215e+00 -6.040033e-01 4.214473e-02 -7.958667e-01 -8.680885e+00 +-7.953220e-01 4.724253e-03 6.061688e-01 -2.392054e+02 2.959217e-02 9.990800e-01 3.103985e-02 5.844869e+00 -6.054645e-01 4.262451e-02 -7.947301e-01 -9.558654e+00 +-7.944682e-01 3.896271e-03 6.072932e-01 -2.385276e+02 2.872274e-02 9.991014e-01 3.116538e-02 5.859514e+00 -6.066261e-01 4.220302e-02 -7.938663e-01 -1.044142e+01 +-7.941019e-01 2.635367e-03 6.077789e-01 -2.378462e+02 2.797243e-02 9.990894e-01 3.221565e-02 5.873132e+00 -6.071406e-01 4.258355e-02 -7.934526e-01 -1.132743e+01 +-7.942090e-01 2.247800e-03 6.076405e-01 -2.371540e+02 2.782070e-02 9.990790e-01 3.266687e-02 5.887034e+00 -6.070075e-01 4.284930e-02 -7.935401e-01 -1.222912e+01 +-7.949469e-01 8.964253e-04 6.066783e-01 -2.364829e+02 2.613867e-02 9.991209e-01 3.277390e-02 5.900348e+00 -6.061156e-01 4.191127e-02 -7.942716e-01 -1.310267e+01 +-7.965963e-01 8.892338e-04 6.045110e-01 -2.358081e+02 2.561533e-02 9.991504e-01 3.228493e-02 5.913428e+00 -6.039687e-01 4.120280e-02 -7.959423e-01 -1.398867e+01 +-7.991127e-01 -9.121601e-04 6.011806e-01 -2.351307e+02 2.367230e-02 9.991755e-01 3.298216e-02 5.925277e+00 -6.007151e-01 4.058778e-02 -7.984322e-01 -1.488366e+01 +-8.024722e-01 -3.047273e-03 5.966818e-01 -2.344630e+02 2.174816e-02 9.991731e-01 3.435171e-02 5.935750e+00 -5.962931e-01 4.054301e-02 -8.017424e-01 -1.577832e+01 +-8.061257e-01 -3.762356e-03 5.917324e-01 -2.338031e+02 2.125176e-02 9.991506e-01 3.530438e-02 5.946317e+00 -5.913626e-01 4.103512e-02 -8.053610e-01 -1.667718e+01 +-8.100659e-01 -4.474767e-03 5.863217e-01 -2.331506e+02 2.054630e-02 9.991401e-01 3.601227e-02 5.959005e+00 -5.859787e-01 4.121905e-02 -8.092774e-01 -1.758017e+01 +-8.142359e-01 -4.573300e-03 5.805161e-01 -2.325087e+02 1.991933e-02 9.991600e-01 3.581036e-02 5.971457e+00 -5.801923e-01 4.072156e-02 -8.134609e-01 -1.848187e+01 +-8.187264e-01 -4.712595e-03 5.741646e-01 -2.318742e+02 1.922164e-02 9.991809e-01 3.560999e-02 5.985208e+00 -5.738621e-01 4.019121e-02 -8.179651e-01 -1.938812e+01 +-8.236777e-01 -4.859918e-03 5.670375e-01 -2.312485e+02 1.880279e-02 9.991793e-01 3.587657e-02 5.999850e+00 -5.667465e-01 4.021261e-02 -8.229103e-01 -2.029765e+01 +-8.286128e-01 -4.876977e-03 5.598010e-01 -2.306317e+02 1.920251e-02 9.991260e-01 3.712776e-02 6.016131e+00 -5.594928e-01 4.151411e-02 -8.277949e-01 -2.121160e+01 +-8.333377e-01 -3.421134e-03 5.527537e-01 -2.300287e+02 2.105972e-02 9.990583e-01 3.793329e-02 6.032159e+00 -5.523630e-01 4.325207e-02 -8.324809e-01 -2.212786e+01 +-8.377084e-01 -1.088358e-03 5.461167e-01 -2.294332e+02 2.382105e-02 9.989734e-01 3.853083e-02 6.048744e+00 -5.455980e-01 4.528667e-02 -8.368225e-01 -2.305228e+01 +-8.408998e-01 3.103083e-03 5.411820e-01 -2.288502e+02 2.840626e-02 9.988582e-01 3.841087e-02 6.066954e+00 -5.404449e-01 4.767264e-02 -8.400278e-01 -2.397314e+01 +-8.426885e-01 7.372778e-03 5.383510e-01 -2.282725e+02 3.307844e-02 9.987262e-01 3.810047e-02 6.086688e+00 -5.373844e-01 4.991463e-02 -8.418590e-01 -2.489484e+01 +-8.437263e-01 1.034811e-02 5.366739e-01 -2.276946e+02 3.630704e-02 9.986246e-01 3.782430e-02 6.106457e+00 -5.355444e-01 5.139839e-02 -8.429415e-01 -2.581550e+01 +-8.447453e-01 1.124619e-02 5.350504e-01 -2.271205e+02 3.796289e-02 9.985198e-01 3.894852e-02 6.123930e+00 -5.338204e-01 5.321363e-02 -8.439218e-01 -2.673151e+01 +-8.457874e-01 1.191659e-02 5.333870e-01 -2.265480e+02 3.915750e-02 9.984407e-01 3.978518e-02 6.142417e+00 -5.320812e-01 5.453590e-02 -8.449352e-01 -2.764633e+01 +-8.467003e-01 1.390367e-02 5.318885e-01 -2.259806e+02 4.135252e-02 9.983543e-01 3.973086e-02 6.161219e+00 -5.304608e-01 5.563505e-02 -8.458818e-01 -2.855785e+01 +-8.473192e-01 1.673062e-02 5.308203e-01 -2.254202e+02 4.444528e-02 9.982313e-01 3.948284e-02 6.177865e+00 -5.292209e-01 5.704701e-02 -8.465642e-01 -2.946682e+01 +-8.476773e-01 1.937955e-02 5.301581e-01 -2.248626e+02 4.758521e-02 9.980819e-01 3.960046e-02 6.194842e+00 -5.283738e-01 5.879609e-02 -8.469735e-01 -3.037398e+01 +-8.479173e-01 2.183454e-02 5.296787e-01 -2.243086e+02 5.076402e-02 9.979042e-01 4.012792e-02 6.213071e+00 -5.276924e-01 6.091376e-02 -8.472486e-01 -3.127582e+01 +-8.481762e-01 2.462764e-02 5.291414e-01 -2.237566e+02 5.332270e-02 9.978142e-01 3.903158e-02 6.230095e+00 -5.270236e-01 6.132089e-02 -8.476355e-01 -3.217526e+01 +-8.483896e-01 2.676865e-02 5.286951e-01 -2.232068e+02 5.539631e-02 9.977266e-01 3.837723e-02 6.247450e+00 -5.264659e-01 6.184659e-02 -8.479438e-01 -3.306925e+01 +-8.485155e-01 2.702678e-02 5.284799e-01 -2.226579e+02 5.644132e-02 9.976202e-01 3.960200e-02 6.265007e+00 -5.261519e-01 6.343100e-02 -8.480216e-01 -3.396277e+01 +-8.487932e-01 2.806937e-02 5.279793e-01 -2.221135e+02 5.840350e-02 9.974564e-01 4.086240e-02 6.283262e+00 -5.254894e-01 6.551956e-02 -8.482736e-01 -3.485288e+01 +-8.490345e-01 2.967823e-02 5.275033e-01 -2.215747e+02 6.058299e-02 9.973042e-01 4.140033e-02 6.300099e+00 -5.248526e-01 6.710802e-02 -8.485437e-01 -3.573435e+01 +-8.492327e-01 3.087614e-02 5.271152e-01 -2.210365e+02 6.229657e-02 9.971754e-01 4.195542e-02 6.315815e+00 -5.243310e-01 6.846737e-02 -8.487575e-01 -3.661568e+01 +-8.494523e-01 3.138494e-02 5.267312e-01 -2.205030e+02 6.319140e-02 9.970962e-01 4.249656e-02 6.332407e+00 -5.238679e-01 6.938367e-02 -8.489690e-01 -3.748779e+01 +-8.497388e-01 3.115211e-02 5.262828e-01 -2.199744e+02 6.313302e-02 9.970820e-01 4.291487e-02 6.349833e+00 -5.234102e-01 6.969224e-02 -8.492260e-01 -3.834971e+01 +-8.494187e-01 3.103760e-02 5.268060e-01 -2.194540e+02 6.341752e-02 9.970381e-01 4.351194e-02 6.366844e+00 -5.238952e-01 7.036857e-02 -8.488711e-01 -3.919493e+01 +-8.479127e-01 3.212073e-02 5.291619e-01 -2.189456e+02 6.545988e-02 9.968678e-01 4.437985e-02 6.385013e+00 -5.260790e-01 7.226909e-02 -8.473595e-01 -4.002000e+01 +-8.456098e-01 3.182057e-02 5.328523e-01 -2.184440e+02 6.622609e-02 9.967633e-01 4.557330e-02 6.403188e+00 -5.296775e-01 7.382593e-02 -8.449802e-01 -4.082160e+01 +-8.428366e-01 3.231951e-02 5.371982e-01 -2.179538e+02 6.816955e-02 9.965661e-01 4.699801e-02 6.418270e+00 -5.338347e-01 7.623219e-02 -8.421456e-01 -4.160042e+01 +-8.391690e-01 3.299324e-02 5.428691e-01 -2.174737e+02 6.943422e-02 9.964896e-01 4.676930e-02 6.431240e+00 -5.394204e-01 7.694102e-02 -8.385140e-01 -4.235038e+01 +-8.350515e-01 3.455871e-02 5.490854e-01 -2.170021e+02 7.096036e-02 9.964544e-01 4.520128e-02 6.443372e+00 -5.455765e-01 7.670867e-02 -8.345431e-01 -4.307506e+01 +-8.306506e-01 3.572172e-02 5.556470e-01 -2.165389e+02 7.195818e-02 9.964581e-01 4.351126e-02 6.455728e+00 -5.521247e-01 7.612598e-02 -8.302790e-01 -4.377460e+01 +-8.268128e-01 3.446395e-02 5.614204e-01 -2.160818e+02 7.144710e-02 9.964712e-01 4.405080e-02 6.466055e+00 -5.579211e-01 7.653361e-02 -8.263575e-01 -4.444990e+01 +-8.232295e-01 3.165423e-02 5.668255e-01 -2.156341e+02 7.004771e-02 9.964785e-01 4.608575e-02 6.475687e+00 -5.633706e-01 7.764396e-02 -8.225479e-01 -4.509630e+01 +-8.193538e-01 3.156649e-02 5.724185e-01 -2.152018e+02 7.045565e-02 9.964583e-01 4.589894e-02 6.485621e+00 -5.689423e-01 7.793757e-02 -8.186760e-01 -4.571612e+01 +-8.156429e-01 3.028665e-02 5.777624e-01 -2.147782e+02 6.875113e-02 9.966268e-01 4.481405e-02 6.495470e+00 -5.744563e-01 7.627407e-02 -8.149738e-01 -4.631022e+01 +-8.120920e-01 3.044602e-02 5.827345e-01 -2.143684e+02 6.845324e-02 9.967133e-01 4.332052e-02 6.504620e+00 -5.795004e-01 7.507030e-02 -8.115071e-01 -4.687839e+01 +-8.084773e-01 2.941298e-02 5.877920e-01 -2.139679e+02 6.741849e-02 9.968042e-01 4.285074e-02 6.513314e+00 -5.846532e-01 7.427188e-02 -8.078765e-01 -4.742424e+01 +-8.049343e-01 2.924423e-02 5.926428e-01 -2.135699e+02 6.773659e-02 9.967842e-01 4.281383e-02 6.521274e+00 -5.894849e-01 7.460591e-02 -8.043267e-01 -4.796337e+01 +-8.013560e-01 2.883571e-02 5.974923e-01 -2.132027e+02 6.786084e-02 9.967716e-01 4.290944e-02 6.528158e+00 -5.943261e-01 7.493205e-02 -8.007258e-01 -4.845302e+01 +-7.970448e-01 2.843824e-02 6.032502e-01 -2.128329e+02 6.850605e-02 9.967007e-01 4.352750e-02 6.535653e+00 -6.000221e-01 7.601964e-02 -7.963633e-01 -4.893873e+01 +-7.918774e-01 2.873726e-02 6.100035e-01 -2.124698e+02 6.971429e-02 9.966159e-01 4.354916e-02 6.543111e+00 -6.066878e-01 7.701155e-02 -7.912011e-01 -4.940660e+01 +-7.856643e-01 2.938783e-02 6.179547e-01 -2.121122e+02 7.058519e-02 9.966065e-01 4.234639e-02 6.550060e+00 -6.146132e-01 7.688848e-02 -7.850725e-01 -4.985500e+01 +-7.781550e-01 3.017824e-02 6.273468e-01 -2.117578e+02 7.139213e-02 9.966212e-01 4.061207e-02 6.557332e+00 -6.240015e-01 7.639010e-02 -7.776803e-01 -5.028632e+01 +-7.699160e-01 3.082661e-02 6.374002e-01 -2.114027e+02 7.201212e-02 9.966495e-01 3.878246e-02 6.563935e+00 -6.340691e-01 7.575976e-02 -7.695563e-01 -5.070357e+01 +-7.611004e-01 3.092531e-02 6.478964e-01 -2.110501e+02 7.159648e-02 9.967645e-01 3.652875e-02 6.566205e+00 -6.446705e-01 7.418913e-02 -7.608521e-01 -5.110351e+01 +-7.519433e-01 3.121250e-02 6.584885e-01 -2.106995e+02 7.159789e-02 9.968364e-01 3.450901e-02 6.568704e+00 -6.553282e-01 7.309519e-02 -7.517992e-01 -5.149244e+01 +-7.420772e-01 3.205577e-02 6.695475e-01 -2.103503e+02 7.282473e-02 9.967990e-01 3.299004e-02 6.571368e+00 -6.663468e-01 7.324076e-02 -7.420363e-01 -5.186665e+01 +-7.313190e-01 3.264330e-02 6.812539e-01 -2.100072e+02 7.378172e-02 9.967786e-01 3.144175e-02 6.572852e+00 -6.780331e-01 7.325802e-02 -7.313716e-01 -5.222392e+01 +-7.194995e-01 3.480542e-02 6.936203e-01 -2.096638e+02 7.641234e-02 9.966471e-01 2.925217e-02 6.571371e+00 -6.902766e-01 7.404805e-02 -7.197466e-01 -5.256511e+01 +-7.063471e-01 3.431985e-02 7.070331e-01 -2.093290e+02 7.659101e-02 9.966655e-01 2.813789e-02 6.567908e+00 -7.037099e-01 7.402749e-02 -7.066204e-01 -5.288218e+01 +-6.906465e-01 3.378566e-02 7.224029e-01 -2.089962e+02 7.788050e-02 9.965736e-01 2.784870e-02 6.565456e+00 -7.189869e-01 7.549469e-02 -6.909113e-01 -5.318249e+01 +-6.733173e-01 3.299703e-02 7.386169e-01 -2.086629e+02 7.857433e-02 9.965396e-01 2.710823e-02 6.563325e+00 -7.351666e-01 7.628876e-02 -6.735801e-01 -5.345948e+01 +-6.543986e-01 3.178035e-02 7.554816e-01 -2.083421e+02 7.783334e-02 9.966403e-01 2.549425e-02 6.561582e+00 -7.521333e-01 7.548504e-02 -6.546736e-01 -5.371281e+01 +-6.339587e-01 3.029194e-02 7.727734e-01 -2.080232e+02 7.557467e-02 9.968766e-01 2.292247e-02 6.554483e+00 -7.696654e-01 7.293398e-02 -6.342680e-01 -5.393803e+01 +-6.130138e-01 2.778655e-02 7.895834e-01 -2.077233e+02 7.142351e-02 9.972383e-01 2.035728e-02 6.547898e+00 -7.868372e-01 6.887410e-02 -6.133055e-01 -5.413833e+01 +-5.929226e-01 2.373574e-02 8.049096e-01 -2.074339e+02 6.565896e-02 9.976622e-01 1.894675e-02 6.541905e+00 -8.025782e-01 6.408347e-02 -5.930949e-01 -5.431481e+01 +-5.739138e-01 2.205711e-02 8.186186e-01 -2.071595e+02 6.118838e-02 9.979978e-01 1.600733e-02 6.536224e+00 -8.166266e-01 5.927676e-02 -5.741144e-01 -5.447024e+01 +-5.546428e-01 2.343923e-02 8.317583e-01 -2.069009e+02 5.898298e-02 9.981961e-01 1.120221e-02 6.531964e+00 -8.299954e-01 5.527280e-02 -5.550248e-01 -5.461405e+01 +-5.354290e-01 2.533492e-02 8.442001e-01 -2.066392e+02 5.727849e-02 9.983379e-01 6.367858e-03 6.524111e+00 -8.426357e-01 5.176404e-02 -5.359902e-01 -5.475077e+01 +-5.150232e-01 2.647779e-02 8.567672e-01 -2.063805e+02 5.638871e-02 9.984042e-01 3.041594e-03 6.516998e+00 -8.553195e-01 4.987848e-02 -5.156944e-01 -5.488102e+01 +-4.922315e-01 2.478213e-02 8.701115e-01 -2.061190e+02 5.524629e-02 9.984688e-01 2.815459e-03 6.512863e+00 -8.687094e-01 4.945628e-02 -4.928469e-01 -5.500359e+01 +-4.680604e-01 2.125760e-02 8.834408e-01 -2.058467e+02 5.290333e-02 9.985916e-01 4.000590e-03 6.507652e+00 -8.821116e-01 4.860947e-02 -4.685257e-01 -5.511241e+01 +-4.428430e-01 1.725255e-02 8.964332e-01 -2.055811e+02 4.822995e-02 9.988256e-01 4.602683e-03 6.502122e+00 -8.953011e-01 4.527318e-02 -4.431550e-01 -5.520882e+01 +-4.163938e-01 1.455190e-02 9.090679e-01 -2.053094e+02 4.457464e-02 9.989962e-01 4.425738e-03 6.495054e+00 -9.080911e-01 4.236421e-02 -4.166244e-01 -5.529491e+01 +-3.897559e-01 1.270311e-02 9.208306e-01 -2.050465e+02 4.222184e-02 9.990999e-01 4.088181e-03 6.489143e+00 -9.199498e-01 4.047254e-02 -3.899414e-01 -5.537685e+01 +-3.637509e-01 1.123831e-02 9.314285e-01 -2.047845e+02 4.021237e-02 9.991845e-01 3.648301e-03 6.482039e+00 -9.306279e-01 3.878201e-02 -3.639061e-01 -5.545099e+01 +-3.369527e-01 1.068990e-02 9.414609e-01 -2.045113e+02 3.777087e-02 9.992840e-01 2.171885e-03 6.471127e+00 -9.407637e-01 3.629161e-02 -3.371152e-01 -5.551420e+01 +-3.095978e-01 1.033333e-02 9.508114e-01 -2.042383e+02 3.416367e-02 9.994162e-01 2.626087e-04 6.460492e+00 -9.502537e-01 3.256450e-02 -3.097701e-01 -5.557213e+01 +-2.816485e-01 1.094308e-02 9.594552e-01 -2.039476e+02 3.243616e-02 9.994720e-01 -1.877854e-03 6.451432e+00 -9.589693e-01 3.059214e-02 -2.818547e-01 -5.562424e+01 +-2.517617e-01 1.159444e-02 9.677198e-01 -2.036539e+02 3.194036e-02 9.994830e-01 -3.665409e-03 6.442325e+00 -9.672621e-01 2.998650e-02 -2.520019e-01 -5.567591e+01 +-2.222085e-01 1.277970e-02 9.749154e-01 -2.033404e+02 3.294100e-02 9.994416e-01 -5.593103e-03 6.429446e+00 -9.744426e-01 3.087185e-02 -2.225054e-01 -5.572001e+01 +-1.926394e-01 1.357083e-02 9.811757e-01 -2.030228e+02 3.339130e-02 9.994159e-01 -7.267232e-03 6.415913e+00 -9.807013e-01 3.136277e-02 -1.929801e-01 -5.575907e+01 +-1.619476e-01 1.495114e-02 9.866861e-01 -2.026932e+02 3.419393e-02 9.993697e-01 -9.530992e-03 6.402192e+00 -9.862068e-01 3.219515e-02 -1.623568e-01 -5.579096e+01 +-1.308515e-01 1.742058e-02 9.912489e-01 -2.023437e+02 3.415309e-02 9.993313e-01 -1.305419e-02 6.391656e+00 -9.908136e-01 3.214605e-02 -1.313590e-01 -5.581263e+01 +-1.001473e-01 1.966710e-02 9.947782e-01 -2.019903e+02 3.482499e-02 9.992613e-01 -1.624981e-02 6.380116e+00 -9.943630e-01 3.301576e-02 -1.007582e-01 -5.582997e+01 +-6.861241e-02 2.014603e-02 9.974399e-01 -2.016126e+02 3.385883e-02 9.992671e-01 -1.785385e-02 6.366487e+00 -9.970687e-01 3.254715e-02 -6.924425e-02 -5.583354e+01 +-3.690302e-02 2.126145e-02 9.990926e-01 -2.012300e+02 3.562380e-02 9.991662e-01 -1.994720e-02 6.351614e+00 -9.986837e-01 3.485536e-02 -3.762967e-02 -5.583190e+01 +-6.053122e-03 2.260749e-02 9.997261e-01 -2.008309e+02 3.369529e-02 9.991813e-01 -2.239116e-02 6.335860e+00 -9.994139e-01 3.355052e-02 -6.809934e-03 -5.581188e+01 +2.483566e-02 2.410228e-02 9.994009e-01 -2.004046e+02 3.024439e-02 9.992336e-01 -2.484984e-02 6.320815e+00 -9.992340e-01 3.084343e-02 2.408766e-02 -5.577561e+01 +5.534510e-02 2.347851e-02 9.981912e-01 -1.999669e+02 2.733472e-02 9.993131e-01 -2.502049e-02 6.306043e+00 -9.980931e-01 2.867003e-02 5.466531e-02 -5.572791e+01 +8.438500e-02 2.069961e-02 9.962182e-01 -1.995014e+02 2.594881e-02 9.993995e-01 -2.296372e-02 6.290395e+00 -9.960953e-01 2.778846e-02 8.379719e-02 -5.566825e+01 +1.115787e-01 1.721646e-02 9.936064e-01 -1.990221e+02 2.689681e-02 9.994313e-01 -2.033781e-02 6.274124e+00 -9.933916e-01 2.899410e-02 1.110521e-01 -5.559858e+01 +1.372074e-01 1.574081e-02 9.904172e-01 -1.985118e+02 2.835288e-02 9.994016e-01 -1.981147e-02 6.257745e+00 -9.901365e-01 3.079945e-02 1.366790e-01 -5.551570e+01 +1.595196e-01 1.393863e-02 9.870963e-01 -1.979991e+02 3.002888e-02 9.993691e-01 -1.896475e-02 6.241763e+00 -9.867380e-01 3.266664e-02 1.590004e-01 -5.542175e+01 +1.810061e-01 1.240707e-02 9.834037e-01 -1.974592e+02 2.949613e-02 9.994021e-01 -1.803800e-02 6.226768e+00 -9.830396e-01 3.227158e-02 1.805319e-01 -5.530993e+01 +2.031659e-01 1.209645e-02 9.790696e-01 -1.968963e+02 2.861318e-02 9.994233e-01 -1.828543e-02 6.212680e+00 -9.787262e-01 3.172927e-02 2.027027e-01 -5.517799e+01 +2.263985e-01 1.306899e-02 9.739471e-01 -1.963171e+02 2.769491e-02 9.994193e-01 -1.984861e-02 6.198000e+00 -9.736410e-01 3.146707e-02 2.259051e-01 -5.502812e+01 +2.499221e-01 1.227608e-02 9.681881e-01 -1.957191e+02 2.765947e-02 9.994210e-01 -1.981195e-02 6.184175e+00 -9.678708e-01 3.173100e-02 2.494378e-01 -5.485966e+01 +2.748778e-01 7.335696e-03 9.614512e-01 -1.951012e+02 3.189286e-02 9.993510e-01 -1.674300e-02 6.167599e+00 -9.609501e-01 3.526570e-02 2.744655e-01 -5.467531e+01 +3.004881e-01 2.394799e-03 9.537826e-01 -1.944653e+02 3.583231e-02 9.992625e-01 -1.379792e-02 6.149182e+00 -9.531123e-01 3.832233e-02 3.001806e-01 -5.446763e+01 +3.258363e-01 -5.376246e-03 9.454109e-01 -1.938069e+02 4.221517e-02 9.990692e-01 -8.868094e-03 6.133914e+00 -9.444833e-01 4.280022e-02 3.257599e-01 -5.423745e+01 +3.524659e-01 -9.908284e-03 9.357722e-01 -1.931445e+02 4.595387e-02 9.989209e-01 -6.731958e-03 6.119265e+00 -9.346957e-01 4.537513e-02 3.525408e-01 -5.398002e+01 +3.795868e-01 -1.089850e-02 9.250919e-01 -1.924691e+02 5.152557e-02 9.986276e-01 -9.377317e-03 6.103204e+00 -9.237202e-01 5.122538e-02 3.796274e-01 -5.369855e+01 +4.065388e-01 -1.079884e-02 9.135697e-01 -1.917846e+02 5.681735e-02 9.982935e-01 -1.348342e-02 6.086870e+00 -9.118651e-01 5.738813e-02 4.064586e-01 -5.338917e+01 +4.335129e-01 -8.029037e-03 9.011116e-01 -1.910895e+02 6.456112e-02 9.976674e-01 -2.217014e-02 6.071799e+00 -8.988317e-01 6.778780e-02 4.330201e-01 -5.305956e+01 +4.580368e-01 -6.921589e-03 8.889063e-01 -1.903911e+02 6.678404e-02 9.974116e-01 -2.664609e-02 6.049869e+00 -8.864210e-01 7.156963e-02 4.573135e-01 -5.269364e+01 +4.797767e-01 -8.881175e-03 8.773457e-01 -1.896820e+02 6.579891e-02 9.974971e-01 -2.588471e-02 6.021925e+00 -8.749199e-01 7.014725e-02 4.791602e-01 -5.229508e+01 +4.996093e-01 -1.168131e-02 8.661721e-01 -1.889595e+02 6.451196e-02 9.976341e-01 -2.375637e-02 5.991475e+00 -8.638453e-01 6.774735e-02 4.991809e-01 -5.187066e+01 +5.167035e-01 -1.409523e-02 8.560483e-01 -1.882304e+02 6.257046e-02 9.978124e-01 -2.133756e-02 5.960013e+00 -8.538750e-01 6.458852e-02 5.164552e-01 -5.142014e+01 +5.313527e-01 -1.478311e-02 8.470217e-01 -1.874933e+02 6.054049e-02 9.979539e-01 -2.056085e-02 5.928955e+00 -8.449847e-01 6.220416e-02 5.311605e-01 -5.094992e+01 +5.429738e-01 -1.329371e-02 8.396444e-01 -1.867483e+02 5.784789e-02 9.980916e-01 -2.160623e-02 5.898615e+00 -8.377548e-01 6.030326e-02 5.427066e-01 -5.045759e+01 +5.520226e-01 -1.053610e-02 8.337625e-01 -1.859944e+02 5.406435e-02 9.982683e-01 -2.318032e-02 5.869960e+00 -8.320746e-01 5.787288e-02 5.516364e-01 -4.994782e+01 +5.578613e-01 -7.368340e-03 8.299015e-01 -1.852271e+02 4.944240e-02 9.984796e-01 -2.437019e-02 5.839552e+00 -8.284602e-01 5.462749e-02 5.573774e-01 -4.942089e+01 +5.609458e-01 -5.663961e-03 8.278331e-01 -1.844468e+02 4.476469e-02 9.987211e-01 -2.349972e-02 5.807630e+00 -8.266414e-01 5.023976e-02 5.604820e-01 -4.888224e+01 +5.615834e-01 -5.502418e-03 8.274018e-01 -1.836530e+02 4.169502e-02 9.988956e-01 -2.165681e-02 5.776020e+00 -8.263690e-01 4.666063e-02 5.611926e-01 -4.833677e+01 +5.610471e-01 -4.677976e-03 8.277706e-01 -1.828493e+02 3.958455e-02 9.989916e-01 -2.118406e-02 5.742140e+00 -8.268369e-01 4.465217e-02 5.606666e-01 -4.778810e+01 +5.601490e-01 -1.644774e-03 8.283902e-01 -1.819970e+02 3.905263e-02 9.989386e-01 -2.442359e-02 5.708420e+00 -8.274708e-01 4.603165e-02 5.596188e-01 -4.721172e+01 +5.593583e-01 2.326936e-04 8.289259e-01 -1.812032e+02 3.918936e-02 9.988743e-01 -2.672534e-02 5.676050e+00 -8.279991e-01 4.743411e-02 5.587196e-01 -4.667761e+01 +5.584729e-01 -1.937237e-04 8.295227e-01 -1.803603e+02 3.935934e-02 9.988798e-01 -2.626525e-02 5.639582e+00 -8.285885e-01 4.731788e-02 5.578550e-01 -4.611200e+01 +5.574816e-01 -1.620260e-03 8.301877e-01 -1.794977e+02 3.812886e-02 9.989928e-01 -2.365430e-02 5.600657e+00 -8.293133e-01 4.484093e-02 5.569819e-01 -4.553211e+01 +5.562567e-01 -3.597331e-03 8.310027e-01 -1.786275e+02 3.751297e-02 9.990799e-01 -2.078552e-02 5.564601e+00 -8.301634e-01 4.273546e-02 5.558798e-01 -4.494959e+01 +5.547021e-01 -3.885480e-03 8.320400e-01 -1.777455e+02 3.540519e-02 9.991936e-01 -1.893778e-02 5.527931e+00 -8.312955e-01 3.996335e-02 5.543923e-01 -4.436122e+01 +5.527933e-01 -2.878112e-03 8.333134e-01 -1.768451e+02 3.410123e-02 9.992345e-01 -1.917049e-02 5.490826e+00 -8.326204e-01 3.901432e-02 5.524683e-01 -4.376464e+01 +5.507240e-01 -5.066387e-04 8.346872e-01 -1.759365e+02 3.287114e-02 9.992372e-01 -2.108176e-02 5.454066e+00 -8.340399e-01 3.904734e-02 5.503206e-01 -4.316482e+01 +5.481437e-01 2.670694e-03 8.363799e-01 -1.750139e+02 3.079719e-02 9.992523e-01 -2.337452e-02 5.415626e+00 -8.358170e-01 3.857074e-02 5.476516e-01 -4.255993e+01 +5.454032e-01 5.784383e-03 8.381538e-01 -1.740792e+02 2.908331e-02 9.992434e-01 -2.582120e-02 5.374146e+00 -8.376691e-01 3.845924e-02 5.448223e-01 -4.195134e+01 +5.421818e-01 5.880682e-03 8.402406e-01 -1.731293e+02 2.673881e-02 9.993483e-01 -2.424799e-02 5.330910e+00 -8.398357e-01 3.561385e-02 5.416712e-01 -4.133758e+01 +5.384013e-01 2.111973e-03 8.426859e-01 -1.721609e+02 2.497107e-02 9.995177e-01 -1.845932e-02 5.288826e+00 -8.423186e-01 3.098128e-02 5.380889e-01 -4.071585e+01 +5.338054e-01 1.095318e-03 8.456066e-01 -1.711827e+02 2.162706e-02 9.996543e-01 -1.494736e-02 5.248273e+00 -8.453308e-01 2.626696e-02 5.335972e-01 -4.009405e+01 +5.286672e-01 1.307915e-03 8.488282e-01 -1.701958e+02 2.158643e-02 9.996547e-01 -1.498478e-02 5.214023e+00 -8.485547e-01 2.624512e-02 5.284564e-01 -3.947803e+01 +5.232491e-01 1.613265e-03 8.521783e-01 -1.691962e+02 2.159839e-02 9.996518e-01 -1.515416e-02 5.177783e+00 -8.519061e-01 2.633507e-02 5.230321e-01 -3.886377e+01 +5.177731e-01 9.290288e-04 8.555175e-01 -1.681815e+02 2.346079e-02 9.996079e-01 -1.528435e-02 5.140427e+00 -8.551963e-01 2.798493e-02 5.175483e-01 -3.825218e+01 +5.125981e-01 -1.731462e-03 8.586269e-01 -1.671568e+02 2.600142e-02 9.995706e-01 -1.350710e-02 5.104024e+00 -8.582349e-01 2.924922e-02 5.124230e-01 -3.764371e+01 +5.071796e-01 -4.966491e-03 8.618261e-01 -1.661220e+02 2.909207e-02 9.995122e-01 -1.136057e-02 5.066952e+00 -8.613493e-01 3.083415e-02 5.070767e-01 -3.703978e+01 +5.014830e-01 -6.758797e-03 8.651411e-01 -1.650807e+02 3.035380e-02 9.994913e-01 -9.786329e-03 5.029773e+00 -8.646349e-01 3.116799e-02 5.014331e-01 -3.643744e+01 +4.955358e-01 -5.196400e-03 8.685719e-01 -1.640411e+02 3.005235e-02 9.994859e-01 -1.116578e-02 4.992355e+00 -8.680675e-01 3.163567e-02 4.954373e-01 -3.584195e+01 +4.891051e-01 -2.453514e-03 8.722214e-01 -1.629931e+02 2.879215e-02 9.994965e-01 -1.333390e-02 4.953310e+00 -8.717495e-01 3.163480e-02 4.889295e-01 -3.525050e+01 +4.819925e-01 -5.909094e-04 8.761751e-01 -1.619369e+02 2.761700e-02 9.995131e-01 -1.451829e-02 4.913727e+00 -8.757400e-01 3.119503e-02 4.817742e-01 -3.466444e+01 +4.749052e-01 -1.385927e-03 8.800358e-01 -1.608735e+02 2.726281e-02 9.995419e-01 -1.313806e-02 4.874235e+00 -8.796146e-01 3.023157e-02 4.747255e-01 -3.408707e+01 +4.678297e-01 -3.533409e-03 8.838116e-01 -1.598027e+02 2.706683e-02 9.995802e-01 -1.033109e-02 4.834745e+00 -8.834041e-01 2.875516e-02 4.677289e-01 -3.351726e+01 +4.612687e-01 -4.419011e-03 8.872495e-01 -1.587309e+02 2.790747e-02 9.995651e-01 -9.530301e-03 4.796201e+00 -8.868215e-01 2.915691e-02 4.611914e-01 -3.296105e+01 +4.550958e-01 -4.953859e-03 8.904287e-01 -1.576554e+02 2.673462e-02 9.996097e-01 -8.102713e-03 4.760142e+00 -8.900411e-01 2.749278e-02 4.550506e-01 -3.241020e+01 +4.496470e-01 -7.086424e-03 8.931782e-01 -1.565776e+02 2.599155e-02 9.996489e-01 -5.153604e-03 4.724677e+00 -8.928281e-01 2.553238e-02 4.496733e-01 -3.186329e+01 +4.452017e-01 -1.010410e-02 8.953733e-01 -1.554985e+02 2.695353e-02 9.996344e-01 -2.121297e-03 4.693787e+00 -8.950246e-01 2.507787e-02 4.453113e-01 -3.132607e+01 +4.419677e-01 -1.028925e-02 8.969719e-01 -1.544229e+02 2.357628e-02 9.997220e-01 -1.489063e-04 4.661896e+00 -8.967211e-01 2.121306e-02 4.420875e-01 -3.078859e+01 +4.407979e-01 -6.249389e-03 8.975846e-01 -1.533542e+02 2.920791e-02 9.995461e-01 -7.384520e-03 4.628272e+00 -8.971311e-01 2.947164e-02 4.407803e-01 -3.027178e+01 +4.397149e-01 -2.305319e-03 8.981345e-01 -1.522849e+02 3.473150e-02 9.992923e-01 -1.443912e-02 4.594480e+00 -8.974657e-01 3.754264e-02 4.394838e-01 -2.975452e+01 +4.396299e-01 -2.137838e-03 8.981765e-01 -1.512111e+02 3.678859e-02 9.992008e-01 -1.562859e-02 4.554670e+00 -8.974253e-01 3.991343e-02 4.393572e-01 -2.923250e+01 +4.394179e-01 -6.171247e-03 8.982615e-01 -1.501382e+02 3.670793e-02 9.992645e-01 -1.109188e-02 4.513587e+00 -8.975324e-01 3.784728e-02 4.393213e-01 -2.870806e+01 +4.385451e-01 -7.509182e-03 8.986778e-01 -1.490693e+02 3.565425e-02 9.993232e-01 -9.048735e-03 4.477108e+00 -8.980017e-01 3.600995e-02 4.385161e-01 -2.818276e+01 +4.373701e-01 -7.872643e-03 8.992471e-01 -1.480044e+02 3.340722e-02 9.994137e-01 -7.498822e-03 4.441814e+00 -8.986609e-01 3.332110e-02 4.373767e-01 -2.765773e+01 +4.365793e-01 -7.241586e-03 8.996366e-01 -1.469315e+02 3.337931e-02 9.994095e-01 -8.153746e-03 4.405940e+00 -8.990464e-01 3.358900e-02 4.365633e-01 -2.713375e+01 +4.364048e-01 -5.772958e-03 8.997319e-01 -1.458577e+02 3.437591e-02 9.993563e-01 -1.026147e-02 4.368950e+00 -8.990936e-01 3.540725e-02 4.363223e-01 -2.661215e+01 +4.365421e-01 -1.488492e-03 8.996826e-01 -1.447893e+02 3.745564e-02 9.991617e-01 -1.652107e-02 4.329825e+00 -8.989039e-01 4.091032e-02 4.362319e-01 -2.609816e+01 +4.360146e-01 2.285013e-04 8.999396e-01 -1.437156e+02 3.997084e-02 9.990082e-01 -1.961925e-02 4.287681e+00 -8.990515e-01 4.452561e-02 4.355730e-01 -2.557867e+01 +4.351536e-01 9.643453e-04 9.003557e-01 -1.426410e+02 4.032510e-02 9.989750e-01 -2.055962e-02 4.241418e+00 -8.994527e-01 4.525352e-02 4.346688e-01 -2.505700e+01 +4.346262e-01 -4.174270e-04 9.006108e-01 -1.415608e+02 3.994599e-02 9.990247e-01 -1.881452e-02 4.193464e+00 -8.997246e-01 4.415307e-02 4.342190e-01 -2.453011e+01 +4.340915e-01 -2.912127e-03 9.008640e-01 -1.404819e+02 4.054011e-02 9.990448e-01 -1.630521e-02 4.146681e+00 -8.999562e-01 4.359907e-02 4.337950e-01 -2.400687e+01 +4.336306e-01 -4.161050e-03 9.010811e-01 -1.394025e+02 4.196175e-02 9.989977e-01 -1.558020e-02 4.100868e+00 -9.001132e-01 4.456698e-02 4.333706e-01 -2.348633e+01 +4.328913e-01 -4.279299e-03 9.014359e-01 -1.383236e+02 4.305028e-02 9.989458e-01 -1.593159e-02 4.055097e+00 -9.004176e-01 4.570370e-02 4.326193e-01 -2.296824e+01 +4.325633e-01 -2.269312e-03 9.016007e-01 -1.372477e+02 4.266861e-02 9.989279e-01 -1.795695e-02 4.007681e+00 -9.005934e-01 4.623755e-02 4.321964e-01 -2.245090e+01 +4.321956e-01 -1.117971e-03 9.017792e-01 -1.361730e+02 4.365410e-02 9.988528e-01 -1.968378e-02 3.960473e+00 -9.007227e-01 4.787359e-02 4.317485e-01 -2.193465e+01 +4.317003e-01 -2.299185e-03 9.020142e-01 -1.350973e+02 4.316571e-02 9.989037e-01 -1.811278e-02 3.912458e+00 -9.009837e-01 4.675537e-02 4.313262e-01 -2.141571e+01 +4.310694e-01 -4.940018e-03 9.023053e-01 -1.340227e+02 4.221707e-02 9.990003e-01 -1.469947e-02 3.866005e+00 -9.013307e-01 4.442917e-02 4.308470e-01 -2.089614e+01 +4.305971e-01 -7.730330e-03 9.025111e-01 -1.329453e+02 4.186804e-02 9.990579e-01 -1.141838e-02 3.821506e+00 -9.015726e-01 4.270309e-02 4.305151e-01 -2.037706e+01 +4.310669e-01 -8.410387e-03 9.022808e-01 -1.318768e+02 4.290863e-02 9.990163e-01 -1.118762e-02 3.781015e+00 -9.012992e-01 4.353823e-02 4.310038e-01 -1.986621e+01 +4.324618e-01 -7.530893e-03 9.016208e-01 -1.308138e+02 4.448564e-02 9.989255e-01 -1.299386e-02 3.739768e+00 -9.005542e-01 4.572851e-02 4.323321e-01 -1.935808e+01 +4.342552e-01 -5.564501e-03 9.007727e-01 -1.297549e+02 4.554022e-02 9.988378e-01 -1.578427e-02 3.696042e+00 -8.996380e-01 4.787577e-02 4.340039e-01 -1.884932e+01 +4.359818e-01 -4.876365e-03 8.999422e-01 -1.286987e+02 4.555809e-02 9.988228e-01 -1.665871e-02 3.651177e+00 -8.988016e-01 4.826253e-02 4.356907e-01 -1.833706e+01 +4.374174e-01 -6.403042e-03 8.992358e-01 -1.276469e+02 4.538582e-02 9.988574e-01 -1.496473e-02 3.605648e+00 -8.981126e-01 4.735837e-02 4.372082e-01 -1.782499e+01 +4.388841e-01 -7.625387e-03 8.985113e-01 -1.265948e+02 4.500135e-02 9.988956e-01 -1.350390e-02 3.559821e+00 -8.974161e-01 4.636086e-02 4.387425e-01 -1.731178e+01 +4.401849e-01 -6.949072e-03 8.978803e-01 -1.255523e+02 4.402227e-02 9.989345e-01 -1.385070e-02 3.515310e+00 -8.968274e-01 4.562359e-02 4.400218e-01 -1.680016e+01 +4.407942e-01 -3.246496e-03 8.976023e-01 -1.245160e+02 4.167477e-02 9.989891e-01 -1.685243e-02 3.470006e+00 -8.966403e-01 4.483582e-02 4.404839e-01 -1.628867e+01 +4.396459e-01 -8.068149e-04 8.981708e-01 -1.234816e+02 3.769935e-02 9.991349e-01 -1.755596e-02 3.426795e+00 -8.973797e-01 4.157885e-02 4.392960e-01 -1.577719e+01 +4.363012e-01 -4.151370e-03 8.997911e-01 -1.224473e+02 3.282879e-02 9.993970e-01 -1.130749e-02 3.385704e+00 -8.992016e-01 3.447252e-02 4.361744e-01 -1.526694e+01 +4.309847e-01 -8.744837e-03 9.023169e-01 -1.214091e+02 2.667358e-02 9.996395e-01 -3.052388e-03 3.345291e+00 -9.019650e-01 2.538355e-02 4.310626e-01 -1.476313e+01 +4.241039e-01 -5.569642e-03 9.055964e-01 -1.203820e+02 2.285745e-02 9.997283e-01 -4.555898e-03 3.311607e+00 -9.053251e-01 2.263180e-02 4.241160e-01 -1.427526e+01 +4.159153e-01 2.595279e-03 9.093996e-01 -1.193569e+02 1.889541e-02 9.997554e-01 -1.149499e-02 3.277647e+00 -9.092071e-01 2.196442e-02 4.157646e-01 -1.379956e+01 +4.064203e-01 9.082507e-03 9.136411e-01 -1.183280e+02 1.544826e-02 9.997393e-01 -1.681036e-02 3.239201e+00 -9.135557e-01 2.094623e-02 4.061741e-01 -1.333353e+01 +3.962769e-01 9.747097e-03 9.180793e-01 -1.172909e+02 1.328937e-02 9.997780e-01 -1.635066e-02 3.197775e+00 -9.180349e-01 1.868008e-02 3.960594e-01 -1.287873e+01 +3.860580e-01 5.243488e-03 9.224596e-01 -1.162439e+02 1.127994e-02 9.998822e-01 -1.040434e-02 3.158455e+00 -9.224056e-01 1.442197e-02 3.859534e-01 -1.243525e+01 +3.760385e-01 1.501751e-03 9.266028e-01 -1.151904e+02 1.080742e-02 9.999235e-01 -6.006506e-03 3.124650e+00 -9.265411e-01 1.227286e-02 3.759935e-01 -1.200288e+01 +3.670060e-01 2.733888e-03 9.302146e-01 -1.141405e+02 1.233952e-02 9.998934e-01 -7.807096e-03 3.093371e+00 -9.301368e-01 1.434364e-02 3.669331e-01 -1.158751e+01 +3.598644e-01 6.627692e-03 9.329811e-01 -1.131016e+02 1.502484e-02 9.998039e-01 -1.289769e-02 3.061043e+00 -9.328837e-01 1.865931e-02 3.596943e-01 -1.118769e+01 +3.543155e-01 7.729493e-03 9.350940e-01 -1.120481e+02 1.729091e-02 9.997407e-01 -1.481555e-02 3.025503e+00 -9.349661e-01 2.141800e-02 3.540899e-01 -1.078946e+01 +3.497473e-01 3.482908e-04 9.368440e-01 -1.109859e+02 2.445570e-02 9.996557e-01 -9.501569e-03 2.992042e+00 -9.365249e-01 2.623432e-02 3.496184e-01 -1.039983e+01 +3.461510e-01 -3.792229e-03 9.381711e-01 -1.099246e+02 2.328425e-02 9.997185e-01 -4.550031e-03 2.959612e+00 -9.378898e-01 2.341960e-02 3.461419e-01 -1.000735e+01 +3.412792e-01 2.326060e-04 9.399619e-01 -1.088744e+02 1.956331e-02 9.997816e-01 -7.350410e-03 2.928507e+00 -9.397584e-01 2.089730e-02 3.412001e-01 -9.617412e+00 +3.367603e-01 7.156681e-03 9.415632e-01 -1.078237e+02 2.215365e-02 9.996341e-01 -1.552157e-02 2.896739e+00 -9.413298e-01 2.608610e-02 3.364785e-01 -9.243398e+00 +3.323135e-01 1.189290e-02 9.430940e-01 -1.067662e+02 1.673280e-02 9.996888e-01 -1.850265e-02 2.857071e+00 -9.430206e-01 2.192927e-02 3.320110e-01 -8.864286e+00 +3.289302e-01 1.147339e-02 9.442845e-01 -1.057052e+02 1.501014e-02 9.997363e-01 -1.737576e-02 2.815858e+00 -9.442350e-01 1.988925e-02 3.286713e-01 -8.492253e+00 +3.270077e-01 7.695721e-03 9.449903e-01 -1.046399e+02 1.614195e-02 9.997754e-01 -1.372770e-02 2.777678e+00 -9.448838e-01 1.974305e-02 3.268101e-01 -8.124757e+00 +3.258739e-01 4.555579e-03 9.454023e-01 -1.035751e+02 1.714631e-02 9.997954e-01 -1.072790e-02 2.740474e+00 -9.452578e-01 1.970609e-02 3.257291e-01 -7.760123e+00 +3.251263e-01 2.501672e-03 9.456673e-01 -1.025122e+02 1.719254e-02 9.998156e-01 -8.555822e-03 2.704654e+00 -9.455143e-01 1.904014e-02 3.250234e-01 -7.394219e+00 +3.238295e-01 9.973256e-04 9.461149e-01 -1.014453e+02 1.179417e-02 9.999175e-01 -5.090867e-03 2.668834e+00 -9.460420e-01 1.280721e-02 3.237910e-01 -7.020636e+00 +3.205962e-01 1.924187e-03 9.472140e-01 -1.003834e+02 4.367386e-03 9.999843e-01 -3.509583e-03 2.635642e+00 -9.472059e-01 5.262006e-03 3.205827e-01 -6.646982e+00 +3.158335e-01 6.180745e-03 9.487945e-01 -9.932333e+01 4.205086e-05 9.999787e-01 -6.528177e-03 2.600359e+00 -9.488147e-01 2.101712e-03 3.158265e-01 -6.281885e+00 +3.102347e-01 1.521883e-02 9.505382e-01 -9.826682e+01 -1.265223e-03 9.998776e-01 -1.559586e-02 2.563161e+00 -9.506592e-01 3.635730e-03 3.102159e-01 -5.927679e+00 +3.041658e-01 2.281045e-02 9.523460e-01 -9.721118e+01 -5.190575e-04 9.997171e-01 -2.377930e-02 2.518780e+00 -9.526190e-01 6.738524e-03 3.040916e-01 -5.584438e+00 +2.979862e-01 2.093150e-02 9.543407e-01 -9.613410e+01 3.452110e-03 9.997294e-01 -2.300492e-02 2.468113e+00 -9.545640e-01 1.014963e-02 2.978333e-01 -5.250177e+00 +2.909210e-01 1.637494e-02 9.566069e-01 -9.505702e+01 6.203794e-03 9.998002e-01 -1.900100e-02 2.417757e+00 -9.567270e-01 1.146238e-02 2.907613e-01 -4.924307e+00 +2.831403e-01 1.329637e-02 9.589863e-01 -9.397692e+01 7.872345e-03 9.998380e-01 -1.618709e-02 2.371604e+00 -9.590462e-01 1.213268e-02 2.829897e-01 -4.604329e+00 +2.749621e-01 1.217895e-02 9.613779e-01 -9.289696e+01 7.982020e-03 9.998564e-01 -1.494934e-02 2.328432e+00 -9.614220e-01 1.178423e-02 2.748254e-01 -4.291721e+00 +2.664333e-01 1.118156e-02 9.637885e-01 -9.181618e+01 8.555121e-03 9.998659e-01 -1.396513e-02 2.286046e+00 -9.638154e-01 1.196610e-02 2.663019e-01 -3.988153e+00 +2.578781e-01 1.094975e-02 9.661154e-01 -9.073315e+01 9.835155e-03 9.998542e-01 -1.395737e-02 2.243515e+00 -9.661274e-01 1.310119e-02 2.577328e-01 -3.695911e+00 +2.495970e-01 1.172778e-02 9.682788e-01 -8.965036e+01 1.099940e-02 9.998278e-01 -1.494526e-02 2.200770e+00 -9.682874e-01 1.438077e-02 2.494250e-01 -3.413659e+00 +2.417457e-01 1.158219e-02 9.702705e-01 -8.856033e+01 1.231289e-02 9.998116e-01 -1.500262e-02 2.159070e+00 -9.702615e-01 1.557364e-02 2.415576e-01 -3.139167e+00 +2.348040e-01 9.644887e-03 9.719949e-01 -8.746938e+01 1.359539e-02 9.998204e-01 -1.320522e-02 2.117909e+00 -9.719477e-01 1.631528e-02 2.346307e-01 -2.871097e+00 +2.281217e-01 7.757494e-03 9.736017e-01 -8.637312e+01 1.500966e-02 9.998214e-01 -1.148328e-02 2.078223e+00 -9.735170e-01 1.723301e-02 2.279645e-01 -2.610895e+00 +2.213078e-01 6.628104e-03 9.751815e-01 -8.527567e+01 1.561488e-02 9.998246e-01 -1.033924e-02 2.039649e+00 -9.750790e-01 1.751549e-02 2.211655e-01 -2.357662e+00 +2.151986e-01 5.277988e-03 9.765560e-01 -8.417869e+01 1.766836e-02 9.998007e-01 -9.297106e-03 2.003235e+00 -9.764105e-01 1.925486e-02 2.150624e-01 -2.113087e+00 +2.110733e-01 4.613421e-03 9.774593e-01 -8.308090e+01 2.104610e-02 9.997356e-01 -9.263274e-03 1.967570e+00 -9.772437e-01 2.252693e-02 2.109204e-01 -1.875303e+00 +2.083584e-01 5.937187e-03 9.780345e-01 -8.198418e+01 2.446472e-02 9.996370e-01 -1.128024e-02 1.929078e+00 -9.777466e-01 2.627766e-02 2.081375e-01 -1.642797e+00 +2.060522e-01 7.914596e-03 9.785090e-01 -8.088804e+01 2.749008e-02 9.995258e-01 -1.387339e-02 1.891113e+00 -9.781548e-01 2.975793e-02 2.057369e-01 -1.413132e+00 +2.035603e-01 6.901156e-03 9.790381e-01 -7.979309e+01 2.888200e-02 9.994976e-01 -1.305049e-02 1.852304e+00 -9.786363e-01 3.093313e-02 2.032587e-01 -1.185025e+00 +2.007665e-01 2.345341e-03 9.796363e-01 -7.869561e+01 2.912776e-02 9.995407e-01 -8.362436e-03 1.815692e+00 -9.792060e-01 3.021350e-02 2.006060e-01 -9.567200e-01 +1.976081e-01 -1.304067e-03 9.802802e-01 -7.756902e+01 2.909700e-02 9.995663e-01 -4.535748e-03 1.781295e+00 -9.798492e-01 2.941951e-02 1.975603e-01 -7.254460e-01 +1.946188e-01 -2.080297e-03 9.808767e-01 -7.651124e+01 3.016999e-02 9.995373e-01 -3.866251e-03 1.753369e+00 -9.804149e-01 3.034548e-02 1.945915e-01 -5.132001e-01 +1.914358e-01 -1.102030e-03 9.815045e-01 -7.542280e+01 3.158256e-02 9.994884e-01 -5.037745e-03 1.726310e+00 -9.809969e-01 3.196282e-02 1.913727e-01 -3.006804e-01 +1.884231e-01 -5.112766e-04 9.820878e-01 -7.433776e+01 3.281143e-02 9.994449e-01 -5.774883e-03 1.698157e+00 -9.815397e-01 3.331182e-02 1.883353e-01 -9.103084e-02 +1.860767e-01 -2.331192e-03 9.825324e-01 -7.325165e+01 3.406022e-02 9.994114e-01 -4.079249e-03 1.670106e+00 -9.819447e-01 3.422432e-02 1.860466e-01 1.148072e-01 +1.841134e-01 -3.715286e-03 9.828980e-01 -7.216636e+01 3.421078e-02 9.994112e-01 -2.630553e-03 1.641851e+00 -9.823095e-01 3.411001e-02 1.841321e-01 3.199942e-01 +1.819925e-01 -3.240276e-03 9.832946e-01 -7.108516e+01 3.462587e-02 9.993955e-01 -3.115375e-03 1.617211e+00 -9.826901e-01 3.461439e-02 1.819946e-01 5.217201e-01 +1.801004e-01 -1.928749e-03 9.836463e-01 -7.000677e+01 3.405801e-02 9.994107e-01 -4.276182e-03 1.591142e+00 -9.830585e-01 3.427117e-02 1.800600e-01 7.229528e-01 +1.782500e-01 -4.665177e-04 9.839851e-01 -6.892853e+01 3.314024e-02 9.994354e-01 -5.529551e-03 1.564706e+00 -9.834270e-01 3.359513e-02 1.781648e-01 9.233017e-01 +1.766810e-01 -3.486143e-05 9.842682e-01 -6.785230e+01 3.246801e-02 9.994560e-01 -5.792772e-03 1.536979e+00 -9.837325e-01 3.298070e-02 1.765860e-01 1.120257e+00 +1.747897e-01 -2.367630e-03 9.846029e-01 -6.677302e+01 3.339484e-02 9.994360e-01 -3.525056e-03 1.510680e+00 -9.840393e-01 3.349680e-02 1.747701e-01 1.313423e+00 +1.727864e-01 -4.776588e-03 9.849477e-01 -6.570055e+01 3.474596e-02 9.993954e-01 -1.248727e-03 1.484221e+00 -9.843463e-01 3.443870e-02 1.728479e-01 1.500442e+00 +1.709499e-01 -5.508668e-03 9.852643e-01 -6.462519e+01 3.556459e-02 9.993672e-01 -5.831759e-04 1.458586e+00 -9.846377e-01 3.514020e-02 1.710376e-01 1.686604e+00 +1.694500e-01 -4.202793e-03 9.855298e-01 -6.355616e+01 3.733503e-02 9.993005e-01 -2.157793e-03 1.433237e+00 -9.848314e-01 3.716042e-02 1.694883e-01 1.869261e+00 +1.680501e-01 -1.831248e-03 9.857767e-01 -6.248959e+01 4.054608e-02 9.991649e-01 -5.055967e-03 1.407401e+00 -9.849443e-01 4.081903e-02 1.679840e-01 2.047975e+00 +1.660960e-01 -1.340874e-03 9.861087e-01 -6.142558e+01 4.250851e-02 9.990792e-01 -5.801446e-03 1.380271e+00 -9.851930e-01 4.288160e-02 1.660000e-01 2.225378e+00 +1.640854e-01 -3.024018e-03 9.864415e-01 -6.036042e+01 4.288236e-02 9.990718e-01 -4.070346e-03 1.352125e+00 -9.855137e-01 4.296881e-02 1.640627e-01 2.402354e+00 +1.620214e-01 -5.936006e-03 9.867694e-01 -5.929526e+01 4.280410e-02 9.990829e-01 -1.018090e-03 1.324166e+00 -9.858585e-01 4.240272e-02 1.621269e-01 2.577472e+00 +1.602793e-01 -7.736769e-03 9.870414e-01 -5.823435e+01 4.045701e-02 9.991805e-01 1.262366e-03 1.298326e+00 -9.862423e-01 3.973040e-02 1.604609e-01 2.754083e+00 +1.580353e-01 -7.389346e-03 9.874058e-01 -5.717914e+01 4.205932e-02 9.991148e-01 7.453325e-04 1.271580e+00 -9.865373e-01 4.141182e-02 1.582062e-01 2.922340e+00 +1.561131e-01 -3.715552e-03 9.877322e-01 -5.612897e+01 4.078635e-02 9.991643e-01 -2.687813e-03 1.245740e+00 -9.868968e-01 4.070559e-02 1.561342e-01 3.091711e+00 +1.538278e-01 -1.767243e-03 9.880961e-01 -5.507579e+01 4.099958e-02 9.991486e-01 -4.595846e-03 1.220130e+00 -9.872467e-01 4.121848e-02 1.537693e-01 3.257606e+00 +1.516513e-01 -9.589047e-04 9.884336e-01 -5.402578e+01 4.093008e-02 9.991479e-01 -5.310438e-03 1.190980e+00 -9.875863e-01 4.126199e-02 1.515613e-01 3.418967e+00 +1.485537e-01 1.128021e-03 9.889037e-01 -5.298854e+01 4.088205e-02 9.991374e-01 -7.281023e-03 1.158485e+00 -9.880590e-01 4.151002e-02 1.483794e-01 3.575444e+00 +1.453418e-01 3.587332e-03 9.893750e-01 -5.194871e+01 3.989622e-02 9.991588e-01 -9.483672e-03 1.126192e+00 -9.885768e-01 4.085069e-02 1.450764e-01 3.731990e+00 +1.421420e-01 3.712632e-03 9.898393e-01 -5.090978e+01 3.626161e-02 9.993022e-01 -8.955337e-03 1.092700e+00 -9.891819e-01 3.716609e-02 1.419082e-01 3.888602e+00 +1.388847e-01 1.195828e-03 9.903078e-01 -4.986836e+01 3.478609e-02 9.993762e-01 -6.085321e-03 1.059508e+00 -9.896974e-01 3.529409e-02 1.387564e-01 4.040344e+00 +1.362735e-01 -1.023395e-03 9.906707e-01 -4.883083e+01 3.433055e-02 9.994037e-01 -3.689988e-03 1.028182e+00 -9.900763e-01 3.451311e-02 1.362274e-01 4.185866e+00 +1.337272e-01 5.013548e-04 9.910180e-01 -4.780073e+01 3.326149e-02 9.994342e-01 -4.993894e-03 9.972302e-01 -9.904599e-01 3.363055e-02 1.336348e-01 4.328703e+00 +1.318428e-01 3.834874e-03 9.912632e-01 -4.677630e+01 3.482217e-02 9.993574e-01 -8.497710e-03 9.663776e-01 -9.906588e-01 3.563829e-02 1.316246e-01 4.464286e+00 +1.297510e-01 6.091046e-03 9.915279e-01 -4.575602e+01 3.600793e-02 9.992926e-01 -1.085073e-02 9.333240e-01 -9.908926e-01 3.711075e-02 1.294399e-01 4.596502e+00 +1.273351e-01 6.379432e-03 9.918392e-01 -4.473131e+01 3.703200e-02 9.992515e-01 -1.118138e-02 8.991455e-01 -9.911682e-01 3.815357e-02 1.270035e-01 4.727656e+00 +1.252355e-01 5.076040e-03 9.921140e-01 -4.371218e+01 3.726296e-02 9.992573e-01 -9.816330e-03 8.642522e-01 -9.914271e-01 3.819845e-02 1.249533e-01 4.856902e+00 +1.231197e-01 3.767534e-03 9.923847e-01 -4.269700e+01 3.875180e-02 9.992118e-01 -8.601181e-03 8.291555e-01 -9.916350e-01 3.951566e-02 1.228767e-01 4.980987e+00 +1.210955e-01 2.050569e-03 9.926387e-01 -4.168052e+01 3.993208e-02 9.991783e-01 -6.935538e-03 7.934946e-01 -9.918374e-01 4.047799e-02 1.209141e-01 5.102229e+00 +1.190339e-01 8.383305e-04 9.928898e-01 -4.066636e+01 4.078381e-02 9.991515e-01 -5.733040e-03 7.602702e-01 -9.920523e-01 4.117624e-02 1.188987e-01 5.223322e+00 +1.169957e-01 4.972231e-04 9.931323e-01 -3.966271e+01 4.118731e-02 9.991371e-01 -5.352291e-03 7.277943e-01 -9.922780e-01 4.153063e-02 1.168742e-01 5.340218e+00 +1.149560e-01 1.778099e-03 9.933690e-01 -3.867547e+01 4.287172e-02 9.990578e-01 -6.749544e-03 6.971953e-01 -9.924451e-01 4.336332e-02 1.147715e-01 5.453221e+00 +1.133153e-01 3.447306e-03 9.935531e-01 -3.768929e+01 4.346558e-02 9.990194e-01 -8.423548e-03 6.664957e-01 -9.926079e-01 4.413986e-02 1.130543e-01 5.564962e+00 +1.119746e-01 4.989480e-03 9.936985e-01 -3.671239e+01 4.354192e-02 9.990023e-01 -9.922620e-03 6.339514e-01 -9.927567e-01 4.437861e-02 1.116456e-01 5.676298e+00 +1.106486e-01 4.573317e-03 9.938491e-01 -3.574547e+01 4.439424e-02 9.989685e-01 -9.539440e-03 6.030199e-01 -9.928676e-01 4.517669e-02 1.103314e-01 5.782569e+00 +1.093419e-01 3.029956e-03 9.939996e-01 -3.478624e+01 4.474151e-02 9.989668e-01 -7.966754e-03 5.714296e-01 -9.929968e-01 4.534413e-02 1.090934e-01 5.888495e+00 +1.078212e-01 1.381543e-03 9.941693e-01 -3.384239e+01 4.416611e-02 9.990051e-01 -6.178240e-03 5.394425e-01 -9.931888e-01 4.457473e-02 1.076529e-01 5.992028e+00 +1.065331e-01 1.647125e-03 9.943078e-01 -3.291346e+01 4.422526e-02 9.990011e-01 -6.393331e-03 5.073475e-01 -9.933252e-01 4.465461e-02 1.063539e-01 6.092164e+00 +1.051886e-01 2.288916e-03 9.944496e-01 -3.199672e+01 4.368657e-02 9.990213e-01 -6.920418e-03 4.767447e-01 -9.934923e-01 4.417203e-02 1.049856e-01 6.190015e+00 +1.040611e-01 2.157340e-03 9.945686e-01 -3.108729e+01 4.452481e-02 9.989849e-01 -6.825525e-03 4.481242e-01 -9.935738e-01 4.499323e-02 1.038594e-01 6.284223e+00 +1.030513e-01 -8.214025e-04 9.946757e-01 -3.018694e+01 4.503412e-02 9.989780e-01 -3.840711e-03 4.209403e-01 -9.936561e-01 4.519012e-02 1.029829e-01 6.375925e+00 +1.018882e-01 -5.885390e-03 9.947784e-01 -2.929691e+01 4.693580e-02 9.988973e-01 1.102452e-03 3.981240e-01 -9.936880e-01 4.657838e-02 1.020521e-01 6.465571e+00 +1.006112e-01 -1.132178e-02 9.948614e-01 -2.842101e+01 4.754504e-02 9.988475e-01 6.558877e-03 3.793711e-01 -9.937892e-01 4.664081e-02 1.010335e-01 6.554033e+00 +9.897330e-02 -1.424527e-02 9.949881e-01 -2.755435e+01 4.929786e-02 9.987399e-01 9.395240e-03 3.627527e-01 -9.938682e-01 4.812090e-02 9.955084e-02 6.639511e+00 +9.767201e-02 -1.417523e-02 9.951177e-01 -2.672099e+01 4.925926e-02 9.987418e-01 9.391997e-03 3.464437e-01 -9.939989e-01 4.810141e-02 9.824738e-02 6.720779e+00 +9.661554e-02 -1.183547e-02 9.952514e-01 -2.590015e+01 4.918349e-02 9.987645e-01 7.102683e-03 3.315628e-01 -9.941059e-01 4.826369e-02 9.707828e-02 6.800062e+00 +9.533064e-02 -8.983203e-03 9.954051e-01 -2.509954e+01 4.794763e-02 9.988400e-01 4.422223e-03 3.141138e-01 -9.942903e-01 4.730574e-02 9.565079e-02 6.878691e+00 +9.427363e-02 -6.045431e-03 9.955280e-01 -2.432024e+01 4.627396e-02 9.989273e-01 1.684062e-03 2.945977e-01 -9.944703e-01 4.590824e-02 9.445225e-02 6.954131e+00 +9.314243e-02 -3.509821e-03 9.956466e-01 -2.355888e+01 4.640000e-02 9.989226e-01 -8.193384e-04 2.745003e-01 -9.945711e-01 4.627431e-02 9.320493e-02 7.025199e+00 +9.293004e-02 -2.926262e-03 9.956683e-01 -2.281595e+01 4.744741e-02 9.988726e-01 -1.492795e-03 2.547338e-01 -9.945415e-01 4.738060e-02 9.296411e-02 7.091691e+00 +9.342517e-02 -4.140123e-03 9.956177e-01 -2.208931e+01 4.861190e-02 9.988176e-01 -4.081379e-04 2.347427e-01 -9.944389e-01 4.843699e-02 9.351597e-02 7.159574e+00 +9.437508e-02 -6.014656e-03 9.955185e-01 -2.138003e+01 4.766266e-02 9.988623e-01 1.516440e-03 2.143897e-01 -9.943951e-01 4.730593e-02 9.455438e-02 7.228366e+00 +9.549207e-02 -8.544701e-03 9.953935e-01 -2.068820e+01 4.712280e-02 9.988809e-01 4.053958e-03 1.953748e-01 -9.943142e-01 4.651860e-02 9.578785e-02 7.297213e+00 +9.637925e-02 -9.010115e-03 9.953039e-01 -2.001668e+01 4.848194e-02 9.988146e-01 4.347195e-03 1.799987e-01 -9.941633e-01 4.783527e-02 9.670183e-02 7.362635e+00 +9.686460e-02 -9.043554e-03 9.952565e-01 -1.936227e+01 4.921201e-02 9.987791e-01 4.285941e-03 1.654748e-01 -9.940802e-01 4.856340e-02 9.719140e-02 7.426242e+00 +9.683213e-02 -7.692582e-03 9.952710e-01 -1.872487e+01 4.813865e-02 9.988360e-01 3.036619e-03 1.491883e-01 -9.941359e-01 4.761695e-02 9.708973e-02 7.490892e+00 +9.582538e-02 -4.900056e-03 9.953861e-01 -1.810682e+01 4.775232e-02 9.988591e-01 3.200559e-04 1.335137e-01 -9.942521e-01 4.750132e-02 9.595005e-02 7.551445e+00 +9.401627e-02 -3.404720e-03 9.955648e-01 -1.750149e+01 4.761640e-02 9.988651e-01 -1.080655e-03 1.206821e-01 -9.944313e-01 4.750680e-02 9.407169e-02 7.606545e+00 +9.192086e-02 -2.856452e-03 9.957622e-01 -1.691207e+01 4.961196e-02 9.987671e-01 -1.714713e-03 1.067444e-01 -9.945297e-01 4.955932e-02 9.194924e-02 7.655970e+00 +9.001897e-02 -2.608285e-03 9.959366e-01 -1.633775e+01 5.138381e-02 9.986769e-01 -2.028931e-03 9.110642e-02 -9.946137e-01 5.135765e-02 9.003389e-02 7.702083e+00 +8.795783e-02 -3.958710e-03 9.961163e-01 -1.578080e+01 5.386576e-02 9.985479e-01 -7.880164e-04 7.488558e-02 -9.946668e-01 5.372587e-02 8.804334e-02 7.743640e+00 +8.643175e-02 -5.379888e-03 9.962432e-01 -1.524156e+01 5.613545e-02 9.984230e-01 5.214759e-04 6.013457e-02 -9.946750e-01 5.587948e-02 8.659745e-02 7.782305e+00 +8.496832e-02 -4.040548e-03 9.963754e-01 -1.472605e+01 5.693034e-02 9.983778e-01 -8.062055e-04 4.502491e-02 -9.947559e-01 5.679248e-02 8.506051e-02 7.819683e+00 +8.293432e-02 -3.137625e-03 9.965501e-01 -1.423157e+01 5.658325e-02 9.983966e-01 -1.565502e-03 2.934784e-02 -9.949474e-01 5.651786e-02 8.297888e-02 7.858547e+00 +8.114794e-02 -2.477677e-03 9.966990e-01 -1.375924e+01 5.475273e-02 9.984980e-01 -1.975640e-03 1.302983e-02 -9.951971e-01 5.473230e-02 8.116171e-02 7.895598e+00 +7.944859e-02 2.232339e-04 9.968389e-01 -1.331350e+01 5.556272e-02 9.984443e-01 -4.651975e-03 -4.622482e-03 -9.952893e-01 5.575666e-02 7.931260e-02 7.930153e+00 +7.883108e-02 5.856753e-03 9.968708e-01 -1.289537e+01 5.540031e-02 9.984116e-01 -1.024679e-02 -2.060084e-02 -9.953474e-01 5.603471e-02 7.838140e-02 7.961591e+00 +7.775441e-02 9.753741e-03 9.969248e-01 -1.250101e+01 5.616750e-02 9.983211e-01 -1.414815e-02 -3.582507e-02 -9.953891e-01 5.709485e-02 7.707603e-02 7.991449e+00 +7.720467e-02 1.047628e-02 9.969602e-01 -1.212827e+01 5.462177e-02 9.983986e-01 -1.472132e-02 -5.019853e-02 -9.955179e-01 5.559227e-02 7.650880e-02 8.022018e+00 +7.729256e-02 1.054440e-02 9.969527e-01 -1.177624e+01 5.563179e-02 9.983406e-01 -1.487215e-02 -6.087555e-02 -9.954552e-01 5.661176e-02 7.657769e-02 8.048012e+00 +7.853951e-02 1.290878e-02 9.968274e-01 -1.144837e+01 5.579559e-02 9.982919e-01 -1.732385e-02 -7.197440e-02 -9.953484e-01 5.697917e-02 7.768510e-02 8.073279e+00 +8.052301e-02 1.451903e-02 9.966470e-01 -1.113924e+01 5.569445e-02 9.982662e-01 -1.904240e-02 -8.414595e-02 -9.951956e-01 5.704104e-02 7.957477e-02 8.100664e+00 +8.458036e-02 1.447823e-02 9.963115e-01 -1.084393e+01 5.412875e-02 9.983512e-01 -1.910306e-02 -9.606796e-02 -9.949454e-01 5.554482e-02 8.365721e-02 8.129478e+00 +9.039463e-02 1.448387e-02 9.958007e-01 -1.056139e+01 5.308733e-02 9.984025e-01 -1.934076e-02 -1.092295e-01 -9.944901e-01 5.461269e-02 8.948132e-02 8.159923e+00 +9.678301e-02 1.329032e-02 9.952168e-01 -1.028741e+01 5.064873e-02 9.985496e-01 -1.826033e-02 -1.231666e-01 -9.940160e-01 5.217374e-02 9.596950e-02 8.195045e+00 +1.060404e-01 1.219763e-02 9.942870e-01 -1.002383e+01 4.914349e-02 9.986385e-01 -1.749216e-02 -1.353748e-01 -9.931467e-01 5.071760e-02 1.052966e-01 8.231512e+00 +1.175540e-01 1.198730e-02 9.929941e-01 -9.768380e+00 4.919016e-02 9.986294e-01 -1.787863e-02 -1.456691e-01 -9.918475e-01 5.094724e-02 1.168033e-01 8.269016e+00 +1.302756e-01 1.281595e-02 9.913950e-01 -9.518219e+00 5.006191e-02 9.985560e-01 -1.948698e-02 -1.559451e-01 -9.902132e-01 5.216979e-02 1.294459e-01 8.309922e+00 +1.455008e-01 1.318641e-02 9.892702e-01 -9.271286e+00 5.070398e-02 9.984978e-01 -2.076690e-02 -1.666681e-01 -9.880580e-01 5.318152e-02 1.446136e-01 8.356433e+00 +1.628833e-01 1.241171e-02 9.865673e-01 -9.028161e+00 4.944832e-02 9.985616e-01 -2.072659e-02 -1.786991e-01 -9.854055e-01 5.216010e-02 1.620353e-01 8.412767e+00 +1.805963e-01 1.073683e-02 9.834987e-01 -8.789252e+00 4.608940e-02 9.987495e-01 -1.936655e-02 -1.908124e-01 -9.824769e-01 4.882638e-02 1.798756e-01 8.478175e+00 +1.967724e-01 9.992473e-03 9.803983e-01 -8.555633e+00 4.124218e-02 9.989786e-01 -1.845943e-02 -2.017356e-01 -9.795814e-01 4.406605e-02 1.961593e-01 8.547386e+00 +2.086575e-01 7.623443e-03 9.779590e-01 -8.336972e+00 3.808385e-02 9.991478e-01 -1.591420e-02 -2.107318e-01 -9.772470e-01 4.056505e-02 2.081894e-01 8.612311e+00 +2.166672e-01 2.906894e-03 9.762412e-01 -8.149181e+00 3.645069e-02 9.992742e-01 -1.106536e-02 -2.160158e-01 -9.755648e-01 3.798216e-02 2.164040e-01 8.669320e+00 +2.238611e-01 -8.916906e-04 9.746206e-01 -8.000355e+00 3.778256e-02 9.992558e-01 -7.764068e-03 -2.199045e-01 -9.738885e-01 3.856172e-02 2.237282e-01 8.711552e+00 +2.288623e-01 -1.053953e-03 9.734582e-01 -7.897603e+00 3.800341e-02 9.992467e-01 -7.852820e-03 -2.223291e-01 -9.727167e-01 3.879194e-02 2.287300e-01 8.744962e+00 +2.314513e-01 1.037305e-03 9.728459e-01 -7.829442e+00 3.690538e-02 9.992702e-01 -9.845698e-03 -2.241240e-01 -9.721463e-01 3.818204e-02 2.312441e-01 8.769976e+00 +2.331274e-01 2.547517e-03 9.724428e-01 -7.791718e+00 3.535896e-02 9.993131e-01 -1.109465e-02 -2.246539e-01 -9.718032e-01 3.697103e-02 2.328772e-01 8.786063e+00 +2.337616e-01 2.251628e-03 9.722913e-01 -7.784130e+00 3.521964e-02 9.993214e-01 -1.078185e-02 -2.239065e-01 -9.716559e-01 3.676412e-02 2.335236e-01 8.790737e+00 +2.331962e-01 3.873990e-03 9.724220e-01 -7.799252e+00 3.599789e-02 9.992722e-01 -1.261360e-02 -2.248585e-01 -9.717632e-01 3.794658e-02 2.328870e-01 8.787461e+00 +2.336038e-01 8.083659e-03 9.722982e-01 -7.811419e+00 3.801049e-02 9.991251e-01 -1.743908e-02 -2.287597e-01 -9.715887e-01 4.103136e-02 2.330922e-01 8.783576e+00 +2.336405e-01 1.228358e-02 9.722454e-01 -7.813388e+00 3.824065e-02 9.990305e-01 -2.181161e-02 -2.308480e-01 -9.715708e-01 4.227537e-02 2.329443e-01 8.785181e+00 +2.331332e-01 1.267343e-02 9.723622e-01 -7.813018e+00 3.767073e-02 9.990468e-01 -2.205315e-02 -2.282196e-01 -9.717149e-01 4.177091e-02 2.324335e-01 8.786625e+00 +2.336604e-01 1.151359e-02 9.722501e-01 -7.813526e+00 3.707238e-02 9.990973e-01 -2.074111e-02 -2.248221e-01 -9.716113e-01 4.088999e-02 2.330226e-01 8.787200e+00 +2.335231e-01 1.092972e-02 9.722898e-01 -7.811450e+00 3.701155e-02 9.991122e-01 -2.012062e-02 -2.241583e-01 -9.716466e-01 4.068458e-02 2.329113e-01 8.787825e+00 +2.333287e-01 1.042408e-02 9.723420e-01 -7.809395e+00 3.700549e-02 9.991230e-01 -1.959123e-02 -2.242167e-01 -9.716936e-01 4.055318e-02 2.327383e-01 8.788143e+00 +2.336400e-01 1.012740e-02 9.722704e-01 -7.810347e+00 3.736009e-02 9.991138e-01 -1.938478e-02 -2.239353e-01 -9.716052e-01 4.085316e-02 2.330546e-01 8.784998e+00 +2.336111e-01 1.058526e-02 9.722725e-01 -7.811258e+00 3.741647e-02 9.991022e-01 -1.986754e-02 -2.253094e-01 -9.716100e-01 4.102028e-02 2.330053e-01 8.781898e+00 +2.335943e-01 1.032955e-02 9.722793e-01 -7.809451e+00 3.731807e-02 9.991116e-01 -1.958044e-02 -2.268914e-01 -9.716178e-01 4.085745e-02 2.330013e-01 8.779000e+00 +2.337485e-01 9.891339e-03 9.722468e-01 -7.808845e+00 3.725737e-02 9.991227e-01 -1.912222e-02 -2.283597e-01 -9.715830e-01 4.069313e-02 2.331750e-01 8.776078e+00 +2.336626e-01 1.017240e-02 9.722645e-01 -7.809797e+00 3.735064e-02 9.991133e-01 -1.942972e-02 -2.294419e-01 -9.716001e-01 4.085469e-02 2.330755e-01 8.773619e+00 +2.337270e-01 1.017907e-02 9.722490e-01 -7.809131e+00 3.740922e-02 9.991106e-01 -1.945342e-02 -2.314897e-01 -9.715824e-01 4.091785e-02 2.331383e-01 8.771007e+00 +2.337074e-01 9.823533e-03 9.722573e-01 -7.806451e+00 3.737520e-02 9.991191e-01 -1.907905e-02 -2.332348e-01 -9.715884e-01 4.079721e-02 2.331344e-01 8.768686e+00 +2.337036e-01 9.982206e-03 9.722566e-01 -7.805910e+00 3.734433e-02 9.991173e-01 -1.923453e-02 -2.344691e-01 -9.715905e-01 4.080344e-02 2.331245e-01 8.766426e+00 +2.337492e-01 1.007609e-02 9.722447e-01 -7.804822e+00 3.748385e-02 9.991095e-01 -1.936646e-02 -2.355641e-01 -9.715742e-01 4.097036e-02 2.331634e-01 8.762953e+00 +2.336573e-01 9.950790e-03 9.722681e-01 -7.804019e+00 3.751336e-02 9.991108e-01 -1.924080e-02 -2.354612e-01 -9.715951e-01 4.096878e-02 2.330762e-01 8.761064e+00 +2.336742e-01 9.895407e-03 9.722646e-01 -7.801403e+00 3.743971e-02 9.991150e-01 -1.916695e-02 -2.381377e-01 -9.715939e-01 4.088011e-02 2.330969e-01 8.758008e+00 +2.337061e-01 1.000177e-02 9.722558e-01 -7.800766e+00 3.746686e-02 9.991118e-01 -1.928414e-02 -2.387322e-01 -9.715852e-01 4.093418e-02 2.331238e-01 8.755551e+00 +2.336442e-01 9.999170e-03 9.722707e-01 -7.798535e+00 3.752956e-02 9.991092e-01 -1.929384e-02 -2.397780e-01 -9.715976e-01 4.099678e-02 2.330609e-01 8.752918e+00 +2.336606e-01 9.805288e-03 9.722688e-01 -7.796886e+00 3.751300e-02 9.991137e-01 -1.909134e-02 -2.402344e-01 -9.715943e-01 4.093361e-02 2.330857e-01 8.751680e+00 +2.337162e-01 9.897291e-03 9.722545e-01 -7.795082e+00 3.743311e-02 9.991152e-01 -1.916912e-02 -2.417762e-01 -9.715840e-01 4.087463e-02 2.331390e-01 8.750163e+00 +2.336901e-01 9.934236e-03 9.722604e-01 -7.793436e+00 3.743456e-02 9.991145e-01 -1.920631e-02 -2.436941e-01 -9.715903e-01 4.088445e-02 2.331113e-01 8.748519e+00 +2.336537e-01 9.785473e-03 9.722706e-01 -7.790990e+00 3.746471e-02 9.991162e-01 -1.905909e-02 -2.458614e-01 -9.715979e-01 4.087905e-02 2.330805e-01 8.746808e+00 +2.335352e-01 9.867926e-03 9.722983e-01 -7.789514e+00 3.741835e-02 9.991166e-01 -1.912758e-02 -2.474295e-01 -9.716281e-01 4.084875e-02 2.329596e-01 8.745234e+00 +2.335620e-01 9.840150e-03 9.722921e-01 -7.788334e+00 3.747901e-02 9.991146e-01 -1.911474e-02 -2.486310e-01 -9.716194e-01 4.090501e-02 2.329864e-01 8.743396e+00 +2.335179e-01 9.872460e-03 9.723024e-01 -7.786579e+00 3.748072e-02 9.991139e-01 -1.914645e-02 -2.490955e-01 -9.716299e-01 4.091362e-02 2.329410e-01 8.741897e+00 +2.335116e-01 9.748751e-03 9.723051e-01 -7.784930e+00 3.754312e-02 9.991137e-01 -1.903401e-02 -2.498791e-01 -9.716290e-01 4.094802e-02 2.329386e-01 8.740517e+00 +2.334498e-01 9.853762e-03 9.723189e-01 -7.783308e+00 3.750121e-02 9.991134e-01 -1.912920e-02 -2.516519e-01 -9.716455e-01 4.092883e-02 2.328733e-01 8.738162e+00 +2.334148e-01 9.730485e-03 9.723285e-01 -7.781759e+00 3.756117e-02 9.991134e-01 -1.901538e-02 -2.522750e-01 -9.716515e-01 4.096026e-02 2.328424e-01 8.736836e+00 +2.333226e-01 9.759334e-03 9.723504e-01 -7.780166e+00 3.760258e-02 9.991111e-01 -1.905095e-02 -2.531388e-01 -9.716721e-01 4.100789e-02 2.327482e-01 8.734843e+00 +2.333177e-01 9.773064e-03 9.723514e-01 -7.778886e+00 3.760062e-02 9.991110e-01 -1.906437e-02 -2.542421e-01 -9.716733e-01 4.100906e-02 2.327428e-01 8.733631e+00 +2.333454e-01 9.806411e-03 9.723444e-01 -7.777029e+00 3.756691e-02 9.991117e-01 -1.909176e-02 -2.571410e-01 -9.716680e-01 4.098295e-02 2.327697e-01 8.731859e+00 +2.332963e-01 9.773426e-03 9.723566e-01 -7.775784e+00 3.759354e-02 9.991113e-01 -1.906212e-02 -2.577456e-01 -9.716788e-01 4.100144e-02 2.327216e-01 8.730871e+00 +2.331990e-01 9.755216e-03 9.723801e-01 -7.774105e+00 3.758086e-02 9.991122e-01 -1.903616e-02 -2.601129e-01 -9.717026e-01 4.098208e-02 2.326254e-01 8.728550e+00 +2.331558e-01 9.793359e-03 9.723901e-01 -7.773048e+00 3.752264e-02 9.991140e-01 -1.905954e-02 -2.614363e-01 -9.717152e-01 4.093048e-02 2.325817e-01 8.727049e+00 +2.330851e-01 9.756724e-03 9.724074e-01 -7.771600e+00 3.753395e-02 9.991143e-01 -1.902154e-02 -2.629991e-01 -9.717318e-01 4.093192e-02 2.325124e-01 8.726560e+00 +2.331429e-01 9.732892e-03 9.723938e-01 -7.770532e+00 3.751796e-02 9.991154e-01 -1.899573e-02 -2.636369e-01 -9.717185e-01 4.091094e-02 2.325715e-01 8.725711e+00 +2.330793e-01 9.704870e-03 9.724093e-01 -7.769440e+00 3.750324e-02 9.991166e-01 -1.896067e-02 -2.639662e-01 -9.717343e-01 4.088783e-02 2.325095e-01 8.724407e+00 +2.329898e-01 9.778038e-03 9.724300e-01 -7.768634e+00 3.750801e-02 9.991150e-01 -1.903311e-02 -2.644940e-01 -9.717556e-01 4.090842e-02 2.324168e-01 8.723581e+00 +2.330665e-01 9.696960e-03 9.724124e-01 -7.767855e+00 3.744539e-02 9.991192e-01 -1.893815e-02 -2.639164e-01 -9.717396e-01 4.082620e-02 2.324981e-01 8.723371e+00 +2.329936e-01 9.771118e-03 9.724292e-01 -7.767373e+00 3.746268e-02 9.991171e-01 -1.901533e-02 -2.626878e-01 -9.717565e-01 4.086024e-02 2.324218e-01 8.722710e+00 +2.328969e-01 9.845742e-03 9.724516e-01 -7.766879e+00 3.749542e-02 9.991143e-01 -1.909565e-02 -2.612522e-01 -9.717784e-01 4.090978e-02 2.323214e-01 8.721761e+00 +2.328437e-01 9.716679e-03 9.724656e-01 -7.766332e+00 3.752170e-02 9.991158e-01 -1.896703e-02 -2.601754e-01 -9.717901e-01 4.090490e-02 2.322733e-01 8.720475e+00 +2.327739e-01 9.829550e-03 9.724812e-01 -7.766130e+00 3.751261e-02 9.991140e-01 -1.907780e-02 -2.595991e-01 -9.718072e-01 4.092112e-02 2.321989e-01 8.719138e+00 +2.327178e-01 9.815362e-03 9.724948e-01 -7.765762e+00 3.752415e-02 9.991138e-01 -1.906355e-02 -2.586022e-01 -9.718202e-01 4.092845e-02 2.321433e-01 8.717584e+00 +2.326625e-01 9.869219e-03 9.725074e-01 -7.765154e+00 3.750437e-02 9.991137e-01 -1.911177e-02 -2.580429e-01 -9.718342e-01 4.091987e-02 2.320862e-01 8.716311e+00 +2.325466e-01 9.804424e-03 9.725358e-01 -7.764534e+00 3.752746e-02 9.991141e-01 -1.904570e-02 -2.574981e-01 -9.718610e-01 4.092580e-02 2.319727e-01 8.715316e+00 +2.326433e-01 9.857644e-03 9.725122e-01 -7.763983e+00 3.752143e-02 9.991132e-01 -1.910312e-02 -2.572062e-01 -9.718381e-01 4.093425e-02 2.320671e-01 8.714586e+00 +2.324926e-01 9.851609e-03 9.725483e-01 -7.763616e+00 3.752912e-02 9.991131e-01 -1.909223e-02 -2.564538e-01 -9.718739e-01 4.093768e-02 2.319167e-01 8.713827e+00 +2.325082e-01 9.855010e-03 9.725445e-01 -7.763291e+00 3.755657e-02 9.991119e-01 -1.910295e-02 -2.566759e-01 -9.718691e-01 4.096701e-02 2.319316e-01 8.713138e+00 +2.323928e-01 9.868068e-03 9.725719e-01 -7.763294e+00 3.750008e-02 9.991141e-01 -1.909790e-02 -2.577684e-01 -9.718989e-01 4.090973e-02 2.318168e-01 8.713489e+00 +2.323539e-01 9.855265e-03 9.725814e-01 -7.763326e+00 3.751892e-02 9.991136e-01 -1.908755e-02 -2.583820e-01 -9.719074e-01 4.092526e-02 2.317781e-01 8.712834e+00 +2.322784e-01 9.930590e-03 9.725986e-01 -7.763222e+00 3.742671e-02 9.991160e-01 -1.913968e-02 -2.602086e-01 -9.719290e-01 4.084689e-02 2.317014e-01 8.712820e+00 +2.322928e-01 9.857087e-03 9.725959e-01 -7.762963e+00 3.744754e-02 9.991166e-01 -1.906977e-02 -2.608122e-01 -9.719248e-01 4.085108e-02 2.317185e-01 8.712553e+00 +2.322600e-01 9.942894e-03 9.726029e-01 -7.763016e+00 3.741386e-02 9.991164e-01 -1.914847e-02 -2.630367e-01 -9.719339e-01 4.083624e-02 2.316827e-01 8.712505e+00 +2.321430e-01 9.885782e-03 9.726314e-01 -7.763016e+00 3.742755e-02 9.991170e-01 -1.908801e-02 -2.640248e-01 -9.719614e-01 4.083435e-02 2.315680e-01 8.712363e+00 +2.321898e-01 9.894098e-03 9.726202e-01 -7.763086e+00 3.742301e-02 9.991170e-01 -1.909749e-02 -2.653472e-01 -9.719504e-01 4.083260e-02 2.316145e-01 8.713488e+00 +2.321892e-01 9.899131e-03 9.726202e-01 -7.762777e+00 3.739549e-02 9.991180e-01 -1.909608e-02 -2.669149e-01 -9.719515e-01 4.080551e-02 2.316143e-01 8.713287e+00 +2.321369e-01 9.890896e-03 9.726328e-01 -7.762300e+00 3.738531e-02 9.991187e-01 -1.908294e-02 -2.682438e-01 -9.719644e-01 4.079203e-02 2.315626e-01 8.712924e+00 +2.320573e-01 9.920878e-03 9.726515e-01 -7.762455e+00 3.735502e-02 9.991194e-01 -1.910309e-02 -2.692439e-01 -9.719846e-01 4.076642e-02 2.314823e-01 8.714167e+00 +2.322414e-01 1.001799e-02 9.726066e-01 -7.762182e+00 3.760088e-02 9.991070e-01 -1.926938e-02 -2.697417e-01 -9.719312e-01 4.104600e-02 2.316573e-01 8.716338e+00 +2.327854e-01 1.082495e-02 9.724679e-01 -7.759318e+00 3.742231e-02 9.990978e-01 -2.007938e-02 -2.690780e-01 -9.718079e-01 4.106617e-02 2.321702e-01 8.719035e+00 +2.330129e-01 1.157764e-02 9.724047e-01 -7.753295e+00 3.731547e-02 9.990862e-01 -2.083706e-02 -2.684805e-01 -9.717575e-01 4.114103e-02 2.323679e-01 8.722145e+00 +2.333679e-01 1.203374e-02 9.723140e-01 -7.744025e+00 3.708368e-02 9.990858e-01 -2.126565e-02 -2.693866e-01 -9.716812e-01 4.101969e-02 2.327083e-01 8.726961e+00 +2.341310e-01 1.192937e-02 9.721318e-01 -7.731740e+00 3.696954e-02 9.990922e-01 -2.116406e-02 -2.712793e-01 -9.715019e-01 4.089442e-02 2.334775e-01 8.733879e+00 +2.347461e-01 1.193860e-02 9.719834e-01 -7.717107e+00 3.675587e-02 9.991004e-01 -2.114868e-02 -2.740607e-01 -9.713616e-01 4.069065e-02 2.340961e-01 8.742340e+00 +2.355623e-01 1.207123e-02 9.717843e-01 -7.700361e+00 3.634390e-02 9.991140e-01 -2.122055e-02 -2.762791e-01 -9.711795e-01 4.031719e-02 2.349148e-01 8.751022e+00 +2.367935e-01 1.228318e-02 9.714823e-01 -7.681544e+00 3.598030e-02 9.991233e-01 -2.140267e-02 -2.780647e-01 -9.708936e-01 4.002223e-02 2.361439e-01 8.760683e+00 +2.384238e-01 1.316730e-02 9.710719e-01 -7.658875e+00 3.571253e-02 9.991129e-01 -2.231590e-02 -2.799270e-01 -9.705044e-01 4.000007e-02 2.377421e-01 8.770779e+00 +2.412404e-01 1.558782e-02 9.703402e-01 -7.627090e+00 3.541725e-02 9.990635e-01 -2.485449e-02 -2.824105e-01 -9.698189e-01 4.036268e-02 2.404624e-01 8.786498e+00 +2.457000e-01 1.913117e-02 9.691571e-01 -7.580503e+00 3.462240e-02 9.989941e-01 -2.849760e-02 -2.851154e-01 -9.687274e-01 4.055640e-02 2.447905e-01 8.806943e+00 +2.520869e-01 2.212099e-02 9.674517e-01 -7.513039e+00 3.391078e-02 9.989227e-01 -3.167665e-02 -2.896364e-01 -9.671103e-01 4.079230e-02 2.510652e-01 8.836058e+00 +2.607393e-01 2.381114e-02 9.651156e-01 -7.424021e+00 3.276120e-02 9.989017e-01 -3.349560e-02 -2.951357e-01 -9.648532e-01 4.035195e-02 2.596729e-01 8.873075e+00 +2.718308e-01 2.382522e-02 9.620501e-01 -7.310861e+00 3.164615e-02 9.989315e-01 -3.368033e-02 -3.014302e-01 -9.618246e-01 3.960052e-02 2.707864e-01 8.922220e+00 +2.859396e-01 2.385707e-02 9.579506e-01 -7.175297e+00 2.974741e-02 9.989872e-01 -3.375840e-02 -3.092874e-01 -9.577858e-01 3.814941e-02 2.849403e-01 8.982757e+00 +3.032597e-01 2.403588e-02 9.526048e-01 -7.020116e+00 2.855739e-02 9.990035e-01 -3.429779e-02 -3.170139e-01 -9.524800e-01 3.760503e-02 3.022711e-01 9.054806e+00 +3.239933e-01 2.377256e-02 9.457606e-01 -6.840984e+00 2.865075e-02 9.989791e-01 -3.492528e-02 -3.244552e-01 -9.456255e-01 3.841230e-02 3.229815e-01 9.138610e+00 +3.474886e-01 2.139745e-02 9.374400e-01 -6.640897e+00 2.961257e-02 9.989905e-01 -3.377911e-02 -3.325367e-01 -9.372165e-01 3.949786e-02 3.465042e-01 9.236569e+00 +3.739355e-01 1.840184e-02 9.272721e-01 -6.421125e+00 2.853577e-02 9.991015e-01 -3.133476e-02 -3.434678e-01 -9.270156e-01 3.817759e-02 3.730745e-01 9.355307e+00 +4.028476e-01 1.447706e-02 9.151525e-01 -6.183682e+00 2.919888e-02 9.991627e-01 -2.865931e-02 -3.541851e-01 -9.148012e-01 3.826676e-02 4.020876e-01 9.491639e+00 +4.340889e-01 1.169855e-02 9.007941e-01 -5.930743e+00 3.015055e-02 9.991668e-01 -2.750555e-02 -3.653588e-01 -9.003654e-01 3.909928e-02 4.333745e-01 9.644152e+00 +4.672260e-01 1.007552e-02 8.840805e-01 -5.669734e+00 2.643617e-02 9.993287e-01 -2.536016e-02 -3.802068e-01 -8.837426e-01 3.522063e-02 4.666461e-01 9.825674e+00 +5.014280e-01 9.282097e-03 8.651496e-01 -5.399130e+00 2.152318e-02 9.994992e-01 -2.319804e-02 -3.975713e-01 -8.649317e-01 3.025291e-02 5.009770e-01 1.002988e+01 +5.370932e-01 9.751654e-03 8.434665e-01 -5.120740e+00 1.616091e-02 9.996307e-01 -2.184789e-02 -4.174511e-01 -8.433681e-01 2.536553e-02 5.367372e-01 1.025779e+01 +5.732567e-01 9.847356e-03 8.193166e-01 -4.837331e+00 1.154664e-02 9.997314e-01 -2.009467e-02 -4.385010e-01 -8.192945e-01 2.097975e-02 5.729890e-01 1.050906e+01 +6.105544e-01 1.106549e-02 7.918970e-01 -4.550622e+00 7.135841e-03 9.997849e-01 -1.947215e-02 -4.541678e-01 -7.919422e-01 1.753965e-02 6.103442e-01 1.078166e+01 +6.480448e-01 1.031230e-02 7.615324e-01 -4.260731e+00 5.554385e-03 9.998177e-01 -1.826568e-02 -4.659758e-01 -7.615820e-01 1.606682e-02 6.478694e-01 1.108070e+01 +6.845476e-01 1.143084e-02 7.288785e-01 -3.974910e+00 3.589237e-03 9.998121e-01 -1.905078e-02 -4.788020e-01 -7.289594e-01 1.565728e-02 6.843779e-01 1.140594e+01 +7.194361e-01 1.358309e-02 6.944258e-01 -3.693711e+00 2.370578e-03 9.997549e-01 -2.201135e-02 -4.927691e-01 -6.945546e-01 1.748194e-02 7.192276e-01 1.175393e+01 +7.533388e-01 1.468151e-02 6.574687e-01 -3.414512e+00 6.014343e-05 9.997492e-01 -2.239368e-02 -5.085419e-01 -6.576326e-01 1.690956e-02 7.531490e-01 1.213562e+01 +7.850142e-01 1.213703e-02 6.193589e-01 -3.135391e+00 -1.007250e-03 9.998317e-01 -1.831617e-02 -5.243862e-01 -6.194770e-01 1.375460e-02 7.848943e-01 1.254641e+01 +8.142749e-01 8.997387e-03 5.804097e-01 -2.862178e+00 -9.281950e-04 9.998987e-01 -1.419803e-02 -5.380326e-01 -5.804787e-01 1.102236e-02 8.142008e-01 1.299267e+01 +8.416931e-01 7.185775e-03 5.399084e-01 -2.599066e+00 -1.716312e-03 9.999420e-01 -1.063283e-02 -5.509808e-01 -5.399535e-01 8.022923e-03 8.416566e-01 1.346790e+01 +8.664784e-01 9.353877e-03 4.991269e-01 -2.352855e+00 -2.874894e-03 9.999013e-01 -1.374785e-02 -5.588841e-01 -4.992062e-01 1.047728e-02 8.664199e-01 1.397239e+01 +8.888786e-01 1.233421e-02 4.579767e-01 -2.118271e+00 -6.843616e-03 9.998834e-01 -1.364618e-02 -5.719196e-01 -4.580917e-01 8.995576e-03 8.888594e-01 1.451226e+01 +9.085937e-01 8.376965e-03 4.175971e-01 -1.884998e+00 -4.467195e-03 9.999365e-01 -1.033908e-02 -5.854659e-01 -4.176573e-01 7.528536e-03 9.085735e-01 1.508331e+01 +9.249707e-01 4.905548e-03 3.800068e-01 -1.661773e+00 -2.018913e-03 9.999660e-01 -7.994455e-03 -5.949507e-01 -3.800331e-01 6.627434e-03 9.249491e-01 1.568604e+01 +9.388831e-01 2.377674e-03 3.442280e-01 -1.456347e+00 2.448548e-04 9.999713e-01 -7.574910e-03 -6.010921e-01 -3.442361e-01 7.196239e-03 9.388555e-01 1.631856e+01 +9.509275e-01 -8.395830e-04 3.094128e-01 -1.260100e+00 3.859885e-03 9.999507e-01 -9.149360e-03 -6.127757e-01 -3.093899e-01 9.894673e-03 9.508838e-01 1.697489e+01 +9.614661e-01 -9.361078e-03 2.747642e-01 -1.073956e+00 1.262831e-02 9.998690e-01 -1.012445e-02 -6.240981e-01 -2.746335e-01 1.320412e-02 9.614583e-01 1.766108e+01 +9.706205e-01 -1.636509e-02 2.400586e-01 -9.045466e-01 1.955554e-02 9.997492e-01 -1.091407e-02 -6.338585e-01 -2.398198e-01 1.528789e-02 9.706971e-01 1.837374e+01 +9.783786e-01 -1.785354e-02 2.060501e-01 -7.660186e-01 2.092174e-02 9.997002e-01 -1.272114e-02 -6.447196e-01 -2.057612e-01 1.675701e-02 9.784588e-01 1.911706e+01 +9.846622e-01 -1.831689e-02 1.735078e-01 -6.476116e-01 2.066182e-02 9.997178e-01 -1.171811e-02 -6.598908e-01 -1.732442e-01 1.512336e-02 9.847628e-01 1.988282e+01 +9.895835e-01 -1.973855e-02 1.426004e-01 -5.481500e-01 2.190658e-02 9.996668e-01 -1.364942e-02 -6.749805e-01 -1.422835e-01 1.663113e-02 9.896862e-01 2.067541e+01 +9.933531e-01 -1.932060e-02 1.134741e-01 -4.693740e-01 2.133996e-02 9.996343e-01 -1.660798e-02 -6.929246e-01 -1.131117e-01 1.891912e-02 9.934021e-01 2.148941e+01 +9.960755e-01 -1.728438e-02 8.680309e-02 -4.117778e-01 1.905593e-02 9.996258e-01 -1.962172e-02 -7.110847e-01 -8.643147e-02 2.119882e-02 9.960322e-01 2.232327e+01 +9.979047e-01 -1.412625e-02 6.314041e-02 -3.740026e-01 1.549258e-02 9.996551e-01 -2.120258e-02 -7.320349e-01 -6.281913e-02 2.213635e-02 9.977794e-01 2.318476e+01 +9.990384e-01 -1.071433e-02 4.251581e-02 -3.531069e-01 1.165422e-02 9.996918e-01 -2.192073e-02 -7.554471e-01 -4.226784e-02 2.239513e-02 9.988553e-01 2.406623e+01 +9.996367e-01 -7.317665e-03 2.594109e-02 -3.456498e-01 7.903439e-03 9.997144e-01 -2.255073e-02 -7.831420e-01 -2.576867e-02 2.274756e-02 9.994091e-01 2.497417e+01 +9.999079e-01 -3.955509e-03 1.298628e-02 -3.477693e-01 4.261324e-03 9.997122e-01 -2.360638e-02 -8.110963e-01 -1.288917e-02 2.365954e-02 9.996370e-01 2.589974e+01 +9.999920e-01 -1.480101e-03 3.712568e-03 -3.561916e-01 1.567618e-03 9.997183e-01 -2.368213e-02 -8.396012e-01 -3.676470e-03 2.368775e-02 9.997127e-01 2.685034e+01 +9.999945e-01 9.986745e-04 -3.165611e-03 -3.699857e-01 -1.072113e-03 9.997283e-01 -2.328275e-02 -8.686624e-01 3.141500e-03 2.328601e-02 9.997239e-01 2.782127e+01 +9.999650e-01 3.467935e-03 -7.618840e-03 -3.872380e-01 -3.629077e-03 9.997678e-01 -2.123932e-02 -8.972598e-01 7.543415e-03 2.126622e-02 9.997454e-01 2.881849e+01 +9.999397e-01 5.150416e-03 -9.703332e-03 -4.057436e-01 -5.347238e-03 9.997782e-01 -2.036825e-02 -9.266744e-01 9.596276e-03 2.041890e-02 9.997455e-01 2.983658e+01 +9.999305e-01 6.070221e-03 -1.011033e-02 -4.250198e-01 -6.284404e-03 9.997536e-01 -2.128917e-02 -9.552236e-01 9.978607e-03 2.135122e-02 9.997222e-01 3.087400e+01 +9.999207e-01 7.107561e-03 -1.040099e-02 -4.435254e-01 -7.337744e-03 9.997252e-01 -2.226254e-02 -9.834229e-01 1.023990e-02 2.233709e-02 9.996981e-01 3.193512e+01 +9.999237e-01 5.653235e-03 -1.098472e-02 -4.593569e-01 -5.883322e-03 9.997616e-01 -2.102778e-02 -1.012283e+00 1.086323e-02 2.109080e-02 9.997186e-01 3.301760e+01 +9.999184e-01 4.841705e-03 -1.181909e-02 -4.747214e-01 -5.047527e-03 9.998350e-01 -1.744703e-02 -1.041566e+00 1.173266e-02 1.750526e-02 9.997779e-01 3.412627e+01 +9.999081e-01 4.792449e-03 -1.268329e-02 -4.931853e-01 -4.953123e-03 9.999075e-01 -1.266715e-02 -1.069567e+00 1.262141e-02 1.272881e-02 9.998393e-01 3.525202e+01 +9.998918e-01 4.592205e-03 -1.397788e-02 -5.126275e-01 -4.722889e-03 9.999453e-01 -9.330704e-03 -1.095653e+00 1.393427e-02 9.395709e-03 9.998588e-01 3.639240e+01 +9.998733e-01 4.274534e-03 -1.533099e-02 -5.355460e-01 -4.395839e-03 9.999592e-01 -7.887374e-03 -1.121610e+00 1.529666e-02 7.953767e-03 9.998514e-01 3.753899e+01 +9.998492e-01 4.368950e-03 -1.680703e-02 -5.588949e-01 -4.470175e-03 9.999720e-01 -5.989872e-03 -1.147517e+00 1.678040e-02 6.064099e-03 9.998408e-01 3.868620e+01 +9.998168e-01 4.212013e-03 -1.867430e-02 -5.843039e-01 -4.300653e-03 9.999796e-01 -4.708950e-03 -1.174080e+00 1.865409e-02 4.788399e-03 9.998145e-01 3.983562e+01 +9.997806e-01 3.881639e-03 -2.058451e-02 -6.096948e-01 -3.947754e-03 9.999872e-01 -3.172178e-03 -1.200981e+00 2.057193e-02 3.252745e-03 9.997831e-01 4.098569e+01 +9.997406e-01 4.010072e-03 -2.241961e-02 -6.387808e-01 -4.036515e-03 9.999912e-01 -1.134292e-03 -1.227352e+00 2.241486e-02 1.224495e-03 9.997480e-01 4.213484e+01 +9.996999e-01 4.529809e-03 -2.407413e-02 -6.691375e-01 -4.545907e-03 9.999895e-01 -6.139303e-04 -1.254196e+00 2.407110e-02 7.231855e-04 9.997100e-01 4.328304e+01 +9.996499e-01 5.415572e-03 -2.589841e-02 -7.035249e-01 -5.523426e-03 9.999763e-01 -4.094743e-03 -1.285555e+00 2.587562e-02 4.236358e-03 9.996562e-01 4.442219e+01 +9.995975e-01 6.339772e-03 -2.765385e-02 -7.394543e-01 -6.567049e-03 9.999453e-01 -8.135540e-03 -1.316843e+00 2.760076e-02 8.313869e-03 9.995845e-01 4.556433e+01 +9.995570e-01 6.124158e-03 -2.912657e-02 -7.757210e-01 -6.357676e-03 9.999483e-01 -7.931470e-03 -1.350382e+00 2.907649e-02 8.113133e-03 9.995443e-01 4.670678e+01 +9.994917e-01 8.343771e-03 -3.077022e-02 -8.149361e-01 -8.478773e-03 9.999550e-01 -4.259502e-03 -1.383309e+00 3.073330e-02 4.518230e-03 9.995174e-01 4.785330e+01 +9.994828e-01 6.783094e-03 -3.143413e-02 -8.503797e-01 -6.820229e-03 9.999761e-01 -1.074242e-03 -1.414736e+00 3.142609e-02 1.288075e-03 9.995053e-01 4.899701e+01 +9.994480e-01 5.877263e-03 -3.269879e-02 -8.845200e-01 -5.963479e-03 9.999790e-01 -2.539713e-03 -1.444282e+00 3.268318e-02 2.733310e-03 9.994620e-01 5.013248e+01 +9.994261e-01 8.429932e-03 -3.280901e-02 -9.230893e-01 -8.541723e-03 9.999582e-01 -3.268584e-03 -1.474260e+00 3.278008e-02 3.546954e-03 9.994563e-01 5.126683e+01 +9.994320e-01 7.392943e-03 -3.287994e-02 -9.579931e-01 -7.547134e-03 9.999611e-01 -4.567812e-03 -1.502468e+00 3.284489e-02 4.813366e-03 9.994489e-01 5.239662e+01 +9.994533e-01 6.641660e-03 -3.238824e-02 -9.936302e-01 -6.854964e-03 9.999555e-01 -6.479218e-03 -1.535368e+00 3.234376e-02 6.697695e-03 9.994544e-01 5.352159e+01 +9.994707e-01 5.290414e-03 -3.210026e-02 -1.026726e+00 -5.595224e-03 9.999400e-01 -9.413138e-03 -1.570397e+00 3.204854e-02 9.587762e-03 9.994403e-01 5.464386e+01 +9.994730e-01 3.681779e-03 -3.225087e-02 -1.058519e+00 -4.106329e-03 9.999056e-01 -1.310763e-02 -1.607705e+00 3.219957e-02 1.323315e-02 9.993939e-01 5.576123e+01 +9.994754e-01 1.985117e-03 -3.232520e-02 -1.089707e+00 -2.422481e-03 9.999060e-01 -1.349657e-02 -1.645788e+00 3.229538e-02 1.356780e-02 9.993863e-01 5.688370e+01 +9.994703e-01 6.977065e-04 -3.253716e-02 -1.121249e+00 -9.634470e-04 9.999663e-01 -8.152323e-03 -1.681990e+00 3.253038e-02 8.179352e-03 9.994373e-01 5.800859e+01 +9.994675e-01 -5.452218e-04 -3.262430e-02 -1.153354e+00 5.101510e-04 9.999993e-01 -1.083311e-03 -1.713449e+00 3.262487e-02 1.066092e-03 9.994671e-01 5.913220e+01 +9.994694e-01 -1.994817e-03 -3.251234e-02 -1.185006e+00 2.103689e-03 9.999923e-01 3.314755e-03 -1.739715e+00 3.250547e-02 -3.381391e-03 9.994658e-01 6.024888e+01 +9.994583e-01 -5.041295e-03 -3.252315e-02 -1.213473e+00 5.073099e-03 9.999867e-01 8.954103e-04 -1.765856e+00 3.251821e-02 -1.059917e-03 9.994706e-01 6.135987e+01 +9.994195e-01 -1.027169e-02 -3.248475e-02 -1.238850e+00 1.015832e-02 9.999417e-01 -3.653140e-03 -1.790051e+00 3.252039e-02 3.321029e-03 9.994656e-01 6.246393e+01 +9.994264e-01 -9.400937e-03 -3.253593e-02 -1.270319e+00 9.137456e-03 9.999243e-01 -8.237488e-03 -1.822128e+00 3.261091e-02 7.935466e-03 9.994366e-01 6.356585e+01 +9.994541e-01 -7.924512e-03 -3.207321e-02 -1.304675e+00 7.537162e-03 9.998974e-01 -1.218005e-02 -1.856919e+00 3.216644e-02 1.193166e-02 9.994113e-01 6.466489e+01 +9.994695e-01 -6.885132e-03 -3.183291e-02 -1.337326e+00 6.388179e-03 9.998565e-01 -1.568678e-02 -1.894574e+00 3.193635e-02 1.547510e-02 9.993701e-01 6.576270e+01 +9.995272e-01 -1.384840e-03 -3.071627e-02 -1.374798e+00 1.028236e-03 9.999319e-01 -1.162238e-02 -1.935202e+00 3.073028e-02 1.158530e-02 9.994606e-01 6.686894e+01 +9.995461e-01 2.507463e-03 -3.002170e-02 -1.411676e+00 -2.804853e-03 9.999474e-01 -9.867812e-03 -1.975334e+00 2.999538e-02 9.947538e-03 9.995005e-01 6.796703e+01 +9.995440e-01 2.872817e-03 -3.005865e-02 -1.442686e+00 -3.118330e-03 9.999621e-01 -8.124086e-03 -2.008672e+00 3.003418e-02 8.214114e-03 9.995151e-01 6.906158e+01 +9.995360e-01 2.329081e-03 -3.037164e-02 -1.472152e+00 -2.512687e-03 9.999788e-01 -6.008532e-03 -2.039409e+00 3.035700e-02 6.082058e-03 9.995206e-01 7.015547e+01 +9.995229e-01 6.566707e-04 -3.087898e-02 -1.501593e+00 -8.232008e-04 9.999852e-01 -5.380582e-03 -2.071991e+00 3.087499e-02 5.403434e-03 9.995087e-01 7.124366e+01 +9.995042e-01 -8.973385e-04 -3.147172e-02 -1.531721e+00 7.698910e-04 9.999914e-01 -4.061482e-03 -2.102578e+00 3.147510e-02 4.035239e-03 9.994964e-01 7.233085e+01 +9.994826e-01 -2.439063e-03 -3.207333e-02 -1.562229e+00 2.364997e-03 9.999944e-01 -2.347030e-03 -2.132560e+00 3.207887e-02 2.269963e-03 9.994828e-01 7.341608e+01 +9.994592e-01 -3.414550e-03 -3.270435e-02 -1.593624e+00 3.309945e-03 9.999892e-01 -3.252133e-03 -2.162929e+00 3.271511e-02 3.142125e-03 9.994598e-01 7.449454e+01 +9.994420e-01 -4.128080e-03 -3.314625e-02 -1.625772e+00 3.906661e-03 9.999696e-01 -6.742087e-03 -2.193626e+00 3.317308e-02 6.608834e-03 9.994278e-01 7.556828e+01 +9.994203e-01 -3.909072e-03 -3.381867e-02 -1.660434e+00 3.581116e-03 9.999460e-01 -9.752666e-03 -2.225262e+00 3.385497e-02 9.625904e-03 9.993804e-01 7.663661e+01 +9.994034e-01 -2.439574e-03 -3.445248e-02 -1.698099e+00 2.121785e-03 9.999549e-01 -9.257544e-03 -2.257835e+00 3.447351e-02 9.178920e-03 9.993635e-01 7.770960e+01 +9.993863e-01 -7.931820e-04 -3.502025e-02 -1.736262e+00 5.972876e-04 9.999841e-01 -5.603858e-03 -2.289900e+00 3.502414e-02 5.579501e-03 9.993709e-01 7.878068e+01 +9.993710e-01 6.115529e-04 -3.545749e-02 -1.775229e+00 -6.544999e-04 9.999990e-01 -1.199627e-03 -2.319234e+00 3.545673e-02 1.222080e-03 9.993705e-01 7.985204e+01 +9.993509e-01 2.717302e-03 -3.592107e-02 -1.815737e+00 -2.671525e-03 9.999955e-01 1.322343e-03 -2.346468e+00 3.592450e-02 -1.225520e-03 9.993538e-01 8.091453e+01 +9.993381e-01 3.124970e-03 -3.624467e-02 -1.856476e+00 -3.172348e-03 9.999942e-01 -1.249708e-03 -2.370869e+00 3.624055e-02 1.363862e-03 9.993422e-01 8.197255e+01 +9.993202e-01 2.300476e-03 -3.679542e-02 -1.895797e+00 -2.412922e-03 9.999925e-01 -3.011856e-03 -2.393122e+00 3.678822e-02 3.098593e-03 9.993183e-01 8.303226e+01 +9.993011e-01 2.445733e-03 -3.730064e-02 -1.936720e+00 -2.579075e-03 9.999904e-01 -3.527079e-03 -2.417674e+00 3.729166e-02 3.620816e-03 9.992979e-01 8.408849e+01 +9.992879e-01 1.479581e-03 -3.770291e-02 -1.977116e+00 -1.647660e-03 9.999888e-01 -4.427287e-03 -2.443876e+00 3.769594e-02 4.486256e-03 9.992792e-01 8.513908e+01 +9.992717e-01 3.278694e-04 -3.815829e-02 -2.017852e+00 -5.301758e-04 9.999858e-01 -5.291770e-03 -2.466419e+00 3.815602e-02 5.308146e-03 9.992577e-01 8.618538e+01 +9.992510e-01 4.084332e-04 -3.869446e-02 -2.060208e+00 -5.396593e-04 9.999941e-01 -3.380956e-03 -2.490081e+00 3.869286e-02 3.399305e-03 9.992454e-01 8.723802e+01 +9.992405e-01 7.427970e-04 -3.895996e-02 -2.103774e+00 -8.103463e-04 9.999982e-01 -1.718049e-03 -2.513205e+00 3.895861e-02 1.748316e-03 9.992393e-01 8.828643e+01 +9.992593e-01 1.045037e-03 -3.846849e-02 -2.146481e+00 -1.107403e-03 9.999981e-01 -1.599954e-03 -2.536284e+00 3.846675e-02 1.641370e-03 9.992585e-01 8.932926e+01 +9.993059e-01 1.340448e-03 -3.722893e-02 -2.187833e+00 -1.437955e-03 9.999956e-01 -2.592459e-03 -2.559082e+00 3.722530e-02 2.644194e-03 9.993034e-01 9.036824e+01 +9.993568e-01 4.868562e-04 -3.585688e-02 -2.226841e+00 -6.263733e-04 9.999923e-01 -3.879812e-03 -2.581569e+00 3.585472e-02 3.899776e-03 9.993494e-01 9.140553e+01 +9.993912e-01 -3.502784e-04 -3.488606e-02 -2.263400e+00 2.203153e-04 9.999930e-01 -3.729137e-03 -2.605028e+00 3.488713e-02 3.719181e-03 9.993843e-01 9.244253e+01 +9.994254e-01 -3.743276e-04 -3.389237e-02 -2.300411e+00 2.818218e-04 9.999962e-01 -2.734139e-03 -2.629120e+00 3.389327e-02 2.723017e-03 9.994218e-01 9.347693e+01 +9.994621e-01 -1.616946e-04 -3.279332e-02 -2.336050e+00 1.146829e-04 9.999989e-01 -1.435453e-03 -2.652197e+00 3.279353e-02 1.430921e-03 9.994611e-01 9.450818e+01 +9.995068e-01 9.355243e-04 -3.138874e-02 -2.372203e+00 -9.555120e-04 9.999993e-01 -6.217816e-04 -2.672743e+00 3.138814e-02 6.514680e-04 9.995071e-01 9.553822e+01 +9.995593e-01 2.283846e-03 -2.959581e-02 -2.406668e+00 -2.271120e-03 9.999973e-01 4.636169e-04 -2.695230e+00 2.959679e-02 -3.961961e-04 9.995618e-01 9.656505e+01 +9.996058e-01 2.954897e-03 -2.792168e-02 -2.437822e+00 -3.016627e-03 9.999931e-01 -2.168958e-03 -2.720792e+00 2.791508e-02 2.252333e-03 9.996078e-01 9.759023e+01 +9.996489e-01 3.360165e-03 -2.628199e-02 -2.465941e+00 -3.577676e-03 9.999597e-01 -8.233357e-03 -2.746454e+00 2.625327e-02 8.324494e-03 9.996207e-01 9.860554e+01 +9.996883e-01 2.600246e-03 -2.482866e-02 -2.491997e+00 -2.954212e-03 9.998944e-01 -1.423033e-02 -2.772152e+00 2.478904e-02 1.429924e-02 9.995904e-01 9.961807e+01 +9.997311e-01 2.420345e-03 -2.306381e-02 -2.516259e+00 -2.779228e-03 9.998753e-01 -1.554106e-02 -2.802258e+00 2.302332e-02 1.560098e-02 9.996132e-01 1.006323e+02 +9.997853e-01 4.124556e-03 -2.030698e-02 -2.540211e+00 -4.366615e-03 9.999198e-01 -1.189006e-02 -2.838082e+00 2.025631e-02 1.197618e-02 9.997231e-01 1.016515e+02 +9.998521e-01 5.093142e-03 -1.642513e-02 -2.559424e+00 -5.180910e-03 9.999725e-01 -5.305300e-03 -2.870099e+00 1.639766e-02 5.389612e-03 9.998510e-01 1.026720e+02 +9.999065e-01 5.185198e-03 -1.265185e-02 -2.573631e+00 -5.175995e-03 9.999863e-01 7.601347e-04 -2.899440e+00 1.265562e-02 -6.945769e-04 9.999197e-01 1.036884e+02 +9.999482e-01 3.477027e-03 -9.565992e-03 -2.582148e+00 -3.463847e-03 9.999930e-01 1.394128e-03 -2.925752e+00 9.570774e-03 -1.360920e-03 9.999533e-01 1.046967e+02 +9.999719e-01 7.754970e-04 -7.453091e-03 -2.587543e+00 -8.223710e-04 9.999799e-01 -6.288169e-03 -2.951613e+00 7.448066e-03 6.294121e-03 9.999525e-01 1.056908e+02 +9.999787e-01 -1.909172e-03 -6.238637e-03 -2.591377e+00 1.801076e-03 9.998489e-01 -1.728687e-02 -2.985411e+00 6.270699e-03 1.727526e-02 9.998311e-01 1.066807e+02 +9.999801e-01 -3.055848e-03 -5.528003e-03 -2.595436e+00 2.919293e-03 9.996945e-01 -2.454408e-02 -3.023919e+00 5.601317e-03 2.452745e-02 9.996835e-01 1.076743e+02 +9.999853e-01 -1.921614e-03 -5.068001e-03 -2.603074e+00 1.787222e-03 9.996501e-01 -2.639035e-02 -3.068168e+00 5.116941e-03 2.638090e-02 9.996389e-01 1.086731e+02 +9.999863e-01 1.442877e-03 -5.040721e-03 -2.613518e+00 -1.565849e-03 9.996991e-01 -2.447745e-02 -3.112783e+00 5.003887e-03 2.448500e-02 9.996877e-01 1.096792e+02 +9.999869e-01 2.078613e-03 -4.687571e-03 -2.621977e+00 -2.179742e-03 9.997627e-01 -2.167283e-02 -3.154950e+00 4.641410e-03 2.168276e-02 9.997541e-01 1.106919e+02 +9.999713e-01 5.601517e-03 -5.107705e-03 -2.632184e+00 -5.682957e-03 9.998547e-01 -1.607176e-02 -3.191876e+00 5.016937e-03 1.610032e-02 9.998578e-01 1.117158e+02 +9.999547e-01 8.002609e-03 -5.148389e-03 -2.643630e+00 -8.047817e-03 9.999287e-01 -8.820741e-03 -3.225087e+00 5.077433e-03 8.861774e-03 9.999479e-01 1.127480e+02 +9.999628e-01 5.290399e-03 -6.811146e-03 -2.648827e+00 -5.317345e-03 9.999781e-01 -3.943878e-03 -3.251978e+00 6.790133e-03 3.979948e-03 9.999690e-01 1.137867e+02 +9.999479e-01 5.612422e-03 -8.526135e-03 -2.658982e+00 -5.613966e-03 9.999842e-01 -1.570009e-04 -3.272939e+00 8.525120e-03 2.048588e-04 9.999636e-01 1.148366e+02 +9.999366e-01 5.029364e-03 -1.007948e-02 -2.670822e+00 -4.965922e-03 9.999677e-01 6.309430e-03 -3.289386e+00 1.011089e-02 -6.258974e-03 9.999293e-01 1.158956e+02 +9.999248e-01 3.648261e-03 -1.171077e-02 -2.681214e+00 -3.547540e-03 9.999566e-01 8.610033e-03 -3.305847e+00 1.174168e-02 -8.567838e-03 9.998944e-01 1.169672e+02 +9.999105e-01 1.770879e-03 -1.326324e-02 -2.693727e+00 -1.690992e-03 9.999804e-01 6.031978e-03 -3.316682e+00 1.327367e-02 -6.009008e-03 9.998939e-01 1.180391e+02 +9.998978e-01 -2.003294e-03 -1.415879e-02 -2.704277e+00 2.033673e-03 9.999956e-01 2.131522e-03 -3.331533e+00 1.415446e-02 -2.160097e-03 9.998975e-01 1.191204e+02 +9.998832e-01 -1.932089e-03 -1.516392e-02 -2.721440e+00 1.839994e-03 9.999798e-01 -6.084918e-03 -3.353173e+00 1.517537e-02 6.056305e-03 9.998665e-01 1.202045e+02 +9.998728e-01 -4.129843e-03 -1.540843e-02 -2.737358e+00 3.875803e-03 9.998566e-01 -1.648078e-02 -3.381869e+00 1.547428e-02 1.641896e-02 9.997455e-01 1.212928e+02 +9.998496e-01 -6.547146e-03 -1.605875e-02 -2.753130e+00 6.145901e-03 9.996708e-01 -2.490952e-02 -3.418047e+00 1.621656e-02 2.480708e-02 9.995607e-01 1.223904e+02 +9.998464e-01 -5.772054e-03 -1.654965e-02 -2.774777e+00 5.411916e-03 9.997493e-01 -2.172396e-02 -3.458707e+00 1.667089e-02 2.163106e-02 9.996270e-01 1.235067e+02 +9.998400e-01 -4.927363e-03 -1.719456e-02 -2.796853e+00 4.645657e-03 9.998549e-01 -1.638519e-02 -3.498461e+00 1.727281e-02 1.630269e-02 9.997179e-01 1.246336e+02 +9.998158e-01 -6.136035e-03 -1.818830e-02 -2.818486e+00 5.925793e-03 9.999152e-01 -1.159069e-02 -3.533192e+00 1.825788e-02 1.148077e-02 9.997674e-01 1.257673e+02 +9.998016e-01 -5.444960e-03 -1.915822e-02 -2.842109e+00 5.249020e-03 9.999335e-01 -1.026299e-02 -3.568332e+00 1.921283e-02 1.016040e-02 9.997638e-01 1.269024e+02 +9.997842e-01 -4.183162e-03 -2.034873e-02 -2.868633e+00 3.928600e-03 9.999137e-01 -1.253399e-02 -3.606098e+00 2.039940e-02 1.245134e-02 9.997144e-01 1.280456e+02 +9.997463e-01 -4.531689e-03 -2.206534e-02 -2.894674e+00 4.189683e-03 9.998707e-01 -1.552135e-02 -3.642637e+00 2.213282e-02 1.542496e-02 9.996360e-01 1.291941e+02 +9.997124e-01 -3.586939e-03 -2.371110e-02 -2.924595e+00 3.298082e-03 9.999200e-01 -1.221030e-02 -3.680213e+00 2.375301e-02 1.212859e-02 9.996443e-01 1.303510e+02 +9.996735e-01 -3.244676e-03 -2.534372e-02 -2.955332e+00 3.066232e-03 9.999702e-01 -7.076694e-03 -3.716558e+00 2.536593e-02 6.996674e-03 9.996538e-01 1.315075e+02 +9.996233e-01 -3.229876e-03 -2.725496e-02 -2.989266e+00 3.080205e-03 9.999799e-01 -5.531760e-03 -3.751573e+00 2.727229e-02 5.445725e-03 9.996132e-01 1.326632e+02 +9.995770e-01 -3.613452e-03 -2.885948e-02 -3.024507e+00 3.477178e-03 9.999825e-01 -4.770822e-03 -3.787047e+00 2.887622e-02 4.668454e-03 9.995721e-01 1.338196e+02 +9.995287e-01 -3.185642e-03 -3.053428e-02 -3.061487e+00 3.033118e-03 9.999827e-01 -5.040231e-03 -3.822251e+00 3.054981e-02 4.945241e-03 9.995210e-01 1.349693e+02 +9.994747e-01 -4.052960e-03 -3.215572e-02 -3.098988e+00 3.872369e-03 9.999764e-01 -5.676468e-03 -3.858432e+00 3.217797e-02 5.548967e-03 9.994668e-01 1.361179e+02 +9.994221e-01 -3.581326e-03 -3.380340e-02 -3.138966e+00 3.414520e-03 9.999817e-01 -4.991036e-03 -3.892406e+00 3.382066e-02 4.872729e-03 9.994160e-01 1.372625e+02 +9.994002e-01 -2.274567e-03 -3.455616e-02 -3.181202e+00 2.189178e-03 9.999944e-01 -2.508661e-03 -3.926711e+00 3.456168e-02 2.431507e-03 9.993996e-01 1.384126e+02 +9.993887e-01 -2.071757e-03 -3.489882e-02 -3.223176e+00 1.989178e-03 9.999951e-01 -2.400791e-03 -3.959275e+00 3.490363e-02 2.329904e-03 9.993880e-01 1.395546e+02 +9.993894e-01 -1.970590e-03 -3.488559e-02 -3.265946e+00 1.815561e-03 9.999883e-01 -4.475061e-03 -3.992143e+00 3.489400e-02 4.408991e-03 9.993813e-01 1.406935e+02 +9.993867e-01 -1.748509e-03 -3.497518e-02 -3.308422e+00 1.507282e-03 9.999749e-01 -6.922295e-03 -4.025489e+00 3.498641e-02 6.865332e-03 9.993642e-01 1.418271e+02 +9.993706e-01 -3.082724e-03 -3.533991e-02 -3.349036e+00 2.877648e-03 9.999787e-01 -5.852369e-03 -4.057588e+00 3.535720e-02 5.746990e-03 9.993582e-01 1.429599e+02 +9.993240e-01 -3.789496e-03 -3.656809e-02 -3.389718e+00 3.735068e-03 9.999918e-01 -1.556628e-03 -4.089633e+00 3.657369e-02 1.418992e-03 9.993300e-01 1.440955e+02 +9.992506e-01 -5.344983e-03 -3.833624e-02 -3.431331e+00 5.469699e-03 9.999801e-01 3.149044e-03 -4.117886e+00 3.831864e-02 -3.356370e-03 9.992599e-01 1.452273e+02 +9.991880e-01 -5.412867e-03 -3.992643e-02 -3.477541e+00 5.553684e-03 9.999787e-01 3.416805e-03 -4.142642e+00 3.990709e-02 -3.635768e-03 9.991968e-01 1.463510e+02 +9.991429e-01 -5.201852e-03 -4.106705e-02 -3.526115e+00 5.278838e-03 9.999845e-01 1.766402e-03 -4.167273e+00 4.105723e-02 -1.981673e-03 9.991548e-01 1.474675e+02 +9.991011e-01 -3.936001e-03 -4.220884e-02 -3.577485e+00 3.882443e-03 9.999915e-01 -1.350788e-03 -4.193843e+00 4.221380e-02 1.185701e-03 9.991079e-01 1.485769e+02 +9.991022e-01 -3.643856e-03 -4.220810e-02 -3.624478e+00 3.461432e-03 9.999843e-01 -4.394326e-03 -4.226003e+00 4.222346e-02 4.244280e-03 9.990992e-01 1.496798e+02 +9.991452e-01 -2.647962e-03 -4.125413e-02 -3.671472e+00 2.487627e-03 9.999891e-01 -3.937385e-03 -4.261989e+00 4.126411e-02 3.831394e-03 9.991409e-01 1.507753e+02 +9.992024e-01 -3.236514e-03 -3.980089e-02 -3.714791e+00 3.155804e-03 9.999928e-01 -2.090513e-03 -4.296808e+00 3.980737e-02 1.963242e-03 9.992055e-01 1.518613e+02 +9.992542e-01 -3.878437e-03 -3.841814e-02 -3.754718e+00 3.844738e-03 9.999921e-01 -9.510289e-04 -4.333155e+00 3.842153e-02 8.026127e-04 9.992613e-01 1.529390e+02 +9.993086e-01 -3.757345e-03 -3.699068e-02 -3.794318e+00 3.712718e-03 9.999923e-01 -1.275086e-03 -4.368932e+00 3.699519e-02 1.136869e-03 9.993148e-01 1.540039e+02 +9.993660e-01 -3.704258e-03 -3.540963e-02 -3.831714e+00 3.642315e-03 9.999917e-01 -1.813706e-03 -4.406174e+00 3.541605e-02 1.683584e-03 9.993712e-01 1.550663e+02 +9.994209e-01 -3.092233e-03 -3.388737e-02 -3.868959e+00 3.049861e-03 9.999945e-01 -1.301997e-03 -4.438864e+00 3.389122e-02 1.197892e-03 9.994248e-01 1.561225e+02 +9.994764e-01 -2.238680e-03 -3.227976e-02 -3.904131e+00 2.222728e-03 9.999974e-01 -5.300639e-04 -4.473277e+00 3.228087e-02 4.580379e-04 9.994787e-01 1.571722e+02 +9.995228e-01 -1.441184e-03 -3.085496e-02 -3.938124e+00 1.429193e-03 9.999989e-01 -4.106866e-04 -4.504975e+00 3.085552e-02 3.663937e-04 9.995238e-01 1.582148e+02 +9.995628e-01 1.956640e-04 -2.956767e-02 -3.969460e+00 -2.767401e-04 9.999962e-01 -2.737984e-03 -4.537441e+00 2.956703e-02 2.744969e-03 9.995590e-01 1.592473e+02 +9.996093e-01 -8.285543e-04 -2.793896e-02 -3.996788e+00 7.088910e-04 9.999905e-01 -4.292666e-03 -4.569107e+00 2.794226e-02 4.271183e-03 9.996004e-01 1.602765e+02 +9.996551e-01 4.371355e-04 -2.625929e-02 -4.024156e+00 -5.801337e-04 9.999850e-01 -5.438250e-03 -4.602946e+00 2.625652e-02 5.451608e-03 9.996404e-01 1.613026e+02 +9.996968e-01 3.787441e-03 -2.433086e-02 -4.053863e+00 -3.989166e-03 9.999580e-01 -8.247707e-03 -4.638812e+00 2.429860e-02 8.342265e-03 9.996699e-01 1.623204e+02 +9.997419e-01 -9.328112e-04 -2.269807e-02 -4.071651e+00 6.806797e-04 9.999380e-01 -1.111326e-02 -4.668349e+00 2.270703e-02 1.109494e-02 9.996806e-01 1.633340e+02 +9.997774e-01 -3.013850e-03 -2.088467e-02 -4.088980e+00 2.801455e-03 9.999441e-01 -1.019173e-02 -4.702620e+00 2.091422e-02 1.013096e-02 9.997300e-01 1.643467e+02 +9.998048e-01 -4.906538e-03 -1.913686e-02 -4.105311e+00 4.760516e-03 9.999592e-01 -7.668545e-03 -4.733185e+00 1.917371e-02 7.575947e-03 9.997875e-01 1.653600e+02 +9.998226e-01 -3.946682e-03 -1.841701e-02 -4.122556e+00 3.830973e-03 9.999727e-01 -6.313831e-03 -4.761485e+00 1.844143e-02 6.242156e-03 9.998105e-01 1.663689e+02 +9.998486e-01 -1.137471e-04 -1.739812e-02 -4.143234e+00 -7.056470e-05 9.999439e-01 -1.059280e-02 -4.790723e+00 1.739835e-02 1.059242e-02 9.997925e-01 1.673719e+02 +9.998506e-01 5.152716e-03 -1.649747e-02 -4.167454e+00 -5.458574e-03 9.998130e-01 -1.854860e-02 -4.821002e+00 1.639881e-02 1.863587e-02 9.996919e-01 1.683701e+02 +9.997976e-01 1.147115e-02 -1.652964e-02 -4.194278e+00 -1.183019e-02 9.996926e-01 -2.178919e-02 -4.852698e+00 1.627462e-02 2.198033e-02 9.996259e-01 1.693809e+02 +9.997425e-01 1.445842e-02 -1.748986e-02 -4.218861e+00 -1.479404e-02 9.997059e-01 -1.921436e-02 -4.886548e+00 1.720691e-02 1.946816e-02 9.996624e-01 1.703973e+02 +9.996748e-01 1.607323e-02 -1.979786e-02 -4.242992e+00 -1.642733e-02 9.997056e-01 -1.785516e-02 -4.921437e+00 1.950505e-02 1.817458e-02 9.996446e-01 1.714177e+02 +9.996458e-01 1.452707e-02 -2.229735e-02 -4.264263e+00 -1.492019e-02 9.997343e-01 -1.756695e-02 -4.946285e+00 2.203624e-02 1.789341e-02 9.995970e-01 1.724404e+02 +9.996782e-01 7.843050e-03 -2.412660e-02 -4.279245e+00 -8.207177e-03 9.998533e-01 -1.503045e-02 -4.974309e+00 2.400518e-02 1.522363e-02 9.995959e-01 1.734701e+02 +9.996643e-01 2.966542e-03 -2.573739e-02 -4.294270e+00 -3.275926e-03 9.999228e-01 -1.198695e-02 -4.999888e+00 2.569985e-02 1.206724e-02 9.995969e-01 1.745052e+02 +9.996173e-01 2.444408e-03 -2.755437e-02 -4.319751e+00 -2.591563e-03 9.999825e-01 -5.306068e-03 -5.021846e+00 2.754092e-02 5.375446e-03 9.996062e-01 1.755473e+02 +9.995613e-01 -1.164360e-03 -2.959547e-02 -4.342706e+00 1.288829e-03 9.999904e-01 4.186940e-03 -5.037103e+00 2.959032e-02 -4.223245e-03 9.995532e-01 1.766016e+02 +9.994898e-01 -5.911920e-03 -3.138734e-02 -4.366190e+00 6.205875e-03 9.999377e-01 9.276205e-03 -5.046741e+00 3.133055e-02 -9.466256e-03 9.994643e-01 1.776560e+02 +9.994204e-01 -9.595183e-03 -3.266124e-02 -4.393173e+00 9.855145e-03 9.999209e-01 7.807615e-03 -5.055111e+00 3.258374e-02 -8.124969e-03 9.994360e-01 1.787056e+02 +9.993654e-01 -8.375575e-03 -3.462100e-02 -4.428389e+00 8.410396e-03 9.999642e-01 8.602230e-04 -5.066353e+00 3.461256e-02 -1.150852e-03 9.994002e-01 1.797615e+02 +9.993074e-01 -9.583336e-03 -3.595654e-02 -4.461887e+00 9.375178e-03 9.999383e-01 -5.953382e-03 -5.080405e+00 3.601138e-02 5.612160e-03 9.993356e-01 1.808223e+02 +9.993230e-01 -7.635276e-03 -3.598962e-02 -4.501446e+00 7.298892e-03 9.999285e-01 -9.468883e-03 -5.102497e+00 3.605934e-02 9.199787e-03 9.993073e-01 1.818929e+02 +9.993761e-01 -6.988167e-03 -3.462092e-02 -4.538249e+00 6.574767e-03 9.999059e-01 -1.204028e-02 -5.128816e+00 3.470181e-02 1.180514e-02 9.993280e-01 1.829724e+02 +9.994287e-01 -2.912131e-03 -3.367206e-02 -4.577398e+00 2.478357e-03 9.999135e-01 -1.291689e-02 -5.161098e+00 3.370676e-02 1.282606e-02 9.993495e-01 1.840596e+02 +9.994517e-01 -6.020910e-03 -3.255937e-02 -4.607667e+00 5.594600e-03 9.998976e-01 -1.316863e-02 -5.193870e+00 3.263533e-02 1.297925e-02 9.993831e-01 1.851560e+02 +9.994253e-01 -7.767366e-03 -3.299755e-02 -4.635545e+00 7.268084e-03 9.998577e-01 -1.522402e-02 -5.228298e+00 3.311111e-02 1.497544e-02 9.993395e-01 1.862574e+02 +9.994460e-01 -7.052202e-03 -3.252628e-02 -4.669631e+00 6.560814e-03 9.998631e-01 -1.518954e-02 -5.264110e+00 3.262895e-02 1.496772e-02 9.993555e-01 1.873649e+02 +9.994490e-01 -7.654867e-03 -3.229613e-02 -4.701222e+00 7.176371e-03 9.998631e-01 -1.490596e-02 -5.299376e+00 3.240581e-02 1.466597e-02 9.993672e-01 1.884778e+02 +9.995034e-01 -3.380476e-03 -3.132847e-02 -4.740433e+00 2.960858e-03 9.999054e-01 -1.343088e-02 -5.337478e+00 3.137091e-02 1.333145e-02 9.994189e-01 1.896005e+02 +9.995340e-01 -2.488106e-03 -3.042330e-02 -4.775134e+00 2.115099e-03 9.999223e-01 -1.228665e-02 -5.370083e+00 3.045151e-02 1.221658e-02 9.994616e-01 1.907235e+02 +9.995470e-01 -3.059655e-03 -2.994032e-02 -4.806531e+00 2.773121e-03 9.999500e-01 -9.607018e-03 -5.400336e+00 2.996822e-02 9.519637e-03 9.995055e-01 1.918495e+02 +9.995637e-01 -5.532011e-03 -2.901572e-02 -4.834232e+00 5.263344e-03 9.999426e-01 -9.327633e-03 -5.432643e+00 2.906566e-02 9.170843e-03 9.995354e-01 1.929745e+02 +9.995634e-01 -7.575366e-03 -2.855851e-02 -4.861001e+00 7.182189e-03 9.998783e-01 -1.384501e-02 -5.465950e+00 2.865992e-02 1.363385e-02 9.994962e-01 1.940911e+02 +9.995707e-01 -8.630863e-03 -2.799772e-02 -4.887285e+00 8.102511e-03 9.997880e-01 -1.893020e-02 -5.503274e+00 2.815517e-02 1.869522e-02 9.994287e-01 1.952074e+02 +9.995723e-01 -8.966187e-03 -2.783564e-02 -4.913229e+00 8.524616e-03 9.998366e-01 -1.594191e-02 -5.542014e+00 2.797403e-02 1.569780e-02 9.994854e-01 1.963293e+02 +9.996218e-01 -4.551373e-03 -2.712029e-02 -4.944453e+00 4.268268e-03 9.999359e-01 -1.048764e-02 -5.583495e+00 2.716629e-02 1.036792e-02 9.995772e-01 1.974501e+02 +9.996623e-01 -6.285682e-04 -2.597821e-02 -4.976513e+00 4.008784e-04 9.999614e-01 -8.768931e-03 -5.620180e+00 2.598272e-02 8.755555e-03 9.996241e-01 1.985656e+02 +9.996910e-01 5.131976e-04 -2.485439e-02 -5.004174e+00 -7.613317e-04 9.999499e-01 -9.975074e-03 -5.653498e+00 2.484803e-02 9.990912e-03 9.996413e-01 1.996738e+02 +9.996859e-01 2.000690e-03 -2.498235e-02 -5.032187e+00 -2.252552e-03 9.999469e-01 -1.005753e-02 -5.688522e+00 2.496090e-02 1.011065e-02 9.996373e-01 2.007832e+02 +9.996942e-01 2.391928e-03 -2.461165e-02 -5.057617e+00 -2.600892e-03 9.999608e-01 -8.461916e-03 -5.726707e+00 2.459045e-02 8.523340e-03 9.996613e-01 2.018908e+02 +9.996677e-01 -3.257222e-04 -2.577564e-02 -5.080255e+00 5.249388e-05 9.999438e-01 -1.060022e-02 -5.763733e+00 2.577765e-02 1.059535e-02 9.996116e-01 2.029899e+02 +9.996705e-01 1.208130e-03 -2.564270e-02 -5.108008e+00 -1.432991e-03 9.999606e-01 -8.752434e-03 -5.794768e+00 2.563112e-02 8.786295e-03 9.996329e-01 2.040882e+02 +9.996696e-01 1.078014e-03 -2.568106e-02 -5.132018e+00 -1.267608e-03 9.999720e-01 -7.367484e-03 -5.828125e+00 2.567240e-02 7.397603e-03 9.996430e-01 2.051795e+02 +9.996673e-01 3.957746e-03 -2.548954e-02 -5.162327e+00 -4.032202e-03 9.999877e-01 -2.870253e-03 -5.858524e+00 2.547787e-02 2.972077e-03 9.996710e-01 2.062655e+02 +9.996909e-01 2.898174e-03 -2.469118e-02 -5.187354e+00 -2.905160e-03 9.999957e-01 -2.470640e-04 -5.884600e+00 2.469036e-02 3.187202e-04 9.996951e-01 2.073378e+02 +9.997134e-01 2.662842e-03 -2.379049e-02 -5.210165e+00 -2.659072e-03 9.999964e-01 1.901289e-04 -5.910540e+00 2.379091e-02 -1.268130e-04 9.997170e-01 2.083940e+02 +9.997468e-01 9.493557e-04 -2.248152e-02 -5.229687e+00 -9.089549e-04 9.999979e-01 1.807224e-03 -5.935315e+00 2.248320e-02 -1.786331e-03 9.997456e-01 2.094337e+02 +9.997701e-01 2.929101e-03 -2.124065e-02 -5.256357e+00 -2.918637e-03 9.999956e-01 5.236528e-04 -5.964227e+00 2.124209e-02 -4.615378e-04 9.997743e-01 2.104534e+02 +9.997923e-01 1.630986e-03 -2.031664e-02 -5.281372e+00 -1.703771e-03 9.999922e-01 -3.565713e-03 -5.994618e+00 2.031067e-02 3.599587e-03 9.997872e-01 2.114515e+02 +9.998144e-01 3.254894e-03 -1.899102e-02 -5.306406e+00 -3.434346e-03 9.999497e-01 -9.424322e-03 -6.028197e+00 1.895939e-02 9.487794e-03 9.997752e-01 2.124318e+02 +9.998276e-01 5.005704e-03 -1.787885e-02 -5.333844e+00 -5.136821e-03 9.999602e-01 -7.295150e-03 -6.061449e+00 1.784162e-02 7.385733e-03 9.998136e-01 2.134063e+02 +9.998226e-01 5.958091e-03 -1.786813e-02 -5.354878e+00 -6.032295e-03 9.999734e-01 -4.101814e-03 -6.093104e+00 1.784322e-02 4.208872e-03 9.998319e-01 2.143656e+02 +9.998215e-01 4.692117e-03 -1.830401e-02 -5.376504e+00 -4.793289e-03 9.999734e-01 -5.487291e-03 -6.125768e+00 1.827778e-02 5.574047e-03 9.998174e-01 2.153190e+02 +9.998241e-01 1.783400e-03 -1.867071e-02 -5.394247e+00 -1.930475e-03 9.999672e-01 -7.862205e-03 -6.155286e+00 1.865608e-02 7.896865e-03 9.997948e-01 2.162647e+02 +9.998241e-01 2.851062e-03 -1.853927e-02 -5.416052e+00 -3.024720e-03 9.999517e-01 -9.345711e-03 -6.187427e+00 1.851173e-02 9.400142e-03 9.997845e-01 2.172057e+02 +9.998333e-01 4.144771e-03 -1.778095e-02 -5.436926e+00 -4.302134e-03 9.999518e-01 -8.820955e-03 -6.219919e+00 1.774354e-02 8.895980e-03 9.998030e-01 2.181455e+02 +9.998459e-01 1.710043e-03 -1.747064e-02 -5.451802e+00 -1.850919e-03 9.999659e-01 -8.050556e-03 -6.252915e+00 1.745628e-02 8.081652e-03 9.998150e-01 2.190794e+02 +9.998598e-01 3.076820e-04 -1.674475e-02 -5.469074e+00 -4.376933e-04 9.999698e-01 -7.761190e-03 -6.284507e+00 1.674185e-02 7.767430e-03 9.998297e-01 2.200140e+02 +9.998790e-01 -2.792205e-03 -1.530170e-02 -5.483243e+00 2.678638e-03 9.999687e-01 -7.437329e-03 -6.315979e+00 1.532199e-02 7.395441e-03 9.998553e-01 2.209438e+02 +9.998905e-01 -4.285404e-03 -1.416242e-02 -5.495490e+00 4.178496e-03 9.999626e-01 -7.569823e-03 -6.347473e+00 1.419433e-02 7.509816e-03 9.998711e-01 2.218719e+02 +9.998990e-01 -6.952067e-03 -1.239601e-02 -5.505322e+00 6.865036e-03 9.999516e-01 -7.049784e-03 -6.379467e+00 1.244442e-02 6.963972e-03 9.998983e-01 2.227981e+02 +9.999039e-01 -8.867054e-03 -1.066007e-02 -5.516509e+00 8.781052e-03 9.999287e-01 -8.087806e-03 -6.411726e+00 1.073102e-02 7.993421e-03 9.999105e-01 2.237223e+02 +9.999238e-01 -8.757063e-03 -8.698359e-03 -5.529255e+00 8.684656e-03 9.999276e-01 -8.327674e-03 -6.442633e+00 8.770656e-03 8.251497e-03 9.999275e-01 2.246470e+02 +9.999605e-01 -5.927373e-03 -6.629487e-03 -5.545023e+00 5.866337e-03 9.999405e-01 -9.188879e-03 -6.475233e+00 6.683559e-03 9.149624e-03 9.999358e-01 2.255714e+02 +9.999041e-01 -1.311503e-02 -4.448991e-03 -5.545765e+00 1.307223e-02 9.998692e-01 -9.516454e-03 -6.504615e+00 4.573219e-03 9.457382e-03 9.999448e-01 2.264983e+02 +9.999097e-01 -1.291211e-02 -3.733744e-03 -5.552133e+00 1.285166e-02 9.997928e-01 -1.578505e-02 -6.541266e+00 3.936789e-03 1.573563e-02 9.998684e-01 2.274200e+02 +9.999382e-01 -1.087851e-02 -2.290716e-03 -5.563610e+00 1.082018e-02 9.996510e-01 -2.409807e-02 -6.579923e+00 2.552068e-03 2.407179e-02 9.997070e-01 2.283373e+02 +9.998639e-01 -1.578548e-02 -4.806557e-03 -5.565319e+00 1.560906e-02 9.992737e-01 -3.476162e-02 -6.618473e+00 5.351795e-03 3.468185e-02 9.993841e-01 2.292590e+02 +9.998219e-01 -1.666376e-02 -8.861901e-03 -5.574282e+00 1.633510e-02 9.992201e-01 -3.594954e-02 -6.662608e+00 9.454045e-03 3.579837e-02 9.993143e-01 2.301888e+02 +9.998104e-01 -1.300996e-02 -1.448994e-02 -5.598680e+00 1.254752e-02 9.994230e-01 -3.156112e-02 -6.712705e+00 1.489219e-02 3.137332e-02 9.993968e-01 2.311303e+02 +9.996844e-01 -1.126688e-02 -2.245558e-02 -5.627327e+00 1.065175e-02 9.995698e-01 -2.732707e-02 -6.756883e+00 2.275381e-02 2.707925e-02 9.993743e-01 2.320713e+02 +9.994850e-01 -8.705977e-03 -3.088517e-02 -5.665685e+00 8.157867e-03 9.998078e-01 -1.782860e-02 -6.795956e+00 3.103445e-02 1.756746e-02 9.993639e-01 2.330283e+02 +9.992251e-01 -4.109504e-03 -3.914620e-02 -5.715519e+00 3.801075e-03 9.999611e-01 -7.950084e-03 -6.828623e+00 3.917735e-02 7.795125e-03 9.992019e-01 2.339927e+02 +9.989200e-01 -2.411271e-04 -4.646325e-02 -5.771009e+00 2.486273e-04 9.999999e-01 1.556425e-04 -6.852764e+00 4.646321e-02 -1.670256e-04 9.989200e-01 2.349616e+02 +9.986032e-01 -1.532752e-03 -5.281421e-02 -5.826839e+00 1.681762e-03 9.999947e-01 2.777063e-03 -6.869182e+00 5.280968e-02 -2.862004e-03 9.986005e-01 2.359345e+02 +9.983098e-01 -1.635975e-03 -5.809423e-02 -5.886862e+00 1.743579e-03 9.999968e-01 1.801584e-03 -6.885877e+00 5.809111e-02 -1.899830e-03 9.983095e-01 2.369129e+02 +9.981805e-01 6.657036e-03 -5.992825e-02 -5.960975e+00 -6.709729e-03 9.999772e-01 -6.780466e-04 -6.902209e+00 5.992238e-02 1.078916e-03 9.982025e-01 2.379024e+02 +9.982708e-01 8.477839e-03 -5.816782e-02 -6.024778e+00 -8.787477e-03 9.999485e-01 -5.069423e-03 -6.921190e+00 5.812185e-02 5.571805e-03 9.982940e-01 2.389004e+02 +9.984481e-01 5.442054e-03 -5.542360e-02 -6.076718e+00 -5.864016e-03 9.999550e-01 -7.453606e-03 -6.943334e+00 5.538055e-02 7.767043e-03 9.984351e-01 2.399117e+02 +9.986130e-01 1.825962e-03 -5.261866e-02 -6.127033e+00 -2.234218e-03 9.999678e-01 -7.700984e-03 -6.963063e+00 5.260291e-02 7.807864e-03 9.985850e-01 2.409341e+02 +9.987086e-01 -7.321071e-04 -5.079911e-02 -6.173462e+00 2.532673e-04 9.999555e-01 -9.431948e-03 -6.989056e+00 5.080375e-02 9.406901e-03 9.986644e-01 2.419667e+02 +9.987830e-01 -7.127905e-03 -4.880297e-02 -6.214931e+00 6.514595e-03 9.998979e-01 -1.271465e-02 -7.013397e+00 4.888862e-02 1.238124e-02 9.987275e-01 2.430115e+02 +9.988428e-01 -8.404928e-03 -4.735433e-02 -6.260968e+00 7.552363e-03 9.998066e-01 -1.815425e-02 -7.042540e+00 4.749776e-02 1.777560e-02 9.987132e-01 2.440632e+02 +9.989293e-01 -8.520397e-03 -4.547273e-02 -6.311473e+00 7.591667e-03 9.997598e-01 -2.055771e-02 -7.075354e+00 4.563697e-02 2.019048e-02 9.987540e-01 2.451299e+02 +9.989832e-01 -7.189513e-03 -4.450709e-02 -6.364206e+00 6.295929e-03 9.997764e-01 -2.018510e-02 -7.112863e+00 4.464227e-02 1.988436e-02 9.988051e-01 2.462100e+02 +9.990527e-01 -4.756456e-03 -4.325531e-02 -6.418186e+00 4.129383e-03 9.998852e-01 -1.457486e-02 -7.149031e+00 4.331967e-02 1.438243e-02 9.989577e-01 2.473066e+02 +9.990879e-01 -4.624974e-03 -4.244963e-02 -6.472198e+00 4.125027e-03 9.999212e-01 -1.185748e-02 -7.184133e+00 4.250113e-02 1.167156e-02 9.990283e-01 2.484194e+02 +9.991194e-01 -6.632461e-03 -4.143008e-02 -6.521044e+00 6.209424e-03 9.999273e-01 -1.033127e-02 -7.214125e+00 4.149559e-02 1.006491e-02 9.990880e-01 2.495426e+02 +9.991326e-01 -9.585443e-03 -4.052481e-02 -6.568485e+00 9.158205e-03 9.999006e-01 -1.071521e-02 -7.241317e+00 4.062350e-02 1.033478e-02 9.991211e-01 2.506774e+02 +9.991333e-01 -1.257973e-02 -3.967785e-02 -6.614428e+00 1.206345e-02 9.998398e-01 -1.322445e-02 -7.271394e+00 3.983786e-02 1.273433e-02 9.991250e-01 2.518203e+02 +9.991171e-01 -1.310290e-02 -3.991714e-02 -6.657659e+00 1.233806e-02 9.997367e-01 -1.934727e-02 -7.302307e+00 4.016014e-02 1.883768e-02 9.990157e-01 2.529720e+02 +9.991138e-01 -1.466072e-02 -3.945402e-02 -6.699168e+00 1.377436e-02 9.996487e-01 -2.264466e-02 -7.339793e+00 3.977214e-02 2.208114e-02 9.989648e-01 2.541351e+02 +9.991759e-01 -1.159807e-02 -3.889851e-02 -6.746367e+00 1.084902e-02 9.997527e-01 -1.941263e-02 -7.379589e+00 3.911404e-02 1.897462e-02 9.990546e-01 2.553108e+02 +9.992230e-01 -9.866415e-03 -3.815942e-02 -6.794881e+00 9.380382e-03 9.998728e-01 -1.289512e-02 -7.414470e+00 3.828180e-02 1.252715e-02 9.991885e-01 2.564919e+02 +9.992196e-01 -1.030262e-02 -3.813137e-02 -6.837373e+00 1.001372e-02 9.999197e-01 -7.759706e-03 -7.444359e+00 3.820825e-02 7.371813e-03 9.992426e-01 2.576737e+02 +9.992495e-01 -8.739178e-03 -3.773620e-02 -6.881155e+00 8.518500e-03 9.999457e-01 -6.004820e-03 -7.475593e+00 3.778663e-02 5.678858e-03 9.992697e-01 2.588504e+02 +9.992706e-01 -8.239698e-03 -3.728929e-02 -6.924264e+00 8.037297e-03 9.999521e-01 -5.574567e-03 -7.504615e+00 3.733344e-02 5.270795e-03 9.992890e-01 2.600266e+02 +9.992751e-01 -7.691449e-03 -3.728429e-02 -6.967188e+00 7.490256e-03 9.999566e-01 -5.532917e-03 -7.534244e+00 3.732523e-02 5.249637e-03 9.992894e-01 2.611974e+02 +9.993057e-01 -4.822436e-03 -3.694317e-02 -7.013517e+00 4.552174e-03 9.999623e-01 -7.396270e-03 -7.568596e+00 3.697745e-02 7.222963e-03 9.992900e-01 2.623621e+02 +9.992996e-01 -6.914276e-03 -3.677535e-02 -7.052122e+00 6.506852e-03 9.999162e-01 -1.118694e-02 -7.602776e+00 3.684962e-02 1.093981e-02 9.992609e-01 2.635226e+02 +9.993035e-01 -6.888252e-03 -3.667502e-02 -7.093594e+00 6.372337e-03 9.998793e-01 -1.416558e-02 -7.643185e+00 3.676817e-02 1.392201e-02 9.992268e-01 2.646822e+02 +9.993213e-01 -7.549045e-03 -3.605466e-02 -7.131035e+00 7.014050e-03 9.998637e-01 -1.494199e-02 -7.687472e+00 3.616255e-02 1.467896e-02 9.992381e-01 2.658405e+02 +9.992926e-01 -1.159991e-02 -3.577382e-02 -7.164917e+00 1.113205e-02 9.998502e-01 -1.324991e-02 -7.729946e+00 3.592217e-02 1.284230e-02 9.992721e-01 2.669982e+02 +9.992794e-01 -1.332753e-02 -3.554054e-02 -7.201390e+00 1.305183e-02 9.998830e-01 -7.978145e-03 -7.770953e+00 3.564271e-02 7.508525e-03 9.993364e-01 2.681579e+02 +9.993260e-01 -1.110036e-02 -3.499028e-02 -7.243244e+00 1.099077e-02 9.999341e-01 -3.322987e-03 -7.807983e+00 3.502486e-02 2.936178e-03 9.993821e-01 2.693111e+02 +9.993597e-01 -8.785190e-03 -3.468464e-02 -7.284815e+00 8.584060e-03 9.999455e-01 -5.943547e-03 -7.841528e+00 3.473496e-02 5.642006e-03 9.993806e-01 2.704572e+02 +9.993997e-01 -4.644987e-03 -3.433306e-02 -7.330537e+00 4.336990e-03 9.999497e-01 -9.039943e-03 -7.875920e+00 3.437333e-02 8.885613e-03 9.993696e-01 2.715913e+02 +9.994383e-01 -1.523216e-03 -3.347873e-02 -7.373617e+00 1.169206e-03 9.999432e-01 -1.059122e-02 -7.917319e+00 3.349297e-02 1.054613e-02 9.993833e-01 2.727257e+02 +9.994651e-01 1.284813e-03 -3.267790e-02 -7.417194e+00 -1.586755e-03 9.999563e-01 -9.215681e-03 -7.959648e+00 3.266463e-02 9.262603e-03 9.994235e-01 2.738528e+02 +9.994523e-01 2.321706e-04 -3.309024e-02 -7.451103e+00 -5.050455e-04 9.999659e-01 -8.238265e-03 -8.002928e+00 3.308720e-02 8.250465e-03 9.994184e-01 2.749698e+02 +9.994198e-01 -1.693589e-03 -3.401776e-02 -7.486337e+00 1.508834e-03 9.999840e-01 -5.456070e-03 -8.037434e+00 3.402646e-02 5.401577e-03 9.994063e-01 2.760763e+02 +9.993698e-01 -3.253580e-03 -3.534818e-02 -7.523524e+00 3.166063e-03 9.999918e-01 -2.531562e-03 -8.072171e+00 3.535613e-02 2.418053e-03 9.993719e-01 2.771744e+02 +9.993257e-01 -3.894795e-03 -3.651057e-02 -7.564462e+00 3.808796e-03 9.999898e-01 -2.424733e-03 -8.102989e+00 3.651965e-02 2.284037e-03 9.993303e-01 2.782512e+02 +9.992832e-01 -3.487931e-03 -3.769513e-02 -7.607877e+00 3.311824e-03 9.999833e-01 -4.733320e-03 -8.132476e+00 3.771101e-02 4.605087e-03 9.992781e-01 2.793126e+02 +9.992380e-01 -2.927762e-03 -3.892012e-02 -7.651625e+00 2.670496e-03 9.999742e-01 -6.660475e-03 -8.164074e+00 3.893862e-02 6.551463e-03 9.992201e-01 2.803583e+02 +9.991838e-01 -1.742943e-03 -4.035735e-02 -7.695437e+00 1.478222e-03 9.999772e-01 -6.588364e-03 -8.196817e+00 4.036791e-02 6.523329e-03 9.991636e-01 2.813917e+02 +9.991230e-01 -1.308215e-03 -4.185221e-02 -7.739183e+00 1.101193e-03 9.999870e-01 -4.969180e-03 -8.228729e+00 4.185817e-02 4.918735e-03 9.991115e-01 2.824095e+02 +9.990648e-01 -1.482659e-03 -4.321268e-02 -7.782923e+00 1.451294e-03 9.999986e-01 -7.571931e-04 -8.257546e+00 4.321374e-02 6.937714e-04 9.990656e-01 2.834149e+02 +9.990166e-01 -7.899872e-04 -4.433196e-02 -7.827832e+00 1.017632e-03 9.999864e-01 5.112662e-03 -8.283317e+00 4.432732e-02 -5.152745e-03 9.990038e-01 2.844024e+02 +9.989797e-01 -7.730951e-04 -4.515519e-02 -7.871954e+00 1.149019e-03 9.999649e-01 8.299796e-03 -8.306128e+00 4.514719e-02 -8.343209e-03 9.989455e-01 2.853685e+02 +9.989491e-01 -2.732227e-04 -4.583227e-02 -7.918403e+00 5.424979e-04 9.999826e-01 5.862894e-03 -8.323367e+00 4.582987e-02 -5.881594e-03 9.989320e-01 2.863152e+02 +9.989271e-01 1.937923e-04 -4.631076e-02 -7.965933e+00 -1.809186e-04 9.999999e-01 2.821763e-04 -8.340680e+00 4.631081e-02 -2.734942e-04 9.989271e-01 2.872514e+02 +9.988968e-01 -4.087002e-04 -4.695686e-02 -8.012239e+00 2.214398e-04 9.999920e-01 -3.993059e-03 -8.358964e+00 4.695811e-02 3.978256e-03 9.988889e-01 2.881858e+02 +9.988686e-01 -1.573800e-03 -4.752895e-02 -8.055697e+00 1.347276e-03 9.999876e-01 -4.797702e-03 -8.377774e+00 4.753592e-02 4.728240e-03 9.988583e-01 2.891193e+02 +9.988573e-01 -1.693474e-03 -4.776267e-02 -8.099656e+00 1.480994e-03 9.999888e-01 -4.483707e-03 -8.395247e+00 4.776973e-02 4.407847e-03 9.988487e-01 2.900536e+02 +9.988622e-01 -1.626744e-03 -4.766224e-02 -8.143950e+00 1.466481e-03 9.999931e-01 -3.397266e-03 -8.412569e+00 4.766744e-02 3.323505e-03 9.988577e-01 2.909826e+02 +9.989202e-01 3.963521e-04 -4.645812e-02 -8.185460e+00 -5.665981e-04 9.999931e-01 -3.651392e-03 -8.425613e+00 4.645636e-02 3.673772e-03 9.989136e-01 2.919113e+02 +9.990153e-01 2.743753e-03 -4.428244e-02 -8.229547e+00 -3.014545e-03 9.999771e-01 -6.049466e-03 -8.444553e+00 4.426483e-02 6.177000e-03 9.990007e-01 2.928345e+02 +9.990920e-01 6.085747e-03 -4.216865e-02 -8.273088e+00 -6.590384e-03 9.999082e-01 -1.183841e-02 -8.465367e+00 4.209274e-02 1.210556e-02 9.990404e-01 2.937505e+02 +9.991564e-01 9.046658e-03 -4.005754e-02 -8.314789e+00 -9.738379e-03 9.998062e-01 -1.710683e-02 -8.489262e+00 3.989502e-02 1.748249e-02 9.990509e-01 2.946684e+02 +9.992358e-01 1.046410e-02 -3.766166e-02 -8.352569e+00 -1.121895e-02 9.997393e-01 -1.988754e-02 -8.513983e+00 3.744373e-02 2.029486e-02 9.990926e-01 2.955867e+02 +9.992958e-01 1.397995e-02 -3.482130e-02 -8.389719e+00 -1.467707e-02 9.996953e-01 -1.984518e-02 -8.543865e+00 3.453326e-02 2.034227e-02 9.991965e-01 2.965071e+02 +9.993565e-01 1.661803e-02 -3.178894e-02 -8.425515e+00 -1.720821e-02 9.996829e-01 -1.838290e-02 -8.576711e+00 3.147337e-02 1.891810e-02 9.993255e-01 2.974337e+02 +9.994462e-01 1.668828e-02 -2.878976e-02 -8.452455e+00 -1.715945e-02 9.997215e-01 -1.619711e-02 -8.607877e+00 2.851144e-02 1.668215e-02 9.994543e-01 2.983651e+02 +9.995760e-01 1.393865e-02 -2.556629e-02 -8.469175e+00 -1.433020e-02 9.997818e-01 -1.519620e-02 -8.637605e+00 2.534890e-02 1.555613e-02 9.995576e-01 2.992996e+02 +9.996755e-01 1.222468e-02 -2.234700e-02 -8.486769e+00 -1.252118e-02 9.998348e-01 -1.317684e-02 -8.662529e+00 2.218223e-02 1.345237e-02 9.996634e-01 3.002399e+02 +9.997580e-01 1.100530e-02 -1.904608e-02 -8.503287e+00 -1.126354e-02 9.998453e-01 -1.350496e-02 -8.687345e+00 1.889451e-02 1.371621e-02 9.997274e-01 3.011803e+02 +9.998118e-01 1.108949e-02 -1.592170e-02 -8.517484e+00 -1.126859e-02 9.998737e-01 -1.120330e-02 -8.709594e+00 1.579545e-02 1.138061e-02 9.998105e-01 3.021317e+02 +9.998635e-01 1.072810e-02 -1.256403e-02 -8.528132e+00 -1.085074e-02 9.998937e-01 -9.734363e-03 -8.728974e+00 1.245827e-02 9.869362e-03 9.998737e-01 3.030876e+02 +9.998866e-01 1.215313e-02 -8.889963e-03 -8.533879e+00 -1.220862e-02 9.999061e-01 -6.214085e-03 -8.745470e+00 8.813609e-03 6.321915e-03 9.999412e-01 3.040586e+02 +9.998814e-01 1.454909e-02 -5.052956e-03 -8.539296e+00 -1.457769e-02 9.998776e-01 -5.669587e-03 -8.762769e+00 4.969851e-03 5.742574e-03 9.999712e-01 3.050331e+02 +9.998806e-01 1.540322e-02 -1.280918e-03 -8.538802e+00 -1.541449e-02 9.998378e-01 -9.312009e-03 -8.775323e+00 1.137276e-03 9.330640e-03 9.999558e-01 3.060125e+02 +9.998755e-01 1.555798e-02 2.652877e-03 -8.536915e+00 -1.552358e-02 9.998010e-01 -1.253048e-02 -8.794196e+00 -2.847298e-03 1.248773e-02 9.999180e-01 3.070010e+02 +9.998948e-01 1.290411e-02 6.629408e-03 -8.525271e+00 -1.283139e-02 9.998583e-01 -1.089658e-02 -8.814466e+00 -6.769079e-03 1.081037e-02 9.999187e-01 3.080124e+02 +9.998635e-01 1.240200e-02 1.092075e-02 -8.512542e+00 -1.233672e-02 9.999057e-01 -6.025007e-03 -8.837861e+00 -1.099444e-02 5.889458e-03 9.999222e-01 3.090309e+02 +9.998516e-01 9.175111e-03 1.458127e-02 -8.492832e+00 -9.038607e-03 9.999149e-01 -9.400169e-03 -8.861627e+00 -1.466628e-02 9.266978e-03 9.998495e-01 3.100558e+02 +9.998065e-01 7.863061e-03 1.803203e-02 -8.470877e+00 -7.503406e-03 9.997733e-01 -1.992707e-02 -8.889772e+00 -1.818463e-02 1.978791e-02 9.996388e-01 3.110803e+02 +9.997225e-01 7.544625e-03 2.231809e-02 -8.446156e+00 -6.934233e-03 9.996032e-01 -2.730180e-02 -8.921880e+00 -2.251522e-02 2.713946e-02 9.993781e-01 3.121119e+02 +9.996194e-01 7.624336e-03 2.651330e-02 -8.417003e+00 -6.983468e-03 9.996832e-01 -2.418078e-02 -8.960250e+00 -2.668927e-02 2.398642e-02 9.993560e-01 3.131671e+02 +9.994766e-01 9.434162e-03 3.094306e-02 -8.389103e+00 -8.945401e-03 9.998336e-01 -1.589615e-02 -9.000111e+00 -3.108788e-02 1.561103e-02 9.993947e-01 3.142336e+02 +9.993353e-01 9.009627e-03 3.532346e-02 -8.351900e+00 -8.502391e-03 9.998589e-01 -1.448382e-02 -9.032267e+00 -3.544897e-02 1.417386e-02 9.992710e-01 3.152979e+02 +9.991768e-01 8.823380e-03 3.959635e-02 -8.309687e+00 -8.106411e-03 9.998009e-01 -1.823117e-02 -9.063443e+00 -3.974933e-02 1.789518e-02 9.990494e-01 3.163648e+02 +9.990114e-01 8.787378e-03 4.357880e-02 -8.262018e+00 -7.817038e-03 9.997188e-01 -2.238702e-02 -9.098983e+00 -4.376327e-02 2.202422e-02 9.987991e-01 3.174365e+02 +9.988090e-01 9.970755e-03 4.776107e-02 -8.211642e+00 -8.776088e-03 9.996449e-01 -2.515817e-02 -9.139482e+00 -4.799496e-02 2.470905e-02 9.985419e-01 3.185205e+02 +9.985988e-01 9.760084e-03 5.201057e-02 -8.155870e+00 -8.346180e-03 9.995915e-01 -2.733319e-02 -9.183213e+00 -5.225610e-02 2.686080e-02 9.982724e-01 3.196104e+02 +9.983687e-01 1.001854e-02 5.621080e-02 -8.095540e+00 -8.498374e-03 9.995934e-01 -2.721819e-02 -9.226087e+00 -5.646063e-02 2.669608e-02 9.980479e-01 3.207088e+02 +9.981029e-01 1.049898e-02 6.066628e-02 -8.031870e+00 -9.192182e-03 9.997205e-01 -2.177987e-02 -9.263036e+00 -6.087800e-02 2.118090e-02 9.979205e-01 3.218163e+02 +9.978421e-01 9.501015e-03 6.496819e-02 -7.960404e+00 -8.476437e-03 9.998356e-01 -1.602798e-02 -9.297324e+00 -6.510980e-02 1.544269e-02 9.977586e-01 3.229341e+02 +9.975723e-01 8.040524e-03 6.917341e-02 -7.881873e+00 -7.092436e-03 9.998776e-01 -1.394069e-02 -9.325499e+00 -6.927704e-02 1.341624e-02 9.975073e-01 3.240556e+02 +9.973043e-01 7.326687e-03 7.300997e-02 -7.798255e+00 -6.398408e-03 9.998958e-01 -1.294022e-02 -9.353057e+00 -7.309718e-02 1.243819e-02 9.972473e-01 3.251794e+02 +9.970910e-01 4.149379e-03 7.610692e-02 -7.703403e+00 -3.188109e-03 9.999136e-01 -1.274768e-02 -9.376684e+00 -7.615325e-02 1.246796e-02 9.970182e-01 3.263113e+02 +9.969433e-01 1.742072e-03 7.810894e-02 -7.607920e+00 -4.773769e-04 9.998685e-01 -1.620718e-02 -9.406538e+00 -7.812691e-02 1.612035e-02 9.968131e-01 3.274454e+02 +9.968566e-01 1.950749e-03 7.920304e-02 -7.513710e+00 -2.690291e-04 9.997744e-01 -2.123815e-02 -9.435047e+00 -7.922660e-02 2.115008e-02 9.966322e-01 3.285830e+02 +9.967800e-01 2.549173e-03 8.014482e-02 -7.419185e+00 -6.669816e-04 9.997235e-01 -2.350289e-02 -9.470959e+00 -8.018258e-02 2.337375e-02 9.965061e-01 3.297352e+02 +9.967052e-01 2.433333e-03 8.107363e-02 -7.322558e+00 -6.411255e-04 9.997550e-01 -2.212463e-02 -9.507679e+00 -8.110761e-02 2.199975e-02 9.964625e-01 3.308977e+02 +9.966437e-01 3.082017e-03 8.180347e-02 -7.227060e+00 -1.565013e-03 9.998257e-01 -1.860215e-02 -9.545983e+00 -8.184655e-02 1.841169e-02 9.964749e-01 3.320704e+02 +9.966011e-01 1.578355e-03 8.236343e-02 -7.127779e+00 -1.409463e-04 9.998476e-01 -1.745493e-02 -9.583792e+00 -8.237843e-02 1.738399e-02 9.964495e-01 3.332491e+02 +9.966069e-01 -2.712346e-04 8.230762e-02 -7.028228e+00 1.815006e-03 9.998238e-01 -1.868187e-02 -9.625415e+00 -8.228805e-02 1.876787e-02 9.964319e-01 3.344427e+02 +9.966321e-01 -1.109778e-03 8.199549e-02 -6.930360e+00 2.805657e-03 9.997844e-01 -2.057026e-02 -9.674579e+00 -8.195499e-02 2.073103e-02 9.964204e-01 3.356446e+02 +9.966765e-01 -1.983343e-03 8.143777e-02 -6.832860e+00 3.702825e-03 9.997733e-01 -2.096845e-02 -9.724804e+00 -8.137772e-02 2.120031e-02 9.964578e-01 3.368462e+02 +9.967065e-01 -2.302069e-03 8.106042e-02 -6.734158e+00 3.872705e-03 9.998077e-01 -1.922423e-02 -9.772633e+00 -8.100058e-02 1.947483e-02 9.965238e-01 3.380489e+02 +9.967178e-01 -3.758401e-03 8.086729e-02 -6.634241e+00 4.999819e-03 9.998726e-01 -1.515428e-02 -9.817662e+00 -8.080004e-02 1.550886e-02 9.966097e-01 3.392522e+02 +9.967687e-01 -6.348698e-03 8.007471e-02 -6.537898e+00 7.213005e-03 9.999187e-01 -1.050911e-02 -9.864470e+00 -8.000149e-02 1.105273e-02 9.967335e-01 3.404585e+02 +9.968632e-01 -6.079126e-03 7.890986e-02 -6.445909e+00 6.842096e-03 9.999324e-01 -9.402100e-03 -9.910367e+00 -7.884737e-02 9.912515e-03 9.968374e-01 3.416581e+02 +9.969196e-01 -8.263558e-03 7.799355e-02 -6.353320e+00 9.137238e-03 9.998993e-01 -1.085171e-02 -9.950653e+00 -7.789603e-02 1.153093e-02 9.968948e-01 3.428491e+02 +9.969725e-01 -6.418295e-03 7.748963e-02 -6.266625e+00 7.500218e-03 9.998783e-01 -1.367920e-02 -9.994225e+00 -7.739241e-02 1.421897e-02 9.968993e-01 3.440377e+02 +9.970622e-01 -4.304498e-03 7.647510e-02 -6.181209e+00 5.397492e-03 9.998861e-01 -1.409120e-02 -1.004011e+01 -7.640574e-02 1.446258e-02 9.969719e-01 3.452194e+02 +9.971644e-01 -3.316089e-03 7.518053e-02 -6.099343e+00 4.434098e-03 9.998820e-01 -1.470894e-02 -1.009924e+01 -7.512289e-02 1.500058e-02 9.970615e-01 3.464097e+02 +9.972719e-01 -3.337999e-03 7.373990e-02 -6.015877e+00 4.414169e-03 9.998860e-01 -1.443598e-02 -1.015062e+01 -7.368332e-02 1.472210e-02 9.971730e-01 3.475921e+02 +9.973544e-01 -2.697631e-03 7.264260e-02 -5.935452e+00 3.670548e-03 9.999053e-01 -1.326303e-02 -1.020417e+01 -7.259994e-02 1.349457e-02 9.972699e-01 3.487732e+02 +9.974299e-01 -9.579069e-04 7.164339e-02 -5.858059e+00 1.908523e-03 9.999110e-01 -1.320143e-02 -1.025290e+01 -7.162438e-02 1.330423e-02 9.973430e-01 3.499450e+02 +9.975381e-01 6.976070e-04 7.012344e-02 -5.787179e+00 3.198974e-04 9.998948e-01 -1.449791e-02 -1.030853e+01 -7.012619e-02 1.448465e-02 9.974330e-01 3.511117e+02 +9.976283e-01 1.959530e-03 6.880366e-02 -5.716445e+00 -9.326454e-04 9.998877e-01 -1.495381e-02 -1.036230e+01 -6.882524e-02 1.485417e-02 9.975181e-01 3.522800e+02 +9.977378e-01 2.351987e-03 6.718434e-02 -5.647279e+00 -1.435875e-03 9.999054e-01 -1.368084e-02 -1.041632e+01 -6.721016e-02 1.355342e-02 9.976468e-01 3.534440e+02 +9.978687e-01 1.485368e-03 6.523730e-02 -5.576861e+00 -6.444800e-04 9.999164e-01 -1.290885e-02 -1.046583e+01 -6.525103e-02 1.283929e-02 9.977863e-01 3.546010e+02 +9.980214e-01 1.262293e-03 6.286189e-02 -5.509189e+00 -1.380227e-04 9.998400e-01 -1.788591e-02 -1.051734e+01 -6.287441e-02 1.784184e-02 9.978620e-01 3.557461e+02 +9.981693e-01 -2.229415e-03 6.044111e-02 -5.439992e+00 3.632442e-03 9.997262e-01 -2.311319e-02 -1.056737e+01 -6.037304e-02 2.329042e-02 9.979041e-01 3.568850e+02 +9.982811e-01 -5.987820e-03 5.830061e-02 -5.370219e+00 7.139827e-03 9.997829e-01 -1.957154e-02 -1.061757e+01 -5.817076e-02 1.995415e-02 9.981072e-01 3.580303e+02 +9.983744e-01 -6.742297e-03 5.659643e-02 -5.307417e+00 7.243050e-03 9.999364e-01 -8.647305e-03 -1.066318e+01 -5.653453e-02 9.043178e-03 9.983597e-01 3.591764e+02 +9.984521e-01 -4.447678e-03 5.544039e-02 -5.251048e+00 4.424469e-03 9.999900e-01 5.413738e-04 -1.069810e+01 -5.544225e-02 -2.952409e-04 9.984619e-01 3.603156e+02 +9.984914e-01 -4.023478e-03 5.476171e-02 -5.194755e+00 3.827077e-03 9.999858e-01 3.690882e-03 -1.072819e+01 -5.477579e-02 -3.475735e-03 9.984926e-01 3.614428e+02 +9.985287e-01 1.376497e-03 5.420859e-02 -5.144171e+00 -1.314276e-03 9.999984e-01 -1.183442e-03 -1.075600e+01 -5.421014e-02 1.110456e-03 9.985289e-01 3.625628e+02 +9.985310e-01 8.040658e-03 5.358318e-02 -5.098453e+00 -7.585719e-03 9.999335e-01 -8.688335e-03 -1.079009e+01 -5.364948e-02 8.269105e-03 9.985256e-01 3.636716e+02 +9.985579e-01 1.086923e-02 5.257398e-02 -5.048256e+00 -1.009785e-02 9.998377e-01 -1.491578e-02 -1.082466e+01 -5.272757e-02 1.436338e-02 9.985056e-01 3.647771e+02 +9.985345e-01 1.469259e-02 5.208651e-02 -5.000053e+00 -1.397567e-02 9.998029e-01 -1.410180e-02 -1.086545e+01 -5.228344e-02 1.335319e-02 9.985430e-01 3.658850e+02 +9.985013e-01 1.776870e-02 5.176429e-02 -4.951017e+00 -1.733322e-02 9.998106e-01 -8.849731e-03 -1.090103e+01 -5.191174e-02 7.939225e-03 9.986201e-01 3.669898e+02 +9.985261e-01 1.948914e-02 5.065395e-02 -4.901568e+00 -1.916250e-02 9.997924e-01 -6.926240e-03 -1.093291e+01 -5.077842e-02 5.945374e-03 9.986923e-01 3.680890e+02 +9.985875e-01 2.014232e-02 4.916695e-02 -4.851686e+00 -1.992706e-02 9.997896e-01 -4.864494e-03 -1.096449e+01 -4.925459e-02 3.877869e-03 9.987787e-01 3.691784e+02 +9.986568e-01 2.151376e-02 4.713539e-02 -4.804541e+00 -2.125353e-02 9.997560e-01 -6.015357e-03 -1.099719e+01 -4.725330e-02 5.005483e-03 9.988704e-01 3.702569e+02 diff --git a/tools/Ground-Truth/dataset/poses/06.txt b/tools/Ground-Truth/dataset/poses/06.txt new file mode 100644 index 0000000..6bcc46e --- /dev/null +++ b/tools/Ground-Truth/dataset/poses/06.txt @@ -0,0 +1,1101 @@ +1.000000e+00 1.197625e-11 1.704638e-10 0.000000e+00 1.197625e-11 1.000000e+00 3.562503e-10 -1.110223e-16 1.704638e-10 3.562503e-10 1.000000e+00 2.220446e-16 +9.999995e-01 7.196824e-04 -6.870876e-04 -1.401751e-02 -7.197717e-04 9.999997e-01 -1.295633e-04 -2.820321e-02 6.869946e-04 1.300585e-04 9.999998e-01 1.198998e+00 +9.999981e-01 1.430880e-03 -1.366265e-03 -2.787365e-02 -1.431233e-03 9.999989e-01 -2.576187e-04 -5.608120e-02 1.365895e-03 2.595743e-04 9.999990e-01 2.384181e+00 +9.999956e-01 2.145639e-03 -2.049036e-03 -4.180320e-02 -2.146435e-03 9.999976e-01 -3.863468e-04 -8.410629e-02 2.048203e-03 3.907438e-04 9.999978e-01 3.575628e+00 +9.999922e-01 2.860329e-03 -2.731935e-03 -5.573543e-02 -2.861747e-03 9.999957e-01 -5.150906e-04 -1.121362e-01 2.730451e-03 5.229053e-04 9.999961e-01 4.767291e+00 +9.999878e-01 3.576816e-03 -3.416746e-03 -6.970674e-02 -3.579038e-03 9.999934e-01 -6.441878e-04 -1.402442e-01 3.414420e-03 6.564092e-04 9.999940e-01 5.962283e+00 +9.999824e-01 4.290400e-03 -4.098979e-03 -8.362554e-02 -4.293603e-03 9.999905e-01 -7.727885e-04 -1.682458e-01 4.095625e-03 7.903748e-04 9.999913e-01 7.152769e+00 +9.999760e-01 5.005068e-03 -4.782444e-03 -9.756958e-02 -5.009436e-03 9.999870e-01 -9.016141e-04 -1.962977e-01 4.777870e-03 9.255504e-04 9.999882e-01 8.345400e+00 +9.999687e-01 5.718771e-03 -5.465184e-03 -1.114989e-01 -5.724485e-03 9.999831e-01 -1.030294e-03 -2.243193e-01 5.459201e-03 1.061548e-03 9.999845e-01 9.536762e+00 +9.999604e-01 6.432384e-03 -6.148038e-03 -1.254307e-01 -6.439629e-03 9.999786e-01 -1.158988e-03 -2.523452e-01 6.140452e-03 1.198534e-03 9.999804e-01 1.072832e+01 +9.999511e-01 7.145767e-03 -6.830869e-03 -1.393621e-01 -7.154725e-03 9.999736e-01 -1.287669e-03 -2.803697e-01 6.821488e-03 1.336480e-03 9.999758e-01 1.191983e+01 +9.999409e-01 7.859281e-03 -7.514028e-03 -1.533004e-01 -7.870140e-03 9.999680e-01 -1.416404e-03 -3.084073e-01 7.502657e-03 1.475458e-03 9.999708e-01 1.311191e+01 +9.999311e-01 8.435908e-03 -8.163220e-03 -1.671408e-01 -8.448594e-03 9.999631e-01 -1.520606e-03 -3.362948e-01 8.150093e-03 1.589470e-03 9.999655e-01 1.430348e+01 +9.999063e-01 1.021484e-02 -9.110264e-03 -1.818140e-01 -1.023202e-02 9.999459e-01 -1.840097e-03 -3.654237e-01 9.090976e-03 1.933142e-03 9.999568e-01 1.549659e+01 +9.999049e-01 9.942671e-03 -9.559126e-03 -1.950729e-01 -9.960151e-03 9.999488e-01 -1.782531e-03 -3.924445e-01 9.540914e-03 1.877572e-03 9.999527e-01 1.668758e+01 +9.999045e-01 9.373887e-03 -1.015134e-02 -2.081761e-01 -9.389118e-03 9.999548e-01 -1.453538e-03 -4.191514e-01 1.013726e-02 1.548712e-03 9.999474e-01 1.788104e+01 +9.999026e-01 9.037036e-03 -1.063812e-02 -2.220687e-01 -9.048731e-03 9.999585e-01 -1.051573e-03 -4.450814e-01 1.062817e-02 1.147733e-03 9.999429e-01 1.907663e+01 +9.998928e-01 9.270131e-03 -1.133310e-02 -2.372951e-01 -9.293058e-03 9.999548e-01 -1.971849e-03 -4.715143e-01 1.131431e-02 2.076957e-03 9.999338e-01 2.027019e+01 +9.998895e-01 9.007105e-03 -1.182761e-02 -2.531559e-01 -9.043321e-03 9.999545e-01 -3.011911e-03 -4.977817e-01 1.179995e-02 3.118539e-03 9.999255e-01 2.146468e+01 +9.998739e-01 9.613273e-03 -1.263921e-02 -2.707637e-01 -9.644484e-03 9.999506e-01 -2.410510e-03 -5.247441e-01 1.261541e-02 2.532105e-03 9.999172e-01 2.265883e+01 +9.998622e-01 9.849565e-03 -1.336112e-02 -2.887908e-01 -9.880847e-03 9.999486e-01 -2.277132e-03 -5.527301e-01 1.333801e-02 2.408838e-03 9.999082e-01 2.385296e+01 +9.998496e-01 9.852334e-03 -1.427518e-02 -3.071147e-01 -9.896726e-03 9.999464e-01 -3.042267e-03 -5.812326e-01 1.424445e-02 3.183087e-03 9.998935e-01 2.504684e+01 +9.998348e-01 1.011489e-02 -1.510546e-02 -3.273512e-01 -1.015685e-02 9.999447e-01 -2.703181e-03 -6.069839e-01 1.507729e-02 2.856158e-03 9.998823e-01 2.624310e+01 +9.998322e-01 9.254980e-03 -1.580829e-02 -3.472488e-01 -9.264587e-03 9.999569e-01 -5.344808e-04 -6.329432e-01 1.580266e-02 6.808490e-04 9.998749e-01 2.744168e+01 +9.998234e-01 8.611256e-03 -1.670535e-02 -3.677985e-01 -8.617934e-03 9.999628e-01 -3.276812e-04 -6.565642e-01 1.670191e-02 4.715896e-04 9.998604e-01 2.863712e+01 +9.998146e-01 7.984938e-03 -1.751954e-02 -3.892136e-01 -8.016013e-03 9.999664e-01 -1.704144e-03 -6.824261e-01 1.750535e-02 1.844266e-03 9.998451e-01 2.982830e+01 +9.998008e-01 7.461297e-03 -1.851044e-02 -4.112762e-01 -7.508905e-03 9.999686e-01 -2.503665e-03 -7.087202e-01 1.849118e-02 2.642160e-03 9.998255e-01 3.102794e+01 +9.997835e-01 7.872528e-03 -1.925948e-02 -4.357161e-01 -7.922232e-03 9.999655e-01 -2.505745e-03 -7.356474e-01 1.923909e-02 2.657781e-03 9.998114e-01 3.223193e+01 +9.997742e-01 7.403986e-03 -1.991672e-02 -4.596533e-01 -7.444296e-03 9.999704e-01 -1.950489e-03 -7.632533e-01 1.990169e-02 2.098315e-03 9.997997e-01 3.342024e+01 +9.997630e-01 7.159487e-03 -2.056208e-02 -4.846981e-01 -7.195731e-03 9.999727e-01 -1.689150e-03 -7.915945e-01 2.054943e-02 1.836709e-03 9.997872e-01 3.461480e+01 +9.997578e-01 6.402722e-03 -2.105455e-02 -5.098190e-01 -6.438109e-03 9.999779e-01 -1.613319e-03 -8.182722e-01 2.104376e-02 1.748481e-03 9.997770e-01 3.581256e+01 +9.997447e-01 6.469361e-03 -2.164904e-02 -5.367057e-01 -6.505831e-03 9.999775e-01 -1.614507e-03 -8.457827e-01 2.163811e-02 1.754941e-03 9.997643e-01 3.700928e+01 +9.997456e-01 5.595697e-03 -2.184987e-02 -5.627412e-01 -5.621433e-03 9.999836e-01 -1.116570e-03 -8.734675e-01 2.184326e-02 1.239114e-03 9.997606e-01 3.820690e+01 +9.997469e-01 5.730089e-03 -2.175759e-02 -5.904619e-01 -5.729521e-03 9.999836e-01 8.851327e-05 -9.001114e-01 2.175774e-02 3.617047e-05 9.997633e-01 3.940549e+01 +9.997473e-01 6.200803e-03 -2.160647e-02 -6.181703e-01 -6.179958e-03 9.999803e-01 1.031475e-03 -9.268582e-01 2.161244e-02 -8.976860e-04 9.997660e-01 4.060244e+01 +9.997432e-01 6.994168e-03 -2.155419e-02 -6.466319e-01 -6.982521e-03 9.999754e-01 6.156644e-04 -9.531287e-01 2.155797e-02 -4.650029e-04 9.997675e-01 4.179871e+01 +9.997393e-01 7.822383e-03 -2.144963e-02 -6.756680e-01 -7.813016e-03 9.999693e-01 5.205581e-04 -9.776312e-01 2.145304e-02 -3.528353e-04 9.997698e-01 4.299592e+01 +9.997217e-01 1.079817e-02 -2.097680e-02 -7.080160e-01 -1.075808e-02 9.999401e-01 2.023359e-03 -1.000412e+00 2.099740e-02 -1.797125e-03 9.997779e-01 4.419563e+01 +9.997511e-01 1.107363e-02 -1.936701e-02 -7.358613e-01 -1.097598e-02 9.999265e-01 5.141411e-03 -1.020365e+00 1.942252e-02 -4.927557e-03 9.997992e-01 4.539563e+01 +9.997773e-01 1.163716e-02 -1.760589e-02 -7.617275e-01 -1.150000e-02 9.999029e-01 7.871628e-03 -1.037444e+00 1.769578e-02 -7.667405e-03 9.998140e-01 4.659612e+01 +9.998038e-01 1.191970e-02 -1.582127e-02 -7.844470e-01 -1.174383e-02 9.998687e-01 1.116292e-02 -1.051207e+00 1.595226e-02 -1.097492e-02 9.998125e-01 4.780149e+01 +9.998273e-01 1.160707e-02 -1.451319e-02 -8.050204e-01 -1.141471e-02 9.998468e-01 1.326758e-02 -1.064092e+00 1.466497e-02 -1.309962e-02 9.998067e-01 4.900454e+01 +9.998655e-01 9.923126e-03 -1.305597e-02 -8.220020e-01 -9.772672e-03 9.998857e-01 1.153769e-02 -1.073850e+00 1.316897e-02 -1.140854e-02 9.998482e-01 5.020348e+01 +9.998740e-01 1.039847e-02 -1.199806e-02 -8.402902e-01 -1.028811e-02 9.999045e-01 9.223321e-03 -1.085315e+00 1.209283e-02 -9.098718e-03 9.998855e-01 5.140457e+01 +9.998708e-01 1.154741e-02 -1.118360e-02 -8.594630e-01 -1.144656e-02 9.998936e-01 9.040290e-03 -1.098286e+00 1.128680e-02 -8.911106e-03 9.998966e-01 5.260583e+01 +9.998820e-01 1.057346e-02 -1.114335e-02 -8.753783e-01 -1.047818e-02 9.999083e-01 8.574574e-03 -1.112635e+00 1.123299e-02 -8.456798e-03 9.999012e-01 5.381125e+01 +9.998803e-01 9.904895e-03 -1.188406e-02 -8.928730e-01 -9.811863e-03 9.999209e-01 7.861425e-03 -1.127883e+00 1.196099e-02 -7.743878e-03 9.998985e-01 5.501520e+01 +9.998592e-01 1.007197e-02 -1.341953e-02 -9.118602e-01 -9.967695e-03 9.999198e-01 7.815017e-03 -1.143152e+00 1.349716e-02 -7.680153e-03 9.998794e-01 5.622027e+01 +9.998373e-01 1.009708e-02 -1.494468e-02 -9.332309e-01 -9.958179e-03 9.999068e-01 9.339764e-03 -1.160687e+00 1.503759e-02 -9.189421e-03 9.998447e-01 5.742777e+01 +9.998225e-01 1.009404e-02 -1.590911e-02 -9.562150e-01 -9.940127e-03 9.999033e-01 9.724525e-03 -1.175655e+00 1.600573e-02 -9.564658e-03 9.998262e-01 5.863262e+01 +9.997987e-01 1.105266e-02 -1.674529e-02 -9.814360e-01 -1.089512e-02 9.998958e-01 9.469924e-03 -1.190278e+00 1.684822e-02 -9.285574e-03 9.998149e-01 5.983857e+01 +9.997821e-01 1.144537e-02 -1.745778e-02 -1.006715e+00 -1.128333e-02 9.998926e-01 9.352647e-03 -1.205600e+00 1.756296e-02 -9.153625e-03 9.998039e-01 6.104209e+01 +9.997862e-01 1.080107e-02 -1.763248e-02 -1.031126e+00 -1.064714e-02 9.999046e-01 8.800715e-03 -1.221320e+00 1.772586e-02 -8.611096e-03 9.998058e-01 6.224563e+01 +9.997955e-01 9.508883e-03 -1.785067e-02 -1.053863e+00 -9.370520e-03 9.999255e-01 7.818952e-03 -1.237483e+00 1.792369e-02 -7.650080e-03 9.998101e-01 6.344747e+01 +9.997930e-01 9.088420e-03 -1.820103e-02 -1.078473e+00 -8.930260e-03 9.999218e-01 8.752215e-03 -1.251701e+00 1.827916e-02 -8.587861e-03 9.997960e-01 6.464755e+01 +9.997889e-01 9.083060e-03 -1.842881e-02 -1.103193e+00 -8.882419e-03 9.999007e-01 1.094025e-02 -1.267101e+00 1.852635e-02 -1.077425e-02 9.997703e-01 6.585040e+01 +9.997792e-01 9.523957e-03 -1.872882e-02 -1.129538e+00 -9.347320e-03 9.999112e-01 9.496443e-03 -1.281112e+00 1.881760e-02 -9.319280e-03 9.997795e-01 6.704761e+01 +9.997624e-01 1.103353e-02 -1.880211e-02 -1.157680e+00 -1.088822e-02 9.999102e-01 7.813077e-03 -1.293922e+00 1.888663e-02 -7.606496e-03 9.997927e-01 6.824107e+01 +9.997347e-01 1.319593e-02 -1.887929e-02 -1.186930e+00 -1.304722e-02 9.998830e-01 7.978688e-03 -1.309417e+00 1.898237e-02 -7.730246e-03 9.997899e-01 6.943527e+01 +9.997104e-01 1.500435e-02 -1.881231e-02 -1.215316e+00 -1.485154e-02 9.998558e-01 8.236958e-03 -1.324678e+00 1.893319e-02 -7.955179e-03 9.997891e-01 7.062616e+01 +9.996883e-01 1.665714e-02 -1.859770e-02 -1.243226e+00 -1.649733e-02 9.998259e-01 8.713768e-03 -1.339456e+00 1.873961e-02 -8.404237e-03 9.997891e-01 7.181600e+01 +9.996991e-01 1.706543e-02 -1.762360e-02 -1.268567e+00 -1.689744e-02 9.998108e-01 9.637712e-03 -1.355743e+00 1.778473e-02 -9.337016e-03 9.997983e-01 7.300219e+01 +9.997036e-01 1.873150e-02 -1.555211e-02 -1.292838e+00 -1.857394e-02 9.997753e-01 1.021438e-02 -1.371470e+00 1.573995e-02 -9.922484e-03 9.998269e-01 7.418749e+01 +9.997520e-01 1.814331e-02 -1.291317e-02 -1.310252e+00 -1.802225e-02 9.997931e-01 9.430321e-03 -1.390125e+00 1.308160e-02 -9.195255e-03 9.998722e-01 7.536554e+01 +9.998364e-01 1.463832e-02 -1.062524e-02 -1.320138e+00 -1.459781e-02 9.998859e-01 3.880945e-03 -1.407515e+00 1.068084e-02 -3.725203e-03 9.999360e-01 7.654079e+01 +9.998511e-01 1.519312e-02 -8.185862e-03 -1.330920e+00 -1.517584e-02 9.998825e-01 2.169593e-03 -1.427085e+00 8.217863e-03 -2.045042e-03 9.999642e-01 7.771630e+01 +9.998810e-01 1.450242e-02 -5.257612e-03 -1.337950e+00 -1.447064e-02 9.998771e-01 6.033895e-03 -1.448797e+00 5.344472e-03 -5.957094e-03 9.999680e-01 7.889460e+01 +9.998917e-01 1.459305e-02 -1.933843e-03 -1.340942e+00 -1.457722e-02 9.998620e-01 7.962398e-03 -1.468534e+00 2.049772e-03 -7.933343e-03 9.999664e-01 8.006843e+01 +9.998850e-01 1.502471e-02 2.051608e-03 -1.342290e+00 -1.503622e-02 9.998706e-01 5.712941e-03 -1.485826e+00 -1.965507e-03 -5.743131e-03 9.999816e-01 8.123454e+01 +9.998850e-01 1.413375e-02 5.503277e-03 -1.335651e+00 -1.415117e-02 9.998949e-01 3.138992e-03 -1.506096e+00 -5.458334e-03 -3.216507e-03 9.999799e-01 8.239913e+01 +9.998797e-01 1.272917e-02 8.863339e-03 -1.323865e+00 -1.272312e-02 9.999188e-01 -7.394368e-04 -1.530312e+00 -8.872032e-03 6.265791e-04 9.999605e-01 8.355801e+01 +9.998558e-01 1.187376e-02 1.214485e-02 -1.309268e+00 -1.185235e-02 9.999281e-01 -1.833271e-03 -1.555472e+00 -1.216575e-02 1.689062e-03 9.999246e-01 8.471745e+01 +9.998073e-01 1.167643e-02 1.578168e-02 -1.292993e+00 -1.167891e-02 9.999318e-01 6.528232e-05 -1.580587e+00 -1.577984e-02 -2.495819e-04 9.998755e-01 8.587696e+01 +9.997260e-01 1.277107e-02 1.961989e-02 -1.273121e+00 -1.279238e-02 9.999177e-01 9.604842e-04 -1.605074e+00 -1.960601e-02 -1.211205e-03 9.998071e-01 8.703114e+01 +9.996514e-01 1.244423e-02 2.328416e-02 -1.247131e+00 -1.241599e-02 9.999220e-01 -1.357177e-03 -1.630673e+00 -2.329923e-02 1.067609e-03 9.997280e-01 8.818383e+01 +9.995737e-01 1.212483e-02 2.656002e-02 -1.216671e+00 -1.202445e-02 9.999199e-01 -3.935727e-03 -1.656163e+00 -2.660561e-02 3.614679e-03 9.996395e-01 8.933336e+01 +9.994807e-01 1.221273e-02 2.981802e-02 -1.182745e+00 -1.208868e-02 9.999175e-01 -4.336840e-03 -1.683163e+00 -2.986853e-02 3.974127e-03 9.995459e-01 9.048344e+01 +9.994064e-01 1.086439e-02 3.269309e-02 -1.144128e+00 -1.076847e-02 9.999372e-01 -3.108733e-03 -1.710419e+00 -3.272481e-02 2.754834e-03 9.994606e-01 9.163655e+01 +9.993189e-01 1.010851e-02 3.549009e-02 -1.101750e+00 -1.005139e-02 9.999479e-01 -1.787571e-03 -1.736086e+00 -3.550631e-02 1.429629e-03 9.993684e-01 9.279129e+01 +9.992253e-01 9.287854e-03 3.824408e-02 -1.056015e+00 -9.297315e-03 9.999568e-01 6.948751e-05 -1.760650e+00 -3.824179e-02 -4.250003e-04 9.992684e-01 9.394713e+01 +9.991384e-01 8.157564e-03 4.069360e-02 -1.006119e+00 -8.214536e-03 9.999655e-01 1.232957e-03 -1.785071e+00 -4.068214e-02 -1.566173e-03 9.991709e-01 9.510262e+01 +9.990531e-01 6.863193e-03 4.296190e-02 -9.539660e-01 -6.830006e-03 9.999762e-01 -9.192473e-04 -1.809543e+00 -4.296719e-02 6.249473e-04 9.990763e-01 9.625538e+01 +9.989655e-01 5.398510e-03 4.515419e-02 -8.975398e-01 -5.201348e-03 9.999764e-01 -4.482798e-03 -1.834871e+00 -4.517733e-02 4.243297e-03 9.989700e-01 9.741317e+01 +9.988685e-01 5.748713e-03 4.720814e-02 -8.410031e-01 -5.394134e-03 9.999563e-01 -7.634949e-03 -1.861916e+00 -4.724997e-02 7.371663e-03 9.988559e-01 9.857222e+01 +9.987897e-01 5.894856e-03 4.883027e-02 -7.820453e-01 -5.478100e-03 9.999474e-01 -8.664245e-03 -1.891643e+00 -4.887878e-02 8.386260e-03 9.987695e-01 9.973968e+01 +9.987595e-01 5.954325e-03 4.943638e-02 -7.233569e-01 -5.563042e-03 9.999521e-01 -8.048731e-03 -1.922457e+00 -4.948194e-02 7.763729e-03 9.987449e-01 1.009141e+02 +9.987950e-01 6.151443e-03 4.869060e-02 -6.655319e-01 -5.864212e-03 9.999645e-01 -6.039799e-03 -1.953029e+00 -4.872603e-02 5.746988e-03 9.987957e-01 1.020947e+02 +9.988645e-01 5.468002e-03 4.732677e-02 -6.077182e-01 -5.265287e-03 9.999764e-01 -4.406917e-03 -1.983093e+00 -4.734975e-02 4.152724e-03 9.988697e-01 1.032788e+02 +9.989556e-01 5.748434e-03 4.532808e-02 -5.505715e-01 -5.583725e-03 9.999773e-01 -3.759517e-03 -2.012875e+00 -4.534867e-02 3.502491e-03 9.989651e-01 1.044700e+02 +9.990632e-01 5.895617e-03 4.287054e-02 -4.977483e-01 -5.765335e-03 9.999784e-01 -3.161991e-03 -2.041118e+00 -4.288825e-02 2.911866e-03 9.990756e-01 1.056679e+02 +9.991887e-01 6.377172e-03 3.976665e-02 -4.483272e-01 -6.255912e-03 9.999754e-01 -3.173039e-03 -2.069739e+00 -3.978591e-02 2.921688e-03 9.992040e-01 1.068672e+02 +9.993208e-01 7.835242e-03 3.600760e-02 -4.053771e-01 -7.714880e-03 9.999642e-01 -3.480448e-03 -2.098282e+00 -3.603358e-02 3.200290e-03 9.993455e-01 1.080719e+02 +9.994529e-01 7.975423e-03 3.209954e-02 -3.651076e-01 -7.874505e-03 9.999636e-01 -3.269149e-03 -2.127000e+00 -3.212445e-02 3.014592e-03 9.994793e-01 1.092786e+02 +9.995691e-01 8.622270e-03 2.805899e-02 -3.290753e-01 -8.565552e-03 9.999610e-01 -2.141033e-03 -2.156853e+00 -2.807636e-02 1.899770e-03 9.996040e-01 1.104916e+02 +9.996794e-01 8.809002e-03 2.373857e-02 -2.985283e-01 -8.780628e-03 9.999606e-01 -1.299316e-03 -2.185665e+00 -2.374908e-02 1.090461e-03 9.997174e-01 1.117073e+02 +9.997737e-01 8.964040e-03 1.929126e-02 -2.726718e-01 -8.955499e-03 9.999597e-01 -5.291835e-04 -2.213402e+00 -1.929523e-02 3.563015e-04 9.998138e-01 1.129237e+02 +9.998512e-01 9.347451e-03 1.450220e-02 -2.537792e-01 -9.343926e-03 9.999563e-01 -3.109408e-04 -2.240145e+00 -1.450447e-02 1.753877e-04 9.998948e-01 1.141425e+02 +9.999025e-01 1.017829e-02 9.563341e-03 -2.415523e-01 -1.017616e-02 9.999482e-01 -2.718613e-04 -2.267804e+00 -9.565613e-03 1.745173e-04 9.999542e-01 1.153628e+02 +9.999322e-01 1.069373e-02 4.603702e-03 -2.340717e-01 -1.069143e-02 9.999427e-01 -5.259432e-04 -2.296830e+00 -4.609062e-03 4.766880e-04 9.999893e-01 1.165860e+02 +9.999330e-01 1.157952e-02 -4.926628e-05 -2.325711e-01 -1.157957e-02 9.999323e-01 -1.083758e-03 -2.327575e+00 3.671389e-05 1.084256e-03 9.999994e-01 1.178116e+02 +9.999030e-01 1.341513e-02 -3.741016e-03 -2.372931e-01 -1.342029e-02 9.999090e-01 -1.356297e-03 -2.358001e+00 3.722482e-03 1.406371e-03 9.999921e-01 1.190399e+02 +9.998586e-01 1.576019e-02 -5.858555e-03 -2.464440e-01 -1.576711e-02 9.998750e-01 -1.137254e-03 -2.388148e+00 5.839900e-03 1.229467e-03 9.999822e-01 1.202714e+02 +9.998370e-01 1.671111e-02 -6.828606e-03 -2.562318e-01 -1.672110e-02 9.998592e-01 -1.409243e-03 -2.417424e+00 6.804096e-03 1.523196e-03 9.999757e-01 1.215013e+02 +9.997912e-01 1.884223e-02 -7.907589e-03 -2.696789e-01 -1.885055e-02 9.998218e-01 -9.793676e-04 -2.444635e+00 7.887727e-03 1.128226e-03 9.999683e-01 1.227424e+02 +9.997552e-01 2.025636e-02 -8.898890e-03 -2.835717e-01 -2.025535e-02 9.997948e-01 2.043085e-04 -2.471500e+00 8.901204e-03 -2.400768e-05 9.999604e-01 1.239829e+02 +9.997474e-01 2.029456e-02 -9.654303e-03 -2.970155e-01 -2.029377e-02 9.997940e-01 1.809995e-04 -2.498919e+00 9.655989e-03 1.496909e-05 9.999534e-01 1.252241e+02 +9.996672e-01 2.356820e-02 -1.049308e-02 -3.168152e-01 -2.354959e-02 9.997208e-01 1.894705e-03 -2.521615e+00 1.053481e-02 -1.646965e-03 9.999432e-01 1.264702e+02 +9.996212e-01 2.520161e-02 -1.106575e-02 -3.360760e-01 -2.514942e-02 9.996720e-01 4.830972e-03 -2.543289e+00 1.118387e-02 -4.550843e-03 9.999271e-01 1.277202e+02 +9.996376e-01 2.417676e-02 -1.184163e-02 -3.532043e-01 -2.411481e-02 9.996949e-01 5.347020e-03 -2.561295e+00 1.196730e-02 -5.059522e-03 9.999156e-01 1.289699e+02 +9.996381e-01 2.388106e-02 -1.238522e-02 -3.704424e-01 -2.384011e-02 9.997098e-01 3.443432e-03 -2.578125e+00 1.246386e-02 -3.146919e-03 9.999174e-01 1.302201e+02 +9.996900e-01 2.116355e-02 -1.311680e-02 -3.845450e-01 -2.111080e-02 9.997685e-01 4.147837e-03 -2.596170e+00 1.320155e-02 -3.869644e-03 9.999054e-01 1.314756e+02 +9.997230e-01 1.881769e-02 -1.413891e-02 -3.976226e-01 -1.873314e-02 9.998060e-01 6.088651e-03 -2.614808e+00 1.425075e-02 -5.822097e-03 9.998815e-01 1.327335e+02 +9.997671e-01 1.603321e-02 -1.444671e-02 -4.133731e-01 -1.591964e-02 9.998417e-01 7.941936e-03 -2.631357e+00 1.457176e-02 -7.710097e-03 9.998641e-01 1.339959e+02 +9.997891e-01 1.427647e-02 -1.476542e-02 -4.299121e-01 -1.413295e-02 9.998523e-01 9.779037e-03 -2.646140e+00 1.490285e-02 -9.568293e-03 9.998432e-01 1.352593e+02 +9.998429e-01 9.895168e-03 -1.470929e-02 -4.438867e-01 -9.781329e-03 9.999218e-01 7.791337e-03 -2.660056e+00 1.478524e-02 -7.646234e-03 9.998615e-01 1.365226e+02 +9.998650e-01 7.231494e-03 -1.475431e-02 -4.570556e-01 -7.142445e-03 9.999560e-01 6.079343e-03 -2.675992e+00 1.479762e-02 -5.973139e-03 9.998727e-01 1.377895e+02 +9.998778e-01 5.644588e-03 -1.457692e-02 -4.720570e-01 -5.557022e-03 9.999663e-01 6.040789e-03 -2.693213e+00 1.461053e-02 -5.959045e-03 9.998755e-01 1.390568e+02 +9.998820e-01 5.598248e-03 -1.430578e-02 -4.908150e-01 -5.506331e-03 9.999640e-01 6.456574e-03 -2.711316e+00 1.434142e-02 -6.377037e-03 9.998768e-01 1.403306e+02 +9.998897e-01 5.971145e-03 -1.360251e-02 -5.099508e-01 -5.859504e-03 9.999489e-01 8.232571e-03 -2.728134e+00 1.365098e-02 -8.151956e-03 9.998736e-01 1.416060e+02 +9.998800e-01 8.591962e-03 -1.289361e-02 -5.316574e-01 -8.463478e-03 9.999143e-01 9.986780e-03 -2.744134e+00 1.297831e-02 -9.876454e-03 9.998670e-01 1.428802e+02 +9.998866e-01 8.660587e-03 -1.231871e-02 -5.501461e-01 -8.547757e-03 9.999213e-01 9.182760e-03 -2.759529e+00 1.239727e-02 -9.076419e-03 9.998820e-01 1.441530e+02 +9.998890e-01 8.954282e-03 -1.191151e-02 -5.681071e-01 -8.876444e-03 9.999390e-01 6.571729e-03 -2.775354e+00 1.196963e-02 -6.465265e-03 9.999075e-01 1.454241e+02 +9.998925e-01 9.105110e-03 -1.149425e-02 -5.862240e-01 -9.053901e-03 9.999489e-01 4.499613e-03 -2.794830e+00 1.153464e-02 -4.395060e-03 9.999238e-01 1.466940e+02 +9.999061e-01 7.812498e-03 -1.125845e-02 -6.015689e-01 -7.808799e-03 9.999694e-01 3.725598e-04 -2.818864e+00 1.126102e-02 -2.846090e-04 9.999366e-01 1.479611e+02 +9.999110e-01 7.891193e-03 -1.075911e-02 -6.184009e-01 -7.925180e-03 9.999637e-01 -3.119781e-03 -2.844547e+00 1.073410e-02 3.204771e-03 9.999373e-01 1.492270e+02 +9.999147e-01 7.643519e-03 -1.059073e-02 -6.344428e-01 -7.688832e-03 9.999614e-01 -4.244256e-03 -2.875057e+00 1.055788e-02 4.325325e-03 9.999349e-01 1.504924e+02 +9.999151e-01 7.470657e-03 -1.068148e-02 -6.492857e-01 -7.512242e-03 9.999643e-01 -3.858175e-03 -2.908757e+00 1.065227e-02 3.938089e-03 9.999355e-01 1.517562e+02 +9.999104e-01 8.117233e-03 -1.064694e-02 -6.669047e-01 -8.155002e-03 9.999606e-01 -3.508696e-03 -2.939717e+00 1.061804e-02 3.595208e-03 9.999372e-01 1.530248e+02 +9.999008e-01 8.932264e-03 -1.088975e-02 -6.841745e-01 -8.957684e-03 9.999572e-01 -2.287657e-03 -2.969914e+00 1.086885e-02 2.384978e-03 9.999381e-01 1.542883e+02 +9.998937e-01 9.403347e-03 -1.114181e-02 -7.034750e-01 -9.423055e-03 9.999541e-01 -1.717437e-03 -2.997619e+00 1.112515e-02 1.822245e-03 9.999365e-01 1.555533e+02 +9.998850e-01 9.671333e-03 -1.168366e-02 -7.212308e-01 -9.694938e-03 9.999510e-01 -1.965176e-03 -3.024885e+00 1.166408e-02 2.078223e-03 9.999298e-01 1.568169e+02 +9.998742e-01 9.992074e-03 -1.232232e-02 -7.401339e-01 -1.001482e-02 9.999482e-01 -1.785279e-03 -3.051707e+00 1.230385e-02 1.908461e-03 9.999225e-01 1.580778e+02 +9.998709e-01 9.437093e-03 -1.300483e-02 -7.581397e-01 -9.446748e-03 9.999551e-01 -6.809684e-04 -3.079341e+00 1.299782e-02 8.037345e-04 9.999152e-01 1.593422e+02 +9.998535e-01 1.030765e-02 -1.366465e-02 -7.785169e-01 -1.031359e-02 9.999467e-01 -3.643023e-04 -3.107330e+00 1.366017e-02 5.051812e-04 9.999066e-01 1.606037e+02 +9.998420e-01 1.059246e-02 -1.427720e-02 -7.989665e-01 -1.061205e-02 9.999428e-01 -1.296387e-03 -3.135262e+00 1.426265e-02 1.447693e-03 9.998972e-01 1.618641e+02 +9.998251e-01 1.103635e-02 -1.510106e-02 -8.210143e-01 -1.107364e-02 9.999358e-01 -2.387686e-03 -3.162340e+00 1.507374e-02 2.554492e-03 9.998831e-01 1.631262e+02 +9.998060e-01 1.187481e-02 -1.571594e-02 -8.448485e-01 -1.191344e-02 9.999262e-01 -2.366601e-03 -3.191224e+00 1.568668e-02 2.553373e-03 9.998737e-01 1.643903e+02 +9.997991e-01 1.155638e-02 -1.637606e-02 -8.676072e-01 -1.160774e-02 9.999280e-01 -3.044212e-03 -3.221845e+00 1.633971e-02 3.233690e-03 9.998613e-01 1.656519e+02 +9.997825e-01 1.181146e-02 -1.718910e-02 -8.915914e-01 -1.188598e-02 9.999203e-01 -4.239466e-03 -3.252329e+00 1.713766e-02 4.442854e-03 9.998433e-01 1.669143e+02 +9.997696e-01 1.198696e-02 -1.780678e-02 -9.159259e-01 -1.206133e-02 9.999189e-01 -4.074819e-03 -3.282708e+00 1.775650e-02 4.288653e-03 9.998332e-01 1.681765e+02 +9.997523e-01 1.233623e-02 -1.852434e-02 -9.418036e-01 -1.238731e-02 9.999198e-01 -2.645128e-03 -3.313952e+00 1.849023e-02 2.873939e-03 9.998249e-01 1.694414e+02 +9.997374e-01 1.240974e-02 -1.926473e-02 -9.682551e-01 -1.245386e-02 9.999201e-01 -2.172174e-03 -3.344600e+00 1.923624e-02 2.411524e-03 9.998121e-01 1.707047e+02 +9.997203e-01 1.277294e-02 -1.990499e-02 -9.957698e-01 -1.281257e-02 9.999162e-01 -1.864756e-03 -3.373848e+00 1.987950e-02 2.119268e-03 9.998001e-01 1.719707e+02 +9.997000e-01 1.321051e-02 -2.062505e-02 -1.024319e+00 -1.324422e-02 9.999111e-01 -1.498835e-03 -3.402447e+00 2.060342e-02 1.771549e-03 9.997862e-01 1.732343e+02 +9.996846e-01 1.341994e-02 -2.122912e-02 -1.053647e+00 -1.347116e-02 9.999067e-01 -2.271637e-03 -3.431925e+00 2.119666e-02 2.556902e-03 9.997721e-01 1.744983e+02 +9.996607e-01 1.445123e-02 -2.167176e-02 -1.083166e+00 -1.451821e-02 9.998903e-01 -2.936385e-03 -3.461238e+00 2.162695e-02 3.250024e-03 9.997608e-01 1.757590e+02 +9.996489e-01 1.465281e-02 -2.207794e-02 -1.111965e+00 -1.470976e-02 9.998889e-01 -2.418874e-03 -3.491932e+00 2.204005e-02 2.742786e-03 9.997533e-01 1.770264e+02 +9.996424e-01 1.457372e-02 -2.241892e-02 -1.140940e+00 -1.465169e-02 9.998871e-01 -3.317459e-03 -3.523533e+00 2.236804e-02 3.644748e-03 9.997432e-01 1.782891e+02 +9.996589e-01 1.325812e-02 -2.250071e-02 -1.167498e+00 -1.337849e-02 9.998969e-01 -5.207424e-03 -3.555449e+00 2.242935e-02 5.506673e-03 9.997333e-01 1.795492e+02 +9.996874e-01 1.030641e-02 -2.277718e-02 -1.193384e+00 -1.041999e-02 9.999338e-01 -4.873750e-03 -3.587083e+00 2.272545e-02 5.109565e-03 9.997287e-01 1.808107e+02 +9.996814e-01 1.024882e-02 -2.306885e-02 -1.220912e+00 -1.028926e-02 9.999457e-01 -1.634951e-03 -3.617217e+00 2.305085e-02 1.871792e-03 9.997326e-01 1.820722e+02 +9.996814e-01 1.002918e-02 -2.316311e-02 -1.249819e+00 -9.950237e-03 9.999443e-01 3.520889e-03 -3.644685e+00 2.319713e-02 -3.289288e-03 9.997255e-01 1.833367e+02 +9.996734e-01 1.036281e-02 -2.336066e-02 -1.280267e+00 -1.030116e-02 9.999431e-01 2.757641e-03 -3.669131e+00 2.338791e-02 -2.516097e-03 9.997233e-01 1.845934e+02 +9.996606e-01 1.201921e-02 -2.311524e-02 -1.311919e+00 -1.202986e-02 9.999276e-01 -3.217053e-04 -3.694209e+00 2.310970e-02 5.996700e-04 9.997328e-01 1.858431e+02 +9.996501e-01 1.230447e-02 -2.341722e-02 -1.342768e+00 -1.236717e-02 9.999203e-01 -2.534452e-03 -3.722358e+00 2.338417e-02 2.823170e-03 9.997226e-01 1.870923e+02 +9.996511e-01 1.188341e-02 -2.358974e-02 -1.371475e+00 -1.194447e-02 9.999256e-01 -2.448977e-03 -3.752664e+00 2.355889e-02 2.729890e-03 9.997187e-01 1.883388e+02 +9.996525e-01 1.192754e-02 -2.350798e-02 -1.400872e+00 -1.194974e-02 9.999283e-01 -8.037377e-04 -3.781861e+00 2.349670e-02 1.084373e-03 9.997233e-01 1.895856e+02 +9.996551e-01 1.202913e-02 -2.334368e-02 -1.429913e+00 -1.200463e-02 9.999272e-01 1.189625e-03 -3.811043e+00 2.335630e-02 -9.089811e-04 9.997268e-01 1.908308e+02 +9.996763e-01 1.143527e-02 -2.272955e-02 -1.456920e+00 -1.138960e-02 9.999328e-01 2.137711e-03 -3.839753e+00 2.275247e-02 -1.878138e-03 9.997394e-01 1.920697e+02 +9.997053e-01 1.146956e-02 -2.139564e-02 -1.482347e+00 -1.143659e-02 9.999332e-01 1.663004e-03 -3.868861e+00 2.141328e-02 -1.417820e-03 9.997697e-01 1.933035e+02 +9.997487e-01 1.007974e-02 -2.002253e-02 -1.504387e+00 -1.008263e-02 9.999491e-01 -4.303345e-05 -3.897568e+00 2.002108e-02 2.449032e-04 9.997995e-01 1.945344e+02 +9.997735e-01 1.002801e-02 -1.877428e-02 -1.525428e+00 -1.005744e-02 9.999483e-01 -1.473791e-03 -3.929306e+00 1.875854e-02 1.662279e-03 9.998227e-01 1.957610e+02 +9.998066e-01 9.130046e-03 -1.742092e-02 -1.543340e+00 -9.171383e-03 9.999553e-01 -2.294297e-03 -3.962116e+00 1.739919e-02 2.453627e-03 9.998456e-01 1.969816e+02 +9.998262e-01 9.265399e-03 -1.617662e-02 -1.561315e+00 -9.289747e-03 9.999558e-01 -1.430490e-03 -3.994523e+00 1.616265e-02 1.580518e-03 9.998681e-01 1.981987e+02 +9.998506e-01 8.954749e-03 -1.478447e-02 -1.577337e+00 -8.947165e-03 9.999598e-01 5.791481e-04 -4.025379e+00 1.478906e-02 -4.467817e-04 9.998905e-01 1.994115e+02 +9.998606e-01 9.654808e-03 -1.362211e-02 -1.593225e+00 -9.642126e-03 9.999530e-01 9.965228e-04 -4.055718e+00 1.363109e-02 -8.650369e-04 9.999067e-01 2.006192e+02 +9.998768e-01 9.445742e-03 -1.253497e-02 -1.607052e+00 -9.436407e-03 9.999551e-01 8.038410e-04 -4.084508e+00 1.254200e-02 -6.854560e-04 9.999211e-01 2.018207e+02 +9.998851e-01 9.829830e-03 -1.154091e-02 -1.619569e+00 -9.817733e-03 9.999512e-01 1.104585e-03 -4.112611e+00 1.155120e-02 -9.911520e-04 9.999328e-01 2.030155e+02 +9.998948e-01 1.008993e-02 -1.042026e-02 -1.629855e+00 -1.007460e-02 9.999481e-01 1.522759e-03 -4.142166e+00 1.043509e-02 -1.417618e-03 9.999446e-01 2.042033e+02 +9.999026e-01 1.007774e-02 -9.652882e-03 -1.639698e+00 -1.006681e-02 9.999486e-01 1.180268e-03 -4.168995e+00 9.664281e-03 -1.082978e-03 9.999527e-01 2.053821e+02 +9.999104e-01 1.012366e-02 -8.754828e-03 -1.649074e+00 -1.011278e-02 9.999480e-01 1.287178e-03 -4.196218e+00 8.767405e-03 -1.198526e-03 9.999609e-01 2.065525e+02 +9.999265e-01 8.942437e-03 -8.192095e-03 -1.655974e+00 -8.930852e-03 9.999590e-01 1.449907e-03 -4.223531e+00 8.204726e-03 -1.376637e-03 9.999654e-01 2.077094e+02 +9.999297e-01 8.776023e-03 -7.972737e-03 -1.663162e+00 -8.760059e-03 9.999595e-01 2.035326e-03 -4.250230e+00 7.990277e-03 -1.965340e-03 9.999662e-01 2.088522e+02 +9.999313e-01 8.300880e-03 -8.282961e-03 -1.670517e+00 -8.272806e-03 9.999599e-01 3.418130e-03 -4.277047e+00 8.311003e-03 -3.349370e-03 9.999599e-01 2.099818e+02 +9.999233e-01 8.543601e-03 -8.972630e-03 -1.680916e+00 -8.513509e-03 9.999580e-01 3.386803e-03 -4.301812e+00 9.001190e-03 -3.310153e-03 9.999540e-01 2.110937e+02 +9.999174e-01 8.823204e-03 -9.346568e-03 -1.692609e+00 -8.801091e-03 9.999584e-01 2.404531e-03 -4.326860e+00 9.367395e-03 -2.322071e-03 9.999534e-01 2.121907e+02 +9.999105e-01 9.129603e-03 -9.785277e-03 -1.705386e+00 -9.115221e-03 9.999573e-01 1.513563e-03 -4.351615e+00 9.798678e-03 -1.424232e-03 9.999510e-01 2.132749e+02 +9.999054e-01 9.064680e-03 -1.034486e-02 -1.717659e+00 -9.051482e-03 9.999581e-01 1.322076e-03 -4.376802e+00 1.035641e-02 -1.228314e-03 9.999456e-01 2.143453e+02 +9.998981e-01 8.510470e-03 -1.146091e-02 -1.730641e+00 -8.494998e-03 9.999629e-01 1.398205e-03 -4.402081e+00 1.147238e-02 -1.300701e-03 9.999334e-01 2.154046e+02 +9.998818e-01 8.129220e-03 -1.304707e-02 -1.744177e+00 -8.101782e-03 9.999648e-01 2.154590e-03 -4.426871e+00 1.306412e-02 -2.048630e-03 9.999126e-01 2.164482e+02 +9.998623e-01 7.075987e-03 -1.501205e-02 -1.758097e+00 -7.022485e-03 9.999688e-01 3.613773e-03 -4.450451e+00 1.503715e-02 -3.507852e-03 9.998808e-01 2.174854e+02 +9.998251e-01 7.305260e-03 -1.721456e-02 -1.775959e+00 -7.206667e-03 9.999573e-01 5.782506e-03 -4.472509e+00 1.725607e-02 -5.657433e-03 9.998351e-01 2.185077e+02 +9.997825e-01 7.515842e-03 -1.945529e-02 -1.796549e+00 -7.402042e-03 9.999551e-01 5.914789e-03 -4.494237e+00 1.949887e-02 -5.769491e-03 9.997932e-01 2.195114e+02 +9.997238e-01 7.888414e-03 -2.213934e-02 -1.820190e+00 -7.773002e-03 9.999557e-01 5.294275e-03 -4.513126e+00 2.218012e-02 -5.120721e-03 9.997409e-01 2.204950e+02 +9.996589e-01 7.966565e-03 -2.487172e-02 -1.844527e+00 -7.835822e-03 9.999550e-01 5.349820e-03 -4.532452e+00 2.491322e-02 -5.153103e-03 9.996763e-01 2.214612e+02 +9.995792e-01 8.537703e-03 -2.772305e-02 -1.871601e+00 -8.373634e-03 9.999467e-01 6.028901e-03 -4.553298e+00 2.777305e-02 -5.794219e-03 9.995975e-01 2.224026e+02 +9.994888e-01 8.894846e-03 -3.070881e-02 -1.900504e+00 -8.713670e-03 9.999438e-01 6.028646e-03 -4.574348e+00 3.076072e-02 -5.757976e-03 9.995102e-01 2.233228e+02 +9.993905e-01 8.840090e-03 -3.377245e-02 -1.931080e+00 -8.663861e-03 9.999481e-01 5.360979e-03 -4.594192e+00 3.381809e-02 -5.065110e-03 9.994152e-01 2.242192e+02 +9.992779e-01 8.632605e-03 -3.700289e-02 -1.963226e+00 -8.456524e-03 9.999522e-01 4.912510e-03 -4.613875e+00 3.704353e-02 -4.596045e-03 9.993031e-01 2.250932e+02 +9.991469e-01 9.829968e-03 -4.011115e-02 -1.999321e+00 -9.647864e-03 9.999422e-01 4.731100e-03 -4.634336e+00 4.015535e-02 -4.340075e-03 9.991840e-01 2.259462e+02 +9.990191e-01 1.011427e-02 -4.311066e-02 -2.036110e+00 -9.956056e-03 9.999429e-01 3.883171e-03 -4.655490e+00 4.314748e-02 -3.450149e-03 9.990628e-01 2.267758e+02 +9.988931e-01 1.204947e-02 -4.546860e-02 -2.076063e+00 -1.187886e-02 9.999213e-01 4.020761e-03 -4.674144e+00 4.551348e-02 -3.476194e-03 9.989577e-01 2.275885e+02 +9.988454e-01 1.285424e-02 -4.628840e-02 -2.113952e+00 -1.267270e-02 9.999108e-01 4.213335e-03 -4.692285e+00 4.633843e-02 -3.621870e-03 9.989192e-01 2.283820e+02 +9.988548e-01 1.291834e-02 -4.606738e-02 -2.149429e+00 -1.268396e-02 9.999051e-01 5.376447e-03 -4.710568e+00 4.613246e-02 -4.785971e-03 9.989239e-01 2.291590e+02 +9.988768e-01 1.301272e-02 -4.556029e-02 -2.182836e+00 -1.274276e-02 9.998995e-01 6.210896e-03 -4.728951e+00 4.563653e-02 -5.623355e-03 9.989423e-01 2.299166e+02 +9.988935e-01 1.280984e-02 -4.525061e-02 -2.215172e+00 -1.256706e-02 9.999051e-01 5.645617e-03 -4.746558e+00 4.531864e-02 -5.070702e-03 9.989597e-01 2.306577e+02 +9.989018e-01 1.327722e-02 -4.493224e-02 -2.247910e+00 -1.312331e-02 9.999069e-01 3.718701e-03 -4.762455e+00 4.497743e-02 -3.124956e-03 9.989831e-01 2.313882e+02 +9.989383e-01 1.329114e-02 -4.410856e-02 -2.278813e+00 -1.323631e-02 9.999112e-01 1.535033e-03 -4.778921e+00 4.412505e-02 -9.495678e-04 9.990256e-01 2.321156e+02 +9.989870e-01 1.331303e-02 -4.298534e-02 -2.309140e+00 -1.331792e-02 9.999113e-01 1.726322e-04 -4.795655e+00 4.298383e-02 4.000187e-04 9.990757e-01 2.328383e+02 +9.990394e-01 1.403758e-02 -4.151247e-02 -2.338553e+00 -1.406235e-02 9.999010e-01 -3.048143e-04 -4.813178e+00 4.150409e-02 8.882852e-04 9.991379e-01 2.335600e+02 +9.991162e-01 1.347006e-02 -3.981679e-02 -2.364800e+00 -1.350330e-02 9.999086e-01 -5.659031e-04 -4.830531e+00 3.980553e-02 1.103062e-03 9.992068e-01 2.342776e+02 +9.991906e-01 1.328640e-02 -3.796862e-02 -2.389577e+00 -1.331778e-02 9.999111e-01 -5.736147e-04 -4.847959e+00 3.795763e-02 1.078809e-03 9.992788e-01 2.349915e+02 +9.992651e-01 1.336426e-02 -3.592461e-02 -2.414706e+00 -1.339616e-02 9.999100e-01 -6.472486e-04 -4.864866e+00 3.591273e-02 1.128025e-03 9.993543e-01 2.357021e+02 +9.993419e-01 1.311040e-02 -3.382173e-02 -2.437161e+00 -1.314953e-02 9.999131e-01 -9.347198e-04 -4.881579e+00 3.380654e-02 1.378845e-03 9.994275e-01 2.364085e+02 +9.994337e-01 1.322481e-02 -3.094321e-02 -2.458270e+00 -1.325259e-02 9.999119e-01 -6.927423e-04 -4.896919e+00 3.093133e-02 1.102428e-03 9.995209e-01 2.371116e+02 +9.995398e-01 1.231020e-02 -2.772615e-02 -2.475218e+00 -1.231979e-02 9.999241e-01 -1.750582e-04 -4.912132e+00 2.772190e-02 5.165588e-04 9.996156e-01 2.378114e+02 +9.996282e-01 1.126815e-02 -2.483098e-02 -2.489243e+00 -1.126448e-02 9.999365e-01 2.877643e-04 -4.929647e+00 2.483264e-02 -7.948487e-06 9.996916e-01 2.385076e+02 +9.997013e-01 1.098992e-02 -2.182982e-02 -2.501543e+00 -1.098202e-02 9.999396e-01 4.818198e-04 -4.947554e+00 2.183380e-02 -2.419396e-04 9.997616e-01 2.391999e+02 +9.997657e-01 1.059942e-02 -1.887178e-02 -2.511949e+00 -1.059804e-02 9.999438e-01 1.729227e-04 -4.965562e+00 1.887255e-02 2.712253e-05 9.998219e-01 2.398878e+02 +9.998182e-01 1.038177e-02 -1.599609e-02 -2.520293e+00 -1.038785e-02 9.999460e-01 -2.970442e-04 -4.981740e+00 1.599214e-02 4.631559e-04 9.998720e-01 2.405753e+02 +9.998505e-01 1.134175e-02 -1.304889e-02 -2.528203e+00 -1.135881e-02 9.999347e-01 -1.233928e-03 -4.998210e+00 1.303405e-02 1.381964e-03 9.999141e-01 2.412639e+02 +9.998847e-01 1.126161e-02 -1.018625e-02 -2.534352e+00 -1.128179e-02 9.999345e-01 -1.926060e-03 -5.015660e+00 1.016389e-02 2.040757e-03 9.999463e-01 2.419573e+02 +9.999093e-01 1.129863e-02 -7.336242e-03 -2.538348e+00 -1.130652e-02 9.999355e-01 -1.034001e-03 -5.032044e+00 7.324087e-03 1.116855e-03 9.999726e-01 2.426535e+02 +9.999189e-01 1.181599e-02 -4.762593e-03 -2.543393e+00 -1.181795e-02 9.999301e-01 -3.816016e-04 -5.048170e+00 4.757752e-03 4.378554e-04 9.999886e-01 2.433559e+02 +9.999302e-01 1.155370e-02 -2.459278e-03 -2.545596e+00 -1.155511e-02 9.999331e-01 -5.591492e-04 -5.064282e+00 2.452654e-03 5.875280e-04 9.999968e-01 2.440590e+02 +9.999351e-01 1.139254e-02 -1.714107e-04 -2.546852e+00 -1.139283e-02 9.999335e-01 -1.782130e-03 -5.080295e+00 1.510966e-04 1.783967e-03 9.999984e-01 2.447634e+02 +9.999318e-01 1.157600e-02 1.542321e-03 -2.546619e+00 -1.156915e-02 9.999234e-01 -4.383648e-03 -5.094783e+00 -1.592948e-03 4.365505e-03 9.999892e-01 2.454715e+02 +9.999381e-01 1.084619e-02 2.490505e-03 -2.545576e+00 -1.083126e-02 9.999237e-01 -5.935101e-03 -5.109038e+00 -2.554688e-03 5.907758e-03 9.999793e-01 2.461863e+02 +9.999384e-01 1.077194e-02 2.672936e-03 -2.543734e+00 -1.075364e-02 9.999193e-01 -6.767155e-03 -5.126143e+00 -2.745615e-03 6.737994e-03 9.999735e-01 2.469081e+02 +9.999458e-01 1.001294e-02 2.848720e-03 -2.542056e+00 -9.992817e-03 9.999256e-01 -6.991832e-03 -5.145191e+00 -2.918517e-03 6.962986e-03 9.999715e-01 2.476359e+02 +9.999358e-01 1.092501e-02 3.021948e-03 -2.541896e+00 -1.090312e-02 9.999148e-01 -7.169908e-03 -5.164585e+00 -3.100022e-03 7.136498e-03 9.999697e-01 2.483695e+02 +9.999253e-01 1.176096e-02 3.320979e-03 -2.542204e+00 -1.173454e-02 9.999002e-01 -7.865426e-03 -5.185382e+00 -3.413152e-03 7.825868e-03 9.999636e-01 2.491114e+02 +9.999323e-01 1.108684e-02 3.527473e-03 -2.540944e+00 -1.105160e-02 9.998903e-01 -9.858624e-03 -5.205979e+00 -3.636387e-03 9.818971e-03 9.999452e-01 2.498573e+02 +9.999656e-01 7.322526e-03 3.910257e-03 -2.535403e+00 -7.276476e-03 9.999055e-01 -1.166438e-02 -5.227370e+00 -3.995300e-03 1.163553e-02 9.999243e-01 2.506100e+02 +9.999829e-01 4.023655e-03 4.247560e-03 -2.529259e+00 -3.969773e-03 9.999125e-01 -1.261880e-02 -5.246305e+00 -4.297962e-03 1.260172e-02 9.999114e-01 2.513708e+02 +9.999724e-01 5.633027e-03 4.841945e-03 -2.529475e+00 -5.586639e-03 9.999388e-01 -9.541481e-03 -5.263872e+00 -4.895396e-03 9.514167e-03 9.999428e-01 2.521450e+02 +9.999347e-01 1.001002e-02 5.514964e-03 -2.534412e+00 -9.991019e-03 9.999441e-01 -3.461758e-03 -5.282956e+00 -5.549308e-03 3.406432e-03 9.999788e-01 2.529289e+02 +9.999320e-01 9.753806e-03 6.386489e-03 -2.531730e+00 -9.761918e-03 9.999516e-01 1.239967e-03 -5.300222e+00 -6.374086e-03 -1.302226e-03 9.999788e-01 2.537160e+02 +9.999315e-01 8.282980e-03 8.265151e-03 -2.522827e+00 -8.277616e-03 9.999655e-01 -6.832156e-04 -5.316153e+00 -8.270525e-03 6.147536e-04 9.999656e-01 2.545107e+02 +9.998814e-01 9.412307e-03 1.219179e-02 -2.516895e+00 -9.326539e-03 9.999315e-01 -7.072959e-03 -5.328791e+00 -1.225752e-02 6.958412e-03 9.999007e-01 2.553056e+02 +9.998035e-01 1.155317e-02 1.610904e-02 -2.508908e+00 -1.136567e-02 9.998671e-01 -1.168301e-02 -5.345294e+00 -1.624188e-02 1.149762e-02 9.998020e-01 2.561119e+02 +9.997287e-01 1.301807e-02 1.931264e-02 -2.495854e+00 -1.279623e-02 9.998512e-01 -1.156648e-02 -5.364407e+00 -1.946034e-02 1.131621e-02 9.997466e-01 2.569296e+02 +9.996769e-01 1.167319e-02 2.257978e-02 -2.476437e+00 -1.147257e-02 9.998937e-01 -8.994677e-03 -5.385775e+00 -2.268238e-02 8.732722e-03 9.997046e-01 2.577578e+02 +9.996371e-01 8.632262e-03 2.551858e-02 -2.451908e+00 -8.485886e-03 9.999469e-01 -5.838899e-03 -5.406872e+00 -2.556763e-02 5.620232e-03 9.996573e-01 2.585928e+02 +9.995828e-01 6.150285e-03 2.821921e-02 -2.426274e+00 -6.038441e-03 9.999736e-01 -4.046954e-03 -5.425049e+00 -2.824336e-02 3.874865e-03 9.995936e-01 2.594295e+02 +9.994894e-01 5.930202e-03 3.139750e-02 -2.401831e+00 -5.823188e-03 9.999769e-01 -3.498755e-03 -5.445288e+00 -3.141752e-02 3.314135e-03 9.995009e-01 2.602685e+02 +9.993904e-01 8.171329e-03 3.394327e-02 -2.377452e+00 -7.988728e-03 9.999529e-01 -5.511768e-03 -5.467449e+00 -3.398671e-02 5.237244e-03 9.994086e-01 2.611028e+02 +9.993040e-01 8.631655e-03 3.629000e-02 -2.347909e+00 -8.351913e-03 9.999343e-01 -7.853110e-03 -5.488513e+00 -3.635540e-02 7.544553e-03 9.993105e-01 2.619398e+02 +9.992037e-01 8.956979e-03 3.888208e-02 -2.315586e+00 -8.641401e-03 9.999284e-01 -8.276839e-03 -5.509575e+00 -3.895343e-02 7.934251e-03 9.992095e-01 2.627787e+02 +9.990772e-01 9.860672e-03 4.180323e-02 -2.282743e+00 -9.602689e-03 9.999336e-01 -6.367741e-03 -5.533299e+00 -4.186324e-02 5.960441e-03 9.991056e-01 2.636212e+02 +9.989173e-01 1.138173e-02 4.510767e-02 -2.249292e+00 -1.119240e-02 9.999274e-01 -4.447533e-03 -5.557575e+00 -4.515502e-02 3.937854e-03 9.989722e-01 2.644631e+02 +9.987824e-01 1.192758e-02 4.786978e-02 -2.211671e+00 -1.172932e-02 9.999214e-01 -4.420534e-03 -5.580169e+00 -4.791874e-02 3.853672e-03 9.988438e-01 2.653026e+02 +9.986533e-01 1.179716e-02 5.052105e-02 -2.169031e+00 -1.154917e-02 9.999198e-01 -5.197782e-03 -5.601556e+00 -5.057832e-02 4.607306e-03 9.987095e-01 2.661456e+02 +9.985364e-01 1.019645e-02 5.311482e-02 -2.120601e+00 -9.914560e-03 9.999353e-01 -5.568043e-03 -5.622751e+00 -5.316817e-02 5.033283e-03 9.985729e-01 2.669886e+02 +9.984643e-01 7.188352e-03 5.493063e-02 -2.070929e+00 -6.923578e-03 9.999635e-01 -5.008957e-03 -5.642388e+00 -5.496464e-02 4.620948e-03 9.984776e-01 2.678345e+02 +9.984232e-01 5.720778e-03 5.584260e-02 -2.020152e+00 -5.456183e-03 9.999731e-01 -4.889568e-03 -5.662313e+00 -5.586908e-02 4.577170e-03 9.984276e-01 2.686821e+02 +9.983947e-01 4.968563e-03 5.642066e-02 -1.972336e+00 -4.699585e-03 9.999769e-01 -4.899074e-03 -5.683949e+00 -5.644370e-02 4.626055e-03 9.983951e-01 2.695293e+02 +9.983663e-01 4.848794e-03 5.693179e-02 -1.923826e+00 -4.581796e-03 9.999779e-01 -4.819406e-03 -5.705921e+00 -5.695390e-02 4.550683e-03 9.983664e-01 2.703816e+02 +9.983677e-01 4.824387e-03 5.690876e-02 -1.875688e+00 -4.582192e-03 9.999799e-01 -4.385600e-03 -5.726987e+00 -5.692878e-02 4.117674e-03 9.983698e-01 2.712341e+02 +9.983956e-01 5.374549e-03 5.636852e-02 -1.829452e+00 -5.169485e-03 9.999795e-01 -3.783122e-03 -5.750154e+00 -5.638770e-02 3.485656e-03 9.984029e-01 2.720891e+02 +9.984601e-01 5.007634e-03 5.524747e-02 -1.783337e+00 -4.765767e-03 9.999785e-01 -4.508777e-03 -5.773108e+00 -5.526886e-02 4.238538e-03 9.984625e-01 2.729432e+02 +9.985463e-01 5.133179e-03 5.365578e-02 -1.741198e+00 -4.852447e-03 9.999738e-01 -5.361069e-03 -5.793806e+00 -5.368190e-02 5.092913e-03 9.985451e-01 2.737954e+02 +9.986284e-01 5.918529e-03 5.202125e-02 -1.700845e+00 -5.597716e-03 9.999644e-01 -6.310512e-03 -5.814912e+00 -5.205675e-02 6.010657e-03 9.986260e-01 2.746511e+02 +9.986949e-01 7.010597e-03 5.059033e-02 -1.660663e+00 -6.694403e-03 9.999570e-01 -6.416858e-03 -5.835884e+00 -5.063314e-02 6.069810e-03 9.986989e-01 2.755035e+02 +9.987660e-01 8.133439e-03 4.899410e-02 -1.622669e+00 -7.822405e-03 9.999480e-01 -6.536837e-03 -5.858238e+00 -4.904473e-02 6.145518e-03 9.987777e-01 2.763544e+02 +9.988683e-01 8.613455e-03 4.677598e-02 -1.585579e+00 -8.338551e-03 9.999468e-01 -6.069013e-03 -5.879709e+00 -4.682577e-02 5.672100e-03 9.988870e-01 2.772037e+02 +9.989946e-01 8.422478e-03 4.403156e-02 -1.550632e+00 -8.228132e-03 9.999556e-01 -4.593216e-03 -5.901149e+00 -4.406829e-02 4.226300e-03 9.990196e-01 2.780516e+02 +9.991778e-01 7.024358e-03 3.992963e-02 -1.517863e+00 -6.940009e-03 9.999734e-01 -2.250700e-03 -5.921904e+00 -3.994438e-02 1.971738e-03 9.992000e-01 2.788967e+02 +9.993635e-01 5.822915e-03 3.519509e-02 -1.489305e+00 -5.819062e-03 9.999830e-01 -2.119652e-04 -5.941918e+00 -3.519573e-02 7.028462e-06 9.993804e-01 2.797354e+02 +9.995223e-01 5.332099e-03 3.044189e-02 -1.466242e+00 -5.371251e-03 9.999848e-01 1.204461e-03 -5.960750e+00 -3.043501e-02 -1.367396e-03 9.995358e-01 2.805687e+02 +9.996574e-01 4.914014e-03 2.570864e-02 -1.447757e+00 -4.962389e-03 9.999860e-01 1.818158e-03 -5.978025e+00 -2.569935e-02 -1.945110e-03 9.996678e-01 2.813897e+02 +9.997660e-01 4.426975e-03 2.117290e-02 -1.431895e+00 -4.481629e-03 9.999867e-01 2.534527e-03 -5.994410e+00 -2.116140e-02 -2.628822e-03 9.997726e-01 2.822031e+02 +9.998582e-01 3.417936e-03 1.649028e-02 -1.419054e+00 -3.464110e-03 9.999901e-01 2.772280e-03 -6.010847e+00 -1.648064e-02 -2.829010e-03 9.998602e-01 2.830036e+02 +9.999190e-01 3.019938e-03 1.236106e-02 -1.412086e+00 -3.051025e-03 9.999922e-01 2.496810e-03 -6.026687e+00 -1.235343e-02 -2.534321e-03 9.999205e-01 2.837879e+02 +9.999589e-01 3.448345e-03 8.391040e-03 -1.411252e+00 -3.468664e-03 9.999911e-01 2.408034e-03 -6.040170e+00 -8.382662e-03 -2.437039e-03 9.999619e-01 2.845553e+02 +9.999825e-01 3.782048e-03 4.558225e-03 -1.414317e+00 -3.793442e-03 9.999897e-01 2.493418e-03 -6.053988e+00 -4.548748e-03 -2.510664e-03 9.999865e-01 2.853052e+02 +9.999935e-01 3.534352e-03 7.657028e-04 -1.417779e+00 -3.536370e-03 9.999902e-01 2.648300e-03 -6.069167e+00 -7.563350e-04 -2.650989e-03 9.999962e-01 2.860359e+02 +9.999905e-01 2.663619e-03 -3.440635e-03 -1.423417e+00 -2.657059e-03 9.999946e-01 1.909798e-03 -6.085125e+00 3.445704e-03 -1.900636e-03 9.999923e-01 2.867440e+02 +9.999577e-01 3.814336e-03 -8.374917e-03 -1.435822e+00 -3.810160e-03 9.999926e-01 5.145885e-04 -6.101380e+00 8.376818e-03 -4.826561e-04 9.999648e-01 2.874331e+02 +9.998773e-01 5.429416e-03 -1.469453e-02 -1.454441e+00 -5.449682e-03 9.999842e-01 -1.339424e-03 -6.117454e+00 1.468703e-02 1.419340e-03 9.998911e-01 2.881005e+02 +9.997187e-01 6.283694e-03 -2.287209e-02 -1.477649e+00 -6.356257e-03 9.999750e-01 -3.101172e-03 -6.132605e+00 2.285203e-02 3.245680e-03 9.997336e-01 2.887511e+02 +9.994316e-01 6.168463e-03 -3.314286e-02 -1.506373e+00 -6.306868e-03 9.999718e-01 -4.073051e-03 -6.149396e+00 3.311680e-02 4.279764e-03 9.994423e-01 2.893890e+02 +9.988958e-01 6.604999e-03 -4.651366e-02 -1.545617e+00 -6.812456e-03 9.999675e-01 -4.302986e-03 -6.167037e+00 4.648373e-02 4.615107e-03 9.989084e-01 2.900173e+02 +9.979962e-01 7.563684e-03 -6.282002e-02 -1.597157e+00 -7.789806e-03 9.999640e-01 -3.355350e-03 -6.182453e+00 6.279239e-02 3.837983e-03 9.980192e-01 2.906281e+02 +9.965471e-01 1.023420e-02 -8.239691e-02 -1.665044e+00 -1.047295e-02 9.999421e-01 -2.465836e-03 -6.196964e+00 8.236691e-02 3.320260e-03 9.965966e-01 2.912300e+02 +9.944339e-01 1.193309e-02 -1.046845e-01 -1.742378e+00 -1.224625e-02 9.999222e-01 -2.349099e-03 -6.210196e+00 1.046483e-01 3.618017e-03 9.945027e-01 2.918062e+02 +9.914480e-01 1.338096e-02 -1.298146e-01 -1.834488e+00 -1.378449e-02 9.999025e-01 -2.210401e-03 -6.224247e+00 1.297724e-01 3.980927e-03 9.915358e-01 2.923790e+02 +9.874435e-01 1.494253e-02 -1.572642e-01 -1.942994e+00 -1.538155e-02 9.998804e-01 -1.574791e-03 -6.237015e+00 1.572219e-01 3.973984e-03 9.875553e-01 2.929374e+02 +9.821456e-01 1.637005e-02 -1.874087e-01 -2.067997e+00 -1.669286e-02 9.998606e-01 -1.443122e-04 -6.247853e+00 1.873802e-01 3.270123e-03 9.822820e-01 2.934679e+02 +9.751946e-01 1.636349e-02 -2.207437e-01 -2.209538e+00 -1.633564e-02 9.998646e-01 1.951826e-03 -6.257666e+00 2.207458e-01 1.702582e-03 9.753299e-01 2.939981e+02 +9.664279e-01 1.663688e-02 -2.563988e-01 -2.367902e+00 -1.613277e-02 9.998616e-01 4.069517e-03 -6.271075e+00 2.564310e-01 2.035297e-04 9.665625e-01 2.945121e+02 +9.558056e-01 1.816575e-02 -2.934376e-01 -2.543375e+00 -1.687060e-02 9.998335e-01 6.944288e-03 -6.285270e+00 2.935149e-01 -1.686918e-03 9.559530e-01 2.949879e+02 +9.431225e-01 1.991691e-02 -3.318483e-01 -2.739392e+00 -1.767411e-02 9.997960e-01 9.775552e-03 -6.297631e+00 3.319754e-01 -3.354416e-03 9.432821e-01 2.954667e+02 +9.283298e-01 2.079609e-02 -3.711755e-01 -2.949047e+00 -1.750200e-02 9.997719e-01 1.224145e-02 -6.307941e+00 3.713454e-01 -4.867790e-03 9.284821e-01 2.959018e+02 +9.112820e-01 2.094660e-02 -4.112497e-01 -3.178542e+00 -1.646279e-02 9.997601e-01 1.444217e-02 -6.314604e+00 4.114536e-01 -6.390564e-03 9.114083e-01 2.963492e+02 +8.915138e-01 2.087312e-02 -4.525124e-01 -3.425572e+00 -1.529834e-02 9.997553e-01 1.597598e-02 -6.320980e+00 4.527352e-01 -7.320112e-03 8.916150e-01 2.967828e+02 +8.688428e-01 2.058754e-02 -4.946598e-01 -3.687333e+00 -1.375250e-02 9.997531e-01 1.745382e-02 -6.328231e+00 4.948970e-01 -8.361817e-03 8.689114e-01 2.971641e+02 +8.432539e-01 1.998884e-02 -5.371437e-01 -3.968958e+00 -1.154593e-02 9.997513e-01 1.907818e-02 -6.332760e+00 5.373915e-01 -9.885924e-03 8.432750e-01 2.975634e+02 +8.145344e-01 2.035925e-02 -5.797579e-01 -4.268559e+00 -9.936276e-03 9.997270e-01 2.114720e-02 -6.336992e+00 5.800302e-01 -1.146448e-02 8.145143e-01 2.979439e+02 +7.828475e-01 2.209783e-02 -6.218211e-01 -4.586321e+00 -1.043145e-02 9.996948e-01 2.239367e-02 -6.339444e+00 6.221262e-01 -1.104433e-02 7.828391e-01 2.982617e+02 +7.478901e-01 2.152852e-02 -6.634734e-01 -4.922654e+00 -8.359254e-03 9.997001e-01 2.301564e-02 -6.345184e+00 6.637700e-01 -1.166702e-02 7.478458e-01 2.985997e+02 +7.092480e-01 2.101313e-02 -7.046458e-01 -5.270323e+00 -4.493999e-03 9.996701e-01 2.528766e-02 -6.347814e+00 7.049447e-01 -1.476854e-02 7.091085e-01 2.988694e+02 +6.661165e-01 2.048042e-02 -7.455664e-01 -5.635576e+00 1.868369e-03 9.995739e-01 2.912719e-02 -6.343982e+00 7.458454e-01 -2.079509e-02 6.657945e-01 2.991672e+02 +6.185955e-01 2.121490e-02 -7.854232e-01 -6.014393e+00 6.372302e-03 9.994670e-01 3.201520e-02 -6.339964e+00 7.856838e-01 -2.480940e-02 6.181306e-01 2.994337e+02 +5.677589e-01 2.491865e-02 -8.228177e-01 -6.404391e+00 6.450511e-03 9.993764e-01 3.471663e-02 -6.332310e+00 8.231697e-01 -2.501826e-02 5.672441e-01 2.996092e+02 +5.150100e-01 3.174472e-02 -8.565961e-01 -6.808874e+00 1.903388e-03 9.992692e-01 3.817644e-02 -6.331276e+00 8.571821e-01 -2.129168e-02 5.145733e-01 2.998050e+02 +4.600217e-01 3.653914e-02 -8.871555e-01 -7.216405e+00 -9.613100e-04 9.991728e-01 4.065431e-02 -6.326098e+00 8.879072e-01 -1.784903e-02 4.596763e-01 2.999751e+02 +4.030798e-01 3.874929e-02 -9.143441e-01 -7.620091e+00 -1.025936e-03 9.991217e-01 4.188984e-02 -6.315633e+00 9.151643e-01 -1.594688e-02 4.027656e-01 3.000619e+02 +3.453982e-01 4.091513e-02 -9.375639e-01 -8.027228e+00 7.942996e-04 9.990360e-01 4.389040e-02 -6.304576e+00 9.384559e-01 -1.590437e-02 3.450328e-01 3.001811e+02 +2.869159e-01 4.417682e-02 -9.569366e-01 -8.436151e+00 3.484167e-03 9.988813e-01 4.715786e-02 -6.292308e+00 9.579495e-01 -1.686446e-02 2.864410e-01 3.002200e+02 +2.276281e-01 4.821035e-02 -9.725539e-01 -8.849753e+00 5.518634e-03 9.986937e-01 5.079778e-02 -6.282888e+00 9.737325e-01 -1.693016e-02 2.270647e-01 3.002873e+02 +1.658405e-01 5.158130e-02 -9.848027e-01 -9.270289e+00 8.732677e-03 9.985151e-01 5.377012e-02 -6.271213e+00 9.861140e-01 -1.751722e-02 1.651438e-01 3.003291e+02 +1.020290e-01 5.558781e-02 -9.932271e-01 -9.696194e+00 9.495467e-03 9.983376e-01 5.684926e-02 -6.256955e+00 9.947361e-01 -1.523142e-02 1.013315e-01 3.002840e+02 +3.728192e-02 6.091022e-02 -9.974467e-01 -1.013605e+01 1.207917e-02 9.980402e-01 6.139797e-02 -6.242546e+00 9.992318e-01 -1.433736e-02 3.647311e-02 3.002712e+02 +-2.861154e-02 6.761246e-02 -9.973013e-01 -1.058129e+01 1.450990e-02 9.976327e-01 6.721867e-02 -6.224323e+00 9.994853e-01 -1.254750e-02 -2.952486e-02 3.002293e+02 +-9.567329e-02 7.433318e-02 -9.926335e-01 -1.103111e+01 1.756901e-02 9.971786e-01 7.298020e-02 -6.199526e+00 9.952578e-01 -1.045732e-02 -9.670932e-02 3.000970e+02 +-1.622278e-01 8.061149e-02 -9.834551e-01 -1.148794e+01 2.046263e-02 9.967180e-01 7.832318e-02 -6.178297e+00 9.865412e-01 -7.417880e-03 -1.633449e-01 2.999941e+02 +-2.276266e-01 8.661270e-02 -9.698888e-01 -1.194318e+01 2.513975e-02 9.962270e-01 8.306463e-02 -6.150180e+00 9.734240e-01 -5.475042e-03 -2.289451e-01 2.997982e+02 +-2.916010e-01 9.114715e-02 -9.521875e-01 -1.240289e+01 3.022664e-02 9.958306e-01 8.606815e-02 -6.123531e+00 9.560624e-01 -3.683863e-03 -2.931403e-01 2.996328e+02 +-3.531290e-01 9.363637e-02 -9.308770e-01 -1.285980e+01 3.485062e-02 9.956049e-01 8.692672e-02 -6.094784e+00 9.349253e-01 -1.745286e-03 -3.548403e-01 2.994338e+02 +-4.122464e-01 9.449474e-02 -9.061587e-01 -1.331090e+01 3.933185e-02 9.955253e-01 8.592039e-02 -6.063773e+00 9.102230e-01 -2.205223e-04 -4.141184e-01 2.991429e+02 +-4.677578e-01 9.454540e-02 -8.787854e-01 -1.376340e+01 4.279433e-02 9.955188e-01 8.432590e-02 -6.028358e+00 8.828201e-01 1.837069e-03 -4.697077e-01 2.988742e+02 +-5.195944e-01 9.466394e-02 -8.491528e-01 -1.421251e+01 4.594067e-02 9.955010e-01 8.286797e-02 -5.989762e+00 8.531771e-01 4.047087e-03 -5.216057e-01 2.985219e+02 +-5.661043e-01 9.480093e-02 -8.188643e-01 -1.466311e+01 4.852789e-02 9.954749e-01 8.169868e-02 -5.950116e+00 8.229040e-01 6.512222e-03 -5.681432e-01 2.981811e+02 +-6.071218e-01 9.561220e-02 -7.888355e-01 -1.511616e+01 5.049700e-02 9.953702e-01 8.178097e-02 -5.913525e+00 7.930027e-01 9.817187e-03 -6.091391e-01 2.978016e+02 +-6.444110e-01 9.890993e-02 -7.582554e-01 -1.556917e+01 5.533819e-02 9.950313e-01 8.276627e-02 -5.871992e+00 7.626744e-01 1.137501e-02 -6.466826e-01 2.973601e+02 +-6.809154e-01 1.056329e-01 -7.247040e-01 -1.602426e+01 6.436168e-02 9.943458e-01 8.446317e-02 -5.830931e+00 7.295285e-01 1.086911e-02 -6.838641e-01 2.969179e+02 +-7.164120e-01 1.114214e-01 -6.887228e-01 -1.647064e+01 7.174229e-02 9.936971e-01 8.613348e-02 -5.783464e+00 6.939791e-01 1.229651e-02 -7.198902e-01 2.964013e+02 +-7.492835e-01 1.134759e-01 -6.524550e-01 -1.690392e+01 7.593209e-02 9.934337e-01 8.557864e-02 -5.737737e+00 6.578820e-01 1.458039e-02 -7.529799e-01 2.958766e+02 +-7.797406e-01 1.101848e-01 -6.163311e-01 -1.732241e+01 7.643205e-02 9.937819e-01 8.096699e-02 -5.692386e+00 6.214200e-01 1.602580e-02 -7.833137e-01 2.952843e+02 +-8.072322e-01 1.073610e-01 -5.803876e-01 -1.772918e+01 7.840312e-02 9.941082e-01 7.484467e-02 -5.645499e+00 5.850036e-01 1.491282e-02 -8.108936e-01 2.946844e+02 +-8.323704e-01 1.024434e-01 -5.446696e-01 -1.812343e+01 7.772816e-02 9.946330e-01 6.828905e-02 -5.596317e+00 5.487422e-01 1.450562e-02 -8.358658e-01 2.940467e+02 +-8.550526e-01 9.971903e-02 -5.088626e-01 -1.850534e+01 7.890277e-02 9.949281e-01 6.238870e-02 -5.550791e+00 5.125031e-01 1.319495e-02 -8.585840e-01 2.933496e+02 +-8.757636e-01 9.783343e-02 -4.727227e-01 -1.887203e+01 7.850299e-02 9.950761e-01 6.050415e-02 -5.509383e+00 4.763144e-01 1.587719e-02 -8.791317e-01 2.926362e+02 +-8.954302e-01 9.445256e-02 -4.350672e-01 -1.921381e+01 7.670849e-02 9.953527e-01 5.821294e-02 -5.472940e+00 4.385437e-01 1.875228e-02 -8.985142e-01 2.918625e+02 +-9.130170e-01 9.361816e-02 -3.970335e-01 -1.953852e+01 7.794413e-02 9.954132e-01 5.547255e-02 -5.435497e+00 4.004056e-01 1.970095e-02 -9.161262e-01 2.910794e+02 +-9.288132e-01 9.558846e-02 -3.580067e-01 -1.984548e+01 8.161866e-02 9.952013e-01 5.396910e-02 -5.397191e+00 3.614476e-01 2.090719e-02 -9.321580e-01 2.902408e+02 +-9.426026e-01 9.921231e-02 -3.188373e-01 -2.012922e+01 8.684633e-02 9.948211e-01 5.280735e-02 -5.364689e+00 3.224252e-01 2.208649e-02 -9.463372e-01 2.893905e+02 +-9.546984e-01 9.969512e-02 -2.803781e-01 -2.038184e+01 8.826347e-02 9.946786e-01 5.314125e-02 -5.330467e+00 2.841840e-01 2.598672e-02 -9.584175e-01 2.885047e+02 +-9.646218e-01 1.026359e-01 -2.428389e-01 -2.061251e+01 9.255909e-02 9.943180e-01 5.257907e-02 -5.296130e+00 2.468556e-01 2.824196e-02 -9.686407e-01 2.875677e+02 +-9.731786e-01 1.019882e-01 -2.062084e-01 -2.081155e+01 9.328698e-02 9.943057e-01 5.151404e-02 -5.265003e+00 2.102880e-01 3.089581e-02 -9.771512e-01 2.866208e+02 +-9.799848e-01 1.002184e-01 -1.720061e-01 -2.097738e+01 9.367627e-02 9.945505e-01 4.575985e-02 -5.231887e+00 1.756548e-01 2.873107e-02 -9.840325e-01 2.856322e+02 +-9.853644e-01 9.883847e-02 -1.388813e-01 -2.111659e+01 9.399114e-02 9.947262e-01 4.105462e-02 -5.198232e+00 1.422066e-01 2.740015e-02 -9.894577e-01 2.846297e+02 +-9.893987e-01 9.801091e-02 -1.071642e-01 -2.122691e+01 9.424259e-02 9.947576e-01 3.969274e-02 -5.169612e+00 1.104928e-01 2.917251e-02 -9.934487e-01 2.835931e+02 +-9.924318e-01 9.622513e-02 -7.628790e-02 -2.130702e+01 9.351779e-02 9.948803e-01 3.830874e-02 -5.143301e+00 7.958360e-02 3.088454e-02 -9.963496e-01 2.825205e+02 +-9.943661e-01 9.483394e-02 -4.735592e-02 -2.135871e+01 9.316416e-02 9.949885e-01 3.630859e-02 -5.118237e+00 5.056189e-02 3.169215e-02 -9.982180e-01 2.814312e+02 +-9.952359e-01 9.527046e-02 -2.071198e-02 -2.138358e+01 9.453364e-02 9.949394e-01 3.404260e-02 -5.092068e+00 2.385042e-02 3.192243e-02 -9.992058e-01 2.803112e+02 +-9.957527e-01 9.196279e-02 4.401056e-03 -2.137724e+01 9.206004e-02 9.951590e-01 3.440270e-02 -5.068634e+00 -1.215982e-03 3.466174e-02 -9.993984e-01 2.791733e+02 +-9.955379e-01 9.014441e-02 2.789736e-02 -2.134556e+01 9.107603e-02 9.952583e-01 3.414826e-02 -5.044246e+00 -2.468681e-02 3.653666e-02 -9.990274e-01 2.780075e+02 +-9.949989e-01 8.744165e-02 4.828300e-02 -2.128976e+01 8.906838e-02 9.954908e-01 3.263150e-02 -5.021530e+00 -4.521193e-02 3.676879e-02 -9.983005e-01 2.768295e+02 +-9.944714e-01 8.274355e-02 6.465401e-02 -2.120924e+01 8.478673e-02 9.959617e-01 2.951923e-02 -5.001358e+00 -6.195040e-02 3.483783e-02 -9.974710e-01 2.756388e+02 +-9.939989e-01 7.766700e-02 7.703248e-02 -2.111193e+01 8.002149e-02 9.964009e-01 2.795927e-02 -4.983245e+00 -7.458373e-02 3.395574e-02 -9.966365e-01 2.744313e+02 +-9.937177e-01 7.283445e-02 8.497212e-02 -2.100190e+01 7.555378e-02 9.967131e-01 2.923372e-02 -4.965436e+00 -8.256361e-02 3.547002e-02 -9.959544e-01 2.732075e+02 +-9.936305e-01 6.923457e-02 8.890975e-02 -2.088617e+01 7.224505e-02 9.969020e-01 3.109654e-02 -4.946924e+00 -8.648135e-02 3.732176e-02 -9.955542e-01 2.719630e+02 +-9.937315e-01 6.743772e-02 8.916219e-02 -2.077685e+01 7.031330e-02 9.970883e-01 2.950970e-02 -4.927465e+00 -8.691252e-02 3.559400e-02 -9.955799e-01 2.707050e+02 +-9.940577e-01 6.528026e-02 8.710749e-02 -2.066591e+01 6.797206e-02 9.972858e-01 2.829890e-02 -4.906062e+00 -8.502371e-02 3.405161e-02 -9.957969e-01 2.694279e+02 +-9.943053e-01 6.465090e-02 8.471917e-02 -2.055522e+01 6.734172e-02 9.972998e-01 2.929534e-02 -4.883412e+00 -8.259645e-02 3.483364e-02 -9.959741e-01 2.681360e+02 +-9.945887e-01 6.358020e-02 8.216374e-02 -2.044759e+01 6.626821e-02 9.973383e-01 3.041031e-02 -4.861751e+00 -8.001156e-02 3.569059e-02 -9.961548e-01 2.668306e+02 +-9.949224e-01 6.316236e-02 7.835820e-02 -2.034586e+01 6.577420e-02 9.973463e-01 3.120866e-02 -4.838516e+00 -7.617905e-02 3.620413e-02 -9.964367e-01 2.655097e+02 +-9.954163e-01 6.153648e-02 7.321024e-02 -2.024967e+01 6.409009e-02 9.973965e-01 3.305593e-02 -4.817703e+00 -7.098549e-02 3.759645e-02 -9.967686e-01 2.641794e+02 +-9.958434e-01 6.098343e-02 6.765249e-02 -2.015628e+01 6.348814e-02 9.973506e-01 3.551046e-02 -4.799526e+00 -6.530771e-02 3.965798e-02 -9.970768e-01 2.628481e+02 +-9.962213e-01 6.036625e-02 6.244236e-02 -2.007085e+01 6.277692e-02 9.973269e-01 3.739114e-02 -4.780284e+00 -6.001828e-02 4.116978e-02 -9.973479e-01 2.615173e+02 +-9.965353e-01 6.012226e-02 5.746893e-02 -1.999327e+01 6.235652e-02 9.973338e-01 3.790726e-02 -4.760491e+00 -5.503663e-02 4.135948e-02 -9.976274e-01 2.601902e+02 +-9.968829e-01 5.910461e-02 5.226116e-02 -1.992130e+01 6.109617e-02 9.974321e-01 3.736753e-02 -4.738614e+00 -4.991837e-02 4.044400e-02 -9.979341e-01 2.588499e+02 +-9.972498e-01 5.752394e-02 4.673083e-02 -1.985530e+01 5.926837e-02 9.975620e-01 3.684197e-02 -4.717988e+00 -4.449761e-02 3.951030e-02 -9.982279e-01 2.575113e+02 +-9.975286e-01 5.689094e-02 4.123285e-02 -1.979675e+01 5.839868e-02 9.976319e-01 3.633289e-02 -4.696286e+00 -3.906820e-02 3.865103e-02 -9.984888e-01 2.561702e+02 +-9.977634e-01 5.628839e-02 3.605180e-02 -1.974591e+01 5.768839e-02 9.975707e-01 3.904651e-02 -4.673674e+00 -3.376635e-02 4.103895e-02 -9.985868e-01 2.548239e+02 +-9.978951e-01 5.674917e-02 3.138365e-02 -1.970344e+01 5.805626e-02 9.974110e-01 4.243589e-02 -4.648388e+00 -2.889419e-02 4.416857e-02 -9.986062e-01 2.534746e+02 +-9.979769e-01 5.761641e-02 2.687747e-02 -1.966817e+01 5.872767e-02 9.973659e-01 4.257070e-02 -4.618642e+00 -2.435391e-02 4.406302e-02 -9.987319e-01 2.521232e+02 +-9.979978e-01 5.887029e-02 2.312488e-02 -1.963934e+01 5.980328e-02 9.973274e-01 4.197085e-02 -4.586765e+00 -2.059224e-02 4.326976e-02 -9.988512e-01 2.507731e+02 +-9.980481e-01 5.913679e-02 2.007311e-02 -1.961368e+01 5.992960e-02 9.973393e-01 4.150632e-02 -4.556415e+00 -1.756515e-02 4.262827e-02 -9.989366e-01 2.494162e+02 +-9.980824e-01 5.943551e-02 1.729297e-02 -1.959029e+01 6.006154e-02 9.974609e-01 3.826697e-02 -4.529158e+00 -1.497464e-02 3.923223e-02 -9.991179e-01 2.480644e+02 +-9.981369e-01 5.919834e-02 1.477775e-02 -1.956928e+01 5.969545e-02 9.975733e-01 3.583310e-02 -4.501374e+00 -1.262063e-02 3.664849e-02 -9.992485e-01 2.467060e+02 +-9.982308e-01 5.812437e-02 1.252122e-02 -1.955134e+01 5.856403e-02 9.975526e-01 3.819790e-02 -4.473848e+00 -1.027035e-02 3.886361e-02 -9.991918e-01 2.453382e+02 +-9.981876e-01 5.921292e-02 1.073651e-02 -1.953800e+01 5.960278e-02 9.973957e-01 4.061157e-02 -4.445003e+00 -8.303821e-03 4.117788e-02 -9.991173e-01 2.439698e+02 +-9.981870e-01 5.937727e-02 9.849455e-03 -1.952666e+01 5.972852e-02 9.973989e-01 4.034601e-02 -4.411335e+00 -7.428201e-03 4.086115e-02 -9.991372e-01 2.425957e+02 +-9.981139e-01 6.061611e-02 9.718180e-03 -1.951383e+01 6.096378e-02 9.973087e-01 4.072748e-02 -4.378260e+00 -7.223285e-03 4.124311e-02 -9.991230e-01 2.412224e+02 +-9.980956e-01 6.087736e-02 9.953914e-03 -1.950318e+01 6.123455e-02 9.972920e-01 4.072925e-02 -4.346093e+00 -7.447471e-03 4.126120e-02 -9.991206e-01 2.398385e+02 +-9.979809e-01 6.267143e-02 1.031297e-02 -1.949325e+01 6.303017e-02 9.972411e-01 3.920854e-02 -4.316996e+00 -7.827265e-03 3.977940e-02 -9.991778e-01 2.384577e+02 +-9.978852e-01 6.405743e-02 1.103267e-02 -1.948099e+01 6.442804e-02 9.972225e-01 3.736653e-02 -4.286446e+00 -8.608427e-03 3.799832e-02 -9.992407e-01 2.370732e+02 +-9.977711e-01 6.561590e-02 1.214200e-02 -1.946668e+01 6.603224e-02 9.970998e-01 3.783881e-02 -4.255713e+00 -9.623957e-03 3.855623e-02 -9.992101e-01 2.356839e+02 +-9.977320e-01 6.601196e-02 1.316213e-02 -1.945014e+01 6.650327e-02 9.969333e-01 4.124696e-02 -4.223798e+00 -1.039897e-02 4.202873e-02 -9.990623e-01 2.342911e+02 +-9.977923e-01 6.485151e-02 1.431108e-02 -1.943040e+01 6.540146e-02 9.969723e-01 4.205776e-02 -4.186692e+00 -1.154024e-02 4.290086e-02 -9.990127e-01 2.328928e+02 +-9.978634e-01 6.355648e-02 1.513812e-02 -1.940660e+01 6.415142e-02 9.970246e-01 4.273659e-02 -4.152924e+00 -1.237689e-02 4.361641e-02 -9.989717e-01 2.314922e+02 +-9.979663e-01 6.174237e-02 1.585104e-02 -1.938129e+01 6.236575e-02 9.971515e-01 4.241971e-02 -4.121142e+00 -1.318680e-02 4.332199e-02 -9.989741e-01 2.300914e+02 +-9.980544e-01 6.016142e-02 1.637221e-02 -1.935555e+01 6.080140e-02 9.972703e-01 4.189278e-02 -4.091351e+00 -1.380719e-02 4.280672e-02 -9.989880e-01 2.286877e+02 +-9.980329e-01 6.046357e-02 1.656546e-02 -1.933238e+01 6.109387e-02 9.973047e-01 4.063085e-02 -4.061083e+00 -1.406413e-02 4.156297e-02 -9.990369e-01 2.272832e+02 +-9.980343e-01 6.040561e-02 1.669300e-02 -1.930936e+01 6.101503e-02 9.973827e-01 3.879221e-02 -4.031202e+00 -1.430604e-02 3.973447e-02 -9.991079e-01 2.258709e+02 +-9.979659e-01 6.149586e-02 1.680165e-02 -1.928821e+01 6.211767e-02 9.972907e-01 3.940344e-02 -4.003413e+00 -1.433298e-02 4.036697e-02 -9.990821e-01 2.244541e+02 +-9.979743e-01 6.125772e-02 1.717213e-02 -1.926526e+01 6.190904e-02 9.972645e-01 4.038287e-02 -3.975161e+00 -1.465140e-02 4.136416e-02 -9.990367e-01 2.230339e+02 +-9.979633e-01 6.139365e-02 1.732551e-02 -1.924098e+01 6.206277e-02 9.972230e-01 4.116377e-02 -3.945563e+00 -1.475020e-02 4.215519e-02 -9.990022e-01 2.216106e+02 +-9.980303e-01 6.028357e-02 1.736234e-02 -1.921490e+01 6.096642e-02 9.972587e-01 4.192965e-02 -3.915755e+00 -1.478708e-02 4.290557e-02 -9.989697e-01 2.201863e+02 +-9.979836e-01 6.110581e-02 1.716889e-02 -1.919066e+01 6.178213e-02 9.972016e-01 4.209496e-02 -3.884537e+00 -1.454860e-02 4.307080e-02 -9.989661e-01 2.187565e+02 +-9.980152e-01 6.056504e-02 1.725168e-02 -1.916474e+01 6.122045e-02 9.973062e-01 4.040353e-02 -3.851913e+00 -1.475817e-02 4.137948e-02 -9.990345e-01 2.173282e+02 +-9.979114e-01 6.221097e-02 1.739951e-02 -1.914051e+01 6.288757e-02 9.971574e-01 4.149915e-02 -3.816692e+00 -1.476835e-02 4.250668e-02 -9.989870e-01 2.158915e+02 +-9.978891e-01 6.255050e-02 1.745961e-02 -1.911492e+01 6.325307e-02 9.970663e-01 4.310101e-02 -3.783819e+00 -1.471241e-02 4.411439e-02 -9.989182e-01 2.144523e+02 +-9.978702e-01 6.285014e-02 1.745980e-02 -1.908395e+01 6.354393e-02 9.970727e-01 4.252177e-02 -3.744539e+00 -1.473619e-02 4.354066e-02 -9.989430e-01 2.130109e+02 +-9.978354e-01 6.341608e-02 1.740589e-02 -1.905320e+01 6.406733e-02 9.971504e-01 3.982862e-02 -3.706671e+00 -1.483052e-02 4.085755e-02 -9.990549e-01 2.115703e+02 +-9.978256e-01 6.360738e-02 1.726781e-02 -1.902208e+01 6.424687e-02 9.971551e-01 3.942191e-02 -3.670204e+00 -1.471116e-02 4.044559e-02 -9.990734e-01 2.101235e+02 +-9.978662e-01 6.293656e-02 1.737925e-02 -1.899038e+01 6.359881e-02 9.971484e-01 4.062271e-02 -3.634175e+00 -1.477303e-02 4.164132e-02 -9.990234e-01 2.086722e+02 +-9.978515e-01 6.318628e-02 1.731718e-02 -1.896021e+01 6.381415e-02 9.972195e-01 3.848408e-02 -3.596747e+00 -1.483736e-02 3.950647e-02 -9.991092e-01 2.072186e+02 +-9.979070e-01 6.225054e-02 1.750851e-02 -1.892786e+01 6.290267e-02 9.972355e-01 3.955449e-02 -3.559153e+00 -1.499782e-02 4.057303e-02 -9.990640e-01 2.057582e+02 +-9.979836e-01 6.106341e-02 1.732024e-02 -1.889614e+01 6.174706e-02 9.972015e-01 4.214746e-02 -3.524788e+00 -1.469810e-02 4.313194e-02 -9.989613e-01 2.042948e+02 +-9.980022e-01 6.077958e-02 1.724760e-02 -1.886476e+01 6.145568e-02 9.972328e-01 4.183091e-02 -3.487637e+00 -1.465741e-02 4.280730e-02 -9.989758e-01 2.028318e+02 +-9.979399e-01 6.177544e-02 1.731352e-02 -1.883712e+01 6.245196e-02 9.971756e-01 4.171989e-02 -3.453039e+00 -1.468736e-02 4.271520e-02 -9.989793e-01 2.013684e+02 +-9.979145e-01 6.217060e-02 1.736122e-02 -1.880904e+01 6.283352e-02 9.971945e-01 4.068185e-02 -3.419171e+00 -1.478330e-02 4.168787e-02 -9.990213e-01 1.999091e+02 +-9.978883e-01 6.268795e-02 1.700779e-02 -1.878081e+01 6.336644e-02 9.970713e-01 4.281826e-02 -3.384783e+00 -1.427379e-02 4.380556e-02 -9.989381e-01 1.984404e+02 +-9.979418e-01 6.201566e-02 1.631736e-02 -1.875193e+01 6.270247e-02 9.969889e-01 4.562410e-02 -3.350644e+00 -1.343882e-02 4.655333e-02 -9.988254e-01 1.969762e+02 +-9.980246e-01 6.093849e-02 1.527725e-02 -1.872357e+01 6.158334e-02 9.970387e-01 4.605726e-02 -3.313855e+00 -1.242535e-02 4.690710e-02 -9.988220e-01 1.955153e+02 +-9.980821e-01 6.026172e-02 1.416547e-02 -1.869718e+01 6.085354e-02 9.970899e-01 4.591840e-02 -3.276436e+00 -1.135713e-02 4.669235e-02 -9.988448e-01 1.940556e+02 +-9.981625e-01 5.910499e-02 1.334739e-02 -1.867123e+01 5.966629e-02 9.971332e-01 4.653246e-02 -3.241513e+00 -1.055882e-02 4.724334e-02 -9.988276e-01 1.926001e+02 +-9.981659e-01 5.927435e-02 1.230079e-02 -1.864803e+01 5.978183e-02 9.971469e-01 4.608906e-02 -3.205048e+00 -9.533794e-03 4.673989e-02 -9.988616e-01 1.911441e+02 +-9.981180e-01 6.024253e-02 1.146167e-02 -1.862849e+01 6.070015e-02 9.971421e-01 4.497873e-02 -3.170622e+00 -8.719279e-03 4.558980e-02 -9.989222e-01 1.896915e+02 +-9.980831e-01 6.092178e-02 1.089092e-02 -1.861037e+01 6.135043e-02 9.971150e-01 4.469666e-02 -3.138275e+00 -8.136504e-03 4.527914e-02 -9.989412e-01 1.882429e+02 +-9.980962e-01 6.079152e-02 1.041410e-02 -1.859411e+01 6.120405e-02 9.970925e-01 4.539418e-02 -3.107703e+00 -7.624245e-03 4.594513e-02 -9.989149e-01 1.867945e+02 +-9.981119e-01 6.067060e-02 9.575214e-03 -1.857686e+01 6.104037e-02 9.971314e-01 4.475472e-02 -3.075839e+00 -6.832451e-03 4.525469e-02 -9.989521e-01 1.853525e+02 +-9.981305e-01 6.044985e-02 9.023489e-03 -1.856047e+01 6.080123e-02 9.971000e-01 4.576877e-02 -3.044236e+00 -6.230606e-03 4.623184e-02 -9.989113e-01 1.839085e+02 +-9.981521e-01 6.018802e-02 8.358786e-03 -1.854600e+01 6.051800e-02 9.970409e-01 4.740273e-02 -3.011131e+00 -5.480976e-03 4.782098e-02 -9.988409e-01 1.824687e+02 +-9.981562e-01 6.026515e-02 7.227764e-03 -1.853340e+01 6.054472e-02 9.969979e-01 4.826398e-02 -2.977267e+00 -4.297430e-03 4.861259e-02 -9.988085e-01 1.810316e+02 +-9.981736e-01 6.018664e-02 5.196148e-03 -1.852315e+01 6.036427e-02 9.970785e-01 4.680433e-02 -2.942176e+00 -2.363972e-03 4.703251e-02 -9.988906e-01 1.796010e+02 +-9.981994e-01 5.989496e-02 3.239115e-03 -1.851524e+01 5.998059e-02 9.971416e-01 4.594386e-02 -2.908289e+00 -4.780511e-04 4.605541e-02 -9.989388e-01 1.781753e+02 +-9.981656e-01 6.053059e-02 1.230860e-03 -1.851072e+01 6.052063e-02 9.970345e-01 4.753230e-02 -2.873542e+00 1.649948e-03 4.751959e-02 -9.988690e-01 1.767507e+02 +-9.981132e-01 6.139777e-02 -6.649709e-04 -1.851025e+01 6.128967e-02 9.968915e-01 4.950552e-02 -2.838653e+00 3.702433e-03 4.937135e-02 -9.987736e-01 1.753373e+02 +-9.980410e-01 6.249892e-02 -2.828214e-03 -1.851326e+01 6.228811e-02 9.968739e-01 4.860683e-02 -2.803213e+00 5.857247e-03 4.833544e-02 -9.988140e-01 1.739296e+02 +-9.980241e-01 6.264693e-02 -4.814795e-03 -1.851829e+01 6.233951e-02 9.968673e-01 4.867634e-02 -2.769552e+00 7.849135e-03 4.828000e-02 -9.988030e-01 1.725375e+02 +-9.979973e-01 6.288849e-02 -6.819731e-03 -1.852671e+01 6.246779e-02 9.967776e-01 5.032034e-02 -2.736025e+00 9.962326e-03 4.979354e-02 -9.987099e-01 1.711562e+02 +-9.979751e-01 6.298205e-02 -8.889852e-03 -1.853710e+01 6.243942e-02 9.966994e-01 5.188039e-02 -2.701364e+00 1.212804e-02 5.122025e-02 -9.986137e-01 1.697919e+02 +-9.979020e-01 6.380086e-02 -1.100312e-02 -1.855169e+01 6.312875e-02 9.965812e-01 5.329817e-02 -2.666950e+00 1.436598e-02 5.249173e-02 -9.985180e-01 1.684471e+02 +-9.978659e-01 6.404682e-02 -1.271561e-02 -1.856810e+01 6.329804e-02 9.966148e-01 5.246113e-02 -2.633527e+00 1.603253e-02 5.154429e-02 -9.985420e-01 1.671265e+02 +-9.977830e-01 6.498793e-02 -1.434217e-02 -1.858704e+01 6.415141e-02 9.965519e-01 5.261987e-02 -2.599237e+00 1.771237e-02 5.158313e-02 -9.985116e-01 1.658218e+02 +-9.978216e-01 6.415528e-02 -1.536985e-02 -1.860503e+01 6.320942e-02 9.964465e-01 5.566746e-02 -2.565877e+00 1.888660e-02 5.457466e-02 -9.983311e-01 1.645390e+02 +-9.977857e-01 6.458454e-02 -1.589332e-02 -1.862542e+01 6.360871e-02 9.964188e-01 5.570958e-02 -2.533595e+00 1.943438e-02 5.457526e-02 -9.983205e-01 1.632792e+02 +-9.978070e-01 6.424039e-02 -1.594981e-02 -1.864444e+01 6.329955e-02 9.965447e-01 5.377561e-02 -2.502804e+00 1.934926e-02 5.264806e-02 -9.984257e-01 1.620471e+02 +-9.978557e-01 6.350305e-02 -1.585228e-02 -1.866211e+01 6.258130e-02 9.966264e-01 5.309807e-02 -2.473852e+00 1.917069e-02 5.199215e-02 -9.984635e-01 1.608371e+02 +-9.977987e-01 6.445013e-02 -1.561879e-02 -1.868207e+01 6.353464e-02 9.965528e-01 5.334611e-02 -2.447586e+00 1.900311e-02 5.223633e-02 -9.984539e-01 1.596532e+02 +-9.977964e-01 6.454058e-02 -1.538923e-02 -1.870043e+01 6.363878e-02 9.965513e-01 5.324983e-02 -2.422217e+00 1.877294e-02 5.215313e-02 -9.984626e-01 1.584929e+02 +-9.978310e-01 6.411174e-02 -1.493438e-02 -1.871715e+01 6.321650e-02 9.965262e-01 5.421489e-02 -2.396857e+00 1.835831e-02 5.315319e-02 -9.984176e-01 1.573598e+02 +-9.978108e-01 6.458533e-02 -1.422522e-02 -1.873344e+01 6.369579e-02 9.963979e-01 5.598298e-02 -2.370798e+00 1.778966e-02 5.495432e-02 -9.983304e-01 1.562503e+02 +-9.978577e-01 6.396917e-02 -1.370752e-02 -1.874892e+01 6.309175e-02 9.963799e-01 5.697798e-02 -2.347373e+00 1.730273e-02 5.599107e-02 -9.982813e-01 1.551689e+02 +-9.979400e-01 6.276388e-02 -1.328544e-02 -1.876231e+01 6.192651e-02 9.965023e-01 5.610902e-02 -2.322647e+00 1.676059e-02 5.517070e-02 -9.983363e-01 1.541173e+02 +-9.979074e-01 6.335877e-02 -1.290651e-02 -1.877790e+01 6.255920e-02 9.965231e-01 5.502748e-02 -2.297427e+00 1.634811e-02 5.410489e-02 -9.984014e-01 1.530881e+02 +-9.978925e-01 6.371756e-02 -1.227587e-02 -1.879239e+01 6.296793e-02 9.965540e-01 5.399154e-02 -2.274461e+00 1.567378e-02 5.310476e-02 -9.984659e-01 1.520873e+02 +-9.979567e-01 6.279238e-02 -1.181664e-02 -1.880437e+01 6.206699e-02 9.966055e-01 5.408376e-02 -2.252345e+00 1.517257e-02 5.323981e-02 -9.984665e-01 1.511111e+02 +-9.979125e-01 6.358313e-02 -1.130268e-02 -1.881642e+01 6.286866e-02 9.964982e-01 5.512573e-02 -2.230220e+00 1.476817e-02 5.430006e-02 -9.984155e-01 1.501621e+02 +-9.979340e-01 6.333791e-02 -1.077747e-02 -1.882738e+01 6.264382e-02 9.964792e-01 5.572195e-02 -2.209938e+00 1.426883e-02 5.493168e-02 -9.983882e-01 1.492397e+02 +-9.979186e-01 6.364182e-02 -1.040490e-02 -1.883766e+01 6.296500e-02 9.964479e-01 5.591984e-02 -2.187753e+00 1.392678e-02 5.514829e-02 -9.983811e-01 1.483393e+02 +-9.979103e-01 6.388396e-02 -9.686838e-03 -1.884754e+01 6.324257e-02 9.964140e-01 5.620877e-02 -2.164801e+00 1.324294e-02 5.547868e-02 -9.983721e-01 1.474612e+02 +-9.980088e-01 6.241967e-02 -9.070757e-03 -1.885476e+01 6.182043e-02 9.965290e-01 5.575081e-02 -2.144196e+00 1.251922e-02 5.507903e-02 -9.984035e-01 1.465989e+02 +-9.979514e-01 6.337055e-02 -8.787069e-03 -1.886279e+01 6.281443e-02 9.965962e-01 5.338806e-02 -2.123511e+00 1.214039e-02 5.272673e-02 -9.985352e-01 1.457538e+02 +-9.977615e-01 6.631953e-02 -8.591413e-03 -1.887376e+01 6.579673e-02 9.965214e-01 5.114550e-02 -2.100874e+00 1.195347e-02 5.046571e-02 -9.986543e-01 1.449223e+02 +-9.976722e-01 6.770280e-02 -8.158376e-03 -1.888239e+01 6.721185e-02 9.964784e-01 5.013280e-02 -2.078341e+00 1.152378e-02 4.946775e-02 -9.987092e-01 1.441037e+02 +-9.977489e-01 6.655102e-02 -8.249246e-03 -1.888627e+01 6.605312e-02 9.965391e-01 5.046446e-02 -2.059412e+00 1.157916e-02 4.980597e-02 -9.986918e-01 1.433024e+02 +-9.977372e-01 6.676070e-02 -7.968624e-03 -1.889195e+01 6.628102e-02 9.965441e-01 5.006705e-02 -2.042113e+00 1.128360e-02 4.942558e-02 -9.987141e-01 1.425198e+02 +-9.975890e-01 6.895791e-02 -7.812209e-03 -1.890126e+01 6.850400e-02 9.964848e-01 4.821970e-02 -2.022990e+00 1.110988e-02 4.756826e-02 -9.988062e-01 1.417522e+02 +-9.975489e-01 6.952911e-02 -7.865364e-03 -1.890872e+01 6.907921e-02 9.964759e-01 4.757852e-02 -2.005121e+00 1.114574e-02 4.691856e-02 -9.988365e-01 1.409929e+02 +-9.975675e-01 6.921825e-02 -8.246384e-03 -1.891348e+01 6.874303e-02 9.964668e-01 4.825259e-02 -1.989403e+00 1.155721e-02 4.756833e-02 -9.988011e-01 1.402422e+02 +-9.975578e-01 6.928915e-02 -8.804152e-03 -1.891945e+01 6.877575e-02 9.964180e-01 4.920408e-02 -1.974562e+00 1.218193e-02 4.847839e-02 -9.987500e-01 1.394994e+02 +-9.975003e-01 7.004178e-02 -9.344217e-03 -1.892677e+01 6.950735e-02 9.963904e-01 4.873287e-02 -1.960534e+00 1.272383e-02 4.796155e-02 -9.987681e-01 1.387654e+02 +-9.973998e-01 7.138826e-02 -9.870739e-03 -1.893511e+01 7.083934e-02 9.963412e-01 4.781246e-02 -1.944374e+00 1.324787e-02 4.698889e-02 -9.988076e-01 1.380440e+02 +-9.973117e-01 7.254798e-02 -1.030340e-02 -1.894438e+01 7.199175e-02 9.963078e-01 4.677424e-02 -1.928158e+00 1.365873e-02 4.590674e-02 -9.988524e-01 1.373298e+02 +-9.972044e-01 7.397922e-02 -1.050948e-02 -1.895464e+01 7.344019e-02 9.962952e-01 4.474853e-02 -1.914991e+00 1.378100e-02 4.385160e-02 -9.989430e-01 1.366214e+02 +-9.971650e-01 7.444601e-02 -1.094780e-02 -1.896431e+01 7.391846e-02 9.963560e-01 4.255269e-02 -1.905325e+00 1.407579e-02 4.162280e-02 -9.990343e-01 1.359170e+02 +-9.970785e-01 7.547934e-02 -1.171689e-02 -1.897372e+01 7.495188e-02 9.963712e-01 4.033118e-02 -1.895274e+00 1.471854e-02 3.933514e-02 -9.991177e-01 1.352161e+02 +-9.971856e-01 7.395330e-02 -1.232253e-02 -1.897911e+01 7.343605e-02 9.965695e-01 3.816268e-02 -1.881347e+00 1.510252e-02 3.715035e-02 -9.991956e-01 1.345169e+02 +-9.973118e-01 7.212608e-02 -1.292720e-02 -1.898311e+01 7.160974e-02 9.967560e-01 3.673587e-02 -1.867920e+00 1.553488e-02 3.571140e-02 -9.992414e-01 1.338197e+02 +-9.972392e-01 7.305818e-02 -1.328370e-02 -1.899097e+01 7.250962e-02 9.966464e-01 3.792354e-02 -1.854861e+00 1.600977e-02 3.685564e-02 -9.991924e-01 1.331238e+02 +-9.969964e-01 7.628375e-02 -1.338041e-02 -1.900389e+01 7.568349e-02 9.962988e-01 4.075101e-02 -1.839020e+00 1.643953e-02 3.961593e-02 -9.990797e-01 1.324286e+02 +-9.972662e-01 7.258449e-02 -1.384022e-02 -1.900820e+01 7.197070e-02 9.965790e-01 4.062510e-02 -1.829069e+00 1.674163e-02 3.951794e-02 -9.990786e-01 1.317402e+02 +-9.976670e-01 6.672033e-02 -1.445388e-02 -1.900738e+01 6.612293e-02 9.970693e-01 3.847781e-02 -1.823556e+00 1.697877e-02 3.743230e-02 -9.991549e-01 1.310599e+02 +-9.978507e-01 6.392978e-02 -1.438580e-02 -1.901169e+01 6.341152e-02 9.974086e-01 3.398530e-02 -1.813487e+00 1.652119e-02 3.300002e-02 -9.993188e-01 1.303774e+02 +-9.975954e-01 6.779486e-02 -1.439440e-02 -1.902656e+01 6.741042e-02 9.973943e-01 2.569738e-02 -1.799997e+00 1.609904e-02 2.466525e-02 -9.995661e-01 1.296926e+02 +-9.978503e-01 6.391429e-02 -1.448441e-02 -1.902976e+01 6.355878e-02 9.976941e-01 2.380369e-02 -1.790406e+00 1.597241e-02 2.283191e-02 -9.996117e-01 1.289952e+02 +-9.981713e-01 5.886338e-02 -1.375146e-02 -1.902968e+01 5.849225e-02 9.979494e-01 2.599102e-02 -1.783236e+00 1.525318e-02 2.513913e-02 -9.995676e-01 1.282867e+02 +-9.983442e-01 5.605760e-02 -1.290253e-02 -1.903291e+01 5.566152e-02 9.980212e-01 2.924615e-02 -1.773597e+00 1.451647e-02 2.847955e-02 -9.994890e-01 1.275639e+02 +-9.984597e-01 5.433894e-02 -1.119994e-02 -1.903689e+01 5.395501e-02 9.980264e-01 3.212621e-02 -1.762349e+00 1.292355e-02 3.147243e-02 -9.994211e-01 1.268317e+02 +-9.984842e-01 5.425734e-02 -9.241762e-03 -1.904093e+01 5.392233e-02 9.979899e-01 3.329493e-02 -1.751742e+00 1.102968e-02 3.274612e-02 -9.994028e-01 1.260904e+02 +-9.985180e-01 5.404950e-02 -6.367162e-03 -1.904310e+01 5.381617e-02 9.980248e-01 3.240933e-02 -1.739549e+00 8.106295e-03 3.201864e-02 -9.994544e-01 1.253386e+02 +-9.985829e-01 5.314164e-02 -2.856048e-03 -1.904060e+01 5.303145e-02 9.981356e-01 3.021352e-02 -1.721883e+00 4.456320e-03 3.001924e-02 -9.995394e-01 1.245754e+02 +-9.986914e-01 5.114192e-02 1.777954e-04 -1.903398e+01 5.112396e-02 9.982351e-01 3.021532e-02 -1.704964e+00 1.367788e-03 3.018486e-02 -9.995434e-01 1.237928e+02 +-9.987542e-01 4.977001e-02 3.598165e-03 -1.902609e+01 4.986262e-02 9.981972e-01 3.340552e-02 -1.689113e+00 -1.929086e-03 3.354331e-02 -9.994354e-01 1.229911e+02 +-9.987317e-01 4.982558e-02 7.236706e-03 -1.901737e+01 5.006679e-02 9.980140e-01 3.822849e-02 -1.671608e+00 -5.317577e-03 3.854232e-02 -9.992428e-01 1.221724e+02 +-9.986218e-01 5.138803e-02 1.067010e-02 -1.900788e+01 5.178354e-02 9.978218e-01 4.086713e-02 -1.651373e+00 -8.546777e-03 4.136333e-02 -9.991076e-01 1.213372e+02 +-9.985047e-01 5.273051e-02 1.441749e-02 -1.899551e+01 5.328616e-02 9.977232e-01 4.133871e-02 -1.630463e+00 -1.220485e-02 4.204515e-02 -9.990412e-01 1.204889e+02 +-9.983512e-01 5.446804e-02 1.811322e-02 -1.898110e+01 5.515388e-02 9.976840e-01 3.980659e-02 -1.606831e+00 -1.590309e-02 4.073996e-02 -9.990432e-01 1.196223e+02 +-9.981926e-01 5.585162e-02 2.218268e-02 -1.896236e+01 5.664881e-02 9.977046e-01 3.710050e-02 -1.583863e+00 -2.005964e-02 3.829006e-02 -9.990653e-01 1.187404e+02 +-9.979786e-01 5.798391e-02 2.601031e-02 -1.894089e+01 5.889822e-02 9.976189e-01 3.588194e-02 -1.562360e+00 -2.386780e-02 3.734136e-02 -9.990175e-01 1.178410e+02 +-9.977965e-01 5.912120e-02 3.011254e-02 -1.891249e+01 6.019304e-02 9.975364e-01 3.602611e-02 -1.539442e+00 -2.790845e-02 3.775929e-02 -9.988971e-01 1.169209e+02 +-9.975845e-01 6.049776e-02 3.413533e-02 -1.888164e+01 6.178455e-02 9.973661e-01 3.799211e-02 -1.518580e+00 -3.174699e-02 4.000937e-02 -9.986948e-01 1.159843e+02 +-9.973475e-01 6.170899e-02 3.859965e-02 -1.884566e+01 6.325193e-02 9.971910e-01 4.011660e-02 -1.495740e+00 -3.601567e-02 4.245168e-02 -9.984492e-01 1.150276e+02 +-9.969923e-01 6.466589e-02 4.271621e-02 -1.880738e+01 6.636739e-02 9.970054e-01 3.969254e-02 -1.472691e+00 -4.002154e-02 4.240812e-02 -9.982985e-01 1.140573e+02 +-9.966944e-01 6.618328e-02 4.711763e-02 -1.876261e+01 6.797479e-02 9.969823e-01 3.749143e-02 -1.449607e+00 -4.449414e-02 4.057031e-02 -9.981855e-01 1.130721e+02 +-9.964201e-01 6.734609e-02 5.110368e-02 -1.871096e+01 6.912801e-02 9.970303e-01 3.393931e-02 -1.425819e+00 -4.866624e-02 3.735050e-02 -9.981165e-01 1.120705e+02 +-9.961594e-01 6.817787e-02 5.493905e-02 -1.865467e+01 7.001165e-02 9.970272e-01 3.217295e-02 -1.402779e+00 -5.258225e-02 3.589575e-02 -9.979713e-01 1.110501e+02 +-9.960060e-01 6.805744e-02 5.779571e-02 -1.859273e+01 6.999691e-02 9.970267e-01 3.222097e-02 -1.382089e+00 -5.543099e-02 3.613779e-02 -9.978083e-01 1.100104e+02 +-9.958875e-01 6.818637e-02 5.965418e-02 -1.852665e+01 7.016921e-02 9.970281e-01 3.179804e-02 -1.362588e+00 -5.730871e-02 3.585316e-02 -9.977125e-01 1.089547e+02 +-9.959013e-01 6.726601e-02 6.046367e-02 -1.845845e+01 6.913180e-02 9.971768e-01 2.931225e-02 -1.343346e+00 -5.832126e-02 3.337206e-02 -9.977399e-01 1.078847e+02 +-9.959161e-01 6.684999e-02 6.068136e-02 -1.838974e+01 6.854367e-02 9.973022e-01 2.626971e-02 -1.326090e+00 -5.876152e-02 3.032174e-02 -9.978115e-01 1.067965e+02 +-9.957873e-01 6.896935e-02 6.042233e-02 -1.832377e+01 7.046992e-02 9.972472e-01 2.306330e-02 -1.307555e+00 -5.866535e-02 2.722410e-02 -9.979064e-01 1.056929e+02 +-9.957182e-01 7.035410e-02 5.996276e-02 -1.825676e+01 7.202398e-02 9.970599e-01 2.615479e-02 -1.288139e+00 -5.794637e-02 3.036155e-02 -9.978579e-01 1.045622e+02 +-9.957664e-01 6.972792e-02 5.989481e-02 -1.818725e+01 7.177999e-02 9.968804e-01 3.281891e-02 -1.269054e+00 -5.741957e-02 3.697921e-02 -9.976650e-01 1.034111e+02 +-9.957485e-01 7.024849e-02 5.958279e-02 -1.811737e+01 7.242159e-02 9.967552e-01 3.512959e-02 -1.244731e+00 -5.692166e-02 3.929531e-02 -9.976050e-01 1.022464e+02 +-9.958391e-01 6.940797e-02 5.905071e-02 -1.804504e+01 7.142824e-02 9.969058e-01 3.281588e-02 -1.219976e+00 -5.659031e-02 3.689722e-02 -9.977155e-01 1.010740e+02 +-9.959458e-01 6.860165e-02 5.818689e-02 -1.797200e+01 7.049533e-02 9.970259e-01 3.113907e-02 -1.195663e+00 -5.587765e-02 3.511473e-02 -9.978200e-01 9.988171e+01 +-9.960716e-01 6.720884e-02 5.765755e-02 -1.789756e+01 6.911570e-02 9.971036e-01 3.173886e-02 -1.172886e+00 -5.535743e-02 3.559921e-02 -9.978318e-01 9.867175e+01 +-9.960935e-01 6.714465e-02 5.735214e-02 -1.782503e+01 6.900526e-02 9.971314e-01 3.109974e-02 -1.151222e+00 -5.509945e-02 3.493584e-02 -9.978695e-01 9.744780e+01 +-9.960740e-01 6.802731e-02 5.664779e-02 -1.775374e+01 6.981702e-02 9.971015e-01 3.023529e-02 -1.126795e+00 -5.442678e-02 3.407156e-02 -9.979363e-01 9.620855e+01 +-9.961179e-01 6.826950e-02 5.557284e-02 -1.768421e+01 7.018436e-02 9.969792e-01 3.326451e-02 -1.102525e+00 -5.313402e-02 3.703571e-02 -9.979004e-01 9.495275e+01 +-9.962900e-01 6.700916e-02 5.400000e-02 -1.761270e+01 6.900179e-02 9.969696e-01 3.591986e-02 -1.077492e+00 -5.142940e-02 3.951269e-02 -9.978947e-01 9.367749e+01 +-9.964260e-01 6.652959e-02 5.204775e-02 -1.754366e+01 6.834552e-02 9.970848e-01 3.392240e-02 -1.049972e+00 -4.963918e-02 3.735839e-02 -9.980683e-01 9.239323e+01 +-9.965975e-01 6.582485e-02 4.960385e-02 -1.747710e+01 6.755603e-02 9.971336e-01 3.406954e-02 -1.022258e+00 -4.721905e-02 3.730465e-02 -9.981877e-01 9.109028e+01 +-9.969251e-01 6.271703e-02 4.697842e-02 -1.740999e+01 6.433236e-02 9.973594e-01 3.369840e-02 -9.990056e-01 -4.474091e-02 3.661701e-02 -9.983273e-01 8.977477e+01 +-9.969195e-01 6.515997e-02 4.365506e-02 -1.735065e+01 6.625060e-02 9.975139e-01 2.401804e-02 -9.753403e-01 -4.198151e-02 2.683622e-02 -9.987579e-01 8.845413e+01 +-9.970342e-01 6.521848e-02 4.085759e-02 -1.729334e+01 6.606948e-02 9.976178e-01 1.983445e-02 -9.584784e-01 -3.946669e-02 2.247507e-02 -9.989681e-01 8.710974e+01 +-9.971387e-01 6.512979e-02 3.837386e-02 -1.723975e+01 6.622563e-02 9.974114e-01 2.801191e-02 -9.440549e-01 -3.645012e-02 3.047309e-02 -9.988708e-01 8.573751e+01 +-9.972765e-01 6.440234e-02 3.594408e-02 -1.718834e+01 6.565620e-02 9.972330e-01 3.486590e-02 -9.218292e-01 -3.359918e-02 3.713089e-02 -9.987454e-01 8.435171e+01 +-9.974248e-01 6.351723e-02 3.330578e-02 -1.713847e+01 6.469622e-02 9.972697e-01 3.560305e-02 -8.925921e-01 -3.095344e-02 3.766612e-02 -9.988109e-01 8.295643e+01 +-9.975580e-01 6.267214e-02 3.082569e-02 -1.709087e+01 6.370436e-02 9.973987e-01 3.372697e-02 -8.621183e-01 -2.863177e-02 3.560833e-02 -9.989556e-01 8.155322e+01 +-9.976284e-01 6.267509e-02 2.845103e-02 -1.704828e+01 6.360032e-02 9.974340e-01 3.287022e-02 -8.330614e-01 -2.631789e-02 3.460175e-02 -9.990546e-01 8.012646e+01 +-9.976295e-01 6.355908e-02 2.637506e-02 -1.700912e+01 6.442637e-02 9.973617e-01 3.344957e-02 -8.053784e-01 -2.417945e-02 3.506952e-02 -9.990923e-01 7.868382e+01 +-9.975669e-01 6.527738e-02 2.447775e-02 -1.697362e+01 6.608274e-02 9.972456e-01 3.367740e-02 -7.771295e-01 -2.221196e-02 3.521301e-02 -9.991330e-01 7.722778e+01 +-9.975918e-01 6.557428e-02 2.259907e-02 -1.693890e+01 6.634811e-02 9.971689e-01 3.538530e-02 -7.478602e-01 -2.021473e-02 3.679948e-02 -9.991182e-01 7.575752e+01 +-9.976851e-01 6.486008e-02 2.043580e-02 -1.690538e+01 6.559901e-02 9.971283e-01 3.784062e-02 -7.187593e-01 -1.792277e-02 3.909359e-02 -9.990748e-01 7.428435e+01 +-9.978054e-01 6.360369e-02 1.841371e-02 -1.687364e+01 6.431232e-02 9.970930e-01 4.085889e-02 -6.886180e-01 -1.576141e-02 4.195344e-02 -9.989952e-01 7.280871e+01 +-9.979080e-01 6.251511e-02 1.647835e-02 -1.684487e+01 6.319263e-02 9.970119e-01 4.442788e-02 -6.588975e-01 -1.365170e-02 4.537624e-02 -9.988767e-01 7.133452e+01 +-9.978971e-01 6.311226e-02 1.477133e-02 -1.682112e+01 6.372435e-02 9.969308e-01 4.547777e-02 -6.266962e-01 -1.185579e-02 4.632342e-02 -9.988561e-01 6.986187e+01 +-9.979116e-01 6.318727e-02 1.341194e-02 -1.679851e+01 6.372374e-02 9.969847e-01 4.428062e-02 -5.936207e-01 -1.057353e-02 4.504280e-02 -9.989291e-01 6.839401e+01 +-9.978895e-01 6.378877e-02 1.214630e-02 -1.677917e+01 6.425981e-02 9.969876e-01 4.343333e-02 -5.617780e-01 -9.339152e-03 4.412217e-02 -9.989825e-01 6.692462e+01 +-9.978970e-01 6.384617e-02 1.119383e-02 -1.676019e+01 6.427768e-02 9.969732e-01 4.373517e-02 -5.300473e-01 -8.367630e-03 4.436270e-02 -9.989805e-01 6.545693e+01 +-9.979650e-01 6.289225e-02 1.050772e-02 -1.674127e+01 6.330122e-02 9.969954e-01 4.464301e-02 -4.983233e-01 -7.668450e-03 4.521730e-02 -9.989478e-01 6.398723e+01 +-9.979850e-01 6.268201e-02 9.846620e-03 -1.672374e+01 6.305887e-02 9.970263e-01 4.429629e-02 -4.662392e-01 -7.040759e-03 4.482794e-02 -9.989699e-01 6.252254e+01 +-9.979786e-01 6.289153e-02 9.134442e-03 -1.670738e+01 6.321917e-02 9.971310e-01 4.162906e-02 -4.342216e-01 -6.490121e-03 4.212238e-02 -9.990914e-01 6.105928e+01 +-9.979294e-01 6.371530e-02 8.792446e-03 -1.669261e+01 6.403372e-02 9.970382e-01 4.259535e-02 -4.028967e-01 -6.052430e-03 4.307016e-02 -9.990537e-01 5.958850e+01 +-9.979020e-01 6.413386e-02 8.856182e-03 -1.667728e+01 6.448055e-02 9.968145e-01 4.693768e-02 -3.696661e-01 -5.817677e-03 4.741025e-02 -9.988586e-01 5.811853e+01 +-9.978853e-01 6.435988e-02 9.102137e-03 -1.666067e+01 6.473547e-02 9.966556e-01 4.986952e-02 -3.318750e-01 -5.862100e-03 5.035328e-02 -9.987143e-01 5.665100e+01 +-9.979060e-01 6.393729e-02 9.782009e-03 -1.664289e+01 6.434367e-02 9.967110e-01 4.926561e-02 -2.928006e-01 -6.599927e-03 4.979185e-02 -9.987378e-01 5.518855e+01 +-9.978806e-01 6.419216e-02 1.066157e-02 -1.662286e+01 6.461413e-02 9.968685e-01 4.558632e-02 -2.553499e-01 -7.701897e-03 4.617858e-02 -9.989035e-01 5.373519e+01 +-9.979451e-01 6.305049e-02 1.141465e-02 -1.660088e+01 6.347813e-02 9.970958e-01 4.207638e-02 -2.238776e-01 -8.728561e-03 4.271449e-02 -9.990492e-01 5.227704e+01 +-9.979482e-01 6.286691e-02 1.213446e-02 -1.657777e+01 6.331780e-02 9.971398e-01 4.126693e-02 -1.950878e-01 -9.505430e-03 4.195058e-02 -9.990745e-01 5.082074e+01 +-9.979863e-01 6.211617e-02 1.284571e-02 -1.655446e+01 6.261289e-02 9.971209e-01 4.277342e-02 -1.667537e-01 -1.015181e-02 4.349158e-02 -9.990022e-01 4.936683e+01 +-9.979048e-01 6.325124e-02 1.361522e-02 -1.653154e+01 6.380973e-02 9.969250e-01 4.548331e-02 -1.361189e-01 -1.069648e-02 4.625679e-02 -9.988723e-01 4.791138e+01 +-9.979337e-01 6.261598e-02 1.440877e-02 -1.650590e+01 6.325091e-02 9.967987e-01 4.890476e-02 -1.018661e-01 -1.130042e-02 4.971507e-02 -9.986995e-01 4.646111e+01 +-9.980279e-01 6.102909e-02 1.468729e-02 -1.647825e+01 6.168075e-02 9.968925e-01 4.899851e-02 -6.682977e-02 -1.165131e-02 4.980779e-02 -9.986909e-01 4.501382e+01 +-9.980346e-01 6.096175e-02 1.451392e-02 -1.645171e+01 6.155180e-02 9.971141e-01 4.443839e-02 -3.390796e-02 -1.176299e-02 4.524440e-02 -9.989067e-01 4.357573e+01 +-9.980527e-01 6.078660e-02 1.399326e-02 -1.642535e+01 6.131456e-02 9.972746e-01 4.103506e-02 -4.286154e-03 -1.146074e-02 4.181313e-02 -9.990597e-01 4.213696e+01 +-9.980190e-01 6.143993e-02 1.353255e-02 -1.640183e+01 6.195427e-02 9.972118e-01 4.159547e-02 2.267275e-02 -1.093920e-02 4.235146e-02 -9.990429e-01 4.069789e+01 +-9.979471e-01 6.264033e-02 1.333417e-02 -1.638003e+01 6.317701e-02 9.970059e-01 4.458515e-02 5.139880e-02 -1.050142e-02 4.533603e-02 -9.989166e-01 3.926177e+01 +-9.979832e-01 6.213644e-02 1.298538e-02 -1.635679e+01 6.267273e-02 9.969707e-01 4.605970e-02 8.060552e-02 -1.008406e-02 4.678063e-02 -9.988543e-01 3.782483e+01 +-9.980653e-01 6.094545e-02 1.229859e-02 -1.633245e+01 6.143728e-02 9.971125e-01 4.463312e-02 1.118254e-01 -9.542891e-03 4.530235e-02 -9.989277e-01 3.639684e+01 +-9.981822e-01 5.912608e-02 1.168322e-02 -1.630758e+01 5.958615e-02 9.972525e-01 4.401012e-02 1.414094e-01 -9.048970e-03 4.462627e-02 -9.989628e-01 3.497003e+01 +-9.982400e-01 5.825875e-02 1.108149e-02 -1.628474e+01 5.868661e-02 9.973376e-01 4.328518e-02 1.706823e-01 -8.530246e-03 4.385933e-02 -9.990013e-01 3.354441e+01 +-9.981956e-01 5.907366e-02 1.076243e-02 -1.626400e+01 5.947831e-02 9.973349e-01 4.225277e-02 1.998713e-01 -8.237723e-03 4.281666e-02 -9.990490e-01 3.212471e+01 +-9.980851e-01 6.093635e-02 1.062518e-02 -1.624608e+01 6.133212e-02 9.972300e-01 4.207949e-02 2.279988e-01 -8.031575e-03 4.265057e-02 -9.990578e-01 3.070783e+01 +-9.979286e-01 6.345056e-02 1.061285e-02 -1.622987e+01 6.385518e-02 9.970088e-01 4.354314e-02 2.572810e-01 -7.818268e-03 4.413062e-02 -9.989952e-01 2.928474e+01 +-9.978948e-01 6.398418e-02 1.057938e-02 -1.621276e+01 6.439424e-02 9.969318e-01 4.450035e-02 2.860073e-01 -7.699599e-03 4.508792e-02 -9.989534e-01 2.786760e+01 +-9.978945e-01 6.400279e-02 1.049413e-02 -1.619488e+01 6.439883e-02 9.969898e-01 4.317492e-02 3.156601e-01 -7.699227e-03 4.375982e-02 -9.990124e-01 2.645737e+01 +-9.979995e-01 6.240263e-02 1.014253e-02 -1.617482e+01 6.278443e-02 9.970946e-01 4.313270e-02 3.455316e-01 -7.421471e-03 4.368320e-02 -9.990179e-01 2.505017e+01 +-9.981263e-01 6.041187e-02 9.715641e-03 -1.615363e+01 6.077779e-02 9.972130e-01 4.326857e-02 3.743586e-01 -7.074629e-03 4.377798e-02 -9.990162e-01 2.364610e+01 +-9.981867e-01 5.945625e-02 9.394593e-03 -1.613407e+01 5.980790e-02 9.972786e-01 4.310881e-02 4.041376e-01 -6.805939e-03 4.359250e-02 -9.990262e-01 2.224839e+01 +-9.981998e-01 5.925734e-02 9.260632e-03 -1.611623e+01 5.961225e-02 9.972315e-01 4.444893e-02 4.323654e-01 -6.601068e-03 4.492095e-02 -9.989687e-01 2.085659e+01 +-9.981502e-01 6.010732e-02 9.123937e-03 -1.610044e+01 6.045769e-02 9.971637e-01 4.482651e-02 4.615578e-01 -6.403658e-03 4.529519e-02 -9.989531e-01 1.947255e+01 +-9.980702e-01 6.144745e-02 8.945937e-03 -1.608658e+01 6.179252e-02 9.970517e-01 4.549194e-02 4.926781e-01 -6.124199e-03 4.595694e-02 -9.989247e-01 1.808843e+01 +-9.980492e-01 6.178748e-02 8.949430e-03 -1.607258e+01 6.213921e-02 9.969782e-01 4.661700e-02 5.236603e-01 -6.042040e-03 4.708216e-02 -9.988728e-01 1.670842e+01 +-9.980720e-01 6.147985e-02 8.521729e-03 -1.605730e+01 6.179773e-02 9.971113e-01 4.415916e-02 5.539333e-01 -5.782215e-03 4.460063e-02 -9.989882e-01 1.533299e+01 +-9.982061e-01 5.935397e-02 7.858637e-03 -1.604039e+01 5.962051e-02 9.974311e-01 3.970658e-02 5.822458e-01 -5.481706e-03 4.010388e-02 -9.991805e-01 1.396230e+01 +-9.984388e-01 5.533209e-02 7.635271e-03 -1.601956e+01 5.558142e-02 9.977448e-01 3.763058e-02 6.052059e-01 -5.535874e-03 3.799620e-02 -9.992626e-01 1.259501e+01 +-9.986130e-01 5.206469e-02 7.830086e-03 -1.599987e+01 5.233384e-02 9.978530e-01 3.937758e-02 6.277813e-01 -5.763094e-03 3.973274e-02 -9.991937e-01 1.122152e+01 +-9.986657e-01 5.099182e-02 8.161612e-03 -1.598184e+01 5.129300e-02 9.977852e-01 4.235195e-02 6.536360e-01 -5.983933e-03 4.271407e-02 -9.990694e-01 9.852998e+00 +-9.986022e-01 5.221129e-02 8.223331e-03 -1.596753e+01 5.252303e-02 9.976560e-01 4.386144e-02 6.821976e-01 -5.913994e-03 4.423204e-02 -9.990038e-01 8.487382e+00 +-9.983719e-01 5.637386e-02 8.693603e-03 -1.595764e+01 5.671841e-02 9.973086e-01 4.646100e-02 7.126679e-01 -6.051019e-03 4.687843e-02 -9.988823e-01 7.122797e+00 +-9.980954e-01 6.101955e-02 9.065314e-03 -1.594956e+01 6.138594e-02 9.969603e-01 4.797761e-02 7.443265e-01 -6.110186e-03 4.844271e-02 -9.988073e-01 5.763789e+00 +-9.979395e-01 6.350818e-02 9.133854e-03 -1.593877e+01 6.386991e-02 9.968446e-01 4.713245e-02 7.787213e-01 -6.111738e-03 4.761871e-02 -9.988469e-01 4.400318e+00 +-9.978490e-01 6.489754e-02 9.256706e-03 -1.592590e+01 6.524991e-02 9.968564e-01 4.494122e-02 8.125999e-01 -6.311033e-03 4.544854e-02 -9.989468e-01 3.038918e+00 +-9.978945e-01 6.425028e-02 8.864203e-03 -1.590918e+01 6.456916e-02 9.970187e-01 4.224322e-02 8.446651e-01 -6.123639e-03 4.272662e-02 -9.990680e-01 1.676097e+00 +-9.980357e-01 6.206958e-02 8.496662e-03 -1.588963e+01 6.237150e-02 9.971814e-01 4.170102e-02 8.754178e-01 -5.884349e-03 4.214905e-02 -9.990940e-01 3.089439e-01 +-9.981426e-01 6.035870e-02 8.262218e-03 -1.587121e+01 6.065482e-02 9.972680e-01 4.215947e-02 9.045038e-01 -5.694956e-03 4.258229e-02 -9.990767e-01 -1.063172e+00 +-9.981915e-01 5.958268e-02 7.982717e-03 -1.585397e+01 5.986557e-02 9.973312e-01 4.179185e-02 9.332548e-01 -5.471342e-03 4.219415e-02 -9.990945e-01 -2.436523e+00 +-9.981810e-01 5.978109e-02 7.806611e-03 -1.583843e+01 6.004647e-02 9.973962e-01 3.993950e-02 9.601236e-01 -5.398658e-03 4.033560e-02 -9.991716e-01 -3.813595e+00 +-9.982110e-01 5.929823e-02 7.650330e-03 -1.582320e+01 5.955514e-02 9.974449e-01 3.945702e-02 9.870965e-01 -5.291051e-03 3.984204e-02 -9.991920e-01 -5.192326e+00 +-9.982221e-01 5.911473e-02 7.621830e-03 -1.580825e+01 5.937414e-02 9.974291e-01 4.012206e-02 1.014088e+00 -5.230431e-03 4.050326e-02 -9.991657e-01 -6.576470e+00 +-9.982980e-01 5.783633e-02 7.488140e-03 -1.579123e+01 5.808934e-02 9.975203e-01 3.973480e-02 1.041956e+00 -5.171457e-03 4.010214e-02 -9.991822e-01 -7.966034e+00 +-9.984120e-01 5.589645e-02 7.002522e-03 -1.577390e+01 5.613218e-02 9.976267e-01 3.987574e-02 1.070725e+00 -4.756991e-03 4.020548e-02 -9.991801e-01 -9.357139e+00 +-9.985480e-01 5.343326e-02 6.838777e-03 -1.575586e+01 5.367726e-02 9.976462e-01 4.267025e-02 1.100590e+00 -4.542669e-03 4.297538e-02 -9.990658e-01 -1.075522e+01 +-9.986392e-01 5.173857e-02 6.549272e-03 -1.573852e+01 5.197258e-02 9.977273e-01 4.288286e-02 1.129671e+00 -4.315691e-03 4.316488e-02 -9.990587e-01 -1.214993e+01 +-9.986651e-01 5.129537e-02 6.064406e-03 -1.572233e+01 5.149608e-02 9.978863e-01 3.963645e-02 1.159922e+00 -4.018422e-03 3.989583e-02 -9.991958e-01 -1.354746e+01 +-9.987259e-01 5.009593e-02 6.075486e-03 -1.570577e+01 5.029395e-02 9.979864e-01 3.864713e-02 1.188722e+00 -4.127190e-03 3.890344e-02 -9.992345e-01 -1.495103e+01 +-9.987346e-01 4.987561e-02 6.450228e-03 -1.569090e+01 5.009362e-02 9.979506e-01 3.981517e-02 1.214563e+00 -4.451203e-03 4.008790e-02 -9.991863e-01 -1.635914e+01 +-9.987919e-01 4.871015e-02 6.484127e-03 -1.567519e+01 4.892095e-02 9.980891e-01 3.774680e-02 1.238904e+00 -4.633084e-03 3.801841e-02 -9.992663e-01 -1.776435e+01 +-9.988395e-01 4.771289e-02 6.570235e-03 -1.565947e+01 4.790896e-02 9.982765e-01 3.389294e-02 1.258378e+00 -4.941782e-03 3.416838e-02 -9.994039e-01 -1.917351e+01 +-9.988650e-01 4.714921e-02 6.758016e-03 -1.564353e+01 4.734747e-02 9.983327e-01 3.301464e-02 1.279114e+00 -5.190135e-03 3.329713e-02 -9.994320e-01 -2.058415e+01 +-9.988259e-01 4.792008e-02 7.108967e-03 -1.562986e+01 4.814156e-02 9.982201e-01 3.520011e-02 1.298206e+00 -5.409522e-03 3.550102e-02 -9.993550e-01 -2.200393e+01 +-9.986792e-01 5.080472e-02 7.668109e-03 -1.561782e+01 5.104820e-02 9.980521e-01 3.586218e-02 1.320134e+00 -5.831205e-03 3.620625e-02 -9.993273e-01 -2.342439e+01 +-9.985784e-01 5.266642e-02 8.207361e-03 -1.560601e+01 5.292318e-02 9.979830e-01 3.505759e-02 1.342475e+00 -6.344450e-03 3.544210e-02 -9.993516e-01 -2.484504e+01 +-9.985995e-01 5.219932e-02 8.624543e-03 -1.559027e+01 5.247315e-02 9.979963e-01 3.535317e-02 1.362532e+00 -6.761851e-03 3.575620e-02 -9.993377e-01 -2.626783e+01 +-9.986265e-01 5.170082e-02 8.491415e-03 -1.557331e+01 5.195665e-02 9.980928e-01 3.333387e-02 1.381668e+00 -6.751833e-03 3.372927e-02 -9.994082e-01 -2.768798e+01 +-9.986824e-01 5.059419e-02 8.583301e-03 -1.555401e+01 5.085643e-02 9.981362e-01 3.372896e-02 1.401278e+00 -6.860815e-03 3.412103e-02 -9.993942e-01 -2.911536e+01 +-9.986996e-01 5.013583e-02 9.247076e-03 -1.553676e+01 5.045358e-02 9.979988e-01 3.811475e-02 1.423844e+00 -7.317657e-03 3.853173e-02 -9.992306e-01 -3.054783e+01 +-9.985720e-01 5.249946e-02 9.889389e-03 -1.552140e+01 5.284486e-02 9.978529e-01 3.869151e-02 1.450596e+00 -7.836873e-03 3.915885e-02 -9.992023e-01 -3.197309e+01 +-9.984151e-01 5.523641e-02 1.078343e-02 -1.550772e+01 5.560162e-02 9.977612e-01 3.716145e-02 1.474487e+00 -8.706622e-03 3.770212e-02 -9.992511e-01 -3.339613e+01 +-9.982982e-01 5.717049e-02 1.150016e-02 -1.549326e+01 5.756597e-02 9.976318e-01 3.764192e-02 1.496909e+00 -9.320924e-03 3.823987e-02 -9.992251e-01 -3.481999e+01 +-9.982158e-01 5.851036e-02 1.190891e-02 -1.547662e+01 5.893325e-02 9.975016e-01 3.895420e-02 1.519635e+00 -9.599936e-03 3.958653e-02 -9.991700e-01 -3.624448e+01 +-9.980951e-01 6.048764e-02 1.213909e-02 -1.546088e+01 6.092067e-02 9.973724e-01 3.920397e-02 1.542757e+00 -9.735842e-03 3.986881e-02 -9.991575e-01 -3.766558e+01 +-9.979538e-01 6.270493e-02 1.250440e-02 -1.544410e+01 6.315510e-02 9.972169e-01 3.962063e-02 1.566849e+00 -9.985189e-03 4.032927e-02 -9.991366e-01 -3.908217e+01 +-9.978350e-01 6.448159e-02 1.294394e-02 -1.542668e+01 6.496352e-02 9.970406e-01 4.110680e-02 1.593713e+00 -1.025500e-02 4.185868e-02 -9.990709e-01 -4.049901e+01 +-9.977114e-01 6.633606e-02 1.309394e-02 -1.540927e+01 6.683278e-02 9.968766e-01 4.207560e-02 1.621146e+00 -1.026191e-02 4.285441e-02 -9.990286e-01 -4.191388e+01 +-9.975562e-01 6.863974e-02 1.304847e-02 -1.539245e+01 6.909955e-02 9.968530e-01 3.884983e-02 1.647343e+00 -1.034077e-02 3.965652e-02 -9.991599e-01 -4.332259e+01 +-9.973844e-01 7.107147e-02 1.316364e-02 -1.537523e+01 7.147924e-02 9.968743e-01 3.364828e-02 1.670185e+00 -1.073107e-02 3.450119e-02 -9.993471e-01 -4.472465e+01 +-9.973393e-01 7.167338e-02 1.331325e-02 -1.535699e+01 7.207628e-02 9.968611e-01 3.275498e-02 1.689780e+00 -1.092381e-02 3.362739e-02 -9.993747e-01 -4.613041e+01 +-9.973255e-01 7.182933e-02 1.350404e-02 -1.533783e+01 7.227029e-02 9.967482e-01 3.563565e-02 1.710257e+00 -1.090045e-02 3.651628e-02 -9.992736e-01 -4.753795e+01 +-9.973551e-01 7.141115e-02 1.353397e-02 -1.531710e+01 7.186265e-02 9.967472e-01 3.647791e-02 1.733637e+00 -1.088502e-02 3.735401e-02 -9.992428e-01 -4.894398e+01 +-9.973876e-01 7.099656e-02 1.332579e-02 -1.529715e+01 7.143116e-02 9.968098e-01 3.560447e-02 1.757778e+00 -1.075548e-02 3.646333e-02 -9.992771e-01 -5.034660e+01 +-9.973739e-01 7.118336e-02 1.335207e-02 -1.527696e+01 7.161440e-02 9.968112e-01 3.519577e-02 1.783280e+00 -1.080414e-02 3.605954e-02 -9.992912e-01 -5.174850e+01 +-9.974228e-01 7.049477e-02 1.334801e-02 -1.525676e+01 7.094330e-02 9.968014e-01 3.679631e-02 1.808697e+00 -1.071136e-02 3.764843e-02 -9.992336e-01 -5.315272e+01 +-9.973928e-01 7.105422e-02 1.260758e-02 -1.523749e+01 7.145221e-02 9.968447e-01 3.457273e-02 1.833987e+00 -1.011126e-02 3.538342e-02 -9.993227e-01 -5.454794e+01 +-9.974727e-01 7.007673e-02 1.172164e-02 -1.521771e+01 7.043414e-02 9.969531e-01 3.351899e-02 1.859642e+00 -9.337023e-03 3.425988e-02 -9.993694e-01 -5.594950e+01 +-9.974996e-01 6.986203e-02 1.067253e-02 -1.519945e+01 7.019448e-02 9.969250e-01 3.483105e-02 1.883021e+00 -8.206342e-03 3.549311e-02 -9.993362e-01 -5.735212e+01 +-9.974445e-01 7.074861e-02 9.959040e-03 -1.518410e+01 7.105641e-02 9.968584e-01 3.498852e-02 1.905888e+00 -7.452364e-03 3.560676e-02 -9.993381e-01 -5.875141e+01 +-9.973821e-01 7.174891e-02 9.005116e-03 -1.517008e+01 7.201266e-02 9.968400e-01 3.352794e-02 1.927806e+00 -6.571067e-03 3.408865e-02 -9.993972e-01 -6.015069e+01 +-9.974123e-01 7.141855e-02 8.250467e-03 -1.515697e+01 7.165585e-02 9.968711e-01 3.336899e-02 1.949198e+00 -5.841488e-03 3.387383e-02 -9.994091e-01 -6.154936e+01 +-9.974611e-01 7.082439e-02 7.441251e-03 -1.514226e+01 7.104011e-02 9.968779e-01 3.446403e-02 1.969588e+00 -4.977126e-03 3.490515e-02 -9.993782e-01 -6.295149e+01 +-9.975182e-01 7.009872e-02 6.600210e-03 -1.512801e+01 7.028769e-02 9.969132e-01 3.498168e-02 1.989950e+00 -4.127665e-03 3.535878e-02 -9.993662e-01 -6.435076e+01 +-9.976038e-01 6.893953e-02 5.836322e-03 -1.511338e+01 6.910363e-02 9.969812e-01 3.539958e-02 2.010300e+00 -3.378274e-03 3.571806e-02 -9.993562e-01 -6.575074e+01 +-9.976086e-01 6.892245e-02 5.171941e-03 -1.510121e+01 6.906309e-02 9.969809e-01 3.548840e-02 2.031551e+00 -2.710379e-03 3.576072e-02 -9.993567e-01 -6.714653e+01 +-9.976182e-01 6.881088e-02 4.792441e-03 -1.509141e+01 6.893829e-02 9.969853e-01 3.560591e-02 2.052437e+00 -2.327919e-03 3.585149e-02 -9.993544e-01 -6.853878e+01 +-9.975525e-01 6.975974e-02 4.749880e-03 -1.508303e+01 6.988353e-02 9.969428e-01 3.494575e-02 2.071234e+00 -2.297553e-03 3.519215e-02 -9.993779e-01 -6.993462e+01 +-9.975163e-01 7.025772e-02 5.011024e-03 -1.507453e+01 7.038292e-02 9.970029e-01 3.211704e-02 2.087360e+00 -2.739536e-03 3.238996e-02 -9.994716e-01 -7.132326e+01 +-9.975162e-01 7.024302e-02 5.223299e-03 -1.506438e+01 7.037346e-02 9.970212e-01 3.156201e-02 2.102811e+00 -2.990730e-03 3.185120e-02 -9.994882e-01 -7.270839e+01 +-9.974560e-01 7.104846e-02 5.800281e-03 -1.505383e+01 7.120179e-02 9.969169e-01 3.296757e-02 2.117081e+00 -3.440104e-03 3.329669e-02 -9.994396e-01 -7.409527e+01 +-9.973383e-01 7.261206e-02 6.626743e-03 -1.504316e+01 7.279938e-02 9.967420e-01 3.472240e-02 2.130723e+00 -4.083888e-03 3.511240e-02 -9.993750e-01 -7.547624e+01 +-9.972610e-01 7.354770e-02 7.823469e-03 -1.503084e+01 7.378874e-02 9.965841e-01 3.708515e-02 2.146554e+00 -5.069218e-03 3.756085e-02 -9.992815e-01 -7.685642e+01 +-9.971982e-01 7.425921e-02 9.013432e-03 -1.501678e+01 7.454127e-02 9.965473e-01 3.656561e-02 2.163460e+00 -6.266979e-03 3.713503e-02 -9.992906e-01 -7.822646e+01 +-9.972048e-01 7.410788e-02 9.521483e-03 -1.499833e+01 7.438356e-02 9.966868e-01 3.290164e-02 2.179823e+00 -7.051666e-03 3.351791e-02 -9.994132e-01 -7.959325e+01 +-9.973372e-01 7.227791e-02 9.722193e-03 -1.497930e+01 7.254016e-02 9.969125e-01 3.005627e-02 2.191194e+00 -7.519772e-03 3.068148e-02 -9.995009e-01 -8.095360e+01 +-9.974315e-01 7.094710e-02 9.843520e-03 -1.495957e+01 7.122432e-02 9.969642e-01 3.145664e-02 2.200916e+00 -7.581880e-03 3.207694e-02 -9.994567e-01 -8.231728e+01 +-9.974248e-01 7.101847e-02 1.000900e-02 -1.494128e+01 7.133688e-02 9.967953e-01 3.619517e-02 2.214391e+00 -7.406403e-03 3.681597e-02 -9.992946e-01 -8.368053e+01 +-9.973876e-01 7.151375e-02 1.018872e-02 -1.492467e+01 7.185845e-02 9.966573e-01 3.886684e-02 2.232509e+00 -7.375146e-03 3.949744e-02 -9.991925e-01 -8.503495e+01 +-9.973437e-01 7.213573e-02 1.009619e-02 -1.490817e+01 7.247511e-02 9.966191e-01 3.870065e-02 2.250863e+00 -7.270352e-03 3.932956e-02 -9.991999e-01 -8.638401e+01 +-9.973415e-01 7.222395e-02 9.672534e-03 -1.489187e+01 7.253602e-02 9.966730e-01 3.716616e-02 2.268643e+00 -6.956067e-03 3.776896e-02 -9.992623e-01 -8.772673e+01 +-9.973953e-01 7.159730e-02 8.749062e-03 -1.487398e+01 7.186371e-02 9.967883e-01 3.533504e-02 2.282365e+00 -6.191070e-03 3.587174e-02 -9.993372e-01 -8.907040e+01 +-9.974807e-01 7.051089e-02 7.777308e-03 -1.485657e+01 7.073804e-02 9.969025e-01 3.437215e-02 2.296993e+00 -5.329608e-03 3.483570e-02 -9.993789e-01 -9.040801e+01 +-9.975694e-01 6.934890e-02 6.780333e-03 -1.483919e+01 6.954582e-02 9.969561e-01 3.524114e-02 2.311152e+00 -4.315760e-03 3.562703e-02 -9.993558e-01 -9.174112e+01 +-9.975926e-01 6.907079e-02 6.191566e-03 -1.482426e+01 6.925341e-02 9.969124e-01 3.700800e-02 2.326927e+00 -3.616278e-03 3.734769e-02 -9.992958e-01 -9.307672e+01 +-9.975963e-01 6.908327e-02 5.400464e-03 -1.481076e+01 6.923290e-02 9.969578e-01 3.580445e-02 2.341502e+00 -2.910546e-03 3.609227e-02 -9.993442e-01 -9.440039e+01 +-9.975990e-01 6.908942e-02 4.782445e-03 -1.479798e+01 6.921422e-02 9.969976e-01 3.471631e-02 2.357904e+00 -2.369557e-03 3.496396e-02 -9.993858e-01 -9.572436e+01 +-9.975879e-01 6.929139e-02 4.137105e-03 -1.478703e+01 6.939571e-02 9.969385e-01 3.602484e-02 2.374193e+00 -1.628228e-03 3.622503e-02 -9.993423e-01 -9.704551e+01 +-9.976264e-01 6.877106e-02 3.472441e-03 -1.477603e+01 6.885297e-02 9.969242e-01 3.743363e-02 2.389834e+00 -8.874102e-04 3.758386e-02 -9.992931e-01 -9.836341e+01 +-9.976363e-01 6.867255e-02 2.439801e-03 -1.476703e+01 6.871580e-02 9.969461e-01 3.710196e-02 2.407843e+00 1.155364e-04 3.718191e-02 -9.993085e-01 -9.967660e+01 +-9.976105e-01 6.906941e-02 1.670244e-03 -1.475854e+01 6.908340e-02 9.969045e-01 3.753403e-02 2.426874e+00 9.273786e-04 3.755972e-02 -9.992940e-01 -1.009838e+02 +-9.976040e-01 6.917780e-02 8.769539e-04 -1.475176e+01 6.916254e-02 9.969122e-01 3.718329e-02 2.444391e+00 1.698012e-03 3.715484e-02 -9.993081e-01 -1.022903e+02 +-9.976217e-01 6.892705e-02 2.303922e-04 -1.474410e+01 6.888804e-02 9.969325e-01 3.714793e-02 2.462669e+00 2.330812e-03 3.707545e-02 -9.993098e-01 -1.035926e+02 +-9.975894e-01 6.939258e-02 -4.083670e-04 -1.473960e+01 6.932965e-02 9.969028e-01 3.712407e-02 2.480363e+00 2.983238e-03 3.700626e-02 -9.993106e-01 -1.048920e+02 +-9.976351e-01 6.872422e-02 -1.069147e-03 -1.473425e+01 6.863915e-02 9.969695e-01 3.661297e-02 2.498308e+00 3.582105e-03 3.645299e-02 -9.993290e-01 -1.061858e+02 +-9.976375e-01 6.867199e-02 -1.894302e-03 -1.473066e+01 6.856168e-02 9.970143e-01 3.551985e-02 2.514949e+00 4.327866e-03 3.530605e-02 -9.993672e-01 -1.074728e+02 +-9.976142e-01 6.899493e-02 -2.354127e-03 -1.472824e+01 6.887531e-02 9.970450e-01 3.402060e-02 2.530663e+00 4.694419e-03 3.377729e-02 -9.994184e-01 -1.087629e+02 +-9.975813e-01 6.945416e-02 -2.756067e-03 -1.472729e+01 6.931596e-02 9.969826e-01 3.494145e-02 2.547386e+00 5.174580e-03 3.466590e-02 -9.993856e-01 -1.100459e+02 +-9.976024e-01 6.915655e-02 -2.631222e-03 -1.472555e+01 6.900680e-02 9.968899e-01 3.805981e-02 2.563690e+00 5.255124e-03 3.778698e-02 -9.992720e-01 -1.113291e+02 +-9.975384e-01 7.007642e-02 -2.521275e-03 -1.472479e+01 6.993704e-02 9.968752e-01 3.672210e-02 2.582153e+00 5.086750e-03 3.645537e-02 -9.993223e-01 -1.126054e+02 +-9.975807e-01 6.947956e-02 -2.304985e-03 -1.472153e+01 6.935391e-02 9.969570e-01 3.559169e-02 2.600374e+00 4.770866e-03 3.534572e-02 -9.993638e-01 -1.138771e+02 +-9.975349e-01 7.013503e-02 -2.293968e-03 -1.471960e+01 7.000618e-02 9.968875e-01 3.625377e-02 2.617244e+00 4.829488e-03 3.600380e-02 -9.993400e-01 -1.151477e+02 +-9.974808e-01 7.090842e-02 -2.022760e-03 -1.471780e+01 7.078658e-02 9.968146e-01 3.674006e-02 2.634202e+00 4.621496e-03 3.650431e-02 -9.993228e-01 -1.164111e+02 +-9.974573e-01 7.124868e-02 -1.602631e-03 -1.471582e+01 7.113805e-02 9.967553e-01 3.765964e-02 2.650909e+00 4.280631e-03 3.744987e-02 -9.992893e-01 -1.176691e+02 +-9.974833e-01 7.088889e-02 -1.379394e-03 -1.471284e+01 7.078300e-02 9.967442e-01 3.861105e-02 2.667793e+00 4.111998e-03 3.841624e-02 -9.992534e-01 -1.189238e+02 +-9.974646e-01 7.115321e-02 -1.300369e-03 -1.470983e+01 7.105249e-02 9.967473e-01 3.803084e-02 2.685657e+00 4.002155e-03 3.784201e-02 -9.992757e-01 -1.201734e+02 +-9.974995e-01 7.066122e-02 -1.290068e-03 -1.470566e+01 7.056123e-02 9.967820e-01 3.803523e-02 2.703911e+00 3.973532e-03 3.784909e-02 -9.992756e-01 -1.214141e+02 +-9.974916e-01 7.076963e-02 -1.486024e-03 -1.470294e+01 7.066285e-02 9.967813e-01 3.786527e-02 2.719941e+00 4.160952e-03 3.766527e-02 -9.992818e-01 -1.226449e+02 +-9.975252e-01 7.028078e-02 -2.044132e-03 -1.470054e+01 7.015567e-02 9.968359e-01 3.736675e-02 2.735913e+00 4.663829e-03 3.713086e-02 -9.992995e-01 -1.238671e+02 +-9.975902e-01 6.930192e-02 -3.333687e-03 -1.469881e+01 6.912645e-02 9.968874e-01 3.790665e-02 2.751503e+00 5.950314e-03 3.758485e-02 -9.992757e-01 -1.250815e+02 +-9.976613e-01 6.819870e-02 -4.563546e-03 -1.469830e+01 6.796967e-02 9.969232e-01 3.904181e-02 2.767801e+00 7.212105e-03 3.864031e-02 -9.992272e-01 -1.262871e+02 +-9.977402e-01 6.694356e-02 -5.746508e-03 -1.469852e+01 6.666242e-02 9.969766e-01 3.992097e-02 2.784821e+00 8.401586e-03 3.944767e-02 -9.991863e-01 -1.274852e+02 +-9.977690e-01 6.637900e-02 -7.127387e-03 -1.470118e+01 6.605285e-02 9.970537e-01 3.899937e-02 2.801395e+00 9.695127e-03 3.844158e-02 -9.992138e-01 -1.286704e+02 +-9.977434e-01 6.662080e-02 -8.357317e-03 -1.470614e+01 6.626589e-02 9.971051e-01 3.728557e-02 2.817529e+00 1.081712e-02 3.664762e-02 -9.992697e-01 -1.298453e+02 +-9.977098e-01 6.703955e-02 -8.992148e-03 -1.471233e+01 6.666532e-02 9.970921e-01 3.691970e-02 2.833172e+00 1.144108e-02 3.623568e-02 -9.992778e-01 -1.310089e+02 +-9.976491e-01 6.794622e-02 -8.924767e-03 -1.471896e+01 6.755099e-02 9.969567e-01 3.891207e-02 2.848691e+00 1.154154e-02 3.821770e-02 -9.992028e-01 -1.321621e+02 +-9.976135e-01 6.850765e-02 -8.606301e-03 -1.472488e+01 6.809693e-02 9.968227e-01 4.131803e-02 2.863999e+00 1.140956e-02 4.063336e-02 -9.991090e-01 -1.332996e+02 +-9.974696e-01 7.057097e-02 -8.609803e-03 -1.473334e+01 7.014963e-02 9.966483e-01 4.208462e-02 2.880267e+00 1.155090e-02 4.137414e-02 -9.990770e-01 -1.344174e+02 +-9.973322e-01 7.249416e-02 -8.554776e-03 -1.474314e+01 7.208322e-02 9.965455e-01 4.124449e-02 2.895211e+00 1.151521e-02 4.051780e-02 -9.991125e-01 -1.355140e+02 +-9.974585e-01 7.069405e-02 -8.881130e-03 -1.474619e+01 7.025830e-02 9.966296e-01 4.234544e-02 2.913166e+00 1.184477e-02 4.161384e-02 -9.990636e-01 -1.365942e+02 +-9.974491e-01 7.084432e-02 -8.740709e-03 -1.475233e+01 7.037702e-02 9.964825e-01 4.549437e-02 2.928943e+00 1.193298e-02 4.476317e-02 -9.989264e-01 -1.376542e+02 +-9.974303e-01 7.092889e-02 -1.009213e-02 -1.475847e+01 7.040234e-02 9.964850e-01 4.539887e-02 2.946711e+00 1.327675e-02 4.457170e-02 -9.989180e-01 -1.386869e+02 +-9.974949e-01 6.969297e-02 -1.211483e-02 -1.476466e+01 6.910044e-02 9.966437e-01 4.389185e-02 2.964758e+00 1.513313e-02 4.294475e-02 -9.989628e-01 -1.396957e+02 +-9.975050e-01 6.929953e-02 -1.346888e-02 -1.477357e+01 6.864393e-02 9.966610e-01 4.421304e-02 2.979529e+00 1.648785e-02 4.317816e-02 -9.989313e-01 -1.406763e+02 +-9.974166e-01 7.034883e-02 -1.453474e-02 -1.478487e+01 6.963502e-02 9.965635e-01 4.485647e-02 2.993256e+00 1.764039e-02 4.372846e-02 -9.988877e-01 -1.416311e+02 +-9.973286e-01 7.143360e-02 -1.525850e-02 -1.479743e+01 7.067695e-02 9.964649e-01 4.541408e-02 3.006784e+00 1.844865e-02 4.421434e-02 -9.988517e-01 -1.425562e+02 +-9.972718e-01 7.230600e-02 -1.485943e-02 -1.480845e+01 7.156572e-02 9.964001e-01 4.544338e-02 3.020005e+00 1.809177e-02 4.425597e-02 -9.988564e-01 -1.434522e+02 +-9.971657e-01 7.410521e-02 -1.300310e-02 -1.481802e+01 7.345845e-02 9.962980e-01 4.465532e-02 3.032842e+00 1.626415e-02 4.357356e-02 -9.989178e-01 -1.443211e+02 +-9.969561e-01 7.764157e-02 -7.091003e-03 -1.482330e+01 7.726579e-02 9.960747e-01 4.318641e-02 3.044707e+00 1.041623e-02 4.250706e-02 -9.990419e-01 -1.451550e+02 +-9.966390e-01 8.180695e-02 4.278719e-03 -1.481877e+01 8.191465e-02 9.957532e-01 4.201770e-02 3.055661e+00 -8.232082e-04 4.222697e-02 -9.991077e-01 -1.459633e+02 +-9.961003e-01 8.541751e-02 2.208988e-02 -1.479757e+01 8.626276e-02 9.954424e-01 4.065773e-02 3.065594e+00 -1.851633e-02 4.240471e-02 -9.989289e-01 -1.467445e+02 +-9.952694e-01 8.631945e-02 4.458408e-02 -1.475456e+01 8.812302e-02 9.952978e-01 4.020616e-02 3.071965e+00 -4.090387e-02 4.394484e-02 -9.981962e-01 -1.474992e+02 +-9.938909e-01 8.523393e-02 7.011484e-02 -1.468816e+01 8.829462e-02 9.952181e-01 4.177187e-02 3.079106e+00 -6.621918e-02 4.770744e-02 -9.966640e-01 -1.482245e+02 +-9.916589e-01 8.301968e-02 9.859229e-02 -1.459929e+01 8.765648e-02 9.951934e-01 4.366123e-02 3.086043e+00 -9.449367e-02 5.193930e-02 -9.941696e-01 -1.489260e+02 +-9.882135e-01 8.181131e-02 1.293874e-01 -1.449202e+01 8.796924e-02 9.952115e-01 4.260690e-02 3.088830e+00 -1.252821e-01 5.348681e-02 -9.906783e-01 -1.495947e+02 +-9.829437e-01 8.228185e-02 1.644732e-01 -1.436420e+01 8.974881e-02 9.952207e-01 3.848285e-02 3.087775e+00 -1.605207e-01 5.258774e-02 -9.856306e-01 -1.502250e+02 +-9.753009e-01 8.351131e-02 2.044848e-01 -1.421312e+01 9.202675e-02 9.952267e-01 3.247701e-02 3.089330e+00 -2.007965e-01 5.049292e-02 -9.783308e-01 -1.508335e+02 +-9.651190e-01 8.402038e-02 2.479637e-01 -1.403648e+01 9.351823e-02 9.952580e-01 2.675483e-02 3.090778e+00 -2.445399e-01 4.901071e-02 -9.683998e-01 -1.514162e+02 +-9.521491e-01 8.297222e-02 2.941561e-01 -1.383342e+01 9.367623e-02 9.953493e-01 2.246210e-02 3.086577e+00 -2.909243e-01 4.894270e-02 -9.554934e-01 -1.519504e+02 +-9.353093e-01 8.285053e-02 3.439946e-01 -1.360854e+01 9.517208e-02 9.952784e-01 1.905835e-02 3.076710e+00 -3.407914e-01 5.056412e-02 -9.387782e-01 -1.524769e+02 +-9.141975e-01 8.348746e-02 3.965764e-01 -1.336041e+01 9.728551e-02 9.951469e-01 1.476601e-02 3.060860e+00 -3.934191e-01 5.208018e-02 -9.178830e-01 -1.529502e+02 +-8.889503e-01 8.191062e-02 4.506197e-01 -1.308243e+01 9.672397e-02 9.952620e-01 9.898022e-03 3.046760e+00 -4.476739e-01 5.238456e-02 -8.926612e-01 -1.534240e+02 +-8.593851e-01 8.022248e-02 5.049967e-01 -1.277723e+01 9.616861e-02 9.953496e-01 5.537504e-03 3.032264e+00 -5.022040e-01 5.332366e-02 -8.631035e-01 -1.538743e+02 +-8.253759e-01 7.811190e-02 5.591539e-01 -1.244653e+01 9.514011e-02 9.954629e-01 1.374991e-03 3.015235e+00 -5.565097e-01 5.433284e-02 -8.290627e-01 -1.542672e+02 +-7.865971e-01 7.659268e-02 6.126977e-01 -1.209330e+01 9.494812e-02 9.954789e-01 -2.546946e-03 2.992923e+00 -6.101228e-01 5.617106e-02 -7.903132e-01 -1.546664e+02 +-7.433711e-01 7.362276e-02 6.648150e-01 -1.171655e+01 9.305332e-02 9.956417e-01 -6.210403e-03 2.969218e+00 -6.623749e-01 5.724660e-02 -7.469822e-01 -1.550328e+02 +-6.944698e-01 7.067550e-02 7.160423e-01 -1.131815e+01 9.170462e-02 9.957424e-01 -9.340961e-03 2.947184e+00 -7.136540e-01 5.917736e-02 -6.979944e-01 -1.553310e+02 +-6.411200e-01 6.687048e-02 7.645217e-01 -1.090107e+01 8.906721e-02 9.959481e-01 -1.242186e-02 2.926439e+00 -7.622547e-01 6.012990e-02 -6.444783e-01 -1.556301e+02 +-5.852209e-01 6.054081e-02 8.086107e-01 -1.046589e+01 8.320129e-02 9.964289e-01 -1.438702e-02 2.901563e+00 -8.065941e-01 5.885785e-02 -5.881681e-01 -1.558564e+02 +-5.271530e-01 5.569091e-02 8.479436e-01 -1.002043e+01 7.773961e-02 9.968263e-01 -1.713973e-02 2.872763e+00 -8.462070e-01 5.688353e-02 -5.298094e-01 -1.560826e+02 +-4.665426e-01 5.245105e-02 8.829422e-01 -9.567123e+00 7.281015e-02 9.971297e-01 -2.076181e-02 2.844586e+00 -8.814969e-01 5.460087e-02 -4.690225e-01 -1.562778e+02 +-4.036625e-01 5.054141e-02 9.135109e-01 -9.106293e+00 7.023344e-02 9.972384e-01 -2.413901e-02 2.815747e+00 -9.122083e-01 5.441499e-02 -4.060975e-01 -1.564059e+02 +-3.388720e-01 5.056037e-02 9.394729e-01 -8.642035e+00 6.895791e-02 9.972039e-01 -2.879392e-02 2.787238e+00 -9.383020e-01 5.502663e-02 -3.414110e-01 -1.565389e+02 +-2.728866e-01 5.136584e-02 9.606740e-01 -8.174402e+00 6.579334e-02 9.972321e-01 -3.463148e-02 2.755500e+00 -9.597938e-01 5.375547e-02 -2.755108e-01 -1.566351e+02 +-2.059116e-01 5.118956e-02 9.772308e-01 -7.699412e+00 6.141803e-02 9.973380e-01 -3.930148e-02 2.722687e+00 -9.766413e-01 5.192694e-02 -2.085075e-01 -1.566631e+02 +-1.372488e-01 4.789029e-02 9.893782e-01 -7.221458e+00 5.525916e-02 9.976452e-01 -4.062478e-02 2.690343e+00 -9.889941e-01 4.909649e-02 -1.395720e-01 -1.566903e+02 +-6.749209e-02 4.009659e-02 9.969138e-01 -6.734167e+00 5.153942e-02 9.979982e-01 -3.665094e-02 2.665011e+00 -9.963878e-01 4.890670e-02 -6.942354e-02 -1.566510e+02 +3.185036e-03 3.007870e-02 9.995424e-01 -6.243160e+00 5.066364e-02 9.982590e-01 -3.020152e-02 2.641270e+00 -9.987107e-01 5.073664e-02 1.655592e-03 -1.566171e+02 +7.399370e-02 1.824071e-02 9.970919e-01 -5.751237e+00 4.778374e-02 9.986194e-01 -2.181468e-02 2.615199e+00 -9.961133e-01 4.925891e-02 7.301994e-02 -1.565444e+02 +1.446246e-01 6.444984e-03 9.894656e-01 -5.261917e+00 4.367422e-02 9.989626e-01 -1.289046e-02 2.593307e+00 -9.885223e-01 4.507841e-02 1.441931e-01 -1.563936e+02 +2.153441e-01 -2.536548e-03 9.765349e-01 -4.779011e+00 3.856752e-02 9.992385e-01 -5.909337e-03 2.569364e+00 -9.757764e-01 3.893506e-02 2.152780e-01 -1.562439e+02 +2.855168e-01 -7.126922e-03 9.583472e-01 -4.305429e+00 3.702661e-02 9.993078e-01 -3.599667e-03 2.552946e+00 -9.576582e-01 3.651211e-02 2.855830e-01 -1.560244e+02 +3.545432e-01 -9.715255e-03 9.349891e-01 -3.838336e+00 3.641650e-02 9.993308e-01 -3.425140e-03 2.542408e+00 -9.343303e-01 3.526338e-02 3.546597e-01 -1.558078e+02 +4.215235e-01 -1.487379e-02 9.066955e-01 -3.375344e+00 3.687970e-02 9.993194e-01 -7.521703e-04 2.534833e+00 -9.060673e-01 3.375570e-02 4.217851e-01 -1.555541e+02 +4.860041e-01 -2.068115e-02 8.737118e-01 -2.922418e+00 3.713383e-02 9.993058e-01 2.998246e-03 2.530704e+00 -8.731673e-01 3.098709e-02 4.864347e-01 -1.552209e+02 +5.478262e-01 -2.549175e-02 8.362037e-01 -2.480572e+00 3.701037e-02 9.992955e-01 6.216844e-03 2.522617e+00 -8.357731e-01 2.754245e-02 5.483838e-01 -1.548906e+02 +6.059605e-01 -2.731152e-02 7.950257e-01 -2.057963e+00 3.499787e-02 9.993580e-01 7.655930e-03 2.510377e+00 -7.947245e-01 2.318501e-02 6.065274e-01 -1.544839e+02 +6.595487e-01 -2.599740e-02 7.512121e-01 -1.653879e+00 3.259140e-02 9.994509e-01 5.973702e-03 2.499815e+00 -7.509549e-01 2.054310e-02 6.600339e-01 -1.540795e+02 +7.087768e-01 -2.439897e-02 7.050107e-01 -1.268487e+00 3.271882e-02 9.994631e-01 1.695776e-03 2.493093e+00 -7.046737e-01 2.186519e-02 7.091946e-01 -1.536401e+02 +7.533520e-01 -2.429471e-02 6.571685e-01 -8.983582e-01 3.466894e-02 9.993949e-01 -2.796695e-03 2.487045e+00 -6.567030e-01 2.489022e-02 7.537385e-01 -1.531409e+02 +7.940748e-01 -2.464464e-02 6.073202e-01 -5.510777e-01 3.456624e-02 9.993916e-01 -4.640924e-03 2.478814e+00 -6.068364e-01 2.467801e-02 7.944436e-01 -1.526325e+02 +8.314209e-01 -2.593021e-02 5.550378e-01 -2.261366e-01 3.340032e-02 9.994364e-01 -3.340532e-03 2.467171e+00 -5.546384e-01 2.131582e-02 8.318184e-01 -1.520606e+02 +8.661018e-01 -2.579227e-02 4.992017e-01 6.230717e-02 3.056835e-02 9.995317e-01 -1.392433e-03 2.456904e+00 -4.989321e-01 1.646576e-02 8.664847e-01 -1.514836e+02 +8.971189e-01 -2.752906e-02 4.409306e-01 3.234820e-01 3.121585e-02 9.995120e-01 -1.108334e-03 2.446327e+00 -4.406850e-01 1.475833e-02 8.975405e-01 -1.508797e+02 +9.237462e-01 -2.721279e-02 3.820373e-01 5.523554e-01 2.945011e-02 9.995662e-01 -8.987232e-06 2.433161e+00 -3.818713e-01 1.125934e-02 9.241469e-01 -1.502166e+02 +9.449167e-01 -2.612841e-02 3.262664e-01 7.484821e-01 2.743938e-02 9.996233e-01 5.843422e-04 2.422189e+00 -3.261587e-01 8.400390e-03 9.452777e-01 -1.495497e+02 +9.612644e-01 -2.039293e-02 2.748725e-01 9.129124e-01 2.153763e-02 9.997674e-01 -1.146595e-03 2.410623e+00 -2.747852e-01 7.022281e-03 9.614800e-01 -1.488380e+02 +9.733537e-01 -1.423653e-02 2.288667e-01 1.048250e+00 1.539388e-02 9.998761e-01 -3.272292e-03 2.402930e+00 -2.287918e-01 6.708242e-03 9.734523e-01 -1.481125e+02 +9.821288e-01 -8.921973e-03 1.879984e-01 1.163229e+00 9.897660e-03 9.999420e-01 -4.251735e-03 2.393425e+00 -1.879496e-01 6.036495e-03 9.821601e-01 -1.473483e+02 +9.883609e-01 -8.628201e-03 1.518828e-01 1.265054e+00 9.235369e-03 9.999519e-01 -3.292598e-03 2.383452e+00 -1.518471e-01 4.656968e-03 9.883930e-01 -1.465668e+02 +9.929339e-01 -8.521186e-03 1.183626e-01 1.348496e+00 8.772109e-03 9.999602e-01 -1.599113e-03 2.371923e+00 -1.183442e-01 2.626103e-03 9.929692e-01 -1.457604e+02 +9.961040e-01 -7.528316e-03 8.786447e-02 1.407670e+00 7.622948e-03 9.999706e-01 -7.415101e-04 2.359471e+00 -8.785631e-02 1.408408e-03 9.961322e-01 -1.449267e+02 +9.981129e-01 -4.324037e-03 6.125267e-02 1.444780e+00 4.379208e-03 9.999901e-01 -7.664915e-04 2.346915e+00 -6.124876e-02 1.033284e-03 9.981220e-01 -1.440738e+02 +9.992350e-01 5.962875e-04 3.910348e-02 1.463451e+00 -5.387739e-04 9.999987e-01 -1.481331e-03 2.332663e+00 -3.910432e-02 1.459130e-03 9.992341e-01 -1.431977e+02 +9.997137e-01 5.769106e-03 2.322264e-02 1.469675e+00 -5.710986e-03 9.999804e-01 -2.568352e-03 2.319985e+00 -2.323700e-02 2.434993e-03 9.997270e-01 -1.423032e+02 +9.998495e-01 1.091336e-02 1.348725e-02 1.468738e+00 -1.086184e-02 9.999334e-01 -3.887312e-03 2.305914e+00 -1.352878e-02 3.740231e-03 9.999015e-01 -1.413867e+02 +9.998497e-01 1.438674e-02 9.678533e-03 1.471319e+00 -1.435034e-02 9.998897e-01 -3.820593e-03 2.290968e+00 -9.732432e-03 3.681128e-03 9.999459e-01 -1.404509e+02 +9.998449e-01 1.528506e-02 8.754673e-03 1.479967e+00 -1.525879e-02 9.998789e-01 -3.059588e-03 2.274698e+00 -8.800379e-03 2.925528e-03 9.999570e-01 -1.394923e+02 +9.998714e-01 1.399469e-02 7.827091e-03 1.489345e+00 -1.398086e-02 9.999006e-01 -1.819670e-03 2.260154e+00 -7.851779e-03 1.710007e-03 9.999677e-01 -1.385154e+02 +9.998881e-01 1.340436e-02 6.646394e-03 1.499366e+00 -1.339892e-02 9.999098e-01 -8.623658e-04 2.246738e+00 -6.657355e-03 7.732153e-04 9.999775e-01 -1.375181e+02 +9.999186e-01 1.176204e-02 4.944630e-03 1.504842e+00 -1.175716e-02 9.999303e-01 -1.014327e-03 2.234017e+00 -4.956216e-03 9.561103e-04 9.999873e-01 -1.365045e+02 +9.999230e-01 1.212913e-02 2.635547e-03 1.505414e+00 -1.212491e-02 9.999252e-01 -1.610297e-03 2.220167e+00 -2.654882e-03 1.578218e-03 9.999952e-01 -1.354735e+02 +9.999310e-01 1.172534e-02 6.855855e-04 1.504501e+00 -1.172483e-02 9.999310e-01 -7.339802e-04 2.205688e+00 -6.941440e-04 7.258918e-04 9.999995e-01 -1.344219e+02 +9.999307e-01 1.172244e-02 -1.101900e-03 1.503329e+00 -1.172044e-02 9.999297e-01 1.805016e-03 2.190202e+00 1.122982e-03 -1.791975e-03 9.999978e-01 -1.333518e+02 +9.999438e-01 1.017712e-02 -2.970131e-03 1.501627e+00 -1.016840e-02 9.999440e-01 2.934698e-03 2.176140e+00 2.999832e-03 -2.904330e-03 9.999913e-01 -1.322648e+02 +9.999410e-01 9.844125e-03 -4.590163e-03 1.498560e+00 -9.837271e-03 9.999504e-01 1.514018e-03 2.159629e+00 4.604841e-03 -1.468773e-03 9.999883e-01 -1.311603e+02 +9.999420e-01 9.050453e-03 -5.833740e-03 1.491650e+00 -9.051606e-03 9.999590e-01 -1.708351e-04 2.144473e+00 5.831955e-03 2.236305e-04 9.999830e-01 -1.300390e+02 +9.999362e-01 8.822615e-03 -7.058630e-03 1.482380e+00 -8.824962e-03 9.999610e-01 -3.011758e-04 2.128143e+00 7.055699e-03 3.634494e-04 9.999751e-01 -1.288996e+02 +9.999224e-01 9.719678e-03 -7.790702e-03 1.470024e+00 -9.722542e-03 9.999527e-01 -3.295456e-04 2.111152e+00 7.787131e-03 4.052662e-04 9.999696e-01 -1.277441e+02 +9.999140e-01 1.025224e-02 -8.175770e-03 1.458443e+00 -1.026282e-02 9.999465e-01 -1.251767e-03 2.092643e+00 8.162501e-03 1.335566e-03 9.999658e-01 -1.265764e+02 +9.999148e-01 1.022533e-02 -8.118666e-03 1.447721e+00 -1.024296e-02 9.999452e-01 -2.132941e-03 2.073753e+00 8.096413e-03 2.215919e-03 9.999648e-01 -1.253883e+02 +9.999145e-01 1.072936e-02 -7.480234e-03 1.436723e+00 -1.074023e-02 9.999413e-01 -1.414140e-03 2.053638e+00 7.464623e-03 1.494359e-03 9.999710e-01 -1.241850e+02 +9.999199e-01 1.084179e-02 -6.535539e-03 1.426398e+00 -1.084800e-02 9.999407e-01 -9.156124e-04 2.032685e+00 6.525225e-03 9.864371e-04 9.999782e-01 -1.229654e+02 +9.999226e-01 1.136649e-02 -5.062827e-03 1.418040e+00 -1.138007e-02 9.999317e-01 -2.661598e-03 2.009877e+00 5.032229e-03 2.719008e-03 9.999837e-01 -1.217344e+02 +9.999270e-01 1.164681e-02 -3.221536e-03 1.413177e+00 -1.166704e-02 9.999119e-01 -6.332524e-03 1.984400e+00 3.147499e-03 6.369647e-03 9.999748e-01 -1.204917e+02 +9.999382e-01 1.100924e-02 -1.526074e-03 1.410381e+00 -1.102253e-02 9.998988e-01 -8.986750e-03 1.956743e+00 1.426983e-03 9.003015e-03 9.999585e-01 -1.192315e+02 +9.999550e-01 9.477174e-03 -5.136483e-04 1.407398e+00 -9.481614e-03 9.999102e-01 -9.463641e-03 1.927293e+00 4.239140e-04 9.468084e-03 9.999551e-01 -1.179509e+02 +9.999653e-01 8.308351e-03 -6.239788e-04 1.405768e+00 -8.313458e-03 9.999277e-01 -8.681081e-03 1.897027e+00 5.518086e-04 8.685966e-03 9.999621e-01 -1.166572e+02 +9.999724e-01 7.237877e-03 -1.684790e-03 1.402662e+00 -7.251946e-03 9.999376e-01 -8.498931e-03 1.864276e+00 1.623171e-03 8.510913e-03 9.999625e-01 -1.153483e+02 +9.999684e-01 7.392424e-03 -2.942274e-03 1.396732e+00 -7.426026e-03 9.999054e-01 -1.157771e-02 1.832056e+00 2.856409e-03 1.159919e-02 9.999287e-01 -1.140291e+02 +9.999585e-01 7.373591e-03 -5.353826e-03 1.385028e+00 -7.442317e-03 9.998887e-01 -1.293208e-02 1.800206e+00 5.257875e-03 1.297139e-02 9.999021e-01 -1.126950e+02 +9.999343e-01 7.785340e-03 -8.409924e-03 1.369687e+00 -7.883585e-03 9.999003e-01 -1.171244e-02 1.767521e+00 8.317901e-03 1.177797e-02 9.998960e-01 -1.113405e+02 +9.999150e-01 7.049963e-03 -1.096645e-02 1.351798e+00 -7.158844e-03 9.999251e-01 -9.921033e-03 1.734254e+00 1.089569e-02 9.998696e-03 9.998907e-01 -1.099726e+02 +9.998908e-01 8.118665e-03 -1.234841e-02 1.330549e+00 -8.244633e-03 9.999141e-01 -1.018451e-02 1.700357e+00 1.226467e-02 1.028521e-02 9.998719e-01 -1.085928e+02 +9.998774e-01 7.803456e-03 -1.357941e-02 1.308290e+00 -7.958173e-03 9.999036e-01 -1.137688e-02 1.668467e+00 1.348933e-02 1.148355e-02 9.998431e-01 -1.072003e+02 +9.998665e-01 6.969211e-03 -1.477678e-02 1.284827e+00 -7.144612e-03 9.999042e-01 -1.185059e-02 1.635925e+00 1.469278e-02 1.195459e-02 9.998206e-01 -1.057911e+02 +9.998518e-01 6.986507e-03 -1.573240e-02 1.259616e+00 -7.196031e-03 9.998856e-01 -1.330096e-02 1.601652e+00 1.563767e-02 1.341220e-02 9.997878e-01 -1.043679e+02 +9.998208e-01 8.762031e-03 -1.678195e-02 1.230259e+00 -8.989554e-03 9.998680e-01 -1.353036e-02 1.565326e+00 1.666119e-02 1.367879e-02 9.997676e-01 -1.029321e+02 +9.998211e-01 8.364186e-03 -1.696268e-02 1.202212e+00 -8.570344e-03 9.998898e-01 -1.211747e-02 1.530047e+00 1.685946e-02 1.226068e-02 9.997827e-01 -1.014787e+02 +9.998095e-01 1.030041e-02 -1.657864e-02 1.170075e+00 -1.045481e-02 9.999025e-01 -9.253150e-03 1.495851e+00 1.648172e-02 9.424713e-03 9.998198e-01 -1.000076e+02 +9.998152e-01 1.049543e-02 -1.610808e-02 1.142136e+00 -1.061219e-02 9.999179e-01 -7.180130e-03 1.463280e+00 1.603140e-02 7.349744e-03 9.998445e-01 -9.852911e+01 +9.998297e-01 9.547110e-03 -1.579432e-02 1.115543e+00 -9.625478e-03 9.999417e-01 -4.893114e-03 1.436157e+00 1.574669e-02 5.044309e-03 9.998633e-01 -9.702601e+01 +9.998310e-01 1.018513e-02 -1.530751e-02 1.089274e+00 -1.016702e-02 9.999475e-01 1.261045e-03 1.410680e+00 1.531956e-02 -1.105199e-03 9.998820e-01 -9.551571e+01 +9.998313e-01 1.055264e-02 -1.503758e-02 1.062982e+00 -1.044967e-02 9.999215e-01 6.909875e-03 1.390693e+00 1.510932e-02 -6.751569e-03 9.998631e-01 -9.400229e+01 +9.998229e-01 1.132651e-02 -1.503073e-02 1.036568e+00 -1.118018e-02 9.998896e-01 9.784020e-03 1.374673e+00 1.513989e-02 -9.614238e-03 9.998392e-01 -9.249143e+01 +9.998011e-01 1.312047e-02 -1.502431e-02 1.009148e+00 -1.294293e-02 9.998459e-01 1.185390e-02 1.361424e+00 1.517752e-02 -1.165708e-02 9.998169e-01 -9.098226e+01 +9.998064e-01 1.258318e-02 -1.512788e-02 9.847340e-01 -1.239264e-02 9.998435e-01 1.262391e-02 1.348472e+00 1.528436e-02 -1.243399e-02 9.998059e-01 -8.947609e+01 +9.998065e-01 1.207195e-02 -1.552940e-02 9.616474e-01 -1.190394e-02 9.998701e-01 1.086670e-02 1.333401e+00 1.565857e-02 -1.067974e-02 9.998204e-01 -8.797323e+01 +9.998224e-01 1.129864e-02 -1.508499e-02 9.399983e-01 -1.117443e-02 9.999031e-01 8.293534e-03 1.316473e+00 1.517723e-02 -8.123493e-03 9.998518e-01 -8.646690e+01 +9.998417e-01 1.069229e-02 -1.421860e-02 9.191412e-01 -1.057739e-02 9.999110e-01 8.131852e-03 1.298308e+00 1.430429e-02 -7.980167e-03 9.998659e-01 -8.496724e+01 +9.998529e-01 1.094089e-02 -1.320999e-02 8.995469e-01 -1.079722e-02 9.998823e-01 1.089828e-02 1.282847e+00 1.332768e-02 -1.075405e-02 9.998534e-01 -8.345436e+01 +9.998786e-01 9.161384e-03 -1.260632e-02 8.834484e-01 -9.026229e-03 9.999016e-01 1.073679e-02 1.268237e+00 1.270345e-02 -1.062170e-02 9.998629e-01 -8.194950e+01 +9.998867e-01 8.924084e-03 -1.212064e-02 8.679533e-01 -8.815571e-03 9.999208e-01 8.977002e-03 1.252710e+00 1.219980e-02 -8.869132e-03 9.998863e-01 -8.044554e+01 +9.998970e-01 8.621624e-03 -1.147891e-02 8.520469e-01 -8.521275e-03 9.999253e-01 8.762624e-03 1.234831e+00 1.155360e-02 -8.663904e-03 9.998957e-01 -7.894240e+01 +9.999072e-01 8.068648e-03 -1.097549e-02 8.381739e-01 -7.948384e-03 9.999083e-01 1.095748e-02 1.219714e+00 1.106290e-02 -1.086922e-02 9.998797e-01 -7.743960e+01 +9.999213e-01 7.106468e-03 -1.034404e-02 8.255732e-01 -6.970239e-03 9.998893e-01 1.314694e-02 1.207956e+00 1.043632e-02 -1.307380e-02 9.998601e-01 -7.593444e+01 +9.999246e-01 6.616504e-03 -1.034792e-02 8.134235e-01 -6.463607e-03 9.998704e-01 1.474004e-02 1.199179e+00 1.044411e-02 -1.467204e-02 9.998378e-01 -7.443200e+01 +9.999226e-01 6.162919e-03 -1.080590e-02 8.003155e-01 -6.012655e-03 9.998855e-01 1.388361e-02 1.189369e+00 1.089023e-02 -1.381756e-02 9.998452e-01 -7.293636e+01 +9.999143e-01 6.437677e-03 -1.140311e-02 7.849788e-01 -6.330936e-03 9.999360e-01 9.372277e-03 1.176896e+00 1.146272e-02 -9.299279e-03 9.998911e-01 -7.144336e+01 +9.998804e-01 9.638168e-03 -1.209595e-02 7.639540e-01 -9.555515e-03 9.999307e-01 6.872532e-03 1.160600e+00 1.216135e-02 -6.756125e-03 9.999032e-01 -6.995600e+01 +9.998636e-01 1.080134e-02 -1.249375e-02 7.450432e-01 -1.069166e-02 9.999040e-01 8.812699e-03 1.144297e+00 1.258774e-02 -8.677916e-03 9.998831e-01 -6.846260e+01 +9.998444e-01 1.216311e-02 -1.277391e-02 7.252411e-01 -1.203053e-02 9.998735e-01 1.040533e-02 1.128317e+00 1.289886e-02 -1.025003e-02 9.998643e-01 -6.697132e+01 +9.998683e-01 9.245344e-03 -1.333996e-02 7.107630e-01 -9.142950e-03 9.999284e-01 7.716532e-03 1.111896e+00 1.341035e-02 -7.593547e-03 9.998813e-01 -6.548911e+01 +9.998662e-01 8.101700e-03 -1.421152e-02 6.946295e-01 -7.985012e-03 9.999341e-01 8.248548e-03 1.096104e+00 1.427741e-02 -8.133963e-03 9.998650e-01 -6.400515e+01 +9.998632e-01 7.168635e-03 -1.490508e-02 6.777408e-01 -6.996316e-03 9.999084e-01 1.158139e-02 1.080622e+00 1.498673e-02 -1.147552e-02 9.998218e-01 -6.252551e+01 +9.998523e-01 6.260061e-03 -1.600617e-02 6.587746e-01 -6.098097e-03 9.999299e-01 1.014782e-02 1.067484e+00 1.606858e-02 -1.004871e-02 9.998204e-01 -6.104536e+01 +9.998328e-01 5.763396e-03 -1.735357e-02 6.370383e-01 -5.662902e-03 9.999669e-01 5.834658e-03 1.049226e+00 1.738662e-02 -5.735409e-03 9.998324e-01 -5.957557e+01 +9.998140e-01 5.161769e-03 -1.858173e-02 6.135026e-01 -5.039257e-03 9.999653e-01 6.634012e-03 1.030981e+00 1.861533e-02 -6.539139e-03 9.998053e-01 -5.810346e+01 +9.997897e-01 5.268217e-03 -1.981739e-02 5.856644e-01 -5.036417e-03 9.999185e-01 1.172866e-02 1.015669e+00 1.987756e-02 -1.162638e-02 9.997348e-01 -5.662762e+01 +9.997643e-01 4.956661e-03 -2.113885e-02 5.571177e-01 -4.709208e-03 9.999200e-01 1.173985e-02 1.005763e+00 2.119535e-02 -1.163754e-02 9.997076e-01 -5.516060e+01 +9.997430e-01 5.421569e-03 -2.201151e-02 5.253982e-01 -5.191608e-03 9.999315e-01 1.049109e-02 9.957028e-01 2.206689e-02 -1.037411e-02 9.997027e-01 -5.369802e+01 +9.997366e-01 6.646111e-03 -2.196887e-02 4.907091e-01 -6.412830e-03 9.999225e-01 1.067225e-02 9.846881e-01 2.203810e-02 -1.052855e-02 9.997017e-01 -5.223668e+01 +9.997252e-01 7.966123e-03 -2.204857e-02 4.561315e-01 -7.729505e-03 9.999118e-01 1.079625e-02 9.709516e-01 2.213263e-02 -1.062286e-02 9.996986e-01 -5.077854e+01 +9.997206e-01 8.051061e-03 -2.222549e-02 4.235407e-01 -7.821933e-03 9.999155e-01 1.037708e-02 9.558653e-01 2.230716e-02 -1.020033e-02 9.996991e-01 -4.932287e+01 +9.997240e-01 7.722918e-03 -2.218627e-02 3.928533e-01 -7.512660e-03 9.999262e-01 9.544790e-03 9.391869e-01 2.225835e-02 -9.375475e-03 9.997083e-01 -4.786940e+01 +9.997396e-01 7.072866e-03 -2.169461e-02 3.621644e-01 -6.865575e-03 9.999302e-01 9.614648e-03 9.230089e-01 2.176110e-02 -9.463196e-03 9.997184e-01 -4.641797e+01 +9.997566e-01 6.034064e-03 -2.122182e-02 3.335672e-01 -5.829469e-03 9.999360e-01 9.689560e-03 9.069681e-01 2.127893e-02 -9.563487e-03 9.997278e-01 -4.496842e+01 +9.997766e-01 4.542442e-03 -2.064113e-02 3.070324e-01 -4.343222e-03 9.999436e-01 9.686209e-03 8.911135e-01 2.068397e-02 -9.594394e-03 9.997400e-01 -4.352559e+01 +9.997953e-01 3.823003e-03 -1.986628e-02 2.806278e-01 -3.598325e-03 9.999293e-01 1.133304e-02 8.754699e-01 1.990820e-02 -1.125923e-02 9.997384e-01 -4.207912e+01 +9.998119e-01 4.019898e-03 -1.897195e-02 2.543730e-01 -3.804325e-03 9.999279e-01 1.138521e-02 8.594365e-01 1.901635e-02 -1.131089e-02 9.997552e-01 -4.063656e+01 +9.998220e-01 4.495945e-03 -1.832218e-02 2.281179e-01 -4.312328e-03 9.999402e-01 1.004882e-02 8.436096e-01 1.836627e-02 -9.968014e-03 9.997816e-01 -3.919717e+01 +9.998350e-01 5.004731e-03 -1.746088e-02 2.029690e-01 -4.864234e-03 9.999555e-01 8.079647e-03 8.253285e-01 1.750054e-02 -7.993378e-03 9.998149e-01 -3.776252e+01 +9.998441e-01 6.189759e-03 -1.653956e-02 1.777994e-01 -6.067079e-03 9.999538e-01 7.457353e-03 8.063360e-01 1.658496e-02 -7.355841e-03 9.998354e-01 -3.632796e+01 +9.998442e-01 8.141479e-03 -1.566539e-02 1.537249e-01 -7.988071e-03 9.999197e-01 9.830733e-03 7.865138e-01 1.574417e-02 -9.704062e-03 9.998290e-01 -3.489508e+01 +9.998526e-01 8.906088e-03 -1.468173e-02 1.326690e-01 -8.737024e-03 9.998952e-01 1.153962e-02 7.682861e-01 1.478297e-02 -1.140964e-02 9.998256e-01 -3.346381e+01 +9.998653e-01 9.263287e-03 -1.355059e-02 1.133742e-01 -9.110795e-03 9.998949e-01 1.127242e-02 7.522313e-01 1.365359e-02 -1.114744e-02 9.998447e-01 -3.203604e+01 +9.998785e-01 9.482928e-03 -1.237535e-02 9.746084e-02 -9.363547e-03 9.999094e-01 9.669376e-03 7.352840e-01 1.246592e-02 -9.552322e-03 9.998767e-01 -3.061396e+01 +9.999053e-01 8.379982e-03 -1.091685e-02 8.482880e-02 -8.301671e-03 9.999396e-01 7.199262e-03 7.168959e-01 1.097653e-02 -7.107951e-03 9.999145e-01 -2.919399e+01 +9.999173e-01 8.547511e-03 -9.614706e-03 7.224084e-02 -8.469286e-03 9.999309e-01 8.147705e-03 6.980984e-01 9.683685e-03 -8.065599e-03 9.999206e-01 -2.777753e+01 +9.999246e-01 9.152485e-03 -8.189666e-03 6.062565e-02 -9.068226e-03 9.999061e-01 1.026726e-02 6.785993e-01 8.282869e-03 -1.019222e-02 9.999138e-01 -2.635596e+01 +9.999358e-01 9.104301e-03 -6.743385e-03 5.256871e-02 -9.066955e-03 9.999435e-01 5.548381e-03 6.586934e-01 6.793519e-03 -5.486882e-03 9.999619e-01 -2.494768e+01 +9.999246e-01 1.096660e-02 -5.529149e-03 4.390241e-02 -1.096725e-02 9.999398e-01 -8.612968e-05 6.329309e-01 5.527872e-03 1.467634e-04 9.999847e-01 -2.354342e+01 +9.999173e-01 1.209460e-02 -4.368970e-03 3.720921e-02 -1.210507e-02 9.999239e-01 -2.377934e-03 6.021743e-01 4.339878e-03 2.430624e-03 9.999876e-01 -2.213989e+01 +9.999235e-01 1.188897e-02 -3.418280e-03 3.232865e-02 -1.190120e-02 9.999227e-01 -3.578946e-03 5.653751e-01 3.375467e-03 3.619354e-03 9.999878e-01 -2.073844e+01 +9.999317e-01 1.138156e-02 -2.646028e-03 2.925888e-02 -1.139097e-02 9.999287e-01 -3.566734e-03 5.295576e-01 2.605245e-03 3.596631e-03 9.999901e-01 -1.934063e+01 +9.999396e-01 1.075105e-02 -2.295642e-03 2.669736e-02 -1.075543e-02 9.999403e-01 -1.903248e-03 4.947389e-01 2.275043e-03 1.927824e-03 9.999956e-01 -1.794366e+01 +9.999493e-01 9.889531e-03 -1.899619e-03 2.516131e-02 -9.889237e-03 9.999511e-01 1.651180e-04 4.624741e-01 1.901160e-03 -1.463231e-04 9.999982e-01 -1.655026e+01 +9.999611e-01 8.655552e-03 -1.675731e-03 2.416042e-02 -8.654767e-03 9.999624e-01 4.762288e-04 4.312538e-01 1.679790e-03 -4.617064e-04 9.999985e-01 -1.516614e+01 +9.999673e-01 7.807279e-03 -2.093571e-03 2.354535e-02 -7.810553e-03 9.999683e-01 -1.559480e-03 3.987551e-01 2.081330e-03 1.575781e-03 9.999966e-01 -1.378259e+01 +9.999717e-01 7.018225e-03 -2.703494e-03 2.158789e-02 -7.024605e-03 9.999725e-01 -2.357227e-03 3.670075e-01 2.686877e-03 2.376151e-03 9.999936e-01 -1.240382e+01 +9.999593e-01 8.224788e-03 -3.700336e-03 1.528089e-02 -8.229507e-03 9.999653e-01 -1.261366e-03 3.343854e-01 3.689834e-03 1.291767e-03 9.999924e-01 -1.102737e+01 +9.999551e-01 8.112711e-03 -4.908754e-03 8.955879e-03 -8.114698e-03 9.999670e-01 -3.847374e-04 3.016035e-01 4.905472e-03 4.245538e-04 9.999879e-01 -9.654739e+00 +9.999418e-01 8.783783e-03 -6.258949e-03 -5.365659e-04 -8.784483e-03 9.999614e-01 -8.411024e-05 2.716196e-01 6.257969e-03 1.390877e-04 9.999804e-01 -8.285137e+00 +9.999374e-01 8.432227e-03 -7.359981e-03 -9.785478e-03 -8.423849e-03 9.999638e-01 1.168710e-03 2.414501e-01 7.369570e-03 -1.106637e-03 9.999722e-01 -6.914129e+00 +9.999346e-01 7.699825e-03 -8.456563e-03 -2.044470e-02 -7.705608e-03 9.999701e-01 -6.513404e-04 2.108318e-01 8.451296e-03 7.164614e-04 9.999640e-01 -5.548032e+00 +9.999381e-01 6.820873e-03 -8.786999e-03 -3.114140e-02 -6.842266e-03 9.999737e-01 -2.406709e-03 1.812868e-01 8.770353e-03 2.466684e-03 9.999585e-01 -4.183286e+00 +9.999335e-01 7.117782e-03 -9.073195e-03 -4.437224e-02 -7.146580e-03 9.999695e-01 -3.145252e-03 1.473329e-01 9.050532e-03 3.209885e-03 9.999539e-01 -2.818515e+00 +9.999265e-01 7.608354e-03 -9.436997e-03 -5.789727e-02 -7.635683e-03 9.999667e-01 -2.863106e-03 1.134699e-01 9.414901e-03 2.934954e-03 9.999514e-01 -1.456295e+00 +9.999193e-01 8.189613e-03 -9.713120e-03 -7.289734e-02 -8.207802e-03 9.999646e-01 -1.834026e-03 7.816926e-02 9.697757e-03 1.913602e-03 9.999512e-01 -9.070031e-02 +9.999109e-01 9.021878e-03 -9.841600e-03 -8.864261e-02 -9.048961e-03 9.999554e-01 -2.710606e-03 4.590358e-02 9.816707e-03 2.799421e-03 9.999479e-01 1.269419e+00 +9.999040e-01 9.472990e-03 -1.011565e-02 -1.031707e-01 -9.500380e-03 9.999513e-01 -2.662938e-03 1.177150e-02 1.008993e-02 2.758785e-03 9.999453e-01 2.629005e+00 +9.998998e-01 9.687175e-03 -1.032285e-02 -1.175645e-01 -9.710260e-03 9.999504e-01 -2.188326e-03 -2.016324e-02 1.030114e-02 2.288345e-03 9.999443e-01 3.988036e+00 +9.998955e-01 9.970539e-03 -1.046973e-02 -1.318827e-01 -9.995602e-03 9.999473e-01 -2.344029e-03 -5.346280e-02 1.044581e-02 2.448436e-03 9.999425e-01 5.344099e+00 +9.998980e-01 9.489532e-03 -1.067172e-02 -1.458828e-01 -9.519134e-03 9.999510e-01 -2.726330e-03 -8.812058e-02 1.064533e-02 2.827638e-03 9.999393e-01 6.704415e+00 +9.998956e-01 9.566852e-03 -1.082537e-02 -1.601769e-01 -9.603194e-03 9.999484e-01 -3.309954e-03 -1.221722e-01 1.079314e-02 3.413567e-03 9.999359e-01 8.059835e+00 +9.998965e-01 9.450261e-03 -1.085044e-02 -1.750950e-01 -9.474104e-03 9.999528e-01 -2.147965e-03 -1.546373e-01 1.082963e-02 2.250541e-03 9.999388e-01 9.415895e+00 +9.998797e-01 1.119674e-02 -1.073929e-02 -1.926087e-01 -1.120686e-02 9.999368e-01 -8.824675e-04 -1.870422e-01 1.072874e-02 1.002716e-03 9.999420e-01 1.077107e+01 +9.998823e-01 1.096505e-02 -1.073561e-02 -2.081545e-01 -1.097913e-02 9.999389e-01 -1.252834e-03 -2.207459e-01 1.072121e-02 1.370554e-03 9.999416e-01 1.212317e+01 +9.998837e-01 1.095582e-02 -1.060952e-02 -2.231040e-01 -1.097862e-02 9.999375e-01 -2.092453e-03 -2.534493e-01 1.058593e-02 2.208688e-03 9.999415e-01 1.347733e+01 +9.998894e-01 1.056645e-02 -1.046248e-02 -2.355330e-01 -1.058964e-02 9.999416e-01 -2.163256e-03 -2.892015e-01 1.043901e-02 2.273811e-03 9.999429e-01 1.483032e+01 +9.998869e-01 1.074386e-02 -1.052292e-02 -2.482197e-01 -1.076655e-02 9.999398e-01 -2.101941e-03 -3.237106e-01 1.049970e-02 2.214999e-03 9.999424e-01 1.618093e+01 +9.998978e-01 9.726524e-03 -1.047650e-02 -2.588532e-01 -9.742046e-03 9.999515e-01 -1.431374e-03 -3.582793e-01 1.046207e-02 1.533290e-03 9.999441e-01 1.753356e+01 +9.999021e-01 9.599717e-03 -1.018585e-02 -2.709142e-01 -9.610657e-03 9.999533e-01 -1.025395e-03 -3.936047e-01 1.017554e-02 1.123188e-03 9.999476e-01 1.888305e+01 +9.999007e-01 9.726336e-03 -1.019922e-02 -2.833573e-01 -9.742241e-03 9.999514e-01 -1.510705e-03 -4.284891e-01 1.018403e-02 1.609919e-03 9.999469e-01 2.023330e+01 +9.999027e-01 9.426946e-03 -1.027865e-02 -2.952092e-01 -9.454004e-03 9.999519e-01 -2.586919e-03 -4.630010e-01 1.025377e-02 2.683842e-03 9.999438e-01 2.158016e+01 +9.998918e-01 1.010698e-02 -1.068503e-02 -3.094675e-01 -1.012974e-02 9.999465e-01 -2.077221e-03 -4.966128e-01 1.066346e-02 2.185233e-03 9.999408e-01 2.292653e+01 +9.998897e-01 9.983924e-03 -1.099857e-02 -3.233764e-01 -1.000517e-02 9.999482e-01 -1.878507e-03 -5.315032e-01 1.097925e-02 1.988343e-03 9.999378e-01 2.427308e+01 +9.998822e-01 1.014293e-02 -1.151695e-02 -3.380715e-01 -1.016926e-02 9.999458e-01 -2.229930e-03 -5.652421e-01 1.149371e-02 2.346786e-03 9.999312e-01 2.561353e+01 +9.998789e-01 9.942275e-03 -1.197254e-02 -3.534582e-01 -9.952077e-03 9.999502e-01 -7.591861e-04 -5.991642e-01 1.196440e-02 8.782464e-04 9.999280e-01 2.695489e+01 +9.998859e-01 8.996626e-03 -1.213120e-02 -3.674572e-01 -8.989313e-03 9.999594e-01 6.573768e-04 -6.308020e-01 1.213662e-02 -5.482498e-04 9.999262e-01 2.829306e+01 +9.998867e-01 9.090725e-03 -1.199877e-02 -3.836725e-01 -9.091970e-03 9.999586e-01 -4.903920e-05 -6.611411e-01 1.199783e-02 1.581268e-04 9.999280e-01 2.962384e+01 +9.998990e-01 8.142627e-03 -1.164752e-02 -3.976799e-01 -8.155909e-03 9.999661e-01 -1.093090e-03 -6.925713e-01 1.163823e-02 1.187976e-03 9.999316e-01 3.095090e+01 +9.998969e-01 8.852172e-03 -1.131033e-02 -4.139985e-01 -8.868111e-03 9.999597e-01 -1.359635e-03 -7.240355e-01 1.129784e-02 1.459797e-03 9.999351e-01 3.228248e+01 +9.999079e-01 8.239612e-03 -1.078647e-02 -4.270073e-01 -8.248986e-03 9.999656e-01 -8.247296e-04 -7.566562e-01 1.077931e-02 9.136317e-04 9.999415e-01 3.360651e+01 +9.999192e-01 7.482778e-03 -1.027639e-02 -4.397568e-01 -7.485062e-03 9.999719e-01 -1.836766e-04 -7.887161e-01 1.027473e-02 2.605819e-04 9.999472e-01 3.492691e+01 +9.999249e-01 7.255525e-03 -9.873318e-03 -4.515375e-01 -7.259172e-03 9.999736e-01 -3.334670e-04 -8.206355e-01 9.870638e-03 4.051148e-04 9.999512e-01 3.624336e+01 +9.999364e-01 5.909102e-03 -9.608635e-03 -4.615286e-01 -5.910868e-03 9.999825e-01 -1.553373e-04 -8.517037e-01 9.607550e-03 2.121234e-04 9.999538e-01 3.755497e+01 +9.999427e-01 5.072329e-03 -9.427280e-03 -4.718552e-01 -5.065874e-03 9.999869e-01 7.085240e-04 -8.824570e-01 9.430751e-03 -6.607251e-04 9.999553e-01 3.886652e+01 +9.999418e-01 4.509516e-03 -9.806357e-03 -4.839122e-01 -4.491546e-03 9.999882e-01 1.853837e-03 -9.115305e-01 9.814602e-03 -1.809682e-03 9.999502e-01 4.017377e+01 +9.999319e-01 4.407113e-03 -1.081005e-02 -4.974895e-01 -4.383829e-03 9.999880e-01 2.176719e-03 -9.403596e-01 1.081951e-02 -2.129180e-03 9.999392e-01 4.148016e+01 +9.999166e-01 4.812225e-03 -1.198367e-02 -5.125043e-01 -4.789496e-03 9.999867e-01 1.924728e-03 -9.685698e-01 1.199278e-02 -1.867171e-03 9.999264e-01 4.277845e+01 +9.998867e-01 7.571241e-03 -1.301324e-02 -5.346231e-01 -7.532226e-03 9.999670e-01 3.044661e-03 -9.956525e-01 1.303586e-02 -2.946296e-03 9.999107e-01 4.407602e+01 +9.998733e-01 8.066496e-03 -1.371981e-02 -5.552041e-01 -7.979896e-03 9.999479e-01 6.355288e-03 -1.019285e+00 1.377036e-02 -6.244999e-03 9.998857e-01 4.537317e+01 +9.998558e-01 9.052465e-03 -1.436656e-02 -5.782583e-01 -8.908265e-03 9.999096e-01 1.006977e-02 -1.038533e+00 1.445642e-02 -9.940333e-03 9.998461e-01 4.667010e+01 +9.998414e-01 9.385942e-03 -1.513889e-02 -5.999916e-01 -9.183637e-03 9.998683e-01 1.337800e-02 -1.053627e+00 1.526246e-02 -1.323684e-02 9.997959e-01 4.796111e+01 +9.998213e-01 9.720731e-03 -1.621312e-02 -6.230983e-01 -9.477844e-03 9.998427e-01 1.499117e-02 -1.066505e+00 1.635629e-02 -1.483482e-02 9.997562e-01 4.924944e+01 +9.998219e-01 7.939037e-03 -1.712345e-02 -6.456359e-01 -7.719994e-03 9.998880e-01 1.282052e-02 -1.075808e+00 1.722331e-02 -1.268604e-02 9.997712e-01 5.052765e+01 +9.997930e-01 9.294848e-03 -1.809898e-02 -6.740058e-01 -9.098108e-03 9.998989e-01 1.092253e-02 -1.087279e+00 1.819867e-02 -1.075560e-02 9.997765e-01 5.181041e+01 +9.997666e-01 9.906171e-03 -1.920057e-02 -7.020633e-01 -9.710704e-03 9.999003e-01 1.024702e-02 -1.100738e+00 1.930017e-02 -1.005817e-02 9.997631e-01 5.308722e+01 +9.997359e-01 1.072286e-02 -2.032890e-02 -7.311397e-01 -1.051490e-02 9.998915e-01 1.030973e-02 -1.115793e+00 2.043725e-02 -1.009325e-02 9.997402e-01 5.436090e+01 +9.997114e-01 1.097557e-02 -2.136771e-02 -7.624769e-01 -1.078434e-02 9.999009e-01 9.044393e-03 -1.130431e+00 2.146486e-02 -8.811345e-03 9.997308e-01 5.562948e+01 +9.996850e-01 1.121076e-02 -2.245720e-02 -7.942812e-01 -1.098835e-02 9.998896e-01 1.000300e-02 -1.144783e+00 2.256686e-02 -9.753078e-03 9.996978e-01 5.690157e+01 +9.996625e-01 1.111683e-02 -2.348219e-02 -8.268987e-01 -1.086637e-02 9.998830e-01 1.076686e-02 -1.159941e+00 2.359914e-02 -1.050806e-02 9.996663e-01 5.817085e+01 +9.996411e-01 1.133862e-02 -2.427072e-02 -8.597866e-01 -1.108281e-02 9.998819e-01 1.064876e-02 -1.174664e+00 2.438860e-02 -1.037595e-02 9.996487e-01 5.943408e+01 +9.996203e-01 1.174607e-02 -2.492658e-02 -8.950914e-01 -1.149353e-02 9.998814e-01 1.025067e-02 -1.188757e+00 2.504403e-02 -9.960277e-03 9.996367e-01 6.069463e+01 +9.996152e-01 1.104936e-02 -2.544228e-02 -9.282884e-01 -1.079808e-02 9.998917e-01 9.992751e-03 -1.203865e+00 2.554994e-02 -9.714175e-03 9.996264e-01 6.194931e+01 +9.996124e-01 9.547512e-03 -2.615245e-02 -9.621792e-01 -9.313787e-03 9.999157e-01 9.044397e-03 -1.218811e+00 2.623660e-02 -8.797310e-03 9.996171e-01 6.320740e+01 +9.995977e-01 8.692473e-03 -2.699685e-02 -9.961734e-01 -8.447507e-03 9.999222e-01 9.174778e-03 -1.234090e+00 2.707450e-02 -8.943029e-03 9.995934e-01 6.445843e+01 +9.995780e-01 8.653869e-03 -2.772834e-02 -1.031828e+00 -8.356042e-03 9.999063e-01 1.083888e-02 -1.250518e+00 2.781954e-02 -1.060261e-02 9.995567e-01 6.571017e+01 +9.995595e-01 9.167532e-03 -2.822590e-02 -1.068654e+00 -8.888883e-03 9.999106e-01 9.981903e-03 -1.267809e+00 2.831489e-02 -9.726607e-03 9.995517e-01 6.695370e+01 +9.995346e-01 1.086485e-02 -2.850423e-02 -1.107414e+00 -1.063644e-02 9.999102e-01 8.152873e-03 -1.284607e+00 2.859025e-02 -7.845893e-03 9.995604e-01 6.819143e+01 +9.995060e-01 1.321087e-02 -2.851652e-02 -1.148265e+00 -1.297314e-02 9.998796e-01 8.505547e-03 -1.303043e+00 2.862545e-02 -8.131395e-03 9.995571e-01 6.943308e+01 +9.994795e-01 1.570538e-02 -2.818091e-02 -1.188155e+00 -1.546926e-02 9.998435e-01 8.577606e-03 -1.321203e+00 2.831121e-02 -8.137201e-03 9.995660e-01 7.066875e+01 +9.994736e-01 1.777784e-02 -2.713983e-02 -1.227083e+00 -1.754236e-02 9.998066e-01 8.890201e-03 -1.338073e+00 2.729263e-02 -8.409422e-03 9.995921e-01 7.190028e+01 +9.995210e-01 1.796413e-02 -2.520035e-02 -1.261385e+00 -1.770002e-02 9.997864e-01 1.066476e-02 -1.354666e+00 2.538656e-02 -1.021360e-02 9.996255e-01 7.312719e+01 +9.995454e-01 1.889959e-02 -2.349096e-02 -1.293464e+00 -1.862072e-02 9.997542e-01 1.203410e-02 -1.370635e+00 2.371263e-02 -1.159120e-02 9.996516e-01 7.434109e+01 +9.996174e-01 1.671055e-02 -2.204114e-02 -1.318225e+00 -1.645513e-02 9.997959e-01 1.171967e-02 -1.387753e+00 2.223249e-02 -1.135249e-02 9.996884e-01 7.554359e+01 +9.997005e-01 1.353066e-02 -2.039217e-02 -1.337076e+00 -1.339298e-02 9.998867e-01 6.873380e-03 -1.406295e+00 2.048286e-02 -6.598208e-03 9.997684e-01 7.672276e+01 +9.997246e-01 1.486884e-02 -1.815776e-02 -1.359396e+00 -1.473734e-02 9.998643e-01 7.354386e-03 -1.424263e+00 1.826465e-02 -7.084761e-03 9.998081e-01 7.788694e+01 +9.997738e-01 1.475585e-02 -1.531820e-02 -1.377966e+00 -1.456271e-02 9.998140e-01 1.264481e-02 -1.443308e+00 1.550194e-02 -1.241887e-02 9.998027e-01 7.903738e+01 +9.998040e-01 1.553055e-02 -1.227894e-02 -1.392300e+00 -1.537009e-02 9.997966e-01 1.305632e-02 -1.459771e+00 1.247921e-02 -1.286503e-02 9.998394e-01 8.015990e+01 +9.998389e-01 1.575425e-02 -8.602252e-03 -1.402951e+00 -1.567251e-02 9.998321e-01 9.488219e-03 -1.475612e+00 8.750289e-03 -9.351869e-03 9.999180e-01 8.126768e+01 +9.998735e-01 1.486270e-02 -5.660999e-03 -1.407266e+00 -1.483838e-02 9.998806e-01 4.315108e-03 -1.495464e+00 5.724457e-03 -4.230561e-03 9.999747e-01 8.236682e+01 +9.999111e-01 1.302760e-02 -2.842128e-03 -1.406566e+00 -1.303174e-02 9.999140e-01 -1.442424e-03 -1.518542e+00 2.823093e-03 1.479334e-03 9.999949e-01 8.346190e+01 +9.999364e-01 1.127162e-02 -4.142917e-04 -1.402636e+00 -1.127299e-02 9.999305e-01 -3.454388e-03 -1.542197e+00 3.753267e-04 3.458839e-03 9.999940e-01 8.455751e+01 +9.999502e-01 9.886800e-03 1.345364e-03 -1.397294e+00 -9.885214e-03 9.999504e-01 -1.181922e-03 -1.566145e+00 -1.356982e-03 1.168565e-03 9.999984e-01 8.565524e+01 +9.999444e-01 1.022223e-02 2.580627e-03 -1.394094e+00 -1.022552e-02 9.999469e-01 1.264405e-03 -1.587213e+00 -2.567564e-03 -1.290722e-03 9.999959e-01 8.675113e+01 +9.999403e-01 1.032786e-02 3.576178e-03 -1.391329e+00 -1.032915e-02 9.999466e-01 3.420709e-04 -1.608126e+00 -3.572454e-03 -3.789886e-04 9.999936e-01 8.783653e+01 +9.999365e-01 1.034840e-02 4.469650e-03 -1.385563e+00 -1.033960e-02 9.999445e-01 -1.988457e-03 -1.630039e+00 -4.489980e-03 1.942117e-03 9.999880e-01 8.891917e+01 +9.999270e-01 1.082670e-02 5.363927e-03 -1.380200e+00 -1.081171e-02 9.999376e-01 -2.816100e-03 -1.654701e+00 -5.394082e-03 2.757901e-03 9.999817e-01 8.999811e+01 +9.999268e-01 1.054403e-02 5.931181e-03 -1.372397e+00 -1.053967e-02 9.999441e-01 -7.666500e-04 -1.681009e+00 -5.938934e-03 7.040818e-04 9.999821e-01 9.107568e+01 +9.999395e-01 9.289105e-03 5.899274e-03 -1.363832e+00 -9.294397e-03 9.999564e-01 8.698777e-04 -1.705257e+00 -5.890937e-03 -9.246544e-04 9.999822e-01 9.214962e+01 +9.999513e-01 8.179152e-03 5.530713e-03 -1.356111e+00 -8.188528e-03 9.999650e-01 1.674311e-03 -1.726171e+00 -5.516826e-03 -1.719517e-03 9.999833e-01 9.321864e+01 +9.999715e-01 6.329244e-03 4.115017e-03 -1.348852e+00 -6.340199e-03 9.999764e-01 2.654283e-03 -1.747689e+00 -4.098120e-03 -2.680297e-03 9.999880e-01 9.428214e+01 +9.999906e-01 4.191084e-03 1.126218e-03 -1.343107e+00 -4.194215e-03 9.999873e-01 2.790845e-03 -1.769082e+00 -1.114507e-03 -2.795542e-03 9.999955e-01 9.534468e+01 +9.999948e-01 1.952887e-03 -2.563672e-03 -1.341283e+00 -1.951049e-03 9.999978e-01 7.193127e-04 -1.790649e+00 2.565071e-03 -7.143063e-04 9.999965e-01 9.639851e+01 +9.999790e-01 1.630426e-03 -6.272616e-03 -1.346362e+00 -1.647982e-03 9.999947e-01 -2.794737e-03 -1.812458e+00 6.268027e-03 2.805016e-03 9.999764e-01 9.745206e+01 +9.999468e-01 2.352878e-03 -1.004498e-02 -1.357998e+00 -2.420071e-03 9.999747e-01 -6.682308e-03 -1.835038e+00 1.002901e-02 6.706262e-03 9.999272e-01 9.850801e+01 +9.998897e-01 3.278344e-03 -1.448548e-02 -1.375059e+00 -3.391546e-03 9.999638e-01 -7.797173e-03 -1.861895e+00 1.445939e-02 7.845440e-03 9.998647e-01 9.957007e+01 +9.997993e-01 3.573218e-03 -1.971124e-02 -1.397412e+00 -3.702574e-03 9.999718e-01 -6.529899e-03 -1.887691e+00 1.968735e-02 6.601570e-03 9.997844e-01 1.006364e+02 +9.996516e-01 4.328603e-03 -2.603575e-02 -1.426691e+00 -4.454861e-03 9.999786e-01 -4.793320e-03 -1.913252e+00 2.601444e-02 4.907636e-03 9.996495e-01 1.017103e+02 +9.994472e-01 4.094737e-03 -3.299238e-02 -1.463118e+00 -4.216021e-03 9.999846e-01 -3.607363e-03 -1.939200e+00 3.297710e-02 3.744465e-03 9.994491e-01 1.027874e+02 +9.991751e-01 4.812453e-03 -4.032397e-02 -1.507808e+00 -4.947300e-03 9.999825e-01 -3.244960e-03 -1.964419e+00 4.030765e-02 3.441778e-03 9.991814e-01 1.038682e+02 +9.988927e-01 6.628557e-03 -4.657746e-02 -1.561792e+00 -6.731905e-03 9.999752e-01 -2.062290e-03 -1.988222e+00 4.656264e-02 2.373561e-03 9.989126e-01 1.049566e+02 +9.986543e-01 1.012518e-02 -5.086330e-02 -1.622720e+00 -1.017055e-02 9.999481e-01 -6.332057e-04 -2.010967e+00 5.085425e-02 1.149662e-03 9.987054e-01 1.060502e+02 +9.985334e-01 1.416334e-02 -5.225390e-02 -1.686244e+00 -1.423269e-02 9.998982e-01 -9.552021e-04 -2.034406e+00 5.223506e-02 1.697515e-03 9.986334e-01 1.071475e+02 +9.985431e-01 1.879615e-02 -5.058111e-02 -1.748773e+00 -1.891570e-02 9.998193e-01 -1.885656e-03 -2.056669e+00 5.053653e-02 2.839686e-03 9.987182e-01 1.082514e+02 +9.986659e-01 2.264617e-02 -4.640630e-02 -1.806035e+00 -2.280845e-02 9.997354e-01 -2.970244e-03 -2.079756e+00 4.632676e-02 4.024737e-03 9.989182e-01 1.093616e+02 +9.988525e-01 2.507315e-02 -4.080427e-02 -1.855701e+00 -2.519680e-02 9.996793e-01 -2.518591e-03 -2.102084e+00 4.072803e-02 3.543838e-03 9.991640e-01 1.104821e+02 +9.990574e-01 2.682532e-02 -3.412843e-02 -1.897032e+00 -2.688051e-02 9.996380e-01 -1.159008e-03 -2.123092e+00 3.408499e-02 2.075306e-03 9.994168e-01 1.116084e+02 +9.992736e-01 2.776193e-02 -2.610690e-02 -1.928092e+00 -2.779215e-02 9.996134e-01 -7.950258e-04 -2.145152e+00 2.607473e-02 1.520016e-03 9.996588e-01 1.127436e+02 +9.994407e-01 2.891245e-02 -1.680463e-02 -1.949092e+00 -2.894781e-02 9.995792e-01 -1.864732e-03 -2.166434e+00 1.674365e-02 2.350147e-03 9.998571e-01 1.138811e+02 +9.995400e-01 2.951898e-02 -6.963941e-03 -1.958712e+00 -2.954090e-02 9.995588e-01 -3.065392e-03 -2.187910e+00 6.870383e-03 3.269703e-03 9.999711e-01 1.150263e+02 +9.995813e-01 2.883750e-02 2.381917e-03 -1.956136e+00 -2.882901e-02 9.995781e-01 -3.527482e-03 -2.210288e+00 -2.482636e-03 3.457336e-03 9.999910e-01 1.161788e+02 +9.995419e-01 2.782959e-02 1.189496e-02 -1.940135e+00 -2.777611e-02 9.996034e-01 -4.637968e-03 -2.235787e+00 -1.201931e-02 4.305447e-03 9.999185e-01 1.173414e+02 +9.994423e-01 2.575447e-02 2.125459e-02 -1.913209e+00 -2.564016e-02 9.996553e-01 -5.633208e-03 -2.261146e+00 -2.139235e-02 5.085095e-03 9.997582e-01 1.185076e+02 +9.992569e-01 2.476838e-02 2.953176e-02 -1.876270e+00 -2.461681e-02 9.996819e-01 -5.485189e-03 -2.286958e+00 -2.965822e-02 4.754136e-03 9.995488e-01 1.196839e+02 +9.990366e-01 2.423355e-02 3.658675e-02 -1.833080e+00 -2.408414e-02 9.996997e-01 -4.519283e-03 -2.312120e+00 -3.668528e-02 3.633769e-03 9.993203e-01 1.208659e+02 +9.987992e-01 2.429063e-02 4.254466e-02 -1.781388e+00 -2.415386e-02 9.997013e-01 -3.725937e-03 -2.338144e+00 -4.262246e-02 2.693845e-03 9.990876e-01 1.220560e+02 +9.985232e-01 2.567729e-02 4.787673e-02 -1.725066e+00 -2.555452e-02 9.996684e-01 -3.174842e-03 -2.362701e+00 -4.794237e-02 1.946687e-03 9.988482e-01 1.232581e+02 +9.982176e-01 2.822631e-02 5.258225e-02 -1.665951e+00 -2.812578e-02 9.996009e-01 -2.651062e-03 -2.387598e+00 -5.263609e-02 1.167420e-03 9.986131e-01 1.244659e+02 +9.979275e-01 3.093217e-02 5.642671e-02 -1.602097e+00 -3.084342e-02 9.995212e-01 -2.443229e-03 -2.410925e+00 -5.647528e-02 6.977722e-04 9.984038e-01 1.256836e+02 +9.977625e-01 3.047971e-02 5.950676e-02 -1.529042e+00 -3.047169e-02 9.995351e-01 -1.042488e-03 -2.432251e+00 -5.951087e-02 -7.731151e-04 9.982274e-01 1.269096e+02 +9.976752e-01 3.041028e-02 6.098786e-02 -1.454190e+00 -3.042619e-02 9.995368e-01 -6.682034e-04 -2.455779e+00 -6.097994e-02 -1.188977e-03 9.981383e-01 1.281428e+02 +9.977337e-01 2.839515e-02 6.100185e-02 -1.374919e+00 -2.812060e-02 9.995902e-01 -5.354743e-03 -2.480551e+00 -6.112891e-02 3.627198e-03 9.981233e-01 1.293864e+02 +9.979098e-01 2.391628e-02 6.003360e-02 -1.292610e+00 -2.358693e-02 9.997026e-01 -6.188904e-03 -2.504395e+00 -6.016377e-02 4.759959e-03 9.981772e-01 1.306411e+02 +9.981257e-01 1.977442e-02 5.791465e-02 -1.212752e+00 -1.964845e-02 9.998032e-01 -2.743867e-03 -2.530425e+00 -5.795752e-02 1.600791e-03 9.983178e-01 1.319105e+02 +9.983955e-01 1.519630e-02 5.454844e-02 -1.135332e+00 -1.514701e-02 9.998844e-01 -1.316981e-03 -2.552624e+00 -5.456215e-02 4.886223e-04 9.985103e-01 1.331888e+02 +9.987108e-01 1.070166e-02 4.962045e-02 -1.063477e+00 -1.077369e-02 9.999412e-01 1.184333e-03 -2.571936e+00 -4.960486e-02 -1.717400e-03 9.987675e-01 1.344809e+02 +9.990454e-01 5.922890e-03 4.328192e-02 -9.982536e-01 -6.013204e-03 9.999800e-01 1.956722e-03 -2.593743e+00 -4.326947e-02 -2.215116e-03 9.990610e-01 1.357808e+02 +9.993315e-01 2.073275e-03 3.650068e-02 -9.419915e-01 -2.089383e-03 9.999977e-01 4.031660e-04 -2.613858e+00 -3.649976e-02 -4.791597e-04 9.993336e-01 1.370887e+02 +9.995513e-01 -3.841430e-04 2.995233e-02 -8.957984e-01 3.680378e-04 9.999998e-01 5.432080e-04 -2.633690e+00 -2.995254e-02 -5.319399e-04 9.995512e-01 1.384140e+02 +9.997209e-01 -1.140910e-03 2.359711e-02 -8.600700e-01 1.106136e-03 9.999983e-01 1.486680e-03 -2.654048e+00 -2.359876e-02 -1.460162e-03 9.997205e-01 1.397491e+02 +9.998371e-01 -8.371187e-04 1.803255e-02 -8.326782e-01 7.900712e-04 9.999962e-01 2.616006e-03 -2.674907e+00 -1.803468e-02 -2.601332e-03 9.998340e-01 1.410912e+02 +9.999182e-01 8.956099e-04 1.276188e-02 -8.166247e-01 -9.545678e-04 9.999889e-01 4.614484e-03 -2.693332e+00 -1.275761e-02 -4.626287e-03 9.999079e-01 1.424513e+02 +9.999704e-01 2.024220e-03 7.419893e-03 -8.082126e-01 -2.052174e-03 9.999908e-01 3.761699e-03 -2.711653e+00 -7.412210e-03 -3.776813e-03 9.999654e-01 1.438175e+02 +9.999933e-01 2.913491e-03 2.212671e-03 -8.063071e-01 -2.915208e-03 9.999954e-01 7.729679e-04 -2.728963e+00 -2.210409e-03 -7.794123e-04 9.999973e-01 1.451909e+02 +9.999882e-01 4.079509e-03 -2.643608e-03 -8.107742e-01 -4.082826e-03 9.999909e-01 -1.250286e-03 -2.750987e+00 2.638484e-03 1.261065e-03 9.999957e-01 1.465742e+02 +9.999711e-01 4.105639e-03 -6.405988e-03 -8.181994e-01 -4.141622e-03 9.999756e-01 -5.613686e-03 -2.779541e+00 6.382785e-03 5.640054e-03 9.999637e-01 1.479621e+02 +9.999475e-01 5.439807e-03 -8.683498e-03 -8.311338e-01 -5.520276e-03 9.999418e-01 -9.269763e-03 -2.811042e+00 8.632567e-03 9.317211e-03 9.999193e-01 1.493663e+02 +9.999281e-01 6.178314e-03 -1.028047e-02 -8.465134e-01 -6.281749e-03 9.999296e-01 -1.005943e-02 -2.846681e+00 1.021760e-02 1.012329e-02 9.998966e-01 1.507791e+02 +9.999067e-01 6.676256e-03 -1.191734e-02 -8.636978e-01 -6.788881e-03 9.999324e-01 -9.435052e-03 -2.884423e+00 1.185355e-02 9.515076e-03 9.998845e-01 1.522017e+02 +9.998853e-01 7.172633e-03 -1.333943e-02 -8.818614e-01 -7.283598e-03 9.999391e-01 -8.288559e-03 -2.922677e+00 1.327916e-02 8.384767e-03 9.998767e-01 1.536297e+02 +9.998585e-01 7.926808e-03 -1.483702e-02 -9.031410e-01 -8.024620e-03 9.999464e-01 -6.544361e-03 -2.959476e+00 1.478435e-02 6.662496e-03 9.998685e-01 1.550655e+02 +9.998354e-01 8.006171e-03 -1.628215e-02 -9.252286e-01 -8.093037e-03 9.999533e-01 -5.276084e-03 -2.995496e+00 1.623915e-02 5.406987e-03 9.998535e-01 1.565082e+02 +9.998005e-01 8.692671e-03 -1.798494e-02 -9.505879e-01 -8.764532e-03 9.999539e-01 -3.920530e-03 -3.030265e+00 1.795003e-02 4.077378e-03 9.998306e-01 1.579490e+02 +9.997709e-01 8.339827e-03 -1.971565e-02 -9.765171e-01 -8.375370e-03 9.999634e-01 -1.720796e-03 -3.064935e+00 1.970058e-02 1.885528e-03 9.998042e-01 1.593917e+02 +9.997253e-01 9.205868e-03 -2.155291e-02 -1.007339e+00 -9.215356e-03 9.999575e-01 -3.408414e-04 -3.096653e+00 2.154886e-02 5.393662e-04 9.997677e-01 1.608317e+02 +9.996815e-01 9.689927e-03 -2.330082e-02 -1.039444e+00 -9.717771e-03 9.999522e-01 -1.081953e-03 -3.129506e+00 2.328922e-02 1.308041e-03 9.997279e-01 1.622714e+02 +9.996388e-01 1.088222e-02 -2.457409e-02 -1.075629e+00 -1.093555e-02 9.999381e-01 -2.036797e-03 -3.162047e+00 2.455041e-02 2.304793e-03 9.996959e-01 1.637088e+02 +9.996116e-01 1.162841e-02 -2.532738e-02 -1.112662e+00 -1.169735e-02 9.999282e-01 -2.575432e-03 -3.196968e+00 2.529562e-02 2.870695e-03 9.996759e-01 1.651447e+02 +9.995946e-01 1.249824e-02 -2.558142e-02 -1.150964e+00 -1.261298e-02 9.999111e-01 -4.328692e-03 -3.232057e+00 2.552505e-02 4.649595e-03 9.996634e-01 1.665807e+02 +9.995851e-01 1.352936e-02 -2.542805e-02 -1.188887e+00 -1.365068e-02 9.998962e-01 -4.603208e-03 -3.267867e+00 2.536313e-02 4.948408e-03 9.996661e-01 1.680142e+02 +9.995898e-01 1.386313e-02 -2.506213e-02 -1.225583e+00 -1.393116e-02 9.998997e-01 -2.541691e-03 -3.303343e+00 2.502439e-02 2.889793e-03 9.996827e-01 1.694545e+02 +9.995985e-01 1.402493e-02 -2.461981e-02 -1.262468e+00 -1.405632e-02 9.999006e-01 -1.102440e-03 -3.337774e+00 2.460190e-02 1.448062e-03 9.996963e-01 1.708876e+02 +9.996115e-01 1.419757e-02 -2.398367e-02 -1.297634e+00 -1.421541e-02 9.998988e-01 -5.733376e-04 -3.371687e+00 2.397310e-02 9.140533e-04 9.997122e-01 1.723194e+02 +9.996153e-01 1.527226e-02 -2.315224e-02 -1.333194e+00 -1.528457e-02 9.998831e-01 -3.547561e-04 -3.405560e+00 2.314412e-02 7.084923e-04 9.997319e-01 1.737467e+02 +9.996284e-01 1.588357e-02 -2.215380e-02 -1.366304e+00 -1.591490e-02 9.998726e-01 -1.238561e-03 -3.440420e+00 2.213131e-02 1.590677e-03 9.997538e-01 1.751688e+02 +9.996391e-01 1.672955e-02 -2.101886e-02 -1.398479e+00 -1.676491e-02 9.998583e-01 -1.506960e-03 -3.475354e+00 2.099067e-02 1.858796e-03 9.997780e-01 1.765929e+02 +9.996701e-01 1.660095e-02 -1.960114e-02 -1.427528e+00 -1.665314e-02 9.998582e-01 -2.502347e-03 -3.511715e+00 1.955682e-02 2.827943e-03 9.998048e-01 1.780112e+02 +9.997181e-01 1.517311e-02 -1.826508e-02 -1.453391e+00 -1.525278e-02 9.998747e-01 -4.230826e-03 -3.547073e+00 1.819860e-02 4.508226e-03 9.998242e-01 1.794251e+02 +9.997759e-01 1.276794e-02 -1.688436e-02 -1.476326e+00 -1.283877e-02 9.999092e-01 -4.093273e-03 -3.583634e+00 1.683057e-02 4.309131e-03 9.998491e-01 1.808386e+02 +9.998138e-01 1.141090e-02 -1.556478e-02 -1.498241e+00 -1.143550e-02 9.999335e-01 -1.491953e-03 -3.619675e+00 1.554672e-02 1.669667e-03 9.998778e-01 1.822502e+02 +9.998438e-01 1.079241e-02 -1.399405e-02 -1.518870e+00 -1.075457e-02 9.999383e-01 2.776372e-03 -3.652469e+00 1.402316e-02 -2.625437e-03 9.998982e-01 1.836608e+02 +9.998537e-01 1.174643e-02 -1.243052e-02 -1.539735e+00 -1.172437e-02 9.999295e-01 1.846303e-03 -3.680137e+00 1.245134e-02 -1.700292e-03 9.999210e-01 1.850616e+02 +9.998568e-01 1.300544e-02 -1.083181e-02 -1.559212e+00 -1.301769e-02 9.999147e-01 -1.061251e-03 -3.708117e+00 1.081708e-02 1.202105e-03 9.999408e-01 1.864556e+02 +9.998674e-01 1.310364e-02 -9.668110e-03 -1.576113e+00 -1.312792e-02 9.999108e-01 -2.452292e-03 -3.742055e+00 9.635114e-03 2.578889e-03 9.999503e-01 1.878484e+02 +9.998816e-01 1.288894e-02 -8.405838e-03 -1.590302e+00 -1.291053e-02 9.999135e-01 -2.518920e-03 -3.777663e+00 8.372645e-03 2.627146e-03 9.999615e-01 1.892418e+02 +9.998969e-01 1.214596e-02 -7.662628e-03 -1.603074e+00 -1.214958e-02 9.999261e-01 -4.258046e-04 -3.811744e+00 7.656890e-03 5.188590e-04 9.999706e-01 1.906344e+02 +9.999174e-01 1.052472e-02 -7.372427e-03 -1.613327e+00 -1.051454e-02 9.999437e-01 1.417635e-03 -3.843743e+00 7.386933e-03 -1.339999e-03 9.999718e-01 1.920206e+02 +9.999302e-01 9.216314e-03 -7.391662e-03 -1.623756e+00 -9.210188e-03 9.999572e-01 8.626716e-04 -3.875123e+00 7.399298e-03 -7.945319e-04 9.999723e-01 1.934008e+02 +9.999411e-01 7.687602e-03 -7.661810e-03 -1.633867e+00 -7.694240e-03 9.999700e-01 -8.369925e-04 -3.905876e+00 7.655146e-03 8.958956e-04 9.999703e-01 1.947764e+02 +9.999390e-01 7.639871e-03 -7.983359e-03 -1.645539e+00 -7.658777e-03 9.999679e-01 -2.340083e-03 -3.938930e+00 7.965226e-03 2.401083e-03 9.999654e-01 1.961509e+02 +9.999402e-01 7.250304e-03 -8.187591e-03 -1.657445e+00 -7.274968e-03 9.999691e-01 -2.986454e-03 -3.973595e+00 8.165686e-03 3.045840e-03 9.999620e-01 1.975229e+02 +9.999342e-01 7.917978e-03 -8.305242e-03 -1.669867e+00 -7.932334e-03 9.999671e-01 -1.696767e-03 -4.009132e+00 8.291535e-03 1.762536e-03 9.999641e-01 1.988896e+02 +9.999310e-01 8.129002e-03 -8.482994e-03 -1.682304e+00 -8.131021e-03 9.999669e-01 -2.033912e-04 -4.042827e+00 8.481061e-03 2.723533e-04 9.999640e-01 2.002547e+02 +9.999274e-01 8.340017e-03 -8.703275e-03 -1.694878e+00 -8.339690e-03 9.999652e-01 7.408078e-05 -4.074851e+00 8.703591e-03 -1.492042e-06 9.999621e-01 2.016110e+02 +9.999241e-01 8.605957e-03 -8.817104e-03 -1.705984e+00 -8.602037e-03 9.999629e-01 4.826322e-04 -4.106859e+00 8.820931e-03 -4.067497e-04 9.999610e-01 2.029698e+02 +9.999185e-01 9.302688e-03 -8.740575e-03 -1.717412e+00 -9.298686e-03 9.999566e-01 4.986847e-04 -4.139885e+00 8.744836e-03 -4.173674e-04 9.999617e-01 2.043226e+02 +9.999159e-01 9.399784e-03 -8.937425e-03 -1.727574e+00 -9.401125e-03 9.999558e-01 -1.077690e-04 -4.171862e+00 8.936018e-03 1.917825e-04 9.999601e-01 2.056689e+02 +9.999171e-01 9.092707e-03 -9.122822e-03 -1.737778e+00 -9.097895e-03 9.999584e-01 -5.271022e-04 -4.204811e+00 9.117651e-03 6.100575e-04 9.999583e-01 2.070122e+02 +9.999198e-01 8.654113e-03 -9.251870e-03 -1.746442e+00 -8.666408e-03 9.999616e-01 -1.289368e-03 -4.238781e+00 9.240357e-03 1.369446e-03 9.999564e-01 2.083506e+02 +9.999189e-01 8.682762e-03 -9.322143e-03 -1.757196e+00 -8.688232e-03 9.999621e-01 -5.461852e-04 -4.270954e+00 9.317048e-03 6.271345e-04 9.999564e-01 2.096908e+02 +9.999123e-01 9.179577e-03 -9.542219e-03 -1.768399e+00 -9.178489e-03 9.999578e-01 1.579489e-04 -4.303818e+00 9.543268e-03 -7.035119e-05 9.999545e-01 2.110251e+02 +9.999134e-01 8.750535e-03 -9.827801e-03 -1.780005e+00 -8.752422e-03 9.999617e-01 -1.488808e-04 -4.335485e+00 9.826123e-03 2.348857e-04 9.999517e-01 2.123505e+02 +9.999095e-01 8.499700e-03 -1.042769e-02 -1.792488e+00 -8.499948e-03 9.999638e-01 2.076070e-05 -4.366042e+00 1.042749e-02 6.787670e-05 9.999456e-01 2.136668e+02 +9.999083e-01 7.362392e-03 -1.136858e-02 -1.802728e+00 -7.346949e-03 9.999720e-01 1.399744e-03 -4.397364e+00 1.137856e-02 -1.316091e-03 9.999344e-01 2.149667e+02 +9.998904e-01 7.280593e-03 -1.289052e-02 -1.814957e+00 -7.236642e-03 9.999678e-01 3.453043e-03 -4.428604e+00 1.291525e-02 -3.359379e-03 9.999110e-01 2.162478e+02 +9.998760e-01 6.337258e-03 -1.441585e-02 -1.826714e+00 -6.255424e-03 9.999641e-01 5.714833e-03 -4.458316e+00 1.445155e-02 -5.623945e-03 9.998798e-01 2.175072e+02 +9.998505e-01 6.934611e-03 -1.584311e-02 -1.842513e+00 -6.805620e-03 9.999433e-01 8.181322e-03 -4.486884e+00 1.589894e-02 -8.072274e-03 9.998410e-01 2.187426e+02 +9.998191e-01 7.930483e-03 -1.728774e-02 -1.859734e+00 -7.788959e-03 9.999357e-01 8.238527e-03 -4.515014e+00 1.735197e-02 -8.102381e-03 9.998166e-01 2.199508e+02 +9.997922e-01 7.968728e-03 -1.876385e-02 -1.877890e+00 -7.833830e-03 9.999430e-01 7.251914e-03 -4.540479e+00 1.882057e-02 -7.103412e-03 9.997977e-01 2.211287e+02 +9.997504e-01 7.551267e-03 -2.102683e-02 -1.895168e+00 -7.390881e-03 9.999431e-01 7.695046e-03 -4.569335e+00 2.108374e-02 -7.537717e-03 9.997493e-01 2.222852e+02 +9.996746e-01 7.551955e-03 -2.436480e-02 -1.917244e+00 -7.372129e-03 9.999450e-01 7.462025e-03 -4.598297e+00 2.441981e-02 -7.279974e-03 9.996753e-01 2.234108e+02 +9.995815e-01 6.737814e-03 -2.813216e-02 -1.941670e+00 -6.543690e-03 9.999542e-01 6.986858e-03 -4.625178e+00 2.817795e-02 -6.799844e-03 9.995798e-01 2.245051e+02 +9.994698e-01 7.623291e-03 -3.165418e-02 -1.971966e+00 -7.414553e-03 9.999500e-01 6.706525e-03 -4.651833e+00 3.170372e-02 -6.468266e-03 9.994764e-01 2.255672e+02 +9.993698e-01 8.261262e-03 -3.452264e-02 -2.004581e+00 -8.045493e-03 9.999472e-01 6.384374e-03 -4.679495e+00 3.457357e-02 -6.102597e-03 9.993835e-01 2.266035e+02 +9.992722e-01 1.056957e-02 -3.665114e-02 -2.040151e+00 -1.033103e-02 9.999242e-01 6.691751e-03 -4.706339e+00 3.671909e-02 -6.308235e-03 9.993057e-01 2.276035e+02 +9.992210e-01 1.057024e-02 -3.802292e-02 -2.073778e+00 -1.027522e-02 9.999156e-01 7.946193e-03 -4.731016e+00 3.810371e-02 -7.549306e-03 9.992453e-01 2.285742e+02 +9.991677e-01 1.062093e-02 -3.938547e-02 -2.106014e+00 -1.024246e-02 9.998995e-01 9.798736e-03 -4.755443e+00 3.948559e-02 -9.387173e-03 9.991761e-01 2.295125e+02 +9.991121e-01 1.048654e-02 -4.080517e-02 -2.139617e+00 -1.007524e-02 9.998965e-01 1.027226e-02 -4.778138e+00 4.090866e-02 -9.852017e-03 9.991143e-01 2.304146e+02 +9.990370e-01 1.082683e-02 -4.251827e-02 -2.174190e+00 -1.040481e-02 9.998945e-01 1.013437e-02 -4.799162e+00 4.262351e-02 -9.682214e-03 9.990443e-01 2.312868e+02 +9.989592e-01 1.017154e-02 -4.446472e-02 -2.207888e+00 -9.749455e-03 9.999054e-01 9.699184e-03 -4.818374e+00 4.455917e-02 -9.255579e-03 9.989639e-01 2.321263e+02 +9.988665e-01 1.127910e-02 -4.624455e-02 -2.243669e+00 -1.091462e-02 9.999074e-01 8.126702e-03 -4.838575e+00 4.633193e-02 -7.612746e-03 9.988971e-01 2.329333e+02 +9.988185e-01 1.281120e-02 -4.687709e-02 -2.280068e+00 -1.256032e-02 9.999052e-01 5.642761e-03 -4.860372e+00 4.694494e-02 -5.047301e-03 9.988847e-01 2.337189e+02 +9.988537e-01 1.431853e-02 -4.567530e-02 -2.314971e+00 -1.425772e-02 9.998970e-01 1.656898e-03 -4.881633e+00 4.569432e-02 -1.003772e-03 9.989550e-01 2.344921e+02 +9.989893e-01 1.592924e-02 -4.203076e-02 -2.346879e+00 -1.601516e-02 9.998703e-01 -1.708103e-03 -4.903083e+00 4.199810e-02 2.379507e-03 9.991149e-01 2.352654e+02 +9.991859e-01 1.566786e-02 -3.717535e-02 -2.372559e+00 -1.578253e-02 9.998715e-01 -2.792938e-03 -4.923693e+00 3.712682e-02 3.377386e-03 9.993049e-01 2.360372e+02 +9.993581e-01 1.415485e-02 -3.291097e-02 -2.391165e+00 -1.423317e-02 9.998964e-01 -2.146836e-03 -4.943065e+00 3.287718e-02 2.613886e-03 9.994560e-01 2.368075e+02 +9.995074e-01 1.246894e-02 -2.879997e-02 -2.406340e+00 -1.250456e-02 9.999212e-01 -1.056776e-03 -4.961684e+00 2.878453e-02 1.416387e-03 9.995846e-01 2.375762e+02 +9.996376e-01 1.117471e-02 -2.449259e-02 -2.421540e+00 -1.117944e-02 9.999375e-01 -5.601485e-05 -4.979606e+00 2.449044e-02 3.298088e-04 9.997000e-01 2.383384e+02 +9.997386e-01 1.119289e-02 -1.993575e-02 -2.438172e+00 -1.119139e-02 9.999373e-01 1.867437e-04 -4.997815e+00 1.993660e-02 3.641468e-05 9.998013e-01 2.391021e+02 +9.998224e-01 1.087433e-02 -1.539577e-02 -2.449188e+00 -1.087590e-02 9.999408e-01 -1.832973e-05 -5.016120e+00 1.539466e-02 1.857701e-04 9.998815e-01 2.398593e+02 +9.998777e-01 1.091797e-02 -1.119574e-02 -2.457471e+00 -1.091986e-02 9.999403e-01 -1.069537e-04 -5.032857e+00 1.119391e-02 2.291972e-04 9.999373e-01 2.406138e+02 +9.999126e-01 1.096613e-02 -7.382659e-03 -2.464848e+00 -1.096472e-02 9.999398e-01 2.316705e-04 -5.049016e+00 7.384756e-03 -1.507007e-04 9.999727e-01 2.413652e+02 +9.999348e-01 1.076581e-02 -3.802846e-03 -2.471118e+00 -1.076117e-02 9.999413e-01 1.240418e-03 -5.064022e+00 3.815977e-03 -1.199413e-03 9.999920e-01 2.421130e+02 +9.999389e-01 1.103487e-02 -6.452769e-04 -2.477940e+00 -1.103319e-02 9.999358e-01 2.558946e-03 -5.076752e+00 6.734735e-04 -2.551669e-03 9.999965e-01 2.428585e+02 +9.999462e-01 1.029158e-02 1.271865e-03 -2.481229e+00 -1.029538e-02 9.999424e-01 3.013502e-03 -5.090455e+00 -1.240778e-03 -3.026433e-03 9.999947e-01 2.436012e+02 +9.999489e-01 9.827357e-03 2.361305e-03 -2.485941e+00 -9.832033e-03 9.999497e-01 1.975849e-03 -5.103671e+00 -2.341769e-03 -1.998963e-03 9.999953e-01 2.443383e+02 +9.999453e-01 9.973889e-03 3.162717e-03 -2.487604e+00 -9.971653e-03 9.999500e-01 -7.225253e-04 -5.118722e+00 -3.169765e-03 6.909488e-04 9.999947e-01 2.450752e+02 +9.999332e-01 1.088235e-02 3.893034e-03 -2.493249e+00 -1.086468e-02 9.999307e-01 -4.530871e-03 -5.131839e+00 -3.942070e-03 4.488272e-03 9.999822e-01 2.458164e+02 +9.999314e-01 1.088615e-02 4.328560e-03 -2.494730e+00 -1.085683e-02 9.999183e-01 -6.741594e-03 -5.147361e+00 -4.401596e-03 6.694136e-03 9.999679e-01 2.465623e+02 +9.999418e-01 1.006026e-02 3.890944e-03 -2.497272e+00 -1.003353e-02 9.999263e-01 -6.830947e-03 -5.164438e+00 -3.959379e-03 6.791509e-03 9.999691e-01 2.473157e+02 +9.999495e-01 9.474676e-03 3.352411e-03 -2.498606e+00 -9.453014e-03 9.999347e-01 -6.420287e-03 -5.182585e+00 -3.413022e-03 6.388272e-03 9.999738e-01 2.480723e+02 +9.999413e-01 1.049023e-02 2.707354e-03 -2.503085e+00 -1.047337e-02 9.999261e-01 -6.169404e-03 -5.199298e+00 -2.771872e-03 6.140686e-03 9.999773e-01 2.488329e+02 +9.999390e-01 1.083270e-02 2.144089e-03 -2.506486e+00 -1.081597e-02 9.999121e-01 -7.668262e-03 -5.218219e+00 -2.226968e-03 7.644603e-03 9.999683e-01 2.495991e+02 +9.999548e-01 9.177994e-03 2.504348e-03 -2.508505e+00 -9.152254e-03 9.999070e-01 -1.010403e-02 -5.237784e+00 -2.596850e-03 1.008066e-02 9.999458e-01 2.503665e+02 +9.999736e-01 6.470664e-03 3.303288e-03 -2.505563e+00 -6.430964e-03 9.999086e-01 -1.189109e-02 -5.256841e+00 -3.379929e-03 1.186954e-02 9.999239e-01 2.511395e+02 +9.999758e-01 5.281873e-03 4.530930e-03 -2.503453e+00 -5.237654e-03 9.999391e-01 -9.716539e-03 -5.273084e+00 -4.581976e-03 9.692572e-03 9.999425e-01 2.519216e+02 +9.999406e-01 9.433827e-03 5.467482e-03 -2.508541e+00 -9.412875e-03 9.999483e-01 -3.845713e-03 -5.289235e+00 -5.503479e-03 3.794020e-03 9.999777e-01 2.527116e+02 +9.999297e-01 9.641464e-03 6.907654e-03 -2.507121e+00 -9.656426e-03 9.999511e-01 2.135714e-03 -5.306929e+00 -6.886725e-03 -2.202266e-03 9.999739e-01 2.535088e+02 +9.999322e-01 7.620517e-03 8.801850e-03 -2.498934e+00 -7.637402e-03 9.999690e-01 1.886147e-03 -5.321532e+00 -8.787205e-03 -1.953241e-03 9.999595e-01 2.543037e+02 +9.998970e-01 8.014346e-03 1.190449e-02 -2.491981e+00 -7.965181e-03 9.999596e-01 -4.171834e-03 -5.336196e+00 -1.193744e-02 4.076583e-03 9.999204e-01 2.550990e+02 +9.998410e-01 9.660556e-03 1.499153e-02 -2.485561e+00 -9.524730e-03 9.999132e-01 -9.105475e-03 -5.351123e+00 -1.507820e-02 8.961235e-03 9.998462e-01 2.559000e+02 +9.997865e-01 1.130946e-02 1.729403e-02 -2.475778e+00 -1.113862e-02 9.998885e-01 -9.943296e-03 -5.370200e+00 -1.740456e-02 9.748541e-03 9.998010e-01 2.567068e+02 +9.997447e-01 1.120578e-02 1.962191e-02 -2.461593e+00 -1.104347e-02 9.999040e-01 -8.361325e-03 -5.392720e+00 -1.971372e-02 8.142495e-03 9.997725e-01 2.575259e+02 +9.997246e-01 8.891802e-03 2.171671e-02 -2.442073e+00 -8.767519e-03 9.999447e-01 -5.811556e-03 -5.414196e+00 -2.176718e-02 5.619554e-03 9.997473e-01 2.583481e+02 +9.997106e-01 5.280783e-03 2.346869e-02 -2.418788e+00 -5.177078e-03 9.999765e-01 -4.477485e-03 -5.432422e+00 -2.349179e-02 4.354690e-03 9.997146e-01 2.591759e+02 +9.996641e-01 4.670670e-03 2.549158e-02 -2.398099e+00 -4.540290e-03 9.999763e-01 -5.170153e-03 -5.451575e+00 -2.551513e-02 5.052677e-03 9.996617e-01 2.600072e+02 +9.996032e-01 6.624154e-03 2.737855e-02 -2.379400e+00 -6.420206e-03 9.999510e-01 -7.530449e-03 -5.472421e+00 -2.742710e-02 7.351684e-03 9.995968e-01 2.608436e+02 +9.995532e-01 8.088178e-03 2.877476e-02 -2.357178e+00 -7.777341e-03 9.999103e-01 -1.089807e-02 -5.492976e+00 -2.886032e-02 1.066941e-02 9.995265e-01 2.616878e+02 +9.995051e-01 8.368310e-03 3.032272e-02 -2.331649e+00 -7.980024e-03 9.998849e-01 -1.290364e-02 -5.513461e+00 -3.042722e-02 1.265528e-02 9.994569e-01 2.625408e+02 +9.994346e-01 9.257638e-03 3.232330e-02 -2.305211e+00 -8.893630e-03 9.998956e-01 -1.138719e-02 -5.536213e+00 -3.242535e-02 1.109328e-02 9.994126e-01 2.634078e+02 +9.993508e-01 1.038315e-02 3.449830e-02 -2.278446e+00 -1.006528e-02 9.999054e-01 -9.375279e-03 -5.560785e+00 -3.459239e-02 9.021957e-03 9.993608e-01 2.642827e+02 +9.992965e-01 1.075830e-02 3.592686e-02 -2.248880e+00 -1.044322e-02 9.999054e-01 -8.946231e-03 -5.585020e+00 -3.601971e-02 8.564744e-03 9.993144e-01 2.651670e+02 +9.992793e-01 1.073554e-02 3.640937e-02 -2.217026e+00 -1.039931e-02 9.999016e-01 -9.411746e-03 -5.608340e+00 -3.650683e-02 9.026329e-03 9.992926e-01 2.660593e+02 +9.992961e-01 8.639368e-03 3.650557e-02 -2.181048e+00 -8.294582e-03 9.999196e-01 -9.585727e-03 -5.632766e+00 -3.658545e-02 9.276180e-03 9.992875e-01 2.669604e+02 +9.993047e-01 7.187293e-03 3.658430e-02 -2.144562e+00 -6.879141e-03 9.999398e-01 -8.542033e-03 -5.657825e+00 -3.664349e-02 8.284425e-03 9.992941e-01 2.678693e+02 +9.993004e-01 6.086866e-03 3.690053e-02 -2.107091e+00 -5.783862e-03 9.999487e-01 -8.312626e-03 -5.684566e+00 -3.694924e-02 8.093382e-03 9.992844e-01 2.687872e+02 +9.993015e-01 5.331312e-03 3.698893e-02 -2.072995e+00 -5.047568e-03 9.999571e-01 -7.760237e-03 -5.710527e+00 -3.702872e-02 7.568111e-03 9.992856e-01 2.697117e+02 +9.993114e-01 4.804147e-03 3.679318e-02 -2.039857e+00 -4.555353e-03 9.999662e-01 -6.842832e-03 -5.735484e+00 -3.682482e-02 6.670513e-03 9.992995e-01 2.706435e+02 +9.993194e-01 5.341212e-03 3.649913e-02 -2.008137e+00 -5.160256e-03 9.999739e-01 -5.050263e-03 -5.759967e+00 -3.652515e-02 4.858481e-03 9.993209e-01 2.715780e+02 +9.993532e-01 5.038453e-03 3.560629e-02 -1.977183e+00 -4.885341e-03 9.999784e-01 -4.385857e-03 -5.786935e+00 -3.562762e-02 4.209071e-03 9.993563e-01 2.725156e+02 +9.994115e-01 5.132943e-03 3.391536e-02 -1.948577e+00 -4.978627e-03 9.999768e-01 -4.632976e-03 -5.813039e+00 -3.393836e-02 4.461397e-03 9.994140e-01 2.734511e+02 +9.994858e-01 5.387659e-03 3.160784e-02 -1.923694e+00 -5.211505e-03 9.999704e-01 -5.652905e-03 -5.837506e+00 -3.163736e-02 5.485273e-03 9.994844e-01 2.743868e+02 +9.995565e-01 6.857947e-03 2.898023e-02 -1.903306e+00 -6.675370e-03 9.999573e-01 -6.392186e-03 -5.862752e+00 -2.902283e-02 6.195897e-03 9.995596e-01 2.753220e+02 +9.996180e-01 8.514883e-03 2.629539e-02 -1.886301e+00 -8.345081e-03 9.999436e-01 -6.560566e-03 -5.888992e+00 -2.634977e-02 6.338622e-03 9.996327e-01 2.762556e+02 +9.996760e-01 9.689845e-03 2.353655e-02 -1.871958e+00 -9.551224e-03 9.999364e-01 -5.995004e-03 -5.914599e+00 -2.359314e-02 5.768258e-03 9.997050e-01 2.771894e+02 +9.997224e-01 1.068062e-02 2.100385e-02 -1.860171e+00 -1.058638e-02 9.999334e-01 -4.593014e-03 -5.940087e+00 -2.105151e-02 4.369384e-03 9.997689e-01 2.781217e+02 +9.997710e-01 1.071425e-02 1.852399e-02 -1.850165e+00 -1.066890e-02 9.999398e-01 -2.545723e-03 -5.965237e+00 -1.855015e-02 2.347510e-03 9.998252e-01 2.790549e+02 +9.998082e-01 1.084615e-02 1.630911e-02 -1.841130e+00 -1.082870e-02 9.999407e-01 -1.158029e-03 -5.989292e+00 -1.632070e-02 9.812008e-04 9.998663e-01 2.799822e+02 +9.998377e-01 1.107780e-02 1.420800e-02 -1.834878e+00 -1.107304e-02 9.999386e-01 -4.138802e-04 -6.011766e+00 -1.421172e-02 2.564879e-04 9.998990e-01 2.809067e+02 +9.998581e-01 1.147113e-02 1.233381e-02 -1.829538e+00 -1.147046e-02 9.999342e-01 -1.255600e-04 -6.033194e+00 -1.233444e-02 -1.593163e-05 9.999239e-01 2.818284e+02 +9.998863e-01 1.060708e-02 1.072039e-02 -1.824423e+00 -1.060543e-02 9.999437e-01 -2.111885e-04 -6.054240e+00 -1.072203e-02 9.747080e-05 9.999425e-01 2.827472e+02 +9.999039e-01 1.030296e-02 9.271631e-03 -1.820378e+00 -1.029719e-02 9.999467e-01 -6.701255e-04 -6.076007e+00 -9.278042e-03 5.745899e-04 9.999568e-01 2.836626e+02 +9.999160e-01 1.034896e-02 7.803210e-03 -1.819188e+00 -1.034215e-02 9.999461e-01 -9.136697e-04 -6.097253e+00 -7.812245e-03 8.328916e-04 9.999691e-01 2.845738e+02 +9.999180e-01 1.112185e-02 6.341957e-03 -1.820078e+00 -1.112122e-02 9.999381e-01 -1.343928e-04 -6.118356e+00 -6.343060e-03 6.385208e-05 9.999799e-01 2.854729e+02 +9.999265e-01 1.100402e-02 5.098273e-03 -1.821293e+00 -1.100905e-02 9.999389e-01 9.596741e-04 -6.140076e+00 -5.087401e-03 -1.015730e-03 9.999866e-01 2.863559e+02 +9.999164e-01 1.225528e-02 4.132102e-03 -1.824665e+00 -1.225768e-02 9.999247e-01 5.559105e-04 -6.162957e+00 -4.124978e-03 -6.065132e-04 9.999913e-01 2.872165e+02 +9.998853e-01 1.472443e-02 3.541050e-03 -1.831132e+00 -1.471882e-02 9.998904e-01 -1.607192e-03 -6.186044e+00 -3.564327e-03 1.554888e-03 9.999924e-01 2.880602e+02 +9.998455e-01 1.726903e-02 3.272629e-03 -1.835812e+00 -1.725374e-02 9.998403e-01 -4.644346e-03 -6.208970e+00 -3.352309e-03 4.587163e-03 9.999839e-01 2.888905e+02 +9.998156e-01 1.893316e-02 3.210282e-03 -1.838573e+00 -1.891072e-02 9.997975e-01 -6.883107e-03 -6.232745e+00 -3.339951e-03 6.821128e-03 9.999712e-01 2.897169e+02 +9.997806e-01 2.064512e-02 3.544867e-03 -1.841599e+00 -2.061808e-02 9.997592e-01 -7.504371e-03 -6.257807e+00 -3.698942e-03 7.429635e-03 9.999656e-01 2.905416e+02 +9.997359e-01 2.262203e-02 4.044413e-03 -1.843827e+00 -2.258880e-02 9.997122e-01 -8.081122e-03 -6.281585e+00 -4.226061e-03 7.987628e-03 9.999592e-01 2.913657e+02 +9.997049e-01 2.378395e-02 4.943895e-03 -1.844053e+00 -2.373936e-02 9.996786e-01 -8.890345e-03 -6.305431e+00 -5.153753e-03 8.770356e-03 9.999483e-01 2.921857e+02 +9.996476e-01 2.574672e-02 6.461941e-03 -1.843243e+00 -2.568194e-02 9.996210e-01 -9.916378e-03 -6.332348e+00 -6.714806e-03 9.746928e-03 9.999300e-01 2.930004e+02 +9.996044e-01 2.695498e-02 8.028663e-03 -1.840209e+00 -2.687211e-02 9.995862e-01 -1.025729e-02 -6.360716e+00 -8.301826e-03 1.003748e-02 9.999152e-01 2.938122e+02 +9.995672e-01 2.792092e-02 9.269551e-03 -1.836186e+00 -2.783653e-02 9.995709e-01 -9.111955e-03 -6.387429e+00 -9.519989e-03 8.849978e-03 9.999155e-01 2.946199e+02 +9.995716e-01 2.743437e-02 1.020005e-02 -1.829836e+00 -2.736189e-02 9.995998e-01 -7.179074e-03 -6.414405e+00 -1.039292e-02 6.896905e-03 9.999222e-01 2.954284e+02 +9.996041e-01 2.626205e-02 1.009843e-02 -1.823832e+00 -2.621280e-02 9.996440e-01 -4.979358e-03 -6.440313e+00 -1.022561e-02 4.712678e-03 9.999366e-01 2.962317e+02 +9.996482e-01 2.500295e-02 8.856661e-03 -1.817940e+00 -2.497842e-02 9.996838e-01 -2.870060e-03 -6.464190e+00 -8.925621e-03 2.647825e-03 9.999567e-01 2.970309e+02 +9.996795e-01 2.422393e-02 7.353445e-03 -1.814744e+00 -2.421551e-02 9.997060e-01 -1.231507e-03 -6.486179e+00 -7.381115e-03 1.053046e-03 9.999722e-01 2.978283e+02 +9.997097e-01 2.336701e-02 5.873977e-03 -1.812035e+00 -2.336494e-02 9.997269e-01 -4.208807e-04 -6.506511e+00 -5.882207e-03 2.835140e-04 9.999827e-01 2.986243e+02 +9.997434e-01 2.221300e-02 4.447164e-03 -1.809517e+00 -2.221642e-02 9.997529e-01 7.179632e-04 -6.524789e+00 -4.430117e-03 -8.165782e-04 9.999899e-01 2.994226e+02 +9.997879e-01 2.044351e-02 2.478338e-03 -1.807621e+00 -2.044671e-02 9.997901e-01 1.267676e-03 -6.541554e+00 -2.451902e-03 -1.318080e-03 9.999961e-01 3.002232e+02 diff --git a/tools/Ground-Truth/dataset/poses/07.txt b/tools/Ground-Truth/dataset/poses/07.txt new file mode 100644 index 0000000..010ace0 --- /dev/null +++ b/tools/Ground-Truth/dataset/poses/07.txt @@ -0,0 +1,1101 @@ +1.000000e+00 1.197625e-11 1.704638e-10 5.551115e-17 1.197625e-11 1.000000e+00 3.562503e-10 0.000000e+00 1.704638e-10 3.562503e-10 1.000000e+00 2.220446e-16 +9.999795e-01 5.025123e-04 -6.380358e-03 -4.596714e-03 -5.005160e-04 9.999998e-01 3.144878e-04 -2.001524e-03 6.380515e-03 -3.112871e-04 9.999796e-01 9.154274e-02 +9.999096e-01 1.061516e-03 -1.340599e-02 -1.001116e-02 -1.058762e-03 9.999994e-01 2.126022e-04 -4.359704e-03 1.340621e-02 -1.983884e-04 9.999101e-01 1.857373e-01 +9.997800e-01 1.386756e-03 -2.092925e-02 -1.753371e-02 -1.395506e-03 9.999989e-01 -4.034725e-04 -6.859665e-03 2.092867e-02 4.325913e-04 9.997809e-01 2.834672e-01 +9.995454e-01 2.025309e-03 -3.008212e-02 -2.863192e-02 -2.080074e-03 9.999962e-01 -1.789331e-03 -6.726660e-03 3.007839e-02 1.851091e-03 9.995458e-01 3.873100e-01 +9.991403e-01 2.230707e-03 -4.139680e-02 -4.273697e-02 -2.379114e-03 9.999909e-01 -3.536042e-03 -7.303015e-03 4.138854e-02 3.631490e-03 9.991365e-01 5.011396e-01 +9.984892e-01 2.145631e-03 -5.490591e-02 -6.000009e-02 -2.394373e-03 9.999871e-01 -4.464951e-03 -8.065471e-03 5.489562e-02 4.589671e-03 9.984816e-01 6.279359e-01 +9.974753e-01 2.223074e-03 -7.097932e-02 -8.275693e-02 -2.545053e-03 9.999869e-01 -4.446103e-03 -8.995000e-03 7.096851e-02 4.615524e-03 9.974679e-01 7.669396e-01 +9.959798e-01 9.912399e-04 -8.957233e-02 -1.090497e-01 -1.397593e-03 9.999890e-01 -4.473982e-03 -1.033982e-02 8.956691e-02 4.581182e-03 9.959703e-01 9.191805e-01 +9.939836e-01 -3.564687e-04 -1.095286e-01 -1.415335e-01 -1.406643e-04 9.999897e-01 -4.531084e-03 -1.195088e-02 1.095291e-01 4.519231e-03 9.939733e-01 1.081913e+00 +9.912980e-01 -4.511767e-04 -1.316366e-01 -1.816057e-01 -1.745510e-04 9.999887e-01 -4.741873e-03 -1.604515e-02 1.316372e-01 4.723586e-03 9.912867e-01 1.251378e+00 +9.877899e-01 2.927872e-03 -1.557641e-01 -2.325643e-01 -3.900867e-03 9.999747e-01 -5.941284e-03 -2.265364e-02 1.557428e-01 6.476356e-03 9.877764e-01 1.425643e+00 +9.834265e-01 7.281907e-03 -1.811611e-01 -2.934590e-01 -8.809762e-03 9.999321e-01 -7.630442e-03 -3.116429e-02 1.810932e-01 9.099964e-03 9.834238e-01 1.604140e+00 +9.780772e-01 1.080196e-02 -2.079623e-01 -3.616512e-01 -1.279341e-02 9.998842e-01 -8.233354e-03 -3.933357e-02 2.078493e-01 1.071340e-02 9.781022e-01 1.788640e+00 +9.713483e-01 1.158386e-02 -2.373782e-01 -4.366243e-01 -1.400444e-02 9.998657e-01 -8.513365e-03 -4.313507e-02 2.372477e-01 1.159379e-02 9.713800e-01 1.979231e+00 +9.632837e-01 1.344571e-02 -2.681487e-01 -5.224919e-01 -1.613640e-02 9.998391e-01 -7.832912e-03 -4.573638e-02 2.680003e-01 1.187227e-02 9.633457e-01 2.173020e+00 +9.538090e-01 1.577198e-02 -2.999995e-01 -6.200940e-01 -1.861376e-02 9.998048e-01 -6.616866e-03 -4.902232e-02 2.998367e-01 1.189534e-02 9.539164e-01 2.368741e+00 +9.425175e-01 1.774119e-02 -3.336855e-01 -7.248452e-01 -2.073817e-02 9.997702e-01 -5.421185e-03 -5.140743e-02 3.335126e-01 1.202959e-02 9.426689e-01 2.565689e+00 +9.299713e-01 2.036643e-02 -3.670676e-01 -8.394934e-01 -2.385302e-02 9.997031e-01 -4.964301e-03 -5.397789e-02 3.668575e-01 1.337233e-02 9.301810e-01 2.758285e+00 +9.160371e-01 2.349847e-02 -4.004045e-01 -9.687591e-01 -2.746958e-02 9.996139e-01 -4.180152e-03 -5.101001e-02 4.001517e-01 1.482812e-02 9.163290e-01 2.950416e+00 +8.999654e-01 2.432815e-02 -4.352819e-01 -1.103633e+00 -2.866013e-02 9.995834e-01 -3.388838e-03 -4.676236e-02 4.350182e-01 1.552507e-02 9.002878e-01 3.142085e+00 +8.815780e-01 2.050712e-02 -4.715927e-01 -1.242764e+00 -2.543755e-02 9.996681e-01 -4.081633e-03 -4.292676e-02 4.713525e-01 1.559444e-02 8.818071e-01 3.333105e+00 +8.604449e-01 1.550968e-02 -5.093075e-01 -1.392475e+00 -2.063887e-02 9.997772e-01 -4.422429e-03 -4.238966e-02 5.091254e-01 1.431679e-02 8.605733e-01 3.523028e+00 +8.357453e-01 1.684757e-02 -5.488588e-01 -1.564446e+00 -2.109935e-02 9.997763e-01 -1.439127e-03 -4.491985e-02 5.487118e-01 1.278331e-02 8.359139e-01 3.706267e+00 +8.069523e-01 2.370092e-02 -5.901408e-01 -1.761568e+00 -2.696201e-02 9.996311e-01 3.279095e-03 -4.899414e-02 5.900009e-01 1.326531e-02 8.072937e-01 3.880703e+00 +7.747743e-01 2.685279e-02 -6.316674e-01 -1.969361e+00 -3.022770e-02 9.995283e-01 5.415012e-03 -5.141144e-02 6.315149e-01 1.489844e-02 7.752206e-01 4.049498e+00 +7.390815e-01 2.703623e-02 -6.730732e-01 -2.187835e+00 -3.078163e-02 9.995059e-01 6.348111e-03 -5.358748e-02 6.729124e-01 1.602652e-02 7.395486e-01 4.215884e+00 +6.998654e-01 2.300743e-02 -7.139041e-01 -2.415527e+00 -2.506270e-02 9.996566e-01 7.646713e-03 -5.318918e-02 7.138350e-01 1.254069e-02 7.002017e-01 4.382391e+00 +6.574738e-01 1.958832e-02 -7.532227e-01 -2.663146e+00 -2.008945e-02 9.997623e-01 8.464136e-03 -5.287039e-02 7.532096e-01 9.566887e-03 6.577111e-01 4.540774e+00 +6.131629e-01 1.930946e-02 -7.897204e-01 -2.929115e+00 -1.750863e-02 9.997878e-01 1.085159e-02 -5.283789e-02 7.897624e-01 7.173130e-03 6.133709e-01 4.687680e+00 +5.654772e-01 2.029055e-02 -8.245143e-01 -3.215512e+00 -1.550389e-02 9.997822e-01 1.397070e-02 -5.138930e-02 8.246182e-01 4.883068e-03 5.656686e-01 4.824434e+00 +5.147145e-01 2.089948e-02 -8.571069e-01 -3.517839e+00 -1.382236e-02 9.997752e-01 1.607760e-02 -4.877551e-02 8.572503e-01 3.571869e-03 5.148876e-01 4.948178e+00 +4.622315e-01 2.267230e-02 -8.864694e-01 -3.836955e+00 -1.311577e-02 9.997385e-01 1.873032e-02 -4.505658e-02 8.866623e-01 2.968993e-03 4.624080e-01 5.057271e+00 +4.081172e-01 2.482780e-02 -9.125918e-01 -4.177130e+00 -1.202969e-02 9.996896e-01 2.181762e-02 -3.878842e-02 9.128503e-01 2.074055e-03 4.082892e-01 5.153468e+00 +3.528221e-01 2.685154e-02 -9.353051e-01 -4.534335e+00 -1.174859e-02 9.996365e-01 2.426655e-02 -3.325067e-02 9.356167e-01 2.426748e-03 3.530093e-01 5.233794e+00 +2.977517e-01 2.999078e-02 -9.541721e-01 -4.911075e+00 -9.323251e-03 9.995501e-01 2.850773e-02 -2.945435e-02 9.545979e-01 4.077656e-04 2.978973e-01 5.302451e+00 +2.439423e-01 3.226578e-02 -9.692528e-01 -5.299329e+00 -5.239211e-03 9.994756e-01 3.195328e-02 -2.697748e-02 9.697756e-01 -2.716632e-03 2.439834e-01 5.360943e+00 +1.928119e-01 3.260781e-02 -9.806938e-01 -5.701357e+00 -2.205280e-03 9.994595e-01 3.279820e-02 -2.303083e-02 9.812333e-01 -4.161174e-03 1.927796e-01 5.401694e+00 +1.451008e-01 3.362423e-02 -9.888454e-01 -6.122091e+00 -3.991990e-03 9.994341e-01 3.339852e-02 -1.604266e-02 9.894089e-01 -8.986869e-04 1.451529e-01 5.421290e+00 +1.020609e-01 3.392393e-02 -9.941995e-01 -6.558994e+00 -6.144850e-03 9.994208e-01 3.347129e-02 -5.757046e-03 9.947592e-01 2.693100e-03 1.022102e-01 5.427674e+00 +6.378191e-02 3.251618e-02 -9.974340e-01 -7.009091e+00 -7.384401e-03 9.994570e-01 3.210994e-02 6.191584e-03 9.979366e-01 5.317422e-03 6.398739e-02 5.424017e+00 +2.904726e-02 2.991174e-02 -9.991304e-01 -7.473426e+00 -6.521623e-03 9.995365e-01 2.973431e-02 1.625113e-02 9.995568e-01 5.652255e-03 2.922887e-02 5.410697e+00 +-2.721994e-03 2.726005e-02 -9.996247e-01 -7.950411e+00 -5.718749e-03 9.996116e-01 2.727527e-02 2.306424e-02 9.999800e-01 5.790849e-03 -2.565041e-03 5.389282e+00 +-2.964894e-02 2.550783e-02 -9.992348e-01 -8.444612e+00 -6.326376e-03 9.996495e-01 2.570614e-02 3.066422e-02 9.995404e-01 7.083698e-03 -2.947717e-02 5.353644e+00 +-5.091764e-02 2.313000e-02 -9.984350e-01 -8.953007e+00 -6.820021e-03 9.997004e-01 2.350713e-02 4.057477e-02 9.986796e-01 8.006278e-03 -5.074464e-02 5.310729e+00 +-6.733280e-02 2.173972e-02 -9.974937e-01 -9.480377e+00 -6.474859e-03 9.997320e-01 2.222558e-02 5.248992e-02 9.977096e-01 7.955144e-03 -6.717399e-02 5.263869e+00 +-8.060838e-02 2.217432e-02 -9.964992e-01 -1.002302e+01 -5.344046e-03 9.997285e-01 2.267848e-02 6.141731e-02 9.967316e-01 7.153416e-03 -8.046799e-02 5.211227e+00 +-9.045247e-02 2.383599e-02 -9.956155e-01 -1.057921e+01 -6.387145e-03 9.996791e-01 2.451356e-02 6.596199e-02 9.958803e-01 8.576455e-03 -9.027120e-02 5.153075e+00 +-9.725791e-02 2.540281e-02 -9.949350e-01 -1.115274e+01 -8.559783e-03 9.996159e-01 2.635907e-02 6.936405e-02 9.952224e-01 1.108006e-02 -9.700311e-02 5.088360e+00 +-1.018114e-01 2.626013e-02 -9.944570e-01 -1.173941e+01 -8.587813e-03 9.995911e-01 2.727492e-02 7.855473e-02 9.947667e-01 1.131711e-02 -1.015442e-01 5.025880e+00 +-1.035005e-01 2.648562e-02 -9.942767e-01 -1.234412e+01 -6.117944e-03 9.996095e-01 2.726454e-02 9.123047e-02 9.946106e-01 8.904824e-03 -1.032980e-01 4.964841e+00 +-1.028278e-01 2.847192e-02 -9.942916e-01 -1.296427e+01 -3.919262e-03 9.995709e-01 2.902843e-02 1.026715e-01 9.946915e-01 6.881821e-03 -1.026721e-01 4.901812e+00 +-1.013578e-01 3.126980e-02 -9.943585e-01 -1.360015e+01 -4.596263e-03 9.994805e-01 3.189940e-02 1.095163e-01 9.948395e-01 7.803588e-03 -1.011614e-01 4.835681e+00 +-9.950488e-02 3.165295e-02 -9.945335e-01 -1.425164e+01 -7.042716e-03 9.994464e-01 3.251396e-02 1.178242e-01 9.950122e-01 1.023952e-02 -9.922688e-02 4.767225e+00 +-9.786425e-02 2.880843e-02 -9.947827e-01 -1.491341e+01 -8.778970e-03 9.995170e-01 2.980919e-02 1.296149e-01 9.951611e-01 1.165042e-02 -9.756407e-02 4.697363e+00 +-9.663340e-02 2.858456e-02 -9.949095e-01 -1.559372e+01 -9.168533e-03 9.995195e-01 2.960754e-02 1.450798e-01 9.952778e-01 1.198294e-02 -9.632490e-02 4.629999e+00 +-9.508533e-02 3.088559e-02 -9.949899e-01 -1.629098e+01 -8.691167e-03 9.994547e-01 3.185476e-02 1.622254e-01 9.954312e-01 1.167655e-02 -9.476505e-02 4.563302e+00 +-9.324592e-02 3.432541e-02 -9.950512e-01 -1.700478e+01 -9.606841e-03 9.993280e-01 3.537320e-02 1.770188e-01 9.955968e-01 1.285771e-02 -9.285350e-02 4.494630e+00 +-9.143352e-02 3.749733e-02 -9.951049e-01 -1.773322e+01 -1.072094e-02 9.991958e-01 3.863657e-02 1.905594e-01 9.957535e-01 1.420114e-02 -9.095798e-02 4.426532e+00 +-8.963018e-02 3.633795e-02 -9.953120e-01 -1.847183e+01 -1.191924e-02 9.992235e-01 3.755412e-02 2.092753e-01 9.959038e-01 1.522934e-02 -8.912746e-02 4.359249e+00 +-8.776869e-02 3.343541e-02 -9.955796e-01 -1.922427e+01 -1.418124e-02 9.992933e-01 3.481034e-02 2.305555e-01 9.960400e-01 1.717381e-02 -8.723251e-02 4.290984e+00 +-8.620014e-02 3.252667e-02 -9.957467e-01 -1.998833e+01 -1.553740e-02 9.993014e-01 3.398785e-02 2.503189e-01 9.961567e-01 1.840107e-02 -8.563454e-02 4.223122e+00 +-8.451284e-02 3.487323e-02 -9.958119e-01 -2.077310e+01 -1.290088e-02 9.992653e-01 3.608905e-02 2.703516e-01 9.963389e-01 1.589684e-02 -8.400085e-02 4.161929e+00 +-8.331618e-02 3.705888e-02 -9.958338e-01 -2.156448e+01 -1.052013e-02 9.992199e-01 3.806506e-02 2.880249e-01 9.964677e-01 1.364774e-02 -8.286132e-02 4.100217e+00 +-8.195788e-02 3.938854e-02 -9.958571e-01 -2.236419e+01 -9.754524e-03 9.991391e-01 4.032114e-02 3.062236e-01 9.965881e-01 1.301875e-02 -8.150311e-02 4.035961e+00 +-8.125065e-02 3.526391e-02 -9.960697e-01 -2.316415e+01 -9.827283e-03 9.992970e-01 3.617980e-02 3.216152e-01 9.966453e-01 1.272829e-02 -8.084698e-02 3.971019e+00 +-8.074505e-02 2.784209e-02 -9.963458e-01 -2.396950e+01 -8.508473e-03 9.995541e-01 2.862128e-02 3.342058e-01 9.966985e-01 1.078841e-02 -8.047215e-02 3.908970e+00 +-8.068463e-02 2.317276e-02 -9.964703e-01 -2.478947e+01 -5.031547e-03 9.997075e-01 2.365546e-02 3.492536e-01 9.967270e-01 6.922422e-03 -8.054443e-02 3.849052e+00 +-8.117506e-02 2.268473e-02 -9.964417e-01 -2.561886e+01 -3.485151e-03 9.997284e-01 2.304348e-02 3.615096e-01 9.966938e-01 5.343309e-03 -8.107395e-02 3.786079e+00 +-8.098689e-02 3.123790e-02 -9.962255e-01 -2.646136e+01 -4.490308e-03 9.994872e-01 3.170522e-02 3.717697e-01 9.967051e-01 7.041069e-03 -8.080509e-02 3.716343e+00 +-8.132601e-02 3.806049e-02 -9.959606e-01 -2.730755e+01 -5.642357e-03 9.992370e-01 3.864644e-02 3.854991e-01 9.966716e-01 8.762529e-03 -8.104921e-02 3.644752e+00 +-8.165962e-02 4.388270e-02 -9.956937e-01 -2.815287e+01 -7.595689e-03 9.989738e-01 4.465022e-02 4.028815e-01 9.966314e-01 1.120910e-02 -8.124250e-02 3.569541e+00 +-8.204879e-02 4.465936e-02 -9.956272e-01 -2.899762e+01 -9.387220e-03 9.989165e-01 4.558051e-02 4.194172e-01 9.965841e-01 1.308600e-02 -8.154066e-02 3.492898e+00 +-8.245294e-02 4.133613e-02 -9.957373e-01 -2.983721e+01 -9.690603e-03 9.990589e-01 4.227647e-02 4.370064e-01 9.965479e-01 1.313512e-02 -8.197477e-02 3.418460e+00 +-8.290210e-02 3.805547e-02 -9.958308e-01 -3.067424e+01 -9.508351e-03 9.991949e-01 3.897560e-02 4.566603e-01 9.965124e-01 1.269987e-02 -8.247351e-02 3.346046e+00 +-8.288970e-02 3.922072e-02 -9.957866e-01 -3.151586e+01 -1.105292e-02 9.991276e-01 4.027237e-02 4.763855e-01 9.964975e-01 1.434452e-02 -8.238388e-02 3.271990e+00 +-8.269813e-02 4.194649e-02 -9.956915e-01 -3.235442e+01 -1.214292e-02 9.989972e-01 4.309431e-02 4.917256e-01 9.965007e-01 1.565442e-02 -8.210584e-02 3.198821e+00 +-8.271724e-02 4.082259e-02 -9.957366e-01 -3.319517e+01 -1.302830e-02 9.990310e-01 4.203994e-02 5.076454e-01 9.964879e-01 1.645018e-02 -8.210524e-02 3.123626e+00 +-8.231200e-02 3.566380e-02 -9.959683e-01 -3.402626e+01 -1.376549e-02 9.992235e-01 3.691803e-02 5.241899e-01 9.965116e-01 1.674879e-02 -8.175715e-02 3.051261e+00 +-8.195133e-02 3.105421e-02 -9.961524e-01 -3.486004e+01 -1.499027e-02 9.993629e-01 3.238752e-02 5.386702e-01 9.965236e-01 1.758679e-02 -8.143361e-02 2.980358e+00 +-8.151395e-02 3.157687e-02 -9.961718e-01 -3.569639e+01 -1.501861e-02 9.993456e-01 3.290641e-02 5.500320e-01 9.965591e-01 1.764345e-02 -8.098637e-02 2.910621e+00 +-8.074712e-02 3.441770e-02 -9.961402e-01 -3.653345e+01 -1.407711e-02 9.992646e-01 3.566675e-02 5.579548e-01 9.966352e-01 1.690276e-02 -8.020323e-02 2.843137e+00 +-8.028235e-02 3.893236e-02 -9.960115e-01 -3.737375e+01 -1.355742e-02 9.991018e-01 4.014595e-02 5.707777e-01 9.966800e-01 1.672636e-02 -7.968242e-02 2.775070e+00 +-7.964970e-02 4.443042e-02 -9.958322e-01 -3.821476e+01 -1.275581e-02 9.988789e-01 4.558661e-02 5.878615e-01 9.967413e-01 1.633361e-02 -7.899366e-02 2.706985e+00 +-7.980664e-02 4.835639e-02 -9.956367e-01 -3.904918e+01 -1.285875e-02 9.986896e-01 4.953538e-02 6.055646e-01 9.967275e-01 1.675590e-02 -7.908026e-02 2.638855e+00 +-7.952916e-02 4.776542e-02 -9.956875e-01 -3.988167e+01 -1.253987e-02 9.987243e-01 4.891272e-02 6.246496e-01 9.967537e-01 1.637579e-02 -7.882874e-02 2.572257e+00 +-7.935204e-02 4.425698e-02 -9.958637e-01 -4.071171e+01 -1.242385e-02 9.988924e-01 4.538155e-02 6.464858e-01 9.967693e-01 1.597358e-02 -7.871431e-02 2.504806e+00 +-7.897161e-02 3.959310e-02 -9.960903e-01 -4.153840e+01 -1.315326e-02 9.990826e-01 4.075486e-02 6.640169e-01 9.967901e-01 1.632031e-02 -7.837838e-02 2.436154e+00 +-7.862370e-02 3.683575e-02 -9.962236e-01 -4.236520e+01 -1.711449e-02 9.991199e-01 3.829356e-02 6.807227e-01 9.967575e-01 2.006064e-02 -7.792408e-02 2.363072e+00 +-7.912445e-02 3.465562e-02 -9.962622e-01 -4.319143e+01 -2.040105e-02 9.991299e-01 3.637566e-02 6.977483e-01 9.966560e-01 2.320300e-02 -7.834860e-02 2.290205e+00 +-7.976546e-02 3.312770e-02 -9.962630e-01 -4.401519e+01 -1.910751e-02 9.992131e-01 3.475564e-02 7.092788e-01 9.966305e-01 2.180841e-02 -7.906970e-02 2.223683e+00 +-8.099499e-02 2.976202e-02 -9.962700e-01 -4.483883e+01 -1.535850e-02 9.993981e-01 3.110410e-02 7.206987e-01 9.965962e-01 1.782049e-02 -8.048914e-02 2.160908e+00 +-8.168221e-02 2.762876e-02 -9.962754e-01 -4.566121e+01 -1.115209e-02 9.995277e-01 2.863330e-02 7.331961e-01 9.965961e-01 1.344938e-02 -8.133552e-02 2.096619e+00 +-8.331048e-02 3.088015e-02 -9.960451e-01 -4.648335e+01 -1.024723e-02 9.994403e-01 3.184251e-02 7.434451e-01 9.964710e-01 1.285952e-02 -8.294742e-02 2.028253e+00 +-8.506616e-02 3.760111e-02 -9.956655e-01 -4.730744e+01 -8.393766e-03 9.992251e-01 3.845268e-02 7.534145e-01 9.963400e-01 1.162841e-02 -8.468463e-02 1.959122e+00 +-8.682806e-02 4.163558e-02 -9.953529e-01 -4.812333e+01 -6.298404e-03 9.990833e-01 4.234107e-02 7.646921e-01 9.962034e-01 9.945529e-03 -8.648623e-02 1.890493e+00 +-8.855103e-02 4.048818e-02 -9.952484e-01 -4.893314e+01 -5.319431e-03 9.991400e-01 4.111980e-02 7.767209e-01 9.960575e-01 8.935358e-03 -8.825951e-02 1.820295e+00 +-8.958858e-02 3.722221e-02 -9.952831e-01 -4.973553e+01 -9.200308e-03 9.992278e-01 3.819790e-02 7.874193e-01 9.959364e-01 1.257901e-02 -8.917694e-02 1.740695e+00 +-9.088125e-02 3.306855e-02 -9.953125e-01 -5.053252e+01 -1.334325e-02 9.993184e-01 3.442002e-02 7.989932e-01 9.957724e-01 1.640884e-02 -9.037806e-02 1.659366e+00 +-9.202649e-02 3.137353e-02 -9.952622e-01 -5.132871e+01 -1.768445e-02 9.992944e-01 3.313583e-02 8.126433e-01 9.955995e-01 2.065004e-02 -9.140673e-02 1.575304e+00 +-9.301301e-02 3.268320e-02 -9.951283e-01 -5.212276e+01 -1.993854e-02 9.991995e-01 3.468054e-02 8.219496e-01 9.954653e-01 2.306714e-02 -9.228690e-02 1.493752e+00 +-9.396287e-02 3.429642e-02 -9.949848e-01 -5.291590e+01 -1.947438e-02 9.991519e-01 3.627916e-02 8.317695e-01 9.953852e-01 2.278560e-02 -9.321528e-02 1.416807e+00 +-9.489148e-02 3.383215e-02 -9.949125e-01 -5.370196e+01 -2.126901e-02 9.991253e-01 3.600398e-02 8.419538e-01 9.952604e-01 2.457727e-02 -9.408890e-02 1.337479e+00 +-9.547628e-02 3.365711e-02 -9.948625e-01 -5.448400e+01 -2.234157e-02 9.991040e-01 3.594471e-02 8.494927e-01 9.951810e-01 2.565866e-02 -9.463878e-02 1.258994e+00 +-9.600787e-02 3.526470e-02 -9.947557e-01 -5.526303e+01 -2.088946e-02 9.990807e-01 3.743416e-02 8.601357e-01 9.951614e-01 2.437388e-02 -9.518295e-02 1.184702e+00 +-9.631614e-02 3.786491e-02 -9.946303e-01 -5.603808e+01 -1.966748e-02 9.990086e-01 3.993612e-02 8.696735e-01 9.951565e-01 2.340836e-02 -9.547595e-02 1.110756e+00 +-9.631889e-02 4.229139e-02 -9.944516e-01 -5.681074e+01 -2.023666e-02 9.988072e-01 4.443667e-02 8.820234e-01 9.951448e-01 2.440447e-02 -9.534816e-02 1.032637e+00 +-9.679243e-02 4.476912e-02 -9.942972e-01 -5.757460e+01 -2.017706e-02 9.986943e-01 4.693131e-02 8.957003e-01 9.951001e-01 2.460459e-02 -9.576274e-02 9.565390e-01 +-9.751230e-02 4.461774e-02 -9.942337e-01 -5.833039e+01 -1.973636e-02 9.987114e-01 4.675439e-02 9.106542e-01 9.950386e-01 2.418168e-02 -9.650605e-02 8.830630e-01 +-9.795446e-02 4.283838e-02 -9.942685e-01 -5.907759e+01 -1.906692e-02 9.988089e-01 4.491248e-02 9.234551e-01 9.950083e-01 2.335701e-02 -9.702100e-02 8.100074e-01 +-9.803627e-02 3.931108e-02 -9.944061e-01 -5.981040e+01 -1.882451e-02 9.989675e-01 4.134728e-02 9.337799e-01 9.950048e-01 2.277274e-02 -9.719504e-02 7.359683e-01 +-9.799930e-02 3.666304e-02 -9.945109e-01 -6.053658e+01 -1.904440e-02 9.990691e-01 3.870773e-02 9.432177e-01 9.950043e-01 2.273319e-02 -9.720985e-02 6.623665e-01 +-9.675594e-02 3.416077e-02 -9.947217e-01 -6.124548e+01 -1.957872e-02 9.991521e-01 3.621733e-02 9.508013e-01 9.951156e-01 2.297962e-02 -9.600508e-02 5.919478e-01 +-9.446826e-02 3.336158e-02 -9.949687e-01 -6.194033e+01 -2.166315e-02 9.991328e-01 3.555804e-02 9.565112e-01 9.952922e-01 2.491326e-02 -9.366362e-02 5.237598e-01 +-9.065597e-02 3.447304e-02 -9.952854e-01 -6.262022e+01 -2.266347e-02 9.990704e-01 3.666846e-02 9.607290e-01 9.956244e-01 2.588084e-02 -8.979042e-02 4.617179e-01 +-8.478874e-02 3.562920e-02 -9.957617e-01 -6.328551e+01 -2.179694e-02 9.990550e-01 3.760305e-02 9.654748e-01 9.961605e-01 2.489288e-02 -8.393200e-02 4.088407e-01 +-7.769131e-02 3.737607e-02 -9.962766e-01 -6.393546e+01 -2.099037e-02 9.990142e-01 3.911565e-02 9.696725e-01 9.967565e-01 2.395116e-02 -7.683019e-02 3.622951e-01 +-6.908210e-02 3.878501e-02 -9.968567e-01 -6.457047e+01 -2.201573e-02 9.989413e-01 4.039181e-02 9.742130e-01 9.973681e-01 2.473688e-02 -6.815508e-02 3.201877e-01 +-5.715155e-02 4.050175e-02 -9.975436e-01 -6.518991e+01 -2.428573e-02 9.988247e-01 4.194516e-02 9.801827e-01 9.980701e-01 2.662331e-02 -5.610077e-02 2.859581e-01 +-4.271090e-02 4.211609e-02 -9.981994e-01 -6.579136e+01 -2.736683e-02 9.986869e-01 4.330764e-02 9.882448e-01 9.987126e-01 2.916726e-02 -4.150223e-02 2.627668e-01 +-2.429915e-02 4.346382e-02 -9.987594e-01 -6.637563e+01 -2.907338e-02 9.986011e-01 4.416428e-02 9.966522e-01 9.992819e-01 3.011046e-02 -2.300152e-02 2.555668e-01 +-2.518869e-03 4.426213e-02 -9.990168e-01 -6.693703e+01 -3.030184e-02 9.985578e-01 4.431821e-02 1.003712e+00 9.995377e-01 3.038367e-02 -1.174011e-03 2.646196e-01 +2.288678e-02 4.500994e-02 -9.987243e-01 -6.747673e+01 -3.012122e-02 9.985635e-01 4.431245e-02 1.009213e+00 9.992842e-01 2.906862e-02 2.420966e-02 2.941699e-01 +5.165759e-02 4.439305e-02 -9.976777e-01 -6.799052e+01 -2.852108e-02 9.986696e-01 4.296044e-02 1.013813e+00 9.982575e-01 2.623562e-02 5.285500e-02 3.455598e-01 +8.536048e-02 4.448258e-02 -9.953566e-01 -6.848214e+01 -2.750150e-02 9.987274e-01 4.227474e-02 1.016477e+00 9.959705e-01 2.376521e-02 8.647519e-02 4.164808e-01 +1.227573e-01 4.458956e-02 -9.914345e-01 -6.895412e+01 -2.686321e-02 9.987734e-01 4.159349e-02 1.019824e+00 9.920731e-01 2.152721e-02 1.238045e-01 5.048813e-01 +1.629811e-01 4.426984e-02 -9.856355e-01 -6.940376e+01 -2.671630e-02 9.988245e-01 4.044453e-02 1.021543e+00 9.862674e-01 1.974084e-02 1.639723e-01 6.110892e-01 +2.077988e-01 4.518369e-02 -9.771275e-01 -6.984846e+01 -2.578527e-02 9.988384e-01 4.070408e-02 1.023928e+00 9.778317e-01 1.673724e-02 2.087225e-01 7.419667e-01 +2.555492e-01 4.418568e-02 -9.657858e-01 -7.027047e+01 -2.323950e-02 9.989471e-01 3.955363e-02 1.024337e+00 9.665167e-01 1.233648e-02 2.563070e-01 8.955753e-01 +3.052822e-01 3.940288e-02 -9.514463e-01 -7.068171e+01 -1.572097e-02 9.992159e-01 3.633695e-02 1.023888e+00 9.521322e-01 3.864635e-03 3.056623e-01 1.080744e+00 +3.561290e-01 3.412235e-02 -9.338136e-01 -7.106861e+01 -1.009255e-02 9.994152e-01 3.267050e-02 1.025888e+00 9.343823e-01 -2.210349e-03 3.562651e-01 1.285746e+00 +4.079745e-01 2.889902e-02 -9.125358e-01 -7.145144e+01 -4.496180e-03 9.995504e-01 2.964455e-02 1.032362e+00 9.129823e-01 -7.991289e-03 4.079211e-01 1.513560e+00 +4.589753e-01 2.786762e-02 -8.880119e-01 -7.181419e+01 -4.383319e-03 9.995668e-01 2.910289e-02 1.040291e+00 8.884383e-01 -9.465065e-03 4.588986e-01 1.753829e+00 +5.069013e-01 2.653927e-02 -8.615955e-01 -7.217075e+01 -3.181020e-03 9.995767e-01 2.891796e-02 1.045549e+00 8.619983e-01 -1.191779e-02 5.067711e-01 2.013647e+00 +5.520074e-01 2.262555e-02 -8.335322e-01 -7.250742e+01 4.001910e-03 9.995484e-01 2.978219e-02 1.049184e+00 8.338297e-01 -1.977570e-02 5.516675e-01 2.296944e+00 +5.956629e-01 1.585576e-02 -8.030780e-01 -7.281071e+01 1.549808e-02 9.993921e-01 3.122705e-02 1.052187e+00 8.030850e-01 -3.104695e-02 5.950551e-01 2.601772e+00 +6.381226e-01 1.052786e-02 -7.698628e-01 -7.310855e+01 1.763745e-02 9.994442e-01 2.828668e-02 1.052214e+00 7.697328e-01 -3.162878e-02 6.375822e-01 2.908665e+00 +6.793713e-01 6.183858e-03 -7.337686e-01 -7.338524e+01 1.438602e-02 9.996600e-01 2.174420e-02 1.051991e+00 7.336537e-01 -2.532839e-02 6.790514e-01 3.220823e+00 +7.198790e-01 -1.153949e-03 -6.940987e-01 -7.365932e+01 1.134516e-02 9.998846e-01 1.010422e-02 1.056081e+00 6.940069e-01 -1.514848e-02 7.198090e-01 3.554385e+00 +7.593590e-01 -4.902043e-03 -6.506534e-01 -7.391333e+01 7.111606e-03 9.999744e-01 7.659137e-04 1.058753e+00 6.506330e-01 -5.208790e-03 7.593745e-01 3.911270e+00 +7.967185e-01 -6.044423e-03 -6.043204e-01 -7.416588e+01 5.806608e-03 9.999804e-01 -2.346559e-03 1.057855e+00 6.043228e-01 -1.639502e-03 7.967379e-01 4.300551e+00 +8.310408e-01 -8.059018e-03 -5.561530e-01 -7.440171e+01 6.588534e-03 9.999675e-01 -4.645155e-03 1.057076e+00 5.561724e-01 1.960829e-04 8.310669e-01 4.718510e+00 +8.620977e-01 -7.374496e-03 -5.066885e-01 -7.461515e+01 4.114510e-03 9.999630e-01 -7.553191e-03 1.053457e+00 5.067255e-01 4.426815e-03 8.620961e-01 5.155827e+00 +8.886387e-01 -5.432656e-03 -4.585759e-01 -7.482560e+01 3.165614e-03 9.999786e-01 -5.712150e-03 1.044844e+00 4.585971e-01 3.624365e-03 8.886369e-01 5.623155e+00 +9.103879e-01 1.247129e-04 -4.137557e-01 -7.501816e+01 -2.268793e-03 9.999864e-01 -4.690620e-03 1.038119e+00 4.137495e-01 5.209011e-03 9.103759e-01 6.110247e+00 +9.282975e-01 4.418182e-03 -3.718121e-01 -7.520557e+01 -7.412496e-03 9.999506e-01 -6.624412e-03 1.035836e+00 3.717645e-01 8.905481e-03 9.282844e-01 6.618096e+00 +9.422181e-01 8.825716e-03 -3.348837e-01 -7.537989e+01 -1.143552e-02 9.999176e-01 -5.822212e-03 1.030282e+00 3.348048e-01 9.315364e-03 9.422415e-01 7.151976e+00 +9.526123e-01 1.032154e-02 -3.040119e-01 -7.553930e+01 -1.194835e-02 9.999225e-01 -3.491331e-03 1.020134e+00 3.039523e-01 6.958325e-03 9.526619e-01 7.706095e+00 +9.601292e-01 9.160134e-03 -2.794067e-01 -7.569196e+01 -1.017334e-02 9.999459e-01 -2.176331e-03 1.010452e+00 2.793717e-01 4.932060e-03 9.601704e-01 8.281091e+00 +9.661414e-01 8.961543e-03 -2.578573e-01 -7.583698e+01 -9.326138e-03 9.999565e-01 -1.908557e-04 1.004688e+00 2.578444e-01 2.589208e-03 9.661830e-01 8.874404e+00 +9.708685e-01 1.164663e-02 -2.393295e-01 -7.598069e+01 -1.133083e-02 9.999321e-01 2.695421e-03 9.966334e-01 2.393447e-01 9.490508e-05 9.709347e-01 9.486418e+00 +9.745261e-01 1.556476e-02 -2.237336e-01 -7.612225e+01 -1.516088e-02 9.998788e-01 3.522981e-03 9.889481e-01 2.237613e-01 -4.123826e-05 9.746440e-01 1.011220e+01 +9.775062e-01 2.013451e-02 -2.099436e-01 -7.625804e+01 -1.939283e-02 9.997963e-01 5.591008e-03 9.812746e-01 2.100134e-01 -1.393842e-03 9.776975e-01 1.075522e+01 +9.802980e-01 1.842505e-02 -1.966633e-01 -7.637903e+01 -1.774418e-02 9.998289e-01 5.223750e-03 9.768095e-01 1.967259e-01 -1.631200e-03 9.804572e-01 1.141499e+01 +9.829611e-01 1.830401e-02 -1.828999e-01 -7.649294e+01 -1.770182e-02 9.998312e-01 4.924682e-03 9.734490e-01 1.829592e-01 -1.603108e-03 9.831192e-01 1.209150e+01 +9.855730e-01 1.863308e-02 -1.682221e-01 -7.660203e+01 -1.798644e-02 9.998238e-01 5.367037e-03 9.705966e-01 1.682925e-01 -2.263888e-03 9.857345e-01 1.278422e+01 +9.879063e-01 1.985395e-02 -1.537755e-01 -7.670271e+01 -1.919323e-02 9.997991e-01 5.780145e-03 9.650851e-01 1.538594e-01 -2.758791e-03 9.880889e-01 1.349407e+01 +9.898226e-01 1.986472e-02 -1.409137e-01 -7.679658e+01 -1.959850e-02 9.998025e-01 3.276917e-03 9.546485e-01 1.409510e-01 -4.818675e-04 9.900165e-01 1.421250e+01 +9.913422e-01 2.118524e-02 -1.295831e-01 -7.688462e+01 -2.151281e-02 9.997679e-01 -1.128479e-03 9.437305e-01 1.295291e-01 3.906406e-03 9.915679e-01 1.494545e+01 +9.926196e-01 1.845295e-02 -1.198577e-01 -7.696463e+01 -1.957470e-02 9.997748e-01 -8.188277e-03 9.352274e-01 1.196796e-01 1.047402e-02 9.927573e-01 1.568785e+01 +9.935925e-01 1.788793e-02 -1.115977e-01 -7.704091e+01 -1.906292e-02 9.997734e-01 -9.470564e-03 9.267552e-01 1.114030e-01 1.153726e-02 9.937084e-01 1.644684e+01 +9.943126e-01 1.972079e-02 -1.046592e-01 -7.711873e+01 -2.014681e-02 9.997925e-01 -3.014790e-03 9.133109e-01 1.045780e-01 5.106192e-03 9.945036e-01 1.721856e+01 +9.947552e-01 2.430267e-02 -9.935508e-02 -7.719881e+01 -2.389875e-02 9.997006e-01 5.253839e-03 8.975356e-01 9.945301e-02 -2.851820e-03 9.950382e-01 1.799359e+01 +9.951550e-01 2.547064e-02 -9.496225e-02 -7.727201e+01 -2.458401e-02 9.996426e-01 1.049518e-02 8.859440e-01 9.519564e-02 -8.109779e-03 9.954256e-01 1.876754e+01 +9.955248e-01 2.343596e-02 -9.154850e-02 -7.733723e+01 -2.275392e-02 9.997050e-01 8.486912e-03 8.765600e-01 9.172041e-02 -6.365842e-03 9.957645e-01 1.953401e+01 +9.958152e-01 2.366515e-02 -8.827304e-02 -7.740244e+01 -2.309353e-02 9.997052e-01 7.491474e-03 8.673710e-01 8.842431e-02 -5.421586e-03 9.960682e-01 2.030151e+01 +9.961043e-01 2.209172e-02 -8.537129e-02 -7.746374e+01 -2.137124e-02 9.997279e-01 9.344273e-03 8.595219e-01 8.555450e-02 -7.483377e-03 9.963054e-01 2.107246e+01 +9.963535e-01 2.020556e-02 -8.289442e-02 -7.752113e+01 -1.925622e-02 9.997397e-01 1.223602e-02 8.514204e-01 8.312008e-02 -1.059517e-02 9.964832e-01 2.184296e+01 +9.966536e-01 1.782813e-02 -7.977275e-02 -7.757340e+01 -1.673759e-02 9.997574e-01 1.431852e-02 8.408161e-01 8.000867e-02 -1.293540e-02 9.967102e-01 2.261434e+01 +9.968839e-01 1.707070e-02 -7.701412e-02 -7.762210e+01 -1.623422e-02 9.998023e-01 1.147455e-02 8.279106e-01 7.719478e-02 -1.018853e-02 9.969640e-01 2.337766e+01 +9.969879e-01 1.955555e-02 -7.505097e-02 -7.767675e+01 -1.932613e-02 9.998061e-01 3.782018e-03 8.191268e-01 7.511038e-02 -2.320180e-03 9.971725e-01 2.413827e+01 +9.970950e-01 2.005108e-02 -7.348164e-02 -7.773420e+01 -2.039302e-02 9.997844e-01 -3.906001e-03 8.046718e-01 7.338749e-02 5.393166e-03 9.972889e-01 2.489811e+01 +9.971687e-01 2.063475e-02 -7.231107e-02 -7.778961e+01 -2.132267e-02 9.997343e-01 -8.754247e-03 7.903154e-01 7.211122e-02 1.027133e-02 9.973437e-01 2.565478e+01 +9.972686e-01 2.248671e-02 -7.035370e-02 -7.784614e+01 -2.302359e-02 9.997116e-01 -6.829295e-03 7.739409e-01 7.017985e-02 8.430436e-03 9.974987e-01 2.642191e+01 +9.973626e-01 2.544213e-02 -6.797409e-02 -7.790878e+01 -2.571467e-02 9.996644e-01 -3.137224e-03 7.508496e-01 6.787147e-02 4.876881e-03 9.976822e-01 2.718067e+01 +9.974099e-01 2.928043e-02 -6.569765e-02 -7.796897e+01 -2.918789e-02 9.995711e-01 2.368255e-03 7.293732e-01 6.573882e-02 -4.445438e-04 9.978368e-01 2.793923e+01 +9.976148e-01 2.726027e-02 -6.341609e-02 -7.802007e+01 -2.705552e-02 9.996256e-01 4.085521e-03 7.137060e-01 6.350372e-02 -2.360019e-03 9.979788e-01 2.869200e+01 +9.977642e-01 2.414407e-02 -6.231882e-02 -7.806469e+01 -2.395666e-02 9.997059e-01 3.753051e-03 6.969693e-01 6.239112e-02 -2.251708e-03 9.980492e-01 2.944067e+01 +9.978606e-01 2.223991e-02 -6.147886e-02 -7.810970e+01 -2.201720e-02 9.997483e-01 4.297682e-03 6.798769e-01 6.155897e-02 -2.934894e-03 9.980991e-01 3.019277e+01 +9.979345e-01 2.226502e-02 -6.025832e-02 -7.815548e+01 -2.214324e-02 9.997512e-01 2.688050e-03 6.647429e-01 6.030318e-02 -1.348182e-03 9.981792e-01 3.094569e+01 +9.980139e-01 2.011648e-02 -5.969513e-02 -7.819810e+01 -2.011991e-02 9.997974e-01 5.437240e-04 6.476766e-01 5.969397e-02 6.584171e-04 9.982165e-01 3.170130e+01 +9.980837e-01 1.853880e-02 -5.903657e-02 -7.824233e+01 -1.850660e-02 9.998281e-01 1.092321e-03 6.301632e-01 5.904668e-02 2.339810e-06 9.982552e-01 3.246413e+01 +9.980745e-01 2.157565e-02 -5.815252e-02 -7.829498e+01 -2.151672e-02 9.997671e-01 1.639538e-03 6.149092e-01 5.817435e-02 -3.851293e-04 9.983064e-01 3.323079e+01 +9.980777e-01 2.145585e-02 -5.814208e-02 -7.834624e+01 -2.145232e-02 9.997696e-01 6.849280e-04 5.990528e-01 5.814338e-02 5.636721e-04 9.983081e-01 3.400093e+01 +9.979711e-01 2.159270e-02 -5.989508e-02 -7.839928e+01 -2.159192e-02 9.997666e-01 6.603379e-04 5.789981e-01 5.989536e-02 6.342523e-04 9.982045e-01 3.477685e+01 +9.978929e-01 1.912200e-02 -6.200057e-02 -7.844974e+01 -1.908247e-02 9.998171e-01 1.229822e-03 5.641545e-01 6.201275e-02 -4.410566e-05 9.980754e-01 3.556152e+01 +9.976774e-01 2.011746e-02 -6.507739e-02 -7.850718e+01 -2.011485e-02 9.997974e-01 6.953249e-04 5.473641e-01 6.507820e-02 6.153131e-04 9.978800e-01 3.634754e+01 +9.973910e-01 2.402159e-02 -6.807438e-02 -7.857152e+01 -2.400464e-02 9.997113e-01 1.067185e-03 5.285291e-01 6.808036e-02 5.697015e-04 9.976797e-01 3.714347e+01 +9.971704e-01 2.553434e-02 -7.070529e-02 -7.863617e+01 -2.581427e-02 9.996621e-01 -3.047894e-03 5.110168e-01 7.060358e-02 4.864475e-03 9.974926e-01 3.793752e+01 +9.969805e-01 2.538411e-02 -7.338608e-02 -7.870040e+01 -2.603828e-02 9.996291e-01 -7.970985e-03 4.940833e-01 7.315654e-02 9.857764e-03 9.972718e-01 3.873523e+01 +9.968668e-01 2.420540e-02 -7.530350e-02 -7.876270e+01 -2.494465e-02 9.996493e-01 -8.891721e-03 4.825696e-01 7.506187e-02 1.074228e-02 9.971210e-01 3.954602e+01 +9.966769e-01 2.519982e-02 -7.746066e-02 -7.882862e+01 -2.586973e-02 9.996360e-01 -7.656899e-03 4.646182e-01 7.723952e-02 9.635340e-03 9.969660e-01 4.036454e+01 +9.965245e-01 2.452513e-02 -7.960794e-02 -7.889593e+01 -2.510311e-02 9.996652e-01 -6.267558e-03 4.461482e-01 7.942758e-02 8.244181e-03 9.968066e-01 4.119468e+01 +9.964140e-01 2.263245e-02 -8.152874e-02 -7.895989e+01 -2.312866e-02 9.997192e-01 -5.146836e-03 4.339025e-01 8.138937e-02 7.014029e-03 9.966577e-01 4.203064e+01 +9.963375e-01 2.221964e-02 -8.257034e-02 -7.902897e+01 -2.241261e-02 9.997478e-01 -1.410729e-03 4.207820e-01 8.251817e-02 3.256179e-03 9.965843e-01 4.287429e+01 +9.962742e-01 2.183304e-02 -8.343279e-02 -7.910034e+01 -2.163733e-02 9.997606e-01 3.249453e-03 4.039919e-01 8.348377e-02 -1.432082e-03 9.965081e-01 4.372474e+01 +9.963146e-01 2.183582e-02 -8.294879e-02 -7.917130e+01 -2.140884e-02 9.997526e-01 6.033575e-03 3.888969e-01 8.306002e-02 -4.235500e-03 9.965356e-01 4.457894e+01 +9.964057e-01 2.536308e-02 -8.082327e-02 -7.924668e+01 -2.496686e-02 9.996708e-01 5.909382e-03 3.756583e-01 8.094655e-02 -3.870238e-03 9.967109e-01 4.543863e+01 +9.965520e-01 2.539001e-02 -7.899005e-02 -7.931863e+01 -2.509685e-02 9.996739e-01 4.702072e-03 3.639286e-01 7.908368e-02 -2.703457e-03 9.968643e-01 4.629920e+01 +9.967286e-01 2.305048e-02 -7.746535e-02 -7.938492e+01 -2.293337e-02 9.997341e-01 2.401242e-03 3.498958e-01 7.750011e-02 -6.168441e-04 9.969922e-01 4.716296e+01 +9.969335e-01 1.893559e-02 -7.592862e-02 -7.944527e+01 -1.895157e-02 9.998202e-01 5.102881e-04 3.344377e-01 7.592464e-02 9.302438e-04 9.971131e-01 4.803166e+01 +9.971031e-01 1.749554e-02 -7.402269e-02 -7.950861e+01 -1.751297e-02 9.998465e-01 4.136421e-04 3.209956e-01 7.401858e-02 8.839143e-04 9.972565e-01 4.890207e+01 +9.972126e-01 1.581570e-02 -7.291775e-02 -7.957376e+01 -1.565802e-02 9.998736e-01 2.733572e-03 3.027919e-01 7.295177e-02 -1.584204e-03 9.973342e-01 4.977895e+01 +9.973040e-01 1.270520e-02 -7.227324e-02 -7.963392e+01 -1.234224e-02 9.999089e-01 5.466448e-03 2.867505e-01 7.233611e-02 -4.559694e-03 9.973699e-01 5.065630e+01 +9.973788e-01 1.166362e-02 -7.141078e-02 -7.969742e+01 -1.127732e-02 9.999195e-01 5.810410e-03 2.720427e-01 7.147281e-02 -4.989856e-03 9.974301e-01 5.152945e+01 +9.974314e-01 1.336104e-02 -7.037133e-02 -7.976468e+01 -1.315987e-02 9.999079e-01 3.321583e-03 2.574406e-01 7.040924e-02 -2.386972e-03 9.975153e-01 5.239664e+01 +9.974391e-01 1.598027e-02 -6.971308e-02 -7.983358e+01 -1.619357e-02 9.998657e-01 -2.495506e-03 2.408602e-01 6.966385e-02 3.618019e-03 9.975640e-01 5.325480e+01 +9.974783e-01 1.766750e-02 -6.873771e-02 -7.990039e+01 -1.824544e-02 9.998032e-01 -7.789141e-03 2.201002e-01 6.858657e-02 9.023648e-03 9.976044e-01 5.411350e+01 +9.974312e-01 2.221504e-02 -6.809873e-02 -7.996964e+01 -2.324070e-02 9.996275e-01 -1.430614e-02 1.922996e-01 6.775555e-02 1.585205e-02 9.975760e-01 5.496562e+01 +9.974862e-01 2.287299e-02 -6.706849e-02 -8.003259e+01 -2.394011e-02 9.995986e-01 -1.515030e-02 1.649343e-01 6.669504e-02 1.671784e-02 9.976334e-01 5.581906e+01 +9.975764e-01 1.936231e-02 -6.683203e-02 -8.009273e+01 -2.008845e-02 9.997460e-01 -1.021019e-02 1.408072e-01 6.661737e-02 1.152800e-02 9.977120e-01 5.667063e+01 +9.975594e-01 1.905347e-02 -6.717376e-02 -8.015558e+01 -1.905553e-02 9.998182e-01 6.101767e-04 1.161116e-01 6.717318e-02 6.713453e-04 9.977411e-01 5.752689e+01 +9.974598e-01 2.043472e-02 -6.823714e-02 -8.022244e+01 -1.982576e-02 9.997574e-01 9.589694e-03 9.233457e-02 6.841656e-02 -8.212479e-03 9.976230e-01 5.837775e+01 +9.973475e-01 1.637144e-02 -7.092222e-02 -8.028086e+01 -1.600464e-02 9.998554e-01 5.737102e-03 7.510008e-02 7.100590e-02 -4.586798e-03 9.974654e-01 5.921310e+01 +9.972626e-01 1.027044e-02 -7.322438e-02 -8.033871e+01 -1.012140e-02 9.999459e-01 2.406207e-03 5.914325e-02 7.324513e-02 -1.658486e-03 9.973126e-01 6.004264e+01 +9.970686e-01 9.839836e-03 -7.587720e-02 -8.040305e+01 -9.745675e-03 9.999512e-01 1.611168e-03 4.000654e-02 7.588935e-02 -8.669694e-04 9.971159e-01 6.087223e+01 +9.968586e-01 1.117945e-02 -7.840894e-02 -8.047401e+01 -1.129988e-02 9.999355e-01 -1.092300e-03 1.826730e-02 7.839168e-02 1.974881e-03 9.969207e-01 6.169567e+01 +9.965538e-01 1.302843e-02 -8.191992e-02 -8.054972e+01 -1.342493e-02 9.999006e-01 -4.291024e-03 -3.742664e-03 8.185588e-02 5.376005e-03 9.966297e-01 6.251365e+01 +9.962044e-01 1.356199e-02 -8.598214e-02 -8.062089e+01 -1.429631e-02 9.998663e-01 -7.930284e-03 -2.632294e-02 8.586311e-02 9.129410e-03 9.962651e-01 6.332787e+01 +9.959022e-01 1.469750e-02 -8.923512e-02 -8.069604e+01 -1.586026e-02 9.997981e-01 -1.233511e-02 -5.452812e-02 8.903581e-02 1.369985e-02 9.959342e-01 6.413629e+01 +9.955324e-01 2.018083e-02 -9.223929e-02 -8.077810e+01 -2.133438e-02 9.997058e-01 -1.153712e-02 -8.379998e-02 9.197933e-02 1.345344e-02 9.956700e-01 6.494508e+01 +9.951360e-01 2.300598e-02 -9.578676e-02 -8.085967e+01 -2.409303e-02 9.996576e-01 -1.020740e-02 -1.090773e-01 9.551914e-02 1.246554e-02 9.953495e-01 6.575279e+01 +9.946717e-01 2.644463e-02 -9.964404e-02 -8.094518e+01 -2.706427e-02 9.996218e-01 -4.871640e-03 -1.360470e-01 9.947753e-02 7.542475e-03 9.950112e-01 6.655929e+01 +9.942522e-01 2.749508e-02 -1.034727e-01 -8.103408e+01 -2.742471e-02 9.996216e-01 2.103045e-03 -1.573834e-01 1.034913e-01 7.467515e-04 9.946301e-01 6.736350e+01 +9.937512e-01 2.685355e-02 -1.083396e-01 -8.112341e+01 -2.642608e-02 9.996363e-01 5.379751e-03 -1.755819e-01 1.084446e-01 -2.483143e-03 9.940994e-01 6.815999e+01 +9.930349e-01 2.640960e-02 -1.148227e-01 -8.121916e+01 -2.589901e-02 9.996469e-01 5.936642e-03 -1.913565e-01 1.149389e-01 -2.921497e-03 9.933683e-01 6.894880e+01 +9.923841e-01 2.388637e-02 -1.208442e-01 -8.131685e+01 -2.290157e-02 9.996923e-01 9.531912e-03 -2.042169e-01 1.210347e-01 -6.691793e-03 9.926257e-01 6.973955e+01 +9.915731e-01 2.407923e-02 -1.272910e-01 -8.142164e+01 -2.304024e-02 9.996881e-01 9.628695e-03 -2.174815e-01 1.274832e-01 -6.614737e-03 9.918187e-01 7.052030e+01 +9.906752e-01 2.878540e-02 -1.331689e-01 -8.154226e+01 -2.781246e-02 9.995712e-01 9.160900e-03 -2.305564e-01 1.333755e-01 -5.371720e-03 9.910510e-01 7.129191e+01 +9.898411e-01 3.060365e-02 -1.388453e-01 -8.166368e+01 -3.013394e-02 9.995308e-01 5.484427e-03 -2.426308e-01 1.389480e-01 -1.244755e-03 9.902989e-01 7.205943e+01 +9.889858e-01 2.968952e-02 -1.450022e-01 -8.178344e+01 -2.963715e-02 9.995575e-01 2.521779e-03 -2.550723e-01 1.450129e-01 1.803450e-03 9.894281e-01 7.282193e+01 +9.881343e-01 3.153952e-02 -1.503194e-01 -8.191089e+01 -3.159826e-02 9.994986e-01 1.998407e-03 -2.691768e-01 1.503071e-01 2.775138e-03 9.886355e-01 7.358474e+01 +9.873798e-01 3.326103e-02 -1.548380e-01 -8.204910e+01 -3.277161e-02 9.994465e-01 5.713068e-03 -2.836517e-01 1.549424e-01 -5.666748e-04 9.879234e-01 7.434335e+01 +9.864030e-01 3.427245e-02 -1.607315e-01 -8.218657e+01 -3.300776e-02 9.993996e-01 1.053264e-02 -2.975894e-01 1.609960e-01 -5.084039e-03 9.869420e-01 7.510124e+01 +9.853626e-01 3.400571e-02 -1.670456e-01 -8.232699e+01 -3.223878e-02 9.993920e-01 1.327876e-02 -3.160459e-01 1.673956e-01 -7.699045e-03 9.858598e-01 7.585198e+01 +9.842290e-01 3.187628e-02 -1.740035e-01 -8.246709e+01 -3.058414e-02 9.994811e-01 1.010295e-02 -3.273793e-01 1.742353e-01 -4.621867e-03 9.846932e-01 7.659470e+01 +9.827805e-01 2.892232e-02 -1.824992e-01 -8.261416e+01 -2.899126e-02 9.995770e-01 2.290686e-03 -3.380953e-01 1.824882e-01 3.039639e-03 9.832033e-01 7.733161e+01 +9.811245e-01 2.632367e-02 -1.915771e-01 -8.276564e+01 -2.684762e-02 9.996395e-01 -1.392230e-04 -3.542448e-01 1.915044e-01 5.279985e-03 9.814776e-01 7.806923e+01 +9.789754e-01 2.717525e-02 -2.021601e-01 -8.293034e+01 -2.694436e-02 9.996293e-01 3.894513e-03 -3.753983e-01 2.021910e-01 1.634442e-03 9.793448e-01 7.880777e+01 +9.766120e-01 2.610930e-02 -2.134180e-01 -8.310119e+01 -2.486657e-02 9.996546e-01 8.505821e-03 -3.866320e-01 2.135664e-01 -2.999910e-03 9.769240e-01 7.954411e+01 +9.739399e-01 2.838646e-02 -2.250227e-01 -8.328409e+01 -2.525288e-02 9.995400e-01 1.679221e-02 -3.994934e-01 2.253959e-01 -1.067213e-02 9.742088e-01 8.028097e+01 +9.712876e-01 2.949127e-02 -2.360734e-01 -8.346726e+01 -2.505677e-02 9.994491e-01 2.176316e-02 -4.083909e-01 2.365852e-01 -1.522305e-02 9.714915e-01 8.101060e+01 +9.683190e-01 3.263245e-02 -2.475750e-01 -8.365790e+01 -2.923310e-02 9.994212e-01 1.739514e-02 -4.178227e-01 2.479994e-01 -9.606655e-03 9.687126e-01 8.172568e+01 +9.651691e-01 3.120823e-02 -2.597589e-01 -8.385643e+01 -3.033783e-02 9.995126e-01 7.360235e-03 -4.258951e-01 2.598620e-01 7.766520e-04 9.656455e-01 8.243070e+01 +9.618068e-01 2.926476e-02 -2.721603e-01 -8.405742e+01 -2.967254e-02 9.995562e-01 2.618079e-03 -4.274942e-01 2.721162e-01 5.557600e-03 9.622484e-01 8.314038e+01 +9.583100e-01 2.728584e-02 -2.844247e-01 -8.426582e+01 -2.654382e-02 9.996267e-01 6.463758e-03 -4.288742e-01 2.844949e-01 1.355435e-03 9.586766e-01 8.386239e+01 +9.548139e-01 2.935585e-02 -2.957510e-01 -8.449278e+01 -2.609382e-02 9.995474e-01 1.497147e-02 -4.369496e-01 2.960566e-01 -6.577694e-03 9.551477e-01 8.458416e+01 +9.511074e-01 3.068897e-02 -3.073318e-01 -8.472751e+01 -2.552079e-02 9.994574e-01 2.082214e-02 -4.424402e-01 3.078041e-01 -1.196073e-02 9.513746e-01 8.530299e+01 +9.470296e-01 2.680373e-02 -3.200258e-01 -8.496507e+01 -2.186718e-02 9.995801e-01 1.900979e-02 -4.446969e-01 3.204009e-01 -1.100477e-02 9.472181e-01 8.601174e+01 +9.430702e-01 2.468379e-02 -3.316766e-01 -8.521230e+01 -2.123288e-02 9.996762e-01 1.402483e-02 -4.477484e-01 3.319154e-01 -6.183949e-03 9.432889e-01 8.671556e+01 +9.398766e-01 2.184172e-02 -3.408152e-01 -8.546879e+01 -2.010926e-02 9.997606e-01 8.615450e-03 -4.551185e-01 3.409218e-01 -1.243917e-03 9.400909e-01 8.741701e+01 +9.371067e-01 1.714544e-02 -3.486217e-01 -8.572668e+01 -1.775628e-02 9.998413e-01 1.443362e-03 -4.633066e-01 3.485911e-01 4.837642e-03 9.372624e-01 8.811804e+01 +9.343112e-01 1.670852e-02 -3.560666e-01 -8.599632e+01 -1.806969e-02 9.998366e-01 -4.968568e-04 -4.725988e-01 3.560002e-01 6.898232e-03 9.344604e-01 8.882079e+01 +9.312646e-01 2.180425e-02 -3.636906e-01 -8.628029e+01 -2.362202e-02 9.997208e-01 -5.504198e-04 -4.872714e-01 3.635771e-01 9.103693e-03 9.315197e-01 8.952111e+01 +9.281430e-01 2.311602e-02 -3.715053e-01 -8.656905e+01 -2.398840e-02 9.997096e-01 2.273564e-03 -4.896331e-01 3.714500e-01 6.801627e-03 9.284281e-01 9.021553e+01 +9.249334e-01 2.313847e-02 -3.794244e-01 -8.686039e+01 -2.178644e-02 9.997317e-01 7.857321e-03 -4.833979e-01 3.795045e-01 9.988106e-04 9.251894e-01 9.091809e+01 +9.220800e-01 2.377708e-02 -3.862682e-01 -8.715878e+01 -1.933902e-02 9.996948e-01 1.537198e-02 -4.804139e-01 3.865158e-01 -6.704146e-03 9.222584e-01 9.162194e+01 +9.193440e-01 3.416534e-02 -3.919686e-01 -8.747632e+01 -2.709705e-02 9.993553e-01 2.355242e-02 -4.825025e-01 3.925206e-01 -1.103158e-02 9.196771e-01 9.231850e+01 +9.166730e-01 4.222960e-02 -3.974007e-01 -8.780250e+01 -3.629672e-02 9.990890e-01 2.244315e-02 -4.756232e-01 3.979864e-01 -6.148685e-03 9.173707e-01 9.300351e+01 +9.142241e-01 3.856213e-02 -4.033699e-01 -8.811795e+01 -3.615563e-02 9.992538e-01 1.358310e-02 -4.680556e-01 4.035928e-01 2.166101e-03 9.149362e-01 9.368698e+01 +9.121701e-01 3.050276e-02 -4.086750e-01 -8.842784e+01 -3.076794e-02 9.995090e-01 5.926946e-03 -4.619748e-01 4.086552e-01 7.167704e-03 9.126607e-01 9.437577e+01 +9.103967e-01 3.049936e-02 -4.126108e-01 -8.874901e+01 -3.152904e-02 9.994935e-01 4.313954e-03 -4.631796e-01 4.125334e-01 9.081815e-03 9.108972e-01 9.506817e+01 +9.082629e-01 3.717963e-02 -4.167447e-01 -8.908452e+01 -3.633541e-02 9.992900e-01 9.960858e-03 -4.666220e-01 4.168192e-01 6.095514e-03 9.089690e-01 9.576606e+01 +9.057833e-01 4.006249e-02 -4.218431e-01 -8.941637e+01 -3.736374e-02 9.991941e-01 1.466603e-02 -4.736535e-01 4.220907e-01 2.477394e-03 9.065502e-01 9.646571e+01 +9.033931e-01 3.685824e-02 -4.272264e-01 -8.974796e+01 -3.407694e-02 9.993189e-01 1.415707e-02 -4.788901e-01 4.274572e-01 1.769167e-03 9.040339e-01 9.716351e+01 +9.012369e-01 3.463436e-02 -4.319404e-01 -9.008495e+01 -3.478352e-02 9.993663e-01 7.557112e-03 -4.847031e-01 4.319284e-01 8.213660e-03 9.018705e-01 9.784976e+01 +8.990019e-01 3.151276e-02 -4.368096e-01 -9.042665e+01 -3.495250e-02 9.993889e-01 1.628784e-04 -4.875902e-01 4.365478e-01 1.512116e-02 8.995540e-01 9.853474e+01 +8.966246e-01 3.188904e-02 -4.416416e-01 -9.077493e+01 -3.638479e-02 9.993364e-01 -1.710908e-03 -4.958138e-01 4.412940e-01 1.760308e-02 8.971899e-01 9.921955e+01 +8.945911e-01 3.566952e-02 -4.454599e-01 -9.113104e+01 -3.821885e-02 9.992640e-01 3.261876e-03 -5.064823e-01 4.452484e-01 1.410692e-02 8.952960e-01 9.990950e+01 +8.924765e-01 3.705554e-02 -4.495694e-01 -9.148703e+01 -3.875384e-02 9.992340e-01 5.428021e-03 -5.172294e-01 4.494262e-01 1.257816e-02 8.932289e-01 1.005948e+02 +8.901319e-01 3.804467e-02 -4.541121e-01 -9.184000e+01 -3.946244e-02 9.992008e-01 6.358551e-03 -5.261980e-01 4.539911e-01 1.226042e-02 8.909219e-01 1.012774e+02 +8.878868e-01 3.673343e-02 -4.585932e-01 -9.219617e+01 -3.816812e-02 9.992524e-01 6.142706e-03 -5.349382e-01 4.584760e-01 1.204961e-02 8.886251e-01 1.019541e+02 +8.857904e-01 3.453353e-02 -4.627988e-01 -9.255294e+01 -3.625907e-02 9.993290e-01 5.169495e-03 -5.434586e-01 4.626668e-01 1.220156e-02 8.864483e-01 1.026273e+02 +8.836111e-01 3.434905e-02 -4.669600e-01 -9.291478e+01 -3.563710e-02 9.993463e-01 6.076049e-03 -5.511717e-01 4.668634e-01 1.127223e-02 8.842576e-01 1.032961e+02 +8.813923e-01 3.522323e-02 -4.710700e-01 -9.328321e+01 -3.658770e-02 9.993108e-01 6.264141e-03 -5.589669e-01 4.709660e-01 1.171420e-02 8.820736e-01 1.039601e+02 +8.790575e-01 3.637209e-02 -4.753262e-01 -9.365046e+01 -3.747987e-02 9.992718e-01 7.150149e-03 -5.659964e-01 4.752401e-01 1.152977e-02 8.797806e-01 1.046187e+02 +8.766763e-01 3.328006e-02 -4.799282e-01 -9.401507e+01 -3.630651e-02 9.993362e-01 2.977368e-03 -5.767572e-01 4.797088e-01 1.481433e-02 8.773027e-01 1.052674e+02 +8.743880e-01 3.013636e-02 -4.842906e-01 -9.438211e+01 -3.517202e-02 9.993804e-01 -1.313869e-03 -5.883920e-01 4.839510e-01 1.818231e-02 8.749062e-01 1.059103e+02 +8.722627e-01 2.821580e-02 -4.882229e-01 -9.474824e+01 -3.480935e-02 9.993841e-01 -4.433357e-03 -5.980777e-01 4.877972e-01 2.086177e-02 8.727077e-01 1.065472e+02 +8.702813e-01 2.978177e-02 -4.916539e-01 -9.512335e+01 -3.479658e-02 9.993938e-01 -1.055815e-03 -6.050065e-01 4.913244e-01 1.802673e-02 8.707901e-01 1.071878e+02 +8.684481e-01 3.401415e-02 -4.946119e-01 -9.549621e+01 -3.470690e-02 9.993672e-01 7.786899e-03 -6.134439e-01 4.945638e-01 1.040393e-02 8.690791e-01 1.078233e+02 +8.669419e-01 3.641112e-02 -4.970774e-01 -9.586451e+01 -3.197040e-02 9.993366e-01 1.744294e-02 -6.210034e-01 4.973828e-01 7.697512e-04 8.675309e-01 1.084529e+02 +8.654369e-01 3.625525e-02 -4.997044e-01 -9.622320e+01 -2.861616e-02 9.993271e-01 2.294432e-02 -6.251307e-01 5.002000e-01 -5.557237e-03 8.658921e-01 1.090677e+02 +8.638730e-01 3.277621e-02 -5.026421e-01 -9.657402e+01 -2.481486e-02 9.994383e-01 2.252282e-02 -6.245992e-01 5.030980e-01 -6.983865e-03 8.642012e-01 1.096683e+02 +8.621072e-01 3.082854e-02 -5.057872e-01 -9.692077e+01 -2.471299e-02 9.995178e-01 1.879927e-02 -6.262052e-01 5.061229e-01 -3.707466e-03 8.624534e-01 1.102481e+02 +8.604880e-01 2.901689e-02 -5.086437e-01 -9.726338e+01 -2.420205e-02 9.995777e-01 1.608015e-02 -6.273272e-01 5.088956e-01 -1.526556e-03 8.608269e-01 1.108135e+02 +8.589787e-01 2.761315e-02 -5.112661e-01 -9.760083e+01 -2.319451e-02 9.996181e-01 1.501961e-02 -6.270850e-01 5.114857e-01 -1.042954e-03 8.592912e-01 1.113654e+02 +8.576929e-01 2.552506e-02 -5.135284e-01 -9.792433e+01 -2.122491e-02 9.996733e-01 1.423928e-02 -6.283274e-01 5.137241e-01 -1.313337e-03 8.579545e-01 1.119025e+02 +8.563908e-01 2.615873e-02 -5.156651e-01 -9.824175e+01 -2.116463e-02 9.996549e-01 1.556149e-02 -6.324615e-01 5.158942e-01 -2.412857e-03 8.566489e-01 1.124233e+02 +8.551887e-01 2.632932e-02 -5.176476e-01 -9.855027e+01 -2.027669e-02 9.996439e-01 1.734686e-02 -6.360649e-01 5.179200e-01 -4.338655e-03 8.554181e-01 1.129252e+02 +8.538736e-01 2.501776e-02 -5.198789e-01 -9.884348e+01 -1.842777e-02 9.996710e-01 1.783982e-02 -6.367940e-01 5.201542e-01 -5.652739e-03 8.540537e-01 1.134056e+02 +8.525658e-01 2.300783e-02 -5.221132e-01 -9.912485e+01 -1.598964e-02 9.997111e-01 1.794433e-02 -6.384109e-01 5.223752e-01 -6.950316e-03 8.526874e-01 1.138657e+02 +8.514464e-01 2.200552e-02 -5.239798e-01 -9.939682e+01 -1.525940e-02 9.997358e-01 1.718988e-02 -6.400806e-01 5.242196e-01 -6.640636e-03 8.515572e-01 1.143023e+02 +8.502349e-01 2.237476e-02 -5.259277e-01 -9.966423e+01 -1.755837e-02 9.997457e-01 1.414706e-02 -6.481915e-01 5.261106e-01 -2.793885e-03 8.504116e-01 1.147173e+02 +8.487383e-01 2.004088e-02 -5.284333e-01 -9.991884e+01 -1.744868e-02 9.997988e-01 9.892447e-03 -6.560401e-01 5.285252e-01 8.243642e-04 8.489172e-01 1.151137e+02 +8.465713e-01 1.638269e-02 -5.320232e-01 -1.001623e+02 -1.449194e-02 9.998651e-01 7.729033e-03 -6.586289e-01 5.320781e-01 1.166872e-03 8.466945e-01 1.154941e+02 +8.440195e-01 1.231158e-02 -5.361711e-01 -1.003993e+02 -9.473063e-03 9.999227e-01 8.048149e-03 -6.585884e-01 5.362288e-01 -1.713609e-03 8.440709e-01 1.158608e+02 +8.407253e-01 1.286955e-02 -5.413089e-01 -1.006332e+02 -9.322154e-03 9.999133e-01 9.294257e-03 -6.607942e-01 5.413817e-01 -2.767749e-03 8.407724e-01 1.162046e+02 +8.370973e-01 1.671075e-02 -5.467988e-01 -1.008652e+02 -1.245354e-02 9.998564e-01 1.149150e-02 -6.647242e-01 5.469123e-01 -2.809920e-03 8.371852e-01 1.165286e+02 +8.334971e-01 2.250171e-02 -5.520654e-01 -1.010904e+02 -1.674193e-02 9.997401e-01 1.547193e-02 -6.694671e-01 5.522701e-01 -3.653171e-03 8.336572e-01 1.168348e+02 +8.297184e-01 2.829663e-02 -5.574645e-01 -1.013056e+02 -1.887682e-02 9.995654e-01 2.264161e-02 -6.713923e-01 5.578630e-01 -8.262992e-03 8.298920e-01 1.171266e+02 +8.252128e-01 3.039574e-02 -5.640034e-01 -1.015060e+02 -1.830069e-02 9.994655e-01 2.708766e-02 -6.722784e-01 5.645254e-01 -1.203143e-02 8.253280e-01 1.174011e+02 +8.200253e-01 2.797336e-02 -5.716433e-01 -1.016929e+02 -1.429213e-02 9.994942e-01 2.840812e-02 -6.721459e-01 5.721489e-01 -1.512537e-02 8.200103e-01 1.176574e+02 +8.134516e-01 2.553501e-02 -5.810719e-01 -1.018739e+02 -1.048910e-02 9.995174e-01 2.923961e-02 -6.729960e-01 5.815381e-01 -1.769008e-02 8.133268e-01 1.178992e+02 +8.051579e-01 2.419731e-02 -5.925666e-01 -1.020513e+02 -7.576002e-03 9.995054e-01 3.052057e-02 -6.736387e-01 5.930121e-01 -2.008458e-02 8.049430e-01 1.181220e+02 +7.952832e-01 2.486111e-02 -6.057282e-01 -1.022292e+02 -7.165982e-03 9.994745e-01 3.161330e-02 -6.753232e-01 6.061958e-01 -2.080088e-02 7.950434e-01 1.183256e+02 +7.836390e-01 2.664974e-02 -6.206446e-01 -1.024053e+02 -9.010756e-03 9.994619e-01 3.153855e-02 -6.766433e-01 6.211511e-01 -1.912236e-02 7.834575e-01 1.185086e+02 +7.701169e-01 2.593285e-02 -6.373754e-01 -1.025760e+02 -8.981638e-03 9.995151e-01 2.981504e-02 -6.819095e-01 6.378395e-01 -1.723638e-02 7.699764e-01 1.186815e+02 +7.557080e-01 2.356824e-02 -6.544846e-01 -1.027420e+02 -9.752834e-03 9.996464e-01 2.473643e-02 -6.858513e-01 6.548362e-01 -1.231044e-02 7.556706e-01 1.188380e+02 +7.410694e-01 2.004899e-02 -6.711290e-01 -1.029018e+02 -9.297542e-03 9.997646e-01 1.960003e-02 -6.870036e-01 6.713641e-01 -8.285129e-03 7.410814e-01 1.189816e+02 +7.261313e-01 1.990391e-02 -6.872679e-01 -1.030684e+02 -1.290432e-02 9.997993e-01 1.532109e-02 -6.855969e-01 6.874350e-01 -2.256399e-03 7.262424e-01 1.191160e+02 +7.108736e-01 2.370184e-02 -7.029203e-01 -1.032450e+02 -2.015155e-02 9.997080e-01 1.332970e-02 -6.827537e-01 7.030310e-01 4.689201e-03 7.111437e-01 1.192422e+02 +6.942655e-01 2.626477e-02 -7.192396e-01 -1.034183e+02 -2.379218e-02 9.996252e-01 1.353770e-02 -6.819887e-01 7.193256e-01 7.713521e-03 6.946302e-01 1.193668e+02 +6.762025e-01 2.487456e-02 -7.362958e-01 -1.035947e+02 -2.049498e-02 9.996781e-01 1.495024e-02 -6.769315e-01 7.364307e-01 4.980977e-03 6.764947e-01 1.194976e+02 +6.568134e-01 2.395315e-02 -7.536726e-01 -1.037731e+02 -1.755662e-02 9.997101e-01 1.647239e-02 -6.726550e-01 7.538487e-01 2.412663e-03 6.570436e-01 1.196238e+02 +6.354473e-01 2.548306e-02 -7.717236e-01 -1.039548e+02 -1.698091e-02 9.996747e-01 1.902792e-02 -6.680274e-01 7.719575e-01 1.013332e-03 6.356734e-01 1.197348e+02 +6.121995e-01 3.033862e-02 -7.901211e-01 -1.041481e+02 -2.061469e-02 9.995363e-01 2.240702e-02 -6.624189e-01 7.904346e-01 2.570538e-03 6.125411e-01 1.198384e+02 +5.883415e-01 3.447575e-02 -8.078772e-01 -1.043385e+02 -2.259228e-02 9.994015e-01 2.619600e-02 -6.580382e-01 8.082969e-01 2.839598e-03 5.887683e-01 1.199342e+02 +5.634743e-01 3.764848e-02 -8.252753e-01 -1.045336e+02 -2.419062e-02 9.992846e-01 2.907001e-02 -6.558701e-01 8.257794e-01 3.583724e-03 5.639819e-01 1.200291e+02 +5.382124e-01 4.087249e-02 -8.418176e-01 -1.047330e+02 -2.695693e-02 9.991472e-01 3.127647e-02 -6.537004e-01 8.423781e-01 5.859440e-03 5.388552e-01 1.201137e+02 +5.122978e-01 4.558652e-02 -8.575971e-01 -1.049312e+02 -3.112374e-02 9.989197e-01 3.450648e-02 -6.515101e-01 8.582437e-01 9.014040e-03 5.131632e-01 1.201854e+02 +4.850922e-01 4.926544e-02 -8.730741e-01 -1.051362e+02 -3.346351e-02 9.987262e-01 3.776290e-02 -6.502394e-01 8.738225e-01 1.089764e-02 4.861229e-01 1.202566e+02 +4.561354e-01 4.910516e-02 -8.885545e-01 -1.053437e+02 -3.233505e-02 9.987316e-01 3.859496e-02 -6.512383e-01 8.893228e-01 1.112693e-02 4.571446e-01 1.203283e+02 +4.247164e-01 4.648377e-02 -9.041323e-01 -1.055582e+02 -3.170487e-02 9.988321e-01 3.645917e-02 -6.512936e-01 9.047711e-01 1.318059e-02 4.256942e-01 1.203886e+02 +3.909836e-01 4.240587e-02 -9.194202e-01 -1.058016e+02 -3.099238e-02 9.989781e-01 3.289576e-02 -6.467220e-01 9.198757e-01 1.563332e-02 3.918983e-01 1.204520e+02 +3.530581e-01 4.016684e-02 -9.347388e-01 -1.060565e+02 -3.016432e-02 9.990473e-01 3.153697e-02 -6.404796e-01 9.351151e-01 1.706138e-02 3.539333e-01 1.205003e+02 +3.124471e-01 3.932739e-02 -9.491207e-01 -1.063408e+02 -2.910442e-02 9.990699e-01 3.181601e-02 -6.320823e-01 9.494892e-01 1.768279e-02 3.133011e-01 1.205536e+02 +2.697084e-01 3.786323e-02 -9.621973e-01 -1.066408e+02 -2.804717e-02 9.991116e-01 3.145409e-02 -6.251645e-01 9.625335e-01 1.850348e-02 2.705307e-01 1.205994e+02 +2.234765e-01 3.507325e-02 -9.740781e-01 -1.069460e+02 -2.623512e-02 9.992067e-01 2.995910e-02 -6.151359e-01 9.743562e-01 1.885990e-02 2.242194e-01 1.206206e+02 +1.749796e-01 3.323298e-02 -9.840110e-01 -1.072795e+02 -2.476393e-02 9.992625e-01 2.934449e-02 -6.047007e-01 9.842606e-01 1.923329e-02 1.756735e-01 1.206402e+02 +1.254397e-01 3.299074e-02 -9.915526e-01 -1.076301e+02 -2.366468e-02 9.992621e-01 3.025348e-02 -5.937682e-01 9.918190e-01 1.966979e-02 1.261278e-01 1.206434e+02 +7.422523e-02 3.427442e-02 -9.966523e-01 -1.079733e+02 -2.214724e-02 9.992193e-01 3.271330e-02 -5.851771e-01 9.969956e-01 1.964494e-02 7.492637e-02 1.206163e+02 +2.122537e-02 3.663835e-02 -9.991031e-01 -1.083468e+02 -1.818862e-02 9.991770e-01 3.625467e-02 -5.780578e-01 9.996093e-01 1.740279e-02 2.187430e-02 1.205908e+02 +-3.218362e-02 3.879313e-02 -9.987288e-01 -1.087113e+02 -1.358154e-02 9.991372e-01 3.924666e-02 -5.724405e-01 9.993897e-01 1.482738e-02 -3.162899e-02 1.205308e+02 +-8.559961e-02 4.059260e-02 -9.955023e-01 -1.091034e+02 -8.797143e-03 9.990999e-01 4.149574e-02 -5.651093e-01 9.962908e-01 1.230960e-02 -8.516546e-02 1.204648e+02 +-1.383601e-01 4.236407e-02 -9.894755e-01 -1.095039e+02 -4.720745e-03 9.990451e-01 4.343391e-02 -5.571731e-01 9.903708e-01 1.068058e-02 -1.380280e-01 1.203764e+02 +-1.898080e-01 4.394759e-02 -9.808371e-01 -1.098936e+02 -1.637565e-03 9.989821e-01 4.507750e-02 -5.498158e-01 9.818199e-01 1.016226e-02 -1.895429e-01 1.202526e+02 +-2.393286e-01 4.521660e-02 -9.698852e-01 -1.103105e+02 2.445837e-03 9.989399e-01 4.596763e-02 -5.385017e-01 9.709356e-01 8.629191e-03 -2.391855e-01 1.201212e+02 +-2.877480e-01 4.668609e-02 -9.565676e-01 -1.107358e+02 8.279552e-03 9.988950e-01 4.626133e-02 -5.271191e-01 9.576704e-01 5.391657e-03 -2.878166e-01 1.199688e+02 +-3.346155e-01 4.809612e-02 -9.411266e-01 -1.111598e+02 1.399587e-02 9.988402e-01 4.606938e-02 -5.145431e-01 9.422508e-01 2.243642e-03 -3.349006e-01 1.197761e+02 +-3.791908e-01 4.985243e-02 -9.239746e-01 -1.116037e+02 1.948819e-02 9.987564e-01 4.588947e-02 -5.003029e-01 9.251133e-01 -6.057272e-04 -3.796907e-01 1.195688e+02 +-4.214956e-01 5.129773e-02 -9.053783e-01 -1.120419e+02 2.394144e-02 9.986802e-01 4.543827e-02 -4.860644e-01 9.065144e-01 -2.524024e-03 -4.221675e-01 1.193248e+02 +-4.607358e-01 5.216322e-02 -8.860031e-01 -1.124967e+02 2.716715e-02 9.986324e-01 4.466691e-02 -4.701443e-01 8.871215e-01 -3.490531e-03 -4.615228e-01 1.190622e+02 +-4.952290e-01 5.263507e-02 -8.671665e-01 -1.129599e+02 2.870388e-02 9.986093e-01 4.422091e-02 -4.518107e-01 8.682882e-01 -2.991566e-03 -4.960512e-01 1.187686e+02 +-5.244114e-01 5.234440e-02 -8.498546e-01 -1.134215e+02 2.906760e-02 9.986273e-01 4.357121e-02 -4.332770e-01 8.509688e-01 -1.853991e-03 -5.252131e-01 1.184470e+02 +-5.478370e-01 5.099196e-02 -8.350296e-01 -1.138987e+02 2.790612e-02 9.986990e-01 4.267829e-02 -4.140913e-01 8.361195e-01 7.831756e-05 -5.485473e-01 1.181067e+02 +-5.663021e-01 4.898964e-02 -8.227405e-01 -1.143790e+02 2.667038e-02 9.987984e-01 4.111539e-02 -4.005528e-01 8.237661e-01 1.340940e-03 -5.669282e-01 1.177492e+02 +-5.804739e-01 4.834624e-02 -8.128423e-01 -1.148756e+02 2.559142e-02 9.988259e-01 4.113263e-02 -3.846543e-01 8.138766e-01 3.074637e-03 -5.810297e-01 1.173755e+02 +-5.918390e-01 4.920885e-02 -8.045527e-01 -1.153845e+02 2.658306e-02 9.987834e-01 4.153377e-02 -3.685473e-01 8.056178e-01 3.193840e-03 -5.924271e-01 1.169889e+02 +-6.016909e-01 5.030468e-02 -7.971433e-01 -1.159072e+02 2.782236e-02 9.987291e-01 4.202544e-02 -3.511796e-01 7.982444e-01 3.107915e-03 -6.023258e-01 1.165875e+02 +-6.096544e-01 5.169924e-02 -7.909796e-01 -1.164394e+02 2.914620e-02 9.986580e-01 4.280865e-02 -3.334200e-01 7.921314e-01 3.044435e-03 -6.103431e-01 1.161705e+02 +-6.160694e-01 5.173926e-02 -7.859908e-01 -1.169780e+02 2.861515e-02 9.986518e-01 4.330917e-02 -3.145039e-01 7.871719e-01 4.190216e-03 -6.167194e-01 1.157373e+02 +-6.217490e-01 5.159735e-02 -7.815151e-01 -1.175268e+02 2.820515e-02 9.986554e-01 4.349432e-02 -2.939813e-01 7.827086e-01 4.999804e-03 -6.223683e-01 1.152919e+02 +-6.262794e-01 5.197506e-02 -7.778642e-01 -1.180864e+02 2.862566e-02 9.986354e-01 4.367921e-02 -2.732940e-01 7.790730e-01 5.088516e-03 -6.269126e-01 1.148352e+02 +-6.296183e-01 5.276167e-02 -7.751110e-01 -1.186599e+02 2.959963e-02 9.985960e-01 4.393067e-02 -2.513318e-01 7.763406e-01 4.716556e-03 -6.302960e-01 1.143662e+02 +-6.320345e-01 5.391669e-02 -7.730623e-01 -1.192396e+02 3.084404e-02 9.985364e-01 4.442500e-02 -2.283537e-01 7.743262e-01 4.233769e-03 -6.327725e-01 1.138874e+02 +-6.331395e-01 5.424664e-02 -7.721345e-01 -1.198351e+02 3.128798e-02 9.985195e-01 4.449573e-02 -2.043772e-01 7.734052e-01 4.013474e-03 -6.338994e-01 1.133947e+02 +-6.339116e-01 5.397883e-02 -7.715195e-01 -1.204389e+02 3.158847e-02 9.985361e-01 4.390755e-02 -1.816124e-01 7.727602e-01 3.462383e-03 -6.346887e-01 1.128933e+02 +-6.347218e-01 5.346434e-02 -7.708890e-01 -1.210569e+02 3.191314e-02 9.985661e-01 4.297860e-02 -1.575086e-01 7.720815e-01 2.677969e-03 -6.355179e-01 1.123812e+02 +-6.353366e-01 5.305633e-02 -7.704106e-01 -1.216870e+02 3.262167e-02 9.985904e-01 4.186835e-02 -1.322116e-01 7.715461e-01 1.468411e-03 -6.361718e-01 1.118577e+02 +-6.361552e-01 5.371925e-02 -7.696888e-01 -1.223282e+02 3.279522e-02 9.985543e-01 4.258703e-02 -1.050706e-01 7.708639e-01 1.849851e-03 -6.369972e-01 1.113222e+02 +-6.371377e-01 5.467189e-02 -7.688085e-01 -1.229704e+02 3.153192e-02 9.984949e-01 4.487391e-02 -7.535629e-02 7.701048e-01 4.348851e-03 -6.379026e-01 1.107728e+02 +-6.384034e-01 5.576446e-02 -7.676792e-01 -1.236258e+02 3.049076e-02 9.984214e-01 4.716949e-02 -4.736641e-02 7.690978e-01 6.706041e-03 -6.390960e-01 1.102135e+02 +-6.395288e-01 5.599430e-02 -7.667252e-01 -1.242849e+02 3.066053e-02 9.984081e-01 4.734015e-02 -1.867648e-02 7.681555e-01 6.767193e-03 -6.402276e-01 1.096502e+02 +-6.405461e-01 5.483645e-02 -7.659593e-01 -1.249562e+02 3.155445e-02 9.984842e-01 4.509543e-02 1.110994e-02 7.672712e-01 4.716275e-03 -6.413055e-01 1.090798e+02 +-6.413875e-01 5.432909e-02 -7.652911e-01 -1.256369e+02 3.253119e-02 9.985183e-01 4.362198e-02 4.221843e-02 7.665271e-01 3.082760e-03 -6.422045e-01 1.085006e+02 +-6.423178e-01 5.530909e-02 -7.644401e-01 -1.263320e+02 3.475676e-02 9.984687e-01 4.303742e-02 7.133427e-02 7.656500e-01 1.074243e-03 -6.432566e-01 1.079136e+02 +-6.431044e-01 5.686590e-02 -7.636642e-01 -1.270372e+02 3.729233e-02 9.983814e-01 4.293905e-02 9.929117e-02 7.648699e-01 -8.645199e-04 -6.441842e-01 1.073179e+02 +-6.443445e-01 5.487375e-02 -7.627641e-01 -1.277453e+02 3.718315e-02 9.984906e-01 4.042165e-02 1.250424e-01 7.638309e-01 -2.316499e-03 -6.454123e-01 1.067132e+02 +-6.454794e-01 5.165757e-02 -7.620288e-01 -1.284619e+02 3.704776e-02 9.986533e-01 3.631682e-02 1.484347e-01 7.628787e-01 -4.789697e-03 -6.465239e-01 1.061014e+02 +-6.464204e-01 4.749143e-02 -7.615020e-01 -1.291860e+02 3.554941e-02 9.988517e-01 3.211685e-02 1.669410e-01 7.621529e-01 -6.309957e-03 -6.473664e-01 1.054824e+02 +-6.463785e-01 4.518995e-02 -7.616775e-01 -1.299193e+02 3.281356e-02 9.989674e-01 3.142186e-02 1.835941e-01 7.623111e-01 -4.682937e-03 -6.471939e-01 1.048515e+02 +-6.462990e-01 4.543464e-02 -7.617305e-01 -1.306623e+02 3.133869e-02 9.989640e-01 3.299517e-02 1.979002e-01 7.624405e-01 -2.546888e-03 -6.470533e-01 1.042149e+02 +-6.463611e-01 4.720907e-02 -7.615698e-01 -1.314132e+02 3.054604e-02 9.988850e-01 3.599495e-02 2.144697e-01 7.624200e-01 2.797270e-06 -6.470825e-01 1.035744e+02 +-6.463919e-01 4.990347e-02 -7.613719e-01 -1.321648e+02 3.161416e-02 9.987536e-01 3.862258e-02 2.318873e-01 7.623504e-01 8.951891e-04 -6.471639e-01 1.029386e+02 +-6.464693e-01 5.240601e-02 -7.611380e-01 -1.329234e+02 3.311670e-02 9.986253e-01 4.063002e-02 2.513658e-01 7.622210e-01 1.059678e-03 -6.473161e-01 1.023035e+02 +-6.465598e-01 5.357037e-02 -7.609801e-01 -1.336799e+02 3.375429e-02 9.985633e-01 4.161642e-02 2.702986e-01 7.621162e-01 1.221165e-03 -6.474391e-01 1.016681e+02 +-6.465548e-01 5.418809e-02 -7.609405e-01 -1.344357e+02 3.422569e-02 9.985301e-01 4.202650e-02 2.900097e-01 7.620994e-01 1.128723e-03 -6.474591e-01 1.010301e+02 +-6.467821e-01 5.330896e-02 -7.608094e-01 -1.351892e+02 3.266538e-02 9.985751e-01 4.219930e-02 3.106498e-01 7.619750e-01 2.441633e-03 -6.476019e-01 1.003904e+02 +-6.467717e-01 5.405138e-02 -7.607659e-01 -1.359465e+02 3.255466e-02 9.985329e-01 4.326781e-02 3.298425e-01 7.619886e-01 3.217921e-03 -6.475825e-01 9.975107e+01 +-6.469056e-01 5.488490e-02 -7.605924e-01 -1.367105e+02 3.211773e-02 9.984825e-01 4.473420e-02 3.478641e-01 7.618935e-01 4.510303e-03 -6.476867e-01 9.910851e+01 +-6.470020e-01 5.587287e-02 -7.604384e-01 -1.374685e+02 3.236215e-02 9.984251e-01 4.582425e-02 3.680159e-01 7.618013e-01 5.038959e-03 -6.477912e-01 9.846944e+01 +-6.474888e-01 5.591651e-02 -7.600207e-01 -1.382274e+02 3.251834e-02 9.984234e-01 4.575285e-02 3.899821e-01 7.613809e-01 4.909849e-03 -6.482863e-01 9.782785e+01 +-6.479718e-01 5.568539e-02 -7.596260e-01 -1.389901e+02 3.346596e-02 9.984422e-01 4.464521e-02 4.148069e-01 7.609288e-01 3.507227e-03 -6.488260e-01 9.718269e+01 +-6.487532e-01 5.567193e-02 -7.589598e-01 -1.397480e+02 3.408349e-02 9.984453e-01 4.410461e-02 4.343912e-01 7.602353e-01 2.745016e-03 -6.496421e-01 9.654609e+01 +-6.493896e-01 5.616798e-02 -7.583788e-01 -1.405111e+02 3.459986e-02 9.984181e-01 4.431870e-02 4.529559e-01 7.596684e-01 2.540305e-03 -6.503057e-01 9.590422e+01 +-6.502005e-01 5.565784e-02 -7.577212e-01 -1.412656e+02 3.405124e-02 9.984457e-01 4.412073e-02 4.726101e-01 7.589992e-01 2.885982e-03 -6.510851e-01 9.526259e+01 +-6.507781e-01 5.470254e-02 -7.572949e-01 -1.420208e+02 3.337598e-02 9.984982e-01 4.344417e-02 4.912744e-01 7.585341e-01 2.997059e-03 -6.516265e-01 9.462044e+01 +-6.512694e-01 5.347435e-02 -7.569601e-01 -1.427704e+02 3.266842e-02 9.985650e-01 4.243511e-02 5.111815e-01 7.581431e-01 2.908002e-03 -6.520818e-01 9.397889e+01 +-6.512026e-01 5.277174e-02 -7.570669e-01 -1.435294e+02 3.182284e-02 9.986007e-01 4.223510e-02 5.274135e-01 7.582364e-01 3.411590e-03 -6.519708e-01 9.333700e+01 +-6.511605e-01 5.114720e-02 -7.572146e-01 -1.442862e+02 2.855639e-02 9.986712e-01 4.289993e-02 5.445632e-01 7.584026e-01 6.311429e-03 -6.517558e-01 9.269067e+01 +-6.503822e-01 5.036423e-02 -7.579356e-01 -1.450409e+02 2.708532e-02 9.987026e-01 4.312121e-02 5.612957e-01 7.591241e-01 7.516344e-03 -6.509026e-01 9.204892e+01 +-6.494136e-01 4.861105e-02 -7.588801e-01 -1.457940e+02 2.603743e-02 9.987909e-01 4.169728e-02 5.779645e-01 7.599896e-01 7.319490e-03 -6.498941e-01 9.141052e+01 +-6.480610e-01 4.603184e-02 -7.601960e-01 -1.465475e+02 2.412882e-02 9.989116e-01 3.991709e-02 5.937592e-01 7.612061e-01 7.526081e-03 -6.484664e-01 9.077404e+01 +-6.465859e-01 4.634081e-02 -7.614323e-01 -1.473072e+02 2.492243e-02 9.989035e-01 3.962995e-02 6.086489e-01 7.624340e-01 6.647426e-03 -6.470319e-01 9.013928e+01 +-6.455338e-01 4.889900e-02 -7.621646e-01 -1.480704e+02 2.617218e-02 9.987784e-01 4.191254e-02 6.250373e-01 7.632831e-01 7.108459e-03 -6.460251e-01 8.950321e+01 +-6.442557e-01 5.464892e-02 -7.628552e-01 -1.488333e+02 2.896060e-02 9.984717e-01 4.706973e-02 6.468099e-01 7.642616e-01 8.232197e-03 -6.448538e-01 8.887146e+01 +-6.432656e-01 6.160484e-02 -7.631607e-01 -1.496005e+02 3.171803e-02 9.980462e-01 5.383057e-02 6.716835e-01 7.649859e-01 1.042140e-02 -6.439628e-01 8.823696e+01 +-6.427117e-01 6.393031e-02 -7.634360e-01 -1.503591e+02 3.209023e-02 9.978840e-01 5.654736e-02 6.967564e-01 7.654358e-01 1.184482e-02 -6.434033e-01 8.760683e+01 +-6.425511e-01 6.032541e-02 -7.638645e-01 -1.511134e+02 3.231318e-02 9.981425e-01 5.164595e-02 7.256258e-01 7.655612e-01 8.502276e-03 -6.433069e-01 8.697809e+01 +-6.426114e-01 5.645154e-02 -7.641098e-01 -1.518671e+02 3.212413e-02 9.983902e-01 4.674373e-02 7.539528e-01 7.655186e-01 5.491693e-03 -6.433904e-01 8.634989e+01 +-6.424432e-01 5.639400e-02 -7.642555e-01 -1.526218e+02 3.249778e-02 9.983963e-01 4.635309e-02 7.806961e-01 7.656440e-01 4.942624e-03 -6.432456e-01 8.571894e+01 +-6.425603e-01 5.837811e-02 -7.640080e-01 -1.533790e+02 3.171360e-02 9.982652e-01 4.960544e-02 8.039512e-01 7.655786e-01 7.645046e-03 -6.432970e-01 8.508539e+01 +-6.426567e-01 6.049709e-02 -7.637621e-01 -1.541322e+02 3.258913e-02 9.981339e-01 5.163989e-02 8.288243e-01 7.654609e-01 8.296381e-03 -6.434290e-01 8.445676e+01 +-6.431479e-01 5.986322e-02 -7.633984e-01 -1.548823e+02 3.378566e-02 9.981870e-01 4.981086e-02 8.536668e-01 7.649963e-01 6.243830e-03 -6.440044e-01 8.383215e+01 +-6.438258e-01 5.874944e-02 -7.629134e-01 -1.556292e+02 3.429074e-02 9.982617e-01 4.793476e-02 8.796994e-01 7.644034e-01 4.700774e-03 -6.447212e-01 8.320615e+01 +-6.444559e-01 5.910036e-02 -7.623541e-01 -1.563743e+02 3.369850e-02 9.982350e-01 4.889968e-02 9.056545e-01 7.638986e-01 5.823502e-03 -6.453100e-01 8.257906e+01 +-6.448800e-01 6.257715e-02 -7.617177e-01 -1.571190e+02 3.425531e-02 9.980074e-01 5.298802e-02 9.324518e-01 7.635159e-01 8.078038e-03 -6.457386e-01 8.195146e+01 +-6.454261e-01 6.577348e-02 -7.609855e-01 -1.578614e+02 3.471173e-02 9.977820e-01 5.679970e-02 9.618364e-01 7.630336e-01 1.024489e-02 -6.462777e-01 8.132671e+01 +-6.459200e-01 6.677058e-02 -7.604795e-01 -1.586032e+02 3.611815e-02 9.977250e-01 5.692364e-02 9.920658e-01 7.625503e-01 9.301002e-03 -6.468621e-01 8.070349e+01 +-6.465276e-01 6.641559e-02 -7.599941e-01 -1.593358e+02 3.720081e-02 9.977628e-01 5.554738e-02 1.022069e+00 7.619831e-01 7.640516e-03 -6.475519e-01 8.008383e+01 +-6.469687e-01 6.525242e-02 -7.597194e-01 -1.600585e+02 3.777343e-02 9.978511e-01 5.353817e-02 1.049905e+00 7.615804e-01 5.940314e-03 -6.480433e-01 7.946455e+01 +-6.470368e-01 6.302762e-02 -7.598493e-01 -1.607804e+02 3.574975e-02 9.979893e-01 5.233868e-02 1.077505e+00 7.616203e-01 6.700632e-03 -6.479890e-01 7.884428e+01 +-6.462966e-01 6.110321e-02 -7.606360e-01 -1.615000e+02 3.319896e-02 9.980966e-01 5.197039e-02 1.102704e+00 7.623638e-01 8.335959e-03 -6.470950e-01 7.822487e+01 +-6.458213e-01 5.980054e-02 -7.611430e-01 -1.622213e+02 3.180653e-02 9.981697e-01 5.143550e-02 1.128462e+00 7.628258e-01 9.008824e-03 -6.465413e-01 7.760858e+01 +-6.452629e-01 5.885567e-02 -7.616901e-01 -1.629402e+02 3.008946e-02 9.982123e-01 5.164155e-02 1.154301e+00 7.633678e-01 1.040353e-02 -6.458803e-01 7.699411e+01 +-6.447113e-01 5.801038e-02 -7.622218e-01 -1.636585e+02 2.849878e-02 9.982472e-01 5.186841e-02 1.179845e+00 7.638948e-01 1.171776e-02 -6.452345e-01 7.638223e+01 +-6.441184e-01 5.888661e-02 -7.626558e-01 -1.643767e+02 2.918479e-02 9.981983e-01 5.242480e-02 1.205952e+00 7.643689e-01 1.150983e-02 -6.446765e-01 7.577428e+01 +-6.437684e-01 5.733999e-02 -7.630690e-01 -1.650930e+02 2.843930e-02 9.982925e-01 5.102261e-02 1.231444e+00 7.646917e-01 1.114560e-02 -6.442999e-01 7.517018e+01 +-6.431937e-01 5.586034e-02 -7.636632e-01 -1.658081e+02 2.755609e-02 9.983780e-01 4.982020e-02 1.257020e+00 7.652076e-01 1.100046e-02 -6.436897e-01 7.456637e+01 +-6.427698e-01 5.656035e-02 -7.639685e-01 -1.665248e+02 2.861006e-02 9.983473e-01 4.984133e-02 1.282062e+00 7.655250e-01 1.017932e-02 -6.433257e-01 7.396713e+01 +-6.420327e-01 5.939250e-02 -7.643733e-01 -1.672418e+02 3.146816e-02 9.981961e-01 5.112921e-02 1.306576e+00 7.660312e-01 8.773208e-03 -6.427436e-01 7.337210e+01 +-6.417897e-01 6.070444e-02 -7.644743e-01 -1.679552e+02 3.245390e-02 9.981190e-01 5.201181e-02 1.330108e+00 7.661937e-01 8.570471e-03 -6.425526e-01 7.277838e+01 +-6.414898e-01 5.863152e-02 -7.648877e-01 -1.686684e+02 3.248127e-02 9.982567e-01 4.927902e-02 1.351053e+00 7.664437e-01 6.767464e-03 -6.422759e-01 7.219108e+01 +-6.411565e-01 5.662618e-02 -7.653181e-01 -1.693812e+02 3.399575e-02 9.983907e-01 4.539089e-02 1.373431e+00 7.666568e-01 3.085099e-03 -6.420497e-01 7.161267e+01 +-6.403780e-01 5.577115e-02 -7.660324e-01 -1.700844e+02 3.508055e-02 9.984431e-01 4.336570e-02 1.396727e+00 7.672584e-01 8.976054e-04 -6.413375e-01 7.103558e+01 +-6.398494e-01 5.436515e-02 -7.665750e-01 -1.707831e+02 3.167854e-02 9.985126e-01 4.437246e-02 1.405731e+00 7.678472e-01 4.107716e-03 -6.406199e-01 7.046800e+01 +-6.396969e-01 5.491240e-02 -7.666633e-01 -1.714722e+02 3.087900e-02 9.984755e-01 4.575085e-02 1.416166e+00 7.680068e-01 5.592882e-03 -6.404173e-01 6.990570e+01 +-6.398714e-01 5.487944e-02 -7.665199e-01 -1.721588e+02 3.082442e-02 9.984770e-01 4.575512e-02 1.425569e+00 7.678636e-01 5.649867e-03 -6.405885e-01 6.935261e+01 +-6.400269e-01 5.437972e-02 -7.664257e-01 -1.728299e+02 3.095182e-02 9.985074e-01 4.499923e-02 1.436887e+00 7.677289e-01 5.078452e-03 -6.407547e-01 6.880749e+01 +-6.399736e-01 5.455099e-02 -7.664581e-01 -1.734939e+02 3.143292e-02 9.985004e-01 4.482041e-02 1.448357e+00 7.677537e-01 4.591870e-03 -6.407286e-01 6.826999e+01 +-6.400838e-01 5.417777e-02 -7.663925e-01 -1.741451e+02 3.096746e-02 9.985193e-01 4.472355e-02 1.460081e+00 7.676808e-01 4.893591e-03 -6.408138e-01 6.773915e+01 +-6.400459e-01 5.377408e-02 -7.664526e-01 -1.747856e+02 2.996269e-02 9.985359e-01 4.503589e-02 1.470417e+00 7.677523e-01 5.860056e-03 -6.407200e-01 6.721605e+01 +-6.402351e-01 5.366964e-02 -7.663019e-01 -1.754193e+02 2.983323e-02 9.985410e-01 4.500977e-02 1.482743e+00 7.675995e-01 5.955573e-03 -6.409021e-01 6.669815e+01 +-6.404712e-01 5.442425e-02 -7.660513e-01 -1.760447e+02 3.021354e-02 9.984992e-01 4.567798e-02 1.496245e+00 7.673876e-01 6.110312e-03 -6.411544e-01 6.618835e+01 +-6.406157e-01 5.614235e-02 -7.658065e-01 -1.766638e+02 3.041021e-02 9.983960e-01 4.775496e-02 1.510435e+00 7.672593e-01 7.304241e-03 -6.412955e-01 6.568420e+01 +-6.407315e-01 5.812858e-02 -7.655613e-01 -1.772745e+02 3.088011e-02 9.982740e-01 4.995343e-02 1.525125e+00 7.671438e-01 8.366123e-03 -6.414207e-01 6.518539e+01 +-6.406910e-01 6.023602e-02 -7.654323e-01 -1.778683e+02 3.198492e-02 9.981463e-01 5.177718e-02 1.538016e+00 7.671323e-01 8.690887e-03 -6.414300e-01 6.468934e+01 +-6.408903e-01 6.204167e-02 -7.651212e-01 -1.784448e+02 3.338313e-02 9.980382e-01 5.296553e-02 1.550332e+00 7.669062e-01 8.402956e-03 -6.417042e-01 6.419739e+01 +-6.410091e-01 6.387398e-02 -7.648709e-01 -1.790078e+02 3.538205e-02 9.979309e-01 5.368438e-02 1.561925e+00 7.667174e-01 7.349473e-03 -6.419427e-01 6.371223e+01 +-6.413462e-01 6.463854e-02 -7.645240e-01 -1.795612e+02 3.658053e-02 9.978878e-01 5.368209e-02 1.575397e+00 7.663791e-01 6.462121e-03 -6.423561e-01 6.324071e+01 +-6.421016e-01 6.463336e-02 -7.638900e-01 -1.801003e+02 3.614028e-02 9.978838e-01 5.405341e-02 1.586480e+00 7.657672e-01 7.100584e-03 -6.430787e-01 6.276519e+01 +-6.428834e-01 6.567946e-02 -7.631429e-01 -1.806249e+02 3.786223e-02 9.978238e-01 5.398143e-02 1.600125e+00 7.650277e-01 5.809474e-03 -6.439712e-01 6.231141e+01 +-6.447407e-01 6.575811e-02 -7.615677e-01 -1.811416e+02 3.966692e-02 9.978287e-01 5.257639e-02 1.611948e+00 7.633715e-01 3.689100e-03 -6.459492e-01 6.186056e+01 +-6.480579e-01 6.665657e-02 -7.586684e-01 -1.816486e+02 4.255797e-02 9.977755e-01 5.131132e-02 1.623859e+00 7.604011e-01 9.653260e-04 -6.494531e-01 6.141959e+01 +-6.530127e-01 6.800060e-02 -7.542880e-01 -1.821422e+02 4.562165e-02 9.976842e-01 5.044708e-02 1.635244e+00 7.559716e-01 -1.469276e-03 -6.546028e-01 6.098005e+01 +-6.604873e-01 6.960899e-02 -7.476036e-01 -1.826223e+02 4.870988e-02 9.975682e-01 4.984925e-02 1.648540e+00 7.492556e-01 -3.490882e-03 -6.622718e-01 6.054530e+01 +-6.691152e-01 7.162616e-02 -7.396989e-01 -1.830885e+02 5.145583e-02 9.974210e-01 5.003600e-02 1.662241e+00 7.413752e-01 -4.581971e-03 -6.710752e-01 6.011032e+01 +-6.790672e-01 7.307650e-02 -7.304298e-01 -1.835369e+02 5.363983e-02 9.973123e-01 4.990906e-02 1.673611e+00 7.321138e-01 -5.288521e-03 -6.811618e-01 5.967252e+01 +-6.909268e-01 7.521748e-02 -7.190011e-01 -1.839747e+02 5.658612e-02 9.971480e-01 4.993889e-02 1.685440e+00 7.207068e-01 -6.181362e-03 -6.932125e-01 5.923570e+01 +-7.049019e-01 7.806521e-02 -7.049959e-01 -1.844045e+02 6.125005e-02 9.969117e-01 4.914763e-02 1.698748e+00 7.066554e-01 -8.536774e-03 -7.075064e-01 5.880121e+01 +-7.205772e-01 8.079459e-02 -6.886514e-01 -1.848122e+02 6.566146e-02 9.966758e-01 4.822743e-02 1.713703e+00 6.902587e-01 -1.046626e-02 -7.234869e-01 5.836066e+01 +-7.384341e-01 8.213636e-02 -6.693046e-01 -1.851982e+02 6.742783e-02 9.965733e-01 4.790632e-02 1.732581e+00 6.709461e-01 -9.754091e-03 -7.414420e-01 5.791203e+01 +-7.577802e-01 8.157959e-02 -6.473901e-01 -1.855495e+02 6.626024e-02 9.966456e-01 4.803173e-02 1.749510e+00 6.491370e-01 -6.498730e-03 -7.606438e-01 5.745834e+01 +-7.778313e-01 8.003764e-02 -6.233558e-01 -1.858798e+02 6.386685e-02 9.967893e-01 4.829193e-02 1.767896e+00 6.252196e-01 -2.248789e-03 -7.804457e-01 5.700033e+01 +-7.988411e-01 7.793289e-02 -5.964725e-01 -1.861871e+02 6.121497e-02 9.969565e-01 4.827497e-02 1.784988e+00 5.984193e-01 2.050994e-03 -8.011805e-01 5.653757e+01 +-8.206053e-01 7.637512e-02 -5.663690e-01 -1.864550e+02 5.960271e-02 9.970628e-01 4.809677e-02 1.807526e+00 5.683789e-01 5.711337e-03 -8.227471e-01 5.606608e+01 +-8.431125e-01 7.749341e-02 -5.321242e-01 -1.867152e+02 6.098436e-02 9.969567e-01 4.856183e-02 1.826654e+00 5.342680e-01 8.491831e-03 -8.452725e-01 5.559683e+01 +-8.665648e-01 7.378531e-02 -4.935800e-01 -1.869445e+02 5.780157e-02 9.971931e-01 4.758990e-02 1.842880e+00 4.957061e-01 1.271003e-02 -8.683974e-01 5.512564e+01 +-8.891895e-01 6.644194e-02 -4.526892e-01 -1.871206e+02 5.173784e-02 9.976552e-01 4.480209e-02 1.856411e+00 4.546045e-01 1.641639e-02 -8.905421e-01 5.464759e+01 +-9.098548e-01 5.445376e-02 -4.113381e-01 -1.872835e+02 4.117828e-02 9.983072e-01 4.107410e-02 1.870218e+00 4.128785e-01 2.043327e-02 -9.105569e-01 5.417085e+01 +-9.283201e-01 4.509830e-02 -3.690366e-01 -1.874227e+02 3.357747e-02 9.987291e-01 3.758534e-02 1.883289e+00 3.702626e-01 2.249990e-02 -9.286546e-01 5.369416e+01 +-9.452512e-01 3.706129e-02 -3.242324e-01 -1.875256e+02 2.776133e-02 9.990610e-01 3.326342e-02 1.887417e+00 3.251607e-01 2.244117e-02 -9.453925e-01 5.321309e+01 +-9.602059e-01 3.410654e-02 -2.772028e-01 -1.876307e+02 2.674480e-02 9.991831e-01 3.029615e-02 1.893359e+00 2.780097e-01 2.167680e-02 -9.603337e-01 5.273710e+01 +-9.729422e-01 3.276894e-02 -2.287129e-01 -1.876915e+02 2.667847e-02 9.992036e-01 2.967147e-02 1.900316e+00 2.295031e-01 2.276691e-02 -9.730416e-01 5.225276e+01 +-9.831529e-01 3.240420e-02 -1.798899e-01 -1.877485e+02 2.738709e-02 9.991654e-01 3.030454e-02 1.901338e+00 1.807218e-01 2.486734e-02 -9.832198e-01 5.177232e+01 +-9.911510e-01 2.523874e-02 -1.303180e-01 -1.877723e+02 2.111370e-02 9.992343e-01 3.293915e-02 1.900778e+00 1.310496e-01 2.989617e-02 -9.909249e-01 5.129098e+01 +-9.966637e-01 1.446740e-02 -8.032513e-02 -1.877414e+02 1.146235e-02 9.992216e-01 3.774707e-02 1.901606e+00 8.080871e-02 3.670042e-02 -9.960537e-01 5.080341e+01 +-9.995040e-01 1.006074e-02 -2.984320e-02 -1.877165e+02 8.815319e-03 9.990965e-01 4.157437e-02 1.903912e+00 3.023451e-02 4.129067e-02 -9.986896e-01 5.033042e+01 +-9.996705e-01 1.307490e-02 2.209183e-02 -1.876828e+02 1.395603e-02 9.990937e-01 4.021250e-02 1.909578e+00 -2.154603e-02 4.050756e-02 -9.989469e-01 4.986716e+01 +-9.970705e-01 2.051987e-02 7.368440e-02 -1.876045e+02 2.335961e-02 9.990090e-01 3.788635e-02 1.913879e+00 -7.283396e-02 3.949659e-02 -9.965617e-01 4.940375e+01 +-9.919546e-01 2.316199e-02 1.244574e-01 -1.875198e+02 2.767742e-02 9.990153e-01 3.467489e-02 1.916071e+00 -1.235318e-01 3.784057e-02 -9.916189e-01 4.895472e+01 +-9.843986e-01 2.362611e-02 1.743596e-01 -1.873856e+02 2.975169e-02 9.990255e-01 3.260177e-02 1.916040e+00 -1.734194e-01 3.728062e-02 -9.841422e-01 4.850872e+01 +-9.745046e-01 2.207656e-02 2.232787e-01 -1.872454e+02 2.939030e-02 9.991330e-01 2.948581e-02 1.919502e+00 -2.224342e-01 3.529628e-02 -9.743086e-01 4.808322e+01 +-9.620042e-01 2.331542e-02 2.720374e-01 -1.870919e+02 3.162970e-02 9.991557e-01 2.621754e-02 1.921924e+00 -2.711965e-01 3.382584e-02 -9.619295e-01 4.766758e+01 +-9.466844e-01 2.747540e-02 3.209888e-01 -1.869050e+02 3.735473e-02 9.989978e-01 2.465901e-02 1.925132e+00 -3.199896e-01 3.533474e-02 -9.467619e-01 4.724980e+01 +-9.303521e-01 3.021656e-02 3.654203e-01 -1.867142e+02 4.116827e-02 9.989052e-01 2.221412e-02 1.922721e+00 -3.643491e-01 3.571067e-02 -9.305775e-01 4.684089e+01 +-9.132370e-01 2.475193e-02 4.066762e-01 -1.864782e+02 3.739334e-02 9.990320e-01 2.316585e-02 1.917552e+00 -4.057092e-01 3.636289e-02 -9.132786e-01 4.643056e+01 +-8.953418e-01 1.994046e-02 4.449332e-01 -1.862433e+02 3.564541e-02 9.990008e-01 2.695748e-02 1.910636e+00 -4.439511e-01 3.999598e-02 -8.951580e-01 4.602498e+01 +-8.776813e-01 1.983338e-02 4.788341e-01 -1.859999e+02 3.901401e-02 9.987839e-01 3.014110e-02 1.906858e+00 -4.776541e-01 4.513551e-02 -8.773878e-01 4.562057e+01 +-8.608718e-01 2.164481e-02 5.083614e-01 -1.857437e+02 4.407236e-02 9.985119e-01 3.211896e-02 1.904895e+00 -5.069097e-01 5.005498e-02 -8.605447e-01 4.521752e+01 +-8.451571e-01 2.084750e-02 5.341113e-01 -1.854762e+02 4.497868e-02 9.984688e-01 3.220013e-02 1.903482e+00 -5.326223e-01 5.123778e-02 -8.448007e-01 4.482494e+01 +-8.309578e-01 1.849718e-02 5.560279e-01 -1.851904e+02 4.411559e-02 9.984907e-01 3.271225e-02 1.903992e+00 -5.545836e-01 5.171199e-02 -8.305196e-01 4.443350e+01 +-8.187995e-01 1.697153e-02 5.738286e-01 -1.848981e+02 4.276455e-02 9.985889e-01 3.148676e-02 1.906175e+00 -5.724845e-01 5.032086e-02 -8.183699e-01 4.404415e+01 +-8.087019e-01 1.617290e-02 5.879963e-01 -1.845971e+02 4.220964e-02 9.986405e-01 3.058539e-02 1.908337e+00 -5.867023e-01 4.955357e-02 -8.082852e-01 4.365148e+01 +-8.004594e-01 1.505932e-02 5.991977e-01 -1.842874e+02 4.110786e-02 9.987097e-01 2.981533e-02 1.908808e+00 -5.979757e-01 4.849769e-02 -8.000457e-01 4.325715e+01 +-7.938748e-01 1.369429e-02 6.079270e-01 -1.839689e+02 3.910696e-02 9.988265e-01 2.856890e-02 1.909156e+00 -6.068224e-01 4.645430e-02 -7.934788e-01 4.285899e+01 +-7.885180e-01 1.277601e-02 6.148789e-01 -1.836434e+02 3.674891e-02 9.989765e-01 2.636980e-02 1.911087e+00 -6.139128e-01 4.338919e-02 -7.881805e-01 4.245635e+01 +-7.839208e-01 1.439576e-02 6.206939e-01 -1.833133e+02 3.766703e-02 9.989923e-01 2.440285e-02 1.914906e+00 -6.197172e-01 4.250959e-02 -7.836731e-01 4.204606e+01 +-7.802917e-01 1.576827e-02 6.252169e-01 -1.829728e+02 3.925412e-02 9.989458e-01 2.379656e-02 1.921291e+00 -6.241826e-01 4.311059e-02 -7.800882e-01 4.162858e+01 +-7.774459e-01 1.916976e-02 6.286576e-01 -1.826247e+02 4.323140e-02 9.988001e-01 2.300664e-02 1.928571e+00 -6.274623e-01 4.506416e-02 -7.773418e-01 4.120434e+01 +-7.752609e-01 1.747523e-02 6.313994e-01 -1.822608e+02 4.062155e-02 9.989273e-01 2.222968e-02 1.933488e+00 -6.303337e-01 4.288221e-02 -7.751391e-01 4.077740e+01 +-7.736951e-01 1.525901e-02 6.333744e-01 -1.818872e+02 3.648927e-02 9.991237e-01 2.050275e-02 1.936481e+00 -6.325065e-01 3.897424e-02 -7.735739e-01 4.034468e+01 +-7.727979e-01 1.245903e-02 6.345299e-01 -1.815012e+02 3.297646e-02 9.992450e-01 2.054200e-02 1.944762e+00 -6.337949e-01 3.679936e-02 -7.726253e-01 3.989489e+01 +-7.721832e-01 1.363875e-02 6.352536e-01 -1.811166e+02 3.526394e-02 9.991486e-01 2.141362e-02 1.952827e+00 -6.344207e-01 3.893677e-02 -7.720067e-01 3.943245e+01 +-7.720920e-01 1.771611e-02 6.352638e-01 -1.807267e+02 4.063309e-02 9.989422e-01 2.152664e-02 1.954282e+00 -6.342105e-01 4.243327e-02 -7.719952e-01 3.895179e+01 +-7.726991e-01 1.851669e-02 6.345023e-01 -1.803265e+02 4.147552e-02 9.989112e-01 2.135778e-02 1.951012e+00 -6.334160e-01 4.281944e-02 -7.726258e-01 3.846147e+01 +-7.731938e-01 1.750785e-02 6.339280e-01 -1.799121e+02 3.693870e-02 9.991650e-01 1.745866e-02 1.948467e+00 -6.330931e-01 3.691540e-02 -7.731950e-01 3.796509e+01 +-7.734679e-01 2.123109e-02 6.334797e-01 -1.794927e+02 3.592724e-02 9.993005e-01 1.037495e-02 1.950893e+00 -6.328164e-01 3.078387e-02 -7.736897e-01 3.745911e+01 +-7.738922e-01 2.344744e-02 6.328832e-01 -1.790635e+02 3.477357e-02 9.993801e-01 5.495602e-03 1.950476e+00 -6.323620e-01 2.626060e-02 -7.742278e-01 3.693739e+01 +-7.742689e-01 2.561184e-02 6.323383e-01 -1.786239e+02 3.752559e-02 9.992806e-01 5.474080e-03 1.946894e+00 -6.317433e-01 2.796728e-02 -7.746730e-01 3.639418e+01 +-7.745069e-01 2.281632e-02 6.321538e-01 -1.781621e+02 3.591383e-02 9.993234e-01 7.932587e-03 1.942150e+00 -6.315451e-01 2.884690e-02 -7.748023e-01 3.584918e+01 +-7.748066e-01 1.662207e-02 6.319798e-01 -1.776842e+02 2.993010e-02 9.994978e-01 1.040588e-02 1.937626e+00 -6.314895e-01 2.697775e-02 -7.749150e-01 3.529616e+01 +-7.746446e-01 1.254996e-02 6.322722e-01 -1.771997e+02 2.594053e-02 9.995921e-01 1.194081e-02 1.929672e+00 -6.318646e-01 2.565136e-02 -7.746543e-01 3.472689e+01 +-7.743612e-01 1.140599e-02 6.326410e-01 -1.767106e+02 2.538766e-02 9.995924e-01 1.305301e-02 1.923186e+00 -6.322343e-01 2.616901e-02 -7.743352e-01 3.414270e+01 +-7.744470e-01 9.052690e-03 6.325740e-01 -1.762079e+02 2.502673e-02 9.995533e-01 1.633520e-02 1.922565e+00 -6.321436e-01 2.848200e-02 -7.743276e-01 3.353889e+01 +-7.748757e-01 7.106280e-03 6.320737e-01 -1.756955e+02 2.596852e-02 9.994505e-01 2.059885e-02 1.923742e+00 -6.315800e-01 3.237556e-02 -7.746345e-01 3.292207e+01 +-7.747823e-01 3.640077e-03 6.322177e-01 -1.751718e+02 2.325803e-02 9.994706e-01 2.274810e-02 1.922179e+00 -6.318002e-01 3.232895e-02 -7.744568e-01 3.229666e+01 +-7.744527e-01 2.191109e-03 6.326281e-01 -1.746388e+02 1.971523e-02 9.995919e-01 2.067295e-02 1.921438e+00 -6.323246e-01 2.848262e-02 -7.741798e-01 3.166497e+01 +-7.741310e-01 5.407391e-03 6.330024e-01 -1.741052e+02 2.079182e-02 9.996412e-01 1.688798e-02 1.927099e+00 -6.326840e-01 2.623477e-02 -7.739656e-01 3.102204e+01 +-7.734498e-01 7.172730e-03 6.338170e-01 -1.735590e+02 2.343539e-02 9.995759e-01 1.728639e-02 1.933011e+00 -6.334242e-01 2.822390e-02 -7.732898e-01 3.036327e+01 +-7.736503e-01 4.786133e-03 6.335947e-01 -1.730021e+02 2.523362e-02 9.994109e-01 2.326200e-02 1.938375e+00 -6.331102e-01 3.398453e-02 -7.733153e-01 2.969599e+01 +-7.736503e-01 5.890196e-03 6.335855e-01 -1.724382e+02 2.872992e-02 9.992544e-01 2.579146e-02 1.945840e+00 -6.329612e-01 3.815642e-02 -7.732427e-01 2.902358e+01 +-7.732664e-01 7.089408e-03 6.340416e-01 -1.718670e+02 3.009467e-02 9.992209e-01 2.553035e-02 1.951405e+00 -6.333667e-01 3.882303e-02 -7.728773e-01 2.834675e+01 +-7.729817e-01 1.194900e-02 6.343157e-01 -1.712881e+02 3.341364e-02 9.992017e-01 2.189551e-02 1.956277e+00 -6.335478e-01 3.811962e-02 -7.727640e-01 2.766060e+01 +-7.726454e-01 1.798946e-02 6.345829e-01 -1.707093e+02 3.748792e-02 9.991470e-01 1.731964e-02 1.958687e+00 -6.337301e-01 3.717112e-02 -7.726607e-01 2.696332e+01 +-7.727645e-01 2.002888e-02 6.343768e-01 -1.701234e+02 3.810695e-02 9.991629e-01 1.487376e-02 1.951058e+00 -6.335479e-01 3.566807e-02 -7.728809e-01 2.625927e+01 +-7.735452e-01 1.995500e-02 6.334269e-01 -1.695314e+02 3.716411e-02 9.992124e-01 1.390661e-02 1.943279e+00 -6.326506e-01 3.429813e-02 -7.736775e-01 2.554622e+01 +-7.741503e-01 1.744114e-02 6.327615e-01 -1.689342e+02 3.618695e-02 9.992049e-01 1.673119e-02 1.936670e+00 -6.319667e-01 3.585016e-02 -7.741659e-01 2.482358e+01 +-7.746740e-01 1.466747e-02 6.321906e-01 -1.683371e+02 3.523400e-02 9.991791e-01 1.999306e-02 1.929608e+00 -6.313784e-01 3.776271e-02 -7.745549e-01 2.409784e+01 +-7.753592e-01 1.393365e-02 6.313668e-01 -1.677434e+02 3.653659e-02 9.990717e-01 2.282073e-02 1.921892e+00 -6.304628e-01 4.076225e-02 -7.751485e-01 2.336870e+01 +-7.756371e-01 1.696891e-02 6.309510e-01 -1.671591e+02 4.159490e-02 9.988397e-01 2.427022e-02 1.914344e+00 -6.298071e-01 4.506921e-02 -7.754430e-01 2.263920e+01 +-7.759565e-01 2.219868e-02 6.303956e-01 -1.665815e+02 4.896270e-02 9.984850e-01 2.510784e-02 1.908782e+00 -6.288832e-01 5.034845e-02 -7.758679e-01 2.190866e+01 +-7.762817e-01 2.295506e-02 6.299681e-01 -1.660001e+02 5.250428e-02 9.982189e-01 2.832511e-02 1.908068e+00 -6.281959e-01 5.506428e-02 -7.761043e-01 2.117959e+01 +-7.766189e-01 2.188649e-02 6.295904e-01 -1.654129e+02 5.578051e-02 9.978599e-01 3.411825e-02 1.914190e+00 -6.274964e-01 6.161574e-02 -7.761777e-01 2.044842e+01 +-7.767751e-01 2.058793e-02 6.294414e-01 -1.648351e+02 5.913600e-02 9.974339e-01 4.035365e-02 1.923826e+00 -6.269955e-01 6.856835e-02 -7.759994e-01 1.971467e+01 +-7.770396e-01 2.297537e-02 6.290322e-01 -1.642567e+02 6.115890e-02 9.973611e-01 3.912063e-02 1.934077e+00 -6.264735e-01 6.886919e-02 -7.763943e-01 1.899252e+01 +-7.775165e-01 2.635662e-02 6.283099e-01 -1.636778e+02 5.916654e-02 9.977553e-01 3.136269e-02 1.940348e+00 -6.260730e-01 6.155992e-02 -7.773307e-01 1.828024e+01 +-7.782597e-01 3.217212e-02 6.271179e-01 -1.631045e+02 5.910436e-02 9.980060e-01 2.214984e-02 1.941640e+00 -6.251549e-01 5.430372e-02 -7.786093e-01 1.757387e+01 +-7.788291e-01 3.489893e-02 6.262645e-01 -1.625251e+02 5.950586e-02 9.980586e-01 1.838473e-02 1.942748e+00 -6.244071e-01 5.158496e-02 -7.793938e-01 1.685680e+01 +-7.796187e-01 3.314613e-02 6.253767e-01 -1.619505e+02 5.955193e-02 9.979970e-01 2.134402e-02 1.939281e+00 -6.234166e-01 5.388257e-02 -7.800310e-01 1.614389e+01 +-7.802128e-01 3.195104e-02 6.246976e-01 -1.613773e+02 6.014093e-02 9.978995e-01 2.407369e-02 1.936519e+00 -6.226164e-01 5.635249e-02 -7.804956e-01 1.542915e+01 +-7.808086e-01 3.116559e-02 6.239925e-01 -1.608026e+02 6.027596e-02 9.978538e-01 2.558568e-02 1.935710e+00 -6.218559e-01 5.758925e-02 -7.810114e-01 1.471206e+01 +-7.829338e-01 2.870224e-02 6.214426e-01 -1.602415e+02 5.728490e-02 9.980172e-01 2.607633e-02 1.936584e+00 -6.194620e-01 5.601531e-02 -7.830256e-01 1.401383e+01 +-7.871131e-01 2.596409e-02 6.162620e-01 -1.596822e+02 5.354950e-02 9.982177e-01 2.633893e-02 1.936046e+00 -6.144799e-01 5.373223e-02 -7.871006e-01 1.330347e+01 +-7.927358e-01 2.421727e-02 6.090841e-01 -1.591338e+02 5.137167e-02 9.983100e-01 2.716834e-02 1.935031e+00 -6.073969e-01 5.282697e-02 -7.926401e-01 1.259096e+01 +-7.996515e-01 2.524614e-02 5.999334e-01 -1.586027e+02 5.173827e-02 9.982969e-01 2.695204e-02 1.939067e+00 -5.982313e-01 5.259174e-02 -7.995958e-01 1.187586e+01 +-8.082955e-01 2.646177e-02 5.881820e-01 -1.580880e+02 5.309014e-02 9.981957e-01 2.804997e-02 1.945549e+00 -5.863785e-01 5.389932e-02 -8.082420e-01 1.115361e+01 +-8.185399e-01 2.855866e-02 5.737394e-01 -1.575933e+02 5.654963e-02 9.979182e-01 3.100521e-02 1.952156e+00 -5.716595e-01 5.782374e-02 -8.184509e-01 1.042311e+01 +-8.300177e-01 2.862510e-02 5.570020e-01 -1.571079e+02 5.828585e-02 9.976655e-01 3.558336e-02 1.958096e+00 -5.546831e-01 6.200014e-02 -8.297485e-01 9.685989e+00 +-8.432347e-01 3.084959e-02 5.366596e-01 -1.566525e+02 6.016140e-02 9.974956e-01 3.718900e-02 1.968002e+00 -5.341683e-01 6.364523e-02 -8.429789e-01 8.940913e+00 +-8.577965e-01 3.512916e-02 5.127875e-01 -1.562137e+02 6.374148e-02 9.972308e-01 3.831085e-02 1.981362e+00 -5.100217e-01 6.554874e-02 -8.576603e-01 8.187478e+00 +-8.733223e-01 3.845868e-02 4.856223e-01 -1.558113e+02 6.627396e-02 9.969902e-01 4.022794e-02 2.002674e+00 -4.826136e-01 6.731606e-02 -8.732426e-01 7.419730e+00 +-8.887523e-01 4.151905e-02 4.565036e-01 -1.554337e+02 6.840631e-02 9.967509e-01 4.252342e-02 2.020771e+00 -4.532549e-01 6.902050e-02 -8.887048e-01 6.640524e+00 +-9.030378e-01 4.503010e-02 4.271944e-01 -1.550736e+02 6.971431e-02 9.966693e-01 4.230981e-02 2.039549e+00 -4.238664e-01 6.798891e-02 -9.031693e-01 5.854252e+00 +-9.163015e-01 5.148583e-02 3.971660e-01 -1.547551e+02 7.142559e-02 9.968116e-01 3.556618e-02 2.055959e+00 -3.940686e-01 6.095715e-02 -9.170574e-01 5.066725e+00 +-9.287984e-01 5.768384e-02 3.660685e-01 -1.544511e+02 7.225129e-02 9.970421e-01 2.620724e-02 2.070725e+00 -3.634740e-01 5.079016e-02 -9.302188e-01 4.275819e+00 +-9.405924e-01 5.709213e-02 3.347036e-01 -1.541799e+02 6.800481e-02 9.974646e-01 2.096601e-02 2.076776e+00 -3.326580e-01 4.248191e-02 -9.420902e-01 3.475256e+00 +-9.511629e-01 5.323359e-02 3.040648e-01 -1.539186e+02 6.274660e-02 9.977958e-01 2.159395e-02 2.081455e+00 -3.022451e-01 3.961839e-02 -9.524066e-01 2.660279e+00 +-9.597480e-01 5.161216e-02 2.760797e-01 -1.536909e+02 6.018704e-02 9.979296e-01 2.267125e-02 2.081084e+00 -2.743380e-01 3.837510e-02 -9.608673e-01 1.836084e+00 +-9.665155e-01 5.324764e-02 2.510229e-01 -1.534863e+02 6.078856e-02 9.978998e-01 2.237747e-02 2.082675e+00 -2.493041e-01 3.688749e-02 -9.677225e-01 1.004297e+00 +-9.716011e-01 5.787948e-02 2.294370e-01 -1.532952e+02 6.420401e-02 9.977325e-01 2.019039e-02 2.088962e+00 -2.277481e-01 3.434778e-02 -9.731141e-01 1.642828e-01 +-9.758920e-01 5.763828e-02 2.105055e-01 -1.531167e+02 6.358256e-02 9.977433e-01 2.157423e-02 2.094656e+00 -2.087870e-01 3.443859e-02 -9.773546e-01 -6.849197e-01 +-9.800320e-01 5.326072e-02 1.915741e-01 -1.529463e+02 5.974494e-02 9.978145e-01 2.822730e-02 2.099191e+00 -1.896520e-01 3.910924e-02 -9.810722e-01 -1.551019e+00 +-9.834470e-01 5.305041e-02 1.732560e-01 -1.527936e+02 5.943047e-02 9.977244e-01 3.184311e-02 2.108057e+00 -1.711725e-01 4.161270e-02 -9.843619e-01 -2.422346e+00 +-9.863759e-01 5.356656e-02 1.555416e-01 -1.526592e+02 5.920798e-02 9.977370e-01 3.186262e-02 2.120983e+00 -1.534829e-01 4.063782e-02 -9.873153e-01 -3.301845e+00 +-9.888600e-01 5.327137e-02 1.389895e-01 -1.525347e+02 5.770336e-02 9.979396e-01 2.805187e-02 2.129986e+00 -1.372087e-01 3.575952e-02 -9.898965e-01 -4.184410e+00 +-9.905866e-01 5.639369e-02 1.247318e-01 -1.524224e+02 6.000550e-02 9.978751e-01 2.538861e-02 2.145234e+00 -1.230350e-01 3.263420e-02 -9.918656e-01 -5.081774e+00 +-9.914729e-01 6.231527e-02 1.144477e-01 -1.523238e+02 6.588321e-02 9.974439e-01 2.765813e-02 2.164537e+00 -1.124316e-01 3.496247e-02 -9.930442e-01 -6.003442e+00 +-9.918984e-01 6.697717e-02 1.079427e-01 -1.522301e+02 7.148133e-02 9.967021e-01 3.840841e-02 2.184519e+00 -1.050142e-01 4.581312e-02 -9.934149e-01 -6.932667e+00 +-9.920408e-01 6.959146e-02 1.049381e-01 -1.521344e+02 7.491590e-02 9.960495e-01 4.767641e-02 2.208027e+00 -1.012057e-01 5.515847e-02 -9.933353e-01 -7.875658e+00 +-9.922338e-01 6.914451e-02 1.033984e-01 -1.520349e+02 7.444703e-02 9.960531e-01 4.832976e-02 2.236569e+00 -9.964857e-02 5.565211e-02 -9.934652e-01 -8.818435e+00 +-9.925437e-01 6.646175e-02 1.021752e-01 -1.519309e+02 7.137732e-02 9.964235e-01 4.522663e-02 2.264380e+00 -9.880394e-02 5.218239e-02 -9.937378e-01 -9.767273e+00 +-9.929599e-01 6.169034e-02 1.011183e-01 -1.518222e+02 6.614837e-02 9.969530e-01 4.134057e-02 2.290503e+00 -9.825984e-02 4.773833e-02 -9.940151e-01 -1.072343e+01 +-9.934866e-01 5.355313e-02 1.005808e-01 -1.517054e+02 5.768773e-02 9.975860e-01 3.865668e-02 2.314806e+00 -9.826781e-02 4.420716e-02 -9.941776e-01 -1.169649e+01 +-9.937560e-01 4.837927e-02 1.005408e-01 -1.515906e+02 5.253161e-02 9.978547e-01 3.906966e-02 2.340253e+00 -9.843498e-02 4.410727e-02 -9.941655e-01 -1.268601e+01 +-9.937888e-01 4.595056e-02 1.013530e-01 -1.514796e+02 5.034163e-02 9.978819e-01 4.119955e-02 2.366234e+00 -9.924519e-02 4.604592e-02 -9.939971e-01 -1.368436e+01 +-9.938138e-01 4.345373e-02 1.022055e-01 -1.513681e+02 4.807903e-02 9.979074e-01 4.323433e-02 2.390739e+00 -1.001129e-01 4.788081e-02 -9.938233e-01 -1.468941e+01 +-9.936981e-01 4.315331e-02 1.034502e-01 -1.512539e+02 4.785382e-02 9.979113e-01 4.339341e-02 2.419304e+00 -1.013615e-01 4.807042e-02 -9.936876e-01 -1.570974e+01 +-9.936346e-01 4.124027e-02 1.048309e-01 -1.511385e+02 4.593021e-02 9.980306e-01 4.272379e-02 2.446252e+00 -1.028625e-01 4.726673e-02 -9.935719e-01 -1.672996e+01 +-9.936119e-01 3.955357e-02 1.056927e-01 -1.510183e+02 4.406723e-02 9.981985e-01 4.071612e-02 2.471748e+00 -1.038918e-01 4.511359e-02 -9.935649e-01 -1.776061e+01 +-9.935948e-01 3.781976e-02 1.064850e-01 -1.508986e+02 4.216448e-02 9.983551e-01 3.884906e-02 2.495354e+00 -1.048406e-01 4.309010e-02 -9.935551e-01 -1.879445e+01 +-9.937308e-01 3.467869e-02 1.062846e-01 -1.507787e+02 3.889983e-02 9.985240e-01 3.790244e-02 2.516209e+00 -1.048133e-01 4.179927e-02 -9.936131e-01 -1.983629e+01 +-9.939518e-01 3.214620e-02 1.050071e-01 -1.506584e+02 3.633639e-02 9.986078e-01 3.823702e-02 2.531082e+00 -1.036318e-01 4.182133e-02 -9.937361e-01 -2.088457e+01 +-9.941628e-01 3.062121e-02 1.034534e-01 -1.505418e+02 3.481680e-02 9.986326e-01 3.899547e-02 2.546922e+00 -1.021179e-01 4.236976e-02 -9.938696e-01 -2.193524e+01 +-9.943256e-01 3.018545e-02 1.020068e-01 -1.504287e+02 3.436810e-02 9.986284e-01 3.949758e-02 2.562912e+00 -1.006746e-01 4.277923e-02 -9.939993e-01 -2.298777e+01 +-9.945002e-01 2.933431e-02 1.005425e-01 -1.503173e+02 3.351853e-02 9.986300e-01 4.018247e-02 2.580523e+00 -9.922603e-02 4.333151e-02 -9.941210e-01 -2.403963e+01 +-9.946208e-01 2.935157e-02 9.933793e-02 -1.502100e+02 3.359382e-02 9.985816e-01 4.130505e-02 2.602248e+00 -9.798467e-02 4.441999e-02 -9.941961e-01 -2.509394e+01 +-9.947189e-01 2.873181e-02 9.853280e-02 -1.501008e+02 3.319882e-02 9.984798e-01 4.399907e-02 2.624842e+00 -9.711884e-02 4.703787e-02 -9.941606e-01 -2.614805e+01 +-9.948240e-01 2.779561e-02 9.773792e-02 -1.499955e+02 3.239060e-02 9.984279e-01 4.574505e-02 2.652068e+00 -9.631276e-02 4.867405e-02 -9.941603e-01 -2.719872e+01 +-9.949605e-01 2.701229e-02 9.656055e-02 -1.498915e+02 3.144483e-02 9.985063e-01 4.468085e-02 2.677343e+00 -9.520939e-02 4.749200e-02 -9.943237e-01 -2.824318e+01 +-9.950464e-01 2.683256e-02 9.572213e-02 -1.497898e+02 3.100693e-02 9.986198e-01 4.239147e-02 2.703716e+00 -9.445255e-02 4.514952e-02 -9.945050e-01 -2.928484e+01 +-9.951318e-01 2.629112e-02 9.498175e-02 -1.496882e+02 3.030102e-02 9.986985e-01 4.102457e-02 2.727489e+00 -9.377956e-02 4.370289e-02 -9.946333e-01 -3.032621e+01 +-9.952394e-01 2.586822e-02 9.396432e-02 -1.495881e+02 2.984556e-02 9.987062e-01 4.117215e-02 2.749371e+00 -9.277771e-02 4.378056e-02 -9.947239e-01 -3.136520e+01 +-9.954180e-01 2.496498e-02 9.230313e-02 -1.494892e+02 2.896225e-02 9.986883e-01 4.222277e-02 2.772055e+00 -9.112798e-02 4.470260e-02 -9.948354e-01 -3.240607e+01 +-9.956885e-01 2.377655e-02 8.966130e-02 -1.493925e+02 2.776184e-02 9.986691e-01 4.346617e-02 2.798290e+00 -8.850850e-02 4.576792e-02 -9.950234e-01 -3.344880e+01 +-9.959658e-01 2.276499e-02 8.679761e-02 -1.493004e+02 2.669349e-02 9.986584e-01 4.437149e-02 2.822913e+00 -8.567105e-02 4.650941e-02 -9.952373e-01 -3.447237e+01 +-9.962306e-01 2.225481e-02 8.384080e-02 -1.492116e+02 2.593192e-02 9.987373e-01 4.302746e-02 2.847794e+00 -8.277736e-02 4.503942e-02 -9.955498e-01 -3.550025e+01 +-9.965023e-01 2.131129e-02 8.080275e-02 -1.491247e+02 2.481715e-02 9.987824e-01 4.263466e-02 2.872146e+00 -7.979577e-02 4.449082e-02 -9.958179e-01 -3.652570e+01 +-9.967644e-01 2.042812e-02 7.773907e-02 -1.490389e+02 2.387675e-02 9.987596e-01 4.369370e-02 2.893300e+00 -7.675007e-02 4.540847e-02 -9.960158e-01 -3.754989e+01 +-9.969736e-01 2.015416e-02 7.508346e-02 -1.489571e+02 2.361781e-02 9.986836e-01 4.553181e-02 2.914898e+00 -7.406697e-02 4.716731e-02 -9.961372e-01 -3.857065e+01 +-9.971667e-01 2.070158e-02 7.231856e-02 -1.488814e+02 2.413645e-02 9.986056e-01 4.694985e-02 2.936848e+00 -7.124578e-02 4.856233e-02 -9.962759e-01 -3.958889e+01 +-9.973144e-01 2.146031e-02 7.002450e-02 -1.488101e+02 2.479847e-02 9.985797e-01 4.715525e-02 2.958886e+00 -6.891308e-02 4.876510e-02 -9.964301e-01 -4.060275e+01 +-9.974732e-01 2.130839e-02 6.777307e-02 -1.487352e+02 2.450553e-02 9.986084e-01 4.669784e-02 2.980846e+00 -6.668370e-02 4.824065e-02 -9.966073e-01 -4.161181e+01 +-9.975737e-01 2.245378e-02 6.589798e-02 -1.486636e+02 2.548657e-02 9.986369e-01 4.554837e-02 3.002899e+00 -6.478543e-02 4.711737e-02 -9.967862e-01 -4.262144e+01 +-9.976842e-01 2.173367e-02 6.445094e-02 -1.485927e+02 2.470382e-02 9.986519e-01 4.565068e-02 3.027276e+00 -6.337190e-02 4.713713e-02 -9.968762e-01 -4.362164e+01 +-9.977937e-01 2.037850e-02 6.318521e-02 -1.485176e+02 2.333198e-02 9.986521e-01 4.636320e-02 3.054980e+00 -6.215524e-02 4.773514e-02 -9.969243e-01 -4.462545e+01 +-9.978591e-01 1.962235e-02 6.238685e-02 -1.484441e+02 2.247240e-02 9.987199e-01 4.531479e-02 3.079101e+00 -6.141781e-02 4.661975e-02 -9.970228e-01 -4.562217e+01 +-9.979032e-01 1.940796e-02 6.174527e-02 -1.483689e+02 2.197546e-02 9.989101e-01 4.117821e-02 3.102061e+00 -6.087879e-02 4.244874e-02 -9.972421e-01 -4.661393e+01 +-9.979373e-01 1.858956e-02 6.144541e-02 -1.482960e+02 2.093551e-02 9.990675e-01 3.775867e-02 3.122209e+00 -6.068620e-02 3.896717e-02 -9.973960e-01 -4.760259e+01 +-9.979067e-01 1.897599e-02 6.182336e-02 -1.482258e+02 2.131120e-02 9.990755e-01 3.733418e-02 3.142814e+00 -6.105776e-02 3.857356e-02 -9.973886e-01 -4.859075e+01 +-9.978574e-01 1.981816e-02 6.235323e-02 -1.481556e+02 2.217510e-02 9.990566e-01 3.733755e-02 3.159721e+00 -6.155445e-02 3.864023e-02 -9.973555e-01 -4.957611e+01 +-9.977734e-01 2.142656e-02 6.315928e-02 -1.480851e+02 2.390782e-02 9.989611e-01 3.879520e-02 3.175297e+00 -6.226242e-02 4.021882e-02 -9.972491e-01 -5.055843e+01 +-9.976673e-01 2.348270e-02 6.409852e-02 -1.480135e+02 2.608162e-02 9.988586e-01 4.001444e-02 3.189403e+00 -6.308571e-02 4.159288e-02 -9.971410e-01 -5.153844e+01 +-9.975829e-01 2.424173e-02 6.512109e-02 -1.479424e+02 2.694003e-02 9.988007e-01 4.088141e-02 3.205788e+00 -6.405196e-02 4.253695e-02 -9.970396e-01 -5.251178e+01 +-9.975081e-01 2.483374e-02 6.603695e-02 -1.478700e+02 2.761147e-02 9.987574e-01 4.148838e-02 3.219705e+00 -6.492459e-02 4.320837e-02 -9.969543e-01 -5.347973e+01 +-9.974655e-01 2.382302e-02 6.704453e-02 -1.477977e+02 2.667715e-02 9.987613e-01 4.200210e-02 3.231897e+00 -6.596087e-02 4.368419e-02 -9.968655e-01 -5.444853e+01 +-9.974156e-01 2.368423e-02 6.783198e-02 -1.477243e+02 2.649774e-02 9.988125e-01 4.088251e-02 3.243527e+00 -6.678316e-02 4.257425e-02 -9.968588e-01 -5.541352e+01 +-9.972420e-01 2.580906e-02 6.958616e-02 -1.476532e+02 2.861209e-02 9.988063e-01 3.959001e-02 3.257265e+00 -6.848132e-02 4.147182e-02 -9.967901e-01 -5.637284e+01 +-9.969964e-01 2.716604e-02 7.252724e-02 -1.475797e+02 3.001996e-02 9.988055e-01 3.855372e-02 3.270311e+00 -7.139325e-02 4.061517e-02 -9.966210e-01 -5.733020e+01 +-9.968209e-01 2.594470e-02 7.533233e-02 -1.475001e+02 2.885909e-02 9.988662e-01 3.785954e-02 3.282400e+00 -7.426467e-02 3.991319e-02 -9.964395e-01 -5.828110e+01 +-9.966448e-01 2.581201e-02 7.767159e-02 -1.474207e+02 2.871666e-02 9.989204e-01 3.651475e-02 3.291390e+00 -7.664522e-02 3.862270e-02 -9.963101e-01 -5.922935e+01 +-9.964765e-01 2.612529e-02 7.970044e-02 -1.473415e+02 2.905738e-02 9.989345e-01 3.585337e-02 3.301002e+00 -7.867884e-02 3.804292e-02 -9.961739e-01 -6.017164e+01 +-9.964126e-01 2.531131e-02 8.075427e-02 -1.472599e+02 2.829908e-02 9.989485e-01 3.607053e-02 3.310925e+00 -7.975637e-02 3.822639e-02 -9.960812e-01 -6.110803e+01 +-9.964213e-01 2.352959e-02 8.118456e-02 -1.471781e+02 2.671470e-02 9.989063e-01 3.837213e-02 3.317449e+00 -8.019290e-02 4.040362e-02 -9.959602e-01 -6.203744e+01 +-9.964856e-01 2.261481e-02 8.065392e-02 -1.470991e+02 2.593660e-02 9.988477e-01 4.037855e-02 3.324624e+00 -7.964784e-02 4.232853e-02 -9.959240e-01 -6.295647e+01 +-9.965687e-01 2.231246e-02 7.970528e-02 -1.470218e+02 2.568404e-02 9.988071e-01 4.152874e-02 3.332509e+00 -7.868360e-02 4.343340e-02 -9.959530e-01 -6.386909e+01 +-9.967029e-01 2.094253e-02 7.838836e-02 -1.469462e+02 2.427802e-02 9.988292e-01 4.184234e-02 3.341452e+00 -7.742030e-02 4.360749e-02 -9.960444e-01 -6.476162e+01 +-9.968922e-01 1.971381e-02 7.627073e-02 -1.468736e+02 2.293946e-02 9.988689e-01 4.164960e-02 3.350949e+00 -7.536339e-02 4.326977e-02 -9.962169e-01 -6.564189e+01 +-9.971829e-01 1.880361e-02 7.261393e-02 -1.468046e+02 2.189975e-02 9.988742e-01 4.208011e-02 3.362788e+00 -7.174093e-02 4.355178e-02 -9.964720e-01 -6.650732e+01 +-9.975628e-01 1.910149e-02 6.710873e-02 -1.467409e+02 2.198701e-02 9.988534e-01 4.252534e-02 3.376135e+00 -6.621950e-02 4.389721e-02 -9.968390e-01 -6.735784e+01 +-9.979968e-01 1.981616e-02 6.008024e-02 -1.466842e+02 2.240054e-02 9.988388e-01 4.265149e-02 3.387862e+00 -5.916530e-02 4.391188e-02 -9.972819e-01 -6.818896e+01 +-9.983931e-01 2.184434e-02 5.228873e-02 -1.466370e+02 2.411091e-02 9.987791e-01 4.311620e-02 3.400870e+00 -5.128305e-02 4.430764e-02 -9.977008e-01 -6.899922e+01 +-9.987113e-01 2.430503e-02 4.455273e-02 -1.466018e+02 2.630105e-02 9.986507e-01 4.477632e-02 3.409958e+00 -4.340433e-02 4.589040e-02 -9.980031e-01 -6.978685e+01 +-9.989345e-01 2.785976e-02 3.679402e-02 -1.465750e+02 2.951079e-02 9.985456e-01 4.511833e-02 3.416011e+00 -3.548352e-02 4.615607e-02 -9.983038e-01 -7.055095e+01 +-9.991265e-01 2.974341e-02 2.935191e-02 -1.465515e+02 3.107341e-02 9.984604e-01 4.594724e-02 3.421360e+00 -2.794010e-02 4.681916e-02 -9.985126e-01 -7.128944e+01 +-9.992684e-01 3.130768e-02 2.196605e-02 -1.465298e+02 3.230621e-02 9.983873e-01 4.668000e-02 3.426278e+00 -2.046919e-02 4.735548e-02 -9.986684e-01 -7.200342e+01 +-9.993627e-01 3.234425e-02 1.510226e-02 -1.465152e+02 3.301715e-02 9.983648e-01 4.666396e-02 3.430945e+00 -1.356825e-02 4.713285e-02 -9.987965e-01 -7.268937e+01 +-9.993887e-01 3.383809e-02 8.791605e-03 -1.465063e+02 3.421086e-02 9.983357e-01 4.642556e-02 3.436511e+00 -7.206022e-03 4.669793e-02 -9.988831e-01 -7.334850e+01 +-9.993885e-01 3.484809e-02 2.858852e-03 -1.464990e+02 3.494300e-02 9.983221e-01 4.617195e-02 3.443175e+00 -1.245051e-03 4.624360e-02 -9.989294e-01 -7.398191e+01 +-9.993444e-01 3.611570e-02 -2.547776e-03 -1.464960e+02 3.596157e-02 9.983059e-01 4.573867e-02 3.451189e+00 4.195344e-03 4.561705e-02 -9.989502e-01 -7.458860e+01 +-9.992387e-01 3.831936e-02 -7.320006e-03 -1.464997e+02 3.795118e-02 9.982596e-01 4.513711e-02 3.454673e+00 9.036892e-03 4.482494e-02 -9.989540e-01 -7.516771e+01 +-9.991239e-01 4.015323e-02 -1.179697e-02 -1.465087e+02 3.956174e-02 9.981253e-01 4.669722e-02 3.458263e+00 1.364990e-02 4.618959e-02 -9.988394e-01 -7.572426e+01 +-9.990433e-01 4.078349e-02 -1.578653e-02 -1.465201e+02 3.997070e-02 9.980100e-01 4.876889e-02 3.460680e+00 1.774408e-02 4.809122e-02 -9.986853e-01 -7.624921e+01 +-9.989371e-01 4.176590e-02 -1.949891e-02 -1.465310e+02 4.075222e-02 9.979288e-01 4.977234e-02 3.464948e+00 2.153731e-02 4.892481e-02 -9.985702e-01 -7.674501e+01 +-9.988519e-01 4.226995e-02 -2.254314e-02 -1.465458e+02 4.108996e-02 9.978803e-01 5.046266e-02 3.469095e+00 2.462841e-02 4.947842e-02 -9.984715e-01 -7.720836e+01 +-9.987281e-01 4.380104e-02 -2.497364e-02 -1.465624e+02 4.247964e-02 9.977850e-01 5.119090e-02 3.474975e+00 2.716054e-02 5.006491e-02 -9.983766e-01 -7.764447e+01 +-9.985766e-01 4.610485e-02 -2.681540e-02 -1.465828e+02 4.467050e-02 9.976562e-01 5.183186e-02 3.481100e+00 2.914225e-02 5.056022e-02 -9.982958e-01 -7.804556e+01 +-9.984884e-01 4.731180e-02 -2.797438e-02 -1.465982e+02 4.579623e-02 9.975682e-01 5.253960e-02 3.487735e+00 3.039209e-02 5.117905e-02 -9.982269e-01 -7.841532e+01 +-9.984902e-01 4.709562e-02 -2.827245e-02 -1.466147e+02 4.553028e-02 9.975203e-01 5.366753e-02 3.489838e+00 3.072985e-02 5.229925e-02 -9.981585e-01 -7.875290e+01 +-9.985497e-01 4.608055e-02 -2.783965e-02 -1.466267e+02 4.452491e-02 9.975408e-01 5.412796e-02 3.492333e+00 3.026544e-02 5.280989e-02 -9.981458e-01 -7.906060e+01 +-9.986431e-01 4.464293e-02 -2.681464e-02 -1.466358e+02 4.316037e-02 9.976329e-01 5.353301e-02 3.493390e+00 2.914103e-02 5.230304e-02 -9.982060e-01 -7.932694e+01 +-9.987640e-01 4.286871e-02 -2.515526e-02 -1.466444e+02 4.149353e-02 9.977397e-01 5.285521e-02 3.496768e+00 2.736423e-02 5.174609e-02 -9.982853e-01 -7.957193e+01 +-9.988919e-01 4.120237e-02 -2.274518e-02 -1.466502e+02 3.997253e-02 9.978411e-01 5.210771e-02 3.501775e+00 2.484304e-02 5.114078e-02 -9.983824e-01 -7.979717e+01 +-9.989896e-01 4.008575e-02 -2.032146e-02 -1.466574e+02 3.901045e-02 9.979464e-01 5.080441e-02 3.507398e+00 2.231627e-02 4.996031e-02 -9.985019e-01 -7.999877e+01 +-9.990581e-01 3.969252e-02 -1.753401e-02 -1.466613e+02 3.881060e-02 9.980901e-01 4.806013e-02 3.513405e+00 1.940815e-02 4.733435e-02 -9.986905e-01 -8.019576e+01 +-9.990786e-01 4.011651e-02 -1.525473e-02 -1.466636e+02 3.937862e-02 9.981680e-01 4.593293e-02 3.523785e+00 1.706945e-02 4.528989e-02 -9.988281e-01 -8.038467e+01 +-9.990779e-01 4.091634e-02 -1.301100e-02 -1.466635e+02 4.028300e-02 9.981429e-01 4.569370e-02 3.531968e+00 1.485645e-02 4.512744e-02 -9.988708e-01 -8.056988e+01 +-9.991416e-01 4.001105e-02 -1.073244e-02 -1.466558e+02 3.946964e-02 9.981317e-01 4.663961e-02 3.544429e+00 1.257849e-02 4.617596e-02 -9.988541e-01 -8.074617e+01 +-9.992415e-01 3.803867e-02 -8.342636e-03 -1.466452e+02 3.760600e-02 9.981861e-01 4.701283e-02 3.553303e+00 1.011581e-02 4.666343e-02 -9.988595e-01 -8.091148e+01 +-9.993288e-01 3.619369e-02 -5.649618e-03 -1.466315e+02 3.589408e-02 9.982826e-01 4.629708e-02 3.562076e+00 7.315578e-03 4.606321e-02 -9.989117e-01 -8.106159e+01 +-9.993243e-01 3.670138e-02 -2.003931e-03 -1.466264e+02 3.657281e-02 9.983005e-01 4.537118e-02 3.568355e+00 3.665711e-03 4.526723e-02 -9.989682e-01 -8.120217e+01 +-9.992808e-01 3.782868e-02 2.642267e-03 -1.466236e+02 3.790890e-02 9.982876e-01 4.455103e-02 3.574643e+00 -9.524356e-04 4.461914e-02 -9.990036e-01 -8.133490e+01 +-9.992411e-01 3.811654e-02 8.028401e-03 -1.466172e+02 3.843366e-02 9.982934e-01 4.396687e-02 3.580246e+00 -6.338836e-03 4.424205e-02 -9.990007e-01 -8.146093e+01 +-9.992148e-01 3.683396e-02 1.459509e-02 -1.466064e+02 3.744131e-02 9.983389e-01 4.379046e-02 3.586432e+00 -1.295787e-02 4.430253e-02 -9.989341e-01 -8.158005e+01 +-9.991501e-01 3.466003e-02 2.231007e-02 -1.465910e+02 3.560497e-02 9.984209e-01 4.345117e-02 3.591611e+00 -2.076882e-02 4.420858e-02 -9.988064e-01 -8.169181e+01 +-9.990228e-01 3.243368e-02 3.002508e-02 -1.465743e+02 3.372590e-02 9.984804e-01 4.358132e-02 3.595945e+00 -2.856595e-02 4.455135e-02 -9.985986e-01 -8.179611e+01 +-9.988356e-01 3.093584e-02 3.701946e-02 -1.465544e+02 3.257337e-02 9.984790e-01 4.448054e-02 3.599009e+00 -3.558711e-02 4.563459e-02 -9.983241e-01 -8.188799e+01 +-9.986259e-01 2.940511e-02 4.337928e-02 -1.465371e+02 3.135241e-02 9.984987e-01 4.491438e-02 3.601598e+00 -4.199344e-02 4.621270e-02 -9.980486e-01 -8.196407e+01 +-9.984308e-01 2.855484e-02 4.817171e-02 -1.465218e+02 3.073044e-02 9.985122e-01 4.504414e-02 3.605125e+00 -4.681381e-02 4.645379e-02 -9.978229e-01 -8.202535e+01 +-9.982192e-01 2.862566e-02 5.233593e-02 -1.465098e+02 3.095006e-02 9.985451e-01 4.415531e-02 3.607875e+00 -5.099581e-02 4.569647e-02 -9.976529e-01 -8.207268e+01 +-9.980513e-01 2.843666e-02 5.554344e-02 -1.464988e+02 3.088191e-02 9.985684e-01 4.367327e-02 3.610893e+00 -5.422201e-02 4.530345e-02 -9.975007e-01 -8.210813e+01 +-9.979216e-01 2.862514e-02 5.773380e-02 -1.464897e+02 3.117123e-02 9.985586e-01 4.369264e-02 3.612361e+00 -5.639987e-02 4.540146e-02 -9.973754e-01 -8.213307e+01 +-9.978225e-01 2.814521e-02 5.964963e-02 -1.464813e+02 3.073927e-02 9.986009e-01 4.302612e-02 3.614901e+00 -5.835520e-02 4.476601e-02 -9.972917e-01 -8.214790e+01 +-9.977791e-01 2.784572e-02 6.051007e-02 -1.464749e+02 3.048963e-02 9.986003e-01 4.321861e-02 3.616561e+00 -5.922193e-02 4.496755e-02 -9.972315e-01 -8.215466e+01 +-9.977898e-01 2.779045e-02 6.035835e-02 -1.464700e+02 3.043276e-02 9.985981e-01 4.330782e-02 3.618715e+00 -5.907019e-02 4.504897e-02 -9.972368e-01 -8.215162e+01 +-9.977695e-01 2.855190e-02 6.033992e-02 -1.464675e+02 3.114077e-02 9.986149e-01 4.240889e-02 3.618427e+00 -5.904549e-02 4.419332e-02 -9.972766e-01 -8.214449e+01 +-9.977399e-01 2.901561e-02 6.060613e-02 -1.464666e+02 3.154295e-02 9.986542e-01 4.116889e-02 3.617487e+00 -5.933003e-02 4.298753e-02 -9.973124e-01 -8.214289e+01 +-9.977629e-01 2.878640e-02 6.033684e-02 -1.464691e+02 3.128253e-02 9.986758e-01 4.084152e-02 3.619237e+00 -5.908127e-02 4.263763e-02 -9.973422e-01 -8.214598e+01 +-9.977575e-01 2.852482e-02 6.054951e-02 -1.464743e+02 3.105459e-02 9.986658e-01 4.125842e-02 3.621418e+00 -5.929184e-02 4.304623e-02 -9.973121e-01 -8.214846e+01 +-9.977479e-01 2.855982e-02 6.069135e-02 -1.464784e+02 3.107095e-02 9.986824e-01 4.084235e-02 3.622343e+00 -5.944493e-02 4.263610e-02 -9.973207e-01 -8.214814e+01 +-9.977486e-01 2.875814e-02 6.058696e-02 -1.464809e+02 3.126401e-02 9.986770e-01 4.082579e-02 3.626275e+00 -5.933273e-02 4.262805e-02 -9.973277e-01 -8.214689e+01 +-9.977366e-01 2.871893e-02 6.080177e-02 -1.464837e+02 3.126041e-02 9.986589e-01 4.126909e-02 3.630956e+00 -5.953503e-02 4.307636e-02 -9.972964e-01 -8.214592e+01 +-9.977341e-01 2.874384e-02 6.083105e-02 -1.464853e+02 3.126975e-02 9.986702e-01 4.098664e-02 3.635666e+00 -5.957205e-02 4.279593e-02 -9.973062e-01 -8.214430e+01 +-9.977206e-01 2.881065e-02 6.102116e-02 -1.464860e+02 3.134330e-02 9.986690e-01 4.096184e-02 3.642197e+00 -5.975980e-02 4.278107e-02 -9.972956e-01 -8.214339e+01 +-9.977155e-01 2.882756e-02 6.109637e-02 -1.464874e+02 3.137537e-02 9.986598e-01 4.116049e-02 3.646408e+00 -5.982793e-02 4.298337e-02 -9.972828e-01 -8.214478e+01 +-9.977099e-01 2.887633e-02 6.116505e-02 -1.464896e+02 3.142593e-02 9.986590e-01 4.114007e-02 3.650913e+00 -5.989506e-02 4.296801e-02 -9.972795e-01 -8.214651e+01 +-9.976930e-01 2.900598e-02 6.137843e-02 -1.464903e+02 3.156128e-02 9.986572e-01 4.107995e-02 3.653096e+00 -6.010446e-02 4.292235e-02 -9.972688e-01 -8.214732e+01 +-9.976818e-01 2.907360e-02 6.152901e-02 -1.464929e+02 3.163197e-02 9.986574e-01 4.102231e-02 3.660850e+00 -6.025374e-02 4.287349e-02 -9.972619e-01 -8.215098e+01 +-9.976718e-01 2.917909e-02 6.164102e-02 -1.464935e+02 3.174930e-02 9.986489e-01 4.113654e-02 3.666124e+00 -6.035742e-02 4.299781e-02 -9.972503e-01 -8.215255e+01 +-9.976599e-01 2.922548e-02 6.181077e-02 -1.464950e+02 3.180132e-02 9.986485e-01 4.110783e-02 3.672670e+00 -6.052584e-02 4.297730e-02 -9.972410e-01 -8.215460e+01 +-9.976546e-01 2.925625e-02 6.188179e-02 -1.464952e+02 3.183504e-02 9.986475e-01 4.110539e-02 3.677041e+00 -6.059551e-02 4.297898e-02 -9.972367e-01 -8.215536e+01 +-9.976394e-01 2.928611e-02 6.211225e-02 -1.464961e+02 3.187561e-02 9.986457e-01 4.111747e-02 3.682929e+00 -6.082396e-02 4.300027e-02 -9.972219e-01 -8.215662e+01 +-9.976190e-01 2.935330e-02 6.240803e-02 -1.464944e+02 3.195654e-02 9.986425e-01 4.113218e-02 3.686575e+00 -6.111595e-02 4.302858e-02 -9.972028e-01 -8.215612e+01 +-9.975985e-01 2.952687e-02 6.265234e-02 -1.464943e+02 3.213924e-02 9.986377e-01 4.110631e-02 3.692587e+00 -6.135325e-02 4.302119e-02 -9.971885e-01 -8.215657e+01 +-9.975689e-01 2.962722e-02 6.307489e-02 -1.464929e+02 3.225247e-02 9.986377e-01 4.101772e-02 3.697692e+00 -6.177373e-02 4.295232e-02 -9.971655e-01 -8.215523e+01 +-9.975410e-01 2.975624e-02 6.345498e-02 -1.464903e+02 3.239728e-02 9.986335e-01 4.100579e-02 3.703976e+00 -6.214810e-02 4.296072e-02 -9.971419e-01 -8.215185e+01 +-9.975029e-01 2.983079e-02 6.401590e-02 -1.464878e+02 3.249190e-02 9.986332e-01 4.093878e-02 3.711265e+00 -6.270718e-02 4.291654e-02 -9.971088e-01 -8.214843e+01 +-9.974792e-01 2.997708e-02 6.431610e-02 -1.464858e+02 3.265172e-02 9.986277e-01 4.094552e-02 3.717330e+00 -6.300042e-02 4.294233e-02 -9.970892e-01 -8.214544e+01 +-9.974779e-01 3.005916e-02 6.429857e-02 -1.464866e+02 3.273213e-02 9.986257e-01 4.092945e-02 3.721405e+00 -6.297991e-02 4.293084e-02 -9.970910e-01 -8.214302e+01 +-9.974704e-01 3.018460e-02 6.435536e-02 -1.464873e+02 3.286428e-02 9.986187e-01 4.099464e-02 3.725380e+00 -6.302906e-02 4.300593e-02 -9.970847e-01 -8.214091e+01 +-9.974573e-01 3.013906e-02 6.457980e-02 -1.464876e+02 3.282947e-02 9.986192e-01 4.101176e-02 3.730224e+00 -6.325458e-02 4.302759e-02 -9.970695e-01 -8.213842e+01 +-9.974504e-01 3.020597e-02 6.465555e-02 -1.464871e+02 3.289600e-02 9.986194e-01 4.095320e-02 3.733757e+00 -6.332926e-02 4.297569e-02 -9.970670e-01 -8.213635e+01 +-9.974425e-01 3.035004e-02 6.470955e-02 -1.464865e+02 3.304353e-02 9.986139e-01 4.096830e-02 3.736302e+00 -6.337647e-02 4.300174e-02 -9.970628e-01 -8.213505e+01 +-9.974217e-01 3.052074e-02 6.494986e-02 -1.464860e+02 3.322390e-02 9.986085e-01 4.095399e-02 3.737147e+00 -6.360954e-02 4.300628e-02 -9.970478e-01 -8.213362e+01 +-9.974205e-01 3.061039e-02 6.492633e-02 -1.464879e+02 3.331644e-02 9.986030e-01 4.101355e-02 3.738183e+00 -6.358019e-02 4.307086e-02 -9.970469e-01 -8.213326e+01 +-9.974092e-01 3.059216e-02 6.510741e-02 -1.464881e+02 3.330064e-02 9.986069e-01 4.092943e-02 3.739743e+00 -6.376460e-02 4.299150e-02 -9.970385e-01 -8.213252e+01 +-9.974025e-01 3.064711e-02 6.518498e-02 -1.464887e+02 3.335971e-02 9.986045e-01 4.094046e-02 3.743962e+00 -6.383931e-02 4.300866e-02 -9.970330e-01 -8.213297e+01 +-9.973976e-01 3.063920e-02 6.526376e-02 -1.464887e+02 3.335782e-02 9.986029e-01 4.098134e-02 3.746808e+00 -6.391695e-02 4.305174e-02 -9.970262e-01 -8.213315e+01 +-9.973882e-01 3.068723e-02 6.538369e-02 -1.464890e+02 3.341504e-02 9.985984e-01 4.104293e-02 3.749734e+00 -6.403256e-02 4.312053e-02 -9.970158e-01 -8.213346e+01 +-9.973709e-01 3.072277e-02 6.563065e-02 -1.464885e+02 3.346197e-02 9.985965e-01 4.105286e-02 3.751969e+00 -6.427728e-02 4.314106e-02 -9.969991e-01 -8.213324e+01 +-9.973543e-01 3.074637e-02 6.587226e-02 -1.464862e+02 3.349414e-02 9.985966e-01 4.102319e-02 3.756727e+00 -6.451851e-02 4.312098e-02 -9.969844e-01 -8.213358e+01 +-9.973460e-01 3.073804e-02 6.600099e-02 -1.464847e+02 3.349660e-02 9.985932e-01 4.110375e-02 3.760390e+00 -6.464469e-02 4.320546e-02 -9.969726e-01 -8.213348e+01 +-9.973411e-01 3.086959e-02 6.601396e-02 -1.464850e+02 3.362887e-02 9.985888e-01 4.110368e-02 3.762686e+00 -6.465195e-02 4.321436e-02 -9.969717e-01 -8.213363e+01 +-9.973288e-01 3.094138e-02 6.616616e-02 -1.464854e+02 3.370720e-02 9.985862e-01 4.110135e-02 3.763251e+00 -6.480088e-02 4.322183e-02 -9.969618e-01 -8.213382e+01 +-9.973335e-01 3.085773e-02 6.613340e-02 -1.464849e+02 3.362421e-02 9.985876e-01 4.113479e-02 3.763444e+00 -6.477067e-02 4.324879e-02 -9.969625e-01 -8.213351e+01 +-9.973320e-01 3.088462e-02 6.614430e-02 -1.464851e+02 3.365224e-02 9.985863e-01 4.114456e-02 3.764354e+00 -6.478006e-02 4.326069e-02 -9.969614e-01 -8.213339e+01 +-9.973334e-01 3.091726e-02 6.610751e-02 -1.464851e+02 3.368744e-02 9.985825e-01 4.120803e-02 3.765829e+00 -6.473977e-02 4.332513e-02 -9.969612e-01 -8.213304e+01 +-9.973306e-01 3.080852e-02 6.620116e-02 -1.464801e+02 3.358262e-02 9.985860e-01 4.120761e-02 3.769760e+00 -6.483801e-02 4.332081e-02 -9.969550e-01 -8.213367e+01 +-9.973263e-01 3.073558e-02 6.629952e-02 -1.464764e+02 3.351823e-02 9.985854e-01 4.127465e-02 3.772636e+00 -6.493714e-02 4.338653e-02 -9.969457e-01 -8.213276e+01 +-9.973242e-01 3.076267e-02 6.631799e-02 -1.464733e+02 3.353971e-02 9.985888e-01 4.117576e-02 3.773749e+00 -6.495774e-02 4.328987e-02 -9.969486e-01 -8.213226e+01 +-9.973215e-01 3.079302e-02 6.634455e-02 -1.464721e+02 3.357302e-02 9.985866e-01 4.120287e-02 3.774660e+00 -6.498202e-02 4.331989e-02 -9.969457e-01 -8.213189e+01 +-9.973300e-01 3.078397e-02 6.622091e-02 -1.464755e+02 3.356021e-02 9.985860e-01 4.122790e-02 3.775066e+00 -6.485812e-02 4.334020e-02 -9.969529e-01 -8.213281e+01 +-9.973319e-01 3.079605e-02 6.618666e-02 -1.464771e+02 3.357183e-02 9.985849e-01 4.124339e-02 3.775151e+00 -6.482287e-02 4.335535e-02 -9.969545e-01 -8.213308e+01 +-9.973274e-01 3.085806e-02 6.622624e-02 -1.464775e+02 3.363543e-02 9.985829e-01 4.124029e-02 3.776020e+00 -6.485981e-02 4.335762e-02 -9.969520e-01 -8.213322e+01 +-9.973264e-01 3.085207e-02 6.624430e-02 -1.464765e+02 3.362596e-02 9.985859e-01 4.117496e-02 3.778253e+00 -6.488030e-02 4.329240e-02 -9.969535e-01 -8.213318e+01 +-9.973248e-01 3.086595e-02 6.626147e-02 -1.465060e+02 3.364602e-02 9.985818e-01 4.125812e-02 3.817593e+00 -6.489403e-02 4.337717e-02 -9.969489e-01 -8.214996e+01 +-9.972847e-01 3.075973e-02 6.691093e-02 -1.465250e+02 3.355450e-02 9.985933e-01 4.105333e-02 3.844867e+00 -6.555402e-02 4.318702e-02 -9.969140e-01 -8.216201e+01 +-9.971330e-01 3.056047e-02 6.922350e-02 -1.465414e+02 3.342208e-02 9.986178e-01 4.056442e-02 3.867997e+00 -6.788816e-02 4.276171e-02 -9.967761e-01 -8.217605e+01 +-9.970258e-01 3.004252e-02 7.097227e-02 -1.465569e+02 3.295045e-02 9.986497e-01 4.016324e-02 3.891863e+00 -6.966983e-02 4.238235e-02 -9.966694e-01 -8.219557e+01 +-9.968251e-01 2.943186e-02 7.398333e-02 -1.465659e+02 3.244881e-02 9.986761e-01 3.991279e-02 3.908776e+00 -7.271068e-02 4.218674e-02 -9.964605e-01 -8.221730e+01 +-9.964457e-01 2.979236e-02 7.879297e-02 -1.465794e+02 3.302073e-02 9.986542e-01 3.999197e-02 3.927281e+00 -7.749548e-02 4.245162e-02 -9.960885e-01 -8.224565e+01 +-9.959965e-01 2.969170e-02 8.431734e-02 -1.465858e+02 3.314835e-02 9.986538e-01 3.989566e-02 3.940279e+00 -8.301927e-02 4.253091e-02 -9.956400e-01 -8.227544e+01 +-9.954758e-01 2.889363e-02 9.051530e-02 -1.465906e+02 3.260509e-02 9.986757e-01 3.979661e-02 3.955031e+00 -8.924557e-02 4.256782e-02 -9.950996e-01 -8.231013e+01 +-9.947640e-01 2.847381e-02 9.815262e-02 -1.465878e+02 3.250601e-02 9.986816e-01 3.972924e-02 3.963825e+00 -9.689198e-02 4.271176e-02 -9.943780e-01 -8.234431e+01 +-9.938480e-01 2.825767e-02 1.070876e-01 -1.465882e+02 3.264160e-02 9.986899e-01 3.940820e-02 3.974088e+00 -1.058337e-01 4.266126e-02 -9.934683e-01 -8.238439e+01 +-9.927995e-01 2.784788e-02 1.165064e-01 -1.465818e+02 3.263136e-02 9.986924e-01 3.935336e-02 3.980790e+00 -1.152582e-01 4.287175e-02 -9.924100e-01 -8.242617e+01 +-9.915269e-01 2.729858e-02 1.270009e-01 -1.465780e+02 3.252756e-02 9.986986e-01 3.928230e-02 3.988369e+00 -1.257633e-01 4.308048e-02 -9.911245e-01 -8.247354e+01 +-9.899363e-01 2.704013e-02 1.389064e-01 -1.465675e+02 3.275921e-02 9.987000e-01 3.905172e-02 3.993899e+00 -1.376699e-01 4.320917e-02 -9.895352e-01 -8.252259e+01 +-9.880546e-01 2.659777e-02 1.517917e-01 -1.465518e+02 3.281704e-02 9.987151e-01 3.861488e-02 4.000773e+00 -1.505696e-01 4.313495e-02 -9.876579e-01 -8.257422e+01 +-9.858111e-01 2.614245e-02 1.658106e-01 -1.465331e+02 3.278452e-02 9.987606e-01 3.744801e-02 4.006616e+00 -1.646261e-01 4.235268e-02 -9.854463e-01 -8.263234e+01 +-9.830237e-01 2.546553e-02 1.817028e-01 -1.465075e+02 3.238001e-02 9.988560e-01 3.518885e-02 4.013233e+00 -1.805989e-01 4.047501e-02 -9.827237e-01 -8.269805e+01 +-9.797672e-01 2.410930e-02 1.986834e-01 -1.464759e+02 3.123853e-02 9.989728e-01 3.282577e-02 4.019203e+00 -1.976879e-01 3.836818e-02 -9.795139e-01 -8.277848e+01 +-9.760772e-01 2.263243e-02 2.162431e-01 -1.464452e+02 3.017289e-02 9.990440e-01 3.163229e-02 4.024429e+00 -2.153205e-01 3.740023e-02 -9.758270e-01 -8.288031e+01 +-9.719425e-01 2.148247e-02 2.342355e-01 -1.463964e+02 2.976392e-02 9.990485e-01 3.187726e-02 4.029323e+00 -2.333279e-01 3.795462e-02 -9.716571e-01 -8.298778e+01 +-9.672296e-01 2.209392e-02 2.529402e-01 -1.463513e+02 3.139353e-02 9.989691e-01 3.278875e-02 4.033562e+00 -2.519551e-01 3.965493e-02 -9.669261e-01 -8.311671e+01 +-9.615570e-01 2.296584e-02 2.736436e-01 -1.462958e+02 3.347443e-02 9.988680e-01 3.379476e-02 4.037831e+00 -2.725577e-01 4.165564e-02 -9.612373e-01 -8.325839e+01 +-9.550014e-01 2.133917e-02 2.958326e-01 -1.462309e+02 3.309254e-02 9.988470e-01 3.477929e-02 4.040989e+00 -2.947494e-01 4.300412e-02 -9.546065e-01 -8.341005e+01 +-9.475714e-01 1.874272e-02 3.189940e-01 -1.461563e+02 3.227520e-02 9.987869e-01 3.718898e-02 4.045713e+00 -3.179100e-01 4.553480e-02 -9.470268e-01 -8.357444e+01 +-9.392682e-01 1.781771e-02 3.427211e-01 -1.460701e+02 3.308526e-02 9.987009e-01 3.875268e-02 4.051946e+00 -3.415854e-01 4.773817e-02 -9.386376e-01 -8.374303e+01 +-9.298548e-01 1.858511e-02 3.674571e-01 -1.459804e+02 3.545557e-02 9.986016e-01 3.921380e-02 4.058185e+00 -3.662145e-01 4.949153e-02 -9.292134e-01 -8.392098e+01 +-9.190862e-01 1.838942e-02 3.936273e-01 -1.458795e+02 3.751215e-02 9.984571e-01 4.094188e-02 4.063554e+00 -3.922671e-01 5.239491e-02 -9.183579e-01 -8.410616e+01 +-9.064956e-01 1.762276e-02 4.218474e-01 -1.457599e+02 3.958470e-02 9.982750e-01 4.335925e-02 4.070054e+00 -4.203556e-01 5.600366e-02 -9.056295e-01 -8.429131e+01 +-8.916934e-01 1.678020e-02 4.523287e-01 -1.456332e+02 4.121602e-02 9.981712e-01 4.422122e-02 4.076339e+00 -4.507595e-01 5.807495e-02 -8.907543e-01 -8.448453e+01 +-8.740945e-01 1.648442e-02 4.854762e-01 -1.454913e+02 4.243470e-02 9.981945e-01 4.250933e-02 4.083620e+00 -4.838989e-01 5.775820e-02 -8.732158e-01 -8.468260e+01 +-8.533988e-01 1.523421e-02 5.210358e-01 -1.453153e+02 4.184955e-02 9.983485e-01 3.935486e-02 4.089716e+00 -5.195759e-01 5.539050e-02 -8.526270e-01 -8.488083e+01 +-8.294945e-01 1.247535e-02 5.583755e-01 -1.451255e+02 3.959840e-02 9.985482e-01 3.651558e-02 4.095105e+00 -5.571093e-01 5.240024e-02 -8.287843e-01 -8.509753e+01 +-8.017000e-01 1.146747e-02 5.976166e-01 -1.448957e+02 3.953063e-02 9.986442e-01 3.386749e-02 4.100068e+00 -5.964181e-01 5.077572e-02 -8.010664e-01 -8.531851e+01 +-7.696076e-01 1.411220e-02 6.383611e-01 -1.446601e+02 4.346928e-02 9.985942e-01 3.033068e-02 4.109917e+00 -6.370357e-01 5.109181e-02 -7.691392e-01 -8.556492e+01 +-7.346192e-01 1.807839e-02 6.782387e-01 -1.443964e+02 4.771269e-02 9.985466e-01 2.506276e-02 4.121088e+00 -6.767999e-01 5.077217e-02 -7.344141e-01 -8.581942e+01 +-6.979024e-01 1.988884e-02 7.159167e-01 -1.440775e+02 4.889709e-02 9.986050e-01 1.992452e-02 4.128858e+00 -7.145218e-01 4.891160e-02 -6.979014e-01 -8.606536e+01 +-6.596732e-01 1.922120e-02 7.513068e-01 -1.437422e+02 4.914005e-02 9.986368e-01 1.759782e-02 4.134474e+00 -7.499444e-01 4.852805e-02 -6.597185e-01 -8.632723e+01 +-6.190174e-01 1.862469e-02 7.851564e-01 -1.433707e+02 5.081624e-02 9.985737e-01 1.637636e-02 4.137690e+00 -7.837316e-01 5.003594e-02 -6.190810e-01 -8.659141e+01 +-5.762490e-01 1.755621e-02 8.170856e-01 -1.429474e+02 5.309812e-02 9.984612e-01 1.599408e-02 4.141571e+00 -8.155475e-01 5.260227e-02 -5.762944e-01 -8.684062e+01 +-5.320418e-01 1.330251e-02 8.466136e-01 -1.425033e+02 5.297816e-02 9.984404e-01 1.760523e-02 4.143550e+00 -8.450591e-01 5.421874e-02 -5.319168e-01 -8.708803e+01 +-4.856794e-01 8.888233e-03 8.740918e-01 -1.420100e+02 5.502756e-02 9.982759e-01 2.042444e-02 4.148160e+00 -8.724033e-01 5.801886e-02 -4.853312e-01 -8.731564e+01 +-4.371602e-01 5.514487e-03 8.993667e-01 -1.415092e+02 5.987799e-02 9.979410e-01 2.298633e-02 4.153370e+00 -8.973882e-01 6.390097e-02 -4.365903e-01 -8.754335e+01 +-3.872060e-01 1.907217e-03 9.219912e-01 -1.409762e+02 6.390701e-02 9.976483e-01 2.477512e-02 4.156256e+00 -9.197758e-01 6.851476e-02 -3.864173e-01 -8.775140e+01 +-3.368763e-01 -2.338949e-03 9.415460e-01 -1.403921e+02 6.595906e-02 9.974815e-01 2.607743e-02 4.158657e+00 -9.392358e-01 7.088834e-02 -3.358736e-01 -8.792431e+01 +-2.873528e-01 -6.653956e-03 9.578017e-01 -1.397985e+02 6.790639e-02 9.973181e-01 2.730126e-02 4.160018e+00 -9.554147e-01 7.288594e-02 -2.861303e-01 -8.808758e+01 +-2.384137e-01 -9.494257e-03 9.711173e-01 -1.391586e+02 7.017403e-02 9.971699e-01 2.697700e-02 4.162171e+00 -9.686251e-01 7.457888e-02 -2.370727e-01 -8.821988e+01 +-1.929309e-01 -9.220047e-03 9.811690e-01 -1.385086e+02 7.352143e-02 9.970090e-01 2.382568e-02 4.166045e+00 -9.784541e-01 7.673365e-02 -1.916760e-01 -8.833879e+01 +-1.530139e-01 -8.309384e-03 9.881891e-01 -1.378281e+02 7.410231e-02 9.970529e-01 1.985812e-02 4.168871e+00 -9.854419e-01 7.626565e-02 -1.519472e-01 -8.843333e+01 +-1.188077e-01 -7.939816e-03 9.928855e-01 -1.371128e+02 7.249783e-02 9.972296e-01 1.664957e-02 4.171257e+00 -9.902671e-01 7.396013e-02 -1.179030e-01 -8.850147e+01 +-9.120067e-02 -6.144616e-03 9.958136e-01 -1.363792e+02 7.119598e-02 9.973818e-01 1.267471e-02 4.171706e+00 -9.932843e-01 7.205385e-02 -9.052442e-02 -8.856031e+01 +-6.915588e-02 -4.069726e-03 9.975975e-01 -1.356148e+02 7.112578e-02 9.974267e-01 8.999637e-03 4.169899e+00 -9.950672e-01 7.157726e-02 -6.868847e-02 -8.860753e+01 +-5.182659e-02 -3.597714e-03 9.986496e-01 -1.348254e+02 7.167743e-02 9.974010e-01 7.313033e-03 4.168382e+00 -9.960805e-01 7.195963e-02 -5.143403e-02 -8.864646e+01 +-3.674328e-02 -2.512713e-03 9.993216e-01 -1.340129e+02 7.296331e-02 9.973211e-01 5.190411e-03 4.164762e+00 -9.966576e-01 7.310450e-02 -3.646152e-02 -8.867609e+01 +-2.263965e-02 -7.036847e-04 9.997434e-01 -1.331801e+02 7.436882e-02 9.972279e-01 2.386027e-03 4.156812e+00 -9.969738e-01 7.440374e-02 -2.252456e-02 -8.869656e+01 +-7.918415e-03 2.670978e-03 9.999651e-01 -1.323277e+02 7.596310e-02 9.971085e-01 -2.061824e-03 4.147637e+00 -9.970792e-01 7.594410e-02 -8.098417e-03 -8.870556e+01 +6.417218e-03 6.030028e-03 9.999612e-01 -1.314527e+02 7.590216e-02 9.970941e-01 -6.499842e-03 4.136633e+00 -9.970947e-01 7.594091e-02 5.940876e-03 -8.870109e+01 +1.902447e-02 6.694823e-03 9.997966e-01 -1.305520e+02 7.285462e-02 9.973099e-01 -8.064479e-03 4.122623e+00 -9.971611e-01 7.299320e-02 1.848554e-02 -8.868049e+01 +2.869788e-02 6.288884e-03 9.995683e-01 -1.296312e+02 6.832422e-02 9.976291e-01 -8.238295e-03 4.103983e+00 -9.972504e-01 6.853113e-02 2.820016e-02 -8.864953e+01 +3.409665e-02 5.938369e-03 9.994009e-01 -1.286888e+02 6.336480e-02 9.979576e-01 -8.091620e-03 4.084791e+00 -9.974078e-01 6.360272e-02 3.365073e-02 -8.861212e+01 +3.662491e-02 6.901671e-03 9.993052e-01 -1.277239e+02 6.069258e-02 9.981148e-01 -9.117860e-03 4.065878e+00 -9.974844e-01 6.098434e-02 3.613698e-02 -8.857569e+01 +3.742508e-02 5.812684e-03 9.992825e-01 -1.267352e+02 5.958723e-02 9.981907e-01 -8.037996e-03 4.048213e+00 -9.975213e-01 5.984529e-02 3.701101e-02 -8.854051e+01 +3.858550e-02 4.491696e-03 9.992452e-01 -1.257210e+02 6.041560e-02 9.981500e-01 -6.819704e-03 4.031067e+00 -9.974273e-01 6.063312e-02 3.824275e-02 -8.850489e+01 +4.140600e-02 3.869723e-03 9.991349e-01 -1.246835e+02 6.096142e-02 9.981196e-01 -6.392149e-03 4.013952e+00 -9.972810e-01 6.117334e-02 4.109224e-02 -8.846433e+01 +4.564102e-02 3.841588e-03 9.989505e-01 -1.236288e+02 6.173200e-02 9.980705e-01 -6.658679e-03 3.996890e+00 -9.970487e-01 6.197111e-02 4.531581e-02 -8.841970e+01 +5.030477e-02 4.220308e-03 9.987250e-01 -1.225531e+02 6.165129e-02 9.980709e-01 -7.322861e-03 3.978093e+00 -9.968293e-01 6.194105e-02 4.994753e-02 -8.836834e+01 +5.520429e-02 4.054178e-03 9.984668e-01 -1.214602e+02 6.135183e-02 9.980884e-01 -7.444730e-03 3.960347e+00 -9.965884e-01 6.166874e-02 5.485003e-02 -8.829428e+01 +6.068676e-02 3.943446e-03 9.981491e-01 -1.203502e+02 6.060529e-02 9.981326e-01 -7.628144e-03 3.940654e+00 -9.963153e-01 6.095602e-02 6.033444e-02 -8.821078e+01 +6.593027e-02 1.450684e-03 9.978232e-01 -1.192271e+02 6.141832e-02 9.980969e-01 -5.509245e-03 3.920264e+00 -9.959323e-01 6.164783e-02 6.571570e-02 -8.813057e+01 +7.113607e-02 -2.510371e-03 9.974634e-01 -1.180866e+02 6.250784e-02 9.980426e-01 -1.946043e-03 3.901849e+00 -9.955062e-01 6.248771e-02 7.115375e-02 -8.804055e+01 +7.562722e-02 -5.281743e-03 9.971222e-01 -1.169301e+02 6.278153e-02 9.980271e-01 5.248388e-04 3.883303e+00 -9.951578e-01 6.256115e-02 7.580961e-02 -8.794868e+01 +7.787888e-02 -5.001325e-03 9.969503e-01 -1.157614e+02 6.279889e-02 9.980262e-01 1.010521e-04 3.867981e+00 -9.949830e-01 6.259948e-02 7.803924e-02 -8.784858e+01 +7.801523e-02 -2.818479e-03 9.969482e-01 -1.145794e+02 6.163476e-02 9.980967e-01 -2.001446e-03 3.849717e+00 -9.950451e-01 6.160279e-02 7.804046e-02 -8.774507e+01 +7.708250e-02 -2.260084e-03 9.970221e-01 -1.133837e+02 6.112407e-02 9.981271e-01 -2.463082e-03 3.830963e+00 -9.951493e-01 6.113190e-02 7.707628e-02 -8.763924e+01 +7.638838e-02 -4.739106e-03 9.970669e-01 -1.121817e+02 6.202224e-02 9.980747e-01 -7.821063e-06 3.812180e+00 -9.951473e-01 6.184090e-02 7.653524e-02 -8.753924e+01 +7.596687e-02 -7.156760e-03 9.970846e-01 -1.109751e+02 6.344881e-02 9.979824e-01 2.329102e-03 3.791845e+00 -9.950896e-01 6.308688e-02 7.626768e-02 -8.743868e+01 +7.539885e-02 -8.677029e-03 9.971157e-01 -1.097745e+02 6.473763e-02 9.978951e-01 3.788548e-03 3.771694e+00 -9.950498e-01 6.426524e-02 7.580187e-02 -8.734289e+01 +7.504813e-02 -9.314805e-03 9.971364e-01 -1.085794e+02 6.477733e-02 9.978898e-01 4.446464e-03 3.750574e+00 -9.950737e-01 6.425812e-02 7.549315e-02 -8.724708e+01 +7.451742e-02 -9.545856e-03 9.971740e-01 -1.073857e+02 6.500839e-02 9.978737e-01 4.694566e-03 3.726738e+00 -9.950986e-01 6.447484e-02 7.497953e-02 -8.714676e+01 +7.402081e-02 -8.290886e-03 9.972222e-01 -1.061976e+02 6.423642e-02 9.979284e-01 3.528679e-03 3.701746e+00 -9.951857e-01 6.379677e-02 7.440005e-02 -8.704988e+01 +7.360360e-02 -5.929265e-03 9.972699e-01 -1.050099e+02 6.418565e-02 9.979372e-01 1.196003e-03 3.677172e+00 -9.952200e-01 6.392238e-02 7.383235e-02 -8.695296e+01 +7.324650e-02 -5.564938e-03 9.972983e-01 -1.038211e+02 6.408166e-02 9.979443e-01 8.620676e-04 3.653224e+00 -9.952530e-01 6.384537e-02 7.345254e-02 -8.685966e+01 +7.268849e-02 -7.825939e-03 9.973240e-01 -1.026322e+02 6.316002e-02 9.979982e-01 3.227903e-03 3.628733e+00 -9.953528e-01 6.275635e-02 7.303727e-02 -8.676401e+01 +7.210190e-02 -1.014486e-02 9.973457e-01 -1.014446e+02 6.338252e-02 9.979737e-01 5.569082e-03 3.607239e+00 -9.953814e-01 6.281273e-02 7.259881e-02 -8.667222e+01 +7.191387e-02 -8.669399e-03 9.973732e-01 -1.002617e+02 6.269719e-02 9.980239e-01 4.154382e-03 3.588698e+00 -9.954384e-01 6.223372e-02 7.231531e-02 -8.657200e+01 +7.158703e-02 -6.554927e-03 9.974128e-01 -9.908436e+01 6.363902e-02 9.979710e-01 1.991048e-03 3.569432e+00 -9.954021e-01 6.333183e-02 7.185893e-02 -8.648067e+01 +7.146302e-02 -5.188194e-03 9.974297e-01 -9.791011e+01 6.366112e-02 9.979714e-01 6.298700e-04 3.547496e+00 -9.954096e-01 6.345247e-02 7.164834e-02 -8.638626e+01 +7.108965e-02 -7.285963e-03 9.974433e-01 -9.673614e+01 6.225866e-02 9.980559e-01 2.853145e-03 3.526824e+00 -9.955251e-01 6.189664e-02 7.140506e-02 -8.629387e+01 +7.080506e-02 -1.010356e-02 9.974390e-01 -9.556279e+01 6.147224e-02 9.980922e-01 5.746456e-03 3.506517e+00 -9.955942e-01 6.090791e-02 7.129106e-02 -8.620143e+01 +7.029405e-02 -1.267811e-02 9.974457e-01 -9.439230e+01 5.974232e-02 9.981778e-01 8.477128e-03 3.490095e+00 -9.957357e-01 5.899381e-02 7.092338e-02 -8.611023e+01 +6.992921e-02 -1.154338e-02 9.974852e-01 -9.322888e+01 5.706111e-02 9.983421e-01 7.553000e-03 3.474064e+00 -9.959187e-01 5.638942e-02 7.047195e-02 -8.601752e+01 +6.984349e-02 -1.000221e-02 9.975078e-01 -9.207077e+01 5.620714e-02 9.984006e-01 6.075654e-03 3.457332e+00 -9.959732e-01 5.564271e-02 7.029398e-02 -8.593007e+01 +6.972732e-02 -9.477076e-03 9.975211e-01 -9.091482e+01 5.581404e-02 9.984255e-01 5.584234e-03 3.439932e+00 -9.960035e-01 5.528630e-02 7.014649e-02 -8.584440e+01 +6.947928e-02 -9.917131e-03 9.975341e-01 -8.976083e+01 5.471968e-02 9.984830e-01 6.115282e-03 3.420499e+00 -9.960815e-01 5.415985e-02 6.991654e-02 -8.575750e+01 +6.939717e-02 -1.158794e-02 9.975218e-01 -8.860756e+01 5.559550e-02 9.984234e-01 7.730654e-03 3.402298e+00 -9.960388e-01 5.492123e-02 6.993200e-02 -8.567406e+01 +6.942567e-02 -1.148211e-02 9.975210e-01 -8.745822e+01 5.647187e-02 9.983755e-01 7.561603e-03 3.383825e+00 -9.959875e-01 5.580690e-02 6.996131e-02 -8.559118e+01 +6.921387e-02 -9.534740e-03 9.975563e-01 -8.631428e+01 5.869692e-02 9.982608e-01 5.468880e-03 3.365660e+00 -9.958736e-01 5.817495e-02 6.965316e-02 -8.551130e+01 +6.986209e-02 -8.109160e-03 9.975237e-01 -8.517639e+01 6.090550e-02 9.981361e-01 3.848589e-03 3.347256e+00 -9.956957e-01 6.048579e-02 7.022577e-02 -8.543160e+01 +7.129749e-02 -8.581005e-03 9.974182e-01 -8.404212e+01 6.363860e-02 9.979648e-01 4.036690e-03 3.327124e+00 -9.954230e-01 6.318648e-02 7.169847e-02 -8.535257e+01 +7.394852e-02 -9.829695e-03 9.972136e-01 -8.290481e+01 6.457003e-02 9.979004e-01 5.048265e-03 3.306136e+00 -9.951695e-01 6.401678e-02 7.442796e-02 -8.526665e+01 +7.722417e-02 -1.098194e-02 9.969533e-01 -8.177442e+01 6.505979e-02 9.978636e-01 5.952423e-03 3.285675e+00 -9.948888e-01 6.440188e-02 7.777367e-02 -8.517822e+01 +8.015591e-02 -1.177150e-02 9.967128e-01 -8.064658e+01 6.383527e-02 9.979383e-01 6.652327e-03 3.266626e+00 -9.947362e-01 6.309220e-02 8.074208e-02 -8.508247e+01 +8.292557e-02 -1.068743e-02 9.964984e-01 -7.952584e+01 6.106381e-02 9.981180e-01 5.623255e-03 3.245394e+00 -9.946832e-01 6.038367e-02 8.342212e-02 -8.498283e+01 +8.593229e-02 -8.576979e-03 9.962640e-01 -7.840969e+01 5.984237e-02 9.982019e-01 3.431985e-03 3.221768e+00 -9.945022e-01 5.932387e-02 8.629104e-02 -8.488244e+01 +8.858151e-02 -8.280013e-03 9.960345e-01 -7.728896e+01 5.957074e-02 9.982196e-01 3.000301e-03 3.191912e+00 -9.942860e-01 5.906873e-02 8.891704e-02 -8.478461e+01 +9.058709e-02 -9.885770e-03 9.958395e-01 -7.617485e+01 5.947088e-02 9.982199e-01 4.499599e-03 3.162484e+00 -9.941113e-01 5.881583e-02 9.101375e-02 -8.468498e+01 +9.236203e-02 -1.076129e-02 9.956673e-01 -7.506363e+01 5.973295e-02 9.982006e-01 5.247604e-03 3.133853e+00 -9.939322e-01 5.898945e-02 9.283864e-02 -8.458436e+01 +9.389702e-02 -1.131765e-02 9.955176e-01 -7.395599e+01 5.971938e-02 9.981988e-01 5.715416e-03 3.108503e+00 -9.937892e-01 5.891502e-02 9.440378e-02 -8.448155e+01 +9.526626e-02 -1.261654e-02 9.953719e-01 -7.284964e+01 5.955635e-02 9.982007e-01 6.952305e-03 3.082721e+00 -9.936687e-01 5.861839e-02 9.584624e-02 -8.437548e+01 +9.620759e-02 -1.294739e-02 9.952771e-01 -7.174856e+01 5.786544e-02 9.982970e-01 7.393167e-03 3.059320e+00 -9.936779e-01 5.688085e-02 9.679295e-02 -8.426751e+01 +9.616050e-02 -1.280861e-02 9.952834e-01 -7.065049e+01 5.710102e-02 9.983415e-01 7.331081e-03 3.035851e+00 -9.937267e-01 5.612672e-02 9.673240e-02 -8.415970e+01 +9.552777e-02 -1.193672e-02 9.953552e-01 -6.955640e+01 5.533757e-02 9.984454e-01 6.662841e-03 3.014567e+00 -9.938875e-01 5.444404e-02 9.603981e-02 -8.405165e+01 +9.415765e-02 -1.154020e-02 9.954904e-01 -6.846310e+01 5.507488e-02 9.984619e-01 6.365433e-03 2.993483e+00 -9.940328e-01 5.422714e-02 9.464841e-02 -8.394657e+01 +9.252757e-02 -1.205839e-02 9.956371e-01 -6.736871e+01 5.583407e-02 9.984162e-01 6.903217e-03 2.973202e+00 -9.941435e-01 5.495172e-02 9.305429e-02 -8.384452e+01 +9.028291e-02 -1.191802e-02 9.958448e-01 -6.626978e+01 5.867016e-02 9.982554e-01 6.627850e-03 2.959134e+00 -9.941865e-01 5.782798e-02 9.082464e-02 -8.374424e+01 +8.812779e-02 -1.062564e-02 9.960525e-01 -6.517361e+01 6.183342e-02 9.980730e-01 5.176358e-03 2.945193e+00 -9.941882e-01 6.113314e-02 8.861500e-02 -8.364855e+01 +8.581500e-02 -9.502178e-03 9.962658e-01 -6.407225e+01 6.435267e-02 9.979193e-01 3.974825e-03 2.930056e+00 -9.942307e-01 6.377125e-02 8.624793e-02 -8.355385e+01 +8.354217e-02 -1.006938e-02 9.964534e-01 -6.298846e+01 6.658893e-02 9.977703e-01 4.499902e-03 2.914583e+00 -9.942770e-01 6.597681e-02 8.402640e-02 -8.346386e+01 +8.118209e-02 -1.227477e-02 9.966237e-01 -6.189385e+01 6.671981e-02 9.977482e-01 6.853818e-03 2.894478e+00 -9.944637e-01 6.593812e-02 8.181825e-02 -8.337192e+01 +7.880757e-02 -1.388381e-02 9.967931e-01 -6.080165e+01 6.547942e-02 9.978158e-01 8.721182e-03 2.873362e+00 -9.947371e-01 6.458212e-02 7.954454e-02 -8.327983e+01 +7.647628e-02 -1.329954e-02 9.969827e-01 -5.972532e+01 6.457787e-02 9.978776e-01 8.357861e-03 2.851534e+00 -9.949780e-01 6.374382e-02 7.717282e-02 -8.319229e+01 +7.435884e-02 -1.202971e-02 9.971590e-01 -5.865323e+01 6.303223e-02 9.979845e-01 7.339312e-03 2.826080e+00 -9.952375e-01 6.230740e-02 7.496723e-02 -8.310582e+01 +7.246616e-02 -9.444283e-03 9.973261e-01 -5.758891e+01 6.225283e-02 9.980482e-01 4.927802e-03 2.801637e+00 -9.954262e-01 6.172926e-02 7.291265e-02 -8.302288e+01 +7.079711e-02 -6.634786e-03 9.974687e-01 -5.651193e+01 6.131069e-02 9.981161e-01 2.287456e-03 2.779651e+00 -9.956048e-01 6.099353e-02 7.107052e-02 -8.292872e+01 +6.924973e-02 -4.467706e-03 9.975893e-01 -5.543924e+01 6.244701e-02 9.980482e-01 1.348710e-04 2.756445e+00 -9.956430e-01 6.228711e-02 6.939357e-02 -8.284557e+01 +6.825069e-02 -4.025432e-03 9.976601e-01 -5.436293e+01 6.248004e-02 9.980462e-01 -2.473199e-04 2.731590e+00 -9.957099e-01 6.235070e-02 6.836884e-02 -8.275948e+01 +6.766546e-02 -5.952646e-03 9.976903e-01 -5.328795e+01 6.286746e-02 9.980204e-01 1.690810e-03 2.707333e+00 -9.957254e-01 6.260783e-02 6.790574e-02 -8.267777e+01 +6.785149e-02 -8.540820e-03 9.976589e-01 -5.221491e+01 6.278121e-02 9.980181e-01 4.274100e-03 2.684340e+00 -9.957182e-01 6.234421e-02 6.825322e-02 -8.259449e+01 +6.820584e-02 -1.035896e-02 9.976175e-01 -5.115105e+01 6.042163e-02 9.981535e-01 6.233579e-03 2.663165e+00 -9.958400e-01 5.985249e-02 6.870580e-02 -8.250983e+01 +6.876555e-02 -1.096865e-02 9.975725e-01 -5.010238e+01 5.695581e-02 9.983518e-01 7.051085e-03 2.644628e+00 -9.960057e-01 5.633267e-02 6.927694e-02 -8.242382e+01 +6.927931e-02 -1.057782e-02 9.975412e-01 -4.905334e+01 5.236978e-02 9.986035e-01 6.951999e-03 2.626537e+00 -9.962218e-01 5.175937e-02 6.973653e-02 -8.233696e+01 +6.970160e-02 -9.908823e-03 9.975187e-01 -4.800472e+01 4.896768e-02 9.987792e-01 6.499728e-03 2.609242e+00 -9.963654e-01 4.839312e-02 7.010172e-02 -8.225022e+01 +7.010291e-02 -8.832513e-03 9.975006e-01 -4.696133e+01 4.518960e-02 9.989623e-01 5.669594e-03 2.591640e+00 -9.965157e-01 4.467919e-02 7.042930e-02 -8.216174e+01 +7.043006e-02 -7.850499e-03 9.974858e-01 -4.591385e+01 4.393367e-02 9.990231e-01 4.760547e-03 2.573083e+00 -9.965488e-01 4.348792e-02 7.070616e-02 -8.207717e+01 +7.131189e-02 -5.279172e-03 9.974401e-01 -4.485398e+01 4.251751e-02 9.990932e-01 2.248134e-03 2.560563e+00 -9.965475e-01 4.224834e-02 7.147168e-02 -8.199356e+01 +7.186217e-02 -5.136628e-03 9.974013e-01 -4.379500e+01 4.313464e-02 9.990672e-01 2.037381e-03 2.547118e+00 -9.964815e-01 4.287612e-02 7.201670e-02 -8.191307e+01 +7.262775e-02 -9.126237e-03 9.973173e-01 -4.272975e+01 4.710851e-02 9.988734e-01 5.709887e-03 2.539457e+00 -9.962460e-01 4.656742e-02 7.297585e-02 -8.183600e+01 +7.345113e-02 -1.578846e-02 9.971738e-01 -4.166873e+01 4.843893e-02 9.987511e-01 1.224545e-02 2.528194e+00 -9.961218e-01 4.740258e-02 7.412417e-02 -8.175523e+01 +7.465113e-02 -1.619128e-02 9.970782e-01 -4.060585e+01 5.138632e-02 9.986022e-01 1.236875e-02 2.515850e+00 -9.958849e-01 5.031283e-02 7.537879e-02 -8.166958e+01 +7.599803e-02 -1.231772e-02 9.970319e-01 -3.955165e+01 5.387401e-02 9.985138e-01 8.229522e-03 2.503950e+00 -9.956515e-01 5.308866e-02 7.654869e-02 -8.159330e+01 +7.686738e-02 -8.236940e-03 9.970073e-01 -3.849644e+01 5.456343e-02 9.985021e-01 4.042551e-03 2.488082e+00 -9.955472e-01 5.408938e-02 7.720168e-02 -8.151302e+01 +7.724169e-02 -6.820482e-03 9.969891e-01 -3.744699e+01 5.385555e-02 9.985452e-01 2.658669e-03 2.467897e+00 -9.955568e-01 5.348802e-02 7.749663e-02 -8.142920e+01 +7.788222e-02 -6.440548e-03 9.969417e-01 -3.639931e+01 5.357696e-02 9.985611e-01 2.265515e-03 2.449328e+00 -9.955219e-01 5.323666e-02 7.811522e-02 -8.134352e+01 +7.820365e-02 -6.603094e-03 9.969155e-01 -3.535893e+01 5.499439e-02 9.984840e-01 2.299412e-03 2.430647e+00 -9.954194e-01 5.464493e-02 7.844823e-02 -8.126015e+01 +7.829004e-02 -4.428672e-03 9.969208e-01 -3.432413e+01 5.690970e-02 9.983793e-01 -3.407563e-05 2.409772e+00 -9.953050e-01 5.673712e-02 7.841519e-02 -8.117846e+01 +7.823784e-02 -1.792713e-03 9.969331e-01 -3.329069e+01 5.990293e-02 9.982000e-01 -2.906105e-03 2.388158e+00 -9.951334e-01 5.994657e-02 7.820440e-02 -8.109833e+01 +7.778106e-02 -7.387627e-04 9.969702e-01 -3.226565e+01 6.162362e-02 9.980911e-01 -4.068127e-03 2.364654e+00 -9.950642e-01 6.175332e-02 7.767811e-02 -8.101888e+01 +7.690319e-02 -3.247403e-03 9.970333e-01 -3.123423e+01 6.349262e-02 9.979809e-01 -1.646826e-03 2.341459e+00 -9.950149e-01 6.343089e-02 7.695411e-02 -8.093893e+01 +7.620861e-02 -7.233761e-03 9.970656e-01 -3.020542e+01 6.533500e-02 9.978608e-01 2.245786e-03 2.319947e+00 -9.949491e-01 6.497212e-02 7.651821e-02 -8.086334e+01 +7.536519e-02 -8.977835e-03 9.971156e-01 -2.918198e+01 6.563436e-02 9.978356e-01 4.023462e-03 2.301513e+00 -9.949936e-01 6.514179e-02 7.579132e-02 -8.079003e+01 +7.429861e-02 -7.861044e-03 9.972050e-01 -2.816485e+01 6.464854e-02 9.979034e-01 3.049789e-03 2.286540e+00 -9.951384e-01 6.424124e-02 7.465104e-02 -8.071950e+01 +7.333847e-02 -6.048831e-03 9.972887e-01 -2.715493e+01 6.268523e-02 9.980323e-01 1.443602e-03 2.273856e+00 -9.953352e-01 6.240939e-02 7.357333e-02 -8.065087e+01 +7.224226e-02 -6.352426e-03 9.973669e-01 -2.614248e+01 6.176836e-02 9.980887e-01 1.882955e-03 2.258338e+00 -9.954726e-01 6.146968e-02 7.249656e-02 -8.057960e+01 +7.123191e-02 -8.384073e-03 9.974245e-01 -2.513087e+01 6.148519e-02 9.981000e-01 3.998733e-03 2.243360e+00 -9.955630e-01 6.104199e-02 7.161206e-02 -8.051287e+01 +7.018015e-02 -9.812911e-03 9.974861e-01 -2.412616e+01 6.113107e-02 9.981145e-01 5.518092e-03 2.224417e+00 -9.956595e-01 6.059012e-02 7.064770e-02 -8.044513e+01 +6.943725e-02 -9.670058e-03 9.975394e-01 -2.312314e+01 6.273327e-02 9.980162e-01 5.307908e-03 2.200874e+00 -9.956119e-01 6.221033e-02 6.990614e-02 -8.038011e+01 +6.877725e-02 -9.497710e-03 9.975868e-01 -2.212814e+01 6.288519e-02 9.980074e-01 5.166179e-03 2.179186e+00 -9.956481e-01 6.237811e-02 6.923747e-02 -8.031382e+01 +6.799996e-02 -9.555897e-03 9.976395e-01 -2.113624e+01 6.288120e-02 9.980071e-01 5.273380e-03 2.158118e+00 -9.957018e-01 6.237417e-02 6.846533e-02 -8.024730e+01 +6.723562e-02 -1.090258e-02 9.976775e-01 -2.015914e+01 6.095508e-02 9.981173e-01 6.799493e-03 2.136539e+00 -9.958734e-01 6.035633e-02 6.777361e-02 -8.018102e+01 +6.638152e-02 -1.154055e-02 9.977276e-01 -1.920344e+01 5.997933e-02 9.981710e-01 7.555095e-03 2.115684e+00 -9.959900e-01 5.934150e-02 6.695230e-02 -8.011803e+01 +6.552574e-02 -1.206248e-02 9.977780e-01 -1.826545e+01 5.944253e-02 9.981983e-01 8.163873e-03 2.094794e+00 -9.960788e-01 5.877549e-02 6.612471e-02 -8.005605e+01 +6.488817e-02 -1.302636e-02 9.978075e-01 -1.734296e+01 5.869185e-02 9.982336e-01 9.215145e-03 2.076612e+00 -9.961651e-01 5.796520e-02 6.553809e-02 -7.999311e+01 +6.483637e-02 -1.471962e-02 9.977873e-01 -1.643997e+01 5.695485e-02 9.983158e-01 1.102648e-02 2.056734e+00 -9.962693e-01 5.611390e-02 6.556553e-02 -7.992964e+01 +6.555934e-02 -1.514449e-02 9.977337e-01 -1.555805e+01 5.762275e-02 9.982737e-01 1.136640e-02 2.038136e+00 -9.961835e-01 5.674698e-02 6.631883e-02 -7.986631e+01 +6.785424e-02 -1.390344e-02 9.975983e-01 -1.470187e+01 5.766518e-02 9.982860e-01 9.990774e-03 2.021472e+00 -9.960274e-01 5.684876e-02 6.853968e-02 -7.979755e+01 +7.094782e-02 -1.297589e-02 9.973956e-01 -1.386242e+01 5.779451e-02 9.982890e-01 8.876411e-03 2.006898e+00 -9.958043e-01 5.701421e-02 7.157636e-02 -7.973095e+01 +7.495193e-02 -1.271939e-02 9.971060e-01 -1.304799e+01 5.568737e-02 9.984116e-01 8.550055e-03 1.982635e+00 -9.956311e-01 5.488536e-02 7.554119e-02 -7.965774e+01 +7.931066e-02 -1.206186e-02 9.967770e-01 -1.225209e+01 5.322106e-02 9.985519e-01 7.848689e-03 1.955701e+00 -9.954283e-01 5.242703e-02 7.983776e-02 -7.958095e+01 +8.444444e-02 -1.092940e-02 9.963682e-01 -1.147100e+01 5.291969e-02 9.985778e-01 6.468571e-03 1.931372e+00 -9.950220e-01 5.218125e-02 8.490272e-02 -7.950525e+01 +9.140453e-02 -9.729864e-03 9.957663e-01 -1.071407e+01 5.366315e-02 9.985474e-01 4.831129e-03 1.907256e+00 -9.943669e-01 5.299436e-02 9.179389e-02 -7.942836e+01 +1.004580e-01 -8.066639e-03 9.949086e-01 -9.978597e+00 5.569273e-02 9.984449e-01 2.471896e-03 1.882125e+00 -9.933814e-01 5.516084e-02 1.007511e-01 -7.934685e+01 +1.114259e-01 -6.431569e-03 9.937519e-01 -9.267307e+00 5.739720e-02 9.983514e-01 2.558696e-05 1.855018e+00 -9.921138e-01 5.703572e-02 1.116114e-01 -7.925871e+01 +1.233977e-01 -6.129264e-03 9.923384e-01 -8.577034e+00 5.683821e-02 9.983830e-01 -9.012571e-04 1.824620e+00 -9.907283e-01 5.651394e-02 1.235465e-01 -7.915904e+01 +1.359744e-01 -5.974198e-03 9.906943e-01 -7.915426e+00 5.655995e-02 9.983977e-01 -1.742294e-03 1.793514e+00 -9.890966e-01 5.627051e-02 1.360944e-01 -7.905159e+01 +1.498707e-01 -6.771491e-03 9.886824e-01 -7.272311e+00 5.670944e-02 9.983892e-01 -1.758402e-03 1.764992e+00 -9.870780e-01 5.633115e-02 1.500133e-01 -7.894049e+01 +1.650601e-01 -9.150426e-03 9.862410e-01 -6.660991e+00 5.767773e-02 9.983352e-01 -3.904722e-04 1.732230e+00 -9.845956e-01 5.694858e-02 1.653131e-01 -7.882344e+01 +1.819101e-01 -9.440439e-03 9.832698e-01 -6.068827e+00 5.626292e-02 9.984156e-01 -8.230825e-04 1.702411e+00 -9.817043e-01 5.547135e-02 1.821530e-01 -7.869639e+01 +2.011223e-01 -7.910740e-03 9.795342e-01 -5.472914e+00 5.280547e-02 9.986009e-01 -2.777530e-03 1.669583e+00 -9.781418e-01 5.228338e-02 2.012586e-01 -7.854955e+01 +2.200679e-01 -6.885918e-03 9.754602e-01 -4.940333e+00 4.947550e-02 9.987669e-01 -4.111434e-03 1.642761e+00 -9.742291e-01 4.916616e-02 2.201372e-01 -7.840730e+01 +2.418999e-01 -7.216253e-03 9.702744e-01 -4.382647e+00 4.973669e-02 9.987500e-01 -4.971863e-03 1.616116e+00 -9.690257e-01 4.946092e-02 2.419565e-01 -7.824856e+01 +2.634337e-01 -8.155552e-03 9.646430e-01 -3.867830e+00 4.873326e-02 9.988000e-01 -4.864203e-03 1.594797e+00 -9.634458e-01 4.829158e-02 2.635150e-01 -7.808627e+01 +2.864370e-01 -8.084396e-03 9.580650e-01 -3.358995e+00 4.628100e-02 9.989138e-01 -5.407752e-03 1.576012e+00 -9.569807e-01 4.588918e-02 2.865000e-01 -7.790275e+01 +3.121163e-01 -7.419870e-03 9.500149e-01 -2.864838e+00 4.461791e-02 9.989806e-01 -6.856388e-03 1.557809e+00 -9.489956e-01 4.452766e-02 3.121292e-01 -7.771129e+01 +3.406136e-01 -5.249710e-03 9.401887e-01 -2.385605e+00 4.288666e-02 9.990303e-01 -9.958810e-03 1.538800e+00 -9.392248e-01 4.371365e-02 3.405084e-01 -7.750396e+01 +3.729453e-01 -2.635601e-03 9.278496e-01 -1.921735e+00 4.295085e-02 9.989730e-01 -1.442628e-02 1.519288e+00 -9.268587e-01 4.523213e-02 3.726755e-01 -7.728713e+01 +4.083289e-01 -9.850568e-04 9.128343e-01 -1.469750e+00 4.282880e-02 9.989188e-01 -1.808022e-02 1.500554e+00 -9.118296e-01 4.647826e-02 4.079296e-01 -7.705448e+01 +4.471809e-01 -3.251509e-03 8.944376e-01 -1.027851e+00 4.543206e-02 9.987851e-01 -1.908326e-02 1.487556e+00 -8.932890e-01 4.916981e-02 4.467853e-01 -7.680012e+01 +4.907580e-01 -7.526495e-03 8.712634e-01 -6.036779e-01 4.766703e-02 9.986970e-01 -1.822215e-02 1.472946e+00 -8.699911e-01 5.047319e-02 4.904774e-01 -7.653314e+01 +5.351207e-01 -8.793863e-03 8.447298e-01 -2.051226e-01 4.430177e-02 9.988620e-01 -1.766593e-02 1.455786e+00 -8.436132e-01 4.687643e-02 5.349013e-01 -7.623884e+01 +5.777485e-01 -5.949616e-03 8.161932e-01 1.668060e-01 3.747924e-02 9.991120e-01 -1.924696e-02 1.434811e+00 -8.153539e-01 4.171020e-02 5.774584e-01 -7.591192e+01 +6.192451e-01 -2.973291e-03 7.851921e-01 5.205388e-01 3.338693e-02 9.991881e-01 -2.254711e-02 1.418536e+00 -7.844877e-01 4.017733e-02 6.188416e-01 -7.558157e+01 +6.599357e-01 -2.402047e-03 7.513182e-01 8.592366e-01 3.378981e-02 9.990779e-01 -2.648581e-02 1.400138e+00 -7.505619e-01 4.286582e-02 6.594084e-01 -7.524181e+01 +6.982913e-01 -4.803637e-03 7.157976e-01 1.182030e+00 3.693046e-02 9.988875e-01 -2.932383e-02 1.376718e+00 -7.148604e-01 4.691130e-02 6.976918e-01 -7.488301e+01 +7.339777e-01 -3.210500e-03 6.791660e-01 1.473046e+00 3.070727e-02 9.991231e-01 -2.846251e-02 1.350348e+00 -6.784791e-01 4.174618e-02 7.334327e-01 -7.450932e+01 +7.674229e-01 1.989511e-03 6.411382e-01 1.733786e+00 1.957383e-02 9.994563e-01 -2.653069e-02 1.324453e+00 -6.408424e-01 3.290978e-02 7.669667e-01 -7.411079e+01 +7.994750e-01 4.944322e-03 6.006790e-01 1.977241e+00 1.203970e-02 9.996333e-01 -2.425247e-02 1.308518e+00 -6.005787e-01 2.662123e-02 7.991224e-01 -7.370973e+01 +8.295579e-01 1.816498e-03 5.584177e-01 2.211269e+00 1.039012e-02 9.997714e-01 -1.868724e-02 1.295259e+00 -5.583241e-01 2.130417e-02 8.293494e-01 -7.329908e+01 +8.570797e-01 -3.695950e-03 5.151705e-01 2.431700e+00 1.175772e-02 9.998541e-01 -1.238792e-02 1.282661e+00 -5.150496e-01 1.667466e-02 8.569982e-01 -7.286880e+01 +8.820319e-01 -4.371145e-03 4.711695e-01 2.625592e+00 8.127279e-03 9.999493e-01 -5.937555e-03 1.268760e+00 -4.711197e-01 9.066436e-03 8.820227e-01 -7.243254e+01 +9.046786e-01 3.752186e-03 4.260781e-01 2.778690e+00 -4.389934e-03 9.999902e-01 5.147626e-04 1.258343e+00 -4.260720e-01 -2.336149e-03 9.046863e-01 -7.196837e+01 +9.246712e-01 7.290366e-03 3.806969e-01 2.915642e+00 -9.197771e-03 9.999526e-01 3.191228e-03 1.253995e+00 -3.806556e-01 -6.452398e-03 9.246944e-01 -7.151180e+01 +9.422889e-01 9.345086e-03 3.346704e-01 3.046312e+00 -1.022733e-02 9.999473e-01 8.740171e-04 1.258350e+00 -3.346446e-01 -4.246363e-03 9.423348e-01 -7.105343e+01 +9.564572e-01 9.031349e-03 2.917327e-01 3.160868e+00 -9.235264e-03 9.999571e-01 -6.781167e-04 1.257972e+00 -2.917263e-01 -2.045639e-03 9.564996e-01 -7.057958e+01 +9.673970e-01 9.982670e-03 2.530680e-01 3.257933e+00 -1.013567e-02 9.999484e-01 -6.991916e-04 1.264619e+00 -2.530619e-01 -1.888617e-03 9.674482e-01 -7.010260e+01 +9.761207e-01 1.578365e-02 2.166546e-01 3.332790e+00 -1.598949e-02 9.998718e-01 -8.029222e-04 1.267119e+00 -2.166395e-01 -2.680448e-03 9.762480e-01 -6.961007e+01 +9.828706e-01 2.162045e-02 1.830244e-01 3.394982e+00 -2.159262e-02 9.997645e-01 -2.145107e-03 1.272526e+00 -1.830277e-01 -1.843615e-03 9.831060e-01 -6.911648e+01 +9.876513e-01 2.391556e-02 1.548322e-01 3.452999e+00 -2.398512e-02 9.997113e-01 -1.419107e-03 1.270676e+00 -1.548215e-01 -2.312087e-03 9.879398e-01 -6.861143e+01 +9.908744e-01 2.484393e-02 1.324793e-01 3.505748e+00 -2.505138e-02 9.996861e-01 -1.009034e-04 1.267062e+00 -1.324402e-01 -3.218806e-03 9.911858e-01 -6.809683e+01 +9.933998e-01 2.553282e-02 1.118258e-01 3.551082e+00 -2.581777e-02 9.996660e-01 1.100544e-03 1.261750e+00 -1.117604e-01 -3.980372e-03 9.937272e-01 -6.757573e+01 +9.954075e-01 2.334377e-02 9.283851e-02 3.591560e+00 -2.354810e-02 9.997221e-01 1.105849e-03 1.259481e+00 -9.278690e-02 -3.286940e-03 9.956806e-01 -6.704625e+01 +9.967220e-01 2.265896e-02 7.766517e-02 3.623078e+00 -2.267527e-02 9.997426e-01 -6.720681e-04 1.252875e+00 -7.766042e-02 -1.091213e-03 9.969793e-01 -6.650560e+01 +9.976896e-01 2.382471e-02 6.362259e-02 3.647772e+00 -2.376342e-02 9.997161e-01 -1.720077e-03 1.243096e+00 -6.364552e-02 2.042134e-04 9.979726e-01 -6.595034e+01 +9.984935e-01 2.468544e-02 4.900319e-02 3.663801e+00 -2.463006e-02 9.996951e-01 -1.733896e-03 1.234892e+00 -4.903106e-02 5.243325e-04 9.987971e-01 -6.537705e+01 +9.990859e-01 2.432965e-02 3.514895e-02 3.673887e+00 -2.427315e-02 9.997033e-01 -2.033359e-03 1.227201e+00 -3.518799e-02 1.178325e-03 9.993800e-01 -6.479002e+01 +9.994919e-01 2.378266e-02 2.122342e-02 3.677308e+00 -2.373981e-02 9.997156e-01 -2.269089e-03 1.218704e+00 -2.127135e-02 1.764096e-03 9.997722e-01 -6.418504e+01 +9.997421e-01 2.163578e-02 6.896546e-03 3.675967e+00 -2.162676e-02 9.997651e-01 -1.379989e-03 1.209466e+00 -6.924784e-03 1.230483e-03 9.999753e-01 -6.356337e+01 +9.997506e-01 2.145176e-02 -6.214069e-03 3.664022e+00 -2.146337e-02 9.997680e-01 -1.806634e-03 1.199856e+00 6.173872e-03 1.939559e-03 9.999791e-01 -6.292543e+01 +9.996081e-01 2.260559e-02 -1.651398e-02 3.643049e+00 -2.265457e-02 9.997395e-01 -2.784274e-03 1.189755e+00 1.644674e-02 3.157300e-03 9.998598e-01 -6.227133e+01 +9.993866e-01 2.440838e-02 -2.511346e-02 3.617203e+00 -2.451461e-02 9.996917e-01 -3.930484e-03 1.179028e+00 2.500978e-02 4.543720e-03 9.996769e-01 -6.160236e+01 +9.992087e-01 2.419348e-02 -3.156876e-02 3.591227e+00 -2.437142e-02 9.996891e-01 -5.263790e-03 1.168096e+00 3.143160e-02 6.029001e-03 9.994877e-01 -6.091570e+01 +9.990597e-01 2.437734e-02 -3.585462e-02 3.556391e+00 -2.459956e-02 9.996807e-01 -5.769433e-03 1.152451e+00 3.570254e-02 6.646015e-03 9.993404e-01 -6.020960e+01 +9.989400e-01 2.381988e-02 -3.938908e-02 3.520319e+00 -2.407015e-02 9.996929e-01 -5.891692e-03 1.139602e+00 3.923665e-02 6.833547e-03 9.992066e-01 -5.949348e+01 +9.988218e-01 2.390937e-02 -4.223003e-02 3.485568e+00 -2.413475e-02 9.996970e-01 -4.835105e-03 1.128869e+00 4.210163e-02 5.848619e-03 9.990962e-01 -5.876038e+01 +9.987379e-01 2.258415e-02 -4.486119e-02 3.451301e+00 -2.274054e-02 9.997369e-01 -2.978665e-03 1.117531e+00 4.478212e-02 3.995074e-03 9.989888e-01 -5.801266e+01 +9.986215e-01 2.119095e-02 -4.802178e-02 3.415287e+00 -2.123937e-02 9.997743e-01 -4.982709e-04 1.106594e+00 4.800038e-02 1.517537e-03 9.988462e-01 -5.725520e+01 +9.984889e-01 2.023171e-02 -5.109408e-02 3.375737e+00 -2.016078e-02 9.997949e-01 1.903421e-03 1.094891e+00 5.112212e-02 -8.704474e-04 9.986920e-01 -5.649375e+01 +9.983321e-01 1.997534e-02 -5.416615e-02 3.332427e+00 -1.976898e-02 9.997951e-01 4.342922e-03 1.084248e+00 5.424180e-02 -3.264868e-03 9.985225e-01 -5.572964e+01 +9.981855e-01 1.817689e-02 -5.740457e-02 3.288581e+00 -1.784819e-02 9.998213e-01 6.233701e-03 1.074394e+00 5.750762e-02 -5.197821e-03 9.983315e-01 -5.496514e+01 +9.980158e-01 1.599088e-02 -6.090020e-02 3.243097e+00 -1.559051e-02 9.998536e-01 7.043857e-03 1.064884e+00 6.100393e-02 -6.080413e-03 9.981190e-01 -5.420352e+01 +9.978164e-01 1.394273e-02 -6.456056e-02 3.192353e+00 -1.350223e-02 9.998825e-01 7.254400e-03 1.056466e+00 6.465413e-02 -6.366846e-03 9.978874e-01 -5.343799e+01 +9.975729e-01 1.343433e-02 -6.832136e-02 3.132861e+00 -1.297428e-02 9.998901e-01 7.172939e-03 1.049640e+00 6.841022e-02 -6.269107e-03 9.976376e-01 -5.267327e+01 +9.973121e-01 1.303354e-02 -7.210154e-02 3.069795e+00 -1.257902e-02 9.998980e-01 6.754384e-03 1.042836e+00 7.218223e-02 -5.829260e-03 9.973744e-01 -5.190721e+01 +9.970817e-01 1.308421e-02 -7.521229e-02 3.005492e+00 -1.259852e-02 9.998966e-01 6.928445e-03 1.035311e+00 7.529518e-02 -5.960660e-03 9.971435e-01 -5.114242e+01 +9.969157e-01 1.377859e-02 -7.726091e-02 2.937896e+00 -1.325818e-02 9.998858e-01 7.244605e-03 1.027891e+00 7.735192e-02 -6.197919e-03 9.969846e-01 -5.037643e+01 +9.968091e-01 1.439439e-02 -7.851386e-02 2.871709e+00 -1.388456e-02 9.998788e-01 7.035597e-03 1.018952e+00 7.860562e-02 -5.923015e-03 9.968882e-01 -4.961228e+01 +9.967382e-01 1.563050e-02 -7.917470e-02 2.803220e+00 -1.511941e-02 9.998608e-01 7.050629e-03 1.010036e+00 7.927389e-02 -5.830555e-03 9.968358e-01 -4.884616e+01 +9.967223e-01 1.575436e-02 -7.934992e-02 2.741985e+00 -1.522977e-02 9.998580e-01 7.212076e-03 9.980856e-01 7.945228e-02 -5.979954e-03 9.968207e-01 -4.808220e+01 +9.967388e-01 1.496149e-02 -7.929668e-02 2.690256e+00 -1.438144e-02 9.998655e-01 7.881085e-03 9.818285e-01 7.940393e-02 -6.714980e-03 9.968199e-01 -4.731871e+01 +9.967441e-01 1.477281e-02 -7.926561e-02 2.632847e+00 -1.412881e-02 9.998625e-01 8.679456e-03 9.665624e-01 7.938293e-02 -7.531266e-03 9.968158e-01 -4.655590e+01 +9.967446e-01 1.486375e-02 -7.924244e-02 2.573747e+00 -1.412721e-02 9.998517e-01 9.847431e-03 9.515027e-01 7.937707e-02 -8.695896e-03 9.968067e-01 -4.579733e+01 +9.967485e-01 1.458359e-02 -7.924441e-02 2.514617e+00 -1.377400e-02 9.998473e-01 1.075345e-02 9.390078e-01 7.938914e-02 -9.626972e-03 9.967972e-01 -4.503968e+01 +9.967552e-01 1.441344e-02 -7.919210e-02 2.455917e+00 -1.360735e-02 9.998500e-01 1.070922e-02 9.260055e-01 7.933459e-02 -9.596876e-03 9.968019e-01 -4.428628e+01 +9.967665e-01 1.530523e-02 -7.888214e-02 2.395278e+00 -1.453103e-02 9.998405e-01 1.037933e-02 9.139468e-01 7.902843e-02 -9.199530e-03 9.968299e-01 -4.353558e+01 +9.968392e-01 1.512122e-02 -7.799320e-02 2.336487e+00 -1.439892e-02 9.998481e-01 9.815119e-03 9.025269e-01 7.812978e-02 -8.661074e-03 9.969056e-01 -4.278704e+01 +9.969412e-01 1.407143e-02 -7.687796e-02 2.281395e+00 -1.340251e-02 9.998677e-01 9.210211e-03 8.911355e-01 7.699740e-02 -8.151679e-03 9.969980e-01 -4.204360e+01 +9.970551e-01 1.429033e-02 -7.534487e-02 2.229024e+00 -1.363921e-02 9.998651e-01 9.149361e-03 8.765595e-01 7.546546e-02 -8.094770e-03 9.971156e-01 -4.130397e+01 +9.971552e-01 1.526685e-02 -7.381333e-02 2.176053e+00 -1.467451e-02 9.998557e-01 8.560540e-03 8.564019e-01 7.393337e-02 -7.453010e-03 9.972353e-01 -4.057423e+01 +9.972836e-01 1.264627e-02 -7.256348e-02 2.128161e+00 -1.196597e-02 9.998803e-01 9.802330e-03 8.397655e-01 7.267877e-02 -8.907408e-03 9.973156e-01 -3.985331e+01 +9.973835e-01 1.101299e-02 -7.144915e-02 2.080478e+00 -1.021799e-02 9.998818e-01 1.148283e-02 8.233957e-01 7.156717e-02 -1.072272e-02 9.973782e-01 -3.914184e+01 +9.974425e-01 1.391380e-02 -7.010578e-02 2.023801e+00 -1.298466e-02 9.998219e-01 1.369192e-02 8.103769e-01 7.028381e-02 -1.274660e-02 9.974456e-01 -3.844127e+01 +9.975385e-01 1.450138e-02 -6.860468e-02 1.975410e+00 -1.355973e-02 9.998076e-01 1.417161e-02 7.933529e-01 6.879699e-02 -1.320646e-02 9.975433e-01 -3.775378e+01 +9.975911e-01 1.163154e-02 -6.838716e-02 1.933230e+00 -1.088005e-02 9.998764e-01 1.135098e-02 7.801851e-01 6.851074e-02 -1.057958e-02 9.975943e-01 -3.707880e+01 +9.976231e-01 1.099699e-02 -6.802406e-02 1.895520e+00 -1.038618e-02 9.999025e-01 9.326438e-03 7.597285e-01 6.812000e-02 -8.597757e-03 9.976401e-01 -3.641471e+01 +9.976761e-01 1.322790e-02 -6.683900e-02 1.851613e+00 -1.290825e-02 9.999031e-01 5.212055e-03 7.422292e-01 6.690147e-02 -4.337166e-03 9.977502e-01 -3.575756e+01 +9.976574e-01 1.600367e-02 -6.650957e-02 1.807991e+00 -1.580973e-02 9.998691e-01 3.441391e-03 7.220826e-01 6.655594e-02 -2.381830e-03 9.977799e-01 -3.510587e+01 +9.976678e-01 1.683971e-02 -6.614729e-02 1.766675e+00 -1.667426e-02 9.998563e-01 3.052681e-03 7.015109e-01 6.618920e-02 -1.942603e-03 9.978052e-01 -3.445818e+01 +9.977138e-01 1.683277e-02 -6.545184e-02 1.727417e+00 -1.666814e-02 9.998564e-01 3.060507e-03 6.817103e-01 6.549396e-02 -1.962548e-03 9.978510e-01 -3.381378e+01 +9.977407e-01 1.690294e-02 -6.502116e-02 1.687773e+00 -1.682630e-02 9.998569e-01 1.726302e-03 6.642943e-01 6.504105e-02 -6.283357e-04 9.978824e-01 -3.317691e+01 +9.977190e-01 1.828449e-02 -6.498146e-02 1.645582e+00 -1.827776e-02 9.998327e-01 6.980798e-04 6.488052e-01 6.498336e-02 4.912290e-04 9.978862e-01 -3.254447e+01 +9.976968e-01 1.980410e-02 -6.487657e-02 1.602843e+00 -1.984943e-02 9.998030e-01 -5.410991e-05 6.337501e-01 6.486272e-02 1.341749e-03 9.978933e-01 -3.191722e+01 +9.976710e-01 2.092546e-02 -6.492156e-02 1.561553e+00 -2.098423e-02 9.997798e-01 -2.233501e-04 6.192475e-01 6.490259e-02 1.585160e-03 9.978904e-01 -3.129334e+01 +9.976455e-01 2.058019e-02 -6.542126e-02 1.524724e+00 -2.060028e-02 9.997877e-01 3.675986e-04 6.035847e-01 6.541495e-02 9.809639e-04 9.978577e-01 -3.067447e+01 +9.976202e-01 1.987199e-02 -6.602279e-02 1.488055e+00 -1.983425e-02 9.998025e-01 1.227261e-03 5.854894e-01 6.603414e-02 8.517288e-05 9.978174e-01 -3.005921e+01 +9.975742e-01 1.937253e-02 -6.686161e-02 1.450030e+00 -1.931779e-02 9.998123e-01 1.465204e-03 5.615753e-01 6.687745e-02 -1.700299e-04 9.977612e-01 -2.944928e+01 +9.974953e-01 1.867459e-02 -6.822334e-02 1.412389e+00 -1.864367e-02 9.998256e-01 1.090053e-03 5.423823e-01 6.823181e-02 1.846116e-04 9.976695e-01 -2.884028e+01 +9.973919e-01 1.794667e-02 -6.990941e-02 1.378315e+00 -1.800088e-02 9.998379e-01 -1.454070e-04 5.196914e-01 6.989547e-02 1.403459e-03 9.975533e-01 -2.823460e+01 +9.972900e-01 1.785525e-02 -7.137127e-02 1.340783e+00 -1.798823e-02 9.998374e-01 -1.220747e-03 4.975266e-01 7.133787e-02 2.501282e-03 9.974491e-01 -2.763061e+01 +9.971523e-01 1.793189e-02 -7.325142e-02 1.305986e+00 -1.806946e-02 9.998360e-01 -1.215669e-03 4.776523e-01 7.321762e-02 2.535822e-03 9.973128e-01 -2.702870e+01 +9.969979e-01 1.771867e-02 -7.537349e-02 1.267692e+00 -1.785103e-02 9.998400e-01 -1.082671e-03 4.591265e-01 7.534225e-02 2.424916e-03 9.971548e-01 -2.643074e+01 +9.968624e-01 1.672709e-02 -7.736671e-02 1.229249e+00 -1.686853e-02 9.998570e-01 -1.175021e-03 4.405908e-01 7.733599e-02 2.476397e-03 9.970020e-01 -2.583408e+01 +9.967421e-01 1.501159e-02 -7.924550e-02 1.191105e+00 -1.513364e-02 9.998850e-01 -9.397860e-04 4.256449e-01 7.922228e-02 2.135998e-03 9.968547e-01 -2.523953e+01 +9.965865e-01 1.404841e-02 -8.135132e-02 1.152074e+00 -1.407215e-02 9.999009e-01 2.815532e-04 4.124776e-01 8.134722e-02 8.641965e-04 9.966855e-01 -2.464690e+01 +9.964393e-01 1.412323e-02 -8.312192e-02 1.111448e+00 -1.407111e-02 9.999002e-01 1.212821e-03 4.026685e-01 8.313076e-02 -3.888419e-05 9.965387e-01 -2.406042e+01 +9.962995e-01 1.470148e-02 -8.468325e-02 1.067365e+00 -1.456733e-02 9.998914e-01 2.201906e-03 3.920096e-01 8.470644e-02 -9.601473e-04 9.964055e-01 -2.347692e+01 +9.961302e-01 1.538433e-02 -8.653266e-02 1.022814e+00 -1.513191e-02 9.998791e-01 3.572299e-03 3.816930e-01 8.657717e-02 -2.249069e-03 9.962426e-01 -2.289845e+01 +9.960195e-01 1.531319e-02 -8.781003e-02 9.777518e-01 -1.498985e-02 9.998782e-01 4.340670e-03 3.707154e-01 8.786581e-02 -3.007132e-03 9.961278e-01 -2.232660e+01 +9.959581e-01 1.522782e-02 -8.851843e-02 9.345741e-01 -1.488620e-02 9.998790e-01 4.518189e-03 3.612177e-01 8.857652e-02 -3.182222e-03 9.960643e-01 -2.176546e+01 +9.959334e-01 1.561801e-02 -8.872856e-02 8.867823e-01 -1.528068e-02 9.998732e-01 4.479824e-03 3.506486e-01 8.878728e-02 -3.105772e-03 9.960458e-01 -2.121267e+01 +9.959728e-01 1.671008e-02 -8.808480e-02 8.446471e-01 -1.634951e-02 9.998547e-01 4.813353e-03 3.428022e-01 8.815244e-02 -3.353823e-03 9.961014e-01 -2.067046e+01 +9.960823e-01 1.770816e-02 -8.663967e-02 8.029049e-01 -1.736974e-02 9.998383e-01 4.658542e-03 3.330321e-01 8.670816e-02 -3.135382e-03 9.962288e-01 -2.014023e+01 +9.961953e-01 1.808206e-02 -8.525296e-02 7.667103e-01 -1.775132e-02 9.998317e-01 4.636151e-03 3.282057e-01 8.532245e-02 -3.105158e-03 9.963486e-01 -1.961995e+01 +9.963115e-01 1.751696e-02 -8.400374e-02 7.322119e-01 -1.719502e-02 9.998418e-01 4.554529e-03 3.216458e-01 8.407023e-02 -3.093281e-03 9.964550e-01 -1.911160e+01 +9.964352e-01 1.741058e-02 -8.254563e-02 6.995025e-01 -1.711505e-02 9.998443e-01 4.286617e-03 3.170837e-01 8.260742e-02 -2.858562e-03 9.965781e-01 -1.861591e+01 +9.965668e-01 1.746195e-02 -8.093047e-02 6.673674e-01 -1.724230e-02 9.998455e-01 3.412188e-03 3.108239e-01 8.097756e-02 -2.005044e-03 9.967139e-01 -1.813200e+01 +9.966532e-01 1.771274e-02 -7.980453e-02 6.355362e-01 -1.752415e-02 9.998417e-01 3.063035e-03 3.060331e-01 7.984616e-02 -1.654276e-03 9.968058e-01 -1.765726e+01 +9.967425e-01 1.787607e-02 -7.864397e-02 6.017668e-01 -1.768715e-02 9.998387e-01 3.098305e-03 2.964822e-01 7.868668e-02 -1.697223e-03 9.968980e-01 -1.719632e+01 +9.968293e-01 1.832889e-02 -7.743014e-02 5.679449e-01 -1.814556e-02 9.998306e-01 3.070643e-03 2.867121e-01 7.747332e-02 -1.655892e-03 9.969931e-01 -1.674431e+01 +9.969213e-01 1.812867e-02 -7.628409e-02 5.366303e-01 -1.791425e-02 9.998334e-01 3.494268e-03 2.753636e-01 7.633473e-02 -2.116937e-03 9.970800e-01 -1.630704e+01 +9.970070e-01 1.748905e-02 -7.530741e-02 5.073413e-01 -1.725051e-02 9.998439e-01 3.816955e-03 2.644759e-01 7.536241e-02 -2.506439e-03 9.971531e-01 -1.588581e+01 +9.971014e-01 1.689157e-02 -7.418600e-02 4.756959e-01 -1.658801e-02 9.998513e-01 4.706318e-03 2.538892e-01 7.425447e-02 -3.462077e-03 9.972333e-01 -1.546492e+01 +9.971570e-01 1.791011e-02 -7.319266e-02 4.466098e-01 -1.751485e-02 9.998283e-01 6.038704e-03 2.450817e-01 7.328825e-02 -4.739576e-03 9.972995e-01 -1.509502e+01 +9.972023e-01 1.934296e-02 -7.220429e-02 4.170347e-01 -1.889728e-02 9.997979e-01 6.850595e-03 2.363433e-01 7.232222e-02 -5.466963e-03 9.973663e-01 -1.472666e+01 +9.972598e-01 1.992667e-02 -7.124461e-02 3.916312e-01 -1.949579e-02 9.997872e-01 6.738341e-03 2.279003e-01 7.136373e-02 -5.330905e-03 9.974361e-01 -1.438514e+01 +9.973337e-01 1.871660e-02 -7.053456e-02 3.699658e-01 -1.832559e-02 9.998129e-01 6.186654e-03 2.140665e-01 7.063716e-02 -4.877570e-03 9.974902e-01 -1.406463e+01 +9.973913e-01 1.782556e-02 -6.994861e-02 3.512582e-01 -1.749631e-02 9.998328e-01 5.316944e-03 2.032018e-01 7.003170e-02 -4.079229e-03 9.975364e-01 -1.376062e+01 +9.974500e-01 1.724712e-02 -6.925404e-02 3.319222e-01 -1.695846e-02 9.998449e-01 4.754018e-03 1.919107e-01 6.932530e-02 -3.567451e-03 9.975877e-01 -1.347437e+01 +9.974811e-01 1.775533e-02 -6.867415e-02 3.139292e-01 -1.750788e-02 9.998379e-01 4.203478e-03 1.822253e-01 6.873765e-02 -2.990549e-03 9.976303e-01 -1.319914e+01 +9.975144e-01 1.770598e-02 -6.820197e-02 2.995160e-01 -1.752495e-02 9.998411e-01 3.251797e-03 1.737489e-01 6.824871e-02 -2.048477e-03 9.976662e-01 -1.293035e+01 +9.975460e-01 1.712140e-02 -6.788847e-02 2.860852e-01 -1.706906e-02 9.998534e-01 1.350986e-03 1.660659e-01 6.790165e-02 -1.888768e-04 9.976920e-01 -1.266999e+01 +9.975812e-01 1.659670e-02 -6.749996e-02 2.755991e-01 -1.667070e-02 9.998609e-01 -5.331868e-04 1.593153e-01 6.748173e-02 1.657170e-03 9.977191e-01 -1.241089e+01 +9.976007e-01 1.654820e-02 -6.722407e-02 2.638684e-01 -1.664748e-02 9.998610e-01 -9.168608e-04 1.529288e-01 6.719956e-02 2.033773e-03 9.977375e-01 -1.215300e+01 +9.976071e-01 1.655323e-02 -6.712691e-02 2.561202e-01 -1.661570e-02 9.998619e-01 -3.722748e-04 1.472591e-01 6.711148e-02 1.486745e-03 9.977444e-01 -1.189670e+01 +9.976258e-01 1.593973e-02 -6.699854e-02 2.503151e-01 -1.596683e-02 9.998725e-01 1.310897e-04 1.411226e-01 6.699209e-02 9.389765e-04 9.977531e-01 -1.164350e+01 +9.976428e-01 1.540145e-02 -6.687113e-02 2.385751e-01 -1.541067e-02 9.998812e-01 3.780032e-04 1.355226e-01 6.686901e-02 6.534173e-04 9.977616e-01 -1.139105e+01 +9.976508e-01 1.500216e-02 -6.684188e-02 2.255563e-01 -1.498764e-02 9.998874e-01 7.187733e-04 1.287714e-01 6.684514e-02 2.847181e-04 9.977633e-01 -1.114019e+01 +9.976351e-01 1.530905e-02 -6.700671e-02 2.115382e-01 -1.529126e-02 9.998828e-01 7.785234e-04 1.228655e-01 6.701078e-02 2.479356e-04 9.977522e-01 -1.089334e+01 +9.976346e-01 1.496038e-02 -6.709304e-02 1.981649e-01 -1.493747e-02 9.998880e-01 8.432136e-04 1.204292e-01 6.709815e-02 1.609824e-04 9.977464e-01 -1.064489e+01 +9.975848e-01 1.401580e-02 -6.803061e-02 1.839541e-01 -1.400228e-02 9.999017e-01 6.756579e-04 1.141874e-01 6.803340e-02 2.785584e-04 9.976830e-01 -1.039814e+01 +9.974119e-01 1.263380e-02 -7.078135e-02 1.693736e-01 -1.260315e-02 9.999202e-01 8.796708e-04 1.079282e-01 7.078682e-02 1.467454e-05 9.974915e-01 -1.015224e+01 +9.970904e-01 1.237806e-02 -7.521662e-02 1.512010e-01 -1.234612e-02 9.999234e-01 8.897162e-04 1.010753e-01 7.522187e-02 4.150659e-05 9.971668e-01 -9.907869e+00 +9.966089e-01 1.282713e-02 -8.127789e-02 1.327650e-01 -1.278354e-02 9.999177e-01 1.056702e-03 9.648987e-02 8.128476e-02 -1.409834e-05 9.966909e-01 -9.665059e+00 +9.959609e-01 1.310358e-02 -8.882697e-02 1.131098e-01 -1.309102e-02 9.999140e-01 7.240159e-04 9.200309e-02 8.882883e-02 4.417455e-04 9.960468e-01 -9.424513e+00 +9.952353e-01 1.442169e-02 -9.642943e-02 9.101141e-02 -1.440591e-02 9.998958e-01 8.599256e-04 8.827309e-02 9.643180e-02 5.333263e-04 9.953395e-01 -9.183499e+00 +9.946328e-01 1.653338e-02 -1.021380e-01 6.543519e-02 -1.651989e-02 9.998630e-01 9.780041e-04 8.241309e-02 1.021402e-01 7.145553e-04 9.947698e-01 -8.947690e+00 +9.941165e-01 1.796623e-02 -1.068158e-01 4.083069e-02 -1.798936e-02 9.998379e-01 7.471040e-04 7.406821e-02 1.068119e-01 1.178840e-03 9.942786e-01 -8.713565e+00 +9.935955e-01 1.699499e-02 -1.117099e-01 1.685971e-02 -1.704867e-02 9.998545e-01 4.747517e-04 6.895291e-02 1.117017e-01 1.432795e-03 9.937408e-01 -8.476707e+00 +9.930426e-01 1.583353e-02 -1.166867e-01 -8.130694e-03 -1.589524e-02 9.998736e-01 4.017085e-04 6.531960e-02 1.166783e-01 1.455851e-03 9.931687e-01 -8.242587e+00 +9.925466e-01 1.681935e-02 -1.206992e-01 -3.708140e-02 -1.690151e-02 9.998571e-01 3.430821e-04 6.224212e-02 1.206877e-01 1.699474e-03 9.926891e-01 -8.008871e+00 +9.922172e-01 1.941589e-02 -1.229966e-01 -7.086213e-02 -1.953677e-02 9.998091e-01 2.233598e-04 5.793854e-02 1.229775e-01 2.181335e-03 9.924071e-01 -7.778389e+00 +9.921010e-01 2.167214e-02 -1.235555e-01 -1.055715e-01 -2.183738e-02 9.997615e-01 1.689665e-05 5.057470e-02 1.235264e-01 2.681365e-03 9.923377e-01 -7.549918e+00 +9.921912e-01 2.169936e-02 -1.228240e-01 -1.332081e-01 -2.189754e-02 9.997602e-01 -2.636542e-04 4.493818e-02 1.227888e-01 2.951138e-03 9.924284e-01 -7.321385e+00 +9.923631e-01 2.124122e-02 -1.215086e-01 -1.584155e-01 -2.141980e-02 9.997705e-01 -1.635135e-04 4.066731e-02 1.214773e-01 2.764957e-03 9.925904e-01 -7.094030e+00 +9.925869e-01 2.045444e-02 -1.198039e-01 -1.817262e-01 -2.059847e-02 9.997878e-01 3.617791e-05 3.554511e-02 1.197792e-01 2.431867e-03 9.927976e-01 -6.867589e+00 +9.928497e-01 2.067121e-02 -1.175678e-01 -2.082007e-01 -2.076376e-02 9.997843e-01 4.376831e-04 2.607704e-02 1.175515e-01 2.006598e-03 9.930648e-01 -6.638255e+00 +9.931455e-01 2.053147e-02 -1.150672e-01 -2.343012e-01 -2.060297e-02 9.997875e-01 5.680283e-04 1.689914e-02 1.150545e-01 1.806593e-03 9.933576e-01 -6.412690e+00 +9.934339e-01 2.020405e-02 -1.126092e-01 -2.605138e-01 -2.034881e-02 9.997929e-01 -1.360777e-04 6.487083e-03 1.125832e-01 2.426649e-03 9.936394e-01 -6.188841e+00 +9.937384e-01 2.000421e-02 -1.099265e-01 -2.848702e-01 -2.016031e-02 9.997967e-01 -3.086507e-04 -2.995286e-03 1.098980e-01 2.522872e-03 9.939397e-01 -5.965868e+00 +9.940798e-01 2.023102e-02 -1.067522e-01 -3.079171e-01 -2.036292e-02 9.997926e-01 -1.455225e-04 -1.257988e-02 1.067272e-01 2.318449e-03 9.942857e-01 -5.742297e+00 +9.944872e-01 1.994737e-02 -1.029437e-01 -3.276403e-01 -2.006810e-02 9.997986e-01 -1.371310e-04 -2.120828e-02 1.029202e-01 2.202260e-03 9.946872e-01 -5.519328e+00 +9.949101e-01 1.989845e-02 -9.878215e-02 -3.442492e-01 -2.001509e-02 9.997996e-01 -1.898427e-04 -2.776683e-02 9.875858e-02 2.166011e-03 9.951091e-01 -5.296044e+00 +9.952974e-01 1.973490e-02 -9.483452e-02 -3.603525e-01 -1.992242e-02 9.998010e-01 -1.030768e-03 -3.365884e-02 9.479531e-02 2.915254e-03 9.954925e-01 -5.068979e+00 +9.956810e-01 1.954063e-02 -9.076114e-02 -3.761889e-01 -1.989151e-02 9.997977e-01 -2.962953e-03 -4.017510e-02 9.068489e-02 4.755533e-03 9.958683e-01 -4.833849e+00 +9.960939e-01 1.887129e-02 -8.625994e-02 -3.883831e-01 -1.933517e-02 9.998027e-01 -4.545257e-03 -4.408253e-02 8.615715e-02 6.195354e-03 9.962623e-01 -4.586875e+00 +9.964847e-01 1.853058e-02 -8.169994e-02 -4.015895e-01 -1.899903e-02 9.998072e-01 -4.960046e-03 -4.852264e-02 8.159228e-02 6.494829e-03 9.966446e-01 -4.328040e+00 +9.968770e-01 1.805917e-02 -7.687764e-02 -4.129028e-01 -1.847308e-02 9.998184e-01 -4.676153e-03 -5.184738e-02 7.677924e-02 6.081716e-03 9.970296e-01 -4.057574e+00 +9.972523e-01 1.723081e-02 -7.204787e-02 -4.240876e-01 -1.760392e-02 9.998347e-01 -4.546817e-03 -5.696394e-02 7.195761e-02 5.802649e-03 9.973908e-01 -3.776090e+00 +9.976297e-01 1.536395e-02 -6.707434e-02 -4.312891e-01 -1.565304e-02 9.998703e-01 -3.786523e-03 -6.308662e-02 6.700747e-02 4.827465e-03 9.977408e-01 -3.483170e+00 +9.979956e-01 1.365422e-02 -6.179300e-02 -4.408512e-01 -1.383024e-02 9.999014e-01 -2.421699e-03 -6.990187e-02 6.175385e-02 3.271457e-03 9.980861e-01 -3.181643e+00 +9.982979e-01 1.262204e-02 -5.693831e-02 -4.540060e-01 -1.270744e-02 9.999186e-01 -1.137972e-03 -7.544684e-02 5.691931e-02 1.859575e-03 9.983771e-01 -2.872732e+00 +9.985646e-01 1.176395e-02 -5.225319e-02 -4.645429e-01 -1.181092e-02 9.999300e-01 -5.901061e-04 -8.065293e-02 5.224260e-02 1.206418e-03 9.986337e-01 -2.555900e+00 +9.987771e-01 1.186872e-02 -4.799330e-02 -4.725894e-01 -1.187787e-02 9.999294e-01 9.452154e-05 -8.314586e-02 4.799104e-02 4.756532e-04 9.988477e-01 -2.231273e+00 +9.989714e-01 1.192752e-02 -4.374709e-02 -4.804756e-01 -1.189382e-02 9.999287e-01 1.030616e-03 -8.733471e-02 4.375627e-02 -5.092352e-04 9.990421e-01 -1.896997e+00 +9.991563e-01 1.096113e-02 -3.957994e-02 -4.879376e-01 -1.088912e-02 9.999386e-01 2.034509e-03 -9.335250e-02 3.959982e-02 -1.601800e-03 9.992143e-01 -1.556277e+00 +9.993061e-01 9.288550e-03 -3.606926e-02 -4.929063e-01 -9.208702e-03 9.999547e-01 2.379288e-03 -9.990064e-02 3.608973e-02 -2.045485e-03 9.993465e-01 -1.206877e+00 +9.994152e-01 6.726202e-03 -3.352639e-02 -4.949177e-01 -6.709007e-03 9.999773e-01 6.253925e-04 -1.050763e-01 3.352984e-02 -4.000971e-04 9.994376e-01 -8.506597e-01 +9.994744e-01 5.347177e-03 -3.197401e-02 -4.997101e-01 -5.404565e-03 9.999839e-01 -1.708656e-03 -1.105933e-01 3.196436e-02 1.880564e-03 9.994872e-01 -4.851712e-01 +9.995098e-01 6.587979e-03 -3.060741e-02 -5.088378e-01 -6.712522e-03 9.999696e-01 -3.968010e-03 -1.157865e-01 3.058034e-02 4.171518e-03 9.995236e-01 -1.088576e-01 +9.995564e-01 9.955033e-03 -2.806965e-02 -5.209827e-01 -1.007002e-02 9.999414e-01 -3.958041e-03 -1.196282e-01 2.802860e-02 4.238947e-03 9.995981e-01 2.785206e-01 +9.996295e-01 1.499362e-02 -2.271884e-02 -5.115556e-01 -1.506209e-02 9.998825e-01 -2.845735e-03 -1.105472e-01 2.267350e-02 3.186874e-03 9.997379e-01 6.797468e-01 +9.998048e-01 1.304202e-02 -1.484246e-02 -4.737364e-01 -1.307313e-02 9.999125e-01 -2.000904e-03 -9.224491e-02 1.481506e-02 2.194551e-03 9.998879e-01 1.088900e+00 +9.999648e-01 4.598395e-03 -7.017647e-03 -4.339981e-01 -4.611829e-03 9.999875e-01 -1.899259e-03 -8.769902e-02 7.008827e-03 1.931557e-03 9.999736e-01 1.492117e+00 +9.999858e-01 -4.126513e-03 -3.373211e-03 -3.883676e-01 4.111717e-03 9.999819e-01 -4.382027e-03 -8.660640e-02 3.391233e-03 4.368095e-03 9.999847e-01 1.890361e+00 +9.999489e-01 -7.843070e-03 -6.376524e-03 -3.696291e-01 7.793619e-03 9.999396e-01 -7.743619e-03 -9.413486e-02 6.436873e-03 7.693527e-03 9.999497e-01 2.281506e+00 +9.998367e-01 -4.232277e-03 -1.756996e-02 -3.685772e-01 4.059956e-03 9.999434e-01 -9.831908e-03 -9.619576e-02 1.761058e-02 9.758968e-03 9.997973e-01 2.669212e+00 +9.994166e-01 8.296160e-04 -3.414274e-02 -3.877857e-01 -1.289766e-03 9.999086e-01 -1.345742e-02 -9.757224e-02 3.412846e-02 1.349360e-02 9.993264e-01 3.050660e+00 +9.986323e-01 8.173466e-03 -5.164103e-02 -4.147316e-01 -9.051352e-03 9.998181e-01 -1.678880e-02 -9.948540e-02 5.149442e-02 1.723325e-02 9.985246e-01 3.428579e+00 +9.974700e-01 8.768056e-03 -7.054550e-02 -4.428038e-01 -1.010078e-02 9.997768e-01 -1.855711e-02 -1.044886e-01 7.036705e-02 1.922273e-02 9.973359e-01 3.803063e+00 +9.956022e-01 4.717865e-03 -9.356266e-02 -4.733750e-01 -6.463275e-03 9.998105e-01 -1.836072e-02 -1.130000e-01 9.345831e-02 1.888469e-02 9.954441e-01 4.175334e+00 +9.930598e-01 5.128398e-03 -1.174989e-01 -5.212578e-01 -6.578704e-03 9.999068e-01 -1.195862e-02 -1.244534e-01 1.174266e-01 1.264861e-02 9.930010e-01 4.545801e+00 +9.897147e-01 1.108922e-02 -1.426248e-01 -5.907949e-01 -1.188873e-02 9.999180e-01 -4.754651e-03 -1.371187e-01 1.425604e-01 6.401375e-03 9.897654e-01 4.909245e+00 +9.855441e-01 1.649497e-02 -1.686140e-01 -6.694622e-01 -1.681574e-02 9.998585e-01 -4.745488e-04 -1.454802e-01 1.685824e-01 3.303060e-03 9.856820e-01 5.262875e+00 +9.807578e-01 1.922702e-02 -1.942795e-01 -7.540070e-01 -1.924806e-02 9.998131e-01 1.779621e-03 -1.526452e-01 1.942774e-01 1.994128e-03 9.809446e-01 5.608678e+00 +9.757233e-01 2.050991e-02 -2.180445e-01 -8.389403e-01 -1.978829e-02 9.997891e-01 5.492856e-03 -1.577788e-01 2.181111e-01 -1.044778e-03 9.759234e-01 5.951591e+00 +9.708687e-01 2.003780e-02 -2.387728e-01 -9.296743e-01 -1.850405e-02 9.997912e-01 8.663525e-03 -1.628340e-01 2.388966e-01 -3.992878e-03 9.710368e-01 6.291946e+00 +9.672756e-01 2.504079e-02 -2.524895e-01 -1.032008e+00 -2.260711e-02 9.996658e-01 1.253566e-02 -1.682553e-01 2.527191e-01 -6.417376e-03 9.675184e-01 6.626423e+00 +9.649335e-01 3.248024e-02 -2.604772e-01 -1.135960e+00 -2.920080e-02 9.994382e-01 1.645121e-02 -1.742996e-01 2.608653e-01 -8.268176e-03 9.653398e-01 6.958512e+00 +9.642284e-01 3.710697e-02 -2.624626e-01 -1.229340e+00 -3.316120e-02 9.992607e-01 1.944876e-02 -1.749966e-01 2.629903e-01 -1.004947e-02 9.647462e-01 7.289411e+00 +9.653597e-01 3.858621e-02 -2.580538e-01 -1.312862e+00 -3.474754e-02 9.992074e-01 1.942138e-02 -1.762270e-01 2.585986e-01 -9.781883e-03 9.659353e-01 7.617634e+00 +9.674419e-01 3.629996e-02 -2.504766e-01 -1.383808e+00 -3.256454e-02 9.992882e-01 1.904300e-02 -1.783610e-01 2.509895e-01 -1.026634e-02 9.679354e-01 7.944145e+00 +9.696547e-01 3.102355e-02 -2.425020e-01 -1.438607e+00 -2.646382e-02 9.994068e-01 2.203852e-02 -1.800396e-01 2.430419e-01 -1.495222e-02 9.699006e-01 8.249384e+00 +9.720284e-01 2.817069e-02 -2.331678e-01 -1.485319e+00 -2.324249e-02 9.994451e-01 2.385709e-02 -1.784785e-01 2.337105e-01 -1.777037e-02 9.721438e-01 8.521081e+00 +9.743542e-01 2.970305e-02 -2.230505e-01 -1.531094e+00 -2.465981e-02 9.993741e-01 2.536228e-02 -1.800686e-01 2.236643e-01 -1.921146e-02 9.744769e-01 8.751345e+00 +9.764878e-01 3.052353e-02 -2.134010e-01 -1.565470e+00 -2.567933e-02 9.993466e-01 2.543585e-02 -1.843807e-01 2.140379e-01 -1.935780e-02 9.766335e-01 8.946937e+00 +9.785319e-01 2.992319e-02 -2.039114e-01 -1.589383e+00 -2.558437e-02 9.993873e-01 2.388166e-02 -1.876084e-01 2.045011e-01 -1.815202e-02 9.786980e-01 9.106580e+00 +9.801784e-01 2.710182e-02 -1.962547e-01 -1.603789e+00 -2.312220e-02 9.994785e-01 2.254117e-02 -1.880929e-01 1.967632e-01 -1.755652e-02 9.802938e-01 9.232185e+00 +9.812500e-01 2.514262e-02 -1.910926e-01 -1.615795e+00 -2.145703e-02 9.995421e-01 2.133210e-02 -1.881750e-01 1.915414e-01 -1.683183e-02 9.813402e-01 9.324632e+00 +9.819807e-01 2.547507e-02 -1.872562e-01 -1.626597e+00 -2.203930e-02 9.995488e-01 2.040741e-02 -1.885721e-01 1.876916e-01 -1.591268e-02 9.820991e-01 9.380866e+00 +9.823021e-01 2.615516e-02 -1.854685e-01 -1.634967e+00 -2.304768e-02 9.995558e-01 1.889142e-02 -1.888051e-01 1.858802e-01 -1.428246e-02 9.824686e-01 9.405472e+00 +9.822602e-01 2.598796e-02 -1.857137e-01 -1.635852e+00 -2.295532e-02 9.995660e-01 1.846172e-02 -1.890361e-01 1.861129e-01 -1.387109e-02 9.824305e-01 9.404838e+00 +9.821727e-01 2.628121e-02 -1.861347e-01 -1.636807e+00 -2.367748e-02 9.995884e-01 1.619810e-02 -1.924645e-01 1.864838e-01 -1.150213e-02 9.823907e-01 9.386956e+00 +9.822343e-01 2.601447e-02 -1.858469e-01 -1.637558e+00 -2.433936e-02 9.996400e-01 1.128973e-02 -1.977199e-01 1.860737e-01 -6.565766e-03 9.825139e-01 9.378778e+00 +9.821847e-01 2.537468e-02 -1.861972e-01 -1.640332e+00 -2.425584e-02 9.996714e-01 8.284938e-03 -1.993791e-01 1.863463e-01 -3.620966e-03 9.824775e-01 9.376167e+00 +9.821928e-01 2.511001e-02 -1.861905e-01 -1.641127e+00 -2.389673e-02 9.996760e-01 8.758163e-03 -1.963128e-01 1.863501e-01 -4.152858e-03 9.824746e-01 9.372464e+00 +9.822399e-01 2.511477e-02 -1.859412e-01 -1.643107e+00 -2.375055e-02 9.996722e-01 9.561127e-03 -1.932542e-01 1.861204e-01 -4.975112e-03 9.825144e-01 9.369584e+00 +9.821755e-01 2.517525e-02 -1.862725e-01 -1.643540e+00 -2.371988e-02 9.996682e-01 1.003805e-02 -1.932834e-01 1.864634e-01 -5.440765e-03 9.824468e-01 9.371050e+00 +9.821916e-01 2.562504e-02 -1.861266e-01 -1.643726e+00 -2.404424e-02 9.996531e-01 1.074592e-02 -1.924916e-01 1.863374e-01 -6.079276e-03 9.824670e-01 9.370281e+00 +9.821853e-01 2.567392e-02 -1.861530e-01 -1.643555e+00 -2.411462e-02 9.996526e-01 1.063629e-02 -1.910780e-01 1.863614e-01 -5.957800e-03 9.824632e-01 9.367453e+00 diff --git a/tools/Ground-Truth/dataset/poses/08.txt b/tools/Ground-Truth/dataset/poses/08.txt new file mode 100644 index 0000000..b75068b --- /dev/null +++ b/tools/Ground-Truth/dataset/poses/08.txt @@ -0,0 +1,4071 @@ +1.000000e+00 1.197624e-11 1.704639e-10 3.214096e-14 1.197625e-11 1.000000e+00 3.562503e-10 -1.998401e-15 1.704639e-10 3.562503e-10 1.000000e+00 -4.041212e-14 +9.999956e-01 2.872219e-03 6.839952e-04 3.879738e-03 -2.873712e-03 9.999934e-01 2.190302e-03 -1.849906e-01 -6.776995e-04 -2.192257e-03 9.999974e-01 8.085136e-01 +9.999832e-01 5.587658e-03 1.562738e-03 7.192398e-03 -5.592623e-03 9.999792e-01 3.190365e-03 -3.682362e-01 -1.544879e-03 -3.199050e-03 9.999937e-01 1.630418e+00 +9.999733e-01 6.921214e-03 2.355063e-03 2.045472e-02 -6.928386e-03 9.999713e-01 3.050144e-03 -5.523196e-01 -2.333885e-03 -3.066378e-03 9.999926e-01 2.389887e+00 +9.999566e-01 8.891450e-03 2.795368e-03 2.958663e-02 -8.899773e-03 9.999559e-01 2.978514e-03 -7.343270e-01 -2.768761e-03 -3.003261e-03 9.999917e-01 3.173915e+00 +9.999525e-01 9.051769e-03 3.609113e-03 3.335121e-02 -9.062748e-03 9.999543e-01 3.036917e-03 -9.183096e-01 -3.581458e-03 -3.069480e-03 9.999889e-01 3.898587e+00 +9.999467e-01 9.344229e-03 4.393637e-03 3.816708e-02 -9.363343e-03 9.999467e-01 4.349580e-03 -1.102394e+00 -4.352760e-03 -4.390486e-03 9.999809e-01 4.630767e+00 +9.999351e-01 1.002404e-02 5.411108e-03 5.059318e-02 -1.006298e-02 9.999233e-01 7.217335e-03 -1.285097e+00 -5.338346e-03 -7.271317e-03 9.999593e-01 5.321596e+00 +9.999263e-01 9.856341e-03 7.085165e-03 5.170819e-02 -9.936435e-03 9.998861e-01 1.135916e-02 -1.470593e+00 -6.972398e-03 -1.142872e-02 9.999104e-01 5.969282e+00 +9.999227e-01 9.036040e-03 8.544750e-03 6.247458e-02 -9.164425e-03 9.998439e-01 1.510696e-02 -1.655746e+00 -8.406909e-03 -1.518410e-02 9.998494e-01 6.584575e+00 +9.999187e-01 8.184367e-03 9.779584e-03 7.747077e-02 -8.356401e-03 9.998087e-01 1.768149e-02 -1.839855e+00 -9.633002e-03 -1.776177e-02 9.997959e-01 7.179430e+00 +9.998992e-01 8.569443e-03 1.131733e-02 9.159598e-02 -8.771741e-03 9.998004e-01 1.794785e-02 -2.023392e+00 -1.116127e-02 -1.804531e-02 9.997749e-01 7.763325e+00 +9.998704e-01 9.739189e-03 1.281973e-02 7.806213e-02 -9.942603e-03 9.998241e-01 1.590012e-02 -2.206950e+00 -1.266263e-02 -1.602552e-02 9.997914e-01 8.294502e+00 +9.998544e-01 9.705443e-03 1.403662e-02 5.269462e-02 -9.883636e-03 9.998707e-01 1.268159e-02 -2.394913e+00 -1.391173e-02 -1.281847e-02 9.998211e-01 8.771047e+00 +9.998390e-01 8.391631e-03 1.586179e-02 4.539942e-02 -8.573432e-03 9.998979e-01 1.142837e-02 -2.579811e+00 -1.576427e-02 -1.156252e-02 9.998089e-01 9.219163e+00 +9.998292e-01 4.730911e-03 1.786430e-02 3.629999e-02 -4.897407e-03 9.999448e-01 9.287785e-03 -2.767953e+00 -1.781938e-02 -9.373685e-03 9.997973e-01 9.647129e+00 +9.998011e-01 2.371753e-03 1.980421e-02 4.725479e-02 -2.529940e-03 9.999650e-01 7.966288e-03 -2.953575e+00 -1.978462e-02 -8.014805e-03 9.997721e-01 1.004720e+01 +9.997320e-01 6.671026e-03 2.216805e-02 4.201541e-02 -6.814894e-03 9.999561e-01 6.420606e-03 -3.142551e+00 -2.212425e-02 -6.569956e-03 9.997337e-01 1.043530e+01 +9.996154e-01 1.130346e-02 2.532319e-02 3.769119e-02 -1.144998e-02 9.999185e-01 5.648136e-03 -3.333269e+00 -2.525729e-02 -5.935912e-03 9.996634e-01 1.075569e+01 +9.995108e-01 1.217647e-02 2.880683e-02 3.176480e-02 -1.236975e-02 9.999021e-01 6.540985e-03 -3.523226e+00 -2.872436e-02 -6.894116e-03 9.995636e-01 1.104825e+01 +9.994553e-01 8.077445e-03 3.199665e-02 5.072266e-02 -8.312721e-03 9.999393e-01 7.226896e-03 -3.706655e+00 -3.193634e-02 -7.488937e-03 9.994619e-01 1.132402e+01 +9.993994e-01 2.921373e-03 3.452893e-02 7.039616e-02 -3.148932e-03 9.999736e-01 6.537843e-03 -3.888842e+00 -3.450892e-02 -6.642644e-03 9.993823e-01 1.157202e+01 +9.993136e-01 -6.270530e-04 3.703920e-02 9.529700e-02 3.258714e-04 9.999668e-01 8.136908e-03 -4.071233e+00 -3.704308e-02 -8.119251e-03 9.992807e-01 1.179524e+01 +9.992103e-01 -1.028734e-03 3.971975e-02 9.028128e-02 6.523598e-04 9.999548e-01 9.487540e-03 -4.268076e+00 -3.972772e-02 -9.454134e-03 9.991658e-01 1.189602e+01 +9.991274e-01 -2.084992e-04 4.176701e-02 9.669037e-02 -1.395792e-04 9.999653e-01 8.330723e-03 -4.457474e+00 -4.176729e-02 -8.329281e-03 9.990927e-01 1.200800e+01 +9.990296e-01 6.213576e-04 4.403971e-02 1.064885e-01 -9.165791e-04 9.999772e-01 6.683651e-03 -4.644611e+00 -4.403456e-02 -6.717529e-03 9.990074e-01 1.210436e+01 +9.989076e-01 2.813382e-03 4.664482e-02 1.123430e-01 -3.078608e-03 9.999795e-01 5.615203e-03 -4.833710e+00 -4.662806e-02 -5.752669e-03 9.988958e-01 1.219147e+01 +9.988112e-01 5.743441e-03 4.840768e-02 1.244047e-01 -6.004889e-03 9.999681e-01 5.257229e-03 -5.021684e+00 -4.837595e-02 -5.541660e-03 9.988138e-01 1.228097e+01 +9.987373e-01 7.422855e-03 4.968710e-02 1.056002e-01 -7.627692e-03 9.999631e-01 3.934157e-03 -5.220757e+00 -4.965607e-02 -4.308186e-03 9.987571e-01 1.229323e+01 +9.986443e-01 6.635480e-03 5.162929e-02 1.073966e-01 -6.749877e-03 9.999751e-01 2.041670e-03 -5.410556e+00 -5.161447e-02 -2.387392e-03 9.986642e-01 1.233543e+01 +9.985752e-01 5.360110e-03 5.309252e-02 1.060557e-01 -5.390645e-03 9.999854e-01 4.319112e-04 -5.599752e+00 -5.308943e-02 -7.174980e-04 9.985895e-01 1.236696e+01 +9.985214e-01 4.548472e-03 5.417033e-02 1.205438e-01 -4.516012e-03 9.999895e-01 -7.216379e-04 -5.782798e+00 -5.417305e-02 4.759374e-04 9.985315e-01 1.242383e+01 +9.984370e-01 5.270555e-03 5.563918e-02 1.175632e-01 -5.162522e-03 9.999845e-01 -2.085249e-03 -5.973298e+00 -5.564931e-02 1.794751e-03 9.984488e-01 1.244527e+01 +9.983586e-01 6.302588e-03 5.692470e-02 1.252757e-01 -6.070502e-03 9.999725e-01 -4.249087e-03 -6.160582e+00 -5.694992e-02 3.896550e-03 9.983694e-01 1.248072e+01 +9.983128e-01 6.443194e-03 5.770626e-02 1.270332e-01 -6.078422e-03 9.999604e-01 -6.494510e-03 -6.350324e+00 -5.774583e-02 6.132789e-03 9.983125e-01 1.250060e+01 +9.982767e-01 5.676981e-03 5.840777e-02 1.425398e-01 -5.172603e-03 9.999480e-01 -8.783055e-03 -6.534828e+00 -5.845460e-02 8.465798e-03 9.982542e-01 1.254514e+01 +9.983039e-01 4.780262e-03 5.802114e-02 1.569458e-01 -4.162037e-03 9.999333e-01 -1.077135e-02 -6.719215e+00 -5.806876e-02 1.051159e-02 9.982573e-01 1.259012e+01 +9.984240e-01 4.280180e-03 5.595733e-02 1.601825e-01 -3.612148e-03 9.999210e-01 -1.203394e-02 -6.903920e+00 -5.600442e-02 1.181285e-02 9.983606e-01 1.262960e+01 +9.985875e-01 4.443316e-03 5.294651e-02 1.504195e-01 -3.758633e-03 9.999081e-01 -1.302418e-02 -7.091533e+00 -5.299952e-02 1.280677e-02 9.985124e-01 1.265651e+01 +9.987906e-01 5.077515e-03 4.890448e-02 1.515087e-01 -4.388270e-03 9.998897e-01 -1.419078e-02 -7.275414e+00 -4.897114e-02 1.395900e-02 9.987027e-01 1.270288e+01 +9.990505e-01 5.410248e-03 4.323012e-02 1.551810e-01 -4.750593e-03 9.998709e-01 -1.534737e-02 -7.457603e+00 -4.330758e-02 1.512742e-02 9.989473e-01 1.275494e+01 +9.993167e-01 5.333669e-03 3.657522e-02 1.567734e-01 -4.745805e-03 9.998584e-01 -1.614082e-02 -7.639654e+00 -3.665614e-02 1.595621e-02 9.992006e-01 1.280649e+01 +9.995545e-01 5.452373e-03 2.934509e-02 1.461490e-01 -4.955577e-03 9.998436e-01 -1.697565e-02 -7.823270e+00 -2.943306e-02 1.682266e-02 9.994252e-01 1.283660e+01 +9.997592e-01 5.662531e-03 2.120070e-02 1.313744e-01 -5.280664e-03 9.998236e-01 -1.802496e-02 -8.006755e+00 -2.129902e-02 1.790866e-02 9.996127e-01 1.286669e+01 +9.999268e-01 4.573882e-03 1.119881e-02 1.281229e-01 -4.356898e-03 9.998038e-01 -1.932405e-02 -8.187426e+00 -1.128500e-02 1.927384e-02 9.997506e-01 1.292430e+01 +9.999934e-01 3.206484e-03 -1.725845e-03 1.181032e-01 -3.242068e-03 9.997736e-01 -2.102607e-02 -8.368884e+00 1.658035e-03 2.103152e-02 9.997774e-01 1.298660e+01 +9.998427e-01 2.398227e-03 -1.757496e-02 1.134195e-01 -2.803070e-03 9.997304e-01 -2.304686e-02 -8.547404e+00 1.751495e-02 2.309250e-02 9.995799e-01 1.307848e+01 +9.993119e-01 2.905017e-03 -3.697792e-02 7.784537e-02 -3.796787e-03 9.997031e-01 -2.406895e-02 -8.732867e+00 3.689702e-02 2.419278e-02 9.990262e-01 1.314705e+01 +9.982647e-01 3.775973e-03 -5.876569e-02 4.601114e-02 -5.179831e-03 9.997044e-01 -2.375509e-02 -8.916116e+00 5.865862e-02 2.401826e-02 9.979891e-01 1.325183e+01 +9.965951e-01 4.491985e-03 -8.232913e-02 2.378998e-03 -6.363678e-03 9.997269e-01 -2.248598e-02 -9.098829e+00 8.220565e-02 2.293333e-02 9.963515e-01 1.336218e+01 +9.940242e-01 5.520365e-03 -1.090201e-01 -3.834925e-02 -7.841460e-03 9.997514e-01 -2.087327e-02 -9.281445e+00 1.088778e-01 2.160341e-02 9.938204e-01 1.351464e+01 +9.902740e-01 6.837615e-03 -1.389626e-01 -1.027432e-01 -9.541583e-03 9.997777e-01 -1.880136e-02 -9.464301e+00 1.388031e-01 1.994442e-02 9.901192e-01 1.366245e+01 +9.850518e-01 7.041311e-03 -1.721142e-01 -1.784095e-01 -9.828243e-03 9.998339e-01 -1.534554e-02 -9.647142e+00 1.719776e-01 1.680773e-02 9.849575e-01 1.384670e+01 +9.779226e-01 8.129758e-03 -2.088091e-01 -2.635490e-01 -1.074140e-02 9.998776e-01 -1.137638e-02 -9.829144e+00 2.086911e-01 1.336812e-02 9.778902e-01 1.404914e+01 +9.685783e-01 9.648296e-03 -2.485216e-01 -3.773915e-01 -1.144352e-02 9.999178e-01 -5.779958e-03 -1.000672e+01 2.484454e-01 8.442305e-03 9.686091e-01 1.423718e+01 +9.569505e-01 1.368059e-02 -2.899287e-01 -4.912886e-01 -1.459916e-02 9.998929e-01 -1.005599e-03 -1.018528e+01 2.898839e-01 5.195026e-03 9.570477e-01 1.446594e+01 +9.431378e-01 1.732265e-02 -3.319503e-01 -6.372956e-01 -1.715754e-02 9.998469e-01 3.428447e-03 -1.036472e+01 3.319589e-01 2.461953e-03 9.432907e-01 1.469815e+01 +9.268127e-01 2.016847e-02 -3.749819e-01 -8.037392e-01 -1.812196e-02 9.997954e-01 8.983588e-03 -1.053985e+01 3.750864e-01 -1.530696e-03 9.269886e-01 1.491810e+01 +9.078697e-01 2.365652e-02 -4.185846e-01 -9.848121e-01 -1.826631e-02 9.996906e-01 1.688019e-02 -1.071770e+01 4.188544e-01 -7.679015e-03 9.080209e-01 1.516902e+01 +8.864286e-01 2.825927e-02 -4.620019e-01 -1.171897e+00 -1.944747e-02 9.995269e-01 2.382483e-02 -1.089272e+01 4.624566e-01 -1.213424e-02 8.865589e-01 1.540908e+01 +8.620790e-01 3.340437e-02 -5.056718e-01 -1.393517e+00 -2.199160e-02 9.993511e-01 2.852483e-02 -1.106348e+01 5.062965e-01 -1.347012e-02 8.622543e-01 1.559951e+01 +8.346104e-01 3.694401e-02 -5.496004e-01 -1.628279e+00 -2.304378e-02 9.992166e-01 3.217337e-02 -1.123333e+01 5.503585e-01 -1.418736e-02 8.348079e-01 1.583724e+01 +8.042209e-01 4.061583e-02 -5.929410e-01 -1.909394e+00 -2.563447e-02 9.991042e-01 3.366891e-02 -1.139957e+01 5.937774e-01 -1.187751e-02 8.045417e-01 1.603100e+01 +7.711116e-01 4.337310e-02 -6.352210e-01 -2.183640e+00 -2.609686e-02 9.989917e-01 3.653184e-02 -1.156138e+01 6.361650e-01 -1.159285e-02 7.714660e-01 1.625791e+01 +7.346863e-01 4.707185e-02 -6.767720e-01 -2.477419e+00 -2.705056e-02 9.988292e-01 4.010667e-02 -1.172013e+01 6.778675e-01 -1.115876e-02 7.350994e-01 1.648134e+01 +6.963124e-01 4.886637e-02 -7.160734e-01 -2.812854e+00 -2.539172e-02 9.987322e-01 4.346463e-02 -1.187697e+01 7.172896e-01 -1.208262e-02 6.966704e-01 1.665771e+01 +6.560448e-01 4.895327e-02 -7.531326e-01 -3.168635e+00 -2.271313e-02 9.987228e-01 4.513140e-02 -1.203628e+01 7.543801e-01 -1.250221e-02 6.563188e-01 1.689162e+01 +6.138729e-01 4.823250e-02 -7.879300e-01 -3.558518e+00 -1.781634e-02 9.987239e-01 4.725546e-02 -1.219440e+01 7.892038e-01 -1.497081e-02 6.139489e-01 1.711347e+01 +5.695872e-01 4.848083e-02 -8.204998e-01 -3.975381e+00 -1.300290e-02 9.986655e-01 4.998156e-02 -1.234846e+01 8.218281e-01 -1.779998e-02 5.694575e-01 1.729265e+01 +5.233982e-01 5.016380e-02 -8.506103e-01 -4.410526e+00 -1.113655e-02 9.985830e-01 5.203778e-02 -1.249954e+01 8.520155e-01 -1.776361e-02 5.232152e-01 1.749197e+01 +4.744464e-01 4.980177e-02 -8.788745e-01 -4.868512e+00 -1.007275e-02 9.986401e-01 5.115074e-02 -1.264852e+01 8.802268e-01 -1.541559e-02 4.743029e-01 1.762521e+01 +4.224059e-01 4.885757e-02 -9.050890e-01 -5.372255e+00 -4.957667e-03 9.986558e-01 5.159466e-02 -1.279641e+01 9.063932e-01 -1.730675e-02 4.220804e-01 1.779999e+01 +3.691101e-01 4.874751e-02 -9.281064e-01 -5.887262e+00 2.489877e-04 9.986182e-01 5.255008e-02 -1.294388e+01 9.293857e-01 -1.962784e-02 3.685879e-01 1.795787e+01 +3.153256e-01 4.693099e-02 -9.478223e-01 -6.444529e+00 3.824875e-03 9.987054e-01 5.072293e-02 -1.308799e+01 9.489759e-01 -1.961954e-02 3.147379e-01 1.804900e+01 +2.621717e-01 5.207782e-02 -9.636150e-01 -7.011137e+00 4.584747e-03 9.984643e-01 5.520862e-02 -1.323067e+01 9.650104e-01 -1.889206e-02 2.615303e-01 1.815574e+01 +2.108090e-01 5.802377e-02 -9.758037e-01 -7.603442e+00 7.000052e-03 9.981216e-01 6.086313e-02 -1.337344e+01 9.775022e-01 -1.966117e-02 2.100069e-01 1.824184e+01 +1.619793e-01 5.928470e-02 -9.850117e-01 -8.252992e+00 1.313697e-02 9.979756e-01 6.222527e-02 -1.351325e+01 9.867067e-01 -2.301927e-02 1.608726e-01 1.828627e+01 +1.173383e-01 6.123356e-02 -9.912024e-01 -8.902786e+00 1.586576e-02 9.978542e-01 6.352270e-02 -1.365686e+01 9.929653e-01 -2.317982e-02 1.161150e-01 1.833142e+01 +7.646129e-02 6.035371e-02 -9.952442e-01 -9.593783e+00 1.560785e-02 9.979715e-01 6.171821e-02 -1.379526e+01 9.969504e-01 -2.025267e-02 7.536421e-02 1.833353e+01 +4.064302e-02 5.583345e-02 -9.976125e-01 -1.027763e+01 1.415900e-02 9.983051e-01 5.644906e-02 -1.392496e+01 9.990734e-01 -1.641945e-02 3.978358e-02 1.832822e+01 +1.125897e-02 5.491995e-02 -9.984273e-01 -1.099243e+01 1.173809e-02 9.984145e-01 5.505163e-02 -1.405557e+01 9.998678e-01 -1.233945e-02 1.059647e-02 1.829695e+01 +-1.025772e-02 5.945623e-02 -9.981782e-01 -1.173793e+01 1.018075e-02 9.981852e-01 5.935203e-02 -1.418805e+01 9.998956e-01 -9.553378e-03 -1.084441e-02 1.826240e+01 +-2.370650e-02 6.555616e-02 -9.975672e-01 -1.254144e+01 1.115112e-02 9.978029e-01 6.530667e-02 -1.431625e+01 9.996568e-01 -9.575791e-03 -2.438544e-02 1.822514e+01 +-3.198896e-02 6.879714e-02 -9.971177e-01 -1.331623e+01 1.133150e-02 9.975891e-01 6.846615e-02 -1.444618e+01 9.994240e-01 -9.108672e-03 -3.269141e-02 1.817976e+01 +-3.608163e-02 6.637987e-02 -9.971418e-01 -1.412357e+01 1.247605e-02 9.977437e-01 6.596851e-02 -1.457497e+01 9.992710e-01 -1.006013e-02 -3.682838e-02 1.813721e+01 +-3.571904e-02 6.263283e-02 -9.973972e-01 -1.493036e+01 1.827605e-02 9.979081e-01 6.201042e-02 -1.469894e+01 9.991948e-01 -1.601352e-02 -3.678900e-02 1.809812e+01 +-3.164508e-02 6.008287e-02 -9.976916e-01 -1.580118e+01 3.128630e-02 9.977620e-01 5.909477e-02 -1.481184e+01 9.990094e-01 -2.934401e-02 -3.345402e-02 1.807756e+01 +-2.617862e-02 6.034060e-02 -9.978345e-01 -1.666008e+01 3.252688e-02 9.976994e-01 5.947909e-02 -1.493472e+01 9.991280e-01 -3.089935e-02 -2.808108e-02 1.804356e+01 +-2.067797e-02 5.974136e-02 -9.979997e-01 -1.755346e+01 2.923875e-02 9.978223e-01 5.912494e-02 -1.506398e+01 9.993586e-01 -2.795767e-02 -2.237970e-02 1.800715e+01 +-1.761589e-02 5.309273e-02 -9.984342e-01 -1.844036e+01 3.424683e-02 9.980352e-01 5.246729e-02 -1.518985e+01 9.992582e-01 -3.326894e-02 -1.939953e-02 1.798098e+01 +-1.567119e-02 4.255996e-02 -9.989710e-01 -1.938035e+01 3.241267e-02 9.985902e-01 4.203529e-02 -1.530597e+01 9.993517e-01 -3.172056e-02 -1.702857e-02 1.794148e+01 +-1.478129e-02 3.465260e-02 -9.992901e-01 -2.030903e+01 2.453191e-02 9.991110e-01 3.428353e-02 -1.543651e+01 9.995898e-01 -2.400773e-02 -1.561825e-02 1.789376e+01 +-1.617203e-02 3.088548e-02 -9.993921e-01 -2.126054e+01 1.899556e-02 9.993519e-01 3.057686e-02 -1.556623e+01 9.996888e-01 -1.848951e-02 -1.674824e-02 1.784686e+01 +-1.963659e-02 3.743840e-02 -9.991060e-01 -2.223204e+01 1.032284e-02 9.992530e-01 3.724103e-02 -1.570538e+01 9.997539e-01 -9.582323e-03 -2.000839e-02 1.779120e+01 +-2.404653e-02 4.528804e-02 -9.986845e-01 -2.322660e+01 3.459999e-03 9.989711e-01 4.521774e-02 -1.583917e+01 9.997049e-01 -2.368113e-03 -2.417849e-02 1.773257e+01 +-2.894458e-02 5.470490e-02 -9.980829e-01 -2.425401e+01 2.761574e-03 9.985018e-01 5.464779e-02 -1.595485e+01 9.995772e-01 -1.174519e-03 -2.905228e-02 1.767332e+01 +-3.089862e-02 6.432144e-02 -9.974507e-01 -2.529453e+01 1.407134e-03 9.979290e-01 6.430871e-02 -1.606607e+01 9.995216e-01 5.835076e-04 -3.092514e-02 1.761259e+01 +-3.200157e-02 7.328434e-02 -9.967975e-01 -2.634037e+01 2.673252e-03 9.973110e-01 7.323629e-02 -1.617237e+01 9.994843e-01 -3.210109e-04 -3.211142e-02 1.755519e+01 +-3.328380e-02 7.492391e-02 -9.966336e-01 -2.737967e+01 4.588331e-03 9.971871e-01 7.481230e-02 -1.627576e+01 9.994354e-01 -2.082842e-03 -3.353395e-02 1.749961e+01 +-3.529431e-02 7.145897e-02 -9.968189e-01 -2.842035e+01 3.126781e-03 9.974433e-01 7.139304e-02 -1.639261e+01 9.993721e-01 -5.970620e-04 -3.542751e-02 1.743663e+01 +-3.776024e-02 6.701814e-02 -9.970370e-01 -2.953257e+01 2.963673e-03 9.977516e-01 6.695396e-02 -1.620289e+01 9.992825e-01 -4.266899e-04 -3.787396e-02 1.738267e+01 +-4.252075e-02 6.206396e-02 -9.971660e-01 -3.065335e+01 3.274803e-03 9.980719e-01 6.198072e-02 -1.593634e+01 9.990903e-01 -6.300514e-04 -4.264201e-02 1.732554e+01 +-4.829629e-02 5.700185e-02 -9.972052e-01 -3.173535e+01 3.288774e-03 9.983739e-01 5.690939e-02 -1.578394e+01 9.988277e-01 -5.310654e-04 -4.840523e-02 1.725923e+01 +-5.493241e-02 5.431888e-02 -9.970115e-01 -3.284010e+01 2.588800e-03 9.985235e-01 5.425864e-02 -1.554092e+01 9.984868e-01 3.994990e-04 -5.499192e-02 1.718702e+01 +-6.139335e-02 5.761689e-02 -9.964493e-01 -3.393642e+01 2.900272e-03 9.983385e-01 5.754745e-02 -1.538867e+01 9.981095e-01 6.430604e-04 -6.145845e-02 1.710564e+01 +-6.811247e-02 6.286410e-02 -9.956951e-01 -3.506183e+01 1.980838e-03 9.980194e-01 6.287536e-02 -1.516174e+01 9.976757e-01 2.310289e-03 -6.810209e-02 1.701234e+01 +-7.415595e-02 6.602684e-02 -9.950585e-01 -3.617205e+01 -9.470293e-04 9.978006e-01 6.627939e-02 -1.500021e+01 9.972462e-01 5.857364e-03 -7.393032e-02 1.691299e+01 +-7.920505e-02 6.785172e-02 -9.945465e-01 -3.729835e+01 -3.582909e-03 9.976550e-01 6.834916e-02 -1.481235e+01 9.968519e-01 8.976971e-03 -7.877621e-02 1.681080e+01 +-8.206543e-02 6.964787e-02 -9.941903e-01 -3.840568e+01 -8.185577e-03 9.974744e-01 7.055363e-02 -1.466221e+01 9.965934e-01 1.392804e-02 -8.128806e-02 1.670138e+01 +-8.371459e-02 7.083704e-02 -9.939688e-01 -3.952742e+01 -1.239617e-02 9.973189e-01 7.211985e-02 -1.448917e+01 9.964127e-01 1.835889e-02 -8.261203e-02 1.658923e+01 +-8.541948e-02 7.071176e-02 -9.938326e-01 -4.062925e+01 -1.382670e-02 9.972982e-01 7.214675e-02 -1.434628e+01 9.962492e-01 1.990416e-02 -8.421098e-02 1.648346e+01 +-8.686037e-02 6.974801e-02 -9.937759e-01 -4.172631e+01 -1.412098e-02 9.973597e-01 7.123379e-02 -1.420935e+01 9.961204e-01 2.022048e-02 -8.564612e-02 1.637621e+01 +-8.794605e-02 6.892771e-02 -9.937376e-01 -4.282445e+01 -1.524843e-02 9.973930e-01 7.053076e-02 -1.406397e+01 9.960086e-01 2.135584e-02 -8.666574e-02 1.626519e+01 +-8.893179e-02 6.841399e-02 -9.936854e-01 -4.392347e+01 -1.754482e-02 9.973759e-01 7.023830e-02 -1.394380e+01 9.958832e-01 2.368045e-02 -8.749812e-02 1.615263e+01 +-8.995253e-02 6.620537e-02 -9.937431e-01 -4.502105e+01 -2.151425e-02 9.974261e-01 6.839820e-02 -1.380485e+01 9.957137e-01 2.753223e-02 -8.829664e-02 1.601244e+01 +-9.049383e-02 6.127481e-02 -9.940102e-01 -4.612460e+01 -2.690920e-02 9.975905e-01 6.394532e-02 -1.369977e+01 9.955334e-01 3.253467e-02 -8.862693e-02 1.587466e+01 +-8.991260e-02 5.990905e-02 -9.941462e-01 -4.723304e+01 -2.934124e-02 9.975966e-01 6.277068e-02 -1.357689e+01 9.955174e-01 3.481335e-02 -8.793869e-02 1.573585e+01 +-8.828340e-02 6.355482e-02 -9.940658e-01 -4.834697e+01 -3.033166e-02 9.973281e-01 6.645718e-02 -1.348082e+01 9.956335e-01 3.601873e-02 -8.611980e-02 1.561279e+01 +-8.668332e-02 6.811416e-02 -9.939046e-01 -4.944347e+01 -3.137247e-02 9.969785e-01 7.106098e-02 -1.336907e+01 9.957419e-01 3.734104e-02 -8.428449e-02 1.545981e+01 +-8.549475e-02 6.706539e-02 -9.940789e-01 -5.055227e+01 -2.842936e-02 9.971615e-01 6.971842e-02 -1.326722e+01 9.959330e-01 3.422158e-02 -8.334544e-02 1.533206e+01 +-8.364524e-02 6.640441e-02 -9.942806e-01 -5.167686e+01 -2.774387e-02 9.972352e-01 6.893575e-02 -1.315869e+01 9.961093e-01 3.335133e-02 -8.157167e-02 1.519243e+01 +-8.017773e-02 6.721528e-02 -9.945117e-01 -5.279743e+01 -3.203724e-02 9.970346e-01 6.996865e-02 -1.306503e+01 9.962656e-01 3.747134e-02 -7.778658e-02 1.505126e+01 +-7.535716e-02 6.775177e-02 -9.948522e-01 -5.392582e+01 -3.748531e-02 9.967914e-01 7.072325e-02 -1.296288e+01 9.964518e-01 4.262185e-02 -7.257567e-02 1.489226e+01 +-7.008221e-02 6.758686e-02 -9.952489e-01 -5.503106e+01 -4.140134e-02 9.966453e-01 7.059705e-02 -1.286464e+01 9.966817e-01 4.615223e-02 -6.704892e-02 1.474256e+01 +-6.502658e-02 6.692597e-02 -9.956367e-01 -5.614945e+01 -4.318935e-02 9.966247e-01 6.981317e-02 -1.275200e+01 9.969485e-01 4.754061e-02 -6.191660e-02 1.457561e+01 +-5.980959e-02 6.572816e-02 -9.960435e-01 -5.727099e+01 -4.287178e-02 9.967399e-01 6.834847e-02 -1.265622e+01 9.972888e-01 4.679004e-02 -5.679672e-02 1.444475e+01 +-5.494773e-02 6.589686e-02 -9.963124e-01 -5.840183e+01 -4.137153e-02 9.968127e-01 6.821166e-02 -1.256374e+01 9.976318e-01 4.496704e-02 -5.204634e-02 1.432993e+01 +-5.022289e-02 6.618981e-02 -9.965423e-01 -5.953937e+01 -4.056991e-02 9.968427e-01 6.825438e-02 -1.247048e+01 9.979137e-01 4.385756e-02 -4.737900e-02 1.421939e+01 +-4.500112e-02 6.782186e-02 -9.966820e-01 -6.067988e+01 -3.928251e-02 9.968010e-01 6.960361e-02 -1.238487e+01 9.982143e-01 4.228441e-02 -4.219295e-02 1.413022e+01 +-4.023555e-02 6.841947e-02 -9.968449e-01 -6.182984e+01 -4.063030e-02 9.967156e-01 7.005057e-02 -1.228364e+01 9.983638e-01 4.332063e-02 -3.732350e-02 1.403477e+01 +-3.516736e-02 6.905608e-02 -9.969927e-01 -6.296889e+01 -4.056068e-02 9.966892e-01 7.046579e-02 -1.219174e+01 9.985580e-01 4.291679e-02 -3.224997e-02 1.395899e+01 +-3.052410e-02 6.426185e-02 -9.974661e-01 -6.410374e+01 -4.019110e-02 9.970451e-01 6.546466e-02 -1.209714e+01 9.987257e-01 4.208750e-02 -2.785115e-02 1.388201e+01 +-2.640420e-02 5.890871e-02 -9.979141e-01 -6.524509e+01 -3.991461e-02 9.974039e-01 5.993472e-02 -1.201647e+01 9.988542e-01 4.141387e-02 -2.398434e-02 1.382443e+01 +-2.321517e-02 5.737191e-02 -9.980829e-01 -6.640401e+01 -3.983960e-02 9.975058e-01 5.826542e-02 -1.193274e+01 9.989364e-01 4.111586e-02 -2.087160e-02 1.377020e+01 +-2.034543e-02 6.036822e-02 -9.979688e-01 -6.759390e+01 -3.973630e-02 9.973379e-01 6.114017e-02 -1.184384e+01 9.990031e-01 4.089951e-02 -1.789246e-02 1.370405e+01 +-1.869192e-02 6.043286e-02 -9.979972e-01 -6.880347e+01 -3.948006e-02 9.973485e-01 6.113303e-02 -1.175307e+01 9.990455e-01 4.054368e-02 -1.625647e-02 1.362873e+01 +-1.809779e-02 5.985205e-02 -9.980432e-01 -7.000114e+01 -4.127001e-02 9.973112e-01 6.055653e-02 -1.167314e+01 9.989841e-01 4.228518e-02 -1.557903e-02 1.356370e+01 +-1.770478e-02 6.095358e-02 -9.979836e-01 -7.119765e+01 -4.267752e-02 9.971842e-01 6.166190e-02 -1.159789e+01 9.989320e-01 4.368317e-02 -1.505358e-02 1.349639e+01 +-1.686692e-02 6.096638e-02 -9.979973e-01 -7.239633e+01 -4.337039e-02 9.971552e-01 6.164794e-02 -1.151584e+01 9.989167e-01 4.432334e-02 -1.417480e-02 1.344487e+01 +-1.595734e-02 5.882457e-02 -9.981408e-01 -7.361041e+01 -4.394737e-02 9.972619e-01 5.947538e-02 -1.144335e+01 9.989064e-01 4.481473e-02 -1.332846e-02 1.341530e+01 +-1.554827e-02 5.759721e-02 -9.982188e-01 -7.484838e+01 -4.229507e-02 9.974080e-01 5.820923e-02 -1.137302e+01 9.989842e-01 4.312478e-02 -1.307189e-02 1.338556e+01 +-1.543484e-02 5.763970e-02 -9.982181e-01 -7.604076e+01 -3.851485e-02 9.975618e-01 5.819735e-02 -1.131342e+01 9.991388e-01 3.934448e-02 -1.317722e-02 1.336502e+01 +-1.560555e-02 5.777323e-02 -9.982077e-01 -7.723489e+01 -3.659646e-02 9.976274e-01 5.831178e-02 -1.125606e+01 9.992083e-01 3.744086e-02 -1.345423e-02 1.334215e+01 +-1.558433e-02 6.045475e-02 -9.980493e-01 -7.842878e+01 -3.588218e-02 9.974937e-01 6.098141e-02 -1.119081e+01 9.992345e-01 3.676254e-02 -1.337602e-02 1.331764e+01 +-1.562562e-02 6.441173e-02 -9.978011e-01 -7.962987e+01 -3.851885e-02 9.971433e-01 6.497250e-02 -1.112002e+01 9.991357e-01 3.944938e-02 -1.309991e-02 1.328629e+01 +-1.520367e-02 6.463839e-02 -9.977929e-01 -8.081425e+01 -4.089853e-02 9.970329e-01 6.521236e-02 -1.105497e+01 9.990477e-01 4.179973e-02 -1.251494e-02 1.324767e+01 +-1.512821e-02 6.231167e-02 -9.979421e-01 -8.199092e+01 -4.185086e-02 9.971422e-01 6.289617e-02 -1.098760e+01 9.990094e-01 4.271623e-02 -1.247717e-02 1.320252e+01 +-1.514787e-02 5.979552e-02 -9.980957e-01 -8.317804e+01 -4.189772e-02 9.972955e-01 6.038347e-02 -1.092504e+01 9.990071e-01 4.273261e-02 -1.260160e-02 1.317232e+01 +-1.544064e-02 5.927158e-02 -9.981225e-01 -8.440032e+01 -3.978761e-02 9.974144e-01 5.984505e-02 -1.086319e+01 9.990889e-01 4.063695e-02 -1.304244e-02 1.315402e+01 +-1.548268e-02 6.094840e-02 -9.980208e-01 -8.560631e+01 -3.817466e-02 9.973767e-01 6.150130e-02 -1.080328e+01 9.991512e-01 3.905131e-02 -1.311538e-02 1.313614e+01 +-1.529085e-02 6.367263e-02 -9.978537e-01 -8.680645e+01 -3.746143e-02 9.972332e-01 6.420710e-02 -1.074239e+01 9.991811e-01 3.836280e-02 -1.286328e-02 1.311627e+01 +-1.492959e-02 6.600542e-02 -9.977076e-01 -8.800584e+01 -3.793016e-02 9.970632e-01 6.653039e-02 -1.067854e+01 9.991689e-01 3.883648e-02 -1.238215e-02 1.309053e+01 +-1.494369e-02 6.664049e-02 -9.976651e-01 -8.920185e+01 -3.954052e-02 9.969567e-01 6.718545e-02 -1.060913e+01 9.991063e-01 4.045220e-02 -1.226321e-02 1.305741e+01 +-1.483176e-02 6.457297e-02 -9.978027e-01 -9.040737e+01 -3.904764e-02 9.971139e-01 6.510882e-02 -1.053637e+01 9.991273e-01 3.992751e-02 -1.226753e-02 1.303023e+01 +-1.473156e-02 6.291316e-02 -9.979103e-01 -9.159022e+01 -3.738751e-02 9.972860e-01 6.342575e-02 -1.047161e+01 9.991923e-01 3.824373e-02 -1.233941e-02 1.300185e+01 +-1.479234e-02 6.375926e-02 -9.978557e-01 -9.276422e+01 -3.576915e-02 9.972923e-01 6.425353e-02 -1.041435e+01 9.992506e-01 3.664291e-02 -1.247167e-02 1.296581e+01 +-1.475696e-02 6.691903e-02 -9.976493e-01 -9.393275e+01 -3.380333e-02 9.971542e-01 6.738585e-02 -1.035522e+01 9.993196e-01 3.471827e-02 -1.245288e-02 1.293824e+01 +-1.458909e-02 6.949556e-02 -9.974756e-01 -9.510568e+01 -3.229558e-02 9.970285e-01 6.993678e-02 -1.029043e+01 9.993719e-01 3.323436e-02 -1.230134e-02 1.290998e+01 +-1.433771e-02 7.088181e-02 -9.973817e-01 -9.626960e+01 -3.294447e-02 9.969091e-01 7.132183e-02 -1.022043e+01 9.993544e-01 3.388080e-02 -1.195823e-02 1.287472e+01 +-1.410932e-02 7.285906e-02 -9.972424e-01 -9.742594e+01 -3.518273e-02 9.966879e-01 7.331635e-02 -1.014736e+01 9.992813e-01 3.612015e-02 -1.149921e-02 1.283029e+01 +-1.410676e-02 7.217106e-02 -9.972925e-01 -9.858643e+01 -3.785543e-02 9.966381e-01 7.265920e-02 -1.007536e+01 9.991837e-01 3.877792e-02 -1.132727e-02 1.279300e+01 +-1.393330e-02 6.865269e-02 -9.975433e-01 -9.975488e+01 -4.047711e-02 9.967837e-01 6.916579e-02 -9.994701e+00 9.990833e-01 4.134138e-02 -1.110962e-02 1.275337e+01 +-1.378196e-02 6.721519e-02 -9.976433e-01 -1.009218e+02 -4.238305e-02 9.968021e-01 6.774403e-02 -9.909116e+00 9.990064e-01 4.321681e-02 -1.088910e-02 1.272104e+01 +-1.389790e-02 6.558643e-02 -9.977501e-01 -1.020871e+02 -4.189948e-02 9.969318e-01 6.611628e-02 -9.825948e+00 9.990252e-01 4.272408e-02 -1.110722e-02 1.269500e+01 +-1.382142e-02 6.419182e-02 -9.978418e-01 -1.032538e+02 -4.050965e-02 9.970819e-01 6.470406e-02 -9.744093e+00 9.990836e-01 4.131652e-02 -1.118070e-02 1.267107e+01 +-1.394370e-02 6.610929e-02 -9.977149e-01 -1.044187e+02 -3.997502e-02 9.969774e-01 6.661911e-02 -9.664877e+00 9.991034e-01 4.081259e-02 -1.125883e-02 1.264679e+01 +-1.376547e-02 6.909021e-02 -9.975154e-01 -1.055891e+02 -3.882954e-02 9.968205e-01 6.957793e-02 -9.584647e+00 9.991511e-01 3.969083e-02 -1.103896e-02 1.262204e+01 +-1.445445e-02 6.806213e-02 -9.975764e-01 -1.067623e+02 -4.247975e-02 9.967380e-01 6.862046e-02 -9.502039e+00 9.989928e-01 4.336866e-02 -1.151603e-02 1.259867e+01 +-1.511515e-02 6.918361e-02 -9.974894e-01 -1.079507e+02 -4.716132e-02 9.964437e-01 6.982575e-02 -9.415204e+00 9.987730e-01 4.809834e-02 -1.179860e-02 1.257471e+01 +-1.532489e-02 6.826655e-02 -9.975494e-01 -1.091316e+02 -5.037358e-02 9.963469e-01 6.895814e-02 -9.337677e+00 9.986129e-01 5.130691e-02 -1.183007e-02 1.254532e+01 +-1.546785e-02 6.486281e-02 -9.977743e-01 -1.103205e+02 -5.108528e-02 9.965391e-01 6.557448e-02 -9.260090e+00 9.985745e-01 5.198587e-02 -1.210078e-02 1.251737e+01 +-1.618993e-02 6.037193e-02 -9.980446e-01 -1.115065e+02 -5.140837e-02 9.968050e-01 6.113088e-02 -9.187743e+00 9.985465e-01 5.229755e-02 -1.303458e-02 1.249198e+01 +-1.697470e-02 5.962553e-02 -9.980765e-01 -1.127058e+02 -4.814105e-02 9.970138e-01 6.038082e-02 -9.117584e+00 9.986963e-01 4.907339e-02 -1.405358e-02 1.247059e+01 +-1.752368e-02 5.937481e-02 -9.980819e-01 -1.139114e+02 -4.372259e-02 9.972348e-01 6.009208e-02 -9.050788e+00 9.988900e-01 4.469176e-02 -1.487920e-02 1.245171e+01 +-1.811674e-02 6.064886e-02 -9.979947e-01 -1.151254e+02 -4.251462e-02 9.972090e-01 6.137290e-02 -8.981268e+00 9.989316e-01 4.354124e-02 -1.548771e-02 1.242753e+01 +-1.886440e-02 6.479969e-02 -9.977200e-01 -1.163446e+02 -4.206456e-02 9.969625e-01 6.554585e-02 -8.912616e+00 9.989368e-01 4.320513e-02 -1.608133e-02 1.240154e+01 +-1.956861e-02 6.523925e-02 -9.976777e-01 -1.175658e+02 -4.047871e-02 9.969989e-01 6.598883e-02 -8.839873e+00 9.989888e-01 4.167601e-02 -1.686908e-02 1.237794e+01 +-2.004092e-02 6.088923e-02 -9.979433e-01 -1.187914e+02 -4.018544e-02 9.972881e-01 6.165628e-02 -8.763005e+00 9.989913e-01 4.133844e-02 -1.753970e-02 1.235686e+01 +-2.077225e-02 5.688173e-02 -9.981648e-01 -1.200196e+02 -4.036182e-02 9.975186e-01 5.768486e-02 -8.692054e+00 9.989692e-01 4.148599e-02 -1.842485e-02 1.233172e+01 +-2.182535e-02 5.541515e-02 -9.982248e-01 -1.212572e+02 -3.972772e-02 9.976260e-01 5.625053e-02 -8.625666e+00 9.989722e-01 4.088488e-02 -1.957202e-02 1.230645e+01 +-2.236095e-02 5.644258e-02 -9.981554e-01 -1.225069e+02 -4.084259e-02 9.975200e-01 5.732163e-02 -8.560565e+00 9.989154e-01 4.204901e-02 -2.000023e-02 1.227758e+01 +-2.297861e-02 6.104698e-02 -9.978703e-01 -1.237655e+02 -4.568371e-02 9.970271e-01 6.204740e-02 -8.492707e+00 9.986917e-01 4.701218e-02 -2.012144e-02 1.224313e+01 +-2.337087e-02 6.485528e-02 -9.976210e-01 -1.250246e+02 -5.160286e-02 9.964850e-01 6.599033e-02 -8.423794e+00 9.983942e-01 5.302234e-02 -1.994200e-02 1.220345e+01 +-2.352697e-02 6.443399e-02 -9.976446e-01 -1.262830e+02 -5.866983e-02 9.961119e-01 6.571859e-02 -8.349988e+00 9.980002e-01 6.007779e-02 -1.965516e-02 1.216234e+01 +-2.336488e-02 6.227403e-02 -9.977855e-01 -1.275410e+02 -6.224465e-02 9.960310e-01 6.362211e-02 -8.279418e+00 9.977874e-01 6.359333e-02 -1.939592e-02 1.212394e+01 +-2.389148e-02 6.098701e-02 -9.978526e-01 -1.288006e+02 -6.415111e-02 9.959868e-01 6.240895e-02 -8.210838e+00 9.976542e-01 6.550439e-02 -1.988321e-02 1.208869e+01 +-2.450825e-02 6.093630e-02 -9.978407e-01 -1.300583e+02 -6.481837e-02 9.959434e-01 6.241247e-02 -8.146584e+00 9.975961e-01 6.620802e-02 -2.045903e-02 1.205681e+01 +-2.507999e-02 5.985552e-02 -9.978919e-01 -1.313178e+02 -6.254336e-02 9.961565e-01 6.132334e-02 -8.083157e+00 9.977271e-01 6.394949e-02 -2.124002e-02 1.203575e+01 +-2.559010e-02 6.019129e-02 -9.978588e-01 -1.325698e+02 -6.262396e-02 9.961286e-01 6.169293e-02 -8.016231e+00 9.977091e-01 6.406859e-02 -2.172161e-02 1.198862e+01 +-2.632779e-02 6.524672e-02 -9.975218e-01 -1.338382e+02 -6.246609e-02 9.958102e-01 6.678346e-02 -7.937189e+00 9.976998e-01 6.406954e-02 -2.214177e-02 1.194014e+01 +-2.711301e-02 7.025143e-02 -9.971608e-01 -1.351127e+02 -6.179923e-02 9.955016e-01 7.181489e-02 -7.849143e+00 9.977203e-01 6.357088e-02 -2.264956e-02 1.188153e+01 +-2.733857e-02 6.836613e-02 -9.972856e-01 -1.363739e+02 -6.175474e-02 9.956374e-01 6.994603e-02 -7.760464e+00 9.977169e-01 6.349934e-02 -2.299737e-02 1.182054e+01 +-2.682924e-02 6.672025e-02 -9.974109e-01 -1.376470e+02 -6.177165e-02 9.957526e-01 6.827092e-02 -7.667958e+00 9.977297e-01 6.344337e-02 -2.259386e-02 1.176337e+01 +-2.579681e-02 6.686053e-02 -9.974288e-01 -1.389060e+02 -6.113358e-02 9.957878e-01 6.833167e-02 -7.586989e+00 9.977962e-01 6.273913e-02 -2.160072e-02 1.171546e+01 +-2.502910e-02 6.609067e-02 -9.974996e-01 -1.401685e+02 -6.146398e-02 9.958227e-01 6.752183e-02 -7.505311e+00 9.977955e-01 6.300030e-02 -2.086235e-02 1.166712e+01 +-2.436471e-02 6.744136e-02 -9.974257e-01 -1.414242e+02 -6.115818e-02 9.957525e-01 6.882219e-02 -7.428721e+00 9.978307e-01 6.267756e-02 -2.013663e-02 1.162467e+01 +-2.363088e-02 7.168037e-02 -9.971477e-01 -1.426864e+02 -6.250069e-02 9.953691e-01 7.303371e-02 -7.340825e+00 9.977652e-01 6.404826e-02 -1.904137e-02 1.159260e+01 +-2.233123e-02 7.306954e-02 -9.970768e-01 -1.439374e+02 -6.398695e-02 9.951762e-01 7.436337e-02 -7.255331e+00 9.977009e-01 6.546052e-02 -1.754801e-02 1.155864e+01 +-2.147886e-02 7.044829e-02 -9.972841e-01 -1.451859e+02 -6.634030e-02 9.952153e-01 7.173096e-02 -7.169433e+00 9.975659e-01 6.770082e-02 -1.670253e-02 1.152369e+01 +-2.134088e-02 6.702912e-02 -9.975227e-01 -1.464259e+02 -6.526441e-02 9.955284e-01 6.829138e-02 -7.089788e+00 9.976398e-01 6.656012e-02 -1.687083e-02 1.149266e+01 +-2.139799e-02 6.537338e-02 -9.976314e-01 -1.476694e+02 -6.242783e-02 9.958253e-01 6.659404e-02 -7.013380e+00 9.978201e-01 6.370494e-02 -1.722754e-02 1.146581e+01 +-2.162731e-02 6.489254e-02 -9.976578e-01 -1.489193e+02 -6.118526e-02 9.959348e-01 6.610686e-02 -6.932530e+00 9.978921e-01 6.247166e-02 -1.756892e-02 1.144946e+01 +-2.180570e-02 6.500904e-02 -9.976464e-01 -1.501606e+02 -5.841013e-02 9.960963e-01 6.618472e-02 -6.855330e+00 9.980545e-01 5.971585e-02 -1.792339e-02 1.142916e+01 +-2.199914e-02 6.433136e-02 -9.976861e-01 -1.514021e+02 -5.621122e-02 9.962694e-01 6.547950e-02 -6.780422e+00 9.981765e-01 5.752163e-02 -1.830092e-02 1.140858e+01 +-2.179096e-02 6.441207e-02 -9.976854e-01 -1.526382e+02 -5.578181e-02 9.962895e-01 6.554032e-02 -6.706249e+00 9.982052e-01 5.708088e-02 -1.811708e-02 1.138177e+01 +-2.200736e-02 6.642195e-02 -9.975489e-01 -1.538791e+02 -5.305911e-02 9.963067e-01 6.750982e-02 -6.629037e+00 9.983489e-01 5.441476e-02 -1.840179e-02 1.135916e+01 +-2.229257e-02 6.811946e-02 -9.974281e-01 -1.551151e+02 -5.065852e-02 9.963174e-01 6.917584e-02 -6.552505e+00 9.984672e-01 5.207033e-02 -1.875964e-02 1.133296e+01 +-2.236642e-02 6.666813e-02 -9.975245e-01 -1.563504e+02 -4.818255e-02 9.965427e-01 6.768288e-02 -6.473273e+00 9.985881e-01 4.957709e-02 -1.907685e-02 1.131053e+01 +-2.299800e-02 6.680775e-02 -9.975008e-01 -1.575798e+02 -4.929138e-02 9.964754e-01 6.787554e-02 -6.397565e+00 9.985197e-01 5.072918e-02 -1.962389e-02 1.128127e+01 +-2.296675e-02 7.159319e-02 -9.971694e-01 -1.588158e+02 -4.988767e-02 9.961078e-01 7.266600e-02 -6.318685e+00 9.984908e-01 5.141536e-02 -1.930574e-02 1.125125e+01 +-2.282772e-02 7.800936e-02 -9.966912e-01 -1.600474e+02 -5.548653e-02 9.953155e-01 7.917254e-02 -6.238274e+00 9.981985e-01 5.711026e-02 -1.839231e-02 1.121406e+01 +-2.148104e-02 7.851244e-02 -9.966817e-01 -1.612774e+02 -6.006041e-02 9.950098e-01 7.967522e-02 -6.151798e+00 9.979636e-01 6.157260e-02 -1.665836e-02 1.117789e+01 +-2.021618e-02 7.450810e-02 -9.970155e-01 -1.624963e+02 -6.392141e-02 9.950827e-01 7.565979e-02 -6.066573e+00 9.977502e-01 6.526018e-02 -1.535411e-02 1.114320e+01 +-1.861198e-02 6.935149e-02 -9.974186e-01 -1.637094e+02 -6.573296e-02 9.953483e-01 7.043414e-02 -5.982960e+00 9.976637e-01 6.687418e-02 -1.396673e-02 1.110756e+01 +-1.787969e-02 6.694463e-02 -9.975965e-01 -1.649275e+02 -6.824238e-02 9.953475e-01 6.801682e-02 -5.893695e+00 9.975086e-01 6.929447e-02 -1.322805e-02 1.105807e+01 +-1.692045e-02 6.521076e-02 -9.977280e-01 -1.661457e+02 -6.400365e-02 9.957537e-01 6.616717e-02 -5.813017e+00 9.978062e-01 6.497781e-02 -1.267487e-02 1.102021e+01 +-1.674962e-02 5.980427e-02 -9.980696e-01 -1.673604e+02 -5.978266e-02 9.963638e-01 6.070535e-02 -5.732439e+00 9.980709e-01 6.068404e-02 -1.311346e-02 1.098338e+01 +-1.687655e-02 5.816005e-02 -9.981646e-01 -1.685647e+02 -5.441935e-02 9.967736e-01 5.899911e-02 -5.666988e+00 9.983756e-01 5.531516e-02 -1.365707e-02 1.096569e+01 +-1.781171e-02 5.875010e-02 -9.981138e-01 -1.697601e+02 -5.092762e-02 9.969230e-01 5.958884e-02 -5.605440e+00 9.985435e-01 5.189293e-02 -1.476490e-02 1.095552e+01 +-1.735444e-02 6.663810e-02 -9.976263e-01 -1.709676e+02 -5.148246e-02 9.963934e-01 6.745134e-02 -5.541431e+00 9.985231e-01 5.253082e-02 -1.386115e-02 1.093372e+01 +-1.583274e-02 6.957455e-02 -9.974511e-01 -1.721695e+02 -5.361843e-02 9.960817e-01 7.033015e-02 -5.472772e+00 9.984360e-01 5.459528e-02 -1.204022e-02 1.091427e+01 +-1.395892e-02 6.627148e-02 -9.977040e-01 -1.733686e+02 -5.425728e-02 9.962809e-01 6.693609e-02 -5.400947e+00 9.984294e-01 5.506705e-02 -1.031129e-02 1.089482e+01 +-1.313538e-02 6.521238e-02 -9.977849e-01 -1.745714e+02 -5.623549e-02 9.962435e-01 6.585197e-02 -5.329432e+00 9.983312e-01 5.697591e-02 -9.418785e-03 1.087682e+01 +-1.225548e-02 6.744229e-02 -9.976479e-01 -1.757740e+02 -5.519165e-02 9.961562e-01 6.801946e-02 -5.262290e+00 9.984006e-01 5.589544e-02 -8.486124e-03 1.086154e+01 +-1.158080e-02 6.590723e-02 -9.977585e-01 -1.769647e+02 -5.443479e-02 9.963042e-01 6.644300e-02 -5.194579e+00 9.984502e-01 5.508223e-02 -7.950348e-03 1.084637e+01 +-9.964691e-03 6.427281e-02 -9.978826e-01 -1.781372e+02 -5.455101e-02 9.964111e-01 6.472279e-02 -5.127657e+00 9.984613e-01 5.508044e-02 -6.422781e-03 1.083308e+01 +-8.388822e-03 6.580292e-02 -9.977974e-01 -1.792850e+02 -5.633023e-02 9.962169e-01 6.617230e-02 -5.066445e+00 9.983770e-01 5.676126e-02 -4.650391e-03 1.081724e+01 +-6.942482e-03 6.780724e-02 -9.976743e-01 -1.804028e+02 -5.647856e-02 9.960791e-01 6.809186e-02 -5.009609e+00 9.983797e-01 5.681993e-02 -3.085604e-03 1.080603e+01 +-6.540296e-03 6.937317e-02 -9.975693e-01 -1.814905e+02 -5.718671e-02 9.959321e-01 6.963426e-02 -4.952631e+00 9.983421e-01 5.750313e-02 -2.546465e-03 1.079613e+01 +-6.304416e-03 7.083852e-02 -9.974679e-01 -1.825545e+02 -5.776087e-02 9.957965e-01 7.108491e-02 -4.894590e+00 9.983106e-01 5.806275e-02 -2.186219e-03 1.078787e+01 +-6.359991e-03 7.207244e-02 -9.973791e-01 -1.835944e+02 -5.676449e-02 9.957650e-01 7.231779e-02 -4.834936e+00 9.983674e-01 5.707566e-02 -2.241899e-03 1.078029e+01 +-6.112660e-03 7.129729e-02 -9.974364e-01 -1.846024e+02 -5.706538e-02 9.958046e-01 7.153039e-02 -4.775207e+00 9.983518e-01 5.735632e-02 -2.018406e-03 1.077372e+01 +-4.743684e-03 7.124931e-02 -9.974472e-01 -1.855760e+02 -5.784703e-02 9.957686e-01 7.140453e-02 -4.716960e+00 9.983142e-01 5.803807e-02 -6.020487e-04 1.076462e+01 +-3.171605e-03 7.139933e-02 -9.974428e-01 -1.865239e+02 -5.863232e-02 9.957185e-01 7.146236e-02 -4.661198e+00 9.982746e-01 5.870903e-02 1.028285e-03 1.075866e+01 +-3.778346e-03 6.997751e-02 -9.975414e-01 -1.874583e+02 -5.770893e-02 9.958708e-01 7.007892e-02 -4.609149e+00 9.983263e-01 5.783182e-02 2.755850e-04 1.075884e+01 +-6.711295e-03 6.726787e-02 -9.977124e-01 -1.883924e+02 -5.505698e-02 9.961965e-01 6.753603e-02 -4.557958e+00 9.984607e-01 5.538428e-02 -2.982201e-03 1.076230e+01 +-1.165042e-02 6.389029e-02 -9.978889e-01 -1.893138e+02 -5.447499e-02 9.964340e-01 6.443316e-02 -4.505680e+00 9.984472e-01 5.511065e-02 -8.128451e-03 1.075260e+01 +-1.658927e-02 6.073842e-02 -9.980158e-01 -1.902327e+02 -5.608032e-02 9.965254e-01 6.157991e-02 -4.452246e+00 9.982885e-01 5.699060e-02 -1.312540e-02 1.073390e+01 +-2.071766e-02 5.943642e-02 -9.980171e-01 -1.911562e+02 -5.793056e-02 9.964828e-01 6.054763e-02 -4.399103e+00 9.981057e-01 5.907009e-02 -1.720161e-02 1.071114e+01 +-2.360947e-02 6.026417e-02 -9.979032e-01 -1.920679e+02 -5.980735e-02 9.963085e-01 6.158287e-02 -4.345411e+00 9.979307e-01 6.113588e-02 -1.991808e-02 1.068535e+01 +-2.550640e-02 6.166065e-02 -9.977712e-01 -1.929869e+02 -5.907277e-02 9.962588e-01 6.307731e-02 -4.289628e+00 9.979278e-01 6.054998e-02 -2.176851e-02 1.066332e+01 +-2.717903e-02 6.362537e-02 -9.976037e-01 -1.938968e+02 -5.590118e-02 9.963139e-01 6.506611e-02 -4.234421e+00 9.980663e-01 5.753565e-02 -2.352211e-02 1.064111e+01 +-2.850303e-02 6.420524e-02 -9.975296e-01 -1.948035e+02 -5.441767e-02 9.963555e-01 6.568459e-02 -4.179889e+00 9.981114e-01 5.615544e-02 -2.490524e-02 1.061677e+01 +-2.952181e-02 6.349612e-02 -9.975453e-01 -1.957061e+02 -5.446102e-02 9.963957e-01 6.503470e-02 -4.125617e+00 9.980794e-01 5.624727e-02 -2.595734e-02 1.058591e+01 +-3.031412e-02 6.220597e-02 -9.976028e-01 -1.966085e+02 -5.593546e-02 9.963919e-01 6.383018e-02 -4.067261e+00 9.979741e-01 5.773632e-02 -2.672523e-02 1.055882e+01 +-3.030872e-02 6.154257e-02 -9.976442e-01 -1.975097e+02 -5.995682e-02 9.961935e-01 6.327460e-02 -4.011638e+00 9.977408e-01 6.173334e-02 -2.650345e-02 1.052513e+01 +-2.954154e-02 5.959992e-02 -9.977851e-01 -1.984163e+02 -6.252220e-02 9.961559e-01 6.135373e-02 -3.956722e+00 9.976063e-01 6.419619e-02 -2.570166e-02 1.049574e+01 +-2.862473e-02 5.720988e-02 -9.979517e-01 -1.993224e+02 -6.314372e-02 9.962634e-01 5.892429e-02 -3.902813e+00 9.975939e-01 6.470107e-02 -2.490532e-02 1.046518e+01 +-2.808593e-02 5.428418e-02 -9.981304e-01 -2.002354e+02 -6.284353e-02 9.964532e-01 5.596130e-02 -3.849512e+00 9.976282e-01 6.429776e-02 -2.457490e-02 1.043745e+01 +-2.727411e-02 5.393665e-02 -9.981718e-01 -2.011527e+02 -6.284268e-02 9.964756e-01 5.556213e-02 -3.794847e+00 9.976507e-01 6.424319e-02 -2.378846e-02 1.041203e+01 +-2.673599e-02 5.624753e-02 -9.980588e-01 -2.020796e+02 -6.105064e-02 9.964601e-01 5.779287e-02 -3.740004e+00 9.977766e-01 6.247727e-02 -2.320740e-02 1.038822e+01 +-2.676068e-02 5.871183e-02 -9.979162e-01 -2.030142e+02 -6.044114e-02 9.963523e-01 6.024065e-02 -3.685828e+00 9.978130e-01 6.192726e-02 -2.311445e-02 1.036421e+01 +-2.581602e-02 5.576046e-02 -9.981104e-01 -2.039467e+02 -5.600544e-02 9.967943e-01 5.713553e-02 -3.633391e+00 9.980967e-01 5.737461e-02 -2.261037e-02 1.034146e+01 +-2.598609e-02 5.076943e-02 -9.983723e-01 -2.048858e+02 -5.313935e-02 9.972273e-01 5.209436e-02 -3.579058e+00 9.982490e-01 5.440657e-02 -2.321619e-02 1.033104e+01 +-2.543751e-02 5.176775e-02 -9.983351e-01 -2.058363e+02 -5.703048e-02 9.969567e-01 5.314942e-02 -3.519027e+00 9.980484e-01 5.828751e-02 -2.240775e-02 1.031186e+01 +-2.400580e-02 5.515810e-02 -9.981890e-01 -2.068023e+02 -5.944467e-02 9.966312e-01 5.650165e-02 -3.467731e+00 9.979429e-01 6.069337e-02 -2.064607e-02 1.029835e+01 +-2.205886e-02 5.575481e-02 -9.982008e-01 -2.077650e+02 -5.744562e-02 9.967234e-01 5.694177e-02 -3.412268e+00 9.981049e-01 5.859833e-02 -1.878371e-02 1.028253e+01 +-1.981783e-02 5.610649e-02 -9.982281e-01 -2.087622e+02 -5.541393e-02 9.968278e-01 5.712793e-02 -3.338453e+00 9.982668e-01 5.644788e-02 -1.664589e-02 1.031292e+01 +-1.806830e-02 6.090254e-02 -9.979802e-01 -2.097571e+02 -5.684079e-02 9.964662e-01 6.183926e-02 -3.273747e+00 9.982198e-01 5.784331e-02 -1.454270e-02 1.031768e+01 +-1.624532e-02 6.533164e-02 -9.977313e-01 -2.107676e+02 -5.371660e-02 9.963649e-01 6.611681e-02 -3.197320e+00 9.984241e-01 5.466882e-02 -1.267687e-02 1.033685e+01 +-1.496581e-02 6.622398e-02 -9.976925e-01 -2.117729e+02 -5.272617e-02 9.963637e-01 6.692671e-02 -3.123933e+00 9.984969e-01 5.360611e-02 -1.141965e-02 1.034507e+01 +-1.284947e-02 6.656123e-02 -9.976996e-01 -2.128048e+02 -5.556820e-02 9.961925e-01 6.717637e-02 -3.064476e+00 9.983722e-01 5.630355e-02 -9.101856e-03 1.036107e+01 +-9.866479e-03 6.819971e-02 -9.976229e-01 -2.138494e+02 -5.855223e-02 9.959202e-01 6.866241e-02 -3.016552e+00 9.982356e-01 5.909049e-02 -5.832979e-03 1.037602e+01 +-6.263305e-03 6.894493e-02 -9.976008e-01 -2.149023e+02 -5.979030e-02 9.958097e-01 6.919655e-02 -2.966109e+00 9.981913e-01 6.008024e-02 -2.114820e-03 1.039647e+01 +-3.122797e-03 6.658013e-02 -9.977762e-01 -2.159302e+02 -6.273852e-02 9.958023e-01 6.664479e-02 -2.904648e+00 9.980251e-01 6.280711e-02 1.067452e-03 1.039643e+01 +-2.476161e-04 6.347817e-02 -9.979832e-01 -2.169299e+02 -6.264984e-02 9.960217e-01 6.336897e-02 -2.834208e+00 9.980356e-01 6.253917e-02 3.730268e-03 1.037534e+01 +1.435434e-03 6.204185e-02 -9.980725e-01 -2.179558e+02 -6.171973e-02 9.961762e-01 6.183522e-02 -2.773949e+00 9.980925e-01 6.151199e-02 5.259153e-03 1.036291e+01 +3.055629e-03 6.426151e-02 -9.979284e-01 -2.190129e+02 -6.213066e-02 9.960172e-01 6.394822e-02 -2.720097e+00 9.980634e-01 6.180654e-02 7.036072e-03 1.036059e+01 +4.243336e-03 6.756078e-02 -9.977061e-01 -2.200584e+02 -6.432724e-02 9.956671e-01 6.714913e-02 -2.663629e+00 9.979199e-01 6.389473e-02 8.570951e-03 1.034511e+01 +5.642486e-03 6.782326e-02 -9.976814e-01 -2.211045e+02 -6.469412e-02 9.956319e-01 6.731806e-02 -2.618251e+00 9.978892e-01 6.416427e-02 1.000561e-02 1.032094e+01 +6.431035e-03 6.461696e-02 -9.978894e-01 -2.221551e+02 -6.343982e-02 9.959262e-01 6.408100e-02 -2.575045e+00 9.979650e-01 6.289381e-02 1.050413e-02 1.029838e+01 +6.647617e-03 6.194418e-02 -9.980575e-01 -2.232157e+02 -6.072482e-02 9.962625e-01 6.142833e-02 -2.522336e+00 9.981324e-01 6.019850e-02 1.038432e-02 1.028870e+01 +6.438027e-03 6.049971e-02 -9.981474e-01 -2.242839e+02 -5.860416e-02 9.964753e-01 6.002038e-02 -2.503990e+00 9.982606e-01 5.810917e-02 9.960872e-03 1.026292e+01 +6.611958e-03 5.975639e-02 -9.981911e-01 -2.253655e+02 -5.926640e-02 9.964816e-01 5.926149e-02 -2.464362e+00 9.982203e-01 5.876735e-02 1.013024e-02 1.024681e+01 +6.920264e-03 5.938003e-02 -9.982114e-01 -2.264719e+02 -5.864734e-02 9.965412e-01 5.887410e-02 -2.433694e+00 9.982548e-01 5.813502e-02 1.037881e-02 1.022636e+01 +6.693245e-03 6.109942e-02 -9.981092e-01 -2.275849e+02 -6.131984e-02 9.962783e-01 6.057615e-02 -2.392587e+00 9.980958e-01 6.079844e-02 1.041494e-02 1.020920e+01 +6.341156e-03 6.284007e-02 -9.980034e-01 -2.287073e+02 -6.220976e-02 9.961151e-01 6.232591e-02 -2.381919e+00 9.980430e-01 6.169033e-02 1.022579e-02 1.021551e+01 +5.666549e-03 6.448234e-02 -9.979027e-01 -2.298327e+02 -6.261962e-02 9.959831e-01 6.400273e-02 -2.353650e+00 9.980214e-01 6.212561e-02 9.681649e-03 1.021951e+01 +5.054909e-03 6.596283e-02 -9.978093e-01 -2.309676e+02 -6.328017e-02 9.958432e-01 6.551230e-02 -2.317504e+00 9.979830e-01 6.281038e-02 9.208039e-03 1.022162e+01 +4.283764e-03 6.783194e-02 -9.976875e-01 -2.321123e+02 -6.555862e-02 9.955694e-01 6.740645e-02 -2.281065e+00 9.978396e-01 6.511826e-02 8.711754e-03 1.022095e+01 +3.069931e-03 6.660715e-02 -9.977745e-01 -2.332586e+02 -6.807365e-02 9.954786e-01 6.624445e-02 -2.235976e+00 9.976756e-01 6.771878e-02 7.590245e-03 1.021704e+01 +2.076201e-03 6.231871e-02 -9.980541e-01 -2.344084e+02 -6.666603e-02 9.958446e-01 6.204207e-02 -2.193086e+00 9.977732e-01 6.640748e-02 6.222117e-03 1.021654e+01 +6.768305e-04 5.571284e-02 -9.984466e-01 -2.355643e+02 -6.366571e-02 9.964236e-01 5.555682e-02 -2.147001e+00 9.979711e-01 6.352920e-02 4.221410e-03 1.021494e+01 +-1.206254e-03 5.111888e-02 -9.986918e-01 -2.367346e+02 -5.888789e-02 9.969558e-01 5.110115e-02 -2.104069e+00 9.982639e-01 5.887249e-02 1.807703e-03 1.021939e+01 +-3.327886e-03 5.079804e-02 -9.987034e-01 -2.379134e+02 -5.275793e-02 9.973091e-01 5.090294e-02 -2.057775e+00 9.986018e-01 5.285892e-02 -6.389298e-04 1.021978e+01 +-5.548409e-03 5.509928e-02 -9.984654e-01 -2.391043e+02 -4.796967e-02 9.973166e-01 5.530246e-02 -2.013195e+00 9.988334e-01 4.820289e-02 -2.890425e-03 1.021773e+01 +-7.581156e-03 5.765249e-02 -9.983079e-01 -2.402958e+02 -4.573875e-02 9.972717e-01 5.794001e-02 -1.961591e+00 9.989247e-01 4.610060e-02 -4.923517e-03 1.020644e+01 +-9.693913e-03 5.693296e-02 -9.983309e-01 -2.414949e+02 -4.366559e-02 9.974014e-01 5.730396e-02 -1.906501e+00 9.989992e-01 4.414820e-02 -7.182710e-03 1.019688e+01 +-1.200061e-02 5.714243e-02 -9.982939e-01 -2.427027e+02 -4.379389e-02 9.973778e-01 5.761646e-02 -1.850854e+00 9.989685e-01 4.441060e-02 -9.466654e-03 1.018339e+01 +-1.405742e-02 5.883774e-02 -9.981686e-01 -2.439116e+02 -4.296040e-02 9.973098e-01 5.939216e-02 -1.799394e+00 9.989779e-01 4.371661e-02 -1.149191e-02 1.016958e+01 +-1.630846e-02 5.897401e-02 -9.981263e-01 -2.451254e+02 -4.195777e-02 9.973393e-01 5.961308e-02 -1.747591e+00 9.989863e-01 4.285135e-02 -1.379065e-02 1.015370e+01 +-1.855639e-02 5.746432e-02 -9.981751e-01 -2.463473e+02 -4.191581e-02 9.974246e-01 5.820036e-02 -1.691926e+00 9.989488e-01 4.291930e-02 -1.609993e-02 1.013022e+01 +-2.066257e-02 5.691441e-02 -9.981652e-01 -2.475719e+02 -4.158237e-02 9.974655e-01 5.773531e-02 -1.634409e+00 9.989214e-01 4.269903e-02 -1.824356e-02 1.010415e+01 +-2.310361e-02 5.796503e-02 -9.980512e-01 -2.488105e+02 -4.213026e-02 9.973744e-01 5.890100e-02 -1.573711e+00 9.988450e-01 4.340898e-02 -2.060087e-02 1.007064e+01 +-2.530633e-02 5.859978e-02 -9.979607e-01 -2.500528e+02 -4.252548e-02 9.973137e-01 5.964017e-02 -1.513495e+00 9.987749e-01 4.394803e-02 -2.274637e-02 1.003680e+01 +-2.776737e-02 5.930840e-02 -9.978534e-01 -2.512993e+02 -4.376276e-02 9.972091e-01 6.048791e-02 -1.451596e+00 9.986560e-01 4.534841e-02 -2.509438e-02 9.995560e+00 +-3.015200e-02 6.112452e-02 -9.976746e-01 -2.525378e+02 -4.543485e-02 9.970129e-01 6.245714e-02 -1.393398e+00 9.985122e-01 4.721239e-02 -2.728475e-02 9.939396e+00 +-3.174601e-02 6.173293e-02 -9.975877e-01 -2.537738e+02 -4.703529e-02 9.968927e-01 6.318673e-02 -1.327249e+00 9.983887e-01 4.892775e-02 -2.874374e-02 9.880518e+00 +-3.278375e-02 6.249175e-02 -9.975069e-01 -2.550283e+02 -4.969858e-02 9.967068e-01 6.407502e-02 -1.262747e+00 9.982261e-01 5.167529e-02 -2.957003e-02 9.822378e+00 +-3.272559e-02 6.297471e-02 -9.974784e-01 -2.562862e+02 -5.074166e-02 9.966213e-01 6.458536e-02 -1.203572e+00 9.981755e-01 5.272730e-02 -2.941958e-02 9.772827e+00 +-3.273539e-02 6.171208e-02 -9.975570e-01 -2.575351e+02 -4.959263e-02 9.967622e-01 6.329034e-02 -1.140329e+00 9.982330e-01 5.154330e-02 -2.956894e-02 9.718989e+00 +-3.264861e-02 5.994137e-02 -9.976678e-01 -2.587805e+02 -4.654600e-02 9.970257e-01 6.142602e-02 -1.073678e+00 9.983825e-01 4.844292e-02 -2.976147e-02 9.669636e+00 +-3.272390e-02 6.020464e-02 -9.976495e-01 -2.600378e+02 -4.600837e-02 9.970352e-01 6.167671e-02 -1.009453e+00 9.984049e-01 4.791852e-02 -2.985696e-02 9.628883e+00 +-3.281900e-02 6.105007e-02 -9.975950e-01 -2.613005e+02 -4.576014e-02 9.969942e-01 6.251874e-02 -9.527103e-01 9.984132e-01 4.770189e-02 -2.992669e-02 9.591512e+00 +-3.251487e-02 6.094674e-02 -9.976113e-01 -2.625570e+02 -4.497006e-02 9.970390e-01 6.237749e-02 -9.090161e-01 9.984591e-01 4.689083e-02 -2.967781e-02 9.547024e+00 +-3.201777e-02 6.143857e-02 -9.975972e-01 -2.638110e+02 -4.462419e-02 9.970257e-01 6.283560e-02 -8.653600e-01 9.984907e-01 4.652881e-02 -2.918089e-02 9.503110e+00 +-3.182472e-02 6.305955e-02 -9.975022e-01 -2.650590e+02 -4.233198e-02 9.970272e-01 6.438011e-02 -8.158997e-01 9.985966e-01 4.427511e-02 -2.906067e-02 9.459547e+00 +-3.200027e-02 6.500253e-02 -9.973719e-01 -2.663195e+02 -3.761712e-02 9.970976e-01 6.619160e-02 -7.640980e-01 9.987798e-01 3.963640e-02 -2.946219e-02 9.421874e+00 +-3.189689e-02 6.852819e-02 -9.971391e-01 -2.675739e+02 -3.453335e-02 9.969755e-01 6.962163e-02 -7.054812e-01 9.988944e-01 3.665527e-02 -2.943391e-02 9.379979e+00 +-3.173985e-02 7.090867e-02 -9.969777e-01 -2.688269e+02 -3.244044e-02 9.968816e-01 7.193463e-02 -6.454916e-01 9.989696e-01 3.462559e-02 -2.934057e-02 9.337703e+00 +-3.173281e-02 6.985924e-02 -9.970520e-01 -2.700659e+02 -3.265993e-02 9.969492e-01 7.089151e-02 -5.809950e-01 9.989627e-01 3.481323e-02 -2.935440e-02 9.290325e+00 +-3.171938e-02 6.768685e-02 -9.972023e-01 -2.713042e+02 -3.457768e-02 9.970327e-01 6.877522e-02 -5.162337e-01 9.988986e-01 3.666244e-02 -2.928481e-02 9.241239e+00 +-3.222694e-02 7.023825e-02 -9.970095e-01 -2.725496e+02 -4.009846e-02 9.966337e-01 7.150792e-02 -4.515802e-01 9.986759e-01 4.228303e-02 -2.930201e-02 9.176257e+00 +-3.250460e-02 7.689134e-02 -9.965095e-01 -2.737988e+02 -4.606260e-02 9.958617e-01 7.834386e-02 -3.874985e-01 9.984096e-01 4.844835e-02 -2.882827e-02 9.103787e+00 +-3.255513e-02 7.711603e-02 -9.964905e-01 -2.750361e+02 -5.041520e-02 9.956230e-01 7.869598e-02 -3.169753e-01 9.981976e-01 5.280022e-02 -2.852482e-02 9.036666e+00 +-3.233841e-02 7.006898e-02 -9.970178e-01 -2.762637e+02 -5.023423e-02 9.961649e-01 7.163840e-02 -2.467918e-01 9.982138e-01 5.240109e-02 -2.869452e-02 8.976101e+00 +-3.289738e-02 6.421271e-02 -9.973938e-01 -2.774844e+02 -4.727821e-02 9.967169e-01 6.572853e-02 -1.669578e-01 9.983399e-01 4.931728e-02 -2.975351e-02 8.919687e+00 +-3.305437e-02 6.328081e-02 -9.974482e-01 -2.787106e+02 -4.193883e-02 9.970267e-01 6.464390e-02 -8.454746e-02 9.985733e-01 4.396857e-02 -3.030216e-02 8.872822e+00 +-3.208162e-02 6.503364e-02 -9.973672e-01 -2.799472e+02 -3.841457e-02 9.970633e-01 6.624950e-02 -3.192001e-03 9.987468e-01 4.043882e-02 -2.948917e-02 8.832825e+00 +-3.040375e-02 6.672305e-02 -9.973082e-01 -2.811799e+02 -3.739511e-02 9.969950e-01 6.784214e-02 7.274121e-02 9.988380e-01 3.935710e-02 -2.781727e-02 8.789754e+00 +-2.933702e-02 6.913143e-02 -9.971761e-01 -2.824183e+02 -3.860088e-02 9.967830e-01 7.023983e-02 1.571976e-01 9.988240e-01 4.055250e-02 -2.657410e-02 8.753128e+00 +-2.848848e-02 7.102636e-02 -9.970675e-01 -2.836504e+02 -3.979895e-02 9.966008e-01 7.213028e-02 2.427808e-01 9.988015e-01 4.173712e-02 -2.556487e-02 8.715404e+00 +-2.772071e-02 7.181723e-02 -9.970325e-01 -2.848821e+02 -4.079344e-02 9.965036e-01 7.291334e-02 3.207171e-01 9.987830e-01 4.269359e-02 -2.469411e-02 8.682429e+00 +-2.692902e-02 7.176740e-02 -9.970578e-01 -2.861035e+02 -4.037772e-02 9.965274e-01 7.281978e-02 3.940960e-01 9.988216e-01 4.221988e-02 -2.393771e-02 8.646228e+00 +-2.678289e-02 6.977560e-02 -9.972031e-01 -2.873229e+02 -4.075289e-02 9.966554e-01 7.083183e-02 4.664034e-01 9.988103e-01 4.253598e-02 -2.384976e-02 8.610515e+00 +-2.650175e-02 6.860617e-02 -9.972917e-01 -2.885424e+02 -4.051950e-02 9.967485e-01 6.964557e-02 5.369466e-01 9.988273e-01 4.225549e-02 -2.363569e-02 8.572727e+00 +-2.646512e-02 6.812184e-02 -9.973259e-01 -2.897636e+02 -4.104675e-02 9.967599e-01 6.917242e-02 6.090076e-01 9.988067e-01 4.276764e-02 -2.358319e-02 8.538765e+00 +-2.614545e-02 6.790538e-02 -9.973491e-01 -2.909884e+02 -4.168390e-02 9.967484e-01 6.895724e-02 6.817957e-01 9.987887e-01 4.337631e-02 -2.322987e-02 8.505150e+00 +-2.596978e-02 6.842443e-02 -9.973182e-01 -2.922095e+02 -4.229928e-02 9.966860e-01 6.948252e-02 7.537895e-01 9.987674e-01 4.399029e-02 -2.298941e-02 8.467495e+00 +-2.574115e-02 6.877742e-02 -9.972999e-01 -2.934329e+02 -4.158118e-02 9.966934e-01 6.980886e-02 8.251983e-01 9.988035e-01 4.326586e-02 -2.279619e-02 8.432741e+00 +-2.563301e-02 6.729475e-02 -9.974038e-01 -2.946547e+02 -4.127126e-02 9.968097e-01 6.831535e-02 8.953778e-01 9.988192e-01 4.291524e-02 -2.277389e-02 8.394904e+00 +-2.580736e-02 6.433839e-02 -9.975944e-01 -2.959050e+02 -4.084530e-02 9.970255e-01 6.535837e-02 9.937322e-01 9.988322e-01 4.243377e-02 -2.310268e-02 8.360706e+00 +-2.620977e-02 6.156181e-02 -9.977591e-01 -2.970928e+02 -4.186842e-02 9.971585e-01 6.262460e-02 1.083163e+00 9.987793e-01 4.341597e-02 -2.355780e-02 8.327719e+00 +-2.637804e-02 6.015869e-02 -9.978402e-01 -2.983204e+02 -4.331550e-02 9.971812e-01 6.126403e-02 1.178547e+00 9.987132e-01 4.483797e-02 -2.369788e-02 8.294475e+00 +-2.676094e-02 6.036692e-02 -9.978174e-01 -2.995507e+02 -4.646517e-02 9.970209e-01 6.156492e-02 1.268367e+00 9.985614e-01 4.801128e-02 -2.387625e-02 8.253446e+00 +-2.727546e-02 6.160606e-02 -9.977278e-01 -3.007835e+02 -4.970164e-02 9.967811e-01 6.290634e-02 1.348203e+00 9.983916e-01 5.130451e-02 -2.412573e-02 8.212884e+00 +-2.759659e-02 6.268585e-02 -9.976517e-01 -3.020130e+02 -5.325990e-02 9.965220e-01 6.408814e-02 1.421779e+00 9.981993e-01 5.490344e-02 -2.416196e-02 8.169718e+00 +-2.800207e-02 6.302884e-02 -9.976188e-01 -3.032550e+02 -5.503168e-02 9.963994e-01 6.449649e-02 1.498626e+00 9.980919e-01 5.670667e-02 -2.443266e-02 8.135973e+00 +-2.835833e-02 6.110574e-02 -9.977284e-01 -3.044989e+02 -5.488412e-02 9.965289e-01 6.259226e-02 1.559814e+00 9.980900e-01 5.653444e-02 -2.490616e-02 8.103441e+00 +-2.884320e-02 5.871284e-02 -9.978581e-01 -3.057462e+02 -5.276146e-02 9.967924e-01 6.017523e-02 1.614957e+00 9.981905e-01 5.438409e-02 -2.565290e-02 8.074212e+00 +-2.962474e-02 5.813253e-02 -9.978692e-01 -3.069958e+02 -4.967080e-02 9.969884e-01 5.955586e-02 1.652575e+00 9.983262e-01 5.132929e-02 -2.664803e-02 8.046454e+00 +-3.045324e-02 6.043833e-02 -9.977073e-01 -3.082465e+02 -4.755653e-02 9.969522e-01 6.184418e-02 1.684706e+00 9.984042e-01 4.933085e-02 -2.748619e-02 8.015343e+00 +-3.113285e-02 6.215381e-02 -9.975809e-01 -3.094945e+02 -4.622872e-02 9.969071e-01 6.355457e-02 1.710544e+00 9.984457e-01 4.809552e-02 -2.816326e-02 7.982975e+00 +-3.168158e-02 6.116447e-02 -9.976248e-01 -3.107342e+02 -4.689872e-02 9.969354e-01 6.261159e-02 1.749365e+00 9.983971e-01 4.877095e-02 -2.871596e-02 7.941655e+00 +-3.168712e-02 5.963393e-02 -9.977172e-01 -3.119784e+02 -4.825898e-02 9.969630e-01 6.112155e-02 1.770563e+00 9.983321e-01 5.008558e-02 -2.871301e-02 7.903865e+00 +-3.107324e-02 5.915506e-02 -9.977651e-01 -3.132202e+02 -4.864529e-02 9.969746e-01 6.062317e-02 1.803426e+00 9.983327e-01 5.042032e-02 -2.810162e-02 7.863686e+00 +-3.005658e-02 5.925245e-02 -9.977904e-01 -3.144806e+02 -4.682718e-02 9.970619e-01 6.061978e-02 1.814808e+00 9.984507e-01 4.854573e-02 -2.719364e-02 7.839842e+00 +-2.956676e-02 5.975092e-02 -9.977753e-01 -3.157338e+02 -4.407776e-02 9.971628e-01 6.102039e-02 1.843363e+00 9.985905e-01 4.578387e-02 -2.684918e-02 7.810147e+00 +-2.911146e-02 6.085295e-02 -9.977221e-01 -3.169895e+02 -4.070155e-02 9.972452e-01 6.201146e-02 1.871300e+00 9.987472e-01 4.241408e-02 -2.655445e-02 7.782544e+00 +-2.869899e-02 6.139112e-02 -9.977011e-01 -3.182417e+02 -3.866313e-02 9.972971e-01 6.247843e-02 1.909514e+00 9.988401e-01 4.036731e-02 -2.624784e-02 7.749923e+00 +-2.811788e-02 6.152348e-02 -9.977095e-01 -3.195411e+02 -3.772234e-02 9.973278e-01 6.256307e-02 1.948822e+00 9.988926e-01 3.939507e-02 -2.572194e-02 7.715753e+00 +-2.755655e-02 6.075543e-02 -9.977722e-01 -3.207540e+02 -3.766486e-02 9.973793e-01 6.177175e-02 1.992466e+00 9.989104e-01 3.928316e-02 -2.519599e-02 7.679468e+00 +-2.653710e-02 6.154189e-02 -9.977516e-01 -3.220062e+02 -3.894568e-02 9.972817e-01 6.254875e-02 2.035460e+00 9.988889e-01 4.051798e-02 -2.406818e-02 7.640517e+00 +-2.512402e-02 6.367468e-02 -9.976544e-01 -3.232694e+02 -4.133446e-02 9.970498e-01 6.467704e-02 2.075673e+00 9.988295e-01 4.286245e-02 -2.241794e-02 7.601752e+00 +-2.337374e-02 6.461530e-02 -9.976365e-01 -3.245295e+02 -4.321692e-02 9.969109e-01 6.558086e-02 2.124559e+00 9.987923e-01 4.464764e-02 -2.050906e-02 7.563218e+00 +-2.159921e-02 6.540038e-02 -9.976253e-01 -3.257958e+02 -4.596549e-02 9.967379e-01 6.633741e-02 2.174114e+00 9.987095e-01 4.728917e-02 -1.852259e-02 7.527011e+00 +-2.009285e-02 6.770272e-02 -9.975032e-01 -3.270580e+02 -4.842929e-02 9.964675e-01 6.860796e-02 2.230412e+00 9.986245e-01 4.968690e-02 -1.674308e-02 7.490522e+00 +-1.949763e-02 7.156876e-02 -9.972451e-01 -3.283440e+02 -5.060932e-02 9.960853e-01 7.247504e-02 2.289367e+00 9.985282e-01 5.188298e-02 -1.579926e-02 7.456111e+00 +-1.938000e-02 7.506189e-02 -9.969905e-01 -3.295868e+02 -5.296714e-02 9.957004e-01 7.599438e-02 2.354188e+00 9.984082e-01 5.428050e-02 -1.532086e-02 7.421332e+00 +-1.952377e-02 7.676175e-02 -9.968583e-01 -3.308478e+02 -5.666134e-02 9.953609e-01 7.775620e-02 2.422264e+00 9.982026e-01 5.800141e-02 -1.508378e-02 7.384904e+00 +-1.946960e-02 7.847659e-02 -9.967258e-01 -3.321097e+02 -6.187649e-02 9.949092e-01 7.954225e-02 2.493332e+00 9.978939e-01 6.322254e-02 -1.451463e-02 7.347334e+00 +-1.967631e-02 7.883558e-02 -9.966934e-01 -3.333691e+02 -6.660284e-02 9.945687e-01 7.998238e-02 2.564801e+00 9.975856e-01 6.795636e-02 -1.431876e-02 7.309602e+00 +-1.964321e-02 7.298695e-02 -9.971394e-01 -3.346162e+02 -6.774316e-02 9.949427e-01 7.416069e-02 2.635203e+00 9.975094e-01 6.900612e-02 -1.459950e-02 7.274746e+00 +-1.966195e-02 6.590137e-02 -9.976324e-01 -3.358601e+02 -6.786588e-02 9.954359e-01 6.709383e-02 2.701429e+00 9.975007e-01 6.902438e-02 -1.509975e-02 7.242255e+00 +-2.030337e-02 6.478199e-02 -9.976929e-01 -3.371117e+02 -6.925651e-02 9.954104e-01 6.604320e-02 2.764273e+00 9.973923e-01 7.043761e-02 -1.572360e-02 7.208515e+00 +-2.027404e-02 6.872379e-02 -9.974297e-01 -3.383651e+02 -6.839717e-02 9.952021e-01 6.996059e-02 2.823993e+00 9.974522e-01 6.963975e-02 -1.547626e-02 7.178709e+00 +-2.007416e-02 6.857751e-02 -9.974438e-01 -3.396088e+02 -6.863251e-02 9.951969e-01 6.980432e-02 2.887212e+00 9.974401e-01 6.985833e-02 -1.527109e-02 7.147781e+00 +-2.005292e-02 7.091378e-02 -9.972808e-01 -3.408481e+02 -6.885916e-02 9.950149e-01 7.213727e-02 2.953515e+00 9.974249e-01 7.011848e-02 -1.506989e-02 7.114792e+00 +-2.028125e-02 7.457794e-02 -9.970089e-01 -3.420844e+02 -6.835859e-02 9.947769e-01 7.580156e-02 3.018259e+00 9.974547e-01 6.969146e-02 -1.507727e-02 7.084257e+00 +-2.038563e-02 7.646260e-02 -9.968640e-01 -3.433093e+02 -6.728850e-02 9.947055e-01 7.767309e-02 3.085784e+00 9.975253e-01 6.866089e-02 -1.513264e-02 7.053936e+00 +-2.064655e-02 7.706925e-02 -9.968119e-01 -3.445226e+02 -6.788182e-02 9.946156e-01 7.830547e-02 3.152380e+00 9.974797e-01 6.928214e-02 -1.530378e-02 7.024157e+00 +-2.079699e-02 7.536330e-02 -9.969392e-01 -3.457214e+02 -6.918224e-02 9.946562e-01 7.663394e-02 3.218274e+00 9.973873e-01 7.056423e-02 -1.547205e-02 6.991297e+00 +-2.090183e-02 7.260566e-02 -9.971417e-01 -3.469075e+02 -7.107707e-02 9.947280e-01 7.391983e-02 3.282478e+00 9.972518e-01 7.241895e-02 -1.563103e-02 6.957315e+00 +-2.102092e-02 7.264555e-02 -9.971363e-01 -3.480809e+02 -7.177611e-02 9.946734e-01 7.397928e-02 3.346166e+00 9.971993e-01 7.312566e-02 -1.569473e-02 6.923481e+00 +-2.106488e-02 7.543295e-02 -9.969283e-01 -3.492403e+02 -7.192196e-02 9.944517e-01 7.676527e-02 3.409140e+00 9.971878e-01 7.331808e-02 -1.552272e-02 6.891245e+00 +-2.137684e-02 7.832324e-02 -9.966988e-01 -3.503846e+02 -7.052768e-02 9.943248e-01 7.964936e-02 3.472552e+00 9.972808e-01 7.199750e-02 -1.573156e-02 6.860419e+00 +-2.160331e-02 8.062910e-02 -9.965100e-01 -3.515102e+02 -6.789420e-02 9.943233e-01 8.192407e-02 3.538555e+00 9.974586e-01 6.942708e-02 -1.600643e-02 6.832352e+00 +-2.209795e-02 8.358191e-02 -9.962558e-01 -3.526175e+02 -6.779329e-02 9.940802e-01 8.490313e-02 3.606496e+00 9.974547e-01 6.941563e-02 -1.630085e-02 6.801164e+00 +-2.279915e-02 8.613727e-02 -9.960224e-01 -3.537084e+02 -6.759733e-02 9.938685e-01 8.749834e-02 3.674715e+00 9.974522e-01 6.932333e-02 -1.683670e-02 6.768393e+00 +-2.348515e-02 8.148148e-02 -9.963981e-01 -3.547819e+02 -6.739739e-02 9.942765e-01 8.289656e-02 3.739229e+00 9.974498e-01 6.910146e-02 -1.785909e-02 6.735903e+00 +-2.414574e-02 7.019947e-02 -9.972407e-01 -3.558341e+02 -6.822755e-02 9.950900e-01 7.170006e-02 3.799447e+00 9.973776e-01 6.977053e-02 -1.923764e-02 6.699937e+00 +-2.490286e-02 5.838376e-02 -9.979835e-01 -3.568778e+02 -6.979236e-02 9.957558e-01 5.999498e-02 3.853828e+00 9.972507e-01 7.114567e-02 -2.072243e-02 6.663296e+00 +-2.572759e-02 5.306213e-02 -9.982597e-01 -3.579186e+02 -7.009316e-02 9.960368e-01 5.475045e-02 3.900970e+00 9.972087e-01 7.137976e-02 -2.190633e-02 6.626785e+00 +-2.644441e-02 5.654159e-02 -9.980500e-01 -3.589634e+02 -7.088646e-02 9.957797e-01 5.829120e-02 3.945285e+00 9.971338e-01 7.228969e-02 -2.232477e-02 6.589618e+00 +-2.703587e-02 6.338835e-02 -9.976226e-01 -3.600012e+02 -7.067588e-02 9.953688e-01 6.516049e-02 3.992163e+00 9.971329e-01 7.226952e-02 -2.243063e-02 6.552425e+00 +-2.771723e-02 6.917337e-02 -9.972195e-01 -3.610331e+02 -7.130589e-02 9.949246e-01 7.099611e-02 4.041676e+00 9.970694e-01 7.307544e-02 -2.264408e-02 6.515324e+00 +-2.778594e-02 7.219376e-02 -9.970035e-01 -3.620458e+02 -7.238570e-02 9.946248e-01 7.403888e-02 4.096755e+00 9.969896e-01 7.422603e-02 -2.241079e-02 6.476905e+00 +-2.750753e-02 7.457671e-02 -9.968358e-01 -3.630410e+02 -7.629443e-02 9.941478e-01 7.648096e-02 4.153749e+00 9.967059e-01 7.815681e-02 -2.165676e-02 6.435692e+00 +-2.628582e-02 7.584892e-02 -9.967728e-01 -3.640152e+02 -8.000680e-02 9.937590e-01 7.772946e-02 4.207344e+00 9.964477e-01 8.179177e-02 -2.005334e-02 6.395532e+00 +-2.433159e-02 7.500320e-02 -9.968864e-01 -3.649490e+02 -8.305427e-02 9.935827e-01 7.678181e-02 4.261365e+00 9.962480e-01 8.466389e-02 -1.794611e-02 6.367778e+00 +-2.107271e-02 7.233164e-02 -9.971580e-01 -3.658558e+02 -8.519224e-02 9.936220e-01 7.387551e-02 4.315120e+00 9.961417e-01 8.650687e-02 -1.477621e-02 6.345080e+00 +-1.705816e-02 6.941638e-02 -9.974419e-01 -3.667422e+02 -8.689500e-02 9.937096e-01 7.064272e-02 4.363637e+00 9.960715e-01 8.787774e-02 -1.091892e-02 6.324926e+00 +-1.146986e-02 6.643625e-02 -9.977247e-01 -3.676006e+02 -8.653565e-02 9.939810e-01 6.718179e-02 4.406994e+00 9.961828e-01 8.710931e-02 -5.651714e-03 6.314964e+00 +-3.491961e-03 6.380231e-02 -9.979564e-01 -3.684376e+02 -8.749569e-02 9.941157e-01 6.386293e-02 4.446554e+00 9.961588e-01 8.753989e-02 2.111016e-03 6.307072e+00 +9.314142e-03 6.068268e-02 -9.981136e-01 -3.692451e+02 -8.725064e-02 9.943993e-01 5.964267e-02 4.481263e+00 9.961429e-01 8.653052e-02 1.455658e-02 6.316497e+00 +2.641610e-02 5.964180e-02 -9.978702e-01 -3.700263e+02 -8.726248e-02 9.945456e-01 5.713305e-02 4.512707e+00 9.958351e-01 8.556738e-02 3.147651e-02 6.334382e+00 +4.821799e-02 5.959483e-02 -9.970574e-01 -3.707814e+02 -8.534990e-02 9.948133e-01 5.533317e-02 4.539282e+00 9.951836e-01 8.243069e-02 5.305432e-02 6.383962e+00 +7.362703e-02 6.079903e-02 -9.954308e-01 -3.715060e+02 -8.186760e-02 9.951395e-01 5.472591e-02 4.563734e+00 9.939199e-01 7.746421e-02 7.824665e-02 6.454801e+00 +1.018188e-01 6.246572e-02 -9.928398e-01 -3.721935e+02 -7.873386e-02 9.954019e-01 5.455253e-02 4.587790e+00 9.916824e-01 7.261563e-02 1.062688e-01 6.534681e+00 +1.329968e-01 6.530915e-02 -9.889623e-01 -3.728659e+02 -7.574399e-02 9.955782e-01 5.555992e-02 4.611651e+00 9.882180e-01 6.751865e-02 1.373555e-01 6.648568e+00 +1.666235e-01 6.963385e-02 -9.835587e-01 -3.735016e+02 -7.253448e-02 9.956662e-01 5.820307e-02 4.637038e+00 9.833491e-01 6.164391e-02 1.709523e-01 6.767825e+00 +2.021033e-01 7.334323e-02 -9.766141e-01 -3.741256e+02 -6.806480e-02 9.958326e-01 6.070103e-02 4.660346e+00 9.769962e-01 5.420516e-02 2.062531e-01 6.927950e+00 +2.395036e-01 7.645407e-02 -9.678806e-01 -3.747250e+02 -6.478511e-02 9.959313e-01 6.263868e-02 4.682451e+00 9.687316e-01 4.770206e-02 2.434822e-01 7.109350e+00 +2.794165e-01 7.603009e-02 -9.571551e-01 -3.752804e+02 -6.187309e-02 9.962139e-01 6.107044e-02 4.706477e+00 9.581744e-01 4.215804e-02 2.830628e-01 7.290046e+00 +3.221675e-01 7.422777e-02 -9.437682e-01 -3.758441e+02 -6.049732e-02 9.964979e-01 5.772346e-02 4.729898e+00 9.447477e-01 3.849882e-02 3.255298e-01 7.519283e+00 +3.670445e-01 7.386301e-02 -9.272662e-01 -3.763632e+02 -6.064859e-02 9.966216e-01 5.538082e-02 4.755205e+00 9.282242e-01 3.591016e-02 3.702842e-01 7.741893e+00 +4.138310e-01 7.316333e-02 -9.074089e-01 -3.768948e+02 -5.961253e-02 9.968038e-01 5.318439e-02 4.778493e+00 9.083998e-01 3.208359e-02 4.168698e-01 8.025093e+00 +4.597730e-01 7.251484e-02 -8.850708e-01 -3.773754e+02 -5.879851e-02 9.969592e-01 5.113758e-02 4.802424e+00 8.860878e-01 2.852916e-02 4.626387e-01 8.299848e+00 +5.043440e-01 6.613710e-02 -8.609663e-01 -3.778624e+02 -5.209987e-02 9.975767e-01 4.611167e-02 4.816809e+00 8.619297e-01 2.160008e-02 5.065676e-01 8.633829e+00 +5.469220e-01 6.303045e-02 -8.348075e-01 -3.783339e+02 -5.349664e-02 9.977551e-01 4.028532e-02 4.832875e+00 8.354726e-01 2.262647e-02 5.490661e-01 8.982602e+00 +5.889115e-01 6.133090e-02 -8.058671e-01 -3.787601e+02 -5.304920e-02 9.978995e-01 3.717834e-02 4.851714e+00 8.064547e-01 2.085586e-02 5.909281e-01 9.318767e+00 +6.285576e-01 6.253977e-02 -7.752446e-01 -3.791963e+02 -5.312690e-02 9.978862e-01 3.742596e-02 4.871334e+00 7.759465e-01 1.766197e-02 6.305515e-01 9.712570e+00 +6.658382e-01 6.401742e-02 -7.433447e-01 -3.795861e+02 -5.079472e-02 9.978900e-01 4.044058e-02 4.890809e+00 7.443651e-01 1.083110e-02 6.676850e-01 1.009641e+01 +7.016591e-01 6.373121e-02 -7.096568e-01 -3.799898e+02 -4.736526e-02 9.979606e-01 4.279109e-02 4.905093e+00 7.109368e-01 3.588320e-03 7.032468e-01 1.054153e+01 +7.350916e-01 6.326349e-02 -6.750097e-01 -3.803487e+02 -4.806274e-02 9.979945e-01 4.119366e-02 4.918412e+00 6.762621e-01 2.161703e-03 7.366580e-01 1.096597e+01 +7.663637e-01 6.481427e-02 -6.391289e-01 -3.807241e+02 -5.138189e-02 9.978942e-01 3.958604e-02 4.935599e+00 6.403488e-01 2.502347e-03 7.680802e-01 1.144316e+01 +7.960608e-01 6.456767e-02 -6.017626e-01 -3.810804e+02 -5.219622e-02 9.979127e-01 3.802420e-02 4.952071e+00 6.029617e-01 1.140164e-03 7.977693e-01 1.194649e+01 +8.230969e-01 5.764546e-02 -5.649677e-01 -3.813857e+02 -4.582732e-02 9.983326e-01 3.509764e-02 4.974297e+00 5.660489e-01 -2.997798e-03 8.243662e-01 1.244814e+01 +8.472840e-01 5.028374e-02 -5.287545e-01 -3.816943e+02 -4.082183e-02 9.987289e-01 2.956410e-02 4.989496e+00 5.295691e-01 -3.464459e-03 8.482598e-01 1.299594e+01 +8.692222e-01 4.555996e-02 -4.923180e-01 -3.819738e+02 -3.875164e-02 9.989599e-01 2.402675e-02 5.001597e+00 4.929007e-01 -1.806449e-03 8.700837e-01 1.353817e+01 +8.884037e-01 4.450250e-02 -4.569008e-01 -3.822601e+02 -4.011833e-02 9.990085e-01 1.929765e-02 5.014401e+00 4.573067e-01 1.185996e-03 8.893083e-01 1.412272e+01 +9.055186e-01 4.143482e-02 -4.222787e-01 -3.825278e+02 -3.889557e-02 9.991361e-01 1.463104e-02 5.027764e+00 4.225202e-01 3.176093e-03 9.063480e-01 1.472920e+01 +9.212486e-01 4.239973e-02 -3.866565e-01 -3.827647e+02 -4.035746e-02 9.990954e-01 1.340240e-02 5.034682e+00 3.868750e-01 3.257538e-03 9.221264e-01 1.533954e+01 +9.351028e-01 4.782750e-02 -3.511343e-01 -3.830108e+02 -4.575214e-02 9.988517e-01 1.421006e-02 5.040977e+00 3.514108e-01 2.777283e-03 9.362173e-01 1.599453e+01 +9.471891e-01 5.231788e-02 -3.163789e-01 -3.832216e+02 -5.058061e-02 9.986259e-01 1.370698e-02 5.044374e+00 3.166613e-01 3.019537e-03 9.485339e-01 1.665151e+01 +9.574293e-01 5.365745e-02 -2.836373e-01 -3.834238e+02 -5.342579e-02 9.985351e-01 8.558304e-03 5.048150e+00 2.836810e-01 6.959575e-03 9.588935e-01 1.734294e+01 +9.657939e-01 5.532281e-02 -2.533406e-01 -3.836103e+02 -5.613432e-02 9.984151e-01 4.029963e-03 5.050769e+00 2.531620e-01 1.032899e-02 9.673688e-01 1.805793e+01 +9.721712e-01 5.964491e-02 -2.265516e-01 -3.837799e+02 -6.148106e-02 9.981077e-01 -1.050772e-03 5.050086e+00 2.260602e-01 1.495016e-02 9.739986e-01 1.878164e+01 +9.768450e-01 6.375433e-02 -2.042282e-01 -3.839455e+02 -6.585765e-02 9.978228e-01 -3.511645e-03 5.049065e+00 2.035597e-01 1.688032e-02 9.789170e-01 1.954011e+01 +9.802603e-01 6.929801e-02 -1.851689e-01 -3.841003e+02 -7.110687e-02 9.974637e-01 -3.137486e-03 5.044266e+00 1.844819e-01 1.624234e-02 9.827017e-01 2.031452e+01 +9.830526e-01 7.519367e-02 -1.671933e-01 -3.842443e+02 -7.671306e-02 9.970497e-01 -2.638417e-03 5.037683e+00 1.665016e-01 1.541961e-02 9.859206e-01 2.110738e+01 +9.854244e-01 8.060678e-02 -1.498043e-01 -3.843799e+02 -8.200009e-02 9.966274e-01 -3.137084e-03 5.031566e+00 1.490462e-01 1.537532e-02 9.887107e-01 2.192275e+01 +9.876696e-01 8.454717e-02 -1.317591e-01 -3.844971e+02 -8.575541e-02 9.963100e-01 -3.512491e-03 5.023967e+00 1.309759e-01 1.476823e-02 9.912756e-01 2.274826e+01 +9.896375e-01 8.684062e-02 -1.143518e-01 -3.846034e+02 -8.787371e-02 9.961235e-01 -4.014915e-03 5.016522e+00 1.135599e-01 1.402182e-02 9.934322e-01 2.360378e+01 +9.912417e-01 8.808704e-02 -9.838995e-02 -3.846967e+02 -8.892682e-02 9.960294e-01 -4.173891e-03 5.008339e+00 9.763163e-02 1.288684e-02 9.951392e-01 2.447572e+01 +9.925061e-01 8.704227e-02 -8.576324e-02 -3.847766e+02 -8.775268e-02 9.961319e-01 -4.541072e-03 4.999047e+00 8.503624e-02 1.203299e-02 9.963052e-01 2.536441e+01 +9.934102e-01 8.499354e-02 -7.689131e-02 -3.848497e+02 -8.565192e-02 9.963110e-01 -5.299334e-03 4.989684e+00 7.615726e-02 1.185030e-02 9.970254e-01 2.626918e+01 +9.939760e-01 8.408914e-02 -7.029074e-02 -3.849210e+02 -8.477099e-02 9.963774e-01 -6.768817e-03 4.979224e+00 6.946693e-02 1.268666e-02 9.975036e-01 2.719419e+01 +9.943537e-01 8.449402e-02 -6.419939e-02 -3.849889e+02 -8.519952e-02 9.963291e-01 -8.326830e-03 4.967085e+00 6.326016e-02 1.374957e-02 9.979024e-01 2.812819e+01 +9.946587e-01 8.499872e-02 -5.856084e-02 -3.850594e+02 -8.569792e-02 9.962756e-01 -9.528631e-03 4.961528e+00 5.753282e-02 1.449628e-02 9.982384e-01 2.908783e+01 +9.949760e-01 8.483978e-02 -5.315150e-02 -3.851240e+02 -8.547356e-02 9.962926e-01 -9.762148e-03 4.956885e+00 5.212623e-02 1.425615e-02 9.985388e-01 3.005839e+01 +9.953765e-01 8.229622e-02 -4.952770e-02 -3.852127e+02 -8.278753e-02 9.965355e-01 -7.947768e-03 4.957621e+00 4.870205e-02 1.201130e-02 9.987411e-01 3.108622e+01 +9.956447e-01 8.039788e-02 -4.720067e-02 -3.852881e+02 -8.075057e-02 9.967185e-01 -5.610019e-03 4.958926e+00 4.659476e-02 9.397065e-03 9.988697e-01 3.210933e+01 +9.958159e-01 7.907536e-02 -4.580181e-02 -3.853675e+02 -7.930199e-02 9.968456e-01 -3.149123e-03 4.975144e+00 4.540832e-02 6.768122e-03 9.989456e-01 3.315304e+01 +9.960023e-01 7.766321e-02 -4.413351e-02 -3.854493e+02 -7.773679e-02 9.969739e-01 4.970566e-05 4.990551e+00 4.400382e-02 3.381290e-03 9.990257e-01 3.419205e+01 +9.961294e-01 7.690670e-02 -4.256263e-02 -3.855550e+02 -7.693308e-02 9.970357e-01 1.020672e-03 5.005009e+00 4.251496e-02 2.257753e-03 9.990933e-01 3.523815e+01 +9.961650e-01 7.707706e-02 -4.140525e-02 -3.856790e+02 -7.712156e-02 9.970215e-01 5.244731e-04 5.000295e+00 4.132236e-02 2.670776e-03 9.991423e-01 3.627881e+01 +9.963114e-01 7.581232e-02 -4.020110e-02 -3.857806e+02 -7.584406e-02 9.971194e-01 7.374924e-04 4.992503e+00 4.014121e-02 2.314243e-03 9.991913e-01 3.731573e+01 +9.964364e-01 7.489266e-02 -3.880240e-02 -3.858844e+02 -7.493753e-02 9.971882e-01 2.993328e-04 4.983206e+00 3.871571e-02 2.609490e-03 9.992469e-01 3.835747e+01 +9.965589e-01 7.454297e-02 -3.624602e-02 -3.859713e+02 -7.461505e-02 9.972122e-01 -6.378626e-04 4.973275e+00 3.609743e-02 3.340167e-03 9.993427e-01 3.938747e+01 +9.966732e-01 7.436503e-02 -3.335322e-02 -3.860610e+02 -7.442119e-02 9.972268e-01 -4.435364e-04 4.963478e+00 3.322774e-02 2.924247e-03 9.994435e-01 4.042660e+01 +9.968255e-01 7.361738e-02 -3.032221e-02 -3.861311e+02 -7.363864e-02 9.972849e-01 4.171005e-04 4.952560e+00 3.027059e-02 1.817110e-03 9.995401e-01 4.145790e+01 +9.969805e-01 7.250638e-02 -2.779786e-02 -3.861899e+02 -7.247953e-02 9.973679e-01 1.974236e-03 4.935533e+00 2.786785e-02 4.650192e-05 9.996116e-01 4.248300e+01 +9.971281e-01 7.126839e-02 -2.561984e-02 -3.862290e+02 -7.121733e-02 9.974566e-01 2.901598e-03 4.914915e+00 2.576148e-02 -1.068687e-03 9.996676e-01 4.349269e+01 +9.971895e-01 7.096767e-02 -2.401426e-02 -3.862636e+02 -7.092474e-02 9.974782e-01 2.636536e-03 4.894314e+00 2.414081e-02 -9.259203e-04 9.997081e-01 4.450433e+01 +9.972491e-01 7.059878e-02 -2.258508e-02 -3.862864e+02 -7.058962e-02 9.975047e-01 1.204192e-03 4.876504e+00 2.261374e-02 3.933935e-04 9.997442e-01 4.551515e+01 +9.972867e-01 7.049425e-02 -2.121010e-02 -3.863090e+02 -7.050303e-02 9.975115e-01 3.351508e-04 4.858662e+00 2.118094e-02 1.161135e-03 9.997750e-01 4.651863e+01 +9.972576e-01 7.146202e-02 -1.924894e-02 -3.863359e+02 -7.144531e-02 9.974433e-01 1.556256e-03 4.842405e+00 1.931094e-02 -1.767415e-04 9.998135e-01 4.752062e+01 +9.972919e-01 7.145764e-02 -1.739687e-02 -3.863611e+02 -7.142215e-02 9.974426e-01 2.654241e-03 4.825604e+00 1.754205e-02 -1.404530e-03 9.998451e-01 4.851434e+01 +9.973664e-01 7.082631e-02 -1.561472e-02 -3.863832e+02 -7.078100e-02 9.974859e-01 3.437560e-03 4.809737e+00 1.581893e-02 -2.323281e-03 9.998722e-01 4.950574e+01 +9.974206e-01 7.041182e-02 -1.394186e-02 -3.864057e+02 -7.037312e-02 9.975154e-01 3.249133e-03 4.795880e+00 1.413600e-02 -2.259619e-03 9.998975e-01 5.048312e+01 +9.974381e-01 7.045890e-02 -1.236330e-02 -3.864239e+02 -7.041946e-02 9.975110e-01 3.598435e-03 4.780138e+00 1.258607e-02 -2.718598e-03 9.999171e-01 5.145591e+01 +9.975401e-01 6.925214e-02 -1.086103e-02 -3.864355e+02 -6.921404e-02 9.975944e-01 3.847163e-03 4.765323e+00 1.110133e-02 -3.085962e-03 9.999336e-01 5.241580e+01 +9.975469e-01 6.935906e-02 -9.457196e-03 -3.864476e+02 -6.932591e-02 9.975868e-01 3.790991e-03 4.754990e+00 9.697315e-03 -3.126062e-03 9.999481e-01 5.336490e+01 +9.975260e-01 6.982925e-02 -8.112692e-03 -3.864700e+02 -6.981027e-02 9.975569e-01 2.602202e-03 4.753328e+00 8.274583e-03 -2.029414e-03 9.999637e-01 5.429935e+01 +9.974240e-01 7.142626e-02 -6.604293e-03 -3.864932e+02 -7.142035e-02 9.974456e-01 1.128749e-03 4.750570e+00 6.668046e-03 -6.541595e-04 9.999776e-01 5.522536e+01 +9.973901e-01 7.205952e-02 -4.515114e-03 -3.865136e+02 -7.206285e-02 9.973999e-01 -5.748111e-04 4.740505e+00 4.461955e-03 8.986834e-04 9.999897e-01 5.613841e+01 +9.973262e-01 7.305339e-02 -1.929295e-03 -3.865264e+02 -7.305562e-02 9.973272e-01 -1.105508e-03 4.714973e+00 1.843377e-03 1.243499e-03 9.999975e-01 5.704227e+01 +9.972519e-01 7.407609e-02 1.207399e-03 -3.865544e+02 -7.407583e-02 9.972525e-01 -2.717766e-04 4.687689e+00 -1.224214e-03 1.815912e-04 9.999992e-01 5.794382e+01 +9.972612e-01 7.381429e-02 4.641308e-03 -3.865730e+02 -7.381917e-02 9.972712e-01 8.839541e-04 4.668079e+00 -4.563395e-03 -1.224150e-03 9.999888e-01 5.883729e+01 +9.972093e-01 7.415524e-02 8.638113e-03 -3.865972e+02 -7.416530e-02 9.972456e-01 8.474897e-04 4.636269e+00 -8.551475e-03 -1.485772e-03 9.999623e-01 5.971589e+01 +9.971044e-01 7.471842e-02 1.413910e-02 -3.866103e+02 -7.473437e-02 9.972033e-01 6.012530e-04 4.604297e+00 -1.405463e-02 -1.656188e-03 9.998999e-01 6.057853e+01 +9.968837e-01 7.594007e-02 2.135607e-02 -3.866123e+02 -7.596922e-02 9.971100e-01 5.552253e-04 4.568426e+00 -2.125219e-02 -2.175898e-03 9.997718e-01 6.142730e+01 +9.965591e-01 7.684848e-02 3.105155e-02 -3.866028e+02 -7.691260e-02 9.970374e-01 8.735374e-04 4.534990e+00 -3.089243e-02 -3.258786e-03 9.995174e-01 6.225953e+01 +9.959357e-01 7.921437e-02 4.286218e-02 -3.865856e+02 -7.930778e-02 9.968500e-01 4.802367e-04 4.488590e+00 -4.268913e-02 -3.877589e-03 9.990809e-01 6.307902e+01 +9.951990e-01 7.985824e-02 5.658346e-02 -3.865472e+02 -7.993979e-02 9.967993e-01 -8.247531e-04 4.453827e+00 -5.646822e-02 -3.702475e-03 9.983975e-01 6.388194e+01 +9.941427e-01 8.002575e-02 7.263773e-02 -3.864602e+02 -8.005885e-02 9.967871e-01 -2.460542e-03 4.400652e+00 -7.260126e-02 -3.369162e-03 9.973554e-01 6.466610e+01 +9.925716e-01 8.052018e-02 9.120329e-02 -3.863709e+02 -8.049598e-02 9.967471e-01 -3.949966e-03 4.361178e+00 -9.122467e-02 -3.420873e-03 9.958245e-01 6.543382e+01 +9.905363e-01 7.872251e-02 1.124304e-01 -3.862546e+02 -7.891457e-02 9.968776e-01 -2.748170e-03 4.310911e+00 -1.122957e-01 -6.150230e-03 9.936558e-01 6.619311e+01 +9.881014e-01 7.278873e-02 1.354895e-01 -3.861147e+02 -7.342736e-02 9.973005e-01 -2.847299e-04 4.258967e+00 -1.351445e-01 -9.667291e-03 9.907788e-01 6.693535e+01 +9.850184e-01 6.415408e-02 1.600721e-01 -3.859148e+02 -6.497619e-02 9.978868e-01 -9.861213e-05 4.185071e+00 -1.597402e-01 -1.030374e-02 9.871053e-01 6.764830e+01 +9.807636e-01 5.702266e-02 1.866848e-01 -3.857300e+02 -5.771303e-02 9.983317e-01 -1.739325e-03 4.125313e+00 -1.864726e-01 -9.068279e-03 9.824183e-01 6.835655e+01 +9.753494e-01 4.926249e-02 2.150973e-01 -3.855002e+02 -4.913767e-02 9.987744e-01 -5.930986e-03 4.065030e+00 -2.151258e-01 -4.784593e-03 9.765746e-01 6.902793e+01 +9.687792e-01 3.864602e-02 2.448946e-01 -3.852492e+02 -3.744948e-02 9.992529e-01 -9.542422e-03 4.013303e+00 -2.450805e-01 7.332426e-05 9.695027e-01 6.969486e+01 +9.605073e-01 2.985961e-02 2.766479e-01 -3.849467e+02 -2.789252e-02 9.995499e-01 -1.104367e-02 3.962535e+00 -2.768532e-01 2.891120e-03 9.609079e-01 7.032087e+01 +9.503252e-01 2.212954e-02 3.104710e-01 -3.846375e+02 -1.972120e-02 9.997461e-01 -1.089433e-02 3.909495e+00 -3.106333e-01 4.230293e-03 9.505204e-01 7.095396e+01 +9.387817e-01 1.518136e-02 3.441779e-01 -3.843351e+02 -1.232626e-02 9.998691e-01 -1.048210e-02 3.867952e+00 -3.442920e-01 5.597978e-03 9.388459e-01 7.157362e+01 +9.255624e-01 9.891702e-03 3.784659e-01 -3.839970e+02 -6.014313e-03 9.999166e-01 -1.142575e-02 3.825384e+00 -3.785474e-01 8.299032e-03 9.255447e-01 7.214448e+01 +9.100127e-01 9.296077e-03 4.144762e-01 -3.836839e+02 -4.741611e-03 9.999165e-01 -1.201607e-02 3.791281e+00 -4.145534e-01 8.969493e-03 9.099808e-01 7.272365e+01 +8.921508e-01 9.223071e-03 4.516436e-01 -3.833356e+02 -4.054814e-03 9.999147e-01 -1.240975e-02 3.743116e+00 -4.517196e-01 9.240031e-03 8.921121e-01 7.325502e+01 +8.719709e-01 1.290339e-02 4.893875e-01 -3.830087e+02 -6.080540e-03 9.998609e-01 -1.552869e-02 3.686261e+00 -4.895199e-01 1.056482e-02 8.719281e-01 7.380723e+01 +8.484534e-01 1.780515e-02 5.289704e-01 -3.826815e+02 -7.676295e-03 9.997428e-01 -2.133881e-02 3.621687e+00 -5.292144e-01 1.404445e-02 8.483719e-01 7.434726e+01 +8.207237e-01 1.840225e-02 5.710288e-01 -3.822953e+02 -4.883199e-03 9.996705e-01 -2.519739e-02 3.572042e+00 -5.713044e-01 1.789164e-02 8.205432e-01 7.481888e+01 +7.893179e-01 1.718138e-02 6.137443e-01 -3.819175e+02 -1.743982e-03 9.996671e-01 -2.574217e-02 3.525874e+00 -6.139823e-01 1.924839e-02 7.890851e-01 7.531640e+01 +7.562144e-01 1.516016e-02 6.541483e-01 -3.814882e+02 4.737248e-03 9.995785e-01 -2.864205e-02 3.492060e+00 -6.543068e-01 2.475838e-02 7.558238e-01 7.573698e+01 +7.208081e-01 1.493036e-02 6.929739e-01 -3.810917e+02 6.237834e-03 9.995877e-01 -2.802486e-02 3.438736e+00 -6.931067e-01 2.452319e-02 7.204178e-01 7.619170e+01 +6.838480e-01 1.441810e-02 7.294820e-01 -3.806362e+02 7.956722e-03 9.995979e-01 -2.721587e-02 3.403867e+00 -7.295811e-01 2.441580e-02 6.834583e-01 7.657608e+01 +6.454386e-01 1.755974e-02 7.636102e-01 -3.802189e+02 5.978856e-03 9.995889e-01 -2.803985e-02 3.373353e+00 -7.637888e-01 2.266351e-02 6.450683e-01 7.698820e+01 +6.052640e-01 1.992137e-02 7.957755e-01 -3.797747e+02 6.981761e-03 9.995155e-01 -3.033209e-02 3.350777e+00 -7.959942e-01 2.391483e-02 6.048317e-01 7.736446e+01 +5.639372e-01 2.410297e-02 8.254659e-01 -3.792899e+02 5.024776e-03 9.994553e-01 -3.261613e-02 3.320751e+00 -8.258024e-01 2.254122e-02 5.635089e-01 7.767482e+01 +5.230203e-01 2.705726e-02 8.518907e-01 -3.788016e+02 6.038536e-03 9.993532e-01 -3.544827e-02 3.288247e+00 -8.522989e-01 2.368433e-02 5.225186e-01 7.799106e+01 +4.832737e-01 3.016063e-02 8.749496e-01 -3.782710e+02 7.411260e-03 9.992296e-01 -3.853830e-02 3.254157e+00 -8.754380e-01 2.510902e-02 4.826779e-01 7.825197e+01 +4.449539e-01 3.074552e-02 8.950255e-01 -3.777323e+02 6.357401e-03 9.992769e-01 -3.748725e-02 3.219515e+00 -8.955309e-01 2.237013e-02 4.444367e-01 7.852225e+01 +4.080550e-01 3.050719e-02 9.124475e-01 -3.771709e+02 4.607724e-03 9.993600e-01 -3.547369e-02 3.183033e+00 -9.129458e-01 1.867952e-02 4.076533e-01 7.877365e+01 +3.724633e-01 2.698356e-02 9.276546e-01 -3.765739e+02 9.649860e-04 9.995654e-01 -2.946276e-02 3.148159e+00 -9.280465e-01 1.186897e-02 3.722754e-01 7.898705e+01 +3.382289e-01 2.313285e-02 9.407795e-01 -3.759763e+02 2.896092e-03 9.996675e-01 -2.562206e-02 3.107600e+00 -9.410595e-01 1.139070e-02 3.380494e-01 7.919562e+01 +3.059352e-01 2.261135e-02 9.517838e-01 -3.753673e+02 6.383630e-03 9.996467e-01 -2.580034e-02 3.059451e+00 -9.520310e-01 1.396906e-02 3.056828e-01 7.938258e+01 +2.744123e-01 2.268208e-02 9.613446e-01 -3.747281e+02 6.215201e-03 9.996590e-01 -2.536019e-02 3.021292e+00 -9.615921e-01 1.293409e-02 2.741778e-01 7.953785e+01 +2.432354e-01 2.813418e-02 9.695592e-01 -3.740884e+02 7.973582e-04 9.995731e-01 -2.920515e-02 2.984454e+00 -9.699670e-01 7.876811e-03 2.431092e-01 7.970015e+01 +2.140797e-01 3.032088e-02 9.763455e-01 -3.734236e+02 -1.176862e-03 9.995254e-01 -3.078271e-02 2.956911e+00 -9.768155e-01 5.440925e-03 2.140137e-01 7.982830e+01 +1.871939e-01 2.552431e-02 9.819913e-01 -3.727399e+02 9.000268e-04 9.996575e-01 -2.615507e-02 2.921012e+00 -9.823226e-01 5.779885e-03 1.871068e-01 7.994184e+01 +1.629236e-01 2.345391e-02 9.863599e-01 -3.720439e+02 4.656807e-03 9.996880e-01 -2.454003e-02 2.891012e+00 -9.866277e-01 8.591434e-03 1.627635e-01 8.003915e+01 +1.419526e-01 2.248713e-02 9.896180e-01 -3.713254e+02 7.889177e-03 9.996845e-01 -2.384752e-02 2.862556e+00 -9.898421e-01 1.119249e-02 1.417304e-01 8.011956e+01 +1.246053e-01 2.243105e-02 9.919528e-01 -3.706070e+02 9.938195e-03 9.996660e-01 -2.385388e-02 2.824343e+00 -9.921566e-01 1.283054e-02 1.243408e-01 8.019998e+01 +1.101188e-01 2.284538e-02 9.936558e-01 -3.698784e+02 1.171118e-02 9.996366e-01 -2.428075e-02 2.789923e+00 -9.938495e-01 1.431064e-02 1.098112e-01 8.027645e+01 +9.791847e-02 2.194786e-02 9.949524e-01 -3.691311e+02 1.151229e-02 9.996649e-01 -2.318481e-02 2.750135e+00 -9.951279e-01 1.372439e-02 9.763298e-02 8.034818e+01 +8.728909e-02 2.008438e-02 9.959805e-01 -3.683703e+02 1.114177e-02 9.997145e-01 -2.113617e-02 2.712003e+00 -9.961207e-01 1.294194e-02 8.704040e-02 8.041558e+01 +7.745038e-02 1.774720e-02 9.968382e-01 -3.675962e+02 1.223821e-02 9.997493e-01 -1.874990e-02 2.675324e+00 -9.969211e-01 1.365170e-02 7.721377e-02 8.047155e+01 +6.762617e-02 1.615202e-02 9.975800e-01 -3.668160e+02 1.320500e-02 9.997669e-01 -1.708261e-02 2.643275e+00 -9.976234e-01 1.432827e-02 6.739712e-02 8.052200e+01 +5.743673e-02 1.618281e-02 9.982180e-01 -3.660320e+02 1.420664e-02 9.997541e-01 -1.702516e-02 2.614501e+00 -9.982481e-01 1.515919e-02 5.719270e-02 8.057135e+01 +4.772629e-02 1.621114e-02 9.987289e-01 -3.652324e+02 1.359707e-02 9.997651e-01 -1.687773e-02 2.588549e+00 -9.987679e-01 1.438530e-02 4.749465e-02 8.061280e+01 +3.851429e-02 1.668594e-02 9.991187e-01 -3.644226e+02 1.309266e-02 9.997663e-01 -1.720146e-02 2.552169e+00 -9.991723e-01 1.374361e-02 3.828682e-02 8.064760e+01 +2.987461e-02 1.733809e-02 9.994033e-01 -3.635984e+02 1.507358e-02 9.997280e-01 -1.779431e-02 2.511430e+00 -9.994400e-01 1.559618e-02 2.960514e-02 8.067330e+01 +2.164021e-02 1.761558e-02 9.996106e-01 -3.627671e+02 1.715372e-02 9.996910e-01 -1.798836e-02 2.466161e+00 -9.996187e-01 1.753630e-02 2.133135e-02 8.069174e+01 +1.428922e-02 1.752477e-02 9.997443e-01 -3.619246e+02 1.851449e-02 9.996703e-01 -1.778810e-02 2.417847e+00 -9.997265e-01 1.876393e-02 1.396004e-02 8.070664e+01 +7.134552e-03 1.692615e-02 9.998313e-01 -3.610717e+02 1.871084e-02 9.996794e-01 -1.705710e-02 2.365276e+00 -9.997995e-01 1.882938e-02 6.815561e-03 8.071632e+01 +3.727182e-04 1.637863e-02 9.998658e-01 -3.602092e+02 1.959813e-02 9.996737e-01 -1.638280e-02 2.328456e+00 -9.998079e-01 1.960160e-02 5.160410e-05 8.071928e+01 +-6.510105e-03 1.573838e-02 9.998549e-01 -3.593382e+02 2.063856e-02 9.996652e-01 -1.560102e-02 2.293464e+00 -9.997658e-01 2.053400e-02 -6.832745e-03 8.071605e+01 +-1.320616e-02 1.520137e-02 9.997972e-01 -3.584699e+02 2.155240e-02 9.996564e-01 -1.491455e-02 2.267535e+00 -9.996805e-01 2.135106e-02 -1.352925e-02 8.070585e+01 +-1.906280e-02 1.550672e-02 9.996980e-01 -3.575951e+02 2.409813e-02 9.995963e-01 -1.504563e-02 2.251796e+00 -9.995279e-01 2.380403e-02 -1.942879e-02 8.068843e+01 +-2.322514e-02 1.646507e-02 9.995946e-01 -3.567191e+02 2.809604e-02 9.994802e-01 -1.581040e-02 2.238760e+00 -9.993354e-01 2.771744e-02 -2.367567e-02 8.066402e+01 +-2.584511e-02 1.759766e-02 9.995110e-01 -3.558328e+02 3.155184e-02 9.993612e-01 -1.677917e-02 2.216750e+00 -9.991679e-01 3.110275e-02 -2.638385e-02 8.063830e+01 +-2.761546e-02 1.698687e-02 9.994743e-01 -3.549412e+02 3.379718e-02 9.992998e-01 -1.605009e-02 2.193109e+00 -9.990471e-01 3.333617e-02 -2.817024e-02 8.061244e+01 +-2.866679e-02 1.935073e-02 9.994017e-01 -3.540526e+02 3.606009e-02 9.991818e-01 -1.831213e-02 2.173607e+00 -9.989384e-01 3.551356e-02 -2.934113e-02 8.058406e+01 +-2.944386e-02 2.371522e-02 9.992851e-01 -3.531610e+02 3.799415e-02 9.990226e-01 -2.258951e-02 2.156139e+00 -9.988441e-01 3.730185e-02 -3.031613e-02 8.055390e+01 +-2.938804e-02 2.909711e-02 9.991445e-01 -3.522634e+02 4.033576e-02 9.987965e-01 -2.790058e-02 2.132324e+00 -9.987539e-01 3.948130e-02 -3.052633e-02 8.052304e+01 +-2.801551e-02 2.985448e-02 9.991616e-01 -3.513579e+02 4.278479e-02 9.986737e-01 -2.864027e-02 2.101040e+00 -9.986915e-01 4.194653e-02 -2.925568e-02 8.049292e+01 +-2.620762e-02 2.760427e-02 9.992753e-01 -3.504501e+02 4.425318e-02 9.986707e-01 -2.642696e-02 2.064742e+00 -9.986766e-01 4.352851e-02 -2.739436e-02 8.046555e+01 +-2.388165e-02 2.609374e-02 9.993742e-01 -3.495528e+02 4.604809e-02 9.986270e-01 -2.497385e-02 2.037963e+00 -9.986537e-01 4.542284e-02 -2.505043e-02 8.044086e+01 +-2.071640e-02 2.582559e-02 9.994518e-01 -3.486604e+02 4.752445e-02 9.985617e-01 -2.481752e-02 2.015011e+00 -9.986553e-01 4.698426e-02 -2.191395e-02 8.041789e+01 +-1.716662e-02 2.595113e-02 9.995158e-01 -3.477631e+02 4.840129e-02 9.985127e-01 -2.509381e-02 1.979667e+00 -9.986805e-01 4.794707e-02 -1.839716e-02 8.039846e+01 +-1.284342e-02 2.617142e-02 9.995749e-01 -3.468679e+02 5.083545e-02 9.983818e-01 -2.548701e-02 1.943743e+00 -9.986245e-01 5.048649e-02 -1.415307e-02 8.038100e+01 +-7.327368e-03 2.553392e-02 9.996471e-01 -3.459723e+02 5.243591e-02 9.983084e-01 -2.511539e-02 1.907657e+00 -9.985974e-01 5.223337e-02 -8.653869e-03 8.037051e+01 +-9.760611e-04 2.468882e-02 9.996947e-01 -3.450869e+02 5.197139e-02 9.983454e-01 -2.460477e-02 1.874915e+00 -9.986481e-01 5.193150e-02 -2.257561e-03 8.037074e+01 +5.651598e-03 2.416298e-02 9.996920e-01 -3.441955e+02 5.258142e-02 9.983178e-01 -2.442703e-02 1.837896e+00 -9.986007e-01 5.270327e-02 4.371565e-03 8.037465e+01 +1.239104e-02 2.419271e-02 9.996305e-01 -3.433073e+02 5.209159e-02 9.983341e-01 -2.480705e-02 1.791116e+00 -9.985655e-01 5.237971e-02 1.111016e-02 8.038461e+01 +1.879404e-02 2.322938e-02 9.995535e-01 -3.424174e+02 5.129727e-02 9.983910e-01 -2.416689e-02 1.747674e+00 -9.985066e-01 5.172855e-02 1.757219e-02 8.040297e+01 +2.451152e-02 2.256258e-02 9.994449e-01 -3.415362e+02 4.921571e-02 9.985058e-01 -2.374841e-02 1.707100e+00 -9.984874e-01 4.977049e-02 2.336446e-02 8.042749e+01 +2.940874e-02 2.424631e-02 9.992733e-01 -3.406544e+02 4.809539e-02 9.985135e-01 -2.564334e-02 1.665107e+00 -9.984097e-01 4.881456e-02 2.819889e-02 8.045575e+01 +3.243498e-02 2.534465e-02 9.991524e-01 -3.397741e+02 4.716808e-02 9.985257e-01 -2.685995e-02 1.620074e+00 -9.983603e-01 4.799929e-02 3.119170e-02 8.048336e+01 +3.440471e-02 2.536469e-02 9.990860e-01 -3.388925e+02 4.556868e-02 9.985984e-01 -2.692153e-02 1.572604e+00 -9.983686e-01 4.645325e-02 3.320065e-02 8.051201e+01 +3.594240e-02 2.509926e-02 9.990386e-01 -3.380111e+02 4.530224e-02 9.986159e-01 -2.671849e-02 1.524986e+00 -9.983266e-01 4.621900e-02 3.475560e-02 8.054135e+01 +3.789843e-02 2.586905e-02 9.989467e-01 -3.371398e+02 4.481744e-02 9.986149e-01 -2.756077e-02 1.480371e+00 -9.982761e-01 4.581474e-02 3.668655e-02 8.057511e+01 +3.879235e-02 2.628539e-02 9.989015e-01 -3.362701e+02 4.436602e-02 9.986228e-01 -2.800102e-02 1.441672e+00 -9.982619e-01 4.540350e-02 3.757274e-02 8.061323e+01 +3.930056e-02 2.639964e-02 9.988786e-01 -3.354027e+02 4.232662e-02 9.987097e-01 -2.806051e-02 1.405387e+00 -9.983306e-01 4.338194e-02 3.813244e-02 8.065466e+01 +3.944788e-02 2.558759e-02 9.988939e-01 -3.345289e+02 4.146258e-02 9.987691e-01 -2.722182e-02 1.366729e+00 -9.983610e-01 4.249055e-02 3.833840e-02 8.069348e+01 +3.966773e-02 2.490041e-02 9.989026e-01 -3.336586e+02 4.040636e-02 9.988317e-01 -2.650324e-02 1.333427e+00 -9.983956e-01 4.141333e-02 3.861525e-02 8.073432e+01 +3.921012e-02 2.448245e-02 9.989310e-01 -3.327915e+02 3.905101e-02 9.988985e-01 -2.601449e-02 1.304597e+00 -9.984677e-01 4.002929e-02 3.821087e-02 8.077734e+01 +3.715134e-02 2.499513e-02 9.989970e-01 -3.319327e+02 3.751121e-02 9.989477e-01 -2.638890e-02 1.279266e+00 -9.986054e-01 3.845396e-02 3.617465e-02 8.082451e+01 +3.387511e-02 2.565374e-02 9.990968e-01 -3.310656e+02 3.607856e-02 9.989875e-01 -2.687421e-02 1.241296e+00 -9.987747e-01 3.695633e-02 3.291527e-02 8.086115e+01 +3.010168e-02 2.546309e-02 9.992224e-01 -3.301973e+02 3.594140e-02 9.990014e-01 -2.654020e-02 1.207248e+00 -9.989005e-01 3.671235e-02 2.915644e-02 8.089339e+01 +2.658521e-02 2.511846e-02 9.993309e-01 -3.293252e+02 3.573711e-02 9.990213e-01 -2.606140e-02 1.167920e+00 -9.990076e-01 3.640604e-02 2.566153e-02 8.091850e+01 +2.321467e-02 2.518893e-02 9.994131e-01 -3.284618e+02 3.622383e-02 9.990049e-01 -2.602007e-02 1.133825e+00 -9.990741e-01 3.680660e-02 2.227912e-02 8.094492e+01 +2.042588e-02 2.622278e-02 9.994474e-01 -3.276059e+02 3.721095e-02 9.989434e-01 -2.697005e-02 1.098039e+00 -9.990987e-01 3.774127e-02 1.942852e-02 8.097059e+01 +1.808905e-02 2.562500e-02 9.995079e-01 -3.267391e+02 3.748400e-02 9.989513e-01 -2.628912e-02 1.058423e+00 -9.991335e-01 3.794109e-02 1.710955e-02 8.099070e+01 +1.633319e-02 2.545877e-02 9.995424e-01 -3.258738e+02 3.705721e-02 9.989735e-01 -2.604983e-02 1.014285e+00 -9.991797e-01 3.746573e-02 1.537299e-02 8.101013e+01 +1.450265e-02 2.408706e-02 9.996046e-01 -3.250019e+02 3.725807e-02 9.990025e-01 -2.461311e-02 9.657148e-01 -9.992005e-01 3.760028e-02 1.359075e-02 8.102279e+01 +1.392277e-02 2.476231e-02 9.995964e-01 -3.241441e+02 3.866418e-02 9.989323e-01 -2.528440e-02 9.191409e-01 -9.991553e-01 3.900060e-02 1.295049e-02 8.103877e+01 +1.420197e-02 2.523814e-02 9.995806e-01 -3.232796e+02 4.069020e-02 9.988387e-01 -2.579754e-02 8.755404e-01 -9.990709e-01 4.103950e-02 1.315853e-02 8.105150e+01 +1.545065e-02 2.565738e-02 9.995514e-01 -3.224241e+02 4.225499e-02 9.987609e-01 -2.629026e-02 8.411539e-01 -9.989874e-01 4.264223e-02 1.434735e-02 8.107183e+01 +1.772400e-02 2.657848e-02 9.994896e-01 -3.215623e+02 4.353146e-02 9.986782e-01 -2.732886e-02 8.075155e-01 -9.988949e-01 4.399361e-02 1.654357e-02 8.109114e+01 +2.093747e-02 2.744062e-02 9.994041e-01 -3.207139e+02 4.497077e-02 9.985856e-01 -2.836029e-02 7.848539e-01 -9.987689e-01 4.553776e-02 1.967383e-02 8.112106e+01 +2.484634e-02 2.731854e-02 9.993179e-01 -3.198617e+02 4.609516e-02 9.985320e-01 -2.844314e-02 7.604346e-01 -9.986280e-01 4.677042e-02 2.355061e-02 8.115310e+01 +2.855261e-02 2.600080e-02 9.992541e-01 -3.190116e+02 4.569159e-02 9.985828e-01 -2.728893e-02 7.352537e-01 -9.985475e-01 4.643667e-02 2.732412e-02 8.119007e+01 +3.224221e-02 2.430557e-02 9.991845e-01 -3.181563e+02 4.505685e-02 9.986526e-01 -2.574656e-02 7.031537e-01 -9.984640e-01 4.585022e-02 3.110363e-02 8.122634e+01 +3.546577e-02 2.219829e-02 9.991243e-01 -3.173009e+02 4.469508e-02 9.987177e-01 -2.377580e-02 6.744877e-01 -9.983710e-01 4.549915e-02 3.442814e-02 8.126389e+01 +3.825299e-02 1.917658e-02 9.990840e-01 -3.164509e+02 4.371538e-02 9.988265e-01 -2.084542e-02 6.529662e-01 -9.983114e-01 4.447273e-02 3.736978e-02 8.130809e+01 +4.039940e-02 1.607504e-02 9.990543e-01 -3.156024e+02 4.261425e-02 9.989331e-01 -1.779632e-02 6.301279e-01 -9.982745e-01 4.329290e-02 3.967127e-02 8.135592e+01 +4.254480e-02 1.531475e-02 9.989772e-01 -3.147590e+02 4.194748e-02 9.989734e-01 -1.710117e-02 6.105982e-01 -9.982136e-01 4.263213e-02 4.185871e-02 8.140304e+01 +4.382834e-02 1.640296e-02 9.989044e-01 -3.139092e+02 4.088331e-02 9.989982e-01 -1.819832e-02 5.837601e-01 -9.982022e-01 4.163611e-02 4.311382e-02 8.144465e+01 +4.381588e-02 1.791876e-02 9.988789e-01 -3.130655e+02 4.003316e-02 9.990046e-01 -1.967708e-02 5.596864e-01 -9.982372e-01 4.085044e-02 4.305492e-02 8.148834e+01 +4.321412e-02 1.905973e-02 9.988840e-01 -3.122264e+02 3.902554e-02 9.990227e-01 -2.075073e-02 5.388538e-01 -9.983034e-01 3.987871e-02 4.242807e-02 8.153253e+01 +4.287172e-02 1.973038e-02 9.988857e-01 -3.113919e+02 3.812212e-02 9.990445e-01 -2.136971e-02 5.253465e-01 -9.983530e-01 3.899579e-02 4.207859e-02 8.158006e+01 +4.276660e-02 1.998843e-02 9.988851e-01 -3.105535e+02 3.880467e-02 9.990122e-01 -2.165238e-02 5.070300e-01 -9.983312e-01 3.968740e-02 4.194870e-02 8.162151e+01 +4.278355e-02 1.976820e-02 9.988888e-01 -3.097173e+02 3.936411e-02 9.989945e-01 -2.145631e-02 4.885564e-01 -9.983086e-01 4.023834e-02 4.196238e-02 8.166308e+01 +4.313866e-02 1.876709e-02 9.988928e-01 -3.088764e+02 3.872339e-02 9.990408e-01 -2.044221e-02 4.659141e-01 -9.983184e-01 3.956235e-02 4.237056e-02 8.170697e+01 +4.397396e-02 1.827848e-02 9.988654e-01 -3.080463e+02 3.802526e-02 9.990775e-01 -1.995638e-02 4.482109e-01 -9.983088e-01 3.885967e-02 4.323835e-02 8.175553e+01 +4.464057e-02 1.836416e-02 9.988343e-01 -3.072106e+02 3.690984e-02 9.991180e-01 -2.001899e-02 4.165126e-01 -9.983211e-01 3.776046e-02 4.392338e-02 8.180205e+01 +4.502170e-02 1.877117e-02 9.988096e-01 -3.063789e+02 3.616556e-02 9.991374e-01 -2.040751e-02 3.906744e-01 -9.983312e-01 3.704129e-02 4.430399e-02 8.184925e+01 +4.498146e-02 1.949737e-02 9.987975e-01 -3.055496e+02 3.563615e-02 9.991418e-01 -2.110900e-02 3.689983e-01 -9.983520e-01 3.654280e-02 4.424804e-02 8.189756e+01 +4.495621e-02 2.001702e-02 9.987884e-01 -3.047192e+02 3.491015e-02 9.991571e-01 -2.159575e-02 3.431954e-01 -9.983788e-01 3.583870e-02 4.421952e-02 8.194310e+01 +4.632113e-02 2.012179e-02 9.987239e-01 -3.038887e+02 3.620880e-02 9.991062e-01 -2.180887e-02 3.106819e-01 -9.982702e-01 3.717280e-02 4.555114e-02 8.199440e+01 +4.976948e-02 2.096797e-02 9.985406e-01 -3.030534e+02 3.718014e-02 9.990477e-01 -2.283177e-02 2.767413e-01 -9.980685e-01 3.826220e-02 4.894249e-02 8.204414e+01 +5.287256e-02 2.165317e-02 9.983665e-01 -3.022179e+02 3.724530e-02 9.990265e-01 -2.363997e-02 2.426660e-01 -9.979065e-01 3.843436e-02 5.201461e-02 8.210066e+01 +5.531219e-02 2.241004e-02 9.982176e-01 -3.013763e+02 3.493972e-02 9.990923e-01 -2.436573e-02 2.063512e-01 -9.978576e-01 3.622516e-02 5.447899e-02 8.215819e+01 +5.768168e-02 2.362719e-02 9.980554e-01 -3.005347e+02 3.282805e-02 9.991344e-01 -2.555001e-02 1.819028e-01 -9.977952e-01 3.423797e-02 5.685611e-02 8.221450e+01 +5.952833e-02 2.447578e-02 9.979265e-01 -2.996885e+02 3.151608e-02 9.991549e-01 -2.638592e-02 1.545294e-01 -9.977290e-01 3.302144e-02 5.870664e-02 8.227001e+01 +6.135702e-02 2.484506e-02 9.978066e-01 -2.988329e+02 3.018987e-02 9.991865e-01 -2.673586e-02 1.184718e-01 -9.976592e-01 3.176408e-02 6.055704e-02 8.232573e+01 +6.306957e-02 2.429265e-02 9.977134e-01 -2.979698e+02 2.989878e-02 9.992090e-01 -2.621910e-02 7.929509e-02 -9.975612e-01 3.148403e-02 6.229336e-02 8.238329e+01 +6.506481e-02 2.507654e-02 9.975659e-01 -2.971029e+02 2.857412e-02 9.992274e-01 -2.698202e-02 3.459801e-02 -9.974719e-01 3.026014e-02 6.429801e-02 8.244259e+01 +6.594735e-02 2.772638e-02 9.974378e-01 -2.962379e+02 2.670726e-02 9.992067e-01 -2.954136e-02 -7.332329e-03 -9.974657e-01 2.858700e-02 6.515453e-02 8.250414e+01 +6.669349e-02 3.069742e-02 9.973012e-01 -2.953690e+02 2.462881e-02 9.991714e-01 -3.240202e-02 -4.611866e-02 -9.974695e-01 2.672334e-02 6.588218e-02 8.256758e+01 +6.732093e-02 3.210046e-02 9.972148e-01 -2.944851e+02 2.364008e-02 9.991504e-01 -3.375869e-02 -9.203292e-02 -9.974513e-01 2.584690e-02 6.650488e-02 8.262489e+01 +6.645689e-02 3.059922e-02 9.973200e-01 -2.935904e+02 2.197797e-02 9.992422e-01 -3.212272e-02 -1.389483e-01 -9.975473e-01 2.405384e-02 6.573402e-02 8.268341e+01 +6.375148e-02 2.853630e-02 9.975577e-01 -2.926861e+02 1.934437e-02 9.993679e-01 -2.982435e-02 -1.839035e-01 -9.977783e-01 2.119847e-02 6.315917e-02 8.274347e+01 +6.066217e-02 2.853322e-02 9.977504e-01 -2.917837e+02 1.811633e-02 9.993952e-01 -2.968172e-02 -2.240962e-01 -9.979940e-01 1.987613e-02 6.010857e-02 8.280022e+01 +5.774235e-02 3.034787e-02 9.978701e-01 -2.908766e+02 1.786952e-02 9.993463e-01 -3.142680e-02 -2.563851e-01 -9.981716e-01 1.964611e-02 5.716230e-02 8.285334e+01 +5.416230e-02 3.263694e-02 9.979986e-01 -2.899648e+02 1.805515e-02 9.992703e-01 -3.365840e-02 -2.918656e-01 -9.983689e-01 1.984203e-02 5.353351e-02 8.290211e+01 +4.857272e-02 3.302984e-02 9.982734e-01 -2.890472e+02 1.667891e-02 9.992869e-01 -3.387493e-02 -3.253248e-01 -9.986804e-01 1.829550e-02 4.798718e-02 8.294773e+01 +4.146910e-02 3.253492e-02 9.986099e-01 -2.881200e+02 1.513920e-02 9.993345e-01 -3.318722e-02 -3.580759e-01 -9.990251e-01 1.649440e-02 4.094895e-02 8.298771e+01 +3.443881e-02 3.140790e-02 9.989131e-01 -2.871918e+02 1.491596e-02 9.993786e-01 -3.193679e-02 -3.803976e-01 -9.992955e-01 1.599961e-02 3.394893e-02 8.302060e+01 +2.755254e-02 3.106244e-02 9.991376e-01 -2.862575e+02 1.563593e-02 9.993814e-01 -3.150121e-02 -4.030460e-01 -9.994981e-01 1.649038e-02 2.704980e-02 8.304517e+01 +2.108882e-02 3.055896e-02 9.993105e-01 -2.853147e+02 1.716291e-02 9.993744e-01 -3.092312e-02 -4.320350e-01 -9.996303e-01 1.780320e-02 2.055115e-02 8.306201e+01 +1.513993e-02 3.028958e-02 9.994265e-01 -2.843638e+02 1.860347e-02 9.993595e-01 -3.056938e-02 -4.701418e-01 -9.997123e-01 1.905561e-02 1.456674e-02 8.307348e+01 +1.052140e-02 2.981267e-02 9.995001e-01 -2.834086e+02 1.983691e-02 9.993525e-01 -3.001709e-02 -5.062144e-01 -9.997479e-01 2.014281e-02 9.923199e-03 8.308074e+01 +7.841811e-03 2.760270e-02 9.995882e-01 -2.824604e+02 2.106485e-02 9.993925e-01 -2.776256e-02 -5.307643e-01 -9.997474e-01 2.127388e-02 7.255599e-03 8.308933e+01 +6.076392e-03 2.569487e-02 9.996513e-01 -2.815095e+02 2.258343e-02 9.994113e-01 -2.582598e-02 -5.617159e-01 -9.997265e-01 2.273248e-02 5.492534e-03 8.309506e+01 +4.285510e-03 2.535006e-02 9.996694e-01 -2.805564e+02 2.257424e-02 9.994214e-01 -2.544056e-02 -5.986130e-01 -9.997360e-01 2.267580e-02 3.710770e-03 8.310032e+01 +2.477392e-03 2.590249e-02 9.996614e-01 -2.796114e+02 2.215387e-02 9.994177e-01 -2.595109e-02 -6.315537e-01 -9.997515e-01 2.221066e-02 1.902107e-03 8.310504e+01 +7.638148e-04 2.634187e-02 9.996527e-01 -2.786701e+02 2.242542e-02 9.994011e-01 -2.635238e-02 -6.640213e-01 -9.997483e-01 2.243775e-02 1.726280e-04 8.310662e+01 +-7.849651e-04 2.592521e-02 9.996636e-01 -2.777330e+02 2.298655e-02 9.994002e-01 -2.590034e-02 -6.965357e-01 -9.997355e-01 2.295848e-02 -1.380427e-03 8.310771e+01 +-2.334147e-03 2.513103e-02 9.996814e-01 -2.768011e+02 2.391562e-02 9.993996e-01 -2.506811e-02 -7.254530e-01 -9.997113e-01 2.384948e-02 -2.933772e-03 8.310797e+01 +-3.901813e-03 2.461411e-02 9.996894e-01 -2.758743e+02 2.443595e-02 9.994008e-01 -2.451163e-02 -7.599488e-01 -9.996938e-01 2.433272e-02 -4.500946e-03 8.310550e+01 +-5.892091e-03 2.495633e-02 9.996712e-01 -2.749563e+02 2.471889e-02 9.993867e-01 -2.480355e-02 -7.923450e-01 -9.996771e-01 2.456461e-02 -6.505373e-03 8.310287e+01 +-8.979482e-03 2.497505e-02 9.996477e-01 -2.740515e+02 2.409009e-02 9.994033e-01 -2.475256e-02 -8.243629e-01 -9.996695e-01 2.385934e-02 -9.575777e-03 8.309989e+01 +-1.297884e-02 2.421718e-02 9.996225e-01 -2.731523e+02 2.403540e-02 9.994253e-01 -2.390035e-02 -8.545490e-01 -9.996269e-01 2.371612e-02 -1.355346e-02 8.309384e+01 +-1.671141e-02 2.430921e-02 9.995648e-01 -2.722535e+02 2.474075e-02 9.994083e-01 -2.389178e-02 -8.908475e-01 -9.995542e-01 2.433071e-02 -1.730295e-02 8.307887e+01 +-2.034357e-02 2.519150e-02 9.994756e-01 -2.713531e+02 2.737051e-02 9.993218e-01 -2.463053e-02 -9.307137e-01 -9.994184e-01 2.685508e-02 -2.101928e-02 8.305487e+01 +-2.361517e-02 2.792387e-02 9.993311e-01 -2.704571e+02 2.983655e-02 9.991842e-01 -2.721471e-02 -9.732812e-01 -9.992758e-01 2.917390e-02 -2.442906e-02 8.302734e+01 +-2.619151e-02 2.885347e-02 9.992404e-01 -2.695677e+02 3.215086e-02 9.990905e-01 -2.800644e-02 -1.012488e+00 -9.991398e-01 3.139290e-02 -2.709535e-02 8.300021e+01 +-2.706064e-02 2.727959e-02 9.992615e-01 -2.686768e+02 3.494784e-02 9.990423e-01 -2.632720e-02 -1.048958e+00 -9.990227e-01 3.420959e-02 -2.798809e-02 8.297095e+01 +-2.680576e-02 2.341398e-02 9.993664e-01 -2.677887e+02 3.723816e-02 9.990551e-01 -2.240787e-02 -1.087200e+00 -9.989469e-01 3.661389e-02 -2.765232e-02 8.294441e+01 +-2.598387e-02 2.255508e-02 9.994079e-01 -2.669037e+02 3.865562e-02 9.990204e-01 -2.154132e-02 -1.126052e+00 -9.989147e-01 3.807300e-02 -2.683030e-02 8.292256e+01 +-2.372631e-02 2.499266e-02 9.994060e-01 -2.660292e+02 4.014155e-02 9.989051e-01 -2.402717e-02 -1.158098e+00 -9.989123e-01 3.954762e-02 -2.470357e-02 8.290390e+01 +-2.015503e-02 2.676816e-02 9.994384e-01 -2.651633e+02 4.169470e-02 9.987944e-01 -2.591009e-02 -1.185318e+00 -9.989271e-01 4.114906e-02 -2.124683e-02 8.288984e+01 +-1.507932e-02 2.673265e-02 9.995289e-01 -2.642886e+02 4.373228e-02 9.987036e-01 -2.605082e-02 -1.217156e+00 -9.989295e-01 4.331884e-02 -1.622886e-02 8.287621e+01 +-8.726426e-03 2.628674e-02 9.996163e-01 -2.634188e+02 4.488654e-02 9.986571e-01 -2.586967e-02 -1.249840e+00 -9.989540e-01 4.464355e-02 -9.894630e-03 8.287325e+01 +-1.520589e-03 2.526039e-02 9.996797e-01 -2.625486e+02 4.599382e-02 9.986247e-01 -2.516378e-02 -1.280969e+00 -9.989406e-01 4.594081e-02 -2.680322e-03 8.287522e+01 +5.977443e-03 2.388470e-02 9.996968e-01 -2.616766e+02 4.616678e-02 9.986421e-01 -2.413556e-02 -1.308238e+00 -9.989159e-01 4.629704e-02 4.866645e-03 8.288553e+01 +1.353122e-02 2.019297e-02 9.997045e-01 -2.608042e+02 4.599101e-02 9.987253e-01 -2.079569e-02 -1.331520e+00 -9.988502e-01 4.625880e-02 1.258527e-02 8.290333e+01 +2.127057e-02 1.772780e-02 9.996166e-01 -2.599281e+02 4.675335e-02 9.987313e-01 -1.870696e-02 -1.355081e+00 -9.986800e-01 4.713332e-02 2.041475e-02 8.292635e+01 +2.943506e-02 1.878469e-02 9.993902e-01 -2.590506e+02 4.722990e-02 9.986805e-01 -2.016242e-02 -1.383832e+00 -9.984503e-01 4.779457e-02 2.850903e-02 8.295438e+01 +3.782455e-02 2.081774e-02 9.990675e-01 -2.581688e+02 4.662005e-02 9.986576e-01 -2.257424e-02 -1.415451e+00 -9.981963e-01 4.743043e-02 3.680325e-02 8.299041e+01 +4.599657e-02 2.193234e-02 9.987008e-01 -2.572839e+02 4.537429e-02 9.986812e-01 -2.402170e-02 -1.451109e+00 -9.979106e-01 4.642025e-02 4.494074e-02 8.303330e+01 +5.435020e-02 2.132210e-02 9.982942e-01 -2.563976e+02 4.398605e-02 9.987503e-01 -2.372659e-02 -1.488358e+00 -9.975527e-01 4.520056e-02 5.334440e-02 8.308472e+01 +6.261447e-02 2.042004e-02 9.978289e-01 -2.555105e+02 4.273770e-02 9.988187e-01 -2.312212e-02 -1.526485e+00 -9.971224e-01 4.409268e-02 6.166780e-02 8.314556e+01 +7.079910e-02 1.985141e-02 9.972930e-01 -2.546230e+02 3.987635e-02 9.989464e-01 -2.271520e-02 -1.562907e+00 -9.966932e-01 4.137661e-02 6.993290e-02 8.321341e+01 +7.837050e-02 1.982955e-02 9.967271e-01 -2.537341e+02 3.771130e-02 9.990276e-01 -2.284048e-02 -1.604054e+00 -9.962108e-01 3.937788e-02 7.754649e-02 8.329056e+01 +8.418208e-02 2.039066e-02 9.962417e-01 -2.528447e+02 3.355402e-02 9.991656e-01 -2.328582e-02 -1.643031e+00 -9.958853e-01 3.538816e-02 8.342765e-02 8.337383e+01 +8.719032e-02 2.121060e-02 9.959658e-01 -2.519542e+02 2.989029e-02 9.992674e-01 -2.389762e-02 -1.681951e+00 -9.957432e-01 3.185334e-02 8.649246e-02 8.346339e+01 +8.896357e-02 2.143418e-02 9.958042e-01 -2.510548e+02 2.699181e-02 9.993494e-01 -2.392190e-02 -1.726676e+00 -9.956691e-01 2.900673e-02 8.832714e-02 8.355063e+01 +9.059598e-02 2.107237e-02 9.956647e-01 -2.501522e+02 2.498266e-02 9.994134e-01 -2.342490e-02 -1.772067e+00 -9.955744e-01 2.699654e-02 9.001639e-02 8.363769e+01 +9.243666e-02 2.056760e-02 9.955061e-01 -2.492462e+02 2.442871e-02 9.994388e-01 -2.291716e-02 -1.818586e+00 -9.954189e-01 2.643731e-02 9.188235e-02 8.372554e+01 +9.410203e-02 2.054336e-02 9.953506e-01 -2.483427e+02 2.379651e-02 9.994550e-01 -2.287784e-02 -1.863230e+00 -9.952782e-01 2.583871e-02 9.356188e-02 8.381597e+01 +9.488278e-02 2.047267e-02 9.952779e-01 -2.474403e+02 2.075016e-02 9.995306e-01 -2.253833e-02 -1.901229e+00 -9.952722e-01 2.279067e-02 9.441343e-02 8.391096e+01 +9.375181e-02 2.023062e-02 9.953900e-01 -2.465333e+02 1.692790e-02 9.996166e-01 -2.191090e-02 -1.945740e+00 -9.954517e-01 1.890405e-02 9.337340e-02 8.400559e+01 +9.070915e-02 2.019312e-02 9.956727e-01 -2.456224e+02 1.320909e-02 9.996820e-01 -2.147783e-02 -1.991930e+00 -9.957899e-01 1.510017e-02 9.041358e-02 8.409561e+01 +8.603205e-02 2.124539e-02 9.960658e-01 -2.447143e+02 1.083659e-02 9.996935e-01 -2.225875e-02 -2.037244e+00 -9.962335e-01 1.270892e-02 8.577546e-02 8.417861e+01 +8.003743e-02 2.192638e-02 9.965507e-01 -2.438130e+02 9.732634e-03 9.996932e-01 -2.277720e-02 -2.081787e+00 -9.967444e-01 1.152209e-02 7.979947e-02 8.425551e+01 +7.270627e-02 2.259855e-02 9.970973e-01 -2.429081e+02 8.923581e-03 9.996885e-01 -2.330797e-02 -2.126323e+00 -9.973135e-01 1.059231e-02 7.248196e-02 8.432341e+01 +6.510223e-02 2.315042e-02 9.976100e-01 -2.420020e+02 8.386478e-03 9.996828e-01 -2.374582e-02 -2.174312e+00 -9.978434e-01 9.912336e-03 6.488743e-02 8.438300e+01 +5.737615e-02 2.433871e-02 9.980559e-01 -2.411000e+02 8.517023e-03 9.996545e-01 -2.486733e-02 -2.221071e+00 -9.983163e-01 9.927253e-03 5.714903e-02 8.443197e+01 +4.904542e-02 2.527116e-02 9.984768e-01 -2.402039e+02 8.041504e-03 9.996374e-01 -2.569554e-02 -2.269376e+00 -9.987642e-01 9.289500e-03 4.882442e-02 8.447696e+01 +3.966598e-02 2.675396e-02 9.988547e-01 -2.393147e+02 7.655088e-03 9.996040e-01 -2.707803e-02 -2.313926e+00 -9.991837e-01 8.720394e-03 3.944547e-02 8.451471e+01 +2.927402e-02 2.837006e-02 9.991687e-01 -2.384304e+02 7.502934e-03 9.995627e-01 -2.860108e-02 -2.351636e+00 -9.995433e-01 8.333962e-03 2.904836e-02 8.454423e+01 +1.870870e-02 2.855439e-02 9.994171e-01 -2.375452e+02 7.312355e-03 9.995614e-01 -2.869541e-02 -2.393920e+00 -9.997983e-01 7.844943e-03 1.849169e-02 8.456314e+01 +8.011531e-03 2.658907e-02 9.996143e-01 -2.366575e+02 9.291465e-03 9.996013e-01 -2.666320e-02 -2.436713e+00 -9.999248e-01 9.501491e-03 7.761284e-03 8.456785e+01 +-2.325512e-03 2.493865e-02 9.996863e-01 -2.357767e+02 1.170738e-02 9.996211e-01 -2.490980e-02 -2.480094e+00 -9.999288e-01 1.164578e-02 -2.616599e-03 8.456247e+01 +-1.269291e-02 2.451475e-02 9.996189e-01 -2.349011e+02 1.410753e-02 9.996043e-01 -2.433527e-02 -2.522049e+00 -9.998200e-01 1.379326e-02 -1.303373e-02 8.454935e+01 +-2.286684e-02 2.556848e-02 9.994115e-01 -2.340290e+02 1.689287e-02 9.995400e-01 -2.518526e-02 -2.560857e+00 -9.995958e-01 1.630701e-02 -2.328825e-02 8.452621e+01 +-3.229053e-02 2.624507e-02 9.991339e-01 -2.331622e+02 1.990488e-02 9.994738e-01 -2.561071e-02 -2.603084e+00 -9.992803e-01 1.906065e-02 -3.279594e-02 8.449470e+01 +-4.043140e-02 2.654571e-02 9.988296e-01 -2.323021e+02 2.472325e-02 9.993675e-01 -2.555925e-02 -2.647305e+00 -9.988764e-01 2.366091e-02 -4.106213e-02 8.445356e+01 +-4.591315e-02 2.585184e-02 9.986109e-01 -2.314433e+02 2.992382e-02 9.992520e-01 -2.449264e-02 -2.690406e+00 -9.984972e-01 2.875771e-02 -4.665240e-02 8.440589e+01 +-4.949068e-02 2.471815e-02 9.984687e-01 -2.305922e+02 3.458534e-02 9.991366e-01 -2.302042e-02 -2.730178e+00 -9.981756e-01 3.339308e-02 -5.030283e-02 8.435609e+01 +-5.228410e-02 2.267996e-02 9.983747e-01 -2.297476e+02 3.768804e-02 9.990746e-01 -2.072218e-02 -2.769140e+00 -9.979209e-01 3.654334e-02 -5.309049e-02 8.430589e+01 +-5.472637e-02 2.136313e-02 9.982728e-01 -2.289207e+02 4.090216e-02 9.989799e-01 -1.913597e-02 -2.805402e+00 -9.976633e-01 3.978427e-02 -5.554434e-02 8.425581e+01 +-5.596114e-02 2.140964e-02 9.982034e-01 -2.281053e+02 4.434206e-02 9.988369e-01 -1.893734e-02 -2.840823e+00 -9.974478e-01 4.320262e-02 -5.684540e-02 8.420460e+01 +-5.611755e-02 2.237658e-02 9.981734e-01 -2.273134e+02 4.807959e-02 9.986495e-01 -1.968422e-02 -2.872170e+00 -9.972659e-01 4.688713e-02 -5.711762e-02 8.415418e+01 +-5.545965e-02 2.242701e-02 9.982090e-01 -2.265368e+02 5.052807e-02 9.985297e-01 -1.962693e-02 -2.902915e+00 -9.971816e-01 4.934906e-02 -5.651131e-02 8.410546e+01 +-5.465988e-02 2.184904e-02 9.982659e-01 -2.257778e+02 5.260649e-02 9.984351e-01 -1.897229e-02 -2.932963e+00 -9.971183e-01 5.147824e-02 -5.572375e-02 8.405944e+01 +-5.380948e-02 2.159131e-02 9.983177e-01 -2.250403e+02 5.440828e-02 9.983444e-01 -1.865928e-02 -2.966523e+00 -9.970679e-01 5.331269e-02 -5.489514e-02 8.401568e+01 +-5.271441e-02 2.096520e-02 9.983895e-01 -2.243226e+02 5.610237e-02 9.982627e-01 -1.800037e-02 -3.001553e+00 -9.970325e-01 5.506312e-02 -5.379903e-02 8.397326e+01 +-5.194036e-02 2.064179e-02 9.984368e-01 -2.236304e+02 5.803144e-02 9.981593e-01 -1.761716e-02 -3.038024e+00 -9.969627e-01 5.702567e-02 -5.304263e-02 8.393101e+01 +-5.126303e-02 2.073269e-02 9.984699e-01 -2.229618e+02 5.990413e-02 9.980481e-01 -1.764836e-02 -3.074000e+00 -9.968870e-01 5.890775e-02 -5.240494e-02 8.389096e+01 +-5.036265e-02 1.950575e-02 9.985405e-01 -2.223178e+02 6.126051e-02 9.979870e-01 -1.640519e-02 -3.113908e+00 -9.968505e-01 6.034488e-02 -5.145621e-02 8.385292e+01 +-4.960494e-02 1.921887e-02 9.985840e-01 -2.217020e+02 6.300227e-02 9.978839e-01 -1.607575e-02 -3.148339e+00 -9.967799e-01 6.211560e-02 -5.071081e-02 8.381633e+01 +-4.861702e-02 1.927318e-02 9.986315e-01 -2.211071e+02 6.380756e-02 9.978315e-01 -1.615137e-02 -3.186378e+00 -9.967773e-01 6.293500e-02 -4.974137e-02 8.378300e+01 +-4.705982e-02 1.985347e-02 9.986947e-01 -2.205255e+02 6.497046e-02 9.977462e-01 -1.677313e-02 -3.226920e+00 -9.967769e-01 6.409630e-02 -4.824364e-02 8.374869e+01 +-4.482378e-02 2.195581e-02 9.987536e-01 -2.199698e+02 6.848374e-02 9.974740e-01 -1.885415e-02 -3.266755e+00 -9.966448e-01 6.755325e-02 -4.621418e-02 8.371212e+01 +-4.117312e-02 2.415742e-02 9.988599e-01 -2.194360e+02 7.005449e-02 9.973172e-01 -2.123246e-02 -3.298955e+00 -9.966931e-01 6.910040e-02 -4.275500e-02 8.368192e+01 +-3.581393e-02 2.526681e-02 9.990390e-01 -2.189135e+02 7.045812e-02 9.972565e-01 -2.269593e-02 -3.334555e+00 -9.968716e-01 6.957756e-02 -3.749593e-02 8.365478e+01 +-2.906809e-02 2.413522e-02 9.992860e-01 -2.184169e+02 7.225918e-02 9.971436e-01 -2.198155e-02 -3.362897e+00 -9.969622e-01 7.156861e-02 -3.072906e-02 8.363622e+01 +-2.027815e-02 2.070338e-02 9.995800e-01 -2.179441e+02 7.274620e-02 9.971661e-01 -1.917762e-02 -3.394262e+00 -9.971443e-01 7.232674e-02 -2.172678e-02 8.362147e+01 +-8.338001e-03 1.886113e-02 9.997873e-01 -2.174914e+02 7.637178e-02 9.969138e-01 -1.817001e-02 -3.425713e+00 -9.970446e-01 7.620402e-02 -9.752728e-03 8.361487e+01 +7.993174e-03 1.952204e-02 9.997775e-01 -2.170522e+02 7.976092e-02 9.966114e-01 -2.009791e-02 -3.471406e+00 -9.967820e-01 7.990380e-02 6.408990e-03 8.361462e+01 +2.803353e-02 2.147225e-02 9.993763e-01 -2.166191e+02 7.946450e-02 9.965573e-01 -2.364075e-02 -3.524977e+00 -9.964435e-01 8.007766e-02 2.623074e-02 8.362100e+01 +5.342174e-02 2.394402e-02 9.982849e-01 -2.162004e+02 7.529846e-02 9.967696e-01 -2.793717e-02 -3.574493e+00 -9.957290e-01 7.666175e-02 5.144622e-02 8.366353e+01 +8.471648e-02 2.665329e-02 9.960485e-01 -2.157917e+02 7.281003e-02 9.968041e-01 -3.286620e-02 -3.630214e+00 -9.937414e-01 7.530661e-02 8.250511e-02 8.372444e+01 +1.195000e-01 2.823128e-02 9.924327e-01 -2.153766e+02 6.920180e-02 9.969277e-01 -3.669182e-02 -3.667906e+00 -9.904196e-01 7.306279e-02 1.171792e-01 8.378372e+01 +1.568303e-01 2.731430e-02 9.872478e-01 -2.149753e+02 6.441503e-02 9.972062e-01 -3.782255e-02 -3.706844e+00 -9.855227e-01 6.952530e-02 1.546326e-01 8.389058e+01 +1.957718e-01 2.444494e-02 9.803448e-01 -2.145778e+02 5.922236e-02 9.975699e-01 -3.670097e-02 -3.742523e+00 -9.788596e-01 6.524333e-02 1.938483e-01 8.401757e+01 +2.348106e-01 2.143684e-02 9.718047e-01 -2.141864e+02 5.259027e-02 9.980123e-01 -3.472199e-02 -3.775136e+00 -9.706175e-01 5.926055e-02 2.332165e-01 8.413880e+01 +2.747375e-01 1.825679e-02 9.613459e-01 -2.138129e+02 4.684228e-02 9.983784e-01 -3.234686e-02 -3.799905e+00 -9.603776e-01 5.391851e-02 2.734368e-01 8.430313e+01 +3.154195e-01 1.743367e-02 9.487922e-01 -2.134453e+02 3.930346e-02 9.987333e-01 -3.141749e-02 -3.829845e+00 -9.481381e-01 4.720049e-02 3.143347e-01 8.445321e+01 +3.553872e-01 1.960722e-02 9.345135e-01 -2.131011e+02 3.272479e-02 9.989060e-01 -3.340320e-02 -3.861511e+00 -9.341462e-01 4.245281e-02 3.543567e-01 8.464712e+01 +3.952906e-01 2.238116e-02 9.182834e-01 -2.127684e+02 2.761106e-02 9.989618e-01 -3.623318e-02 -3.890465e+00 -9.181411e-01 3.967741e-02 3.942623e-01 8.485198e+01 +4.350557e-01 2.290095e-02 9.001122e-01 -2.124374e+02 2.464174e-02 9.989992e-01 -3.732709e-02 -3.911045e+00 -9.000663e-01 3.841969e-02 4.340560e-01 8.503586e+01 +4.735064e-01 2.196629e-02 8.805164e-01 -2.121216e+02 2.275498e-02 9.990502e-01 -3.716008e-02 -3.929718e+00 -8.804964e-01 3.763166e-02 4.725568e-01 8.526274e+01 +5.107015e-01 2.233372e-02 8.594680e-01 -2.118194e+02 1.809390e-02 9.991619e-01 -3.671526e-02 -3.949775e+00 -8.595677e-01 3.430165e-02 5.098694e-01 8.550515e+01 +5.471514e-01 2.438526e-02 8.366784e-01 -2.115185e+02 1.346554e-02 9.991897e-01 -3.792759e-02 -3.971061e+00 -8.369254e-01 3.201846e-02 5.463797e-01 8.572801e+01 +5.834405e-01 2.804078e-02 8.116717e-01 -2.112345e+02 8.322697e-03 9.991449e-01 -4.049988e-02 -3.994680e+00 -8.121133e-01 3.038456e-02 5.827082e-01 8.599966e+01 +6.188914e-01 2.984542e-02 7.849094e-01 -2.109445e+02 6.053311e-03 9.990669e-01 -4.276152e-02 -4.010096e+00 -7.854533e-01 3.121603e-02 6.181333e-01 8.624943e+01 +6.550806e-01 2.912471e-02 7.549974e-01 -2.106654e+02 7.743520e-03 9.989455e-01 -4.525398e-02 -4.023285e+00 -7.555194e-01 3.549133e-02 6.541643e-01 8.655540e+01 +6.910122e-01 2.659991e-02 7.223535e-01 -2.103894e+02 1.037863e-02 9.988545e-01 -4.671010e-02 -4.041701e+00 -7.227686e-01 3.977428e-02 6.899446e-01 8.688026e+01 +7.253186e-01 2.658653e-02 6.878998e-01 -2.101149e+02 9.498089e-03 9.987724e-01 -4.861614e-02 -4.057861e+00 -6.883479e-01 4.179592e-02 7.241757e-01 8.719098e+01 +7.585576e-01 3.033233e-02 6.508996e-01 -2.098666e+02 2.725112e-03 9.987595e-01 -4.971866e-02 -4.079412e+00 -6.516003e-01 3.948824e-02 7.575340e-01 8.757423e+01 +7.908796e-01 3.466258e-02 6.109894e-01 -2.096250e+02 -6.177326e-03 9.987959e-01 -4.866751e-02 -4.099679e+00 -6.119407e-01 3.471585e-02 7.901414e-01 8.798664e+01 +8.211198e-01 3.614948e-02 5.696099e-01 -2.093759e+02 -1.142926e-02 9.988335e-01 -4.691373e-02 -4.118383e+00 -5.706415e-01 3.201157e-02 8.205752e-01 8.837945e+01 +8.485573e-01 3.048400e-02 5.282246e-01 -2.091376e+02 -7.642776e-03 9.989409e-01 -4.537159e-02 -4.142045e+00 -5.290483e-01 3.446328e-02 8.478916e-01 8.883220e+01 +8.733183e-01 2.471933e-02 4.865224e-01 -2.088979e+02 -4.703936e-03 9.990931e-01 -4.231848e-02 -4.176509e+00 -4.871273e-01 3.466893e-02 8.726426e-01 8.927459e+01 +8.949814e-01 2.115670e-02 4.456015e-01 -2.086855e+02 -6.177636e-03 9.993667e-01 -3.504125e-02 -4.202322e+00 -4.460607e-01 2.860850e-02 8.945454e-01 8.978611e+01 +9.137100e-01 2.312115e-02 4.057085e-01 -2.084907e+02 -1.088705e-02 9.994145e-01 -3.243711e-02 -4.220744e+00 -4.062209e-01 2.522114e-02 9.134268e-01 9.032449e+01 +9.295255e-01 2.409026e-02 3.679700e-01 -2.083002e+02 -1.377127e-02 9.994355e-01 -3.064359e-02 -4.238900e+00 -3.685005e-01 2.341658e-02 9.293326e-01 9.086022e+01 +9.431436e-01 2.149768e-02 3.316897e-01 -2.081201e+02 -1.329267e-02 9.995474e-01 -2.698626e-02 -4.257226e+00 -3.321197e-01 2.104287e-02 9.430025e-01 9.144700e+01 +9.551328e-01 1.047218e-02 2.959927e-01 -2.079344e+02 -4.600625e-03 9.997787e-01 -2.052636e-02 -4.282963e+00 -2.961422e-01 1.824364e-02 9.549696e-01 9.203216e+01 +9.654830e-01 3.744795e-03 2.604393e-01 -2.077744e+02 1.436448e-03 9.998049e-01 -1.970106e-02 -4.302909e+00 -2.604623e-01 1.939514e-02 9.652892e-01 9.266281e+01 +9.743312e-01 9.941077e-04 2.251172e-01 -2.076368e+02 4.088024e-03 9.997472e-01 -2.210824e-02 -4.328351e+00 -2.250823e-01 2.246103e-02 9.740808e-01 9.331804e+01 +9.818039e-01 -8.139986e-04 1.898958e-01 -2.075149e+02 5.541974e-03 9.996877e-01 -2.436804e-02 -4.350657e+00 -1.898166e-01 2.497703e-02 9.815018e-01 9.397382e+01 +9.876997e-01 5.738474e-05 1.563625e-01 -2.074211e+02 4.774906e-03 9.995225e-01 -3.052861e-02 -4.372521e+00 -1.562896e-01 3.089971e-02 9.872278e-01 9.467191e+01 +9.921389e-01 1.955223e-03 1.251260e-01 -2.073437e+02 2.188254e-03 9.994540e-01 -3.296842e-02 -4.397165e+00 -1.251222e-01 3.298306e-02 9.915929e-01 9.537757e+01 +9.952925e-01 2.634228e-03 9.688132e-02 -2.072813e+02 1.889121e-04 9.995759e-01 -2.911948e-02 -4.428422e+00 -9.691695e-02 2.900070e-02 9.948699e-01 9.612625e+01 +9.974613e-01 1.561222e-03 7.119416e-02 -2.072308e+02 6.223973e-06 9.997577e-01 -2.201097e-02 -4.457310e+00 -7.121128e-02 2.195553e-02 9.972196e-01 9.689979e+01 +9.988031e-01 2.735874e-03 4.883505e-02 -2.071985e+02 -1.945299e-03 9.998664e-01 -1.622889e-02 -4.475020e+00 -4.887293e-02 1.611447e-02 9.986750e-01 9.767733e+01 +9.995646e-01 4.832312e-03 2.910896e-02 -2.071848e+02 -4.455855e-03 9.999058e-01 -1.298372e-02 -4.491630e+00 -2.916896e-02 1.284836e-02 9.994919e-01 9.847905e+01 +9.999238e-01 4.665474e-03 1.143108e-02 -2.071789e+02 -4.510837e-03 9.998984e-01 -1.351648e-02 -4.504611e+00 -1.149298e-02 1.346388e-02 9.998433e-01 9.928910e+01 +9.999880e-01 2.960381e-03 -3.908674e-03 -2.071768e+02 -3.030247e-03 9.998335e-01 -1.799113e-02 -4.526189e+00 3.854764e-03 1.800276e-02 9.998305e-01 1.001176e+02 +9.998446e-01 2.625912e-03 -1.743157e-02 -2.071838e+02 -2.984290e-03 9.997840e-01 -2.056502e-02 -4.542892e+00 1.737381e-02 2.061384e-02 9.996366e-01 1.009674e+02 +9.995995e-01 1.944956e-03 -2.823207e-02 -2.072005e+02 -2.522236e-03 9.997882e-01 -2.042643e-02 -4.557635e+00 2.818636e-02 2.048946e-02 9.993927e-01 1.018364e+02 +9.993264e-01 4.962622e-03 -3.636144e-02 -2.072359e+02 -5.487266e-03 9.998821e-01 -1.434298e-02 -4.575898e+00 3.628598e-02 1.453284e-02 9.992358e-01 1.027324e+02 +9.991281e-01 7.130788e-03 -4.113636e-02 -2.072757e+02 -7.454446e-03 9.999424e-01 -7.719859e-03 -4.592025e+00 4.107894e-02 8.019776e-03 9.991237e-01 1.036470e+02 +9.990325e-01 1.194657e-02 -4.232435e-02 -2.073186e+02 -1.214754e-02 9.999161e-01 -4.494445e-03 -4.604814e+00 4.226711e-02 5.004233e-03 9.990938e-01 1.045700e+02 +9.990947e-01 1.307414e-02 -4.048166e-02 -2.073579e+02 -1.343713e-02 9.998718e-01 -8.707802e-03 -4.622258e+00 4.036263e-02 9.243876e-03 9.991423e-01 1.054955e+02 +9.992389e-01 1.082937e-02 -3.747389e-02 -2.073858e+02 -1.146657e-02 9.997926e-01 -1.683094e-02 -4.638737e+00 3.728385e-02 1.724782e-02 9.991559e-01 1.064273e+02 +9.993634e-01 1.200984e-02 -3.359435e-02 -2.074169e+02 -1.263280e-02 9.997510e-01 -1.839313e-02 -4.662245e+00 3.336509e-02 1.880581e-02 9.992663e-01 1.073709e+02 +9.994916e-01 1.190481e-02 -2.957764e-02 -2.074469e+02 -1.237377e-02 9.997998e-01 -1.572276e-02 -4.690067e+00 2.938454e-02 1.608076e-02 9.994388e-01 1.083214e+02 +9.996240e-01 1.125928e-02 -2.500312e-02 -2.074686e+02 -1.165269e-02 9.998097e-01 -1.564506e-02 -4.720481e+00 2.482221e-02 1.593053e-02 9.995650e-01 1.092776e+02 +9.997475e-01 1.080617e-02 -1.970060e-02 -2.074866e+02 -1.118951e-02 9.997481e-01 -1.945287e-02 -4.748338e+00 1.948543e-02 1.966839e-02 9.996167e-01 1.102383e+02 +9.998363e-01 1.163449e-02 -1.385679e-02 -2.075012e+02 -1.190359e-02 9.997390e-01 -1.949841e-02 -4.777295e+00 1.362632e-02 1.966016e-02 9.997139e-01 1.112068e+02 +9.999187e-01 1.044296e-02 -7.324155e-03 -2.075066e+02 -1.053169e-02 9.998703e-01 -1.218130e-02 -4.806525e+00 7.195997e-03 1.225744e-02 9.998990e-01 1.121888e+02 +9.999705e-01 7.517120e-03 -1.606460e-03 -2.075041e+02 -7.519605e-03 9.999705e-01 -1.545271e-03 -4.827464e+00 1.594797e-03 1.557305e-03 9.999975e-01 1.131740e+02 +9.999835e-01 5.234464e-03 2.361213e-03 -2.074968e+02 -5.241506e-03 9.999818e-01 2.985622e-03 -4.846691e+00 -2.345542e-03 -2.997948e-03 9.999928e-01 1.141535e+02 +9.999825e-01 2.585189e-03 5.331563e-03 -2.074851e+02 -2.563564e-03 9.999885e-01 -4.058891e-03 -4.863576e+00 -5.341995e-03 4.045152e-03 9.999776e-01 1.151183e+02 +9.999581e-01 2.843026e-03 8.704304e-03 -2.074752e+02 -2.719287e-03 9.998955e-01 -1.419493e-02 -4.883743e+00 -8.743752e-03 1.417066e-02 9.998614e-01 1.160764e+02 +9.999122e-01 5.487915e-03 1.205797e-02 -2.074670e+02 -5.290995e-03 9.998531e-01 -1.630291e-02 -4.912737e+00 -1.214567e-02 1.623767e-02 9.997944e-01 1.170403e+02 +9.998519e-01 8.990106e-03 1.467230e-02 -2.074464e+02 -8.798687e-03 9.998760e-01 -1.305927e-02 -4.905659e+00 -1.478789e-02 1.292823e-02 9.998071e-01 1.179889e+02 +9.997711e-01 1.342658e-02 1.665892e-02 -2.073928e+02 -1.325773e-02 9.998600e-01 -1.020499e-02 -4.794460e+00 -1.679361e-02 9.981795e-03 9.998092e-01 1.188931e+02 +9.996713e-01 1.835318e-02 1.790060e-02 -2.073571e+02 -1.816552e-02 9.997789e-01 -1.059078e-02 -4.742034e+00 -1.809102e-02 1.026213e-02 9.997837e-01 1.198181e+02 +9.996753e-01 1.849295e-02 1.753014e-02 -2.073097e+02 -1.823766e-02 9.997269e-01 -1.461251e-02 -4.670504e+00 -1.779558e-02 1.428806e-02 9.997396e-01 1.207291e+02 +9.997565e-01 1.559868e-02 1.560721e-02 -2.072693e+02 -1.532802e-02 9.997326e-01 -1.731392e-02 -4.643402e+00 -1.587311e-02 1.707048e-02 9.997283e-01 1.216551e+02 +9.998426e-01 1.209093e-02 1.298789e-02 -2.072316e+02 -1.188926e-02 9.998092e-01 -1.549434e-02 -4.611655e+00 -1.317276e-02 1.533749e-02 9.997956e-01 1.225805e+02 +9.998916e-01 1.126792e-02 9.477034e-03 -2.072073e+02 -1.115113e-02 9.998623e-01 -1.228757e-02 -4.603460e+00 -9.614184e-03 1.218055e-02 9.998796e-01 1.235133e+02 +9.999415e-01 9.160359e-03 5.756511e-03 -2.071844e+02 -9.107302e-03 9.999164e-01 -9.176734e-03 -4.591904e+00 -5.840092e-03 9.123769e-03 9.999413e-01 1.244387e+02 +9.999753e-01 6.635464e-03 2.306595e-03 -2.071696e+02 -6.611600e-03 9.999260e-01 -1.020464e-02 -4.588147e+00 -2.374137e-03 1.018914e-02 9.999453e-01 1.253607e+02 +9.999861e-01 5.222885e-03 -6.781364e-04 -2.071593e+02 -5.230707e-03 9.999131e-01 -1.209499e-02 -4.591410e+00 6.149072e-04 1.209836e-02 9.999266e-01 1.262755e+02 +9.999767e-01 5.622745e-03 -3.885079e-03 -2.071539e+02 -5.663958e-03 9.999269e-01 -1.067941e-02 -4.596783e+00 3.824748e-03 1.070116e-02 9.999354e-01 1.271844e+02 +9.999617e-01 5.549561e-03 -6.773440e-03 -2.071516e+02 -5.599264e-03 9.999574e-01 -7.341034e-03 -4.610152e+00 6.732412e-03 7.378679e-03 9.999501e-01 1.280869e+02 +9.999479e-01 3.076817e-03 -9.732421e-03 -2.071478e+02 -3.137377e-03 9.999758e-01 -6.213332e-03 -4.624992e+00 9.713069e-03 6.243542e-03 9.999333e-01 1.289703e+02 +9.999114e-01 2.994219e-03 -1.297060e-02 -2.071519e+02 -3.141434e-03 9.999307e-01 -1.134431e-02 -4.642383e+00 1.293574e-02 1.138405e-02 9.998515e-01 1.298325e+02 +9.998776e-01 3.363361e-03 -1.528090e-02 -2.071589e+02 -3.592567e-03 9.998811e-01 -1.499684e-02 -4.655650e+00 1.522865e-02 1.504990e-02 9.997708e-01 1.306766e+02 +9.998332e-01 4.565933e-03 -1.768481e-02 -2.071712e+02 -4.806167e-03 9.998964e-01 -1.356559e-02 -4.681036e+00 1.762104e-02 1.364832e-02 9.997516e-01 1.315055e+02 +9.997802e-01 4.268428e-03 -2.052687e-02 -2.071807e+02 -4.488536e-03 9.999328e-01 -1.068878e-02 -4.705958e+00 2.047987e-02 1.077856e-02 9.997322e-01 1.323124e+02 +9.997070e-01 1.816677e-03 -2.413677e-02 -2.071922e+02 -2.067552e-03 9.999440e-01 -1.037299e-02 -4.729400e+00 2.411658e-02 1.041985e-02 9.996549e-01 1.330993e+02 +9.995881e-01 1.760645e-03 -2.864605e-02 -2.072069e+02 -2.064759e-03 9.999418e-01 -1.059011e-02 -4.751155e+00 2.862574e-02 1.064489e-02 9.995335e-01 1.338591e+02 +9.994226e-01 3.908149e-03 -3.375323e-02 -2.072307e+02 -4.207290e-03 9.999524e-01 -8.796105e-03 -4.777156e+00 3.371726e-02 8.933035e-03 9.993915e-01 1.345972e+02 +9.992120e-01 5.429138e-03 -3.931725e-02 -2.072572e+02 -5.747988e-03 9.999514e-01 -8.001144e-03 -4.800037e+00 3.927190e-02 8.220833e-03 9.991948e-01 1.353118e+02 +9.989404e-01 5.562403e-03 -4.568545e-02 -2.072858e+02 -5.850519e-03 9.999638e-01 -6.175209e-03 -4.819858e+00 4.564945e-02 6.435949e-03 9.989368e-01 1.360000e+02 +9.986014e-01 6.686928e-03 -5.244634e-02 -2.073190e+02 -6.916589e-03 9.999672e-01 -4.198667e-03 -4.841679e+00 5.241655e-02 4.555544e-03 9.986149e-01 1.366618e+02 +9.981238e-01 7.587668e-03 -6.075594e-02 -2.073578e+02 -7.861414e-03 9.999600e-01 -4.267866e-03 -4.861537e+00 6.072113e-02 4.737486e-03 9.981435e-01 1.372934e+02 +9.974131e-01 7.884676e-03 -7.144943e-02 -2.074040e+02 -8.133175e-03 9.999618e-01 -3.187674e-03 -4.879982e+00 7.142157e-02 3.760539e-03 9.974391e-01 1.379016e+02 +9.963895e-01 7.473587e-03 -8.456974e-02 -2.074550e+02 -7.802669e-03 9.999632e-01 -3.561364e-03 -4.896312e+00 8.454002e-02 4.208376e-03 9.964112e-01 1.384802e+02 +9.948678e-01 6.331082e-03 -1.009853e-01 -2.075160e+02 -6.877424e-03 9.999635e-01 -5.062867e-03 -4.912852e+00 1.009496e-01 5.731402e-03 9.948750e-01 1.390393e+02 +9.927721e-01 8.658403e-03 -1.197018e-01 -2.075947e+02 -9.522071e-03 9.999326e-01 -6.645064e-03 -4.932800e+00 1.196362e-01 7.736843e-03 9.927877e-01 1.395799e+02 +9.900293e-01 1.096346e-02 -1.404343e-01 -2.076841e+02 -1.248168e-02 9.998727e-01 -9.934594e-03 -4.952480e+00 1.403076e-01 1.158839e-02 9.900402e-01 1.400991e+02 +9.862535e-01 1.411154e-02 -1.646360e-01 -2.077927e+02 -1.628967e-02 9.997966e-01 -1.188730e-02 -4.967272e+00 1.644348e-01 1.440576e-02 9.862828e-01 1.406243e+02 +9.812961e-01 1.288037e-02 -1.920729e-01 -2.079108e+02 -1.530917e-02 9.998204e-01 -1.116644e-02 -4.980438e+00 1.918946e-01 1.389806e-02 9.813171e-01 1.411498e+02 +9.750800e-01 1.419864e-02 -2.213989e-01 -2.080416e+02 -1.678048e-02 9.998113e-01 -9.784827e-03 -4.995249e+00 2.212182e-01 1.325617e-02 9.751343e-01 1.416494e+02 +9.674836e-01 1.819205e-02 -2.522787e-01 -2.081994e+02 -2.062746e-02 9.997626e-01 -7.012050e-03 -5.014132e+00 2.520913e-01 1.198791e-02 9.676292e-01 1.421558e+02 +9.580066e-01 2.371604e-02 -2.857636e-01 -2.083738e+02 -2.582659e-02 9.996599e-01 -3.618582e-03 -5.029354e+00 2.855806e-01 1.084693e-02 9.582933e-01 1.426288e+02 +9.460688e-01 2.861799e-02 -3.226994e-01 -2.085745e+02 -3.046033e-02 9.995357e-01 -6.595922e-04 -5.040287e+00 3.225308e-01 1.045355e-02 9.465013e-01 1.431133e+02 +9.315004e-01 3.183034e-02 -3.623450e-01 -2.087961e+02 -3.413487e-02 9.994172e-01 4.181985e-05 -5.047299e+00 3.621352e-01 1.232965e-02 9.320440e-01 1.435914e+02 +9.146640e-01 3.870800e-02 -4.023574e-01 -2.090317e+02 -4.082827e-02 9.991607e-01 3.308922e-03 -5.050961e+00 4.021478e-01 1.340101e-02 9.154767e-01 1.440193e+02 +8.963652e-01 4.766092e-02 -4.407469e-01 -2.092968e+02 -4.834042e-02 9.987839e-01 9.693306e-03 -5.062360e+00 4.406729e-01 1.261715e-02 8.975791e-01 1.444687e+02 +8.767649e-01 5.305173e-02 -4.779842e-01 -2.095780e+02 -5.245331e-02 9.985165e-01 1.461099e-02 -5.067831e+00 4.780503e-01 1.226145e-02 8.782469e-01 1.449065e+02 +8.553705e-01 5.504253e-02 -5.150841e-01 -2.098612e+02 -5.361877e-02 9.984055e-01 1.764929e-02 -5.069288e+00 5.152343e-01 1.252149e-02 8.569579e-01 1.452972e+02 +8.323436e-01 5.481799e-02 -5.515426e-01 -2.101744e+02 -5.309690e-02 9.984066e-01 1.910242e-02 -5.067648e+00 5.517109e-01 1.338542e-02 8.339280e-01 1.457149e+02 +8.073508e-01 5.644729e-02 -5.873657e-01 -2.105094e+02 -5.450423e-02 9.982922e-01 2.102076e-02 -5.064385e+00 5.875492e-01 1.504279e-02 8.090486e-01 1.461230e+02 +7.801051e-01 6.077568e-02 -6.226896e-01 -2.108611e+02 -5.760985e-02 9.980202e-01 2.523509e-02 -5.053059e+00 6.229905e-01 1.618703e-02 7.820619e-01 1.464847e+02 +7.509709e-01 6.372312e-02 -6.572535e-01 -2.112447e+02 -5.800522e-02 9.978512e-01 3.046917e-02 -5.042235e+00 6.577828e-01 1.524267e-02 7.530534e-01 1.468776e+02 +7.194793e-01 6.461580e-02 -6.915015e-01 -2.116406e+02 -5.559926e-02 9.978257e-01 3.539081e-02 -5.033033e+00 6.922848e-01 1.298402e-02 7.215076e-01 1.472216e+02 +6.850987e-01 6.380505e-02 -7.256505e-01 -2.120692e+02 -5.153581e-02 9.979059e-01 3.908814e-02 -5.023315e+00 7.266250e-01 1.061776e-02 6.869523e-01 1.475980e+02 +6.481661e-01 6.079595e-02 -7.590682e-01 -2.125226e+02 -4.887881e-02 9.980739e-01 3.820115e-02 -5.012870e+00 7.599287e-01 1.234166e-02 6.498893e-01 1.479573e+02 +6.085009e-01 5.674131e-02 -7.915220e-01 -2.129865e+02 -4.672003e-02 9.982718e-01 3.564536e-02 -5.001933e+00 7.921767e-01 1.528970e-02 6.101002e-01 1.482434e+02 +5.660051e-01 5.181307e-02 -8.227719e-01 -2.134884e+02 -4.323551e-02 9.985152e-01 3.313753e-02 -4.981594e+00 8.232673e-01 1.681696e-02 5.674048e-01 1.485702e+02 +5.212704e-01 4.542314e-02 -8.521819e-01 -2.140165e+02 -3.961448e-02 9.987939e-01 2.900615e-02 -4.963919e+00 8.524717e-01 1.863869e-02 5.224411e-01 1.488768e+02 +4.751671e-01 4.498237e-02 -8.787450e-01 -2.145608e+02 -4.056502e-02 9.987504e-01 2.919050e-02 -4.946807e+00 8.789601e-01 2.177594e-02 4.763980e-01 1.491018e+02 +4.282178e-01 4.938578e-02 -9.023250e-01 -2.151519e+02 -4.387662e-02 9.984641e-01 3.382506e-02 -4.933908e+00 9.026098e-01 2.510648e-02 4.297271e-01 1.493579e+02 +3.809126e-01 5.142480e-02 -9.231799e-01 -2.157461e+02 -4.357156e-02 9.983412e-01 3.763357e-02 -4.913185e+00 9.235839e-01 2.588928e-02 3.825214e-01 1.495424e+02 +3.347779e-01 5.416889e-02 -9.407388e-01 -2.163755e+02 -4.289244e-02 9.981875e-01 4.221287e-02 -4.894638e+00 9.413204e-01 2.621864e-02 3.364946e-01 1.497520e+02 +2.906649e-01 5.750404e-02 -9.550954e-01 -2.170268e+02 -4.328411e-02 9.979608e-01 4.691219e-02 -4.879639e+00 9.558454e-01 2.770473e-02 2.925612e-01 1.499336e+02 +2.479367e-01 5.965134e-02 -9.669380e-01 -2.176840e+02 -4.404604e-02 9.977645e-01 5.025904e-02 -4.856965e+00 9.677745e-01 3.012873e-02 2.500098e-01 1.500542e+02 +2.070153e-01 5.735136e-02 -9.766552e-01 -2.183642e+02 -4.494325e-02 9.977838e-01 4.906577e-02 -4.830778e+00 9.773049e-01 3.373670e-02 2.091341e-01 1.501830e+02 +1.701165e-01 5.454271e-02 -9.839133e-01 -2.190530e+02 -4.566781e-02 9.978306e-01 4.741836e-02 -4.805996e+00 9.843652e-01 3.686652e-02 1.722383e-01 1.502693e+02 +1.372529e-01 5.369168e-02 -9.890798e-01 -2.197673e+02 -4.427476e-02 9.978644e-01 4.802463e-02 -4.778166e+00 9.895461e-01 3.719975e-02 1.393370e-01 1.503611e+02 +1.096493e-01 5.443297e-02 -9.924787e-01 -2.204957e+02 -4.326937e-02 9.978142e-01 4.994520e-02 -4.749191e+00 9.930281e-01 3.746747e-02 1.117649e-01 1.504319e+02 +8.763727e-02 5.895359e-02 -9.944064e-01 -2.212396e+02 -4.258480e-02 9.975564e-01 5.538734e-02 -4.720425e+00 9.952418e-01 3.749260e-02 8.993365e-02 1.504803e+02 +7.002451e-02 6.203813e-02 -9.956143e-01 -2.219933e+02 -4.101269e-02 9.973994e-01 5.926484e-02 -4.689137e+00 9.967019e-01 3.668283e-02 7.238676e-02 1.505252e+02 +5.727910e-02 6.395336e-02 -9.963077e-01 -2.227584e+02 -3.928962e-02 9.973174e-01 6.175937e-02 -4.654403e+00 9.975848e-01 3.560703e-02 5.963815e-02 1.505609e+02 +4.801027e-02 6.427798e-02 -9.967765e-01 -2.235374e+02 -3.968368e-02 9.972621e-01 6.239792e-02 -4.619193e+00 9.980583e-01 3.656001e-02 5.042961e-02 1.505909e+02 +4.156617e-02 6.360533e-02 -9.971091e-01 -2.243266e+02 -3.854466e-02 9.973308e-01 6.201269e-02 -4.582603e+00 9.983920e-01 3.585560e-02 4.390687e-02 1.506177e+02 +3.778047e-02 6.269921e-02 -9.973171e-01 -2.251255e+02 -3.861981e-02 9.973756e-01 6.123990e-02 -4.545661e+00 9.985395e-01 3.620252e-02 4.010276e-02 1.506436e+02 +3.595908e-02 6.263344e-02 -9.973886e-01 -2.259370e+02 -3.843461e-02 9.973823e-01 6.124737e-02 -4.509117e+00 9.986139e-01 3.613184e-02 3.827225e-02 1.506685e+02 +3.655804e-02 6.349561e-02 -9.973123e-01 -2.267596e+02 -3.818437e-02 9.973394e-01 6.209764e-02 -4.472385e+00 9.986018e-01 3.581157e-02 3.888532e-02 1.506968e+02 +3.708679e-02 6.344414e-02 -9.972960e-01 -2.275969e+02 -3.741930e-02 9.973709e-01 6.205739e-02 -4.437985e+00 9.986113e-01 3.501661e-02 3.936333e-02 1.507273e+02 +3.774667e-02 6.315123e-02 -9.972899e-01 -2.284443e+02 -3.476818e-02 9.974798e-01 6.184733e-02 -4.401562e+00 9.986823e-01 3.233942e-02 3.984720e-02 1.507630e+02 +3.826672e-02 6.261247e-02 -9.973040e-01 -2.293018e+02 -3.215449e-02 9.975953e-01 6.139701e-02 -4.363185e+00 9.987501e-01 2.971834e-02 4.018797e-02 1.507988e+02 +3.857710e-02 6.273851e-02 -9.972841e-01 -2.301752e+02 -3.033409e-02 9.976406e-01 6.158757e-02 -4.323637e+00 9.987951e-01 2.787583e-02 4.038920e-02 1.508354e+02 +3.915508e-02 6.409239e-02 -9.971755e-01 -2.310595e+02 -2.837474e-02 9.976097e-01 6.300615e-02 -4.282961e+00 9.988302e-01 2.582758e-02 4.088010e-02 1.508727e+02 +3.955056e-02 6.456078e-02 -9.971297e-01 -2.319608e+02 -2.602719e-02 9.976385e-01 6.356139e-02 -4.240411e+00 9.988786e-01 2.343859e-02 4.113750e-02 1.509133e+02 +3.988791e-02 6.434969e-02 -9.971299e-01 -2.328709e+02 -2.353399e-02 9.977078e-01 6.344557e-02 -4.197591e+00 9.989270e-01 2.093574e-02 4.131088e-02 1.509544e+02 +4.016690e-02 6.378465e-02 -9.971550e-01 -2.337966e+02 -2.086976e-02 9.977962e-01 6.298502e-02 -4.152079e+00 9.989750e-01 1.828048e-02 4.140955e-02 1.509976e+02 +4.062960e-02 6.367425e-02 -9.971433e-01 -2.347343e+02 -1.800619e-02 9.978519e-01 6.298583e-02 -4.105241e+00 9.990121e-01 1.539566e-02 4.168886e-02 1.510414e+02 +4.073137e-02 6.406098e-02 -9.971144e-01 -2.356864e+02 -1.656466e-02 9.978487e-01 6.343152e-02 -4.059425e+00 9.990328e-01 1.393320e-02 4.170490e-02 1.510845e+02 +4.055603e-02 6.360033e-02 -9.971510e-01 -2.366573e+02 -1.323687e-02 9.979187e-01 6.311094e-02 -4.013183e+00 9.990896e-01 1.063963e-02 4.131349e-02 1.511310e+02 +3.927153e-02 6.199071e-02 -9.973038e-01 -2.376415e+02 -1.113401e-02 9.980389e-01 6.159799e-02 -3.964915e+00 9.991666e-01 8.684943e-03 3.988472e-02 1.511765e+02 +3.777789e-02 5.989982e-02 -9.974893e-01 -2.386346e+02 -8.359561e-03 9.981858e-01 5.962507e-02 -3.915718e+00 9.992512e-01 6.086066e-03 3.821009e-02 1.512192e+02 +3.507749e-02 5.911292e-02 -9.976348e-01 -2.396452e+02 -6.427305e-03 9.982418e-01 5.892291e-02 -3.863264e+00 9.993640e-01 4.345238e-03 3.539576e-02 1.512553e+02 +3.175372e-02 6.154572e-02 -9.975990e-01 -2.406693e+02 -2.725227e-03 9.981039e-01 6.149014e-02 -3.810995e+00 9.994920e-01 7.661474e-04 3.186124e-02 1.512927e+02 +2.667148e-02 6.558571e-02 -9.974904e-01 -2.417140e+02 -1.158350e-03 9.978467e-01 6.557818e-02 -3.758003e+00 9.996436e-01 -5.936201e-04 2.669002e-02 1.513242e+02 +2.075443e-02 6.713099e-02 -9.975283e-01 -2.427621e+02 7.077772e-04 9.977419e-01 6.716012e-02 -3.706079e+00 9.997844e-01 -2.099893e-03 2.066006e-02 1.513482e+02 +1.344909e-02 6.626830e-02 -9.977112e-01 -2.438232e+02 6.265912e-04 9.978007e-01 6.628271e-02 -3.650308e+00 9.999094e-01 -1.516595e-03 1.337799e-02 1.513636e+02 +6.287246e-03 6.610376e-02 -9.977929e-01 -2.448935e+02 8.176681e-04 9.978120e-01 6.611019e-02 -3.593888e+00 9.999799e-01 -1.231510e-03 6.219440e-03 1.513702e+02 +-1.021327e-03 6.944700e-02 -9.975851e-01 -2.459792e+02 -5.630788e-04 9.975854e-01 6.944762e-02 -3.535941e+00 9.999994e-01 6.326518e-04 -9.797549e-04 1.513675e+02 +-8.160829e-03 7.347979e-02 -9.972633e-01 -2.470687e+02 -2.183503e-03 9.972928e-01 7.349986e-02 -3.481830e+00 9.999643e-01 2.777351e-03 -7.978291e-03 1.513571e+02 +-1.534974e-02 7.309212e-02 -9.972070e-01 -2.481528e+02 -1.751712e-03 9.973210e-01 7.312746e-02 -3.428212e+00 9.998807e-01 2.869310e-03 -1.518058e-02 1.513408e+02 +-2.276162e-02 6.579913e-02 -9.975732e-01 -2.492291e+02 -1.466090e-03 9.978285e-01 6.584943e-02 -3.376470e+00 9.997399e-01 2.961375e-03 -2.261572e-02 1.513172e+02 +-2.982001e-02 6.031602e-02 -9.977338e-01 -2.503051e+02 -1.328388e-03 9.981744e-01 6.038238e-02 -3.329526e+00 9.995544e-01 3.125985e-03 -2.968545e-02 1.512848e+02 +-3.703545e-02 6.023176e-02 -9.974971e-01 -2.513868e+02 -1.332169e-03 9.981780e-01 6.032235e-02 -3.285207e+00 9.993131e-01 3.562904e-03 -3.688773e-02 1.512455e+02 +-4.404541e-02 6.324186e-02 -9.970258e-01 -2.524705e+02 -1.603237e-03 9.979885e-01 6.337377e-02 -3.242168e+00 9.990283e-01 4.389796e-03 -4.385543e-02 1.511984e+02 +-5.074230e-02 6.303314e-02 -9.967206e-01 -2.535518e+02 -3.173139e-04 9.980052e-01 6.313054e-02 -3.196416e+00 9.987118e-01 3.519666e-03 -5.062108e-02 1.511455e+02 +-5.744807e-02 6.299385e-02 -9.963591e-01 -2.546288e+02 -5.772245e-04 9.980050e-01 6.313121e-02 -3.149483e+00 9.983484e-01 4.201892e-03 -5.729710e-02 1.510839e+02 +-6.390273e-02 6.314497e-02 -9.959564e-01 -2.557074e+02 -2.550641e-03 9.979826e-01 6.343710e-02 -3.106599e+00 9.979529e-01 6.594134e-03 -6.361275e-02 1.510156e+02 +-6.989150e-02 6.350635e-02 -9.955311e-01 -2.567821e+02 -3.939634e-03 9.979461e-01 6.393701e-02 -3.061543e+00 9.975469e-01 8.390684e-03 -6.949776e-02 1.509401e+02 +-7.505207e-02 6.492395e-02 -9.950638e-01 -2.578551e+02 -4.282806e-03 9.978480e-01 6.542865e-02 -3.015595e+00 9.971705e-01 9.172224e-03 -7.461251e-02 1.508609e+02 +-7.943115e-02 6.782516e-02 -9.945302e-01 -2.589174e+02 -5.131857e-03 9.976415e-01 6.844724e-02 -2.966853e+00 9.968272e-01 1.054063e-02 -7.889575e-02 1.507758e+02 +-8.232050e-02 6.781525e-02 -9.942959e-01 -2.599639e+02 -7.217876e-03 9.976154e-01 6.863926e-02 -2.916979e+00 9.965798e-01 1.282712e-02 -8.163471e-02 1.506863e+02 +-8.355035e-02 6.492587e-02 -9.943862e-01 -2.609895e+02 -1.026789e-02 9.977662e-01 6.600930e-02 -2.870050e+00 9.964507e-01 1.572535e-02 -8.269706e-02 1.505959e+02 +-8.366743e-02 6.453090e-02 -9.944021e-01 -2.620037e+02 -1.326197e-02 9.977405e-01 6.586341e-02 -2.826133e+00 9.964055e-01 1.869835e-02 -8.262258e-02 1.505055e+02 +-8.411321e-02 6.643426e-02 -9.942391e-01 -2.630003e+02 -1.411313e-02 9.975955e-01 6.785252e-02 -2.782584e+00 9.963563e-01 1.973912e-02 -8.297337e-02 1.504210e+02 +-8.457056e-02 7.165133e-02 -9.938380e-01 -2.639796e+02 -1.585442e-02 9.971881e-01 7.324202e-02 -2.740846e+00 9.962914e-01 2.195084e-02 -8.319677e-02 1.503356e+02 +-8.494708e-02 7.309666e-02 -9.937006e-01 -2.649348e+02 -1.757168e-02 9.970404e-01 7.484448e-02 -2.697823e+00 9.962305e-01 2.381880e-02 -8.341124e-02 1.502502e+02 +-8.571882e-02 6.996901e-02 -9.938594e-01 -2.658624e+02 -1.849469e-02 9.972473e-01 7.180268e-02 -2.654745e+00 9.961477e-01 2.453596e-02 -8.418881e-02 1.501683e+02 +-8.596366e-02 6.794911e-02 -9.939784e-01 -2.667666e+02 -2.026568e-02 9.973459e-01 6.993200e-02 -2.612643e+00 9.960922e-01 2.615526e-02 -8.435846e-02 1.500877e+02 +-8.432395e-02 6.854085e-02 -9.940783e-01 -2.676511e+02 -2.356462e-02 9.972152e-01 7.075606e-02 -2.573744e+00 9.961598e-01 2.939150e-02 -8.247399e-02 1.500081e+02 +-8.127268e-02 7.023481e-02 -9.942142e-01 -2.685157e+02 -2.783828e-02 9.969649e-01 7.270481e-02 -2.540023e+00 9.963031e-01 3.358613e-02 -7.907080e-02 1.499341e+02 +-7.739311e-02 6.921680e-02 -9.945950e-01 -2.693685e+02 -3.029549e-02 9.969632e-01 7.173903e-02 -2.504933e+00 9.965403e-01 3.568385e-02 -7.506113e-02 1.498662e+02 +-7.344499e-02 6.651653e-02 -9.950786e-01 -2.702147e+02 -3.143136e-02 9.971232e-01 6.897311e-02 -2.469877e+00 9.968039e-01 3.634240e-02 -7.114300e-02 1.498050e+02 +-6.952604e-02 6.458528e-02 -9.954872e-01 -2.710650e+02 -3.044780e-02 9.972997e-01 6.682940e-02 -2.433634e+00 9.971154e-01 3.495678e-02 -6.737182e-02 1.497491e+02 +-6.597323e-02 6.385678e-02 -9.957760e-01 -2.719100e+02 -3.007273e-02 9.973695e-01 6.595140e-02 -2.397318e+00 9.973682e-01 3.429673e-02 -6.387934e-02 1.496960e+02 +-6.329160e-02 6.466668e-02 -9.958978e-01 -2.727551e+02 -3.166466e-02 9.972659e-01 6.676790e-02 -2.361004e+00 9.974927e-01 3.576061e-02 -6.107091e-02 1.496427e+02 +-6.087648e-02 6.522533e-02 -9.960119e-01 -2.735966e+02 -3.161997e-02 9.972358e-01 6.723812e-02 -2.326093e+00 9.976444e-01 3.558709e-02 -5.864577e-02 1.495937e+02 +-5.872467e-02 6.403467e-02 -9.962183e-01 -2.744320e+02 -3.270874e-02 9.972813e-01 6.603111e-02 -2.291365e+00 9.977383e-01 3.646270e-02 -5.647052e-02 1.495473e+02 +-5.551244e-02 6.182965e-02 -9.965417e-01 -2.752628e+02 -3.401548e-02 9.973843e-01 6.377678e-02 -2.257073e+00 9.978784e-01 3.743825e-02 -5.326407e-02 1.495011e+02 +-5.165380e-02 5.987559e-02 -9.968685e-01 -2.760902e+02 -3.767464e-02 9.973736e-01 6.185809e-02 -2.222677e+00 9.979542e-01 4.075186e-02 -4.926234e-02 1.494568e+02 +-4.707733e-02 6.172852e-02 -9.969821e-01 -2.769178e+02 -3.813463e-02 9.972500e-01 6.354584e-02 -2.185534e+00 9.981631e-01 4.101111e-02 -4.459387e-02 1.494198e+02 +-4.190194e-02 6.700555e-02 -9.968723e-01 -2.777459e+02 -3.680946e-02 9.969677e-01 6.855921e-02 -2.147924e+00 9.984435e-01 3.956709e-02 -3.930844e-02 1.493894e+02 +-3.717246e-02 7.269665e-02 -9.966611e-01 -2.785735e+02 -3.658618e-02 9.965828e-01 7.405551e-02 -2.108097e+00 9.986389e-01 3.921684e-02 -3.438574e-02 1.493618e+02 +-3.246424e-02 7.391080e-02 -9.967363e-01 -2.793934e+02 -3.555763e-02 9.965452e-01 7.505478e-02 -2.066294e+00 9.988402e-01 3.787817e-02 -2.972399e-02 1.493376e+02 +-2.897203e-02 7.272258e-02 -9.969313e-01 -2.802109e+02 -3.441805e-02 9.966860e-01 7.370494e-02 -2.021877e+00 9.989875e-01 3.644781e-02 -2.637305e-02 1.493180e+02 +-2.518120e-02 7.077364e-02 -9.971745e-01 -2.810264e+02 -3.274820e-02 9.968970e-01 7.158094e-02 -1.972919e+00 9.991464e-01 3.445817e-02 -2.278535e-02 1.493013e+02 +-2.150556e-02 6.920353e-02 -9.973707e-01 -2.818426e+02 -3.309139e-02 9.970055e-01 6.989173e-02 -1.926127e+00 9.992210e-01 3.450745e-02 -1.915112e-02 1.492841e+02 +-1.839649e-02 6.894732e-02 -9.974507e-01 -2.826688e+02 -3.371414e-02 9.970094e-01 6.953864e-02 -1.879199e+00 9.992622e-01 3.490745e-02 -1.601697e-02 1.492681e+02 +-1.601497e-02 6.777060e-02 -9.975724e-01 -2.834957e+02 -3.335205e-02 9.971089e-01 6.827457e-02 -1.835735e+00 9.993154e-01 3.436450e-02 -1.370838e-02 1.492555e+02 +-1.418548e-02 6.710331e-02 -9.976452e-01 -2.843270e+02 -3.245536e-02 9.971889e-01 6.753412e-02 -1.790523e+00 9.993725e-01 3.333694e-02 -1.196774e-02 1.492453e+02 +-1.244499e-02 6.793622e-02 -9.976120e-01 -2.851659e+02 -3.105936e-02 9.971816e-01 6.829439e-02 -1.746381e+00 9.994401e-01 3.183511e-02 -1.029986e-02 1.492364e+02 +-1.163715e-02 6.881163e-02 -9.975618e-01 -2.860071e+02 -3.122563e-02 9.971178e-01 6.914528e-02 -1.703369e+00 9.994446e-01 3.195415e-02 -9.454919e-03 1.492259e+02 +-1.149864e-02 6.985677e-02 -9.974907e-01 -2.868514e+02 -3.034171e-02 9.970730e-01 7.017729e-02 -1.659932e+00 9.994735e-01 3.107252e-02 -9.345404e-03 1.492159e+02 +-1.250614e-02 7.035554e-02 -9.974436e-01 -2.876949e+02 -2.955712e-02 9.970597e-01 7.069907e-02 -1.615329e+00 9.994849e-01 3.036573e-02 -1.038986e-02 1.492050e+02 +-1.406939e-02 7.165001e-02 -9.973306e-01 -2.885374e+02 -2.819029e-02 9.970044e-01 7.202427e-02 -1.571373e+00 9.995036e-01 2.912838e-02 -1.200741e-02 1.491934e+02 +-1.578705e-02 7.293189e-02 -9.972120e-01 -2.893746e+02 -2.843859e-02 9.969000e-01 7.335931e-02 -1.529689e+00 9.994709e-01 2.951742e-02 -1.366403e-02 1.491754e+02 +-1.749479e-02 7.390724e-02 -9.971116e-01 -2.902070e+02 -2.847598e-02 9.968229e-01 7.438548e-02 -1.488007e+00 9.994414e-01 2.969509e-02 -1.533462e-02 1.491558e+02 +-1.938476e-02 7.354463e-02 -9.971035e-01 -2.910427e+02 -2.789355e-02 9.968629e-01 7.406918e-02 -1.446777e+00 9.994230e-01 2.924857e-02 -1.727253e-02 1.491365e+02 +-2.168815e-02 7.182820e-02 -9.971812e-01 -2.918727e+02 -2.827914e-02 9.969726e-01 7.242825e-02 -1.406039e+00 9.993648e-01 2.977026e-02 -1.959125e-02 1.491137e+02 +-2.377805e-02 6.989984e-02 -9.972706e-01 -2.927028e+02 -2.844545e-02 9.971014e-01 7.056623e-02 -1.365766e+00 9.993125e-01 3.004574e-02 -2.172080e-02 1.490889e+02 +-2.598025e-02 6.824709e-02 -9.973301e-01 -2.935337e+02 -2.855407e-02 9.972091e-01 6.898265e-02 -1.325920e+00 9.992546e-01 3.027001e-02 -2.395901e-02 1.490628e+02 +-2.798130e-02 6.631859e-02 -9.974061e-01 -2.943670e+02 -2.903984e-02 9.973217e-01 6.712768e-02 -1.286556e+00 9.991866e-01 3.084283e-02 -2.598048e-02 1.490353e+02 +-2.908711e-02 6.382140e-02 -9.975373e-01 -2.952044e+02 -3.154509e-02 9.974039e-01 6.473270e-02 -1.249777e+00 9.990790e-01 3.335029e-02 -2.699834e-02 1.490025e+02 +-2.962850e-02 6.275170e-02 -9.975893e-01 -2.960479e+02 -3.218081e-02 9.974502e-01 6.369874e-02 -1.210964e+00 9.990428e-01 3.399053e-02 -2.753355e-02 1.489731e+02 +-2.975906e-02 6.549116e-02 -9.974093e-01 -2.969004e+02 -3.040748e-02 9.973301e-01 6.639322e-02 -1.167559e+00 9.990945e-01 3.230450e-02 -2.768818e-02 1.489468e+02 +-3.008048e-02 7.013802e-02 -9.970836e-01 -2.977616e+02 -3.115760e-02 9.969845e-01 7.107104e-02 -1.125818e+00 9.990618e-01 3.320458e-02 -2.780444e-02 1.489173e+02 +-3.014130e-02 7.322862e-02 -9.968596e-01 -2.986280e+02 -3.193325e-02 9.967331e-01 7.418489e-02 -1.082347e+00 9.990355e-01 3.406899e-02 -2.770441e-02 1.488865e+02 +-3.090027e-02 6.991280e-02 -9.970744e-01 -2.994968e+02 -3.152629e-02 9.969862e-01 7.088367e-02 -1.034226e+00 9.990252e-01 3.362438e-02 -2.860305e-02 1.488579e+02 +-3.124489e-02 6.724497e-02 -9.972471e-01 -3.003726e+02 -3.112623e-02 9.971849e-01 6.821601e-02 -9.862713e-01 9.990270e-01 3.317194e-02 -2.906385e-02 1.488279e+02 +-3.160085e-02 6.516872e-02 -9.973737e-01 -3.012570e+02 -3.239796e-02 9.972810e-01 6.618917e-02 -9.411879e-01 9.989754e-01 3.440451e-02 -2.940359e-02 1.487957e+02 +-3.193711e-02 6.495782e-02 -9.973768e-01 -3.021527e+02 -3.282516e-02 9.972794e-01 6.600259e-02 -8.965176e-01 9.989507e-01 3.484698e-02 -2.971796e-02 1.487630e+02 +-3.245557e-02 6.621506e-02 -9.972774e-01 -3.030592e+02 -3.411717e-02 9.971481e-01 6.731681e-02 -8.505369e-01 9.988907e-01 3.620909e-02 -3.010394e-02 1.487291e+02 +-3.291984e-02 6.781017e-02 -9.971550e-01 -3.039731e+02 -3.469762e-02 9.970168e-01 6.894628e-02 -8.048631e-01 9.988556e-01 3.686860e-02 -3.046878e-02 1.486956e+02 +-3.282575e-02 6.763652e-02 -9.971699e-01 -3.048944e+02 -3.473414e-02 9.970277e-01 6.877030e-02 -7.589259e-01 9.988574e-01 3.689327e-02 -3.037888e-02 1.486627e+02 +-3.183158e-02 6.539492e-02 -9.973516e-01 -3.058223e+02 -3.529001e-02 9.971615e-01 6.650879e-02 -7.113172e-01 9.988701e-01 3.731363e-02 -2.943344e-02 1.486302e+02 +-3.112944e-02 6.405132e-02 -9.974610e-01 -3.067552e+02 -3.643967e-02 9.972084e-01 6.517236e-02 -6.645960e-01 9.988509e-01 3.837592e-02 -2.870853e-02 1.485969e+02 +-3.124689e-02 6.333720e-02 -9.975029e-01 -3.076988e+02 -3.641415e-02 9.972555e-01 6.446219e-02 -6.197519e-01 9.988482e-01 3.833745e-02 -2.885476e-02 1.485652e+02 +-3.166128e-02 6.142679e-02 -9.976093e-01 -3.086450e+02 -3.486225e-02 9.974345e-01 6.252247e-02 -5.780574e-01 9.988905e-01 3.675845e-02 -2.943857e-02 1.485350e+02 +-3.148768e-02 5.925522e-02 -9.977461e-01 -3.095929e+02 -3.359326e-02 9.976144e-01 6.030758e-02 -5.368955e-01 9.989395e-01 3.541649e-02 -2.942199e-02 1.485045e+02 +-3.102496e-02 5.837877e-02 -9.978123e-01 -3.105428e+02 -3.373227e-02 9.976630e-01 5.941889e-02 -4.968028e-01 9.989493e-01 3.550194e-02 -2.898321e-02 1.484723e+02 +-3.033396e-02 5.932239e-02 -9.977779e-01 -3.114942e+02 -3.314240e-02 9.976286e-01 6.032111e-02 -4.585262e-01 9.989902e-01 3.489853e-02 -2.829594e-02 1.484425e+02 +-2.960414e-02 6.034157e-02 -9.977387e-01 -3.124495e+02 -3.051290e-02 9.976564e-01 6.124196e-02 -4.200840e-01 9.990959e-01 3.225692e-02 -2.769356e-02 1.484157e+02 +-2.880779e-02 6.018296e-02 -9.977716e-01 -3.134019e+02 -2.950065e-02 9.976998e-01 6.103040e-02 -3.825102e-01 9.991496e-01 3.119306e-02 -2.696609e-02 1.483885e+02 +-2.798657e-02 5.990097e-02 -9.978119e-01 -3.143547e+02 -2.974231e-02 9.977110e-01 6.072914e-02 -3.449637e-01 9.991658e-01 3.137683e-02 -2.614092e-02 1.483596e+02 +-2.710990e-02 5.999579e-02 -9.978304e-01 -3.153042e+02 -2.830984e-02 9.977508e-01 6.076016e-02 -3.064296e-01 9.992315e-01 2.989562e-02 -2.535045e-02 1.483336e+02 +-2.611763e-02 6.154690e-02 -9.977624e-01 -3.162536e+02 -2.722895e-02 9.976887e-01 6.225512e-02 -2.682537e-01 9.992880e-01 2.879397e-02 -2.438141e-02 1.483092e+02 +-2.498152e-02 6.307180e-02 -9.976963e-01 -3.172030e+02 -2.773350e-02 9.975799e-01 6.375888e-02 -2.373528e-01 9.993032e-01 2.926240e-02 -2.317186e-02 1.482890e+02 +-2.357063e-02 6.409138e-02 -9.976656e-01 -3.181477e+02 -2.718191e-02 9.975328e-01 6.472506e-02 -2.033352e-01 9.993526e-01 2.864406e-02 -2.177035e-02 1.482694e+02 +-2.231169e-02 6.445347e-02 -9.976712e-01 -3.190871e+02 -2.618286e-02 9.975397e-01 6.503054e-02 -1.642148e-01 9.994082e-01 2.757282e-02 -2.056921e-02 1.482463e+02 +-2.092515e-02 6.329405e-02 -9.977755e-01 -3.200177e+02 -2.575783e-02 9.976286e-01 6.382494e-02 -1.238960e-01 9.994492e-01 2.703608e-02 -1.924521e-02 1.482179e+02 +-2.028235e-02 6.143697e-02 -9.979049e-01 -3.209473e+02 -2.744997e-02 9.976997e-01 6.198227e-02 -8.509348e-02 9.994174e-01 2.864960e-02 -1.854925e-02 1.481857e+02 +-2.014907e-02 5.855427e-02 -9.980808e-01 -3.218742e+02 -2.689593e-02 9.978905e-01 5.908609e-02 -4.592552e-02 9.994352e-01 2.803484e-02 -1.853170e-02 1.481596e+02 +-1.994830e-02 6.057960e-02 -9.979640e-01 -3.228014e+02 -2.672862e-02 9.977735e-01 6.110233e-02 -5.957702e-03 9.994437e-01 2.789309e-02 -1.828468e-02 1.481327e+02 +-1.935557e-02 6.329743e-02 -9.978070e-01 -3.237256e+02 -2.626578e-02 9.976173e-01 6.379492e-02 3.169360e-02 9.994676e-01 2.744297e-02 -1.764689e-02 1.481077e+02 +-1.879097e-02 6.542374e-02 -9.976806e-01 -3.246435e+02 -2.829076e-02 9.974224e-01 6.593968e-02 6.860811e-02 9.994231e-01 2.946421e-02 -1.689164e-02 1.480807e+02 +-1.826241e-02 6.281470e-02 -9.978581e-01 -3.255561e+02 -2.650663e-02 9.976433e-01 6.328631e-02 1.104512e-01 9.994818e-01 2.760561e-02 -1.655436e-02 1.480598e+02 +-1.801582e-02 6.330498e-02 -9.978316e-01 -3.264690e+02 -2.523773e-02 9.976468e-01 6.374893e-02 1.520655e-01 9.995192e-01 2.633149e-02 -1.637575e-02 1.480393e+02 +-1.756630e-02 6.589382e-02 -9.976720e-01 -3.273800e+02 -2.556316e-02 9.974702e-01 6.633060e-02 1.907993e-01 9.995189e-01 2.666883e-02 -1.583741e-02 1.480179e+02 +-1.725025e-02 6.623916e-02 -9.976546e-01 -3.282842e+02 -2.667599e-02 9.974174e-01 6.668468e-02 2.288998e-01 9.994953e-01 2.776375e-02 -1.543871e-02 1.479949e+02 +-1.696725e-02 6.382753e-02 -9.978167e-01 -3.291821e+02 -2.674928e-02 9.975742e-01 6.426688e-02 2.686740e-01 9.994982e-01 2.778131e-02 -1.521875e-02 1.479748e+02 +-1.684123e-02 6.414389e-02 -9.977985e-01 -3.300846e+02 -2.752491e-02 9.975321e-01 6.459136e-02 3.166239e-01 9.994793e-01 2.855211e-02 -1.503411e-02 1.479437e+02 +-1.664117e-02 6.620289e-02 -9.976674e-01 -3.309916e+02 -2.768377e-02 9.973925e-01 6.664643e-02 3.729860e-01 9.994782e-01 2.872827e-02 -1.476503e-02 1.479187e+02 +-1.617805e-02 6.883065e-02 -9.974972e-01 -3.318843e+02 -2.816058e-02 9.972006e-01 6.926693e-02 4.247571e-01 9.994725e-01 2.921070e-02 -1.419445e-02 1.478985e+02 +-1.607918e-02 6.921295e-02 -9.974723e-01 -3.327688e+02 -2.838129e-02 9.971677e-01 6.964933e-02 4.794155e-01 9.994679e-01 2.942945e-02 -1.406928e-02 1.478794e+02 +-1.582850e-02 6.879158e-02 -9.975055e-01 -3.336308e+02 -2.839261e-02 9.971972e-01 6.922088e-02 5.224037e-01 9.994716e-01 2.941745e-02 -1.383096e-02 1.478682e+02 +-1.578276e-02 6.622729e-02 -9.976797e-01 -3.344878e+02 -2.819798e-02 9.973776e-01 6.665333e-02 5.643558e-01 9.994778e-01 2.918453e-02 -1.387389e-02 1.478598e+02 +-1.559907e-02 6.310159e-02 -9.978852e-01 -3.353390e+02 -2.712977e-02 9.976125e-01 6.350845e-02 6.031181e-01 9.995102e-01 2.806307e-02 -1.384990e-02 1.478492e+02 +-1.580734e-02 6.192050e-02 -9.979559e-01 -3.361940e+02 -2.708565e-02 9.976878e-01 6.233291e-02 6.405812e-01 9.995082e-01 2.801560e-02 -1.409363e-02 1.478399e+02 +-1.624604e-02 6.407757e-02 -9.978127e-01 -3.370551e+02 -2.635971e-02 9.975700e-01 6.449119e-02 6.727457e-01 9.995205e-01 2.734978e-02 -1.451750e-02 1.478307e+02 +-1.701736e-02 6.820238e-02 -9.975263e-01 -3.379175e+02 -2.588801e-02 9.973063e-01 6.862899e-02 7.047747e-01 9.995200e-01 2.699185e-02 -1.520590e-02 1.478214e+02 +-1.793563e-02 7.099411e-02 -9.973155e-01 -3.387707e+02 -2.513896e-02 9.971285e-01 7.143292e-02 7.400700e-01 9.995231e-01 2.635266e-02 -1.609941e-02 1.478078e+02 +-1.895825e-02 7.190941e-02 -9.972310e-01 -3.396185e+02 -2.465461e-02 9.970733e-01 7.236676e-02 7.773835e-01 9.995163e-01 2.595829e-02 -1.712986e-02 1.477899e+02 +-2.008245e-02 7.275336e-02 -9.971477e-01 -3.404617e+02 -2.387268e-02 9.970296e-01 7.322556e-02 8.188686e-01 9.995133e-01 2.527514e-02 -1.828598e-02 1.477714e+02 +-2.150248e-02 7.287624e-02 -9.971092e-01 -3.413010e+02 -2.208644e-02 9.970617e-01 7.334908e-02 8.600913e-01 9.995248e-01 2.359978e-02 -1.982972e-02 1.477529e+02 +-2.400631e-02 7.209920e-02 -9.971085e-01 -3.421373e+02 -2.219004e-02 9.971118e-01 7.263370e-02 8.986743e-01 9.994655e-01 2.386954e-02 -2.233709e-02 1.477301e+02 +-2.739057e-02 6.983051e-02 -9.971827e-01 -3.429755e+02 -2.108065e-02 9.972948e-01 7.041742e-02 9.441748e-01 9.994025e-01 2.295004e-02 -2.584440e-02 1.477037e+02 +-3.130756e-02 6.615356e-02 -9.973182e-01 -3.438132e+02 -2.148781e-02 9.975321e-01 6.684231e-02 9.937445e-01 9.992788e-01 2.352285e-02 -2.980880e-02 1.476724e+02 +-3.440032e-02 6.496363e-02 -9.972945e-01 -3.446568e+02 -2.291899e-02 9.975714e-01 6.577225e-02 1.041610e+00 9.991453e-01 2.511957e-02 -3.282788e-02 1.476361e+02 +-3.691737e-02 6.707794e-02 -9.970645e-01 -3.455078e+02 -2.513538e-02 9.973666e-01 6.802895e-02 1.089789e+00 9.990022e-01 2.757305e-02 -3.513412e-02 1.475968e+02 +-3.893127e-02 6.966359e-02 -9.968106e-01 -3.463664e+02 -2.541634e-02 9.971750e-01 7.068173e-02 1.131349e+00 9.989186e-01 2.808700e-02 -3.705070e-02 1.475624e+02 +-4.045200e-02 7.033716e-02 -9.967027e-01 -3.472304e+02 -2.404512e-02 9.971618e-01 7.134547e-02 1.170817e+00 9.988922e-01 2.685190e-02 -3.864592e-02 1.475339e+02 +-4.208489e-02 6.778745e-02 -9.968118e-01 -3.480884e+02 -2.309805e-02 9.973630e-01 6.880014e-02 1.213215e+00 9.988470e-01 2.591985e-02 -4.040816e-02 1.475020e+02 +-4.361564e-02 6.575739e-02 -9.968819e-01 -3.489513e+02 -2.314360e-02 9.974972e-01 6.681057e-02 1.261341e+00 9.987803e-01 2.598542e-02 -4.198462e-02 1.474654e+02 +-4.472790e-02 6.566899e-02 -9.968385e-01 -3.498171e+02 -2.315478e-02 9.975009e-01 6.675159e-02 1.308257e+00 9.987309e-01 2.606723e-02 -4.309557e-02 1.474264e+02 +-4.513519e-02 6.717547e-02 -9.967197e-01 -3.506955e+02 -2.257192e-02 9.974132e-01 6.824437e-02 1.355975e+00 9.987259e-01 2.557810e-02 -4.350215e-02 1.473873e+02 +-4.549072e-02 6.859541e-02 -9.966069e-01 -3.515769e+02 -2.480610e-02 9.972544e-01 6.977229e-02 1.402676e+00 9.986568e-01 2.789592e-02 -4.366423e-02 1.473426e+02 +-4.590113e-02 6.869300e-02 -9.965813e-01 -3.524683e+02 -2.595369e-02 9.972141e-01 6.993202e-02 1.447707e+00 9.986088e-01 2.907492e-02 -4.399042e-02 1.472941e+02 +-4.659110e-02 6.902855e-02 -9.965261e-01 -3.533575e+02 -2.635863e-02 9.971771e-01 7.030602e-02 1.493364e+00 9.985663e-01 2.954270e-02 -4.464008e-02 1.472542e+02 +-4.713296e-02 6.863365e-02 -9.965279e-01 -3.542477e+02 -2.831488e-02 9.971440e-01 7.001531e-02 1.536891e+00 9.984873e-01 3.151659e-02 -4.505499e-02 1.472111e+02 +-4.745029e-02 6.731026e-02 -9.966031e-01 -3.551420e+02 -3.020925e-02 9.971738e-01 6.878714e-02 1.579550e+00 9.984167e-01 3.337060e-02 -4.528279e-02 1.471669e+02 +-4.822837e-02 6.590411e-02 -9.966597e-01 -3.560351e+02 -3.124154e-02 9.972331e-01 6.745382e-02 1.624262e+00 9.983477e-01 3.439037e-02 -4.603598e-02 1.471230e+02 +-4.866745e-02 6.670500e-02 -9.965851e-01 -3.569295e+02 -3.205761e-02 9.971491e-01 6.830827e-02 1.667394e+00 9.983005e-01 3.527252e-02 -4.639029e-02 1.470788e+02 +-4.927770e-02 6.895647e-02 -9.964019e-01 -3.578199e+02 -3.445777e-02 9.969026e-01 7.069527e-02 1.715119e+00 9.981906e-01 3.781749e-02 -4.674898e-02 1.470307e+02 +-4.981420e-02 7.107482e-02 -9.962263e-01 -3.587064e+02 -3.411012e-02 9.967617e-01 7.281864e-02 1.763616e+00 9.981759e-01 3.760880e-02 -4.722851e-02 1.469876e+02 +-5.040956e-02 7.395333e-02 -9.959868e-01 -3.595953e+02 -3.233682e-02 9.966110e-01 7.563634e-02 1.808976e+00 9.982050e-01 3.601984e-02 -4.784731e-02 1.469476e+02 +-5.054214e-02 7.622200e-02 -9.958091e-01 -3.604842e+02 -3.045973e-02 9.965019e-01 7.782104e-02 1.849084e+00 9.982574e-01 3.426532e-02 -4.804364e-02 1.469115e+02 +-5.114635e-02 7.536561e-02 -9.958434e-01 -3.613654e+02 -3.095006e-02 9.965499e-01 7.700868e-02 1.890629e+00 9.982115e-01 3.476013e-02 -4.863732e-02 1.468690e+02 +-5.173257e-02 7.169767e-02 -9.960839e-01 -3.622424e+02 -3.142533e-02 9.968087e-01 7.338196e-02 1.933851e+00 9.981664e-01 3.509850e-02 -4.931435e-02 1.468269e+02 +-5.154642e-02 6.940008e-02 -9.962563e-01 -3.631190e+02 -3.291970e-02 9.969222e-01 7.114976e-02 1.978909e+00 9.981279e-01 3.646397e-02 -4.910314e-02 1.467850e+02 +-4.947157e-02 7.027514e-02 -9.963001e-01 -3.639988e+02 -3.483024e-02 9.967934e-01 7.203946e-02 2.023273e+00 9.981681e-01 3.826528e-02 -4.686523e-02 1.467473e+02 +-4.574907e-02 7.216917e-02 -9.963426e-01 -3.648725e+02 -3.725129e-02 9.965699e-01 7.389612e-02 2.065987e+00 9.982582e-01 4.049572e-02 -4.290376e-02 1.467108e+02 +-4.163975e-02 7.127559e-02 -9.965871e-01 -3.657366e+02 -3.993884e-02 9.965362e-01 7.294070e-02 2.106303e+00 9.983342e-01 4.283976e-02 -3.864885e-02 1.466781e+02 +-3.724141e-02 6.851858e-02 -9.969545e-01 -3.665924e+02 -4.016311e-02 9.967378e-01 7.000400e-02 2.150730e+00 9.984989e-01 4.264784e-02 -3.436800e-02 1.466515e+02 +-3.307190e-02 6.705753e-02 -9.972008e-01 -3.674403e+02 -4.062862e-02 9.968317e-01 6.838016e-02 2.197858e+00 9.986269e-01 4.277635e-02 -3.024266e-02 1.466275e+02 +-2.869901e-02 6.706433e-02 -9.973358e-01 -3.682783e+02 -4.053192e-02 9.968481e-01 6.819789e-02 2.237361e+00 9.987660e-01 4.238114e-02 -2.589030e-02 1.466055e+02 +-2.428493e-02 6.686817e-02 -9.974662e-01 -3.691032e+02 -4.058390e-02 9.968720e-01 6.781643e-02 2.275037e+00 9.988810e-01 4.212798e-02 -2.149519e-02 1.465860e+02 +-1.972090e-02 6.641366e-02 -9.975973e-01 -3.699138e+02 -4.006897e-02 9.969372e-01 6.716183e-02 2.317775e+00 9.990023e-01 4.129718e-02 -1.699937e-02 1.465711e+02 +-1.508282e-02 6.638266e-02 -9.976802e-01 -3.707112e+02 -4.108691e-02 9.969098e-01 6.695257e-02 2.358587e+00 9.990418e-01 4.200143e-02 -1.230875e-02 1.465561e+02 +-1.020353e-02 7.052390e-02 -9.974579e-01 -3.714988e+02 -3.777162e-02 9.967707e-01 7.086171e-02 2.397216e+00 9.992343e-01 3.839864e-02 -7.506780e-03 1.465525e+02 +-4.246276e-03 7.319327e-02 -9.973087e-01 -3.722667e+02 -3.721492e-02 9.966153e-01 7.330084e-02 2.430776e+00 9.992983e-01 3.742602e-02 -1.508019e-03 1.465546e+02 +4.840463e-03 7.157257e-02 -9.974236e-01 -3.730116e+02 -4.102405e-02 9.966098e-01 7.131510e-02 2.460969e+00 9.991465e-01 4.057316e-02 7.760252e-03 1.465583e+02 +1.586696e-02 6.880758e-02 -9.975037e-01 -3.737341e+02 -4.565754e-02 9.966385e-01 6.802166e-02 2.492985e+00 9.988312e-01 4.446427e-02 1.895522e-02 1.465694e+02 +2.970078e-02 6.498752e-02 -9.974440e-01 -3.744322e+02 -4.353207e-02 9.970215e-01 6.366376e-02 2.523966e+00 9.986105e-01 4.152993e-02 3.244136e-02 1.465953e+02 +4.720876e-02 6.429707e-02 -9.968135e-01 -3.751118e+02 -4.434103e-02 9.970773e-01 6.221413e-02 2.545502e+00 9.979004e-01 4.126268e-02 4.992179e-02 1.466386e+02 +6.641158e-02 6.552576e-02 -9.956384e-01 -3.757660e+02 -4.433808e-02 9.970495e-01 6.266118e-02 2.566415e+00 9.968068e-01 3.998326e-02 6.912092e-02 1.466879e+02 +8.442557e-02 6.657945e-02 -9.942029e-01 -3.763977e+02 -4.530344e-02 9.969898e-01 6.291903e-02 2.585909e+00 9.953994e-01 3.972883e-02 8.718771e-02 1.467549e+02 +1.033475e-01 6.811281e-02 -9.923104e-01 -3.770066e+02 -4.302413e-02 9.970249e-01 6.395553e-02 2.606477e+00 9.937144e-01 3.608364e-02 1.059705e-01 1.468367e+02 +1.230284e-01 7.049899e-02 -9.898959e-01 -3.775878e+02 -3.885424e-02 9.970509e-01 6.617961e-02 2.626681e+00 9.916423e-01 3.031968e-02 1.254048e-01 1.469235e+02 +1.434701e-01 7.201902e-02 -9.870307e-01 -3.781571e+02 -3.466237e-02 9.971023e-01 6.771556e-02 2.648745e+00 9.890475e-01 2.449766e-02 1.455507e-01 1.470292e+02 +1.646590e-01 7.251449e-02 -9.836814e-01 -3.787000e+02 -3.207505e-02 9.971601e-01 6.813906e-02 2.668898e+00 9.858289e-01 2.033192e-02 1.665173e-01 1.471327e+02 +1.880513e-01 7.123889e-02 -9.795722e-01 -3.792282e+02 -3.180981e-02 9.972845e-01 6.642041e-02 2.684974e+00 9.816440e-01 1.866955e-02 1.898068e-01 1.472540e+02 +2.127991e-01 6.765637e-02 -9.747508e-01 -3.797250e+02 -3.283732e-02 9.975315e-01 6.206881e-02 2.699238e+00 9.765441e-01 1.880001e-02 2.144955e-01 1.473703e+02 +2.402092e-01 6.415050e-02 -9.685991e-01 -3.802116e+02 -3.296043e-02 9.977776e-01 5.790894e-02 2.711000e+00 9.701614e-01 1.801518e-02 2.417898e-01 1.475162e+02 +2.706641e-01 5.922999e-02 -9.608500e-01 -3.806801e+02 -3.189514e-02 9.981092e-01 5.254217e-02 2.716656e+00 9.621454e-01 1.642517e-02 2.720415e-01 1.476815e+02 +3.055186e-01 5.457412e-02 -9.506208e-01 -3.811186e+02 -2.864336e-02 9.984311e-01 4.811322e-02 2.728456e+00 9.517552e-01 1.252949e-02 3.066025e-01 1.478404e+02 +3.437634e-01 5.216450e-02 -9.376063e-01 -3.815663e+02 -2.480809e-02 9.986119e-01 4.646299e-02 2.732779e+00 9.387286e-01 7.287949e-03 3.445803e-01 1.480504e+02 +3.817928e-01 5.175231e-02 -9.227979e-01 -3.819839e+02 -2.355760e-02 9.986516e-01 4.625977e-02 2.739785e+00 9.239477e-01 4.077260e-03 3.824972e-01 1.482406e+02 +4.200509e-01 5.058000e-02 -9.060899e-01 -3.824105e+02 -2.621030e-02 9.987052e-01 4.359927e-02 2.748608e+00 9.071220e-01 5.434982e-03 4.208327e-01 1.484781e+02 +4.588645e-01 4.684643e-02 -8.872704e-01 -3.827968e+02 -2.743292e-02 9.988799e-01 3.855192e-02 2.753382e+00 8.880827e-01 6.650320e-03 4.596357e-01 1.486936e+02 +4.971085e-01 4.363761e-02 -8.665904e-01 -3.831893e+02 -2.668892e-02 9.990310e-01 3.499698e-02 2.755781e+00 8.672779e-01 5.731064e-03 4.977914e-01 1.489671e+02 +5.343459e-01 3.879464e-02 -8.443751e-01 -3.835624e+02 -2.125874e-02 9.992470e-01 3.245705e-02 2.762504e+00 8.449985e-01 6.070610e-04 5.347683e-01 1.492585e+02 +5.691091e-01 3.424364e-02 -8.215487e-01 -3.839027e+02 -1.756501e-02 9.994107e-01 2.948951e-02 2.766956e+00 8.220744e-01 -2.352232e-03 5.693752e-01 1.495258e+02 +6.029442e-01 3.604221e-02 -7.969688e-01 -3.842606e+02 -2.270597e-02 9.993495e-01 2.801658e-02 2.773668e+00 7.974602e-01 1.203516e-03 6.033704e-01 1.498326e+02 +6.354692e-01 4.178998e-02 -7.709945e-01 -3.845944e+02 -3.398194e-02 9.990804e-01 2.614426e-02 2.772538e+00 7.713781e-01 9.586022e-03 6.363050e-01 1.501117e+02 +6.660912e-01 4.111996e-02 -7.447360e-01 -3.849361e+02 -3.875431e-02 9.990385e-01 2.049926e-02 2.770941e+00 7.448629e-01 1.520736e-02 6.670443e-01 1.504502e+02 +6.956113e-01 3.323124e-02 -7.176494e-01 -3.852617e+02 -3.219307e-02 9.993680e-01 1.507196e-02 2.762838e+00 7.176967e-01 1.261912e-02 6.962415e-01 1.508229e+02 +7.242137e-01 2.302182e-02 -6.891912e-01 -3.855564e+02 -2.096514e-02 9.997156e-01 1.136410e-02 2.766241e+00 6.892569e-01 6.218954e-03 7.244904e-01 1.511947e+02 +7.532381e-01 1.961289e-02 -6.574554e-01 -3.858821e+02 -1.716491e-02 9.998010e-01 1.015998e-02 2.770205e+00 6.575239e-01 3.632277e-03 7.534249e-01 1.516266e+02 +7.822703e-01 2.567825e-02 -6.224097e-01 -3.861896e+02 -2.706558e-02 9.996075e-01 7.222859e-03 2.769888e+00 6.223509e-01 1.119565e-02 7.826583e-01 1.520269e+02 +8.108230e-01 3.564312e-02 -5.842052e-01 -3.865221e+02 -3.950265e-02 9.992006e-01 6.136509e-03 2.775660e+00 5.839569e-01 1.810203e-02 8.115828e-01 1.525001e+02 +8.383395e-01 4.168214e-02 -5.435526e-01 -3.868325e+02 -4.495231e-02 9.989626e-01 7.273648e-03 2.765584e+00 5.432920e-01 1.833616e-02 8.393436e-01 1.530136e+02 +8.639835e-01 4.087034e-02 -5.018587e-01 -3.870883e+02 -4.362819e-02 9.990283e-01 6.249969e-03 2.757803e+00 5.016265e-01 1.649531e-02 8.649271e-01 1.535084e+02 +8.879950e-01 3.914484e-02 -4.581840e-01 -3.873559e+02 -4.283288e-02 9.990795e-01 2.342800e-03 2.751713e+00 4.578540e-01 1.754494e-02 8.888543e-01 1.540839e+02 +9.100552e-01 3.751141e-02 -4.127861e-01 -3.875750e+02 -4.251410e-02 9.990915e-01 -2.938166e-03 2.744945e+00 4.123010e-01 2.022312e-02 9.108232e-01 1.546292e+02 +9.293709e-01 3.823464e-02 -3.671618e-01 -3.878035e+02 -4.314306e-02 9.990555e-01 -5.167671e-03 2.731001e+00 3.666175e-01 2.064317e-02 9.301427e-01 1.552552e+02 +9.452790e-01 3.679850e-02 -3.241814e-01 -3.880046e+02 -4.094534e-02 9.991435e-01 -5.977447e-03 2.713501e+00 3.236838e-01 1.892407e-02 9.459761e-01 1.559039e+02 +9.582788e-01 3.642105e-02 -2.835055e-01 -3.881649e+02 -4.039030e-02 9.991506e-01 -8.165770e-03 2.695081e+00 2.829673e-01 1.927595e-02 9.589359e-01 1.565365e+02 +9.686777e-01 3.707261e-02 -2.455384e-01 -3.883282e+02 -4.059826e-02 9.991321e-01 -9.310923e-03 2.678055e+00 2.449802e-01 1.898772e-02 9.693421e-01 1.572276e+02 +9.767314e-01 3.692342e-02 -2.112641e-01 -3.884568e+02 -3.985601e-02 9.991589e-01 -9.638367e-03 2.661018e+00 2.107305e-01 1.783424e-02 9.773815e-01 1.579131e+02 +9.828735e-01 3.736521e-02 -1.804536e-01 -3.885817e+02 -3.963821e-02 9.991735e-01 -9.005152e-03 2.642337e+00 1.799680e-01 1.600378e-02 9.835423e-01 1.586442e+02 +9.876401e-01 3.790497e-02 -1.520866e-01 -3.886901e+02 -3.955224e-02 9.991869e-01 -7.819367e-03 2.622200e+00 1.516666e-01 1.373809e-02 9.883362e-01 1.593905e+02 +9.913264e-01 3.808568e-02 -1.257831e-01 -3.887749e+02 -3.917854e-02 9.992128e-01 -6.225102e-03 2.603357e+00 1.254470e-01 1.109911e-02 9.920382e-01 1.601452e+02 +9.939481e-01 3.917053e-02 -1.026300e-01 -3.888527e+02 -3.996946e-02 9.991844e-01 -5.738822e-03 2.584504e+00 1.023215e-01 9.806155e-03 9.947031e-01 1.609289e+02 +9.958039e-01 3.864159e-02 -8.295396e-02 -3.889143e+02 -3.929645e-02 9.992079e-01 -6.275453e-03 2.563277e+00 8.264576e-02 9.508916e-03 9.965336e-01 1.617274e+02 +9.970447e-01 3.874304e-02 -6.633844e-02 -3.889638e+02 -3.935882e-02 9.991931e-01 -8.000003e-03 2.542089e+00 6.597497e-02 1.058736e-02 9.977651e-01 1.625360e+02 +9.979644e-01 3.655914e-02 -5.225431e-02 -3.890023e+02 -3.715675e-02 9.992541e-01 -1.051079e-02 2.521108e+00 5.183108e-02 1.243099e-02 9.985785e-01 1.633699e+02 +9.985882e-01 3.428846e-02 -4.056996e-02 -3.890338e+02 -3.477387e-02 9.993311e-01 -1.131985e-02 2.500351e+00 4.015468e-02 1.271465e-02 9.991126e-01 1.642236e+02 +9.989565e-01 3.262046e-02 -3.196570e-02 -3.890619e+02 -3.300007e-02 9.993901e-01 -1.142047e-02 2.475464e+00 3.157366e-02 1.246342e-02 9.994237e-01 1.650988e+02 +9.991723e-01 3.118254e-02 -2.612316e-02 -3.890865e+02 -3.149355e-02 9.994369e-01 -1.157954e-02 2.449919e+00 2.574737e-02 1.239266e-02 9.995917e-01 1.659914e+02 +9.993339e-01 2.840988e-02 -2.290609e-02 -3.891077e+02 -2.873324e-02 9.994903e-01 -1.391305e-02 2.423001e+00 2.249915e-02 1.456195e-02 9.996408e-01 1.668995e+02 +9.994398e-01 2.539552e-02 -2.179823e-02 -3.891279e+02 -2.576040e-02 9.995299e-01 -1.662477e-02 2.395290e+00 2.136579e-02 1.717698e-02 9.996242e-01 1.678213e+02 +9.994846e-01 2.435855e-02 -2.090979e-02 -3.891501e+02 -2.477132e-02 9.994987e-01 -1.971352e-02 2.366321e+00 2.041912e-02 2.022132e-02 9.995870e-01 1.687553e+02 +9.995131e-01 2.381808e-02 -2.015622e-02 -3.891772e+02 -2.425600e-02 9.994687e-01 -2.176770e-02 2.330230e+00 1.962705e-02 2.224600e-02 9.995599e-01 1.697031e+02 +9.995385e-01 2.327648e-02 -1.952023e-02 -3.892033e+02 -2.373890e-02 9.994348e-01 -2.380196e-02 2.290624e+00 1.895518e-02 2.425436e-02 9.995261e-01 1.706583e+02 +9.995707e-01 2.201862e-02 -1.932753e-02 -3.892283e+02 -2.246783e-02 9.994750e-01 -2.334072e-02 2.250546e+00 1.880345e-02 2.376494e-02 9.995407e-01 1.716261e+02 +9.995996e-01 2.078328e-02 -1.920308e-02 -3.892492e+02 -2.119980e-02 9.995387e-01 -2.174721e-02 2.212388e+00 1.874224e-02 2.214560e-02 9.995791e-01 1.726026e+02 +9.996504e-01 1.872601e-02 -1.866783e-02 -3.892647e+02 -1.905316e-02 9.996652e-01 -1.750367e-02 2.175958e+00 1.833381e-02 1.785323e-02 9.996725e-01 1.735888e+02 +9.996986e-01 1.596177e-02 -1.865475e-02 -3.892821e+02 -1.624727e-02 9.997516e-01 -1.525461e-02 2.142271e+00 1.840663e-02 1.555310e-02 9.997096e-01 1.745746e+02 +9.997299e-01 1.418068e-02 -1.841324e-02 -3.892948e+02 -1.441072e-02 9.998190e-01 -1.242088e-02 2.111015e+00 1.823378e-02 1.268288e-02 9.997533e-01 1.755662e+02 +9.997545e-01 1.223378e-02 -1.847339e-02 -3.893082e+02 -1.246460e-02 9.998450e-01 -1.243152e-02 2.076855e+00 1.831844e-02 1.265873e-02 9.997521e-01 1.765523e+02 +9.997732e-01 1.066164e-02 -1.843874e-02 -3.893211e+02 -1.092719e-02 9.998371e-01 -1.436137e-02 2.041216e+00 1.828262e-02 1.455959e-02 9.997269e-01 1.775355e+02 +9.997712e-01 1.106763e-02 -1.830583e-02 -3.893404e+02 -1.138354e-02 9.997865e-01 -1.724438e-02 2.006405e+00 1.811107e-02 1.744882e-02 9.996837e-01 1.785188e+02 +9.997749e-01 1.192806e-02 -1.754689e-02 -3.893609e+02 -1.224458e-02 9.997622e-01 -1.804280e-02 1.972475e+00 1.732751e-02 1.825359e-02 9.996832e-01 1.795030e+02 +9.997494e-01 1.462028e-02 -1.695538e-02 -3.893856e+02 -1.490100e-02 9.997520e-01 -1.654987e-02 1.935822e+00 1.670921e-02 1.679838e-02 9.997193e-01 1.804872e+02 +9.997595e-01 1.469211e-02 -1.628153e-02 -3.894084e+02 -1.496840e-02 9.997438e-01 -1.697932e-02 1.899292e+00 1.602790e-02 1.721895e-02 9.997233e-01 1.814662e+02 +9.997677e-01 1.443864e-02 -1.600102e-02 -3.894324e+02 -1.472031e-02 9.997362e-01 -1.762699e-02 1.862098e+00 1.574229e-02 1.785844e-02 9.997166e-01 1.824430e+02 +9.997773e-01 1.440624e-02 -1.541848e-02 -3.894558e+02 -1.466192e-02 9.997547e-01 -1.660014e-02 1.823795e+00 1.517556e-02 1.682251e-02 9.997433e-01 1.834210e+02 +9.997756e-01 1.505354e-02 -1.490618e-02 -3.894771e+02 -1.526810e-02 9.997799e-01 -1.438608e-02 1.787575e+00 1.468634e-02 1.461044e-02 9.997854e-01 1.843951e+02 +9.997856e-01 1.487411e-02 -1.440424e-02 -3.894968e+02 -1.503811e-02 9.998225e-01 -1.134449e-02 1.752590e+00 1.423295e-02 1.155867e-02 9.998319e-01 1.853685e+02 +9.998018e-01 1.402528e-02 -1.412962e-02 -3.895146e+02 -1.414994e-02 9.998615e-01 -8.761011e-03 1.720446e+00 1.400479e-02 8.959207e-03 9.998618e-01 1.863378e+02 +9.997987e-01 1.432876e-02 -1.404533e-02 -3.895340e+02 -1.443558e-02 9.998674e-01 -7.534016e-03 1.690076e+00 1.393551e-02 7.735251e-03 9.998730e-01 1.873039e+02 +9.997739e-01 1.573548e-02 -1.430315e-02 -3.895551e+02 -1.584762e-02 9.998443e-01 -7.760747e-03 1.663816e+00 1.417880e-02 7.985662e-03 9.998676e-01 1.882632e+02 +9.997558e-01 1.658744e-02 -1.459850e-02 -3.895769e+02 -1.669032e-02 9.998365e-01 -6.953354e-03 1.636654e+00 1.448078e-02 7.195310e-03 9.998693e-01 1.892122e+02 +9.997446e-01 1.730783e-02 -1.452934e-02 -3.895961e+02 -1.738228e-02 9.998363e-01 -5.013065e-03 1.611298e+00 1.444020e-02 5.264338e-03 9.998819e-01 1.901514e+02 +9.997188e-01 1.904100e-02 -1.413728e-02 -3.896152e+02 -1.905945e-02 9.998176e-01 -1.171560e-03 1.583834e+00 1.411240e-02 1.440680e-03 9.998994e-01 1.910745e+02 +9.996852e-01 2.084398e-02 -1.396579e-02 -3.896351e+02 -2.082486e-02 9.997820e-01 1.513046e-03 1.557758e+00 1.399429e-02 -1.221733e-03 9.999013e-01 1.919820e+02 +9.996649e-01 2.217600e-02 -1.335645e-02 -3.896504e+02 -2.215879e-02 9.997534e-01 1.435340e-03 1.529963e+00 1.338499e-02 -1.138895e-03 9.999098e-01 1.928681e+02 +9.996531e-01 2.377067e-02 -1.133856e-02 -3.896647e+02 -2.380765e-02 9.997116e-01 -3.137398e-03 1.501257e+00 1.126072e-02 3.406254e-03 9.999308e-01 1.937297e+02 +9.996580e-01 2.472818e-02 -8.506096e-03 -3.896784e+02 -2.483158e-02 9.996163e-01 -1.227255e-02 1.467320e+00 8.199355e-03 1.247957e-02 9.998885e-01 1.945649e+02 +9.996645e-01 2.532265e-02 -5.446845e-03 -3.896886e+02 -2.541430e-02 9.995243e-01 -1.747244e-02 1.434902e+00 5.001806e-03 1.760501e-02 9.998325e-01 1.953812e+02 +9.996704e-01 2.557683e-02 -2.238112e-03 -3.896968e+02 -2.561101e-02 9.995296e-01 -1.687266e-02 1.402457e+00 1.805511e-03 1.692441e-02 9.998552e-01 1.961821e+02 +9.996213e-01 2.741188e-02 2.415699e-03 -3.897035e+02 -2.738327e-02 9.995625e-01 -1.117445e-02 1.368583e+00 -2.720955e-03 1.110407e-02 9.999347e-01 1.969665e+02 +9.995223e-01 2.944739e-02 9.382696e-03 -3.897065e+02 -2.938770e-02 9.995473e-01 -6.438431e-03 1.336074e+00 -9.568045e-03 6.159620e-03 9.999353e-01 1.977293e+02 +9.993915e-01 2.926004e-02 1.898449e-02 -3.896958e+02 -2.915151e-02 9.995572e-01 -5.968733e-03 1.309790e+00 -1.915073e-02 5.411674e-03 9.998020e-01 1.984638e+02 +9.989771e-01 3.056805e-02 3.332109e-02 -3.896739e+02 -3.041266e-02 9.995241e-01 -5.160748e-03 1.288614e+00 -3.346298e-02 4.142086e-03 9.994314e-01 1.991767e+02 +9.982058e-01 3.011526e-02 5.175115e-02 -3.896372e+02 -2.998917e-02 9.995450e-01 -3.211567e-03 1.266918e+00 -5.182432e-02 1.653831e-03 9.986549e-01 1.998810e+02 +9.969373e-01 2.928602e-02 7.251424e-02 -3.895780e+02 -2.935993e-02 9.995689e-01 -4.679650e-05 1.248566e+00 -7.248436e-02 -2.082359e-03 9.973674e-01 2.005610e+02 +9.948313e-01 2.770209e-02 9.768965e-02 -3.895080e+02 -2.790469e-02 9.996103e-01 7.078576e-04 1.226505e+00 -9.763198e-02 -3.430197e-03 9.952167e-01 2.012443e+02 +9.913495e-01 2.737359e-02 1.283626e-01 -3.894065e+02 -2.753115e-02 9.996208e-01 -5.470888e-04 1.203085e+00 -1.283289e-01 -2.991613e-03 9.917272e-01 2.018943e+02 +9.860447e-01 2.726064e-02 1.642336e-01 -3.892930e+02 -2.683817e-02 9.996283e-01 -4.791222e-03 1.183000e+00 -1.643032e-01 3.166306e-04 9.864098e-01 2.025587e+02 +9.784867e-01 2.798787e-02 2.044028e-01 -3.891331e+02 -2.649447e-02 9.995985e-01 -1.003973e-02 1.160844e+00 -2.046017e-01 4.408198e-03 9.788354e-01 2.031748e+02 +9.682386e-01 2.917706e-02 2.483200e-01 -3.889644e+02 -2.638610e-02 9.995457e-01 -1.456095e-02 1.139340e+00 -2.486320e-01 7.546275e-03 9.685686e-01 2.038248e+02 +9.549518e-01 2.864830e-02 2.953750e-01 -3.887649e+02 -2.453544e-02 9.995436e-01 -1.762192e-02 1.111915e+00 -2.957451e-01 9.580931e-03 9.552189e-01 2.044674e+02 +9.387738e-01 2.800353e-02 3.433942e-01 -3.885012e+02 -2.253673e-02 9.995479e-01 -1.990129e-02 1.082188e+00 -3.437962e-01 1.094382e-02 9.389805e-01 2.050350e+02 +9.201436e-01 2.513025e-02 3.907739e-01 -3.882375e+02 -1.724485e-02 9.995709e-01 -2.367543e-02 1.052181e+00 -3.912012e-01 1.504595e-02 9.201822e-01 2.056419e+02 +8.992295e-01 2.342639e-02 4.368495e-01 -3.879157e+02 -1.428067e-02 9.996049e-01 -2.420865e-02 1.020561e+00 -4.372441e-01 1.553062e-02 8.992088e-01 2.061749e+02 +8.761329e-01 2.240393e-02 4.815488e-01 -3.875990e+02 -1.265920e-02 9.996442e-01 -2.347597e-02 9.856586e-01 -4.819035e-01 1.447204e-02 8.761048e-01 2.067491e+02 +8.509550e-01 2.114892e-02 5.248127e-01 -3.872256e+02 -1.108741e-02 9.996896e-01 -2.230793e-02 9.498629e-01 -5.251216e-01 1.316423e-02 8.509254e-01 2.072474e+02 +8.234985e-01 2.107864e-02 5.669267e-01 -3.868534e+02 -9.448736e-03 9.996805e-01 -2.344376e-02 9.143036e-01 -5.672398e-01 1.394916e-02 8.234346e-01 2.077793e+02 +7.933804e-01 2.647329e-02 6.081502e-01 -3.864463e+02 -1.012227e-02 9.994895e-01 -3.030333e-02 8.788487e-01 -6.086420e-01 1.788621e-02 7.932434e-01 2.082939e+02 +7.604259e-01 2.972184e-02 6.487442e-01 -3.859852e+02 -6.717486e-03 9.992587e-01 -3.790656e-02 8.372290e-01 -6.493899e-01 2.446720e-02 7.600619e-01 2.087254e+02 +7.250551e-01 3.442933e-02 6.878298e-01 -3.855250e+02 -6.458262e-03 9.990456e-01 -4.319948e-02 7.998909e-01 -6.886607e-01 2.687981e-02 7.245854e-01 2.092003e+02 +6.877239e-01 3.524296e-02 7.251164e-01 -3.850072e+02 -2.333935e-03 9.989231e-01 -4.633728e-02 7.644286e-01 -7.259686e-01 3.017487e-02 6.870656e-01 2.095917e+02 +6.484517e-01 3.243115e-02 7.605647e-01 -3.844875e+02 1.385048e-03 9.990402e-01 -4.378085e-02 7.205875e-01 -7.612546e-01 2.944318e-02 6.477843e-01 2.100252e+02 +6.084927e-01 2.910781e-02 7.930254e-01 -3.839443e+02 3.976089e-03 9.992027e-01 -3.972638e-02 6.780795e-01 -7.935495e-01 2.732635e-02 6.078918e-01 2.104401e+02 +5.677277e-01 2.917798e-02 8.226991e-01 -3.833528e+02 4.790964e-03 9.992376e-01 -3.874528e-02 6.355226e-01 -8.232025e-01 2.593829e-02 5.671551e-01 2.107730e+02 +5.268925e-01 2.807196e-02 8.494682e-01 -3.827669e+02 7.336105e-03 9.992669e-01 -3.757260e-02 5.932607e-01 -8.499003e-01 2.602850e-02 5.263003e-01 2.111337e+02 +4.879007e-01 2.989981e-02 8.723869e-01 -3.821357e+02 8.742417e-03 9.991956e-01 -3.913538e-02 5.528527e-01 -8.728554e-01 2.672095e-02 4.872469e-01 2.114259e+02 +4.501679e-01 2.979017e-02 8.924468e-01 -3.815037e+02 1.419903e-02 9.990781e-01 -4.051184e-02 5.148568e-01 -8.928310e-01 3.090900e-02 4.493300e-01 2.117341e+02 +4.136593e-01 2.923259e-02 9.099623e-01 -3.808480e+02 1.676912e-02 9.990702e-01 -3.971826e-02 4.750314e-01 -9.102773e-01 3.168909e-02 4.127845e-01 2.120243e+02 +3.781436e-01 2.945148e-02 9.252783e-01 -3.801574e+02 1.810324e-02 9.990674e-01 -3.919863e-02 4.340302e-01 -9.255699e-01 3.157325e-02 3.772578e-01 2.122606e+02 +3.430368e-01 3.056342e-02 9.388246e-01 -3.794664e+02 1.840636e-02 9.990599e-01 -3.924988e-02 3.921567e-01 -9.391416e-01 3.074449e-02 3.421517e-01 2.125120e+02 +3.100632e-01 3.159247e-02 9.501909e-01 -3.787412e+02 2.106417e-02 9.989741e-01 -4.008804e-02 3.518857e-01 -9.504826e-01 3.244480e-02 3.090796e-01 2.127108e+02 +2.797022e-01 3.331395e-02 9.595087e-01 -3.780114e+02 2.782082e-02 9.986969e-01 -4.278449e-02 3.170122e-01 -9.596837e-01 3.866122e-02 2.784108e-01 2.129126e+02 +2.513570e-01 3.167455e-02 9.673760e-01 -3.772533e+02 3.247655e-02 9.986256e-01 -4.113626e-02 2.746673e-01 -9.673495e-01 4.175692e-02 2.499828e-01 2.130976e+02 +2.266960e-01 2.815672e-02 9.735585e-01 -3.764734e+02 3.381533e-02 9.987518e-01 -3.675936e-02 2.341312e-01 -9.733784e-01 4.125439e-02 2.254609e-01 2.132573e+02 +2.047202e-01 2.548753e-02 9.784886e-01 -3.756764e+02 3.796295e-02 9.987020e-01 -3.395669e-02 1.910364e-01 -9.780841e-01 4.409793e-02 2.034869e-01 2.134147e+02 +1.853399e-01 2.570673e-02 9.823382e-01 -3.748679e+02 4.016624e-02 9.986241e-01 -3.371118e-02 1.496837e-01 -9.818533e-01 4.570485e-02 1.840524e-01 2.135584e+02 +1.679892e-01 2.851077e-02 9.853764e-01 -3.740388e+02 4.264434e-02 9.984358e-01 -3.615873e-02 1.100466e-01 -9.848661e-01 4.809500e-02 1.665106e-01 2.136834e+02 +1.522007e-01 3.082842e-02 9.878687e-01 -3.731971e+02 4.434399e-02 9.982939e-01 -3.798583e-02 7.249781e-02 -9.873544e-01 4.958749e-02 1.505740e-01 2.138078e+02 +1.386824e-01 3.096078e-02 9.898528e-01 -3.723348e+02 4.572633e-02 9.982450e-01 -3.762973e-02 3.183645e-02 -9.892807e-01 5.048091e-02 1.370233e-01 2.139190e+02 +1.265023e-01 2.907988e-02 9.915400e-01 -3.714585e+02 4.581544e-02 9.983322e-01 -3.512430e-02 -1.028734e-02 -9.909078e-01 4.987113e-02 1.249590e-01 2.140252e+02 +1.166770e-01 2.764462e-02 9.927851e-01 -3.705637e+02 4.593225e-02 9.983927e-01 -3.319896e-02 -5.192589e-02 -9.921072e-01 4.947439e-02 1.152197e-01 2.141256e+02 +1.084058e-01 2.560228e-02 9.937770e-01 -3.696539e+02 4.637172e-02 9.984499e-01 -3.078112e-02 -8.859508e-02 -9.930246e-01 4.941999e-02 1.070506e-01 2.142171e+02 +1.020206e-01 2.390633e-02 9.944950e-01 -3.687312e+02 4.764587e-02 9.984464e-01 -2.888910e-02 -1.259426e-01 -9.936406e-01 5.033085e-02 1.007231e-01 2.143040e+02 +9.753644e-02 2.253374e-02 9.949768e-01 -3.677991e+02 5.020036e-02 9.983596e-01 -2.753144e-02 -1.623055e-01 -9.939651e-01 5.263350e-02 9.624524e-02 2.143853e+02 +9.438715e-02 2.368388e-02 9.952538e-01 -3.668581e+02 5.293495e-02 9.981833e-01 -2.877380e-02 -2.008675e-01 -9.941273e-01 5.539958e-02 9.296197e-02 2.144675e+02 +9.089481e-02 2.395205e-02 9.955724e-01 -3.659070e+02 5.403930e-02 9.981191e-01 -2.894706e-02 -2.384108e-01 -9.943933e-01 5.643116e-02 8.942949e-02 2.145484e+02 +8.699837e-02 2.291667e-02 9.959448e-01 -3.649411e+02 5.398733e-02 9.981578e-01 -2.768353e-02 -2.756974e-01 -9.947445e-01 5.617681e-02 8.560089e-02 2.146265e+02 +8.275187e-02 2.128349e-02 9.963429e-01 -3.639666e+02 5.324714e-02 9.982494e-01 -2.574670e-02 -3.147800e-01 -9.951467e-01 5.518299e-02 8.147372e-02 2.147012e+02 +7.845380e-02 2.130853e-02 9.966900e-01 -3.629864e+02 5.297898e-02 9.982696e-01 -2.551252e-02 -3.536308e-01 -9.955091e-01 5.480516e-02 7.718914e-02 2.147746e+02 +7.371998e-02 2.314137e-02 9.970104e-01 -3.619980e+02 5.041648e-02 9.983659e-01 -2.690069e-02 -3.925995e-01 -9.960038e-01 5.224887e-02 7.243280e-02 2.148472e+02 +6.897433e-02 2.515923e-02 9.973011e-01 -3.610030e+02 4.745931e-02 9.984673e-01 -2.847099e-02 -4.351993e-01 -9.964889e-01 4.929498e-02 6.767457e-02 2.149179e+02 +6.431413e-02 2.742915e-02 9.975527e-01 -3.600005e+02 4.517933e-02 9.985172e-01 -3.036848e-02 -4.776722e-01 -9.969065e-01 4.702187e-02 6.297953e-02 2.149825e+02 +5.951378e-02 2.853175e-02 9.978196e-01 -3.589909e+02 4.370035e-02 9.985586e-01 -3.115935e-02 -5.188830e-01 -9.972705e-01 4.545947e-02 5.818115e-02 2.150402e+02 +5.466538e-02 2.819868e-02 9.981065e-01 -3.579724e+02 4.195737e-02 9.986534e-01 -3.051211e-02 -5.639892e-01 -9.976228e-01 4.354587e-02 5.340862e-02 2.150945e+02 +4.986111e-02 2.710142e-02 9.983884e-01 -3.569467e+02 4.066367e-02 9.987478e-01 -2.914199e-02 -6.071135e-01 -9.979281e-01 4.205118e-02 4.869663e-02 2.151443e+02 +4.496856e-02 2.628597e-02 9.986425e-01 -3.559162e+02 3.998615e-02 9.988053e-01 -2.809083e-02 -6.502004e-01 -9.981879e-01 4.119506e-02 4.386376e-02 2.151902e+02 +4.025401e-02 2.540865e-02 9.988663e-01 -3.548813e+02 3.874505e-02 9.988851e-01 -2.697055e-02 -6.917482e-01 -9.984380e-01 3.978679e-02 3.922467e-02 2.152321e+02 +3.567042e-02 2.416104e-02 9.990715e-01 -3.538448e+02 3.794977e-02 9.989539e-01 -2.551315e-02 -7.345462e-01 -9.986428e-01 3.882459e-02 3.471619e-02 2.152691e+02 +3.147740e-02 2.156972e-02 9.992717e-01 -3.528056e+02 3.871396e-02 9.989905e-01 -2.278317e-02 -7.742450e-01 -9.987545e-01 3.940291e-02 3.061057e-02 2.152990e+02 +2.753594e-02 1.926331e-02 9.994352e-01 -3.517655e+02 3.960087e-02 9.990084e-01 -2.034616e-02 -8.123048e-01 -9.988361e-01 4.013874e-02 2.674579e-02 2.153234e+02 +2.391549e-02 1.832375e-02 9.995460e-01 -3.507282e+02 3.971133e-02 9.990254e-01 -1.926436e-02 -8.477046e-01 -9.989250e-01 4.015401e-02 2.316452e-02 2.153438e+02 +2.074017e-02 2.171379e-02 9.995491e-01 -3.496923e+02 3.959161e-02 9.989621e-01 -2.252256e-02 -8.852006e-01 -9.990007e-01 4.004086e-02 1.985895e-02 2.153625e+02 +1.766387e-02 2.677795e-02 9.994853e-01 -3.486559e+02 3.770984e-02 9.989122e-01 -2.742905e-02 -9.245787e-01 -9.991326e-01 3.817492e-02 1.663486e-02 2.153802e+02 +1.462258e-02 3.056776e-02 9.994257e-01 -3.476218e+02 3.544357e-02 9.988886e-01 -3.106991e-02 -9.677412e-01 -9.992647e-01 3.587752e-02 1.352289e-02 2.153966e+02 +1.139242e-02 3.087304e-02 9.994584e-01 -3.465854e+02 3.269158e-02 9.989774e-01 -3.123083e-02 -1.013764e+00 -9.994006e-01 3.302966e-02 1.037148e-02 2.154119e+02 +8.147760e-03 2.827499e-02 9.995670e-01 -3.455447e+02 2.940896e-02 9.991610e-01 -2.850324e-02 -1.055609e+00 -9.995343e-01 2.962845e-02 7.309384e-03 2.154267e+02 +4.296346e-03 2.471911e-02 9.996852e-01 -3.445036e+02 2.716007e-02 9.993227e-01 -2.482688e-02 -1.095703e+00 -9.996219e-01 2.725818e-02 3.622062e-03 2.154361e+02 +1.873643e-04 2.210087e-02 9.997557e-01 -3.434669e+02 2.482948e-02 9.994474e-01 -2.209871e-02 -1.135441e+00 -9.996917e-01 2.482755e-02 -3.614941e-04 2.154416e+02 +-4.591100e-03 2.623738e-02 9.996452e-01 -3.424366e+02 2.212381e-02 9.994137e-01 -2.612971e-02 -1.173119e+00 -9.997447e-01 2.199599e-02 -5.168881e-03 2.154395e+02 +-9.721772e-03 2.901289e-02 9.995317e-01 -3.414045e+02 2.059431e-02 9.993728e-01 -2.880798e-02 -1.207931e+00 -9.997407e-01 2.030460e-02 -1.031318e-02 2.154315e+02 +-1.571678e-02 2.680197e-02 9.995172e-01 -3.403698e+02 1.778989e-02 9.994899e-01 -2.652152e-02 -1.250859e+00 -9.997182e-01 1.736446e-02 -1.618557e-02 2.154210e+02 +-2.221447e-02 2.574667e-02 9.994216e-01 -3.393363e+02 1.660152e-02 9.995400e-01 -2.538072e-02 -1.291571e+00 -9.996154e-01 1.602810e-02 -2.263168e-02 2.154035e+02 +-2.838261e-02 2.602882e-02 9.992582e-01 -3.383072e+02 1.810558e-02 9.995103e-01 -2.552113e-02 -1.330598e+00 -9.994332e-01 1.736778e-02 -2.883998e-02 2.153747e+02 +-3.459906e-02 2.488007e-02 9.990915e-01 -3.372770e+02 1.930545e-02 9.995202e-01 -2.422219e-02 -1.369628e+00 -9.992148e-01 1.844984e-02 -3.506279e-02 2.153386e+02 +-4.085240e-02 2.164578e-02 9.989307e-01 -3.362508e+02 1.999435e-02 9.995828e-01 -2.084223e-02 -1.411300e+00 -9.989652e-01 1.912151e-02 -4.126815e-02 2.153010e+02 +-4.680911e-02 1.868034e-02 9.987292e-01 -3.352229e+02 2.208489e-02 9.996001e-01 -1.766154e-02 -1.456147e+00 -9.986597e-01 2.123009e-02 -4.720295e-02 2.152583e+02 +-5.187671e-02 2.057566e-02 9.984415e-01 -3.342045e+02 2.620752e-02 9.994714e-01 -1.923521e-02 -1.497106e+00 -9.983096e-01 2.516881e-02 -5.238853e-02 2.152067e+02 +-5.571691e-02 2.606087e-02 9.981064e-01 -3.331909e+02 3.133178e-02 9.992126e-01 -2.434074e-02 -1.537374e+00 -9.979549e-01 2.991626e-02 -5.648958e-02 2.151499e+02 +-5.837856e-02 2.912801e-02 9.978695e-01 -3.321769e+02 3.569412e-02 9.989960e-01 -2.707268e-02 -1.578645e+00 -9.976562e-01 3.403760e-02 -5.935964e-02 2.150907e+02 +-5.984836e-02 2.478873e-02 9.978996e-01 -3.311599e+02 3.550950e-02 9.991117e-01 -2.268919e-02 -1.623555e+00 -9.975757e-01 3.407700e-02 -6.067543e-02 2.150355e+02 +-6.024172e-02 1.744717e-02 9.980313e-01 -3.301344e+02 3.867583e-02 9.991372e-01 -1.513202e-02 -1.669195e+00 -9.974343e-01 3.768810e-02 -6.086453e-02 2.149779e+02 +-5.911605e-02 1.528574e-02 9.981341e-01 -3.291139e+02 4.201953e-02 9.990346e-01 -1.281087e-02 -1.709449e+00 -9.973664e-01 4.118378e-02 -5.970129e-02 2.149194e+02 +-5.723289e-02 1.902569e-02 9.981795e-01 -3.281031e+02 4.472263e-02 9.988636e-01 -1.647446e-02 -1.748733e+00 -9.973587e-01 4.369832e-02 -5.801873e-02 2.148648e+02 +-5.410110e-02 2.574719e-02 9.982034e-01 -3.270926e+02 4.813705e-02 9.985725e-01 -2.314776e-02 -1.786199e+00 -9.973745e-01 4.679824e-02 -5.526326e-02 2.148078e+02 +-4.838761e-02 2.999020e-02 9.983783e-01 -3.260833e+02 5.711570e-02 9.979967e-01 -2.721056e-02 -1.832213e+00 -9.971943e-01 5.570641e-02 -5.000359e-02 2.147550e+02 +-4.142886e-02 3.086425e-02 9.986646e-01 -3.250701e+02 6.202671e-02 9.976743e-01 -2.826052e-02 -1.883345e+00 -9.972143e-01 6.077307e-02 -4.324692e-02 2.147075e+02 +-3.604803e-02 3.006553e-02 9.988977e-01 -3.240549e+02 6.258956e-02 9.976529e-01 -2.776935e-02 -1.934870e+00 -9.973882e-01 6.151952e-02 -3.784522e-02 2.146723e+02 +-3.097477e-02 2.654514e-02 9.991676e-01 -3.230355e+02 6.267106e-02 9.977319e-01 -2.456417e-02 -1.983939e+00 -9.975535e-01 6.185801e-02 -3.256813e-02 2.146451e+02 +-2.453177e-02 2.506060e-02 9.993849e-01 -3.220198e+02 6.264388e-02 9.977596e-01 -2.348214e-02 -2.035681e+00 -9.977344e-01 6.202928e-02 -2.604671e-02 2.146221e+02 +-1.690402e-02 2.854163e-02 9.994496e-01 -3.210094e+02 6.540362e-02 9.974832e-01 -2.737929e-02 -2.091033e+00 -9.977157e-01 6.490479e-02 -1.872820e-02 2.146042e+02 +-9.016428e-03 3.098981e-02 9.994790e-01 -3.199977e+02 6.686269e-02 9.973014e-01 -3.031912e-02 -2.146423e+00 -9.977215e-01 6.655447e-02 -1.106416e-02 2.145945e+02 +-1.370598e-03 2.832254e-02 9.995979e-01 -3.189790e+02 6.811495e-02 9.972799e-01 -2.816347e-02 -2.203532e+00 -9.976766e-01 6.804894e-02 -3.296060e-03 2.145912e+02 +6.065849e-03 2.453568e-02 9.996805e-01 -3.179620e+02 6.867391e-02 9.973285e-01 -2.489466e-02 -2.258664e+00 -9.976208e-01 6.880297e-02 4.364681e-03 2.145966e+02 +1.330650e-02 2.637185e-02 9.995636e-01 -3.169498e+02 6.829640e-02 9.972936e-01 -2.722115e-02 -2.314191e+00 -9.975764e-01 6.862880e-02 1.146939e-02 2.146134e+02 +2.082310e-02 2.969411e-02 9.993421e-01 -3.159333e+02 6.801531e-02 9.972010e-01 -3.104772e-02 -2.368006e+00 -9.974670e-01 6.861706e-02 1.874516e-02 2.146360e+02 +2.838258e-02 2.925464e-02 9.991689e-01 -3.149156e+02 6.801484e-02 9.971985e-01 -3.112900e-02 -2.428913e+00 -9.972805e-01 6.884182e-02 2.631332e-02 2.146664e+02 +3.523457e-02 2.633097e-02 9.990321e-01 -3.138946e+02 6.842086e-02 9.972437e-01 -2.869696e-02 -2.486746e+00 -9.970342e-01 6.936574e-02 3.333587e-02 2.147017e+02 +4.130782e-02 2.434496e-02 9.988498e-01 -3.128744e+02 6.744361e-02 9.973550e-01 -2.709769e-02 -2.547570e+00 -9.968676e-01 6.848537e-02 3.955665e-02 2.147478e+02 +4.594854e-02 2.346405e-02 9.986682e-01 -3.118558e+02 6.551795e-02 9.975007e-01 -2.645110e-02 -2.602956e+00 -9.967930e-01 6.664607e-02 4.429639e-02 2.147984e+02 +4.933176e-02 2.396788e-02 9.984948e-01 -3.108340e+02 6.388021e-02 9.975895e-01 -2.710223e-02 -2.659278e+00 -9.967376e-01 6.512104e-02 4.768177e-02 2.148518e+02 +5.168577e-02 2.597107e-02 9.983256e-01 -3.098153e+02 6.148091e-02 9.976828e-01 -2.913738e-02 -2.714715e+00 -9.967692e-01 6.288394e-02 4.996928e-02 2.149081e+02 +5.397535e-02 2.734726e-02 9.981677e-01 -3.087948e+02 6.105309e-02 9.976643e-01 -3.063488e-02 -2.769947e+00 -9.966741e-01 6.259474e-02 5.217964e-02 2.149641e+02 +5.596585e-02 2.546792e-02 9.981078e-01 -3.077688e+02 6.080943e-02 9.977318e-01 -2.886804e-02 -2.822669e+00 -9.965792e-01 6.230998e-02 5.429022e-02 2.150215e+02 +5.764040e-02 2.012689e-02 9.981345e-01 -3.067391e+02 5.912257e-02 9.979732e-01 -2.353786e-02 -2.874610e+00 -9.965853e-01 6.036899e-02 5.633362e-02 2.150832e+02 +5.918301e-02 1.612733e-02 9.981169e-01 -3.057095e+02 5.832383e-02 9.981056e-01 -1.958545e-02 -2.923047e+00 -9.965419e-01 5.937311e-02 5.813028e-02 2.151455e+02 +6.013657e-02 1.468952e-02 9.980821e-01 -3.046820e+02 5.684644e-02 9.982185e-01 -1.811666e-02 -2.967310e+00 -9.965702e-01 5.782687e-02 5.919439e-02 2.152096e+02 +6.044002e-02 1.472771e-02 9.980632e-01 -3.036580e+02 5.548204e-02 9.982958e-01 -1.809099e-02 -3.011095e+00 -9.966287e-01 5.646799e-02 5.951989e-02 2.152740e+02 +6.095831e-02 1.601324e-02 9.980118e-01 -3.026364e+02 5.295104e-02 9.984115e-01 -1.925389e-02 -3.055918e+00 -9.967348e-01 5.401944e-02 6.001356e-02 2.153395e+02 +6.166201e-02 1.732604e-02 9.979467e-01 -3.016193e+02 5.207852e-02 9.984315e-01 -2.055233e-02 -3.099209e+00 -9.967375e-01 5.323887e-02 6.066297e-02 2.154034e+02 +6.207189e-02 1.712673e-02 9.979247e-01 -3.005956e+02 5.045287e-02 9.985206e-01 -2.027518e-02 -3.144009e+00 -9.967957e-01 5.160667e-02 6.111597e-02 2.154683e+02 +6.114107e-02 1.694409e-02 9.979853e-01 -2.995781e+02 4.724502e-02 9.986860e-01 -1.985044e-02 -3.194166e+00 -9.970104e-01 4.836350e-02 6.026021e-02 2.155360e+02 +5.919851e-02 1.724955e-02 9.980972e-01 -2.985641e+02 4.432747e-02 9.988190e-01 -1.989115e-02 -3.239103e+00 -9.972616e-01 4.542064e-02 5.836397e-02 2.156021e+02 +5.633166e-02 1.702522e-02 9.982669e-01 -2.975503e+02 4.184887e-02 9.989356e-01 -1.939814e-02 -3.283160e+00 -9.975347e-01 4.286906e-02 5.555922e-02 2.156643e+02 +5.351772e-02 1.611723e-02 9.984368e-01 -2.965356e+02 4.067144e-02 9.990048e-01 -1.830645e-02 -3.326622e+00 -9.977383e-01 4.158757e-02 5.280895e-02 2.157213e+02 +5.118381e-02 1.578466e-02 9.985645e-01 -2.955235e+02 4.036438e-02 9.990254e-01 -1.786093e-02 -3.369048e+00 -9.978732e-01 4.122062e-02 5.049678e-02 2.157745e+02 +4.968422e-02 1.568447e-02 9.986418e-01 -2.945182e+02 4.108635e-02 9.989982e-01 -1.773419e-02 -3.412178e+00 -9.979196e-01 4.191164e-02 4.899003e-02 2.158246e+02 +4.959162e-02 1.649846e-02 9.986333e-01 -2.935194e+02 4.120169e-02 9.989786e-01 -1.855022e-02 -3.456119e+00 -9.979194e-01 4.206530e-02 4.886120e-02 2.158752e+02 +4.936852e-02 1.672420e-02 9.986406e-01 -2.925245e+02 4.091921e-02 9.989864e-01 -1.875287e-02 -3.501250e+00 -9.979421e-01 4.178937e-02 4.863415e-02 2.159257e+02 +4.910537e-02 1.761979e-02 9.986382e-01 -2.915363e+02 4.023261e-02 9.989980e-01 -1.960448e-02 -3.546331e+00 -9.979830e-01 4.114049e-02 4.834727e-02 2.159788e+02 +4.864850e-02 1.739644e-02 9.986644e-01 -2.905447e+02 3.963558e-02 9.990271e-01 -1.933356e-02 -3.589515e+00 -9.980293e-01 4.052318e-02 4.791166e-02 2.160303e+02 +4.833927e-02 1.735652e-02 9.986801e-01 -2.895692e+02 3.838959e-02 9.990779e-01 -1.922162e-02 -3.632727e+00 -9.980930e-01 3.926807e-02 4.762839e-02 2.160801e+02 +4.727059e-02 1.895464e-02 9.987022e-01 -2.886087e+02 3.842459e-02 9.990454e-01 -2.077987e-02 -3.676801e+00 -9.981428e-01 3.935699e-02 4.649714e-02 2.161264e+02 +4.596030e-02 2.268123e-02 9.986857e-01 -2.876490e+02 3.950867e-02 9.989187e-01 -2.450475e-02 -3.721450e+00 -9.981617e-01 4.058298e-02 4.501450e-02 2.161658e+02 +4.375142e-02 2.477786e-02 9.987351e-01 -2.866860e+02 3.833319e-02 9.989146e-01 -2.646157e-02 -3.766888e+00 -9.983068e-01 3.944243e-02 4.275411e-02 2.162080e+02 +4.143242e-02 2.498571e-02 9.988288e-01 -2.857329e+02 3.607835e-02 9.989979e-01 -2.648651e-02 -3.815229e+00 -9.984897e-01 3.713349e-02 4.048946e-02 2.162494e+02 +3.905751e-02 2.446142e-02 9.989375e-01 -2.847843e+02 3.621765e-02 9.990088e-01 -2.587925e-02 -3.863898e+00 -9.985804e-01 3.718994e-02 3.813285e-02 2.162859e+02 +3.643742e-02 2.444144e-02 9.990370e-01 -2.838443e+02 3.563124e-02 9.990334e-01 -2.574092e-02 -3.911636e+00 -9.987006e-01 3.653485e-02 3.553133e-02 2.163208e+02 +3.365091e-02 2.387826e-02 9.991483e-01 -2.829111e+02 3.537101e-02 9.990598e-01 -2.506743e-02 -3.958988e+00 -9.988076e-01 3.618442e-02 3.277467e-02 2.163532e+02 +3.113369e-02 2.249336e-02 9.992621e-01 -2.819892e+02 3.550050e-02 9.990910e-01 -2.359560e-02 -4.001601e+00 -9.988846e-01 3.620891e-02 3.030687e-02 2.163848e+02 +2.867436e-02 2.109403e-02 9.993662e-01 -2.810754e+02 3.526131e-02 9.991337e-01 -2.210087e-02 -4.043876e+00 -9.989667e-01 3.587268e-02 2.790571e-02 2.164149e+02 +2.591223e-02 2.208685e-02 9.994202e-01 -2.801737e+02 3.543503e-02 9.991073e-01 -2.299868e-02 -4.086683e+00 -9.990360e-01 3.601042e-02 2.510645e-02 2.164425e+02 +2.314876e-02 2.424339e-02 9.994380e-01 -2.792794e+02 3.682120e-02 9.990069e-01 -2.508579e-02 -4.129470e+00 -9.990538e-01 3.738120e-02 2.223310e-02 2.164640e+02 +2.030489e-02 2.591920e-02 9.994578e-01 -2.783848e+02 3.733899e-02 9.989468e-01 -2.666454e-02 -4.168829e+00 -9.990964e-01 3.786016e-02 1.931570e-02 2.164824e+02 +1.758313e-02 2.731515e-02 9.994722e-01 -2.775009e+02 3.839437e-02 9.988710e-01 -2.797418e-02 -4.211638e+00 -9.991080e-01 3.886597e-02 1.651452e-02 2.164975e+02 +1.559140e-02 2.639834e-02 9.995299e-01 -2.766211e+02 3.861636e-02 9.988897e-01 -2.698381e-02 -4.254633e+00 -9.991325e-01 3.901891e-02 1.455468e-02 2.165123e+02 +1.350756e-02 2.439802e-02 9.996110e-01 -2.757499e+02 3.976304e-02 9.988984e-01 -2.491795e-02 -4.297821e+00 -9.991179e-01 4.008415e-02 1.252254e-02 2.165247e+02 +1.206986e-02 2.119913e-02 9.997024e-01 -2.748867e+02 4.063353e-02 9.989390e-01 -2.167354e-02 -4.342282e+00 -9.991012e-01 4.088302e-02 1.119565e-02 2.165366e+02 +1.096338e-02 2.021795e-02 9.997355e-01 -2.740390e+02 3.984129e-02 9.989928e-01 -2.063985e-02 -4.384284e+00 -9.991459e-01 4.005703e-02 1.014682e-02 2.165493e+02 +1.022968e-02 2.182500e-02 9.997095e-01 -2.732110e+02 3.945843e-02 9.989743e-01 -2.221272e-02 -4.428007e+00 -9.991689e-01 3.967419e-02 9.358005e-03 2.165635e+02 +9.734880e-03 2.251222e-02 9.996992e-01 -2.723937e+02 3.969112e-02 9.989499e-01 -2.288186e-02 -4.469313e+00 -9.991646e-01 3.990192e-02 8.831120e-03 2.165747e+02 +9.159346e-03 2.255409e-02 9.997036e-01 -2.715831e+02 4.021655e-02 9.989284e-01 -2.290508e-02 -4.508845e+00 -9.991490e-01 4.041442e-02 8.242481e-03 2.165860e+02 +8.784022e-03 2.278810e-02 9.997017e-01 -2.707869e+02 4.032554e-02 9.989189e-01 -2.312459e-02 -4.548307e+00 -9.991480e-01 4.051663e-02 7.855582e-03 2.165968e+02 +8.994521e-03 2.204124e-02 9.997166e-01 -2.699975e+02 4.071213e-02 9.989200e-01 -2.238997e-02 -4.588251e+00 -9.991305e-01 4.090197e-02 8.087459e-03 2.166076e+02 +9.489616e-03 2.008322e-02 9.997533e-01 -2.692199e+02 4.212150e-02 9.989028e-01 -2.046596e-02 -4.625320e+00 -9.990675e-01 4.230532e-02 8.633267e-03 2.166164e+02 +9.921934e-03 1.737647e-02 9.997998e-01 -2.684522e+02 4.291324e-02 9.989204e-01 -1.778706e-02 -4.663376e+00 -9.990296e-01 4.308112e-02 9.165540e-03 2.166274e+02 +1.033474e-02 1.442256e-02 9.998426e-01 -2.676948e+02 4.341206e-02 9.989467e-01 -1.485837e-02 -4.701604e+00 -9.990038e-01 4.355878e-02 9.697740e-03 2.166407e+02 +1.106710e-02 1.298795e-02 9.998544e-01 -2.669477e+02 4.423878e-02 9.989302e-01 -1.346561e-02 -4.740061e+00 -9.989597e-01 4.438135e-02 1.048069e-02 2.166549e+02 +1.186531e-02 1.281156e-02 9.998475e-01 -2.662101e+02 4.474683e-02 9.989094e-01 -1.333056e-02 -4.777623e+00 -9.989279e-01 4.489816e-02 1.127909e-02 2.166702e+02 +1.266509e-02 1.388250e-02 9.998234e-01 -2.654835e+02 4.574086e-02 9.988488e-01 -1.444839e-02 -4.815936e+00 -9.988731e-01 4.591576e-02 1.201551e-02 2.166839e+02 +1.335983e-02 1.487067e-02 9.998002e-01 -2.647669e+02 4.587365e-02 9.988274e-01 -1.546919e-02 -4.852572e+00 -9.988579e-01 4.607114e-02 1.266199e-02 2.166992e+02 +1.420129e-02 1.577943e-02 9.997746e-01 -2.640579e+02 4.578369e-02 9.988165e-01 -1.641464e-02 -4.886019e+00 -9.988505e-01 4.600647e-02 1.346204e-02 2.167150e+02 +1.475029e-02 1.531505e-02 9.997739e-01 -2.633564e+02 4.601245e-02 9.988130e-01 -1.597919e-02 -4.917615e+00 -9.988320e-01 4.623773e-02 1.402810e-02 2.167319e+02 +1.551982e-02 1.431297e-02 9.997771e-01 -2.626598e+02 4.700806e-02 9.987814e-01 -1.502844e-02 -4.949404e+00 -9.987740e-01 4.723081e-02 1.482808e-02 2.167453e+02 +1.631207e-02 1.389658e-02 9.997704e-01 -2.619776e+02 4.817122e-02 9.987314e-01 -1.466810e-02 -4.985703e+00 -9.987059e-01 4.839941e-02 1.562196e-02 2.167587e+02 +1.697528e-02 1.408425e-02 9.997567e-01 -2.613089e+02 4.866781e-02 9.987039e-01 -1.489578e-02 -5.019036e+00 -9.986708e-01 4.890881e-02 1.626783e-02 2.167735e+02 +1.770045e-02 1.418901e-02 9.997426e-01 -2.606516e+02 4.833921e-02 9.987179e-01 -1.503032e-02 -5.050750e+00 -9.986742e-01 4.859280e-02 1.699186e-02 2.167900e+02 +1.844259e-02 1.468698e-02 9.997220e-01 -2.600093e+02 4.858222e-02 9.986978e-01 -1.556817e-02 -5.080658e+00 -9.986489e-01 4.885582e-02 1.770505e-02 2.168055e+02 +1.930389e-02 1.557932e-02 9.996923e-01 -2.593686e+02 4.873017e-02 9.986756e-01 -1.650445e-02 -5.109185e+00 -9.986255e-01 4.903377e-02 1.851914e-02 2.168180e+02 +2.006733e-02 1.566572e-02 9.996759e-01 -2.587378e+02 4.840494e-02 9.986895e-01 -1.662194e-02 -5.138425e+00 -9.986262e-01 4.872280e-02 1.928273e-02 2.168324e+02 +2.063476e-02 1.520320e-02 9.996715e-01 -2.581180e+02 4.812129e-02 9.987104e-01 -1.618189e-02 -5.166371e+00 -9.986284e-01 4.843938e-02 1.987655e-02 2.168469e+02 +2.129344e-02 1.526659e-02 9.996567e-01 -2.575095e+02 4.839256e-02 9.986956e-01 -1.628272e-02 -5.189733e+00 -9.986014e-01 4.872265e-02 2.052688e-02 2.168614e+02 +2.195475e-02 1.583621e-02 9.996335e-01 -2.569129e+02 4.848346e-02 9.986812e-01 -1.688597e-02 -5.213843e+00 -9.985827e-01 4.883641e-02 2.115800e-02 2.168764e+02 +2.247889e-02 1.567362e-02 9.996244e-01 -2.563241e+02 4.869485e-02 9.986732e-01 -1.675373e-02 -5.235994e+00 -9.985608e-01 4.905315e-02 2.168584e-02 2.168921e+02 +2.294228e-02 1.538139e-02 9.996184e-01 -2.557396e+02 4.838707e-02 9.986927e-01 -1.647769e-02 -5.256971e+00 -9.985652e-01 4.874663e-02 2.216802e-02 2.169071e+02 +2.312338e-02 1.479165e-02 9.996232e-01 -2.551622e+02 4.814468e-02 9.987139e-01 -1.589189e-02 -5.278566e+00 -9.985727e-01 4.849400e-02 2.238150e-02 2.169220e+02 +2.325211e-02 1.402412e-02 9.996312e-01 -2.545916e+02 4.751046e-02 9.987563e-01 -1.511698e-02 -5.301988e+00 -9.986001e-01 4.784443e-02 2.255690e-02 2.169371e+02 +2.324979e-02 1.351985e-02 9.996382e-01 -2.540274e+02 4.744983e-02 9.987667e-01 -1.461166e-02 -5.325849e+00 -9.986030e-01 4.777237e-02 2.257960e-02 2.169499e+02 +2.345119e-02 1.340720e-02 9.996351e-01 -2.534698e+02 4.759353e-02 9.987613e-01 -1.451202e-02 -5.350226e+00 -9.985915e-01 4.791648e-02 2.278404e-02 2.169602e+02 +2.378044e-02 1.362769e-02 9.996243e-01 -2.529140e+02 4.794512e-02 9.987409e-01 -1.475624e-02 -5.374185e+00 -9.985669e-01 4.827800e-02 2.309712e-02 2.169688e+02 +2.375551e-02 1.359204e-02 9.996254e-01 -2.523598e+02 4.820283e-02 9.987290e-01 -1.472537e-02 -5.398703e+00 -9.985551e-01 4.853457e-02 2.307014e-02 2.169796e+02 +2.382273e-02 1.409262e-02 9.996168e-01 -2.518108e+02 4.802847e-02 9.987299e-01 -1.522473e-02 -5.425246e+00 -9.985619e-01 4.837275e-02 2.311562e-02 2.169906e+02 +2.392926e-02 1.518172e-02 9.995984e-01 -2.512615e+02 4.783546e-02 9.987220e-01 -1.631355e-02 -5.451758e+00 -9.985686e-01 4.820661e-02 2.317245e-02 2.170023e+02 +2.425248e-02 1.677371e-02 9.995651e-01 -2.507123e+02 4.842516e-02 9.986658e-01 -1.793357e-02 -5.477629e+00 -9.985324e-01 4.883902e-02 2.340785e-02 2.170075e+02 +2.455315e-02 1.839757e-02 9.995292e-01 -2.501664e+02 4.948010e-02 9.985828e-01 -1.959562e-02 -5.505164e+00 -9.984733e-01 4.993793e-02 2.360804e-02 2.170183e+02 +2.452843e-02 1.953756e-02 9.995082e-01 -2.496233e+02 4.970986e-02 9.985483e-01 -2.073871e-02 -5.529581e+00 -9.984625e-01 5.019409e-02 2.352161e-02 2.170306e+02 +2.499043e-02 1.926619e-02 9.995020e-01 -2.490830e+02 4.917652e-02 9.985801e-01 -2.047798e-02 -5.555011e+00 -9.984774e-01 4.966377e-02 2.400750e-02 2.170451e+02 +2.522376e-02 1.760958e-02 9.995267e-01 -2.485409e+02 4.850018e-02 9.986459e-01 -1.881801e-02 -5.581165e+00 -9.985047e-01 4.895188e-02 2.433553e-02 2.170598e+02 +2.537338e-02 1.609599e-02 9.995484e-01 -2.480000e+02 4.881143e-02 9.986578e-01 -1.732072e-02 -5.609989e+00 -9.984857e-01 4.922886e-02 2.455365e-02 2.170751e+02 +2.596636e-02 1.558440e-02 9.995413e-01 -2.474625e+02 4.951051e-02 9.986313e-01 -1.685642e-02 -5.638190e+00 -9.984360e-01 4.992549e-02 2.515923e-02 2.170899e+02 +2.658772e-02 1.529742e-02 9.995294e-01 -2.469266e+02 4.941164e-02 9.986405e-01 -1.659819e-02 -5.665572e+00 -9.984246e-01 4.982968e-02 2.579570e-02 2.171065e+02 +2.702127e-02 1.559975e-02 9.995131e-01 -2.463947e+02 4.884650e-02 9.986632e-01 -1.690703e-02 -5.690987e+00 -9.984408e-01 4.927955e-02 2.622316e-02 2.171236e+02 +2.764551e-02 1.679711e-02 9.994766e-01 -2.458628e+02 4.865428e-02 9.986511e-01 -1.812902e-02 -5.714971e+00 -9.984330e-01 4.912999e-02 2.679096e-02 2.171416e+02 +2.864609e-02 1.730007e-02 9.994399e-01 -2.453299e+02 4.883269e-02 9.986321e-01 -1.868574e-02 -5.737016e+00 -9.983961e-01 4.934060e-02 2.776209e-02 2.171594e+02 +2.985054e-02 1.631916e-02 9.994211e-01 -2.447985e+02 4.973073e-02 9.986042e-01 -1.779117e-02 -5.759278e+00 -9.983165e-01 5.023301e-02 2.899731e-02 2.171777e+02 +3.105457e-02 1.597421e-02 9.993900e-01 -2.442756e+02 5.026492e-02 9.985822e-01 -1.752321e-02 -5.782688e+00 -9.982530e-01 5.077842e-02 3.020760e-02 2.171957e+02 +3.217174e-02 1.810323e-02 9.993184e-01 -2.437539e+02 4.779331e-02 9.986643e-01 -1.963004e-02 -5.809748e+00 -9.983390e-01 4.839225e-02 3.126355e-02 2.172182e+02 +3.336407e-02 2.236717e-02 9.991929e-01 -2.432385e+02 4.412060e-02 9.987419e-01 -2.383032e-02 -5.840219e+00 -9.984690e-01 4.488005e-02 3.233524e-02 2.172423e+02 +3.449531e-02 2.665816e-02 9.990492e-01 -2.427233e+02 4.128383e-02 9.987529e-01 -2.807572e-02 -5.871536e+00 -9.985518e-01 4.221305e-02 3.335174e-02 2.172651e+02 +3.578475e-02 3.061452e-02 9.988905e-01 -2.422098e+02 4.191006e-02 9.986053e-01 -3.210720e-02 -5.900070e+00 -9.984804e-01 4.301250e-02 3.445179e-02 2.172832e+02 +3.723446e-02 3.373558e-02 9.987369e-01 -2.416977e+02 4.311618e-02 9.984450e-01 -3.533317e-02 -5.928176e+00 -9.983760e-01 4.437732e-02 3.572201e-02 2.173012e+02 +3.794500e-02 3.514550e-02 9.986616e-01 -2.411846e+02 4.225643e-02 9.984309e-01 -3.674296e-02 -5.958643e+00 -9.983860e-01 4.359408e-02 3.640034e-02 2.173242e+02 +3.816983e-02 3.423817e-02 9.986845e-01 -2.406696e+02 3.840193e-02 9.986243e-01 -3.570384e-02 -5.989240e+00 -9.985331e-01 3.971421e-02 3.680251e-02 2.173521e+02 +3.843721e-02 3.300104e-02 9.987159e-01 -2.401595e+02 3.586767e-02 9.987649e-01 -3.438309e-02 -6.017363e+00 -9.986171e-01 3.714319e-02 3.720606e-02 2.173796e+02 +3.883815e-02 3.159128e-02 9.987460e-01 -2.396467e+02 3.529865e-02 9.988329e-01 -3.296670e-02 -6.045720e+00 -9.986219e-01 3.653474e-02 3.767769e-02 2.174027e+02 +3.910581e-02 3.018711e-02 9.987790e-01 -2.391327e+02 3.629233e-02 9.988411e-01 -3.160997e-02 -6.073875e+00 -9.985758e-01 3.748414e-02 3.796493e-02 2.174243e+02 +3.923855e-02 3.061166e-02 9.987608e-01 -2.386237e+02 3.561076e-02 9.988528e-01 -3.201353e-02 -6.104958e+00 -9.985952e-01 3.682279e-02 3.810343e-02 2.174475e+02 +3.882078e-02 3.264883e-02 9.987127e-01 -2.381164e+02 3.351334e-02 9.988612e-01 -3.395638e-02 -6.137935e+00 -9.986841e-01 3.478840e-02 3.768240e-02 2.174738e+02 +3.804926e-02 3.493309e-02 9.986651e-01 -2.376103e+02 3.182269e-02 9.988395e-01 -3.615165e-02 -6.169457e+00 -9.987691e-01 3.315574e-02 3.689343e-02 2.174973e+02 +3.678659e-02 3.640703e-02 9.986597e-01 -2.370981e+02 3.196637e-02 9.987818e-01 -3.758901e-02 -6.200318e+00 -9.988118e-01 3.330629e-02 3.557798e-02 2.175177e+02 +3.507731e-02 3.814516e-02 9.986563e-01 -2.365889e+02 3.250283e-02 9.986991e-01 -3.928845e-02 -6.232098e+00 -9.988560e-01 3.383728e-02 3.379185e-02 2.175367e+02 +3.333664e-02 3.946059e-02 9.986649e-01 -2.360822e+02 3.242949e-02 9.986514e-01 -4.054261e-02 -6.269469e+00 -9.989179e-01 3.373774e-02 3.201199e-02 2.175567e+02 +3.170099e-02 3.840602e-02 9.987592e-01 -2.355687e+02 3.122255e-02 9.987357e-01 -3.939614e-02 -6.307022e+00 -9.990096e-01 3.243270e-02 3.046178e-02 2.175783e+02 +3.005907e-02 3.701325e-02 9.988626e-01 -2.350527e+02 3.114937e-02 9.987941e-01 -3.794811e-02 -6.344166e+00 -9.990627e-01 3.225462e-02 2.886988e-02 2.175976e+02 +2.860086e-02 3.635344e-02 9.989296e-01 -2.345341e+02 3.090190e-02 9.988286e-01 -3.723454e-02 -6.378826e+00 -9.991132e-01 3.193375e-02 2.744397e-02 2.176146e+02 +2.699096e-02 3.575777e-02 9.989959e-01 -2.340136e+02 3.072229e-02 9.988582e-01 -3.658291e-02 -6.414708e+00 -9.991635e-01 3.167885e-02 2.586158e-02 2.176324e+02 +2.596660e-02 3.416059e-02 9.990790e-01 -2.334872e+02 3.038957e-02 9.989271e-01 -3.494525e-02 -6.449287e+00 -9.992008e-01 3.126898e-02 2.490061e-02 2.176491e+02 +2.477757e-02 3.279148e-02 9.991550e-01 -2.329593e+02 3.174397e-02 9.989320e-01 -3.357137e-02 -6.483526e+00 -9.991889e-01 3.254895e-02 2.371018e-02 2.176625e+02 +2.356984e-02 3.159131e-02 9.992229e-01 -2.324293e+02 3.398514e-02 9.988976e-01 -3.238268e-02 -6.514251e+00 -9.991444e-01 3.472198e-02 2.247022e-02 2.176755e+02 +2.229682e-02 2.917444e-02 9.993256e-01 -2.318898e+02 3.552537e-02 9.989197e-01 -2.995524e-02 -6.542106e+00 -9.991200e-01 3.616931e-02 2.123630e-02 2.176871e+02 +2.107937e-02 2.604432e-02 9.994385e-01 -2.313641e+02 3.567676e-02 9.990043e-01 -2.678548e-02 -6.563978e+00 -9.991411e-01 3.622134e-02 2.012920e-02 2.176986e+02 +1.977699e-02 2.327520e-02 9.995334e-01 -2.308250e+02 3.584838e-02 9.990696e-01 -2.397371e-02 -6.587092e+00 -9.991616e-01 3.630578e-02 1.892421e-02 2.177090e+02 +1.848466e-02 2.053126e-02 9.996183e-01 -2.302815e+02 3.626184e-02 9.991176e-01 -2.119153e-02 -6.605310e+00 -9.991714e-01 3.663971e-02 1.772384e-02 2.177150e+02 +1.753154e-02 1.753266e-02 9.996926e-01 -2.297503e+02 3.672062e-02 9.991604e-01 -1.816730e-02 -6.622958e+00 -9.991718e-01 3.702782e-02 1.687301e-02 2.177225e+02 +1.654196e-02 1.546142e-02 9.997436e-01 -2.292135e+02 3.888088e-02 9.991142e-01 -1.609502e-02 -6.633655e+00 -9.991070e-01 3.913715e-02 1.592616e-02 2.177274e+02 +1.531445e-02 1.431789e-02 9.997802e-01 -2.286811e+02 4.116102e-02 9.990408e-01 -1.493780e-02 -6.648381e+00 -9.990352e-01 4.138072e-02 1.471042e-02 2.177325e+02 +1.388610e-02 1.399307e-02 9.998057e-01 -2.281497e+02 4.201351e-02 9.990108e-01 -1.456547e-02 -6.662940e+00 -9.990206e-01 4.220759e-02 1.328447e-02 2.177370e+02 +1.251061e-02 1.393119e-02 9.998247e-01 -2.276202e+02 4.087223e-02 9.990601e-01 -1.443197e-02 -6.679276e+00 -9.990861e-01 4.104561e-02 1.192945e-02 2.177432e+02 +1.043721e-02 1.390977e-02 9.998488e-01 -2.270920e+02 3.924951e-02 9.991270e-01 -1.430945e-02 -6.694727e+00 -9.991750e-01 3.939292e-02 9.882145e-03 2.177488e+02 +7.438270e-03 1.399795e-02 9.998743e-01 -2.265657e+02 3.845960e-02 9.991582e-01 -1.427404e-02 -6.710349e+00 -9.992325e-01 3.856093e-02 6.893651e-03 2.177518e+02 +3.412075e-03 1.403615e-02 9.998957e-01 -2.260386e+02 3.919704e-02 9.991312e-01 -1.415919e-02 -6.721710e+00 -9.992257e-01 3.924125e-02 2.858933e-03 2.177492e+02 +-2.257767e-03 1.366449e-02 9.999041e-01 -2.255150e+02 4.117835e-02 9.990598e-01 -1.355998e-02 -6.738710e+00 -9.991493e-01 4.114377e-02 -2.818328e-03 2.177427e+02 +-9.171211e-03 1.393464e-02 9.998608e-01 -2.249937e+02 4.200183e-02 9.990258e-01 -1.353774e-02 -6.757222e+00 -9.990755e-01 4.187181e-02 -9.747559e-03 2.177340e+02 +-1.714320e-02 1.489604e-02 9.997421e-01 -2.244745e+02 4.217252e-02 9.990099e-01 -1.416198e-02 -6.776167e+00 -9.989633e-01 4.191885e-02 -1.775444e-02 2.177206e+02 +-2.590660e-02 1.522114e-02 9.995485e-01 -2.239579e+02 4.134195e-02 9.990449e-01 -1.414197e-02 -6.792317e+00 -9.988092e-01 4.095691e-02 -2.651114e-02 2.177048e+02 +-3.597172e-02 1.519843e-02 9.992372e-01 -2.234438e+02 4.143329e-02 9.990473e-01 -1.370398e-02 -6.804656e+00 -9.984936e-01 4.090872e-02 -3.656717e-02 2.176783e+02 +-4.784764e-02 1.769840e-02 9.986978e-01 -2.229437e+02 4.291499e-02 9.989562e-01 -1.564692e-02 -6.820553e+00 -9.979323e-01 4.211043e-02 -4.855723e-02 2.176464e+02 +-6.173616e-02 2.126102e-02 9.978660e-01 -2.224564e+02 4.594666e-02 9.987737e-01 -1.843773e-02 -6.836939e+00 -9.970344e-01 4.471033e-02 -6.263733e-02 2.176047e+02 +-7.760603e-02 2.392901e-02 9.966969e-01 -2.219798e+02 4.770104e-02 9.986561e-01 -2.026190e-02 -6.856519e+00 -9.958423e-01 4.597102e-02 -7.864318e-02 2.175509e+02 +-9.576382e-02 2.851919e-02 9.949954e-01 -2.215175e+02 4.825421e-02 9.985472e-01 -2.397676e-02 -6.873839e+00 -9.942338e-01 4.571660e-02 -9.700088e-02 2.174977e+02 +-1.154381e-01 3.452164e-02 9.927146e-01 -2.210663e+02 4.996000e-02 9.983328e-01 -2.890741e-02 -6.894792e+00 -9.920575e-01 4.625900e-02 -1.169703e-01 2.174265e+02 +-1.359327e-01 3.697362e-02 9.900279e-01 -2.206271e+02 5.342961e-02 9.981227e-01 -2.993996e-02 -6.918071e+00 -9.892763e-01 4.882698e-02 -1.376530e-01 2.173550e+02 +-1.566958e-01 3.534337e-02 9.870143e-01 -2.201964e+02 5.601133e-02 9.980691e-01 -2.684702e-02 -6.941490e+00 -9.860574e-01 5.107715e-02 -1.583729e-01 2.172643e+02 +-1.775629e-01 3.410354e-02 9.835183e-01 -2.197850e+02 6.020858e-02 9.979036e-01 -2.373240e-02 -6.965369e+00 -9.822660e-01 5.500224e-02 -1.792440e-01 2.171762e+02 +-1.979141e-01 3.346746e-02 9.796478e-01 -2.193941e+02 6.367340e-02 9.977451e-01 -2.122206e-02 -6.987969e+00 -9.781492e-01 5.817735e-02 -1.995988e-01 2.170819e+02 +-2.173146e-01 3.111401e-02 9.756056e-01 -2.190154e+02 6.527715e-02 9.977175e-01 -1.727884e-02 -7.010122e+00 -9.739165e-01 5.992980e-02 -2.188496e-01 2.169793e+02 +-2.355481e-01 2.909621e-02 9.714270e-01 -2.186616e+02 6.620334e-02 9.977103e-01 -1.383071e-02 -7.029396e+00 -9.696052e-01 6.105390e-02 -2.369350e-01 2.168834e+02 +-2.535686e-01 2.877161e-02 9.668894e-01 -2.183230e+02 6.706755e-02 9.976751e-01 -1.209911e-02 -7.042534e+00 -9.649896e-01 6.177894e-02 -2.549087e-01 2.167749e+02 +-2.728152e-01 2.936817e-02 9.616181e-01 -2.180006e+02 6.801970e-02 9.976214e-01 -1.117025e-02 -7.053843e+00 -9.596589e-01 6.236155e-02 -2.741639e-01 2.166713e+02 +-2.928695e-01 2.907210e-02 9.557103e-01 -2.176861e+02 6.787889e-02 9.976479e-01 -9.546901e-03 -7.065447e+00 -9.537400e-01 6.207655e-02 -2.941541e-01 2.165644e+02 +-3.140615e-01 2.783480e-02 9.489945e-01 -2.173755e+02 6.772252e-02 9.976807e-01 -6.850643e-03 -7.075055e+00 -9.469842e-01 6.211676e-02 -3.152181e-01 2.164387e+02 +-3.368969e-01 2.688225e-02 9.411577e-01 -2.170743e+02 6.837157e-02 9.976518e-01 -4.021605e-03 -7.085016e+00 -9.390558e-01 6.299355e-02 -3.379438e-01 2.163164e+02 +-3.618213e-01 2.689154e-02 9.318595e-01 -2.167801e+02 6.962365e-02 9.975718e-01 -1.754482e-03 -7.092564e+00 -9.296440e-01 6.424464e-02 -3.628150e-01 2.161678e+02 +-3.881518e-01 2.691298e-02 9.212024e-01 -2.164980e+02 7.099921e-02 9.974760e-01 7.744301e-04 -7.100396e+00 -9.188565e-01 6.570522e-02 -3.890829e-01 2.160276e+02 +-4.152816e-01 2.687851e-02 9.092957e-01 -2.162249e+02 7.126798e-02 9.974525e-01 3.064158e-03 -7.108479e+00 -9.068970e-01 6.607614e-02 -4.161392e-01 2.158820e+02 +-4.430150e-01 2.905026e-02 8.960434e-01 -2.159556e+02 7.189118e-02 9.974073e-01 3.207350e-03 -7.116668e+00 -8.936271e-01 6.583851e-02 -4.439549e-01 2.157086e+02 +-4.709881e-01 3.342712e-02 8.815060e-01 -2.157038e+02 7.203336e-02 9.974020e-01 6.654084e-04 -7.127475e+00 -8.791937e-01 6.381122e-02 -4.721723e-01 2.155481e+02 +-4.991620e-01 3.859450e-02 8.656487e-01 -2.154538e+02 7.198549e-02 9.974013e-01 -2.959395e-03 -7.137276e+00 -8.635134e-01 6.083692e-02 -5.006431e-01 2.153576e+02 +-5.283970e-01 4.469885e-02 8.478199e-01 -2.152216e+02 7.247148e-02 9.973429e-01 -7.414762e-03 -7.137019e+00 -8.458986e-01 5.752481e-02 -5.302324e-01 2.151871e+02 +-5.591042e-01 5.068214e-02 8.275469e-01 -2.149863e+02 7.174140e-02 9.973435e-01 -1.261149e-02 -7.139750e+00 -8.259877e-01 5.231822e-02 -5.612549e-01 2.149756e+02 +-5.907253e-01 5.650380e-02 8.048919e-01 -2.147574e+02 7.157704e-02 9.972819e-01 -1.747797e-02 -7.137502e+00 -8.036917e-01 4.728708e-02 -5.931641e-01 2.147829e+02 +-6.230620e-01 5.971421e-02 7.798897e-01 -2.145291e+02 7.072359e-02 9.972982e-01 -1.985885e-02 -7.135112e+00 -7.789685e-01 4.278329e-02 -6.256018e-01 2.145760e+02 +-6.559770e-01 6.215734e-02 7.522171e-01 -2.142950e+02 7.128070e-02 9.972508e-01 -2.024412e-02 -7.126983e+00 -7.514075e-01 4.033887e-02 -6.586043e-01 2.143085e+02 +-6.890701e-01 6.423905e-02 7.218419e-01 -2.140772e+02 7.376972e-02 9.971071e-01 -1.831526e-02 -7.121172e+00 -7.209303e-01 4.062957e-02 -6.918156e-01 2.140656e+02 +-7.216969e-01 6.747193e-02 6.889130e-01 -2.138602e+02 7.909478e-02 9.967577e-01 -1.476344e-02 -7.116848e+00 -6.876755e-01 4.383468e-02 -7.246937e-01 2.137525e+02 +-7.539941e-01 6.819752e-02 6.533314e-01 -2.136581e+02 8.252999e-02 9.965499e-01 -8.778284e-03 -7.115701e+00 -6.516761e-01 4.730065e-02 -7.570211e-01 2.134741e+02 +-7.852460e-01 6.531401e-02 6.157295e-01 -2.134597e+02 8.189459e-02 9.966402e-01 -1.278465e-03 -7.118581e+00 -6.137443e-01 4.942100e-02 -7.879566e-01 2.131829e+02 +-8.152940e-01 5.990361e-02 5.759403e-01 -2.132558e+02 7.815405e-02 9.969171e-01 6.944432e-03 -7.111335e+00 -5.737487e-01 5.067381e-02 -8.174623e-01 2.128186e+02 +-8.437837e-01 5.714364e-02 5.336325e-01 -2.130776e+02 7.609467e-02 9.970084e-01 1.355752e-02 -7.107977e+00 -5.312614e-01 5.204619e-02 -8.456078e-01 2.124929e+02 +-8.696546e-01 5.824598e-02 4.902124e-01 -2.129075e+02 7.783658e-02 9.967724e-01 1.965051e-02 -7.097534e+00 -4.874857e-01 5.524561e-02 -8.713814e-01 2.120864e+02 +-8.926943e-01 5.697318e-02 4.470468e-01 -2.127536e+02 7.667098e-02 9.967154e-01 2.607710e-02 -7.089987e+00 -4.440928e-01 5.755439e-02 -8.941304e-01 2.117147e+02 +-9.132763e-01 5.225533e-02 4.039750e-01 -2.125923e+02 7.035276e-02 9.970687e-01 3.007448e-02 -7.074716e+00 -4.012193e-01 5.588706e-02 -9.142755e-01 2.112775e+02 +-9.309292e-01 4.769179e-02 3.620722e-01 -2.124522e+02 6.322400e-02 9.975126e-01 3.116474e-02 -7.066863e+00 -3.596853e-01 5.190381e-02 -9.316289e-01 2.108706e+02 +-9.455550e-01 4.967962e-02 3.216485e-01 -2.123284e+02 6.282981e-02 9.975542e-01 3.062629e-02 -7.053341e+00 -3.193403e-01 4.916795e-02 -9.463637e-01 2.104336e+02 +-9.573659e-01 5.442983e-02 2.837039e-01 -2.122150e+02 6.553159e-02 9.974060e-01 2.978126e-02 -7.040673e+00 -2.813470e-01 4.710313e-02 -9.584494e-01 2.099399e+02 +-9.672677e-01 5.591605e-02 2.475209e-01 -2.121143e+02 6.489850e-02 9.974912e-01 2.827410e-02 -7.024880e+00 -2.453189e-01 4.341235e-02 -9.684699e-01 2.094566e+02 +-9.757027e-01 5.394300e-02 2.123546e-01 -2.120125e+02 6.067226e-02 9.978371e-01 2.529608e-02 -7.005138e+00 -2.105308e-01 3.756548e-02 -9.768652e-01 2.089285e+02 +-9.823768e-01 5.103748e-02 1.798081e-01 -2.119269e+02 5.671802e-02 9.980361e-01 2.659060e-02 -6.996237e+00 -1.780979e-01 3.632034e-02 -9.833423e-01 2.083974e+02 +-9.874232e-01 4.964324e-02 1.501034e-01 -2.118585e+02 5.520841e-02 9.979248e-01 3.313603e-02 -6.989747e+00 -1.481469e-01 4.100624e-02 -9.881149e-01 2.078370e+02 +-9.913624e-01 5.102317e-02 1.208192e-01 -2.118031e+02 5.586232e-02 9.977524e-01 3.700810e-02 -6.984177e+00 -1.186594e-01 4.343767e-02 -9.919844e-01 2.072398e+02 +-9.943453e-01 5.395111e-02 9.146997e-02 -2.117688e+02 5.756990e-02 9.976409e-01 3.739487e-02 -6.967995e+00 -8.923669e-02 4.244933e-02 -9.951055e-01 2.066442e+02 +-9.965190e-01 5.307982e-02 6.428323e-02 -2.117420e+02 5.559901e-02 9.977277e-01 3.805408e-02 -6.949691e+00 -6.211726e-02 4.149570e-02 -9.972059e-01 2.060284e+02 +-9.977462e-01 5.381268e-02 4.008347e-02 -2.117268e+02 5.537352e-02 9.977075e-01 3.890363e-02 -6.933161e+00 -3.789807e-02 4.103551e-02 -9.984387e-01 2.053805e+02 +-9.981343e-01 5.759197e-02 2.027622e-02 -2.117268e+02 5.838934e-02 9.974427e-01 4.121494e-02 -6.917191e+00 -1.785072e-02 4.232195e-02 -9.989446e-01 2.047198e+02 +-9.979890e-01 6.314593e-02 5.522863e-03 -2.117363e+02 6.332995e-02 9.969949e-01 4.461503e-02 -6.899680e+00 -2.689009e-03 4.487507e-02 -9.989890e-01 2.040336e+02 +-9.977471e-01 6.690276e-02 -4.978143e-03 -2.117486e+02 6.661290e-02 9.967669e-01 4.492778e-02 -6.878206e+00 7.967841e-03 4.449495e-02 -9.989778e-01 2.033356e+02 +-9.975054e-01 6.963771e-02 -1.155976e-02 -2.117601e+02 6.903641e-02 9.965475e-01 4.611861e-02 -6.855545e+00 1.473144e-02 4.520551e-02 -9.988691e-01 2.026147e+02 +-9.976412e-01 6.721110e-02 -1.395090e-02 -2.117669e+02 6.648786e-02 9.966762e-01 4.707203e-02 -6.828239e+00 1.706830e-02 4.603343e-02 -9.987941e-01 2.018733e+02 +-9.975489e-01 6.829988e-02 -1.520768e-02 -2.117752e+02 6.753942e-02 9.966605e-01 4.589363e-02 -6.796527e+00 1.829143e-02 4.475402e-02 -9.988306e-01 2.011113e+02 +-9.975178e-01 6.889690e-02 -1.454416e-02 -2.117841e+02 6.816267e-02 9.966104e-01 4.606074e-02 -6.766600e+00 1.766831e-02 4.495503e-02 -9.988328e-01 2.003312e+02 +-9.972033e-01 7.362171e-02 -1.286334e-02 -2.117962e+02 7.295096e-02 9.962491e-01 4.653960e-02 -6.732759e+00 1.624142e-02 4.547104e-02 -9.988336e-01 1.995335e+02 +-9.972019e-01 7.400791e-02 -1.055016e-02 -2.117983e+02 7.344459e-02 9.962209e-01 4.636624e-02 -6.697286e+00 1.394176e-02 4.546164e-02 -9.988688e-01 1.987167e+02 +-9.972668e-01 7.354258e-02 -7.100182e-03 -2.117964e+02 7.312169e-02 9.961759e-01 4.782057e-02 -6.661490e+00 1.058988e-02 4.717069e-02 -9.988307e-01 1.978826e+02 +-9.976160e-01 6.889956e-02 -3.902432e-03 -2.117868e+02 6.861536e-02 9.963627e-01 5.053060e-02 -6.628960e+00 7.369775e-03 5.014236e-02 -9.987149e-01 1.970274e+02 +-9.976871e-01 6.797261e-02 -4.399949e-04 -2.117784e+02 6.786586e-02 9.964433e-01 4.994971e-02 -6.592550e+00 3.833642e-03 4.980431e-02 -9.987516e-01 1.961589e+02 +-9.974061e-01 7.189739e-02 3.452663e-03 -2.117730e+02 7.198016e-02 9.961762e-01 4.951475e-02 -6.548829e+00 1.205202e-04 4.963483e-02 -9.987674e-01 1.952734e+02 +-9.975209e-01 7.003947e-02 6.822423e-03 -2.117599e+02 7.029437e-02 9.962638e-01 5.017146e-02 -6.512536e+00 -3.282951e-03 5.052665e-02 -9.987173e-01 1.943739e+02 +-9.974886e-01 7.015138e-02 9.760418e-03 -2.117409e+02 7.054104e-02 9.963548e-01 4.796849e-02 -6.475499e+00 -6.359785e-03 4.853652e-02 -9.988012e-01 1.934673e+02 +-9.974580e-01 6.985202e-02 1.407680e-02 -2.117217e+02 7.040565e-02 9.965619e-01 4.367402e-02 -6.441793e+00 -1.097769e-02 4.455408e-02 -9.989467e-01 1.925558e+02 +-9.972600e-01 7.179929e-02 1.781477e-02 -2.116979e+02 7.248560e-02 9.965078e-01 4.144947e-02 -6.412962e+00 -1.477651e-02 4.262721e-02 -9.989818e-01 1.916336e+02 +-9.968170e-01 7.684897e-02 2.121637e-02 -2.116775e+02 7.770914e-02 9.960382e-01 4.323340e-02 -6.384488e+00 -1.780988e-02 4.474449e-02 -9.988397e-01 1.907002e+02 +-9.966834e-01 7.763703e-02 2.438568e-02 -2.116488e+02 7.876930e-02 9.956617e-01 4.952938e-02 -6.356135e+00 -2.043458e-02 5.128594e-02 -9.984749e-01 1.897594e+02 +-9.962182e-01 8.291818e-02 2.595767e-02 -2.116267e+02 8.421032e-02 9.950142e-01 5.343549e-02 -6.324224e+00 -2.139748e-02 5.541930e-02 -9.982339e-01 1.888160e+02 +-9.960131e-01 8.498989e-02 2.710482e-02 -2.115991e+02 8.640450e-02 9.946750e-01 5.617672e-02 -6.287854e+00 -2.218603e-02 5.829472e-02 -9.980529e-01 1.878741e+02 +-9.959669e-01 8.572749e-02 2.647129e-02 -2.115690e+02 8.719311e-02 9.943624e-01 6.033860e-02 -6.249486e+00 -2.114938e-02 6.240335e-02 -9.978269e-01 1.869320e+02 +-9.961269e-01 8.399355e-02 2.600666e-02 -2.115370e+02 8.547105e-02 9.943990e-01 6.217206e-02 -6.212008e+00 -2.063894e-02 6.415406e-02 -9.977266e-01 1.859922e+02 +-9.962541e-01 8.290240e-02 2.459758e-02 -2.115055e+02 8.432625e-02 9.943822e-01 6.397642e-02 -6.174195e+00 -1.915559e-02 6.581098e-02 -9.976482e-01 1.850520e+02 +-9.963795e-01 8.154351e-02 2.405344e-02 -2.114747e+02 8.290950e-02 9.945847e-01 6.266743e-02 -6.133132e+00 -1.881306e-02 6.443479e-02 -9.977446e-01 1.841142e+02 +-9.964139e-01 8.147600e-02 2.282611e-02 -2.114444e+02 8.277712e-02 9.945451e-01 6.346646e-02 -6.090039e+00 -1.753060e-02 6.512833e-02 -9.977229e-01 1.831734e+02 +-9.962171e-01 8.391402e-02 2.258342e-02 -2.114203e+02 8.525682e-02 9.940960e-01 6.711493e-02 -6.047240e+00 -1.681821e-02 6.878642e-02 -9.974896e-01 1.822324e+02 +-9.964924e-01 8.061194e-02 2.246393e-02 -2.113912e+02 8.196372e-02 9.943322e-01 6.771514e-02 -6.014291e+00 -1.687796e-02 6.931884e-02 -9.974518e-01 1.812994e+02 +-9.966798e-01 7.838735e-02 2.201789e-02 -2.113628e+02 7.957034e-02 9.950637e-01 5.930266e-02 -5.980596e+00 -1.726062e-02 6.085773e-02 -9.979972e-01 1.803741e+02 +-9.968848e-01 7.584469e-02 2.163803e-02 -2.113326e+02 7.684306e-02 9.957986e-01 4.980221e-02 -5.952377e+00 -1.776989e-02 5.130979e-02 -9.985247e-01 1.794512e+02 +-9.973202e-01 7.002102e-02 2.120075e-02 -2.112979e+02 7.094348e-02 9.963989e-01 4.643588e-02 -5.927095e+00 -1.787292e-02 4.781549e-02 -9.986963e-01 1.785267e+02 +-9.975339e-01 6.644122e-02 2.261978e-02 -2.112647e+02 6.747532e-02 9.965404e-01 4.852112e-02 -5.904498e+00 -1.931773e-02 4.992773e-02 -9.985660e-01 1.776003e+02 +-9.976866e-01 6.338002e-02 2.458539e-02 -2.112338e+02 6.459954e-02 9.965310e-01 5.246717e-02 -5.882852e+00 -2.117473e-02 5.393398e-02 -9.983200e-01 1.766747e+02 +-9.977372e-01 6.172488e-02 2.665526e-02 -2.112021e+02 6.311771e-02 9.964879e-01 5.502731e-02 -5.857461e+00 -2.316509e-02 5.658521e-02 -9.981290e-01 1.757541e+02 +-9.976560e-01 6.208002e-02 2.878394e-02 -2.111720e+02 6.362714e-02 9.963802e-01 5.637456e-02 -5.829335e+00 -2.518002e-02 5.807385e-02 -9.979947e-01 1.748347e+02 +-9.975401e-01 6.260070e-02 3.154148e-02 -2.111398e+02 6.444966e-02 9.960252e-01 6.148167e-02 -5.801620e+00 -2.756732e-02 6.336326e-02 -9.976097e-01 1.739187e+02 +-9.972409e-01 6.549248e-02 3.494768e-02 -2.111071e+02 6.749612e-02 9.959367e-01 5.961768e-02 -5.774563e+00 -3.090117e-02 6.181201e-02 -9.976093e-01 1.730188e+02 +-9.971495e-01 6.474296e-02 3.874628e-02 -2.110679e+02 6.680216e-02 9.962795e-01 5.444722e-02 -5.748131e+00 -3.507705e-02 5.688035e-02 -9.977646e-01 1.721323e+02 +-9.969871e-01 6.475316e-02 4.270482e-02 -2.110276e+02 6.677322e-02 9.966270e-01 4.770598e-02 -5.725014e+00 -3.947167e-02 5.041378e-02 -9.979481e-01 1.712598e+02 +-9.966507e-01 6.736707e-02 4.635756e-02 -2.109863e+02 6.947056e-02 9.965519e-01 4.536648e-02 -5.703921e+00 -4.314151e-02 4.843501e-02 -9.978942e-01 1.703970e+02 +-9.964624e-01 6.777084e-02 4.969656e-02 -2.109425e+02 7.005243e-02 9.964958e-01 4.570193e-02 -5.685131e+00 -4.642516e-02 4.902162e-02 -9.977182e-01 1.695485e+02 +-9.964644e-01 6.523327e-02 5.294646e-02 -2.108926e+02 6.790259e-02 9.964238e-01 5.028678e-02 -5.664783e+00 -4.947675e-02 5.370418e-02 -9.973304e-01 1.687128e+02 +-9.965229e-01 6.162569e-02 5.607568e-02 -2.108459e+02 6.465446e-02 9.964508e-01 5.390313e-02 -5.648736e+00 -5.255484e-02 5.734123e-02 -9.969704e-01 1.679012e+02 +-9.962373e-01 6.365436e-02 5.881714e-02 -2.108075e+02 6.683173e-02 9.963164e-01 5.373185e-02 -5.627670e+00 -5.518022e-02 5.746051e-02 -9.968217e-01 1.671156e+02 +-9.959147e-01 6.596697e-02 6.166242e-02 -2.107723e+02 6.913131e-02 9.963197e-01 5.067396e-02 -5.604228e+00 -5.809268e-02 5.472974e-02 -9.968099e-01 1.663552e+02 +-9.958124e-01 6.510992e-02 6.417387e-02 -2.107271e+02 6.835862e-02 9.964172e-01 4.979748e-02 -5.585872e+00 -6.070165e-02 5.397577e-02 -9.966955e-01 1.656117e+02 +-9.958230e-01 6.217404e-02 6.686554e-02 -2.106779e+02 6.568068e-02 9.965062e-01 5.158839e-02 -5.570710e+00 -6.342447e-02 5.576467e-02 -9.964274e-01 1.648913e+02 +-9.954977e-01 6.458830e-02 6.937313e-02 -2.106313e+02 6.823865e-02 9.963335e-01 5.160383e-02 -5.556506e+00 -6.578578e-02 5.610541e-02 -9.962552e-01 1.641928e+02 +-9.953944e-01 6.356420e-02 7.176028e-02 -2.105826e+02 6.729887e-02 9.964346e-01 5.088223e-02 -5.539846e+00 -6.827014e-02 5.547726e-02 -9.961232e-01 1.635068e+02 +-9.956649e-01 5.674819e-02 7.369617e-02 -2.105238e+02 6.064206e-02 9.968188e-01 5.171888e-02 -5.523969e+00 -7.052678e-02 5.596375e-02 -9.959388e-01 1.628316e+02 +-9.956710e-01 5.401752e-02 7.564024e-02 -2.104688e+02 5.791319e-02 9.970540e-01 5.029173e-02 -5.513155e+00 -7.270078e-02 5.445457e-02 -9.958661e-01 1.621685e+02 +-9.955628e-01 5.220067e-02 7.829362e-02 -2.104178e+02 5.626669e-02 9.971298e-01 5.065741e-02 -5.501282e+00 -7.542456e-02 5.483795e-02 -9.956425e-01 1.615153e+02 +-9.955305e-01 5.175712e-02 7.899539e-02 -2.103693e+02 5.571099e-02 9.972587e-01 4.869571e-02 -5.484230e+00 -7.625850e-02 5.287896e-02 -9.956849e-01 1.608839e+02 +-9.959536e-01 4.690772e-02 7.665531e-02 -2.103205e+02 5.075331e-02 9.975078e-01 4.901313e-02 -5.467645e+00 -7.416518e-02 5.270530e-02 -9.958522e-01 1.602754e+02 +-9.965216e-01 4.058848e-02 7.278190e-02 -2.102752e+02 4.438526e-02 9.976949e-01 5.133044e-02 -5.457424e+00 -7.053071e-02 5.438233e-02 -9.960261e-01 1.596935e+02 +-9.968530e-01 3.963179e-02 6.865474e-02 -2.102434e+02 4.342911e-02 9.975563e-01 5.472999e-02 -5.448397e+00 -6.631792e-02 5.753936e-02 -9.961381e-01 1.591407e+02 +-9.970003e-01 4.167350e-02 6.522089e-02 -2.102176e+02 4.534745e-02 9.974059e-01 5.590251e-02 -5.438743e+00 -6.272205e-02 5.869241e-02 -9.963038e-01 1.586178e+02 +-9.970146e-01 4.503172e-02 6.272239e-02 -2.102000e+02 4.844030e-02 9.973692e-01 5.392686e-02 -5.427855e+00 -6.012896e-02 5.680414e-02 -9.965730e-01 1.581286e+02 +-9.970881e-01 4.696741e-02 6.007847e-02 -2.101804e+02 5.012143e-02 9.973825e-01 5.211508e-02 -5.414440e+00 -5.747351e-02 5.497453e-02 -9.968323e-01 1.576548e+02 +-9.973119e-01 4.533815e-02 5.756250e-02 -2.101593e+02 4.813435e-02 9.976793e-01 4.815659e-02 -5.405152e+00 -5.524558e-02 5.079787e-02 -9.971798e-01 1.571902e+02 +-9.974415e-01 4.398668e-02 5.635284e-02 -2.101355e+02 4.661255e-02 9.978458e-01 4.616178e-02 -5.397323e+00 -5.420095e-02 4.867041e-02 -9.973432e-01 1.567245e+02 +-9.973949e-01 4.406423e-02 5.711270e-02 -2.101197e+02 4.666515e-02 9.978948e-01 4.503545e-02 -5.384597e+00 -5.500802e-02 4.758330e-02 -9.973515e-01 1.562630e+02 +-9.973874e-01 4.390437e-02 5.736523e-02 -2.101016e+02 4.657091e-02 9.978551e-01 4.600389e-02 -5.371609e+00 -5.522242e-02 4.855525e-02 -9.972928e-01 1.558017e+02 +-9.973639e-01 4.319266e-02 5.830710e-02 -2.100810e+02 4.588705e-02 9.979012e-01 4.569025e-02 -5.353544e+00 -5.621124e-02 4.824534e-02 -9.972526e-01 1.553447e+02 +-9.971828e-01 4.438324e-02 6.046928e-02 -2.100598e+02 4.704524e-02 9.979524e-01 4.333318e-02 -5.338763e+00 -5.842220e-02 4.605589e-02 -9.972290e-01 1.548929e+02 +-9.970218e-01 4.361954e-02 6.360008e-02 -2.100368e+02 4.631727e-02 9.980611e-01 4.157774e-02 -5.330124e+00 -6.166317e-02 4.439969e-02 -9.971090e-01 1.544460e+02 +-9.968260e-01 4.261444e-02 6.724475e-02 -2.100084e+02 4.519914e-02 9.982778e-01 3.739495e-02 -5.324180e+00 -6.553539e-02 4.031566e-02 -9.970355e-01 1.540066e+02 +-9.965137e-01 4.289857e-02 7.155602e-02 -2.099787e+02 4.528685e-02 9.984583e-01 3.209391e-02 -5.317249e+00 -7.006893e-02 3.522256e-02 -9.969201e-01 1.535710e+02 +-9.961566e-01 4.424491e-02 7.559432e-02 -2.099495e+02 4.643794e-02 9.985425e-01 2.750223e-02 -5.307955e+00 -7.426731e-02 3.090696e-02 -9.967593e-01 1.531398e+02 +-9.957218e-01 4.745565e-02 7.928534e-02 -2.099211e+02 4.964879e-02 9.984303e-01 2.592162e-02 -5.294879e+00 -7.793076e-02 2.974714e-02 -9.965149e-01 1.527086e+02 +-9.951845e-01 5.080567e-02 8.382532e-02 -2.098917e+02 5.319934e-02 9.982303e-01 2.657155e-02 -5.278681e+00 -8.232699e-02 3.090304e-02 -9.961261e-01 1.522725e+02 +-9.947547e-01 5.202561e-02 8.807082e-02 -2.098558e+02 5.477255e-02 9.980757e-01 2.906455e-02 -5.266096e+00 -8.638925e-02 3.373595e-02 -9.956901e-01 1.518252e+02 +-9.944372e-01 5.062317e-02 9.236821e-02 -2.098134e+02 5.401675e-02 9.979398e-01 3.461555e-02 -5.259962e+00 -9.042557e-02 3.941241e-02 -9.951231e-01 1.513688e+02 +-9.940376e-01 4.890324e-02 9.745669e-02 -2.097667e+02 5.317025e-02 9.977153e-01 4.167690e-02 -5.256315e+00 -9.519590e-02 4.661019e-02 -9.943668e-01 1.509003e+02 +-9.934704e-01 4.912954e-02 1.029699e-01 -2.097207e+02 5.429341e-02 9.973726e-01 4.795989e-02 -5.249506e+00 -1.003431e-01 5.323731e-02 -9.935276e-01 1.504243e+02 +-9.927063e-01 5.231173e-02 1.086175e-01 -2.096751e+02 5.795470e-02 9.970932e-01 4.946067e-02 -5.235258e+00 -1.057145e-01 5.539480e-02 -9.928524e-01 1.499422e+02 +-9.920344e-01 5.488601e-02 1.133808e-01 -2.096184e+02 6.063283e-02 9.970114e-01 4.787278e-02 -5.217367e+00 -1.104145e-01 5.436604e-02 -9.923976e-01 1.494539e+02 +-9.915611e-01 5.390750e-02 1.179007e-01 -2.095515e+02 5.971018e-02 9.971438e-01 4.624857e-02 -5.198881e+00 -1.150708e-01 5.289815e-02 -9.919478e-01 1.489526e+02 +-9.912496e-01 5.080363e-02 1.218326e-01 -2.094768e+02 5.681403e-02 9.973071e-01 4.637548e-02 -5.180534e+00 -1.191485e-01 5.289147e-02 -9.914667e-01 1.484393e+02 +-9.910820e-01 4.772702e-02 1.244129e-01 -2.094020e+02 5.407378e-02 9.973756e-01 4.814427e-02 -5.160394e+00 -1.217886e-01 5.444238e-02 -9.910618e-01 1.479118e+02 +-9.909392e-01 4.565767e-02 1.263131e-01 -2.093257e+02 5.236387e-02 9.973610e-01 5.028944e-02 -5.139565e+00 -1.236836e-01 5.644800e-02 -9.907149e-01 1.473706e+02 +-9.907879e-01 4.499240e-02 1.277304e-01 -2.092519e+02 5.192755e-02 9.973224e-01 5.149311e-02 -5.120002e+00 -1.250716e-01 5.765147e-02 -9.904713e-01 1.468160e+02 +-9.908599e-01 4.349662e-02 1.276896e-01 -2.091745e+02 5.038239e-02 9.974168e-01 5.119934e-02 -5.099743e+00 -1.251328e-01 5.716468e-02 -9.904918e-01 1.462480e+02 +-9.911522e-01 4.218087e-02 1.258499e-01 -2.090957e+02 4.878933e-02 9.975619e-01 4.989755e-02 -5.077073e+00 -1.234383e-01 5.559619e-02 -9.907937e-01 1.456660e+02 +-9.915365e-01 4.081560e-02 1.232455e-01 -2.090174e+02 4.699866e-02 9.977561e-01 4.768419e-02 -5.053225e+00 -1.210227e-01 5.307298e-02 -9.912299e-01 1.450680e+02 +-9.919341e-01 4.005040e-02 1.202609e-01 -2.089394e+02 4.586163e-02 9.978905e-01 4.594831e-02 -5.028544e+00 -1.181670e-01 5.109305e-02 -9.916784e-01 1.444530e+02 +-9.924255e-01 3.804769e-02 1.168076e-01 -2.088613e+02 4.381897e-02 9.979218e-01 4.724367e-02 -5.003423e+00 -1.147674e-01 5.200421e-02 -9.920303e-01 1.438192e+02 +-9.928395e-01 3.963236e-02 1.126903e-01 -2.087871e+02 4.550011e-02 9.977131e-01 4.998271e-02 -4.979672e+00 -1.104517e-01 5.475222e-02 -9.923722e-01 1.431640e+02 +-9.933107e-01 3.936079e-02 1.085568e-01 -2.087149e+02 4.508601e-02 9.976907e-01 5.079834e-02 -4.958162e+00 -1.063067e-01 5.535292e-02 -9.927915e-01 1.424972e+02 +-9.940970e-01 3.480002e-02 1.027629e-01 -2.086371e+02 4.014443e-02 9.979217e-01 5.040482e-02 -4.934711e+00 -1.007953e-01 5.423262e-02 -9.934280e-01 1.418131e+02 +-9.950747e-01 3.092912e-02 9.417934e-02 -2.085645e+02 3.548775e-02 9.982586e-01 4.711955e-02 -4.906115e+00 -9.255798e-02 5.022968e-02 -9.944395e-01 1.411172e+02 +-9.960448e-01 2.965648e-02 8.375755e-02 -2.085038e+02 3.345925e-02 9.984547e-01 4.436902e-02 -4.877445e+00 -8.231230e-02 4.699599e-02 -9.954979e-01 1.404032e+02 +-9.970964e-01 2.822993e-02 7.072331e-02 -2.084549e+02 3.148137e-02 9.984777e-01 4.528906e-02 -4.851981e+00 -6.933715e-02 4.738402e-02 -9.964673e-01 1.396707e+02 +-9.980986e-01 2.713018e-02 5.534552e-02 -2.084151e+02 2.971243e-02 9.984819e-01 4.637998e-02 -4.822992e+00 -5.400320e-02 4.793624e-02 -9.973895e-01 1.389172e+02 +-9.987968e-01 2.765989e-02 4.049513e-02 -2.083930e+02 2.957809e-02 9.984302e-01 4.756185e-02 -4.793719e+00 -3.911601e-02 4.870239e-02 -9.980471e-01 1.381509e+02 +-9.992907e-01 2.780223e-02 2.540136e-02 -2.083787e+02 2.894621e-02 9.985294e-01 4.583703e-02 -4.767033e+00 -2.408964e-02 4.653978e-02 -9.986259e-01 1.373689e+02 +-9.995209e-01 2.924458e-02 1.013666e-02 -2.083775e+02 2.967806e-02 9.985171e-01 4.563794e-02 -4.735258e+00 -8.786967e-03 4.591691e-02 -9.989066e-01 1.365700e+02 +-9.994854e-01 3.191833e-02 -3.185807e-03 -2.083896e+02 3.173695e-02 9.984242e-01 4.627890e-02 -4.700582e+00 4.657933e-03 4.615397e-02 -9.989235e-01 1.357510e+02 +-9.993264e-01 3.376975e-02 -1.436202e-02 -2.084084e+02 3.300765e-02 9.981861e-01 5.034780e-02 -4.668737e+00 1.603620e-02 4.983982e-02 -9.986285e-01 1.349119e+02 +-9.991734e-01 3.339344e-02 -2.318186e-02 -2.084293e+02 3.212726e-02 9.980777e-01 5.299662e-02 -4.637261e+00 2.490704e-02 5.220804e-02 -9.983256e-01 1.340569e+02 +-9.989351e-01 3.542378e-02 -2.956126e-02 -2.084583e+02 3.385368e-02 9.980719e-01 5.202306e-02 -4.601627e+00 3.134712e-02 5.096690e-02 -9.982083e-01 1.331905e+02 +-9.988238e-01 3.468039e-02 -3.388684e-02 -2.084857e+02 3.292252e-02 9.981495e-01 5.112413e-02 -4.566084e+00 3.559714e-02 4.994835e-02 -9.981172e-01 1.323082e+02 +-9.986325e-01 3.709306e-02 -3.684000e-02 -2.085188e+02 3.513386e-02 9.980039e-01 5.247604e-02 -4.529298e+00 3.871296e-02 5.110994e-02 -9.979424e-01 1.314126e+02 +-9.985328e-01 3.786232e-02 -3.871235e-02 -2.085549e+02 3.569097e-02 9.978305e-01 5.532055e-02 -4.490779e+00 4.072293e-02 5.385770e-02 -9.977179e-01 1.305038e+02 +-9.983992e-01 3.982531e-02 -4.016202e-02 -2.085945e+02 3.741306e-02 9.975493e-01 5.912440e-02 -4.450291e+00 4.241824e-02 5.752716e-02 -9.974424e-01 1.295794e+02 +-9.982681e-01 4.269404e-02 -4.047298e-02 -2.086379e+02 4.035901e-02 9.975664e-01 5.685387e-02 -4.412283e+00 4.280181e-02 5.512194e-02 -9.975618e-01 1.286512e+02 +-9.982348e-01 4.368169e-02 -4.023934e-02 -2.086796e+02 4.166147e-02 9.978926e-01 4.974541e-02 -4.372725e+00 4.232751e-02 4.798116e-02 -9.979510e-01 1.277089e+02 +-9.980932e-01 4.755410e-02 -3.935164e-02 -2.087220e+02 4.580389e-02 9.979702e-01 4.424299e-02 -4.331543e+00 4.137571e-02 4.235616e-02 -9.982455e-01 1.267531e+02 +-9.981338e-01 4.803353e-02 -3.770600e-02 -2.087634e+02 4.620086e-02 9.977755e-01 4.805757e-02 -4.294315e+00 3.993050e-02 4.622583e-02 -9.981326e-01 1.257780e+02 +-9.980910e-01 4.998506e-02 -3.627485e-02 -2.088077e+02 4.806380e-02 9.974881e-01 5.203253e-02 -4.253239e+00 3.878458e-02 5.018968e-02 -9.979864e-01 1.247883e+02 +-9.980075e-01 5.263443e-02 -3.479315e-02 -2.088528e+02 5.065330e-02 9.971696e-01 5.555985e-02 -4.211516e+00 3.761904e-02 5.368675e-02 -9.978490e-01 1.237917e+02 +-9.979244e-01 5.513963e-02 -3.326516e-02 -2.088931e+02 5.322520e-02 9.970153e-01 5.592494e-02 -4.168374e+00 3.624955e-02 5.403831e-02 -9.978807e-01 1.227906e+02 +-9.980866e-01 5.367938e-02 -3.068612e-02 -2.089278e+02 5.183760e-02 9.969724e-01 5.795633e-02 -4.126068e+00 3.370428e-02 5.625474e-02 -9.978474e-01 1.217860e+02 +-9.979181e-01 5.797983e-02 -2.824532e-02 -2.089520e+02 5.615810e-02 9.965256e-01 6.150511e-02 -4.077227e+00 3.171325e-02 5.979085e-02 -9.977070e-01 1.207766e+02 +-9.977902e-01 6.154511e-02 -2.503903e-02 -2.089752e+02 5.997151e-02 9.964328e-01 5.937170e-02 -4.031311e+00 2.860375e-02 5.773886e-02 -9.979219e-01 1.197726e+02 +-9.978393e-01 6.210775e-02 -2.143348e-02 -2.089864e+02 6.084406e-02 9.966151e-01 5.528458e-02 -3.985710e+00 2.479453e-02 5.386102e-02 -9.982406e-01 1.187706e+02 +-9.973568e-01 7.074711e-02 -1.656174e-02 -2.090034e+02 6.982607e-02 9.962647e-01 5.080213e-02 -3.940764e+00 2.009398e-02 4.951140e-02 -9.985714e-01 1.177690e+02 +-9.970515e-01 7.601476e-02 -1.049561e-02 -2.090099e+02 7.540545e-02 9.959156e-01 4.965917e-02 -3.898789e+00 1.422757e-02 4.872131e-02 -9.987111e-01 1.167602e+02 +-9.969056e-01 7.853927e-02 -3.303632e-03 -2.090108e+02 7.826138e-02 9.955699e-01 5.211157e-02 -3.859261e+00 7.381802e-03 5.169176e-02 -9.986358e-01 1.157539e+02 +-9.970606e-01 7.648932e-02 4.420754e-03 -2.089924e+02 7.661614e-02 9.956606e-01 5.281983e-02 -3.822236e+00 -3.614181e-04 5.300326e-02 -9.985943e-01 1.147487e+02 +-9.969328e-01 7.746439e-02 1.114675e-02 -2.089740e+02 7.795772e-02 9.954822e-01 5.420042e-02 -3.784211e+00 -6.897787e-03 5.490314e-02 -9.984679e-01 1.137523e+02 +-9.972201e-01 7.243522e-02 1.747174e-02 -2.089440e+02 7.324913e-02 9.959777e-01 5.160400e-02 -3.746651e+00 -1.366352e-02 5.274032e-02 -9.985148e-01 1.127619e+02 +-9.973679e-01 6.872381e-02 2.311518e-02 -2.089088e+02 6.972877e-02 9.965087e-01 4.591514e-02 -3.714344e+00 -1.987902e-02 4.740607e-02 -9.986779e-01 1.117801e+02 +-9.971962e-01 6.893950e-02 2.910479e-02 -2.088767e+02 7.024485e-02 9.964453e-01 4.650208e-02 -3.683660e+00 -2.579550e-02 4.841616e-02 -9.984941e-01 1.107927e+02 +-9.972963e-01 6.495081e-02 3.437198e-02 -2.088365e+02 6.670219e-02 9.963892e-01 5.252941e-02 -3.656693e+00 -3.083605e-02 5.468006e-02 -9.980277e-01 1.098091e+02 +-9.971907e-01 6.448976e-02 3.810196e-02 -2.087973e+02 6.670531e-02 9.959633e-01 6.006149e-02 -3.627959e+00 -3.407481e-02 6.243435e-02 -9.974672e-01 1.088279e+02 +-9.972409e-01 6.133594e-02 4.181472e-02 -2.087538e+02 6.379008e-02 9.961503e-01 6.012815e-02 -3.600164e+00 -3.796573e-02 6.262961e-02 -9.973145e-01 1.078628e+02 +-9.972849e-01 5.944301e-02 4.346736e-02 -2.087106e+02 6.189493e-02 9.964293e-01 5.742469e-02 -3.571250e+00 -3.989866e-02 5.995918e-02 -9.974031e-01 1.069138e+02 +-9.974570e-01 5.584002e-02 4.428900e-02 -2.086738e+02 5.825846e-02 9.967666e-01 5.533703e-02 -3.547612e+00 -4.105578e-02 5.777650e-02 -9.974850e-01 1.059754e+02 +-9.973377e-01 5.747682e-02 4.487670e-02 -2.086412e+02 5.991819e-02 9.966816e-01 5.509663e-02 -3.530616e+00 -4.156100e-02 5.763887e-02 -9.974720e-01 1.050613e+02 +-9.970700e-01 6.071987e-02 4.652413e-02 -2.086129e+02 6.323710e-02 9.964987e-01 5.469259e-02 -3.509977e+00 -4.304031e-02 5.747438e-02 -9.974188e-01 1.041648e+02 +-9.967292e-01 6.566567e-02 4.710456e-02 -2.085844e+02 6.813267e-02 9.962764e-01 5.283239e-02 -3.486661e+00 -4.345989e-02 5.586894e-02 -9.974918e-01 1.032909e+02 +-9.963339e-01 7.074971e-02 4.809564e-02 -2.085548e+02 7.334655e-02 9.958129e-01 5.456131e-02 -3.464868e+00 -4.403406e-02 5.788892e-02 -9.973514e-01 1.024383e+02 +-9.960788e-01 7.317221e-02 4.972777e-02 -2.085241e+02 7.590019e-02 9.955762e-01 5.538236e-02 -3.446468e+00 -4.545533e-02 5.893954e-02 -9.972261e-01 1.016129e+02 +-9.962713e-01 6.969401e-02 5.085485e-02 -2.084864e+02 7.257192e-02 9.957258e-01 5.712691e-02 -3.428738e+00 -4.665609e-02 6.060453e-02 -9.970709e-01 1.008106e+02 +-9.963472e-01 6.870568e-02 5.071282e-02 -2.084487e+02 7.148064e-02 9.959190e-01 5.509900e-02 -3.408348e+00 -4.672025e-02 5.852271e-02 -9.971922e-01 1.000377e+02 +-9.965472e-01 6.666812e-02 4.948801e-02 -2.084118e+02 6.933196e-02 9.961192e-01 5.421827e-02 -3.391020e+00 -4.568133e-02 5.746215e-02 -9.973020e-01 9.929195e+01 +-9.968887e-01 6.269860e-02 4.776790e-02 -2.083728e+02 6.531699e-02 9.963265e-01 5.538181e-02 -3.374128e+00 -4.412007e-02 5.832955e-02 -9.973220e-01 9.857546e+01 +-9.972541e-01 5.843370e-02 4.549482e-02 -2.083355e+02 6.091803e-02 9.966106e-01 5.528282e-02 -3.359539e+00 -4.211024e-02 5.790246e-02 -9.974337e-01 9.788868e+01 +-9.974766e-01 5.543883e-02 4.435110e-02 -2.083040e+02 5.786099e-02 9.967900e-01 5.533336e-02 -3.344992e+00 -4.114112e-02 5.775992e-02 -9.974824e-01 9.723140e+01 +-9.975920e-01 5.414462e-02 4.334275e-02 -2.082796e+02 5.656865e-02 9.967814e-01 5.680426e-02 -3.331175e+00 -4.012761e-02 5.911930e-02 -9.974441e-01 9.660377e+01 +-9.976704e-01 5.329998e-02 4.257847e-02 -2.082589e+02 5.572539e-02 9.967620e-01 5.796740e-02 -3.318805e+00 -3.935094e-02 6.020505e-02 -9.974101e-01 9.600899e+01 +-9.977263e-01 5.300924e-02 4.161945e-02 -2.082399e+02 5.548410e-02 9.966097e-01 6.075064e-02 -3.306868e+00 -3.825801e-02 6.292172e-02 -9.972849e-01 9.544144e+01 +-9.979074e-01 4.997928e-02 4.102212e-02 -2.082248e+02 5.251971e-02 9.966063e-01 6.338349e-02 -3.291645e+00 -3.771505e-02 6.540532e-02 -9.971458e-01 9.490682e+01 +-9.982190e-01 4.477720e-02 3.941872e-02 -2.082051e+02 4.727600e-02 9.967697e-01 6.492411e-02 -3.274545e+00 -3.638427e-02 6.667203e-02 -9.971113e-01 9.440178e+01 +-9.984562e-01 4.023824e-02 3.829020e-02 -2.081866e+02 4.265024e-02 9.970115e-01 6.441314e-02 -3.257993e+00 -3.558390e-02 6.594677e-02 -9.971885e-01 9.392899e+01 +-9.985329e-01 3.925398e-02 3.729825e-02 -2.081728e+02 4.155691e-02 9.971405e-01 6.311805e-02 -3.242366e+00 -3.471396e-02 6.457544e-02 -9.973089e-01 9.347869e+01 +-9.983084e-01 4.454050e-02 3.737035e-02 -2.081715e+02 4.667337e-02 9.972081e-01 5.828842e-02 -3.229713e+00 -3.466982e-02 5.993400e-02 -9.976001e-01 9.304521e+01 +-9.980423e-01 4.950946e-02 3.821393e-02 -2.081694e+02 5.151590e-02 9.972413e-01 5.343989e-02 -3.217688e+00 -3.546273e-02 5.530389e-02 -9.978396e-01 9.262010e+01 +-9.979380e-01 5.116152e-02 3.875869e-02 -2.081590e+02 5.302500e-02 9.974058e-01 4.868198e-02 -3.206346e+00 -3.616750e-02 5.063677e-02 -9.980620e-01 9.219859e+01 +-9.981947e-01 4.469479e-02 4.012032e-02 -2.081349e+02 4.652448e-02 9.978624e-01 4.589272e-02 -3.196441e+00 -3.798340e-02 4.767644e-02 -9.981404e-01 9.177931e+01 +-9.983323e-01 3.964744e-02 4.196145e-02 -2.081114e+02 4.154665e-02 9.981045e-01 4.540028e-02 -3.185915e+00 -4.008191e-02 4.706792e-02 -9.980872e-01 9.135906e+01 +-9.980926e-01 4.310404e-02 4.419598e-02 -2.081019e+02 4.512679e-02 9.979290e-01 4.583974e-02 -3.173097e+00 -4.212858e-02 4.774672e-02 -9.979707e-01 9.094010e+01 +-9.976143e-01 5.052555e-02 4.704109e-02 -2.081043e+02 5.279760e-02 9.974326e-01 4.837886e-02 -3.159591e+00 -4.447595e-02 5.074709e-02 -9.977207e-01 9.052143e+01 +-9.972019e-01 5.671444e-02 4.870250e-02 -2.081037e+02 5.908382e-02 9.970657e-01 4.867215e-02 -3.148259e+00 -4.579919e-02 5.141348e-02 -9.976267e-01 9.010806e+01 +-9.970181e-01 5.850325e-02 5.032119e-02 -2.080945e+02 6.089496e-02 9.970187e-01 4.738623e-02 -3.141868e+00 -4.739893e-02 5.030923e-02 -9.976083e-01 8.970191e+01 +-9.970214e-01 5.735625e-02 5.156072e-02 -2.080795e+02 5.976157e-02 9.971343e-01 4.638531e-02 -3.140057e+00 -4.875248e-02 4.932849e-02 -9.975921e-01 8.929831e+01 +-9.969647e-01 5.675984e-02 5.328942e-02 -2.080573e+02 5.925849e-02 9.971571e-01 4.654054e-02 -3.133050e+00 -5.049630e-02 4.955712e-02 -9.974940e-01 8.889905e+01 +-9.965310e-01 5.987261e-02 5.780271e-02 -2.080384e+02 6.271322e-02 9.968453e-01 4.864687e-02 -3.116641e+00 -5.470775e-02 5.210311e-02 -9.971421e-01 8.849747e+01 +-9.958311e-01 6.552448e-02 6.345862e-02 -2.080225e+02 6.870092e-02 9.964215e-01 4.923664e-02 -3.093235e+00 -6.000534e-02 5.339103e-02 -9.967692e-01 8.809395e+01 +-9.955607e-01 6.413654e-02 6.888643e-02 -2.079897e+02 6.757981e-02 9.965161e-01 4.887301e-02 -3.076235e+00 -6.551190e-02 5.331138e-02 -9.964267e-01 8.768622e+01 +-9.953511e-01 6.024522e-02 7.514438e-02 -2.079509e+02 6.401149e-02 9.967572e-01 4.875994e-02 -3.068810e+00 -7.196316e-02 5.334335e-02 -9.959798e-01 8.727126e+01 +-9.947819e-01 6.088316e-02 8.186674e-02 -2.079168e+02 6.498587e-02 9.967108e-01 4.841824e-02 -3.067509e+00 -7.864961e-02 5.348577e-02 -9.954665e-01 8.685100e+01 +-9.939245e-01 6.560835e-02 8.837168e-02 -2.078875e+02 7.010821e-02 9.963443e-01 4.881358e-02 -3.060190e+00 -8.484605e-02 5.471259e-02 -9.948908e-01 8.642484e+01 +-9.931341e-01 6.964136e-02 9.399379e-02 -2.078511e+02 7.431163e-02 9.961206e-01 4.713291e-02 -3.047394e+00 -9.034675e-02 5.379412e-02 -9.944565e-01 8.598992e+01 +-9.926171e-01 6.993931e-02 9.909526e-02 -2.078060e+02 7.450430e-02 9.962873e-01 4.313600e-02 -3.032393e+00 -9.571046e-02 5.020054e-02 -9.941426e-01 8.555205e+01 +-9.924159e-01 6.601009e-02 1.036987e-01 -2.077497e+02 7.032434e-02 9.967805e-01 3.850955e-02 -3.020153e+00 -1.008228e-01 4.551002e-02 -9.938630e-01 8.510648e+01 +-9.921099e-01 6.153816e-02 1.092291e-01 -2.076903e+02 6.595663e-02 9.971248e-01 3.730677e-02 -3.011341e+00 -1.066192e-01 4.421680e-02 -9.933163e-01 8.464649e+01 +-9.914829e-01 6.009694e-02 1.155420e-01 -2.076323e+02 6.509516e-02 9.970778e-01 3.998023e-02 -3.004311e+00 -1.128017e-01 4.716094e-02 -9.924977e-01 8.417017e+01 +-9.905738e-01 6.306130e-02 1.216015e-01 -2.075734e+02 6.844105e-02 9.968295e-01 4.057946e-02 -2.999691e+00 -1.186570e-01 4.851947e-02 -9.917492e-01 8.367943e+01 +-9.897090e-01 6.632593e-02 1.267951e-01 -2.075100e+02 7.186609e-02 9.966268e-01 3.962530e-02 -2.994865e+00 -1.237392e-01 4.832978e-02 -9.911372e-01 8.317606e+01 +-9.890615e-01 6.796346e-02 1.309134e-01 -2.074397e+02 7.375673e-02 9.964770e-01 3.991868e-02 -2.993126e+00 -1.277392e-01 4.913777e-02 -9.905898e-01 8.265887e+01 +-9.888409e-01 6.559860e-02 1.337551e-01 -2.073638e+02 7.151015e-02 9.966424e-01 3.987733e-02 -2.990417e+00 -1.306901e-01 4.899717e-02 -9.902118e-01 8.212821e+01 +-9.889216e-01 6.106177e-02 1.352978e-01 -2.072799e+02 6.655059e-02 9.971181e-01 3.641962e-02 -2.989393e+00 -1.326841e-01 4.502029e-02 -9.901354e-01 8.158879e+01 +-9.891033e-01 5.737240e-02 1.355841e-01 -2.071987e+02 6.214772e-02 9.975776e-01 3.125054e-02 -2.985665e+00 -1.334628e-01 3.933626e-02 -9.902729e-01 8.103588e+01 +-9.892656e-01 5.547763e-02 1.351879e-01 -2.071178e+02 5.971776e-02 9.978361e-01 2.751076e-02 -2.983265e+00 -1.333692e-01 3.528856e-02 -9.904380e-01 8.046675e+01 +-9.894800e-01 5.424725e-02 1.341143e-01 -2.070397e+02 5.836967e-02 9.979299e-01 2.699671e-02 -2.974518e+00 -1.323722e-01 3.454090e-02 -9.905981e-01 7.987968e+01 +-9.899964e-01 5.100397e-02 1.315512e-01 -2.069638e+02 5.549674e-02 9.979864e-01 3.071262e-02 -2.964375e+00 -1.297199e-01 3.770604e-02 -9.908335e-01 7.927897e+01 +-9.906077e-01 4.598443e-02 1.287707e-01 -2.068866e+02 5.129445e-02 9.979517e-01 3.822620e-02 -2.956007e+00 -1.267491e-01 4.447238e-02 -9.909374e-01 7.865799e+01 +-9.912702e-01 4.015451e-02 1.255831e-01 -2.068088e+02 4.650192e-02 9.977630e-01 4.802607e-02 -2.947579e+00 -1.233737e-01 5.344665e-02 -9.909200e-01 7.802143e+01 +-9.920580e-01 3.398432e-02 1.211030e-01 -2.067298e+02 4.069227e-02 9.977462e-01 5.335416e-02 -2.935628e+00 -1.190168e-01 5.785837e-02 -9.912050e-01 7.737446e+01 +-9.928557e-01 2.896562e-02 1.157521e-01 -2.066532e+02 3.501938e-02 9.981042e-01 5.061220e-02 -2.919758e+00 -1.140666e-01 5.430417e-02 -9.919878e-01 7.672114e+01 +-9.937291e-01 2.556653e-02 1.088525e-01 -2.065841e+02 3.090227e-02 9.983875e-01 4.761645e-02 -2.901849e+00 -1.074596e-01 5.068163e-02 -9.929168e-01 7.605626e+01 +-9.947445e-01 2.566428e-02 9.911968e-02 -2.065253e+02 2.988387e-02 9.986988e-01 4.132294e-02 -2.884761e+00 -9.793019e-02 4.406784e-02 -9.942171e-01 7.537959e+01 +-9.958403e-01 2.798860e-02 8.671021e-02 -2.064743e+02 3.125361e-02 9.988438e-01 3.652799e-02 -2.872191e+00 -8.558759e-02 3.908604e-02 -9.955637e-01 7.468719e+01 +-9.970010e-01 2.661144e-02 7.266945e-02 -2.064313e+02 2.914385e-02 9.989963e-01 3.401308e-02 -2.860695e+00 -7.169138e-02 3.602894e-02 -9.967759e-01 7.398221e+01 +-9.979677e-01 2.916895e-02 5.665471e-02 -2.064026e+02 3.100811e-02 9.990112e-01 3.185915e-02 -2.849991e+00 -5.566940e-02 3.355115e-02 -9.978854e-01 7.326248e+01 +-9.988111e-01 2.879659e-02 3.933386e-02 -2.063881e+02 3.010433e-02 9.989996e-01 3.306919e-02 -2.840941e+00 -3.834223e-02 3.421399e-02 -9.986788e-01 7.253724e+01 +-9.993308e-01 2.999563e-02 2.093278e-02 -2.063898e+02 3.076737e-02 9.988201e-01 3.757417e-02 -2.834688e+00 -1.978102e-02 3.819306e-02 -9.990746e-01 7.180209e+01 +-9.995397e-01 3.032471e-02 9.198298e-04 -2.064030e+02 3.033694e-02 9.986994e-01 4.097832e-02 -2.821783e+00 3.240222e-04 4.098736e-02 -9.991596e-01 7.105204e+01 +-9.993650e-01 2.982374e-02 -1.949565e-02 -2.064322e+02 2.888420e-02 9.984857e-01 4.681758e-02 -2.805616e+00 2.086240e-02 4.622473e-02 -9.987132e-01 7.029823e+01 +-9.987454e-01 3.013494e-02 -3.999305e-02 -2.064743e+02 2.808504e-02 9.983106e-01 5.086479e-02 -2.790108e+00 4.145829e-02 4.967776e-02 -9.979045e-01 6.953225e+01 +-9.977472e-01 3.139079e-02 -5.928914e-02 -2.065346e+02 2.845099e-02 9.983542e-01 4.979404e-02 -2.774963e+00 6.075464e-02 4.799503e-02 -9.969982e-01 6.876717e+01 +-9.964761e-01 3.484116e-02 -7.629871e-02 -2.066101e+02 3.182730e-02 9.986779e-01 4.036727e-02 -2.753931e+00 7.760428e-02 3.779663e-02 -9.962675e-01 6.800061e+01 +-9.951402e-01 3.992303e-02 -9.001247e-02 -2.066954e+02 3.705298e-02 9.987571e-01 3.333449e-02 -2.731269e+00 9.123142e-02 2.983725e-02 -9.953826e-01 6.722158e+01 +-9.941469e-01 4.571264e-02 -9.788943e-02 -2.067920e+02 4.264620e-02 9.985387e-01 3.319334e-02 -2.713533e+00 9.926374e-02 2.882444e-02 -9.946436e-01 6.642676e+01 +-9.934693e-01 5.313976e-02 -1.009703e-01 -2.068927e+02 4.961636e-02 9.980793e-01 3.709388e-02 -2.701554e+00 1.027476e-01 3.184184e-02 -9.941977e-01 6.562261e+01 +-9.931405e-01 5.965011e-02 -1.005680e-01 -2.069911e+02 5.603536e-02 9.976902e-01 3.839562e-02 -2.685436e+00 1.026260e-01 3.249688e-02 -9.941891e-01 6.480806e+01 +-9.931113e-01 6.471971e-02 -9.767989e-02 -2.070872e+02 6.097708e-02 9.973037e-01 4.082936e-02 -2.663884e+00 1.000590e-01 3.459186e-02 -9.943800e-01 6.398349e+01 +-9.935177e-01 6.548761e-02 -9.291902e-02 -2.071764e+02 6.151792e-02 9.970926e-01 4.496487e-02 -2.644012e+00 9.559351e-02 3.895720e-02 -9.946578e-01 6.314509e+01 +-9.938455e-01 6.880979e-02 -8.681225e-02 -2.072609e+02 6.446633e-02 9.965701e-01 5.188474e-02 -2.621091e+00 9.008468e-02 4.596894e-02 -9.948727e-01 6.229617e+01 +-9.942678e-01 7.212626e-02 -7.892637e-02 -2.073410e+02 6.824357e-02 9.963727e-01 5.083572e-02 -2.596241e+00 8.230667e-02 4.515810e-02 -9.955834e-01 6.144487e+01 +-9.947263e-01 7.450692e-02 -7.048652e-02 -2.074113e+02 7.125761e-02 9.963241e-01 4.754465e-02 -2.570615e+00 7.376984e-02 4.227121e-02 -9.963790e-01 6.058253e+01 +-9.949939e-01 7.874384e-02 -6.153558e-02 -2.074768e+02 7.625318e-02 9.962106e-01 4.182998e-02 -2.545537e+00 6.459626e-02 3.692828e-02 -9.972280e-01 5.971478e+01 +-9.956133e-01 7.707283e-02 -5.304625e-02 -2.075278e+02 7.516317e-02 9.964807e-01 3.710263e-02 -2.527116e+00 5.571918e-02 3.295274e-02 -9.979026e-01 5.883306e+01 +-9.962529e-01 7.448504e-02 -4.395565e-02 -2.075664e+02 7.295447e-02 9.967048e-01 3.545672e-02 -2.510016e+00 4.645180e-02 3.211710e-02 -9.984041e-01 5.793678e+01 +-9.965740e-01 7.493479e-02 -3.499975e-02 -2.076019e+02 7.365463e-02 9.966142e-01 3.653779e-02 -2.490917e+00 3.761921e-02 3.383471e-02 -9.987192e-01 5.703045e+01 +-9.966573e-01 7.715079e-02 -2.687180e-02 -2.076339e+02 7.607180e-02 9.963355e-01 3.909667e-02 -2.473284e+00 2.978967e-02 3.692179e-02 -9.988741e-01 5.611027e+01 +-9.970353e-01 7.439179e-02 -1.966054e-02 -2.076477e+02 7.353936e-02 9.964487e-01 4.101093e-02 -2.456900e+00 2.264159e-02 3.944352e-02 -9.989653e-01 5.518456e+01 +-9.974998e-01 6.963406e-02 -1.205517e-02 -2.076532e+02 6.908802e-02 9.967692e-01 4.096391e-02 -2.436469e+00 1.486871e-02 4.002862e-02 -9.990879e-01 5.425422e+01 +-9.975179e-01 7.024026e-02 -4.933111e-03 -2.076589e+02 6.998523e-02 9.967309e-01 4.036821e-02 -2.416480e+00 7.752458e-03 3.992277e-02 -9.991727e-01 5.332067e+01 +-9.974890e-01 7.081352e-02 1.074986e-03 -2.076615e+02 7.079769e-02 9.966407e-01 4.117020e-02 -2.400240e+00 1.844033e-03 4.114293e-02 -9.991516e-01 5.238539e+01 +-9.975725e-01 6.940852e-02 5.626068e-03 -2.076525e+02 6.958732e-02 9.966398e-01 4.320577e-02 -2.377317e+00 -2.608315e-03 4.349238e-02 -9.990504e-01 5.143694e+01 +-9.974956e-01 7.015064e-02 9.022500e-03 -2.076393e+02 7.049041e-02 9.964740e-01 4.550434e-02 -2.352708e+00 -5.798528e-03 4.602637e-02 -9.989234e-01 5.049008e+01 +-9.975292e-01 6.921055e-02 1.206272e-02 -2.076213e+02 6.968155e-02 9.965814e-01 4.438513e-02 -2.330805e+00 -8.949560e-03 4.511600e-02 -9.989417e-01 4.954641e+01 +-9.977105e-01 6.601210e-02 1.469998e-02 -2.076028e+02 6.654564e-02 9.970062e-01 3.937289e-02 -2.308720e+00 -1.205689e-02 4.026096e-02 -9.991165e-01 4.861090e+01 +-9.975475e-01 6.806905e-02 1.629805e-02 -2.075855e+02 6.865189e-02 9.969027e-01 3.836492e-02 -2.282299e+00 -1.363610e-02 3.938972e-02 -9.991309e-01 4.766944e+01 +-9.975264e-01 6.812217e-02 1.733652e-02 -2.075709e+02 6.880670e-02 9.967224e-01 4.254532e-02 -2.263682e+00 -1.438142e-02 4.363294e-02 -9.989441e-01 4.673040e+01 +-9.975396e-01 6.812516e-02 1.654754e-02 -2.075531e+02 6.880203e-02 9.966364e-01 4.452124e-02 -2.241866e+00 -1.345886e-02 4.555020e-02 -9.988714e-01 4.579047e+01 +-9.972290e-01 7.258953e-02 1.628481e-02 -2.075424e+02 7.325676e-02 9.962968e-01 4.501264e-02 -2.221425e+00 -1.295706e-02 4.608087e-02 -9.988537e-01 4.486668e+01 +-9.969752e-01 7.602008e-02 1.617014e-02 -2.075289e+02 7.663609e-02 9.961875e-01 4.168172e-02 -2.208445e+00 -1.293985e-02 4.279485e-02 -9.990001e-01 4.395152e+01 +-9.968341e-01 7.791418e-02 1.584794e-02 -2.075160e+02 7.847422e-02 9.961735e-01 3.847297e-02 -2.194919e+00 -1.278971e-02 3.959482e-02 -9.991340e-01 4.303924e+01 +-9.965055e-01 8.206418e-02 1.556638e-02 -2.075027e+02 8.261614e-02 9.958201e-01 3.894568e-02 -2.181102e+00 -1.230527e-02 4.009562e-02 -9.991201e-01 4.212539e+01 +-9.964840e-01 8.227685e-02 1.581912e-02 -2.074849e+02 8.292634e-02 9.954896e-01 4.608269e-02 -2.167105e+00 -1.195623e-02 4.723247e-02 -9.988124e-01 4.120790e+01 +-9.969550e-01 7.653629e-02 1.493409e-02 -2.074595e+02 7.725100e-02 9.954780e-01 5.527958e-02 -2.145786e+00 -1.063567e-02 5.626491e-02 -9.983592e-01 4.029232e+01 +-9.973266e-01 7.193759e-02 1.282856e-02 -2.074351e+02 7.259439e-02 9.954630e-01 6.151003e-02 -2.119224e+00 -8.345476e-03 6.227687e-02 -9.980240e-01 3.938305e+01 +-9.975539e-01 6.919570e-02 9.909089e-03 -2.074193e+02 6.968467e-02 9.955753e-01 6.303823e-02 -2.091716e+00 -5.503271e-03 6.357453e-02 -9.979619e-01 3.848386e+01 +-9.974196e-01 7.145316e-02 6.968912e-03 -2.074096e+02 7.173520e-02 9.957889e-01 5.708346e-02 -2.062944e+00 -2.860772e-03 5.743607e-02 -9.983451e-01 3.759959e+01 +-9.972943e-01 7.332158e-02 5.303118e-03 -2.074064e+02 7.349238e-02 9.961291e-01 4.822482e-02 -2.037832e+00 -1.746670e-03 4.848407e-02 -9.988224e-01 3.672689e+01 +-9.973245e-01 7.295017e-02 4.697232e-03 -2.073983e+02 7.308794e-02 9.963088e-01 4.502160e-02 -2.015469e+00 -1.395561e-03 4.524445e-02 -9.989750e-01 3.585908e+01 +-9.970611e-01 7.645109e-02 4.940488e-03 -2.073980e+02 7.659846e-02 9.959754e-01 4.653571e-02 -1.996553e+00 -1.362899e-03 4.677737e-02 -9.989044e-01 3.499904e+01 +-9.969630e-01 7.766187e-02 5.787762e-03 -2.073954e+02 7.784843e-02 9.958598e-01 4.693487e-02 -1.982120e+00 -2.118750e-03 4.724289e-02 -9.988812e-01 3.415212e+01 +-9.970125e-01 7.702898e-02 5.710894e-03 -2.073896e+02 7.720891e-02 9.959897e-01 4.520294e-02 -1.964660e+00 -2.206056e-03 4.550882e-02 -9.989615e-01 3.332353e+01 +-9.966690e-01 8.131468e-02 6.237328e-03 -2.073892e+02 8.151527e-02 9.956269e-01 4.563313e-02 -1.946729e+00 -2.499408e-03 4.598955e-02 -9.989388e-01 3.250912e+01 +-9.964463e-01 8.389263e-02 7.536729e-03 -2.073903e+02 8.416084e-02 9.952671e-01 4.858286e-02 -1.931831e+00 -3.425315e-03 4.904450e-02 -9.987907e-01 3.171130e+01 +-9.965446e-01 8.257389e-02 8.962643e-03 -2.073836e+02 8.293916e-02 9.950895e-01 5.401740e-02 -1.915779e+00 -4.458206e-03 5.457410e-02 -9.984998e-01 3.092886e+01 +-9.966112e-01 8.162620e-02 1.016520e-02 -2.073749e+02 8.207251e-02 9.950232e-01 5.650610e-02 -1.898462e+00 -5.502233e-03 5.714889e-02 -9.983505e-01 3.017125e+01 +-9.965080e-01 8.267783e-02 1.166998e-02 -2.073712e+02 8.320083e-02 9.949917e-01 5.539930e-02 -1.883860e+00 -7.031237e-03 5.617679e-02 -9.983961e-01 2.944096e+01 +-9.963844e-01 8.405570e-02 1.235759e-02 -2.073657e+02 8.457239e-02 9.951641e-01 4.995884e-02 -1.869989e+00 -8.098510e-03 5.082332e-02 -9.986748e-01 2.873795e+01 +-9.964108e-01 8.373046e-02 1.243701e-02 -2.073577e+02 8.421103e-02 9.954252e-01 4.513514e-02 -1.855335e+00 -8.600926e-03 4.602047e-02 -9.989035e-01 2.806111e+01 +-9.965203e-01 8.222667e-02 1.363779e-02 -2.073475e+02 8.274019e-02 9.956540e-01 4.274397e-02 -1.843859e+00 -1.006383e-02 4.372363e-02 -9.989930e-01 2.740888e+01 +-9.964905e-01 8.210106e-02 1.631520e-02 -2.073382e+02 8.275484e-02 9.955741e-01 4.454098e-02 -1.837106e+00 -1.258613e-02 4.573481e-02 -9.988743e-01 2.678015e+01 +-9.964308e-01 8.191997e-02 2.036758e-02 -2.073261e+02 8.281006e-02 9.954292e-01 4.757237e-02 -1.831290e+00 -1.637735e-02 4.908921e-02 -9.986601e-01 2.617982e+01 +-9.962502e-01 8.264674e-02 2.559443e-02 -2.073026e+02 8.385255e-02 9.952078e-01 5.030020e-02 -1.819937e+00 -2.131463e-02 5.225773e-02 -9.984061e-01 2.560799e+01 +-9.962231e-01 8.113822e-02 3.092182e-02 -2.072722e+02 8.263016e-02 9.953006e-01 5.048620e-02 -1.810771e+00 -2.668015e-02 5.285058e-02 -9.982460e-01 2.507616e+01 +-9.962462e-01 7.856476e-02 3.634639e-02 -2.072438e+02 8.035254e-02 9.954782e-01 5.066211e-02 -1.803794e+00 -3.220178e-02 5.339246e-02 -9.980543e-01 2.456677e+01 +-9.961430e-01 7.693460e-02 4.219140e-02 -2.072128e+02 7.905428e-02 9.955592e-01 5.110985e-02 -1.795948e+00 -3.807193e-02 5.424812e-02 -9.978014e-01 2.408967e+01 +-9.958975e-01 7.665953e-02 4.807847e-02 -2.071849e+02 7.906915e-02 9.955945e-01 5.039551e-02 -1.788253e+00 -4.400337e-02 5.399027e-02 -9.975714e-01 2.363786e+01 +-9.955458e-01 7.689551e-02 5.454868e-02 -2.071546e+02 7.954283e-02 9.956682e-01 4.814205e-02 -1.778943e+00 -5.061048e-02 5.226657e-02 -9.973499e-01 2.320868e+01 +-9.952316e-01 7.562852e-02 6.159900e-02 -2.071206e+02 7.853904e-02 9.958361e-01 4.628151e-02 -1.772352e+00 -5.784231e-02 5.089874e-02 -9.970274e-01 2.280002e+01 +-9.949072e-01 7.322790e-02 6.926295e-02 -2.070807e+02 7.653953e-02 9.959849e-01 4.642906e-02 -1.775259e+00 -6.558496e-02 5.149395e-02 -9.965174e-01 2.240705e+01 +-9.944080e-01 7.110418e-02 7.808284e-02 -2.070397e+02 7.483277e-02 9.961388e-01 4.590828e-02 -1.779084e+00 -7.451708e-02 5.149471e-02 -9.958893e-01 2.203420e+01 +-9.936312e-01 7.093260e-02 8.755404e-02 -2.069986e+02 7.499181e-02 9.962141e-01 4.397431e-02 -1.781879e+00 -8.410336e-02 5.026008e-02 -9.951887e-01 2.167450e+01 +-9.926904e-01 7.106473e-02 9.754779e-02 -2.069543e+02 7.542622e-02 9.962760e-01 4.177207e-02 -1.784658e+00 -9.421601e-02 4.882439e-02 -9.943538e-01 2.132257e+01 +-9.916610e-01 6.972016e-02 1.083864e-01 -2.069059e+02 7.434735e-02 9.964597e-01 3.924860e-02 -1.787212e+00 -1.052663e-01 4.697955e-02 -9.933338e-01 2.098322e+01 +-9.905432e-01 6.723822e-02 1.195962e-01 -2.068517e+02 7.201491e-02 9.967510e-01 3.607211e-02 -1.792573e+00 -1.167822e-01 4.434369e-02 -9.921671e-01 2.065380e+01 +-9.891428e-01 6.569270e-02 1.314571e-01 -2.067816e+02 7.049120e-02 9.969931e-01 3.218293e-02 -1.806421e+00 -1.289477e-01 4.110008e-02 -9.907993e-01 2.033440e+01 +-9.874620e-01 6.408714e-02 1.442626e-01 -2.067057e+02 6.892039e-02 9.972077e-01 2.875347e-02 -1.820864e+00 -1.420171e-01 3.833559e-02 -9.891216e-01 2.002604e+01 +-9.854164e-01 6.271395e-02 1.581820e-01 -2.066320e+02 6.772378e-02 9.973527e-01 2.647695e-02 -1.829014e+00 -1.561028e-01 3.680350e-02 -9.870549e-01 1.972503e+01 +-9.829642e-01 6.129138e-02 1.732764e-01 -2.065517e+02 6.675345e-02 9.974341e-01 2.586680e-02 -1.837220e+00 -1.712464e-01 3.699293e-02 -9.845335e-01 1.943671e+01 +-9.799061e-01 6.022245e-02 1.901507e-01 -2.064721e+02 6.619355e-02 9.974884e-01 2.520236e-02 -1.841492e+00 -1.881554e-01 3.728269e-02 -9.814314e-01 1.915364e+01 +-9.759505e-01 6.029131e-02 2.094887e-01 -2.063855e+02 6.691550e-02 9.974535e-01 2.467156e-02 -1.848095e+00 -2.074678e-01 3.809626e-02 -9.774998e-01 1.888093e+01 +-9.710300e-01 6.009873e-02 2.312766e-01 -2.062947e+02 6.763965e-02 9.974013e-01 2.480819e-02 -1.854363e+00 -2.291847e-01 3.973296e-02 -9.725717e-01 1.861492e+01 +-9.651218e-01 5.735838e-02 2.554409e-01 -2.061897e+02 6.611289e-02 9.974782e-01 2.581122e-02 -1.864016e+00 -2.533162e-01 4.179889e-02 -9.664801e-01 1.834605e+01 +-9.581955e-01 5.227720e-02 2.812979e-01 -2.060776e+02 6.250607e-02 9.976654e-01 2.750773e-02 -1.872623e+00 -2.792031e-01 4.394060e-02 -9.592262e-01 1.809535e+01 +-9.504102e-01 4.662109e-02 3.074847e-01 -2.059594e+02 5.834504e-02 9.978739e-01 2.904123e-02 -1.881775e+00 -3.054771e-01 4.554128e-02 -9.511098e-01 1.785230e+01 +-9.418160e-01 4.242720e-02 3.334405e-01 -2.058373e+02 5.589314e-02 9.979587e-01 3.089139e-02 -1.888791e+00 -3.314493e-01 4.773104e-02 -9.422649e-01 1.760507e+01 +-9.322045e-01 4.029987e-02 3.596813e-01 -2.057241e+02 5.550058e-02 9.979447e-01 3.203068e-02 -1.886547e+00 -3.576512e-01 4.982166e-02 -9.325253e-01 1.737708e+01 +-9.214453e-01 3.799765e-02 3.866456e-01 -2.056017e+02 5.455391e-02 9.980001e-01 3.193306e-02 -1.882446e+00 -3.846589e-01 5.051759e-02 -9.216754e-01 1.714784e+01 +-9.096132e-01 3.677145e-02 4.138256e-01 -2.054746e+02 5.420871e-02 9.980646e-01 3.046853e-02 -1.878176e+00 -4.119044e-01 5.014752e-02 -9.098462e-01 1.693896e+01 +-8.964158e-01 3.703447e-02 4.416640e-01 -2.053360e+02 5.493166e-02 9.981031e-01 2.779800e-02 -1.864324e+00 -4.397968e-01 4.917990e-02 -8.967498e-01 1.672641e+01 +-8.821260e-01 3.696879e-02 4.695605e-01 -2.051832e+02 5.501588e-02 9.981782e-01 2.476672e-02 -1.856435e+00 -4.677896e-01 4.768064e-02 -8.825528e-01 1.649957e+01 +-8.665693e-01 3.535600e-02 4.978027e-01 -2.050180e+02 5.290831e-02 9.983744e-01 2.119349e-02 -1.846667e+00 -4.962442e-01 4.470352e-02 -8.670313e-01 1.628630e+01 +-8.492641e-01 3.345249e-02 5.269074e-01 -2.048382e+02 5.053641e-02 9.985589e-01 1.805717e-02 -1.842211e+00 -5.255441e-01 4.196330e-02 -8.497309e-01 1.607054e+01 +-8.302451e-01 3.236056e-02 5.564583e-01 -2.046402e+02 4.880300e-02 9.986997e-01 1.473598e-02 -1.838079e+00 -5.552579e-01 3.939130e-02 -8.307449e-01 1.583434e+01 +-8.092335e-01 3.467875e-02 5.864628e-01 -2.044342e+02 5.068572e-02 9.986553e-01 1.088637e-02 -1.838157e+00 -5.852967e-01 3.853490e-02 -8.099030e-01 1.560857e+01 +-7.863277e-01 3.775871e-02 6.166547e-01 -2.042080e+02 5.305670e-02 9.985702e-01 6.511276e-03 -1.837902e+00 -6.155272e-01 3.783765e-02 -7.872068e-01 1.536015e+01 +-7.621900e-01 3.888292e-02 6.461846e-01 -2.039620e+02 5.381263e-02 9.985453e-01 3.387690e-03 -1.840360e+00 -6.451129e-01 3.735495e-02 -7.631736e-01 1.512639e+01 +-7.362048e-01 4.113059e-02 6.755077e-01 -2.036991e+02 5.664865e-02 9.983937e-01 9.481394e-04 -1.840696e+00 -6.743837e-01 3.896462e-02 -7.373523e-01 1.488938e+01 +-7.078564e-01 4.247915e-02 7.050779e-01 -2.034067e+02 5.762419e-02 9.983357e-01 -2.295941e-03 -1.838885e+00 -7.040020e-01 3.900434e-02 -7.091262e-01 1.463242e+01 +-6.780828e-01 4.301537e-02 7.337257e-01 -2.031059e+02 5.737684e-02 9.983374e-01 -5.502900e-03 -1.842361e+00 -7.327425e-01 3.836743e-02 -6.794235e-01 1.440230e+01 +-6.474899e-01 4.057830e-02 7.609929e-01 -2.027871e+02 5.376412e-02 9.985255e-01 -7.499088e-03 -1.849029e+00 -7.601752e-01 3.605852e-02 -6.487169e-01 1.418060e+01 +-6.150975e-01 3.824904e-02 7.875227e-01 -2.024453e+02 5.217471e-02 9.986079e-01 -7.749961e-03 -1.859298e+00 -7.867229e-01 3.632178e-02 -6.162369e-01 1.393935e+01 +-5.815098e-01 3.621569e-02 8.127329e-01 -2.020933e+02 5.263900e-02 9.985902e-01 -6.834410e-03 -1.877355e+00 -8.118347e-01 3.880716e-02 -5.825963e-01 1.372377e+01 +-5.477189e-01 3.699515e-02 8.358441e-01 -2.017130e+02 5.437256e-02 9.984840e-01 -8.564031e-03 -1.895950e+00 -8.348938e-01 4.075630e-02 -5.489001e-01 1.348742e+01 +-5.134149e-01 3.626843e-02 8.573737e-01 -2.013173e+02 5.533247e-02 9.984265e-01 -9.100886e-03 -1.917624e+00 -8.563548e-01 4.276807e-02 -5.146139e-01 1.327834e+01 +-4.802771e-01 3.444276e-02 8.764403e-01 -2.008907e+02 5.536794e-02 9.984264e-01 -8.895779e-03 -1.935471e+00 -8.753676e-01 4.425425e-02 -4.814284e-01 1.307285e+01 +-4.485431e-01 3.312582e-02 8.931471e-01 -2.004376e+02 5.666142e-02 9.983566e-01 -8.572283e-03 -1.952751e+00 -8.919634e-01 4.676194e-02 -4.496829e-01 1.285479e+01 +-4.201570e-01 3.269851e-02 9.068621e-01 -1.999639e+02 5.779760e-02 9.982858e-01 -9.216845e-03 -1.969966e+00 -9.056090e-01 4.854192e-02 -4.213267e-01 1.265530e+01 +-3.955751e-01 3.216292e-02 9.178703e-01 -1.994549e+02 5.825085e-02 9.982531e-01 -9.875211e-03 -1.987806e+00 -9.165846e-01 4.956033e-02 -3.967576e-01 1.245112e+01 +-3.750341e-01 3.150452e-02 9.264755e-01 -1.989220e+02 5.766966e-02 9.982794e-01 -1.060172e-02 -2.007051e+00 -9.252155e-01 4.945351e-02 -3.762057e-01 1.225462e+01 +-3.574478e-01 3.185925e-02 9.333895e-01 -1.983701e+02 5.938092e-02 9.981711e-01 -1.133012e-02 -2.026131e+00 -9.320435e-01 5.137559e-02 -3.586859e-01 1.205553e+01 +-3.413952e-01 3.341674e-02 9.393256e-01 -1.978030e+02 6.416184e-02 9.978652e-01 -1.217988e-02 -2.041867e+00 -9.377274e-01 5.611070e-02 -3.428105e-01 1.184790e+01 +-3.242657e-01 3.535484e-02 9.453051e-01 -1.972185e+02 7.165987e-02 9.973480e-01 -1.271997e-02 -2.054299e+00 -9.432480e-01 6.361578e-02 -3.259392e-01 1.164260e+01 +-3.048359e-01 3.460317e-02 9.517760e-01 -1.966108e+02 7.742775e-02 9.969322e-01 -1.144625e-02 -2.072851e+00 -9.492524e-01 7.020464e-02 -3.065800e-01 1.143755e+01 +-2.832148e-01 3.157816e-02 9.585365e-01 -1.959858e+02 8.266256e-02 9.965421e-01 -8.406269e-03 -2.097242e+00 -9.554875e-01 7.685428e-02 -2.848459e-01 1.125123e+01 +-2.587189e-01 2.789042e-02 9.655499e-01 -1.953525e+02 8.708753e-02 9.961858e-01 -5.440283e-03 -2.122286e+00 -9.620189e-01 8.267984e-02 -2.601610e-01 1.108274e+01 +-2.318337e-01 2.380714e-02 9.724641e-01 -1.947136e+02 9.048474e-02 9.958939e-01 -2.809337e-03 -2.144291e+00 -9.685379e-01 8.734184e-02 -2.330359e-01 1.092402e+01 +-2.042980e-01 1.974298e-02 9.787096e-01 -1.940783e+02 9.310874e-02 9.956557e-01 -6.491157e-04 -2.165831e+00 -9.744707e-01 9.099379e-02 -2.052487e-01 1.079980e+01 +-1.765049e-01 1.694729e-02 9.841538e-01 -1.934505e+02 9.401725e-02 9.955705e-01 -2.821979e-04 -2.187458e+00 -9.797994e-01 9.247761e-02 -1.773164e-01 1.068836e+01 +-1.492142e-01 1.452770e-02 9.886982e-01 -1.928391e+02 9.354587e-02 9.956148e-01 -5.114112e-04 -2.211490e+00 -9.843700e-01 9.241230e-02 -1.499189e-01 1.060912e+01 +-1.229855e-01 1.399234e-02 9.923098e-01 -1.922415e+02 9.232534e-02 9.957255e-01 -2.597841e-03 -2.235677e+00 -9.881046e-01 9.129583e-02 -1.237516e-01 1.055003e+01 +-9.688339e-02 1.598398e-02 9.951674e-01 -1.916592e+02 8.995691e-02 9.959193e-01 -7.238415e-03 -2.246557e+00 -9.912222e-01 8.882088e-02 -9.792592e-02 1.051016e+01 +-7.243934e-02 1.815919e-02 9.972075e-01 -1.910853e+02 8.668400e-02 9.961654e-01 -1.184331e-02 -2.253431e+00 -9.935988e-01 8.558400e-02 -7.373568e-02 1.049974e+01 +-5.079777e-02 2.066076e-02 9.984952e-01 -1.905116e+02 8.468348e-02 9.962744e-01 -1.630660e-02 -2.259943e+00 -9.951122e-01 8.372770e-02 -5.235815e-02 1.049251e+01 +-3.335336e-02 2.282409e-02 9.991830e-01 -1.899317e+02 8.139566e-02 9.964802e-01 -2.004532e-02 -2.275344e+00 -9.961237e-01 8.066056e-02 -3.509375e-02 1.049487e+01 +-2.013306e-02 2.336403e-02 9.995243e-01 -1.893487e+02 7.657071e-02 9.968267e-01 -2.175865e-02 -2.292255e+00 -9.968609e-01 7.609620e-02 -2.185818e-02 1.050316e+01 +-1.005429e-02 2.334214e-02 9.996770e-01 -1.887745e+02 7.187303e-02 9.971586e-01 -2.256047e-02 -2.302178e+00 -9.973631e-01 7.162297e-02 -1.170340e-02 1.051475e+01 +-2.110358e-03 2.295537e-02 9.997342e-01 -1.881995e+02 6.974735e-02 9.973052e-01 -2.275237e-02 -2.316402e+00 -9.975625e-01 6.968078e-02 -3.705749e-03 1.051892e+01 +5.909011e-03 2.135154e-02 9.997546e-01 -1.876284e+02 7.022286e-02 9.972949e-01 -2.171407e-02 -2.331230e+00 -9.975139e-01 7.033391e-02 4.393659e-03 1.052160e+01 +1.437368e-02 1.907006e-02 9.997148e-01 -1.870530e+02 6.959313e-02 9.973744e-01 -2.002602e-02 -2.350517e+00 -9.974719e-01 6.986111e-02 1.300880e-02 1.053079e+01 +2.249469e-02 1.822524e-02 9.995808e-01 -1.864801e+02 6.964692e-02 9.973761e-01 -1.975239e-02 -2.367677e+00 -9.973181e-01 7.006204e-02 2.116633e-02 1.054310e+01 +3.083229e-02 1.960328e-02 9.993323e-01 -1.859026e+02 6.932201e-02 9.973582e-01 -2.170335e-02 -2.386788e+00 -9.971178e-01 6.994487e-02 2.939189e-02 1.056339e+01 +3.798385e-02 2.121806e-02 9.990530e-01 -1.853161e+02 6.792202e-02 9.974075e-01 -2.376551e-02 -2.404640e+00 -9.969673e-01 6.876039e-02 3.644420e-02 1.058979e+01 +4.309615e-02 2.340065e-02 9.987968e-01 -1.847156e+02 6.600232e-02 9.974750e-01 -2.621756e-02 -2.427699e+00 -9.968884e-01 6.705277e-02 4.144284e-02 1.061701e+01 +4.629755e-02 2.538985e-02 9.986050e-01 -1.841051e+02 6.527452e-02 9.974635e-01 -2.838711e-02 -2.449229e+00 -9.967928e-01 6.649770e-02 4.452281e-02 1.064505e+01 +4.975463e-02 2.632264e-02 9.984145e-01 -1.834772e+02 6.524795e-02 9.974315e-01 -2.954828e-02 -2.474192e+00 -9.966279e-01 6.661465e-02 4.790934e-02 1.067254e+01 +5.288962e-02 2.637143e-02 9.982521e-01 -1.828392e+02 6.698487e-02 9.973060e-01 -2.989545e-02 -2.497217e+00 -9.963512e-01 6.844893e-02 5.098065e-02 1.069995e+01 +5.593670e-02 2.562074e-02 9.981055e-01 -1.821847e+02 6.758638e-02 9.972805e-01 -2.938731e-02 -2.524417e+00 -9.961442e-01 6.910215e-02 5.405297e-02 1.073143e+01 +5.912722e-02 2.438844e-02 9.979525e-01 -1.815183e+02 6.593329e-02 9.974231e-01 -2.828196e-02 -2.553520e+00 -9.960707e-01 6.747051e-02 5.736685e-02 1.076840e+01 +6.253954e-02 2.372931e-02 9.977603e-01 -1.808354e+02 6.516915e-02 9.974867e-01 -2.780761e-02 -2.584249e+00 -9.959126e-01 6.676226e-02 6.083594e-02 1.080835e+01 +6.608964e-02 2.364041e-02 9.975336e-01 -1.801412e+02 6.548557e-02 9.974612e-01 -2.797732e-02 -2.613019e+00 -9.956625e-01 6.717305e-02 6.437375e-02 1.084862e+01 +6.966898e-02 2.376985e-02 9.972869e-01 -1.794335e+02 6.419619e-02 9.975370e-01 -2.826047e-02 -2.641480e+00 -9.955025e-01 6.599088e-02 6.797146e-02 1.089552e+01 +7.326704e-02 2.439920e-02 9.970138e-01 -1.787133e+02 6.295999e-02 9.975934e-01 -2.904010e-02 -2.672769e+00 -9.953231e-01 6.489965e-02 7.155454e-02 1.094556e+01 +7.646811e-02 2.554911e-02 9.967446e-01 -1.779807e+02 6.235390e-02 9.975924e-01 -3.035450e-02 -2.704797e+00 -9.951204e-01 6.447205e-02 7.469092e-02 1.099727e+01 +7.874216e-02 2.828721e-02 9.964936e-01 -1.772348e+02 5.993530e-02 9.976547e-01 -3.305622e-02 -2.739889e+00 -9.950917e-01 6.232805e-02 7.686209e-02 1.105301e+01 +7.909601e-02 3.339353e-02 9.963075e-01 -1.764772e+02 5.617822e-02 9.977011e-01 -3.790019e-02 -2.778843e+00 -9.952828e-01 5.896852e-02 7.703819e-02 1.111330e+01 +7.870622e-02 3.613375e-02 9.962428e-01 -1.757037e+02 5.514062e-02 9.976552e-01 -4.054127e-02 -2.817521e+00 -9.953717e-01 5.812428e-02 7.652924e-02 1.117159e+01 +7.853027e-02 3.576845e-02 9.962698e-01 -1.749129e+02 5.543758e-02 9.976530e-01 -4.018795e-02 -2.854098e+00 -9.953691e-01 5.838674e-02 7.636304e-02 1.122801e+01 +7.793650e-02 3.278092e-02 9.964192e-01 -1.741034e+02 5.625736e-02 9.977221e-01 -3.722406e-02 -2.896147e+00 -9.953698e-01 5.895701e-02 7.591480e-02 1.128387e+01 +7.836846e-02 2.973147e-02 9.964810e-01 -1.732815e+02 5.502696e-02 9.979023e-01 -3.410149e-02 -2.940039e+00 -9.954047e-01 5.750579e-02 7.656803e-02 1.134403e+01 +8.039215e-02 3.220042e-02 9.962430e-01 -1.724538e+02 5.605202e-02 9.977504e-01 -3.677228e-02 -2.982458e+00 -9.951861e-01 5.879762e-02 7.840640e-02 1.140650e+01 +8.356404e-02 3.419054e-02 9.959157e-01 -1.716152e+02 5.652930e-02 9.976392e-01 -3.899291e-02 -3.025174e+00 -9.948978e-01 5.955680e-02 8.143400e-02 1.147915e+01 +8.736426e-02 3.305113e-02 9.956280e-01 -1.707548e+02 5.712817e-02 9.976384e-01 -3.813075e-02 -3.068790e+00 -9.945370e-01 6.020966e-02 8.526979e-02 1.155411e+01 +9.166349e-02 2.802993e-02 9.953954e-01 -1.698776e+02 5.869631e-02 9.977136e-01 -3.350041e-02 -3.113199e+00 -9.940587e-01 6.149679e-02 8.980865e-02 1.163318e+01 +9.688420e-02 2.551771e-02 9.949685e-01 -1.689882e+02 5.885392e-02 9.977751e-01 -3.132055e-02 -3.160594e+00 -9.935541e-01 6.159225e-02 9.516683e-02 1.171804e+01 +1.024238e-01 2.493301e-02 9.944283e-01 -1.680883e+02 6.138111e-02 9.976224e-01 -3.133521e-02 -3.204265e+00 -9.928453e-01 6.424857e-02 1.006499e-01 1.180701e+01 +1.086792e-01 2.823782e-02 9.936757e-01 -1.671726e+02 6.251986e-02 9.974234e-01 -3.518219e-02 -3.247393e+00 -9.921089e-01 6.594802e-02 1.066338e-01 1.190348e+01 +1.132838e-01 3.170230e-02 9.930568e-01 -1.662475e+02 6.150628e-02 9.973501e-01 -3.885575e-02 -3.295985e+00 -9.916571e-01 6.548094e-02 1.110337e-01 1.200864e+01 +1.167775e-01 3.595700e-02 9.925070e-01 -1.653096e+02 5.892197e-02 9.973332e-01 -4.306457e-02 -3.346744e+00 -9.914087e-01 6.350943e-02 1.143475e-01 1.212125e+01 +1.179914e-01 3.790261e-02 9.922910e-01 -1.643561e+02 5.254077e-02 9.976333e-01 -4.435420e-02 -3.399826e+00 -9.916237e-01 5.736913e-02 1.157207e-01 1.224191e+01 +1.180593e-01 3.636158e-02 9.923406e-01 -1.633867e+02 4.645926e-02 9.980327e-01 -4.209745e-02 -3.457840e+00 -9.919192e-01 5.107339e-02 1.161377e-01 1.236462e+01 +1.175405e-01 3.610615e-02 9.924115e-01 -1.624058e+02 4.186418e-02 9.982703e-01 -4.127768e-02 -3.516845e+00 -9.921853e-01 4.639828e-02 1.158256e-01 1.248444e+01 +1.163971e-01 3.700606e-02 9.925131e-01 -1.614142e+02 3.716923e-02 9.984433e-01 -4.158620e-02 -3.576617e+00 -9.925070e-01 4.173145e-02 1.148404e-01 1.260527e+01 +1.151948e-01 3.943651e-02 9.925598e-01 -1.604139e+02 3.500209e-02 9.984299e-01 -4.373204e-02 -3.635493e+00 -9.927261e-01 3.977936e-02 1.136336e-01 1.272144e+01 +1.134105e-01 3.763915e-02 9.928350e-01 -1.594000e+02 3.066548e-02 9.986734e-01 -4.136339e-02 -3.693860e+00 -9.930749e-01 3.513680e-02 1.121059e-01 1.284084e+01 +1.102791e-01 3.194307e-02 9.933872e-01 -1.583751e+02 2.678612e-02 9.990248e-01 -3.509797e-02 -3.752071e+00 -9.935397e-01 3.047955e-02 1.093159e-01 1.295756e+01 +1.059147e-01 2.643147e-02 9.940239e-01 -1.573446e+02 2.326118e-02 9.993072e-01 -2.905048e-02 -3.809571e+00 -9.941031e-01 2.619903e-02 1.052265e-01 1.306983e+01 +1.001014e-01 2.814042e-02 9.945792e-01 -1.563146e+02 2.254797e-02 9.992791e-01 -3.054279e-02 -3.861033e+00 -9.947218e-01 2.548311e-02 9.939472e-02 1.317205e+01 +9.277385e-02 3.158214e-02 9.951862e-01 -1.552890e+02 2.125589e-02 9.992062e-01 -3.369125e-02 -3.913038e+00 -9.954603e-01 2.427923e-02 9.202890e-02 1.326640e+01 +8.308037e-02 3.368524e-02 9.959734e-01 -1.542515e+02 1.989946e-02 9.991732e-01 -3.545341e-02 -3.969279e+00 -9.963442e-01 2.276480e-02 8.234136e-02 1.335128e+01 +7.106907e-02 3.254643e-02 9.969403e-01 -1.532059e+02 2.214555e-02 9.991697e-01 -3.419792e-02 -4.024514e+00 -9.972256e-01 2.450820e-02 7.028930e-02 1.341878e+01 +5.716637e-02 2.828640e-02 9.979639e-01 -1.521535e+02 1.988849e-02 9.993679e-01 -2.946548e-02 -4.080902e+00 -9.981666e-01 2.153242e-02 5.656766e-02 1.347719e+01 +4.268305e-02 2.517985e-02 9.987713e-01 -1.510988e+02 2.176237e-02 9.994217e-01 -2.612628e-02 -4.131797e+00 -9.988517e-01 2.285078e-02 4.211039e-02 1.351698e+01 +2.878398e-02 2.462697e-02 9.992822e-01 -1.500399e+02 2.293712e-02 9.994169e-01 -2.529099e-02 -4.180362e+00 -9.993225e-01 2.364862e-02 2.820232e-02 1.353486e+01 +1.536547e-02 2.748746e-02 9.995040e-01 -1.489789e+02 2.308024e-02 9.993459e-01 -2.783794e-02 -4.225769e+00 -9.996156e-01 2.349653e-02 1.472100e-02 1.353437e+01 +3.568440e-03 3.111907e-02 9.995093e-01 -1.479100e+02 2.483654e-02 9.992046e-01 -3.119826e-02 -4.274146e+00 -9.996852e-01 2.493567e-02 2.792709e-03 1.351674e+01 +-6.554850e-03 3.106744e-02 9.994958e-01 -1.468368e+02 2.917563e-02 9.990977e-01 -3.086374e-02 -4.324230e+00 -9.995528e-01 2.895860e-02 -7.455349e-03 1.348847e+01 +-1.521449e-02 2.976293e-02 9.994412e-01 -1.457562e+02 3.246157e-02 9.990447e-01 -2.925697e-02 -4.376183e+00 -9.993572e-01 3.199829e-02 -1.616611e-02 1.344946e+01 +-2.159452e-02 2.987242e-02 9.993204e-01 -1.446773e+02 3.661210e-02 9.989067e-01 -2.906890e-02 -4.427108e+00 -9.990962e-01 3.595948e-02 -2.266460e-02 1.340696e+01 +-2.469622e-02 3.112016e-02 9.992105e-01 -1.435934e+02 4.022197e-02 9.987369e-01 -3.011131e-02 -4.477432e+00 -9.988856e-01 3.944656e-02 -2.591675e-02 1.335993e+01 +-2.566669e-02 3.107307e-02 9.991875e-01 -1.425133e+02 4.266125e-02 9.986403e-01 -2.996020e-02 -4.530348e+00 -9.987599e-01 4.185760e-02 -2.695741e-02 1.332396e+01 +-2.434920e-02 2.884210e-02 9.992874e-01 -1.414274e+02 4.448679e-02 9.986248e-01 -2.773900e-02 -4.583118e+00 -9.987132e-01 4.377966e-02 -2.559881e-02 1.329109e+01 +-2.159792e-02 2.775561e-02 9.993814e-01 -1.403252e+02 4.556507e-02 9.986032e-01 -2.674928e-02 -4.639017e+00 -9.987279e-01 4.495914e-02 -2.283244e-02 1.327588e+01 +-1.828249e-02 2.895108e-02 9.994136e-01 -1.392192e+02 4.751251e-02 9.984766e-01 -2.805479e-02 -4.693787e+00 -9.987033e-01 4.697173e-02 -1.963018e-02 1.326409e+01 +-1.471415e-02 3.009756e-02 9.994386e-01 -1.381087e+02 4.901621e-02 9.983668e-01 -2.934365e-02 -4.747381e+00 -9.986896e-01 4.855691e-02 -1.616539e-02 1.325115e+01 +-1.105058e-02 2.918574e-02 9.995129e-01 -1.369892e+02 5.181826e-02 9.982476e-01 -2.857590e-02 -4.801527e+00 -9.985954e-01 5.147723e-02 -1.254358e-02 1.323905e+01 +-7.122768e-03 2.874658e-02 9.995613e-01 -1.358716e+02 5.358494e-02 9.981615e-01 -2.832449e-02 -4.857988e+00 -9.985379e-01 5.335967e-02 -8.650059e-03 1.323518e+01 +-3.216472e-03 3.077812e-02 9.995211e-01 -1.347486e+02 5.397899e-02 9.980743e-01 -3.055988e-02 -4.913923e+00 -9.985369e-01 5.385483e-02 -4.871653e-03 1.323299e+01 +2.192214e-04 3.028795e-02 9.995412e-01 -1.336182e+02 5.504836e-02 9.980252e-01 -3.025409e-02 -4.968357e+00 -9.984837e-01 5.502973e-02 -1.448515e-03 1.323490e+01 +2.441291e-03 2.493081e-02 9.996862e-01 -1.324693e+02 5.520798e-02 9.981611e-01 -2.502760e-02 -5.021919e+00 -9.984719e-01 5.525174e-02 1.060420e-03 1.323795e+01 +3.464575e-03 2.049074e-02 9.997840e-01 -1.313164e+02 5.439070e-02 9.983062e-01 -2.064894e-02 -5.073581e+00 -9.985138e-01 5.445048e-02 2.344199e-03 1.324522e+01 +4.150820e-03 2.090934e-02 9.997727e-01 -1.301600e+02 5.540200e-02 9.982410e-01 -2.110733e-02 -5.121389e+00 -9.984555e-01 5.547701e-02 2.985097e-03 1.324698e+01 +4.461172e-03 2.380049e-02 9.997068e-01 -1.289987e+02 5.683127e-02 9.980949e-01 -2.401573e-02 -5.168884e+00 -9.983739e-01 5.692173e-02 3.100060e-03 1.325022e+01 +4.548535e-03 2.580483e-02 9.996566e-01 -1.278330e+02 5.554685e-02 9.981170e-01 -2.601783e-02 -5.219366e+00 -9.984458e-01 5.564611e-02 3.106591e-03 1.325496e+01 +4.480500e-03 2.648539e-02 9.996391e-01 -1.266487e+02 5.405808e-02 9.981810e-01 -2.668906e-02 -5.271696e+00 -9.985278e-01 5.415814e-02 3.040599e-03 1.325677e+01 +4.453099e-03 2.679524e-02 9.996310e-01 -1.254523e+02 5.031451e-02 9.983688e-01 -2.698555e-02 -5.324664e+00 -9.987235e-01 5.041610e-02 3.097643e-03 1.324797e+01 +4.323084e-03 2.739563e-02 9.996153e-01 -1.242467e+02 4.765161e-02 9.984834e-01 -2.757070e-02 -5.376367e+00 -9.988547e-01 4.775246e-02 3.011079e-03 1.323794e+01 +4.057227e-03 2.537549e-02 9.996697e-01 -1.230362e+02 4.530968e-02 9.986466e-01 -2.553342e-02 -5.429004e+00 -9.989648e-01 4.539830e-02 2.901978e-03 1.323114e+01 +3.949615e-03 2.268840e-02 9.997348e-01 -1.218219e+02 4.405711e-02 9.987679e-01 -2.284052e-02 -5.480908e+00 -9.990212e-01 4.413563e-02 2.945161e-03 1.322423e+01 +3.955770e-03 2.277116e-02 9.997329e-01 -1.205957e+02 4.392796e-02 9.987717e-01 -2.292309e-02 -5.531590e+00 -9.990269e-01 4.400689e-02 2.950619e-03 1.321642e+01 +4.280079e-03 2.596355e-02 9.996537e-01 -1.193735e+02 4.710059e-02 9.985481e-01 -2.613651e-02 -5.583086e+00 -9.988810e-01 4.719613e-02 3.050964e-03 1.320592e+01 +4.763977e-03 2.914405e-02 9.995639e-01 -1.181428e+02 4.810727e-02 9.984111e-01 -2.933973e-02 -5.637661e+00 -9.988308e-01 4.822605e-02 3.354366e-03 1.319706e+01 +5.359974e-03 3.221262e-02 9.994667e-01 -1.169019e+02 4.942649e-02 9.982508e-01 -3.243851e-02 -5.697801e+00 -9.987634e-01 4.957399e-02 3.758440e-03 1.319315e+01 +5.944674e-03 3.134995e-02 9.994908e-01 -1.156327e+02 5.188363e-02 9.981525e-01 -3.161657e-02 -5.763103e+00 -9.986355e-01 5.204514e-02 4.307141e-03 1.319466e+01 +6.192555e-03 2.704459e-02 9.996150e-01 -1.143662e+02 5.330713e-02 9.982039e-01 -2.733665e-02 -5.827239e+00 -9.985590e-01 5.345588e-02 4.739761e-03 1.319545e+01 +6.596227e-03 2.533930e-02 9.996571e-01 -1.130921e+02 5.482563e-02 9.981661e-01 -2.566328e-02 -5.889114e+00 -9.984742e-01 5.497610e-02 5.194885e-03 1.319921e+01 +7.377608e-03 2.667922e-02 9.996168e-01 -1.118234e+02 5.856831e-02 9.979164e-01 -2.706611e-02 -5.946678e+00 -9.982562e-01 5.874554e-02 5.799677e-03 1.319848e+01 +7.656263e-03 2.817333e-02 9.995737e-01 -1.105495e+02 5.801522e-02 9.979068e-01 -2.857072e-02 -6.007978e+00 -9.982864e-01 5.820922e-02 6.005752e-03 1.320298e+01 +7.924534e-03 3.054333e-02 9.995020e-01 -1.092802e+02 5.570903e-02 9.979676e-01 -3.093814e-02 -6.072212e+00 -9.984156e-01 5.592645e-02 6.206886e-03 1.321157e+01 +8.384909e-03 3.456337e-02 9.993673e-01 -1.080018e+02 5.205677e-02 9.980322e-01 -3.495397e-02 -6.140008e+00 -9.986090e-01 5.231691e-02 6.569150e-03 1.322321e+01 +8.354761e-03 3.238366e-02 9.994406e-01 -1.067211e+02 4.886090e-02 9.982684e-01 -3.275414e-02 -6.208717e+00 -9.987707e-01 4.910721e-02 6.757997e-03 1.323496e+01 +8.561524e-03 2.914732e-02 9.995384e-01 -1.054272e+02 4.470201e-02 9.985646e-01 -2.950182e-02 -6.276254e+00 -9.989637e-01 4.493395e-02 7.246290e-03 1.323235e+01 +9.197205e-03 2.822794e-02 9.995592e-01 -1.041319e+02 4.706557e-02 9.984814e-01 -2.863058e-02 -6.334964e+00 -9.988495e-01 4.730813e-02 7.854672e-03 1.322164e+01 +1.037330e-02 2.579069e-02 9.996135e-01 -1.028562e+02 4.928377e-02 9.984392e-01 -2.627183e-02 -6.390335e+00 -9.987310e-01 4.953724e-02 9.086043e-03 1.323772e+01 +1.200745e-02 2.777345e-02 9.995421e-01 -1.015904e+02 5.080515e-02 9.983061e-01 -2.834944e-02 -6.448719e+00 -9.986364e-01 5.112228e-02 1.057607e-02 1.327011e+01 +1.366600e-02 2.826572e-02 9.995070e-01 -1.003214e+02 5.127892e-02 9.982652e-01 -2.893174e-02 -6.507200e+00 -9.985909e-01 5.164901e-02 1.219285e-02 1.330167e+01 +1.447762e-02 2.784215e-02 9.995075e-01 -9.905197e+01 4.699967e-02 9.984884e-01 -2.849455e-02 -6.570639e+00 -9.987900e-01 4.738905e-02 1.314717e-02 1.334434e+01 +1.535417e-02 2.866905e-02 9.994710e-01 -9.778042e+01 4.380752e-02 9.986097e-01 -2.931734e-02 -6.632546e+00 -9.989220e-01 4.423448e-02 1.407690e-02 1.337805e+01 +1.635930e-02 2.927144e-02 9.994376e-01 -9.651228e+01 4.264810e-02 9.986412e-01 -2.994621e-02 -6.695989e+00 -9.989562e-01 4.311400e-02 1.508870e-02 1.341518e+01 +1.752745e-02 2.554841e-02 9.995199e-01 -9.523756e+01 4.278730e-02 9.987385e-01 -2.627876e-02 -6.758585e+00 -9.989305e-01 4.322735e-02 1.641219e-02 1.344476e+01 +1.926453e-02 2.261836e-02 9.995585e-01 -9.396639e+01 4.629334e-02 9.986516e-01 -2.349006e-02 -6.818429e+00 -9.987421e-01 4.672542e-02 1.819147e-02 1.347163e+01 +2.115223e-02 1.962743e-02 9.995836e-01 -9.269421e+01 4.931701e-02 9.985696e-01 -2.065113e-02 -6.875976e+00 -9.985592e-01 4.973328e-02 2.015400e-02 1.349671e+01 +2.285170e-02 1.760068e-02 9.995839e-01 -9.141964e+01 5.130858e-02 9.985067e-01 -1.875469e-02 -6.930557e+00 -9.984214e-01 5.171579e-02 2.191451e-02 1.353014e+01 +2.440731e-02 1.876712e-02 9.995259e-01 -9.015044e+01 5.160537e-02 9.984671e-01 -2.000739e-02 -6.983028e+00 -9.983693e-01 5.206922e-02 2.340141e-02 1.357623e+01 +2.576091e-02 2.077822e-02 9.994522e-01 -8.888441e+01 5.117544e-02 9.984456e-01 -2.207636e-02 -7.036178e+00 -9.983574e-01 5.171610e-02 2.465753e-02 1.362270e+01 +2.725410e-02 2.186801e-02 9.993893e-01 -8.761907e+01 4.967100e-02 9.984961e-01 -2.320304e-02 -7.091078e+00 -9.983937e-01 5.027303e-02 2.612691e-02 1.367430e+01 +2.855430e-02 1.973726e-02 9.993973e-01 -8.635370e+01 4.922889e-02 9.985640e-01 -2.112735e-02 -7.146039e+00 -9.983793e-01 4.980249e-02 2.754165e-02 1.372119e+01 +3.013472e-02 1.658294e-02 9.994083e-01 -8.508715e+01 4.954436e-02 9.986085e-01 -1.806357e-02 -7.198117e+00 -9.983172e-01 5.005937e-02 2.927120e-02 1.376991e+01 +3.150612e-02 1.555275e-02 9.993825e-01 -8.382540e+01 5.111433e-02 9.985455e-01 -1.715114e-02 -7.250634e+00 -9.981958e-01 5.162312e-02 3.066532e-02 1.381215e+01 +3.301548e-02 1.709496e-02 9.993086e-01 -8.256884e+01 5.243639e-02 9.984470e-01 -1.881264e-02 -7.300937e+00 -9.980784e-01 5.302123e-02 3.206780e-02 1.385905e+01 +3.449094e-02 1.936819e-02 9.992173e-01 -8.130969e+01 5.160662e-02 9.984438e-01 -2.113456e-02 -7.351265e+00 -9.980717e-01 5.229517e-02 3.343774e-02 1.389987e+01 +3.529680e-02 2.119447e-02 9.991521e-01 -8.004503e+01 4.881496e-02 9.985451e-01 -2.290607e-02 -7.402482e+00 -9.981840e-01 4.958207e-02 3.421084e-02 1.394119e+01 +3.525473e-02 2.057874e-02 9.991664e-01 -7.878408e+01 4.691062e-02 9.986518e-01 -2.222335e-02 -7.455565e+00 -9.982768e-01 4.765499e-02 3.424183e-02 1.398441e+01 +3.431590e-02 1.650659e-02 9.992747e-01 -7.751949e+01 4.565133e-02 9.987940e-01 -1.806636e-02 -7.506952e+00 -9.983679e-01 4.623817e-02 3.352097e-02 1.402728e+01 +3.341936e-02 1.459482e-02 9.993348e-01 -7.626292e+01 4.746550e-02 9.987419e-01 -1.617349e-02 -7.556556e+00 -9.983137e-01 4.797442e-02 3.268456e-02 1.406421e+01 +3.331848e-02 1.556335e-02 9.993236e-01 -7.501433e+01 5.043449e-02 9.985787e-01 -1.723329e-02 -7.603671e+00 -9.981715e-01 5.097456e-02 3.248620e-02 1.409744e+01 +3.339415e-02 1.693758e-02 9.992987e-01 -7.376641e+01 5.274690e-02 9.984331e-01 -1.868559e-02 -7.651964e+00 -9.980494e-01 5.333389e-02 3.244841e-02 1.413115e+01 +3.355684e-02 2.024630e-02 9.992317e-01 -7.252723e+01 5.183318e-02 9.984140e-01 -2.197044e-02 -7.704966e+00 -9.980918e-01 5.253060e-02 3.245418e-02 1.416969e+01 +3.385440e-02 2.241964e-02 9.991753e-01 -7.126746e+01 4.942332e-02 9.984876e-01 -2.407880e-02 -7.757411e+00 -9.982040e-01 5.019772e-02 3.269515e-02 1.421886e+01 +3.376018e-02 2.112800e-02 9.992066e-01 -7.001285e+01 4.794646e-02 9.985911e-01 -2.273496e-02 -7.812425e+00 -9.982792e-01 4.867595e-02 3.269961e-02 1.426575e+01 +3.427222e-02 1.959889e-02 9.992203e-01 -6.876010e+01 4.636701e-02 9.986999e-01 -2.117903e-02 -7.867347e+00 -9.983364e-01 4.705670e-02 3.331892e-02 1.431494e+01 +3.521728e-02 2.044838e-02 9.991704e-01 -6.751892e+01 4.677787e-02 9.986611e-01 -2.208672e-02 -7.920785e+00 -9.982843e-01 4.751688e-02 3.421359e-02 1.435873e+01 +3.611694e-02 1.980683e-02 9.991513e-01 -6.627669e+01 4.952977e-02 9.985394e-01 -2.158509e-02 -7.972703e+00 -9.981194e-01 5.026731e-02 3.508315e-02 1.440182e+01 +3.707002e-02 1.881873e-02 9.991354e-01 -6.504199e+01 4.824494e-02 9.986231e-01 -2.059907e-02 -8.029118e+00 -9.981474e-01 4.896683e-02 3.611107e-02 1.444829e+01 +3.795331e-02 2.376129e-02 9.989970e-01 -6.381771e+01 4.959088e-02 9.984406e-01 -2.563209e-02 -8.083196e+00 -9.980483e-01 5.051395e-02 3.671578e-02 1.449341e+01 +3.842649e-02 2.828960e-02 9.988609e-01 -6.260502e+01 4.982069e-02 9.983018e-01 -3.019040e-02 -8.143266e+00 -9.980187e-01 5.092404e-02 3.695183e-02 1.454163e+01 +3.887974e-02 3.008220e-02 9.987910e-01 -6.140955e+01 4.854024e-02 9.983098e-01 -3.195723e-02 -8.211070e+00 -9.980643e-01 4.972403e-02 3.735383e-02 1.459751e+01 +3.942066e-02 2.727275e-02 9.988504e-01 -6.020646e+01 4.871954e-02 9.983861e-01 -2.918284e-02 -8.277482e+00 -9.980343e-01 4.981393e-02 3.802832e-02 1.465069e+01 +4.000922e-02 2.467044e-02 9.988947e-01 -5.900620e+01 4.978381e-02 9.984043e-01 -2.665235e-02 -8.341207e+00 -9.979584e-01 5.079511e-02 3.871718e-02 1.470161e+01 +4.078704e-02 2.162963e-02 9.989337e-01 -5.781278e+01 5.169786e-02 9.983808e-01 -2.372852e-02 -8.401802e+00 -9.978296e-01 5.261054e-02 3.960279e-02 1.475293e+01 +4.164942e-02 2.227297e-02 9.988840e-01 -5.662406e+01 5.362356e-02 9.982607e-01 -2.449497e-02 -8.461349e+00 -9.976923e-01 5.458391e-02 4.038262e-02 1.480235e+01 +4.251176e-02 2.448337e-02 9.987959e-01 -5.544649e+01 5.318345e-02 9.982268e-01 -2.673307e-02 -8.522863e+00 -9.976795e-01 5.425588e-02 4.113427e-02 1.485644e+01 +4.302778e-02 2.559170e-02 9.987460e-01 -5.427208e+01 5.220533e-02 9.982485e-01 -2.782806e-02 -8.584502e+00 -9.977090e-01 5.333723e-02 4.161640e-02 1.491668e+01 +4.331086e-02 2.670735e-02 9.987046e-01 -5.313947e+01 5.031203e-02 9.983159e-01 -2.887885e-02 -8.647590e+00 -9.977940e-01 5.149761e-02 4.189422e-02 1.498821e+01 +4.331963e-02 2.456626e-02 9.987592e-01 -5.199403e+01 4.758345e-02 9.985124e-01 -2.662405e-02 -8.710080e+00 -9.979275e-01 4.867774e-02 4.208624e-02 1.505129e+01 +4.368240e-02 2.265764e-02 9.987885e-01 -5.086318e+01 4.854140e-02 9.985139e-01 -2.477439e-02 -8.768372e+00 -9.978655e-01 4.956479e-02 4.251765e-02 1.511169e+01 +4.428204e-02 2.212409e-02 9.987740e-01 -4.972356e+01 5.003078e-02 9.984511e-01 -2.433513e-02 -8.827365e+00 -9.977655e-01 5.104705e-02 4.310657e-02 1.516918e+01 +4.501858e-02 2.246301e-02 9.987336e-01 -4.859008e+01 5.041852e-02 9.984220e-01 -2.472865e-02 -8.884653e+00 -9.977131e-01 5.146790e-02 4.381499e-02 1.522951e+01 +4.561721e-02 2.280834e-02 9.986986e-01 -4.745692e+01 5.025836e-02 9.984208e-01 -2.509764e-02 -8.941083e+00 -9.976940e-01 5.133783e-02 4.439886e-02 1.528897e+01 +4.600131e-02 2.278335e-02 9.986815e-01 -4.633058e+01 5.037872e-02 9.984148e-01 -2.509782e-02 -8.997659e+00 -9.976703e-01 5.146681e-02 4.478059e-02 1.534886e+01 +4.631105e-02 2.438240e-02 9.986294e-01 -4.519584e+01 4.984288e-02 9.984004e-01 -2.668826e-02 -9.055553e+00 -9.976828e-01 5.101052e-02 4.502168e-02 1.539953e+01 +4.662861e-02 2.453492e-02 9.986109e-01 -4.409594e+01 4.966028e-02 9.984052e-01 -2.684869e-02 -9.122087e+00 -9.976771e-01 5.084321e-02 4.533584e-02 1.545387e+01 +4.723173e-02 2.436869e-02 9.985867e-01 -4.300373e+01 5.013980e-02 9.983843e-01 -2.673530e-02 -9.190355e+00 -9.976248e-01 5.133168e-02 4.593358e-02 1.550684e+01 +4.754072e-02 2.314459e-02 9.986011e-01 -4.192275e+01 5.104163e-02 9.983691e-01 -2.556918e-02 -9.255851e+00 -9.975644e-01 5.218580e-02 4.628184e-02 1.555876e+01 +4.782309e-02 2.221447e-02 9.986088e-01 -4.086337e+01 5.128773e-02 9.983793e-01 -2.466553e-02 -9.320056e+00 -9.975383e-01 5.239594e-02 4.660625e-02 1.561151e+01 +4.824591e-02 2.050194e-02 9.986250e-01 -3.981395e+01 5.089705e-02 9.984400e-01 -2.295710e-02 -9.379312e+00 -9.975379e-01 5.193465e-02 4.712715e-02 1.566469e+01 +4.876513e-02 1.920215e-02 9.986257e-01 -3.878977e+01 5.045477e-02 9.984913e-01 -2.166339e-02 -9.439251e+00 -9.975351e-01 5.144184e-02 4.772272e-02 1.571712e+01 +4.901502e-02 1.825135e-02 9.986313e-01 -3.777927e+01 4.996115e-02 9.985366e-01 -2.070183e-02 -9.494703e+00 -9.975477e-01 5.090745e-02 4.803143e-02 1.576893e+01 +4.929876e-02 1.973125e-02 9.985891e-01 -3.679306e+01 4.714095e-02 9.986446e-01 -2.205963e-02 -9.550098e+00 -9.976710e-01 4.816194e-02 4.830179e-02 1.582387e+01 +4.926629e-02 1.951247e-02 9.985950e-01 -3.582840e+01 4.680127e-02 9.986658e-01 -2.182283e-02 -9.606972e+00 -9.976886e-01 4.781063e-02 4.828735e-02 1.591263e+01 +4.977417e-02 1.694616e-02 9.986167e-01 -3.487846e+01 4.732326e-02 9.986930e-01 -1.930620e-02 -9.660793e+00 -9.976388e-01 4.821874e-02 4.890717e-02 1.600162e+01 +4.983874e-02 1.177326e-02 9.986879e-01 -3.393520e+01 4.754430e-02 9.987689e-01 -1.414688e-02 -9.710387e+00 -9.976250e-01 4.818697e-02 4.921763e-02 1.607949e+01 +5.033830e-02 1.210816e-02 9.986588e-01 -3.301200e+01 5.042366e-02 9.986204e-01 -1.464935e-02 -9.759826e+00 -9.974586e-01 5.109344e-02 4.965832e-02 1.615393e+01 +5.026893e-02 1.940320e-02 9.985472e-01 -3.210855e+01 4.793221e-02 9.986123e-01 -2.181748e-02 -9.808261e+00 -9.975849e-01 4.895930e-02 4.926913e-02 1.622431e+01 +4.878100e-02 2.775442e-02 9.984238e-01 -3.120485e+01 4.844446e-02 9.983716e-01 -3.011988e-02 -9.849390e+00 -9.976340e-01 4.983737e-02 4.735701e-02 1.627428e+01 +4.630503e-02 2.995245e-02 9.984782e-01 -3.030385e+01 5.208861e-02 9.981181e-01 -3.235730e-02 -9.898850e+00 -9.975684e-01 5.350763e-02 4.465771e-02 1.630438e+01 +4.300677e-02 2.385546e-02 9.987899e-01 -2.941770e+01 5.232599e-02 9.982890e-01 -2.609661e-02 -9.949646e+00 -9.977036e-01 5.338499e-02 4.168493e-02 1.633667e+01 +3.896537e-02 1.950672e-02 9.990501e-01 -2.852472e+01 5.149491e-02 9.984417e-01 -2.150327e-02 -9.997061e+00 -9.979128e-01 5.228387e-02 3.790015e-02 1.635068e+01 +3.581345e-02 1.912179e-02 9.991755e-01 -2.767703e+01 5.681548e-02 9.981609e-01 -2.113882e-02 -1.003051e+01 -9.977422e-01 5.752568e-02 3.466117e-02 1.636542e+01 +3.258884e-02 1.729953e-02 9.993191e-01 -2.686483e+01 6.039777e-02 9.979888e-01 -1.924614e-02 -1.005517e+01 -9.976423e-01 6.098384e-02 3.147845e-02 1.637737e+01 +2.806429e-02 1.488500e-02 9.994953e-01 -2.607731e+01 6.192285e-02 9.979429e-01 -1.660059e-02 -1.009406e+01 -9.976863e-01 6.235747e-02 2.708484e-02 1.640415e+01 +2.442768e-02 1.108145e-02 9.996402e-01 -2.531440e+01 6.170403e-02 9.980153e-01 -1.257128e-02 -1.013275e+01 -9.977956e-01 6.198890e-02 2.369542e-02 1.643220e+01 +2.093667e-02 1.022730e-02 9.997285e-01 -2.456933e+01 6.183843e-02 9.980198e-01 -1.150487e-02 -1.016432e+01 -9.978666e-01 6.206250e-02 2.026277e-02 1.645391e+01 +1.751956e-02 9.654300e-03 9.997999e-01 -2.384628e+01 6.205541e-02 9.980151e-01 -1.072447e-02 -1.019343e+01 -9.979190e-01 6.223087e-02 1.688568e-02 1.647262e+01 +1.465100e-02 1.065448e-02 9.998359e-01 -2.315952e+01 6.544051e-02 9.977891e-01 -1.159160e-02 -1.021521e+01 -9.977489e-01 6.559959e-02 1.392137e-02 1.648929e+01 +1.169427e-02 1.273996e-02 9.998504e-01 -2.249594e+01 6.770603e-02 9.976139e-01 -1.350336e-02 -1.023594e+01 -9.976368e-01 6.785380e-02 1.080379e-02 1.650307e+01 +8.819224e-03 1.585575e-02 9.998354e-01 -2.183795e+01 7.285429e-02 9.972068e-01 -1.645670e-02 -1.025639e+01 -9.973036e-01 7.298742e-02 7.639428e-03 1.650829e+01 +6.281210e-03 1.786061e-02 9.998207e-01 -2.119980e+01 7.693698e-02 9.968681e-01 -1.829122e-02 -1.027764e+01 -9.970162e-01 7.703806e-02 4.887394e-03 1.651197e+01 +3.876895e-03 2.006687e-02 9.997911e-01 -2.058199e+01 7.620298e-02 9.968856e-01 -2.030405e-02 -1.030683e+01 -9.970848e-01 7.626576e-02 2.335664e-03 1.651971e+01 +1.367736e-03 2.036031e-02 9.997918e-01 -1.998333e+01 7.562223e-02 9.969277e-01 -2.040544e-02 -1.033350e+01 -9.971356e-01 7.563438e-02 -1.761598e-04 1.652173e+01 +-3.487736e-05 2.160585e-02 9.997665e-01 -1.940386e+01 7.674664e-02 9.968179e-01 -2.153946e-02 -1.035761e+01 -9.970507e-01 7.672795e-02 -1.692945e-03 1.651621e+01 +-1.845793e-03 2.402232e-02 9.997097e-01 -1.884618e+01 7.585684e-02 9.968343e-01 -2.381318e-02 -1.037462e+01 -9.971170e-01 7.579085e-02 -3.662209e-03 1.650819e+01 +-4.036855e-03 2.475463e-02 9.996854e-01 -1.831029e+01 7.340630e-02 9.970038e-01 -2.439181e-02 -1.039955e+01 -9.972940e-01 7.328472e-02 -5.841908e-03 1.649850e+01 +-5.546010e-03 2.314363e-02 9.997168e-01 -1.779631e+01 7.109210e-02 9.972116e-01 -2.269125e-02 -1.043522e+01 -9.974544e-01 7.094610e-02 -7.175877e-03 1.648953e+01 +-5.526547e-03 2.358771e-02 9.997065e-01 -1.732899e+01 6.958710e-02 9.973073e-01 -2.314642e-02 -1.045439e+01 -9.975606e-01 6.943874e-02 -7.153069e-03 1.648230e+01 +-5.338999e-03 2.458395e-02 9.996835e-01 -1.686983e+01 6.972448e-02 9.972738e-01 -2.415233e-02 -1.047666e+01 -9.975520e-01 6.957345e-02 -7.038549e-03 1.647777e+01 +-3.044648e-03 2.513822e-02 9.996793e-01 -1.644057e+01 6.768022e-02 9.973969e-01 -2.487470e-02 -1.050421e+01 -9.977025e-01 6.758276e-02 -4.738084e-03 1.647465e+01 +1.514628e-03 2.572559e-02 9.996679e-01 -1.603755e+01 6.807698e-02 9.973472e-01 -2.576902e-02 -1.052421e+01 -9.976790e-01 6.809339e-02 -2.407128e-04 1.647547e+01 +7.652380e-03 2.557019e-02 9.996437e-01 -1.565704e+01 6.709281e-02 9.974072e-01 -2.602659e-02 -1.054126e+01 -9.977174e-01 6.726806e-02 5.916961e-03 1.647926e+01 +1.554203e-02 2.604702e-02 9.995399e-01 -1.529407e+01 6.556707e-02 9.974824e-01 -2.701293e-02 -1.055646e+01 -9.977272e-01 6.595672e-02 1.379507e-02 1.649307e+01 +2.370947e-02 2.611567e-02 9.993777e-01 -1.495612e+01 6.167760e-02 9.977162e-01 -2.753551e-02 -1.056745e+01 -9.978145e-01 6.229205e-02 2.204457e-02 1.651522e+01 +3.313761e-02 2.634548e-02 9.991035e-01 -1.462900e+01 5.863913e-02 9.978792e-01 -2.825811e-02 -1.058095e+01 -9.977291e-01 5.952295e-02 3.152246e-02 1.654218e+01 +4.483142e-02 2.665529e-02 9.986389e-01 -1.431623e+01 5.661235e-02 9.979697e-01 -2.917891e-02 -1.059457e+01 -9.973892e-01 5.784341e-02 4.323138e-02 1.657285e+01 +5.901001e-02 2.559502e-02 9.979292e-01 -1.401777e+01 5.497452e-02 9.980709e-01 -2.884944e-02 -1.060865e+01 -9.967425e-01 5.656307e-02 5.748909e-02 1.660392e+01 +7.771157e-02 2.496575e-02 9.966632e-01 -1.371545e+01 5.485636e-02 9.980649e-01 -2.927812e-02 -1.062679e+01 -9.954656e-01 5.694856e-02 7.619166e-02 1.664197e+01 +1.016329e-01 2.430078e-02 9.945251e-01 -1.341559e+01 5.575421e-02 9.979912e-01 -3.008313e-02 -1.065150e+01 -9.932584e-01 5.850639e-02 1.000738e-01 1.669217e+01 +1.298577e-01 2.246502e-02 9.912781e-01 -1.312557e+01 5.562969e-02 9.980035e-01 -2.990495e-02 -1.067795e+01 -9.899709e-01 5.902787e-02 1.283487e-01 1.674594e+01 +1.612341e-01 2.050374e-02 9.867032e-01 -1.283471e+01 5.182448e-02 9.982289e-01 -2.921173e-02 -1.070857e+01 -9.855546e-01 5.584529e-02 1.598860e-01 1.682830e+01 +1.928561e-01 1.950879e-02 9.810331e-01 -1.255510e+01 4.594879e-02 9.985259e-01 -2.888949e-02 -1.073848e+01 -9.801506e-01 5.064879e-02 1.916754e-01 1.691005e+01 +2.262782e-01 1.922116e-02 9.738730e-01 -1.227722e+01 3.903483e-02 9.988232e-01 -2.878330e-02 -1.078457e+01 -9.732803e-01 4.452799e-02 2.252617e-01 1.701862e+01 +2.622689e-01 1.927233e-02 9.648024e-01 -1.200994e+01 3.310175e-02 9.990325e-01 -2.895438e-02 -1.082266e+01 -9.644270e-01 3.953047e-02 2.613772e-01 1.713992e+01 +2.986820e-01 1.944903e-02 9.541545e-01 -1.175669e+01 2.800269e-02 9.991832e-01 -2.913265e-02 -1.085893e+01 -9.539418e-01 3.542028e-02 2.978935e-01 1.724925e+01 +3.341590e-01 2.065226e-02 9.422904e-01 -1.151869e+01 2.283317e-02 9.992891e-01 -2.999871e-02 -1.089077e+01 -9.422401e-01 3.153981e-02 3.334499e-01 1.738782e+01 +3.700617e-01 2.233351e-02 9.287387e-01 -1.128175e+01 1.897126e-02 9.993208e-01 -3.159003e-02 -1.091923e+01 -9.288135e-01 2.930960e-02 3.693867e-01 1.753719e+01 +4.070037e-01 2.532779e-02 9.130753e-01 -1.104782e+01 1.484010e-02 9.993002e-01 -3.433457e-02 -1.094865e+01 -9.133060e-01 2.752442e-02 4.063430e-01 1.767597e+01 +4.442049e-01 2.676644e-02 8.955253e-01 -1.079390e+01 1.207042e-02 9.992841e-01 -3.585496e-02 -1.097862e+01 -8.958439e-01 2.673631e-02 4.435638e-01 1.785311e+01 +4.817250e-01 2.762387e-02 8.758869e-01 -1.054598e+01 8.872813e-03 9.992980e-01 -3.639596e-02 -1.100326e+01 -8.762775e-01 2.530442e-02 4.811418e-01 1.801815e+01 +5.196728e-01 2.776153e-02 8.539142e-01 -1.028749e+01 7.695993e-03 9.992793e-01 -3.717109e-02 -1.103018e+01 -8.543307e-01 2.588852e-02 5.190846e-01 1.822499e+01 +5.583460e-01 2.603455e-02 8.291996e-01 -1.002369e+01 7.035385e-03 9.993229e-01 -3.611326e-02 -1.106097e+01 -8.295784e-01 2.599743e-02 5.577848e-01 1.845176e+01 +5.967016e-01 2.562406e-02 8.020540e-01 -9.778274e+00 5.178559e-03 9.993463e-01 -3.577985e-02 -1.108657e+01 -8.024465e-01 2.550337e-02 5.961789e-01 1.867022e+01 +6.350505e-01 2.837024e-02 7.719495e-01 -9.524482e+00 1.793140e-04 9.993199e-01 -3.687394e-02 -1.111223e+01 -7.724707e-01 2.355523e-02 6.346135e-01 1.894569e+01 +6.730218e-01 3.256044e-02 7.389056e-01 -9.266871e+00 -6.536807e-03 9.992533e-01 -3.807891e-02 -1.114198e+01 -7.395938e-01 2.079784e-02 6.727321e-01 1.924995e+01 +7.096682e-01 3.566480e-02 7.036327e-01 -9.021320e+00 -1.181165e-02 9.991798e-01 -3.873215e-02 -1.116803e+01 -7.044370e-01 1.917590e-02 7.095074e-01 1.954116e+01 +7.428353e-01 3.617510e-02 6.684961e-01 -8.764530e+00 -1.508244e-02 9.991899e-01 -3.731067e-02 -1.119631e+01 -6.693043e-01 1.763312e-02 7.427791e-01 1.989121e+01 +7.731890e-01 3.561804e-02 6.331746e-01 -8.499983e+00 -1.761584e-02 9.992425e-01 -3.469927e-02 -1.121552e+01 -6.339309e-01 1.567519e-02 7.732308e-01 2.023026e+01 +8.007770e-01 3.585117e-02 5.978887e-01 -8.233362e+00 -2.126534e-02 9.992794e-01 -3.143820e-02 -1.123863e+01 -5.985850e-01 1.246068e-02 8.009624e-01 2.062629e+01 +8.254570e-01 3.917339e-02 5.631040e-01 -7.973471e+00 -2.452057e-02 9.991358e-01 -3.356196e-02 -1.125525e+01 -5.639321e-01 1.389632e-02 8.257042e-01 2.103954e+01 +8.475334e-01 4.083071e-02 5.291691e-01 -7.714471e+00 -2.588802e-02 9.990299e-01 -3.562217e-02 -1.125822e+01 -5.301103e-01 1.649184e-02 8.477683e-01 2.144879e+01 +8.668743e-01 4.187794e-02 4.967648e-01 -7.455310e+00 -2.692034e-02 9.989438e-01 -3.723526e-02 -1.126675e+01 -4.977995e-01 1.890521e-02 8.670861e-01 2.191038e+01 +8.836926e-01 4.073717e-02 4.662916e-01 -7.202167e+00 -2.584893e-02 9.989325e-01 -3.828331e-02 -1.127527e+01 -4.673534e-01 2.177754e-02 8.838023e-01 2.238180e+01 +8.998604e-01 3.717416e-02 4.345910e-01 -6.943853e+00 -2.346865e-02 9.990447e-01 -3.686257e-02 -1.129089e+01 -4.355462e-01 2.297190e-02 8.998732e-01 2.289983e+01 +9.155953e-01 3.262326e-02 4.007755e-01 -6.684246e+00 -2.120706e-02 9.992340e-01 -3.288923e-02 -1.130887e+01 -4.015415e-01 2.161395e-02 9.155858e-01 2.344669e+01 +9.301228e-01 2.275931e-02 3.665427e-01 -6.446020e+00 -1.398629e-02 9.995490e-01 -2.657285e-02 -1.132650e+01 -3.669822e-01 1.958943e-02 9.300217e-01 2.401505e+01 +9.426083e-01 1.987768e-02 3.333083e-01 -6.209422e+00 -1.412298e-02 9.997066e-01 -1.967971e-02 -1.133516e+01 -3.336017e-01 1.384295e-02 9.426125e-01 2.463093e+01 +9.531356e-01 1.797341e-02 3.020092e-01 -6.002323e+00 -1.369409e-02 9.997736e-01 -1.628105e-02 -1.135171e+01 -3.022335e-01 1.138231e-02 9.531660e-01 2.526823e+01 +9.619875e-01 1.564179e-02 2.726453e-01 -5.784033e+00 -1.103175e-02 9.997692e-01 -1.843338e-02 -1.136352e+01 -2.728707e-01 1.472492e-02 9.619380e-01 2.593530e+01 +9.698691e-01 8.114524e-03 2.434914e-01 -5.580618e+00 -2.204482e-03 9.996965e-01 -2.453477e-02 -1.137165e+01 -2.436166e-01 2.325873e-02 9.695927e-01 2.663676e+01 +9.763173e-01 6.332351e-03 2.162507e-01 -5.400907e+00 -5.062522e-04 9.996357e-01 -2.698619e-02 -1.137761e+01 -2.163428e-01 2.623760e-02 9.759649e-01 2.736213e+01 +9.816817e-01 -1.656934e-03 1.905213e-01 -5.241816e+00 6.185689e-03 9.997122e-01 -2.317809e-02 -1.138924e+01 -1.904281e-01 2.393200e-02 9.814094e-01 2.813843e+01 +9.868020e-01 -9.472812e-03 1.616543e-01 -5.100718e+00 1.223161e-02 9.997959e-01 -1.607935e-02 -1.140302e+01 -1.614690e-01 1.784443e-02 9.867164e-01 2.893848e+01 +9.910882e-01 -1.599690e-02 1.322436e-01 -4.985547e+00 1.800585e-02 9.997397e-01 -1.400934e-02 -1.141606e+01 -1.319851e-01 1.626565e-02 9.911182e-01 2.978106e+01 +9.943880e-01 -2.138366e-02 1.036116e-01 -4.894545e+00 2.267640e-02 9.996788e-01 -1.131475e-02 -1.143015e+01 -1.033364e-01 1.360079e-02 9.945535e-01 3.065098e+01 +9.967616e-01 -2.408613e-02 7.672184e-02 -4.832290e+00 2.460464e-02 9.996803e-01 -5.819965e-03 -1.144245e+01 -7.655713e-02 7.688830e-03 9.970356e-01 3.154033e+01 +9.984127e-01 -1.728544e-02 5.360381e-02 -4.785405e+00 1.749809e-02 9.998407e-01 -3.500166e-03 -1.145977e+01 -5.353477e-02 4.432574e-03 9.985562e-01 3.244953e+01 +9.994452e-01 -9.106343e-03 3.203617e-02 -4.764967e+00 9.251229e-03 9.999476e-01 -4.377202e-03 -1.147422e+01 -3.199463e-02 4.671148e-03 9.994771e-01 3.337537e+01 +9.999046e-01 -5.807379e-03 1.253673e-02 -4.752808e+00 5.921729e-03 9.999410e-01 -9.103374e-03 -1.148757e+01 -1.248312e-02 9.176743e-03 9.998800e-01 3.432771e+01 +9.999882e-01 -3.077896e-03 -3.761795e-03 -4.751980e+00 3.025472e-03 9.998993e-01 -1.386319e-02 -1.150547e+01 3.804086e-03 1.385164e-02 9.998968e-01 3.530317e+01 +9.998586e-01 7.081894e-04 -1.680179e-02 -4.771409e+00 -9.957753e-04 9.998530e-01 -1.711419e-02 -1.152759e+01 1.678720e-02 1.712850e-02 9.997124e-01 3.630181e+01 +9.995976e-01 4.851841e-03 -2.794956e-02 -4.799016e+00 -5.294723e-03 9.998612e-01 -1.579357e-02 -1.155048e+01 2.786905e-02 1.593520e-02 9.994846e-01 3.733507e+01 +9.993010e-01 5.921580e-03 -3.691075e-02 -4.824922e+00 -6.251373e-03 9.999415e-01 -8.825859e-03 -1.157689e+01 3.685633e-02 9.050432e-03 9.992796e-01 3.837989e+01 +9.989898e-01 7.050981e-03 -4.438049e-02 -4.857966e+00 -7.349513e-03 9.999514e-01 -6.567054e-03 -1.160715e+01 4.433203e-02 6.886595e-03 9.989931e-01 3.943453e+01 +9.987205e-01 8.847334e-03 -4.979077e-02 -4.911943e+00 -9.157575e-03 9.999400e-01 -6.006194e-03 -1.163721e+01 4.973464e-02 6.454472e-03 9.987416e-01 4.049949e+01 +9.985619e-01 8.614905e-03 -5.291492e-02 -4.964157e+00 -8.770105e-03 9.999579e-01 -2.701462e-03 -1.167505e+01 5.288942e-02 3.161647e-03 9.985954e-01 4.156728e+01 +9.984441e-01 1.150718e-02 -5.456099e-02 -5.025754e+00 -1.147028e-02 9.999337e-01 9.895909e-04 -1.170848e+01 5.456876e-02 -3.622207e-04 9.985100e-01 4.263695e+01 +9.984295e-01 1.024733e-02 -5.507788e-02 -5.090383e+00 -1.045413e-02 9.999393e-01 -3.467777e-03 -1.173822e+01 5.503901e-02 4.038122e-03 9.984760e-01 4.370080e+01 +9.984511e-01 1.137045e-02 -5.446235e-02 -5.153019e+00 -1.172006e-02 9.999127e-01 -6.104000e-03 -1.177148e+01 5.438819e-02 6.732847e-03 9.984972e-01 4.476499e+01 +9.984890e-01 1.214735e-02 -5.359322e-02 -5.215915e+00 -1.248922e-02 9.999037e-01 -6.048641e-03 -1.180003e+01 5.351459e-02 6.708839e-03 9.985445e-01 4.583447e+01 +9.985135e-01 1.258968e-02 -5.303178e-02 -5.276585e+00 -1.276042e-02 9.999144e-01 -2.882056e-03 -1.182445e+01 5.299096e-02 3.554480e-03 9.985887e-01 4.690412e+01 +9.985459e-01 1.088064e-02 -5.279829e-02 -5.332579e+00 -1.094135e-02 9.999397e-01 -8.609503e-04 -1.184656e+01 5.278574e-02 1.437384e-03 9.986048e-01 4.797661e+01 +9.985671e-01 1.075110e-02 -5.242273e-02 -5.396535e+00 -1.088645e-02 9.999381e-01 -2.296985e-03 -1.186349e+01 5.239479e-02 2.864391e-03 9.986224e-01 4.904931e+01 +9.985830e-01 1.139888e-02 -5.198108e-02 -5.464336e+00 -1.149446e-02 9.999327e-01 -1.540068e-03 -1.188005e+01 5.196003e-02 2.135380e-03 9.986469e-01 5.012670e+01 +9.985819e-01 1.193271e-02 -5.188277e-02 -5.541169e+00 -1.201644e-02 9.999269e-01 -1.302169e-03 -1.189215e+01 5.186345e-02 1.923769e-03 9.986523e-01 5.120511e+01 +9.985665e-01 1.302585e-02 -5.191604e-02 -5.618931e+00 -1.326378e-02 9.999030e-01 -4.241008e-03 -1.190430e+01 5.185577e-02 4.923531e-03 9.986425e-01 5.227360e+01 +9.985685e-01 1.183256e-02 -5.216304e-02 -5.701735e+00 -1.221880e-02 9.999002e-01 -7.091700e-03 -1.190993e+01 5.207393e-02 7.718918e-03 9.986134e-01 5.334843e+01 +9.985783e-01 1.028452e-02 -5.230349e-02 -5.775300e+00 -1.065962e-02 9.999194e-01 -6.897604e-03 -1.192695e+01 5.222834e-02 7.445332e-03 9.986074e-01 5.442013e+01 +9.986026e-01 9.580802e-03 -5.197210e-02 -5.858151e+00 -9.770707e-03 9.999465e-01 -3.401093e-03 -1.194246e+01 5.193673e-02 3.904144e-03 9.986428e-01 5.549978e+01 +9.986598e-01 8.184307e-03 -5.110344e-02 -5.926283e+00 -8.180328e-03 9.999665e-01 2.870741e-04 -1.196133e+01 5.110408e-02 1.313544e-04 9.986933e-01 5.656676e+01 +9.986986e-01 6.553442e-03 -5.057902e-02 -6.001036e+00 -6.497944e-03 9.999781e-01 1.261634e-03 -1.197456e+01 5.058618e-02 -9.313312e-04 9.987193e-01 5.763459e+01 +9.987411e-01 5.415511e-03 -4.986882e-02 -6.070795e+00 -5.455977e-03 9.999849e-01 -6.753322e-04 -1.198888e+01 4.986441e-02 9.465659e-04 9.987556e-01 5.869282e+01 +9.987734e-01 6.080329e-03 -4.914064e-02 -6.149722e+00 -6.269453e-03 9.999735e-01 -3.695373e-03 -1.200466e+01 4.911687e-02 3.998925e-03 9.987850e-01 5.974756e+01 +9.988245e-01 5.612738e-03 -4.814783e-02 -6.216629e+00 -5.822681e-03 9.999741e-01 -4.221209e-03 -1.202352e+01 4.812289e-02 4.496596e-03 9.988313e-01 6.079310e+01 +9.988670e-01 5.436306e-03 -4.727766e-02 -6.274301e+00 -5.444214e-03 9.999852e-01 -3.846810e-05 -1.204340e+01 4.727676e-02 2.958150e-04 9.988818e-01 6.182826e+01 +9.989281e-01 6.681294e-03 -4.580499e-02 -6.326192e+00 -6.459700e-03 9.999667e-01 4.984126e-03 -1.206731e+01 4.583676e-02 -4.682896e-03 9.989380e-01 6.285326e+01 +9.989675e-01 6.467594e-03 -4.496887e-02 -6.368922e+00 -6.242702e-03 9.999673e-01 5.139735e-03 -1.209151e+01 4.500065e-02 -4.853699e-03 9.989752e-01 6.385847e+01 +9.989976e-01 6.784639e-03 -4.424660e-02 -6.414114e+00 -6.635921e-03 9.999718e-01 3.507157e-03 -1.211048e+01 4.426915e-02 -3.210024e-03 9.990145e-01 6.484741e+01 +9.990347e-01 6.986557e-03 -4.336972e-02 -6.450595e+00 -6.865304e-03 9.999721e-01 2.944139e-03 -1.213053e+01 4.338908e-02 -2.643550e-03 9.990548e-01 6.581528e+01 +9.990650e-01 8.739369e-03 -4.234041e-02 -6.486426e+00 -8.557684e-03 9.999534e-01 4.470457e-03 -1.214924e+01 4.237750e-02 -4.103940e-03 9.990933e-01 6.677467e+01 +9.990633e-01 1.095911e-02 -4.186302e-02 -6.526388e+00 -1.081247e-02 9.999346e-01 3.727721e-03 -1.217103e+01 4.190114e-02 -3.271585e-03 9.991164e-01 6.771319e+01 +9.990908e-01 9.558584e-03 -4.154845e-02 -6.558018e+00 -9.516206e-03 9.999540e-01 1.217673e-03 -1.219716e+01 4.155818e-02 -8.211813e-04 9.991358e-01 6.863322e+01 +9.990811e-01 1.095694e-02 -4.143670e-02 -6.589651e+00 -1.106313e-02 9.999361e-01 -2.334085e-03 -1.222390e+01 4.140848e-02 2.790360e-03 9.991384e-01 6.953354e+01 +9.991283e-01 1.076321e-02 -4.033385e-02 -6.608988e+00 -1.085765e-02 9.999388e-01 -2.123185e-03 -1.224767e+01 4.030853e-02 2.559266e-03 9.991840e-01 7.041341e+01 +9.991473e-01 1.008150e-02 -4.003733e-02 -6.625230e+00 -9.977313e-03 9.999463e-01 2.801230e-03 -1.226861e+01 4.006342e-02 -2.399375e-03 9.991943e-01 7.127956e+01 +9.991854e-01 1.033001e-02 -3.901017e-02 -6.627217e+00 -9.933012e-03 9.998970e-01 1.035702e-02 -1.228090e+01 3.911314e-02 -9.961096e-03 9.991851e-01 7.212534e+01 +9.992092e-01 1.097118e-02 -3.821941e-02 -6.642849e+00 -1.042801e-02 9.998422e-01 1.438222e-02 -1.229391e+01 3.837117e-02 -1.397229e-02 9.991659e-01 7.294758e+01 +9.992407e-01 9.043364e-03 -3.789704e-02 -6.655510e+00 -8.534474e-03 9.998715e-01 1.356859e-02 -1.230578e+01 3.801488e-02 -1.323485e-02 9.991895e-01 7.374978e+01 +9.992826e-01 7.395998e-03 -3.714400e-02 -6.672594e+00 -7.000923e-03 9.999176e-01 1.075517e-02 -1.231645e+01 3.722049e-02 -1.048741e-02 9.992521e-01 7.452457e+01 +9.993040e-01 8.286367e-03 -3.637218e-02 -6.684239e+00 -8.010330e-03 9.999380e-01 7.728466e-03 -1.233162e+01 3.643397e-02 -7.431731e-03 9.993084e-01 7.527147e+01 +9.993555e-01 8.987037e-03 -3.475457e-02 -6.684464e+00 -8.785131e-03 9.999436e-01 5.957887e-03 -1.235498e+01 3.480616e-02 -5.648722e-03 9.993781e-01 7.599511e+01 +9.994419e-01 1.198675e-02 -3.118024e-02 -6.682743e+00 -1.184200e-02 9.999182e-01 4.822997e-03 -1.237598e+01 3.123551e-02 -4.451068e-03 9.995022e-01 7.668649e+01 +9.996197e-01 1.422099e-02 -2.362756e-02 -6.670029e+00 -1.410843e-02 9.998883e-01 4.923896e-03 -1.239695e+01 2.369494e-02 -4.588674e-03 9.997087e-01 7.735040e+01 +9.997929e-01 1.674607e-02 -1.156140e-02 -6.652349e+00 -1.668146e-02 9.998448e-01 5.662591e-03 -1.241714e+01 1.165443e-02 -5.468556e-03 9.999171e-01 7.798789e+01 +9.998241e-01 1.824150e-02 4.358505e-03 -6.619895e+00 -1.826962e-02 9.998119e-01 6.501937e-03 -1.243964e+01 -4.239080e-03 -6.580420e-03 9.999694e-01 7.858956e+01 +9.995097e-01 1.928538e-02 2.466526e-02 -6.574568e+00 -1.946467e-02 9.997857e-01 7.049372e-03 -1.245990e+01 -2.452403e-02 -7.526015e-03 9.996709e-01 7.916639e+01 +9.985672e-01 2.028011e-02 4.951973e-02 -6.508811e+00 -2.066726e-02 9.997596e-01 7.318459e-03 -1.248199e+01 -4.935941e-02 -8.331409e-03 9.987463e-01 7.971501e+01 +9.966991e-01 2.201066e-02 7.814323e-02 -6.438485e+00 -2.252061e-02 9.997304e-01 5.650487e-03 -1.250173e+01 -7.799780e-02 -7.391667e-03 9.969261e-01 8.021979e+01 +9.934478e-01 2.392887e-02 1.117540e-01 -6.332548e+00 -2.445405e-02 9.996954e-01 3.330805e-03 -1.252831e+01 -1.116403e-01 -6.041818e-03 9.937303e-01 8.071175e+01 +9.883719e-01 2.322507e-02 1.502715e-01 -6.213677e+00 -2.370175e-02 9.997181e-01 1.381570e-03 -1.255250e+01 -1.501970e-01 -4.927200e-03 9.886438e-01 8.115789e+01 +9.814443e-01 1.939265e-02 1.907643e-01 -6.064366e+00 -1.982911e-02 9.998033e-01 3.791399e-04 -1.257308e+01 -1.907194e-01 -4.154789e-03 9.816358e-01 8.160412e+01 +9.729136e-01 1.530264e-02 2.306622e-01 -5.907612e+00 -1.552527e-02 9.998791e-01 -8.499218e-04 -1.259171e+01 -2.306474e-01 -2.754193e-03 9.730335e-01 8.199602e+01 +9.621131e-01 1.341939e-02 2.723201e-01 -5.729615e+00 -1.306305e-02 9.999098e-01 -3.121504e-03 -1.261733e+01 -2.723375e-01 -5.540923e-04 9.622017e-01 8.239046e+01 +9.484226e-01 1.493823e-02 3.166567e-01 -5.547476e+00 -1.392237e-02 9.998881e-01 -5.470505e-03 -1.263913e+01 -3.167030e-01 7.797368e-04 9.485245e-01 8.276885e+01 +9.323857e-01 1.574462e-02 3.611219e-01 -5.368165e+00 -1.424429e-02 9.998753e-01 -6.816217e-03 -1.266024e+01 -3.611842e-01 1.211418e-03 9.324937e-01 8.309573e+01 +9.148413e-01 1.376209e-02 4.035791e-01 -5.161236e+00 -1.205848e-02 9.999044e-01 -6.762461e-03 -1.268006e+01 -4.036336e-01 1.320028e-03 9.149198e-01 8.343520e+01 +8.955785e-01 1.120797e-02 4.447623e-01 -4.962191e+00 -8.982183e-03 9.999343e-01 -7.111640e-03 -1.269976e+01 -4.448129e-01 2.374094e-03 8.956204e-01 8.371943e+01 +8.749116e-01 9.592210e-03 4.841877e-01 -4.749392e+00 -6.027981e-03 9.999420e-01 -8.917423e-03 -1.271850e+01 -4.842452e-01 4.883281e-03 8.749187e-01 8.401244e+01 +8.527419e-01 1.038209e-02 5.222294e-01 -4.542652e+00 -5.384926e-03 9.999240e-01 -1.108584e-02 -1.273758e+01 -5.223048e-01 6.641188e-03 8.527330e-01 8.425287e+01 +8.291147e-01 1.157642e-02 5.589587e-01 -4.311075e+00 -4.888498e-03 9.998975e-01 -1.345736e-02 -1.275584e+01 -5.590573e-01 8.425220e-03 8.290863e-01 8.449853e+01 +8.042581e-01 1.125634e-02 5.941735e-01 -4.078942e+00 -2.174072e-03 9.998696e-01 -1.599930e-02 -1.277383e+01 -5.942762e-01 1.157579e-02 8.041777e-01 8.471718e+01 +7.792087e-01 9.113303e-03 6.266983e-01 -3.866113e+00 3.298060e-03 9.998208e-01 -1.863983e-02 -1.278464e+01 -6.267559e-01 1.659120e-02 7.790390e-01 8.488456e+01 +7.551165e-01 5.683129e-03 6.555660e-01 -3.652536e+00 1.087669e-02 9.997162e-01 -2.119494e-02 -1.279625e+01 -6.555004e-01 2.313503e-02 7.548404e-01 8.505531e+01 +7.315187e-01 1.114512e-03 6.818205e-01 -3.458457e+00 2.011526e-02 9.995281e-01 -2.321532e-02 -1.279983e+01 -6.815246e-01 3.069743e-02 7.311511e-01 8.518387e+01 +7.091557e-01 -1.767976e-03 7.050497e-01 -3.262439e+00 2.609338e-02 9.993776e-01 -2.373931e-02 -1.280834e+01 -7.045690e-01 3.523199e-02 7.087604e-01 8.531172e+01 +6.884541e-01 1.215972e-04 7.252799e-01 -3.083089e+00 2.684614e-02 9.993104e-01 -2.565058e-02 -1.281398e+01 -7.247829e-01 3.713020e-02 6.879761e-01 8.542202e+01 +6.676015e-01 5.962292e-03 7.444949e-01 -2.924428e+00 2.314740e-02 9.993183e-01 -2.875972e-02 -1.282040e+01 -7.441589e-01 3.643315e-02 6.670084e-01 8.551297e+01 +6.456054e-01 1.264291e-02 7.635665e-01 -2.779876e+00 1.779932e-02 9.993422e-01 -3.159638e-02 -1.281107e+01 -7.634637e-01 3.398975e-02 6.449557e-01 8.560816e+01 +6.232122e-01 1.671119e-02 7.818742e-01 -2.632866e+00 1.384232e-02 9.993793e-01 -3.239335e-02 -1.280968e+01 -7.819303e-01 3.101088e-02 6.225941e-01 8.568542e+01 +6.006715e-01 1.879035e-02 7.992751e-01 -2.468267e+00 9.688921e-03 9.994792e-01 -3.077842e-02 -1.280625e+01 -7.994373e-01 2.623183e-02 6.001766e-01 8.576906e+01 +5.779196e-01 1.987912e-02 8.158516e-01 -2.292931e+00 5.593070e-03 9.995833e-01 -2.831788e-02 -1.281215e+01 -8.160746e-01 2.092857e-02 5.775676e-01 8.585543e+01 +5.548022e-01 2.151186e-02 8.317041e-01 -2.119828e+00 1.094191e-03 9.996459e-01 -2.658555e-02 -1.281869e+01 -8.319816e-01 1.565976e-02 5.545822e-01 8.592302e+01 +5.311712e-01 2.143509e-02 8.469933e-01 -1.929887e+00 1.579690e-03 9.996531e-01 -2.628917e-02 -1.282569e+01 -8.472631e-01 1.530203e-02 5.309531e-01 8.598713e+01 +5.071155e-01 2.073695e-02 8.616286e-01 -1.737887e+00 6.115855e-03 9.995987e-01 -2.765702e-02 -1.283084e+01 -8.618564e-01 1.929489e-02 5.067852e-01 8.602521e+01 +4.827597e-01 1.883751e-02 8.755502e-01 -1.536910e+00 1.160993e-02 9.995431e-01 -2.790670e-02 -1.283937e+01 -8.756759e-01 2.363730e-02 4.823205e-01 8.607071e+01 +4.579126e-01 1.496820e-02 8.888712e-01 -1.333074e+00 1.600322e-02 9.995574e-01 -2.507636e-02 -1.285540e+01 -8.888532e-01 2.570758e-02 4.574704e-01 8.611581e+01 +4.340538e-01 9.545872e-03 9.008363e-01 -1.127115e+00 1.934022e-02 9.996146e-01 -1.991138e-02 -1.286735e+01 -9.006793e-01 2.606497e-02 4.337020e-01 8.614739e+01 +4.111285e-01 6.089184e-03 9.115571e-01 -9.230845e-01 2.044952e-02 9.996644e-01 -1.590084e-02 -1.288010e+01 -9.113480e-01 2.517819e-02 4.108660e-01 8.619142e+01 +3.886113e-01 4.925862e-03 9.213886e-01 -7.216544e-01 2.277767e-02 9.996287e-01 -1.495101e-02 -1.289214e+01 -9.211202e-01 2.679721e-02 3.883548e-01 8.621951e+01 +3.672092e-01 6.055973e-03 9.301187e-01 -5.186592e-01 2.519080e-02 9.995472e-01 -1.645330e-02 -1.289651e+01 -9.297972e-01 2.947223e-02 3.668904e-01 8.625125e+01 +3.455362e-01 6.145212e-03 9.383853e-01 -3.110554e-01 2.714530e-02 9.994946e-01 -1.654096e-02 -1.290587e+01 -9.380127e-01 3.118824e-02 3.451948e-01 8.628193e+01 +3.250770e-01 5.432867e-03 9.456719e-01 -1.104130e-01 2.603019e-02 9.995532e-01 -1.469036e-02 -1.292528e+01 -9.453293e-01 2.939151e-02 3.247904e-01 8.631304e+01 +3.045586e-01 4.900300e-03 9.524810e-01 9.828282e-02 2.126281e-02 9.997026e-01 -1.194209e-02 -1.294576e+01 -9.522563e-01 2.388948e-02 3.043638e-01 8.635445e+01 +2.837215e-01 4.022541e-03 9.588983e-01 3.030783e-01 1.858077e-02 9.997804e-01 -9.691774e-03 -1.296404e+01 -9.587267e-01 2.056683e-02 2.835845e-01 8.639138e+01 +2.640160e-01 9.838918e-04 9.645178e-01 5.027926e-01 2.224615e-02 9.997272e-01 -7.109215e-03 -1.298825e+01 -9.642618e-01 2.333374e-02 2.639221e-01 8.641120e+01 +2.459354e-01 -2.389475e-03 9.692833e-01 7.015883e-01 2.804215e-02 9.995959e-01 -4.650911e-03 -1.300837e+01 -9.688805e-01 2.832460e-02 2.459031e-01 8.642735e+01 +2.291120e-01 -5.209211e-03 9.733861e-01 9.019939e-01 3.394554e-02 9.994202e-01 -2.641438e-03 -1.303051e+01 -9.728080e-01 3.364729e-02 2.291559e-01 8.644071e+01 +2.135231e-01 -8.011216e-03 9.769052e-01 1.103310e+00 3.553954e-02 9.993682e-01 4.275140e-04 -1.305331e+01 -9.762914e-01 3.462747e-02 2.136729e-01 8.646516e+01 +1.993577e-01 -9.516976e-03 9.798805e-01 1.306431e+00 3.299198e-02 9.994511e-01 2.994799e-03 -1.307499e+01 -9.793713e-01 3.173116e-02 1.995623e-01 8.649419e+01 +1.869175e-01 -8.778181e-03 9.823364e-01 1.502895e+00 2.920668e-02 9.995677e-01 3.374757e-03 -1.309925e+01 -9.819414e-01 2.805998e-02 1.870930e-01 8.651975e+01 +1.751466e-01 -6.818119e-03 9.845187e-01 1.691940e+00 2.820182e-02 9.996004e-01 1.905440e-03 -1.311590e+01 -9.841384e-01 2.743148e-02 1.752689e-01 8.654055e+01 +1.637954e-01 -2.516516e-03 9.864911e-01 1.881704e+00 3.355995e-02 9.994321e-01 -3.022715e-03 -1.311681e+01 -9.859234e-01 3.360169e-02 1.637869e-01 8.654444e+01 +1.520509e-01 1.943527e-03 9.883707e-01 2.077763e+00 4.169634e-02 9.990952e-01 -8.379182e-03 -1.311423e+01 -9.874928e-01 4.248549e-02 1.518323e-01 8.654586e+01 +1.389418e-01 3.361275e-03 9.902948e-01 2.277033e+00 4.544366e-02 9.989191e-01 -9.766454e-03 -1.311695e+01 -9.892574e-01 4.635958e-02 1.386389e-01 8.655546e+01 +1.265836e-01 3.169499e-03 9.919509e-01 2.482048e+00 4.218298e-02 9.990731e-01 -8.575259e-03 -1.312549e+01 -9.910587e-01 4.292892e-02 1.263325e-01 8.657120e+01 +1.144706e-01 3.195458e-03 9.934215e-01 2.683147e+00 3.723771e-02 9.992782e-01 -7.505152e-03 -1.312569e+01 -9.927285e-01 3.785185e-02 1.142690e-01 8.658709e+01 +1.032254e-01 4.507930e-03 9.946478e-01 2.885571e+00 3.511548e-02 9.993498e-01 -8.173558e-03 -1.311875e+01 -9.940380e-01 3.577124e-02 1.030000e-01 8.659724e+01 +9.375546e-02 5.817378e-03 9.955782e-01 3.081643e+00 3.571153e-02 9.993197e-01 -9.202267e-03 -1.310975e+01 -9.949546e-01 3.641638e-02 9.348394e-02 8.660154e+01 +8.700820e-02 8.718011e-03 9.961694e-01 3.293637e+00 3.835548e-02 9.991909e-01 -1.209453e-02 -1.310622e+01 -9.954690e-01 3.926087e-02 8.660342e-02 8.660479e+01 +8.208786e-02 1.417570e-02 9.965243e-01 3.516013e+00 4.188686e-02 9.989662e-01 -1.766084e-02 -1.310603e+01 -9.957445e-01 4.319100e-02 8.140923e-02 8.660922e+01 +8.019595e-02 1.884208e-02 9.966010e-01 3.761151e+00 4.148528e-02 9.988919e-01 -2.222370e-02 -1.311773e+01 -9.959155e-01 4.312651e-02 7.932541e-02 8.662538e+01 +8.023850e-02 2.202465e-02 9.965323e-01 4.026761e+00 3.831619e-02 9.989488e-01 -2.516320e-02 -1.312628e+01 -9.960390e-01 4.020237e-02 7.931025e-02 8.664934e+01 +7.997047e-02 2.257411e-02 9.965416e-01 4.313870e+00 3.622304e-02 9.990174e-01 -2.553702e-02 -1.312924e+01 -9.961389e-01 3.813996e-02 7.907418e-02 8.667473e+01 +7.975507e-02 2.025209e-02 9.966087e-01 4.619787e+00 3.582877e-02 9.990893e-01 -2.316975e-02 -1.313588e+01 -9.961704e-01 3.755516e-02 7.895683e-02 8.669699e+01 +7.988540e-02 1.866419e-02 9.966293e-01 4.934015e+00 3.681362e-02 9.990873e-01 -2.166105e-02 -1.314491e+01 -9.961241e-01 3.841992e-02 7.912539e-02 8.671819e+01 +7.920946e-02 1.810820e-02 9.966935e-01 5.259887e+00 3.621212e-02 9.991228e-01 -2.103020e-02 -1.315662e+01 -9.962001e-01 3.775817e-02 7.848424e-02 8.674158e+01 +7.852943e-02 1.684813e-02 9.967694e-01 5.591334e+00 3.387841e-02 9.992345e-01 -1.955888e-02 -1.315977e+01 -9.963360e-01 3.530490e-02 7.789853e-02 8.677090e+01 +7.799477e-02 1.474844e-02 9.968447e-01 5.930418e+00 2.968643e-02 9.994128e-01 -1.710916e-02 -1.316144e+01 -9.965117e-01 3.092718e-02 7.751115e-02 8.680205e+01 +7.724801e-02 1.327952e-02 9.969235e-01 6.263192e+00 3.042614e-02 9.994141e-01 -1.567032e-02 -1.314982e+01 -9.965476e-01 3.154302e-02 7.679871e-02 8.682523e+01 +7.568594e-02 1.128471e-02 9.970678e-01 6.608439e+00 3.051457e-02 9.994414e-01 -1.362789e-02 -1.314533e+01 -9.966647e-01 3.145653e-02 7.529931e-02 8.684440e+01 +7.304661e-02 9.982891e-03 9.972785e-01 6.950353e+00 3.024033e-02 9.994679e-01 -1.221979e-02 -1.313182e+01 -9.968700e-01 3.105064e-02 7.270586e-02 8.686023e+01 +7.161612e-02 1.038553e-02 9.973782e-01 7.296706e+00 2.964946e-02 9.994817e-01 -1.253640e-02 -1.312533e+01 -9.969915e-01 3.046953e-02 7.127108e-02 8.687800e+01 +7.007770e-02 1.008049e-02 9.974906e-01 7.634023e+00 2.873530e-02 9.995136e-01 -1.211971e-02 -1.313213e+01 -9.971276e-01 2.951251e-02 6.975394e-02 8.690135e+01 +6.765587e-02 7.464777e-03 9.976808e-01 7.989138e+00 2.830698e-02 9.995551e-01 -9.398391e-03 -1.314589e+01 -9.973071e-01 2.887717e-02 6.741447e-02 8.692498e+01 +6.513885e-02 4.520482e-03 9.978660e-01 8.350811e+00 3.111350e-02 9.994943e-01 -6.558895e-03 -1.315193e+01 -9.973911e-01 3.147434e-02 6.496526e-02 8.694342e+01 +6.229900e-02 4.388192e-03 9.980479e-01 8.711110e+00 3.517435e-02 9.993594e-01 -6.589576e-03 -1.314275e+01 -9.974376e-01 3.551620e-02 6.210474e-02 8.695845e+01 +5.890435e-02 2.402315e-03 9.982607e-01 9.082393e+00 3.853538e-02 9.992463e-01 -4.678547e-03 -1.314141e+01 -9.975196e-01 3.874393e-02 5.876737e-02 8.697131e+01 +5.281736e-02 1.548560e-03 9.986030e-01 9.452876e+00 3.768413e-02 9.992834e-01 -3.542779e-03 -1.314125e+01 -9.978929e-01 3.781860e-02 5.272115e-02 8.699041e+01 +4.490369e-02 2.734393e-03 9.989876e-01 9.832777e+00 3.295106e-02 9.994480e-01 -4.216781e-03 -1.314496e+01 -9.984478e-01 3.310704e-02 4.478881e-02 8.700973e+01 +3.715771e-02 3.469069e-03 9.993034e-01 1.021528e+01 2.900252e-02 9.995690e-01 -4.548413e-03 -1.317658e+01 -9.988885e-01 2.915132e-02 3.704108e-02 8.702338e+01 +2.957964e-02 3.835023e-03 9.995551e-01 1.060812e+01 2.923330e-02 9.995615e-01 -4.700147e-03 -1.321795e+01 -9.991349e-01 2.935931e-02 2.945456e-02 8.702462e+01 +2.251082e-02 5.705929e-03 9.997303e-01 1.100762e+01 3.272022e-02 9.994438e-01 -6.441056e-03 -1.327686e+01 -9.992110e-01 3.285638e-02 2.231160e-02 8.701152e+01 +1.540494e-02 9.053260e-03 9.998403e-01 1.142312e+01 3.738725e-02 9.992545e-01 -9.624000e-03 -1.334537e+01 -9.991821e-01 3.752952e-02 1.505498e-02 8.699864e+01 +7.270160e-03 1.270546e-02 9.998928e-01 1.184462e+01 4.297435e-02 9.989915e-01 -1.300647e-02 -1.341612e+01 -9.990498e-01 4.306429e-02 6.716818e-03 8.698005e+01 +-7.472961e-04 1.353510e-02 9.999081e-01 1.227539e+01 4.583242e-02 9.988581e-01 -1.348664e-02 -1.346959e+01 -9.989489e-01 4.581812e-02 -1.366791e-03 8.696512e+01 +-8.421991e-03 1.264579e-02 9.998846e-01 1.271677e+01 4.486694e-02 9.989178e-01 -1.225565e-02 -1.352541e+01 -9.989575e-01 4.475854e-02 -8.980256e-03 8.695381e+01 +-1.454217e-02 1.262422e-02 9.998145e-01 1.316724e+01 4.284340e-02 9.990098e-01 -1.199091e-02 -1.356427e+01 -9.989760e-01 4.266107e-02 -1.506864e-02 8.693837e+01 +-1.889366e-02 1.249284e-02 9.997434e-01 1.362634e+01 4.298862e-02 9.990074e-01 -1.167123e-02 -1.360213e+01 -9.988969e-01 4.275706e-02 -1.941195e-02 8.691815e+01 +-2.297309e-02 1.047136e-02 9.996812e-01 1.409859e+01 4.595618e-02 9.988991e-01 -9.407081e-03 -1.364202e+01 -9.986793e-01 4.572541e-02 -2.342903e-02 8.689198e+01 +-2.417799e-02 9.061420e-03 9.996666e-01 1.457915e+01 5.112875e-02 9.986615e-01 -7.815712e-03 -1.364973e+01 -9.983994e-01 5.092273e-02 -2.460893e-02 8.686266e+01 +-2.284509e-02 1.042951e-02 9.996846e-01 1.506999e+01 5.901044e-02 9.982162e-01 -9.065668e-03 -1.363822e+01 -9.979960e-01 5.878471e-02 -2.341979e-02 8.682517e+01 +-1.828795e-02 1.305639e-02 9.997475e-01 1.557231e+01 6.468326e-02 9.978355e-01 -1.184820e-02 -1.363298e+01 -9.977383e-01 6.445024e-02 -1.909290e-02 8.679790e+01 +-7.770624e-03 1.405872e-02 9.998710e-01 1.608976e+01 6.641957e-02 9.977003e-01 -1.351202e-02 -1.362863e+01 -9.977616e-01 6.630599e-02 -8.686530e-03 8.678537e+01 +9.013544e-03 1.367676e-02 9.998658e-01 1.661531e+01 6.716436e-02 9.976401e-01 -1.425179e-02 -1.363373e+01 -9.977012e-01 6.728379e-02 8.073681e-03 8.678522e+01 +2.956946e-02 1.281801e-02 9.994805e-01 1.715814e+01 6.614042e-02 9.977012e-01 -1.475195e-02 -1.363627e+01 -9.973721e-01 6.654225e-02 2.865369e-02 8.680577e+01 +5.010761e-02 1.083505e-02 9.986850e-01 1.771308e+01 6.368818e-02 9.978713e-01 -1.402169e-02 -1.364022e+01 -9.967111e-01 6.430701e-02 4.931088e-02 8.684078e+01 +6.918203e-02 6.472641e-03 9.975830e-01 1.828179e+01 6.097024e-02 9.980822e-01 -1.070415e-02 -1.364201e+01 -9.957392e-01 6.156340e-02 6.865471e-02 8.687774e+01 +8.553856e-02 3.565450e-03 9.963285e-01 1.886267e+01 5.506750e-02 9.984481e-01 -8.300792e-03 -1.365148e+01 -9.948119e-01 5.557534e-02 8.520947e-02 8.693860e+01 +9.952029e-02 4.640524e-03 9.950247e-01 1.944894e+01 4.758214e-02 9.988229e-01 -9.417307e-03 -1.366287e+01 -9.938972e-01 4.828260e-02 9.918234e-02 8.700522e+01 +1.087141e-01 8.750734e-03 9.940345e-01 2.004785e+01 3.862019e-02 9.991691e-01 -1.301970e-02 -1.367899e+01 -9.933226e-01 3.980521e-02 1.082859e-01 8.708199e+01 +1.120276e-01 1.457347e-02 9.935982e-01 2.065596e+01 3.505815e-02 9.992120e-01 -1.860860e-02 -1.368939e+01 -9.930865e-01 3.691838e-02 1.114284e-01 8.714939e+01 +1.114985e-01 2.055244e-02 9.935520e-01 2.127663e+01 3.261231e-02 9.991719e-01 -2.432852e-02 -1.369713e+01 -9.932294e-01 3.511461e-02 1.107359e-01 8.721085e+01 +1.071960e-01 2.172286e-02 9.940006e-01 2.190064e+01 3.168946e-02 9.991787e-01 -2.525352e-02 -1.367108e+01 -9.937328e-01 3.420641e-02 1.064196e-01 8.728574e+01 +1.005794e-01 1.875212e-02 9.947523e-01 2.253860e+01 2.901799e-02 9.993417e-01 -2.177265e-02 -1.364707e+01 -9.945058e-01 3.105559e-02 9.996902e-02 8.735687e+01 +9.141828e-02 1.179956e-02 9.957427e-01 2.319863e+01 2.794254e-02 9.995056e-01 -1.440953e-02 -1.363820e+01 -9.954205e-01 2.914087e-02 9.104337e-02 8.742121e+01 +8.190622e-02 6.076956e-03 9.966215e-01 2.386316e+01 2.775205e-02 9.995797e-01 -8.375769e-03 -1.361983e+01 -9.962536e-01 2.834431e-02 8.170315e-02 8.747515e+01 +7.255032e-02 4.886705e-03 9.973528e-01 2.453887e+01 2.970993e-02 9.995336e-01 -7.058581e-03 -1.361605e+01 -9.969222e-01 3.014337e-02 7.237130e-02 8.751801e+01 +6.377926e-02 6.577519e-03 9.979423e-01 2.521658e+01 2.905977e-02 9.995420e-01 -8.445299e-03 -1.360546e+01 -9.975409e-01 2.953860e-02 6.355891e-02 8.755909e+01 +5.502244e-02 1.193307e-02 9.984138e-01 2.590204e+01 2.871395e-02 9.994961e-01 -1.352843e-02 -1.361256e+01 -9.980722e-01 2.941276e-02 5.465207e-02 8.759195e+01 +4.722573e-02 1.719195e-02 9.987363e-01 2.658988e+01 2.901949e-02 9.994062e-01 -1.857569e-02 -1.363692e+01 -9.984627e-01 2.986006e-02 4.669879e-02 8.761223e+01 +4.069843e-02 1.862035e-02 9.989979e-01 2.729646e+01 2.809474e-02 9.994097e-01 -1.977259e-02 -1.366489e+01 -9.987764e-01 2.887129e-02 4.015127e-02 8.762920e+01 +3.595409e-02 1.581124e-02 9.992283e-01 2.801058e+01 2.504240e-02 9.995466e-01 -1.671736e-02 -1.369350e+01 -9.990397e-01 2.562413e-02 3.554183e-02 8.764384e+01 +3.208600e-02 1.258016e-02 9.994059e-01 2.872790e+01 2.253922e-02 9.996574e-01 -1.330696e-02 -1.372097e+01 -9.992310e-01 2.295279e-02 3.179146e-02 8.765976e+01 +2.938316e-02 1.134471e-02 9.995038e-01 2.944184e+01 2.307690e-02 9.996613e-01 -1.202491e-02 -1.373489e+01 -9.993018e-01 2.341878e-02 2.911141e-02 8.766253e+01 +2.691807e-02 9.708204e-03 9.995905e-01 3.016167e+01 2.247743e-02 9.996941e-01 -1.031451e-02 -1.374744e+01 -9.993849e-01 2.274587e-02 2.669162e-02 8.766624e+01 +2.411184e-02 7.689312e-03 9.996797e-01 3.088140e+01 2.270758e-02 9.997082e-01 -8.237233e-03 -1.375863e+01 -9.994514e-01 2.289891e-02 2.393019e-02 8.766700e+01 +2.200384e-02 5.324753e-03 9.997437e-01 3.159982e+01 2.135169e-02 9.997552e-01 -5.794759e-03 -1.377044e+01 -9.995299e-01 2.147372e-02 2.188476e-02 8.766402e+01 +2.056053e-02 3.438516e-03 9.997827e-01 3.232010e+01 2.184365e-02 9.997538e-01 -3.887635e-03 -1.378344e+01 -9.995500e-01 2.191883e-02 2.048035e-02 8.766423e+01 +1.962887e-02 9.054140e-03 9.997663e-01 3.303276e+01 2.269397e-02 9.996973e-01 -9.499081e-03 -1.380039e+01 -9.995498e-01 2.287511e-02 1.941745e-02 8.766180e+01 +1.953806e-02 1.462722e-02 9.997021e-01 3.374607e+01 2.296221e-02 9.996226e-01 -1.507483e-02 -1.381768e+01 -9.995454e-01 2.324990e-02 1.919481e-02 8.766239e+01 +1.939462e-02 1.918927e-02 9.996277e-01 3.445759e+01 2.323912e-02 9.995370e-01 -1.963842e-02 -1.382760e+01 -9.995418e-01 2.361135e-02 1.893969e-02 8.765977e+01 +1.885954e-02 1.724313e-02 9.996734e-01 3.517599e+01 2.233347e-02 9.995945e-01 -1.766311e-02 -1.384318e+01 -9.995727e-01 2.265929e-02 1.846679e-02 8.766425e+01 +1.906906e-02 1.466973e-02 9.997105e-01 3.589110e+01 2.254756e-02 9.996317e-01 -1.509867e-02 -1.388990e+01 -9.995639e-01 2.282894e-02 1.873127e-02 8.766450e+01 +1.963137e-02 1.364790e-02 9.997141e-01 3.660581e+01 2.163888e-02 9.996668e-01 -1.407218e-02 -1.392921e+01 -9.995731e-01 2.190894e-02 1.932950e-02 8.767187e+01 +2.080437e-02 1.533139e-02 9.996660e-01 3.731152e+01 1.972459e-02 9.996815e-01 -1.574213e-02 -1.396612e+01 -9.995890e-01 2.004550e-02 2.049533e-02 8.767542e+01 +2.169407e-02 1.500544e-02 9.996520e-01 3.802164e+01 1.597251e-02 9.997545e-01 -1.535361e-02 -1.399565e+01 -9.996371e-01 1.630003e-02 2.144907e-02 8.768610e+01 +2.201022e-02 1.185138e-02 9.996875e-01 3.873077e+01 1.445355e-02 9.998214e-01 -1.217120e-02 -1.403121e+01 -9.996533e-01 1.471692e-02 2.183499e-02 8.769344e+01 +2.302407e-02 7.572996e-03 9.997062e-01 3.944026e+01 1.403235e-02 9.998703e-01 -7.897421e-03 -1.407721e+01 -9.996365e-01 1.421005e-02 2.291481e-02 8.770061e+01 +2.392422e-02 4.673617e-03 9.997028e-01 4.014757e+01 1.063978e-02 9.999312e-01 -4.929314e-03 -1.411774e+01 -9.996572e-01 1.075455e-02 2.387284e-02 8.771362e+01 +2.487665e-02 6.346795e-03 9.996704e-01 4.084547e+01 4.151438e-03 9.999705e-01 -6.452014e-03 -1.415994e+01 -9.996819e-01 4.310571e-03 2.484956e-02 8.773024e+01 +2.697291e-02 9.350919e-03 9.995924e-01 4.153973e+01 1.965888e-03 9.999538e-01 -9.407353e-03 -1.420664e+01 -9.996343e-01 2.218828e-03 2.695328e-02 8.774686e+01 +2.924018e-02 1.523915e-02 9.994562e-01 4.222801e+01 2.115658e-03 9.998806e-01 -1.530752e-02 -1.425652e+01 -9.995702e-01 2.562100e-03 2.920444e-02 8.775987e+01 +3.209270e-02 1.959504e-02 9.992928e-01 4.291778e+01 4.105838e-04 9.998074e-01 -1.961832e-02 -1.430052e+01 -9.994848e-01 1.039896e-03 3.207848e-02 8.778019e+01 +3.520154e-02 2.061691e-02 9.991675e-01 4.360832e+01 -5.948750e-03 9.997738e-01 -2.041984e-02 -1.434479e+01 -9.993626e-01 -5.224989e-03 3.531622e-02 8.781032e+01 +3.869312e-02 2.066278e-02 9.990375e-01 4.429829e+01 -6.837369e-03 9.997682e-01 -2.041309e-02 -1.438295e+01 -9.992278e-01 -6.040942e-03 3.882543e-02 8.783612e+01 +4.159806e-02 2.110229e-02 9.989115e-01 4.498282e+01 -5.229850e-03 9.997678e-01 -2.090260e-02 -1.442459e+01 -9.991208e-01 -4.354651e-03 4.169876e-02 8.785500e+01 +4.298133e-02 2.457196e-02 9.987736e-01 4.566718e+01 -2.559188e-03 9.996969e-01 -2.448455e-02 -1.446193e+01 -9.990726e-01 -1.503673e-03 4.303119e-02 8.787754e+01 +4.286130e-02 3.012721e-02 9.986267e-01 4.634792e+01 -4.819177e-03 9.995398e-01 -2.994793e-02 -1.450467e+01 -9.990694e-01 -3.528953e-03 4.298676e-02 8.790733e+01 +4.220185e-02 3.164506e-02 9.986078e-01 4.702915e+01 -5.798724e-03 9.994892e-01 -3.142794e-02 -1.454331e+01 -9.990923e-01 -4.464335e-03 4.236379e-02 8.793411e+01 +4.224490e-02 3.173309e-02 9.986032e-01 4.771451e+01 -1.445068e-03 9.994963e-01 -3.170035e-02 -1.458162e+01 -9.991063e-01 -1.038736e-04 4.226948e-02 8.795083e+01 +4.114626e-02 2.857432e-02 9.987444e-01 4.840135e+01 2.322952e-03 9.995855e-01 -2.869409e-02 -1.461848e+01 -9.991505e-01 3.500688e-03 4.106283e-02 8.796838e+01 +4.000793e-02 2.494983e-02 9.988878e-01 4.908854e+01 4.179244e-03 9.996753e-01 -2.513690e-02 -1.465471e+01 -9.991907e-01 5.180268e-03 3.989066e-02 8.798807e+01 +3.896529e-02 2.226050e-02 9.989926e-01 4.977449e+01 4.596916e-03 9.997372e-01 -2.245640e-02 -1.469011e+01 -9.992300e-01 5.467302e-03 3.885273e-02 8.801086e+01 +3.809171e-02 2.216880e-02 9.990283e-01 5.045512e+01 5.416087e-03 9.997346e-01 -2.239099e-02 -1.472473e+01 -9.992596e-01 6.263732e-03 3.796153e-02 8.803219e+01 +3.763997e-02 2.561292e-02 9.989631e-01 5.113119e+01 8.993658e-03 9.996223e-01 -2.596870e-02 -1.475707e+01 -9.992509e-01 9.961789e-03 3.739540e-02 8.804672e+01 +3.737338e-02 2.690332e-02 9.989391e-01 5.180954e+01 1.434668e-02 9.995200e-01 -2.745573e-02 -1.478580e+01 -9.991984e-01 1.535757e-02 3.696947e-02 8.805978e+01 +3.684390e-02 2.850897e-02 9.989143e-01 5.249347e+01 1.661520e-02 9.994373e-01 -2.913675e-02 -1.482097e+01 -9.991829e-01 1.767067e-02 3.634949e-02 8.807222e+01 +3.651865e-02 2.690454e-02 9.989707e-01 5.317889e+01 1.683313e-02 9.994791e-01 -2.753360e-02 -1.486017e+01 -9.991912e-01 1.782129e-02 3.604674e-02 8.808874e+01 +3.690872e-02 2.296740e-02 9.990547e-01 5.386694e+01 1.754538e-02 9.995668e-01 -2.362737e-02 -1.489489e+01 -9.991646e-01 1.840085e-02 3.648976e-02 8.810164e+01 +3.763266e-02 2.412379e-02 9.990004e-01 5.454716e+01 2.025233e-02 9.994848e-01 -2.489841e-02 -1.492385e+01 -9.990864e-01 2.116907e-02 3.712471e-02 8.811260e+01 +3.842795e-02 2.271727e-02 9.990031e-01 5.522872e+01 1.692514e-02 9.995833e-01 -2.338152e-02 -1.495113e+01 -9.991181e-01 1.780677e-02 3.802744e-02 8.813189e+01 +3.807350e-02 2.277774e-02 9.990153e-01 5.590659e+01 1.295288e-02 9.996449e-01 -2.328575e-02 -1.498369e+01 -9.991910e-01 1.382669e-02 3.776494e-02 8.815958e+01 +3.729109e-02 2.361913e-02 9.990253e-01 5.658473e+01 1.274908e-02 9.996280e-01 -2.410928e-02 -1.501502e+01 -9.992231e-01 1.363571e-02 3.697609e-02 8.817633e+01 +3.648551e-02 2.398779e-02 9.990462e-01 5.725727e+01 1.386935e-02 9.996034e-01 -2.450769e-02 -1.503968e+01 -9.992380e-01 1.475029e-02 3.613835e-02 8.818993e+01 +3.424501e-02 2.699159e-02 9.990489e-01 5.793245e+01 1.359550e-02 9.995301e-01 -2.747063e-02 -1.506027e+01 -9.993210e-01 1.452330e-02 3.386195e-02 8.820379e+01 +3.328378e-02 2.447586e-02 9.991462e-01 5.860913e+01 8.130511e-03 9.996604e-01 -2.475931e-02 -1.508760e+01 -9.994129e-01 8.947649e-03 3.307348e-02 8.822442e+01 +3.399432e-02 2.296946e-02 9.991580e-01 5.928424e+01 1.391174e-02 9.996281e-01 -2.345359e-02 -1.511301e+01 -9.993252e-01 1.469731e-02 3.366213e-02 8.823139e+01 +3.384799e-02 2.308723e-02 9.991603e-01 5.995920e+01 1.953446e-02 9.995269e-01 -2.375747e-02 -1.514171e+01 -9.992361e-01 2.032220e-02 3.338098e-02 8.823674e+01 +3.290952e-02 2.342592e-02 9.991837e-01 6.063219e+01 2.166379e-02 9.994737e-01 -2.414626e-02 -1.516068e+01 -9.992236e-01 2.244075e-02 3.238471e-02 8.824647e+01 +3.244706e-02 2.339305e-02 9.991996e-01 6.130787e+01 1.638255e-02 9.995793e-01 -2.393393e-02 -1.517029e+01 -9.993392e-01 1.714601e-02 3.205017e-02 8.826811e+01 +3.155519e-02 2.256456e-02 9.992473e-01 6.198468e+01 1.381992e-02 9.996397e-01 -2.300985e-02 -1.518634e+01 -9.994065e-01 1.453559e-02 3.123198e-02 8.829051e+01 +3.254819e-02 2.264501e-02 9.992136e-01 6.266091e+01 1.579771e-02 9.996067e-01 -2.316852e-02 -1.520528e+01 -9.993453e-01 1.653937e-02 3.217765e-02 8.830376e+01 +3.341557e-02 2.253334e-02 9.991875e-01 6.333345e+01 2.214435e-02 9.994837e-01 -2.328059e-02 -1.522943e+01 -9.991962e-01 2.290428e-02 3.289933e-02 8.831323e+01 +3.367752e-02 2.882616e-02 9.990169e-01 6.401181e+01 2.411411e-02 9.992695e-01 -2.964636e-02 -1.525055e+01 -9.991418e-01 2.508882e-02 3.295780e-02 8.832356e+01 +3.401310e-02 3.410429e-02 9.988393e-01 6.469081e+01 2.317194e-02 9.991220e-01 -3.490302e-02 -1.528103e+01 -9.991528e-01 2.433219e-02 3.319297e-02 8.833835e+01 +3.433960e-02 3.339001e-02 9.988523e-01 6.538359e+01 2.052920e-02 9.992073e-01 -3.410766e-02 -1.531189e+01 -9.991994e-01 2.167687e-02 3.362691e-02 8.835395e+01 +3.432593e-02 3.043335e-02 9.989472e-01 6.607095e+01 1.973438e-02 9.993207e-01 -3.112286e-02 -1.534356e+01 -9.992159e-01 2.078192e-02 3.370203e-02 8.837065e+01 +3.428855e-02 2.430485e-02 9.991164e-01 6.676178e+01 2.008704e-02 9.994855e-01 -2.500321e-02 -1.538984e+01 -9.992101e-01 2.092661e-02 3.378269e-02 8.838111e+01 +3.415462e-02 1.947533e-02 9.992268e-01 6.744648e+01 2.077926e-02 9.995801e-01 -2.019248e-02 -1.542838e+01 -9.992006e-01 2.145285e-02 3.373559e-02 8.839197e+01 +3.369556e-02 1.929161e-02 9.992459e-01 6.812663e+01 1.944027e-02 9.996119e-01 -1.995423e-02 -1.546572e+01 -9.992431e-01 2.009797e-02 3.330745e-02 8.840529e+01 +3.301412e-02 2.259976e-02 9.991993e-01 6.880160e+01 1.611902e-02 9.996022e-01 -2.314146e-02 -1.549917e+01 -9.993249e-01 1.687011e-02 3.263671e-02 8.842499e+01 +3.212938e-02 2.642993e-02 9.991342e-01 6.948309e+01 1.730620e-02 9.994857e-01 -2.699576e-02 -1.552742e+01 -9.993339e-01 1.815857e-02 3.165545e-02 8.843219e+01 +3.215699e-02 2.818602e-02 9.990853e-01 7.017091e+01 1.980096e-02 9.993881e-01 -2.883190e-02 -1.555222e+01 -9.992867e-01 2.070998e-02 3.157920e-02 8.842849e+01 +3.135699e-02 2.565331e-02 9.991790e-01 7.085849e+01 2.296234e-02 9.993882e-01 -2.637931e-02 -1.557332e+01 -9.992445e-01 2.377066e-02 3.074874e-02 8.842794e+01 +3.043444e-02 1.966886e-02 9.993432e-01 7.155119e+01 1.852804e-02 9.996235e-01 -2.023864e-02 -1.559350e+01 -9.993651e-01 1.913182e-02 3.005855e-02 8.843695e+01 +2.940287e-02 1.524796e-02 9.994513e-01 7.223558e+01 1.652523e-02 9.997395e-01 -1.573852e-02 -1.560720e+01 -9.994311e-01 1.697891e-02 2.914323e-02 8.844523e+01 +2.927289e-02 1.681569e-02 9.994300e-01 7.291712e+01 1.931412e-02 9.996623e-01 -1.738531e-02 -1.563086e+01 -9.993849e-01 1.981202e-02 2.893822e-02 8.844509e+01 +2.865181e-02 2.037933e-02 9.993817e-01 7.359028e+01 2.077715e-02 9.995640e-01 -2.097872e-02 -1.564884e+01 -9.993735e-01 2.136537e-02 2.821590e-02 8.844979e+01 +2.726997e-02 2.396349e-02 9.993408e-01 7.427142e+01 1.801193e-02 9.995385e-01 -2.445975e-02 -1.566061e+01 -9.994659e-01 1.866707e-02 2.682575e-02 8.845143e+01 +2.638979e-02 2.329660e-02 9.993802e-01 7.495382e+01 2.050665e-02 9.995054e-01 -2.384103e-02 -1.568390e+01 -9.994414e-01 2.112310e-02 2.589900e-02 8.845245e+01 +2.627643e-02 1.681580e-02 9.995133e-01 7.564244e+01 2.352015e-02 9.995713e-01 -1.743511e-02 -1.571369e+01 -9.993780e-01 2.396683e-02 2.586966e-02 8.844749e+01 +2.552765e-02 1.688593e-02 9.995315e-01 7.632423e+01 2.393180e-02 9.995604e-01 -1.749764e-02 -1.574535e+01 -9.993877e-01 2.436725e-02 2.511231e-02 8.845147e+01 +2.449667e-02 2.094281e-02 9.994805e-01 7.699803e+01 2.214472e-02 9.995238e-01 -2.148648e-02 -1.576654e+01 -9.994546e-01 2.265956e-02 2.402123e-02 8.845743e+01 +2.500632e-02 2.371047e-02 9.994061e-01 7.767564e+01 2.686902e-02 9.993416e-01 -2.438124e-02 -1.578955e+01 -9.993262e-01 2.746274e-02 2.435278e-02 8.845484e+01 +2.563743e-02 2.655723e-02 9.993185e-01 7.835146e+01 3.357145e-02 9.990603e-01 -2.741165e-02 -1.581538e+01 -9.991075e-01 3.425132e-02 2.472177e-02 8.844774e+01 +2.451213e-02 2.602204e-02 9.993608e-01 7.903142e+01 3.312504e-02 9.990911e-01 -2.682751e-02 -1.584922e+01 -9.991506e-01 3.376145e-02 2.362787e-02 8.845316e+01 +2.435738e-02 3.027119e-02 9.992449e-01 7.970583e+01 3.176629e-02 9.990132e-01 -3.103851e-02 -1.588260e+01 -9.991985e-01 3.249831e-02 2.337174e-02 8.846102e+01 +2.507529e-02 3.501628e-02 9.990721e-01 8.037887e+01 3.161365e-02 9.988587e-01 -3.580227e-02 -1.590964e+01 -9.991856e-01 3.248206e-02 2.393968e-02 8.846493e+01 +2.545241e-02 3.168801e-02 9.991737e-01 8.105927e+01 3.197220e-02 9.989603e-01 -3.249570e-02 -1.593749e+01 -9.991647e-01 3.277286e-02 2.441281e-02 8.847053e+01 +2.579492e-02 2.544723e-02 9.993433e-01 8.174404e+01 2.990602e-02 9.992088e-01 -2.621574e-02 -1.596450e+01 -9.992199e-01 3.056261e-02 2.501348e-02 8.848029e+01 +2.664393e-02 1.778193e-02 9.994868e-01 8.242815e+01 2.833465e-02 9.994266e-01 -1.853620e-02 -1.599788e+01 -9.992434e-01 2.881398e-02 2.612480e-02 8.849132e+01 +2.756840e-02 1.575054e-02 9.994958e-01 8.310864e+01 2.978131e-02 9.994190e-01 -1.657078e-02 -1.602927e+01 -9.991762e-01 3.022311e-02 2.708331e-02 8.849848e+01 +2.827093e-02 2.063571e-02 9.993873e-01 8.377458e+01 3.088444e-02 9.992915e-01 -2.150741e-02 -1.605902e+01 -9.991231e-01 3.147354e-02 2.761358e-02 8.851140e+01 +2.881433e-02 2.522364e-02 9.992665e-01 8.444157e+01 3.223946e-02 9.991380e-01 -2.615005e-02 -1.608380e+01 -9.990648e-01 3.296930e-02 2.797629e-02 8.852570e+01 +2.976307e-02 2.349611e-02 9.992808e-01 8.511770e+01 3.141826e-02 9.992077e-01 -2.443018e-02 -1.611276e+01 -9.990631e-01 3.212278e-02 2.900128e-02 8.854164e+01 +3.064349e-02 1.786541e-02 9.993707e-01 8.579934e+01 3.190988e-02 9.993131e-01 -1.884283e-02 -1.614508e+01 -9.990209e-01 3.246720e-02 3.005236e-02 8.855711e+01 +3.103163e-02 1.113837e-02 9.994563e-01 8.647887e+01 3.896560e-02 9.991643e-01 -1.234494e-02 -1.617584e+01 -9.987586e-01 3.932749e-02 3.057168e-02 8.856505e+01 +3.197627e-02 1.396223e-02 9.993911e-01 8.714485e+01 4.278196e-02 9.989669e-01 -1.532515e-02 -1.620936e+01 -9.985726e-01 4.324594e-02 3.134590e-02 8.857827e+01 +3.116755e-02 2.345284e-02 9.992390e-01 8.780442e+01 3.937154e-02 9.989199e-01 -2.467341e-02 -1.624655e+01 -9.987385e-01 4.011057e-02 3.021051e-02 8.860116e+01 +3.025242e-02 3.203766e-02 9.990287e-01 8.846582e+01 3.548178e-02 9.988218e-01 -3.310549e-02 -1.628173e+01 -9.989124e-01 3.644883e-02 2.908003e-02 8.862550e+01 +3.112049e-02 3.602487e-02 9.988662e-01 8.913379e+01 3.952681e-02 9.985241e-01 -3.724403e-02 -1.631026e+01 -9.987338e-01 4.064104e-02 2.965061e-02 8.863569e+01 +3.177645e-02 3.165707e-02 9.989935e-01 8.980692e+01 4.503656e-02 9.984377e-01 -3.307201e-02 -1.634233e+01 -9.984799e-01 4.604213e-02 3.030108e-02 8.864363e+01 +3.046552e-02 2.416015e-02 9.992438e-01 9.048183e+01 4.094785e-02 9.988384e-01 -2.539880e-02 -1.638039e+01 -9.986967e-01 4.169066e-02 2.944083e-02 8.866567e+01 +2.996856e-02 2.338316e-02 9.992773e-01 9.114708e+01 3.626575e-02 9.990426e-01 -2.446530e-02 -1.642007e+01 -9.988928e-01 3.697272e-02 2.909186e-02 8.869024e+01 +3.037967e-02 2.969240e-02 9.990973e-01 9.180337e+01 3.777087e-02 9.988106e-01 -3.083239e-02 -1.645289e+01 -9.988246e-01 3.867344e-02 2.922203e-02 8.870477e+01 +3.090159e-02 3.626067e-02 9.988645e-01 9.245944e+01 4.211416e-02 9.984070e-01 -3.754695e-02 -1.648772e+01 -9.986348e-01 4.322659e-02 2.932528e-02 8.871157e+01 +3.078766e-02 3.814751e-02 9.987977e-01 9.310664e+01 4.469231e-02 9.982194e-01 -3.950306e-02 -1.651409e+01 -9.985263e-01 4.585477e-02 2.902794e-02 8.872189e+01 +3.016948e-02 3.410613e-02 9.989627e-01 9.375402e+01 4.232058e-02 9.984779e-01 -3.536770e-02 -1.654319e+01 -9.986485e-01 4.334370e-02 2.868016e-02 8.873808e+01 +2.952790e-02 2.675082e-02 9.992059e-01 9.439649e+01 3.769158e-02 9.989011e-01 -2.785650e-02 -1.657129e+01 -9.988531e-01 3.848418e-02 2.848717e-02 8.875927e+01 +2.893638e-02 2.299069e-02 9.993168e-01 9.503801e+01 3.387217e-02 9.991387e-01 -2.396741e-02 -1.660196e+01 -9.990072e-01 3.454255e-02 2.813272e-02 8.877754e+01 +2.866172e-02 2.289041e-02 9.993270e-01 9.567050e+01 3.411695e-02 9.991329e-01 -2.386448e-02 -1.662892e+01 -9.990068e-01 3.477798e-02 2.785591e-02 8.879039e+01 +2.845176e-02 2.543491e-02 9.992715e-01 9.629654e+01 3.457639e-02 9.990529e-01 -2.641383e-02 -1.665076e+01 -9.989970e-01 3.530271e-02 2.754536e-02 8.880139e+01 +2.708693e-02 2.668364e-02 9.992769e-01 9.691876e+01 3.563473e-02 9.989825e-01 -2.764172e-02 -1.667075e+01 -9.989978e-01 3.635769e-02 2.610851e-02 8.881342e+01 +2.596987e-02 2.429516e-02 9.993674e-01 9.753839e+01 3.787009e-02 9.989631e-01 -2.526944e-02 -1.669402e+01 -9.989452e-01 3.850237e-02 2.502288e-02 8.882200e+01 +2.538502e-02 2.206455e-02 9.994342e-01 9.814795e+01 3.613143e-02 9.990829e-01 -2.297452e-02 -1.672162e+01 -9.990246e-01 3.669418e-02 2.456451e-02 8.883362e+01 +2.476056e-02 2.127521e-02 9.994670e-01 9.874467e+01 3.347946e-02 9.991950e-01 -2.209884e-02 -1.675059e+01 -9.991327e-01 3.400879e-02 2.402834e-02 8.884704e+01 +2.428647e-02 2.249254e-02 9.994520e-01 9.932299e+01 3.218609e-02 9.992110e-01 -2.326924e-02 -1.677407e+01 -9.991868e-01 3.273357e-02 2.354336e-02 8.885973e+01 +2.429471e-02 2.344625e-02 9.994298e-01 9.988476e+01 3.785461e-02 9.989864e-01 -2.435605e-02 -1.679405e+01 -9.989879e-01 3.842474e-02 2.338253e-02 8.885898e+01 +2.467326e-02 2.710185e-02 9.993281e-01 1.004287e+02 4.827389e-02 9.984340e-01 -2.826949e-02 -1.681503e+01 -9.985294e-01 4.893894e-02 2.332631e-02 8.885029e+01 +2.361814e-02 2.591373e-02 9.993851e-01 1.009549e+02 4.878867e-02 9.984430e-01 -2.704232e-02 -1.683881e+01 -9.985299e-01 4.939734e-02 2.231707e-02 8.885680e+01 +2.258402e-02 2.279865e-02 9.994849e-01 1.014655e+02 4.293770e-02 9.987953e-01 -2.375313e-02 -1.686550e+01 -9.988225e-01 4.345201e-02 2.157789e-02 8.887203e+01 +2.171446e-02 2.105462e-02 9.995425e-01 1.019474e+02 4.034980e-02 9.989452e-01 -2.191862e-02 -1.688103e+01 -9.989497e-01 4.080728e-02 2.084201e-02 8.888524e+01 +2.185005e-02 2.061899e-02 9.995486e-01 1.024094e+02 4.359666e-02 9.988166e-01 -2.155692e-02 -1.690076e+01 -9.988103e-01 4.404799e-02 2.092527e-02 8.888503e+01 +2.178612e-02 2.065687e-02 9.995492e-01 1.028435e+02 4.856862e-02 9.985842e-01 -2.169554e-02 -1.693057e+01 -9.985823e-01 4.901937e-02 2.075200e-02 8.887637e+01 +2.108392e-02 2.133731e-02 9.995500e-01 1.032608e+02 5.074009e-02 9.984610e-01 -2.238436e-02 -1.695960e+01 -9.984893e-01 5.118919e-02 1.996881e-02 8.887203e+01 +1.974662e-02 2.249066e-02 9.995520e-01 1.036605e+02 4.996880e-02 9.984753e-01 -2.345360e-02 -1.698403e+01 -9.985556e-01 5.040953e-02 1.859268e-02 8.887301e+01 +1.858219e-02 2.305223e-02 9.995615e-01 1.040456e+02 4.758240e-02 9.985810e-01 -2.391420e-02 -1.700250e+01 -9.986945e-01 4.800591e-02 1.745893e-02 8.887543e+01 +1.753915e-02 2.161129e-02 9.996126e-01 1.044182e+02 4.730906e-02 9.986286e-01 -2.242011e-02 -1.701972e+01 -9.987263e-01 4.768395e-02 1.649268e-02 8.887372e+01 +1.663953e-02 1.909111e-02 9.996793e-01 1.047735e+02 5.161234e-02 9.984683e-01 -1.992707e-02 -1.703893e+01 -9.985286e-01 5.192735e-02 1.562871e-02 8.886329e+01 +1.624635e-02 1.666007e-02 9.997292e-01 1.051105e+02 5.651821e-02 9.982472e-01 -1.755384e-02 -1.705812e+01 -9.982694e-01 5.678807e-02 1.527628e-02 8.885152e+01 +1.527135e-02 1.720543e-02 9.997353e-01 1.054234e+02 5.892941e-02 9.980984e-01 -1.807743e-02 -1.707264e+01 -9.981454e-01 5.918986e-02 1.422840e-02 8.884541e+01 +1.463287e-02 1.638560e-02 9.997587e-01 1.057182e+02 5.775720e-02 9.981824e-01 -1.720513e-02 -1.708646e+01 -9.982234e-01 5.799501e-02 1.365988e-02 8.884454e+01 +1.482024e-02 1.469853e-02 9.997821e-01 1.059929e+02 5.559668e-02 9.983329e-01 -1.550136e-02 -1.709896e+01 -9.983433e-01 5.581429e-02 1.397834e-02 8.884411e+01 +1.434653e-02 1.322969e-02 9.998095e-01 1.062465e+02 5.322459e-02 9.984847e-01 -1.397590e-02 -1.711092e+01 -9.984795e-01 5.341495e-02 1.362064e-02 8.884408e+01 +1.379578e-02 1.307416e-02 9.998193e-01 1.064758e+02 5.022718e-02 9.986431e-01 -1.375183e-02 -1.711947e+01 -9.986426e-01 5.040781e-02 1.312038e-02 8.884530e+01 +1.435595e-02 1.390925e-02 9.998002e-01 1.066828e+02 4.887423e-02 9.986983e-01 -1.459570e-02 -1.712591e+01 -9.987018e-01 4.907399e-02 1.365745e-02 8.884542e+01 +1.676930e-02 1.647829e-02 9.997236e-01 1.068866e+02 4.921162e-02 9.986388e-01 -1.728589e-02 -1.713072e+01 -9.986476e-01 4.948788e-02 1.593555e-02 8.884188e+01 +2.144992e-02 1.868220e-02 9.995953e-01 1.070809e+02 5.085328e-02 9.985107e-01 -1.975318e-02 -1.713812e+01 -9.984758e-01 5.125639e-02 2.046792e-02 8.883595e+01 +2.946911e-02 2.058305e-02 9.993537e-01 1.072689e+02 5.091163e-02 9.984593e-01 -2.206593e-02 -1.714754e+01 -9.982683e-01 5.152898e-02 2.837579e-02 8.883582e+01 +4.253204e-02 2.181746e-02 9.988568e-01 1.074387e+02 5.198004e-02 9.983592e-01 -2.401994e-02 -1.715600e+01 -9.977420e-01 5.294222e-02 4.132818e-02 8.884528e+01 +6.022588e-02 2.234198e-02 9.979347e-01 1.076001e+02 5.119542e-02 9.983645e-01 -2.544128e-02 -1.716089e+01 -9.968711e-01 5.262190e-02 5.898357e-02 8.886355e+01 +7.925448e-02 2.002915e-02 9.966532e-01 1.077616e+02 5.092130e-02 9.984115e-01 -2.411378e-02 -1.716735e+01 -9.955530e-01 5.266199e-02 7.810867e-02 8.889490e+01 +1.009060e-01 1.604839e-02 9.947665e-01 1.079248e+02 5.147866e-02 9.984463e-01 -2.132960e-02 -1.717354e+01 -9.935633e-01 5.336152e-02 9.992305e-02 8.893345e+01 +1.280227e-01 1.207749e-02 9.916977e-01 1.080757e+02 5.158707e-02 9.984911e-01 -1.881983e-02 -1.718016e+01 -9.904287e-01 5.356813e-02 1.272065e-01 8.896691e+01 +1.576676e-01 9.398845e-03 9.874475e-01 1.082291e+02 4.762616e-02 9.987186e-01 -1.711069e-02 -1.718791e+01 -9.863431e-01 4.972613e-02 1.570179e-01 8.902650e+01 +1.882122e-01 8.584161e-03 9.820909e-01 1.083647e+02 4.228768e-02 9.989636e-01 -1.683584e-02 -1.719075e+01 -9.812176e-01 4.469904e-02 1.876542e-01 8.908026e+01 +2.235777e-01 7.752872e-03 9.746552e-01 1.085069e+02 3.518337e-02 9.992525e-01 -1.601930e-02 -1.719875e+01 -9.740509e-01 3.787320e-02 2.231378e-01 8.916170e+01 +2.614428e-01 7.590678e-03 9.651891e-01 1.086443e+02 2.795099e-02 9.994901e-01 -1.543158e-02 -1.720721e+01 -9.648142e-01 3.101246e-02 2.610974e-01 8.925337e+01 +2.976063e-01 9.281206e-03 9.546436e-01 1.087601e+02 1.971678e-02 9.996797e-01 -1.586569e-02 -1.721160e+01 -9.544851e-01 2.354422e-02 2.973280e-01 8.932492e+01 +3.328235e-01 1.219414e-02 9.429103e-01 1.088879e+02 1.054708e-02 9.998057e-01 -1.665279e-02 -1.721840e+01 -9.429302e-01 1.548739e-02 3.326303e-01 8.942965e+01 +3.702631e-01 1.392877e-02 9.288225e-01 1.090185e+02 5.170141e-03 9.998412e-01 -1.705479e-02 -1.722495e+01 -9.289126e-01 1.111690e-02 3.701323e-01 8.953916e+01 +4.093683e-01 1.552270e-02 9.122371e-01 1.091311e+02 6.016883e-04 9.998504e-01 -1.728355e-02 -1.722814e+01 -9.123690e-01 7.624217e-03 4.092978e-01 8.962432e+01 +4.482418e-01 1.712549e-02 8.937483e-01 1.092675e+02 -4.168114e-03 9.998456e-01 -1.706803e-02 -1.723701e+01 -8.939027e-01 3.925360e-03 4.482440e-01 8.975289e+01 +4.875589e-01 1.898566e-02 8.728836e-01 1.093809e+02 -1.087591e-02 9.998180e-01 -1.567169e-02 -1.724215e+01 -8.730224e-01 -1.852530e-03 4.876767e-01 8.985901e+01 +5.278163e-01 2.030575e-02 8.491158e-01 1.095146e+02 -1.867666e-02 9.997499e-01 -1.229848e-02 -1.725340e+01 -8.491532e-01 -9.367314e-03 5.280636e-01 9.001586e+01 +5.690549e-01 2.168567e-02 8.220136e-01 1.096504e+02 -2.184104e-02 9.996981e-01 -1.125332e-02 -1.726071e+01 -8.220095e-01 -1.154987e-02 5.693567e-01 9.018166e+01 +6.097726e-01 2.322629e-02 7.922360e-01 1.097548e+02 -2.248990e-02 9.996751e-01 -1.199772e-02 -1.726496e+01 -7.922573e-01 -1.050142e-02 6.100969e-01 9.031001e+01 +6.492045e-01 2.504968e-02 7.602013e-01 1.098838e+02 -2.333847e-02 9.996430e-01 -1.300879e-02 -1.727130e+01 -7.602558e-01 -9.296569e-03 6.495574e-01 9.049039e+01 +6.859942e-01 2.816491e-02 7.270617e-01 1.100078e+02 -2.654441e-02 9.995541e-01 -1.367565e-02 -1.727845e+01 -7.271227e-01 -9.918000e-03 6.864359e-01 9.068368e+01 +7.191363e-01 3.298826e-02 6.940856e-01 1.101054e+02 -3.176831e-02 9.993888e-01 -1.458374e-02 -1.727929e+01 -6.941425e-01 -1.156223e-02 7.197447e-01 9.085055e+01 +7.486403e-01 3.765305e-02 6.619063e-01 1.102283e+02 -3.822011e-02 9.991766e-01 -1.361060e-02 -1.728595e+01 -6.618738e-01 -1.510869e-02 7.494630e-01 9.106775e+01 +7.753138e-01 4.131324e-02 6.302235e-01 1.103319e+02 -4.267901e-02 9.990044e-01 -1.298349e-02 -1.728983e+01 -6.301326e-01 -1.683104e-02 7.763052e-01 9.126239e+01 +8.005007e-01 4.346844e-02 5.977534e-01 1.104525e+02 -4.324116e-02 9.989560e-01 -1.473599e-02 -1.729268e+01 -5.977699e-01 -1.405138e-02 8.015446e-01 9.149156e+01 +8.244728e-01 4.469514e-02 5.641338e-01 1.105694e+02 -4.454159e-02 9.989088e-01 -1.404462e-02 -1.730146e+01 -5.641460e-01 -1.354801e-02 8.255639e-01 9.173034e+01 +8.447472e-01 4.657117e-02 5.331354e-01 1.106632e+02 -4.659766e-02 9.988236e-01 -1.341714e-02 -1.730784e+01 -5.331331e-01 -1.350877e-02 8.459236e-01 9.195822e+01 +8.634589e-01 4.963975e-02 5.019707e-01 1.107668e+02 -5.026996e-02 9.986601e-01 -1.228598e-02 -1.731513e+01 -5.019080e-01 -1.462561e-02 8.647973e-01 9.222084e+01 +8.818497e-01 5.251576e-02 4.685971e-01 1.108520e+02 -5.314990e-02 9.985158e-01 -1.188144e-02 -1.731925e+01 -4.685257e-01 -1.442824e-02 8.833321e-01 9.247005e+01 +8.983230e-01 5.524156e-02 4.358487e-01 1.109474e+02 -5.548090e-02 9.983853e-01 -1.218911e-02 -1.732819e+01 -4.358183e-01 -1.323152e-02 8.999374e-01 9.275078e+01 +9.128555e-01 5.594943e-02 4.044311e-01 1.110387e+02 -5.593371e-02 9.983640e-01 -1.186483e-02 -1.733753e+01 -4.044332e-01 -1.179045e-02 9.144915e-01 9.304352e+01 +9.271810e-01 5.488966e-02 3.705706e-01 1.111107e+02 -5.488118e-02 9.984369e-01 -1.057581e-02 -1.734547e+01 -3.705719e-01 -1.053166e-02 9.287441e-01 9.333109e+01 +9.404409e-01 5.264754e-02 3.358557e-01 1.111905e+02 -5.186649e-02 9.985900e-01 -1.130235e-02 -1.735236e+01 -3.359772e-01 -6.790459e-03 9.418456e-01 9.364987e+01 +9.521606e-01 5.488303e-02 3.006294e-01 1.112370e+02 -5.331061e-02 9.984875e-01 -1.343770e-02 -1.735484e+01 -3.009122e-01 -3.231884e-03 9.536464e-01 9.395947e+01 +9.630193e-01 6.086050e-02 2.624689e-01 1.112869e+02 -5.911700e-02 9.981451e-01 -1.454196e-02 -1.736465e+01 -2.628671e-01 -1.512183e-03 9.648309e-01 9.431011e+01 +9.724791e-01 6.456476e-02 2.238655e-01 1.113294e+02 -6.258500e-02 9.979124e-01 -1.593538e-02 -1.737307e+01 -2.244271e-01 1.486195e-03 9.744898e-01 9.467626e+01 +9.801806e-01 6.625859e-02 1.866970e-01 1.113498e+02 -6.393272e-02 9.977835e-01 -1.845839e-02 -1.738055e+01 -1.875062e-01 6.156509e-03 9.822441e-01 9.503263e+01 +9.861017e-01 6.812210e-02 1.515346e-01 1.113740e+02 -6.559610e-02 9.976122e-01 -2.161240e-02 -1.738663e+01 -1.526451e-01 1.137194e-02 9.882157e-01 9.542902e+01 +9.902640e-01 7.410050e-02 1.178403e-01 1.113822e+02 -7.126388e-02 9.970613e-01 -2.811178e-02 -1.739441e+01 -1.195771e-01 1.944033e-02 9.926346e-01 9.583444e+01 +9.931889e-01 7.871855e-02 8.590260e-02 1.113761e+02 -7.641711e-02 9.966316e-01 -2.976378e-02 -1.740383e+01 -8.795622e-02 2.299662e-02 9.958589e-01 9.624445e+01 +9.949518e-01 7.809523e-02 6.302452e-02 1.113798e+02 -7.645148e-02 9.966776e-01 -2.808826e-02 -1.741911e+01 -6.500869e-02 2.312814e-02 9.976166e-01 9.668923e+01 +9.956942e-01 7.891506e-02 4.863547e-02 1.113762e+02 -7.767152e-02 9.966146e-01 -2.695226e-02 -1.743358e+01 -5.059777e-02 2.305862e-02 9.984529e-01 9.715670e+01 +9.961023e-01 7.905223e-02 3.912743e-02 1.113758e+02 -7.802451e-02 9.965821e-01 -2.713338e-02 -1.745118e+01 -4.113865e-02 2.397472e-02 9.988658e-01 9.763987e+01 +9.966260e-01 7.614830e-02 3.062634e-02 1.113656e+02 -7.534060e-02 9.967999e-01 -2.671674e-02 -1.746845e+01 -3.256277e-02 2.431919e-02 9.991738e-01 9.815329e+01 +9.967867e-01 7.690102e-02 2.241554e-02 1.113214e+02 -7.630210e-02 9.967338e-01 -2.645236e-02 -1.748346e+01 -2.437654e-02 2.465701e-02 9.993987e-01 9.871208e+01 +9.969332e-01 7.686432e-02 1.469674e-02 1.112776e+02 -7.641473e-02 9.966533e-01 -2.903447e-02 -1.749582e+01 -1.687927e-02 2.782238e-02 9.994704e-01 9.928671e+01 +9.967983e-01 7.965294e-02 6.971201e-03 1.112240e+02 -7.940776e-02 9.963816e-01 -3.030023e-02 -1.750663e+01 -9.359479e-03 2.964964e-02 9.995165e-01 9.988651e+01 +9.966966e-01 8.120870e-02 1.068562e-03 1.111790e+02 -8.114103e-02 9.962576e-01 -2.977894e-02 -1.752308e+01 -3.482872e-03 2.959386e-02 9.995559e-01 1.004992e+02 +9.966470e-01 8.176615e-02 -3.014973e-03 1.111321e+02 -8.181938e-02 9.962207e-01 -2.915212e-02 -1.754096e+01 6.199224e-04 2.930105e-02 9.995704e-01 1.011342e+02 +9.966526e-01 8.161247e-02 -4.803932e-03 1.110925e+02 -8.171895e-02 9.962212e-01 -2.941685e-02 -1.756481e+01 2.384997e-03 2.971095e-02 9.995557e-01 1.017824e+02 +9.965621e-01 8.264118e-02 -5.860287e-03 1.110526e+02 -8.277751e-02 9.961436e-01 -2.908327e-02 -1.758304e+01 3.434213e-03 2.946838e-02 9.995598e-01 1.024545e+02 +9.966391e-01 8.167735e-02 -6.268270e-03 1.110195e+02 -8.182937e-02 9.961967e-01 -2.993278e-02 -1.760213e+01 3.799601e-03 3.034510e-02 9.995323e-01 1.031391e+02 +9.966883e-01 8.102500e-02 -6.890015e-03 1.109833e+02 -8.119584e-02 9.962510e-01 -2.985072e-02 -1.762342e+01 4.445530e-03 3.031130e-02 9.995306e-01 1.038509e+02 +9.968587e-01 7.883940e-02 -7.557712e-03 1.109534e+02 -7.902241e-02 9.964758e-01 -2.813007e-02 -1.765023e+01 5.313320e-03 2.863893e-02 9.995757e-01 1.045736e+02 +9.967497e-01 8.014286e-02 -8.190332e-03 1.109156e+02 -8.033017e-02 9.964316e-01 -2.590676e-02 -1.767358e+01 6.084865e-03 2.648048e-02 9.996308e-01 1.053227e+02 +9.968257e-01 7.914648e-02 -8.624305e-03 1.108838e+02 -7.933707e-02 9.965439e-01 -2.461215e-02 -1.769731e+01 6.646535e-03 2.521824e-02 9.996599e-01 1.060855e+02 +9.967947e-01 7.934049e-02 -1.026552e-02 1.108481e+02 -7.957427e-02 9.965198e-01 -2.482332e-02 -1.772254e+01 8.260300e-03 2.556062e-02 9.996392e-01 1.068676e+02 +9.967547e-01 7.949687e-02 -1.265850e-02 1.108116e+02 -7.980202e-02 9.964776e-01 -2.576679e-02 -1.774986e+01 1.056553e-02 2.669334e-02 9.995878e-01 1.076658e+02 +9.966105e-01 8.096774e-02 -1.455423e-02 1.107700e+02 -8.133446e-02 9.963299e-01 -2.667044e-02 -1.777284e+01 1.234137e-02 2.776380e-02 9.995383e-01 1.084806e+02 +9.964082e-01 8.302651e-02 -1.665239e-02 1.107290e+02 -8.342706e-02 9.962001e-01 -2.500394e-02 -1.779714e+01 1.451313e-02 2.630339e-02 9.995487e-01 1.093119e+02 +9.963432e-01 8.337974e-02 -1.865780e-02 1.106923e+02 -8.376090e-02 9.962714e-01 -2.067415e-02 -1.782015e+01 1.686443e-02 2.216134e-02 9.996122e-01 1.101583e+02 +9.962113e-01 8.419627e-02 -2.177377e-02 1.106507e+02 -8.465200e-02 9.961907e-01 -2.092956e-02 -1.784411e+01 1.992864e-02 2.269346e-02 9.995438e-01 1.110132e+02 +9.960669e-01 8.480469e-02 -2.566969e-02 1.106046e+02 -8.534830e-02 9.961324e-01 -2.087654e-02 -1.786752e+01 2.379998e-02 2.298529e-02 9.994525e-01 1.118777e+02 +9.959549e-01 8.467970e-02 -3.005205e-02 1.105555e+02 -8.527764e-02 9.961721e-01 -1.920357e-02 -1.789307e+01 2.831087e-02 2.168866e-02 9.993639e-01 1.127513e+02 +9.958372e-01 8.426017e-02 -3.476434e-02 1.105040e+02 -8.493041e-02 9.962193e-01 -1.827243e-02 -1.791994e+01 3.309327e-02 2.114891e-02 9.992285e-01 1.136340e+02 +9.956128e-01 8.484880e-02 -3.944540e-02 1.104511e+02 -8.567332e-02 9.961285e-01 -1.970135e-02 -1.794059e+01 3.762106e-02 2.299433e-02 9.990275e-01 1.145208e+02 +9.952593e-01 8.661616e-02 -4.423354e-02 1.103896e+02 -8.756082e-02 9.959607e-01 -1.988092e-02 -1.796490e+01 4.233287e-02 2.365980e-02 9.988234e-01 1.154179e+02 +9.950326e-01 8.709811e-02 -4.820937e-02 1.103254e+02 -8.807075e-02 9.959437e-01 -1.842835e-02 -1.798871e+01 4.640875e-02 2.258264e-02 9.986672e-01 1.163255e+02 +9.947037e-01 8.906445e-02 -5.130359e-02 1.102540e+02 -8.996608e-02 9.958236e-01 -1.553668e-02 -1.801737e+01 4.970556e-02 2.006997e-02 9.985623e-01 1.172400e+02 +9.946176e-01 8.891217e-02 -5.320232e-02 1.101886e+02 -8.974630e-02 9.958732e-01 -1.349533e-02 -1.803938e+01 5.178287e-02 1.819740e-02 9.984926e-01 1.181523e+02 +9.945532e-01 8.836993e-02 -5.526861e-02 1.101221e+02 -8.917063e-02 9.959418e-01 -1.218800e-02 -1.806321e+01 5.396727e-02 1.704995e-02 9.983971e-01 1.190624e+02 +9.944886e-01 8.784255e-02 -5.723745e-02 1.100556e+02 -8.852674e-02 9.960282e-01 -9.524331e-03 -1.808175e+01 5.617348e-02 1.453888e-02 9.983152e-01 1.199711e+02 +9.944983e-01 8.647969e-02 -5.911416e-02 1.099851e+02 -8.705731e-02 9.961768e-01 -7.261669e-03 -1.810545e+01 5.826018e-02 1.236804e-02 9.982248e-01 1.208800e+02 +9.944469e-01 8.604614e-02 -6.059172e-02 1.099194e+02 -8.644645e-02 9.962484e-01 -4.011281e-03 -1.812479e+01 6.001926e-02 9.226944e-03 9.981546e-01 1.217858e+02 +9.944612e-01 8.549468e-02 -6.113574e-02 1.098559e+02 -8.594918e-02 9.962878e-01 -4.838335e-03 -1.814207e+01 6.049515e-02 1.006610e-02 9.981177e-01 1.226874e+02 +9.945801e-01 8.455308e-02 -6.050776e-02 1.097948e+02 -8.499512e-02 9.963700e-01 -4.764490e-03 -1.815928e+01 5.988527e-02 9.881530e-03 9.981564e-01 1.235883e+02 +9.947033e-01 8.370109e-02 -5.966081e-02 1.097301e+02 -8.421407e-02 9.964288e-01 -6.131661e-03 -1.818107e+01 5.893453e-02 1.112346e-02 9.981999e-01 1.244883e+02 +9.948857e-01 8.260203e-02 -5.813188e-02 1.096660e+02 -8.319392e-02 9.965026e-01 -7.831902e-03 -1.820460e+01 5.728164e-02 1.262806e-02 9.982782e-01 1.253884e+02 +9.952407e-01 7.993715e-02 -5.573102e-02 1.096071e+02 -8.058052e-02 9.967038e-01 -9.390180e-03 -1.822781e+01 5.479670e-02 1.383632e-02 9.984017e-01 1.262837e+02 +9.955412e-01 7.852254e-02 -5.226756e-02 1.095495e+02 -7.913628e-02 9.968159e-01 -9.774517e-03 -1.825354e+01 5.133362e-02 1.386719e-02 9.985853e-01 1.271826e+02 +9.958951e-01 7.666895e-02 -4.811219e-02 1.095018e+02 -7.722535e-02 9.969654e-01 -9.811389e-03 -1.827981e+01 4.721396e-02 1.348659e-02 9.987938e-01 1.280778e+02 +9.962481e-01 7.401550e-02 -4.484821e-02 1.094557e+02 -7.451950e-02 9.971726e-01 -9.669604e-03 -1.830879e+01 4.400571e-02 1.297539e-02 9.989470e-01 1.289723e+02 +9.965905e-01 7.123539e-02 -4.162892e-02 1.094150e+02 -7.165772e-02 9.973910e-01 -8.740356e-03 -1.833608e+01 4.089769e-02 1.169359e-02 9.990949e-01 1.298652e+02 +9.968508e-01 6.935423e-02 -3.845119e-02 1.093712e+02 -6.971947e-02 9.975326e-01 -8.238667e-03 -1.836398e+01 3.778493e-02 1.089352e-02 9.992265e-01 1.307528e+02 +9.971388e-01 6.662272e-02 -3.571494e-02 1.093346e+02 -6.695386e-02 9.977227e-01 -8.155417e-03 -1.839190e+01 3.509027e-02 1.052333e-02 9.993288e-01 1.316414e+02 +9.974059e-01 6.362289e-02 -3.366933e-02 1.092951e+02 -6.394545e-02 9.979164e-01 -8.590312e-03 -1.841940e+01 3.305264e-02 1.072103e-02 9.993961e-01 1.325256e+02 +9.975239e-01 6.242127e-02 -3.239740e-02 1.092564e+02 -6.267659e-02 9.980098e-01 -6.924668e-03 -1.844460e+01 3.190068e-02 8.938080e-03 9.994511e-01 1.334068e+02 +9.975486e-01 6.272761e-02 -3.101581e-02 1.092181e+02 -6.280691e-02 9.980244e-01 -1.587662e-03 -1.846842e+01 3.085495e-02 3.531777e-03 9.995176e-01 1.342872e+02 +9.976062e-01 6.230375e-02 -3.000136e-02 1.091865e+02 -6.221868e-02 9.980554e-01 3.762250e-03 -1.849176e+01 3.017743e-02 -1.886598e-03 9.995428e-01 1.351557e+02 +9.975397e-01 6.372851e-02 -2.921104e-02 1.091491e+02 -6.357520e-02 9.979581e-01 6.148967e-03 -1.851295e+01 2.954326e-02 -4.276740e-03 9.995544e-01 1.360066e+02 +9.975200e-01 6.429545e-02 -2.863552e-02 1.091136e+02 -6.414833e-02 9.979221e-01 6.028577e-03 -1.853001e+01 2.896364e-02 -4.176703e-03 9.995717e-01 1.368376e+02 +9.975275e-01 6.419114e-02 -2.860747e-02 1.090766e+02 -6.404699e-02 9.979292e-01 5.928480e-03 -1.854784e+01 2.892879e-02 -4.081598e-03 9.995732e-01 1.376489e+02 +9.975297e-01 6.395329e-02 -2.906170e-02 1.090393e+02 -6.384999e-02 9.979495e-01 4.469819e-03 -1.856925e+01 2.928797e-02 -2.603186e-03 9.995676e-01 1.384394e+02 +9.974715e-01 6.470209e-02 -2.939879e-02 1.090035e+02 -6.467560e-02 9.979046e-01 1.852387e-03 -1.859232e+01 2.945705e-02 5.368184e-05 9.995661e-01 1.392112e+02 +9.974076e-01 6.533834e-02 -3.015063e-02 1.089729e+02 -6.542534e-02 9.978556e-01 -1.906312e-03 -1.861422e+01 2.996143e-02 3.873986e-03 9.995436e-01 1.399623e+02 +9.974697e-01 6.388089e-02 -3.119903e-02 1.089469e+02 -6.407051e-02 9.979322e-01 -5.115035e-03 -1.863890e+01 3.080777e-02 7.101031e-03 9.995001e-01 1.406872e+02 +9.974480e-01 6.379313e-02 -3.206026e-02 1.089148e+02 -6.401491e-02 9.979312e-01 -5.938207e-03 -1.866528e+01 3.161512e-02 7.975387e-03 9.994683e-01 1.413884e+02 +9.973985e-01 6.406502e-02 -3.304561e-02 1.088832e+02 -6.429994e-02 9.979120e-01 -6.094287e-03 -1.869075e+01 3.258618e-02 8.203263e-03 9.994353e-01 1.420649e+02 +9.973136e-01 6.482271e-02 -3.411226e-02 1.088480e+02 -6.509467e-02 9.978551e-01 -6.921617e-03 -1.871701e+01 3.359042e-02 9.123548e-03 9.993940e-01 1.427136e+02 +9.972807e-01 6.488283e-02 -3.494782e-02 1.088170e+02 -6.514977e-02 9.978540e-01 -6.552730e-03 -1.874314e+01 3.444767e-02 8.811753e-03 9.993677e-01 1.433369e+02 +9.972263e-01 6.508411e-02 -3.610916e-02 1.087830e+02 -6.534082e-02 9.978451e-01 -5.973719e-03 -1.876211e+01 3.564256e-02 8.316550e-03 9.993300e-01 1.439299e+02 +9.972481e-01 6.430199e-02 -3.689768e-02 1.087599e+02 -6.463483e-02 9.978777e-01 -7.898286e-03 -1.877372e+01 3.631150e-02 1.026142e-02 9.992878e-01 1.444864e+02 +9.972338e-01 6.433767e-02 -3.722208e-02 1.087364e+02 -6.472274e-02 9.978605e-01 -9.232965e-03 -1.878578e+01 3.654842e-02 1.161654e-02 9.992644e-01 1.450241e+02 +9.972132e-01 6.452256e-02 -3.745208e-02 1.087140e+02 -6.490413e-02 9.978503e-01 -9.061669e-03 -1.879256e+01 3.678689e-02 1.146721e-02 9.992573e-01 1.455452e+02 +9.972302e-01 6.436925e-02 -3.726391e-02 1.086900e+02 -6.473182e-02 9.978656e-01 -8.604750e-03 -1.880211e+01 3.663050e-02 1.099308e-02 9.992684e-01 1.460452e+02 +9.972911e-01 6.360561e-02 -3.694312e-02 1.086896e+02 -6.396321e-02 9.979154e-01 -8.578355e-03 -1.881388e+01 3.632047e-02 1.091812e-02 9.992806e-01 1.465207e+02 +9.973325e-01 6.304402e-02 -3.678759e-02 1.087032e+02 -6.336782e-02 9.979605e-01 -7.701728e-03 -1.882803e+01 3.622702e-02 1.001233e-02 9.992934e-01 1.469716e+02 +9.973391e-01 6.311520e-02 -3.648673e-02 1.087159e+02 -6.336965e-02 9.979729e-01 -5.858188e-03 -1.884050e+01 3.604303e-02 8.154751e-03 9.993170e-01 1.474024e+02 +9.973977e-01 6.287234e-02 -3.528316e-02 1.087633e+02 -6.310964e-02 9.979906e-01 -5.651270e-03 -1.885361e+01 3.485696e-02 7.863271e-03 9.993614e-01 1.478039e+02 +9.973868e-01 6.437587e-02 -3.279191e-02 1.087933e+02 -6.461747e-02 9.978898e-01 -6.360565e-03 -1.886595e+01 3.231325e-02 8.462873e-03 9.994420e-01 1.481836e+02 +9.974497e-01 6.569828e-02 -2.789079e-02 1.088278e+02 -6.591176e-02 9.978022e-01 -6.803448e-03 -1.887338e+01 2.738252e-02 8.624427e-03 9.995878e-01 1.485398e+02 +9.976267e-01 6.532053e-02 -2.177749e-02 1.088561e+02 -6.549480e-02 9.978255e-01 -7.386154e-03 -1.888471e+01 2.124767e-02 8.794936e-03 9.997356e-01 1.488750e+02 +9.978324e-01 6.366065e-02 -1.667123e-02 1.088980e+02 -6.381898e-02 9.979196e-01 -9.142541e-03 -1.889851e+01 1.605453e-02 1.018666e-02 9.998192e-01 1.491847e+02 +9.980246e-01 6.166709e-02 -1.200006e-02 1.089212e+02 -6.179187e-02 9.980357e-01 -1.032021e-02 -1.891090e+01 1.134007e-02 1.104133e-02 9.998747e-01 1.494854e+02 +9.981068e-01 6.112771e-02 -6.795769e-03 1.089528e+02 -6.119940e-02 9.980661e-01 -1.089265e-02 -1.892212e+01 6.116784e-03 1.128792e-02 9.999176e-01 1.497659e+02 +9.981617e-01 6.057766e-02 -1.867093e-03 1.089747e+02 -6.059482e-02 9.981000e-01 -1.116599e-02 -1.893909e+01 1.187136e-03 1.125859e-02 9.999359e-01 1.500344e+02 +9.981700e-01 6.042645e-02 2.303486e-03 1.090068e+02 -6.039200e-02 9.980916e-01 -1.287987e-02 -1.895904e+01 -3.077374e-03 1.271718e-02 9.999144e-01 1.502844e+02 +9.982385e-01 5.892444e-02 6.913324e-03 1.090214e+02 -5.881141e-02 9.981480e-01 -1.555093e-02 -1.897283e+01 -7.816850e-03 1.511695e-02 9.998552e-01 1.505319e+02 +9.982571e-01 5.793124e-02 1.126271e-02 1.090379e+02 -5.773337e-02 9.981844e-01 -1.716518e-02 -1.898610e+01 -1.223666e-02 1.648502e-02 9.997892e-01 1.507788e+02 +9.982300e-01 5.752318e-02 1.510165e-02 1.090497e+02 -5.725105e-02 9.981998e-01 -1.787397e-02 -1.899838e+01 -1.610263e-02 1.697774e-02 9.997262e-01 1.510266e+02 +9.981745e-01 5.728946e-02 1.911958e-02 1.090630e+02 -5.693705e-02 9.982064e-01 -1.849473e-02 -1.901037e+01 -2.014484e-02 1.737235e-02 9.996461e-01 1.512721e+02 +9.981765e-01 5.585290e-02 2.289294e-02 1.090757e+02 -5.541645e-02 9.982772e-01 -1.927650e-02 -1.902293e+01 -2.393015e-02 1.797271e-02 9.995521e-01 1.515176e+02 +9.981838e-01 5.453328e-02 2.559799e-02 1.091100e+02 -5.404329e-02 9.983489e-01 -1.945912e-02 -1.902342e+01 -2.661690e-02 1.804038e-02 9.994829e-01 1.517490e+02 +9.981704e-01 5.391976e-02 2.736030e-02 1.091626e+02 -5.338108e-02 9.983728e-01 -2.005185e-02 -1.901173e+01 -2.839697e-02 1.855463e-02 9.994245e-01 1.519625e+02 +9.981627e-01 5.359524e-02 2.826245e-02 1.091999e+02 -5.302083e-02 9.983789e-01 -2.069734e-02 -1.900621e+01 -2.932591e-02 1.916081e-02 9.993862e-01 1.521841e+02 +9.981967e-01 5.271487e-02 2.871576e-02 1.092404e+02 -5.210921e-02 9.984110e-01 -2.144740e-02 -1.900103e+01 -2.980073e-02 1.991236e-02 9.993575e-01 1.524031e+02 +9.982137e-01 5.243752e-02 2.863132e-02 1.092698e+02 -5.183576e-02 9.984269e-01 -2.137115e-02 -1.897327e+01 -2.970693e-02 1.984884e-02 9.993616e-01 1.526306e+02 +9.981970e-01 5.262526e-02 2.886852e-02 1.093127e+02 -5.203266e-02 9.984264e-01 -2.090917e-02 -1.890617e+01 -2.992345e-02 1.936936e-02 9.993645e-01 1.528562e+02 +9.982514e-01 5.194379e-02 2.821492e-02 1.093441e+02 -5.128049e-02 9.984019e-01 -2.374552e-02 -1.886099e+01 -2.940326e-02 2.225712e-02 9.993198e-01 1.530976e+02 +9.984798e-01 4.757621e-02 2.783191e-02 1.093884e+02 -4.680617e-02 9.985200e-01 -2.769468e-02 -1.880195e+01 -2.910833e-02 2.634987e-02 9.992289e-01 1.533533e+02 +9.986742e-01 4.322320e-02 2.795612e-02 1.094195e+02 -4.243074e-02 9.986972e-01 -2.834482e-02 -1.877306e+01 -2.914486e-02 2.712104e-02 9.992072e-01 1.536356e+02 +9.987138e-01 4.290183e-02 2.702301e-02 1.094526e+02 -4.217068e-02 9.987436e-01 -2.706954e-02 -1.873613e+01 -2.815039e-02 2.589514e-02 9.992682e-01 1.539336e+02 +9.986213e-01 4.549078e-02 2.619256e-02 1.094772e+02 -4.480488e-02 9.986520e-01 -2.620440e-02 -1.871587e+01 -2.734931e-02 2.499472e-02 9.993134e-01 1.542529e+02 +9.984870e-01 4.888205e-02 2.518621e-02 1.095013e+02 -4.825249e-02 9.985216e-01 -2.502624e-02 -1.869341e+01 -2.637230e-02 2.377307e-02 9.993695e-01 1.545861e+02 +9.984791e-01 5.009774e-02 2.301370e-02 1.095214e+02 -4.953076e-02 9.984701e-01 -2.457994e-02 -1.868181e+01 -2.420989e-02 2.340267e-02 9.994329e-01 1.549360e+02 +9.984759e-01 5.114741e-02 2.073228e-02 1.095400e+02 -5.064679e-02 9.984283e-01 -2.399347e-02 -1.867160e+01 -2.192691e-02 2.290688e-02 9.994971e-01 1.553007e+02 +9.984039e-01 5.315030e-02 1.910002e-02 1.095612e+02 -5.271600e-02 9.983545e-01 -2.256572e-02 -1.865593e+01 -2.026797e-02 2.152282e-02 9.995629e-01 1.556792e+02 +9.984776e-01 5.256035e-02 1.672836e-02 1.095843e+02 -5.219453e-02 9.984032e-01 -2.160211e-02 -1.864537e+01 -1.783707e-02 2.069609e-02 9.996267e-01 1.560727e+02 +9.987610e-01 4.768646e-02 1.422878e-02 1.096140e+02 -4.735618e-02 9.986198e-01 -2.271077e-02 -1.863746e+01 -1.529214e-02 2.200880e-02 9.996408e-01 1.564747e+02 +9.988862e-01 4.542812e-02 1.275321e-02 1.096331e+02 -4.513508e-02 9.987298e-01 -2.239583e-02 -1.863871e+01 -1.375442e-02 2.179527e-02 9.996678e-01 1.568932e+02 +9.987715e-01 4.827794e-02 1.116905e-02 1.096452e+02 -4.804299e-02 9.986364e-01 -2.042649e-02 -1.863849e+01 -1.213997e-02 1.986480e-02 9.997290e-01 1.573289e+02 +9.985535e-01 5.297977e-02 9.172327e-03 1.096511e+02 -5.281592e-02 9.984549e-01 -1.727039e-02 -1.864018e+01 -1.007314e-02 1.676096e-02 9.998088e-01 1.577826e+02 +9.982791e-01 5.814325e-02 7.631978e-03 1.096621e+02 -5.800628e-02 9.981700e-01 -1.708625e-02 -1.863405e+01 -8.611462e-03 1.661414e-02 9.998249e-01 1.582533e+02 +9.981145e-01 6.108903e-02 5.968944e-03 1.096675e+02 -6.096121e-02 9.979465e-01 -1.965796e-02 -1.863406e+01 -7.157573e-03 1.925702e-02 9.997890e-01 1.587380e+02 +9.982518e-01 5.897750e-02 3.877033e-03 1.096844e+02 -5.889124e-02 9.980738e-01 -1.950604e-02 -1.863716e+01 -5.019983e-03 1.924361e-02 9.998022e-01 1.592423e+02 +9.984729e-01 5.518623e-02 2.525607e-03 1.096990e+02 -5.513334e-02 9.983231e-01 -1.764047e-02 -1.864484e+01 -3.494882e-03 1.747428e-02 9.998412e-01 1.597687e+02 +9.985355e-01 5.407847e-02 1.569481e-03 1.097155e+02 -5.404375e-02 9.983915e-01 -1.713644e-02 -1.864688e+01 -2.493669e-03 1.702652e-02 9.998519e-01 1.603116e+02 +9.984964e-01 5.481836e-02 4.632355e-05 1.097246e+02 -5.480969e-02 9.983525e-01 -1.697394e-02 -1.864942e+01 -9.767304e-04 1.694587e-02 9.998559e-01 1.608760e+02 +9.984331e-01 5.592430e-02 -1.959608e-03 1.097170e+02 -5.594969e-02 9.982874e-01 -1.708341e-02 -1.865484e+01 1.000874e-03 1.716628e-02 9.998522e-01 1.614684e+02 +9.984510e-01 5.552766e-02 -3.517966e-03 1.096964e+02 -5.557674e-02 9.983284e-01 -1.585830e-02 -1.867337e+01 2.631512e-03 1.602925e-02 9.998681e-01 1.620886e+02 +9.984036e-01 5.625155e-02 -5.110857e-03 1.096743e+02 -5.632515e-02 9.982902e-01 -1.562340e-02 -1.870676e+01 4.223278e-03 1.588633e-02 9.998649e-01 1.627175e+02 +9.984453e-01 5.531645e-02 -6.861238e-03 1.096615e+02 -5.542142e-02 9.983318e-01 -1.618794e-02 -1.873569e+01 5.954334e-03 1.654303e-02 9.998454e-01 1.633664e+02 +9.984576e-01 5.486872e-02 -8.480712e-03 1.096488e+02 -5.499816e-02 9.983603e-01 -1.586731e-02 -1.875999e+01 7.596188e-03 1.630925e-02 9.998381e-01 1.640317e+02 +9.984743e-01 5.430041e-02 -1.002462e-02 1.096399e+02 -5.445126e-02 9.983970e-01 -1.544216e-02 -1.878462e+01 9.170035e-03 1.596445e-02 9.998305e-01 1.647093e+02 +9.984443e-01 5.453484e-02 -1.161636e-02 1.096341e+02 -5.471304e-02 9.983800e-01 -1.561748e-02 -1.880725e+01 1.074585e-02 1.622875e-02 9.998106e-01 1.653989e+02 +9.984736e-01 5.375160e-02 -1.269706e-02 1.096391e+02 -5.394358e-02 9.984268e-01 -1.529383e-02 -1.881941e+01 1.185502e-02 1.595541e-02 9.998024e-01 1.661087e+02 +9.984091e-01 5.458870e-02 -1.411789e-02 1.096391e+02 -5.479006e-02 9.983956e-01 -1.429139e-02 -1.882273e+01 1.331509e-02 1.504217e-02 9.997982e-01 1.668353e+02 +9.984070e-01 5.434287e-02 -1.517667e-02 1.096400e+02 -5.455312e-02 9.984155e-01 -1.380017e-02 -1.882043e+01 1.440268e-02 1.460612e-02 9.997896e-01 1.675798e+02 +9.984083e-01 5.407866e-02 -1.601462e-02 1.096332e+02 -5.429504e-02 9.984350e-01 -1.339878e-02 -1.882729e+01 1.526497e-02 1.424697e-02 9.997820e-01 1.683399e+02 +9.983440e-01 5.506900e-02 -1.663564e-02 1.096265e+02 -5.529114e-02 9.983830e-01 -1.320103e-02 -1.883146e+01 1.588177e-02 1.409897e-02 9.997745e-01 1.691167e+02 +9.983265e-01 5.526217e-02 -1.703753e-02 1.096176e+02 -5.551366e-02 9.983503e-01 -1.465800e-02 -1.884008e+01 1.619939e-02 1.557929e-02 9.997474e-01 1.699053e+02 +9.982538e-01 5.637363e-02 -1.764593e-02 1.096127e+02 -5.664262e-02 9.982798e-01 -1.513328e-02 -1.884654e+01 1.676246e-02 1.610636e-02 9.997298e-01 1.707107e+02 +9.982782e-01 5.577138e-02 -1.817252e-02 1.096046e+02 -5.605549e-02 9.983070e-01 -1.551794e-02 -1.885639e+01 1.727630e-02 1.650989e-02 9.997144e-01 1.715298e+02 +9.983216e-01 5.496389e-02 -1.824813e-02 1.095946e+02 -5.524221e-02 9.983586e-01 -1.511426e-02 -1.886972e+01 1.738744e-02 1.609695e-02 9.997193e-01 1.723634e+02 +9.982968e-01 5.532248e-02 -1.851643e-02 1.095833e+02 -5.559026e-02 9.983516e-01 -1.427279e-02 -1.888440e+01 1.769630e-02 1.527781e-02 9.997267e-01 1.732103e+02 +9.982905e-01 5.540443e-02 -1.861512e-02 1.095731e+02 -5.564947e-02 9.983668e-01 -1.291329e-02 -1.889789e+01 1.786927e-02 1.392713e-02 9.997433e-01 1.740661e+02 +9.982472e-01 5.603754e-02 -1.903592e-02 1.095649e+02 -5.626091e-02 9.983509e-01 -1.140712e-02 -1.890990e+01 1.836530e-02 1.245810e-02 9.997537e-01 1.749328e+02 +9.982548e-01 5.602251e-02 -1.868011e-02 1.095535e+02 -5.622279e-02 9.983643e-01 -1.037359e-02 -1.892457e+01 1.806840e-02 1.140574e-02 9.997717e-01 1.758104e+02 +9.982511e-01 5.655658e-02 -1.720712e-02 1.095435e+02 -5.674844e-02 9.983293e-01 -1.087279e-02 -1.893953e+01 1.656345e-02 1.183025e-02 9.997928e-01 1.766985e+02 +9.983249e-01 5.594760e-02 -1.473842e-02 1.095326e+02 -5.614306e-02 9.983355e-01 -1.319895e-02 -1.895794e+01 1.397544e-02 1.400430e-02 9.998043e-01 1.775942e+02 +9.983934e-01 5.530199e-02 -1.234527e-02 1.095343e+02 -5.546989e-02 9.983664e-01 -1.369817e-02 -1.897165e+01 1.156757e-02 1.436095e-02 9.998300e-01 1.785002e+02 +9.985491e-01 5.283960e-02 -1.037732e-02 1.095332e+02 -5.297792e-02 9.985039e-01 -1.353893e-02 -1.898959e+01 9.646404e-03 1.406905e-02 9.998545e-01 1.794126e+02 +9.987244e-01 4.968418e-02 -8.998748e-03 1.095370e+02 -4.979338e-02 9.986832e-01 -1.234524e-02 -1.901086e+01 8.373536e-03 1.277757e-02 9.998833e-01 1.803271e+02 +9.988155e-01 4.788421e-02 -8.643632e-03 1.095358e+02 -4.800840e-02 9.987375e-01 -1.478201e-02 -1.903323e+01 7.924895e-03 1.517946e-02 9.998534e-01 1.812371e+02 +9.988754e-01 4.677664e-02 -7.744061e-03 1.095434e+02 -4.690103e-02 9.987592e-01 -1.674500e-02 -1.906449e+01 6.951178e-03 1.708937e-02 9.998298e-01 1.821386e+02 +9.989079e-01 4.617061e-02 -7.168705e-03 1.095597e+02 -4.628028e-02 9.988008e-01 -1.597011e-02 -1.910082e+01 6.422759e-03 1.628444e-02 9.998468e-01 1.830394e+02 +9.989407e-01 4.559369e-02 -6.215883e-03 1.095772e+02 -4.567592e-02 9.988610e-01 -1.379805e-02 -1.913700e+01 5.579700e-03 1.406734e-02 9.998855e-01 1.839405e+02 +9.989385e-01 4.571063e-02 -5.687327e-03 1.095871e+02 -4.577634e-02 9.988794e-01 -1.201530e-02 -1.917144e+01 5.131728e-03 1.226289e-02 9.999116e-01 1.848392e+02 +9.989819e-01 4.479005e-02 -5.389860e-03 1.095889e+02 -4.484800e-02 9.989315e-01 -1.115846e-02 -1.921104e+01 4.884314e-03 1.138882e-02 9.999232e-01 1.857374e+02 +9.990023e-01 4.434530e-02 -5.282889e-03 1.095890e+02 -4.440348e-02 9.989480e-01 -1.145582e-02 -1.925196e+01 4.769320e-03 1.167897e-02 9.999204e-01 1.866359e+02 +9.990418e-01 4.346161e-02 -5.164250e-03 1.095991e+02 -4.352057e-02 9.989815e-01 -1.191051e-02 -1.928429e+01 4.641341e-03 1.212385e-02 9.999157e-01 1.875332e+02 +9.991139e-01 4.165848e-02 -5.997859e-03 1.096150e+02 -4.173507e-02 9.990406e-01 -1.326552e-02 -1.931822e+01 5.439484e-03 1.350409e-02 9.998940e-01 1.884266e+02 +9.991975e-01 3.916399e-02 -8.401364e-03 1.096275e+02 -3.928181e-02 9.991251e-01 -1.434870e-02 -1.934151e+01 7.832062e-03 1.466721e-02 9.998618e-01 1.893111e+02 +9.992198e-01 3.765629e-02 -1.191025e-02 1.096384e+02 -3.782892e-02 9.991773e-01 -1.461678e-02 -1.936381e+01 1.135003e-02 1.505592e-02 9.998222e-01 1.901895e+02 +9.992103e-01 3.621086e-02 -1.635876e-02 1.096471e+02 -3.642476e-02 9.992522e-01 -1.297198e-02 -1.938444e+01 1.587680e-02 1.355760e-02 9.997820e-01 1.910628e+02 +9.991305e-01 3.584190e-02 -2.129619e-02 1.096590e+02 -3.606983e-02 9.992950e-01 -1.041636e-02 -1.940223e+01 2.090783e-02 1.117546e-02 9.997190e-01 1.919271e+02 +9.989889e-01 3.641577e-02 -2.636583e-02 1.096515e+02 -3.665631e-02 9.992901e-01 -8.697706e-03 -1.942225e+01 2.603038e-02 9.655384e-03 9.996145e-01 1.927764e+02 +9.988380e-01 3.719436e-02 -3.064736e-02 1.096459e+02 -3.741005e-02 9.992789e-01 -6.494148e-03 -1.943802e+01 3.038372e-02 7.633121e-03 9.995092e-01 1.936104e+02 +9.986977e-01 3.792304e-02 -3.412976e-02 1.096296e+02 -3.806698e-02 9.992688e-01 -3.577083e-03 -1.945143e+01 3.396915e-02 4.871641e-03 9.994110e-01 1.944303e+02 +9.985843e-01 3.883278e-02 -3.635147e-02 1.096140e+02 -3.892639e-02 9.992403e-01 -1.870641e-03 -1.945967e+01 3.625121e-02 3.283025e-03 9.993373e-01 1.952325e+02 +9.984849e-01 4.014641e-02 -3.763156e-02 1.095932e+02 -4.021856e-02 9.991902e-01 -1.161742e-03 -1.946963e+01 3.755445e-02 2.673469e-03 9.992910e-01 1.960164e+02 +9.984312e-01 4.070843e-02 -3.844552e-02 1.095749e+02 -4.075291e-02 9.991692e-01 -3.736094e-04 -1.947574e+01 3.839837e-02 1.939791e-03 9.992606e-01 1.967832e+02 +9.984149e-01 4.065451e-02 -3.892066e-02 1.095547e+02 -4.064162e-02 9.991731e-01 1.122870e-03 -1.948266e+01 3.893414e-02 4.607092e-04 9.992417e-01 1.975302e+02 +9.983717e-01 4.204435e-02 -3.855136e-02 1.095327e+02 -4.194323e-02 9.991141e-01 3.428579e-03 -1.949203e+01 3.866136e-02 -1.806027e-03 9.992507e-01 1.982592e+02 +9.983827e-01 4.268695e-02 -3.754682e-02 1.095145e+02 -4.256434e-02 9.990855e-01 4.059291e-03 -1.950144e+01 3.768576e-02 -2.454569e-03 9.992866e-01 1.989662e+02 +9.983802e-01 4.352488e-02 -3.664038e-02 1.094976e+02 -4.343398e-02 9.990509e-01 3.273792e-03 -1.950822e+01 3.674810e-02 -1.677050e-03 9.993232e-01 1.996539e+02 +9.984523e-01 4.296367e-02 -3.531414e-02 1.094846e+02 -4.286433e-02 9.990745e-01 3.566189e-03 -1.951236e+01 3.543468e-02 -2.046952e-03 9.993699e-01 2.003234e+02 +9.985424e-01 4.236635e-02 -3.343795e-02 1.094712e+02 -4.226979e-02 9.990998e-01 3.590024e-03 -1.952021e+01 3.355995e-02 -2.171374e-03 9.994344e-01 2.009713e+02 +9.986093e-01 4.280365e-02 -3.077811e-02 1.094607e+02 -4.268152e-02 9.990780e-01 4.614705e-03 -1.952829e+01 3.094726e-02 -3.294630e-03 9.995156e-01 2.016015e+02 +9.986971e-01 4.272194e-02 -2.790834e-02 1.094526e+02 -4.266278e-02 9.990858e-01 2.712337e-03 -1.953735e+01 2.799870e-02 -1.518155e-03 9.996068e-01 2.022165e+02 +9.988007e-01 4.239351e-02 -2.449498e-02 1.094487e+02 -4.243621e-02 9.990984e-01 -1.225625e-03 -1.954528e+01 2.442094e-02 2.263630e-03 9.996992e-01 2.028212e+02 +9.988796e-01 4.251290e-02 -2.078818e-02 1.094444e+02 -4.259838e-02 9.990855e-01 -3.686060e-03 -1.955351e+01 2.061246e-02 4.567473e-03 9.997771e-01 2.034194e+02 +9.989796e-01 4.218109e-02 -1.614054e-02 1.094454e+02 -4.226946e-02 9.990928e-01 -5.173160e-03 -1.956151e+01 1.590769e-02 5.850132e-03 9.998564e-01 2.040129e+02 +9.990817e-01 4.151979e-02 -1.058055e-02 1.094488e+02 -4.157811e-02 9.991209e-01 -5.351307e-03 -1.957126e+01 1.034906e-02 5.786312e-03 9.999297e-01 2.046022e+02 +9.991732e-01 4.031760e-02 -5.227953e-03 1.094586e+02 -4.034468e-02 9.991724e-01 -5.180036e-03 -1.958242e+01 5.014780e-03 5.386673e-03 9.999729e-01 2.051911e+02 +9.992580e-01 3.851019e-02 -6.016686e-04 1.094710e+02 -3.851324e-02 9.992381e-01 -6.309278e-03 -1.959431e+01 3.582390e-04 6.327768e-03 9.999799e-01 2.057753e+02 +9.992954e-01 3.735014e-02 3.690144e-03 1.094875e+02 -3.732188e-02 9.992755e-01 -7.451917e-03 -1.959506e+01 -3.965800e-03 7.308943e-03 9.999654e-01 2.063541e+02 +9.992508e-01 3.785971e-02 8.031584e-03 1.095025e+02 -3.779992e-02 9.992574e-01 -7.470266e-03 -1.959533e+01 -8.308441e-03 7.161075e-03 9.999399e-01 2.069296e+02 +9.992480e-01 3.687463e-02 1.198664e-02 1.095210e+02 -3.677628e-02 9.992888e-01 -8.324757e-03 -1.959699e+01 -1.228508e-02 7.877672e-03 9.998935e-01 2.074984e+02 +9.993102e-01 3.398941e-02 1.496399e-02 1.095462e+02 -3.385284e-02 9.993836e-01 -9.287962e-03 -1.959991e+01 -1.527046e-02 8.774981e-03 9.998449e-01 2.080624e+02 +9.993685e-01 3.121396e-02 1.698117e-02 1.095698e+02 -3.106577e-02 9.994775e-01 -8.921874e-03 -1.960596e+01 -1.725079e-02 8.388706e-03 9.998160e-01 2.086192e+02 +9.993802e-01 3.027302e-02 1.796397e-02 1.095912e+02 -3.011143e-02 9.995042e-01 -9.198759e-03 -1.961000e+01 -1.823354e-02 8.652137e-03 9.997963e-01 2.091680e+02 +9.993841e-01 3.036297e-02 1.759403e-02 1.096105e+02 -3.019309e-02 9.994956e-01 -9.842663e-03 -1.961501e+01 -1.788401e-02 9.305381e-03 9.997968e-01 2.097092e+02 +9.994433e-01 2.909821e-02 1.632379e-02 1.096322e+02 -2.893976e-02 9.995325e-01 -9.860397e-03 -1.962021e+01 -1.660308e-02 9.382499e-03 9.998181e-01 2.102391e+02 +9.995284e-01 2.716318e-02 1.432020e-02 1.096519e+02 -2.704165e-02 9.995972e-01 -8.613135e-03 -1.962804e+01 -1.454840e-02 8.221830e-03 9.998604e-01 2.107576e+02 +9.996206e-01 2.499756e-02 1.156957e-02 1.096719e+02 -2.490820e-02 9.996592e-01 -7.805170e-03 -1.963339e+01 -1.176074e-02 7.514030e-03 9.999026e-01 2.112627e+02 +9.996780e-01 2.402192e-02 8.171428e-03 1.096849e+02 -2.395216e-02 9.996767e-01 -8.530217e-03 -1.964077e+01 -8.373698e-03 8.331747e-03 9.999302e-01 2.117540e+02 +9.996872e-01 2.466021e-02 4.173056e-03 1.096980e+02 -2.461960e-02 9.996515e-01 -9.518742e-03 -1.964785e+01 -4.406336e-03 9.413025e-03 9.999460e-01 2.122328e+02 +9.996604e-01 2.605750e-02 9.465781e-05 1.097059e+02 -2.605541e-02 9.996146e-01 -9.572417e-03 -1.965567e+01 -3.440543e-04 9.566699e-03 9.999542e-01 2.127018e+02 +9.996487e-01 2.620076e-02 -3.994634e-03 1.097150e+02 -2.623928e-02 9.996065e-01 -9.915089e-03 -1.966281e+01 3.733280e-03 1.001642e-02 9.999429e-01 2.131666e+02 +9.996848e-01 2.376418e-02 -8.101991e-03 1.097249e+02 -2.385839e-02 9.996464e-01 -1.173618e-02 -1.967005e+01 7.820227e-03 1.192578e-02 9.998983e-01 2.136261e+02 +9.997026e-01 2.100101e-02 -1.239731e-02 1.097340e+02 -2.115947e-02 9.996943e-01 -1.279130e-02 -1.967764e+01 1.212489e-02 1.304982e-02 9.998413e-01 2.140837e+02 +9.996631e-01 1.952168e-02 -1.710452e-02 1.097377e+02 -1.973584e-02 9.997278e-01 -1.244200e-02 -1.968585e+01 1.685698e-02 1.277538e-02 9.997763e-01 2.145397e+02 +9.995583e-01 2.012911e-02 -2.186621e-02 1.097359e+02 -2.038470e-02 9.997257e-01 -1.152929e-02 -1.969486e+01 2.162814e-02 1.196993e-02 9.996944e-01 2.149935e+02 +9.994247e-01 2.123459e-02 -2.644481e-02 1.097311e+02 -2.153310e-02 9.997070e-01 -1.105467e-02 -1.970332e+01 2.620232e-02 1.161775e-02 9.995892e-01 2.154435e+02 +9.992577e-01 2.275026e-02 -3.108990e-02 1.097231e+02 -2.310347e-02 9.996720e-01 -1.104909e-02 -1.971161e+01 3.082834e-02 1.175918e-02 9.994555e-01 2.158880e+02 +9.990930e-01 2.407217e-02 -3.512300e-02 1.097150e+02 -2.447596e-02 9.996386e-01 -1.111184e-02 -1.972043e+01 3.484282e-02 1.196143e-02 9.993212e-01 2.163290e+02 +9.989841e-01 2.482072e-02 -3.761337e-02 1.097073e+02 -2.525879e-02 9.996180e-01 -1.121648e-02 -1.972933e+01 3.732060e-02 1.215515e-02 9.992294e-01 2.167639e+02 +9.989605e-01 2.429823e-02 -3.856948e-02 1.097028e+02 -2.477006e-02 9.996235e-01 -1.180264e-02 -1.973853e+01 3.826818e-02 1.274573e-02 9.991862e-01 2.171964e+02 +9.990019e-01 2.308413e-02 -3.824038e-02 1.097001e+02 -2.355815e-02 9.996505e-01 -1.199151e-02 -1.974628e+01 3.795021e-02 1.288042e-02 9.991966e-01 2.176247e+02 +9.990853e-01 2.154001e-02 -3.694030e-02 1.096998e+02 -2.198879e-02 9.996887e-01 -1.178572e-02 -1.975315e+01 3.667494e-02 1.258721e-02 9.992480e-01 2.180510e+02 +9.991361e-01 2.205932e-02 -3.521983e-02 1.096965e+02 -2.247254e-02 9.996827e-01 -1.137992e-02 -1.975951e+01 3.495762e-02 1.216157e-02 9.993148e-01 2.184744e+02 +9.991743e-01 2.283802e-02 -3.360299e-02 1.096942e+02 -2.325702e-02 9.996559e-01 -1.213127e-02 -1.976631e+01 3.331438e-02 1.290275e-02 9.993616e-01 2.189027e+02 +9.992203e-01 2.274435e-02 -3.227333e-02 1.096866e+02 -2.318642e-02 9.996415e-01 -1.338999e-02 -1.977855e+01 3.195721e-02 1.412785e-02 9.993894e-01 2.193469e+02 +9.992921e-01 2.202742e-02 -3.049854e-02 1.096738e+02 -2.244750e-02 9.996568e-01 -1.350046e-02 -1.979667e+01 3.019070e-02 1.417551e-02 9.994436e-01 2.198096e+02 +9.994627e-01 1.705384e-02 -2.799055e-02 1.096688e+02 -1.737658e-02 9.997848e-01 -1.132803e-02 -1.979923e+01 2.779134e-02 1.180832e-02 9.995440e-01 2.202738e+02 +9.995852e-01 1.349446e-02 -2.544162e-02 1.096628e+02 -1.372988e-02 9.998643e-01 -9.101383e-03 -1.980025e+01 2.531535e-02 9.446917e-03 9.996349e-01 2.207448e+02 +9.996233e-01 1.574410e-02 -2.248204e-02 1.096513e+02 -1.597626e-02 9.998205e-01 -1.018444e-02 -1.980454e+01 2.231766e-02 1.053978e-02 9.996954e-01 2.212173e+02 +9.995929e-01 2.091423e-02 -1.940903e-02 1.096342e+02 -2.116419e-02 9.996945e-01 -1.276368e-02 -1.980923e+01 1.913616e-02 1.316925e-02 9.997302e-01 2.216954e+02 +9.995822e-01 2.332000e-02 -1.707450e-02 1.096243e+02 -2.353663e-02 9.996436e-01 -1.259742e-02 -1.981376e+01 1.677465e-02 1.299403e-02 9.997749e-01 2.221819e+02 +9.996567e-01 2.115049e-02 -1.546770e-02 1.096232e+02 -2.132716e-02 9.997081e-01 -1.134733e-02 -1.981817e+01 1.522318e-02 1.167332e-02 9.998160e-01 2.226770e+02 +9.997912e-01 1.297754e-02 -1.578289e-02 1.096311e+02 -1.319227e-02 9.998208e-01 -1.357824e-02 -1.982004e+01 1.560385e-02 1.378361e-02 9.997833e-01 2.231789e+02 +9.998397e-01 8.834844e-03 -1.557672e-02 1.096329e+02 -9.024195e-03 9.998857e-01 -1.212782e-02 -1.982434e+01 1.546779e-02 1.226644e-02 9.998051e-01 2.236899e+02 +9.997925e-01 1.261711e-02 -1.599176e-02 1.096182e+02 -1.274689e-02 9.998864e-01 -8.039478e-03 -1.983255e+01 1.588851e-02 8.241654e-03 9.998398e-01 2.242158e+02 +9.996866e-01 1.796516e-02 -1.743479e-02 1.096041e+02 -1.807644e-02 9.998171e-01 -6.245509e-03 -1.983990e+01 1.731940e-02 6.558710e-03 9.998285e-01 2.247478e+02 +9.995982e-01 2.092992e-02 -1.911543e-02 1.095981e+02 -2.108211e-02 9.997473e-01 -7.794586e-03 -1.984897e+01 1.894746e-02 8.194447e-03 9.997869e-01 2.252855e+02 +9.995553e-01 2.088788e-02 -2.128214e-02 1.095939e+02 -2.105894e-02 9.997474e-01 -7.845586e-03 -1.985763e+01 2.111289e-02 8.290276e-03 9.997427e-01 2.258340e+02 +9.994899e-01 1.921157e-02 -2.551305e-02 1.095858e+02 -1.940280e-02 9.997853e-01 -7.268841e-03 -1.986994e+01 2.536793e-02 7.760157e-03 9.996481e-01 2.263959e+02 +9.993749e-01 1.645886e-02 -3.128727e-02 1.095698e+02 -1.670523e-02 9.998313e-01 -7.629473e-03 -1.988305e+01 3.115642e-02 8.147365e-03 9.994813e-01 2.269642e+02 +9.990777e-01 1.692659e-02 -3.946315e-02 1.095362e+02 -1.731780e-02 9.998040e-01 -9.592575e-03 -1.989364e+01 3.929305e-02 1.026714e-02 9.991750e-01 2.275411e+02 +9.985764e-01 1.939309e-02 -4.968939e-02 1.094946e+02 -1.995909e-02 9.997411e-01 -1.091971e-02 -1.990480e+01 4.946477e-02 1.189592e-02 9.987050e-01 2.281303e+02 +9.978169e-01 2.283827e-02 -6.196679e-02 1.094405e+02 -2.365030e-02 9.996433e-01 -1.240234e-02 -1.991549e+01 6.166145e-02 1.384080e-02 9.980012e-01 2.287239e+02 +9.967815e-01 2.438164e-02 -7.636944e-02 1.093750e+02 -2.564996e-02 9.995481e-01 -1.567086e-02 -1.993078e+01 7.595285e-02 1.757929e-02 9.969564e-01 2.293305e+02 +9.953979e-01 2.473054e-02 -9.258244e-02 1.092985e+02 -2.649361e-02 9.994894e-01 -1.786261e-02 -1.994947e+01 9.209342e-02 2.023324e-02 9.955448e-01 2.299476e+02 +9.935859e-01 2.808253e-02 -1.095376e-01 1.092015e+02 -3.015748e-02 9.993949e-01 -1.733203e-02 -1.996829e+01 1.089846e-01 2.052424e-02 9.938315e-01 2.305696e+02 +9.915709e-01 3.486843e-02 -1.247854e-01 1.090890e+02 -3.711902e-02 9.991866e-01 -1.575554e-02 -1.998438e+01 1.241346e-01 2.025465e-02 9.920587e-01 2.312049e+02 +9.897152e-01 4.175247e-02 -1.368230e-01 1.089629e+02 -4.417178e-02 9.989159e-01 -1.469241e-02 -2.000029e+01 1.360612e-01 2.058501e-02 9.904866e-01 2.318458e+02 +9.881982e-01 4.798367e-02 -1.454711e-01 1.088402e+02 -5.050859e-02 9.986295e-01 -1.371115e-02 -2.001747e+01 1.446139e-01 2.089687e-02 9.892675e-01 2.325004e+02 +9.871531e-01 5.241269e-02 -1.509358e-01 1.087096e+02 -5.511313e-02 9.983853e-01 -1.376100e-02 -2.002611e+01 1.499708e-01 2.190275e-02 9.884478e-01 2.331617e+02 +9.865029e-01 5.610372e-02 -1.538327e-01 1.085847e+02 -5.888568e-02 9.981723e-01 -1.358424e-02 -2.003373e+01 1.527894e-01 2.245944e-02 9.880035e-01 2.338312e+02 +9.860695e-01 6.133060e-02 -1.546142e-01 1.084533e+02 -6.405916e-02 9.978650e-01 -1.272270e-02 -2.004095e+01 1.535038e-01 2.244992e-02 9.878930e-01 2.345084e+02 +9.862212e-01 6.533538e-02 -1.519836e-01 1.083315e+02 -6.780545e-02 9.976366e-01 -1.112095e-02 -2.005123e+01 1.508978e-01 2.127303e-02 9.883205e-01 2.351948e+02 +9.869163e-01 6.804638e-02 -1.461706e-01 1.082113e+02 -7.013591e-02 9.974951e-01 -9.183248e-03 -2.006092e+01 1.451796e-01 1.931491e-02 9.892168e-01 2.358945e+02 +9.878751e-01 6.970281e-02 -1.387240e-01 1.081034e+02 -7.152928e-02 9.974046e-01 -8.218282e-03 -2.007076e+01 1.377911e-01 1.804146e-02 9.902970e-01 2.366033e+02 +9.890166e-01 7.117627e-02 -1.295379e-01 1.079985e+02 -7.291742e-02 9.972996e-01 -8.742253e-03 -2.008109e+01 1.285658e-01 1.809180e-02 9.915359e-01 2.373188e+02 +9.903025e-01 7.273365e-02 -1.183668e-01 1.079057e+02 -7.451649e-02 9.971623e-01 -1.070062e-02 -2.009265e+01 1.172527e-01 1.941713e-02 9.929123e-01 2.380488e+02 +9.916444e-01 7.284743e-02 -1.064640e-01 1.078200e+02 -7.469518e-02 9.971155e-01 -1.346695e-02 -2.010391e+01 1.051758e-01 2.130676e-02 9.942254e-01 2.387825e+02 +9.929716e-01 7.169794e-02 -9.416366e-02 1.077486e+02 -7.343740e-02 9.971850e-01 -1.513462e-02 -2.011759e+01 9.281347e-02 2.194338e-02 9.954417e-01 2.395361e+02 +9.940535e-01 7.183466e-02 -8.183825e-02 1.076809e+02 -7.334315e-02 9.971851e-01 -1.557386e-02 -2.013306e+01 8.048915e-02 2.148352e-02 9.965239e-01 2.402948e+02 +9.949757e-01 7.209285e-02 -6.946865e-02 1.076253e+02 -7.338528e-02 9.971715e-01 -1.623205e-02 -2.015156e+01 6.810195e-02 2.124847e-02 9.974521e-01 2.410683e+02 +9.956816e-01 7.277591e-02 -5.763480e-02 1.075772e+02 -7.382878e-02 9.971369e-01 -1.635111e-02 -2.016997e+01 5.627982e-02 2.053560e-02 9.982038e-01 2.418507e+02 +9.962524e-01 7.256334e-02 -4.707159e-02 1.075357e+02 -7.344189e-02 9.971510e-01 -1.720858e-02 -2.018814e+01 4.568878e-02 2.060112e-02 9.987433e-01 2.426402e+02 +9.966922e-01 7.177103e-02 -3.812484e-02 1.075007e+02 -7.249086e-02 9.972094e-01 -1.784443e-02 -2.020483e+01 3.673774e-02 2.054911e-02 9.991137e-01 2.434404e+02 +9.969810e-01 7.130425e-02 -3.073572e-02 1.074632e+02 -7.191228e-02 9.972271e-01 -1.915137e-02 -2.021605e+01 2.928492e-02 2.130383e-02 9.993441e-01 2.442411e+02 +9.971931e-01 7.055908e-02 -2.504559e-02 1.074336e+02 -7.108988e-02 9.972493e-01 -2.097513e-02 -2.023084e+01 2.349672e-02 2.269674e-02 9.994662e-01 2.450557e+02 +9.973018e-01 7.041789e-02 -2.074911e-02 1.074043e+02 -7.087443e-02 9.972391e-01 -2.215511e-02 -2.024443e+01 1.913171e-02 2.356591e-02 9.995392e-01 2.458782e+02 +9.974001e-01 6.987700e-02 -1.761644e-02 1.073806e+02 -7.025352e-02 9.972921e-01 -2.174485e-02 -2.026289e+01 1.604927e-02 2.292593e-02 9.996083e-01 2.467154e+02 +9.974808e-01 6.907329e-02 -1.615266e-02 1.073557e+02 -6.941231e-02 9.973571e-01 -2.146384e-02 -2.028286e+01 1.462739e-02 2.253096e-02 9.996391e-01 2.475613e+02 +9.975021e-01 6.883927e-02 -1.583232e-02 1.073326e+02 -6.915469e-02 9.973989e-01 -2.032045e-02 -2.030368e+01 1.439230e-02 2.136457e-02 9.996682e-01 2.484161e+02 +9.975662e-01 6.786106e-02 -1.601904e-02 1.073087e+02 -6.813977e-02 9.975215e-01 -1.754463e-02 -2.032154e+01 1.478874e-02 1.859347e-02 9.997178e-01 2.492774e+02 +9.975176e-01 6.848675e-02 -1.637760e-02 1.072843e+02 -6.868950e-02 9.975640e-01 -1.215410e-02 -2.033882e+01 1.550531e-02 1.324890e-02 9.997920e-01 2.501470e+02 +9.974536e-01 6.941713e-02 -1.635610e-02 1.072566e+02 -6.950595e-02 9.975694e-01 -4.924325e-03 -2.035574e+01 1.597451e-02 6.048632e-03 9.998541e-01 2.510213e+02 +9.973462e-01 7.081736e-02 -1.689858e-02 1.072292e+02 -7.082739e-02 9.974886e-01 5.620636e-06 -2.036844e+01 1.685654e-02 1.191277e-03 9.998572e-01 2.518934e+02 +9.973449e-01 7.062877e-02 -1.773930e-02 1.072037e+02 -7.062596e-02 9.975025e-01 7.865698e-04 -2.037989e+01 1.775055e-02 4.683744e-04 9.998423e-01 2.527604e+02 +9.973052e-01 7.091968e-02 -1.878014e-02 1.071766e+02 -7.095878e-02 9.974782e-01 -1.422243e-03 -2.038942e+01 1.863192e-02 2.751026e-03 9.998226e-01 2.536248e+02 +9.972081e-01 7.190247e-02 -2.015194e-02 1.071473e+02 -7.198384e-02 9.974002e-01 -3.340201e-03 -2.039863e+01 1.985938e-02 4.781489e-03 9.997914e-01 2.544881e+02 +9.970739e-01 7.341917e-02 -2.128870e-02 1.071157e+02 -7.350388e-02 9.972897e-01 -3.222340e-03 -2.040954e+01 2.099442e-02 4.777713e-03 9.997682e-01 2.553524e+02 +9.970140e-01 7.390475e-02 -2.238858e-02 1.070857e+02 -7.395913e-02 9.972600e-01 -1.608808e-03 -2.042147e+01 2.220834e-02 3.259844e-03 9.997481e-01 2.562168e+02 +9.969447e-01 7.448961e-02 -2.350821e-02 1.070537e+02 -7.453862e-02 9.972174e-01 -1.213547e-03 -2.043392e+01 2.335240e-02 2.962108e-03 9.997229e-01 2.570779e+02 +9.968255e-01 7.572462e-02 -2.459140e-02 1.070220e+02 -7.578298e-02 9.971233e-01 -1.447583e-03 -2.044446e+01 2.441104e-02 3.306597e-03 9.996965e-01 2.579359e+02 +9.968544e-01 7.497656e-02 -2.568541e-02 1.069903e+02 -7.507229e-02 9.971742e-01 -2.781264e-03 -2.045451e+01 2.540430e-02 4.700777e-03 9.996662e-01 2.587883e+02 +9.968399e-01 7.472819e-02 -2.694139e-02 1.069599e+02 -7.488678e-02 9.971799e-01 -4.924351e-03 -2.046799e+01 2.649743e-02 6.926344e-03 9.996249e-01 2.596410e+02 +9.967083e-01 7.634897e-02 -2.726628e-02 1.069251e+02 -7.647743e-02 9.970644e-01 -3.698013e-03 -2.047752e+01 2.690390e-02 5.771095e-03 9.996214e-01 2.604945e+02 +9.964764e-01 7.943388e-02 -2.692781e-02 1.068888e+02 -7.948286e-02 9.968359e-01 -7.509042e-04 -2.048509e+01 2.678297e-02 2.888558e-03 9.996371e-01 2.613457e+02 +9.964790e-01 7.961470e-02 -2.628775e-02 1.068579e+02 -7.954337e-02 9.968243e-01 3.750643e-03 -2.049593e+01 2.650288e-02 -1.646419e-03 9.996474e-01 2.621939e+02 +9.964811e-01 7.981704e-02 -2.558562e-02 1.068276e+02 -7.979182e-02 9.968095e-01 2.007500e-03 -2.050276e+01 2.566422e-02 4.108817e-05 9.996706e-01 2.630286e+02 +9.962571e-01 8.288845e-02 -2.452218e-02 1.068039e+02 -8.292773e-02 9.965554e-01 -5.865067e-04 -2.050631e+01 2.438910e-02 2.617881e-03 9.996991e-01 2.638535e+02 +9.962093e-01 8.376820e-02 -2.345078e-02 1.067901e+02 -8.382517e-02 9.964794e-01 -1.454610e-03 -2.051163e+01 2.324637e-02 3.414861e-03 9.997239e-01 2.646712e+02 +9.962169e-01 8.405799e-02 -2.204739e-02 1.067730e+02 -8.406943e-02 9.964598e-01 4.097769e-04 -2.052297e+01 2.200378e-02 1.445285e-03 9.997569e-01 2.654734e+02 +9.961566e-01 8.520922e-02 -2.028199e-02 1.067568e+02 -8.520164e-02 9.963629e-01 1.240037e-03 -2.053362e+01 2.031389e-02 4.927888e-04 9.997935e-01 2.662565e+02 +9.960979e-01 8.625085e-02 -1.870251e-02 1.067394e+02 -8.623399e-02 9.962734e-01 1.708391e-03 -2.054127e+01 1.878016e-02 -8.893214e-05 9.998236e-01 2.670270e+02 +9.961367e-01 8.614605e-02 -1.704478e-02 1.067418e+02 -8.612310e-02 9.962823e-01 2.077879e-03 -2.054682e+01 1.716042e-02 -6.019007e-04 9.998526e-01 2.677687e+02 +9.962010e-01 8.568074e-02 -1.556896e-02 1.067368e+02 -8.565546e-02 9.963222e-01 2.285759e-03 -2.055359e+01 1.570754e-02 -9.435086e-04 9.998762e-01 2.684959e+02 +9.961543e-01 8.647959e-02 -1.406726e-02 1.067324e+02 -8.645667e-02 9.962531e-01 2.231914e-03 -2.055697e+01 1.420757e-02 -1.007121e-03 9.998986e-01 2.691976e+02 +9.961828e-01 8.633061e-02 -1.292052e-02 1.067246e+02 -8.631567e-02 9.962663e-01 1.711971e-03 -2.055823e+01 1.302008e-02 -5.901913e-04 9.999151e-01 2.698814e+02 +9.962176e-01 8.596727e-02 -1.265314e-02 1.067211e+02 -8.595873e-02 9.962979e-01 1.219842e-03 -2.055910e+01 1.271117e-02 -1.275787e-04 9.999192e-01 2.705430e+02 +9.961914e-01 8.625117e-02 -1.278806e-02 1.067095e+02 -8.625401e-02 9.962731e-01 3.318350e-04 -2.056373e+01 1.276902e-02 7.724505e-04 9.999182e-01 2.711926e+02 +9.961493e-01 8.671597e-02 -1.292311e-02 1.066870e+02 -8.674211e-02 9.962297e-01 -1.473404e-03 -2.057009e+01 1.274662e-02 2.588708e-03 9.999154e-01 2.718318e+02 +9.960333e-01 8.802599e-02 -1.300393e-02 1.066646e+02 -8.806888e-02 9.961105e-01 -2.760918e-03 -2.057444e+01 1.271032e-02 3.895208e-03 9.999116e-01 2.724513e+02 +9.960907e-01 8.730935e-02 -1.342998e-02 1.066455e+02 -8.739652e-02 9.961552e-01 -6.044561e-03 -2.057985e+01 1.285060e-02 7.194665e-03 9.998916e-01 2.730537e+02 +9.961478e-01 8.661594e-02 -1.368071e-02 1.066239e+02 -8.676439e-02 9.961718e-01 -1.065549e-02 -2.058709e+01 1.270540e-02 1.180144e-02 9.998496e-01 2.736455e+02 +9.962360e-01 8.560902e-02 -1.360106e-02 1.066024e+02 -8.579830e-02 9.962141e-01 -1.400022e-02 -2.059638e+01 1.235102e-02 1.511447e-02 9.998095e-01 2.742317e+02 +9.960985e-01 8.729219e-02 -1.295582e-02 1.065774e+02 -8.751834e-02 9.959993e-01 -1.805437e-02 -2.060587e+01 1.132799e-02 1.911780e-02 9.997531e-01 2.748081e+02 +9.960852e-01 8.754178e-02 -1.228022e-02 1.065581e+02 -8.778107e-02 9.959283e-01 -2.052618e-02 -2.061783e+01 1.043332e-02 2.152379e-02 9.997139e-01 2.753754e+02 +9.961792e-01 8.656922e-02 -1.152359e-02 1.065411e+02 -8.679778e-02 9.960029e-01 -2.108103e-02 -2.063156e+01 9.652558e-03 2.200070e-02 9.997114e-01 2.759360e+02 +9.966016e-01 8.183853e-02 -9.370558e-03 1.065323e+02 -8.201092e-02 9.964350e-01 -1.978721e-02 -2.064421e+01 7.717796e-03 2.048845e-02 9.997603e-01 2.764853e+02 +9.967024e-01 8.077411e-02 -7.737264e-03 1.065116e+02 -8.090673e-02 9.965459e-01 -1.871473e-02 -2.065813e+01 6.198874e-03 1.927901e-02 9.997949e-01 2.770265e+02 +9.965911e-01 8.233471e-02 -5.208594e-03 1.064901e+02 -8.241880e-02 9.964208e-01 -1.877866e-02 -2.067288e+01 3.643816e-03 1.914393e-02 9.998101e-01 2.775489e+02 +9.962770e-01 8.619414e-02 -1.627996e-03 1.064652e+02 -8.620953e-02 9.961080e-01 -1.835089e-02 -2.068633e+01 3.992120e-05 1.842292e-02 9.998303e-01 2.780589e+02 +9.961683e-01 8.737397e-02 3.819155e-03 1.064458e+02 -8.729212e-02 9.960205e-01 -1.797532e-02 -2.069880e+01 -5.374532e-03 1.757306e-02 9.998311e-01 2.785509e+02 +9.964765e-01 8.322244e-02 1.042037e-02 1.064310e+02 -8.300574e-02 9.963535e-01 -1.974195e-02 -2.071058e+01 -1.202534e-02 1.880743e-02 9.997508e-01 2.790243e+02 +9.965471e-01 8.070157e-02 1.952555e-02 1.064277e+02 -8.028250e-02 9.965430e-01 -2.137303e-02 -2.072071e+01 -2.118289e-02 1.973166e-02 9.995809e-01 2.794745e+02 +9.961504e-01 8.201175e-02 3.095808e-02 1.064232e+02 -8.135183e-02 9.964424e-01 -2.200869e-02 -2.073438e+01 -3.265291e-02 1.940547e-02 9.992784e-01 2.799078e+02 +9.954166e-01 8.520870e-02 4.342004e-02 1.064360e+02 -8.432187e-02 9.961986e-01 -2.186609e-02 -2.075074e+01 -4.511817e-02 1.810461e-02 9.988176e-01 2.803259e+02 +9.946720e-01 8.650132e-02 5.608176e-02 1.064550e+02 -8.531806e-02 9.960844e-01 -2.316541e-02 -2.076485e+01 -5.786601e-02 1.825719e-02 9.981574e-01 2.807250e+02 +9.939660e-01 8.399029e-02 7.054908e-02 1.064902e+02 -8.239049e-02 9.962791e-01 -2.529373e-02 -2.078175e+01 -7.241100e-02 1.932853e-02 9.971876e-01 2.811131e+02 +9.928525e-01 8.163383e-02 8.706279e-02 1.065257e+02 -7.950031e-02 9.964498e-01 -2.770364e-02 -2.079543e+01 -8.901525e-02 2.058411e-02 9.958176e-01 2.814834e+02 +9.911041e-01 8.038579e-02 1.060702e-01 1.065712e+02 -7.762252e-02 9.965333e-01 -2.993437e-02 -2.080923e+01 -1.081088e-01 2.143464e-02 9.939080e-01 2.818427e+02 +9.888531e-01 7.869851e-02 1.263966e-01 1.066248e+02 -7.529526e-02 9.966640e-01 -3.148842e-02 -2.082197e+01 -1.284531e-01 2.162035e-02 9.914799e-01 2.821855e+02 +9.860758e-01 7.587887e-02 1.479759e-01 1.066908e+02 -7.164057e-02 9.968586e-01 -3.377232e-02 -2.083403e+01 -1.500736e-01 2.270099e-02 9.884142e-01 2.825002e+02 +9.826809e-01 7.196276e-02 1.707620e-01 1.067652e+02 -6.665102e-02 9.971032e-01 -3.664535e-02 -2.085102e+01 -1.729045e-01 2.462921e-02 9.846306e-01 2.828166e+02 +9.786913e-01 6.673071e-02 1.941914e-01 1.068406e+02 -6.021880e-02 9.974131e-01 -3.925241e-02 -2.086472e+01 -1.963084e-01 2.672201e-02 9.801780e-01 2.831060e+02 +9.741108e-01 6.063761e-02 2.177872e-01 1.069342e+02 -5.282160e-02 9.977397e-01 -4.153813e-02 -2.088342e+01 -2.198137e-01 2.895887e-02 9.751120e-01 2.833937e+02 +9.688359e-01 5.763711e-02 2.409043e-01 1.070452e+02 -4.850526e-02 9.978677e-01 -4.367119e-02 -2.090854e+01 -2.429078e-01 3.062509e-02 9.695659e-01 2.836660e+02 +9.629036e-01 5.330118e-02 2.645292e-01 1.071487e+02 -4.239994e-02 9.980061e-01 -4.675424e-02 -2.092866e+01 -2.664938e-01 3.380380e-02 9.632437e-01 2.839142e+02 +9.559399e-01 5.261107e-02 2.888097e-01 1.072645e+02 -4.003173e-02 9.979817e-01 -4.929534e-02 -2.095487e+01 -2.908203e-01 3.556182e-02 9.561166e-01 2.841748e+02 +9.479085e-01 5.332281e-02 3.140480e-01 1.073632e+02 -3.949346e-02 9.979560e-01 -5.023958e-02 -2.097140e+01 -3.160851e-01 3.521967e-02 9.480769e-01 2.844136e+02 +9.391286e-01 5.460302e-02 3.391990e-01 1.074915e+02 -4.014986e-02 9.979674e-01 -4.948765e-02 -2.099230e+01 -3.412117e-01 3.285647e-02 9.394121e-01 2.846629e+02 +9.291514e-01 5.247557e-02 3.659563e-01 1.076150e+02 -3.796843e-02 9.981856e-01 -4.673220e-02 -2.100366e+01 -3.677446e-01 2.952649e-02 9.294580e-01 2.848854e+02 +9.183213e-01 4.716358e-02 3.930161e-01 1.077619e+02 -3.293656e-02 9.985376e-01 -4.286916e-02 -2.102589e+01 -3.944633e-01 2.642305e-02 9.185317e-01 2.851221e+02 +9.069351e-01 4.072774e-02 4.192970e-01 1.079101e+02 -2.658703e-02 9.988651e-01 -3.951573e-02 -2.104536e+01 -4.204306e-01 2.469034e-02 9.069887e-01 2.853505e+02 +8.949647e-01 3.386073e-02 4.448501e-01 1.080529e+02 -2.005249e-02 9.991609e-01 -3.571104e-02 -2.106095e+01 -4.456861e-01 2.303976e-02 8.948928e-01 2.855530e+02 +8.821372e-01 2.769431e-02 4.701776e-01 1.082200e+02 -1.388902e-02 9.993652e-01 -3.280616e-02 -2.108128e+01 -4.707877e-01 2.240923e-02 8.819619e-01 2.857643e+02 +8.684246e-01 2.322216e-02 4.952772e-01 1.083903e+02 -8.656633e-03 9.994604e-01 -3.168328e-02 -2.109914e+01 -4.957458e-01 2.322710e-02 8.681571e-01 2.859484e+02 +8.540717e-01 2.012143e-02 5.197659e-01 1.085642e+02 -5.286559e-03 9.995357e-01 -3.000773e-02 -2.111145e+01 -5.201284e-01 2.288098e-02 8.537816e-01 2.861623e+02 +8.393849e-01 1.902772e-02 5.432043e-01 1.087454e+02 -4.427250e-03 9.995932e-01 -2.817323e-02 -2.112366e+01 -5.435194e-01 2.124328e-02 8.391278e-01 2.863827e+02 +8.240242e-01 1.814872e-02 5.662638e-01 1.089350e+02 -3.889888e-03 9.996444e-01 -2.637800e-02 -2.113768e+01 -5.665413e-01 1.953340e-02 8.238018e-01 2.865870e+02 +8.095460e-01 1.568658e-02 5.868468e-01 1.091344e+02 -2.133763e-03 9.997149e-01 -2.377918e-02 -2.115246e+01 -5.870526e-01 1.799814e-02 8.093487e-01 2.868147e+02 +7.990564e-01 1.165035e-02 6.011432e-01 1.093403e+02 2.017891e-03 9.997546e-01 -2.205782e-02 -2.116513e+01 -6.012527e-01 1.883848e-02 7.988369e-01 2.870428e+02 +7.948485e-01 5.492085e-03 6.067831e-01 1.095356e+02 9.876627e-03 9.997095e-01 -2.198630e-02 -2.117021e+01 -6.067276e-01 2.346874e-02 7.945633e-01 2.872813e+02 +7.949778e-01 2.040737e-03 6.066351e-01 1.097161e+02 1.353007e-02 9.996859e-01 -2.109373e-02 -2.117354e+01 -6.064877e-01 2.497686e-02 7.947005e-01 2.875205e+02 +7.967424e-01 8.789723e-04 6.043185e-01 1.098714e+02 1.264908e-02 9.997556e-01 -1.813086e-02 -2.117719e+01 -6.041867e-01 2.208969e-02 7.965365e-01 2.877558e+02 +8.023000e-01 1.398807e-03 5.969194e-01 1.099973e+02 1.082450e-02 9.997987e-01 -1.689176e-02 -2.117356e+01 -5.968230e-01 2.001361e-02 8.021233e-01 2.879873e+02 +8.118774e-01 1.554616e-03 5.838258e-01 1.101220e+02 1.078937e-02 9.997857e-01 -1.766611e-02 -2.117641e+01 -5.837282e-01 2.064183e-02 8.116867e-01 2.882030e+02 +8.217044e-01 3.707667e-03 5.699018e-01 1.102277e+02 8.685224e-03 9.997812e-01 -1.902704e-02 -2.117758e+01 -5.698477e-01 2.058432e-02 8.214925e-01 2.884052e+02 +8.322266e-01 4.260800e-03 5.544193e-01 1.103279e+02 8.703476e-03 9.997468e-01 -2.074781e-02 -2.117787e+01 -5.543673e-01 2.209225e-02 8.319789e-01 2.886100e+02 +8.465319e-01 3.393389e-03 5.323271e-01 1.104221e+02 1.014746e-02 9.996951e-01 -2.250966e-02 -2.117765e+01 -5.322413e-01 2.445691e-02 8.462394e-01 2.888200e+02 +8.628554e-01 1.941353e-05 5.054508e-01 1.104922e+02 1.360171e-02 9.996369e-01 -2.325788e-02 -2.118079e+01 -5.052678e-01 2.694318e-02 8.625419e-01 2.890061e+02 +8.797806e-01 -1.127184e-03 4.753786e-01 1.105604e+02 1.404835e-02 9.996221e-01 -2.362896e-02 -2.118330e+01 -4.751723e-01 2.746658e-02 8.794640e-01 2.892303e+02 +8.978097e-01 -1.098436e-03 4.403823e-01 1.105865e+02 1.260363e-02 9.996513e-01 -2.320168e-02 -2.117479e+01 -4.402033e-01 2.638111e-02 8.975105e-01 2.894183e+02 +9.165856e-01 3.593918e-05 3.998384e-01 1.106194e+02 1.002811e-02 9.996833e-01 -2.307820e-02 -2.117089e+01 -3.997127e-01 2.516276e-02 9.162951e-01 2.896498e+02 +9.341383e-01 2.927029e-03 3.568993e-01 1.106349e+02 5.577547e-03 9.997245e-01 -2.279753e-02 -2.116990e+01 -3.568677e-01 2.328666e-02 9.338646e-01 2.898888e+02 +9.498628e-01 6.390958e-03 3.126018e-01 1.106183e+02 3.798310e-04 9.997667e-01 -2.159378e-02 -2.116498e+01 -3.126669e-01 2.062986e-02 9.496388e-01 2.900641e+02 +9.639915e-01 9.793723e-03 2.657527e-01 1.106031e+02 -4.623315e-03 9.997878e-01 -2.007434e-02 -2.116364e+01 -2.658929e-01 1.812283e-02 9.638322e-01 2.903045e+02 +9.758701e-01 1.215510e-02 2.180133e-01 1.105790e+02 -8.191441e-03 9.997845e-01 -1.907545e-02 -2.115622e+01 -2.181982e-01 1.682931e-02 9.757594e-01 2.905374e+02 +9.852214e-01 1.401589e-02 1.707112e-01 1.105188e+02 -1.100070e-02 9.997665e-01 -1.859569e-02 -2.114241e+01 -1.709320e-01 1.644292e-02 9.851456e-01 2.907081e+02 +9.921928e-01 1.547793e-02 1.237490e-01 1.104899e+02 -1.335285e-02 9.997491e-01 -1.798355e-02 -2.114207e+01 -1.239963e-01 1.619074e-02 9.921506e-01 2.909310e+02 +9.969269e-01 1.725316e-02 7.641413e-02 1.104155e+02 -1.605427e-02 9.997386e-01 -1.627606e-02 -2.112873e+01 -7.667498e-02 1.499927e-02 9.969433e-01 2.910913e+02 +9.993999e-01 1.958756e-02 2.856840e-02 1.103706e+02 -1.922538e-02 9.997320e-01 -1.289784e-02 -2.112385e+01 -2.881338e-02 1.234086e-02 9.995086e-01 2.913143e+02 +9.995964e-01 2.111318e-02 -1.900496e-02 1.103084e+02 -2.127323e-02 9.997396e-01 -8.258623e-03 -2.111056e+01 1.882565e-02 8.659587e-03 9.997853e-01 2.915393e+02 +9.975054e-01 2.147424e-02 -6.724464e-02 1.102142e+02 -2.172129e-02 9.997597e-01 -2.944640e-03 -2.109859e+01 6.716525e-02 4.397935e-03 9.977322e-01 2.916984e+02 +9.928706e-01 2.122261e-02 -1.172927e-01 1.101419e+02 -2.121140e-02 9.997741e-01 1.344049e-03 -2.109273e+01 1.172947e-01 1.153475e-03 9.930965e-01 2.919254e+02 +9.855578e-01 2.217840e-02 -1.678809e-01 1.100574e+02 -2.149209e-02 9.997516e-01 5.904184e-03 -2.108998e+01 1.679701e-01 -2.210802e-03 9.857896e-01 2.921577e+02 +9.758501e-01 2.545407e-02 -2.169534e-01 1.099383e+02 -2.345170e-02 9.996553e-01 1.179957e-02 -2.108239e+01 2.171790e-01 -6.426678e-03 9.761107e-01 2.923221e+02 +9.642345e-01 3.050219e-02 -2.632898e-01 1.098366e+02 -2.656182e-02 9.994757e-01 1.851336e-02 -2.108711e+01 2.637165e-01 -1.085776e-02 9.645391e-01 2.925490e+02 +9.516424e-01 3.683123e-02 -3.049920e-01 1.097116e+02 -3.083254e-02 9.992251e-01 2.446339e-02 -2.108416e+01 3.056568e-01 -1.387671e-02 9.520407e-01 2.927241e+02 +9.398052e-01 4.187763e-02 -3.391347e-01 1.096099e+02 -3.405647e-02 9.989995e-01 2.898344e-02 -2.109160e+01 3.400092e-01 -1.568906e-02 9.402912e-01 2.929363e+02 +9.292648e-01 4.506388e-02 -3.666554e-01 1.094965e+02 -3.529403e-02 9.988217e-01 3.331000e-02 -2.108926e+01 3.677245e-01 -1.801306e-02 9.297603e-01 2.931502e+02 +9.197302e-01 4.639473e-02 -3.897998e-01 1.093767e+02 -3.441357e-02 9.986975e-01 3.766833e-02 -2.108632e+01 3.910398e-01 -2.123029e-02 9.201289e-01 2.933537e+02 +9.110730e-01 4.591174e-02 -4.096804e-01 1.092576e+02 -3.142392e-02 9.986220e-01 4.203032e-02 -2.108279e+01 4.110456e-01 -2.541892e-02 9.112603e-01 2.935766e+02 +9.029645e-01 5.034410e-02 -4.267559e-01 1.091270e+02 -3.522823e-02 9.984431e-01 4.324695e-02 -2.108147e+01 4.282687e-01 -2.401660e-02 9.033323e-01 2.937863e+02 +8.955918e-01 5.608471e-02 -4.413274e-01 1.089878e+02 -4.348100e-02 9.983071e-01 3.863018e-02 -2.107594e+01 4.427468e-01 -1.540751e-02 8.965143e-01 2.940048e+02 +8.906064e-01 6.134910e-02 -4.506180e-01 1.088409e+02 -5.168745e-02 9.980935e-01 3.372919e-02 -2.106764e+01 4.518282e-01 -6.748137e-03 8.920795e-01 2.942354e+02 +8.876554e-01 6.321169e-02 -4.561492e-01 1.086981e+02 -5.414369e-02 9.979898e-01 3.293592e-02 -2.105818e+01 4.573143e-01 -4.538140e-03 8.892936e-01 2.944851e+02 +8.856457e-01 5.746956e-02 -4.607916e-01 1.085604e+02 -4.888789e-02 9.983370e-01 3.054883e-02 -2.105078e+01 4.617810e-01 -4.528311e-03 8.869824e-01 2.947576e+02 +8.852248e-01 5.452628e-02 -4.619567e-01 1.084148e+02 -4.960356e-02 9.985086e-01 2.280447e-02 -2.105133e+01 4.625112e-01 2.727618e-03 8.866092e-01 2.950346e+02 +8.882860e-01 5.777709e-02 -4.556422e-01 1.082567e+02 -5.951638e-02 9.981716e-01 1.054313e-02 -2.105507e+01 4.554183e-01 1.775286e-02 8.901006e-01 2.953141e+02 +8.932579e-01 6.148405e-02 -4.453201e-01 1.080953e+02 -7.051437e-02 9.975038e-01 -3.720755e-03 -2.105834e+01 4.439798e-01 3.472506e-02 8.953637e-01 2.955943e+02 +9.013857e-01 5.806741e-02 -4.291061e-01 1.079540e+02 -7.318689e-02 9.971410e-01 -1.880236e-02 -2.106135e+01 4.267875e-01 4.835311e-02 9.030584e-01 2.959095e+02 +9.124699e-01 5.405878e-02 -4.055568e-01 1.078181e+02 -7.334737e-02 9.967878e-01 -3.215854e-02 -2.106720e+01 4.025156e-01 5.909021e-02 9.135040e-01 2.962192e+02 +9.228102e-01 6.167943e-02 -3.802853e-01 1.076829e+02 -8.382688e-02 9.955974e-01 -4.193800e-02 -2.107710e+01 3.760244e-01 7.057894e-02 9.239179e-01 2.965682e+02 +9.320466e-01 6.392155e-02 -3.566556e-01 1.075527e+02 -8.699217e-02 9.950028e-01 -4.900698e-02 -2.107916e+01 3.517408e-01 7.670302e-02 9.329497e-01 2.969339e+02 +9.409368e-01 6.128258e-02 -3.329900e-01 1.074283e+02 -8.152096e-02 9.955564e-01 -4.713595e-02 -2.107823e+01 3.286217e-01 7.149760e-02 9.417515e-01 2.973040e+02 +9.496851e-01 6.382549e-02 -3.066343e-01 1.073098e+02 -7.953694e-02 9.960685e-01 -3.900567e-02 -2.108672e+01 3.029392e-01 6.143184e-02 9.510279e-01 2.977079e+02 +9.563808e-01 7.132501e-02 -2.832815e-01 1.071833e+02 -8.238325e-02 9.962267e-01 -2.730099e-02 -2.111252e+01 2.802654e-01 4.944779e-02 9.586481e-01 2.981088e+02 +9.614054e-01 8.012835e-02 -2.632094e-01 1.070650e+02 -8.714858e-02 9.960811e-01 -1.508592e-02 -2.113832e+01 2.609691e-01 3.744200e-02 9.646208e-01 2.985371e+02 +9.660892e-01 8.264183e-02 -2.446261e-01 1.069519e+02 -8.744856e-02 9.961298e-01 -8.834294e-03 -2.115676e+01 2.429493e-01 2.992691e-02 9.695772e-01 2.989688e+02 +9.705321e-01 8.014147e-02 -2.272549e-01 1.068552e+02 -8.410753e-02 9.964261e-01 -7.806151e-03 -2.117548e+01 2.258171e-01 2.668996e-02 9.738040e-01 2.994182e+02 +9.742929e-01 7.792907e-02 -2.113774e-01 1.067611e+02 -8.201742e-02 9.965742e-01 -1.062967e-02 -2.118976e+01 2.098249e-01 2.769304e-02 9.773467e-01 2.998830e+02 +9.777943e-01 7.408200e-02 -1.960364e-01 1.066698e+02 -7.852076e-02 9.968002e-01 -1.495732e-02 -2.119641e+01 1.943011e-01 3.001811e-02 9.804826e-01 3.003619e+02 +9.809661e-01 7.212887e-02 -1.802859e-01 1.065896e+02 -7.685982e-02 9.968534e-01 -1.938560e-02 -2.120864e+01 1.783203e-01 3.287335e-02 9.834232e-01 3.008719e+02 +9.839010e-01 6.944327e-02 -1.646709e-01 1.065046e+02 -7.381956e-02 9.970588e-01 -2.059922e-02 -2.121625e+01 1.627561e-01 3.242352e-02 9.861335e-01 3.014040e+02 +9.863568e-01 6.863923e-02 -1.496290e-01 1.064248e+02 -7.209571e-02 9.972390e-01 -1.779307e-02 -2.122495e+01 1.479946e-01 2.833792e-02 9.885821e-01 3.019669e+02 +9.884543e-01 6.823563e-02 -1.352847e-01 1.063516e+02 -7.054644e-02 9.974319e-01 -1.235563e-02 -2.122993e+01 1.340942e-01 2.175683e-02 9.907297e-01 3.025590e+02 +9.900258e-01 6.758813e-02 -1.236150e-01 1.062751e+02 -6.906258e-02 9.975828e-01 -7.676858e-03 -2.123378e+01 1.227974e-01 1.613746e-02 9.923006e-01 3.031660e+02 +9.914063e-01 6.288061e-02 -1.147149e-01 1.062120e+02 -6.418964e-02 9.979076e-01 -7.749361e-03 -2.124230e+01 1.139876e-01 1.504627e-02 9.933682e-01 3.037915e+02 +9.924951e-01 5.564357e-02 -1.088916e-01 1.061513e+02 -5.693226e-02 9.983396e-01 -8.759105e-03 -2.124825e+01 1.082234e-01 1.489281e-02 9.940151e-01 3.044385e+02 +9.931429e-01 4.932601e-02 -1.059911e-01 1.060858e+02 -5.100480e-02 9.986113e-01 -1.318543e-02 -2.125153e+01 1.051935e-01 1.850107e-02 9.942797e-01 3.051013e+02 +9.935302e-01 4.875462e-02 -1.025702e-01 1.060102e+02 -5.080273e-02 9.985562e-01 -1.744959e-02 -2.125520e+01 1.015714e-01 2.254754e-02 9.945727e-01 3.057851e+02 +9.935673e-01 5.496373e-02 -9.901026e-02 1.059159e+02 -5.700827e-02 9.982125e-01 -1.793808e-02 -2.126581e+01 9.784734e-02 2.346709e-02 9.949247e-01 3.064894e+02 +9.940220e-01 5.714691e-02 -9.302983e-02 1.058323e+02 -5.903899e-02 9.980985e-01 -1.771254e-02 -2.128087e+01 9.184073e-02 2.309904e-02 9.955058e-01 3.072154e+02 +9.943809e-01 6.296885e-02 -8.509751e-02 1.057554e+02 -6.460289e-02 9.977732e-01 -1.658367e-02 -2.129781e+01 8.386377e-02 2.198802e-02 9.962346e-01 3.079574e+02 +9.950261e-01 6.478145e-02 -7.567281e-02 1.056882e+02 -6.605827e-02 9.977105e-01 -1.449079e-02 -2.131209e+01 7.456083e-02 1.941752e-02 9.970274e-01 3.087268e+02 +9.957743e-01 6.460627e-02 -6.526494e-02 1.056313e+02 -6.560666e-02 9.977569e-01 -1.330050e-02 -2.132725e+01 6.425925e-02 1.752611e-02 9.977793e-01 3.095120e+02 +9.961695e-01 6.777565e-02 -5.525152e-02 1.055868e+02 -6.856818e-02 9.975672e-01 -1.257452e-02 -2.134661e+01 5.426486e-02 1.631485e-02 9.983933e-01 3.103019e+02 +9.960605e-01 7.612906e-02 -4.547347e-02 1.055421e+02 -7.704942e-02 9.968493e-01 -1.883888e-02 -2.136270e+01 4.389601e-02 2.226837e-02 9.987879e-01 3.111068e+02 +9.962397e-01 7.863092e-02 -3.638311e-02 1.055110e+02 -7.952988e-02 9.965446e-01 -2.395591e-02 -2.137880e+01 3.437372e-02 2.675937e-02 9.990508e-01 3.119246e+02 +9.970064e-01 7.210439e-02 -2.791372e-02 1.054880e+02 -7.273790e-02 9.970998e-01 -2.238548e-02 -2.140411e+01 2.621867e-02 2.434885e-02 9.993597e-01 3.127682e+02 +9.973037e-01 7.079394e-02 -1.932987e-02 1.054664e+02 -7.108751e-02 9.973581e-01 -1.494606e-02 -2.142936e+01 1.822072e-02 1.627987e-02 9.997015e-01 3.136269e+02 +9.973099e-01 7.229489e-02 -1.209867e-02 1.054453e+02 -7.243256e-02 9.973086e-01 -1.135481e-02 -2.145582e+01 1.124521e-02 1.220061e-02 9.998623e-01 3.144907e+02 +9.973493e-01 7.239100e-02 -7.343014e-03 1.054328e+02 -7.249034e-02 9.972665e-01 -1.430661e-02 -2.148095e+01 6.287272e-03 1.480098e-02 9.998707e-01 3.153597e+02 +9.973015e-01 7.327519e-02 -4.525165e-03 1.054267e+02 -7.335330e-02 9.970938e-01 -2.057235e-02 -2.150644e+01 3.004571e-03 2.084877e-02 9.997781e-01 3.162378e+02 +9.973401e-01 7.287299e-02 -1.494331e-03 1.054210e+02 -7.288806e-02 9.970720e-01 -2.312193e-02 -2.153423e+01 -1.950079e-04 2.316934e-02 9.997315e-01 3.171326e+02 +9.976116e-01 6.906811e-02 8.388487e-04 1.054269e+02 -6.902572e-02 9.973023e-01 -2.496856e-02 -2.157129e+01 -2.561117e-03 2.485102e-02 9.996879e-01 3.180362e+02 +9.977943e-01 6.632368e-02 2.774862e-03 1.054374e+02 -6.623365e-02 9.974889e-01 -2.507979e-02 -2.160225e+01 -4.431278e-03 2.484068e-02 9.996816e-01 3.189467e+02 +9.981713e-01 6.031825e-02 3.966676e-03 1.054428e+02 -6.020837e-02 9.979062e-01 -2.362368e-02 -2.163017e+01 -5.383310e-03 2.334165e-02 9.997131e-01 3.198737e+02 +9.983588e-01 5.712588e-02 4.045884e-03 1.054415e+02 -5.705607e-02 9.982480e-01 -1.566657e-02 -2.166041e+01 -4.933763e-03 1.541002e-02 9.998691e-01 3.208110e+02 +9.986197e-01 5.229183e-02 4.919672e-03 1.054447e+02 -5.223139e-02 9.985664e-01 -1.170420e-02 -2.169530e+01 -5.524653e-03 1.143108e-02 9.999194e-01 3.217496e+02 +9.986097e-01 5.245937e-02 5.160039e-03 1.054464e+02 -5.240928e-02 9.985814e-01 -9.406573e-03 -2.172722e+01 -5.646182e-03 9.123060e-03 9.999425e-01 3.226917e+02 +9.983861e-01 5.653800e-02 5.352104e-03 1.054398e+02 -5.646029e-02 9.983108e-01 -1.370338e-02 -2.175798e+01 -6.117825e-03 1.337908e-02 9.998918e-01 3.236336e+02 +9.981430e-01 6.076760e-02 4.234300e-03 1.054284e+02 -6.068740e-02 9.980116e-01 -1.702391e-02 -2.179052e+01 -5.260383e-03 1.673533e-02 9.998461e-01 3.245883e+02 +9.979439e-01 6.402733e-02 2.909246e-03 1.054180e+02 -6.395949e-02 9.977650e-01 -1.934098e-02 -2.182461e+01 -4.141095e-03 1.911514e-02 9.998087e-01 3.255501e+02 +9.979799e-01 6.348942e-02 2.303417e-03 1.054122e+02 -6.343066e-02 9.977843e-01 -2.007475e-02 -2.185802e+01 -3.572848e-03 1.988809e-02 9.997958e-01 3.265182e+02 +9.978483e-01 6.555244e-02 1.315391e-03 1.054019e+02 -6.551143e-02 9.976381e-01 -2.064887e-02 -2.189206e+01 -2.665868e-03 2.051827e-02 9.997859e-01 3.274917e+02 +9.979950e-01 6.328603e-02 9.042715e-04 1.053952e+02 -6.325218e-02 9.977673e-01 -2.143872e-02 -2.192920e+01 -2.259024e-03 2.133853e-02 9.997698e-01 3.284635e+02 +9.980973e-01 6.165225e-02 -8.383003e-04 1.053879e+02 -6.165764e-02 9.979554e-01 -1.683097e-02 -2.196284e+01 -2.010807e-04 1.685063e-02 9.998580e-01 3.294453e+02 +9.981636e-01 6.053929e-02 -2.105571e-03 1.053789e+02 -6.056140e-02 9.980822e-01 -1.281375e-02 -2.199689e+01 1.325798e-03 1.291774e-02 9.999157e-01 3.304217e+02 +9.982411e-01 5.917486e-02 -3.621395e-03 1.053639e+02 -5.921516e-02 9.981699e-01 -1.226611e-02 -2.203094e+01 2.888923e-03 1.245897e-02 9.999182e-01 3.313948e+02 +9.983276e-01 5.762858e-02 -4.578055e-03 1.053430e+02 -5.769652e-02 9.981989e-01 -1.643229e-02 -2.206599e+01 3.622841e-03 1.666894e-02 9.998545e-01 3.323603e+02 +9.980784e-01 6.175180e-02 -5.112974e-03 1.053159e+02 -6.183928e-02 9.979011e-01 -1.921329e-02 -2.209860e+01 3.915787e-03 1.949255e-02 9.998023e-01 3.333259e+02 +9.980695e-01 6.177421e-02 -6.422946e-03 1.052914e+02 -6.189871e-02 9.978523e-01 -2.143287e-02 -2.213520e+01 5.085153e-03 2.178907e-02 9.997497e-01 3.342917e+02 +9.980943e-01 6.103269e-02 -9.103350e-03 1.052683e+02 -6.119644e-02 9.979459e-01 -1.894621e-02 -2.217005e+01 7.928313e-03 1.946719e-02 9.997791e-01 3.352592e+02 +9.981924e-01 5.902735e-02 -1.130152e-02 1.052435e+02 -5.921131e-02 9.981058e-01 -1.669893e-02 -2.220127e+01 1.029442e-02 1.733792e-02 9.997967e-01 3.362253e+02 +9.983277e-01 5.630190e-02 -1.311107e-02 1.052201e+02 -5.645698e-02 9.983356e-01 -1.177361e-02 -2.223131e+01 1.242637e-02 1.249413e-02 9.998447e-01 3.371917e+02 +9.984579e-01 5.341998e-02 -1.510433e-02 1.051954e+02 -5.356946e-02 9.985173e-01 -9.670185e-03 -2.225943e+01 1.456535e-02 1.046440e-02 9.998392e-01 3.381492e+02 +9.986173e-01 4.967261e-02 -1.721013e-02 1.051695e+02 -4.988366e-02 9.986822e-01 -1.205814e-02 -2.228812e+01 1.658850e-02 1.289997e-02 9.997792e-01 3.391040e+02 +9.987992e-01 4.496421e-02 -1.945361e-02 1.051443e+02 -4.527720e-02 9.988470e-01 -1.595852e-02 -2.231673e+01 1.871362e-02 1.682016e-02 9.996834e-01 3.400523e+02 +9.988857e-01 4.160960e-02 -2.227353e-02 1.051160e+02 -4.207829e-02 9.988935e-01 -2.100383e-02 -2.234860e+01 2.137493e-02 2.191766e-02 9.995313e-01 3.409938e+02 +9.988898e-01 4.008438e-02 -2.474727e-02 1.050824e+02 -4.065899e-02 9.989044e-01 -2.316941e-02 -2.238367e+01 2.379142e-02 2.414989e-02 9.994252e-01 3.419347e+02 +9.989943e-01 3.580791e-02 -2.698608e-02 1.050745e+02 -3.641167e-02 9.990897e-01 -2.222380e-02 -2.241394e+01 2.616573e-02 2.318406e-02 9.993887e-01 3.428679e+02 +9.989252e-01 3.609738e-02 -2.907527e-02 1.050566e+02 -3.664540e-02 9.991563e-01 -1.854089e-02 -2.244476e+01 2.838147e-02 1.958643e-02 9.994053e-01 3.437952e+02 +9.988144e-01 3.820445e-02 -3.016870e-02 1.050382e+02 -3.860536e-02 9.991723e-01 -1.281970e-02 -2.247287e+01 2.965396e-02 1.396918e-02 9.994626e-01 3.447116e+02 +9.986908e-01 4.062760e-02 -3.108101e-02 1.050089e+02 -4.096502e-02 9.991075e-01 -1.029706e-02 -2.249806e+01 3.063493e-02 1.155681e-02 9.994638e-01 3.456156e+02 +9.987194e-01 3.957218e-02 -3.152263e-02 1.049963e+02 -3.989932e-02 9.991555e-01 -9.816657e-03 -2.251794e+01 3.110755e-02 1.106182e-02 9.994548e-01 3.464955e+02 +9.986335e-01 4.177223e-02 -3.140456e-02 1.049876e+02 -4.213469e-02 9.990517e-01 -1.096904e-02 -2.253384e+01 3.091658e-02 1.227728e-02 9.994466e-01 3.473485e+02 +9.985686e-01 4.343434e-02 -3.121201e-02 1.049633e+02 -4.386535e-02 9.989494e-01 -1.325925e-02 -2.254841e+01 3.060332e-02 1.460939e-02 9.994248e-01 3.481838e+02 +9.986502e-01 4.135805e-02 -3.142151e-02 1.049481e+02 -4.185822e-02 9.990044e-01 -1.542998e-02 -2.255821e+01 3.075207e-02 1.672440e-02 9.993871e-01 3.489987e+02 +9.987453e-01 3.901224e-02 -3.139761e-02 1.049314e+02 -3.951657e-02 9.990970e-01 -1.560519e-02 -2.257327e+01 3.076047e-02 1.682633e-02 9.993852e-01 3.497949e+02 +9.987224e-01 4.005586e-02 -3.080730e-02 1.049025e+02 -4.043791e-02 9.991114e-01 -1.187951e-02 -2.259777e+01 3.030408e-02 1.311011e-02 9.994548e-01 3.505690e+02 +9.987406e-01 4.014530e-02 -3.009358e-02 1.048741e+02 -4.048648e-02 9.991215e-01 -1.081455e-02 -2.262458e+01 2.963299e-02 1.201931e-02 9.994886e-01 3.513189e+02 +9.988751e-01 3.752656e-02 -2.898675e-02 1.048522e+02 -3.784795e-02 9.992271e-01 -1.061917e-02 -2.265124e+01 2.856584e-02 1.170431e-02 9.995234e-01 3.520394e+02 +9.989574e-01 3.673804e-02 -2.710231e-02 1.048167e+02 -3.716877e-02 9.991878e-01 -1.556343e-02 -2.267479e+01 2.650853e-02 1.655456e-02 9.995115e-01 3.527343e+02 +9.989203e-01 3.992293e-02 -2.375871e-02 1.047649e+02 -4.041181e-02 9.989735e-01 -2.046472e-02 -2.270211e+01 2.291731e-02 2.140276e-02 9.995082e-01 3.534022e+02 +9.988662e-01 4.338903e-02 -1.959123e-02 1.047171e+02 -4.383606e-02 9.987740e-01 -2.299540e-02 -2.273217e+01 1.856946e-02 2.382813e-02 9.995436e-01 3.540462e+02 +9.989133e-01 4.389703e-02 -1.566261e-02 1.046775e+02 -4.430204e-02 9.986660e-01 -2.652240e-02 -2.276090e+01 1.447746e-02 2.718746e-02 9.995255e-01 3.546613e+02 +9.990667e-01 4.176884e-02 -1.100515e-02 1.046587e+02 -4.207554e-02 9.986850e-01 -2.929048e-02 -2.278709e+01 9.767245e-03 2.972618e-02 9.995104e-01 3.552514e+02 +9.991102e-01 4.175477e-02 -5.954597e-03 1.046353e+02 -4.191328e-02 9.986830e-01 -2.958951e-02 -2.281822e+01 4.711252e-03 2.981275e-02 9.995444e-01 3.558155e+02 +9.989728e-01 4.531020e-02 6.088257e-04 1.046153e+02 -4.526872e-02 9.984803e-01 -3.143055e-02 -2.284810e+01 -2.032025e-03 3.137070e-02 9.995058e-01 3.563523e+02 +9.987961e-01 4.811272e-02 9.568784e-03 1.045999e+02 -4.775559e-02 9.982601e-01 -3.458419e-02 -2.287937e+01 -1.121608e-02 3.408559e-02 9.993560e-01 3.568580e+02 +9.984704e-01 5.101947e-02 2.130646e-02 1.045979e+02 -5.025531e-02 9.981236e-01 -3.498055e-02 -2.290779e+01 -2.305117e-02 3.385628e-02 9.991609e-01 3.573429e+02 +9.981165e-01 5.035258e-02 3.504344e-02 1.046043e+02 -4.911194e-02 9.981655e-01 -3.540697e-02 -2.293699e+01 -3.676199e-02 3.361922e-02 9.987584e-01 3.577991e+02 +9.975321e-01 4.867915e-02 5.059790e-02 1.046308e+02 -4.677175e-02 9.981741e-01 -3.822196e-02 -2.296595e+01 -5.236613e-02 3.576107e-02 9.979875e-01 3.582322e+02 +9.964613e-01 4.888949e-02 6.837206e-02 1.046574e+02 -4.613466e-02 9.980808e-01 -4.130738e-02 -2.299321e+01 -7.026034e-02 3.800687e-02 9.968044e-01 3.586335e+02 +9.948181e-01 4.985470e-02 8.860852e-02 1.047011e+02 -4.623579e-02 9.980287e-01 -4.243653e-02 -2.301937e+01 -9.054952e-02 3.811974e-02 9.951621e-01 3.590264e+02 +9.926780e-01 4.839967e-02 1.106700e-01 1.047552e+02 -4.403985e-02 9.981671e-01 -4.150704e-02 -2.304858e+01 -1.124761e-01 3.632923e-02 9.929901e-01 3.594114e+02 +9.898366e-01 4.431730e-02 1.351278e-01 1.048156e+02 -3.902868e-02 9.983742e-01 -4.154032e-02 -2.307159e+01 -1.367491e-01 3.584426e-02 9.899570e-01 3.597629e+02 +9.857073e-01 4.479522e-02 1.624025e-01 1.048906e+02 -3.791044e-02 9.982561e-01 -4.524881e-02 -2.309496e+01 -1.641462e-01 3.844533e-02 9.856866e-01 3.601239e+02 +9.803339e-01 4.720478e-02 1.916171e-01 1.049723e+02 -3.862400e-02 9.980871e-01 -4.827374e-02 -2.312939e+01 -1.935293e-01 3.992335e-02 9.802819e-01 3.604486e+02 +9.739817e-01 4.879633e-02 2.213111e-01 1.050749e+02 -3.921074e-02 9.981011e-01 -4.750392e-02 -2.316179e+01 -2.232089e-01 3.759017e-02 9.740456e-01 3.607971e+02 +9.665248e-01 4.840005e-02 2.519668e-01 1.051929e+02 -3.857948e-02 9.982963e-01 -4.377390e-02 -2.319604e+01 -2.536562e-01 3.258781e-02 9.667454e-01 3.611398e+02 +9.574894e-01 4.873369e-02 2.843220e-01 1.053044e+02 -3.904770e-02 9.984508e-01 -3.963972e-02 -2.322197e+01 -2.858134e-01 2.685248e-02 9.579090e-01 3.614408e+02 +9.466892e-01 4.836813e-02 3.184967e-01 1.054448e+02 -3.859319e-02 9.985722e-01 -3.693390e-02 -2.324802e+01 -3.198284e-01 2.267311e-02 9.472042e-01 3.617643e+02 +9.344935e-01 4.421380e-02 3.532237e-01 1.055835e+02 -3.391700e-02 9.988014e-01 -3.529092e-02 -2.326293e+01 -3.543607e-01 2.099884e-02 9.348730e-01 3.620335e+02 +9.198583e-01 4.072280e-02 3.901313e-01 1.057553e+02 -3.018268e-02 9.989958e-01 -3.311224e-02 -2.328372e+01 -3.910880e-01 1.868335e-02 9.201637e-01 3.623412e+02 +9.024128e-01 3.660062e-02 4.293153e-01 1.059128e+02 -2.713057e-02 9.992351e-01 -2.816033e-02 -2.330074e+01 -4.300176e-01 1.376467e-02 9.027156e-01 3.625892e+02 +8.833712e-01 3.887949e-02 4.670587e-01 1.060949e+02 -3.355696e-02 9.992424e-01 -1.971229e-02 -2.331260e+01 -4.674712e-01 1.740198e-03 8.840066e-01 3.628913e+02 +8.631473e-01 3.528951e-02 5.037176e-01 1.062900e+02 -3.481884e-02 9.993400e-01 -1.034795e-02 -2.332730e+01 -5.037504e-01 -8.607055e-03 8.638064e-01 3.631794e+02 +8.422670e-01 3.139393e-02 5.381457e-01 1.064769e+02 -3.255784e-02 9.994428e-01 -7.347548e-03 -2.333866e+01 -5.380766e-01 -1.133226e-02 8.428198e-01 3.634004e+02 +8.202374e-01 2.334868e-02 5.715465e-01 1.066994e+02 -2.222003e-02 9.997130e-01 -8.951652e-03 -2.335905e+01 -5.715915e-01 -5.357297e-03 8.205209e-01 3.636523e+02 +7.965026e-01 1.255756e-02 6.045047e-01 1.069210e+02 -7.175718e-03 9.999102e-01 -1.131664e-02 -2.336393e+01 -6.045926e-01 4.675972e-03 7.965212e-01 3.638431e+02 +7.714499e-01 9.034512e-03 6.362259e-01 1.071676e+02 4.667522e-04 9.998909e-01 -1.476457e-02 -2.337825e+01 -6.362899e-01 1.168709e-02 7.713615e-01 3.640848e+02 +7.442850e-01 1.595245e-02 6.676716e-01 1.074142e+02 -2.382759e-03 9.997717e-01 -2.123104e-02 -2.338506e+01 -6.678580e-01 1.421104e-02 7.441531e-01 3.643377e+02 +7.163417e-01 2.645949e-02 6.972478e-01 1.076488e+02 -1.104311e-02 9.995855e-01 -2.658723e-02 -2.340847e+01 -6.976623e-01 1.134575e-02 7.163370e-01 3.645487e+02 +6.878419e-01 3.669334e-02 7.249325e-01 1.079258e+02 -2.022714e-02 9.993025e-01 -3.138869e-02 -2.343604e+01 -7.255787e-01 6.927140e-03 6.881044e-01 3.647911e+02 +6.590446e-01 4.418279e-02 7.508049e-01 1.082073e+02 -2.420753e-02 9.990019e-01 -3.753953e-02 -2.346653e+01 -7.517142e-01 6.565088e-03 6.594564e-01 3.649840e+02 +6.323946e-01 4.094460e-02 7.735636e-01 1.085404e+02 -1.748932e-02 9.991022e-01 -3.858467e-02 -2.349470e+01 -7.744490e-01 1.087163e-02 6.325429e-01 3.652083e+02 +6.054369e-01 3.248122e-02 7.952302e-01 1.089046e+02 -4.151448e-03 9.992821e-01 -3.765510e-02 -2.352118e+01 -7.958825e-01 1.949643e-02 6.051372e-01 3.654284e+02 +5.772209e-01 2.634066e-02 8.161631e-01 1.092742e+02 7.137420e-03 9.992787e-01 -3.729835e-02 -2.352153e+01 -8.165569e-01 2.735468e-02 5.766166e-01 3.656251e+02 +5.496469e-01 2.419700e-02 8.350466e-01 1.096763e+02 1.745159e-02 9.990297e-01 -4.043576e-02 -2.352325e+01 -8.352148e-01 3.679827e-02 5.486913e-01 3.658629e+02 +5.222732e-01 2.689274e-02 8.523541e-01 1.100814e+02 2.046457e-02 9.988195e-01 -4.405340e-02 -2.352827e+01 -8.525327e-01 4.045096e-02 5.211063e-01 3.660684e+02 +4.951345e-01 3.194349e-02 8.682289e-01 1.105182e+02 1.324231e-02 9.989303e-01 -4.430404e-02 -2.353455e+01 -8.687154e-01 3.343381e-02 4.941819e-01 3.663220e+02 +4.679994e-01 3.604577e-02 8.829933e-01 1.109776e+02 7.025962e-04 9.991523e-01 -4.116004e-02 -2.355195e+01 -8.837285e-01 1.988325e-02 4.675774e-01 3.665788e+02 +4.410391e-01 3.596824e-02 8.967669e-01 1.114527e+02 -4.729737e-03 9.992759e-01 -3.775363e-02 -2.357108e+01 -8.974755e-01 1.240935e-02 4.408898e-01 3.667973e+02 +4.132545e-01 3.289660e-02 9.100211e-01 1.119692e+02 -2.731030e-03 9.993875e-01 -3.488694e-02 -2.359075e+01 -9.106115e-01 1.193189e-02 4.130913e-01 3.670235e+02 +3.843357e-01 3.340498e-02 9.225888e-01 1.124947e+02 -4.287474e-03 9.993989e-01 -3.440003e-02 -2.360957e+01 -9.231835e-01 9.265578e-03 3.842479e-01 3.672142e+02 +3.545985e-01 3.728331e-02 9.342750e-01 1.130501e+02 -1.193747e-02 9.993038e-01 -3.534757e-02 -2.362504e+01 -9.349425e-01 1.381313e-03 3.547967e-01 3.674333e+02 +3.252983e-01 4.055895e-02 9.447412e-01 1.136292e+02 -2.085462e-02 9.991444e-01 -3.571379e-02 -2.364609e+01 -9.453815e-01 -8.084586e-03 3.258659e-01 3.676452e+02 +2.972217e-01 4.117112e-02 9.539204e-01 1.142225e+02 -2.412561e-02 9.990747e-01 -3.560295e-02 -2.367142e+01 -9.545037e-01 -1.243194e-02 2.979400e-01 3.678146e+02 +2.685092e-01 4.164936e-02 9.623763e-01 1.148506e+02 -2.318348e-02 9.990548e-01 -3.676839e-02 -2.369404e+01 -9.629981e-01 -1.243858e-02 2.692210e-01 3.679865e+02 +2.378089e-01 4.375507e-02 9.703259e-01 1.155025e+02 -2.143677e-02 9.989779e-01 -3.979333e-02 -2.371713e+01 -9.710754e-01 -1.133744e-02 2.385038e-01 3.681458e+02 +2.071720e-01 4.378169e-02 9.773244e-01 1.161631e+02 -2.165374e-02 9.989585e-01 -4.016073e-02 -2.374506e+01 -9.780649e-01 -1.284255e-02 2.079043e-01 3.682598e+02 +1.780643e-01 4.320355e-02 9.830700e-01 1.168565e+02 -2.080830e-02 9.989776e-01 -4.013364e-02 -2.377785e+01 -9.837989e-01 -1.330965e-02 1.787812e-01 3.683872e+02 +1.501444e-01 4.142606e-02 9.877958e-01 1.175628e+02 -1.689079e-02 9.990834e-01 -3.933206e-02 -2.380824e+01 -9.885198e-01 -1.077917e-02 1.507065e-01 3.684702e+02 +1.238713e-01 3.818004e-02 9.915635e-01 1.183009e+02 -1.222845e-02 9.992423e-01 -3.694808e-02 -2.384110e+01 -9.922230e-01 -7.548476e-03 1.242443e-01 3.685581e+02 +9.890450e-02 3.398123e-02 9.945165e-01 1.190595e+02 -8.692431e-03 9.994081e-01 -3.328392e-02 -2.387235e+01 -9.950590e-01 -5.352838e-03 9.914134e-02 3.686268e+02 +7.599532e-02 3.146483e-02 9.966116e-01 1.198265e+02 -3.668075e-03 9.995040e-01 -3.127646e-02 -2.390268e+01 -9.971015e-01 -1.278783e-03 7.607304e-02 3.686636e+02 +5.749345e-02 3.258397e-02 9.978140e-01 1.206142e+02 4.901909e-03 9.994460e-01 -3.291972e-02 -2.393694e+01 -9.983339e-01 6.783858e-03 5.730187e-02 3.686972e+02 +4.164141e-02 3.585585e-02 9.984890e-01 1.214132e+02 1.169905e-02 9.992698e-01 -3.637181e-02 -2.396862e+01 -9.990642e-01 1.319594e-02 4.119153e-02 3.687155e+02 +2.863754e-02 3.720230e-02 9.988973e-01 1.222382e+02 1.529914e-02 9.991738e-01 -3.765122e-02 -2.399882e+01 -9.994728e-01 1.636050e-02 2.804472e-02 3.687334e+02 +1.882060e-02 3.615625e-02 9.991689e-01 1.230811e+02 1.983111e-02 9.991358e-01 -3.652861e-02 -2.403411e+01 -9.996262e-01 2.050211e-02 1.808731e-02 3.687416e+02 +1.189265e-02 3.422507e-02 9.993434e-01 1.239405e+02 2.454366e-02 9.991029e-01 -3.450893e-02 -2.407180e+01 -9.996281e-01 2.493794e-02 1.104197e-02 3.687418e+02 +7.631602e-03 3.396506e-02 9.993939e-01 1.248126e+02 2.819075e-02 9.990184e-01 -3.416758e-02 -2.410714e+01 -9.995735e-01 2.843441e-02 6.666608e-03 3.687442e+02 +5.014154e-03 3.276831e-02 9.994504e-01 1.256999e+02 3.050153e-02 9.989929e-01 -3.290634e-02 -2.414489e+01 -9.995222e-01 3.064976e-02 4.009618e-03 3.687499e+02 +3.259540e-03 3.216817e-02 9.994771e-01 1.265980e+02 3.282818e-02 9.989403e-01 -3.225796e-02 -2.418514e+01 -9.994557e-01 3.291616e-02 2.200061e-03 3.687494e+02 +1.633024e-03 3.455909e-02 9.994013e-01 1.275096e+02 3.526622e-02 9.987790e-01 -3.459521e-02 -2.422461e+01 -9.993767e-01 3.530159e-02 4.122593e-04 3.687502e+02 +6.599402e-04 3.621735e-02 9.993437e-01 1.284362e+02 3.768879e-02 9.986330e-01 -3.621650e-02 -2.426216e+01 -9.992893e-01 3.768795e-02 -7.059523e-04 3.687471e+02 +-6.731268e-05 3.550487e-02 9.993695e-01 1.293754e+02 4.098055e-02 9.985301e-01 -3.547229e-02 -2.430438e+01 -9.991600e-01 4.095231e-02 -1.522225e-03 3.687465e+02 +7.005806e-05 3.548906e-02 9.993700e-01 1.303341e+02 4.485273e-02 9.983642e-01 -3.545649e-02 -2.434949e+01 -9.989936e-01 4.482695e-02 -1.521840e-03 3.687427e+02 +5.309081e-04 3.651066e-02 9.993331e-01 1.313025e+02 4.815828e-02 9.981728e-01 -3.649386e-02 -2.439428e+01 -9.988396e-01 4.814553e-02 -1.228354e-03 3.687402e+02 +1.574412e-03 3.507623e-02 9.993834e-01 1.322890e+02 4.975216e-02 9.981442e-01 -3.511113e-02 -2.443499e+01 -9.987604e-01 4.977675e-02 -1.736303e-04 3.687388e+02 +2.710061e-03 2.924681e-02 9.995685e-01 1.332957e+02 5.200720e-02 9.982153e-01 -2.934823e-02 -2.447513e+01 -9.986431e-01 5.206429e-02 1.184177e-03 3.687382e+02 +4.256121e-03 2.300312e-02 9.997263e-01 1.343156e+02 5.265652e-02 9.983432e-01 -2.319547e-02 -2.451758e+01 -9.986036e-01 5.274082e-02 3.037804e-03 3.687485e+02 +5.935142e-03 2.294951e-02 9.997190e-01 1.353443e+02 5.481693e-02 9.982259e-01 -2.324068e-02 -2.455398e+01 -9.984788e-01 5.493945e-02 4.666588e-03 3.687580e+02 +8.062373e-03 2.346259e-02 9.996922e-01 1.363839e+02 5.577967e-02 9.981576e-01 -2.387643e-02 -2.458922e+01 -9.984106e-01 5.595499e-02 6.738782e-03 3.687704e+02 +1.001062e-02 2.530164e-02 9.996297e-01 1.374336e+02 5.883642e-02 9.979329e-01 -2.584791e-02 -2.462796e+01 -9.982175e-01 5.907337e-02 8.501272e-03 3.687796e+02 +1.290407e-02 2.804287e-02 9.995234e-01 1.384875e+02 6.260597e-02 9.976227e-01 -2.879781e-02 -2.467123e+01 -9.979549e-01 6.294773e-02 1.111774e-02 3.687971e+02 +1.620272e-02 3.001280e-02 9.994182e-01 1.395550e+02 6.524096e-02 9.973876e-01 -3.100953e-02 -2.471602e+01 -9.977380e-01 6.570543e-02 1.420233e-02 3.688158e+02 +1.972748e-02 2.769245e-02 9.994218e-01 1.406353e+02 6.812504e-02 9.972559e-01 -2.897715e-02 -2.476446e+01 -9.974818e-01 6.865728e-02 1.778680e-02 3.688427e+02 +2.247136e-02 2.438069e-02 9.994501e-01 1.417237e+02 6.865203e-02 9.973051e-01 -2.587193e-02 -2.480997e+01 -9.973876e-01 6.919565e-02 2.073701e-02 3.688708e+02 +2.398572e-02 2.286145e-02 9.994509e-01 1.428173e+02 6.780098e-02 9.973994e-01 -2.444169e-02 -2.485547e+01 -9.974105e-01 6.834998e-02 2.237331e-02 3.689039e+02 +2.468193e-02 2.423675e-02 9.994015e-01 1.439133e+02 6.538795e-02 9.975261e-01 -2.580615e-02 -2.490194e+01 -9.975547e-01 6.598575e-02 2.303608e-02 3.689435e+02 +2.538494e-02 2.612935e-02 9.993362e-01 1.450173e+02 6.399126e-02 9.975657e-01 -2.770856e-02 -2.494905e+01 -9.976276e-01 6.465215e-02 2.365110e-02 3.689875e+02 +2.589921e-02 2.577697e-02 9.993322e-01 1.461292e+02 6.093693e-02 9.977678e-01 -2.731590e-02 -2.499785e+01 -9.978056e-01 6.160368e-02 2.427062e-02 3.690280e+02 +2.554062e-02 2.688068e-02 9.993123e-01 1.472438e+02 5.965415e-02 9.978160e-01 -2.836509e-02 -2.504730e+01 -9.978923e-01 6.033757e-02 2.388129e-02 3.690651e+02 +2.507798e-02 2.890603e-02 9.992675e-01 1.483625e+02 5.938596e-02 9.977735e-01 -3.035319e-02 -2.509861e+01 -9.979201e-01 6.010364e-02 2.330553e-02 3.691002e+02 +2.484940e-02 3.097155e-02 9.992113e-01 1.494839e+02 5.985976e-02 9.976804e-01 -3.241276e-02 -2.515174e+01 -9.978975e-01 6.061798e-02 2.293781e-02 3.691377e+02 +2.472739e-02 3.031984e-02 9.992343e-01 1.506176e+02 5.965380e-02 9.977140e-01 -3.174993e-02 -2.520819e+01 -9.979128e-01 6.039320e-02 2.286217e-02 3.691811e+02 +2.404305e-02 2.790402e-02 9.993214e-01 1.517550e+02 5.879496e-02 9.978406e-01 -2.927725e-02 -2.526123e+01 -9.979805e-01 5.945896e-02 2.235051e-02 3.692181e+02 +2.368991e-02 2.535395e-02 9.993978e-01 1.528915e+02 5.664638e-02 9.980382e-01 -2.666222e-02 -2.534835e+01 -9.981132e-01 5.724388e-02 2.220722e-02 3.693098e+02 +2.308047e-02 2.474901e-02 9.994272e-01 1.540289e+02 5.416710e-02 9.981941e-01 -2.596940e-02 -2.541851e+01 -9.982651e-01 5.473545e-02 2.169821e-02 3.693749e+02 +2.287073e-02 2.438989e-02 9.994409e-01 1.551639e+02 5.093619e-02 9.983755e-01 -2.552950e-02 -2.549606e+01 -9.984400e-01 5.149158e-02 2.159125e-02 3.694582e+02 +2.216692e-02 2.273212e-02 9.994958e-01 1.563060e+02 4.880340e-02 9.985250e-01 -2.379241e-02 -2.556053e+01 -9.985624e-01 4.930619e-02 2.102481e-02 3.695183e+02 +2.203366e-02 2.123616e-02 9.995316e-01 1.574486e+02 4.824292e-02 9.985871e-01 -2.227956e-02 -2.562874e+01 -9.985926e-01 4.871122e-02 2.097804e-02 3.695857e+02 +2.183317e-02 2.169645e-02 9.995262e-01 1.585942e+02 4.933363e-02 9.985231e-01 -2.275231e-02 -2.568831e+01 -9.985437e-01 4.980700e-02 2.073056e-02 3.696351e+02 +2.183165e-02 2.553696e-02 9.994354e-01 1.597372e+02 5.236238e-02 9.982724e-01 -2.665106e-02 -2.574995e+01 -9.983895e-01 5.291465e-02 2.045675e-02 3.696842e+02 +2.208041e-02 2.870951e-02 9.993439e-01 1.608864e+02 5.581030e-02 9.979934e-01 -2.990385e-02 -2.581169e+01 -9.981972e-01 5.643395e-02 2.043381e-02 3.697271e+02 +2.211563e-02 2.895187e-02 9.993361e-01 1.620396e+02 5.818247e-02 9.978492e-01 -3.019639e-02 -2.587618e+01 -9.980610e-01 5.881164e-02 2.038357e-02 3.697725e+02 +2.206653e-02 2.593144e-02 9.994201e-01 1.631985e+02 5.908236e-02 9.978826e-01 -2.719605e-02 -2.593634e+01 -9.980092e-01 5.964821e-02 2.048772e-02 3.698118e+02 +2.156449e-02 2.230261e-02 9.995187e-01 1.643610e+02 5.982362e-02 9.979309e-01 -2.355788e-02 -2.599180e+01 -9.979760e-01 6.030283e-02 2.018564e-02 3.698497e+02 +2.109169e-02 1.841282e-02 9.996080e-01 1.655308e+02 5.931609e-02 9.980461e-01 -1.963562e-02 -2.604530e+01 -9.980164e-01 5.970697e-02 1.995830e-02 3.698901e+02 +2.095807e-02 1.846572e-02 9.996098e-01 1.666954e+02 6.090917e-02 9.979486e-01 -1.971207e-02 -2.609640e+01 -9.979233e-01 6.129852e-02 1.979034e-02 3.699300e+02 +2.162961e-02 2.083852e-02 9.995488e-01 1.678630e+02 6.260857e-02 9.977922e-01 -2.215672e-02 -2.614979e+01 -9.978038e-01 6.305955e-02 2.027718e-02 3.699718e+02 +2.255529e-02 2.494363e-02 9.994344e-01 1.690332e+02 6.351801e-02 9.976332e-01 -2.633217e-02 -2.620170e+01 -9.977258e-01 6.407600e-02 2.091754e-02 3.700060e+02 +2.333746e-02 2.753328e-02 9.993484e-01 1.702070e+02 6.374796e-02 9.975454e-01 -2.897230e-02 -2.625818e+01 -9.976932e-01 6.438255e-02 2.152499e-02 3.700461e+02 +2.406937e-02 2.871726e-02 9.992977e-01 1.713885e+02 6.206533e-02 9.976162e-01 -3.016386e-02 -2.631602e+01 -9.977819e-01 6.274775e-02 2.222965e-02 3.700823e+02 +2.429096e-02 2.763956e-02 9.993228e-01 1.725770e+02 5.985880e-02 9.977840e-01 -2.905203e-02 -2.638082e+01 -9.979113e-01 6.052395e-02 2.258266e-02 3.701201e+02 +2.482006e-02 2.543155e-02 9.993684e-01 1.737716e+02 5.651670e-02 9.980418e-01 -2.680143e-02 -2.644212e+01 -9.980931e-01 5.714620e-02 2.333415e-02 3.701573e+02 +2.526482e-02 2.715795e-02 9.993118e-01 1.749644e+02 5.456745e-02 9.981031e-01 -2.850470e-02 -2.650189e+01 -9.981904e-01 5.525005e-02 2.373495e-02 3.701941e+02 +2.566616e-02 2.942388e-02 9.992374e-01 1.761620e+02 5.239613e-02 9.981532e-01 -3.073779e-02 -2.655959e+01 -9.982965e-01 5.314509e-02 2.407706e-02 3.702303e+02 +2.614720e-02 2.836100e-02 9.992557e-01 1.773609e+02 5.101837e-02 9.982569e-01 -2.966764e-02 -2.661955e+01 -9.983554e-01 5.175611e-02 2.465469e-02 3.702665e+02 +2.679745e-02 2.655658e-02 9.992881e-01 1.785679e+02 4.921567e-02 9.983997e-01 -2.785277e-02 -2.668409e+01 -9.984287e-01 4.992700e-02 2.544756e-02 3.703025e+02 +2.729495e-02 2.645543e-02 9.992773e-01 1.797708e+02 5.007260e-02 9.983586e-01 -2.779884e-02 -2.674321e+01 -9.983726e-01 5.079517e-02 2.592546e-02 3.703356e+02 +2.774946e-02 2.488212e-02 9.993052e-01 1.809750e+02 4.948527e-02 9.984302e-01 -2.623448e-02 -2.681046e+01 -9.983893e-01 5.017887e-02 2.647460e-02 3.703669e+02 +2.792691e-02 2.160367e-02 9.993765e-01 1.821643e+02 5.076414e-02 9.984457e-01 -2.300212e-02 -2.687762e+01 -9.983202e-01 5.137485e-02 2.678681e-02 3.704045e+02 +2.851527e-02 1.869607e-02 9.994185e-01 1.833347e+02 5.180444e-02 9.984538e-01 -2.015611e-02 -2.693935e+01 -9.982501e-01 5.234906e-02 2.750264e-02 3.704559e+02 +2.885571e-02 1.907354e-02 9.994016e-01 1.845181e+02 5.330830e-02 9.983657e-01 -2.059295e-02 -2.698495e+01 -9.981611e-01 5.387061e-02 2.779177e-02 3.704934e+02 +2.895664e-02 1.973245e-02 9.993859e-01 1.856944e+02 5.395803e-02 9.983165e-01 -2.127474e-02 -2.702886e+01 -9.981233e-01 5.454093e-02 2.784316e-02 3.705339e+02 +2.889801e-02 2.073879e-02 9.993672e-01 1.868784e+02 5.507379e-02 9.982330e-01 -2.230779e-02 -2.707664e+01 -9.980641e-01 5.568357e-02 2.770478e-02 3.705711e+02 +2.867620e-02 2.237084e-02 9.993384e-01 1.880579e+02 5.486210e-02 9.982074e-01 -2.391981e-02 -2.712050e+01 -9.980821e-01 5.551172e-02 2.739748e-02 3.706082e+02 +2.853832e-02 2.242116e-02 9.993412e-01 1.892526e+02 5.645011e-02 9.981168e-01 -2.400575e-02 -2.716192e+01 -9.979975e-01 5.709799e-02 2.721890e-02 3.706378e+02 +2.857488e-02 2.128007e-02 9.993651e-01 1.904514e+02 5.775729e-02 9.980679e-01 -2.290391e-02 -2.720603e+01 -9.979217e-01 5.837509e-02 2.729059e-02 3.706647e+02 +2.825155e-02 2.069094e-02 9.993867e-01 1.916495e+02 5.847119e-02 9.980396e-01 -2.231598e-02 -2.725553e+01 -9.978893e-01 5.906577e-02 2.698634e-02 3.706911e+02 +2.803197e-02 2.054972e-02 9.993958e-01 1.928516e+02 5.887339e-02 9.980192e-01 -2.217276e-02 -2.731072e+01 -9.978718e-01 5.945935e-02 2.676661e-02 3.707138e+02 +2.772542e-02 1.971598e-02 9.994211e-01 1.940530e+02 5.730109e-02 9.981301e-01 -2.128013e-02 -2.736486e+01 -9.979719e-01 5.785791e-02 2.654383e-02 3.707378e+02 +2.733715e-02 1.908386e-02 9.994441e-01 1.952563e+02 5.674853e-02 9.981757e-01 -2.061185e-02 -2.742729e+01 -9.980142e-01 5.728043e-02 2.620430e-02 3.707675e+02 +2.701697e-02 2.072601e-02 9.994201e-01 1.964612e+02 5.533918e-02 9.982208e-01 -2.219711e-02 -2.749194e+01 -9.981021e-01 5.590678e-02 2.582194e-02 3.707985e+02 +2.601407e-02 2.205502e-02 9.994182e-01 1.976553e+02 5.282342e-02 9.983295e-01 -2.340595e-02 -2.755329e+01 -9.982650e-01 5.340156e-02 2.480560e-02 3.708312e+02 +2.489928e-02 2.359472e-02 9.994115e-01 1.988495e+02 5.203390e-02 9.983357e-01 -2.486570e-02 -2.761742e+01 -9.983349e-01 5.262241e-02 2.363012e-02 3.708600e+02 +2.386246e-02 2.468120e-02 9.994105e-01 2.000293e+02 5.142593e-02 9.983413e-01 -2.588268e-02 -2.767622e+01 -9.983917e-01 5.201323e-02 2.255362e-02 3.708877e+02 +2.297214e-02 2.221329e-02 9.994893e-01 2.012120e+02 5.151849e-02 9.983985e-01 -2.337315e-02 -2.773600e+01 -9.984078e-01 5.202910e-02 2.179095e-02 3.709172e+02 +2.222043e-02 2.044834e-02 9.995439e-01 2.023813e+02 5.192044e-02 9.984180e-01 -2.157954e-02 -2.778580e+01 -9.984040e-01 5.237625e-02 2.112359e-02 3.709458e+02 +2.128424e-02 1.960266e-02 9.995813e-01 2.035429e+02 5.021586e-02 9.985248e-01 -2.065120e-02 -2.783041e+01 -9.985116e-01 5.063437e-02 2.026848e-02 3.709793e+02 +2.054293e-02 2.132376e-02 9.995615e-01 2.046991e+02 5.085382e-02 9.984561e-01 -2.234533e-02 -2.787513e+01 -9.984948e-01 5.129055e-02 1.942682e-02 3.710090e+02 +2.078650e-02 2.352607e-02 9.995071e-01 2.058459e+02 5.115341e-02 9.983887e-01 -2.456358e-02 -2.792240e+01 -9.984745e-01 5.163877e-02 1.954956e-02 3.710420e+02 +2.174381e-02 2.382212e-02 9.994797e-01 2.069932e+02 5.299988e-02 9.982828e-01 -2.494662e-02 -2.797154e+01 -9.983578e-01 5.351472e-02 2.044390e-02 3.710737e+02 +2.305391e-02 2.118962e-02 9.995096e-01 2.081384e+02 5.408037e-02 9.982850e-01 -2.241104e-02 -2.802182e+01 -9.982705e-01 5.457050e-02 2.186843e-02 3.711066e+02 +2.386756e-02 1.802847e-02 9.995525e-01 2.092829e+02 5.526062e-02 9.982849e-01 -1.932514e-02 -2.807029e+01 -9.981867e-01 5.569712e-02 2.283036e-02 3.711401e+02 +2.452256e-02 1.781443e-02 9.995405e-01 2.104201e+02 5.648632e-02 9.982192e-01 -1.917671e-02 -2.811658e+01 -9.981022e-01 5.693062e-02 2.347262e-02 3.711718e+02 +2.523824e-02 1.900168e-02 9.995008e-01 2.115435e+02 5.621754e-02 9.982102e-01 -2.039669e-02 -2.816387e+01 -9.980995e-01 5.670425e-02 2.412484e-02 3.712116e+02 +2.596534e-02 2.114382e-02 9.994392e-01 2.126680e+02 5.693052e-02 9.981224e-01 -2.259502e-02 -2.822439e+01 -9.980405e-01 5.748527e-02 2.471286e-02 3.712645e+02 +2.688906e-02 2.252342e-02 9.993846e-01 2.138083e+02 5.734950e-02 9.980647e-01 -2.403670e-02 -2.830158e+01 -9.979920e-01 5.796052e-02 2.554531e-02 3.713151e+02 +2.756963e-02 2.370490e-02 9.993388e-01 2.149347e+02 5.903551e-02 9.979352e-01 -2.530028e-02 -2.835740e+01 -9.978751e-01 5.969398e-02 2.611328e-02 3.713599e+02 +2.823530e-02 2.316818e-02 9.993328e-01 2.160644e+02 6.142383e-02 9.978019e-01 -2.486817e-02 -2.841794e+01 -9.977124e-01 6.208500e-02 2.675015e-02 3.714056e+02 +2.895157e-02 2.198305e-02 9.993390e-01 2.172053e+02 6.168615e-02 9.978133e-01 -2.373658e-02 -2.848980e+01 -9.976756e-01 6.233258e-02 2.753221e-02 3.714497e+02 +2.951312e-02 1.907135e-02 9.993824e-01 2.183429e+02 6.321470e-02 9.977809e-01 -2.090761e-02 -2.855632e+01 -9.975635e-01 6.379269e-02 2.824204e-02 3.715013e+02 +2.989349e-02 1.712511e-02 9.994064e-01 2.194816e+02 6.308028e-02 9.978278e-01 -1.898488e-02 -2.861438e+01 -9.975607e-01 6.361034e-02 2.874830e-02 3.715425e+02 +3.011284e-02 1.642563e-02 9.994115e-01 2.206186e+02 6.339360e-02 9.978206e-01 -1.830957e-02 -2.867284e+01 -9.975342e-01 6.390763e-02 2.900593e-02 3.715841e+02 +3.071846e-02 1.794240e-02 9.993670e-01 2.217530e+02 6.409439e-02 9.977457e-01 -1.988343e-02 -2.873305e+01 -9.974710e-01 6.466459e-02 2.949921e-02 3.716305e+02 +3.119720e-02 2.031000e-02 9.993069e-01 2.228841e+02 6.526895e-02 9.976182e-01 -2.231331e-02 -2.879016e+01 -9.973800e-01 6.591981e-02 2.979728e-02 3.716776e+02 +3.163667e-02 2.201799e-02 9.992569e-01 2.240221e+02 6.641822e-02 9.975012e-01 -2.408213e-02 -2.885444e+01 -9.972902e-01 6.713072e-02 3.009522e-02 3.717240e+02 +3.215400e-02 2.212238e-02 9.992381e-01 2.251567e+02 6.791495e-02 9.973959e-01 -2.426701e-02 -2.891106e+01 -9.971729e-01 6.864346e-02 3.056783e-02 3.717687e+02 +3.249416e-02 2.107739e-02 9.992496e-01 2.262981e+02 6.910238e-02 9.973378e-01 -2.328418e-02 -2.897562e+01 -9.970803e-01 6.980712e-02 3.095115e-02 3.718148e+02 +3.259193e-02 2.250187e-02 9.992154e-01 2.274392e+02 6.836365e-02 9.973549e-01 -2.468983e-02 -2.904008e+01 -9.971280e-01 6.911469e-02 3.096741e-02 3.718587e+02 +3.187781e-02 2.525790e-02 9.991726e-01 2.285886e+02 6.756781e-02 9.973392e-01 -2.736726e-02 -2.912584e+01 -9.972053e-01 6.838429e-02 3.008637e-02 3.719044e+02 +3.074562e-02 2.670713e-02 9.991704e-01 2.297358e+02 6.588768e-02 9.974145e-01 -2.868765e-02 -2.920026e+01 -9.973533e-01 6.671502e-02 2.890646e-02 3.719463e+02 +2.907586e-02 2.437294e-02 9.992800e-01 2.308922e+02 6.244129e-02 9.977059e-01 -2.615140e-02 -2.928129e+01 -9.976251e-01 6.315670e-02 2.748728e-02 3.719927e+02 +2.745499e-02 2.234156e-02 9.993733e-01 2.320423e+02 6.009895e-02 9.979048e-01 -2.395979e-02 -2.934947e+01 -9.978148e-01 6.071909e-02 2.605476e-02 3.720378e+02 +2.579172e-02 2.186172e-02 9.994282e-01 2.331941e+02 5.844677e-02 9.980176e-01 -2.333918e-02 -2.942880e+01 -9.979573e-01 5.901529e-02 2.446284e-02 3.720811e+02 +2.368716e-02 2.184153e-02 9.994808e-01 2.343473e+02 5.556369e-02 9.981872e-01 -2.313009e-02 -2.950882e+01 -9.981742e-01 5.608271e-02 2.243062e-02 3.721239e+02 +2.171464e-02 2.296846e-02 9.995003e-01 2.354994e+02 5.352943e-02 9.982753e-01 -2.410327e-02 -2.959659e+01 -9.983302e-01 5.402606e-02 2.044770e-02 3.721654e+02 +1.986651e-02 2.397034e-02 9.995152e-01 2.366505e+02 5.135826e-02 9.983682e-01 -2.496365e-02 -2.967388e+01 -9.984827e-01 5.182929e-02 1.860301e-02 3.722018e+02 +1.832768e-02 2.507352e-02 9.995176e-01 2.378019e+02 5.137417e-02 9.983413e-01 -2.598604e-02 -2.975049e+01 -9.985113e-01 5.182564e-02 1.700915e-02 3.722322e+02 +1.738760e-02 2.422637e-02 9.995553e-01 2.389548e+02 5.141892e-02 9.983619e-01 -2.509190e-02 -2.983935e+01 -9.985258e-01 5.183233e-02 1.611342e-02 3.722611e+02 +1.686987e-02 2.366037e-02 9.995777e-01 2.401112e+02 5.340723e-02 9.982714e-01 -2.453081e-02 -2.992282e+01 -9.984303e-01 5.379849e-02 1.557708e-02 3.722864e+02 +1.714782e-02 2.199497e-02 9.996110e-01 2.412660e+02 5.491312e-02 9.982283e-01 -2.290656e-02 -3.001059e+01 -9.983439e-01 5.528455e-02 1.590963e-02 3.723149e+02 +1.752198e-02 2.132145e-02 9.996191e-01 2.424179e+02 5.737645e-02 9.981036e-01 -2.229486e-02 -3.008224e+01 -9.981989e-01 5.774523e-02 1.626540e-02 3.723390e+02 +1.797492e-02 2.128691e-02 9.996118e-01 2.435643e+02 5.891133e-02 9.980138e-01 -2.231223e-02 -3.015084e+01 -9.981014e-01 5.928951e-02 1.668518e-02 3.723615e+02 +1.821831e-02 2.167787e-02 9.995990e-01 2.447111e+02 6.036818e-02 9.979171e-01 -2.274165e-02 -3.021163e+01 -9.980099e-01 6.075827e-02 1.687171e-02 3.723850e+02 +1.836344e-02 2.015539e-02 9.996282e-01 2.458616e+02 6.053876e-02 9.979400e-01 -2.123347e-02 -3.027507e+01 -9.979969e-01 6.090616e-02 1.710542e-02 3.724123e+02 +1.845766e-02 1.776821e-02 9.996717e-01 2.470154e+02 6.052571e-02 9.979885e-01 -1.885583e-02 -3.033255e+01 -9.979960e-01 6.085386e-02 1.734510e-02 3.724387e+02 +1.838624e-02 1.767309e-02 9.996747e-01 2.481654e+02 6.031276e-02 9.980033e-01 -1.875283e-02 -3.038967e+01 -9.980102e-01 6.063792e-02 1.728361e-02 3.724646e+02 +1.830146e-02 2.049032e-02 9.996225e-01 2.493113e+02 6.023859e-02 9.979511e-01 -2.155894e-02 -3.044398e+01 -9.980163e-01 6.061040e-02 1.702965e-02 3.724896e+02 +1.831494e-02 2.319009e-02 9.995633e-01 2.504570e+02 5.988799e-02 9.979105e-01 -2.424908e-02 -3.050559e+01 -9.980371e-01 6.030594e-02 1.688786e-02 3.725135e+02 +1.824744e-02 2.422714e-02 9.995399e-01 2.516039e+02 5.958663e-02 9.979031e-01 -2.527528e-02 -3.056639e+01 -9.980564e-01 6.002041e-02 1.676556e-02 3.725370e+02 +1.833082e-02 2.379822e-02 9.995487e-01 2.527501e+02 5.876783e-02 9.979626e-01 -2.483822e-02 -3.062720e+01 -9.981034e-01 5.919660e-02 1.689491e-02 3.725609e+02 +1.833458e-02 2.186871e-02 9.995927e-01 2.538916e+02 5.754216e-02 9.980806e-01 -2.289108e-02 -3.068651e+01 -9.981747e-01 5.793841e-02 1.704101e-02 3.725909e+02 +1.895284e-02 2.054646e-02 9.996092e-01 2.550311e+02 5.665422e-02 9.981604e-01 -2.159086e-02 -3.074206e+01 -9.982140e-01 5.704128e-02 1.775392e-02 3.726250e+02 +1.981324e-02 2.152717e-02 9.995719e-01 2.561532e+02 5.521671e-02 9.982187e-01 -2.259253e-02 -3.080809e+01 -9.982778e-01 5.564070e-02 1.858929e-02 3.726690e+02 +2.087556e-02 2.291746e-02 9.995194e-01 2.572903e+02 5.400206e-02 9.982519e-01 -2.401627e-02 -3.089265e+01 -9.983226e-01 5.447745e-02 1.960148e-02 3.726958e+02 +2.179337e-02 2.294936e-02 9.994990e-01 2.584266e+02 5.212832e-02 9.983505e-01 -2.405962e-02 -3.098565e+01 -9.984026e-01 5.262654e-02 2.056111e-02 3.727239e+02 +2.288180e-02 2.205930e-02 9.994948e-01 2.595635e+02 5.081659e-02 9.984385e-01 -2.319936e-02 -3.106173e+01 -9.984459e-01 5.132174e-02 2.172509e-02 3.727525e+02 +2.389504e-02 2.214499e-02 9.994692e-01 2.606907e+02 5.098194e-02 9.984268e-01 -2.334077e-02 -3.114855e+01 -9.984137e-01 5.151259e-02 2.272845e-02 3.727834e+02 +2.507285e-02 2.180893e-02 9.994477e-01 2.618180e+02 5.182303e-02 9.983894e-01 -2.308591e-02 -3.122522e+01 -9.983415e-01 5.237323e-02 2.390226e-02 3.728157e+02 +2.620505e-02 2.112838e-02 9.994333e-01 2.629430e+02 5.300659e-02 9.983407e-01 -2.249512e-02 -3.130298e+01 -9.982503e-01 5.356602e-02 2.504163e-02 3.728478e+02 +2.747809e-02 1.955251e-02 9.994311e-01 2.640695e+02 5.402012e-02 9.983186e-01 -2.101597e-02 -3.137120e+01 -9.981617e-01 5.456686e-02 2.637566e-02 3.728796e+02 +2.880124e-02 1.755130e-02 9.994310e-01 2.651963e+02 5.566907e-02 9.982659e-01 -1.913510e-02 -3.143841e+01 -9.980338e-01 5.618850e-02 2.777423e-02 3.729118e+02 +2.996738e-02 1.680578e-02 9.994096e-01 2.663151e+02 5.686221e-02 9.982108e-01 -1.849065e-02 -3.150194e+01 -9.979322e-01 5.738274e-02 2.895815e-02 3.729472e+02 +3.101353e-02 1.843424e-02 9.993489e-01 2.674316e+02 5.740065e-02 9.981470e-01 -2.019343e-02 -3.156653e+01 -9.978694e-01 5.798953e-02 2.989793e-02 3.729887e+02 +3.204371e-02 1.884488e-02 9.993088e-01 2.685450e+02 5.841564e-02 9.980778e-01 -2.069482e-02 -3.163121e+01 -9.977780e-01 5.903839e-02 3.088128e-02 3.730304e+02 +3.313263e-02 1.892819e-02 9.992717e-01 2.696609e+02 6.019889e-02 9.979676e-01 -2.089950e-02 -3.169280e+01 -9.976364e-01 6.084748e-02 3.192583e-02 3.730692e+02 +3.407353e-02 2.020493e-02 9.992151e-01 2.707768e+02 6.383201e-02 9.977103e-01 -2.235120e-02 -3.175703e+01 -9.973788e-01 6.454348e-02 3.270579e-02 3.731064e+02 +3.509529e-02 2.188017e-02 9.991444e-01 2.718873e+02 6.656603e-02 9.974889e-01 -2.418208e-02 -3.181814e+01 -9.971647e-01 6.735774e-02 3.355069e-02 3.731456e+02 +3.586434e-02 2.073976e-02 9.991414e-01 2.729940e+02 6.775543e-02 9.974336e-01 -2.313641e-02 -3.188518e+01 -9.970572e-01 6.852701e-02 3.436707e-02 3.731917e+02 +3.653254e-02 1.909397e-02 9.991500e-01 2.741090e+02 6.687679e-02 9.975294e-01 -2.150827e-02 -3.194578e+01 -9.970922e-01 6.760568e-02 3.516534e-02 3.732367e+02 +3.638784e-02 1.923931e-02 9.991525e-01 2.752179e+02 6.532282e-02 9.976306e-01 -2.158898e-02 -3.200773e+01 -9.972005e-01 6.605302e-02 3.504486e-02 3.732846e+02 +3.617968e-02 2.058737e-02 9.991332e-01 2.763300e+02 6.244405e-02 9.977875e-01 -2.282081e-02 -3.206778e+01 -9.973925e-01 6.321556e-02 3.481407e-02 3.733318e+02 +3.533805e-02 2.224954e-02 9.991277e-01 2.774329e+02 6.079909e-02 9.978524e-01 -2.437154e-02 -3.212784e+01 -9.975243e-01 6.160729e-02 3.390941e-02 3.733819e+02 +3.475886e-02 2.267348e-02 9.991385e-01 2.785403e+02 6.000085e-02 9.978919e-01 -2.473256e-02 -3.218519e+01 -9.975930e-01 6.080882e-02 3.332515e-02 3.734274e+02 +3.413445e-02 1.963147e-02 9.992244e-01 2.796498e+02 6.020416e-02 9.979510e-01 -2.166309e-02 -3.224190e+01 -9.976023e-01 6.089691e-02 3.288261e-02 3.734689e+02 +3.340342e-02 1.924515e-02 9.992566e-01 2.807593e+02 6.016510e-02 9.979626e-01 -2.123145e-02 -3.229797e+01 -9.976294e-01 6.082957e-02 3.217747e-02 3.735096e+02 +3.217587e-02 2.131791e-02 9.992548e-01 2.818653e+02 5.970760e-02 9.979460e-01 -2.321257e-02 -3.235259e+01 -9.976972e-01 6.040998e-02 3.083694e-02 3.735481e+02 +3.085894e-02 2.354868e-02 9.992463e-01 2.829562e+02 5.804208e-02 9.979932e-01 -2.531163e-02 -3.240408e+01 -9.978371e-01 5.877941e-02 2.943020e-02 3.735969e+02 +2.978499e-02 2.456797e-02 9.992543e-01 2.840560e+02 5.640284e-02 9.980637e-01 -2.621992e-02 -3.245890e+01 -9.979637e-01 5.714173e-02 2.834161e-02 3.736395e+02 +2.874689e-02 2.268368e-02 9.993293e-01 2.851558e+02 5.663423e-02 9.980996e-01 -2.428493e-02 -3.251094e+01 -9.979811e-01 5.729435e-02 2.740758e-02 3.736797e+02 +2.772464e-02 1.948195e-02 9.994257e-01 2.862620e+02 5.798826e-02 9.980950e-01 -2.106465e-02 -3.256342e+01 -9.979322e-01 5.853895e-02 2.654210e-02 3.737115e+02 +2.678622e-02 1.868537e-02 9.994665e-01 2.873590e+02 5.913635e-02 9.980446e-01 -2.024368e-02 -3.261672e+01 -9.978905e-01 5.964704e-02 2.562886e-02 3.737444e+02 +2.556701e-02 1.959153e-02 9.994811e-01 2.884598e+02 6.095751e-02 9.979169e-01 -2.112019e-02 -3.266994e+01 -9.978129e-01 6.146584e-02 2.431950e-02 3.737729e+02 +2.407142e-02 1.877902e-02 9.995338e-01 2.895569e+02 6.145767e-02 9.979047e-01 -2.022848e-02 -3.272520e+01 -9.978194e-01 6.191593e-02 2.286686e-02 3.738027e+02 +2.250750e-02 1.726551e-02 9.995976e-01 2.906596e+02 6.160784e-02 9.979266e-01 -1.862386e-02 -3.277802e+01 -9.978467e-01 6.200221e-02 2.139714e-02 3.738282e+02 +2.121948e-02 1.675093e-02 9.996345e-01 2.917599e+02 6.235930e-02 9.978906e-01 -1.804543e-02 -3.282991e+01 -9.978282e-01 6.271941e-02 2.013014e-02 3.738515e+02 +2.017046e-02 1.772901e-02 9.996393e-01 2.928557e+02 6.349541e-02 9.978017e-01 -1.897762e-02 -3.288535e+01 -9.977783e-01 6.385528e-02 1.900040e-02 3.738717e+02 +1.958363e-02 2.045658e-02 9.995989e-01 2.939479e+02 6.520023e-02 9.976363e-01 -2.169380e-02 -3.294305e+01 -9.976800e-01 6.559891e-02 1.820356e-02 3.738908e+02 +1.911234e-02 2.265476e-02 9.995606e-01 2.950435e+02 6.777548e-02 9.974142e-01 -2.390204e-02 -3.299898e+01 -9.975176e-01 6.820251e-02 1.752748e-02 3.739063e+02 +1.864856e-02 2.294446e-02 9.995628e-01 2.961409e+02 6.969872e-02 9.972747e-01 -2.419229e-02 -3.305593e+01 -9.973938e-01 7.011938e-02 1.699853e-02 3.739208e+02 +1.827626e-02 2.165264e-02 9.995985e-01 2.972378e+02 6.940651e-02 9.973262e-01 -2.287243e-02 -3.311411e+01 -9.974211e-01 6.979665e-02 1.672455e-02 3.739376e+02 +1.799015e-02 2.069440e-02 9.996240e-01 2.983325e+02 6.916362e-02 9.973651e-01 -2.189238e-02 -3.317116e+01 -9.974431e-01 6.953145e-02 1.651145e-02 3.739533e+02 +1.757377e-02 1.975928e-02 9.996503e-01 2.994266e+02 6.743331e-02 9.975048e-01 -2.090235e-02 -3.323273e+01 -9.975690e-01 6.777705e-02 1.619749e-02 3.739713e+02 +1.684571e-02 2.000676e-02 9.996579e-01 3.005214e+02 6.512311e-02 9.976549e-01 -2.106410e-02 -3.328942e+01 -9.977351e-01 6.545566e-02 1.550331e-02 3.739889e+02 +1.630437e-02 2.028024e-02 9.996614e-01 3.016112e+02 6.303737e-02 9.977845e-01 -2.127031e-02 -3.334739e+01 -9.978780e-01 6.336281e-02 1.498983e-02 3.740061e+02 +1.597173e-02 2.139484e-02 9.996435e-01 3.027044e+02 6.171092e-02 9.978439e-01 -2.234232e-02 -3.340187e+01 -9.979663e-01 6.204575e-02 1.461700e-02 3.740202e+02 +1.583999e-02 2.319179e-02 9.996055e-01 3.037683e+02 6.145821e-02 9.978181e-01 -2.412421e-02 -3.348528e+01 -9.979840e-01 6.181608e-02 1.438010e-02 3.740453e+02 +1.565487e-02 2.366279e-02 9.995974e-01 3.048311e+02 6.104826e-02 9.978322e-01 -2.457709e-02 -3.357354e+01 -9.980121e-01 6.140842e-02 1.417636e-02 3.740724e+02 +1.545823e-02 2.232703e-02 9.996312e-01 3.058896e+02 6.072105e-02 9.978845e-01 -2.322701e-02 -3.366320e+01 -9.980351e-01 6.105769e-02 1.406981e-02 3.741002e+02 +1.544784e-02 2.073623e-02 9.996656e-01 3.069579e+02 5.995293e-02 9.979669e-01 -2.162745e-02 -3.374202e+01 -9.980817e-01 6.026696e-02 1.417324e-02 3.741233e+02 +1.535441e-02 1.866612e-02 9.997079e-01 3.080258e+02 5.904052e-02 9.980643e-01 -1.954224e-02 -3.381546e+01 -9.981375e-01 5.932331e-02 1.422263e-02 3.741454e+02 +1.532248e-02 1.642088e-02 9.997477e-01 3.090845e+02 5.834139e-02 9.981469e-01 -1.728875e-02 -3.389186e+01 -9.981791e-01 5.859156e-02 1.433607e-02 3.741688e+02 +1.506775e-02 1.639849e-02 9.997520e-01 3.101465e+02 5.843252e-02 9.981422e-01 -1.725276e-02 -3.396042e+01 -9.981777e-01 5.867798e-02 1.408155e-02 3.741875e+02 +1.492071e-02 2.032847e-02 9.996820e-01 3.112030e+02 6.009224e-02 9.979679e-01 -2.119052e-02 -3.402072e+01 -9.980813e-01 6.038930e-02 1.366880e-02 3.741881e+02 +1.496538e-02 2.326028e-02 9.996174e-01 3.122632e+02 6.111959e-02 9.978386e-01 -2.413392e-02 -3.406995e+01 -9.980183e-01 6.145736e-02 1.351138e-02 3.741769e+02 +1.506507e-02 2.222173e-02 9.996395e-01 3.133224e+02 6.431237e-02 9.976613e-01 -2.314699e-02 -3.412298e+01 -9.978161e-01 6.463789e-02 1.360071e-02 3.741610e+02 +1.527875e-02 2.050008e-02 9.996731e-01 3.143816e+02 6.595827e-02 9.975914e-01 -2.146549e-02 -3.418006e+01 -9.977054e-01 6.626466e-02 1.388980e-02 3.741561e+02 +1.503256e-02 1.946310e-02 9.996975e-01 3.154318e+02 6.712549e-02 9.975353e-01 -2.043038e-02 -3.423482e+01 -9.976313e-01 6.741229e-02 1.368903e-02 3.741498e+02 +1.513520e-02 1.820085e-02 9.997198e-01 3.164837e+02 6.751761e-02 9.975336e-01 -1.918324e-02 -3.428738e+01 -9.976033e-01 6.778902e-02 1.386899e-02 3.741477e+02 +1.467220e-02 1.796064e-02 9.997310e-01 3.175310e+02 6.882042e-02 9.974494e-01 -1.892967e-02 -3.434082e+01 -9.975212e-01 6.907963e-02 1.339872e-02 3.741432e+02 +1.444217e-02 1.989135e-02 9.996978e-01 3.185746e+02 7.018483e-02 9.973159e-01 -2.085789e-02 -3.439366e+01 -9.974295e-01 7.046484e-02 1.300733e-02 3.741411e+02 +1.453355e-02 2.015458e-02 9.996912e-01 3.196141e+02 7.185035e-02 9.971912e-01 -2.114875e-02 -3.444885e+01 -9.973096e-01 7.213551e-02 1.304461e-02 3.741380e+02 +1.502299e-02 1.836250e-02 9.997185e-01 3.206542e+02 7.295167e-02 9.971465e-01 -1.941153e-02 -3.450297e+01 -9.972224e-01 7.322274e-02 1.364055e-02 3.741359e+02 +1.545025e-02 1.854314e-02 9.997087e-01 3.216855e+02 7.417501e-02 9.970518e-01 -1.964022e-02 -3.455579e+01 -9.971256e-01 7.445683e-02 1.402926e-02 3.741346e+02 +1.640900e-02 1.955847e-02 9.996740e-01 3.227109e+02 7.435414e-02 9.970165e-01 -2.072696e-02 -3.460818e+01 -9.970969e-01 7.467000e-02 1.490579e-02 3.741349e+02 +1.757317e-02 2.049954e-02 9.996354e-01 3.237304e+02 7.290594e-02 9.971021e-01 -2.172925e-02 -3.466409e+01 -9.971840e-01 7.326120e-02 1.602771e-02 3.741415e+02 +1.955621e-02 2.221562e-02 9.995619e-01 3.247432e+02 7.224748e-02 9.971081e-01 -2.357460e-02 -3.472413e+01 -9.971950e-01 7.267685e-02 1.789463e-02 3.741499e+02 +2.400102e-02 2.420454e-02 9.994189e-01 3.257546e+02 7.296495e-02 9.969982e-01 -2.589817e-02 -3.478155e+01 -9.970457e-01 7.354411e-02 2.216289e-02 3.741605e+02 +3.124184e-02 2.353357e-02 9.992348e-01 3.267599e+02 7.498778e-02 9.968500e-01 -2.582196e-02 -3.483520e+01 -9.966950e-01 7.573711e-02 2.937870e-02 3.741810e+02 +4.126022e-02 2.088538e-02 9.989301e-01 3.277632e+02 7.500457e-02 9.968957e-01 -2.394087e-02 -3.488989e+01 -9.963293e-01 7.591212e-02 3.956564e-02 3.742084e+02 +5.368858e-02 1.907265e-02 9.983756e-01 3.287600e+02 7.680496e-02 9.967768e-01 -2.317237e-02 -3.494377e+01 -9.955996e-01 7.792427e-02 5.205065e-02 3.742527e+02 +6.867914e-02 2.019478e-02 9.974344e-01 3.297540e+02 7.553177e-02 9.968202e-01 -2.538315e-02 -3.499671e+01 -9.947754e-01 7.708126e-02 6.693541e-02 3.743155e+02 +8.507312e-02 2.035085e-02 9.961668e-01 3.307358e+02 7.594317e-02 9.967506e-01 -2.684836e-02 -3.505053e+01 -9.934764e-01 7.793613e-02 8.325118e-02 3.743830e+02 +1.039982e-01 1.897419e-02 9.943965e-01 3.317234e+02 7.614583e-02 9.967315e-01 -2.698240e-02 -3.510554e+01 -9.916583e-01 7.852525e-02 1.022134e-01 3.744804e+02 +1.246828e-01 1.704763e-02 9.920502e-01 3.327046e+02 7.616829e-02 9.967374e-01 -2.670116e-02 -3.516159e+01 -9.892687e-01 7.889192e-02 1.229775e-01 3.745990e+02 +1.468331e-01 1.554589e-02 9.890391e-01 3.336616e+02 7.567840e-02 9.967693e-01 -2.690264e-02 -3.522067e+01 -9.862621e-01 7.879908e-02 1.451822e-01 3.747290e+02 +1.695940e-01 1.320699e-02 9.854255e-01 3.346297e+02 7.445637e-02 9.968807e-01 -2.617464e-02 -3.527882e+01 -9.826974e-01 7.781025e-02 1.680816e-01 3.748977e+02 +1.925433e-01 1.209853e-02 9.812139e-01 3.355685e+02 7.220381e-02 9.970388e-01 -2.646219e-02 -3.533963e+01 -9.786285e-01 7.594248e-02 1.910996e-01 3.750856e+02 +2.165431e-01 1.230739e-02 9.761955e-01 3.365106e+02 7.081605e-02 9.970884e-01 -2.827947e-02 -3.540340e+01 -9.737013e-01 7.525401e-02 2.150411e-01 3.753199e+02 +2.414280e-01 1.399444e-02 9.703178e-01 3.374435e+02 6.846956e-02 9.971584e-01 -3.141769e-02 -3.548675e+01 -9.680003e-01 7.402233e-02 2.397837e-01 3.755752e+02 +2.664124e-01 1.445478e-02 9.637507e-01 3.383588e+02 6.724205e-02 9.971726e-01 -3.354397e-02 -3.557205e+01 -9.615108e-01 7.374109e-02 2.646872e-01 3.758192e+02 +2.909667e-01 1.331715e-02 9.566405e-01 3.392774e+02 6.415774e-02 9.973807e-01 -3.339817e-02 -3.566666e+01 -9.545796e-01 7.109364e-02 2.893502e-01 3.761125e+02 +3.150581e-01 1.197903e-02 9.489968e-01 3.401906e+02 6.141724e-02 9.975671e-01 -3.298209e-02 -3.574876e+01 -9.470831e-01 6.867603e-02 3.135559e-01 3.764258e+02 +3.386165e-01 1.083876e-02 9.408620e-01 3.410858e+02 5.964464e-02 9.976754e-01 -3.295938e-02 -3.584774e+01 -9.390322e-01 6.727796e-02 3.371829e-01 3.767548e+02 +3.616661e-01 1.134474e-02 9.322386e-01 3.419810e+02 5.785087e-02 9.977260e-01 -3.458519e-02 -3.594102e+01 -9.305111e-01 6.643909e-02 3.601874e-01 3.771224e+02 +3.840006e-01 1.283994e-02 9.232436e-01 3.428581e+02 5.551326e-02 9.977734e-01 -3.696585e-02 -3.603514e+01 -9.216626e-01 6.544715e-02 3.824328e-01 3.775010e+02 +4.044489e-01 1.398036e-02 9.144537e-01 3.437372e+02 5.247520e-02 9.978811e-01 -3.846479e-02 -3.612336e+01 -9.130539e-01 6.354317e-02 4.028583e-01 3.779080e+02 +4.225995e-01 1.512346e-02 9.061904e-01 3.446071e+02 4.881684e-02 9.980295e-01 -3.942178e-02 -3.620812e+01 -9.050009e-01 6.089696e-02 4.210284e-01 3.783285e+02 +4.388722e-01 1.519153e-02 8.984211e-01 3.454683e+02 4.595081e-02 9.981693e-01 -3.932483e-02 -3.629380e+01 -8.973738e-01 5.854174e-02 4.373707e-01 3.787579e+02 +4.535847e-01 1.378553e-02 8.911065e-01 3.463280e+02 4.285553e-02 9.983863e-01 -3.725918e-02 -3.637362e+01 -8.901822e-01 5.508902e-02 4.522620e-01 3.792057e+02 +4.673813e-01 1.152996e-02 8.839806e-01 3.471844e+02 4.080313e-02 9.985680e-01 -3.459812e-02 -3.645408e+01 -8.831137e-01 5.223968e-02 4.662416e-01 3.796741e+02 +4.804250e-01 1.037984e-02 8.769744e-01 3.480318e+02 3.847425e-02 9.987179e-01 -3.289780e-02 -3.652663e+01 -8.761915e-01 4.954584e-02 4.794097e-01 3.801388e+02 +4.919827e-01 1.210394e-02 8.705208e-01 3.488667e+02 3.595274e-02 9.987679e-01 -3.420614e-02 -3.661383e+01 -8.698623e-01 4.812642e-02 4.909414e-01 3.806434e+02 +5.011110e-01 1.553549e-02 8.652435e-01 3.496994e+02 3.088033e-02 9.988810e-01 -3.581949e-02 -3.668708e+01 -8.648319e-01 4.466853e-02 5.000706e-01 3.811433e+02 +5.065468e-01 1.697493e-02 8.620454e-01 3.505280e+02 2.730075e-02 9.989891e-01 -3.571376e-02 -3.676696e+01 -8.617802e-01 4.162517e-02 5.055712e-01 3.816591e+02 +5.091706e-01 1.752000e-02 8.604873e-01 3.513606e+02 2.422140e-02 9.991051e-01 -3.467472e-02 -3.684283e+01 -8.603248e-01 3.849754e-02 5.082905e-01 3.821680e+02 +5.096473e-01 1.948658e-02 8.601627e-01 3.521892e+02 2.154960e-02 9.991407e-01 -3.540323e-02 -3.691785e+01 -8.601135e-01 3.657931e-02 5.087894e-01 3.826770e+02 +5.092742e-01 1.953833e-02 8.603825e-01 3.530187e+02 2.170606e-02 9.991326e-01 -3.553736e-02 -3.699027e+01 -8.603306e-01 3.677377e-02 5.084084e-01 3.831752e+02 +5.079392e-01 1.861843e-02 8.611916e-01 3.538482e+02 2.158717e-02 9.991772e-01 -3.433393e-02 -3.706326e+01 -8.611224e-01 3.603023e-02 5.071194e-01 3.836723e+02 +5.043381e-01 2.107722e-02 8.632490e-01 3.546727e+02 1.944507e-02 9.991713e-01 -3.575638e-02 -3.713485e+01 -8.632873e-01 3.481923e-02 5.035104e-01 3.841627e+02 +4.986392e-01 2.346685e-02 8.664919e-01 3.554913e+02 1.724835e-02 9.991669e-01 -3.698593e-02 -3.721682e+01 -8.666380e-01 3.338818e-02 4.978190e-01 3.846520e+02 +4.907290e-01 2.528486e-02 8.709453e-01 3.563087e+02 1.454665e-02 9.992018e-01 -3.720458e-02 -3.729827e+01 -8.711908e-01 3.092670e-02 4.899695e-01 3.851303e+02 +4.799469e-01 2.496123e-02 8.769424e-01 3.571333e+02 1.166104e-02 9.993253e-01 -3.482678e-02 -3.736955e+01 -8.772201e-01 2.694106e-02 4.793320e-01 3.856029e+02 +4.669944e-01 2.477692e-02 8.839131e-01 3.579474e+02 1.077051e-02 9.993738e-01 -3.370374e-02 -3.743691e+01 -8.841947e-01 2.525964e-02 4.664351e-01 3.860524e+02 +4.512714e-01 2.542345e-02 8.920245e-01 3.587791e+02 9.802427e-03 9.993925e-01 -3.344254e-02 -3.750109e+01 -8.923329e-01 2.383566e-02 4.507481e-01 3.864905e+02 +4.340167e-01 2.485858e-02 9.005618e-01 3.596073e+02 9.052191e-03 9.994484e-01 -3.195081e-02 -3.756468e+01 -9.008594e-01 2.201924e-02 4.335523e-01 3.869021e+02 +4.163071e-01 2.592154e-02 9.088545e-01 3.604504e+02 8.590291e-03 9.994367e-01 -3.243990e-02 -3.762915e+01 -9.091835e-01 2.131228e-02 4.158500e-01 3.872983e+02 +3.978013e-01 2.962639e-02 9.169931e-01 3.612939e+02 1.073255e-02 9.992598e-01 -3.694018e-02 -3.769369e+01 -9.174089e-01 2.453652e-02 3.971889e-01 3.876738e+02 +3.776738e-01 3.686171e-02 9.252047e-01 3.621345e+02 1.207203e-02 9.989263e-01 -4.472678e-02 -3.776131e+01 -9.258600e-01 2.806123e-02 3.768233e-01 3.880084e+02 +3.557663e-01 4.299435e-02 9.335855e-01 3.629894e+02 1.369379e-02 9.985942e-01 -5.120657e-02 -3.783265e+01 -9.344747e-01 3.100189e-02 3.546774e-01 3.883432e+02 +3.323214e-01 4.277980e-02 9.421955e-01 3.638478e+02 1.553681e-02 9.985869e-01 -5.082021e-02 -3.789973e+01 -9.430383e-01 3.152735e-02 3.311872e-01 3.886336e+02 +3.082042e-01 3.389923e-02 9.507160e-01 3.647326e+02 1.970197e-02 9.989231e-01 -4.200514e-02 -3.797253e+01 -9.511162e-01 3.167713e-02 3.072044e-01 3.889204e+02 +2.841251e-01 2.320584e-02 9.585063e-01 3.656296e+02 2.422086e-02 9.992143e-01 -3.137106e-02 -3.804145e+01 -9.584813e-01 3.212914e-02 2.833398e-01 3.891800e+02 +2.598516e-01 2.099832e-02 9.654202e-01 3.665052e+02 2.912858e-02 9.991381e-01 -2.957193e-02 -3.809978e+01 -9.652092e-01 3.580563e-02 2.590160e-01 3.893984e+02 +2.355335e-01 2.635803e-02 9.715087e-01 3.673950e+02 3.045937e-02 9.989409e-01 -3.448690e-02 -3.815653e+01 -9.713888e-01 3.771436e-02 2.344812e-01 3.896122e+02 +2.111106e-01 3.124699e-02 9.769626e-01 3.682768e+02 3.354312e-02 9.986686e-01 -3.918953e-02 -3.821481e+01 -9.768865e-01 4.104368e-02 2.097814e-01 3.897852e+02 +1.863040e-01 3.376144e-02 9.819119e-01 3.691837e+02 3.493054e-02 9.985499e-01 -4.096111e-02 -3.827648e+01 -9.818710e-01 4.192992e-02 1.848546e-01 3.899526e+02 +1.614060e-01 3.345141e-02 9.863210e-01 3.700994e+02 3.802296e-02 9.984725e-01 -4.008580e-02 -3.833966e+01 -9.861554e-01 4.397292e-02 1.598876e-01 3.900969e+02 +1.371867e-01 3.321723e-02 9.899881e-01 3.710002e+02 3.885619e-02 9.984878e-01 -3.888689e-02 -3.840180e+01 -9.897828e-01 4.380192e-02 1.356885e-01 3.902039e+02 +1.134415e-01 3.325141e-02 9.929881e-01 3.719334e+02 4.256531e-02 9.983595e-01 -3.829406e-02 -3.846045e+01 -9.926325e-01 4.661097e-02 1.118400e-01 3.903034e+02 +9.132906e-02 3.454838e-02 9.952213e-01 3.728656e+02 4.724907e-02 9.981221e-01 -3.898502e-02 -3.850820e+01 -9.946992e-01 5.058374e-02 8.952517e-02 3.903595e+02 +7.074693e-02 3.685824e-02 9.968131e-01 3.738109e+02 5.234287e-02 9.978031e-01 -4.060979e-02 -3.856188e+01 -9.961201e-01 5.504907e-02 6.866224e-02 3.904099e+02 +5.159564e-02 3.761108e-02 9.979596e-01 3.747641e+02 5.625412e-02 9.975945e-01 -4.050573e-02 -3.862691e+01 -9.970825e-01 5.822925e-02 4.935575e-02 3.904627e+02 +3.366704e-02 3.663359e-02 9.987615e-01 3.757109e+02 5.908011e-02 9.975075e-01 -3.857913e-02 -3.868727e+01 -9.976854e-01 6.030577e-02 3.141881e-02 3.904864e+02 +1.649719e-02 3.560628e-02 9.992297e-01 3.766697e+02 6.065571e-02 9.974895e-01 -3.654570e-02 -3.874752e+01 -9.980224e-01 6.121188e-02 1.429605e-02 3.905158e+02 +3.234061e-04 3.726176e-02 9.993055e-01 3.776245e+02 6.197497e-02 9.973838e-01 -3.721017e-02 -3.880690e+01 -9.980777e-01 6.194395e-02 -1.986739e-03 3.905099e+02 +-1.468989e-02 3.788718e-02 9.991740e-01 3.785940e+02 6.248885e-02 9.973633e-01 -3.689982e-02 -3.886531e+01 -9.979376e-01 6.189516e-02 -1.701869e-02 3.905014e+02 +-2.819125e-02 3.817298e-02 9.988734e-01 3.795659e+02 6.435643e-02 9.972667e-01 -3.629526e-02 -3.892585e+01 -9.975287e-01 6.326070e-02 -3.057088e-02 3.904758e+02 +-3.979322e-02 3.728231e-02 9.985121e-01 3.805407e+02 6.644989e-02 9.971902e-01 -3.458477e-02 -3.898410e+01 -9.969960e-01 6.497476e-02 -4.215882e-02 3.904399e+02 +-4.940719e-02 3.900922e-02 9.980166e-01 3.815265e+02 6.861378e-02 9.970089e-01 -3.557309e-02 -3.904251e+01 -9.964192e-01 6.672011e-02 -5.193598e-02 3.903932e+02 +-5.772041e-02 3.492883e-02 9.977216e-01 3.825193e+02 7.324736e-02 9.968424e-01 -3.066054e-02 -3.909471e+01 -9.956421e-01 7.131072e-02 -6.009660e-02 3.903346e+02 +-6.473462e-02 3.450784e-02 9.973057e-01 3.835281e+02 7.493275e-02 9.967484e-01 -2.962473e-02 -3.914688e+01 -9.950852e-01 7.281310e-02 -6.710990e-02 3.902604e+02 +-7.176905e-02 3.153623e-02 9.969226e-01 3.845460e+02 7.544198e-02 9.968085e-01 -2.610151e-02 -3.919895e+01 -9.945641e-01 7.333652e-02 -7.391916e-02 3.901811e+02 +-7.716372e-02 2.841466e-02 9.966134e-01 3.855685e+02 7.679296e-02 9.967937e-01 -2.247405e-02 -3.924437e+01 -9.940567e-01 7.479870e-02 -7.909836e-02 3.900964e+02 +-8.201334e-02 2.510265e-02 9.963150e-01 3.865958e+02 7.819100e-02 9.967634e-01 -1.867753e-02 -3.929115e+01 -9.935593e-01 7.637104e-02 -8.371070e-02 3.900058e+02 +-8.543119e-02 2.401072e-02 9.960547e-01 3.876298e+02 8.026450e-02 9.966262e-01 -1.714025e-02 -3.933412e+01 -9.931058e-01 7.848350e-02 -8.707018e-02 3.899114e+02 +-8.803242e-02 2.384530e-02 9.958321e-01 3.886677e+02 8.568043e-02 9.961896e-01 -1.627964e-02 -3.937413e+01 -9.924259e-01 8.389017e-02 -8.974007e-02 3.898064e+02 +-9.041945e-02 2.367495e-02 9.956223e-01 3.897097e+02 8.942196e-02 9.958723e-01 -1.555986e-02 -3.941584e+01 -9.918811e-01 8.762357e-02 -9.216329e-02 3.897018e+02 +-9.237642e-02 2.699857e-02 9.953580e-01 3.907557e+02 9.143995e-02 9.956383e-01 -1.851990e-02 -3.946183e+01 -9.915167e-01 8.930467e-02 -9.444226e-02 3.895946e+02 +-9.422515e-02 3.136285e-02 9.950568e-01 3.918010e+02 8.742361e-02 9.959031e-01 -2.311111e-02 -3.950815e+01 -9.917050e-01 8.481379e-02 -9.658097e-02 3.894955e+02 +-9.704064e-02 3.426806e-02 9.946903e-01 3.928502e+02 8.144691e-02 9.963285e-01 -2.637866e-02 -3.956067e+01 -9.919423e-01 7.845464e-02 -9.947539e-02 3.893973e+02 +-1.001221e-01 3.459528e-02 9.943735e-01 3.938996e+02 7.408308e-02 9.968804e-01 -2.722319e-02 -3.961767e+01 -9.922134e-01 7.094060e-02 -1.023727e-01 3.892965e+02 +-1.033632e-01 3.178098e-02 9.941358e-01 3.949485e+02 6.410318e-02 9.976243e-01 -2.522752e-02 -3.967543e+01 -9.925759e-01 6.111965e-02 -1.051549e-01 3.892009e+02 +-1.072522e-01 2.917917e-02 9.938036e-01 3.959949e+02 5.767532e-02 9.980685e-01 -2.308003e-02 -3.973297e+01 -9.925576e-01 5.484254e-02 -1.087279e-01 3.890961e+02 +-1.111569e-01 2.842543e-02 9.933962e-01 3.970358e+02 5.421474e-02 9.982758e-01 -2.249866e-02 -3.978687e+01 -9.923230e-01 5.135583e-02 -1.125063e-01 3.889826e+02 +-1.161581e-01 3.101226e-02 9.927464e-01 3.980706e+02 5.024148e-02 9.984163e-01 -2.531080e-02 -3.984112e+01 -9.919593e-01 4.693698e-02 -1.175322e-01 3.888652e+02 +-1.214338e-01 3.349091e-02 9.920344e-01 3.991011e+02 4.673828e-02 9.985150e-01 -2.798853e-02 -3.989960e+01 -9.914986e-01 4.296721e-02 -1.228187e-01 3.887417e+02 +-1.259566e-01 3.422799e-02 9.914451e-01 4.001264e+02 4.368655e-02 9.986264e-01 -2.892584e-02 -3.995826e+01 -9.910734e-01 3.966940e-02 -1.272789e-01 3.886147e+02 +-1.307728e-01 3.074390e-02 9.909355e-01 4.011483e+02 4.224459e-02 9.987840e-01 -2.541243e-02 -4.001550e+01 -9.905120e-01 3.853840e-02 -1.319126e-01 3.884819e+02 +-1.372457e-01 2.576622e-02 9.902018e-01 4.021467e+02 3.957139e-02 9.990062e-01 -2.051059e-02 -4.007087e+01 -9.897463e-01 3.636867e-02 -1.381289e-01 3.883435e+02 +-1.468718e-01 2.073528e-02 9.889382e-01 4.031207e+02 3.516095e-02 9.992578e-01 -1.572975e-02 -4.012492e+01 -9.885304e-01 3.246174e-02 -1.474919e-01 3.882065e+02 +-1.583181e-01 2.103874e-02 9.871640e-01 4.040658e+02 3.391612e-02 9.992988e-01 -1.585801e-02 -4.017328e+01 -9.868055e-01 3.097015e-02 -1.589207e-01 3.880589e+02 +-1.724727e-01 2.014981e-02 9.848082e-01 4.049734e+02 3.083869e-02 9.994111e-01 -1.504772e-02 -4.022092e+01 -9.845315e-01 2.777486e-02 -1.729925e-01 3.878976e+02 +-1.914353e-01 1.710742e-02 9.813561e-01 4.058576e+02 2.731648e-02 9.995536e-01 -1.209597e-02 -4.026899e+01 -9.811251e-01 2.449160e-02 -1.918171e-01 3.877328e+02 +-2.142186e-01 1.688515e-02 9.766398e-01 4.066917e+02 2.837192e-02 9.995362e-01 -1.105785e-02 -4.031451e+01 -9.763736e-01 2.534034e-02 -2.145983e-01 3.875304e+02 +-2.415732e-01 1.735650e-02 9.702273e-01 4.075038e+02 3.123680e-02 9.994609e-01 -1.010194e-02 -4.035653e+01 -9.698797e-01 2.786644e-02 -2.419852e-01 3.873265e+02 +-2.735703e-01 1.846768e-02 9.616747e-01 4.082533e+02 3.518469e-02 9.993386e-01 -9.181888e-03 -4.039285e+01 -9.612083e-01 3.132433e-02 -2.740392e-01 3.870592e+02 +-3.093631e-01 1.668805e-02 9.507975e-01 4.090000e+02 3.983733e-02 9.991957e-01 -4.575570e-03 -4.044088e+01 -9.501092e-01 3.646171e-02 -3.097791e-01 3.868063e+02 +-3.473232e-01 1.244234e-02 9.376629e-01 4.097127e+02 4.457546e-02 9.990007e-01 3.255091e-03 -4.048410e+01 -9.366855e-01 4.292731e-02 -3.475307e-01 3.865377e+02 +-3.868260e-01 1.076227e-02 9.220899e-01 4.103338e+02 4.733314e-02 9.988455e-01 8.198594e-03 -4.051211e+01 -9.209372e-01 4.681683e-02 -3.868888e-01 3.861955e+02 +-4.269380e-01 1.251308e-02 9.041943e-01 4.109629e+02 5.130986e-02 9.986285e-01 1.040728e-02 -4.054236e+01 -9.028241e-01 5.083734e-02 -4.269945e-01 3.858960e+02 +-4.669042e-01 1.387528e-02 8.841990e-01 4.114991e+02 5.074638e-02 9.986496e-01 1.112549e-02 -4.057237e+01 -8.828507e-01 5.006443e-02 -4.669779e-01 3.855181e+02 +-5.085598e-01 1.794547e-02 8.608396e-01 4.120722e+02 4.739007e-02 9.988507e-01 7.174203e-03 -4.058979e+01 -8.597215e-01 4.444376e-02 -5.088258e-01 3.851987e+02 +-5.504104e-01 1.892402e-02 8.346797e-01 4.125625e+02 4.005366e-02 9.991904e-01 3.758617e-03 -4.060998e+01 -8.339329e-01 3.550075e-02 -5.507228e-01 3.847855e+02 +-5.923263e-01 2.016678e-02 8.054457e-01 4.130929e+02 3.821936e-02 9.992646e-01 3.086951e-03 -4.062371e+01 -8.047912e-01 3.261209e-02 -5.926615e-01 3.844266e+02 +-6.334111e-01 2.368105e-02 7.734530e-01 4.135967e+02 4.176414e-02 9.991209e-01 3.611886e-03 -4.063771e+01 -7.726876e-01 3.459040e-02 -6.338434e-01 3.840402e+02 +-6.734181e-01 2.638650e-02 7.387908e-01 4.139967e+02 4.389436e-02 9.990268e-01 4.329272e-03 -4.064995e+01 -7.379576e-01 3.534415e-02 -6.739209e-01 3.835453e+02 +-7.118307e-01 3.033642e-02 7.016956e-01 4.144444e+02 4.852914e-02 9.988034e-01 6.048774e-03 -4.066077e+01 -7.006726e-01 3.835838e-02 -7.124511e-01 3.831167e+02 +-7.468844e-01 3.348426e-02 6.641103e-01 4.147911e+02 5.427751e-02 9.984685e-01 1.070008e-02 -4.066324e+01 -6.627350e-01 4.403797e-02 -7.475581e-01 3.825800e+02 +-7.795992e-01 3.359414e-02 6.253771e-01 4.151809e+02 5.782961e-02 9.981555e-01 1.847162e-02 -4.067681e+01 -6.236031e-01 5.056576e-02 -7.801040e-01 3.821059e+02 +-8.105779e-01 3.438205e-02 5.846207e-01 4.154794e+02 6.130817e-02 9.977717e-01 2.632406e-02 -4.067519e+01 -5.824130e-01 5.717972e-02 -8.108795e-01 3.815370e+02 +-8.391133e-01 3.576013e-02 5.427800e-01 4.158130e+02 6.323563e-02 9.974841e-01 3.204185e-02 -4.068038e+01 -5.402686e-01 6.120977e-02 -8.392635e-01 3.810360e+02 +-8.653086e-01 3.760778e-02 4.998266e-01 4.161234e+02 6.362338e-02 9.973564e-01 3.510316e-02 -4.068051e+01 -4.971851e-01 6.217571e-02 -8.654139e-01 3.805171e+02 +-8.894180e-01 3.786038e-02 4.555241e-01 4.163455e+02 6.084659e-02 9.975014e-01 3.589767e-02 -4.067365e+01 -4.530268e-01 5.964511e-02 -8.894994e-01 3.799093e+02 +-9.109226e-01 3.879306e-02 4.107495e-01 4.166093e+02 5.882285e-02 9.976106e-01 3.623299e-02 -4.066719e+01 -4.083625e-01 5.716689e-02 -9.110280e-01 3.793571e+02 +-9.294913e-01 4.161126e-02 3.664894e-01 4.167803e+02 5.973220e-02 9.974817e-01 3.823867e-02 -4.065548e+01 -3.639753e-01 5.743372e-02 -9.296361e-01 3.787153e+02 +-9.457052e-01 4.361622e-02 3.220859e-01 4.169839e+02 5.989778e-02 9.973699e-01 4.080935e-02 -4.064696e+01 -3.194589e-01 5.788583e-02 -9.458305e-01 3.781277e+02 +-9.597580e-01 4.138499e-02 2.777623e-01 4.171682e+02 5.543025e-02 9.975404e-01 4.290143e-02 -4.064126e+01 -2.753037e-01 5.657142e-02 -9.596914e-01 3.775258e+02 +-9.714164e-01 3.788347e-02 2.343397e-01 4.172575e+02 4.935572e-02 9.978429e-01 4.328414e-02 -4.063767e+01 -2.321945e-01 5.361292e-02 -9.711907e-01 3.768620e+02 +-9.805143e-01 3.733988e-02 1.928664e-01 4.173597e+02 4.638709e-02 9.980144e-01 4.260697e-02 -4.063827e+01 -1.908925e-01 5.072324e-02 -9.802996e-01 3.762453e+02 +-9.870897e-01 4.001808e-02 1.550889e-01 4.174088e+02 4.698348e-02 9.980328e-01 4.150869e-02 -4.063174e+01 -1.531227e-01 4.825940e-02 -9.870281e-01 3.755661e+02 +-9.914784e-01 4.734388e-02 1.213639e-01 4.174743e+02 5.290142e-02 9.976741e-01 4.298503e-02 -4.062155e+01 -1.190465e-01 4.903904e-02 -9.916769e-01 3.749224e+02 +-9.944506e-01 5.032159e-02 9.238904e-02 4.175199e+02 5.486441e-02 9.973725e-01 4.730595e-02 -4.062128e+01 -8.976579e-02 5.211229e-02 -9.945986e-01 3.742740e+02 +-9.963579e-01 5.090114e-02 6.841141e-02 4.175464e+02 5.453956e-02 9.971351e-01 5.241210e-02 -4.061484e+01 -6.554758e-02 5.595233e-02 -9.962795e-01 3.735990e+02 +-9.973605e-01 5.257179e-02 5.008196e-02 4.175706e+02 5.539281e-02 9.968527e-01 5.671213e-02 -4.061108e+01 -4.694288e-02 5.933661e-02 -9.971337e-01 3.729408e+02 +-9.977368e-01 5.643176e-02 3.656072e-02 4.175829e+02 5.855275e-02 9.964914e-01 5.980338e-02 -4.059978e+01 -3.305764e-02 6.180875e-02 -9.975404e-01 3.722797e+02 +-9.979387e-01 5.853666e-02 2.630290e-02 4.175868e+02 6.005018e-02 9.963295e-01 6.100361e-02 -4.058532e+01 -2.263541e-02 6.245735e-02 -9.977909e-01 3.716178e+02 +-9.981258e-01 5.859017e-02 1.766497e-02 4.175950e+02 5.959712e-02 9.962185e-01 6.322043e-02 -4.057158e+01 -1.389408e-02 6.415471e-02 -9.978432e-01 3.709572e+02 +-9.983670e-01 5.608826e-02 1.083908e-02 4.176016e+02 5.666494e-02 9.963776e-01 6.340863e-02 -4.055928e+01 -7.243337e-03 6.391927e-02 -9.979288e-01 3.702988e+02 +-9.984587e-01 5.523047e-02 5.468267e-03 4.176066e+02 5.546386e-02 9.965252e-01 6.213883e-02 -4.054554e+01 -2.017310e-03 6.234633e-02 -9.980525e-01 3.696425e+02 +-9.985403e-01 5.400655e-02 7.888959e-04 4.176080e+02 5.395495e-02 9.966999e-01 6.064681e-02 -4.052983e+01 2.489033e-03 6.060084e-02 -9.981590e-01 3.689890e+02 +-9.983432e-01 5.746011e-02 -3.019606e-03 4.175993e+02 5.718863e-02 9.966755e-01 5.802917e-02 -4.051435e+01 6.343930e-03 5.776033e-02 -9.983103e-01 3.683385e+02 +-9.981988e-01 5.980767e-02 -4.714373e-03 4.175914e+02 5.945341e-02 9.966760e-01 5.569691e-02 -4.050263e+01 8.029806e-03 5.531629e-02 -9.984366e-01 3.676879e+02 +-9.980428e-01 6.211134e-02 -7.257784e-03 4.175836e+02 6.161690e-02 9.965644e-01 5.534254e-02 -4.049044e+01 1.067025e-02 5.478701e-02 -9.984411e-01 3.670381e+02 +-9.980911e-01 6.103622e-02 -9.423322e-03 4.175810e+02 6.042491e-02 9.966376e-01 5.533706e-02 -4.047710e+01 1.276920e-02 5.466201e-02 -9.984233e-01 3.663865e+02 +-9.980375e-01 6.167062e-02 -1.086083e-02 4.175717e+02 6.095524e-02 9.965083e-01 5.705803e-02 -4.046211e+01 1.434172e-02 5.628401e-02 -9.983118e-01 3.657427e+02 +-9.980050e-01 6.198111e-02 -1.201468e-02 4.175639e+02 6.113705e-02 9.962575e-01 6.109973e-02 -4.044906e+01 1.575675e-02 6.024329e-02 -9.980594e-01 3.650895e+02 +-9.979314e-01 6.294045e-02 -1.308985e-02 4.175533e+02 6.200190e-02 9.961012e-01 6.275430e-02 -4.043480e+01 1.698860e-02 6.181288e-02 -9.979432e-01 3.644461e+02 +-9.979690e-01 6.232564e-02 -1.317110e-02 4.175479e+02 6.136985e-02 9.960909e-01 6.353472e-02 -4.041964e+01 1.707946e-02 6.259736e-02 -9.978927e-01 3.638033e+02 +-9.979037e-01 6.340727e-02 -1.295431e-02 4.175416e+02 6.246063e-02 9.960141e-01 6.367532e-02 -4.040386e+01 1.694016e-02 6.273269e-02 -9.978866e-01 3.631626e+02 +-9.978645e-01 6.425012e-02 -1.176097e-02 4.175361e+02 6.338159e-02 9.959753e-01 6.337191e-02 -4.038834e+01 1.578529e-02 6.249114e-02 -9.979207e-01 3.625252e+02 +-9.979179e-01 6.382777e-02 -9.271668e-03 4.175335e+02 6.309680e-02 9.959016e-01 6.479748e-02 -4.037199e+01 1.336955e-02 6.407754e-02 -9.978554e-01 3.618882e+02 +-9.980519e-01 6.189874e-02 -7.805749e-03 4.175375e+02 6.127718e-02 9.960781e-01 6.382401e-02 -4.035799e+01 1.172576e-02 6.322135e-02 -9.979307e-01 3.612545e+02 +-9.980457e-01 6.214703e-02 -6.525265e-03 4.175388e+02 6.162126e-02 9.961495e-01 6.236169e-02 -4.034505e+01 1.037573e-02 6.183771e-02 -9.980323e-01 3.606232e+02 +-9.978513e-01 6.536762e-02 -4.465269e-03 4.175344e+02 6.496718e-02 9.959660e-01 6.189384e-02 -4.033016e+01 8.493110e-03 6.147074e-02 -9.980728e-01 3.599929e+02 +-9.976312e-01 6.867260e-02 -4.010350e-03 4.175285e+02 6.831833e-02 9.959236e-01 5.889560e-02 -4.031263e+01 8.038517e-03 5.848210e-02 -9.982561e-01 3.593687e+02 +-9.976576e-01 6.828064e-02 -4.133756e-03 4.175275e+02 6.793318e-02 9.960461e-01 5.724649e-02 -4.029791e+01 8.026239e-03 5.683157e-02 -9.983515e-01 3.587448e+02 +-9.977441e-01 6.705738e-02 -3.163691e-03 4.175300e+02 6.675464e-02 9.960232e-01 5.900504e-02 -4.028499e+01 7.107834e-03 5.866073e-02 -9.982527e-01 3.581193e+02 +-9.976496e-01 6.847307e-02 -2.579748e-03 4.175281e+02 6.820003e-02 9.959062e-01 5.932501e-02 -4.026816e+01 6.631353e-03 5.900963e-02 -9.982354e-01 3.574974e+02 +-9.975187e-01 7.037877e-02 -1.826994e-03 4.175260e+02 7.013948e-02 9.956984e-01 6.054090e-02 -4.025330e+01 6.079929e-03 6.026253e-02 -9.981641e-01 3.568739e+02 +-9.974730e-01 7.103793e-02 -1.120646e-03 4.175267e+02 7.083931e-02 9.956408e-01 6.067282e-02 -4.024284e+01 5.425832e-03 6.044010e-02 -9.981571e-01 3.562535e+02 +-9.975649e-01 6.973804e-02 -9.582234e-04 4.175330e+02 6.955799e-02 9.958056e-01 5.943736e-02 -4.023335e+01 5.099250e-03 5.922596e-02 -9.982316e-01 3.556368e+02 +-9.975238e-01 7.032630e-02 -6.754751e-04 4.175362e+02 7.017378e-02 9.959071e-01 5.696168e-02 -4.022048e+01 4.678615e-03 5.677322e-02 -9.983761e-01 3.550209e+02 +-9.972614e-01 7.395486e-02 5.824489e-04 4.175361e+02 7.388477e-02 9.959057e-01 5.208562e-02 -4.020715e+01 3.271921e-03 5.198600e-02 -9.986425e-01 3.544036e+02 +-9.968543e-01 7.923146e-02 1.956186e-03 4.175352e+02 7.923039e-02 9.956103e-01 4.982613e-02 -4.019308e+01 2.000199e-03 4.982438e-02 -9.987560e-01 3.537794e+02 +-9.968150e-01 7.962148e-02 4.503054e-03 4.175435e+02 7.974778e-02 9.954895e-01 5.139040e-02 -4.018098e+01 -3.909630e-04 5.158583e-02 -9.986685e-01 3.531463e+02 +-9.968619e-01 7.875927e-02 7.961298e-03 4.175567e+02 7.907033e-02 9.954788e-01 5.262904e-02 -4.016848e+01 -3.780279e-03 5.309338e-02 -9.985824e-01 3.525113e+02 +-9.968804e-01 7.809746e-02 1.141722e-02 4.175719e+02 7.862129e-02 9.952993e-01 5.655103e-02 -4.015523e+01 -6.947058e-03 5.727224e-02 -9.983344e-01 3.518713e+02 +-9.966785e-01 8.002104e-02 1.511949e-02 4.175863e+02 8.079116e-02 9.949188e-01 6.007797e-02 -4.014061e+01 -1.023516e-02 6.109994e-02 -9.980792e-01 3.512303e+02 +-9.964299e-01 8.208330e-02 1.974387e-02 4.176006e+02 8.313422e-02 9.947223e-01 6.013520e-02 -4.012150e+01 -1.470358e-02 6.156189e-02 -9.979950e-01 3.505908e+02 +-9.965198e-01 7.988718e-02 2.379756e-02 4.176251e+02 8.117948e-02 9.949235e-01 5.947250e-02 -4.010675e+01 -1.892567e-02 6.119739e-02 -9.979462e-01 3.499510e+02 +-9.966036e-01 7.752111e-02 2.778064e-02 4.176514e+02 7.902016e-02 9.952026e-01 5.768554e-02 -4.008842e+01 -2.317552e-02 5.968483e-02 -9.979482e-01 3.493085e+02 +-9.965350e-01 7.657261e-02 3.247435e-02 4.176730e+02 7.829657e-02 9.953766e-01 5.563369e-02 -4.006743e+01 -2.806419e-02 5.798354e-02 -9.979230e-01 3.486687e+02 +-9.963067e-01 7.749108e-02 3.698810e-02 4.176940e+02 7.946130e-02 9.953109e-01 5.515510e-02 -4.004620e+01 -3.254063e-02 5.789051e-02 -9.977925e-01 3.480239e+02 +-9.961738e-01 7.694770e-02 4.143423e-02 4.177229e+02 7.915755e-02 9.953639e-01 5.463360e-02 -4.003207e+01 -3.703821e-02 5.770439e-02 -9.976464e-01 3.473783e+02 +-9.958695e-01 7.844827e-02 4.571453e-02 4.177520e+02 8.081086e-02 9.953536e-01 5.235272e-02 -4.001916e+01 -4.139515e-02 5.583070e-02 -9.975818e-01 3.467321e+02 +-9.955529e-01 7.946800e-02 5.058952e-02 4.177859e+02 8.199103e-02 9.953821e-01 4.991863e-02 -4.000519e+01 -4.638897e-02 5.384451e-02 -9.974712e-01 3.460817e+02 +-9.952469e-01 8.060070e-02 5.465420e-02 4.178225e+02 8.321709e-02 9.954028e-01 4.741391e-02 -3.998835e+01 -5.058136e-02 5.173670e-02 -9.973790e-01 3.454291e+02 +-9.951743e-01 7.875304e-02 5.853264e-02 4.178654e+02 8.156545e-02 9.955440e-01 4.731888e-02 -3.997543e+01 -5.454533e-02 5.186476e-02 -9.971634e-01 3.447706e+02 +-9.953263e-01 7.572747e-02 5.992490e-02 4.179088e+02 7.876142e-02 9.956389e-01 4.999712e-02 -3.996448e+01 -5.587741e-02 5.448321e-02 -9.969500e-01 3.441035e+02 +-9.955820e-01 7.438084e-02 5.730617e-02 4.179493e+02 7.726252e-02 9.957650e-01 4.982564e-02 -3.995296e+01 -5.335741e-02 5.403312e-02 -9.971125e-01 3.434344e+02 +-9.958326e-01 7.404339e-02 5.324537e-02 4.179847e+02 7.656391e-02 9.959579e-01 4.696595e-02 -3.994100e+01 -4.955264e-02 5.084689e-02 -9.974764e-01 3.427611e+02 +-9.961130e-01 7.366647e-02 4.829207e-02 4.180157e+02 7.591984e-02 9.960236e-01 4.661587e-02 -3.992693e+01 -4.466602e-02 5.010100e-02 -9.977449e-01 3.420773e+02 +-9.965384e-01 7.197934e-02 4.159526e-02 4.180456e+02 7.391268e-02 9.961576e-01 4.697739e-02 -3.991232e+01 -3.805404e-02 4.988918e-02 -9.980295e-01 3.413838e+02 +-9.968599e-01 7.159864e-02 3.382182e-02 4.180650e+02 7.316072e-02 9.961904e-01 4.745700e-02 -3.989858e+01 -3.029512e-02 4.978240e-02 -9.983005e-01 3.406768e+02 +-9.972004e-01 7.058760e-02 2.467257e-02 4.180810e+02 7.170187e-02 9.962874e-01 4.764741e-02 -3.988711e+01 -2.121765e-02 4.928308e-02 -9.985595e-01 3.399647e+02 +-9.974496e-01 6.974288e-02 1.517188e-02 4.180885e+02 7.035258e-02 9.965395e-01 4.426636e-02 -3.987245e+01 -1.203212e-02 4.522083e-02 -9.989046e-01 3.392417e+02 +-9.975800e-01 6.921304e-02 6.604994e-03 4.180929e+02 6.942944e-02 9.967115e-01 4.178103e-02 -3.985706e+01 -3.691482e-03 4.213850e-02 -9.991050e-01 3.385088e+02 +-9.976565e-01 6.841253e-02 -1.101959e-03 4.180902e+02 6.830739e-02 9.967940e-01 4.166190e-02 -3.984248e+01 3.948622e-03 4.148899e-02 -9.991312e-01 3.377607e+02 +-9.975773e-01 6.911781e-02 -7.895807e-03 4.180806e+02 6.871224e-02 9.966890e-01 4.346894e-02 -3.982923e+01 1.087414e-02 4.282108e-02 -9.990236e-01 3.369951e+02 +-9.975370e-01 6.870261e-02 -1.413890e-02 4.180674e+02 6.799319e-02 9.966390e-01 4.568997e-02 -3.981544e+01 1.723040e-02 4.461608e-02 -9.988556e-01 3.362160e+02 +-9.974862e-01 6.795078e-02 -2.009817e-02 4.180506e+02 6.695264e-02 9.966604e-01 4.674752e-02 -3.979992e+01 2.320758e-02 4.528437e-02 -9.987045e-01 3.354239e+02 +-9.973529e-01 6.790502e-02 -2.600249e-02 4.180265e+02 6.662011e-02 9.966496e-01 4.744826e-02 -3.978075e+01 2.913735e-02 4.559037e-02 -9.985352e-01 3.346199e+02 +-9.971020e-01 6.888833e-02 -3.228017e-02 4.179949e+02 6.726754e-02 9.965378e-01 4.886124e-02 -3.975988e+01 3.553438e-02 4.654822e-02 -9.982838e-01 3.338055e+02 +-9.968909e-01 6.886900e-02 -3.828340e-02 4.179583e+02 6.688499e-02 9.964619e-01 5.089204e-02 -3.973825e+01 4.165284e-02 4.817322e-02 -9.979701e-01 3.329741e+02 +-9.965930e-01 6.898154e-02 -4.520951e-02 4.179176e+02 6.659836e-02 9.964105e-01 5.225649e-02 -3.971724e+01 4.865197e-02 4.906756e-02 -9.976098e-01 3.321366e+02 +-9.962923e-01 6.802173e-02 -5.267628e-02 4.178838e+02 6.520007e-02 9.964342e-01 5.355119e-02 -3.969943e+01 5.613109e-02 4.991813e-02 -9.971748e-01 3.312928e+02 +-9.956497e-01 7.037695e-02 -6.106406e-02 4.178604e+02 6.712275e-02 9.962931e-01 5.380166e-02 -3.968873e+01 6.462410e-02 4.946881e-02 -9.966828e-01 3.304432e+02 +-9.952412e-01 6.862712e-02 -6.917611e-02 4.178233e+02 6.484620e-02 9.963508e-01 5.549742e-02 -3.967442e+01 7.273231e-02 5.074750e-02 -9.960596e-01 3.295952e+02 +-9.945865e-01 6.910495e-02 -7.760229e-02 4.177744e+02 6.461117e-02 9.961648e-01 5.900015e-02 -3.965815e+01 8.138188e-02 5.366678e-02 -9.952371e-01 3.287412e+02 +-9.938244e-01 7.020873e-02 -8.592957e-02 4.177127e+02 6.502503e-02 9.959737e-01 6.170890e-02 -3.964024e+01 8.991610e-02 5.574023e-02 -9.943883e-01 3.278916e+02 +-9.930458e-01 6.980894e-02 -9.479900e-02 4.176471e+02 6.383146e-02 9.958618e-01 6.468968e-02 -3.961968e+01 9.892263e-02 5.818864e-02 -9.933924e-01 3.270421e+02 +-9.921457e-01 6.824726e-02 -1.048299e-01 4.175685e+02 6.127492e-02 9.957777e-01 6.835331e-02 -3.959176e+01 1.090522e-01 6.139299e-02 -9.921384e-01 3.261902e+02 +-9.910645e-01 6.481612e-02 -1.165767e-01 4.174826e+02 5.672738e-02 9.958321e-01 7.141653e-02 -3.956530e+01 1.207198e-01 6.416528e-02 -9.906107e-01 3.253404e+02 +-9.892881e-01 6.179250e-02 -1.322526e-01 4.173732e+02 5.280940e-02 9.961207e-01 7.038874e-02 -3.953637e+01 1.360891e-01 6.265056e-02 -9.887137e-01 3.244893e+02 +-9.868316e-01 5.506730e-02 -1.520886e-01 4.172169e+02 4.604011e-02 9.969978e-01 6.225428e-02 -3.950951e+01 1.550602e-01 5.443231e-02 -9.864043e-01 3.236460e+02 +-9.833553e-01 5.064781e-02 -1.744914e-01 4.170334e+02 4.205916e-02 9.977309e-01 5.257458e-02 -3.948831e+01 1.767583e-01 4.436052e-02 -9.832541e-01 3.227957e+02 +-9.786750e-01 5.297727e-02 -1.984660e-01 4.168211e+02 4.492885e-02 9.979832e-01 4.484246e-02 -3.946357e+01 2.004414e-01 3.496933e-02 -9.790814e-01 3.219659e+02 +-9.731606e-01 5.596431e-02 -2.232185e-01 4.165996e+02 4.787777e-02 9.979915e-01 4.148026e-02 -3.944846e+01 2.250916e-01 2.967975e-02 -9.738855e-01 3.211404e+02 +-9.668436e-01 5.681996e-02 -2.489680e-01 4.163424e+02 4.772537e-02 9.979593e-01 4.241933e-02 -3.943539e+01 2.508702e-01 2.913077e-02 -9.675823e-01 3.202960e+02 +-9.600100e-01 6.028192e-02 -2.733989e-01 4.160850e+02 4.962229e-02 9.977199e-01 4.574488e-02 -3.941994e+01 2.755331e-01 3.034886e-02 -9.608124e-01 3.194800e+02 +-9.526510e-01 6.269977e-02 -2.975313e-01 4.157901e+02 4.911452e-02 9.973899e-01 5.292601e-02 -3.939961e+01 3.000731e-01 3.580691e-02 -9.532439e-01 3.186475e+02 +-9.448041e-01 6.215758e-02 -3.216857e-01 4.155003e+02 4.576506e-02 9.972507e-01 5.827957e-02 -3.938292e+01 3.244238e-01 4.034081e-02 -9.450512e-01 3.178468e+02 +-9.362250e-01 6.190869e-02 -3.459047e-01 4.151912e+02 4.393679e-02 9.972569e-01 5.956603e-02 -3.936257e+01 3.486436e-01 4.056926e-02 -9.363770e-01 3.170562e+02 +-9.272982e-01 5.976518e-02 -3.695216e-01 4.148446e+02 4.099988e-02 9.974488e-01 5.843667e-02 -3.933782e+01 3.720714e-01 3.903787e-02 -9.273829e-01 3.162571e+02 +-9.175716e-01 5.749618e-02 -3.933911e-01 4.145022e+02 3.786835e-02 9.976281e-01 5.748199e-02 -3.931273e+01 3.957630e-01 3.784677e-02 -9.175725e-01 3.154856e+02 +-9.074314e-01 5.951668e-02 -4.159640e-01 4.141178e+02 3.800068e-02 9.974854e-01 5.982256e-02 -3.928662e+01 4.184785e-01 3.847795e-02 -9.074113e-01 3.147047e+02 +-8.973573e-01 6.538720e-02 -4.364338e-01 4.137285e+02 4.126777e-02 9.970621e-01 6.453026e-02 -3.925850e+01 4.393710e-01 3.989605e-02 -8.974193e-01 3.139515e+02 +-8.881527e-01 6.938065e-02 -4.542808e-01 4.133181e+02 4.185583e-02 9.966416e-01 7.038221e-02 -3.922615e+01 4.576383e-01 4.349585e-02 -8.880739e-01 3.132017e+02 +-8.799404e-01 7.292533e-02 -4.694538e-01 4.128963e+02 4.078046e-02 9.960957e-01 7.829580e-02 -3.918833e+01 4.733307e-01 4.975109e-02 -8.794788e-01 3.124477e+02 +-8.727932e-01 7.777190e-02 -4.818544e-01 4.124664e+02 4.156938e-02 9.954812e-01 8.537645e-02 -3.914884e+01 4.863169e-01 5.448558e-02 -8.720821e-01 3.117089e+02 +-8.664790e-01 8.093799e-02 -4.926086e-01 4.120329e+02 4.388664e-02 9.952988e-01 8.633763e-02 -3.910808e+01 4.972808e-01 5.319080e-02 -8.659576e-01 3.109834e+02 +-8.610757e-01 7.810755e-02 -5.024419e-01 4.115959e+02 4.307155e-02 9.957842e-01 8.098532e-02 -3.906451e+01 5.066493e-01 4.809353e-02 -8.608098e-01 3.102614e+02 +-8.559759e-01 7.748815e-02 -5.111759e-01 4.111556e+02 4.307674e-02 9.959560e-01 7.884204e-02 -3.901801e+01 5.152180e-01 4.546709e-02 -8.558523e-01 3.095458e+02 +-8.517812e-01 7.798333e-02 -5.180613e-01 4.107051e+02 4.149926e-02 9.957955e-01 8.166445e-02 -3.897287e+01 5.222516e-01 4.806108e-02 -8.514361e-01 3.088264e+02 +-8.470525e-01 7.873570e-02 -5.256451e-01 4.102523e+02 3.851217e-02 9.954594e-01 8.704805e-02 -3.893456e+01 5.301122e-01 5.349053e-02 -8.462386e-01 3.081141e+02 +-8.418034e-01 7.888077e-02 -5.339895e-01 4.097966e+02 3.907107e-02 9.955741e-01 8.547269e-02 -3.888923e+01 5.383683e-01 5.108766e-02 -8.411597e-01 3.074148e+02 +-8.366535e-01 7.579252e-02 -5.424632e-01 4.093327e+02 3.794796e-02 9.960210e-01 8.063526e-02 -3.884515e+01 5.464164e-01 4.687840e-02 -8.362007e-01 3.067233e+02 +-8.315187e-01 7.027706e-02 -5.510334e-01 4.088713e+02 3.425379e-02 9.965641e-01 7.540914e-02 -3.880913e+01 5.544397e-01 4.382912e-02 -8.310690e-01 3.060399e+02 +-8.264256e-01 6.178272e-02 -5.596460e-01 4.084082e+02 2.927698e-02 9.973321e-01 6.686847e-02 -3.877692e+01 5.622843e-01 3.887707e-02 -8.260297e-01 3.053649e+02 +-8.213540e-01 5.291752e-02 -5.679589e-01 4.079387e+02 2.313261e-02 9.979585e-01 5.952799e-02 -3.874785e+01 5.699495e-01 3.575518e-02 -8.209014e-01 3.046903e+02 +-8.160011e-01 4.854728e-02 -5.760082e-01 4.074620e+02 1.899833e-02 9.981811e-01 5.721503e-02 -3.872128e+01 5.777382e-01 3.574433e-02 -8.154391e-01 3.040222e+02 +-8.108043e-01 4.994747e-02 -5.831824e-01 4.069708e+02 1.807348e-02 9.980137e-01 6.034857e-02 -3.869535e+01 5.850383e-01 3.839074e-02 -8.100965e-01 3.033564e+02 +-8.060853e-01 5.128465e-02 -5.895731e-01 4.064733e+02 1.577521e-02 9.977461e-01 6.522161e-02 -3.866868e+01 5.915892e-01 4.327354e-02 -8.050774e-01 3.026931e+02 +-8.023604e-01 5.118404e-02 -5.946411e-01 4.059767e+02 1.291411e-02 9.975715e-01 6.844127e-02 -3.863844e+01 5.967002e-01 4.723530e-02 -8.010729e-01 3.020325e+02 +-7.993996e-01 5.401034e-02 -5.983671e-01 4.054699e+02 1.399497e-02 9.973548e-01 7.132731e-02 -3.860516e+01 6.006367e-01 4.864489e-02 -7.980409e-01 3.013728e+02 +-7.974486e-01 6.036549e-02 -6.003597e-01 4.049550e+02 2.008729e-02 9.970874e-01 7.357441e-02 -3.857147e+01 6.030525e-01 4.661221e-02 -7.963385e-01 3.007197e+02 +-7.967563e-01 6.419880e-02 -6.008809e-01 4.044385e+02 2.506364e-02 9.969959e-01 7.328632e-02 -3.853547e+01 6.037807e-01 4.333108e-02 -7.959719e-01 3.000652e+02 +-7.974043e-01 6.338629e-02 -6.001071e-01 4.039283e+02 2.669962e-02 9.972000e-01 6.985159e-02 -3.849876e+01 6.028544e-01 3.967733e-02 -7.968640e-01 2.994068e+02 +-7.990138e-01 6.201758e-02 -5.981060e-01 4.034217e+02 2.698035e-02 9.973629e-01 6.737332e-02 -3.846373e+01 6.007071e-01 3.769510e-02 -7.985800e-01 2.987440e+02 +-8.009513e-01 6.499850e-02 -5.951909e-01 4.029080e+02 3.033297e-02 9.972184e-01 6.808318e-02 -3.842711e+01 5.979607e-01 3.647740e-02 -8.006950e-01 2.980726e+02 +-8.039509e-01 7.105715e-02 -5.904353e-01 4.023964e+02 3.380305e-02 9.966910e-01 7.392182e-02 -3.838837e+01 5.937343e-01 3.947099e-02 -8.036925e-01 2.973962e+02 +-8.077663e-01 7.844469e-02 -5.842602e-01 4.018845e+02 3.812731e-02 9.959836e-01 8.101133e-02 -3.834540e+01 5.882686e-01 4.316195e-02 -8.075130e-01 2.967089e+02 +-8.121029e-01 8.390017e-02 -5.774510e-01 4.013821e+02 4.114050e-02 9.953790e-01 8.676438e-02 -3.830153e+01 5.820622e-01 4.670498e-02 -8.118019e-01 2.960182e+02 +-8.165155e-01 8.683049e-02 -5.707564e-01 4.008895e+02 4.365821e-02 9.950808e-01 8.892722e-02 -3.825446e+01 5.756704e-01 4.769225e-02 -8.162898e-01 2.953269e+02 +-8.206851e-01 8.867802e-02 -5.644574e-01 4.003919e+02 4.812647e-02 9.951008e-01 8.636066e-02 -3.821589e+01 5.693503e-01 4.370956e-02 -8.209322e-01 2.946399e+02 +-8.247317e-01 8.990770e-02 -5.583317e-01 3.998577e+02 5.328936e-02 9.952438e-01 8.154773e-02 -3.820117e+01 5.630080e-01 3.750186e-02 -8.256002e-01 2.939555e+02 +-8.287173e-01 8.971579e-02 -5.524299e-01 3.993521e+02 5.683850e-02 9.954559e-01 7.639902e-02 -3.817656e+01 5.567739e-01 3.191390e-02 -8.300508e-01 2.932664e+02 +-8.327041e-01 9.004055e-02 -5.463484e-01 3.988481e+02 5.811018e-02 9.954521e-01 7.548753e-02 -3.815469e+01 5.506606e-01 3.111037e-02 -8.341493e-01 2.925689e+02 +-8.366095e-01 9.353832e-02 -5.397546e-01 3.983626e+02 6.057151e-02 9.950676e-01 7.855844e-02 -3.813115e+01 5.444406e-01 3.302898e-02 -8.381489e-01 2.918698e+02 +-8.402401e-01 9.650348e-02 -5.335575e-01 3.978855e+02 6.214883e-02 9.946897e-01 8.203633e-02 -3.810562e+01 5.386410e-01 3.577023e-02 -8.417757e-01 2.911672e+02 +-8.432169e-01 9.881380e-02 -5.284138e-01 3.974121e+02 6.348124e-02 9.943864e-01 8.465084e-02 -3.807648e+01 5.338122e-01 3.783465e-02 -8.447562e-01 2.904636e+02 +-8.457614e-01 9.638537e-02 -5.247833e-01 3.969560e+02 6.142397e-02 9.945976e-01 8.368151e-02 -3.804507e+01 5.300140e-01 3.854031e-02 -8.471127e-01 2.897623e+02 +-8.473816e-01 9.269609e-02 -5.228307e-01 3.965037e+02 5.876544e-02 9.949672e-01 8.115982e-02 -3.801386e+01 5.277226e-01 3.804896e-02 -8.485642e-01 2.890626e+02 +-8.485763e-01 8.990301e-02 -5.213787e-01 3.960574e+02 5.610059e-02 9.951910e-01 8.029683e-02 -3.797866e+01 5.260904e-01 3.888832e-02 -8.495391e-01 2.883630e+02 +-8.488811e-01 9.142226e-02 -5.206178e-01 3.956047e+02 5.798709e-02 9.950913e-01 8.019199e-02 -3.794570e+01 5.253937e-01 3.788435e-02 -8.500155e-01 2.876671e+02 +-8.490447e-01 9.421822e-02 -5.198520e-01 3.951579e+02 6.069875e-02 9.948502e-01 8.117135e-02 -3.791078e+01 5.248227e-01 3.736374e-02 -8.503912e-01 2.869746e+02 +-8.496092e-01 8.926468e-02 -5.198038e-01 3.947182e+02 5.759244e-02 9.953817e-01 7.680089e-02 -3.787681e+01 5.242588e-01 3.531397e-02 -8.508265e-01 2.862803e+02 +-8.502159e-01 8.135294e-02 -5.201103e-01 3.942891e+02 5.227486e-02 9.961510e-01 7.035993e-02 -3.784700e+01 5.238324e-01 3.263244e-02 -8.511961e-01 2.855911e+02 +-8.500745e-01 7.907116e-02 -5.206929e-01 3.938496e+02 5.229241e-02 9.964519e-01 6.594711e-02 -3.781640e+01 5.240600e-01 2.883167e-02 -8.511932e-01 2.849028e+02 +-8.497047e-01 7.893384e-02 -5.213170e-01 3.934084e+02 5.162608e-02 9.964348e-01 6.672625e-02 -3.778627e+01 5.247254e-01 2.978405e-02 -8.507504e-01 2.842095e+02 +-8.491539e-01 7.836142e-02 -5.222999e-01 3.929769e+02 4.805860e-02 9.962935e-01 7.134185e-02 -3.775095e+01 5.259545e-01 3.547920e-02 -8.497724e-01 2.834990e+02 +-8.494749e-01 7.550302e-02 -5.221989e-01 3.925474e+02 4.419734e-02 9.964125e-01 7.217106e-02 -3.771998e+01 5.257747e-01 3.822770e-02 -8.497645e-01 2.827950e+02 +-8.502514e-01 7.427153e-02 -5.211106e-01 3.921174e+02 4.441459e-02 9.965877e-01 6.957170e-02 -3.768592e+01 5.244997e-01 3.600851e-02 -8.506489e-01 2.820938e+02 +-8.516772e-01 7.345893e-02 -5.188928e-01 3.916865e+02 4.554873e-02 9.967563e-01 6.634869e-02 -3.765425e+01 5.220836e-01 3.287275e-02 -8.522606e-01 2.813944e+02 +-8.540025e-01 7.268243e-02 -5.151669e-01 3.912599e+02 4.587674e-02 9.968567e-01 6.459098e-02 -3.762593e+01 5.182422e-01 3.152668e-02 -8.546526e-01 2.806928e+02 +-8.570064e-01 7.198362e-02 -5.102533e-01 3.908351e+02 4.542488e-02 9.968935e-01 6.434179e-02 -3.759919e+01 5.132998e-01 3.196313e-02 -8.576140e-01 2.799825e+02 +-8.600245e-01 7.147313e-02 -5.052222e-01 3.904133e+02 4.522305e-02 9.969214e-01 6.405139e-02 -3.757467e+01 5.082448e-01 3.223807e-02 -8.606091e-01 2.792708e+02 +-8.627596e-01 7.041392e-02 -5.006873e-01 3.899956e+02 4.450538e-02 9.969876e-01 6.352145e-02 -3.755037e+01 5.036518e-01 3.252046e-02 -8.632944e-01 2.785556e+02 +-8.654515e-01 6.974059e-02 -4.961149e-01 3.895797e+02 4.380457e-02 9.970049e-01 6.373725e-02 -3.752591e+01 4.990741e-01 3.342939e-02 -8.659143e-01 2.778379e+02 +-8.679704e-01 7.090506e-02 -4.915281e-01 3.891682e+02 4.467749e-02 9.968903e-01 6.491156e-02 -3.750051e+01 4.946022e-01 3.438107e-02 -8.684392e-01 2.771167e+02 +-8.702087e-01 7.182935e-02 -4.874190e-01 3.887559e+02 4.512280e-02 9.967768e-01 6.633224e-02 -3.747612e+01 4.906126e-01 3.572918e-02 -8.706450e-01 2.763938e+02 +-8.714300e-01 7.169797e-02 -4.852517e-01 3.883453e+02 4.474560e-02 9.967545e-01 6.691917e-02 -3.745202e+01 4.884748e-01 3.660249e-02 -8.718100e-01 2.756656e+02 +-8.720146e-01 7.074578e-02 -4.843404e-01 3.879365e+02 4.444591e-02 9.968566e-01 6.558598e-02 -3.742798e+01 4.874579e-01 3.566497e-02 -8.724178e-01 2.749409e+02 +-8.724077e-01 6.876568e-02 -4.839175e-01 3.875274e+02 4.348444e-02 9.970474e-01 6.328870e-02 -3.740359e+01 4.868408e-01 3.417066e-02 -8.728221e-01 2.742141e+02 +-8.725352e-01 6.750679e-02 -4.838649e-01 3.871201e+02 4.276857e-02 9.971596e-01 6.199661e-02 -3.738231e+01 4.866757e-01 3.340001e-02 -8.729440e-01 2.734832e+02 +-8.723057e-01 6.868849e-02 -4.841123e-01 3.867076e+02 4.271851e-02 9.970037e-01 6.448734e-02 -3.735974e+01 4.870914e-01 3.557211e-02 -8.726263e-01 2.727438e+02 +-8.719624e-01 7.295508e-02 -4.841065e-01 3.862923e+02 4.413009e-02 9.965216e-01 7.069017e-02 -3.733408e+01 4.875798e-01 4.027550e-02 -8.721490e-01 2.720052e+02 +-8.716780e-01 7.600696e-02 -4.841492e-01 3.858757e+02 4.426661e-02 9.960730e-01 7.667526e-02 -3.730697e+01 4.880758e-01 4.540448e-02 -8.716194e-01 2.712650e+02 +-8.713796e-01 7.730350e-02 -4.844809e-01 3.854598e+02 4.381364e-02 9.958242e-01 8.009070e-02 -3.727684e+01 4.886491e-01 4.856252e-02 -8.711279e-01 2.705232e+02 +-8.712914e-01 7.597951e-02 -4.848488e-01 3.850447e+02 4.324177e-02 9.959859e-01 7.837156e-02 -3.724388e+01 4.888573e-01 4.731874e-02 -8.710795e-01 2.697866e+02 +-8.710996e-01 7.482144e-02 -4.853732e-01 3.846282e+02 4.356422e-02 9.962026e-01 7.538231e-02 -3.720928e+01 4.891703e-01 4.452060e-02 -8.710513e-01 2.690492e+02 +-8.707931e-01 7.370569e-02 -4.860935e-01 3.842100e+02 4.329844e-02 9.963541e-01 7.351056e-02 -3.717579e+01 4.897394e-01 4.296539e-02 -8.708096e-01 2.683130e+02 +-8.703351e-01 7.182504e-02 -4.871940e-01 3.837960e+02 4.171472e-02 9.965036e-01 7.239036e-02 -3.714615e+01 4.906900e-01 4.268070e-02 -8.702883e-01 2.675753e+02 +-8.695140e-01 7.063471e-02 -4.888313e-01 3.833819e+02 4.064863e-02 9.965975e-01 7.170130e-02 -3.711849e+01 4.922327e-01 4.247495e-02 -8.694267e-01 2.668430e+02 +-8.686152e-01 7.153422e-02 -4.902964e-01 3.829635e+02 4.155346e-02 9.965545e-01 7.178067e-02 -3.708763e+01 4.937419e-01 4.197626e-02 -8.685948e-01 2.661091e+02 +-8.677361e-01 7.161364e-02 -4.918390e-01 3.825441e+02 4.179329e-02 9.965739e-01 7.137043e-02 -3.705973e+01 4.952650e-01 4.137512e-02 -8.677561e-01 2.653820e+02 +-8.663632e-01 7.085598e-02 -4.943625e-01 3.821259e+02 4.126417e-02 9.966555e-01 7.053380e-02 -3.703359e+01 4.977068e-01 4.070842e-02 -8.663895e-01 2.646563e+02 +-8.646762e-01 6.867580e-02 -4.976131e-01 3.817035e+02 3.942239e-02 9.968325e-01 6.907110e-02 -3.700633e+01 5.007804e-01 4.010703e-02 -8.646447e-01 2.639362e+02 +-8.623018e-01 6.719063e-02 -5.019173e-01 3.812723e+02 3.770182e-02 9.969258e-01 6.868411e-02 -3.697662e+01 5.049893e-01 4.030323e-02 -8.621841e-01 2.632183e+02 +-8.593712e-01 6.794649e-02 -5.068180e-01 3.808545e+02 3.715917e-02 9.968102e-01 7.062942e-02 -3.695190e+01 5.100004e-01 4.186395e-02 -8.591548e-01 2.625043e+02 +-8.565345e-01 6.833280e-02 -5.115460e-01 3.804662e+02 3.642649e-02 9.967283e-01 7.215130e-02 -3.693470e+01 5.148027e-01 4.316624e-02 -8.562213e-01 2.617971e+02 +-8.538075e-01 6.674271e-02 -5.162928e-01 3.800641e+02 3.449439e-02 9.968211e-01 7.181777e-02 -3.691555e+01 5.194449e-01 4.350934e-02 -8.533956e-01 2.610959e+02 +-8.511952e-01 6.562106e-02 -5.207309e-01 3.796615e+02 3.350682e-02 9.969234e-01 7.085876e-02 -3.690082e+01 5.237786e-01 4.286660e-02 -8.507752e-01 2.603946e+02 +-8.486631e-01 6.575298e-02 -5.248310e-01 3.792649e+02 3.355083e-02 9.969369e-01 7.064797e-02 -3.689727e+01 5.278687e-01 4.234780e-02 -8.482696e-01 2.596827e+02 +-8.460580e-01 6.680816e-02 -5.288880e-01 3.788562e+02 3.349489e-02 9.968178e-01 7.233472e-02 -3.688648e+01 5.320376e-01 4.348432e-02 -8.456034e-01 2.589828e+02 +-8.437231e-01 6.853445e-02 -5.323855e-01 3.784466e+02 3.357867e-02 9.966120e-01 7.507938e-02 -3.687630e+01 5.357274e-01 4.546940e-02 -8.431659e-01 2.582841e+02 +-8.421322e-01 7.071191e-02 -5.346151e-01 3.780242e+02 3.420468e-02 9.963736e-01 7.790771e-02 -3.685622e+01 5.381854e-01 4.732224e-02 -8.414970e-01 2.575930e+02 +-8.409820e-01 7.296122e-02 -5.361212e-01 3.775828e+02 3.589423e-02 9.962068e-01 7.926954e-02 -3.682846e+01 5.398712e-01 4.742059e-02 -8.404108e-01 2.569049e+02 +-8.400583e-01 7.380694e-02 -5.374519e-01 3.771354e+02 3.704336e-02 9.961937e-01 7.890463e-02 -3.679578e+01 5.412299e-01 4.637546e-02 -8.395948e-01 2.562319e+02 +-8.391013e-01 7.398132e-02 -5.389210e-01 3.766854e+02 3.805420e-02 9.962648e-01 7.751355e-02 -3.676063e+01 5.426426e-01 4.453351e-02 -8.387824e-01 2.555564e+02 +-8.386358e-01 7.430761e-02 -5.396001e-01 3.762426e+02 3.980068e-02 9.963625e-01 7.535036e-02 -3.672833e+01 5.432365e-01 4.171506e-02 -8.385428e-01 2.548875e+02 +-8.387529e-01 7.399493e-02 -5.394611e-01 3.758301e+02 4.041300e-02 9.964506e-01 7.384368e-02 -3.669075e+01 5.430105e-01 4.013536e-02 -8.387662e-01 2.542039e+02 +-8.390090e-01 7.343329e-02 -5.391396e-01 3.754395e+02 4.003763e-02 9.964970e-01 7.342095e-02 -3.666065e+01 5.426426e-01 4.001496e-02 -8.390100e-01 2.535176e+02 +-8.393576e-01 7.263225e-02 -5.387053e-01 3.750650e+02 3.960406e-02 9.965703e-01 7.265790e-02 -3.663135e+01 5.421350e-01 3.965104e-02 -8.393554e-01 2.528224e+02 +-8.395092e-01 7.207672e-02 -5.385437e-01 3.746661e+02 3.933931e-02 9.966241e-01 7.206047e-02 -3.660645e+01 5.419196e-01 3.930949e-02 -8.395106e-01 2.521423e+02 +-8.391539e-01 7.134641e-02 -5.391942e-01 3.742667e+02 3.823504e-02 9.966446e-01 7.237087e-02 -3.658137e+01 5.425484e-01 4.011418e-02 -8.390662e-01 2.514572e+02 +-8.381380e-01 7.098910e-02 -5.408191e-01 3.738653e+02 3.755447e-02 9.966522e-01 7.262250e-02 -3.655424e+01 5.441640e-01 4.055749e-02 -8.379980e-01 2.507739e+02 +-8.371684e-01 7.085423e-02 -5.423363e-01 3.734674e+02 3.767000e-02 9.966883e-01 7.206501e-02 -3.652793e+01 5.456464e-01 3.990074e-02 -8.370651e-01 2.500899e+02 +-8.362898e-01 7.106447e-02 -5.436628e-01 3.730707e+02 3.817059e-02 9.967051e-01 7.156765e-02 -3.649596e+01 5.469574e-01 3.909936e-02 -8.362469e-01 2.494013e+02 +-8.356175e-01 7.169500e-02 -5.446129e-01 3.726646e+02 3.930759e-02 9.967086e-01 7.089978e-02 -3.645750e+01 5.479036e-01 3.783768e-02 -8.356854e-01 2.487128e+02 +-8.353606e-01 7.162018e-02 -5.450167e-01 3.722603e+02 3.971890e-02 9.967486e-01 7.010379e-02 -3.641915e+01 5.482656e-01 3.691447e-02 -8.354892e-01 2.480169e+02 +-8.351213e-01 7.035285e-02 -5.455482e-01 3.718489e+02 3.895379e-02 9.968611e-01 6.892316e-02 -3.637948e+01 5.486848e-01 3.630803e-02 -8.352405e-01 2.473153e+02 +-8.347285e-01 6.908784e-02 -5.463106e-01 3.714412e+02 3.831173e-02 9.969805e-01 6.754281e-02 -3.633117e+01 5.493274e-01 3.544980e-02 -8.348549e-01 2.466077e+02 +-8.339974e-01 6.872221e-02 -5.474721e-01 3.710072e+02 3.848617e-02 9.970421e-01 6.652685e-02 -3.629107e+01 5.504246e-01 3.441311e-02 -8.341754e-01 2.459002e+02 +-8.332475e-01 6.866288e-02 -5.486201e-01 3.705671e+02 3.829498e-02 9.970430e-01 6.662294e-02 -3.624303e+01 5.515724e-01 3.450400e-02 -8.334131e-01 2.451838e+02 +-8.326030e-01 6.781918e-02 -5.497025e-01 3.701210e+02 3.732152e-02 9.970891e-01 6.648647e-02 -3.620182e+01 5.526115e-01 3.484110e-02 -8.327104e-01 2.444631e+02 +-8.319931e-01 6.799610e-02 -5.506034e-01 3.696934e+02 3.731252e-02 9.970717e-01 6.675087e-02 -3.616451e+01 5.535299e-01 3.499186e-02 -8.320939e-01 2.437227e+02 +-8.314646e-01 6.897918e-02 -5.512790e-01 3.692479e+02 3.805969e-02 9.970034e-01 6.734740e-02 -3.613035e+01 5.542726e-01 3.501546e-02 -8.315983e-01 2.429822e+02 +-8.307255e-01 6.935324e-02 -5.523453e-01 3.687858e+02 3.829001e-02 9.969779e-01 6.759390e-02 -3.608992e+01 5.553639e-01 3.500267e-02 -8.308705e-01 2.422374e+02 +-8.300986e-01 6.851255e-02 -5.533917e-01 3.683151e+02 3.760078e-02 9.970417e-01 6.703667e-02 -3.605182e+01 5.563476e-01 3.483908e-02 -8.302190e-01 2.414895e+02 +-8.297665e-01 6.737437e-02 -5.540291e-01 3.678405e+02 3.644705e-02 9.971092e-01 6.666994e-02 -3.601314e+01 5.569193e-01 3.512775e-02 -8.298234e-01 2.407354e+02 +-8.295849e-01 6.817569e-02 -5.542031e-01 3.673664e+02 3.609875e-02 9.969903e-01 6.860940e-02 -3.596804e+01 5.572126e-01 3.691127e-02 -8.295491e-01 2.399696e+02 +-8.298500e-01 7.043931e-02 -5.535225e-01 3.668885e+02 3.668341e-02 9.967409e-01 7.184539e-02 -3.592190e+01 5.567794e-01 3.931580e-02 -8.297295e-01 2.392035e+02 +-8.306675e-01 7.206184e-02 -5.520857e-01 3.664143e+02 3.687522e-02 9.965321e-01 7.459153e-02 -3.586994e+01 5.555464e-01 4.160248e-02 -8.304442e-01 2.384237e+02 +-8.318616e-01 7.166643e-02 -5.503365e-01 3.659367e+02 3.680931e-02 9.965685e-01 7.413696e-02 -3.581599e+01 5.537611e-01 4.141418e-02 -8.316451e-01 2.376469e+02 +-8.334598e-01 7.065115e-02 -5.480448e-01 3.654608e+02 3.768556e-02 9.967510e-01 7.118437e-02 -3.575733e+01 5.512935e-01 3.867593e-02 -8.334145e-01 2.368689e+02 +-8.355040e-01 6.947226e-02 -5.450750e-01 3.649784e+02 3.836215e-02 9.969297e-01 6.826079e-02 -3.570831e+01 5.481437e-01 3.612191e-02 -8.356038e-01 2.360898e+02 +-8.376163e-01 6.993954e-02 -5.417632e-01 3.644993e+02 3.883560e-02 9.968846e-01 6.865055e-02 -3.566704e+01 5.448768e-01 3.646312e-02 -8.377230e-01 2.353035e+02 +-8.395327e-01 7.261099e-02 -5.384352e-01 3.640126e+02 3.925903e-02 9.965460e-01 7.317682e-02 -3.563064e+01 5.418889e-01 4.029589e-02 -8.394836e-01 2.345096e+02 +-8.413198e-01 7.597285e-02 -5.351720e-01 3.635106e+02 4.009419e-02 9.961171e-01 7.837823e-02 -3.557040e+01 5.390486e-01 4.448386e-02 -8.410992e-01 2.337106e+02 +-8.430815e-01 7.802109e-02 -5.320962e-01 3.630188e+02 4.174169e-02 9.959289e-01 7.989503e-02 -3.551340e+01 5.361635e-01 4.514742e-02 -8.429059e-01 2.329089e+02 +-8.449040e-01 7.672648e-02 -5.293867e-01 3.625299e+02 4.170507e-02 9.960957e-01 7.780732e-02 -3.545330e+01 5.332897e-01 4.366160e-02 -8.448052e-01 2.321039e+02 +-8.463127e-01 7.634243e-02 -5.271875e-01 3.620579e+02 4.310641e-02 9.962463e-01 7.506701e-02 -3.538795e+01 5.309394e-01 4.080500e-02 -8.464268e-01 2.312943e+02 +-8.477535e-01 7.579182e-02 -5.249472e-01 3.615956e+02 4.312929e-02 9.963105e-01 7.419643e-02 -3.532068e+01 5.286340e-01 4.025968e-02 -8.478946e-01 2.304723e+02 +-8.489295e-01 7.561153e-02 -5.230694e-01 3.611270e+02 4.274059e-02 9.962934e-01 7.465078e-02 -3.526153e+01 5.267750e-01 4.101695e-02 -8.490146e-01 2.296467e+02 +-8.495940e-01 7.583993e-02 -5.219562e-01 3.606392e+02 4.205705e-02 9.961982e-01 7.629033e-02 -3.519553e+01 5.257578e-01 4.286387e-02 -8.495537e-01 2.288224e+02 +-8.498627e-01 7.644298e-02 -5.214306e-01 3.601499e+02 4.142554e-02 9.960526e-01 7.850562e-02 -3.512662e+01 5.253736e-01 4.511845e-02 -8.496746e-01 2.279936e+02 +-8.494917e-01 7.295562e-02 -5.225336e-01 3.596610e+02 3.933712e-02 9.963949e-01 7.516467e-02 -3.506396e+01 5.261335e-01 4.329679e-02 -8.492991e-01 2.271652e+02 +-8.482590e-01 6.775064e-02 -5.252300e-01 3.591654e+02 3.697543e-02 9.969394e-01 6.888137e-02 -3.499557e+01 5.282892e-01 3.900864e-02 -8.481679e-01 2.263380e+02 +-8.466231e-01 6.416080e-02 -5.283112e-01 3.586646e+02 3.525012e-02 9.972867e-01 6.462701e-02 -3.494050e+01 5.310243e-01 3.609168e-02 -8.465876e-01 2.255072e+02 +-8.450253e-01 6.208398e-02 -5.311099e-01 3.581726e+02 3.191222e-02 9.973219e-01 6.580765e-02 -3.489342e+01 5.337732e-01 3.866023e-02 -8.447435e-01 2.246648e+02 +-8.429244e-01 6.196125e-02 -5.344522e-01 3.576744e+02 2.941718e-02 9.971683e-01 6.920983e-02 -3.484553e+01 5.372272e-01 4.261658e-02 -8.423603e-01 2.238188e+02 +-8.405238e-01 6.028738e-02 -5.384098e-01 3.571738e+02 2.791356e-02 9.972884e-01 6.809295e-02 -3.478898e+01 5.410550e-01 4.220481e-02 -8.399275e-01 2.229723e+02 +-8.380471e-01 5.846710e-02 -5.424561e-01 3.566670e+02 2.609097e-02 9.973987e-01 6.719358e-02 -3.473356e+01 5.449736e-01 4.215818e-02 -8.373926e-01 2.221245e+02 +-8.358852e-01 5.800860e-02 -5.458306e-01 3.561554e+02 2.403340e-02 9.973142e-01 6.918568e-02 -3.467577e+01 5.483780e-01 4.471312e-02 -8.350343e-01 2.212699e+02 +-8.334229e-01 6.081182e-02 -5.492797e-01 3.556267e+02 2.421819e-02 9.969913e-01 7.363258e-02 -3.462239e+01 5.521049e-01 4.806451e-02 -8.323882e-01 2.204145e+02 +-8.312395e-01 6.208522e-02 -5.524368e-01 3.550935e+02 2.483431e-02 9.968991e-01 7.466820e-02 -3.456073e+01 5.553596e-01 4.834776e-02 -8.302038e-01 2.195629e+02 +-8.293388e-01 6.286578e-02 -5.551982e-01 3.545450e+02 2.554709e-02 9.968775e-01 7.471623e-02 -3.449899e+01 5.581617e-01 4.778137e-02 -8.283553e-01 2.187077e+02 +-8.279379e-01 6.523675e-02 -5.570126e-01 3.539893e+02 2.737139e-02 9.967281e-01 7.605128e-02 -3.443756e+01 5.601515e-01 4.771952e-02 -8.270146e-01 2.178509e+02 +-8.269037e-01 6.892609e-02 -5.581035e-01 3.534241e+02 3.007796e-02 9.964603e-01 7.849900e-02 -3.437784e+01 5.615386e-01 4.812449e-02 -8.260499e-01 2.169944e+02 +-8.261725e-01 7.107393e-02 -5.589164e-01 3.528562e+02 3.132743e-02 9.962716e-01 8.038252e-02 -3.432203e+01 5.625457e-01 4.890041e-02 -8.253188e-01 2.161328e+02 +-8.254472e-01 7.247184e-02 -5.598077e-01 3.522863e+02 3.370513e-02 9.962825e-01 7.927836e-02 -3.425940e+01 5.634721e-01 4.657171e-02 -8.248214e-01 2.152690e+02 +-8.249663e-01 7.219735e-02 -5.605517e-01 3.517121e+02 3.538619e-02 9.964596e-01 7.626300e-02 -3.419993e+01 5.640731e-01 4.307861e-02 -8.246004e-01 2.144008e+02 +-8.248540e-01 7.032773e-02 -5.609545e-01 3.511372e+02 3.500861e-02 9.966822e-01 7.347731e-02 -3.414170e+01 5.642609e-01 4.096982e-02 -8.245794e-01 2.135260e+02 +-8.248531e-01 6.918600e-02 -5.610977e-01 3.505574e+02 3.515443e-02 9.968398e-01 7.123560e-02 -3.408980e+01 5.642531e-01 3.903383e-02 -8.246786e-01 2.126442e+02 +-8.251965e-01 6.838425e-02 -5.606909e-01 3.499756e+02 3.475112e-02 9.969103e-01 7.044253e-02 -3.403807e+01 5.637758e-01 3.864429e-02 -8.250234e-01 2.117576e+02 +-8.257176e-01 6.730484e-02 -5.600541e-01 3.493911e+02 3.382807e-02 9.969776e-01 6.993790e-02 -3.398601e+01 5.630685e-01 3.880340e-02 -8.254987e-01 2.108605e+02 +-8.264496e-01 6.569332e-02 -5.591649e-01 3.488054e+02 3.284151e-02 9.971032e-01 6.860441e-02 -3.393632e+01 5.620520e-01 3.833427e-02 -8.262131e-01 2.099591e+02 +-8.273080e-01 6.409191e-02 -5.580803e-01 3.482173e+02 3.261590e-02 9.972745e-01 6.618015e-02 -3.388874e+01 5.608009e-01 3.654907e-02 -8.271436e-01 2.090539e+02 +-8.282189e-01 6.360706e-02 -5.567832e-01 3.476260e+02 3.227623e-02 9.973027e-01 6.592105e-02 -3.384072e+01 5.594745e-01 3.662619e-02 -8.280380e-01 2.081406e+02 +-8.291291e-01 6.522822e-02 -5.552389e-01 3.470326e+02 3.255916e-02 9.971183e-01 6.851921e-02 -3.379495e+01 5.581083e-01 3.873315e-02 -8.288636e-01 2.072219e+02 +-8.301593e-01 6.513995e-02 -5.537078e-01 3.464401e+02 3.144882e-02 9.970409e-01 7.014474e-02 -3.374694e+01 5.566386e-01 4.081785e-02 -8.297514e-01 2.062958e+02 +-8.312394e-01 6.352195e-02 -5.522735e-01 3.458518e+02 3.081852e-02 9.971880e-01 6.830994e-02 -3.369701e+01 5.550598e-01 3.976166e-02 -8.308596e-01 2.053734e+02 +-8.325560e-01 6.163280e-02 -5.505015e-01 3.452739e+02 2.890590e-02 9.972708e-01 6.793593e-02 -3.365337e+01 5.531862e-01 4.064772e-02 -8.320654e-01 2.044408e+02 +-8.339207e-01 6.054922e-02 -5.485527e-01 3.447187e+02 2.644853e-02 9.972058e-01 6.986398e-02 -3.361644e+01 5.512502e-01 4.375260e-02 -8.331920e-01 2.034914e+02 +-8.350688e-01 6.200412e-02 -5.466403e-01 3.441610e+02 2.567296e-02 9.969380e-01 7.386136e-02 -3.356960e+01 5.495463e-01 4.764543e-02 -8.341036e-01 2.025504e+02 +-8.363609e-01 6.411467e-02 -5.444169e-01 3.436104e+02 2.555163e-02 9.966168e-01 7.811549e-02 -3.350624e+01 5.475834e-01 5.142200e-02 -8.351696e-01 2.016057e+02 +-8.375226e-01 6.551445e-02 -5.424609e-01 3.430489e+02 2.602606e-02 9.964421e-01 8.016056e-02 -3.344600e+01 5.457826e-01 5.301816e-02 -8.362479e-01 2.006683e+02 +-8.381014e-01 6.794176e-02 -5.412670e-01 3.424789e+02 2.938669e-02 9.963961e-01 7.956868e-02 -3.337868e+01 5.447224e-01 5.078058e-02 -8.370776e-01 1.997365e+02 +-8.385037e-01 6.896475e-02 -5.405141e-01 3.419018e+02 3.185882e-02 9.964662e-01 7.771736e-02 -3.331753e+01 5.439638e-01 4.794615e-02 -8.377378e-01 1.988073e+02 +-8.390421e-01 6.929636e-02 -5.396354e-01 3.413245e+02 3.481339e-02 9.966611e-01 7.385563e-02 -3.325507e+01 5.429515e-01 4.318144e-02 -8.386531e-01 1.978812e+02 +-8.399265e-01 6.925474e-02 -5.382632e-01 3.407398e+02 3.660032e-02 9.967947e-01 7.113844e-02 -3.319508e+01 5.414646e-01 4.005045e-02 -8.397691e-01 1.969549e+02 +-8.408959e-01 6.862525e-02 -5.368284e-01 3.401541e+02 3.569893e-02 9.968011e-01 7.150640e-02 -3.313797e+01 5.400183e-01 4.096523e-02 -8.406558e-01 1.960256e+02 +-8.415433e-01 6.891705e-02 -5.357755e-01 3.395685e+02 3.574113e-02 9.967586e-01 7.207492e-02 -3.308719e+01 5.390061e-01 4.150493e-02 -8.412787e-01 1.950944e+02 +-8.423164e-01 6.628003e-02 -5.348925e-01 3.389917e+02 3.374318e-02 9.969481e-01 7.039795e-02 -3.303588e+01 5.379261e-01 4.124837e-02 -8.419822e-01 1.941626e+02 +-8.429531e-01 6.342308e-02 -5.342355e-01 3.384232e+02 3.120177e-02 9.971187e-01 6.914315e-02 -3.298181e+01 5.370815e-01 4.161534e-02 -8.425032e-01 1.932266e+02 +-8.436220e-01 6.337550e-02 -5.331844e-01 3.378525e+02 3.117533e-02 9.971160e-01 6.919288e-02 -3.292097e+01 5.360318e-01 4.175043e-02 -8.431648e-01 1.922866e+02 +-8.445607e-01 6.497858e-02 -5.315026e-01 3.373010e+02 3.188653e-02 9.969512e-01 7.121393e-02 -3.286694e+01 5.345096e-01 4.319671e-02 -8.440578e-01 1.913474e+02 +-8.454976e-01 6.514250e-02 -5.299908e-01 3.367460e+02 3.254772e-02 9.969723e-01 7.061685e-02 -3.281695e+01 5.329864e-01 4.245638e-02 -8.450580e-01 1.904078e+02 +-8.464762e-01 6.548588e-02 -5.283840e-01 3.361946e+02 3.350644e-02 9.969921e-01 6.988577e-02 -3.276464e+01 5.313712e-01 4.145237e-02 -8.461243e-01 1.894670e+02 +-8.474812e-01 6.649010e-02 -5.266448e-01 3.356392e+02 3.371549e-02 9.968633e-01 7.160105e-02 -3.271139e+01 5.297537e-01 4.292445e-02 -8.470647e-01 1.885204e+02 +-8.483816e-01 6.809171e-02 -5.249877e-01 3.350717e+02 3.394655e-02 9.966498e-01 7.440933e-02 -3.265859e+01 5.282956e-01 4.530598e-02 -8.478509e-01 1.875825e+02 +-8.493456e-01 6.861187e-02 -5.233588e-01 3.345051e+02 3.426202e-02 9.965910e-01 7.504927e-02 -3.261185e+01 5.267240e-01 4.581143e-02 -8.488010e-01 1.866436e+02 +-8.500880e-01 6.933251e-02 -5.220568e-01 3.339381e+02 3.596235e-02 9.966245e-01 7.379912e-02 -3.256481e+01 5.254113e-01 4.396136e-02 -8.497119e-01 1.857051e+02 +-8.507713e-01 7.046215e-02 -5.207909e-01 3.333746e+02 3.704913e-02 9.965469e-01 7.430721e-02 -3.251682e+01 5.242285e-01 4.392359e-02 -8.504441e-01 1.847614e+02 +-8.514372e-01 7.135958e-02 -5.195791e-01 3.328102e+02 3.729869e-02 9.964305e-01 7.572935e-02 -3.246501e+01 5.231286e-01 4.509916e-02 -8.510597e-01 1.838134e+02 +-8.520183e-01 7.254516e-02 -5.184612e-01 3.322503e+02 3.860839e-02 9.963625e-01 7.596760e-02 -3.241630e+01 5.220865e-01 4.470883e-02 -8.517200e-01 1.828670e+02 +-8.525722e-01 7.241019e-02 -5.175688e-01 3.316925e+02 3.939489e-02 9.964416e-01 7.451290e-02 -3.237124e+01 5.211226e-01 4.313806e-02 -8.523910e-01 1.819214e+02 +-8.528464e-01 7.137906e-02 -5.172602e-01 3.311364e+02 3.907744e-02 9.965595e-01 7.308982e-02 -3.232759e+01 5.206976e-01 4.212118e-02 -8.527015e-01 1.809752e+02 +-8.530975e-01 7.022389e-02 -5.170041e-01 3.305853e+02 3.830180e-02 9.966564e-01 7.217340e-02 -3.228356e+01 5.203437e-01 4.176875e-02 -8.529348e-01 1.800317e+02 +-8.532417e-01 7.004301e-02 -5.167907e-01 3.300341e+02 3.834553e-02 9.966835e-01 7.177513e-02 -3.223656e+01 5.201041e-01 4.142492e-02 -8.530977e-01 1.790876e+02 +-8.533492e-01 7.088897e-02 -5.164976e-01 3.294907e+02 3.832423e-02 9.965616e-01 7.345879e-02 -3.219052e+01 5.199292e-01 4.289162e-02 -8.531319e-01 1.781487e+02 +-8.534274e-01 7.096450e-02 -5.163581e-01 3.289546e+02 3.816525e-02 9.965367e-01 7.387796e-02 -3.214402e+01 5.198125e-01 4.334254e-02 -8.531802e-01 1.772268e+02 +-8.536648e-01 7.004627e-02 -5.160910e-01 3.284314e+02 3.739383e-02 9.966005e-01 7.341025e-02 -3.210040e+01 5.194787e-01 4.336912e-02 -8.533821e-01 1.763150e+02 +-8.540318e-01 6.883894e-02 -5.156461e-01 3.279329e+02 3.657053e-02 9.966984e-01 7.249020e-02 -3.205625e+01 5.189339e-01 4.305148e-02 -8.537296e-01 1.754202e+02 +-8.543160e-01 6.734657e-02 -5.153722e-01 3.274377e+02 3.533764e-02 9.968015e-01 7.167958e-02 -3.201622e+01 5.185512e-01 4.302497e-02 -8.539634e-01 1.745388e+02 +-8.548405e-01 6.548813e-02 -5.147416e-01 3.269493e+02 3.313394e-02 9.968685e-01 7.180075e-02 -3.198000e+01 5.178318e-01 4.432277e-02 -8.543335e-01 1.736739e+02 +-8.552836e-01 6.581708e-02 -5.139631e-01 3.264715e+02 3.229689e-02 9.967428e-01 7.389582e-02 -3.194484e+01 5.171527e-01 4.660247e-02 -8.546235e-01 1.728332e+02 +-8.557515e-01 6.637938e-02 -5.131112e-01 3.260048e+02 3.100768e-02 9.965330e-01 7.720431e-02 -3.190580e+01 5.164571e-01 5.015731e-02 -8.548429e-01 1.720118e+02 +-8.558504e-01 6.870048e-02 -5.126406e-01 3.255461e+02 3.117820e-02 9.961896e-01 8.145055e-02 -3.185963e+01 5.162829e-01 5.372627e-02 -8.547312e-01 1.712185e+02 +-8.559771e-01 7.131657e-02 -5.120714e-01 3.250953e+02 3.230321e-02 9.958828e-01 8.469942e-02 -3.181148e+01 5.160036e-01 5.595921e-02 -8.547566e-01 1.704450e+02 +-8.558823e-01 7.095984e-02 -5.122794e-01 3.246506e+02 3.182714e-02 9.958917e-01 8.477417e-02 -3.176050e+01 5.161904e-01 5.625232e-02 -8.546246e-01 1.696921e+02 +-8.547655e-01 6.841878e-02 -5.144850e-01 3.242095e+02 2.994015e-02 9.961224e-01 8.272678e-02 -3.171102e+01 5.181502e-01 5.530823e-02 -8.534995e-01 1.689465e+02 +-8.526736e-01 6.754312e-02 -5.180596e-01 3.237622e+02 3.004412e-02 9.963060e-01 8.044600e-02 -3.165965e+01 5.215795e-01 5.302953e-02 -8.515531e-01 1.682061e+02 +-8.500958e-01 6.772112e-02 -5.222557e-01 3.233151e+02 3.010117e-02 9.963244e-01 8.019701e-02 -3.160932e+01 5.257671e-01 5.245463e-02 -8.490097e-01 1.674669e+02 +-8.471059e-01 6.804172e-02 -5.270502e-01 3.228667e+02 2.995893e-02 9.963066e-01 8.047061e-02 -3.155627e+01 5.305790e-01 5.237727e-02 -8.460157e-01 1.667298e+02 +-8.441249e-01 6.855462e-02 -5.317456e-01 3.224124e+02 3.040041e-02 9.963159e-01 8.018934e-02 -3.150703e+01 5.352841e-01 5.152453e-02 -8.430992e-01 1.659969e+02 +-8.417621e-01 6.951414e-02 -5.353545e-01 3.219491e+02 3.197331e-02 9.963537e-01 7.910043e-02 -3.144759e+01 5.389011e-01 4.946668e-02 -8.409154e-01 1.652723e+02 +-8.403657e-01 7.086859e-02 -5.373668e-01 3.214853e+02 3.389362e-02 9.963461e-01 7.839454e-02 -3.139086e+01 5.409591e-01 4.766677e-02 -8.396971e-01 1.645520e+02 +-8.401136e-01 7.225154e-02 -5.375768e-01 3.210111e+02 3.575856e-02 9.963100e-01 7.802363e-02 -3.132764e+01 5.412305e-01 4.632574e-02 -8.395972e-01 1.638354e+02 +-8.408821e-01 7.332851e-02 -5.362278e-01 3.205472e+02 3.816703e-02 9.963466e-01 7.639788e-02 -3.127438e+01 5.398709e-01 4.377538e-02 -8.406088e-01 1.631173e+02 +-8.427355e-01 7.168330e-02 -5.335339e-01 3.200884e+02 3.849723e-02 9.965821e-01 7.308877e-02 -3.122217e+01 5.369496e-01 4.105492e-02 -8.426148e-01 1.624003e+02 +-8.451128e-01 6.916794e-02 -5.300944e-01 3.196418e+02 3.811425e-02 9.968668e-01 6.930918e-02 -3.117586e+01 5.332276e-01 3.836992e-02 -8.451013e-01 1.616786e+02 +-8.473958e-01 6.794025e-02 -5.265970e-01 3.191939e+02 3.851596e-02 9.970324e-01 6.665512e-02 -3.112977e+01 5.295629e-01 3.620088e-02 -8.474979e-01 1.609493e+02 +-8.493765e-01 6.758513e-02 -5.234422e-01 3.187414e+02 3.861147e-02 9.970667e-01 6.608415e-02 -3.108120e+01 5.263731e-01 3.591945e-02 -8.494946e-01 1.602155e+02 +-8.509841e-01 6.646917e-02 -5.209682e-01 3.182955e+02 3.671883e-02 9.970613e-01 6.723388e-02 -3.103757e+01 5.239063e-01 3.808562e-02 -8.509240e-01 1.594724e+02 +-8.522672e-01 6.516676e-02 -5.190317e-01 3.178481e+02 3.530984e-02 9.971137e-01 6.721221e-02 -3.099209e+01 5.219137e-01 3.895583e-02 -8.521083e-01 1.587281e+02 +-8.530100e-01 6.598201e-02 -5.177068e-01 3.174001e+02 3.607219e-02 9.970574e-01 6.764047e-02 -3.095117e+01 5.206465e-01 3.902318e-02 -8.528801e-01 1.579795e+02 +-8.529727e-01 6.518382e-02 -5.178694e-01 3.169518e+02 3.469365e-02 9.970576e-01 6.835567e-02 -3.090799e+01 5.208013e-01 4.033874e-02 -8.527244e-01 1.572293e+02 +-8.520298e-01 6.399165e-02 -5.195674e-01 3.165055e+02 3.288727e-02 9.970832e-01 6.887284e-02 -3.086600e+01 5.224593e-01 4.159456e-02 -8.516491e-01 1.564727e+02 +-8.506742e-01 6.273722e-02 -5.219363e-01 3.160514e+02 3.132077e-02 9.971380e-01 6.880901e-02 -3.082277e+01 5.247594e-01 4.218660e-02 -8.502046e-01 1.557181e+02 +-8.491805e-01 6.181181e-02 -5.244729e-01 3.155888e+02 3.078256e-02 9.972315e-01 6.768845e-02 -3.078326e+01 5.272049e-01 4.133508e-02 -8.487322e-01 1.549611e+02 +-8.480510e-01 6.184675e-02 -5.262932e-01 3.151095e+02 3.164888e-02 9.973043e-01 6.619920e-02 -3.074058e+01 5.289688e-01 3.948370e-02 -8.477223e-01 1.542104e+02 +-8.473177e-01 6.363251e-02 -5.272606e-01 3.146244e+02 3.404373e-02 9.972621e-01 6.564584e-02 -3.069211e+01 5.299942e-01 3.767296e-02 -8.471641e-01 1.534546e+02 +-8.467259e-01 6.394317e-02 -5.281728e-01 3.141356e+02 3.348432e-02 9.971879e-01 6.704499e-02 -3.064189e+01 5.309746e-01 3.908322e-02 -8.464860e-01 1.526928e+02 +-8.458008e-01 6.555164e-02 -5.294564e-01 3.136473e+02 3.453482e-02 9.970684e-01 6.827742e-02 -3.059555e+01 5.323800e-01 3.946441e-02 -8.455851e-01 1.519226e+02 +-8.451494e-01 6.672097e-02 -5.303497e-01 3.131420e+02 3.567894e-02 9.970079e-01 6.857234e-02 -3.054233e+01 5.333381e-01 3.903156e-02 -8.450012e-01 1.511581e+02 +-8.448198e-01 6.703302e-02 -5.308353e-01 3.126319e+02 3.623090e-02 9.970108e-01 6.823979e-02 -3.048983e+01 5.338229e-01 3.841768e-02 -8.447232e-01 1.503873e+02 +-8.450178e-01 6.660140e-02 -5.305744e-01 3.121425e+02 3.619729e-02 9.970618e-01 6.750869e-02 -3.043766e+01 5.335117e-01 3.784069e-02 -8.449458e-01 1.496013e+02 +-8.455026e-01 6.597140e-02 -5.298802e-01 3.116501e+02 3.575558e-02 9.971061e-01 6.708888e-02 -3.038431e+01 5.327728e-01 3.777765e-02 -8.454147e-01 1.488106e+02 +-8.459821e-01 6.598056e-02 -5.291133e-01 3.111485e+02 3.570450e-02 9.970970e-01 6.725151e-02 -3.033270e+01 5.320146e-01 3.800185e-02 -8.458820e-01 1.480121e+02 +-8.463489e-01 6.622936e-02 -5.284953e-01 3.106367e+02 3.547365e-02 9.970450e-01 6.813796e-02 -3.027855e+01 5.314464e-01 3.892082e-02 -8.461973e-01 1.472093e+02 +-8.465210e-01 6.662421e-02 -5.281699e-01 3.101292e+02 3.520396e-02 9.969719e-01 6.933677e-02 -3.022886e+01 5.311901e-01 4.010135e-02 -8.463031e-01 1.463985e+02 +-8.464312e-01 6.685746e-02 -5.282843e-01 3.096129e+02 3.408793e-02 9.968550e-01 7.154126e-02 -3.017283e+01 5.314059e-01 4.254664e-02 -8.460482e-01 1.455802e+02 +-8.458336e-01 6.779160e-02 -5.291217e-01 3.090961e+02 3.431054e-02 9.967520e-01 7.285738e-02 -3.012100e+01 5.323423e-01 4.347077e-02 -8.454123e-01 1.447575e+02 +-8.454251e-01 6.753100e-02 -5.298075e-01 3.085621e+02 3.437256e-02 9.967973e-01 7.220607e-02 -3.006145e+01 5.329868e-01 4.283398e-02 -8.450387e-01 1.439369e+02 +-8.444800e-01 6.710072e-02 -5.313671e-01 3.080167e+02 3.416619e-02 9.968493e-01 7.158263e-02 -3.000226e+01 5.344962e-01 4.229531e-02 -8.441119e-01 1.431091e+02 +-8.428349e-01 6.639917e-02 -5.340604e-01 3.074604e+02 3.268924e-02 9.968436e-01 7.234759e-02 -2.994259e+01 5.371785e-01 4.351904e-02 -8.423451e-01 1.422763e+02 +-8.405826e-01 6.674782e-02 -5.375553e-01 3.069001e+02 3.233591e-02 9.967924e-01 7.320687e-02 -2.988660e+01 5.407175e-01 4.415407e-02 -8.400447e-01 1.414380e+02 +-8.386185e-01 6.751364e-02 -5.405191e-01 3.063311e+02 3.274944e-02 9.967435e-01 7.368753e-02 -2.982556e+01 5.437339e-01 4.409402e-02 -8.380986e-01 1.405982e+02 +-8.368829e-01 6.915685e-02 -5.429957e-01 3.057365e+02 3.421799e-02 9.966563e-01 7.419798e-02 -2.975178e+01 5.463114e-01 4.351479e-02 -8.364510e-01 1.397643e+02 +-8.355301e-01 7.054051e-02 -5.448977e-01 3.051464e+02 3.538395e-02 9.965738e-01 7.475622e-02 -2.968223e+01 5.483042e-01 4.318044e-02 -8.351634e-01 1.389214e+02 +-8.345989e-01 7.151696e-02 -5.461959e-01 3.045644e+02 3.651039e-02 9.965378e-01 7.469453e-02 -2.960531e+01 5.496469e-01 4.239814e-02 -8.343205e-01 1.380760e+02 +-8.341006e-01 7.203644e-02 -5.468885e-01 3.039847e+02 3.689690e-02 9.965018e-01 7.498555e-02 -2.953447e+01 5.503771e-01 4.236699e-02 -8.338406e-01 1.372207e+02 +-8.335265e-01 7.339387e-02 -5.475829e-01 3.033903e+02 3.801786e-02 9.964071e-01 7.568043e-02 -2.946861e+01 5.511700e-01 4.226371e-02 -8.333220e-01 1.363680e+02 +-8.331828e-01 7.458868e-02 -5.479444e-01 3.027974e+02 3.926417e-02 9.963403e-01 7.592285e-02 -2.941285e+01 5.516021e-01 4.174303e-02 -8.330622e-01 1.355089e+02 +-8.332125e-01 7.613907e-02 -5.476859e-01 3.021954e+02 4.077923e-02 9.962385e-01 7.645793e-02 -2.935424e+01 5.514473e-01 4.137149e-02 -8.331833e-01 1.346483e+02 +-8.336077e-01 7.715593e-02 -5.469416e-01 3.016000e+02 4.156195e-02 9.961505e-01 7.717932e-02 -2.929273e+01 5.507911e-01 4.160532e-02 -8.336056e-01 1.337734e+02 +-8.339170e-01 7.786779e-02 -5.463690e-01 3.009970e+02 4.223630e-02 9.960975e-01 7.749775e-02 -2.921731e+01 5.502714e-01 4.155008e-02 -8.339515e-01 1.328936e+02 +-8.341930e-01 7.722151e-02 -5.460392e-01 3.004045e+02 4.181833e-02 9.961544e-01 7.699083e-02 -2.913219e+01 5.498848e-01 4.139076e-02 -8.342143e-01 1.320020e+02 +-8.345008e-01 7.652582e-02 -5.456668e-01 2.998131e+02 4.180596e-02 9.962476e-01 7.578174e-02 -2.905195e+01 5.494186e-01 4.042779e-02 -8.345687e-01 1.311119e+02 +-8.348191e-01 7.615763e-02 -5.452312e-01 2.992228e+02 4.254176e-02 9.963480e-01 7.403254e-02 -2.898385e+01 5.488782e-01 3.860868e-02 -8.350102e-01 1.302186e+02 +-8.353063e-01 7.581511e-02 -5.445324e-01 2.986306e+02 4.295217e-02 9.964181e-01 7.284295e-02 -2.891480e+01 5.481045e-01 3.745732e-02 -8.355707e-01 1.293192e+02 +-8.357606e-01 7.635278e-02 -5.437595e-01 2.980344e+02 4.417963e-02 9.964249e-01 7.201021e-02 -2.885081e+01 5.473138e-01 3.616020e-02 -8.361460e-01 1.284112e+02 +-8.364949e-01 7.575146e-02 -5.427136e-01 2.974371e+02 4.398961e-02 9.964854e-01 7.128651e-02 -2.878976e+01 5.462063e-01 3.575704e-02 -8.368872e-01 1.274963e+02 +-8.371712e-01 7.550294e-02 -5.417044e-01 2.968378e+02 4.482329e-02 9.965653e-01 6.962998e-02 -2.872928e+01 5.451012e-01 3.401124e-02 -8.376801e-01 1.265783e+02 +-8.380730e-01 7.365010e-02 -5.405639e-01 2.962450e+02 4.403097e-02 9.967445e-01 6.753909e-02 -2.868223e+01 5.437785e-01 3.280113e-02 -8.385876e-01 1.256531e+02 +-8.389003e-01 7.144779e-02 -5.395753e-01 2.956555e+02 4.292441e-02 9.969437e-01 6.527383e-02 -2.863924e+01 5.425899e-01 3.159729e-02 -8.394033e-01 1.247255e+02 +-8.397715e-01 6.961389e-02 -5.384587e-01 2.950583e+02 4.198101e-02 9.971025e-01 6.343616e-02 -2.859222e+01 5.413146e-01 3.066683e-02 -8.402607e-01 1.237930e+02 +-8.406968e-01 6.752075e-02 -5.372801e-01 2.944783e+02 4.063393e-02 9.972644e-01 6.174665e-02 -2.855074e+01 5.399795e-01 3.007841e-02 -8.411406e-01 1.228529e+02 +-8.415470e-01 6.610978e-02 -5.361233e-01 2.938870e+02 3.964260e-02 9.973649e-01 6.075932e-02 -2.850928e+01 5.387274e-01 2.987849e-02 -8.419502e-01 1.219049e+02 +-8.423056e-01 6.702597e-02 -5.348165e-01 2.932971e+02 3.970350e-02 9.972580e-01 6.245079e-02 -2.846688e+01 5.375359e-01 3.136857e-02 -8.426572e-01 1.209543e+02 +-8.429420e-01 6.940261e-02 -5.335093e-01 2.926994e+02 3.939980e-02 9.969452e-01 6.743814e-02 -2.841294e+01 5.365599e-01 3.582627e-02 -8.431014e-01 1.199876e+02 +-8.433172e-01 7.192108e-02 -5.325820e-01 2.921067e+02 3.856647e-02 9.965486e-01 7.350815e-02 -2.833343e+01 5.360306e-01 4.145087e-02 -8.431803e-01 1.190149e+02 +-8.435791e-01 7.255110e-02 -5.320814e-01 2.915008e+02 3.877463e-02 9.964745e-01 7.439815e-02 -2.825374e+01 5.356033e-01 4.212946e-02 -8.434182e-01 1.180440e+02 +-8.438781e-01 7.156840e-02 -5.317402e-01 2.908898e+02 3.816208e-02 9.965599e-01 7.356614e-02 -2.818934e+01 5.351760e-01 4.178854e-02 -8.437063e-01 1.170743e+02 +-8.442575e-01 7.120713e-02 -5.311863e-01 2.902856e+02 3.698050e-02 9.965119e-01 7.480936e-02 -2.812565e+01 5.346605e-01 4.351482e-02 -8.439459e-01 1.160968e+02 +-8.446081e-01 7.242390e-02 -5.304639e-01 2.896930e+02 3.654010e-02 9.962957e-01 7.784428e-02 -2.806075e+01 5.341367e-01 4.636471e-02 -8.441258e-01 1.151049e+02 +-8.447802e-01 7.399826e-02 -5.299723e-01 2.890931e+02 3.693773e-02 9.960939e-01 8.020226e-02 -2.800034e+01 5.338370e-01 4.817730e-02 -8.442138e-01 1.141174e+02 +-8.447599e-01 7.568203e-02 -5.297669e-01 2.884862e+02 3.821164e-02 9.959529e-01 8.134916e-02 -2.794099e+01 5.337796e-01 4.847723e-02 -8.442330e-01 1.131347e+02 +-8.445984e-01 7.550417e-02 -5.300497e-01 2.878786e+02 3.833552e-02 9.959935e-01 8.079162e-02 -2.788299e+01 5.340262e-01 4.791674e-02 -8.441090e-01 1.121539e+02 +-8.443749e-01 7.405502e-02 -5.306100e-01 2.872788e+02 3.840748e-02 9.962196e-01 7.791932e-02 -2.783310e+01 5.343744e-01 4.541372e-02 -8.440270e-01 1.111794e+02 +-8.441965e-01 7.107666e-02 -5.313007e-01 2.866860e+02 3.739929e-02 9.965645e-01 7.389440e-02 -2.779225e+01 5.347276e-01 4.251112e-02 -8.439545e-01 1.102048e+02 +-8.438634e-01 6.880679e-02 -5.321279e-01 2.860863e+02 3.642957e-02 9.968022e-01 7.112049e-02 -2.774595e+01 5.353199e-01 4.063079e-02 -8.436716e-01 1.092275e+02 +-8.435970e-01 6.836145e-02 -5.326075e-01 2.854964e+02 3.585913e-02 9.968210e-01 7.114713e-02 -2.769957e+01 5.357781e-01 4.092066e-02 -8.433667e-01 1.082470e+02 +-8.432077e-01 6.961608e-02 -5.330613e-01 2.848937e+02 3.624383e-02 9.966854e-01 7.283265e-02 -2.765117e+01 5.363648e-01 4.209286e-02 -8.429360e-01 1.072690e+02 +-8.428656e-01 6.982968e-02 -5.335742e-01 2.843028e+02 3.671671e-02 9.966967e-01 7.243939e-02 -2.760562e+01 5.368701e-01 4.146557e-02 -8.426453e-01 1.062956e+02 +-8.424446e-01 6.889578e-02 -5.343598e-01 2.837123e+02 3.690604e-02 9.968401e-01 7.033988e-02 -2.755441e+01 5.375174e-01 3.953635e-02 -8.423253e-01 1.053210e+02 +-8.421758e-01 6.748777e-02 -5.349629e-01 2.831261e+02 3.655646e-02 9.969999e-01 6.822595e-02 -2.750445e+01 5.379624e-01 3.790189e-02 -8.421163e-01 1.043501e+02 +-8.420859e-01 6.708252e-02 -5.351554e-01 2.825335e+02 3.600282e-02 9.970132e-01 6.832542e-02 -2.745645e+01 5.381405e-01 3.826877e-02 -8.419860e-01 1.033823e+02 +-8.421835e-01 6.748404e-02 -5.349513e-01 2.819413e+02 3.571437e-02 9.969398e-01 6.953809e-02 -2.740908e+01 5.380070e-01 3.945838e-02 -8.420164e-01 1.024185e+02 +-8.424145e-01 6.836909e-02 -5.344750e-01 2.813551e+02 3.566759e-02 9.968174e-01 7.129356e-02 -2.736254e+01 5.376483e-01 4.099529e-02 -8.421720e-01 1.014545e+02 +-8.426668e-01 6.954501e-02 -5.339253e-01 2.807642e+02 3.657948e-02 9.967268e-01 7.209452e-02 -2.731453e+01 5.371915e-01 4.122094e-02 -8.424525e-01 1.004955e+02 +-8.429786e-01 6.960429e-02 -5.334250e-01 2.801799e+02 3.678513e-02 9.967313e-01 7.192711e-02 -2.726628e+01 5.366879e-01 4.101090e-02 -8.427836e-01 9.954283e+01 +-8.432405e-01 6.888244e-02 -5.331047e-01 2.795941e+02 3.669703e-02 9.968186e-01 7.075325e-02 -2.721867e+01 5.362824e-01 4.009864e-02 -8.430856e-01 9.859369e+01 +-8.434293e-01 6.758093e-02 -5.329727e-01 2.790147e+02 3.667944e-02 9.969853e-01 6.837256e-02 -2.717260e+01 5.359867e-01 3.811827e-02 -8.433655e-01 9.765146e+01 +-8.435195e-01 6.728409e-02 -5.328675e-01 2.784316e+02 3.689017e-02 9.970372e-01 6.749743e-02 -2.711967e+01 5.358302e-01 3.727782e-02 -8.435024e-01 9.671469e+01 +-8.435807e-01 6.797593e-02 -5.326827e-01 2.778537e+02 3.694559e-02 9.969521e-01 6.871292e-02 -2.706629e+01 5.357301e-01 3.828461e-02 -8.435210e-01 9.578233e+01 +-8.435801e-01 6.910691e-02 -5.325382e-01 2.772738e+02 3.735755e-02 9.968345e-01 7.018104e-02 -2.701639e+01 5.357025e-01 3.930900e-02 -8.434914e-01 9.485325e+01 +-8.433028e-01 6.970394e-02 -5.328995e-01 2.766970e+02 3.786312e-02 9.967954e-01 7.046454e-02 -2.696503e+01 5.361034e-01 3.924570e-02 -8.432395e-01 9.393036e+01 +-8.429302e-01 6.866478e-02 -5.336233e-01 2.761233e+02 3.706110e-02 9.968771e-01 6.973169e-02 -2.691312e+01 5.367450e-01 3.900228e-02 -8.428426e-01 9.301509e+01 +-8.425546e-01 6.783891e-02 -5.343216e-01 2.755484e+02 3.673242e-02 9.969640e-01 6.865509e-02 -2.685392e+01 5.373569e-01 3.821873e-02 -8.424885e-01 9.210492e+01 +-8.422169e-01 6.603783e-02 -5.350792e-01 2.749779e+02 3.456722e-02 9.970422e-01 6.864297e-02 -2.679927e+01 5.380296e-01 3.931606e-02 -8.420086e-01 9.119859e+01 +-8.415952e-01 6.609256e-02 -5.360497e-01 2.744071e+02 3.312819e-02 9.969327e-01 7.090635e-02 -2.674595e+01 5.390918e-01 4.191609e-02 -8.412033e-01 9.029459e+01 +-8.409169e-01 6.709193e-02 -5.369893e-01 2.738361e+02 3.310622e-02 9.968044e-01 7.269786e-02 -2.668951e+01 5.401508e-01 4.335517e-02 -8.404508e-01 8.939663e+01 +-8.398419e-01 6.813075e-02 -5.385386e-01 2.732648e+02 3.272399e-02 9.966424e-01 7.505320e-02 -2.663099e+01 5.418439e-01 4.540969e-02 -8.392516e-01 8.850397e+01 +-8.388766e-01 6.902147e-02 -5.399279e-01 2.726929e+02 3.246574e-02 9.965065e-01 7.694660e-02 -2.656353e+01 5.433526e-01 4.701953e-02 -8.381868e-01 8.762063e+01 +-8.381519e-01 6.857075e-02 -5.411095e-01 2.721245e+02 3.150455e-02 9.964960e-01 7.747951e-02 -2.650298e+01 5.445264e-01 4.789218e-02 -8.373753e-01 8.674035e+01 +-8.371860e-01 6.919373e-02 -5.425236e-01 2.715545e+02 3.206214e-02 9.964678e-01 7.761389e-02 -2.643851e+01 5.459777e-01 4.758279e-02 -8.364474e-01 8.586529e+01 +-8.364765e-01 6.975350e-02 -5.435453e-01 2.709861e+02 3.217398e-02 9.964061e-01 7.835603e-02 -2.637794e+01 5.470575e-01 4.805496e-02 -8.357145e-01 8.499076e+01 +-8.358096e-01 7.177148e-02 -5.443079e-01 2.704198e+02 3.236607e-02 9.961354e-01 8.164911e-02 -2.630758e+01 5.480646e-01 5.062600e-02 -8.349026e-01 8.412584e+01 +-8.355162e-01 7.450911e-02 -5.443905e-01 2.698597e+02 3.373046e-02 9.958498e-01 8.453043e-02 -2.623417e+01 5.484295e-01 5.226400e-02 -8.345619e-01 8.325387e+01 +-8.357799e-01 7.467919e-02 -5.439624e-01 2.693251e+02 3.451418e-02 9.958936e-01 8.369383e-02 -2.615430e+01 5.479789e-01 5.117519e-02 -8.349253e-01 8.237064e+01 +-8.363898e-01 7.326415e-02 -5.432167e-01 2.687882e+02 3.462525e-02 9.961097e-01 8.103386e-02 -2.608247e+01 5.470404e-01 4.896688e-02 -8.356728e-01 8.149653e+01 +-8.371691e-01 7.149523e-02 -5.422511e-01 2.682571e+02 3.419751e-02 9.963221e-01 7.856728e-02 -2.601252e+01 5.458740e-01 4.723046e-02 -8.365351e-01 8.062329e+01 +-8.378315e-01 7.086878e-02 -5.413094e-01 2.677215e+02 3.394927e-02 9.963829e-01 7.790127e-02 -2.594002e+01 5.448723e-01 4.689108e-02 -8.372070e-01 7.976136e+01 +-8.386051e-01 7.075845e-02 -5.401248e-01 2.671861e+02 3.305049e-02 9.963102e-01 7.920592e-02 -2.587097e+01 5.437364e-01 4.857109e-02 -8.378494e-01 7.889745e+01 +-8.392883e-01 7.034239e-02 -5.391169e-01 2.666562e+02 3.286103e-02 9.963453e-01 7.884274e-02 -2.580364e+01 5.426926e-01 4.845585e-02 -8.385325e-01 7.803953e+01 +-8.399923e-01 7.026813e-02 -5.380292e-01 2.661250e+02 3.393610e-02 9.964413e-01 7.715573e-02 -2.574104e+01 5.415361e-01 4.655160e-02 -8.393876e-01 7.718776e+01 +-8.405958e-01 7.168287e-02 -5.368987e-01 2.655960e+02 3.582348e-02 9.963916e-01 7.694406e-02 -2.567560e+01 5.404770e-01 4.544527e-02 -8.401306e-01 7.633591e+01 +-8.411443e-01 7.368558e-02 -5.357674e-01 2.650665e+02 3.665199e-02 9.961638e-01 7.946230e-02 -2.561155e+01 5.395674e-01 4.720230e-02 -8.406182e-01 7.549025e+01 +-8.417381e-01 7.505469e-02 -5.346436e-01 2.645427e+02 3.727594e-02 9.960058e-01 8.113507e-02 -2.554047e+01 5.385977e-01 4.836513e-02 -8.411738e-01 7.465006e+01 +-8.422910e-01 7.538582e-02 -5.337255e-01 2.640185e+02 3.750547e-02 9.959685e-01 8.148648e-02 -2.547630e+01 5.377167e-01 4.861770e-02 -8.417227e-01 7.380980e+01 +-8.424874e-01 7.510324e-02 -5.334553e-01 2.635007e+02 3.797656e-02 9.960507e-01 8.025394e-02 -2.540966e+01 5.373759e-01 4.735413e-02 -8.420123e-01 7.297624e+01 +-8.426669e-01 7.365719e-02 -5.333734e-01 2.629856e+02 3.727119e-02 9.962023e-01 7.868838e-02 -2.534975e+01 5.371438e-01 4.642863e-02 -8.422120e-01 7.214608e+01 +-8.430045e-01 7.216175e-02 -5.330442e-01 2.624695e+02 3.639212e-02 9.963413e-01 7.732762e-02 -2.527954e+01 5.366741e-01 4.578892e-02 -8.425463e-01 7.132015e+01 +-8.432738e-01 7.190603e-02 -5.326526e-01 2.619550e+02 3.574903e-02 9.963198e-01 7.790293e-02 -2.521578e+01 5.362941e-01 4.665168e-02 -8.427409e-01 7.049523e+01 +-8.435089e-01 7.215632e-02 -5.322464e-01 2.614423e+02 3.534581e-02 9.962443e-01 7.904392e-02 -2.515470e+01 5.359510e-01 4.786157e-02 -8.428914e-01 6.967212e+01 +-8.436211e-01 7.246795e-02 -5.320261e-01 2.609323e+02 3.564480e-02 9.962232e-01 7.917575e-02 -2.509376e+01 5.357545e-01 4.783037e-02 -8.430180e-01 6.885370e+01 +-8.438303e-01 7.371221e-02 -5.315233e-01 2.604228e+02 3.662783e-02 9.961221e-01 7.999408e-02 -2.503114e+01 5.353587e-01 4.803288e-02 -8.432580e-01 6.803950e+01 +-8.440235e-01 7.503619e-02 -5.310310e-01 2.599140e+02 3.741571e-02 9.959898e-01 8.126750e-02 -2.496052e+01 5.349995e-01 4.872277e-02 -8.434463e-01 6.722891e+01 +-8.443437e-01 7.638898e-02 -5.303286e-01 2.593790e+02 3.890413e-02 9.959127e-01 8.151233e-02 -2.491317e+01 5.343877e-01 4.819245e-02 -8.438645e-01 6.643631e+01 +-8.447582e-01 7.730481e-02 -5.295352e-01 2.588316e+02 4.085046e-02 9.959393e-01 8.022538e-02 -2.487667e+01 5.335868e-01 4.613929e-02 -8.444859e-01 6.566475e+01 +-8.452925e-01 7.745718e-02 -5.286596e-01 2.583045e+02 4.207980e-02 9.960138e-01 7.864930e-02 -2.482166e+01 5.326443e-01 4.423577e-02 -8.451824e-01 6.488445e+01 +-8.460660e-01 7.735222e-02 -5.274362e-01 2.577739e+02 4.255385e-02 9.960590e-01 7.781800e-02 -2.475905e+01 5.313770e-01 4.339472e-02 -8.460233e-01 6.411588e+01 +-8.471765e-01 7.842902e-02 -5.254910e-01 2.572592e+02 4.421626e-02 9.960213e-01 7.737149e-02 -2.470180e+01 5.294685e-01 4.231206e-02 -8.472738e-01 6.333587e+01 +-8.495500e-01 7.958592e-02 -5.214699e-01 2.567456e+02 4.648253e-02 9.960022e-01 7.628156e-02 -2.464397e+01 5.254561e-01 4.056575e-02 -8.498531e-01 6.256617e+01 +-8.532441e-01 8.056953e-02 -5.152505e-01 2.562507e+02 4.908230e-02 9.960148e-01 7.446725e-02 -2.459231e+01 5.191970e-01 3.824905e-02 -8.537983e-01 6.178945e+01 +-8.581000e-01 8.282509e-02 -5.067588e-01 2.557614e+02 5.315285e-02 9.959312e-01 7.277161e-02 -2.454041e+01 5.107242e-01 3.550964e-02 -8.590110e-01 6.101143e+01 +-8.643146e-01 8.402433e-02 -4.958833e-01 2.552950e+02 5.688677e-02 9.959513e-01 6.960529e-02 -2.448994e+01 4.997242e-01 3.195167e-02 -8.655951e-01 6.023475e+01 +-8.718333e-01 8.376906e-02 -4.825863e-01 2.548357e+02 5.892503e-02 9.960486e-01 6.644465e-02 -2.443776e+01 4.862454e-01 2.949224e-02 -8.733245e-01 5.944760e+01 +-8.808473e-01 8.397758e-02 -4.658925e-01 2.544068e+02 6.155759e-02 9.961029e-01 6.316371e-02 -2.439314e+01 4.693812e-01 2.695836e-02 -8.825840e-01 5.865717e+01 +-8.909692e-01 8.587751e-02 -4.458688e-01 2.539978e+02 6.514266e-02 9.959692e-01 6.165778e-02 -2.435109e+01 4.493666e-01 2.589010e-02 -8.929722e-01 5.785932e+01 +-9.017161e-01 8.783458e-02 -4.233120e-01 2.535989e+02 6.775780e-02 9.957561e-01 6.227921e-02 -2.431032e+01 4.269858e-01 2.747547e-02 -9.038408e-01 5.704247e+01 +-9.128271e-01 8.809274e-02 -3.987309e-01 2.532423e+02 6.866959e-02 9.956630e-01 6.276724e-02 -2.426936e+01 4.025309e-01 2.991496e-02 -9.149175e-01 5.622914e+01 +-9.237772e-01 8.792240e-02 -3.727000e-01 2.529109e+02 7.011048e-02 9.956658e-01 6.110785e-02 -2.422491e+01 3.764574e-01 3.031986e-02 -9.259377e-01 5.541356e+01 +-9.342997e-01 8.774824e-02 -3.455203e-01 2.525925e+02 7.161787e-02 9.956735e-01 5.920366e-02 -2.418540e+01 3.492205e-01 3.056854e-02 -9.365419e-01 5.457690e+01 +-9.441894e-01 8.756468e-02 -3.175514e-01 2.523165e+02 7.336391e-02 9.957075e-01 5.642996e-02 -2.414833e+01 3.211296e-01 2.998375e-02 -9.465605e-01 5.375049e+01 +-9.533484e-01 8.655429e-02 -2.891975e-01 2.520708e+02 7.413321e-02 9.958040e-01 5.365315e-02 -2.411521e+01 2.926280e-01 2.971100e-02 -9.557647e-01 5.291837e+01 +-9.616726e-01 8.611911e-02 -2.603254e-01 2.518320e+02 7.520557e-02 9.958312e-01 5.161614e-02 -2.407496e+01 2.636853e-01 3.005990e-02 -9.641403e-01 5.207183e+01 +-9.691449e-01 8.557800e-02 -2.311592e-01 2.516402e+02 7.591092e-02 9.958394e-01 5.041241e-02 -2.404362e+01 2.345117e-01 3.130942e-02 -9.716090e-01 5.123346e+01 +-9.757035e-01 8.496552e-02 -2.019495e-01 2.514562e+02 7.630505e-02 9.958147e-01 5.030387e-02 -2.401326e+01 2.053784e-01 3.367189e-02 -9.781032e-01 5.037950e+01 +-9.813586e-01 8.428865e-02 -1.727156e-01 2.513187e+02 7.667516e-02 9.957865e-01 5.030059e-02 -2.398633e+01 1.762276e-01 3.611992e-02 -9.836865e-01 4.953814e+01 +-9.860443e-01 8.345993e-02 -1.440523e-01 2.512052e+02 7.678874e-02 9.957280e-01 5.127529e-02 -2.395711e+01 1.477163e-01 3.949811e-02 -9.882408e-01 4.869638e+01 +-9.896859e-01 8.199229e-02 -1.174700e-01 2.511015e+02 7.637437e-02 9.957452e-01 5.156065e-02 -2.392358e+01 1.211977e-01 4.205715e-02 -9.917370e-01 4.784901e+01 +-9.923902e-01 7.965008e-02 -9.390167e-02 2.510316e+02 7.513638e-02 9.958852e-01 5.066738e-02 -2.389420e+01 9.755095e-02 4.322637e-02 -9.942914e-01 4.701643e+01 +-9.943359e-01 7.658697e-02 -7.369300e-02 2.509724e+02 7.300593e-02 9.960712e-01 5.012261e-02 -2.386338e+01 7.724222e-02 4.445867e-02 -9.960206e-01 4.618303e+01 +-9.955944e-01 7.471637e-02 -5.665081e-02 2.509323e+02 7.196025e-02 9.961920e-01 4.922523e-02 -2.383795e+01 6.011302e-02 4.493175e-02 -9.971798e-01 4.536232e+01 +-9.963816e-01 7.373887e-02 -4.226402e-02 2.509001e+02 7.166436e-02 9.962410e-01 4.866217e-02 -2.381057e+01 4.569344e-02 4.545726e-02 -9.979207e-01 4.455360e+01 +-9.968632e-01 7.299795e-02 -3.057752e-02 2.508745e+02 7.153081e-02 9.963490e-01 4.660384e-02 -2.378248e+01 3.386787e-02 4.427041e-02 -9.984453e-01 4.375365e+01 +-9.972702e-01 7.042173e-02 -2.220036e-02 2.508589e+02 6.937454e-02 9.965816e-01 4.485806e-02 -2.375310e+01 2.528345e-02 4.319546e-02 -9.987467e-01 4.297044e+01 +-9.975424e-01 6.794557e-02 -1.710682e-02 2.508456e+02 6.713759e-02 9.967708e-01 4.405177e-02 -2.373249e+01 2.004470e-02 4.279499e-02 -9.988828e-01 4.219136e+01 +-9.976738e-01 6.653140e-02 -1.484890e-02 2.508700e+02 6.581289e-02 9.968378e-01 4.453110e-02 -2.366607e+01 1.776466e-02 4.345026e-02 -9.988976e-01 4.144614e+01 +-9.977908e-01 6.447836e-02 -1.600124e-02 2.508806e+02 6.368855e-02 9.969208e-01 4.574567e-02 -2.361432e+01 1.890158e-02 4.462551e-02 -9.988250e-01 4.070310e+01 +-9.978793e-01 6.159268e-02 -2.105571e-02 2.508878e+02 6.057405e-02 9.971029e-01 4.600543e-02 -2.355823e+01 2.382831e-02 4.463242e-02 -9.987193e-01 3.996994e+01 +-9.978237e-01 5.822595e-02 -3.094601e-02 2.508820e+02 5.675616e-02 9.973082e-01 4.642264e-02 -2.351395e+01 3.356571e-02 4.456523e-02 -9.984424e-01 3.924520e+01 +-9.974335e-01 5.462081e-02 -4.629225e-02 2.508602e+02 5.246916e-02 9.975399e-01 4.648649e-02 -2.346631e+01 4.871750e-02 4.393826e-02 -9.978457e-01 3.852960e+01 +-9.964053e-01 5.098167e-02 -6.765679e-02 2.508191e+02 4.784254e-02 9.977374e-01 4.723517e-02 -2.344569e+01 6.991184e-02 4.382849e-02 -9.965899e-01 3.782322e+01 +-9.943749e-01 4.820632e-02 -9.431219e-02 2.507351e+02 4.373361e-02 9.978442e-01 4.893116e-02 -2.344796e+01 9.646768e-02 4.453130e-02 -9.943395e-01 3.710657e+01 +-9.911821e-01 4.631969e-02 -1.241474e-01 2.506431e+02 4.042248e-02 9.979504e-01 4.960824e-02 -2.344427e+01 1.261908e-01 4.415245e-02 -9.910229e-01 3.642219e+01 +-9.866538e-01 4.682815e-02 -1.559532e-01 2.505282e+02 3.943706e-02 9.979624e-01 5.015622e-02 -2.343863e+01 1.579842e-01 4.333649e-02 -9.864902e-01 3.575185e+01 +-9.807147e-01 4.527836e-02 -1.901278e-01 2.503726e+02 3.628705e-02 9.980641e-01 5.051063e-02 -2.343059e+01 1.920467e-01 4.263733e-02 -9.804591e-01 3.507559e+01 +-9.730032e-01 4.337020e-02 -2.266798e-01 2.502199e+02 3.239011e-02 9.981249e-01 5.193764e-02 -2.341877e+01 2.285074e-01 4.319331e-02 -9.725835e-01 3.443151e+01 +-9.634922e-01 4.278912e-02 -2.642952e-01 2.500151e+02 2.898466e-02 9.980148e-01 5.591358e-02 -2.339436e+01 2.661630e-01 4.621178e-02 -9.628197e-01 3.377465e+01 +-9.520611e-01 4.358426e-02 -3.027872e-01 2.498096e+02 2.644086e-02 9.978185e-01 6.049094e-02 -2.337103e+01 3.047631e-01 4.958511e-02 -9.511366e-01 3.315346e+01 +-9.386426e-01 4.373174e-02 -3.421076e-01 2.495503e+02 2.299423e-02 9.976565e-01 6.444144e-02 -2.334708e+01 3.441240e-01 5.262098e-02 -9.374485e-01 3.252237e+01 +-9.227423e-01 4.280727e-02 -3.830330e-01 2.493004e+02 1.888368e-02 9.976407e-01 6.600351e-02 -2.332715e+01 3.849547e-01 5.367115e-02 -9.213736e-01 3.193860e+01 +-9.040639e-01 4.127827e-02 -4.253994e-01 2.489852e+02 1.507646e-02 9.977857e-01 6.477865e-02 -2.329994e+01 4.271314e-01 5.215051e-02 -9.026844e-01 3.134561e+01 +-8.828753e-01 4.026565e-02 -4.678781e-01 2.486824e+02 1.175664e-02 9.979001e-01 6.369494e-02 -2.326638e+01 4.694604e-01 5.073401e-02 -8.814948e-01 3.080593e+01 +-8.589702e-01 4.305437e-02 -5.102122e-01 2.483558e+02 1.296403e-02 9.979677e-01 6.238811e-02 -2.324253e+01 5.118615e-01 4.697511e-02 -8.577827e-01 3.029276e+01 +-8.330330e-01 4.827248e-02 -5.511132e-01 2.479611e+02 1.571387e-02 9.978485e-01 6.365021e-02 -2.321677e+01 5.530001e-01 4.436260e-02 -8.319993e-01 2.976855e+01 +-8.053903e-01 4.999108e-02 -5.906331e-01 2.475951e+02 1.345689e-02 9.977224e-01 6.609721e-02 -2.318943e+01 5.925922e-01 4.528596e-02 -8.042287e-01 2.929617e+01 +-7.758476e-01 4.932566e-02 -6.289892e-01 2.471662e+02 1.039012e-02 9.978029e-01 6.543221e-02 -2.315917e+01 6.308348e-01 4.423015e-02 -7.746555e-01 2.881512e+01 +-7.449270e-01 4.901447e-02 -6.653430e-01 2.467574e+02 6.568108e-03 9.977880e-01 6.615130e-02 -2.313414e+01 6.671136e-01 4.490785e-02 -7.436012e-01 2.839006e+01 +-7.121813e-01 4.929986e-02 -7.002623e-01 2.463256e+02 3.693743e-03 9.977803e-01 6.648913e-02 -2.310829e+01 7.019859e-01 4.476572e-02 -7.107826e-01 2.798679e+01 +-6.767338e-01 5.011028e-02 -7.345204e-01 2.458264e+02 1.635301e-03 9.977808e-01 6.656374e-02 -2.308154e+01 7.362260e-01 4.384477e-02 -6.753140e-01 2.757549e+01 +-6.386711e-01 5.113566e-02 -7.677788e-01 2.453486e+02 -2.234017e-04 9.977770e-01 6.663987e-02 -2.305615e+01 7.694798e-01 4.273248e-02 -6.372400e-01 2.722796e+01 +-5.984567e-01 5.240032e-02 -7.994396e-01 2.448065e+02 -3.175417e-03 9.976957e-01 6.777240e-02 -2.303027e+01 8.011489e-01 4.309740e-02 -5.969113e-01 2.687052e+01 +-5.566191e-01 5.153816e-02 -8.291677e-01 2.443004e+02 -6.259691e-03 9.977853e-01 6.622099e-02 -2.301147e+01 8.307443e-01 4.205019e-02 -5.550637e-01 2.657774e+01 +-5.136708e-01 5.133217e-02 -8.564504e-01 2.437818e+02 -9.514904e-03 9.978064e-01 6.551122e-02 -2.298962e+01 8.579346e-01 4.180024e-02 -5.120556e-01 2.631149e+01 +-4.706670e-01 5.317388e-02 -8.807072e-01 2.432085e+02 -9.341501e-03 9.978260e-01 6.523739e-02 -2.296611e+01 8.822615e-01 3.893221e-02 -4.691470e-01 2.604622e+01 +-4.277418e-01 5.652089e-02 -9.021321e-01 2.426799e+02 -7.724986e-03 9.977780e-01 6.617613e-02 -2.294186e+01 9.038680e-01 3.527525e-02 -4.263547e-01 2.584714e+01 +-3.849619e-01 5.994248e-02 -9.209838e-01 2.421227e+02 -7.540550e-03 9.976511e-01 6.808428e-02 -2.292073e+01 9.229017e-01 3.315458e-02 -3.836057e-01 2.565160e+01 +-3.429058e-01 6.311926e-02 -9.372468e-01 2.416185e+02 -7.898640e-03 9.975109e-01 7.006763e-02 -2.290316e+01 9.393366e-01 3.142957e-02 -3.415538e-01 2.551199e+01 +-3.007216e-01 6.538098e-02 -9.514682e-01 2.411317e+02 -8.376046e-03 9.974278e-01 7.118649e-02 -2.288730e+01 9.536752e-01 2.937686e-02 -2.994005e-01 2.540378e+01 +-2.584646e-01 6.635349e-02 -9.637392e-01 2.406297e+02 -8.480202e-03 9.974439e-01 7.094838e-02 -2.287013e+01 9.659835e-01 2.651035e-02 -2.572412e-01 2.529781e+01 +-2.169732e-01 6.686762e-02 -9.738847e-01 2.401834e+02 -9.522230e-03 9.974587e-01 7.060771e-02 -2.285331e+01 9.761312e-01 2.459353e-02 -2.157851e-01 2.524468e+01 +-1.758238e-01 6.789707e-02 -9.820774e-01 2.397254e+02 -1.119675e-02 9.974161e-01 7.096214e-02 -2.283198e+01 9.843580e-01 2.347291e-02 -1.746093e-01 2.518880e+01 +-1.343184e-01 6.881272e-02 -9.885461e-01 2.393207e+02 -1.622631e-02 9.972995e-01 7.162681e-02 -2.281548e+01 9.908054e-01 2.566126e-02 -1.328391e-01 2.517590e+01 +-9.215642e-02 6.983278e-02 -9.932928e-01 2.389350e+02 -2.100467e-02 9.971795e-01 7.205483e-02 -2.280004e+01 9.955230e-01 2.750410e-02 -9.042968e-02 2.518269e+01 +-4.975416e-02 7.133753e-02 -9.962105e-01 2.385331e+02 -2.340826e-02 9.970886e-01 7.256951e-02 -2.278274e+01 9.984872e-01 2.693019e-02 -4.793942e-02 2.518658e+01 +-6.252190e-03 7.108144e-02 -9.974509e-01 2.381801e+02 -2.529480e-02 9.971400e-01 7.121785e-02 -2.276968e+01 9.996605e-01 2.567559e-02 -4.436316e-03 2.523672e+01 +3.900582e-02 7.004891e-02 -9.967807e-01 2.378344e+02 -2.737495e-02 9.972403e-01 6.900999e-02 -2.275087e+01 9.988640e-01 2.459503e-02 4.081576e-02 2.530640e+01 +8.539554e-02 6.990416e-02 -9.938918e-01 2.374537e+02 -3.315323e-02 9.971827e-01 6.728709e-02 -2.272655e+01 9.957954e-01 2.720470e-02 8.747251e-02 2.535879e+01 +1.347192e-01 7.116629e-02 -9.883249e-01 2.371244e+02 -3.913017e-02 9.970216e-01 6.645867e-02 -2.270989e+01 9.901109e-01 2.972007e-02 1.371027e-01 2.546175e+01 +1.871619e-01 7.435005e-02 -9.795113e-01 2.367510e+02 -4.508159e-02 9.967311e-01 6.704309e-02 -2.268773e+01 9.812941e-01 3.161002e-02 1.899019e-01 2.554744e+01 +2.415574e-01 7.688478e-02 -9.673359e-01 2.364448e+02 -4.904728e-02 9.965495e-01 6.695892e-02 -2.267186e+01 9.691463e-01 3.127077e-02 2.444949e-01 2.569444e+01 +2.974072e-01 7.835093e-02 -9.515304e-01 2.361562e+02 -5.212266e-02 9.964732e-01 6.576035e-02 -2.264523e+01 9.533269e-01 3.003869e-02 3.004421e-01 2.587012e+01 +3.533450e-01 7.873943e-02 -9.321735e-01 2.358196e+02 -5.394335e-02 9.965084e-01 6.372624e-02 -2.262375e+01 9.339365e-01 2.776720e-02 3.563588e-01 2.601504e+01 +4.084903e-01 7.855839e-02 -9.093757e-01 2.355609e+02 -5.541713e-02 9.965860e-01 6.119895e-02 -2.260552e+01 9.110788e-01 2.539581e-02 4.114492e-01 2.622434e+01 +4.619052e-01 7.831062e-02 -8.834653e-01 2.352529e+02 -5.713289e-02 9.966528e-01 5.847263e-02 -2.258854e+01 8.850873e-01 2.346612e-02 4.648332e-01 2.639917e+01 +5.129507e-01 7.867801e-02 -8.548049e-01 2.350188e+02 -6.167972e-02 9.965951e-01 5.471598e-02 -2.257316e+01 8.561993e-01 2.465752e-02 5.160570e-01 2.663401e+01 +5.624715e-01 8.021828e-02 -8.229160e-01 2.347309e+02 -6.890313e-02 9.963680e-01 5.003050e-02 -2.255306e+01 8.239407e-01 2.856076e-02 5.659560e-01 2.682781e+01 +6.114013e-01 8.082111e-02 -7.871826e-01 2.345202e+02 -7.454743e-02 9.962293e-01 4.438357e-02 -2.253833e+01 7.878015e-01 3.154626e-02 6.151209e-01 2.709384e+01 +6.584135e-01 8.091869e-02 -7.482940e-01 2.343225e+02 -7.846892e-02 9.961659e-01 3.867927e-02 -2.252869e+01 7.485549e-01 3.325086e-02 6.622387e-01 2.738039e+01 +7.034565e-01 7.927003e-02 -7.063039e-01 2.340697e+02 -7.932495e-02 9.963086e-01 3.281275e-02 -2.251333e+01 7.062978e-01 3.294517e-02 7.071479e-01 2.763650e+01 +7.455766e-01 7.663373e-02 -6.619991e-01 2.338940e+02 -7.756329e-02 9.965938e-01 2.801114e-02 -2.249857e+01 6.618908e-01 3.046237e-02 7.489811e-01 2.796735e+01 +7.839713e-01 7.463844e-02 -6.162938e-01 2.336653e+02 -7.521405e-02 9.968527e-01 2.504957e-02 -2.248003e+01 6.162239e-01 2.671581e-02 7.871178e-01 2.827003e+01 +8.183101e-01 7.499611e-02 -5.698633e-01 2.335058e+02 -7.520225e-02 9.968982e-01 2.320687e-02 -2.247119e+01 5.698362e-01 2.386459e-02 8.214117e-01 2.863473e+01 +8.484490e-01 7.928380e-02 -5.233053e-01 2.333465e+02 -7.893201e-02 9.966142e-01 2.301829e-02 -2.246298e+01 5.233585e-01 2.177570e-02 8.518343e-01 2.901098e+01 +8.745819e-01 8.055150e-02 -4.781400e-01 2.331522e+02 -7.954376e-02 9.965797e-01 2.239611e-02 -2.244909e+01 4.783088e-01 1.844582e-02 8.779980e-01 2.937022e+01 +8.969886e-01 7.946303e-02 -4.348529e-01 2.330160e+02 -7.738628e-02 9.967469e-01 2.251323e-02 -2.243549e+01 4.352273e-01 1.345753e-02 9.002201e-01 2.978416e+01 +9.155226e-01 8.379427e-02 -3.934423e-01 2.328800e+02 -8.089909e-02 9.964340e-01 2.396930e-02 -2.242441e+01 3.940478e-01 9.884691e-03 9.190368e-01 3.021177e+01 +9.311355e-01 8.890883e-02 -3.536691e-01 2.327177e+02 -8.615496e-02 9.960032e-01 2.355749e-02 -2.242142e+01 3.543501e-01 8.535139e-03 9.350739e-01 3.062384e+01 +9.442106e-01 9.780806e-02 -3.144836e-01 2.325957e+02 -9.527662e-02 9.951745e-01 2.345090e-02 -2.240840e+01 3.152598e-01 7.820342e-03 9.489732e-01 3.107881e+01 +9.558656e-01 1.005863e-01 -2.760497e-01 2.324652e+02 -9.776637e-02 9.949201e-01 2.399502e-02 -2.239760e+01 2.770610e-01 4.052364e-03 9.608438e-01 3.152799e+01 +9.657879e-01 9.741922e-02 -2.403398e-01 2.323813e+02 -9.437290e-02 9.952432e-01 2.418088e-02 -2.237481e+01 2.415522e-01 -6.720389e-04 9.703876e-01 3.202605e+01 +9.739699e-01 8.928450e-02 -2.083531e-01 2.323155e+02 -8.652799e-02 9.959992e-01 2.232586e-02 -2.236066e+01 2.095129e-01 -3.716335e-03 9.777988e-01 3.253182e+01 +9.798247e-01 9.000529e-02 -1.784451e-01 2.322277e+02 -8.821368e-02 9.959395e-01 1.796580e-02 -2.235051e+01 1.793375e-01 -1.862033e-03 9.837859e-01 3.303429e+01 +9.833122e-01 1.001729e-01 -1.518637e-01 2.321465e+02 -9.873914e-02 9.949686e-01 1.697277e-02 -2.234731e+01 1.527999e-01 -1.694630e-03 9.882557e-01 3.356393e+01 +9.858239e-01 1.050729e-01 -1.308088e-01 2.320757e+02 -1.047028e-01 9.944560e-01 9.723293e-03 -2.233920e+01 1.311053e-01 4.110598e-03 9.913599e-01 3.410144e+01 +9.878573e-01 1.063781e-01 -1.132328e-01 2.320114e+02 -1.066789e-01 9.942876e-01 3.416603e-03 -2.232408e+01 1.129494e-01 8.704435e-03 9.935626e-01 3.465565e+01 +9.901576e-01 9.959621e-02 -9.832901e-02 2.319700e+02 -9.996710e-02 9.949900e-01 1.160181e-03 -2.231654e+01 9.795195e-02 8.680904e-03 9.951533e-01 3.523095e+01 +9.914102e-01 9.842471e-02 -8.612979e-02 2.319242e+02 -9.860942e-02 9.951239e-01 2.117982e-03 -2.230892e+01 8.591828e-02 6.393419e-03 9.962817e-01 3.582354e+01 +9.918126e-01 1.030232e-01 -7.545929e-02 2.318728e+02 -1.030370e-01 9.946705e-01 3.720443e-03 -2.230851e+01 7.544043e-02 4.085117e-03 9.971420e-01 3.643272e+01 +9.920515e-01 1.069049e-01 -6.637119e-02 2.318241e+02 -1.068494e-01 9.942655e-01 4.396421e-03 -2.230634e+01 6.646059e-02 2.730243e-03 9.977853e-01 3.705736e+01 +9.920434e-01 1.111745e-01 -5.907660e-02 2.317746e+02 -1.111668e-01 9.937958e-01 3.427628e-03 -2.230502e+01 5.909114e-02 3.167002e-03 9.982476e-01 3.769585e+01 +9.918261e-01 1.162190e-01 -5.267053e-02 2.317444e+02 -1.165565e-01 9.931783e-01 -3.370889e-03 -2.226818e+01 5.191947e-02 9.482426e-03 9.986063e-01 3.831063e+01 +9.918725e-01 1.178134e-01 -4.805156e-02 2.317117e+02 -1.185476e-01 9.928669e-01 -1.271689e-02 -2.226790e+01 4.621059e-02 1.830993e-02 9.987639e-01 3.897182e+01 +9.920713e-01 1.172837e-01 -4.515564e-02 2.316852e+02 -1.181751e-01 9.928368e-01 -1.759547e-02 -2.226651e+01 4.276853e-02 2.279223e-02 9.988250e-01 3.964983e+01 +9.922435e-01 1.164988e-01 -4.336894e-02 2.316566e+02 -1.174651e-01 9.928667e-01 -2.043387e-02 -2.226928e+01 4.067906e-02 2.536971e-02 9.988501e-01 4.034383e+01 +9.913529e-01 1.246660e-01 -4.096252e-02 2.316138e+02 -1.255544e-01 9.918877e-01 -1.987135e-02 -2.227713e+01 3.815294e-02 2.484254e-02 9.989631e-01 4.105471e+01 +9.905421e-01 1.314162e-01 -3.944711e-02 2.315710e+02 -1.322076e-01 9.910556e-01 -1.816096e-02 -2.228416e+01 3.670764e-02 2.320440e-02 9.990566e-01 4.178030e+01 +9.899529e-01 1.360027e-01 -3.868554e-02 2.315325e+02 -1.367957e-01 9.904239e-01 -1.863777e-02 -2.229406e+01 3.578030e-02 2.374253e-02 9.990776e-01 4.251661e+01 +9.899436e-01 1.365323e-01 -3.702175e-02 2.315004e+02 -1.372403e-01 9.903867e-01 -1.729855e-02 -2.230502e+01 3.430404e-02 2.220546e-02 9.991647e-01 4.326538e+01 +9.898329e-01 1.380268e-01 -3.434216e-02 2.314674e+02 -1.385863e-01 9.902446e-01 -1.447220e-02 -2.231578e+01 3.200959e-02 1.908441e-02 9.993054e-01 4.402695e+01 +9.894719e-01 1.411964e-01 -3.176450e-02 2.314332e+02 -1.416644e-01 9.898295e-01 -1.298812e-02 -2.232017e+01 2.960756e-02 1.735128e-02 9.994110e-01 4.479817e+01 +9.889773e-01 1.452754e-01 -2.861680e-02 2.313992e+02 -1.456207e-01 9.892862e-01 -1.036192e-02 -2.232882e+01 2.680488e-02 1.441490e-02 9.995368e-01 4.557638e+01 +9.889814e-01 1.457792e-01 -2.577351e-02 2.313721e+02 -1.460710e-01 9.892254e-01 -9.813524e-03 -2.233838e+01 2.406520e-02 1.347015e-02 9.996196e-01 4.636485e+01 +9.890151e-01 1.457091e-01 -2.486083e-02 2.313469e+02 -1.460528e-01 9.891964e-01 -1.261289e-02 -2.235383e+01 2.275443e-02 1.610533e-02 9.996114e-01 4.715536e+01 +9.889080e-01 1.465771e-01 -2.400438e-02 2.313196e+02 -1.469871e-01 9.890041e-01 -1.630115e-02 -2.235840e+01 2.135105e-02 1.964867e-02 9.995790e-01 4.795805e+01 +9.885470e-01 1.491104e-01 -2.325674e-02 2.312918e+02 -1.495194e-01 9.886134e-01 -1.695618e-02 -2.236586e+01 2.046358e-02 2.023931e-02 9.995857e-01 4.877571e+01 +9.886665e-01 1.486193e-01 -2.123534e-02 2.312677e+02 -1.489116e-01 9.887662e-01 -1.290775e-02 -2.237574e+01 1.907845e-02 1.592364e-02 9.996912e-01 4.960838e+01 +9.886098e-01 1.494185e-01 -1.802189e-02 2.312455e+02 -1.495388e-01 9.887405e-01 -5.509775e-03 -2.238760e+01 1.699571e-02 8.141987e-03 9.998224e-01 5.045512e+01 +9.882618e-01 1.519508e-01 -1.579670e-02 2.312213e+02 -1.520000e-01 9.883785e-01 -1.955740e-03 -2.239727e+01 1.531594e-02 4.333881e-03 9.998733e-01 5.131000e+01 +9.882378e-01 1.522371e-01 -1.449076e-02 2.311983e+02 -1.522993e-01 9.883289e-01 -3.281302e-03 -2.239651e+01 1.382210e-02 5.449639e-03 9.998896e-01 5.217303e+01 +9.884302e-01 1.509948e-01 -1.436612e-02 2.311796e+02 -1.510892e-01 9.885035e-01 -5.724592e-03 -2.240185e+01 1.333658e-02 7.828926e-03 9.998804e-01 5.304573e+01 +9.887181e-01 1.491213e-01 -1.412028e-02 2.311629e+02 -1.492262e-01 9.887805e-01 -6.681349e-03 -2.240620e+01 1.296553e-02 8.713085e-03 9.998780e-01 5.393028e+01 +9.882178e-01 1.523556e-01 -1.460648e-02 2.311387e+02 -1.524708e-01 9.882823e-01 -7.116627e-03 -2.241693e+01 1.335107e-02 9.259837e-03 9.998680e-01 5.482536e+01 +9.879158e-01 1.543419e-01 -1.417863e-02 2.311126e+02 -1.544078e-01 9.880003e-01 -3.674043e-03 -2.242144e+01 1.344144e-02 5.818937e-03 9.998927e-01 5.573460e+01 +9.885751e-01 1.499038e-01 -1.575287e-02 2.310929e+02 -1.500034e-01 9.886711e-01 -5.334484e-03 -2.242663e+01 1.477475e-02 7.636522e-03 9.998617e-01 5.665184e+01 +9.883378e-01 1.511413e-01 -1.856627e-02 2.310529e+02 -1.513272e-01 9.884424e-01 -9.037681e-03 -2.240507e+01 1.698572e-02 1.174186e-02 9.997868e-01 5.758760e+01 +9.888339e-01 1.474180e-01 -2.180586e-02 2.310182e+02 -1.476602e-01 9.889882e-01 -9.941678e-03 -2.239431e+01 2.010016e-02 1.305053e-02 9.997128e-01 5.853200e+01 +9.899414e-01 1.390994e-01 -2.583227e-02 2.309862e+02 -1.391700e-01 9.902680e-01 -9.454887e-04 -2.237833e+01 2.544935e-02 4.531056e-03 9.996659e-01 5.950033e+01 +9.908865e-01 1.317984e-01 -2.780474e-02 2.309608e+02 -1.313840e-01 9.911984e-01 1.624787e-02 -2.236865e+01 2.970146e-02 -1.244669e-02 9.994813e-01 6.048279e+01 +9.925902e-01 1.175418e-01 -3.079955e-02 2.309231e+02 -1.167109e-01 9.927845e-01 2.752070e-02 -2.231965e+01 3.381216e-02 -2.372213e-02 9.991466e-01 6.146833e+01 +9.934228e-01 1.091583e-01 -3.457694e-02 2.308862e+02 -1.080951e-01 9.936489e-01 3.125957e-02 -2.227590e+01 3.776958e-02 -2.731637e-02 9.989131e-01 6.245061e+01 +9.938915e-01 1.032511e-01 -3.897430e-02 2.308382e+02 -1.021140e-01 9.943164e-01 3.012499e-02 -2.224144e+01 4.186323e-02 -2.596114e-02 9.987860e-01 6.342494e+01 +9.941841e-01 9.866974e-02 -4.315311e-02 2.307818e+02 -9.784179e-02 9.949825e-01 2.090068e-02 -2.224087e+01 4.499885e-02 -1.655694e-02 9.988498e-01 6.438642e+01 +9.938575e-01 1.001213e-01 -4.714826e-02 2.307140e+02 -9.977051e-02 9.949628e-01 9.742762e-03 -2.223526e+01 4.788622e-02 -4.978910e-03 9.988404e-01 6.535101e+01 +9.930311e-01 1.069761e-01 -4.945051e-02 2.306321e+02 -1.069527e-01 9.942592e-01 3.127066e-03 -2.223758e+01 4.950115e-02 2.183593e-03 9.987717e-01 6.632155e+01 +9.923521e-01 1.129152e-01 -4.987397e-02 2.305544e+02 -1.130430e-01 9.935900e-01 2.594811e-04 -2.224568e+01 4.958358e-02 5.380408e-03 9.987555e-01 6.730125e+01 +9.923260e-01 1.137114e-01 -4.856746e-02 2.304833e+02 -1.137342e-01 9.935085e-01 2.304779e-03 -2.225362e+01 4.851427e-02 3.236688e-03 9.988173e-01 6.828984e+01 +9.928245e-01 1.103198e-01 -4.614204e-02 2.304315e+02 -1.100501e-01 9.938909e-01 8.354197e-03 -2.225419e+01 4.678179e-02 -3.216317e-03 9.989000e-01 6.928398e+01 +9.931227e-01 1.084196e-01 -4.418759e-02 2.303829e+02 -1.079407e-01 9.940711e-01 1.309203e-02 -2.223774e+01 4.534504e-02 -8.232349e-03 9.989375e-01 7.027942e+01 +9.935926e-01 1.045434e-01 -4.294722e-02 2.303403e+02 -1.041160e-01 9.944918e-01 1.207872e-02 -2.222496e+01 4.397341e-02 -7.529832e-03 9.990043e-01 7.127290e+01 +9.940173e-01 1.007305e-01 -4.222661e-02 2.302973e+02 -1.004487e-01 9.949038e-01 8.747338e-03 -2.221028e+01 4.289254e-02 -4.453393e-03 9.990698e-01 7.226580e+01 +9.942464e-01 9.874741e-02 -4.150926e-02 2.302519e+02 -9.832938e-02 9.950815e-01 1.200011e-02 -2.220558e+01 4.249009e-02 -7.849485e-03 9.990661e-01 7.326581e+01 +9.946304e-01 9.427509e-02 -4.269287e-02 2.302088e+02 -9.391789e-02 9.955266e-01 1.030161e-02 -2.219945e+01 4.347307e-02 -6.236671e-03 9.990351e-01 7.426263e+01 +9.948071e-01 9.144433e-02 -4.468434e-02 2.301633e+02 -9.106973e-02 9.957907e-01 1.035308e-02 -2.218891e+01 4.544299e-02 -6.229929e-03 9.989475e-01 7.526731e+01 +9.951548e-01 8.658751e-02 -4.657732e-02 2.301172e+02 -8.594386e-02 9.961770e-01 1.565280e-02 -2.217618e+01 4.775459e-02 -1.157392e-02 9.987921e-01 7.627916e+01 +9.954467e-01 8.227871e-02 -4.812623e-02 2.300714e+02 -8.140698e-02 9.964841e-01 1.980509e-02 -2.217120e+01 4.958656e-02 -1.579709e-02 9.986449e-01 7.729178e+01 +9.955947e-01 8.015125e-02 -4.865253e-02 2.300205e+02 -7.950164e-02 9.967196e-01 1.514692e-02 -2.216220e+01 4.970698e-02 -1.121223e-02 9.987009e-01 7.829838e+01 +9.954675e-01 8.250379e-02 -4.730347e-02 2.299636e+02 -8.228848e-02 9.965874e-01 6.484851e-03 -2.215238e+01 4.767708e-02 -2.562926e-03 9.988595e-01 7.929900e+01 +9.954331e-01 8.427545e-02 -4.484033e-02 2.299103e+02 -8.422503e-02 9.964422e-01 3.016359e-03 -2.215035e+01 4.493500e-02 7.740954e-04 9.989896e-01 8.031230e+01 +9.955533e-01 8.373771e-02 -4.314621e-02 2.298601e+02 -8.361493e-02 9.964873e-01 4.645952e-03 -2.214931e+01 4.338369e-02 -1.017624e-03 9.990580e-01 8.132836e+01 +9.955424e-01 8.512696e-02 -4.060452e-02 2.298126e+02 -8.476613e-02 9.963452e-01 1.053030e-02 -2.215081e+01 4.135254e-02 -7.041472e-03 9.991198e-01 8.235086e+01 +9.957782e-01 8.326558e-02 -3.863387e-02 2.297645e+02 -8.284514e-02 9.964857e-01 1.236217e-02 -2.215921e+01 3.952745e-02 -9.109346e-03 9.991770e-01 8.336258e+01 +9.956401e-01 8.528404e-02 -3.778176e-02 2.297055e+02 -8.499083e-02 9.963383e-01 9.303350e-03 -2.218084e+01 3.843685e-02 -6.051683e-03 9.992427e-01 8.436294e+01 +9.953333e-01 8.877904e-02 -3.781476e-02 2.296396e+02 -8.854319e-02 9.960412e-01 7.870706e-03 -2.220026e+01 3.836381e-02 -4.485735e-03 9.992538e-01 8.536168e+01 +9.953787e-01 8.827852e-02 -3.779037e-02 2.295850e+02 -8.796773e-02 9.960750e-01 9.813154e-03 -2.221727e+01 3.850834e-02 -6.443469e-03 9.992375e-01 8.636827e+01 +9.952515e-01 8.980809e-02 -3.753501e-02 2.295413e+02 -8.929902e-02 9.958914e-01 1.502983e-02 -2.222667e+01 3.873060e-02 -1.160662e-02 9.991823e-01 8.737300e+01 +9.952947e-01 8.918644e-02 -3.787071e-02 2.295084e+02 -8.872466e-02 9.959618e-01 1.370776e-02 -2.222503e+01 3.894033e-02 -1.028319e-02 9.991886e-01 8.837240e+01 +9.954899e-01 8.705725e-02 -3.769605e-02 2.294631e+02 -8.670198e-02 9.961739e-01 1.096270e-02 -2.223302e+01 3.850621e-02 -7.644930e-03 9.992291e-01 8.938397e+01 +9.964217e-01 7.622520e-02 -3.651842e-02 2.294349e+02 -7.591282e-02 9.970656e-01 9.868170e-03 -2.224387e+01 3.716347e-02 -7.060640e-03 9.992843e-01 9.039730e+01 +9.963795e-01 7.672107e-02 -3.663130e-02 2.293962e+02 -7.654990e-02 9.970473e-01 6.055209e-03 -2.225930e+01 3.698771e-02 -3.229162e-03 9.993105e-01 9.140415e+01 +9.956885e-01 8.529977e-02 -3.644815e-02 2.293409e+02 -8.547922e-02 9.963342e-01 -3.390314e-03 -2.227922e+01 3.602535e-02 6.491256e-03 9.993298e-01 9.239947e+01 +9.952273e-01 9.017813e-02 -3.729086e-02 2.292905e+02 -9.068172e-02 9.958072e-01 -1.203695e-02 -2.230258e+01 3.604904e-02 1.536110e-02 9.992320e-01 9.339367e+01 +9.942443e-01 1.006279e-01 -3.677432e-02 2.292261e+02 -1.010865e-01 9.948187e-01 -1.082721e-02 -2.232113e+01 3.549426e-02 1.448227e-02 9.992649e-01 9.439042e+01 +9.928635e-01 1.136268e-01 -3.620911e-02 2.291612e+02 -1.140631e-01 9.934210e-01 -1.021208e-02 -2.234499e+01 3.481052e-02 1.426932e-02 9.992921e-01 9.539245e+01 +9.913805e-01 1.255558e-01 -3.742275e-02 2.290956e+02 -1.260991e-01 9.919386e-01 -1.251849e-02 -2.236895e+01 3.554931e-02 1.712956e-02 9.992211e-01 9.638910e+01 +9.912131e-01 1.262507e-01 -3.946342e-02 2.290434e+02 -1.268734e-01 9.918245e-01 -1.368364e-02 -2.239351e+01 3.741322e-02 1.857026e-02 9.991273e-01 9.738361e+01 +9.917244e-01 1.215451e-01 -4.134570e-02 2.290010e+02 -1.220116e-01 9.924884e-01 -8.943604e-03 -2.241494e+01 3.994808e-02 1.391424e-02 9.991049e-01 9.838906e+01 +9.922183e-01 1.172333e-01 -4.194302e-02 2.289563e+02 -1.172773e-01 9.930982e-01 1.418798e-03 -2.243053e+01 4.181987e-02 3.511207e-03 9.991190e-01 9.940425e+01 +9.929841e-01 1.102364e-01 -4.278526e-02 2.289156e+02 -1.099697e-01 9.938982e-01 8.546227e-03 -2.244283e+01 4.346630e-02 -3.781186e-03 9.990477e-01 1.004209e+02 +9.935822e-01 1.038797e-01 -4.475916e-02 2.288746e+02 -1.039208e-01 9.945845e-01 1.412845e-03 -2.245276e+01 4.466353e-02 3.247632e-03 9.989968e-01 1.014246e+02 +9.937598e-01 1.016376e-01 -4.594784e-02 2.288276e+02 -1.023140e-01 9.946722e-01 -1.260912e-02 -2.246645e+01 4.442148e-02 1.723154e-02 9.988643e-01 1.024241e+02 +9.938237e-01 1.009822e-01 -4.601123e-02 2.287774e+02 -1.021420e-01 9.944901e-01 -2.358830e-02 -2.248939e+01 4.337572e-02 2.814229e-02 9.986624e-01 1.034296e+02 +9.935867e-01 1.036105e-01 -4.528124e-02 2.287213e+02 -1.048746e-01 9.941327e-01 -2.648607e-02 -2.251587e+01 4.227133e-02 3.106505e-02 9.986231e-01 1.044496e+02 +9.937410e-01 1.032116e-01 -4.273476e-02 2.286710e+02 -1.041353e-01 9.943624e-01 -1.997845e-02 -2.254496e+01 4.043184e-02 2.430360e-02 9.988867e-01 1.054810e+02 +9.936987e-01 1.044691e-01 -4.060926e-02 2.286205e+02 -1.050893e-01 9.943719e-01 -1.344361e-02 -2.257166e+01 3.897626e-02 1.762650e-02 9.990847e-01 1.065153e+02 +9.939705e-01 1.024735e-01 -3.901162e-02 2.285749e+02 -1.029609e-01 9.946279e-01 -1.069248e-02 -2.259529e+01 3.770635e-02 1.464468e-02 9.991816e-01 1.075497e+02 +9.943841e-01 9.818835e-02 -3.948899e-02 2.285345e+02 -9.875825e-02 9.950298e-01 -1.274466e-02 -2.261554e+01 3.804135e-02 1.657295e-02 9.991387e-01 1.085809e+02 +9.947352e-01 9.363253e-02 -4.165077e-02 2.284928e+02 -9.444945e-02 9.953652e-01 -1.809354e-02 -2.263800e+01 3.976359e-02 2.193217e-02 9.989684e-01 1.096177e+02 +9.948667e-01 9.145877e-02 -4.330699e-02 2.284471e+02 -9.220112e-02 9.956203e-01 -1.546142e-02 -2.266196e+01 4.170324e-02 1.937500e-02 9.989422e-01 1.106617e+02 +9.949628e-01 8.985195e-02 -4.444897e-02 2.283970e+02 -9.041889e-02 9.958441e-01 -1.090840e-02 -2.268425e+01 4.328411e-02 1.487248e-02 9.989521e-01 1.117125e+02 +9.950025e-01 8.912856e-02 -4.501173e-02 2.283451e+02 -8.947422e-02 9.959727e-01 -5.719408e-03 -2.270993e+01 4.432070e-02 9.718214e-03 9.989701e-01 1.127660e+02 +9.953793e-01 8.408018e-02 -4.637425e-02 2.283051e+02 -8.457485e-02 9.963782e-01 -8.806042e-03 -2.273065e+01 4.546588e-02 1.268745e-02 9.988853e-01 1.138160e+02 +9.958801e-01 7.750728e-02 -4.706880e-02 2.282803e+02 -7.793137e-02 9.969324e-01 -7.239478e-03 -2.276395e+01 4.636330e-02 1.087779e-02 9.988654e-01 1.148834e+02 +9.963590e-01 7.129759e-02 -4.674758e-02 2.282622e+02 -7.163546e-02 9.974152e-01 -5.589874e-03 -2.281008e+01 4.622820e-02 8.918305e-03 9.988911e-01 1.159538e+02 +9.967270e-01 6.608295e-02 -4.656613e-02 2.282368e+02 -6.674875e-02 9.976865e-01 -1.288888e-02 -2.285247e+01 4.560667e-02 1.595493e-02 9.988321e-01 1.170117e+02 +9.968434e-01 6.397551e-02 -4.701436e-02 2.282092e+02 -6.518972e-02 9.975656e-01 -2.476177e-02 -2.289734e+01 4.531576e-02 2.774846e-02 9.985873e-01 1.180657e+02 +9.969336e-01 6.349648e-02 -4.573499e-02 2.281745e+02 -6.472935e-02 9.975641e-01 -2.599834e-02 -2.294091e+01 4.397278e-02 2.887901e-02 9.986152e-01 1.191236e+02 +9.970330e-01 6.304872e-02 -4.415959e-02 2.281408e+02 -6.395950e-02 9.977615e-01 -1.952300e-02 -2.298422e+01 4.282984e-02 2.228950e-02 9.988337e-01 1.201889e+02 +9.966601e-01 6.933070e-02 -4.314981e-02 2.281014e+02 -7.005044e-02 9.974246e-01 -1.539552e-02 -2.302935e+01 4.197130e-02 1.836676e-02 9.989500e-01 1.212487e+02 +9.964434e-01 7.304011e-02 -4.202042e-02 2.280627e+02 -7.363319e-02 9.972040e-01 -1.274141e-02 -2.306818e+01 4.097230e-02 1.579019e-02 9.990355e-01 1.223005e+02 +9.960828e-01 7.774132e-02 -4.213600e-02 2.280211e+02 -7.835319e-02 9.968400e-01 -1.306686e-02 -2.309916e+01 4.098701e-02 1.631716e-02 9.990264e-01 1.233458e+02 +9.956802e-01 8.340730e-02 -4.079430e-02 2.279713e+02 -8.378766e-02 9.964538e-01 -7.701158e-03 -2.312408e+01 4.000730e-02 1.108595e-02 9.991379e-01 1.243940e+02 +9.952428e-01 8.822298e-02 -4.133302e-02 2.279237e+02 -8.849028e-02 9.960660e-01 -4.678672e-03 -2.314548e+01 4.075766e-02 8.313985e-03 9.991345e-01 1.254386e+02 +9.949282e-01 9.118648e-02 -4.246037e-02 2.278784e+02 -9.145430e-02 9.957995e-01 -4.403737e-03 -2.316918e+01 4.188046e-02 8.264586e-03 9.990885e-01 1.264745e+02 +9.951752e-01 8.738265e-02 -4.461604e-02 2.278429e+02 -8.778429e-02 9.961140e-01 -7.119352e-03 -2.319125e+01 4.382056e-02 1.100159e-02 9.989788e-01 1.275031e+02 +9.949743e-01 8.852795e-02 -4.678639e-02 2.278003e+02 -8.918261e-02 9.959419e-01 -1.209087e-02 -2.321836e+01 4.552615e-02 1.620263e-02 9.988317e-01 1.285261e+02 +9.946760e-01 9.142739e-02 -4.754624e-02 2.277527e+02 -9.220789e-02 9.956344e-01 -1.448467e-02 -2.324203e+01 4.601438e-02 1.879169e-02 9.987640e-01 1.295533e+02 +9.943334e-01 9.535115e-02 -4.700308e-02 2.277030e+02 -9.613979e-02 9.952577e-01 -1.480787e-02 -2.326779e+01 4.536823e-02 1.924282e-02 9.987850e-01 1.305747e+02 +9.938374e-01 1.014566e-01 -4.465173e-02 2.276522e+02 -1.020215e-01 9.947262e-01 -1.055388e-02 -2.329192e+01 4.334549e-02 1.504428e-02 9.989469e-01 1.315983e+02 +9.937031e-01 1.034409e-01 -4.305990e-02 2.276074e+02 -1.038784e-01 9.945574e-01 -8.044305e-03 -2.331896e+01 4.199344e-02 1.246664e-02 9.990401e-01 1.326168e+02 +9.939309e-01 1.015687e-01 -4.225072e-02 2.275714e+02 -1.018989e-01 9.947782e-01 -5.731799e-03 -2.334242e+01 4.144792e-02 1.000232e-02 9.990906e-01 1.336333e+02 +9.939371e-01 1.015644e-01 -4.211591e-02 2.275347e+02 -1.019922e-01 9.947520e-01 -8.130347e-03 -2.336386e+01 4.106913e-02 1.237654e-02 9.990797e-01 1.346394e+02 +9.936132e-01 1.046671e-01 -4.216125e-02 2.274949e+02 -1.052644e-01 9.943694e-01 -1.219922e-02 -2.338850e+01 4.064701e-02 1.655939e-02 9.990363e-01 1.356406e+02 +9.935555e-01 1.049130e-01 -4.290465e-02 2.274566e+02 -1.056537e-01 9.942842e-01 -1.537009e-02 -2.341515e+01 4.104689e-02 1.980407e-02 9.989609e-01 1.366397e+02 +9.936985e-01 1.034727e-01 -4.308969e-02 2.274196e+02 -1.041939e-01 9.944463e-01 -1.483468e-02 -2.344446e+01 4.131540e-02 1.923088e-02 9.989611e-01 1.376381e+02 +9.935992e-01 1.047169e-01 -4.236731e-02 2.273794e+02 -1.051868e-01 9.944116e-01 -9.012342e-03 -2.346420e+01 4.118680e-02 1.341114e-02 9.990615e-01 1.386344e+02 +9.939793e-01 1.014901e-01 -4.129034e-02 2.273469e+02 -1.013536e-01 9.948358e-01 5.391647e-03 -2.347857e+01 4.162432e-02 -1.174259e-03 9.991327e-01 1.396480e+02 +9.940808e-01 9.988880e-02 -4.272819e-02 2.273143e+02 -9.934492e-02 9.949448e-01 1.467408e-02 -2.348927e+01 4.397797e-02 -1.034239e-02 9.989790e-01 1.406482e+02 +9.946209e-01 9.319469e-02 -4.521165e-02 2.272858e+02 -9.291040e-02 9.956394e-01 8.354161e-03 -2.350177e+01 4.579306e-02 -4.108589e-03 9.989425e-01 1.416263e+02 +9.949358e-01 8.769078e-02 -4.912349e-02 2.272553e+02 -8.831633e-02 9.960349e-01 -1.070729e-02 -2.351616e+01 4.798978e-02 1.499147e-02 9.987353e-01 1.425920e+02 +9.945333e-01 9.178146e-02 -4.979556e-02 2.272090e+02 -9.319272e-02 9.952874e-01 -2.679578e-02 -2.354253e+01 4.710154e-02 3.128988e-02 9.983999e-01 1.435519e+02 +9.939198e-01 9.849086e-02 -4.922481e-02 2.271572e+02 -1.002088e-01 9.943943e-01 -3.373729e-02 -2.357489e+01 4.562605e-02 3.846491e-02 9.982178e-01 1.445212e+02 +9.934234e-01 1.041587e-01 -4.754919e-02 2.271097e+02 -1.054576e-01 9.940924e-01 -2.567051e-02 -2.360925e+01 4.459449e-02 3.051610e-02 9.985390e-01 1.455011e+02 +9.932935e-01 1.062605e-01 -4.557039e-02 2.270668e+02 -1.069048e-01 9.941976e-01 -1.193599e-02 -2.364983e+01 4.403765e-02 1.672764e-02 9.988898e-01 1.464910e+02 +9.935828e-01 1.043850e-01 -4.355366e-02 2.270300e+02 -1.046827e-01 9.944950e-01 -4.604497e-03 -2.368922e+01 4.283326e-02 9.134261e-03 9.990405e-01 1.474764e+02 +9.935053e-01 1.055202e-01 -4.257571e-02 2.269935e+02 -1.058401e-01 9.943689e-01 -5.324997e-03 -2.371565e+01 4.177407e-02 9.796630e-03 9.990791e-01 1.484491e+02 +9.935579e-01 1.053752e-01 -4.169853e-02 2.269586e+02 -1.057066e-01 9.943803e-01 -5.817577e-03 -2.374624e+01 4.085117e-02 1.018791e-02 9.991133e-01 1.494209e+02 +9.940719e-01 1.005292e-01 -4.141235e-02 2.269333e+02 -1.008901e-01 9.948749e-01 -6.713551e-03 -2.377887e+01 4.052520e-02 1.085185e-02 9.991196e-01 1.503826e+02 +9.943201e-01 9.793595e-02 -4.166776e-02 2.269076e+02 -9.843849e-02 9.950910e-01 -1.017948e-02 -2.381083e+01 4.046628e-02 1.422337e-02 9.990797e-01 1.513369e+02 +9.942573e-01 9.875607e-02 -4.122642e-02 2.268760e+02 -9.935823e-02 9.949692e-01 -1.281644e-02 -2.384286e+01 3.975332e-02 1.683902e-02 9.990676e-01 1.522858e+02 +9.948934e-01 9.230326e-02 -4.083243e-02 2.268514e+02 -9.294993e-02 9.955691e-01 -1.422828e-02 -2.386347e+01 3.933819e-02 1.795099e-02 9.990647e-01 1.532395e+02 +9.952079e-01 8.891540e-02 -4.068510e-02 2.268278e+02 -8.944174e-02 9.959279e-01 -1.130067e-02 -2.388843e+01 3.951463e-02 1.488546e-02 9.991081e-01 1.541855e+02 +9.953856e-01 8.743242e-02 -3.953655e-02 2.268007e+02 -8.772883e-02 9.961274e-01 -5.821529e-03 -2.391057e+01 3.887445e-02 9.263161e-03 9.992012e-01 1.551350e+02 +9.956656e-01 8.468603e-02 -3.844912e-02 2.267788e+02 -8.488013e-02 9.963852e-01 -3.440696e-03 -2.393552e+01 3.801875e-02 6.689348e-03 9.992546e-01 1.560717e+02 +9.958439e-01 8.320123e-02 -3.704666e-02 2.267564e+02 -8.341829e-02 9.965051e-01 -4.349308e-03 -2.395092e+01 3.655532e-02 7.421600e-03 9.993041e-01 1.570037e+02 +9.957335e-01 8.530361e-02 -3.518648e-02 2.267319e+02 -8.565167e-02 9.962888e-01 -8.502538e-03 -2.396859e+01 3.433060e-02 1.148004e-02 9.993446e-01 1.579286e+02 +9.957816e-01 8.513513e-02 -3.422162e-02 2.267091e+02 -8.575576e-02 9.961695e-01 -1.709342e-02 -2.398850e+01 3.263528e-02 1.995601e-02 9.992681e-01 1.588449e+02 +9.959294e-01 8.291346e-02 -3.535463e-02 2.266892e+02 -8.375902e-02 9.962172e-01 -2.314372e-02 -2.401767e+01 3.330197e-02 2.601078e-02 9.991068e-01 1.597582e+02 +9.960852e-01 7.985504e-02 -3.791344e-02 2.266710e+02 -8.072584e-02 9.964931e-01 -2.201868e-02 -2.404274e+01 3.602218e-02 2.499307e-02 9.990384e-01 1.606770e+02 +9.956233e-01 8.397078e-02 -4.102748e-02 2.266397e+02 -8.451959e-02 9.963516e-01 -1.182691e-02 -2.406586e+01 3.988469e-02 1.524277e-02 9.990880e-01 1.616002e+02 +9.955698e-01 8.314133e-02 -4.391216e-02 2.266085e+02 -8.330286e-02 9.965225e-01 -1.857853e-03 -2.408408e+01 4.360500e-02 5.507630e-03 9.990337e-01 1.625217e+02 +9.957115e-01 7.997832e-02 -4.649821e-02 2.265820e+02 -8.006663e-02 9.967895e-01 -3.650029e-05 -2.409300e+01 4.634602e-02 3.759299e-03 9.989184e-01 1.634335e+02 +9.955502e-01 8.194397e-02 -4.653034e-02 2.265475e+02 -8.199939e-02 9.966321e-01 7.200135e-04 -2.410533e+01 4.643263e-02 3.098650e-03 9.989166e-01 1.643386e+02 +9.953107e-01 8.503497e-02 -4.610479e-02 2.265115e+02 -8.510508e-02 9.963719e-01 4.440720e-04 -2.411935e+01 4.597528e-02 3.481763e-03 9.989365e-01 1.652430e+02 +9.954745e-01 8.294137e-02 -4.638114e-02 2.264850e+02 -8.316593e-02 9.965314e-01 -2.929182e-03 -2.413379e+01 4.597731e-02 6.773256e-03 9.989195e-01 1.661413e+02 +9.956868e-01 8.028200e-02 -4.650302e-02 2.264597e+02 -8.050675e-02 9.967496e-01 -2.977066e-03 -2.413967e+01 4.611287e-02 6.708032e-03 9.989137e-01 1.670441e+02 +9.955712e-01 8.177593e-02 -4.637626e-02 2.264302e+02 -8.190011e-02 9.966402e-01 -7.801140e-04 -2.415192e+01 4.615665e-02 4.574879e-03 9.989237e-01 1.679414e+02 +9.954441e-01 8.315092e-02 -4.665720e-02 2.263972e+02 -8.336843e-02 9.965150e-01 -2.731643e-03 -2.416913e+01 4.626747e-02 6.608935e-03 9.989072e-01 1.688348e+02 +9.951344e-01 8.603280e-02 -4.801894e-02 2.263627e+02 -8.648278e-02 9.962261e-01 -7.369059e-03 -2.418648e+01 4.720374e-02 1.148601e-02 9.988193e-01 1.697201e+02 +9.948626e-01 8.855907e-02 -4.904710e-02 2.263251e+02 -8.923556e-02 9.959409e-01 -1.177444e-02 -2.419484e+01 4.780528e-02 1.609069e-02 9.987271e-01 1.706076e+02 +9.947883e-01 8.966848e-02 -4.853728e-02 2.262918e+02 -8.997977e-02 9.959344e-01 -4.262109e-03 -2.421024e+01 4.795777e-02 8.607268e-03 9.988123e-01 1.715030e+02 +9.946502e-01 9.128469e-02 -4.835288e-02 2.262572e+02 -9.133126e-02 9.958198e-01 1.250446e-03 -2.422263e+01 4.826490e-02 3.172373e-03 9.988295e-01 1.723967e+02 +9.944223e-01 9.404680e-02 -4.774333e-02 2.262231e+02 -9.407182e-02 9.955639e-01 1.728108e-03 -2.423715e+01 4.769407e-02 2.772833e-03 9.988582e-01 1.732795e+02 +9.944104e-01 9.389211e-02 -4.829392e-02 2.261938e+02 -9.427386e-02 9.955301e-01 -5.683247e-03 -2.425287e+01 4.754444e-02 1.020433e-02 9.988170e-01 1.741564e+02 +9.945956e-01 9.163114e-02 -4.881877e-02 2.261645e+02 -9.238905e-02 9.956315e-01 -1.349635e-02 -2.426339e+01 4.736883e-02 1.793373e-02 9.987165e-01 1.750438e+02 +9.945535e-01 9.220931e-02 -4.858889e-02 2.261325e+02 -9.311835e-02 9.955135e-01 -1.678462e-02 -2.428103e+01 4.682320e-02 2.121771e-02 9.986778e-01 1.759400e+02 +9.944283e-01 9.430881e-02 -4.709815e-02 2.260977e+02 -9.503995e-02 9.953815e-01 -1.352807e-02 -2.430031e+01 4.560482e-02 1.792889e-02 9.987987e-01 1.768459e+02 +9.945799e-01 9.307440e-02 -4.634669e-02 2.260699e+02 -9.366303e-02 9.955465e-01 -1.068999e-02 -2.432091e+01 4.514533e-02 1.497302e-02 9.988682e-01 1.777575e+02 +9.946122e-01 9.304145e-02 -4.571552e-02 2.260399e+02 -9.344273e-02 9.956020e-01 -6.715485e-03 -2.433625e+01 4.488965e-02 1.095108e-02 9.989319e-01 1.786776e+02 +9.942972e-01 9.617754e-02 -4.607470e-02 2.260041e+02 -9.653813e-02 9.953132e-01 -5.660487e-03 -2.435520e+01 4.531435e-02 1.007617e-02 9.989220e-01 1.796027e+02 +9.946630e-01 9.189648e-02 -4.690972e-02 2.259670e+02 -9.246691e-02 9.956642e-01 -1.013346e-02 -2.437365e+01 4.577510e-02 1.441697e-02 9.988477e-01 1.805259e+02 +9.949111e-01 8.855378e-02 -4.806341e-02 2.259366e+02 -8.940949e-02 9.958672e-01 -1.595121e-02 -2.439292e+01 4.645224e-02 2.016736e-02 9.987169e-01 1.814463e+02 +9.950211e-01 8.740771e-02 -4.788515e-02 2.258994e+02 -8.833143e-02 9.959370e-01 -1.752197e-02 -2.441375e+01 4.615905e-02 2.166449e-02 9.986992e-01 1.823700e+02 +9.950382e-01 8.708883e-02 -4.811030e-02 2.258624e+02 -8.776970e-02 9.960658e-01 -1.222124e-02 -2.443867e+01 4.685669e-02 1.638323e-02 9.987673e-01 1.832993e+02 +9.952574e-01 8.442552e-02 -4.832293e-02 2.258239e+02 -8.491988e-02 9.963535e-01 -8.266305e-03 -2.445836e+01 4.744884e-02 1.233068e-02 9.987976e-01 1.842270e+02 +9.954660e-01 8.211926e-02 -4.799873e-02 2.257905e+02 -8.256677e-02 9.965579e-01 -7.412448e-03 -2.447804e+01 4.722481e-02 1.134194e-02 9.988199e-01 1.851470e+02 +9.953209e-01 8.447768e-02 -4.690191e-02 2.257488e+02 -8.493758e-02 9.963550e-01 -7.896867e-03 -2.449875e+01 4.606385e-02 1.184365e-02 9.988683e-01 1.860641e+02 +9.951887e-01 8.698986e-02 -4.507926e-02 2.257083e+02 -8.753133e-02 9.961098e-01 -1.017597e-02 -2.452308e+01 4.401869e-02 1.407286e-02 9.989316e-01 1.869750e+02 +9.950191e-01 8.925563e-02 -4.438986e-02 2.256664e+02 -8.991732e-02 9.958626e-01 -1.313562e-02 -2.454584e+01 4.303378e-02 1.706161e-02 9.989279e-01 1.878817e+02 +9.950062e-01 8.965368e-02 -4.387335e-02 2.256249e+02 -9.035043e-02 9.958093e-01 -1.415987e-02 -2.456671e+01 4.242001e-02 1.805313e-02 9.989368e-01 1.887919e+02 +9.952134e-01 8.753851e-02 -4.344425e-02 2.255933e+02 -8.822046e-02 9.960021e-01 -1.403237e-02 -2.458978e+01 4.204220e-02 1.779787e-02 9.989573e-01 1.896978e+02 +9.952586e-01 8.715631e-02 -4.317507e-02 2.255597e+02 -8.792647e-02 9.959941e-01 -1.626825e-02 -2.461577e+01 4.158424e-02 1.998734e-02 9.989351e-01 1.905967e+02 +9.951591e-01 8.867408e-02 -4.237000e-02 2.255282e+02 -8.946561e-02 9.958420e-01 -1.716140e-02 -2.464884e+01 4.067206e-02 2.086898e-02 9.989546e-01 1.914909e+02 +9.950581e-01 9.027179e-02 -4.135779e-02 2.254890e+02 -9.119141e-02 9.956138e-01 -2.091234e-02 -2.466894e+01 3.928859e-02 2.458046e-02 9.989255e-01 1.923800e+02 +9.946999e-01 9.470211e-02 -4.004519e-02 2.254508e+02 -9.541792e-02 9.953029e-01 -1.635386e-02 -2.468877e+01 3.830835e-02 2.008820e-02 9.990640e-01 1.932735e+02 +9.943977e-01 9.870114e-02 -3.783365e-02 2.254102e+02 -9.901298e-02 9.950652e-01 -6.454226e-03 -2.470514e+01 3.700991e-02 1.016409e-02 9.992632e-01 1.941727e+02 +9.939400e-01 1.034421e-01 -3.718924e-02 2.253764e+02 -1.036076e-01 9.946150e-01 -2.543044e-03 -2.472957e+01 3.672592e-02 6.380719e-03 9.993050e-01 1.950672e+02 +9.940055e-01 1.027091e-01 -3.746879e-02 2.253441e+02 -1.029370e-01 9.946790e-01 -4.197598e-03 -2.474063e+01 3.683829e-02 8.029358e-03 9.992890e-01 1.959592e+02 +9.938652e-01 1.037775e-01 -3.823803e-02 2.253111e+02 -1.041242e-01 9.945383e-01 -7.182234e-03 -2.475168e+01 3.728383e-02 1.111967e-02 9.992429e-01 1.968574e+02 +9.938543e-01 1.040990e-01 -3.764347e-02 2.252765e+02 -1.044572e-01 9.944998e-01 -7.672043e-03 -2.476744e+01 3.663778e-02 1.155702e-02 9.992618e-01 1.977562e+02 +9.942994e-01 9.964127e-02 -3.795114e-02 2.252553e+02 -1.001881e-01 9.948863e-01 -1.278610e-02 -2.479109e+01 3.648305e-02 1.651546e-02 9.991978e-01 1.986509e+02 +9.948912e-01 9.340998e-02 -3.828953e-02 2.252369e+02 -9.414419e-02 9.953987e-01 -1.783840e-02 -2.481270e+01 3.644707e-02 2.135200e-02 9.991075e-01 1.995433e+02 +9.952147e-01 9.021377e-02 -3.753857e-02 2.252196e+02 -9.094823e-02 9.956868e-01 -1.833677e-02 -2.484036e+01 3.572243e-02 2.166309e-02 9.991269e-01 2.004342e+02 +9.952678e-01 9.010964e-02 -3.636436e-02 2.251932e+02 -9.061099e-02 9.958094e-01 -1.237881e-02 -2.486351e+01 3.509653e-02 1.561524e-02 9.992619e-01 2.013349e+02 +9.954447e-01 8.855660e-02 -3.532080e-02 2.251686e+02 -8.881378e-02 9.960315e-01 -5.776168e-03 -2.488657e+01 3.466911e-02 8.886829e-03 9.993593e-01 2.022305e+02 +9.955729e-01 8.736246e-02 -3.467451e-02 2.251492e+02 -8.744608e-02 9.961688e-01 -8.990386e-04 -2.490668e+01 3.446312e-02 3.927208e-03 9.993983e-01 2.031210e+02 +9.956278e-01 8.712440e-02 -3.368410e-02 2.251272e+02 -8.716219e-02 9.961940e-01 3.481116e-04 -2.492103e+01 3.358623e-02 2.589390e-03 9.994325e-01 2.040068e+02 +9.955868e-01 8.789765e-02 -3.287713e-02 2.251061e+02 -8.795533e-02 9.961243e-01 -3.086901e-04 -2.493610e+01 3.272258e-02 3.199047e-03 9.994594e-01 2.048858e+02 +9.954570e-01 8.956644e-02 -3.229903e-02 2.250792e+02 -8.963369e-02 9.959746e-01 -6.365284e-04 -2.495039e+01 3.211201e-02 3.528718e-03 9.994781e-01 2.057652e+02 +9.957976e-01 8.577855e-02 -3.208186e-02 2.250655e+02 -8.606742e-02 9.962593e-01 -7.730907e-03 -2.496849e+01 3.129871e-02 1.045962e-02 9.994554e-01 2.066353e+02 +9.957566e-01 8.629235e-02 -3.197406e-02 2.250465e+02 -8.677120e-02 9.961313e-01 -1.390086e-02 -2.498807e+01 3.065083e-02 1.661630e-02 9.993920e-01 2.075007e+02 +9.958568e-01 8.539193e-02 -3.126512e-02 2.250316e+02 -8.591896e-02 9.961749e-01 -1.591736e-02 -2.501231e+01 2.978632e-02 1.853767e-02 9.993844e-01 2.083680e+02 +9.957361e-01 8.703409e-02 -3.057269e-02 2.250108e+02 -8.749675e-02 9.960645e-01 -1.413293e-02 -2.503356e+01 2.922232e-02 1.674767e-02 9.994326e-01 2.092371e+02 +9.953968e-01 9.128857e-02 -2.918292e-02 2.249857e+02 -9.163253e-02 9.957357e-01 -1.067146e-02 -2.506001e+01 2.808429e-02 1.329644e-02 9.995171e-01 2.101091e+02 +9.953034e-01 9.248500e-02 -2.859422e-02 2.249629e+02 -9.277488e-02 9.956466e-01 -8.979150e-03 -2.508558e+01 2.763931e-02 1.158980e-02 9.995508e-01 2.109723e+02 +9.949247e-01 9.623796e-02 -2.938020e-02 2.249425e+02 -9.667054e-02 9.952225e-01 -1.367220e-02 -2.510998e+01 2.792405e-02 1.644300e-02 9.994748e-01 2.118260e+02 +9.950071e-01 9.524604e-02 -2.981793e-02 2.249277e+02 -9.575042e-02 9.952773e-01 -1.596688e-02 -2.513421e+01 2.815633e-02 1.874224e-02 9.994278e-01 2.126788e+02 +9.953959e-01 9.113074e-02 -2.970326e-02 2.249072e+02 -9.150439e-02 9.957386e-01 -1.146891e-02 -2.515688e+01 2.853152e-02 1.413408e-02 9.994930e-01 2.135369e+02 +9.955781e-01 8.932825e-02 -2.906545e-02 2.248911e+02 -8.940679e-02 9.959942e-01 -1.410662e-03 -2.517915e+01 2.882301e-02 4.003073e-03 9.995765e-01 2.144004e+02 +9.956155e-01 8.936123e-02 -2.764538e-02 2.248728e+02 -8.918331e-02 9.959862e-01 7.606454e-03 -2.519699e+01 2.821414e-02 -5.107596e-03 9.995889e-01 2.152575e+02 +9.958860e-01 8.670680e-02 -2.632524e-02 2.248647e+02 -8.658656e-02 9.962281e-01 5.676444e-03 -2.521312e+01 2.671814e-02 -3.373678e-03 9.996373e-01 2.161010e+02 +9.960566e-01 8.490526e-02 -2.573486e-02 2.248513e+02 -8.498022e-02 9.963809e-01 -1.830446e-03 -2.522812e+01 2.548631e-02 4.010182e-03 9.996671e-01 2.169357e+02 +9.961272e-01 8.417295e-02 -2.540579e-02 2.248072e+02 -8.456335e-02 9.963096e-01 -1.470192e-02 -2.523897e+01 2.407453e-02 1.679338e-02 9.995691e-01 2.177499e+02 +9.959341e-01 8.662563e-02 -2.472264e-02 2.246622e+02 -8.719601e-02 9.959254e-01 -2.300670e-02 -2.522568e+01 2.262894e-02 2.506887e-02 9.994296e-01 2.185506e+02 +9.958957e-01 8.744412e-02 -2.335285e-02 2.245747e+02 -8.808572e-02 9.957186e-01 -2.802320e-02 -2.523212e+01 2.080240e-02 2.996523e-02 9.993345e-01 2.193623e+02 +9.954451e-01 9.282374e-02 -2.174570e-02 2.244594e+02 -9.323696e-02 9.954659e-01 -1.882555e-02 -2.523295e+01 1.989965e-02 2.076730e-02 9.995863e-01 2.201825e+02 +9.951047e-01 9.659179e-02 -2.089784e-02 2.243805e+02 -9.682518e-02 9.952464e-01 -1.045666e-02 -2.524319e+01 1.978847e-02 1.242891e-02 9.997269e-01 2.210103e+02 +9.947082e-01 1.005059e-01 -2.131266e-02 2.242965e+02 -1.007289e-01 9.948670e-01 -9.658798e-03 -2.525344e+01 2.023250e-02 1.175449e-02 9.997262e-01 2.218369e+02 +9.945822e-01 1.015484e-01 -2.222946e-02 2.242191e+02 -1.019011e-01 9.946761e-01 -1.534941e-02 -2.523448e+01 2.055241e-02 1.753145e-02 9.996351e-01 2.226610e+02 +9.945106e-01 1.022507e-01 -2.221435e-02 2.241346e+02 -1.026643e-01 9.945468e-01 -1.834792e-02 -2.520904e+01 2.021713e-02 2.052782e-02 9.995849e-01 2.234902e+02 +9.949562e-01 9.778028e-02 -2.238948e-02 2.240775e+02 -9.813907e-02 9.950516e-01 -1.552623e-02 -2.520462e+01 2.076053e-02 1.764520e-02 9.996288e-01 2.243358e+02 +9.951046e-01 9.604667e-02 -2.327878e-02 2.240219e+02 -9.634660e-02 9.952740e-01 -1.212115e-02 -2.520627e+01 2.200457e-02 1.430464e-02 9.996555e-01 2.251845e+02 +9.951026e-01 9.550667e-02 -2.548005e-02 2.239588e+02 -9.583246e-02 9.953265e-01 -1.188304e-02 -2.519920e+01 2.422607e-02 1.426666e-02 9.996047e-01 2.260409e+02 +9.954513e-01 9.116487e-02 -2.767190e-02 2.239126e+02 -9.152602e-02 9.957295e-01 -1.207437e-02 -2.519692e+01 2.645297e-02 1.455215e-02 9.995441e-01 2.269022e+02 +9.955357e-01 8.978773e-02 -2.910024e-02 2.238572e+02 -9.006939e-02 9.958991e-01 -8.513769e-03 -2.519628e+01 2.821647e-02 1.109680e-02 9.995402e-01 2.277720e+02 +9.953247e-01 9.192409e-02 -2.964382e-02 2.238019e+02 -9.219626e-02 9.957091e-01 -7.945485e-03 -2.520308e+01 2.878624e-02 1.064139e-02 9.995290e-01 2.286464e+02 +9.952563e-01 9.225038e-02 -3.089879e-02 2.237418e+02 -9.263595e-02 9.956361e-01 -1.128498e-02 -2.520876e+01 2.972291e-02 1.409379e-02 9.994588e-01 2.295216e+02 +9.954353e-01 8.918224e-02 -3.398831e-02 2.236972e+02 -8.986172e-02 9.957727e-01 -1.901420e-02 -2.521743e+01 3.214890e-02 2.198165e-02 9.992413e-01 2.303983e+02 +9.958616e-01 8.269260e-02 -3.770481e-02 2.236486e+02 -8.366546e-02 9.961803e-01 -2.499545e-02 -2.522792e+01 3.549386e-02 2.804660e-02 9.989763e-01 2.312837e+02 +9.961744e-01 7.636441e-02 -4.248531e-02 2.236069e+02 -7.750823e-02 9.966537e-01 -2.595774e-02 -2.525113e+01 4.036090e-02 2.915139e-02 9.987598e-01 2.321770e+02 +9.962627e-01 7.296707e-02 -4.622113e-02 2.235337e+02 -7.391660e-02 9.970800e-01 -1.917589e-02 -2.528388e+01 4.468696e-02 2.252073e-02 9.987472e-01 2.331194e+02 +9.962596e-01 7.092930e-02 -4.935395e-02 2.234648e+02 -7.160643e-02 9.973597e-01 -1.208718e-02 -2.530547e+01 4.836631e-02 1.557602e-02 9.987082e-01 2.340569e+02 +9.959607e-01 7.312819e-02 -5.210109e-02 2.233855e+02 -7.335407e-02 9.973030e-01 -2.433604e-03 -2.532335e+01 5.178261e-02 6.245601e-03 9.986389e-01 2.350030e+02 +9.957218e-01 7.466464e-02 -5.443605e-02 2.233117e+02 -7.476821e-02 9.972009e-01 1.346308e-04 -2.534086e+01 5.429374e-02 3.936032e-03 9.985173e-01 2.359431e+02 +9.956458e-01 7.428440e-02 -5.631424e-02 2.232381e+02 -7.483343e-02 9.971663e-01 -7.700949e-03 -2.535973e+01 5.558261e-02 1.188160e-02 9.983834e-01 2.368804e+02 +9.953461e-01 7.753447e-02 -5.722439e-02 2.231598e+02 -7.890441e-02 9.966377e-01 -2.207788e-02 -2.538402e+01 5.532019e-02 2.649038e-02 9.981172e-01 2.378093e+02 +9.954352e-01 7.642107e-02 -5.717097e-02 2.230911e+02 -7.825457e-02 9.964653e-01 -3.054690e-02 -2.541273e+01 5.463447e-02 3.488134e-02 9.978970e-01 2.387516e+02 +9.953655e-01 7.802357e-02 -5.621219e-02 2.230243e+02 -7.959707e-02 9.964797e-01 -2.631564e-02 -2.544458e+01 5.396107e-02 3.066800e-02 9.980720e-01 2.397102e+02 +9.953429e-01 8.081247e-02 -5.255332e-02 2.229606e+02 -8.164926e-02 9.965632e-01 -1.397189e-02 -2.547346e+01 5.124360e-02 1.819776e-02 9.985204e-01 2.406748e+02 +9.952446e-01 8.368994e-02 -4.984264e-02 2.228976e+02 -8.408600e-02 9.964410e-01 -5.898976e-03 -2.549672e+01 4.917157e-02 1.006199e-02 9.987397e-01 2.416369e+02 +9.953876e-01 8.295900e-02 -4.817956e-02 2.228426e+02 -8.310999e-02 9.965397e-01 -1.135380e-03 -2.551629e+01 4.791866e-02 5.134346e-03 9.988381e-01 2.425888e+02 +9.955996e-01 8.048282e-02 -4.799878e-02 2.227923e+02 -8.070250e-02 9.967347e-01 -2.653036e-03 -2.553324e+01 4.762853e-02 6.514983e-03 9.988439e-01 2.435350e+02 +9.952624e-01 8.436711e-02 -4.832158e-02 2.227335e+02 -8.478759e-02 9.963764e-01 -6.714994e-03 -2.556535e+01 4.757996e-02 1.078025e-02 9.988093e-01 2.444644e+02 +9.950957e-01 8.592323e-02 -4.900687e-02 2.226561e+02 -8.655440e-02 9.961875e-01 -1.090153e-02 -2.561597e+01 4.788334e-02 1.508983e-02 9.987390e-01 2.454088e+02 +9.951534e-01 8.503250e-02 -4.938773e-02 2.225887e+02 -8.562924e-02 9.962759e-01 -1.009113e-02 -2.565493e+01 4.834574e-02 1.427126e-02 9.987287e-01 2.463521e+02 +9.948818e-01 8.920502e-02 -4.746207e-02 2.225159e+02 -8.952690e-02 9.959733e-01 -4.695158e-03 -2.569419e+01 4.685213e-02 8.920259e-03 9.988620e-01 2.472975e+02 +9.940960e-01 9.846178e-02 -4.558958e-02 2.224429e+02 -9.854093e-02 9.951328e-01 5.140635e-04 -2.572481e+01 4.541831e-02 3.981411e-03 9.989601e-01 2.482386e+02 +9.941237e-01 9.845745e-02 -4.499099e-02 2.223807e+02 -9.854310e-02 9.951327e-01 3.160453e-04 -2.575264e+01 4.480312e-02 4.119363e-03 9.989874e-01 2.491701e+02 +9.943516e-01 9.584473e-02 -4.559356e-02 2.223268e+02 -9.621165e-02 9.953433e-01 -5.916954e-03 -2.578089e+01 4.481414e-02 1.027016e-02 9.989426e-01 2.500920e+02 +9.948974e-01 9.032794e-02 -4.494581e-02 2.222768e+02 -9.111920e-02 9.957134e-01 -1.587423e-02 -2.581159e+01 4.331926e-02 1.988866e-02 9.988633e-01 2.510078e+02 +9.948768e-01 9.015475e-02 -4.574258e-02 2.222215e+02 -9.123136e-02 9.955863e-01 -2.201669e-02 -2.584692e+01 4.355578e-02 2.607704e-02 9.987106e-01 2.519202e+02 +9.949081e-01 9.002190e-02 -4.531939e-02 2.221676e+02 -9.101977e-02 9.956390e-01 -2.045423e-02 -2.588078e+01 4.328043e-02 2.447503e-02 9.987631e-01 2.528409e+02 +9.952785e-01 8.578964e-02 -4.539587e-02 2.221205e+02 -8.637030e-02 9.962025e-01 -1.098383e-02 -2.591307e+01 4.428119e-02 1.485282e-02 9.989087e-01 2.537638e+02 +9.956336e-01 8.184558e-02 -4.488844e-02 2.220800e+02 -8.219623e-02 9.965980e-01 -6.018690e-03 -2.592855e+01 4.424313e-02 9.682070e-03 9.989739e-01 2.546729e+02 +9.958667e-01 7.902598e-02 -4.477057e-02 2.220355e+02 -7.936504e-02 9.968285e-01 -5.843953e-03 -2.593805e+01 4.416675e-02 9.373015e-03 9.989802e-01 2.555735e+02 +9.961754e-01 7.524622e-02 -4.441373e-02 2.219921e+02 -7.560221e-02 9.971176e-01 -6.387900e-03 -2.595191e+01 4.380505e-02 9.721244e-03 9.989928e-01 2.564728e+02 +9.965340e-01 6.998324e-02 -4.497034e-02 2.219569e+02 -7.031148e-02 9.975084e-01 -5.757059e-03 -2.596424e+01 4.445540e-02 8.899035e-03 9.989717e-01 2.573685e+02 +9.968896e-01 6.475611e-02 -4.492045e-02 2.219178e+02 -6.497104e-02 9.978815e-01 -3.339421e-03 -2.597537e+01 4.460904e-02 6.247562e-03 9.989850e-01 2.582649e+02 +9.970313e-01 6.278100e-02 -4.457820e-02 2.218749e+02 -6.282839e-02 9.980243e-01 3.387599e-04 -2.598669e+01 4.451139e-02 2.463023e-03 9.990058e-01 2.591607e+02 +9.969332e-01 6.455097e-02 -4.424206e-02 2.218291e+02 -6.457592e-02 9.979124e-01 8.669990e-04 -2.599486e+01 4.420567e-02 1.992632e-03 9.990205e-01 2.600467e+02 +9.965586e-01 7.033083e-02 -4.387001e-02 2.217842e+02 -7.058058e-02 9.974973e-01 -4.167881e-03 -2.599490e+01 4.346710e-02 7.249908e-03 9.990286e-01 2.609100e+02 +9.963494e-01 7.375244e-02 -4.299375e-02 2.217376e+02 -7.426787e-02 9.971829e-01 -1.051437e-02 -2.600009e+01 4.209718e-02 1.366904e-02 9.990200e-01 2.617787e+02 +9.961667e-01 7.685997e-02 -4.176794e-02 2.216925e+02 -7.745931e-02 9.969117e-01 -1.292270e-02 -2.600950e+01 4.064571e-02 1.610848e-02 9.990438e-01 2.626468e+02 +9.959804e-01 8.024141e-02 -3.980404e-02 2.216494e+02 -8.068083e-02 9.966942e-01 -9.555690e-03 -2.601924e+01 3.890569e-02 1.272870e-02 9.991618e-01 2.635192e+02 +9.957433e-01 8.381657e-02 -3.834130e-02 2.216068e+02 -8.404655e-02 9.964520e-01 -4.423029e-03 -2.602915e+01 3.783454e-02 7.626654e-03 9.992549e-01 2.643920e+02 +9.955629e-01 8.631868e-02 -3.746383e-02 2.215686e+02 -8.634671e-02 9.962647e-01 8.728955e-04 -2.603942e+01 3.739925e-02 2.365857e-03 9.992976e-01 2.652622e+02 +9.958759e-01 8.286859e-02 -3.693133e-02 2.215358e+02 -8.293069e-02 9.965553e-01 -1.496353e-04 -2.605195e+01 3.679171e-02 3.211759e-03 9.993178e-01 2.661245e+02 +9.962361e-01 7.839108e-02 -3.699425e-02 2.215070e+02 -7.859703e-02 9.968978e-01 -4.143308e-03 -2.606129e+01 3.655470e-02 7.035351e-03 9.993069e-01 2.669822e+02 +9.958430e-01 8.309948e-02 -3.730005e-02 2.214597e+02 -8.338723e-02 9.964978e-01 -6.222961e-03 -2.607089e+01 3.665229e-02 9.307439e-03 9.992847e-01 2.678397e+02 +9.954093e-01 8.776688e-02 -3.817531e-02 2.214146e+02 -8.790786e-02 9.961265e-01 -2.026574e-03 -2.608155e+01 3.784958e-02 5.373180e-03 9.992690e-01 2.686964e+02 +9.952746e-01 8.899538e-02 -3.883758e-02 2.213746e+02 -8.879906e-02 9.960266e-01 6.754789e-03 -2.609141e+01 3.928441e-02 -3.274128e-03 9.992227e-01 2.695508e+02 +9.952314e-01 8.909339e-02 -3.970951e-02 2.213362e+02 -8.878162e-02 9.960053e-01 9.550830e-03 -2.610097e+01 4.040180e-02 -5.979809e-03 9.991656e-01 2.703818e+02 +9.949526e-01 9.190760e-02 -4.027848e-02 2.212905e+02 -9.173906e-02 9.957649e-01 6.017332e-03 -2.611161e+01 4.066094e-02 -2.291849e-03 9.991704e-01 2.711930e+02 +9.941692e-01 9.948896e-02 -4.158689e-02 2.212383e+02 -9.959843e-02 9.950275e-01 -5.632060e-04 -2.612368e+01 4.132407e-02 4.701911e-03 9.991347e-01 2.719854e+02 +9.933183e-01 1.079575e-01 -4.079114e-02 2.211897e+02 -1.081928e-01 9.941234e-01 -3.600575e-03 -2.615009e+01 4.016272e-02 7.989826e-03 9.991612e-01 2.727662e+02 +9.930009e-01 1.115221e-01 -3.888587e-02 2.211536e+02 -1.118026e-01 9.937173e-01 -5.107660e-03 -2.618591e+01 3.807194e-02 9.419452e-03 9.992306e-01 2.735319e+02 +9.929632e-01 1.128162e-01 -3.600723e-02 2.211215e+02 -1.130491e-01 9.935792e-01 -4.491151e-03 -2.621226e+01 3.526937e-02 8.530132e-03 9.993414e-01 2.742770e+02 +9.927167e-01 1.160601e-01 -3.230552e-02 2.210880e+02 -1.162685e-01 9.932069e-01 -4.641858e-03 -2.623041e+01 3.154734e-02 8.364164e-03 9.994673e-01 2.750020e+02 +9.925107e-01 1.189613e-01 -2.776053e-02 2.210613e+02 -1.189968e-01 9.928945e-01 3.763199e-04 -2.625383e+01 2.760805e-02 2.929912e-03 9.996145e-01 2.757094e+02 +9.921916e-01 1.226407e-01 -2.269402e-02 2.210366e+02 -1.225133e-01 9.924427e-01 6.927653e-03 -2.627829e+01 2.337212e-02 -4.093240e-03 9.997185e-01 2.763934e+02 +9.926441e-01 1.199496e-01 -1.642783e-02 2.210264e+02 -1.198941e-01 9.927772e-01 4.330786e-03 -2.629921e+01 1.682865e-02 -2.329329e-03 9.998557e-01 2.770456e+02 +9.933881e-01 1.144665e-01 -8.808244e-03 2.210267e+02 -1.144973e-01 9.934188e-01 -3.065532e-03 -2.632020e+01 8.399375e-03 4.053782e-03 9.999565e-01 2.776727e+02 +9.941722e-01 1.077923e-01 -1.574057e-03 2.210397e+02 -1.078030e-01 9.941156e-01 -1.060888e-02 -2.634203e+01 4.212390e-04 1.071674e-02 9.999425e-01 2.782803e+02 +9.947272e-01 1.022256e-01 8.230413e-03 2.210490e+02 -1.021159e-01 9.946901e-01 -1.279908e-02 -2.635691e+01 -9.495105e-03 1.189114e-02 9.998842e-01 2.788723e+02 +9.946739e-01 1.015499e-01 1.764946e-02 2.210704e+02 -1.013418e-01 9.947755e-01 -1.231008e-02 -2.638462e+01 -1.880734e-02 1.045588e-02 9.997685e-01 2.794464e+02 +9.950264e-01 9.613394e-02 2.608917e-02 2.210945e+02 -9.594545e-02 9.953512e-01 -8.386755e-03 -2.640789e+01 -2.677414e-02 5.841905e-03 9.996244e-01 2.800031e+02 +9.952674e-01 9.102660e-02 3.401426e-02 2.211296e+02 -9.091047e-02 9.958467e-01 -4.949255e-03 -2.643095e+01 -3.432351e-02 1.833580e-03 9.994091e-01 2.805433e+02 +9.954772e-01 8.476584e-02 4.289375e-02 2.211608e+02 -8.464178e-02 9.964003e-01 -4.703874e-03 -2.644971e+01 -4.313808e-02 1.051997e-03 9.990686e-01 2.810710e+02 +9.950463e-01 8.610033e-02 4.969607e-02 2.211890e+02 -8.586185e-02 9.962830e-01 -6.918256e-03 -2.647118e+01 -5.010702e-02 2.616988e-03 9.987404e-01 2.815877e+02 +9.946724e-01 8.545552e-02 5.765654e-02 2.212199e+02 -8.510628e-02 9.963357e-01 -8.490617e-03 -2.648598e+01 -5.817084e-02 3.538448e-03 9.983004e-01 2.821002e+02 +9.948475e-01 7.877304e-02 6.382290e-02 2.212595e+02 -7.822395e-02 9.968744e-01 -1.106118e-02 -2.649387e+01 -6.449474e-02 6.011708e-03 9.978999e-01 2.826034e+02 +9.954416e-01 6.879267e-02 6.605799e-02 2.213046e+02 -6.770019e-02 9.975316e-01 -1.863968e-02 -2.649412e+01 -6.717721e-02 1.408258e-02 9.976417e-01 2.830924e+02 +9.959335e-01 6.097990e-02 6.631673e-02 2.213444e+02 -5.934658e-02 9.978902e-01 -2.632830e-02 -2.648889e+01 -6.778231e-02 2.228556e-02 9.974512e-01 2.835723e+02 +9.958063e-01 6.409333e-02 6.528273e-02 2.213652e+02 -6.222914e-02 9.976048e-01 -3.020191e-02 -2.649441e+01 -6.706211e-02 2.601276e-02 9.974097e-01 2.840469e+02 +9.953598e-01 7.302941e-02 6.265452e-02 2.213725e+02 -7.128075e-02 9.970138e-01 -2.970818e-02 -2.650472e+01 -6.463699e-02 2.510426e-02 9.975930e-01 2.845208e+02 +9.955186e-01 7.568449e-02 5.669659e-02 2.213833e+02 -7.404193e-02 9.967875e-01 -3.053549e-02 -2.651272e+01 -5.882552e-02 2.620072e-02 9.979244e-01 2.849828e+02 +9.966129e-01 6.560327e-02 4.958799e-02 2.214089e+02 -6.428561e-02 9.975465e-01 -2.771762e-02 -2.652139e+01 -5.128470e-02 2.443594e-02 9.983851e-01 2.854348e+02 +9.976148e-01 5.524013e-02 4.139072e-02 2.214299e+02 -5.437007e-02 9.982815e-01 -2.186059e-02 -2.653457e+01 -4.252717e-02 1.955803e-02 9.989039e-01 2.858763e+02 +9.981535e-01 5.195074e-02 3.147523e-02 2.214273e+02 -5.139908e-02 9.985143e-01 -1.809033e-02 -2.655072e+01 -3.236827e-02 1.643913e-02 9.993408e-01 2.862975e+02 +9.983608e-01 5.409378e-02 1.869702e-02 2.214169e+02 -5.377901e-02 9.984090e-01 -1.694805e-02 -2.656648e+01 -1.958406e-02 1.591476e-02 9.996816e-01 2.867106e+02 +9.983076e-01 5.801448e-02 4.027802e-03 2.213891e+02 -5.794288e-02 9.981906e-01 -1.606444e-02 -2.657637e+01 -4.952484e-03 1.580386e-02 9.998629e-01 2.871106e+02 +9.979583e-01 6.281193e-02 -1.157520e-02 2.213554e+02 -6.299733e-02 9.978787e-01 -1.641499e-02 -2.658629e+01 1.051959e-02 1.711068e-02 9.997983e-01 2.875054e+02 +9.974617e-01 6.507622e-02 -2.889974e-02 2.213173e+02 -6.561506e-02 9.976807e-01 -1.810393e-02 -2.659453e+01 2.765458e-02 1.995423e-02 9.994184e-01 2.878929e+02 +9.970601e-01 5.953666e-02 -4.823343e-02 2.212822e+02 -6.067321e-02 9.979051e-01 -2.245076e-02 -2.660796e+01 4.679575e-02 2.531123e-02 9.985838e-01 2.882563e+02 +9.961569e-01 5.443175e-02 -6.861966e-02 2.212431e+02 -5.617276e-02 9.981397e-01 -2.370132e-02 -2.661818e+01 6.720190e-02 2.746478e-02 9.973613e-01 2.886258e+02 +9.943901e-01 5.312896e-02 -9.146346e-02 2.211921e+02 -5.538280e-02 9.982165e-01 -2.228091e-02 -2.661626e+01 9.011658e-02 2.722141e-02 9.955591e-01 2.889894e+02 +9.914269e-01 5.462799e-02 -1.186954e-01 2.211138e+02 -5.728836e-02 9.981746e-01 -1.911556e-02 -2.660786e+01 1.174345e-01 2.575154e-02 9.927467e-01 2.893250e+02 +9.874631e-01 5.276239e-02 -1.487712e-01 2.210366e+02 -5.585816e-02 9.982989e-01 -1.670494e-02 -2.660346e+01 1.476367e-01 2.480559e-02 9.887306e-01 2.896787e+02 +9.821902e-01 5.217791e-02 -1.804992e-01 2.209318e+02 -5.553745e-02 9.983639e-01 -1.360552e-02 -2.659651e+01 1.794940e-01 2.338767e-02 9.834810e-01 2.899919e+02 +9.751143e-01 5.721805e-02 -2.141922e-01 2.208261e+02 -6.075220e-02 9.981033e-01 -9.948066e-03 -2.659892e+01 2.132167e-01 2.271314e-02 9.767409e-01 2.903287e+02 +9.666897e-01 6.432914e-02 -2.477352e-01 2.207061e+02 -6.817975e-02 9.976486e-01 -6.986382e-03 -2.660233e+01 2.467032e-01 2.364418e-02 9.688026e-01 2.906520e+02 +9.576578e-01 6.614365e-02 -2.802081e-01 2.205646e+02 -6.941713e-02 9.975861e-01 -1.762458e-03 -2.660356e+01 2.794152e-01 2.113907e-02 9.599377e-01 2.909433e+02 +9.479393e-01 6.231670e-02 -3.122944e-01 2.204599e+02 -6.525851e-02 9.978678e-01 1.033442e-03 -2.660157e+01 3.116930e-01 1.940023e-02 9.499848e-01 2.912493e+02 +9.372898e-01 5.754222e-02 -3.437685e-01 2.203421e+02 -5.961399e-02 9.982111e-01 4.548739e-03 -2.659955e+01 3.434153e-01 1.622992e-02 9.390434e-01 2.915531e+02 +9.251704e-01 5.966916e-02 -3.748324e-01 2.201904e+02 -6.092109e-02 9.981062e-01 8.520567e-03 -2.659079e+01 3.746310e-01 1.495222e-02 9.270534e-01 2.918198e+02 +9.124134e-01 6.249084e-02 -4.044709e-01 2.200358e+02 -6.315014e-02 9.979351e-01 1.172591e-02 -2.658278e+01 4.043685e-01 1.484352e-02 9.144757e-01 2.921086e+02 +8.980231e-01 6.603477e-02 -4.349642e-01 2.198538e+02 -6.569848e-02 9.977139e-01 1.582904e-02 -2.657109e+01 4.350151e-01 1.436164e-02 9.003086e-01 2.923646e+02 +8.827658e-01 6.793718e-02 -4.648753e-01 2.196736e+02 -6.623480e-02 9.976033e-01 2.001516e-02 -2.656343e+01 4.651210e-01 1.312223e-02 8.851499e-01 2.926572e+02 +8.665090e-01 6.825986e-02 -4.944723e-01 2.194881e+02 -6.453530e-02 9.976115e-01 2.462509e-02 -2.655711e+01 4.949722e-01 1.057305e-02 8.688445e-01 2.929522e+02 +8.484403e-01 6.742031e-02 -5.249796e-01 2.192699e+02 -6.158052e-02 9.976921e-01 2.860554e-02 -2.654557e+01 5.256967e-01 8.058428e-03 8.506339e-01 2.932127e+02 +8.290786e-01 6.530632e-02 -5.553051e-01 2.190540e+02 -5.690180e-02 9.978540e-01 3.239684e-02 -2.653316e+01 5.562292e-01 4.738341e-03 8.310154e-01 2.935127e+02 +8.080432e-01 6.689005e-02 -5.853135e-01 2.188190e+02 -5.615908e-02 9.977546e-01 3.649482e-02 -2.652246e+01 5.864404e-01 3.381279e-03 8.099853e-01 2.938092e+02 +7.857266e-01 6.967230e-02 -6.146377e-01 2.185381e+02 -5.732442e-02 9.975620e-01 3.979765e-02 -2.650679e+01 6.159121e-01 3.963680e-03 7.878050e-01 2.940653e+02 +7.620374e-01 6.963475e-02 -6.437779e-01 2.182805e+02 -5.732158e-02 9.975521e-01 4.004970e-02 -2.650256e+01 6.449909e-01 6.382995e-03 7.641637e-01 2.943519e+02 +7.366276e-01 6.718029e-02 -6.729536e-01 2.179756e+02 -5.414331e-02 9.977182e-01 4.033495e-02 -2.649296e+01 6.741278e-01 6.724097e-03 7.385841e-01 2.946013e+02 +7.089279e-01 6.271944e-02 -7.024867e-01 2.176868e+02 -4.864616e-02 9.980143e-01 4.001256e-02 -2.648151e+01 7.036013e-01 5.807262e-03 7.105712e-01 2.948898e+02 +6.795646e-01 5.954431e-02 -7.311952e-01 2.173714e+02 -4.303782e-02 9.982198e-01 4.129040e-02 -2.646745e+01 7.323522e-01 3.409554e-03 6.809175e-01 2.951773e+02 +6.481543e-01 5.912750e-02 -7.592101e-01 2.170134e+02 -3.821423e-02 9.982504e-01 4.511973e-02 -2.644998e+01 7.605496e-01 -2.319173e-04 6.492798e-01 2.954025e+02 +6.150832e-01 6.117217e-02 -7.860856e-01 2.166577e+02 -3.532068e-02 9.981227e-01 5.003550e-02 -2.644186e+01 7.876707e-01 -3.010914e-03 6.160891e-01 2.956814e+02 +5.797847e-01 6.218139e-02 -8.123935e-01 2.162844e+02 -3.195263e-02 9.980518e-01 5.358809e-02 -2.642940e+01 8.141430e-01 -5.111445e-03 5.806420e-01 2.959511e+02 +5.420836e-01 6.151184e-02 -8.380702e-01 2.158598e+02 -2.698293e-02 9.980771e-01 5.580268e-02 -2.641463e+01 8.398913e-01 -7.636120e-03 5.427010e-01 2.961526e+02 +5.023417e-01 6.151341e-02 -8.624783e-01 2.154445e+02 -2.182407e-02 9.980505e-01 5.847146e-02 -2.639962e+01 8.643938e-01 -1.054986e-02 5.027049e-01 2.964001e+02 +4.604652e-01 6.221686e-02 -8.854947e-01 2.149725e+02 -1.673447e-02 9.979718e-01 6.141770e-02 -2.638138e+01 8.875201e-01 -1.346242e-02 4.605724e-01 2.965646e+02 +4.155418e-01 6.075807e-02 -9.075425e-01 2.145186e+02 -9.439275e-03 9.980008e-01 6.249206e-02 -2.635939e+01 9.095251e-01 -1.740151e-02 4.152845e-01 2.967817e+02 +3.684595e-01 5.869061e-02 -9.277893e-01 2.140428e+02 -2.958900e-03 9.980741e-01 6.196166e-02 -2.633314e+01 9.296391e-01 -2.008512e-02 3.679236e-01 2.969808e+02 +3.203183e-01 5.776158e-02 -9.455473e-01 2.134917e+02 9.022592e-04 9.981203e-01 6.127882e-02 -2.630131e+01 9.473096e-01 -2.048185e-02 3.196641e-01 2.970871e+02 +2.723068e-01 5.883282e-02 -9.604102e-01 2.129560e+02 3.110503e-03 9.980699e-01 6.202172e-02 -2.627272e+01 9.622055e-01 -1.987629e-02 2.715982e-01 2.972401e+02 +2.253825e-01 6.052327e-02 -9.723886e-01 2.123926e+02 5.077658e-03 9.979820e-01 6.329317e-02 -2.624419e+01 9.742572e-01 -1.920262e-02 2.246203e-01 2.973672e+02 +1.797233e-01 6.174018e-02 -9.817778e-01 2.117755e+02 7.863551e-03 9.979064e-01 6.419396e-02 -2.621345e+01 9.836858e-01 -1.925741e-02 1.788616e-01 2.974165e+02 +1.368299e-01 6.217035e-02 -9.886417e-01 2.111584e+02 1.005525e-02 9.978900e-01 6.414361e-02 -2.617867e+01 9.905436e-01 -1.871780e-02 1.359160e-01 2.974991e+02 +9.792495e-02 6.237635e-02 -9.932371e-01 2.104968e+02 1.107691e-02 9.979037e-01 6.376153e-02 -2.614249e+01 9.951322e-01 -1.724584e-02 9.702873e-02 2.975228e+02 +6.378872e-02 6.235146e-02 -9.960137e-01 2.098305e+02 9.559437e-03 9.979623e-01 6.308569e-02 -2.610405e+01 9.979177e-01 -1.354548e-02 6.306270e-02 2.975567e+02 +3.473496e-02 6.195976e-02 -9.974740e-01 2.091421e+02 7.273149e-03 9.980342e-01 6.224784e-02 -2.606580e+01 9.993701e-01 -9.416948e-03 3.421604e-02 2.975664e+02 +1.088238e-02 6.092958e-02 -9.980827e-01 2.084226e+02 5.923456e-03 9.981204e-01 6.099647e-02 -2.602820e+01 9.999233e-01 -6.575881e-03 1.050102e-02 2.975505e+02 +-7.935388e-03 6.061203e-02 -9.981298e-01 2.076834e+02 3.741130e-03 9.981561e-01 6.058390e-02 -2.598658e+01 9.999615e-01 -3.253372e-03 -8.147512e-03 2.975371e+02 +-2.191954e-02 6.089520e-02 -9.979034e-01 2.069180e+02 1.189238e-03 9.981441e-01 6.088378e-02 -2.594500e+01 9.997591e-01 1.478035e-04 -2.195128e-02 2.975101e+02 +-2.992367e-02 6.123745e-02 -9.976746e-01 2.061312e+02 -1.197059e-03 9.981186e-01 6.130063e-02 -2.590111e+01 9.995515e-01 3.028619e-03 -2.979407e-02 2.974834e+02 +-3.404375e-02 6.124577e-02 -9.975420e-01 2.053290e+02 -3.503140e-03 9.981071e-01 6.140004e-02 -2.586040e+01 9.994142e-01 5.584820e-03 -3.376476e-02 2.974471e+02 +-3.418436e-02 6.109447e-02 -9.975464e-01 2.045015e+02 -5.479960e-03 9.981033e-01 6.131638e-02 -2.581617e+01 9.994006e-01 7.562579e-03 -3.378473e-02 2.974160e+02 +-3.257365e-02 6.130327e-02 -9.975875e-01 2.036512e+02 -7.412044e-03 9.980749e-01 6.157526e-02 -2.577016e+01 9.994419e-01 9.399895e-03 -3.205656e-02 2.973864e+02 +-3.103488e-02 6.193435e-02 -9.975976e-01 2.027745e+02 -7.286247e-03 9.980378e-01 6.218836e-02 -2.572014e+01 9.994918e-01 9.198754e-03 -3.052271e-02 2.973631e+02 +-2.963625e-02 5.938204e-02 -9.977953e-01 2.018887e+02 -6.043604e-03 9.982049e-01 5.958594e-02 -2.567721e+01 9.995425e-01 7.796186e-03 -2.922416e-02 2.973349e+02 +-2.866084e-02 5.389761e-02 -9.981350e-01 2.009763e+02 -5.079236e-03 9.985245e-01 5.406450e-02 -2.563333e+01 9.995763e-01 6.619301e-03 -2.834479e-02 2.973106e+02 +-2.735849e-02 4.892055e-02 -9.984279e-01 2.000445e+02 -4.511197e-03 9.987855e-01 4.906170e-02 -2.558821e+01 9.996155e-01 5.846362e-03 -2.710458e-02 2.972827e+02 +-2.639869e-02 4.787566e-02 -9.985044e-01 1.990790e+02 -5.771576e-03 9.988285e-01 4.804381e-02 -2.554149e+01 9.996349e-01 7.031240e-03 -2.609144e-02 2.972592e+02 +-2.514256e-02 5.102513e-02 -9.983808e-01 1.980890e+02 -5.707983e-03 9.986729e-01 5.118382e-02 -2.549820e+01 9.996676e-01 6.985636e-03 -2.481795e-02 2.972348e+02 +-2.398848e-02 5.334859e-02 -9.982878e-01 1.970841e+02 -5.296941e-03 9.985543e-01 5.349013e-02 -2.545103e+01 9.996982e-01 6.571022e-03 -2.367121e-02 2.972129e+02 +-2.326979e-02 5.374513e-02 -9.982835e-01 1.960537e+02 -4.684696e-03 9.985371e-01 5.386799e-02 -2.540193e+01 9.997183e-01 5.930154e-03 -2.298396e-02 2.971905e+02 +-2.396559e-02 5.301046e-02 -9.983063e-01 1.949976e+02 -3.770006e-03 9.985812e-01 5.311558e-02 -2.534979e+01 9.997057e-01 5.036570e-03 -2.373173e-02 2.971696e+02 +-2.541801e-02 5.206896e-02 -9.983199e-01 1.939222e+02 -3.185106e-03 9.986333e-01 5.216641e-02 -2.529675e+01 9.996719e-01 4.505724e-03 -2.521742e-02 2.971463e+02 +-2.688753e-02 5.343089e-02 -9.982095e-01 1.928182e+02 -2.183509e-03 9.985650e-01 5.350874e-02 -2.524202e+01 9.996361e-01 3.618320e-03 -2.673227e-02 2.971227e+02 +-2.839320e-02 5.512163e-02 -9.980758e-01 1.917022e+02 -2.711805e-03 9.984705e-01 5.522058e-02 -2.519060e+01 9.995932e-01 4.274479e-03 -2.820029e-02 2.970881e+02 +-3.045515e-02 5.658987e-02 -9.979329e-01 1.905704e+02 -1.512151e-03 9.983922e-01 5.666208e-02 -2.513757e+01 9.995350e-01 3.234681e-03 -3.032061e-02 2.970514e+02 +-3.310525e-02 5.747592e-02 -9.977978e-01 1.894234e+02 -2.647819e-03 9.983365e-01 5.759481e-02 -2.508224e+01 9.994484e-01 4.548682e-03 -3.289800e-02 2.970132e+02 +-3.489149e-02 5.775964e-02 -9.977206e-01 1.882594e+02 -1.969029e-03 9.983225e-01 5.786336e-02 -2.502517e+01 9.993892e-01 3.983483e-03 -3.471923e-02 2.969729e+02 +-3.620433e-02 5.806401e-02 -9.976561e-01 1.870780e+02 -3.324755e-03 9.982981e-01 5.822204e-02 -2.496601e+01 9.993389e-01 5.424855e-03 -3.594966e-02 2.969321e+02 +-3.713883e-02 5.736309e-02 -9.976623e-01 1.858938e+02 -5.956946e-03 9.983206e-01 5.762271e-02 -2.491152e+01 9.992924e-01 8.083063e-03 -3.673475e-02 2.968808e+02 +-3.773426e-02 5.590839e-02 -9.977226e-01 1.846876e+02 -6.026671e-03 9.984028e-01 5.617445e-02 -2.485358e+01 9.992697e-01 8.132650e-03 -3.733705e-02 2.968369e+02 +-3.874146e-02 5.608581e-02 -9.976740e-01 1.834694e+02 -7.357174e-03 9.983805e-01 5.641124e-02 -2.479616e+01 9.992222e-01 9.525518e-03 -3.826609e-02 2.967881e+02 +-3.934471e-02 5.753466e-02 -9.975679e-01 1.822301e+02 -6.368469e-03 9.983062e-01 5.782843e-02 -2.473612e+01 9.992054e-01 8.628225e-03 -3.891166e-02 2.967444e+02 +-4.057243e-02 5.919137e-02 -9.974218e-01 1.809913e+02 -5.210967e-03 9.982176e-01 5.945058e-02 -2.467877e+01 9.991630e-01 7.609589e-03 -4.019167e-02 2.966975e+02 +-4.244523e-02 6.076190e-02 -9.972494e-01 1.797495e+02 -3.491645e-03 9.981338e-01 6.096442e-02 -2.462195e+01 9.990927e-01 6.069692e-03 -4.215386e-02 2.966500e+02 +-4.472416e-02 6.369686e-02 -9.969666e-01 1.785095e+02 -2.008678e-03 9.979574e-01 6.385029e-02 -2.456446e+01 9.989974e-01 4.858239e-03 -4.450486e-02 2.965995e+02 +-4.690801e-02 6.832987e-02 -9.965594e-01 1.772620e+02 -1.747581e-03 9.976505e-01 6.848696e-02 -2.450284e+01 9.988977e-01 4.954159e-03 -4.667839e-02 2.965458e+02 +-4.857064e-02 7.242985e-02 -9.961901e-01 1.760212e+02 -3.274429e-03 9.973504e-01 7.267387e-02 -2.444027e+01 9.988144e-01 6.791773e-03 -4.820478e-02 2.964882e+02 +-4.920967e-02 7.358469e-02 -9.960741e-01 1.747870e+02 -3.968955e-03 9.972601e-01 7.386840e-02 -2.437401e+01 9.987806e-01 7.588416e-03 -4.878278e-02 2.964319e+02 +-4.919912e-02 7.308314e-02 -9.961116e-01 1.735584e+02 -6.133652e-03 9.972784e-01 7.347172e-02 -2.430885e+01 9.987702e-01 9.724548e-03 -4.861696e-02 2.963749e+02 +-4.840658e-02 7.191364e-02 -9.962355e-01 1.723362e+02 -7.244668e-03 9.973532e-01 7.234635e-02 -2.424344e+01 9.988015e-01 1.071944e-02 -4.775746e-02 2.963194e+02 +-4.752543e-02 7.067006e-02 -9.963669e-01 1.711172e+02 -7.594370e-03 9.974397e-01 7.110840e-02 -2.418387e+01 9.988412e-01 1.094624e-02 -4.686706e-02 2.962819e+02 +-4.670153e-02 7.129327e-02 -9.963615e-01 1.699192e+02 -6.613714e-03 9.974059e-01 7.167802e-02 -2.414011e+01 9.988870e-01 9.937125e-03 -4.610887e-02 2.962776e+02 +-4.664180e-02 7.228460e-02 -9.962929e-01 1.687176e+02 -5.051360e-03 9.973485e-01 7.259769e-02 -2.409065e+01 9.988989e-01 8.418723e-03 -4.615299e-02 2.962603e+02 +-4.686382e-02 7.188464e-02 -9.963114e-01 1.675243e+02 -4.974589e-03 9.973781e-01 7.219561e-02 -2.404498e+01 9.988889e-01 8.339604e-03 -4.638335e-02 2.962446e+02 +-4.749436e-02 7.081353e-02 -9.963582e-01 1.663171e+02 -5.576406e-03 9.974495e-01 7.115693e-02 -2.399076e+01 9.988560e-01 8.935653e-03 -4.697834e-02 2.962156e+02 +-4.741995e-02 7.037855e-02 -9.963926e-01 1.651223e+02 -4.985323e-03 9.974856e-01 7.069304e-02 -2.394119e+01 9.988626e-01 8.319602e-03 -4.694986e-02 2.961930e+02 +-4.734356e-02 7.042134e-02 -9.963932e-01 1.639115e+02 -5.726262e-03 9.974762e-01 7.076999e-02 -2.389302e+01 9.988623e-01 9.056114e-03 -4.682083e-02 2.961802e+02 +-4.683670e-02 7.010236e-02 -9.964396e-01 1.627111e+02 -4.317647e-03 9.975108e-01 7.038068e-02 -2.384997e+01 9.988933e-01 7.598676e-03 -4.641744e-02 2.961770e+02 +-4.644319e-02 7.049722e-02 -9.964302e-01 1.615191e+02 -3.636112e-03 9.974880e-01 7.074156e-02 -2.379382e+01 9.989143e-01 6.908598e-03 -4.607019e-02 2.961581e+02 +-4.564088e-02 7.005274e-02 -9.964986e-01 1.603331e+02 -3.391244e-03 9.975215e-01 7.027999e-02 -2.373873e+01 9.989522e-01 6.587014e-03 -4.529020e-02 2.961418e+02 +-4.465969e-02 7.280037e-02 -9.963461e-01 1.591347e+02 -2.711155e-03 9.973287e-01 7.299371e-02 -2.367784e+01 9.989986e-01 5.961128e-03 -4.434301e-02 2.961199e+02 +-4.350631e-02 7.159972e-02 -9.964841e-01 1.579438e+02 -5.877368e-03 9.973929e-01 7.192164e-02 -2.361986e+01 9.990359e-01 8.985752e-03 -4.297207e-02 2.960927e+02 +-4.258321e-02 6.733086e-02 -9.968215e-01 1.567608e+02 -4.818032e-03 9.977011e-01 6.759610e-02 -2.356414e+01 9.990813e-01 7.681180e-03 -4.216091e-02 2.960685e+02 +-4.218703e-02 6.589100e-02 -9.969346e-01 1.555711e+02 -7.278393e-03 9.977762e-01 6.625463e-02 -2.350892e+01 9.990833e-01 1.005117e-02 -4.161363e-02 2.960378e+02 +-4.128836e-02 6.911790e-02 -9.967537e-01 1.543804e+02 -8.218308e-03 9.975471e-01 6.951337e-02 -2.345432e+01 9.991135e-01 1.106172e-02 -4.061905e-02 2.960104e+02 +-4.084484e-02 7.127954e-02 -9.966197e-01 1.531898e+02 -7.640720e-03 9.974006e-01 7.164855e-02 -2.339628e+01 9.991363e-01 1.054137e-02 -4.019405e-02 2.959838e+02 +-4.031288e-02 6.839462e-02 -9.968435e-01 1.520077e+02 -6.414034e-03 9.976162e-01 6.870704e-02 -2.333921e+01 9.991666e-01 9.163569e-03 -3.977810e-02 2.959605e+02 +-3.981578e-02 6.180774e-02 -9.972936e-01 1.508273e+02 -5.118996e-03 9.980593e-01 6.205958e-02 -2.328421e+01 9.991940e-01 7.576096e-03 -3.942211e-02 2.959315e+02 +-3.936633e-02 6.030525e-02 -9.974034e-01 1.496514e+02 -5.317999e-03 9.981503e-01 6.056032e-02 -2.323690e+01 9.992107e-01 7.688231e-03 -3.897281e-02 2.959025e+02 +-3.900840e-02 6.157832e-02 -9.973397e-01 1.484680e+02 -5.620827e-03 9.980700e-01 6.184327e-02 -2.318917e+01 9.992231e-01 8.018283e-03 -3.858699e-02 2.958732e+02 +-3.879098e-02 6.257344e-02 -9.972862e-01 1.472897e+02 -5.774448e-03 9.980067e-01 6.284327e-02 -2.314010e+01 9.992307e-01 8.196532e-03 -3.835233e-02 2.958451e+02 +-3.849359e-02 6.268958e-02 -9.972904e-01 1.461169e+02 -5.431934e-03 9.980023e-01 6.294400e-02 -2.308963e+01 9.992441e-01 7.840159e-03 -3.807616e-02 2.958169e+02 +-3.822691e-02 6.266006e-02 -9.973026e-01 1.449466e+02 -6.409697e-03 9.979961e-01 6.294934e-02 -2.304192e+01 9.992486e-01 8.798768e-03 -3.774867e-02 2.957849e+02 +-3.795869e-02 6.371333e-02 -9.972461e-01 1.437757e+02 -7.116098e-03 9.979227e-01 6.402745e-02 -2.299188e+01 9.992540e-01 9.526901e-03 -3.742645e-02 2.957541e+02 +-3.766763e-02 6.453963e-02 -9.972040e-01 1.426078e+02 -6.714267e-03 9.978733e-01 6.483659e-02 -2.294093e+01 9.992678e-01 9.137737e-03 -3.715419e-02 2.957256e+02 +-3.769540e-02 6.415943e-02 -9.972275e-01 1.414441e+02 -6.712927e-03 9.978979e-01 6.445633e-02 -2.288937e+01 9.992668e-01 9.124024e-03 -3.718546e-02 2.956979e+02 +-3.788084e-02 6.381313e-02 -9.972426e-01 1.402861e+02 -6.560512e-03 9.979215e-01 6.410579e-02 -2.283904e+01 9.992608e-01 8.970806e-03 -3.738346e-02 2.956682e+02 +-3.799933e-02 6.373373e-02 -9.972432e-01 1.391310e+02 -6.073907e-03 9.979308e-01 6.400913e-02 -2.279083e+01 9.992593e-01 8.489470e-03 -3.753359e-02 2.956382e+02 +-3.830434e-02 6.335669e-02 -9.972556e-01 1.379756e+02 -5.792121e-03 9.979571e-01 6.362375e-02 -2.273973e+01 9.992494e-01 8.213294e-03 -3.785912e-02 2.956091e+02 +-3.913798e-02 6.347298e-02 -9.972158e-01 1.368000e+02 -5.126749e-03 9.979545e-01 6.372123e-02 -2.271393e+01 9.992207e-01 7.606398e-03 -3.873252e-02 2.955894e+02 +-4.025216e-02 6.326256e-02 -9.971848e-01 1.356315e+02 -4.708134e-03 9.979706e-01 6.350247e-02 -2.267745e+01 9.991785e-01 7.250994e-03 -3.987262e-02 2.955668e+02 +-4.182804e-02 6.299243e-02 -9.971371e-01 1.344746e+02 -3.112206e-03 9.979974e-01 6.317735e-02 -2.264690e+01 9.991200e-01 5.745884e-03 -4.154823e-02 2.955361e+02 +-4.396326e-02 6.566130e-02 -9.968730e-01 1.333247e+02 -2.515797e-03 9.978273e-01 6.583512e-02 -2.260493e+01 9.990300e-01 5.402260e-03 -4.370256e-02 2.954893e+02 +-4.656022e-02 7.111737e-02 -9.963807e-01 1.321713e+02 -1.739726e-03 9.974551e-01 7.127537e-02 -2.255580e+01 9.989140e-01 5.052030e-03 -4.631801e-02 2.954377e+02 +-5.016892e-02 7.500698e-02 -9.959202e-01 1.310215e+02 -9.420343e-04 9.971719e-01 7.514872e-02 -2.250094e+01 9.987403e-01 4.708324e-03 -4.995637e-02 2.953872e+02 +-5.494665e-02 7.559289e-02 -9.956237e-01 1.298741e+02 8.902629e-05 9.971304e-01 7.570239e-02 -2.243805e+01 9.984893e-01 4.070960e-03 -5.479571e-02 2.953314e+02 +-6.097882e-02 7.481346e-02 -9.953314e-01 1.287258e+02 -1.684477e-03 9.971779e-01 7.505547e-02 -2.237108e+01 9.981377e-01 6.253410e-03 -6.068071e-02 2.952589e+02 +-6.755454e-02 7.257951e-02 -9.950721e-01 1.275848e+02 -2.737498e-03 9.973333e-01 7.293030e-02 -2.230840e+01 9.977119e-01 7.650784e-03 -6.717570e-02 2.951852e+02 +-7.452431e-02 6.988645e-02 -9.947673e-01 1.264523e+02 -4.326375e-03 9.975092e-01 7.040322e-02 -2.225042e+01 9.972098e-01 9.550490e-03 -7.403633e-02 2.951031e+02 +-8.164837e-02 6.905010e-02 -9.942664e-01 1.253235e+02 -5.624840e-03 9.975493e-01 6.974002e-02 -2.219657e+01 9.966454e-01 1.128675e-02 -8.105988e-02 2.950166e+02 +-9.009303e-02 6.988691e-02 -9.934783e-01 1.241942e+02 -5.849242e-03 9.974805e-01 7.069890e-02 -2.214901e+01 9.959162e-01 1.218058e-02 -8.945726e-02 2.949191e+02 +-9.894835e-02 7.143889e-02 -9.925249e-01 1.230673e+02 -4.887803e-03 9.973727e-01 7.227512e-02 -2.210276e+01 9.950806e-01 1.200277e-02 -9.833921e-02 2.948127e+02 +-1.072534e-01 7.211141e-02 -9.916131e-01 1.219451e+02 -3.793295e-03 9.973293e-01 7.293740e-02 -2.206356e+01 9.942245e-01 1.158427e-02 -1.066934e-01 2.946932e+02 +-1.151603e-01 7.053964e-02 -9.908392e-01 1.208330e+02 -4.460155e-03 9.974287e-01 7.152716e-02 -2.201777e+01 9.933369e-01 1.265639e-02 -1.145496e-01 2.945688e+02 +-1.221521e-01 6.984326e-02 -9.900509e-01 1.197235e+02 -7.144129e-03 9.974332e-01 7.124551e-02 -2.197180e+01 9.924857e-01 1.577584e-02 -1.213396e-01 2.944318e+02 +-1.273025e-01 7.143745e-02 -9.892880e-01 1.186198e+02 -1.112837e-02 9.972373e-01 7.344350e-02 -2.192156e+01 9.918015e-01 2.035870e-02 -1.261558e-01 2.942916e+02 +-1.306072e-01 6.968856e-02 -9.889819e-01 1.175241e+02 -1.468174e-02 9.972812e-01 7.221229e-02 -2.187589e+01 9.913255e-01 2.395142e-02 -1.292289e-01 2.941483e+02 +-1.330219e-01 6.052948e-02 -9.892630e-01 1.164399e+02 -1.451636e-02 9.979073e-01 6.301036e-02 -2.182690e+01 9.910068e-01 2.274225e-02 -1.318649e-01 2.940061e+02 +-1.357198e-01 5.005670e-02 -9.894819e-01 1.153580e+02 -1.619644e-02 9.984773e-01 5.273333e-02 -2.178137e+01 9.906149e-01 2.318304e-02 -1.347024e-01 2.938632e+02 +-1.377065e-01 4.355694e-02 -9.895149e-01 1.142772e+02 -1.421321e-02 9.988428e-01 4.594554e-02 -2.175344e+01 9.903711e-01 2.039119e-02 -1.369281e-01 2.937172e+02 +-1.395678e-01 4.485847e-02 -9.891959e-01 1.131964e+02 -1.443590e-02 9.987750e-01 4.732967e-02 -2.172570e+01 9.901073e-01 2.088563e-02 -1.387492e-01 2.935698e+02 +-1.404406e-01 5.212441e-02 -9.887161e-01 1.121159e+02 -1.472514e-02 9.983928e-01 5.472618e-02 -2.170126e+01 9.899796e-01 2.224476e-02 -1.394474e-01 2.934143e+02 +-1.414968e-01 5.667917e-02 -9.883148e-01 1.110442e+02 -1.786210e-02 9.980508e-01 5.979486e-02 -2.167086e+01 9.897776e-01 2.611416e-02 -1.402086e-01 2.932630e+02 +-1.411328e-01 5.157027e-02 -9.886466e-01 1.099857e+02 -1.864161e-02 9.983268e-01 5.473638e-02 -2.163525e+01 9.898152e-01 2.615506e-02 -1.399353e-01 2.931124e+02 +-1.400114e-01 4.850391e-02 -9.889612e-01 1.089307e+02 -2.196632e-02 9.984014e-01 5.207679e-02 -2.159880e+01 9.899062e-01 2.901518e-02 -1.387221e-01 2.929656e+02 +-1.369256e-01 5.210437e-02 -9.892100e-01 1.078753e+02 -2.314935e-02 9.981746e-01 5.578088e-02 -2.157021e+01 9.903108e-01 3.053739e-02 -1.354695e-01 2.928204e+02 +-1.316599e-01 6.121090e-02 -9.894033e-01 1.068115e+02 -2.227520e-02 9.976570e-01 6.468571e-02 -2.153030e+01 9.910447e-01 3.055566e-02 -1.299879e-01 2.926873e+02 +-1.255923e-01 7.140213e-02 -9.895091e-01 1.057465e+02 -2.792631e-02 9.967569e-01 7.546966e-02 -2.148740e+01 9.916888e-01 3.711174e-02 -1.231910e-01 2.925501e+02 +-1.177090e-01 7.607615e-02 -9.901298e-01 1.046888e+02 -2.895941e-02 9.963742e-01 7.999872e-02 -2.143178e+01 9.926258e-01 3.809014e-02 -1.150791e-01 2.924328e+02 +-1.094901e-01 7.241289e-02 -9.913467e-01 1.036371e+02 -3.119624e-02 9.966012e-01 7.624222e-02 -2.137227e+01 9.934983e-01 3.927406e-02 -1.068590e-01 2.923201e+02 +-1.011341e-01 7.075054e-02 -9.923539e-01 1.025838e+02 -3.811517e-02 9.964602e-01 7.492777e-02 -2.131502e+01 9.941424e-01 4.540148e-02 -9.807945e-02 2.922120e+02 +-9.377283e-02 7.039836e-02 -9.931016e-01 1.015262e+02 -4.423182e-02 9.962174e-01 7.479581e-02 -2.125925e+01 9.946106e-01 5.094050e-02 -9.030427e-02 2.921128e+02 +-8.595525e-02 7.109027e-02 -9.937594e-01 1.004616e+02 -4.809420e-02 9.959921e-01 7.540991e-02 -2.120243e+01 9.951375e-01 5.427593e-02 -8.219172e-02 2.920226e+02 +-7.833373e-02 7.011273e-02 -9.944586e-01 9.939616e+01 -5.280218e-02 9.958319e-01 7.436881e-02 -2.114346e+01 9.955279e-01 5.833517e-02 -7.430512e-02 2.919433e+02 +-7.052760e-02 7.087087e-02 -9.949890e-01 9.832067e+01 -5.803219e-02 9.954919e-01 7.502019e-02 -2.108313e+01 9.958204e-01 6.303238e-02 -6.609686e-02 2.918677e+02 +-6.305146e-02 7.007995e-02 -9.955467e-01 9.724368e+01 -6.368597e-02 9.952159e-01 7.409014e-02 -2.102706e+01 9.959762e-01 6.807384e-02 -5.828671e-02 2.918018e+02 +-5.560290e-02 6.816794e-02 -9.961232e-01 9.616187e+01 -6.786699e-02 9.951012e-01 7.188631e-02 -2.097163e+01 9.961438e-01 7.160096e-02 -5.070416e-02 2.917446e+02 +-4.844724e-02 6.437824e-02 -9.967489e-01 9.507573e+01 -7.030445e-02 9.952258e-01 6.769705e-02 -2.091579e+01 9.963484e-01 7.335561e-02 -4.368986e-02 2.916981e+02 +-4.114369e-02 6.028554e-02 -9.973329e-01 9.398368e+01 -7.077728e-02 9.954947e-01 6.309427e-02 -2.086510e+01 9.966433e-01 7.318443e-02 -3.669148e-02 2.916613e+02 +-3.448661e-02 5.880419e-02 -9.976736e-01 9.289014e+01 -7.005945e-02 9.956694e-01 6.110782e-02 -2.081746e+01 9.969465e-01 7.200386e-02 -3.021747e-02 2.916282e+02 +-2.958416e-02 6.241720e-02 -9.976116e-01 9.178161e+01 -6.681831e-02 9.956925e-01 6.427864e-02 -2.077343e+01 9.973265e-01 6.856034e-02 -2.528611e-02 2.916008e+02 +-2.697796e-02 6.699351e-02 -9.973886e-01 9.067616e+01 -6.413592e-02 9.955801e-01 6.860684e-02 -2.073094e+01 9.975765e-01 6.581929e-02 -2.256202e-02 2.915732e+02 +-2.576428e-02 6.638057e-02 -9.974617e-01 8.957204e+01 -6.303569e-02 9.956994e-01 6.789150e-02 -2.068343e+01 9.976787e-01 6.462485e-02 -2.146913e-02 2.915417e+02 +-2.521210e-02 6.463338e-02 -9.975905e-01 8.846173e+01 -6.379186e-02 9.957699e-01 6.612765e-02 -2.062975e+01 9.976447e-01 6.530537e-02 -2.098237e-02 2.915103e+02 +-2.456356e-02 6.343663e-02 -9.976835e-01 8.734875e+01 -6.464089e-02 9.957954e-01 6.490808e-02 -2.058181e+01 9.976063e-01 6.608552e-02 -2.035968e-02 2.914756e+02 +-2.434101e-02 6.276230e-02 -9.977316e-01 8.622308e+01 -6.594325e-02 9.957529e-01 6.424662e-02 -2.053261e+01 9.975265e-01 6.735748e-02 -2.009887e-02 2.914439e+02 +-2.408092e-02 6.217668e-02 -9.977746e-01 8.509401e+01 -6.432460e-02 9.958995e-01 6.361229e-02 -2.048322e+01 9.976385e-01 6.571329e-02 -1.998269e-02 2.914164e+02 +-2.426462e-02 6.248913e-02 -9.977506e-01 8.395800e+01 -6.330685e-02 9.959453e-01 6.391565e-02 -2.042969e+01 9.976991e-01 6.471533e-02 -2.021024e-02 2.913873e+02 +-2.472922e-02 6.274687e-02 -9.977230e-01 8.281697e+01 -6.240090e-02 9.959852e-01 6.418424e-02 -2.037457e+01 9.977448e-01 6.384604e-02 -2.071447e-02 2.913589e+02 +-2.549194e-02 6.383983e-02 -9.976345e-01 8.167254e+01 -6.223233e-02 9.959218e-01 6.532044e-02 -2.032222e+01 9.977361e-01 6.375026e-02 -2.141507e-02 2.913250e+02 +-2.642163e-02 6.458989e-02 -9.975620e-01 8.052478e+01 -6.128479e-02 9.959287e-01 6.610735e-02 -2.026789e+01 9.977706e-01 6.288204e-02 -2.235568e-02 2.912903e+02 +-2.747635e-02 6.491968e-02 -9.975121e-01 7.937427e+01 -6.080627e-02 9.959324e-01 6.649179e-02 -2.021911e+01 9.977714e-01 6.248193e-02 -2.341707e-02 2.912526e+02 +-2.886482e-02 6.539902e-02 -9.974416e-01 7.822359e+01 -6.088846e-02 9.958893e-01 6.705930e-02 -2.017230e+01 9.977272e-01 6.266833e-02 -2.476412e-02 2.912168e+02 +-3.015869e-02 6.623968e-02 -9.973478e-01 7.706616e+01 -5.980910e-02 9.958943e-01 6.795172e-02 -2.012248e+01 9.977542e-01 6.169980e-02 -2.607313e-02 2.911830e+02 +-3.147827e-02 6.647737e-02 -9.972913e-01 7.591644e+01 -5.925887e-02 9.959064e-01 6.825550e-02 -2.007730e+01 9.977462e-01 6.124691e-02 -2.741003e-02 2.911462e+02 +-3.277414e-02 6.709266e-02 -9.972083e-01 7.476645e+01 -5.896130e-02 9.958768e-01 6.894091e-02 -2.003225e+01 9.977221e-01 6.105617e-02 -2.868313e-02 2.911066e+02 +-3.388417e-02 6.784127e-02 -9.971206e-01 7.362108e+01 -5.970460e-02 9.957742e-01 6.977857e-02 -1.998543e+01 9.976409e-01 6.189707e-02 -2.969055e-02 2.910673e+02 +-3.444308e-02 6.775666e-02 -9.971072e-01 7.247978e+01 -6.138266e-02 9.956721e-01 6.977951e-02 -1.993933e+01 9.975199e-01 6.360850e-02 -3.013493e-02 2.910251e+02 +-3.447291e-02 6.605961e-02 -9.972200e-01 7.134424e+01 -6.222578e-02 9.957352e-01 6.811235e-02 -1.989149e+01 9.974666e-01 6.440081e-02 -3.021528e-02 2.909854e+02 +-3.426593e-02 6.189344e-02 -9.974944e-01 7.021252e+01 -6.348263e-02 9.959301e-01 6.397715e-02 -1.984778e+01 9.973945e-01 6.551579e-02 -3.019731e-02 2.909452e+02 +-3.435771e-02 6.190107e-02 -9.974907e-01 6.907498e+01 -6.369418e-02 9.959153e-01 6.399721e-02 -1.980502e+01 9.973779e-01 6.573314e-02 -3.027463e-02 2.909073e+02 +-3.431647e-02 6.380321e-02 -9.973723e-01 6.794188e+01 -6.290647e-02 9.958433e-01 6.586983e-02 -1.976047e+01 9.974293e-01 6.500158e-02 -3.016019e-02 2.908732e+02 +-3.390953e-02 6.578686e-02 -9.972573e-01 6.681166e+01 -6.199429e-02 9.957712e-01 6.779681e-02 -1.971660e+01 9.975003e-01 6.412321e-02 -2.968772e-02 2.908387e+02 +-3.371938e-02 6.412816e-02 -9.973718e-01 6.569324e+01 -6.154856e-02 9.959119e-01 6.611516e-02 -1.966842e+01 9.975344e-01 6.361616e-02 -2.963454e-02 2.908034e+02 +-3.382142e-02 6.433526e-02 -9.973550e-01 6.457462e+01 -6.159283e-02 9.958949e-01 6.632977e-02 -1.962195e+01 9.975282e-01 6.367327e-02 -2.971999e-02 2.907657e+02 +-3.378925e-02 6.667037e-02 -9.972027e-01 6.345933e+01 -6.119061e-02 9.957626e-01 6.864749e-02 -1.957264e+01 9.975540e-01 6.333899e-02 -2.956647e-02 2.907298e+02 +-3.386173e-02 6.618810e-02 -9.972324e-01 6.235096e+01 -6.150347e-02 9.957755e-01 6.817981e-02 -1.952469e+01 9.975323e-01 6.364193e-02 -2.964788e-02 2.906915e+02 +-3.377579e-02 6.447413e-02 -9.973476e-01 6.124641e+01 -6.156605e-02 9.958875e-01 6.646474e-02 -1.947675e+01 9.975314e-01 6.364764e-02 -2.966747e-02 2.906559e+02 +-3.370968e-02 6.396435e-02 -9.973827e-01 6.014673e+01 -6.158295e-02 9.959206e-01 6.595199e-02 -1.943014e+01 9.975326e-01 6.364498e-02 -2.963305e-02 2.906203e+02 +-3.373672e-02 6.517212e-02 -9.973036e-01 5.904468e+01 -6.199325e-02 9.958136e-01 6.717188e-02 -1.938599e+01 9.975063e-01 6.409224e-02 -2.955526e-02 2.905857e+02 +-3.374022e-02 6.663644e-02 -9.972067e-01 5.794438e+01 -6.129501e-02 9.957585e-01 6.861359e-02 -1.933833e+01 9.975493e-01 6.343882e-02 -2.951263e-02 2.905555e+02 +-3.368927e-02 6.659667e-02 -9.972111e-01 5.685412e+01 -6.095574e-02 9.957830e-01 6.856062e-02 -1.929105e+01 9.975718e-01 6.309548e-02 -2.948775e-02 2.905253e+02 +-3.341036e-02 6.600255e-02 -9.972599e-01 5.576827e+01 -6.136504e-02 9.957989e-01 6.796174e-02 -1.924312e+01 9.975561e-01 6.346751e-02 -2.921975e-02 2.904945e+02 +-3.330004e-02 6.544445e-02 -9.973004e-01 5.468849e+01 -6.163604e-02 9.958200e-01 6.740535e-02 -1.919570e+01 9.975431e-01 6.371424e-02 -2.912711e-02 2.904639e+02 +-3.279487e-02 6.496454e-02 -9.973485e-01 5.361134e+01 -6.236530e-02 9.958077e-01 6.691489e-02 -1.915021e+01 9.975145e-01 6.439440e-02 -2.860585e-02 2.904327e+02 +-3.171970e-02 6.350033e-02 -9.974776e-01 5.253584e+01 -6.288985e-02 9.958754e-01 6.539825e-02 -1.910540e+01 9.975163e-01 6.480562e-02 -2.759534e-02 2.904029e+02 +-3.050858e-02 6.169447e-02 -9.976287e-01 5.146518e+01 -6.315870e-02 9.959797e-01 6.352397e-02 -1.906025e+01 9.975371e-01 6.494695e-02 -2.648939e-02 2.903748e+02 +-2.935125e-02 6.139383e-02 -9.976819e-01 5.039243e+01 -6.221104e-02 9.960648e-01 6.312454e-02 -1.901583e+01 9.976314e-01 6.391961e-02 -2.541637e-02 2.903496e+02 +-2.853312e-02 6.385219e-02 -9.975514e-01 4.932323e+01 -6.069243e-02 9.960058e-01 6.548927e-02 -1.897030e+01 9.977486e-01 6.241242e-02 -2.454381e-02 2.903262e+02 +-2.848326e-02 6.787217e-02 -9.972873e-01 4.825039e+01 -6.203336e-02 9.956491e-01 6.953241e-02 -1.892427e+01 9.976676e-01 6.384559e-02 -2.414899e-02 2.902987e+02 +-2.853420e-02 7.121712e-02 -9.970526e-01 4.717846e+01 -6.216912e-02 9.954013e-01 7.287838e-02 -1.887371e+01 9.976577e-01 6.406540e-02 -2.397547e-02 2.902747e+02 +-2.873713e-02 7.211052e-02 -9.969826e-01 4.611095e+01 -6.254801e-02 9.953102e-01 7.379246e-02 -1.881973e+01 9.976282e-01 6.447985e-02 -2.409199e-02 2.902511e+02 +-2.873917e-02 7.002199e-02 -9.971314e-01 4.505013e+01 -6.318381e-02 9.954213e-01 7.172299e-02 -1.876648e+01 9.975881e-01 6.506381e-02 -2.418333e-02 2.902264e+02 +-2.908310e-02 6.786750e-02 -9.972703e-01 4.399243e+01 -6.419375e-02 9.955060e-01 6.961951e-02 -1.871615e+01 9.975136e-01 6.604327e-02 -2.459573e-02 2.902001e+02 +-2.942316e-02 6.788389e-02 -9.972593e-01 4.293390e+01 -6.457089e-02 9.954783e-01 6.966777e-02 -1.866600e+01 9.974793e-01 6.644375e-02 -2.490679e-02 2.901776e+02 +-2.972430e-02 6.898555e-02 -9.971747e-01 4.187527e+01 -6.422684e-02 9.954221e-01 7.077883e-02 -1.861788e+01 9.974926e-01 6.614922e-02 -2.515750e-02 2.901577e+02 +-2.994186e-02 6.731868e-02 -9.972821e-01 4.081812e+01 -6.356957e-02 9.955814e-01 6.911247e-02 -1.857269e+01 9.975282e-01 6.546615e-02 -2.553014e-02 2.901351e+02 +-3.028520e-02 6.665758e-02 -9.973162e-01 3.976699e+01 -6.443298e-02 9.955684e-01 6.849740e-02 -1.852730e+01 9.974624e-01 6.633450e-02 -2.585604e-02 2.901072e+02 +-3.040981e-02 6.848320e-02 -9.971887e-01 3.871149e+01 -6.380104e-02 9.954826e-01 7.031170e-02 -1.848815e+01 9.974992e-01 6.575984e-02 -2.590314e-02 2.900790e+02 +-3.054351e-02 6.938796e-02 -9.971220e-01 3.766281e+01 -6.296904e-02 9.954723e-01 7.120202e-02 -1.844654e+01 9.975480e-01 6.496257e-02 -2.603593e-02 2.900528e+02 +-3.015390e-02 6.751337e-02 -9.972626e-01 3.661981e+01 -6.303120e-02 9.956021e-01 6.930682e-02 -1.840338e+01 9.975560e-01 6.494852e-02 -2.576583e-02 2.900253e+02 +-2.941289e-02 6.738003e-02 -9.972937e-01 3.557869e+01 -6.328091e-02 9.955984e-01 6.913183e-02 -1.835739e+01 9.975623e-01 6.514301e-02 -2.501956e-02 2.899990e+02 +-2.827906e-02 6.874799e-02 -9.972332e-01 3.453931e+01 -6.230599e-02 9.955711e-01 7.040027e-02 -1.831368e+01 9.976564e-01 6.412445e-02 -2.387040e-02 2.899750e+02 +-2.709394e-02 6.989122e-02 -9.971866e-01 3.350161e+01 -6.307328e-02 9.954456e-01 7.148293e-02 -1.827079e+01 9.976411e-01 6.483258e-02 -2.256227e-02 2.899481e+02 +-2.566202e-02 7.064815e-02 -9.971711e-01 3.246804e+01 -6.339186e-02 9.953770e-01 7.215244e-02 -1.823164e+01 9.976588e-01 6.506411e-02 -2.106487e-02 2.899190e+02 +-2.447058e-02 6.976915e-02 -9.972630e-01 3.144194e+01 -6.344016e-02 9.954427e-01 7.119850e-02 -1.818914e+01 9.976856e-01 6.500878e-02 -1.993289e-02 2.898946e+02 +-2.333069e-02 6.837392e-02 -9.973869e-01 3.041735e+01 -6.346382e-02 9.955449e-01 6.973220e-02 -1.814389e+01 9.977114e-01 6.492488e-02 -1.888748e-02 2.898744e+02 +-2.249648e-02 6.818899e-02 -9.974187e-01 2.939903e+01 -6.377624e-02 9.955413e-01 6.949911e-02 -1.809760e+01 9.977107e-01 6.517509e-02 -1.804734e-02 2.898559e+02 +-2.171394e-02 6.971915e-02 -9.973303e-01 2.838154e+01 -6.379698e-02 9.954358e-01 7.097573e-02 -1.805454e+01 9.977267e-01 6.516782e-02 -1.716696e-02 2.898390e+02 +-2.152234e-02 7.091379e-02 -9.972502e-01 2.737335e+01 -6.350037e-02 9.953703e-01 7.215057e-02 -1.801340e+01 9.977497e-01 6.487860e-02 -1.691964e-02 2.898244e+02 +-2.193093e-02 7.048199e-02 -9.972719e-01 2.637444e+01 -6.393132e-02 9.953714e-01 7.175360e-02 -1.797265e+01 9.977133e-01 6.533053e-02 -1.732341e-02 2.898060e+02 +-2.220048e-02 6.843733e-02 -9.974084e-01 2.539057e+01 -6.287699e-02 9.955836e-01 6.971167e-02 -1.793399e+01 9.977744e-01 6.426166e-02 -1.779930e-02 2.897879e+02 +-2.267784e-02 6.641420e-02 -9.975344e-01 2.442189e+01 -6.258732e-02 9.957395e-01 6.771757e-02 -1.789569e+01 9.977818e-01 6.396868e-02 -1.842453e-02 2.897723e+02 +-2.305991e-02 6.550974e-02 -9.975854e-01 2.346619e+01 -6.149208e-02 9.958685e-01 6.681844e-02 -1.786049e+01 9.978412e-01 6.288442e-02 -1.893630e-02 2.897538e+02 +-2.386010e-02 6.774858e-02 -9.974171e-01 2.252760e+01 -6.045483e-02 9.957774e-01 6.908342e-02 -1.782227e+01 9.978858e-01 6.194701e-02 -1.966362e-02 2.897353e+02 +-2.478162e-02 7.010770e-02 -9.972315e-01 2.160703e+01 -6.051607e-02 9.956033e-01 7.149710e-02 -1.778606e+01 9.978596e-01 6.212034e-02 -2.043002e-02 2.897140e+02 +-2.514863e-02 6.867666e-02 -9.973219e-01 2.070325e+01 -5.913024e-02 9.957886e-01 7.006212e-02 -1.775081e+01 9.979335e-01 6.073384e-02 -2.098184e-02 2.896957e+02 +-2.562002e-02 6.538595e-02 -9.975311e-01 1.981418e+01 -5.889191e-02 9.960268e-01 6.679992e-02 -1.771546e+01 9.979356e-01 6.045792e-02 -2.166752e-02 2.896753e+02 +-2.588317e-02 6.453605e-02 -9.975796e-01 1.893545e+01 -5.988952e-02 9.960214e-01 6.598915e-02 -1.768124e+01 9.978694e-01 6.145257e-02 -2.191516e-02 2.896537e+02 +-2.622616e-02 6.538646e-02 -9.975153e-01 1.806559e+01 -6.101946e-02 9.958931e-01 6.688444e-02 -1.765187e+01 9.977920e-01 6.262196e-02 -2.212861e-02 2.896320e+02 +-2.611791e-02 6.585187e-02 -9.974875e-01 1.721049e+01 -6.103225e-02 9.958614e-01 6.734259e-02 -1.762237e+01 9.977941e-01 6.263775e-02 -2.199073e-02 2.896127e+02 +-2.580320e-02 6.505263e-02 -9.975482e-01 1.636884e+01 -6.162201e-02 9.958792e-01 6.653776e-02 -1.759218e+01 9.977660e-01 6.318780e-02 -2.168819e-02 2.895934e+02 +-2.535323e-02 6.399978e-02 -9.976278e-01 1.554509e+01 -6.224525e-02 9.959111e-01 6.547154e-02 -1.756382e+01 9.977388e-01 6.375750e-02 -2.126588e-02 2.895737e+02 +-2.481318e-02 6.418077e-02 -9.976297e-01 1.473340e+01 -6.273655e-02 9.958700e-01 6.562796e-02 -1.753728e+01 9.977217e-01 6.421628e-02 -2.068422e-02 2.895550e+02 +-2.422011e-02 6.491472e-02 -9.975968e-01 1.393301e+01 -6.358281e-02 9.957692e-01 6.633950e-02 -1.751466e+01 9.976827e-01 6.503675e-02 -1.999017e-02 2.895367e+02 +-2.251465e-02 6.561700e-02 -9.975908e-01 1.314789e+01 -6.475369e-02 9.956528e-01 6.695097e-02 -1.749114e+01 9.976473e-01 6.610505e-02 -1.816783e-02 2.895203e+02 +-1.986809e-02 6.518134e-02 -9.976756e-01 1.237721e+01 -6.648309e-02 9.955778e-01 6.636828e-02 -1.747278e+01 9.975898e-01 6.764716e-02 -1.544677e-02 2.895031e+02 +-1.488313e-02 6.454675e-02 -9.978037e-01 1.162280e+01 -6.697611e-02 9.956086e-01 6.540378e-02 -1.745160e+01 9.976436e-01 6.780241e-02 -1.049468e-02 2.894936e+02 +-8.320722e-03 6.469469e-02 -9.978704e-01 1.088803e+01 -6.908590e-02 9.954833e-01 6.511601e-02 -1.742925e+01 9.975760e-01 6.948058e-02 -3.813647e-03 2.894881e+02 +-4.137859e-04 6.675325e-02 -9.977694e-01 1.016527e+01 -7.010381e-02 9.953127e-01 6.661798e-02 -1.740553e+01 9.975396e-01 6.997500e-02 4.267813e-03 2.894909e+02 +8.454121e-03 6.777270e-02 -9.976650e-01 9.468830e+00 -7.013349e-02 9.952839e-01 6.701666e-02 -1.738913e+01 9.975018e-01 6.940315e-02 1.316739e-02 2.895022e+02 +1.792852e-02 6.766074e-02 -9.975473e-01 8.793075e+00 -6.973688e-02 9.953625e-01 6.625922e-02 -1.737238e+01 9.974043e-01 6.837790e-02 2.256383e-02 2.895201e+02 +2.865787e-02 6.680613e-02 -9.973543e-01 8.140703e+00 -7.036783e-02 9.954236e-01 6.465488e-02 -1.735833e+01 9.971094e-01 6.832878e-02 3.322773e-02 2.895446e+02 +3.977049e-02 6.437031e-02 -9.971333e-01 7.508175e+00 -7.061685e-02 9.956086e-01 6.145536e-02 -1.734340e+01 9.967104e-01 6.797029e-02 4.414147e-02 2.895754e+02 +5.089564e-02 6.184779e-02 -9.967871e-01 6.883822e+00 -7.181412e-02 9.957235e-01 5.811501e-02 -1.732740e+01 9.961187e-01 6.862557e-02 5.511953e-02 2.896074e+02 +6.242398e-02 6.188030e-02 -9.961295e-01 6.270834e+00 -7.127266e-02 9.958043e-01 5.739370e-02 -1.731625e+01 9.955016e-01 6.741405e-02 6.657244e-02 2.896562e+02 +7.460765e-02 6.197318e-02 -9.952854e-01 5.671407e+00 -6.956499e-02 9.959590e-01 5.680048e-02 -1.730611e+01 9.947836e-01 6.499926e-02 7.861733e-02 2.897065e+02 +8.599322e-02 6.141217e-02 -9.944012e-01 5.082836e+00 -6.734887e-02 9.961736e-01 5.569750e-02 -1.729649e+01 9.940168e-01 6.218218e-02 8.980023e-02 2.897706e+02 +9.689377e-02 6.060200e-02 -9.934480e-01 4.503051e+00 -6.458279e-02 9.964238e-01 5.448460e-02 -1.728871e+01 9.931972e-01 5.888042e-02 1.004611e-01 2.898402e+02 +1.070979e-01 6.020846e-02 -9.924238e-01 3.929297e+00 -6.191988e-02 9.966310e-01 5.378160e-02 -1.728083e+01 9.923185e-01 5.569085e-02 1.104652e-01 2.899106e+02 +1.162109e-01 5.997552e-02 -9.914121e-01 3.360773e+00 -5.910100e-02 9.968240e-01 5.337526e-02 -1.727156e+01 9.914647e-01 5.239065e-02 1.193864e-01 2.899893e+02 +1.244818e-01 5.942262e-02 -9.904409e-01 2.800298e+00 -5.501622e-02 9.970828e-01 5.290651e-02 -1.726450e+01 9.906955e-01 4.790442e-02 1.273878e-01 2.900709e+02 +1.315312e-01 5.989696e-02 -9.895008e-01 2.243661e+00 -5.050659e-02 9.972814e-01 5.365428e-02 -1.725683e+01 9.900246e-01 4.291910e-02 1.341988e-01 2.901581e+02 +1.379685e-01 6.022252e-02 -9.886040e-01 1.693438e+00 -4.646884e-02 9.974441e-01 5.427590e-02 -1.725026e+01 9.893459e-01 3.845092e-02 1.404143e-01 2.902463e+02 +1.442810e-01 6.021321e-02 -9.877031e-01 1.150040e+00 -4.373906e-02 9.975594e-01 5.442481e-02 -1.724222e+01 9.885696e-01 3.534873e-02 1.465626e-01 2.903354e+02 +1.504043e-01 6.077636e-02 -9.867547e-01 6.130564e-01 -4.035257e-02 9.976542e-01 5.529704e-02 -1.723577e+01 9.878007e-01 3.150117e-02 1.525040e-01 2.904293e+02 +1.565569e-01 6.170291e-02 -9.857396e-01 8.176189e-02 -3.663952e-02 9.977225e-01 5.663384e-02 -1.722666e+01 9.869891e-01 2.725061e-02 1.584611e-01 2.905239e+02 +1.626956e-01 6.115351e-02 -9.847794e-01 -4.393593e-01 -3.331320e-02 9.978488e-01 5.646145e-02 -1.721807e+01 9.861138e-01 2.362013e-02 1.643828e-01 2.906223e+02 +1.692171e-01 6.010067e-02 -9.837446e-01 -9.498869e-01 -3.040157e-02 9.979823e-01 5.574105e-02 -1.720505e+01 9.851098e-01 2.047504e-02 1.707028e-01 2.907239e+02 +1.764776e-01 5.984809e-02 -9.824835e-01 -1.454040e+00 -2.891279e-02 9.980343e-01 5.560195e-02 -1.719230e+01 9.838800e-01 1.859384e-02 1.778610e-01 2.908247e+02 +1.845285e-01 5.962311e-02 -9.810170e-01 -1.949186e+00 -2.610906e-02 9.981033e-01 5.575048e-02 -1.717813e+01 9.824803e-01 1.532588e-02 1.857352e-01 2.909325e+02 +1.922904e-01 5.888957e-02 -9.795695e-01 -2.436637e+00 -2.348265e-02 9.981881e-01 5.539922e-02 -1.716768e+01 9.810571e-01 1.235016e-02 1.933248e-01 2.910422e+02 +2.005722e-01 5.873321e-02 -9.779167e-01 -2.912142e+00 -2.220477e-02 9.982174e-01 5.539823e-02 -1.715748e+01 9.794273e-01 1.060307e-02 2.015188e-01 2.911539e+02 +2.101002e-01 5.883015e-02 -9.759082e-01 -3.375314e+00 -2.057769e-02 9.982329e-01 5.574585e-02 -1.714897e+01 9.774633e-01 8.369724e-03 2.109396e-01 2.912668e+02 +2.199702e-01 6.014296e-02 -9.736508e-01 -3.828155e+00 -2.030172e-02 9.981637e-01 5.707052e-02 -1.714013e+01 9.752954e-01 7.212980e-03 2.207873e-01 2.913782e+02 +2.305059e-01 6.016238e-02 -9.712093e-01 -4.263831e+00 -1.847243e-02 9.981775e-01 5.744874e-02 -1.713243e+01 9.728956e-01 4.698326e-03 2.311972e-01 2.914965e+02 +2.419726e-01 5.833958e-02 -9.685276e-01 -4.684120e+00 -1.581942e-02 9.982953e-01 5.618040e-02 -1.712759e+01 9.701541e-01 1.727432e-03 2.424830e-01 2.916153e+02 +2.550748e-01 5.599887e-02 -9.652984e-01 -5.085439e+00 -1.407174e-02 9.984308e-01 5.420258e-02 -1.712666e+01 9.668190e-01 -2.422807e-04 2.554626e-01 2.917408e+02 +2.695464e-01 5.422548e-02 -9.614595e-01 -5.469629e+00 -1.543008e-02 9.985284e-01 5.199030e-02 -1.712609e+01 9.628638e-01 8.216065e-04 2.699864e-01 2.918652e+02 +2.851396e-01 5.335705e-02 -9.569997e-01 -5.844108e+00 -1.769886e-02 9.985722e-01 5.040151e-02 -1.712108e+01 9.583226e-01 2.566338e-03 2.856769e-01 2.919847e+02 +3.021262e-01 5.053509e-02 -9.519275e-01 -6.205817e+00 -1.919386e-02 9.987139e-01 4.692704e-02 -1.711781e+01 9.530747e-01 4.093280e-03 3.027076e-01 2.921193e+02 +3.208157e-01 4.666355e-02 -9.459914e-01 -6.561797e+00 -2.009884e-02 9.988961e-01 4.245707e-02 -1.711056e+01 9.469284e-01 5.392438e-03 3.213995e-01 2.922502e+02 +3.412806e-01 4.484085e-02 -9.388913e-01 -6.912032e+00 -2.051024e-02 9.989789e-01 4.025527e-02 -1.710972e+01 9.397377e-01 5.518544e-03 3.418519e-01 2.924077e+02 +3.638155e-01 4.509869e-02 -9.303786e-01 -7.249736e+00 -2.122044e-02 9.989693e-01 4.012548e-02 -1.710929e+01 9.312293e-01 5.144768e-03 3.643976e-01 2.925723e+02 +3.878324e-01 4.813050e-02 -9.204724e-01 -7.567325e+00 -2.216231e-02 9.988339e-01 4.289007e-02 -1.711284e+01 9.214635e-01 3.765640e-03 3.884468e-01 2.927204e+02 +4.121768e-01 4.897446e-02 -9.097867e-01 -7.833320e+00 -2.068570e-02 9.987999e-01 4.439451e-02 -1.711410e+01 9.108691e-01 5.211896e-04 4.126952e-01 2.928803e+02 +4.350685e-01 4.706290e-02 -8.991665e-01 -8.062234e+00 -1.714729e-02 9.988850e-01 4.398538e-02 -1.711233e+01 9.002341e-01 -3.718377e-03 4.353904e-01 2.930170e+02 +4.557278e-01 4.590976e-02 -8.889344e-01 -8.250854e+00 -1.565490e-02 9.989279e-01 4.356472e-02 -1.710899e+01 8.899815e-01 -5.937466e-03 4.559580e-01 2.931507e+02 +4.738078e-01 4.616397e-02 -8.794175e-01 -8.410951e+00 -1.850281e-02 9.989264e-01 4.246862e-02 -1.710691e+01 8.804339e-01 -3.850266e-03 4.741533e-01 2.932511e+02 +4.886615e-01 4.442425e-02 -8.713417e-01 -8.529232e+00 -1.951554e-02 9.990095e-01 3.998863e-02 -1.710767e+01 8.722552e-01 -2.536195e-03 4.890444e-01 2.933415e+02 +5.002773e-01 4.285343e-02 -8.648042e-01 -8.615564e+00 -1.796112e-02 9.990732e-01 3.911658e-02 -1.710813e+01 8.656790e-01 -4.036282e-03 5.005833e-01 2.934146e+02 +5.086355e-01 4.183669e-02 -8.599649e-01 -8.671806e+00 -1.499122e-02 9.990976e-01 3.973869e-02 -1.710841e+01 8.608515e-01 -7.320574e-03 5.088037e-01 2.934661e+02 +5.129302e-01 4.056446e-02 -8.574713e-01 -8.700771e+00 -1.397241e-02 9.991451e-01 3.890849e-02 -1.711026e+01 8.583166e-01 -7.976392e-03 5.130585e-01 2.934942e+02 +5.138017e-01 3.973720e-02 -8.569882e-01 -8.701378e+00 -1.395717e-02 9.991817e-01 3.796257e-02 -1.711192e+01 8.577955e-01 -7.544094e-03 5.139359e-01 2.934978e+02 +5.128510e-01 3.958953e-02 -8.575643e-01 -8.689745e+00 -1.715399e-02 9.992092e-01 3.586996e-02 -1.711533e+01 8.583063e-01 -3.685290e-03 5.131246e-01 2.934857e+02 +5.132931e-01 3.665274e-02 -8.574303e-01 -8.680159e+00 -2.015604e-02 9.993268e-01 3.065220e-02 -1.712075e+01 8.579767e-01 1.548837e-03 5.136863e-01 2.934754e+02 +5.133882e-01 3.267494e-02 -8.575342e-01 -8.677816e+00 -2.012685e-02 9.994584e-01 2.603321e-02 -1.712549e+01 8.579205e-01 3.894319e-03 5.137678e-01 2.934762e+02 +5.129838e-01 3.165259e-02 -8.578145e-01 -8.673430e+00 -1.854266e-02 9.994953e-01 2.579175e-02 -1.712465e+01 8.581980e-01 2.675409e-03 5.133119e-01 2.934793e+02 +5.136008e-01 3.250669e-02 -8.574133e-01 -8.670920e+00 -1.771249e-02 9.994708e-01 2.728247e-02 -1.712189e+01 8.578465e-01 1.174627e-03 5.139048e-01 2.934813e+02 +5.137768e-01 3.327731e-02 -8.572782e-01 -8.670689e+00 -1.806505e-02 9.994455e-01 2.796929e-02 -1.712141e+01 8.577337e-01 1.116805e-03 5.140931e-01 2.934814e+02 +5.138223e-01 3.397526e-02 -8.572236e-01 -8.669467e+00 -1.877651e-02 9.994215e-01 2.835645e-02 -1.712188e+01 8.576912e-01 1.525489e-03 5.141630e-01 2.934803e+02 +5.143187e-01 3.441563e-02 -8.569083e-01 -8.664724e+00 -1.934652e-02 9.994058e-01 2.852688e-02 -1.712262e+01 8.573809e-01 1.906288e-03 5.146789e-01 2.934777e+02 +5.144847e-01 3.385373e-02 -8.568310e-01 -8.660467e+00 -1.909167e-02 9.994249e-01 2.802408e-02 -1.712376e+01 8.572870e-01 1.940375e-03 5.148352e-01 2.934766e+02 +5.146730e-01 3.387935e-02 -8.567169e-01 -8.659131e+00 -1.900815e-02 9.994242e-01 2.810365e-02 -1.712490e+01 8.571758e-01 1.820411e-03 5.150207e-01 2.934757e+02 +5.149976e-01 3.437534e-02 -8.565021e-01 -8.655373e+00 -1.934769e-02 9.994072e-01 2.847740e-02 -1.712756e+01 8.569733e-01 1.905548e-03 5.153574e-01 2.934718e+02 +5.151247e-01 3.411708e-02 -8.564360e-01 -8.651698e+00 -1.934624e-02 9.994157e-01 2.817657e-02 -1.712953e+01 8.568969e-01 2.054371e-03 5.154837e-01 2.934687e+02 +5.152120e-01 3.386594e-02 -8.563934e-01 -8.646970e+00 -1.922634e-02 9.994242e-01 2.795539e-02 -1.713165e+01 8.568471e-01 2.062355e-03 5.155665e-01 2.934655e+02 +5.153004e-01 3.418125e-02 -8.563277e-01 -8.646113e+00 -1.938257e-02 9.994135e-01 2.822911e-02 -1.713277e+01 8.567905e-01 2.051364e-03 5.156607e-01 2.934633e+02 +5.157326e-01 3.418107e-02 -8.560675e-01 -8.643833e+00 -1.985786e-02 9.994123e-01 2.794131e-02 -1.713388e+01 8.565195e-01 2.589431e-03 5.161082e-01 2.934600e+02 +5.173645e-01 3.351461e-02 -8.551086e-01 -8.644012e+00 -1.994501e-02 9.994336e-01 2.710392e-02 -1.713530e+01 8.555327e-01 3.032550e-03 5.177400e-01 2.934598e+02 +5.184977e-01 3.269233e-02 -8.544538e-01 -8.644219e+00 -1.949742e-02 9.994610e-01 2.640909e-02 -1.713359e+01 8.548567e-01 2.966591e-03 5.188557e-01 2.934622e+02 +5.199245e-01 3.242040e-02 -8.535968e-01 -8.651930e+00 -1.950866e-02 9.994695e-01 2.607809e-02 -1.713424e+01 8.539895e-01 3.093898e-03 5.202811e-01 2.934684e+02 +5.229489e-01 3.297291e-02 -8.517260e-01 -8.661473e+00 -2.043910e-02 9.994492e-01 2.614239e-02 -1.713620e+01 8.521190e-01 3.737382e-03 5.233348e-01 2.934761e+02 +5.262183e-01 3.298522e-02 -8.497095e-01 -8.673966e+00 -2.063690e-02 9.994484e-01 2.601774e-02 -1.713829e+01 8.500991e-01 3.844359e-03 5.266088e-01 2.934885e+02 +5.296304e-01 3.265050e-02 -8.475999e-01 -8.687854e+00 -2.020102e-02 9.994610e-01 2.587758e-02 -1.714052e+01 8.479880e-01 3.416829e-03 5.300045e-01 2.935024e+02 +5.344968e-01 3.255172e-02 -8.445434e-01 -8.706314e+00 -2.067185e-02 9.994626e-01 2.544002e-02 -1.714225e+01 8.449177e-01 3.860665e-03 5.348825e-01 2.935195e+02 +5.410211e-01 3.226509e-02 -8.403899e-01 -8.729578e+00 -2.222893e-02 9.994633e-01 2.406199e-02 -1.714314e+01 8.407153e-01 5.662928e-03 5.414479e-01 2.935384e+02 +5.494714e-01 3.069734e-02 -8.349484e-01 -8.762112e+00 -2.335812e-02 9.994986e-01 2.137538e-02 -1.714432e+01 8.351860e-01 7.757671e-03 5.499130e-01 2.935700e+02 +5.598873e-01 2.925069e-02 -8.280523e-01 -8.804166e+00 -2.403097e-02 9.995295e-01 1.905954e-02 -1.714511e+01 8.282203e-01 9.227707e-03 5.603268e-01 2.936132e+02 +5.725391e-01 2.851807e-02 -8.193813e-01 -8.857918e+00 -2.449437e-02 9.995437e-01 1.767319e-02 -1.714606e+01 8.195115e-01 9.951639e-03 5.729764e-01 2.936615e+02 +5.871781e-01 2.846599e-02 -8.089571e-01 -8.920494e+00 -2.446532e-02 9.995490e-01 1.741459e-02 -1.714650e+01 8.090880e-01 9.565937e-03 5.876097e-01 2.937307e+02 +6.032626e-01 2.895686e-02 -7.970167e-01 -8.995683e+00 -2.504225e-02 9.995356e-01 1.736019e-02 -1.714661e+01 7.971494e-01 9.486335e-03 6.037077e-01 2.938005e+02 +6.209678e-01 2.929272e-02 -7.832885e-01 -9.078723e+00 -2.570614e-02 9.995250e-01 1.700028e-02 -1.714689e+01 7.834144e-01 9.578700e-03 6.214259e-01 2.938969e+02 +6.396920e-01 2.949894e-02 -7.680651e-01 -9.169684e+00 -2.626216e-02 9.995186e-01 1.651560e-02 -1.714858e+01 7.681826e-01 9.606152e-03 6.401588e-01 2.940082e+02 +6.591408e-01 2.987039e-02 -7.514261e-01 -9.273612e+00 -2.668899e-02 9.995105e-01 1.632094e-02 -1.715012e+01 7.515458e-01 9.297010e-03 6.596154e-01 2.941155e+02 +6.782883e-01 2.974328e-02 -7.341936e-01 -9.382030e+00 -2.636090e-02 9.995222e-01 1.613850e-02 -1.715098e+01 7.343229e-01 8.407449e-03 6.787483e-01 2.942554e+02 +6.965472e-01 2.911994e-02 -7.169199e-01 -9.506103e+00 -2.530136e-02 9.995515e-01 1.601755e-02 -1.715058e+01 7.170648e-01 6.982077e-03 6.969716e-01 2.943947e+02 +7.133990e-01 2.864603e-02 -7.001723e-01 -9.640396e+00 -2.468404e-02 9.995713e-01 1.574497e-02 -1.715097e+01 7.003233e-01 6.050640e-03 7.138002e-01 2.945658e+02 +7.282399e-01 2.903074e-02 -6.847071e-01 -9.792150e+00 -2.636770e-02 9.995495e-01 1.433555e-02 -1.715079e+01 6.848149e-01 7.614432e-03 7.286773e-01 2.947366e+02 +7.414901e-01 3.114016e-02 -6.702408e-01 -9.958653e+00 -3.193999e-02 9.994281e-01 1.109926e-02 -1.714791e+01 6.702032e-01 1.317749e-02 7.420607e-01 2.949350e+02 +7.551025e-01 3.259698e-02 -6.547959e-01 -1.013552e+01 -3.619810e-02 9.993126e-01 8.004485e-03 -1.714820e+01 6.546068e-01 1.765816e-02 7.557633e-01 2.951597e+02 +7.707729e-01 3.551311e-02 -6.361194e-01 -1.032454e+01 -3.931176e-02 9.991937e-01 8.149488e-03 -1.715326e+01 6.358960e-01 1.872557e-02 7.715476e-01 2.953946e+02 +7.876278e-01 4.028285e-02 -6.148331e-01 -1.052047e+01 -4.374872e-02 9.989982e-01 9.408736e-03 -1.715513e+01 6.145963e-01 1.948758e-02 7.886011e-01 2.956757e+02 +8.049445e-01 4.261916e-02 -5.918176e-01 -1.072540e+01 -4.681132e-02 9.988695e-01 8.263484e-03 -1.715770e+01 5.915008e-01 2.105211e-02 8.060296e-01 2.959581e+02 +8.232357e-01 4.166727e-02 -5.661686e-01 -1.092234e+01 -4.658225e-02 9.988977e-01 5.781288e-03 -1.716183e+01 5.657854e-01 2.161404e-02 8.242692e-01 2.962983e+02 +8.416328e-01 3.974937e-02 -5.385854e-01 -1.111755e+01 -4.566335e-02 9.989541e-01 2.369224e-03 -1.716777e+01 5.381163e-01 2.259960e-02 8.425676e-01 2.966681e+02 +8.598226e-01 3.627655e-02 -5.093026e-01 -1.131728e+01 -4.364476e-02 9.990439e-01 -2.522816e-03 -1.717036e+01 5.087242e-01 2.439756e-02 8.605838e-01 2.970299e+02 +8.777955e-01 3.514100e-02 -4.777449e-01 -1.150961e+01 -4.365581e-02 9.990240e-01 -6.727794e-03 -1.717840e+01 4.770422e-01 2.676196e-02 8.784729e-01 2.974528e+02 +8.951702e-01 3.653630e-02 -4.442245e-01 -1.170850e+01 -4.516343e-02 9.989404e-01 -8.849948e-03 -1.718996e+01 4.434305e-01 2.798491e-02 8.958718e-01 2.978664e+02 +9.110903e-01 3.870060e-02 -4.103861e-01 -1.189349e+01 -4.762291e-02 9.987987e-01 -1.153707e-02 -1.720138e+01 4.094466e-01 3.005508e-02 9.118389e-01 2.983434e+02 +9.248876e-01 3.989743e-02 -3.781417e-01 -1.206889e+01 -4.832329e-02 9.987495e-01 -1.281547e-02 -1.721321e+01 3.771575e-01 3.012592e-02 9.256590e-01 2.988442e+02 +9.369673e-01 3.809990e-02 -3.473336e-01 -1.223763e+01 -4.543210e-02 9.988830e-01 -1.298764e-02 -1.722324e+01 3.464509e-01 2.794909e-02 9.376517e-01 2.993392e+02 +9.473205e-01 3.606745e-02 -3.182501e-01 -1.238906e+01 -4.200841e-02 9.990473e-01 -1.182191e-02 -1.724003e+01 3.175205e-01 2.456831e-02 9.479331e-01 2.998851e+02 +9.560972e-01 3.398218e-02 -2.910728e-01 -1.254052e+01 -3.876554e-02 9.991912e-01 -1.068089e-02 -1.725630e+01 2.904745e-01 2.149557e-02 9.566413e-01 3.004304e+02 +9.631550e-01 3.489366e-02 -2.666736e-01 -1.268333e+01 -3.846144e-02 9.992267e-01 -8.165972e-03 -1.727159e+01 2.661825e-01 1.812175e-02 9.637523e-01 3.010184e+02 +9.690759e-01 3.509752e-02 -2.442542e-01 -1.281978e+01 -3.873021e-02 9.991988e-01 -1.008417e-02 -1.728883e+01 2.437046e-01 1.923234e-02 9.696588e-01 3.016205e+02 +9.741083e-01 3.541969e-02 -2.232902e-01 -1.295119e+01 -3.984148e-02 9.990884e-01 -1.532760e-02 -1.731044e+01 2.225438e-01 2.382695e-02 9.746315e-01 3.022251e+02 +9.785235e-01 3.511216e-02 -2.031229e-01 -1.307058e+01 -3.973464e-02 9.990348e-01 -1.872267e-02 -1.733112e+01 2.022694e-01 2.639159e-02 9.789743e-01 3.028646e+02 +9.827024e-01 3.362397e-02 -1.821137e-01 -1.318030e+01 -3.806051e-02 9.990564e-01 -2.092047e-02 -1.734350e+01 1.812384e-01 2.748994e-02 9.830549e-01 3.035166e+02 +9.863139e-01 3.323013e-02 -1.614952e-01 -1.327765e+01 -3.701695e-02 9.991044e-01 -2.049568e-02 -1.736002e+01 1.606695e-01 2.619323e-02 9.866607e-01 3.042030e+02 +9.894172e-01 3.538368e-02 -1.407180e-01 -1.336868e+01 -3.807095e-02 9.991396e-01 -1.644996e-02 -1.738722e+01 1.400149e-01 2.163314e-02 9.899131e-01 3.049102e+02 +9.920193e-01 3.657433e-02 -1.206654e-01 -1.344867e+01 -3.903858e-02 9.990734e-01 -1.812095e-02 -1.741565e+01 1.198908e-01 2.268694e-02 9.925278e-01 3.056216e+02 +9.941024e-01 3.263517e-02 -1.034185e-01 -1.351067e+01 -3.558486e-02 9.990071e-01 -2.680586e-02 -1.744006e+01 1.024410e-01 3.032790e-02 9.942767e-01 3.063531e+02 +9.956383e-01 2.979319e-02 -8.841285e-02 -1.356563e+01 -3.268053e-02 9.989727e-01 -3.139123e-02 -1.746663e+01 8.738679e-02 3.414369e-02 9.955892e-01 3.071031e+02 +9.965437e-01 2.992095e-02 -7.749469e-02 -1.361830e+01 -3.229307e-02 9.990418e-01 -2.953972e-02 -1.749910e+01 7.653658e-02 3.194016e-02 9.965551e-01 3.078789e+02 +9.970955e-01 3.194061e-02 -6.914050e-02 -1.367170e+01 -3.372526e-02 9.991234e-01 -2.480011e-02 -1.753332e+01 6.828777e-02 2.705986e-02 9.972986e-01 3.086771e+02 +9.974814e-01 3.238182e-02 -6.310489e-02 -1.372250e+01 -3.388247e-02 9.991644e-01 -2.285676e-02 -1.756629e+01 6.231202e-02 2.493734e-02 9.977451e-01 3.094837e+02 +9.977645e-01 3.148385e-02 -5.894678e-02 -1.376440e+01 -3.285963e-02 9.992063e-01 -2.251707e-02 -1.759602e+01 5.819108e-02 2.440370e-02 9.980072e-01 3.103057e+02 +9.979596e-01 3.123463e-02 -5.568625e-02 -1.380839e+01 -3.249705e-02 9.992316e-01 -2.191037e-02 -1.762495e+01 5.495911e-02 2.367530e-02 9.982079e-01 3.111493e+02 diff --git a/tools/Ground-Truth/dataset/poses/09.txt b/tools/Ground-Truth/dataset/poses/09.txt new file mode 100644 index 0000000..b21fefc --- /dev/null +++ b/tools/Ground-Truth/dataset/poses/09.txt @@ -0,0 +1,1591 @@ +1.000000e+00 1.197625e-11 1.704638e-10 5.551115e-17 1.197625e-11 1.000000e+00 3.562503e-10 0.000000e+00 1.704638e-10 3.562503e-10 1.000000e+00 2.220446e-16 +9.999268e-01 -3.092411e-03 1.169425e-02 2.138869e-02 3.079219e-03 9.999946e-01 1.146026e-03 -8.456433e-03 -1.169773e-02 -1.109933e-03 9.999310e-01 2.880714e-01 +9.998143e-01 -5.167713e-03 1.856600e-02 3.879027e-02 5.141246e-03 9.999857e-01 1.473072e-03 -1.513783e-02 -1.857335e-02 -1.377345e-03 9.998266e-01 5.807338e-01 +9.997542e-01 -8.010201e-03 2.067129e-02 5.418066e-02 8.008308e-03 9.999679e-01 1.744436e-04 -2.008116e-02 -2.067202e-02 -8.857983e-06 9.997863e-01 8.792349e-01 +9.997748e-01 -9.463067e-03 1.899365e-02 6.515084e-02 9.496346e-03 9.999535e-01 -1.662555e-03 -2.474146e-02 -1.897703e-02 1.842551e-03 9.998182e-01 1.185210e+00 +9.998511e-01 -1.185843e-02 1.253962e-02 7.053236e-02 1.189537e-02 9.999251e-01 -2.875296e-03 -2.883154e-02 -1.250459e-02 3.024031e-03 9.999173e-01 1.500857e+00 +9.999012e-01 -1.405064e-02 5.041622e-04 6.976838e-02 1.405303e-02 9.998882e-01 -5.094792e-03 -3.440223e-02 -4.325204e-04 5.101373e-03 9.999869e-01 1.824326e+00 +9.997888e-01 -1.342620e-02 -1.555879e-02 5.785896e-02 1.334533e-02 9.998969e-01 -5.289823e-03 -4.333150e-02 1.562821e-02 5.081069e-03 9.998650e-01 2.161983e+00 +9.993602e-01 -8.848875e-03 -3.465391e-02 3.493816e-02 8.679166e-03 9.999496e-01 -5.044683e-03 -5.403998e-02 3.469681e-02 4.740688e-03 9.993866e-01 2.516769e+00 +9.985196e-01 -5.196826e-03 -5.414520e-02 3.415143e-03 4.866004e-03 9.999687e-01 -6.239968e-03 -6.304966e-02 5.417593e-02 5.967260e-03 9.985136e-01 2.875512e+00 +9.972366e-01 -4.507958e-03 -7.415363e-02 -3.086300e-02 4.012606e-03 9.999686e-01 -6.827705e-03 -7.085384e-02 7.418209e-02 6.511288e-03 9.972235e-01 3.247151e+00 +9.954565e-01 -5.949698e-03 -9.503163e-02 -7.130281e-02 5.379006e-03 9.999659e-01 -6.260341e-03 -7.742982e-02 9.506564e-02 5.720722e-03 9.954546e-01 3.630711e+00 +9.933378e-01 -7.329142e-03 -1.150053e-01 -1.231303e-01 6.752021e-03 9.999626e-01 -5.406982e-03 -8.517902e-02 1.150406e-01 4.594442e-03 9.933502e-01 4.021896e+00 +9.910850e-01 -6.260087e-03 -1.330839e-01 -1.931244e-01 5.657285e-03 9.999719e-01 -4.907150e-03 -9.480390e-02 1.331109e-01 4.110510e-03 9.910926e-01 4.418357e+00 +9.888528e-01 -4.731324e-03 -1.488211e-01 -2.714242e-01 4.211142e-03 9.999838e-01 -3.810278e-03 -1.043554e-01 1.488367e-01 3.141098e-03 9.888568e-01 4.828313e+00 +9.866849e-01 -3.759229e-03 -1.626003e-01 -3.555623e-01 3.153903e-03 9.999871e-01 -3.980763e-03 -1.137549e-01 1.626132e-01 3.414933e-03 9.866840e-01 5.248722e+00 +9.845820e-01 -4.884309e-03 -1.748553e-01 -4.410342e-01 4.143076e-03 9.999808e-01 -4.603916e-03 -1.230564e-01 1.748744e-01 3.808495e-03 9.845834e-01 5.683091e+00 +9.827221e-01 -8.432073e-03 -1.848951e-01 -5.276696e-01 7.289575e-03 9.999499e-01 -6.858084e-03 -1.316203e-01 1.849437e-01 5.391784e-03 9.827343e-01 6.127820e+00 +9.812037e-01 -8.176023e-03 -1.928017e-01 -6.223879e-01 6.568661e-03 9.999381e-01 -8.974631e-03 -1.398923e-01 1.928631e-01 7.539493e-03 9.811967e-01 6.586939e+00 +9.797396e-01 -7.236126e-03 -2.001446e-01 -7.270140e-01 5.215485e-03 9.999300e-01 -1.062133e-02 -1.495504e-01 2.002075e-01 9.362288e-03 9.797088e-01 7.057528e+00 +9.780320e-01 -7.866009e-03 -2.083063e-01 -8.348053e-01 5.207470e-03 9.998979e-01 -1.330798e-02 -1.604265e-01 2.083897e-01 1.193088e-02 9.779731e-01 7.548378e+00 +9.763063e-01 -1.149733e-02 -2.160876e-01 -9.419591e-01 8.487619e-03 9.998537e-01 -1.485108e-02 -1.729816e-01 2.162267e-01 1.266513e-02 9.762610e-01 8.041587e+00 +9.744447e-01 -1.794209e-02 -2.239099e-01 -1.052874e+00 1.460499e-02 9.997563e-01 -1.655112e-02 -1.870514e-01 2.241524e-01 1.285795e-02 9.744693e-01 8.554975e+00 +9.723895e-01 -1.882262e-02 -2.326035e-01 -1.178089e+00 1.511868e-02 9.997291e-01 -1.769655e-02 -2.016067e-01 2.328736e-01 1.369128e-02 9.724106e-01 9.075980e+00 +9.703810e-01 -1.477647e-02 -2.411273e-01 -1.317954e+00 9.627660e-03 9.997001e-01 -2.251735e-02 -2.194403e-01 2.413877e-01 1.952891e-02 9.702323e-01 9.607606e+00 +9.682175e-01 -1.175727e-02 -2.498331e-01 -1.461512e+00 5.410028e-03 9.996453e-01 -2.607749e-02 -2.434394e-01 2.500511e-01 2.389708e-02 9.679377e-01 1.014898e+01 +9.659985e-01 -1.382599e-02 -2.581776e-01 -1.600917e+00 6.935714e-03 9.995955e-01 -2.757989e-02 -2.736564e-01 2.584545e-01 2.485148e-02 9.657037e-01 1.069971e+01 +9.636100e-01 -1.701693e-02 -2.667699e-01 -1.746028e+00 9.362843e-03 9.995079e-01 -2.993753e-02 -3.017085e-01 2.671481e-01 2.635037e-02 9.632952e-01 1.126149e+01 +9.613945e-01 -1.660121e-02 -2.746727e-01 -1.902902e+00 7.991665e-03 9.994419e-01 -3.243426e-02 -3.279271e-01 2.750579e-01 2.898703e-02 9.609906e-01 1.182926e+01 +9.591271e-01 -1.549079e-02 -2.825514e-01 -2.073218e+00 5.603769e-03 9.993444e-01 -3.576662e-02 -3.566836e-01 2.829203e-01 3.272138e-02 9.585851e-01 1.241106e+01 +9.567949e-01 -1.642720e-02 -2.902992e-01 -2.247333e+00 4.781739e-03 9.991567e-01 -4.077934e-02 -3.862946e-01 2.907243e-01 3.762933e-02 9.560667e-01 1.300126e+01 +9.549986e-01 -1.796302e-02 -2.960658e-01 -2.430940e+00 3.863449e-03 9.988331e-01 -4.813954e-02 -4.149226e-01 2.965851e-01 4.482935e-02 9.539537e-01 1.360353e+01 +9.537103e-01 -1.848289e-02 -3.001583e-01 -2.620930e+00 1.619282e-03 9.984106e-01 -5.633424e-02 -4.420317e-01 3.007225e-01 5.324050e-02 9.522245e-01 1.421692e+01 +9.524710e-01 -1.858298e-02 -3.040618e-01 -2.819369e+00 -1.216390e-03 9.978977e-01 -6.479764e-02 -4.781374e-01 3.046268e-01 6.208772e-02 9.504460e-01 1.484155e+01 +9.511735e-01 -1.798416e-02 -3.081323e-01 -3.024731e+00 -5.045062e-03 9.972618e-01 -7.377885e-02 -5.190175e-01 3.086154e-01 7.173103e-02 9.484784e-01 1.547709e+01 +9.498371e-01 -1.765624e-02 -3.122464e-01 -3.237328e+00 -8.048061e-03 9.966945e-01 -8.084074e-02 -5.701376e-01 3.126416e-01 7.929850e-02 9.465553e-01 1.612456e+01 +9.481933e-01 -1.538124e-02 -3.173214e-01 -3.471584e+00 -1.300717e-02 9.961102e-01 -8.715050e-02 -6.308148e-01 3.174276e-01 8.676296e-02 9.443050e-01 1.679489e+01 +9.465823e-01 -1.443547e-02 -3.221390e-01 -3.703617e+00 -1.649625e-02 9.955216e-01 -9.308367e-02 -6.968511e-01 3.220401e-01 9.342543e-02 9.421050e-01 1.744154e+01 +9.449062e-01 -1.222398e-02 -3.271128e-01 -3.951023e+00 -2.114986e-02 9.949346e-01 -9.827402e-02 -7.690047e-01 3.266572e-01 9.977810e-02 9.398614e-01 1.811394e+01 +9.431819e-01 -9.610002e-03 -3.321379e-01 -4.206227e+00 -2.563137e-02 9.944991e-01 -1.015608e-01 -8.443717e-01 3.312869e-01 1.043034e-01 9.377472e-01 1.880104e+01 +9.414125e-01 -8.075800e-03 -3.371605e-01 -4.466634e+00 -2.826314e-02 9.943075e-01 -1.027318e-01 -9.233994e-01 3.360709e-01 1.062422e-01 9.358253e-01 1.949749e+01 +9.391912e-01 -7.945913e-03 -3.433026e-01 -4.730674e+00 -2.886858e-02 9.943662e-01 -1.019924e-01 -1.007318e+00 3.421789e-01 1.057010e-01 9.336707e-01 2.020757e+01 +9.368681e-01 -7.519302e-03 -3.496021e-01 -5.002325e+00 -2.946952e-02 9.945143e-01 -1.003630e-01 -1.091050e+00 3.484389e-01 1.043295e-01 9.315072e-01 2.092425e+01 +9.342878e-01 -7.529037e-03 -3.564403e-01 -5.285312e+00 -2.950746e-02 9.947138e-01 -9.835504e-02 -1.174887e+00 3.552966e-01 1.024095e-01 9.291268e-01 2.165513e+01 +9.310994e-01 -6.948836e-03 -3.646993e-01 -5.575589e+00 -3.003738e-02 9.949622e-01 -9.564487e-02 -1.260053e+00 3.635266e-01 1.000095e-01 9.262000e-01 2.238962e+01 +9.277392e-01 -5.077233e-03 -3.731947e-01 -5.895726e+00 -3.070041e-02 9.954809e-01 -8.986263e-02 -1.353119e+00 3.719645e-01 9.482629e-02 9.233907e-01 2.314117e+01 +9.242864e-01 -1.524340e-03 -3.816966e-01 -6.215009e+00 -3.317488e-02 9.958871e-01 -8.431084e-02 -1.438960e+00 3.802553e-01 9.059009e-02 9.204343e-01 2.387854e+01 +9.206243e-01 2.247455e-03 -3.904432e-01 -6.553189e+00 -3.648772e-02 9.961026e-01 -8.030049e-02 -1.526495e+00 3.887411e-01 8.817295e-02 9.171183e-01 2.462981e+01 +9.168008e-01 3.486620e-03 -3.993296e-01 -6.893668e+00 -3.796477e-02 9.961938e-01 -7.846345e-02 -1.606967e+00 3.975361e-01 8.709580e-02 9.134437e-01 2.538492e+01 +9.127707e-01 3.235865e-03 -4.084594e-01 -7.246162e+00 -3.828632e-02 9.962441e-01 -7.766479e-02 -1.685830e+00 4.066740e-01 8.652854e-02 9.094664e-01 2.614716e+01 +9.088636e-01 3.268540e-03 -4.170807e-01 -7.606334e+00 -3.875321e-02 9.963054e-01 -7.663965e-02 -1.761966e+00 4.152893e-01 8.581819e-02 9.056324e-01 2.691437e+01 +9.048830e-01 4.608140e-03 -4.256354e-01 -7.982190e+00 -4.021677e-02 9.963939e-01 -7.471170e-02 -1.839860e+00 4.237562e-01 8.472302e-02 9.018052e-01 2.768873e+01 +9.011219e-01 3.561205e-03 -4.335513e-01 -8.362269e+00 -3.882330e-02 9.966120e-01 -7.250673e-02 -1.915761e+00 4.318242e-01 8.216928e-02 8.982072e-01 2.846912e+01 +8.972017e-01 4.003364e-03 -4.416029e-01 -8.757075e+00 -3.820143e-02 9.969142e-01 -6.857602e-02 -1.990234e+00 4.399657e-01 7.839636e-02 8.945860e-01 2.926142e+01 +8.934531e-01 6.286261e-03 -4.491125e-01 -9.164411e+00 -3.863652e-02 9.972714e-01 -6.290362e-02 -2.060214e+00 4.474917e-01 7.355357e-02 8.912582e-01 3.005971e+01 +8.896269e-01 6.524173e-03 -4.566414e-01 -9.580703e+00 -3.732651e-02 9.975913e-01 -5.846647e-02 -2.130016e+00 4.551601e-01 6.905817e-02 8.877276e-01 3.086421e+01 +8.858290e-01 5.849285e-03 -4.639749e-01 -1.000712e+01 -3.614492e-02 9.977521e-01 -5.642995e-02 -2.196452e+00 4.626019e-01 6.675761e-02 8.840492e-01 3.167496e+01 +8.825642e-01 4.764472e-03 -4.701677e-01 -1.044426e+01 -3.498797e-02 9.978418e-01 -5.556515e-02 -2.258264e+00 4.688883e-01 6.549002e-02 8.808262e-01 3.249206e+01 +8.793579e-01 5.398335e-03 -4.761309e-01 -1.089504e+01 -3.522844e-02 9.979329e-01 -5.374831e-02 -2.319480e+00 4.748566e-01 6.403734e-02 8.777303e-01 3.331700e+01 +8.764052e-01 4.444602e-03 -4.815539e-01 -1.135407e+01 -3.365615e-02 9.980776e-01 -5.204062e-02 -2.381080e+00 4.803969e-01 6.181591e-02 8.748701e-01 3.415206e+01 +8.737377e-01 3.155669e-03 -4.863872e-01 -1.182494e+01 -3.246567e-02 9.981273e-01 -5.184495e-02 -2.443855e+00 4.853127e-01 6.108977e-02 8.722039e-01 3.499697e+01 +8.716007e-01 2.167155e-03 -4.902118e-01 -1.230225e+01 -3.196712e-02 9.981130e-01 -5.242529e-02 -2.505327e+00 4.891732e-01 6.136457e-02 8.700253e-01 3.584444e+01 +8.701921e-01 2.319482e-03 -4.927072e-01 -1.279251e+01 -3.265581e-02 9.980616e-01 -5.297637e-02 -2.570879e+00 4.916293e-01 6.218936e-02 8.685811e-01 3.672204e+01 +8.697487e-01 2.525150e-03 -4.934884e-01 -1.328826e+01 -3.229971e-02 9.981340e-01 -5.181923e-02 -2.638091e+00 4.924367e-01 6.100923e-02 8.682073e-01 3.761620e+01 +8.696349e-01 2.975155e-03 -4.936865e-01 -1.378452e+01 -3.195058e-02 9.982247e-01 -5.026564e-02 -2.707338e+00 4.926605e-01 5.948631e-02 8.681861e-01 3.851664e+01 +8.694144e-01 1.873861e-03 -4.940800e-01 -1.428954e+01 -3.037506e-02 9.983040e-01 -4.966368e-02 -2.775142e+00 4.931490e-01 5.818602e-02 8.679968e-01 3.942708e+01 +8.687731e-01 1.966427e-05 -4.952104e-01 -1.480797e+01 -2.858148e-02 9.983350e-01 -5.010232e-02 -2.841759e+00 4.943849e-01 5.768139e-02 8.673272e-01 4.034309e+01 +8.676927e-01 -2.580071e-03 -4.970943e-01 -1.533465e+01 -2.612420e-02 9.983680e-01 -5.078240e-02 -2.909137e+00 4.964140e-01 5.704970e-02 8.662092e-01 4.126523e+01 +8.661087e-01 -3.152817e-03 -4.998457e-01 -1.586740e+01 -2.470117e-02 9.984884e-01 -4.909906e-02 -2.976585e+00 4.992450e-01 5.487189e-02 8.647217e-01 4.219040e+01 +8.640267e-01 -2.135530e-03 -5.034415e-01 -1.640548e+01 -2.364757e-02 9.987151e-01 -4.482132e-02 -3.043619e+00 5.028904e-01 5.063198e-02 8.628660e-01 4.311456e+01 +8.612122e-01 -2.515559e-03 -5.082394e-01 -1.694522e+01 -2.112709e-02 9.989462e-01 -4.074421e-02 -3.108900e+00 5.078064e-01 4.582703e-02 8.602515e-01 4.403507e+01 +8.573170e-01 -2.322740e-03 -5.147836e-01 -1.749249e+01 -2.029804e-02 9.990596e-01 -3.831204e-02 -3.173069e+00 5.143885e-01 4.329465e-02 8.564637e-01 4.494973e+01 +8.520813e-01 -5.804948e-03 -5.233772e-01 -1.804673e+01 -1.816238e-02 9.990084e-01 -4.064949e-02 -3.235637e+00 5.230942e-01 4.414244e-02 8.511310e-01 4.585695e+01 +8.459794e-01 -9.821908e-03 -5.331251e-01 -1.861936e+01 -1.617194e-02 9.988977e-01 -4.406510e-02 -3.298545e+00 5.329703e-01 4.589983e-02 8.448881e-01 4.676609e+01 +8.398031e-01 -1.033534e-02 -5.427928e-01 -1.921229e+01 -1.601771e-02 9.989118e-01 -4.380276e-02 -3.356507e+00 5.426548e-01 4.547998e-02 8.387236e-01 4.766232e+01 +8.339495e-01 -6.907958e-03 -5.517976e-01 -1.982282e+01 -1.727628e-02 9.991047e-01 -3.861801e-02 -3.410242e+00 5.515704e-01 4.173847e-02 8.330835e-01 4.855068e+01 +8.287116e-01 -1.605836e-03 -5.596736e-01 -2.043384e+01 -2.050625e-02 9.992373e-01 -3.323077e-02 -3.465273e+00 5.593001e-01 3.901553e-02 8.280466e-01 4.943336e+01 +8.244741e-01 -1.420809e-03 -5.658979e-01 -2.105696e+01 -2.183704e-02 9.991721e-01 -3.432370e-02 -3.517140e+00 5.654782e-01 4.065653e-02 8.237606e-01 5.029682e+01 +8.208828e-01 -4.306569e-03 -5.710805e-01 -2.167507e+01 -2.223179e-02 9.989726e-01 -3.948978e-02 -3.574727e+00 5.706639e-01 4.511262e-02 8.199437e-01 5.115815e+01 +8.179645e-01 -6.412380e-03 -5.752329e-01 -2.229860e+01 -2.497150e-02 9.985995e-01 -4.664059e-02 -3.635034e+00 5.747265e-01 5.251477e-02 8.166589e-01 5.201179e+01 +8.145803e-01 -6.933137e-03 -5.800093e-01 -2.292529e+01 -2.492187e-02 9.985869e-01 -4.693753e-02 -3.696616e+00 5.795151e-01 5.268930e-02 8.132565e-01 5.287389e+01 +8.111073e-01 -6.174055e-03 -5.848649e-01 -2.356010e+01 -2.436094e-02 9.987200e-01 -4.432731e-02 -3.761561e+00 5.843899e-01 5.020205e-02 8.099186e-01 5.373417e+01 +8.078624e-01 -2.799690e-03 -5.893645e-01 -2.420131e+01 -2.439166e-02 9.989731e-01 -3.817998e-02 -3.822517e+00 5.888662e-01 4.521974e-02 8.069646e-01 5.459689e+01 +8.047634e-01 -1.072406e-03 -5.935948e-01 -2.484571e+01 -2.455639e-02 9.990821e-01 -3.509719e-02 -3.875701e+00 5.930876e-01 4.282147e-02 8.039984e-01 5.545675e+01 +8.016398e-01 -7.168066e-04 -5.978070e-01 -2.549478e+01 -2.557654e-02 9.990425e-01 -3.549523e-02 -3.921434e+00 5.972600e-01 4.374422e-02 8.008539e-01 5.631342e+01 +7.980946e-01 -1.906616e-03 -6.025291e-01 -2.614832e+01 -2.569411e-02 9.989776e-01 -3.719488e-02 -3.971575e+00 6.019841e-01 4.516647e-02 7.972297e-01 5.717032e+01 +7.940434e-01 -4.490124e-03 -6.078445e-01 -2.680899e+01 -2.469164e-02 9.989091e-01 -3.963425e-02 -4.019298e+00 6.073594e-01 4.647998e-02 7.930663e-01 5.801515e+01 +7.896376e-01 -5.883988e-03 -6.135453e-01 -2.748253e+01 -2.381542e-02 9.989066e-01 -4.023028e-02 -4.070618e+00 6.131112e-01 4.637917e-02 7.886340e-01 5.886465e+01 +7.851233e-01 -5.698290e-03 -6.193132e-01 -2.815970e+01 -2.355687e-02 9.989593e-01 -3.905521e-02 -4.126091e+00 6.188913e-01 4.525223e-02 7.841721e-01 5.969578e+01 +7.801529e-01 -5.230775e-03 -6.255670e-01 -2.884498e+01 -2.393247e-02 9.989835e-01 -3.819965e-02 -4.187294e+00 6.251310e-01 4.477292e-02 7.792347e-01 6.053112e+01 +7.747575e-01 -6.527504e-03 -6.322248e-01 -2.954119e+01 -2.367156e-02 9.989461e-01 -3.932200e-02 -4.248257e+00 6.318152e-01 4.543076e-02 7.737865e-01 6.136091e+01 +7.692225e-01 -8.108737e-03 -6.389295e-01 -3.024500e+01 -2.299429e-02 9.989205e-01 -4.036080e-02 -4.308387e+00 6.385672e-01 4.573816e-02 7.682057e-01 6.219212e+01 +7.635463e-01 -9.127523e-03 -6.456885e-01 -3.095782e+01 -2.273018e-02 9.989006e-01 -4.099969e-02 -4.369134e+00 6.453529e-01 4.598178e-02 7.624994e-01 6.301777e+01 +7.578107e-01 -1.050982e-02 -6.523898e-01 -3.167830e+01 -2.224842e-02 9.988726e-01 -4.193515e-02 -4.431688e+00 6.520951e-01 4.629354e-02 7.567225e-01 6.384049e+01 +7.515981e-01 -1.253177e-02 -6.595023e-01 -3.241736e+01 -2.142438e-02 9.988282e-01 -4.339578e-02 -4.495389e+00 6.592733e-01 4.674561e-02 7.504489e-01 6.466956e+01 +7.453405e-01 -1.321772e-02 -6.665529e-01 -3.316065e+01 -2.063561e-02 9.988670e-01 -4.288227e-02 -4.558237e+00 6.663645e-01 4.571662e-02 7.442233e-01 6.548993e+01 +7.390352e-01 -1.353693e-02 -6.735308e-01 -3.390236e+01 -1.966365e-02 9.989386e-01 -4.165317e-02 -4.621788e+00 6.733798e-01 4.402723e-02 7.379846e-01 6.629394e+01 +7.325427e-01 -1.349799e-02 -6.805872e-01 -3.467370e+01 -1.927296e-02 9.989913e-01 -4.055710e-02 -4.690830e+00 6.804482e-01 4.282673e-02 7.315437e-01 6.709446e+01 +7.260757e-01 -1.543598e-02 -6.874415e-01 -3.545262e+01 -1.787203e-02 9.989866e-01 -4.130792e-02 -4.759468e+00 6.873825e-01 4.227865e-02 7.250640e-01 6.789101e+01 +7.194909e-01 -1.708224e-02 -6.942917e-01 -3.625058e+01 -1.775566e-02 9.989182e-01 -4.297733e-02 -4.834985e+00 6.942749e-01 4.324940e-02 7.184093e-01 6.868199e+01 +7.133849e-01 -1.644260e-02 -7.005795e-01 -3.705458e+01 -1.919797e-02 9.988909e-01 -4.299285e-02 -4.906233e+00 7.005094e-01 4.412015e-02 7.122780e-01 6.947298e+01 +7.078765e-01 -1.558863e-02 -7.061641e-01 -3.787518e+01 -1.972175e-02 9.989304e-01 -4.182105e-02 -4.981378e+00 7.060608e-01 4.353093e-02 7.068120e-01 7.026199e+01 +7.028426e-01 -1.503627e-02 -7.111865e-01 -3.869255e+01 -2.087974e-02 9.989097e-01 -4.175424e-02 -5.057858e+00 7.110389e-01 4.419604e-02 7.017623e-01 7.105256e+01 +6.978988e-01 -1.609744e-02 -7.160154e-01 -3.951886e+01 -2.079239e-02 9.988706e-01 -4.272289e-02 -5.137328e+00 7.158945e-01 4.470392e-02 6.967759e-01 7.183896e+01 +6.926488e-01 -1.780251e-02 -7.210553e-01 -4.035157e+01 -2.147030e-02 9.987434e-01 -4.528296e-02 -5.214173e+00 7.209554e-01 4.684646e-02 6.913962e-01 7.262312e+01 +6.875324e-01 -2.030697e-02 -7.258697e-01 -4.119284e+01 -2.112818e-02 9.986262e-01 -4.794991e-02 -5.292359e+00 7.258462e-01 4.830342e-02 6.861589e-01 7.340570e+01 +6.824175e-01 -2.114368e-02 -7.306568e-01 -4.204713e+01 -2.154098e-02 9.985657e-01 -4.901522e-02 -5.369497e+00 7.306452e-01 4.918790e-02 6.809833e-01 7.418462e+01 +6.774179e-01 -2.029179e-02 -7.353185e-01 -4.291451e+01 -2.142543e-02 9.986510e-01 -4.729704e-02 -5.443967e+00 7.352864e-01 4.779437e-02 6.760693e-01 7.495793e+01 +6.722415e-01 -2.004618e-02 -7.400605e-01 -4.378384e+01 -2.098920e-02 9.987154e-01 -4.611819e-02 -5.527046e+00 7.400343e-01 4.653583e-02 6.709572e-01 7.573564e+01 +6.671161e-01 -2.124206e-02 -7.446508e-01 -4.465831e+01 -1.993251e-02 9.987265e-01 -4.634697e-02 -5.602316e+00 7.446871e-01 4.576156e-02 6.658432e-01 7.650974e+01 +6.622093e-01 -2.216481e-02 -7.489911e-01 -4.553830e+01 -1.912889e-02 9.987366e-01 -4.646803e-02 -5.677124e+00 7.490748e-01 4.509892e-02 6.609486e-01 7.727779e+01 +6.576917e-01 -2.323860e-02 -7.529287e-01 -4.643229e+01 -1.800770e-02 9.987533e-01 -4.655573e-02 -5.751800e+00 7.530720e-01 4.417783e-02 6.564533e-01 7.805127e+01 +6.537987e-01 -2.382555e-02 -7.562933e-01 -4.733404e+01 -1.710334e-02 9.987834e-01 -4.625018e-02 -5.824835e+00 7.564752e-01 4.317344e-02 6.525958e-01 7.882482e+01 +6.498156e-01 -2.593030e-02 -7.596494e-01 -4.823900e+01 -1.455254e-02 9.988103e-01 -4.654242e-02 -5.898424e+00 7.599526e-01 4.129881e-02 6.486652e-01 7.959620e+01 +6.455088e-01 -3.066921e-02 -7.631368e-01 -4.915220e+01 -1.116925e-02 9.987075e-01 -4.958406e-02 -5.978524e+00 7.636711e-01 4.053061e-02 6.443320e-01 8.036127e+01 +6.404574e-01 -3.548947e-02 -7.671733e-01 -5.007598e+01 -6.858730e-03 9.986275e-01 -5.192241e-02 -6.064360e+00 7.679631e-01 3.851592e-02 6.393350e-01 8.112920e+01 +6.339648e-01 -3.935732e-02 -7.723598e-01 -5.100162e+01 -1.638042e-03 9.986336e-01 -5.223215e-02 -6.153399e+00 7.733602e-01 3.437850e-02 6.330341e-01 8.189059e+01 +6.255042e-01 -4.266600e-02 -7.790533e-01 -5.194082e+01 2.937217e-03 9.986254e-01 -5.233290e-02 -6.240477e+00 7.802153e-01 3.044620e-02 6.247697e-01 8.264668e+01 +6.162967e-01 -4.426734e-02 -7.862689e-01 -5.289570e+01 6.310456e-03 9.986644e-01 -5.127903e-02 -6.326822e+00 7.874888e-01 2.664138e-02 6.157530e-01 8.339659e+01 +6.073443e-01 -4.248918e-02 -7.933016e-01 -5.386648e+01 6.689869e-03 9.988068e-01 -4.837433e-02 -6.412013e+00 7.944106e-01 2.407279e-02 6.069040e-01 8.413486e+01 +5.981988e-01 -4.203976e-02 -8.002442e-01 -5.484867e+01 6.320427e-03 9.988394e-01 -4.774805e-02 -6.495943e+00 8.013228e-01 2.350495e-02 5.977703e-01 8.486188e+01 +5.885635e-01 -4.399805e-02 -8.072529e-01 -5.584158e+01 5.492000e-03 9.987125e-01 -5.042908e-02 -6.577872e+00 8.084324e-01 2.524728e-02 5.880474e-01 8.557728e+01 +5.784770e-01 -4.577277e-02 -8.144134e-01 -5.684458e+01 6.190303e-03 9.986419e-01 -5.173007e-02 -6.660712e+00 8.156752e-01 2.488319e-02 5.779747e-01 8.628487e+01 +5.684993e-01 -4.744552e-02 -8.213145e-01 -5.785918e+01 6.431293e-03 9.985614e-01 -5.323306e-02 -6.747722e+00 8.226586e-01 2.498085e-02 5.679866e-01 8.698373e+01 +5.581987e-01 -4.826769e-02 -8.283022e-01 -5.888092e+01 8.995736e-03 9.985998e-01 -5.212917e-02 -6.837334e+00 8.296586e-01 2.164725e-02 5.578513e-01 8.767629e+01 +5.476275e-01 -4.823126e-02 -8.353310e-01 -5.991653e+01 1.046800e-02 9.986540e-01 -5.079877e-02 -6.928351e+00 8.366568e-01 1.907456e-02 5.473953e-01 8.835909e+01 +5.371294e-01 -4.842119e-02 -8.421089e-01 -6.096415e+01 1.073061e-02 9.986624e-01 -5.057862e-02 -7.015079e+00 8.434316e-01 1.813092e-02 5.369306e-01 8.902721e+01 +5.267133e-01 -4.963826e-02 -8.485925e-01 -6.202188e+01 1.031530e-02 9.985933e-01 -5.200993e-02 -7.102980e+00 8.499805e-01 1.864083e-02 5.264844e-01 8.968383e+01 +5.164917e-01 -5.044852e-02 -8.548048e-01 -6.309538e+01 8.987048e-03 9.985274e-01 -5.350052e-02 -7.192800e+00 8.562450e-01 1.995041e-02 5.161845e-01 9.032891e+01 +5.064670e-01 -5.110642e-02 -8.607435e-01 -6.417133e+01 7.655844e-03 9.984691e-01 -5.477910e-02 -7.283912e+00 8.622254e-01 2.115409e-02 5.060829e-01 9.095949e+01 +4.966546e-01 -5.105676e-02 -8.664453e-01 -6.526817e+01 6.786521e-03 9.984662e-01 -5.494623e-02 -7.374808e+00 8.679218e-01 2.140915e-02 4.962393e-01 9.158512e+01 +4.877562e-01 -4.910681e-02 -8.715976e-01 -6.637327e+01 5.825330e-03 9.985774e-01 -5.300109e-02 -7.465671e+00 8.729605e-01 2.077427e-02 4.873484e-01 9.220094e+01 +4.796069e-01 -4.700544e-02 -8.762235e-01 -6.748666e+01 6.149553e-03 9.987197e-01 -5.021082e-02 -7.555186e+00 8.774620e-01 1.869307e-02 4.792819e-01 9.280938e+01 +4.719319e-01 -4.732563e-02 -8.803639e-01 -6.860646e+01 6.426764e-03 9.987163e-01 -5.024274e-02 -7.643588e+00 8.816116e-01 1.805326e-02 4.716302e-01 9.340826e+01 +4.642322e-01 -5.055978e-02 -8.842693e-01 -6.972870e+01 8.322060e-03 9.985743e-01 -5.272640e-02 -7.731317e+00 8.856745e-01 1.711835e-02 4.639911e-01 9.399874e+01 +4.570917e-01 -5.386987e-02 -8.877867e-01 -7.085828e+01 1.099739e-02 9.984301e-01 -5.492140e-02 -7.820048e+00 8.893516e-01 1.534078e-02 4.569666e-01 9.458336e+01 +4.508577e-01 -5.668127e-02 -8.907943e-01 -7.199157e+01 1.202786e-02 9.982769e-01 -5.743274e-02 -7.914147e+00 8.925148e-01 1.517964e-02 4.507626e-01 9.515810e+01 +4.452960e-01 -6.019002e-02 -8.933581e-01 -7.313057e+01 1.382460e-02 9.980812e-01 -6.035486e-02 -8.011910e+00 8.952767e-01 1.452546e-02 4.452737e-01 9.572828e+01 +4.404362e-01 -6.118295e-02 -8.956967e-01 -7.426251e+01 1.648406e-02 9.980581e-01 -6.006941e-02 -8.110093e+00 8.976326e-01 1.169203e-02 4.405895e-01 9.628811e+01 +4.361561e-01 -5.858994e-02 -8.979616e-01 -7.540274e+01 1.780717e-02 9.982447e-01 -5.648393e-02 -8.209520e+00 8.996949e-01 8.645658e-03 4.364338e-01 9.684446e+01 +4.322135e-01 -5.653957e-02 -8.999971e-01 -7.658015e+01 2.112313e-02 9.983934e-01 -5.257689e-02 -8.308009e+00 9.015239e-01 3.713691e-03 4.327134e-01 9.741509e+01 +4.288446e-01 -5.587980e-02 -9.016483e-01 -7.767611e+01 2.281072e-02 9.984366e-01 -5.102898e-02 -8.396730e+00 9.030903e-01 1.316265e-03 4.294489e-01 9.793967e+01 +4.259122e-01 -5.624384e-02 -9.030146e-01 -7.880716e+01 2.445442e-02 9.984169e-01 -5.065187e-02 -8.486978e+00 9.044340e-01 -5.094444e-04 4.266134e-01 9.847551e+01 +4.232849e-01 -5.523644e-02 -9.043112e-01 -7.993532e+01 2.629154e-02 9.984682e-01 -4.868128e-02 -8.574915e+00 9.056151e-01 -3.169679e-03 4.240888e-01 9.900669e+01 +4.209215e-01 -5.420603e-02 -9.054760e-01 -8.106306e+01 2.773444e-02 9.985153e-01 -4.688312e-02 -8.661986e+00 9.066730e-01 -5.378750e-03 4.217999e-01 9.953295e+01 +4.186668e-01 -5.526254e-02 -9.064569e-01 -8.218012e+01 3.037902e-02 9.984404e-01 -4.683916e-02 -8.741442e+00 9.076317e-01 -7.927263e-03 4.196927e-01 1.000567e+02 +4.160303e-01 -5.553146e-02 -9.076536e-01 -8.328006e+01 3.246276e-02 9.984044e-01 -4.620416e-02 -8.827999e+00 9.087711e-01 -1.024260e-02 4.171692e-01 1.005627e+02 +4.134067e-01 -5.475406e-02 -9.088987e-01 -8.437076e+01 3.570778e-02 9.983974e-01 -4.390421e-02 -8.914608e+00 9.098461e-01 -1.430446e-02 4.146993e-01 1.010627e+02 +4.112317e-01 -5.406871e-02 -9.099258e-01 -8.546189e+01 3.750869e-02 9.983975e-01 -4.237413e-02 -8.996530e+00 9.107588e-01 -1.670453e-02 4.126007e-01 1.015536e+02 +4.093026e-01 -5.479425e-02 -9.107519e-01 -8.654683e+01 3.979175e-02 9.983173e-01 -4.217965e-02 -9.072686e+00 9.115306e-01 -1.897616e-02 4.107942e-01 1.020328e+02 +4.079197e-01 -5.622149e-02 -9.112852e-01 -8.762037e+01 4.108249e-02 9.982216e-01 -4.319522e-02 -9.149512e+00 9.120931e-01 -1.981767e-02 4.095040e-01 1.025091e+02 +4.072736e-01 -5.741360e-02 -9.114998e-01 -8.868276e+01 4.121229e-02 9.981608e-01 -4.445787e-02 -9.227599e+00 9.123759e-01 -1.945848e-02 4.088907e-01 1.029766e+02 +4.075927e-01 -5.795142e-02 -9.113231e-01 -8.974022e+01 4.017833e-02 9.981559e-01 -4.550326e-02 -9.305889e+00 9.122795e-01 -1.806864e-02 4.091694e-01 1.034282e+02 +4.096552e-01 -5.776576e-02 -9.104097e-01 -9.078632e+01 3.799735e-02 9.982074e-01 -4.623898e-02 -9.383578e+00 9.114488e-01 -1.565111e-02 4.111158e-01 1.038744e+02 +4.139154e-01 -5.777102e-02 -9.084803e-01 -9.182278e+01 3.564327e-02 9.982474e-01 -4.723986e-02 -9.462617e+00 9.096173e-01 -1.282790e-02 4.152491e-01 1.043271e+02 +4.190585e-01 -5.806051e-02 -9.061009e-01 -9.285032e+01 3.396838e-02 9.982572e-01 -4.825577e-02 -9.540419e+00 9.073236e-01 -1.055678e-02 4.203004e-01 1.047844e+02 +4.248597e-01 -5.821256e-02 -9.033856e-01 -9.387053e+01 3.328904e-02 9.982600e-01 -4.867036e-02 -9.609312e+00 9.046470e-01 -9.394764e-03 4.260582e-01 1.052557e+02 +4.318136e-01 -5.709458e-02 -9.001540e-01 -9.488237e+01 3.225411e-02 9.983336e-01 -4.784925e-02 -9.680288e+00 9.013860e-01 -8.371707e-03 4.329355e-01 1.057334e+02 +4.399854e-01 -5.549092e-02 -8.962888e-01 -9.588621e+01 3.065506e-02 9.984353e-01 -4.676655e-02 -9.749076e+00 8.974816e-01 -6.899180e-03 4.409981e-01 1.062164e+02 +4.488454e-01 -5.517551e-02 -8.919044e-01 -9.688157e+01 3.026825e-02 9.984580e-01 -4.653489e-02 -9.818909e+00 8.930967e-01 -6.109403e-03 4.498233e-01 1.067096e+02 +4.583543e-01 -5.470388e-02 -8.870844e-01 -9.786840e+01 2.959346e-02 9.984899e-01 -4.628307e-02 -9.886761e+00 8.882767e-01 -5.037850e-03 4.592811e-01 1.072111e+02 +4.681770e-01 -5.512405e-02 -8.819136e-01 -9.884290e+01 2.851588e-02 9.984749e-01 -4.727166e-02 -9.958087e+00 8.831745e-01 -3.017038e-03 4.690349e-01 1.077189e+02 +4.786921e-01 -5.678936e-02 -8.761443e-01 -9.980583e+01 2.678003e-02 9.983860e-01 -5.008117e-02 -1.002675e+01 8.775744e-01 5.102926e-04 4.794403e-01 1.082398e+02 +4.900937e-01 -5.746268e-02 -8.697736e-01 -1.007547e+02 2.497006e-02 9.983407e-01 -5.188669e-02 -1.009360e+01 8.713120e-01 3.711045e-03 4.907154e-01 1.087790e+02 +5.023364e-01 -5.599002e-02 -8.628576e-01 -1.016995e+02 2.292463e-02 9.984129e-01 -5.143988e-02 -1.015566e+01 8.643683e-01 6.059441e-03 5.028227e-01 1.093330e+02 +5.152097e-01 -5.315552e-02 -8.554142e-01 -1.026360e+02 2.128305e-02 9.985606e-01 -4.923204e-02 -1.021665e+01 8.567999e-01 7.159000e-03 5.155994e-01 1.099002e+02 +5.277749e-01 -5.081668e-02 -8.478628e-01 -1.035604e+02 2.039561e-02 9.986791e-01 -4.716007e-02 -1.027636e+01 8.491394e-01 7.597224e-03 5.281142e-01 1.104797e+02 +5.396874e-01 -5.040390e-02 -8.403553e-01 -1.044750e+02 2.077497e-02 9.986994e-01 -4.655932e-02 -1.032552e+01 8.416092e-01 7.669122e-03 5.400326e-01 1.110646e+02 +5.512438e-01 -5.094885e-02 -8.327871e-01 -1.053784e+02 2.099405e-02 9.986648e-01 -4.720052e-02 -1.037734e+01 8.340800e-01 8.535420e-03 5.515774e-01 1.116592e+02 +5.624291e-01 -5.175227e-02 -8.252243e-01 -1.062592e+02 2.137600e-02 9.986158e-01 -4.805743e-02 -1.042733e+01 8.265692e-01 9.388904e-03 5.627568e-01 1.122557e+02 +5.735172e-01 -5.312901e-02 -8.174688e-01 -1.071244e+02 2.315143e-02 9.985473e-01 -4.865518e-02 -1.048384e+01 8.188663e-01 8.979010e-03 5.739141e-01 1.128599e+02 +5.843075e-01 -5.366822e-02 -8.097558e-01 -1.079760e+02 2.417163e-02 9.985191e-01 -4.873702e-02 -1.053886e+01 8.111723e-01 8.904287e-03 5.847395e-01 1.134723e+02 +5.951811e-01 -5.121604e-02 -8.019578e-01 -1.088156e+02 2.304136e-02 9.986442e-01 -4.667680e-02 -1.059968e+01 8.032612e-01 9.302959e-03 5.955543e-01 1.140873e+02 +6.052642e-01 -4.844117e-02 -7.945493e-01 -1.096406e+02 2.329405e-02 9.987970e-01 -4.314880e-02 -1.065546e+01 7.956838e-01 7.608155e-03 6.056645e-01 1.147106e+02 +6.153476e-01 -4.667761e-02 -7.868726e-01 -1.104479e+02 2.193382e-02 9.988725e-01 -4.210092e-02 -1.071449e+01 7.879507e-01 8.647581e-03 6.156777e-01 1.153330e+02 +6.256110e-01 -4.603175e-02 -7.787760e-01 -1.112427e+02 1.999751e-02 9.988759e-01 -4.297687e-02 -1.076967e+01 7.798789e-01 1.131322e-02 6.258282e-01 1.159602e+02 +6.352746e-01 -4.586128e-02 -7.709234e-01 -1.120216e+02 1.832673e-02 9.988493e-01 -4.431830e-02 -1.082745e+01 7.720689e-01 1.402579e-02 6.353841e-01 1.165904e+02 +6.446320e-01 -4.556259e-02 -7.631341e-01 -1.127849e+02 1.810481e-02 9.988523e-01 -4.434261e-02 -1.088440e+01 7.642787e-01 1.476827e-02 6.447171e-01 1.172256e+02 +6.539294e-01 -4.355499e-02 -7.553008e-01 -1.135420e+02 1.795909e-02 9.989538e-01 -4.205669e-02 -1.094072e+01 7.563424e-01 1.393759e-02 6.540275e-01 1.178586e+02 +6.627892e-01 -4.156585e-02 -7.476515e-01 -1.142854e+02 1.771950e-02 9.990492e-01 -3.983412e-02 -1.099692e+01 7.485964e-01 1.315362e-02 6.628955e-01 1.184946e+02 +6.711328e-01 -4.096189e-02 -7.402046e-01 -1.150150e+02 1.832210e-02 9.990838e-01 -3.867553e-02 -1.105074e+01 7.411107e-01 1.239431e-02 6.712685e-01 1.191327e+02 +6.790069e-01 -4.041487e-02 -7.330186e-01 -1.157305e+02 1.725344e-02 9.990862e-01 -3.910235e-02 -1.110434e+01 7.339292e-01 1.390367e-02 6.790837e-01 1.197729e+02 +6.866300e-01 -3.934016e-02 -7.259419e-01 -1.164343e+02 1.654401e-02 9.991218e-01 -3.849619e-02 -1.115559e+01 7.268188e-01 1.442265e-02 6.866778e-01 1.204136e+02 +6.940511e-01 -3.716524e-02 -7.189658e-01 -1.171234e+02 1.591975e-02 9.992147e-01 -3.628398e-02 -1.120384e+01 7.197497e-01 1.373718e-02 6.940977e-01 1.210568e+02 +7.019590e-01 -3.415441e-02 -7.113979e-01 -1.177905e+02 1.490303e-02 9.993352e-01 -3.327307e-02 -1.124261e+01 7.120614e-01 1.275435e-02 7.020014e-01 1.216885e+02 +7.095204e-01 -3.197352e-02 -7.039592e-01 -1.184457e+02 1.340608e-02 9.994018e-01 -3.188042e-02 -1.128508e+01 7.045574e-01 1.318247e-02 7.095246e-01 1.223238e+02 +7.174647e-01 -3.178964e-02 -6.958691e-01 -1.190789e+02 1.320678e-02 9.993993e-01 -3.203928e-02 -1.132614e+01 6.964697e-01 1.379686e-02 7.174536e-01 1.229483e+02 +7.256900e-01 -2.896043e-02 -6.874120e-01 -1.197016e+02 1.057531e-02 9.994652e-01 -3.094294e-02 -1.136777e+01 6.879406e-01 1.518538e-02 7.256082e-01 1.235775e+02 +7.348171e-01 -2.580783e-02 -6.777742e-01 -1.203051e+02 9.460201e-03 9.995686e-01 -2.780453e-02 -1.140579e+01 6.781994e-01 1.401936e-02 7.347442e-01 1.242110e+02 +7.443270e-01 -2.213196e-02 -6.674484e-01 -1.208956e+02 7.719389e-03 9.996690e-01 -2.453955e-02 -1.144246e+01 6.677707e-01 1.311316e-02 7.442516e-01 1.248571e+02 +7.547535e-01 -2.039380e-02 -6.556914e-01 -1.214729e+02 6.117148e-03 9.996920e-01 -2.405184e-02 -1.147772e+01 6.559800e-01 1.414225e-02 7.546458e-01 1.255059e+02 +7.647006e-01 -1.960252e-02 -6.440875e-01 -1.220228e+02 4.656869e-03 9.996792e-01 -2.489588e-02 -1.151095e+01 6.443689e-01 1.603846e-02 7.645466e-01 1.261435e+02 +7.746034e-01 -2.018036e-02 -6.321253e-01 -1.225640e+02 4.578040e-03 9.996435e-01 -2.630334e-02 -1.154304e+01 6.324308e-01 1.748076e-02 7.744196e-01 1.267939e+02 +7.846071e-01 -2.075187e-02 -6.196459e-01 -1.230910e+02 4.942859e-03 9.996173e-01 -2.721834e-02 -1.157569e+01 6.199736e-01 1.829288e-02 7.844094e-01 1.274499e+02 +7.948394e-01 -1.834724e-02 -6.065424e-01 -1.236107e+02 4.025130e-03 9.996802e-01 -2.496453e-02 -1.160825e+01 6.068065e-01 1.740138e-02 7.946591e-01 1.281154e+02 +8.050896e-01 -1.614937e-02 -5.929333e-01 -1.241152e+02 3.688719e-03 9.997463e-01 -2.222092e-02 -1.163984e+01 5.931417e-01 1.570267e-02 8.049449e-01 1.287847e+02 +8.148581e-01 -1.492357e-02 -5.794684e-01 -1.246090e+02 4.098955e-03 9.997919e-01 -1.998452e-02 -1.167018e+01 5.796460e-01 1.390933e-02 8.147497e-01 1.294645e+02 +8.240620e-01 -1.381468e-02 -5.663311e-01 -1.250882e+02 4.893593e-03 9.998389e-01 -1.726876e-02 -1.170293e+01 5.664785e-01 1.145913e-02 8.239969e-01 1.301548e+02 +8.323700e-01 -1.296992e-02 -5.540686e-01 -1.255569e+02 5.316225e-03 9.998670e-01 -1.541890e-02 -1.173561e+01 5.541949e-01 9.888676e-03 8.323282e-01 1.308488e+02 +8.396772e-01 -1.327468e-02 -5.429235e-01 -1.260103e+02 6.847246e-03 9.998805e-01 -1.385761e-02 -1.177774e+01 5.430427e-01 7.918387e-03 8.396678e-01 1.315496e+02 +8.464589e-01 -1.351566e-02 -5.322824e-01 -1.264556e+02 7.459736e-03 9.998807e-01 -1.352606e-02 -1.180813e+01 5.324018e-01 7.478573e-03 8.464588e-01 1.322593e+02 +8.533775e-01 -1.258659e-02 -5.211414e-01 -1.269007e+02 6.571248e-03 9.998887e-01 -1.338875e-02 -1.183797e+01 5.212520e-01 8.001112e-03 8.533653e-01 1.329864e+02 +8.600178e-01 -1.100492e-02 -5.101454e-01 -1.273259e+02 5.286332e-03 9.999059e-01 -1.265824e-02 -1.186483e+01 5.102367e-01 8.189516e-03 8.599950e-01 1.336942e+02 +8.663899e-01 -9.696004e-03 -4.992740e-01 -1.277507e+02 4.221191e-03 9.999179e-01 -1.209359e-02 -1.189333e+01 4.993503e-01 8.370232e-03 8.663598e-01 1.344241e+02 +8.723606e-01 -1.034370e-02 -4.887535e-01 -1.281662e+02 4.966989e-03 9.999120e-01 -1.229615e-02 -1.191791e+01 4.888377e-01 8.299043e-03 8.723353e-01 1.351627e+02 +8.775617e-01 -1.177845e-02 -4.793190e-01 -1.285745e+02 6.211317e-03 9.998936e-01 -1.319869e-02 -1.193811e+01 4.794234e-01 8.605460e-03 8.775415e-01 1.359153e+02 +8.820099e-01 -1.260976e-02 -4.710621e-01 -1.289796e+02 6.856647e-03 9.998795e-01 -1.392727e-02 -1.195018e+01 4.711810e-01 9.054083e-03 8.819901e-01 1.366699e+02 +8.855067e-01 -1.185366e-02 -4.644754e-01 -1.293903e+02 6.350882e-03 9.998899e-01 -1.340999e-02 -1.196483e+01 4.645832e-01 8.924811e-03 8.854845e-01 1.374388e+02 +8.887377e-01 -1.024149e-02 -4.583016e-01 -1.297992e+02 6.307207e-03 9.999289e-01 -1.011410e-02 -1.197619e+01 4.583726e-01 6.098182e-03 8.887392e-01 1.382215e+02 +8.919360e-01 -6.212235e-03 -4.521190e-01 -1.302152e+02 4.120608e-03 9.999757e-01 -5.610840e-03 -1.198969e+01 4.521429e-01 3.141507e-03 8.919400e-01 1.390168e+02 +8.952692e-01 -3.109988e-03 -4.455148e-01 -1.306247e+02 2.152844e-03 9.999941e-01 -2.654447e-03 -1.199943e+01 4.455205e-01 1.417323e-03 8.952706e-01 1.398168e+02 +8.985310e-01 -8.521526e-04 -4.389091e-01 -1.310349e+02 5.107788e-04 9.999994e-01 -8.958609e-04 -1.200769e+01 4.389097e-01 5.807753e-04 8.985310e-01 1.406304e+02 +9.018299e-01 1.265615e-03 -4.320894e-01 -1.314426e+02 -7.282272e-04 9.999987e-01 1.409146e-03 -1.201240e+01 4.320907e-01 -9.561481e-04 9.018297e-01 1.414623e+02 +9.051450e-01 2.656961e-03 -4.250946e-01 -1.318502e+02 -9.834504e-04 9.999909e-01 4.156186e-03 -1.201698e+01 4.251018e-01 -3.343889e-03 9.051394e-01 1.423079e+02 +9.085700e-01 2.657663e-03 -4.177243e-01 -1.322539e+02 5.308222e-06 9.999797e-01 6.373661e-03 -1.201933e+01 4.177328e-01 -5.793131e-03 9.085515e-01 1.431680e+02 +9.121360e-01 2.373924e-03 -4.098808e-01 -1.326563e+02 6.577650e-04 9.999734e-01 7.255360e-03 -1.202112e+01 4.098871e-01 -6.887477e-03 9.121103e-01 1.440415e+02 +9.158194e-01 1.804681e-03 -4.015863e-01 -1.330539e+02 1.170635e-03 9.999736e-01 7.163401e-03 -1.202274e+01 4.015886e-01 -7.030489e-03 9.157932e-01 1.449288e+02 +9.196830e-01 -8.858128e-04 -3.926607e-01 -1.334442e+02 3.786082e-03 9.999709e-01 6.611834e-03 -1.202321e+01 3.926435e-01 -7.567434e-03 9.196596e-01 1.458318e+02 +9.237461e-01 -2.419590e-03 -3.829978e-01 -1.338322e+02 4.893411e-03 9.999730e-01 5.485000e-03 -1.202503e+01 3.829742e-01 -6.940910e-03 9.237330e-01 1.467482e+02 +9.282909e-01 -3.651010e-03 -3.718368e-01 -1.342211e+02 5.282377e-03 9.999803e-01 3.368800e-03 -1.202922e+01 3.718173e-01 -5.091406e-03 9.282920e-01 1.476967e+02 +9.333695e-01 -2.591909e-03 -3.589076e-01 -1.345894e+02 3.557208e-03 9.999916e-01 2.029220e-03 -1.203712e+01 3.588994e-01 -3.170718e-03 9.333709e-01 1.486265e+02 +9.394995e-01 1.165693e-03 -3.425482e-01 -1.349441e+02 -1.171002e-05 9.999943e-01 3.370868e-03 -1.205065e+01 3.425502e-01 -3.162915e-03 9.394942e-01 1.495973e+02 +9.460789e-01 5.301932e-03 -3.238928e-01 -1.352860e+02 -3.340965e-03 9.999725e-01 6.610121e-03 -1.206100e+01 3.239190e-01 -5.171579e-03 9.460707e-01 1.505851e+02 +9.527436e-01 8.287088e-03 -3.036627e-01 -1.356069e+02 -6.125921e-03 9.999487e-01 8.068928e-03 -1.207054e+01 3.037140e-01 -5.827403e-03 9.527454e-01 1.515955e+02 +9.592679e-01 1.008173e-02 -2.823180e-01 -1.359116e+02 -7.813793e-03 9.999275e-01 9.158056e-03 -1.207541e+01 2.823899e-01 -6.579052e-03 9.592772e-01 1.526125e+02 +9.653823e-01 1.132090e-02 -2.605933e-01 -1.361882e+02 -8.917047e-03 9.999061e-01 1.040504e-02 -1.208576e+01 2.606866e-01 -7.721111e-03 9.653926e-01 1.536548e+02 +9.710369e-01 1.176226e-02 -2.386398e-01 -1.364469e+02 -9.009547e-03 9.998797e-01 1.262258e-02 -1.209323e+01 2.387596e-01 -1.010695e-02 9.710261e-01 1.547167e+02 +9.762270e-01 1.398964e-02 -2.162988e-01 -1.366825e+02 -1.071765e-02 9.998098e-01 1.629286e-02 -1.209908e+01 2.164856e-01 -1.358731e-02 9.761913e-01 1.557900e+02 +9.809216e-01 1.570219e-02 -1.937687e-01 -1.369024e+02 -1.199638e-02 9.997223e-01 2.028362e-02 -1.209800e+01 1.940334e-01 -1.757211e-02 9.808375e-01 1.568857e+02 +9.851399e-01 1.770171e-02 -1.708390e-01 -1.370941e+02 -1.381150e-02 9.996181e-01 2.393300e-02 -1.209538e+01 1.711974e-01 -2.121781e-02 9.850083e-01 1.579996e+02 +9.887447e-01 1.941421e-02 -1.483477e-01 -1.372667e+02 -1.602639e-02 9.995835e-01 2.399850e-02 -1.208864e+01 1.487519e-01 -2.135090e-02 9.886440e-01 1.591246e+02 +9.918466e-01 1.853543e-02 -1.260828e-01 -1.374145e+02 -1.592588e-02 9.996382e-01 2.167388e-02 -1.208012e+01 1.264389e-01 -1.948918e-02 9.917829e-01 1.602678e+02 +9.943196e-01 1.834331e-02 -1.048430e-01 -1.375360e+02 -1.629397e-02 9.996597e-01 2.037012e-02 -1.206524e+01 1.051810e-01 -1.854610e-02 9.942801e-01 1.614249e+02 +9.963072e-01 1.696644e-02 -8.416713e-02 -1.376386e+02 -1.515296e-02 9.996400e-01 2.213848e-02 -1.205149e+01 8.451245e-02 -2.078134e-02 9.962057e-01 1.626009e+02 +9.978084e-01 1.753761e-02 -6.380288e-02 -1.377162e+02 -1.601578e-02 9.995767e-01 2.428577e-02 -1.203634e+01 6.420179e-02 -2.321069e-02 9.976670e-01 1.637972e+02 +9.989010e-01 1.785651e-02 -4.333555e-02 -1.377702e+02 -1.677138e-02 9.995398e-01 2.527609e-02 -1.201731e+01 4.376695e-02 -2.452151e-02 9.987408e-01 1.649998e+02 +9.995661e-01 1.896885e-02 -2.253504e-02 -1.378015e+02 -1.838246e-02 9.994942e-01 2.594959e-02 -1.199947e+01 2.301588e-02 -2.552407e-02 9.994092e-01 1.662283e+02 +9.998103e-01 1.941023e-02 -1.632394e-03 -1.378118e+02 -1.935948e-02 9.994524e-01 2.683354e-02 -1.198516e+01 2.152346e-03 -2.679684e-02 9.996386e-01 1.674517e+02 +9.995868e-01 2.149296e-02 1.908533e-02 -1.377975e+02 -2.198173e-02 9.994259e-01 2.577998e-02 -1.197241e+01 -1.852029e-02 -2.618886e-02 9.994854e-01 1.686920e+02 +9.989610e-01 2.279405e-02 3.946242e-02 -1.377602e+02 -2.378432e-02 9.994092e-01 2.480885e-02 -1.196079e+01 -3.887361e-02 -2.572166e-02 9.989130e-01 1.699379e+02 +9.979831e-01 2.273207e-02 5.927055e-02 -1.376931e+02 -2.408569e-02 9.994628e-01 2.222441e-02 -1.195174e+01 -5.873350e-02 -2.360716e-02 9.979945e-01 1.711903e+02 +9.965962e-01 2.487978e-02 7.859357e-02 -1.376033e+02 -2.651453e-02 9.994518e-01 1.982513e-02 -1.194187e+01 -7.805724e-02 -2.184152e-02 9.967096e-01 1.724609e+02 +9.948688e-01 2.493686e-02 9.805253e-02 -1.374876e+02 -2.683260e-02 9.994767e-01 1.806282e-02 -1.193709e+01 -9.755080e-02 -2.060114e-02 9.950173e-01 1.737397e+02 +9.927796e-01 2.515475e-02 1.172857e-01 -1.373423e+02 -2.709059e-02 9.995213e-01 1.494018e-02 -1.194306e+01 -1.168537e-01 -1.800964e-02 9.929858e-01 1.750193e+02 +9.903387e-01 2.628986e-02 1.361549e-01 -1.371760e+02 -2.785918e-02 9.995654e-01 9.633054e-03 -1.195029e+01 -1.358424e-01 -1.333315e-02 9.906407e-01 1.763073e+02 +9.876246e-01 2.770974e-02 1.543689e-01 -1.369802e+02 -2.855622e-02 9.995868e-01 3.268298e-03 -1.196497e+01 -1.542146e-01 -7.636044e-03 9.880079e-01 1.776055e+02 +9.846194e-01 2.980310e-02 1.721526e-01 -1.367646e+02 -2.985780e-02 9.995515e-01 -2.272270e-03 -1.198376e+01 -1.721431e-01 -2.902776e-03 9.850677e-01 1.789113e+02 +9.812808e-01 3.197000e-02 1.899104e-01 -1.365221e+02 -3.138665e-02 9.994888e-01 -6.079436e-03 -1.201144e+01 -1.900077e-01 4.982182e-06 9.817826e-01 1.802277e+02 +9.775738e-01 3.435102e-02 2.077728e-01 -1.362573e+02 -3.311603e-02 9.994071e-01 -9.420407e-03 -1.204258e+01 -2.079732e-01 2.328533e-03 9.781318e-01 1.815452e+02 +9.736725e-01 3.398047e-02 2.254044e-01 -1.359617e+02 -3.275307e-02 9.994213e-01 -9.183678e-03 -1.208256e+01 -2.255861e-01 1.559206e-03 9.742220e-01 1.828797e+02 +9.695096e-01 3.317081e-02 2.427980e-01 -1.356393e+02 -3.189334e-02 9.994490e-01 -9.191359e-03 -1.212331e+01 -2.429691e-01 1.167473e-03 9.700333e-01 1.842188e+02 +9.651421e-01 3.264889e-02 2.596822e-01 -1.352905e+02 -2.994205e-02 9.994483e-01 -1.437354e-02 -1.216852e+01 -2.600082e-01 6.097088e-03 9.655872e-01 1.855514e+02 +9.605564e-01 3.338092e-02 2.760746e-01 -1.349210e+02 -2.919312e-02 9.993881e-01 -1.926604e-02 -1.221523e+01 -2.765488e-01 1.044663e-02 9.609431e-01 1.868879e+02 +9.555247e-01 3.573794e-02 2.927377e-01 -1.345303e+02 -3.144491e-02 9.993180e-01 -1.935925e-02 -1.226706e+01 -2.932299e-01 9.293129e-03 9.559968e-01 1.882314e+02 +9.499691e-01 3.789933e-02 3.100361e-01 -1.341176e+02 -3.345719e-02 9.992472e-01 -1.963486e-02 -1.231567e+01 -3.105468e-01 8.279573e-03 9.505220e-01 1.895769e+02 +9.439025e-01 4.167229e-02 3.275844e-01 -1.336769e+02 -3.613430e-02 9.990827e-01 -2.297675e-02 -1.236376e+01 -3.282415e-01 9.850776e-03 9.445425e-01 1.909279e+02 +9.377303e-01 4.257239e-02 3.447456e-01 -1.332045e+02 -3.559668e-02 9.990137e-01 -2.654226e-02 -1.241575e+01 -3.455355e-01 1.261769e-02 9.383209e-01 1.922715e+02 +9.312896e-01 4.365191e-02 3.616549e-01 -1.327041e+02 -3.545236e-02 9.989423e-01 -2.928022e-02 -1.247353e+01 -3.625505e-01 1.444684e-02 9.318521e-01 1.936195e+02 +9.243962e-01 4.415322e-02 3.788697e-01 -1.321764e+02 -3.402955e-02 9.988632e-01 -3.337891e-02 -1.253918e+01 -3.799128e-01 1.796257e-02 9.248479e-01 1.949675e+02 +9.165686e-01 4.668534e-02 3.971429e-01 -1.316211e+02 -3.357005e-02 9.986389e-01 -3.991650e-02 -1.261280e+01 -3.984659e-01 2.325410e-02 9.168883e-01 1.963008e+02 +9.070641e-01 4.999738e-02 4.180131e-01 -1.310346e+02 -3.485337e-02 9.984326e-01 -4.378997e-02 -1.269471e+01 -4.195473e-01 2.515114e-02 9.073850e-01 1.976474e+02 +8.958706e-01 5.309420e-02 4.411313e-01 -1.304121e+02 -3.707817e-02 9.983052e-01 -4.485508e-02 -1.278312e+01 -4.427652e-01 2.382800e-02 8.963209e-01 1.989740e+02 +8.830069e-01 5.799881e-02 4.657627e-01 -1.297556e+02 -4.048242e-02 9.980489e-01 -4.753367e-02 -1.287573e+01 -4.676109e-01 2.311735e-02 8.836321e-01 2.003057e+02 +8.693330e-01 6.188306e-02 4.903373e-01 -1.290608e+02 -4.247779e-02 9.978143e-01 -5.061917e-02 -1.297300e+01 -4.923981e-01 2.317646e-02 8.700615e-01 2.016167e+02 +8.550623e-01 6.570777e-02 5.143452e-01 -1.283250e+02 -4.406734e-02 9.975583e-01 -5.417962e-02 -1.307773e+01 -5.166494e-01 2.366112e-02 8.558701e-01 2.029078e+02 +8.403935e-01 6.709962e-02 5.378070e-01 -1.275470e+02 -4.359466e-02 9.974602e-01 -5.632606e-02 -1.318252e+01 -5.402206e-01 2.389054e-02 8.411843e-01 2.041905e+02 +8.251684e-01 6.848328e-02 5.607202e-01 -1.267314e+02 -4.322650e-02 9.973686e-01 -5.820005e-02 -1.329464e+01 -5.632305e-01 2.378686e-02 8.259574e-01 2.054460e+02 +8.094251e-01 7.038394e-02 5.829898e-01 -1.258796e+02 -4.127185e-02 9.971545e-01 -6.308379e-02 -1.341339e+01 -5.857710e-01 2.700053e-02 8.100267e-01 2.066836e+02 +7.935545e-01 7.266576e-02 6.041449e-01 -1.249940e+02 -3.914013e-02 9.968835e-01 -6.849267e-02 -1.353728e+01 -6.072392e-01 3.070634e-02 7.939255e-01 2.078983e+02 +7.777115e-01 7.454201e-02 6.241861e-01 -1.240689e+02 -3.760427e-02 9.966830e-01 -7.217317e-02 -1.367026e+01 -6.274956e-01 3.265784e-02 7.779349e-01 2.090904e+02 +7.618118e-01 7.606509e-02 6.433171e-01 -1.231156e+02 -3.615865e-02 9.965270e-01 -7.500944e-02 -1.380930e+01 -6.467885e-01 3.388159e-02 7.619164e-01 2.102655e+02 +7.463151e-01 7.638970e-02 6.611946e-01 -1.221292e+02 -3.399561e-02 9.964704e-01 -7.675297e-02 -1.395312e+01 -6.647240e-01 3.480418e-02 7.462779e-01 2.114240e+02 +7.311888e-01 7.701624e-02 6.778137e-01 -1.211117e+02 -3.225451e-02 9.963984e-01 -7.842087e-02 -1.409866e+01 -6.814122e-01 3.547791e-02 7.310395e-01 2.125536e+02 +7.164943e-01 7.777927e-02 6.932433e-01 -1.200725e+02 -2.965293e-02 9.962624e-01 -8.112941e-02 -1.424635e+01 -6.969625e-01 3.757206e-02 7.161227e-01 2.136630e+02 +7.018663e-01 7.915916e-02 7.078966e-01 -1.190042e+02 -2.719627e-02 9.960592e-01 -8.441782e-02 -1.439724e+01 -7.117894e-01 3.999787e-02 7.012532e-01 2.147483e+02 +6.873140e-01 8.103110e-02 7.218265e-01 -1.179114e+02 -2.437413e-02 9.957712e-01 -8.857500e-02 -1.455461e+01 -7.259514e-01 4.328494e-02 6.863826e-01 2.158204e+02 +6.723406e-01 8.323069e-02 7.355480e-01 -1.167977e+02 -2.304057e-02 9.955303e-01 -9.158829e-02 -1.471793e+01 -7.398833e-01 4.463107e-02 6.712531e-01 2.168677e+02 +6.571121e-01 8.396092e-02 7.491023e-01 -1.156567e+02 -2.184506e-02 9.954811e-01 -9.241310e-02 -1.488974e+01 -7.534763e-01 4.436157e-02 6.559768e-01 2.178953e+02 +6.409030e-01 8.505921e-02 7.628947e-01 -1.145005e+02 -2.215092e-02 9.954772e-01 -9.238225e-02 -1.505999e+01 -7.673023e-01 4.230923e-02 6.398884e-01 2.188995e+02 +6.237247e-01 8.603367e-02 7.768949e-01 -1.133266e+02 -2.419427e-02 9.955728e-01 -9.082598e-02 -1.522932e+01 -7.812696e-01 3.785399e-02 6.230449e-01 2.198821e+02 +6.060200e-01 8.709357e-02 7.906671e-01 -1.121403e+02 -2.678840e-02 9.956586e-01 -8.914141e-02 -1.539873e+01 -7.949982e-01 3.284077e-02 6.057222e-01 2.208287e+02 +5.883410e-01 8.846893e-02 8.037587e-01 -1.109463e+02 -2.957909e-02 9.956862e-01 -8.794271e-02 -1.556587e+01 -8.080718e-01 2.796585e-02 5.884199e-01 2.217455e+02 +5.707896e-01 9.136522e-02 8.159973e-01 -1.097418e+02 -3.003126e-02 9.954480e-01 -9.045105e-02 -1.573251e+01 -8.205470e-01 2.712308e-02 5.709351e-01 2.226219e+02 +5.528147e-01 9.504673e-02 8.278659e-01 -1.085346e+02 -3.192380e-02 9.951601e-01 -9.293630e-02 -1.589865e+01 -8.326925e-01 2.494792e-02 5.531734e-01 2.234648e+02 +5.338657e-01 9.523624e-02 8.401889e-01 -1.073071e+02 -3.251329e-02 9.952142e-01 -9.214921e-02 -1.606679e+01 -8.449440e-01 2.187799e-02 5.344072e-01 2.242815e+02 +5.134242e-01 9.426517e-02 8.529418e-01 -1.060712e+02 -3.291223e-02 9.953801e-01 -9.019579e-02 -1.623283e+01 -8.575036e-01 1.823647e-02 5.141547e-01 2.250551e+02 +4.922806e-01 9.246650e-02 8.655113e-01 -1.048297e+02 -3.328558e-02 9.956140e-01 -8.743402e-02 -1.639478e+01 -8.698000e-01 1.423301e-02 4.931993e-01 2.257980e+02 +4.710965e-01 9.126403e-02 8.773477e-01 -1.035830e+02 -3.338632e-02 9.957653e-01 -8.565521e-02 -1.655412e+01 -8.814496e-01 1.106046e-02 4.721486e-01 2.265016e+02 +4.497832e-01 8.995012e-02 8.885966e-01 -1.023303e+02 -3.262113e-02 9.959062e-01 -8.430086e-02 -1.670912e+01 -8.925419e-01 8.930084e-03 4.508762e-01 2.271631e+02 +4.286649e-01 8.960883e-02 8.990087e-01 -1.010709e+02 -3.166598e-02 9.959479e-01 -8.417233e-02 -1.686140e+01 -9.029085e-01 7.613732e-03 4.297655e-01 2.277927e+02 +4.080171e-01 8.873843e-02 9.086515e-01 -9.981459e+01 -2.916518e-02 9.960241e-01 -8.417500e-02 -1.701115e+01 -9.125084e-01 7.843853e-03 4.089829e-01 2.283830e+02 +3.872057e-01 8.920905e-02 9.176674e-01 -9.854908e+01 -2.665265e-02 9.959751e-01 -8.557562e-02 -1.716162e+01 -9.216081e-01 8.677094e-03 3.880249e-01 2.289348e+02 +3.666570e-01 8.867475e-02 9.261206e-01 -9.728755e+01 -2.269987e-02 9.960037e-01 -8.637896e-02 -1.731059e+01 -9.300792e-01 1.064864e-02 3.672047e-01 2.294536e+02 +3.459362e-01 8.668983e-02 9.342446e-01 -9.602574e+01 -2.032632e-02 9.961812e-01 -8.491051e-02 -1.745580e+01 -9.380379e-01 1.038386e-02 3.463772e-01 2.299362e+02 +3.253031e-01 8.586682e-02 9.417031e-01 -9.476526e+01 -1.952020e-02 9.962662e-01 -8.409896e-02 -1.760194e+01 -9.454083e-01 8.975414e-03 3.257646e-01 2.303936e+02 +3.053968e-01 9.046685e-02 9.479180e-01 -9.351167e+01 -1.918218e-02 9.958592e-01 -8.886221e-02 -1.774895e+01 -9.520320e-01 8.955094e-03 3.058676e-01 2.308192e+02 +2.860577e-01 9.977084e-02 9.530041e-01 -9.227409e+01 -2.000262e-02 9.949696e-01 -9.816020e-02 -1.790266e+01 -9.580036e-01 9.016899e-03 2.866144e-01 2.312075e+02 +2.668520e-01 1.081341e-01 9.576518e-01 -9.104012e+01 -2.168507e-02 9.941074e-01 -1.062079e-01 -1.806044e+01 -9.634935e-01 7.575053e-03 2.676245e-01 2.315729e+02 +2.470306e-01 1.116261e-01 9.625567e-01 -8.980706e+01 -2.427192e-02 9.937438e-01 -1.090137e-01 -1.822511e+01 -9.687037e-01 3.566621e-03 2.481945e-01 2.319127e+02 +2.268997e-01 1.127631e-01 9.673681e-01 -8.857746e+01 -2.685987e-02 9.936212e-01 -1.095233e-01 -1.839359e+01 -9.735477e-01 -1.132577e-03 2.284811e-01 2.322234e+02 +2.068773e-01 1.131461e-01 9.718023e-01 -8.735636e+01 -3.027199e-02 9.935549e-01 -1.092345e-01 -1.855902e+01 -9.778985e-01 -6.820255e-03 2.089692e-01 2.325085e+02 +1.873948e-01 1.131447e-01 9.757466e-01 -8.613843e+01 -3.211059e-02 9.935187e-01 -1.090386e-01 -1.872416e+01 -9.817597e-01 -1.089853e-02 1.898134e-01 2.327642e+02 +1.683438e-01 1.122459e-01 9.793167e-01 -8.492355e+01 -3.184710e-02 9.935962e-01 -1.084081e-01 -1.888775e+01 -9.852138e-01 -1.293856e-02 1.708404e-01 2.329934e+02 +1.495389e-01 1.117241e-01 9.824234e-01 -8.371282e+01 -3.162045e-02 9.936277e-01 -1.081852e-01 -1.904863e+01 -9.882501e-01 -1.488677e-02 1.521188e-01 2.331988e+02 +1.311714e-01 1.124240e-01 9.849644e-01 -8.250969e+01 -3.013042e-02 9.935421e-01 -1.093905e-01 -1.920896e+01 -9.909018e-01 -1.532849e-02 1.337117e-01 2.333727e+02 +1.117838e-01 1.153775e-01 9.870118e-01 -8.131714e+01 -3.326295e-02 9.931147e-01 -1.123237e-01 -1.936977e+01 -9.931757e-01 -2.027495e-02 1.148520e-01 2.335316e+02 +9.254541e-02 1.171164e-01 9.887968e-01 -8.013180e+01 -3.373466e-02 9.928572e-01 -1.144400e-01 -1.952757e+01 -9.951369e-01 -2.276583e-02 9.583526e-02 2.336653e+02 +7.532815e-02 1.145611e-01 9.905561e-01 -7.895298e+01 -3.386414e-02 9.930994e-01 -1.122800e-01 -1.968703e+01 -9.965836e-01 -2.508649e-02 7.868785e-02 2.337739e+02 +6.003040e-02 1.101942e-01 9.920955e-01 -7.777811e+01 -3.136738e-02 9.936054e-01 -1.084639e-01 -1.984734e+01 -9.977036e-01 -2.460830e-02 6.310303e-02 2.338599e+02 +4.570497e-02 1.062354e-01 9.932900e-01 -7.659714e+01 -3.051178e-02 9.940136e-01 -1.049088e-01 -2.000318e+01 -9.984889e-01 -2.551218e-02 4.867279e-02 2.339286e+02 +3.323415e-02 1.028807e-01 9.941383e-01 -7.546824e+01 -2.845560e-02 9.943820e-01 -1.019547e-01 -2.015044e+01 -9.990425e-01 -2.490042e-02 3.597497e-02 2.339791e+02 +2.258000e-02 1.026340e-01 9.944629e-01 -7.433738e+01 -2.763612e-02 9.944004e-01 -1.020001e-01 -2.029495e+01 -9.993630e-01 -2.517993e-02 2.528997e-02 2.340179e+02 +1.390803e-02 1.055624e-01 9.943154e-01 -7.322171e+01 -2.754376e-02 9.940747e-01 -1.051516e-01 -2.043837e+01 -9.995239e-01 -2.592473e-02 1.673320e-02 2.340470e+02 +7.116424e-03 1.070233e-01 9.942310e-01 -7.211428e+01 -2.862878e-02 9.938704e-01 -1.067796e-01 -2.057930e+01 -9.995648e-01 -2.770373e-02 1.013675e-02 2.340698e+02 +1.102096e-03 1.103412e-01 9.938931e-01 -7.102345e+01 -2.930551e-02 9.934704e-01 -1.102618e-01 -2.072490e+01 -9.995699e-01 -2.900502e-02 4.328505e-03 2.340860e+02 +-4.193877e-03 1.188958e-01 9.928979e-01 -6.995117e+01 -2.857930e-02 9.924867e-01 -1.189673e-01 -2.087505e+01 -9.995828e-01 -2.887526e-02 -7.644094e-04 2.340942e+02 +-8.972000e-03 1.233375e-01 9.923242e-01 -6.888154e+01 -2.961349e-02 9.918961e-01 -1.235521e-01 -2.102076e+01 -9.995212e-01 -3.049469e-02 -5.246840e-03 2.340987e+02 +-1.271124e-02 1.149160e-01 9.932939e-01 -6.781083e+01 -2.953882e-02 9.928974e-01 -1.152482e-01 -2.116769e+01 -9.994828e-01 -3.080567e-02 -9.226477e-03 2.340967e+02 +-1.522544e-02 1.039934e-01 9.944614e-01 -6.674442e+01 -2.845600e-02 9.941288e-01 -1.043943e-01 -2.130620e+01 -9.994791e-01 -2.988784e-02 -1.217682e-02 2.340897e+02 +-1.650024e-02 1.006362e-01 9.947864e-01 -6.569534e+01 -2.728393e-02 9.945061e-01 -1.010604e-01 -2.143534e+01 -9.994916e-01 -2.880921e-02 -1.366384e-02 2.340821e+02 +-1.659104e-02 1.022640e-01 9.946189e-01 -6.465882e+01 -2.792948e-02 9.943203e-01 -1.026992e-01 -2.156167e+01 -9.994722e-01 -2.948307e-02 -1.364063e-02 2.340770e+02 +-1.607624e-02 1.057469e-01 9.942631e-01 -6.363127e+01 -2.742921e-02 9.939707e-01 -1.061593e-01 -2.168850e+01 -9.994945e-01 -2.897850e-02 -1.307876e-02 2.340730e+02 +-1.454802e-02 1.080229e-01 9.940419e-01 -6.261250e+01 -2.943555e-02 9.936700e-01 -1.084133e-01 -2.181801e+01 -9.994608e-01 -3.083737e-02 -1.127622e-02 2.340729e+02 +-1.260702e-02 1.086184e-01 9.940036e-01 -6.159595e+01 -3.190569e-02 9.935327e-01 -1.089717e-01 -2.194850e+01 -9.994114e-01 -3.308817e-02 -9.059944e-03 2.340761e+02 +-9.360384e-03 1.102212e-01 9.938630e-01 -6.058819e+01 -3.272377e-02 9.933404e-01 -1.104714e-01 -2.207608e+01 -9.994206e-01 -3.355699e-02 -5.691197e-03 2.340809e+02 +-5.854104e-03 1.109989e-01 9.938033e-01 -5.958519e+01 -3.534746e-02 9.931762e-01 -1.111371e-01 -2.220492e+01 -9.993580e-01 -3.577903e-02 -1.890630e-03 2.340933e+02 +-1.124662e-03 1.134375e-01 9.935445e-01 -5.858962e+01 -3.675378e-02 9.928691e-01 -1.134021e-01 -2.233445e+01 -9.993238e-01 -3.664405e-02 3.052614e-03 2.341095e+02 +4.928350e-03 1.128019e-01 9.936053e-01 -5.758997e+01 -3.837036e-02 9.929069e-01 -1.125323e-01 -2.246446e+01 -9.992515e-01 -3.757038e-02 9.221639e-03 2.341299e+02 +1.166004e-02 1.099014e-01 9.938741e-01 -5.659296e+01 -3.752136e-02 9.932897e-01 -1.093966e-01 -2.259437e+01 -9.992278e-01 -3.601593e-02 1.570545e-02 2.341542e+02 +1.917433e-02 1.099275e-01 9.937546e-01 -5.561261e+01 -3.542653e-02 9.933879e-01 -1.092034e-01 -2.272297e+01 -9.991884e-01 -3.311137e-02 2.294189e-02 2.341831e+02 +2.657858e-02 1.108702e-01 9.934794e-01 -5.463127e+01 -3.443272e-02 9.933423e-01 -1.099337e-01 -2.284877e+01 -9.990536e-01 -3.128631e-02 3.021918e-02 2.342213e+02 +3.359995e-02 1.106852e-01 9.932874e-01 -5.364951e+01 -3.471302e-02 9.933781e-01 -1.095211e-01 -2.297595e+01 -9.988324e-01 -3.080010e-02 3.721967e-02 2.342666e+02 +4.032596e-02 1.093806e-01 9.931816e-01 -5.266948e+01 -3.608598e-02 9.935011e-01 -1.079507e-01 -2.310390e+01 -9.985348e-01 -3.148672e-02 4.401099e-02 2.343208e+02 +4.704107e-02 1.079612e-01 9.930415e-01 -5.169180e+01 -3.708491e-02 9.936455e-01 -1.062701e-01 -2.322962e+01 -9.982043e-01 -3.182780e-02 5.074587e-02 2.343808e+02 +5.384017e-02 1.052978e-01 9.929822e-01 -5.071747e+01 -3.733266e-02 9.939415e-01 -1.033754e-01 -2.335302e+01 -9.978515e-01 -3.150492e-02 5.744502e-02 2.344474e+02 +6.085965e-02 1.065653e-01 9.924414e-01 -4.975239e+01 -3.714409e-02 9.938376e-01 -1.044374e-01 -2.347790e+01 -9.974550e-01 -3.050730e-02 6.444288e-02 2.345210e+02 +6.778197e-02 1.083457e-01 9.917998e-01 -4.878998e+01 -3.722162e-02 9.936686e-01 -1.060061e-01 -2.359769e+01 -9.970056e-01 -2.973109e-02 7.138561e-02 2.346005e+02 +7.464116e-02 1.103763e-01 9.910831e-01 -4.782873e+01 -3.696289e-02 9.934788e-01 -1.078594e-01 -2.371823e+01 -9.965252e-01 -2.858254e-02 7.823424e-02 2.346851e+02 +8.122069e-02 1.114968e-01 9.904401e-01 -4.686941e+01 -3.910740e-02 9.933145e-01 -1.086134e-01 -2.384177e+01 -9.959287e-01 -2.991188e-02 8.503804e-02 2.347793e+02 +8.771875e-02 1.129924e-01 9.897162e-01 -4.591473e+01 -4.097435e-02 9.931144e-01 -1.097488e-01 -2.396567e+01 -9.953023e-01 -3.092594e-02 9.174455e-02 2.348807e+02 +9.465349e-02 1.124343e-01 9.891406e-01 -4.496036e+01 -4.187033e-02 9.931720e-01 -1.088859e-01 -2.408941e+01 -9.946294e-01 -3.110922e-02 9.871486e-02 2.349871e+02 +1.010260e-01 1.103104e-01 9.887494e-01 -4.400878e+01 -4.283264e-02 9.933948e-01 -1.064523e-01 -2.421455e+01 -9.939614e-01 -3.159629e-02 1.050836e-01 2.351012e+02 +1.073954e-01 1.083270e-01 9.882973e-01 -4.305660e+01 -4.360424e-02 9.936031e-01 -1.041702e-01 -2.433575e+01 -9.932598e-01 -3.190654e-02 1.114320e-01 2.352214e+02 +1.140945e-01 1.078491e-01 9.875986e-01 -4.210966e+01 -4.324480e-02 9.936870e-01 -1.035180e-01 -2.445463e+01 -9.925283e-01 -3.089766e-02 1.180382e-01 2.353479e+02 +1.209945e-01 1.087490e-01 9.866782e-01 -4.116675e+01 -4.350868e-02 9.936066e-01 -1.041772e-01 -2.457047e+01 -9.916992e-01 -3.032419e-02 1.249524e-01 2.354786e+02 +1.282764e-01 1.094041e-01 9.856855e-01 -4.022656e+01 -4.158002e-02 9.936160e-01 -1.048732e-01 -2.468721e+01 -9.908665e-01 -2.753207e-02 1.320065e-01 2.356150e+02 +1.371877e-01 1.111881e-01 9.842849e-01 -3.929119e+01 -4.007854e-02 9.934894e-01 -1.066419e-01 -2.480560e+01 -9.897340e-01 -2.481875e-02 1.407507e-01 2.357584e+02 +1.466588e-01 1.135809e-01 9.826447e-01 -3.836062e+01 -4.011210e-02 9.932518e-01 -1.088203e-01 -2.492222e+01 -9.883736e-01 -2.345649e-02 1.502250e-01 2.359109e+02 +1.563369e-01 1.146135e-01 9.810313e-01 -3.743651e+01 -4.040497e-02 9.931552e-01 -1.095910e-01 -2.503558e+01 -9.868770e-01 -2.250541e-02 1.598978e-01 2.360723e+02 +1.642740e-01 1.139561e-01 9.798102e-01 -3.651652e+01 -4.261524e-02 9.931970e-01 -1.083682e-01 -2.515044e+01 -9.854938e-01 -2.395276e-02 1.680127e-01 2.362425e+02 +1.696955e-01 1.123618e-01 9.790701e-01 -3.559589e+01 -4.429967e-02 9.933444e-01 -1.063219e-01 -2.526483e+01 -9.845004e-01 -2.533014e-02 1.735436e-01 2.364208e+02 +1.735339e-01 1.121319e-01 9.784234e-01 -3.467183e+01 -4.694428e-02 9.933093e-01 -1.055119e-01 -2.537859e+01 -9.837084e-01 -2.762150e-02 1.776368e-01 2.366029e+02 +1.762423e-01 1.147046e-01 9.776408e-01 -3.374449e+01 -4.748187e-02 9.930218e-01 -1.079496e-01 -2.549004e+01 -9.832010e-01 -2.739493e-02 1.804588e-01 2.367860e+02 +1.791364e-01 1.159103e-01 9.769723e-01 -3.281121e+01 -4.707368e-02 9.929079e-01 -1.091696e-01 -2.560259e+01 -9.826975e-01 -2.643343e-02 1.833223e-01 2.369709e+02 +1.821852e-01 1.160467e-01 9.763922e-01 -3.187210e+01 -4.630808e-02 9.929217e-01 -1.093707e-01 -2.571650e+01 -9.821732e-01 -2.528912e-02 1.862695e-01 2.371592e+02 +1.853964e-01 1.149561e-01 9.759166e-01 -3.092803e+01 -4.460952e-02 9.930945e-01 -1.085051e-01 -2.583305e+01 -9.816508e-01 -2.341873e-02 1.892443e-01 2.373485e+02 +1.890239e-01 1.161237e-01 9.750822e-01 -2.998093e+01 -4.381392e-02 9.929916e-01 -1.097631e-01 -2.595197e+01 -9.809946e-01 -2.197433e-02 1.927870e-01 2.375425e+02 +1.925389e-01 1.165764e-01 9.743401e-01 -2.903001e+01 -4.368668e-02 9.929521e-01 -1.101704e-01 -2.607414e+01 -9.803164e-01 -2.135359e-02 1.962748e-01 2.377390e+02 +1.962879e-01 1.151961e-01 9.737561e-01 -2.807792e+01 -4.349005e-02 9.931206e-01 -1.087203e-01 -2.619995e+01 -9.795814e-01 -2.100822e-02 1.999475e-01 2.379448e+02 +1.999946e-01 1.109602e-01 9.734937e-01 -2.712052e+01 -4.114314e-02 9.936414e-01 -1.048042e-01 -2.632376e+01 -9.789328e-01 -1.909231e-02 2.032881e-01 2.381523e+02 +2.042267e-01 1.094460e-01 9.727862e-01 -2.616421e+01 -4.064321e-02 9.938216e-01 -1.032800e-01 -2.645236e+01 -9.780796e-01 -1.844462e-02 2.074131e-01 2.383612e+02 +2.096563e-01 1.114220e-01 9.714059e-01 -2.520641e+01 -3.966392e-02 9.936373e-01 -1.054114e-01 -2.657591e+01 -9.769704e-01 -1.642960e-02 2.127417e-01 2.385754e+02 +2.162759e-01 1.127803e-01 9.697965e-01 -2.424773e+01 -3.816987e-02 9.935231e-01 -1.070272e-01 -2.669510e+01 -9.755859e-01 -1.386960e-02 2.191799e-01 2.387918e+02 +2.224709e-01 1.125592e-01 9.684199e-01 -2.328840e+01 -3.793108e-02 9.935602e-01 -1.067675e-01 -2.681809e+01 -9.742012e-01 -1.298054e-02 2.253078e-01 2.390146e+02 +2.296848e-01 1.112094e-01 9.668906e-01 -2.232641e+01 -3.734160e-02 9.937258e-01 -1.054254e-01 -2.694049e+01 -9.725485e-01 -1.189063e-02 2.323964e-01 2.392487e+02 +2.382463e-01 1.101501e-01 9.649381e-01 -2.136288e+01 -3.651364e-02 9.938610e-01 -1.044364e-01 -2.706134e+01 -9.705182e-01 -1.035181e-02 2.408057e-01 2.394902e+02 +2.477545e-01 1.098948e-01 9.625699e-01 -2.042015e+01 -3.438499e-02 9.939173e-01 -1.046234e-01 -2.718237e+01 -9.682125e-01 -7.177042e-03 2.500262e-01 2.397378e+02 +2.587533e-01 1.111752e-01 9.595242e-01 -1.947329e+01 -3.156187e-02 9.937971e-01 -1.066350e-01 -2.730342e+01 -9.654277e-01 -2.692211e-03 2.606572e-01 2.399989e+02 +2.700453e-01 1.101808e-01 9.565227e-01 -1.852760e+01 -3.036820e-02 9.939114e-01 -1.059140e-01 -2.742264e+01 -9.623686e-01 -4.463024e-04 2.717471e-01 2.402693e+02 +2.810883e-01 1.077539e-01 9.536134e-01 -1.758590e+01 -3.146725e-02 9.941770e-01 -1.030621e-01 -2.754421e+01 -9.591659e-01 -1.038035e-03 2.828422e-01 2.405579e+02 +2.918402e-01 1.065024e-01 9.505191e-01 -1.665096e+01 -3.175612e-02 9.943123e-01 -1.016592e-01 -2.766418e+01 -9.559398e-01 -5.165538e-04 2.935624e-01 2.408545e+02 +3.026799e-01 1.083492e-01 9.469136e-01 -1.571651e+01 -3.459952e-02 9.941115e-01 -1.026900e-01 -2.778349e+01 -9.524641e-01 -1.680556e-03 3.046464e-01 2.411633e+02 +3.131038e-01 1.104784e-01 9.432712e-01 -1.478774e+01 -3.591890e-02 9.938778e-01 -1.044829e-01 -2.790214e+01 -9.490395e-01 -1.167281e-03 3.151551e-01 2.414843e+02 +3.236367e-01 1.117194e-01 9.395627e-01 -1.386544e+01 -3.817752e-02 9.937380e-01 -1.050108e-01 -2.802279e+01 -9.454109e-01 -1.884835e-03 3.258752e-01 2.418115e+02 +3.336129e-01 1.111254e-01 9.361376e-01 -1.294415e+01 -4.065794e-02 9.938001e-01 -1.034810e-01 -2.814553e+01 -9.418330e-01 -3.538844e-03 3.360626e-01 2.421516e+02 +3.424563e-01 1.102890e-01 9.330380e-01 -1.202778e+01 -4.232453e-02 9.938890e-01 -1.019473e-01 -2.826671e+01 -9.385800e-01 -4.577908e-03 3.450315e-01 2.424978e+02 +3.504335e-01 1.087697e-01 9.302502e-01 -1.111234e+01 -4.287245e-02 9.940553e-01 -1.000797e-01 -2.838624e+01 -9.356059e-01 -4.810827e-03 3.530136e-01 2.428532e+02 +3.583093e-01 1.078487e-01 9.273527e-01 -1.020216e+01 -4.329268e-02 9.941561e-01 -9.889043e-02 -2.850521e+01 -9.325987e-01 -4.714229e-03 3.608844e-01 2.432173e+02 +3.661737e-01 1.065187e-01 9.244299e-01 -9.297034e+00 -4.462638e-02 9.942939e-01 -9.689206e-02 -2.862274e+01 -9.294759e-01 -5.774635e-03 3.688378e-01 2.435898e+02 +3.740017e-01 1.067893e-01 9.212593e-01 -8.398430e+00 -4.622716e-02 9.942604e-01 -9.648458e-02 -2.873833e+01 -9.262752e-01 -6.501801e-03 3.767917e-01 2.439669e+02 +3.818725e-01 1.080335e-01 9.178791e-01 -7.504105e+00 -4.685165e-02 9.941305e-01 -9.751615e-02 -2.885496e+01 -9.230267e-01 -5.765415e-03 3.846927e-01 2.443519e+02 +3.899504e-01 1.097752e-01 9.142691e-01 -6.615868e+00 -4.767608e-02 9.939439e-01 -9.900709e-02 -2.896837e+01 -9.196008e-01 -4.980913e-03 3.928225e-01 2.447410e+02 +3.979618e-01 1.091069e-01 9.108908e-01 -5.736688e+00 -4.878672e-02 9.940146e-01 -9.774891e-02 -2.908337e+01 -9.161039e-01 -5.539041e-03 4.009028e-01 2.451390e+02 +4.065937e-01 1.071920e-01 9.072990e-01 -4.863903e+00 -4.818025e-02 9.942270e-01 -9.587069e-02 -2.919595e+01 -9.123378e-01 -4.733480e-03 4.094110e-01 2.455429e+02 +4.153690e-01 1.061796e-01 9.034348e-01 -4.000885e+00 -4.891631e-02 9.943344e-01 -9.437293e-02 -2.930581e+01 -9.083369e-01 -4.993108e-03 4.182096e-01 2.459502e+02 +4.238561e-01 1.021591e-01 8.999497e-01 -3.138302e+00 -4.839269e-02 9.947537e-01 -9.012902e-02 -2.941357e+01 -9.044358e-01 -5.349249e-03 4.265762e-01 2.463659e+02 +4.324715e-01 9.934954e-02 8.961574e-01 -2.279275e+00 -4.918771e-02 9.950304e-01 -8.657358e-02 -2.951821e+01 -9.003050e-01 -6.639323e-03 4.352091e-01 2.467944e+02 +4.410898e-01 9.964042e-02 8.919145e-01 -1.445171e+00 -5.162812e-02 9.949890e-01 -8.562312e-02 -2.961846e+01 -8.959768e-01 -8.280387e-03 4.440238e-01 2.472235e+02 +4.494296e-01 1.007627e-01 8.876147e-01 -6.089908e-01 -5.265195e-02 9.948786e-01 -8.627990e-02 -2.971750e+01 -8.917628e-01 -7.957901e-03 4.524333e-01 2.476612e+02 +4.575802e-01 9.878703e-02 8.836637e-01 2.183283e-01 -5.410544e-02 9.950610e-01 -8.322349e-02 -2.981292e+01 -8.875207e-01 -9.729592e-03 4.606651e-01 2.481060e+02 +4.658026e-01 9.817332e-02 8.794259e-01 1.045353e+00 -5.558640e-02 9.951101e-01 -8.164530e-02 -2.991067e+01 -8.831411e-01 -1.085353e-02 4.689820e-01 2.485608e+02 +4.742125e-01 9.845217e-02 8.748883e-01 1.859248e+00 -5.608922e-02 9.950875e-01 -8.157651e-02 -3.000435e+01 -8.786219e-01 -1.038720e-02 4.774051e-01 2.490180e+02 +4.825798e-01 9.841240e-02 8.703055e-01 2.670980e+00 -5.620447e-02 9.950989e-01 -8.135873e-02 -3.009499e+01 -8.740468e-01 -9.652975e-03 4.857459e-01 2.494807e+02 +4.910236e-01 9.876007e-02 8.655300e-01 3.471952e+00 -5.632972e-02 9.950733e-01 -8.158505e-02 -3.018500e+01 -8.693232e-01 -8.694874e-03 4.941676e-01 2.499508e+02 +4.991477e-01 9.817028e-02 8.609379e-01 4.271917e+00 -5.696934e-02 9.951299e-01 -8.044260e-02 -3.027453e+01 -8.646422e-01 -8.894319e-03 5.023095e-01 2.504292e+02 +5.069948e-01 9.637011e-02 8.565448e-01 5.069513e+00 -5.691393e-02 9.953044e-01 -7.829426e-02 -3.036317e+01 -8.600681e-01 -9.054549e-03 5.100990e-01 2.509148e+02 +5.133747e-01 9.404667e-02 8.529957e-01 5.864994e+00 -5.752752e-02 9.955124e-01 -7.513693e-02 -3.045063e+01 -8.562342e-01 -1.049733e-02 5.164812e-01 2.514103e+02 +5.186050e-01 9.192518e-02 8.500580e-01 6.657400e+00 -5.758548e-02 9.957014e-01 -7.254321e-02 -3.053540e+01 -8.530726e-01 -1.132972e-02 5.216693e-01 2.519098e+02 +5.224205e-01 9.022701e-02 8.479008e-01 7.450741e+00 -5.918057e-02 9.958246e-01 -6.950477e-02 -3.061794e+01 -8.506318e-01 -1.386853e-02 5.255789e-01 2.524159e+02 +5.256822e-01 8.723980e-02 8.461958e-01 8.235125e+00 -5.988482e-02 9.960548e-01 -6.548751e-02 -3.070780e+01 -8.485706e-01 -1.624866e-02 5.288326e-01 2.529478e+02 +5.281496e-01 8.499646e-02 8.448868e-01 9.016959e+00 -5.974922e-02 9.962315e-01 -6.287191e-02 -3.080137e+01 -8.470467e-01 -1.727556e-02 5.312377e-01 2.534953e+02 +5.300688e-01 8.305746e-02 8.438771e-01 9.801622e+00 -5.961973e-02 9.963789e-01 -6.061803e-02 -3.088791e+01 -8.458561e-01 -1.817999e-02 5.331012e-01 2.540322e+02 +5.316076e-01 8.400868e-02 8.428143e-01 1.058369e+01 -6.036185e-02 9.962965e-01 -6.123384e-02 -3.097495e+01 -8.448372e-01 -1.832145e-02 5.347097e-01 2.545731e+02 +5.331778e-01 8.591919e-02 8.416289e-01 1.136948e+01 -6.031454e-02 9.961585e-01 -6.348495e-02 -3.105756e+01 -8.438505e-01 -1.691370e-02 5.363118e-01 2.551065e+02 +5.350143e-01 8.651590e-02 8.404015e-01 1.215623e+01 -5.912513e-02 9.961381e-01 -6.490829e-02 -3.114299e+01 -8.427716e-01 -1.496199e-02 5.380634e-01 2.556432e+02 +5.367063e-01 8.518498e-02 8.394581e-01 1.295334e+01 -5.927602e-02 9.962392e-01 -6.319651e-02 -3.122648e+01 -8.416845e-01 -1.584177e-02 5.397373e-01 2.561774e+02 +5.383121e-01 8.159707e-02 8.387860e-01 1.374910e+01 -5.622790e-02 9.965613e-01 -6.085979e-02 -3.131135e+01 -8.408677e-01 -1.440161e-02 5.410491e-01 2.567107e+02 +5.397997e-01 7.890244e-02 8.380875e-01 1.454836e+01 -5.466300e-02 9.967817e-01 -5.863523e-02 -3.139186e+01 -8.400169e-01 -1.416110e-02 5.423755e-01 2.572442e+02 +5.408717e-01 7.579487e-02 8.376830e-01 1.534640e+01 -5.463084e-02 9.969942e-01 -5.493580e-02 -3.146761e+01 -8.393291e-01 -1.605011e-02 5.433867e-01 2.577811e+02 +5.420978e-01 7.278154e-02 8.371576e-01 1.614924e+01 -5.473123e-02 9.971848e-01 -5.125318e-02 -3.153968e+01 -8.385312e-01 -1.803442e-02 5.445551e-01 2.583218e+02 +5.425939e-01 7.159170e-02 8.369388e-01 1.695281e+01 -5.427550e-02 9.972674e-01 -5.011899e-02 -3.161045e+01 -8.382399e-01 -1.823101e-02 5.449968e-01 2.588641e+02 +5.433594e-01 7.224118e-02 8.363861e-01 1.775105e+01 -5.448382e-02 9.972247e-01 -5.073782e-02 -3.167773e+01 -8.377303e-01 -1.800064e-02 5.457874e-01 2.594004e+02 +5.437838e-01 7.207974e-02 8.361242e-01 1.855725e+01 -5.581819e-02 9.972050e-01 -4.966399e-02 -3.174541e+01 -8.373670e-01 -1.966447e-02 5.462873e-01 2.599430e+02 +5.441986e-01 7.013773e-02 8.360195e-01 1.936920e+01 -5.583219e-02 9.973179e-01 -4.732645e-02 -3.181498e+01 -8.370966e-01 -2.092181e-02 5.466549e-01 2.604861e+02 +5.448464e-01 6.783142e-02 8.357878e-01 2.018886e+01 -5.510685e-02 9.974646e-01 -4.502899e-02 -3.188088e+01 -8.367232e-01 -2.152375e-02 5.472029e-01 2.610303e+02 +5.453973e-01 6.527638e-02 8.356319e-01 2.100873e+01 -5.521060e-02 9.975954e-01 -4.189371e-02 -3.194455e+01 -8.363573e-01 -2.328703e-02 5.476898e-01 2.615765e+02 +5.463254e-01 6.351162e-02 8.351616e-01 2.182846e+01 -5.455346e-02 9.977018e-01 -4.018592e-02 -3.200561e+01 -8.357946e-01 -2.360636e-02 5.485346e-01 2.621211e+02 +5.474545e-01 6.262921e-02 8.344885e-01 2.264772e+01 -5.452839e-02 9.977460e-01 -3.910928e-02 -3.206667e+01 -8.350571e-01 -2.409276e-02 5.496356e-01 2.626668e+02 +5.486411e-01 6.062739e-02 8.338569e-01 2.346534e+01 -5.385519e-02 9.978586e-01 -3.711717e-02 -3.212407e+01 -8.343217e-01 -2.454351e-02 5.507314e-01 2.632117e+02 +5.501672e-01 5.811587e-02 8.330298e-01 2.428406e+01 -5.371415e-02 9.979723e-01 -3.414797e-02 -3.218277e+01 -8.333252e-01 -2.595840e-02 5.521732e-01 2.637578e+02 +5.521677e-01 5.636501e-02 8.318256e-01 2.509945e+01 -5.302498e-02 9.980664e-01 -3.243150e-02 -3.223898e+01 -8.320452e-01 -2.619990e-02 5.540888e-01 2.643056e+02 +5.546154e-01 5.586310e-02 8.302295e-01 2.590965e+01 -5.320382e-02 9.980830e-01 -3.161580e-02 -3.229336e+01 -8.304042e-01 -2.663677e-02 5.565243e-01 2.648536e+02 +5.570906e-01 5.426145e-02 8.286771e-01 2.671834e+01 -5.296265e-02 9.981531e-01 -2.975376e-02 -3.234532e+01 -8.287611e-01 -2.731339e-02 5.589356e-01 2.654038e+02 +5.602099e-01 5.150940e-02 8.267476e-01 2.752584e+01 -5.226128e-02 9.982742e-01 -2.678354e-02 -3.239374e+01 -8.267005e-01 -2.820248e-02 5.619350e-01 2.659545e+02 +5.646411e-01 4.727485e-02 8.239815e-01 2.833742e+01 -5.034849e-02 9.984718e-01 -2.278424e-02 -3.244106e+01 -8.237995e-01 -2.862130e-02 5.661584e-01 2.665106e+02 +5.706915e-01 4.524480e-02 8.199171e-01 2.913951e+01 -4.956418e-02 9.985584e-01 -2.060420e-02 -3.248768e+01 -8.196674e-01 -2.887988e-02 5.721113e-01 2.670673e+02 +5.767276e-01 4.334166e-02 8.157860e-01 2.993629e+01 -4.598379e-02 9.987307e-01 -2.055262e-02 -3.252924e+01 -8.156414e-01 -2.565966e-02 5.779886e-01 2.676317e+02 +5.827853e-01 4.520081e-02 8.113681e-01 3.072188e+01 -4.816059e-02 9.986180e-01 -2.103986e-02 -3.257164e+01 -8.111978e-01 -2.681424e-02 5.841567e-01 2.682023e+02 +5.884962e-01 4.487300e-02 8.072537e-01 3.151535e+01 -4.891655e-02 9.986056e-01 -1.984907e-02 -3.261117e+01 -8.070189e-01 -2.780696e-02 5.898707e-01 2.687870e+02 +5.952026e-01 4.309425e-02 8.024193e-01 3.228615e+01 -4.893157e-02 9.986516e-01 -1.733751e-02 -3.264565e+01 -8.020846e-01 -2.894431e-02 5.965087e-01 2.693609e+02 +6.019435e-01 3.903964e-02 7.975838e-01 3.306738e+01 -4.796050e-02 9.987686e-01 -1.269091e-02 -3.268100e+01 -7.970972e-01 -3.061330e-02 6.030746e-01 2.699506e+02 +6.093981e-01 3.763371e-02 7.919707e-01 3.383956e+01 -4.657196e-02 9.988472e-01 -1.162854e-02 -3.271451e+01 -7.914954e-01 -2.979721e-02 6.104483e-01 2.705455e+02 +6.175829e-01 3.775242e-02 7.855992e-01 3.460616e+01 -4.469838e-02 9.989177e-01 -1.286485e-02 -3.274316e+01 -7.852347e-01 -2.716990e-02 6.186019e-01 2.711437e+02 +6.268720e-01 3.591693e-02 7.782940e-01 3.537431e+01 -4.263127e-02 9.990216e-01 -1.176605e-02 -3.276919e+01 -7.779551e-01 -2.580385e-02 6.277898e-01 2.717630e+02 +6.359020e-01 3.516347e-02 7.709684e-01 3.612313e+01 -4.161523e-02 9.990704e-01 -1.124246e-02 -3.279600e+01 -7.706471e-01 -2.493492e-02 6.367742e-01 2.723795e+02 +6.451634e-01 3.417835e-02 7.632798e-01 3.688517e+01 -4.066385e-02 9.991191e-01 -1.036765e-02 -3.282239e+01 -7.629618e-01 -2.434906e-02 6.459849e-01 2.730271e+02 +6.540681e-01 3.168582e-02 7.557717e-01 3.761896e+01 -4.015629e-02 9.991679e-01 -7.137757e-03 -3.284713e+01 -7.553691e-01 -2.568041e-02 6.547962e-01 2.736648e+02 +6.630377e-01 3.074281e-02 7.479545e-01 3.836067e+01 -4.167732e-02 9.991226e-01 -4.120854e-03 -3.286961e+01 -7.474250e-01 -2.844045e-02 6.637372e-01 2.743264e+02 +6.721231e-01 2.945126e-02 7.398535e-01 3.909705e+01 -4.071792e-02 9.991668e-01 -2.783356e-03 -3.289032e+01 -7.393190e-01 -2.825454e-02 6.727623e-01 2.749985e+02 +6.811514e-01 2.777243e-02 7.316157e-01 3.983251e+01 -4.075056e-02 9.991693e-01 1.083406e-05 -3.290687e+01 -7.310077e-01 -2.982112e-02 6.817173e-01 2.756856e+02 +6.897510e-01 2.414619e-02 7.236439e-01 4.056270e+01 -4.021900e-02 9.991784e-01 4.995189e-03 -3.292236e+01 -7.229288e-01 -3.254967e-02 6.901554e-01 2.763839e+02 +6.984205e-01 1.876291e-02 7.154416e-01 4.129080e+01 -3.816213e-02 9.992104e-01 1.104928e-02 -3.293282e+01 -7.146695e-01 -3.501982e-02 6.985852e-01 2.770968e+02 +7.072487e-01 1.442528e-02 7.068177e-01 4.201104e+01 -3.459381e-02 9.993003e-01 1.422041e-02 -3.294048e+01 -7.061180e-01 -3.450888e-02 7.072528e-01 2.778139e+02 +7.166808e-01 1.145094e-02 6.973073e-01 4.272826e+01 -3.015319e-02 9.994389e-01 1.457849e-02 -3.294141e+01 -6.967492e-01 -3.147416e-02 7.166240e-01 2.785485e+02 +7.265892e-01 9.001702e-03 6.870132e-01 4.343925e+01 -2.659775e-02 9.995331e-01 1.503339e-02 -3.294227e+01 -6.865572e-01 -2.919610e-02 7.264894e-01 2.792973e+02 +7.363185e-01 6.222781e-03 6.766065e-01 4.413891e+01 -2.487820e-02 9.995305e-01 1.788103e-02 -3.294108e+01 -6.761776e-01 -2.999888e-02 7.361277e-01 2.800564e+02 +7.457384e-01 3.188132e-03 6.662313e-01 4.483054e+01 -2.363526e-02 9.994857e-01 2.167299e-02 -3.293892e+01 -6.658196e-01 -3.190893e-02 7.454302e-01 2.808337e+02 +7.549211e-01 6.403670e-04 6.558153e-01 4.551325e+01 -2.171494e-02 9.994756e-01 2.402053e-02 -3.293165e+01 -6.554561e-01 -3.237459e-02 7.545391e-01 2.816223e+02 +7.642401e-01 1.157991e-04 6.449319e-01 4.618797e+01 -2.209286e-02 9.994177e-01 2.600045e-02 -3.292048e+01 -6.445534e-01 -3.411897e-02 7.637977e-01 2.824264e+02 +7.732324e-01 -4.155674e-03 6.341091e-01 4.685704e+01 -1.789717e-02 9.994371e-01 2.837367e-02 -3.290812e+01 -6.338702e-01 -3.328819e-02 7.727228e-01 2.832402e+02 +7.821486e-01 -3.938187e-03 6.230795e-01 4.751422e+01 -1.879005e-02 9.993761e-01 2.990363e-02 -3.289560e+01 -6.228086e-01 -3.509677e-02 7.815866e-01 2.840707e+02 +7.899660e-01 -3.270419e-03 6.131420e-01 4.816186e+01 -1.939351e-02 9.993522e-01 3.031681e-02 -3.288378e+01 -6.128440e-01 -3.584022e-02 7.893908e-01 2.849088e+02 +7.969050e-01 -1.812118e-03 6.041019e-01 4.880087e+01 -2.134296e-02 9.992867e-01 3.115225e-02 -3.286705e+01 -6.037275e-01 -3.771870e-02 7.962979e-01 2.857633e+02 +8.027851e-01 4.314033e-04 5.962683e-01 4.943183e+01 -2.494835e-02 9.991483e-01 3.286630e-02 -3.285123e+01 -5.957463e-01 -4.126048e-02 8.021122e-01 2.866268e+02 +8.084790e-01 2.598190e-03 5.885192e-01 5.005648e+01 -2.662134e-02 9.991281e-01 3.216015e-02 -3.283393e+01 -5.879226e-01 -4.166798e-02 8.078433e-01 2.875006e+02 +8.141306e-01 5.478629e-03 5.806559e-01 5.067806e+01 -2.885670e-02 9.991017e-01 3.103286e-02 -3.281862e+01 -5.799644e-01 -4.202061e-02 8.135574e-01 2.883827e+02 +8.195053e-01 6.648191e-03 5.730331e-01 5.129410e+01 -3.088744e-02 9.989916e-01 3.258264e-02 -3.280140e+01 -5.722387e-01 -4.440116e-02 8.188843e-01 2.892738e+02 +8.246004e-01 7.087372e-03 5.656712e-01 5.190333e+01 -3.472316e-02 9.986703e-01 3.810479e-02 -3.278135e+01 -5.646490e-01 -5.106310e-02 8.237500e-01 2.901798e+02 +8.291537e-01 9.979114e-03 5.589317e-01 5.250376e+01 -3.883974e-02 9.984529e-01 3.979098e-02 -3.275836e+01 -5.576699e-01 -5.470159e-02 8.282585e-01 2.910916e+02 +8.334302e-01 1.277442e-02 5.524771e-01 5.310130e+01 -4.251737e-02 9.982517e-01 4.105720e-02 -3.273217e+01 -5.509868e-01 -5.770817e-02 8.325163e-01 2.920124e+02 +8.369802e-01 1.551135e-02 5.470134e-01 5.369392e+01 -4.685851e-02 9.979583e-01 4.339922e-02 -3.270406e+01 -5.452234e-01 -6.195650e-02 8.359981e-01 2.929404e+02 +8.398391e-01 1.784921e-02 5.425419e-01 5.428513e+01 -5.017686e-02 9.977329e-01 4.484766e-02 -3.267788e+01 -5.405115e-01 -6.488785e-02 8.388307e-01 2.938744e+02 +8.417437e-01 2.200699e-02 5.394286e-01 5.487523e+01 -5.212354e-02 9.978138e-01 4.062775e-02 -3.265164e+01 -5.373553e-01 -6.231507e-02 8.410506e-01 2.948097e+02 +8.428839e-01 2.797891e-02 5.373676e-01 5.546258e+01 -5.526054e-02 9.978680e-01 3.472288e-02 -3.262805e+01 -5.352505e-01 -5.896257e-02 8.426330e-01 2.957482e+02 +8.435908e-01 3.234636e-02 5.360114e-01 5.605376e+01 -5.761230e-02 9.978744e-01 3.045383e-02 -3.260911e+01 -5.338870e-01 -5.657141e-02 8.436613e-01 2.966913e+02 +8.442167e-01 3.407827e-02 5.349176e-01 5.664640e+01 -5.955574e-02 9.977611e-01 3.042705e-02 -3.259218e+01 -5.326831e-01 -5.754443e-02 8.443562e-01 2.976432e+02 +8.446848e-01 3.283325e-02 5.342561e-01 5.724675e+01 -5.871940e-02 9.977768e-01 3.151882e-02 -3.257634e+01 -5.320335e-01 -5.799465e-02 8.447348e-01 2.985989e+02 +8.451674e-01 3.233575e-02 5.335228e-01 5.784400e+01 -5.909066e-02 9.977024e-01 3.313829e-02 -3.255846e+01 -5.312254e-01 -5.953361e-02 8.451363e-01 2.995544e+02 +8.456554e-01 3.140037e-02 5.328048e-01 5.844553e+01 -5.764655e-02 9.978017e-01 3.269071e-02 -3.254287e+01 -5.306070e-01 -5.835942e-02 8.456065e-01 3.005130e+02 +8.462139e-01 3.100368e-02 5.319406e-01 5.904661e+01 -5.651716e-02 9.978968e-01 3.174626e-02 -3.252555e+01 -5.298376e-01 -5.692789e-02 8.461864e-01 3.014742e+02 +8.469787e-01 3.119708e-02 5.307107e-01 5.964824e+01 -5.580932e-02 9.979784e-01 3.040316e-02 -3.251206e+01 -5.286894e-01 -5.536942e-02 8.470075e-01 3.024387e+02 +8.480751e-01 3.013294e-02 5.290185e-01 6.025245e+01 -5.388450e-02 9.981104e-01 2.953034e-02 -3.249993e+01 -5.271291e-01 -5.354984e-02 8.480963e-01 3.034051e+02 +8.495880e-01 2.837910e-02 5.266828e-01 6.085575e+01 -5.210902e-02 9.981825e-01 3.027185e-02 -3.248820e+01 -5.248665e-01 -5.316352e-02 8.495227e-01 3.043772e+02 +8.519568e-01 2.655327e-02 5.229384e-01 6.145457e+01 -5.053213e-02 9.982211e-01 3.163880e-02 -3.247657e+01 -5.211681e-01 -5.338008e-02 8.517831e-01 3.053532e+02 +8.553311e-01 2.604214e-02 5.174269e-01 6.204386e+01 -4.995366e-02 9.982280e-01 3.233484e-02 -3.246368e+01 -5.156680e-01 -5.350435e-02 8.551163e-01 3.063306e+02 +8.599934e-01 2.509201e-02 5.096878e-01 6.262684e+01 -4.809460e-02 9.983300e-01 3.200181e-02 -3.245287e+01 -5.080337e-01 -5.203457e-02 8.597640e-01 3.073125e+02 +8.654638e-01 2.311336e-02 5.004380e-01 6.320067e+01 -4.581122e-02 9.984011e-01 3.311408e-02 -3.244101e+01 -4.988725e-01 -5.158470e-02 8.651389e-01 3.082986e+02 +8.714643e-01 2.337426e-02 4.899016e-01 6.376115e+01 -4.649043e-02 9.983030e-01 3.506855e-02 -3.242862e+01 -4.882506e-01 -5.333672e-02 8.710721e-01 3.092962e+02 +8.778109e-01 2.393620e-02 4.784088e-01 6.430564e+01 -4.601081e-02 9.983459e-01 3.447297e-02 -3.241601e+01 -4.767924e-01 -5.227272e-02 8.774603e-01 3.102960e+02 +8.840561e-01 2.476244e-02 4.667243e-01 6.483487e+01 -4.625473e-02 9.983286e-01 3.464727e-02 -3.240129e+01 -4.650863e-01 -5.221833e-02 8.837239e-01 3.113014e+02 +8.900317e-01 2.506211e-02 4.552092e-01 6.534992e+01 -4.730870e-02 9.981745e-01 3.754291e-02 -3.238606e+01 -4.534374e-01 -5.494973e-02 8.895927e-01 3.123119e+02 +8.959243e-01 2.393901e-02 4.435613e-01 6.584964e+01 -4.660084e-02 9.981020e-01 4.025881e-02 -3.236908e+01 -4.417557e-01 -5.673916e-02 8.953394e-01 3.133280e+02 +9.018856e-01 2.327216e-02 4.313476e-01 6.633619e+01 -4.526859e-02 9.981414e-01 4.079813e-02 -3.234945e+01 -4.295965e-01 -5.632174e-02 9.012629e-01 3.143430e+02 +9.077615e-01 2.289902e-02 4.188612e-01 6.680683e+01 -4.414878e-02 9.981788e-01 4.110964e-02 -3.232900e+01 -4.171570e-01 -5.580995e-02 9.071192e-01 3.153642e+02 +9.133441e-01 2.391462e-02 4.064858e-01 6.726172e+01 -4.499725e-02 9.980875e-01 4.238543e-02 -3.230847e+01 -4.046948e-01 -5.700321e-02 9.126734e-01 3.163929e+02 +9.186636e-01 2.681375e-02 3.941297e-01 6.769762e+01 -4.751215e-02 9.979511e-01 4.285103e-02 -3.228716e+01 -3.921732e-01 -5.809162e-02 9.180553e-01 3.174229e+02 +9.237141e-01 3.067151e-02 3.818527e-01 6.811608e+01 -5.048237e-02 9.978427e-01 4.196887e-02 -3.226561e+01 -3.797417e-01 -5.804406e-02 9.232698e-01 3.184582e+02 +9.280021e-01 3.489912e-02 3.709368e-01 6.851895e+01 -5.424331e-02 9.976507e-01 4.184206e-02 -3.224256e+01 -3.686051e-01 -5.895035e-02 9.277150e-01 3.194969e+02 +9.312206e-01 4.011627e-02 3.622415e-01 6.891120e+01 -5.944661e-02 9.973318e-01 4.237136e-02 -3.221964e+01 -3.595752e-01 -6.099110e-02 9.311207e-01 3.205379e+02 +9.338147e-01 4.236021e-02 3.552403e-01 6.929662e+01 -6.170225e-02 9.971553e-01 4.329112e-02 -3.219587e+01 -3.523960e-01 -6.234500e-02 9.337720e-01 3.215796e+02 +9.359521e-01 4.253500e-02 3.495488e-01 6.968136e+01 -6.128420e-02 9.972044e-01 4.274932e-02 -3.217085e+01 -3.467533e-01 -6.143312e-02 9.359424e-01 3.226199e+02 +9.375960e-01 4.148239e-02 3.452433e-01 7.006439e+01 -5.995499e-02 9.972746e-01 4.299639e-02 -3.214709e+01 -3.425188e-01 -6.101229e-02 9.375278e-01 3.236608e+02 +9.393604e-01 3.981187e-02 3.406127e-01 7.044427e+01 -5.762384e-02 9.974404e-01 4.233424e-02 -3.212381e+01 -3.380554e-01 -5.939451e-02 9.392501e-01 3.247015e+02 +9.411970e-01 3.839767e-02 3.356693e-01 7.081841e+01 -5.580119e-02 9.975432e-01 4.235289e-02 -3.210145e+01 -3.332184e-01 -5.859315e-02 9.410273e-01 3.257426e+02 +9.430818e-01 3.720624e-02 3.304731e-01 7.118513e+01 -5.373161e-02 9.977130e-01 4.100829e-02 -3.208036e+01 -3.281916e-01 -5.643101e-02 9.429241e-01 3.267834e+02 +9.448274e-01 3.698592e-02 3.254738e-01 7.154449e+01 -5.262630e-02 9.978375e-01 3.937895e-02 -3.206064e+01 -3.233135e-01 -5.433479e-02 9.447307e-01 3.278233e+02 +9.466288e-01 3.818826e-02 3.200556e-01 7.189744e+01 -5.313601e-02 9.978602e-01 3.809816e-02 -3.204255e+01 -3.179158e-01 -5.307128e-02 9.466324e-01 3.288691e+02 +9.485479e-01 3.957804e-02 3.141503e-01 7.223984e+01 -5.393370e-02 9.978538e-01 3.713377e-02 -3.202417e+01 -3.120064e-01 -5.216644e-02 9.486468e-01 3.299145e+02 +9.508317e-01 3.958394e-02 3.071679e-01 7.257908e+01 -5.395970e-02 9.978027e-01 3.844679e-02 -3.200816e+01 -3.049711e-01 -5.313111e-02 9.508784e-01 3.309626e+02 +9.529773e-01 4.024064e-02 3.003580e-01 7.290725e+01 -5.557475e-02 9.975418e-01 4.268153e-02 -3.198875e+01 -2.979022e-01 -5.736684e-02 9.528711e-01 3.320149e+02 +9.548738e-01 4.081874e-02 2.941935e-01 7.322541e+01 -5.680030e-02 9.973261e-01 4.598169e-02 -3.196820e+01 -2.915300e-01 -6.061698e-02 9.546391e-01 3.330660e+02 +9.566058e-01 4.098093e-02 2.884890e-01 7.353763e+01 -5.607827e-02 9.974448e-01 4.426016e-02 -3.194626e+01 -2.859381e-01 -5.851748e-02 9.564597e-01 3.341099e+02 +9.579908e-01 3.965355e-02 2.840446e-01 7.384678e+01 -5.365111e-02 9.976900e-01 4.166706e-02 -3.192828e+01 -2.817362e-01 -5.515596e-02 9.579053e-01 3.351522e+02 +9.592983e-01 3.656504e-02 2.800173e-01 7.415395e+01 -4.940245e-02 9.980202e-01 3.892270e-02 -3.191045e+01 -2.780397e-01 -5.117201e-02 9.592056e-01 3.361900e+02 +9.599844e-01 3.594678e-02 2.777370e-01 7.445680e+01 -4.921766e-02 9.979480e-01 4.095657e-02 -3.189088e+01 -2.756948e-01 -5.298722e-02 9.597837e-01 3.372283e+02 +9.598965e-01 3.667299e-02 2.779458e-01 7.475129e+01 -4.992380e-02 9.979215e-01 4.074499e-02 -3.187433e+01 -2.758739e-01 -5.298707e-02 9.597322e-01 3.382575e+02 +9.582819e-01 4.074143e-02 2.829064e-01 7.504168e+01 -5.473006e-02 9.976293e-01 4.171688e-02 -3.186005e+01 -2.805361e-01 -5.546000e-02 9.582399e-01 3.392779e+02 +9.551769e-01 4.492869e-02 2.926066e-01 7.533938e+01 -5.992942e-02 9.972974e-01 4.250045e-02 -3.184496e+01 -2.899063e-01 -5.813118e-02 9.552880e-01 3.402804e+02 +9.513831e-01 4.756742e-02 3.043149e-01 7.564658e+01 -6.336847e-02 9.970953e-01 4.225369e-02 -3.183043e+01 -3.014210e-01 -5.948341e-02 9.516339e-01 3.412657e+02 +9.476980e-01 4.808189e-02 3.155261e-01 7.596199e+01 -6.465591e-02 9.970121e-01 4.226600e-02 -3.181686e+01 -3.125512e-01 -6.045602e-02 9.479751e-01 3.422291e+02 +9.445908e-01 4.586034e-02 3.250309e-01 7.628669e+01 -6.310944e-02 9.970918e-01 4.272087e-02 -3.180263e+01 -3.221265e-01 -6.086625e-02 9.447380e-01 3.431793e+02 +9.420469e-01 4.302002e-02 3.327116e-01 7.661429e+01 -6.077602e-02 9.972187e-01 4.314089e-02 -3.178885e+01 -3.299303e-01 -6.086162e-02 9.420413e-01 3.441086e+02 +9.401575e-01 4.208438e-02 3.381313e-01 7.694057e+01 -5.977432e-02 9.973249e-01 4.207082e-02 -3.177555e+01 -3.354563e-01 -5.976475e-02 9.401581e-01 3.450200e+02 +9.390690e-01 4.096428e-02 3.412789e-01 7.726414e+01 -5.798408e-02 9.975232e-01 3.981562e-02 -3.176135e+01 -3.388026e-01 -5.717835e-02 9.391184e-01 3.459187e+02 +9.390701e-01 4.009681e-02 3.413789e-01 7.758804e+01 -5.620696e-02 9.977173e-01 3.742758e-02 -3.174891e+01 -3.390990e-01 -5.433498e-02 9.391803e-01 3.468106e+02 +9.401852e-01 3.796677e-02 3.385416e-01 7.790573e+01 -5.352424e-02 9.978906e-01 3.673403e-02 -3.173516e+01 -3.364328e-01 -5.265696e-02 9.402341e-01 3.477052e+02 +9.425340e-01 3.586142e-02 3.321801e-01 7.821710e+01 -5.088380e-02 9.980325e-01 3.663327e-02 -3.172234e+01 -3.302129e-01 -5.143068e-02 9.425043e-01 3.485992e+02 +9.457259e-01 3.277664e-02 3.233083e-01 7.851685e+01 -4.699416e-02 9.982366e-01 3.626489e-02 -3.170691e+01 -3.215496e-01 -4.949023e-02 9.455985e-01 3.494904e+02 +9.496039e-01 3.011113e-02 3.120029e-01 7.880464e+01 -4.345337e-02 9.984103e-01 3.589780e-02 -3.168943e+01 -3.104260e-01 -4.764626e-02 9.494027e-01 3.503859e+02 +9.540392e-01 2.828549e-02 2.983441e-01 7.907651e+01 -4.092783e-02 9.985057e-01 3.621163e-02 -3.167291e+01 -2.968740e-01 -4.675788e-02 9.537712e-01 3.512823e+02 +9.590571e-01 2.552107e-02 2.820606e-01 7.933206e+01 -3.755331e-02 9.985969e-01 3.733418e-02 -3.165684e+01 -2.807120e-01 -4.639791e-02 9.586699e-01 3.521784e+02 +9.646254e-01 2.161556e-02 2.627369e-01 7.957169e+01 -3.262064e-02 9.987604e-01 3.759624e-02 -3.164085e+01 -2.615986e-01 -4.483692e-02 9.641348e-01 3.530776e+02 +9.701719e-01 1.865116e-02 2.416996e-01 7.978843e+01 -2.838871e-02 9.989168e-01 3.686791e-02 -3.162513e+01 -2.407502e-01 -4.262974e-02 9.696505e-01 3.539707e+02 +9.755566e-01 1.874980e-02 2.189470e-01 7.998163e+01 -2.732870e-02 9.989701e-01 3.621976e-02 -3.160841e+01 -2.180424e-01 -4.131795e-02 9.750643e-01 3.548763e+02 +9.807129e-01 1.934760e-02 1.944941e-01 8.014676e+01 -2.675395e-02 9.990106e-01 3.552539e-02 -3.159145e+01 -1.936143e-01 -4.004368e-02 9.802602e-01 3.557830e+02 +9.855526e-01 1.902854e-02 1.682974e-01 8.028920e+01 -2.518124e-02 9.990874e-01 3.449995e-02 -3.157733e+01 -1.674873e-01 -3.823945e-02 9.851324e-01 3.566801e+02 +9.897938e-01 2.009418e-02 1.410829e-01 8.040211e+01 -2.482820e-02 9.991834e-01 3.187499e-02 -3.155984e+01 -1.403272e-01 -3.505250e-02 9.894845e-01 3.575935e+02 +9.934330e-01 2.263798e-02 1.121534e-01 8.048729e+01 -2.626344e-02 9.991757e-01 3.095440e-02 -3.154180e+01 -1.113602e-01 -3.369665e-02 9.932087e-01 3.585136e+02 +9.963424e-01 2.319531e-02 8.224292e-02 8.054421e+01 -2.582694e-02 9.991831e-01 3.107998e-02 -3.152557e+01 -8.145483e-02 -3.309038e-02 9.961276e-01 3.594226e+02 +9.984295e-01 2.243571e-02 5.133385e-02 8.057789e+01 -2.412290e-02 9.991810e-01 3.248690e-02 -3.150891e+01 -5.056294e-02 -3.367419e-02 9.981530e-01 3.603471e+02 +9.995068e-01 2.404381e-02 2.020044e-02 8.057910e+01 -2.467591e-02 9.991944e-01 3.164738e-02 -3.149357e+01 -1.942325e-02 -3.213023e-02 9.992950e-01 3.612565e+02 +9.996532e-01 2.417797e-02 -1.043695e-02 8.055395e+01 -2.384796e-02 9.992452e-01 3.066379e-02 -3.148122e+01 1.117047e-02 -3.040425e-02 9.994753e-01 3.621817e+02 +9.989104e-01 2.453541e-02 -3.969878e-02 8.050377e+01 -2.336479e-02 9.992861e-01 2.968761e-02 -3.146835e+01 4.039884e-02 -2.872770e-02 9.987706e-01 3.631079e+02 +9.974469e-01 2.786877e-02 -6.574932e-02 8.042244e+01 -2.611273e-02 9.992829e-01 2.741821e-02 -3.145847e+01 6.646629e-02 -2.563130e-02 9.974594e-01 3.640223e+02 +9.957193e-01 3.037762e-02 -8.729408e-02 8.032530e+01 -2.810733e-02 9.992369e-01 2.712020e-02 -3.144743e+01 8.805133e-02 -2.455050e-02 9.958134e-01 3.649501e+02 +9.938876e-01 3.567106e-02 -1.044753e-01 8.020825e+01 -3.262027e-02 9.989941e-01 3.076616e-02 -3.143001e+01 1.054677e-01 -2.717008e-02 9.940515e-01 3.658859e+02 +9.923495e-01 4.360866e-02 -1.155021e-01 8.007791e+01 -3.953090e-02 9.985195e-01 3.736415e-02 -3.141455e+01 1.169605e-01 -3.251239e-02 9.926043e-01 3.668241e+02 +9.914944e-01 4.668370e-02 -1.214885e-01 7.994829e+01 -4.243669e-02 9.984020e-01 3.731529e-02 -3.139688e+01 1.230363e-01 -3.184233e-02 9.918912e-01 3.677646e+02 +9.909743e-01 4.919857e-02 -1.246974e-01 7.981544e+01 -4.574437e-02 9.984900e-01 3.041603e-02 -3.137499e+01 1.260056e-01 -2.443729e-02 9.917285e-01 3.687053e+02 +9.908227e-01 5.040871e-02 -1.254166e-01 7.968395e+01 -4.760636e-02 9.985471e-01 2.524404e-02 -3.135541e+01 1.265070e-01 -1.904173e-02 9.917830e-01 3.696588e+02 +9.909114e-01 5.270837e-02 -1.237598e-01 7.955293e+01 -5.018119e-02 9.984647e-01 2.345152e-02 -3.134232e+01 1.248059e-01 -1.702796e-02 9.920351e-01 3.706239e+02 +9.912645e-01 5.333366e-02 -1.206245e-01 7.942602e+01 -5.082417e-02 9.984242e-01 2.378817e-02 -3.133323e+01 1.217031e-01 -1.744973e-02 9.924132e-01 3.716010e+02 +9.916542e-01 5.252796e-02 -1.177407e-01 7.930568e+01 -5.001100e-02 9.984546e-01 2.423275e-02 -3.132438e+01 1.188317e-01 -1.814217e-02 9.927487e-01 3.725851e+02 +9.920852e-01 5.006545e-02 -1.151543e-01 7.918987e+01 -4.779956e-02 9.986067e-01 2.235674e-02 -3.131667e+01 1.161131e-01 -1.667546e-02 9.930960e-01 3.735762e+02 +9.924558e-01 4.769287e-02 -1.129460e-01 7.907540e+01 -4.601200e-02 9.987885e-01 1.744400e-02 -3.131062e+01 1.136412e-01 -1.211552e-02 9.934480e-01 3.745782e+02 +9.927932e-01 4.501628e-02 -1.110643e-01 7.896176e+01 -4.390777e-02 9.989585e-01 1.240785e-02 -3.130580e+01 1.115072e-01 -7.441834e-03 9.937358e-01 3.755915e+02 +9.930524e-01 4.349545e-02 -1.093389e-01 7.884772e+01 -4.269849e-02 9.990417e-01 9.620917e-03 -3.130379e+01 1.096526e-01 -4.885466e-03 9.939580e-01 3.766174e+02 +9.932093e-01 4.352486e-02 -1.078933e-01 7.873066e+01 -4.259242e-02 9.990327e-01 1.093288e-02 -3.130337e+01 1.082648e-01 -6.263197e-03 9.941024e-01 3.776606e+02 +9.932070e-01 4.609821e-02 -1.068399e-01 7.860938e+01 -4.493127e-02 9.989014e-01 1.330515e-02 -3.130390e+01 1.073359e-01 -8.414310e-03 9.941872e-01 3.787144e+02 +9.931851e-01 4.771713e-02 -1.063317e-01 7.848722e+01 -4.642767e-02 9.988154e-01 1.457080e-02 -3.130288e+01 1.069010e-01 -9.534770e-03 9.942240e-01 3.797791e+02 +9.931000e-01 4.973064e-02 -1.062041e-01 7.836387e+01 -4.842990e-02 9.987170e-01 1.479341e-02 -3.130012e+01 1.068035e-01 -9.547881e-03 9.942343e-01 3.808531e+02 +9.929200e-01 5.234906e-02 -1.066273e-01 7.823690e+01 -5.109493e-02 9.985891e-01 1.446198e-02 -3.129765e+01 1.072339e-01 -8.911470e-03 9.941939e-01 3.819360e+02 +9.927979e-01 5.312605e-02 -1.073772e-01 7.810922e+01 -5.191795e-02 9.985529e-01 1.401749e-02 -3.129518e+01 1.079666e-01 -8.341730e-03 9.941195e-01 3.830249e+02 +9.926443e-01 5.390435e-02 -1.084052e-01 7.798045e+01 -5.288256e-02 9.985252e-01 1.228076e-02 -3.129528e+01 1.089073e-01 -6.457686e-03 9.940309e-01 3.841197e+02 +9.925223e-01 5.265331e-02 -1.101236e-01 7.785278e+01 -5.198194e-02 9.986078e-01 8.960726e-03 -3.130306e+01 1.104421e-01 -3.169278e-03 9.938775e-01 3.852237e+02 +9.923146e-01 4.998643e-02 -1.131948e-01 7.772434e+01 -4.951751e-02 9.987490e-01 6.952312e-03 -3.131219e+01 1.134007e-01 -1.293755e-03 9.935485e-01 3.863317e+02 +9.919594e-01 4.621712e-02 -1.178157e-01 7.759240e+01 -4.564450e-02 9.989291e-01 7.555467e-03 -3.132406e+01 1.180388e-01 -2.117075e-03 9.930067e-01 3.874466e+02 +9.913434e-01 4.096028e-02 -1.247416e-01 7.745375e+01 -4.014371e-02 9.991529e-01 9.053753e-03 -3.133599e+01 1.250068e-01 -3.967785e-03 9.921480e-01 3.885622e+02 +9.903016e-01 3.685952e-02 -1.339559e-01 7.730367e+01 -3.594185e-02 9.993109e-01 9.263158e-03 -3.134834e+01 1.342051e-01 -4.358693e-03 9.909440e-01 3.896735e+02 +9.890423e-01 3.270875e-02 -1.439635e-01 7.714432e+01 -3.187824e-02 9.994591e-01 8.072509e-03 -3.136269e+01 1.441497e-01 -3.394748e-03 9.895501e-01 3.907854e+02 +9.876362e-01 3.064805e-02 -1.537383e-01 7.697095e+01 -3.000316e-02 9.995286e-01 6.513634e-03 -3.137711e+01 1.538654e-01 -1.820465e-03 9.880901e-01 3.918934e+02 +9.861623e-01 2.891463e-02 -1.632416e-01 7.678571e+01 -2.840817e-02 9.995816e-01 5.436550e-03 -3.139270e+01 1.633305e-01 -7.239256e-04 9.865712e-01 3.929985e+02 +9.846017e-01 2.805261e-02 -1.725475e-01 7.658879e+01 -2.747804e-02 9.996060e-01 5.718083e-03 -3.140867e+01 1.726400e-01 -8.887641e-04 9.849846e-01 3.941042e+02 +9.829211e-01 2.749677e-02 -1.819618e-01 7.638134e+01 -2.670021e-02 9.996202e-01 6.826345e-03 -3.142457e+01 1.820804e-01 -1.851338e-03 9.832819e-01 3.952089e+02 +9.812164e-01 2.653286e-02 -1.910770e-01 7.616426e+01 -2.565879e-02 9.996459e-01 7.047647e-03 -3.144009e+01 1.911963e-01 -2.012460e-03 9.815498e-01 3.963079e+02 +9.794497e-01 2.662757e-02 -1.999229e-01 7.593686e+01 -2.601019e-02 9.996453e-01 5.714523e-03 -3.145710e+01 2.000042e-01 -3.970530e-04 9.797950e-01 3.974008e+02 +9.776321e-01 2.751592e-02 -2.085148e-01 7.569807e+01 -2.732365e-02 9.996194e-01 3.802965e-03 -3.147379e+01 2.085401e-01 1.979487e-03 9.780118e-01 3.984859e+02 +9.758480e-01 2.682004e-02 -2.167982e-01 7.545311e+01 -2.689339e-02 9.996349e-01 2.612565e-03 -3.149232e+01 2.167891e-01 3.280972e-03 9.762130e-01 3.995639e+02 +9.741376e-01 2.714478e-02 -2.243194e-01 7.520190e+01 -2.726094e-02 9.996250e-01 2.579797e-03 -3.151505e+01 2.243053e-01 3.602080e-03 9.745123e-01 4.006413e+02 +9.725444e-01 2.735000e-02 -2.311047e-01 7.494731e+01 -2.756370e-02 9.996174e-01 2.304664e-03 -3.154084e+01 2.310793e-01 4.128713e-03 9.729262e-01 4.017126e+02 +9.711298e-01 2.564116e-02 -2.371695e-01 7.468782e+01 -2.610028e-02 9.996586e-01 1.204434e-03 -3.156546e+01 2.371195e-01 5.020530e-03 9.714675e-01 4.027781e+02 +9.698339e-01 2.137339e-02 -2.428277e-01 7.442503e+01 -2.220539e-02 9.997532e-01 -6.894822e-04 -3.158923e+01 2.427531e-01 6.060770e-03 9.700692e-01 4.038427e+02 +9.684696e-01 1.886897e-02 -2.484162e-01 7.415678e+01 -2.052746e-02 9.997809e-01 -4.087427e-03 -3.161778e+01 2.482846e-01 9.057901e-03 9.686448e-01 4.049015e+02 +9.670849e-01 1.197352e-02 -2.541721e-01 7.388059e+01 -1.491699e-02 9.998421e-01 -9.656303e-03 -3.164410e+01 2.540163e-01 1.312994e-02 9.671108e-01 4.059596e+02 +9.655255e-01 8.761194e-03 -2.601609e-01 7.359545e+01 -1.192685e-02 9.998727e-01 -1.059191e-02 -3.166936e+01 2.600350e-01 1.332966e-02 9.655072e-01 4.070193e+02 +9.642248e-01 9.665364e-03 -2.649097e-01 7.330042e+01 -1.203922e-02 9.999006e-01 -7.338774e-03 -3.169988e+01 2.648125e-01 1.026553e-02 9.642453e-01 4.080800e+02 +9.628993e-01 6.131654e-03 -2.697914e-01 7.300156e+01 -8.535173e-03 9.999336e-01 -7.736581e-03 -3.172440e+01 2.697260e-01 9.752264e-03 9.628877e-01 4.091401e+02 +9.619449e-01 6.480454e-03 -2.731668e-01 7.269584e+01 -8.772435e-03 9.999358e-01 -7.169831e-03 -3.174900e+01 2.731028e-01 9.293320e-03 9.619400e-01 4.101997e+02 +9.610535e-01 8.404343e-03 -2.762345e-01 7.238689e+01 -1.096906e-02 9.999099e-01 -7.740779e-03 -3.177891e+01 2.761446e-01 1.046934e-02 9.610591e-01 4.112612e+02 +9.603689e-01 8.141625e-03 -2.786131e-01 7.207703e+01 -9.874903e-03 9.999396e-01 -4.818200e-03 -3.180392e+01 2.785571e-01 7.378527e-03 9.603913e-01 4.123250e+02 +9.598453e-01 7.672232e-03 -2.804249e-01 7.176328e+01 -7.760704e-03 9.999695e-01 7.949530e-04 -3.182436e+01 2.804225e-01 1.413264e-03 9.598756e-01 4.133909e+02 +9.596106e-01 5.079314e-03 -2.812857e-01 7.145234e+01 -4.859546e-03 9.999871e-01 1.478846e-03 -3.184176e+01 2.812896e-01 -5.219390e-05 9.596229e-01 4.144546e+02 +9.592916e-01 -2.426096e-04 -2.824175e-01 7.114226e+01 6.743045e-04 9.999987e-01 1.431375e-03 -3.185764e+01 2.824168e-01 -1.563539e-03 9.592905e-01 4.155184e+02 +9.590225e-01 -5.100126e-03 -2.832841e-01 7.083109e+01 5.825756e-03 9.999815e-01 1.719114e-03 -3.187188e+01 2.832701e-01 -3.299010e-03 9.590345e-01 4.165892e+02 +9.586750e-01 -8.619838e-03 -2.843729e-01 7.051687e+01 9.482881e-03 9.999536e-01 1.658245e-03 -3.188610e+01 2.843455e-01 -4.286390e-03 9.587123e-01 4.176604e+02 +9.583836e-01 -1.150533e-02 -2.852518e-01 7.019949e+01 1.237432e-02 9.999226e-01 1.244157e-03 -3.190021e+01 2.852154e-01 -4.722172e-03 9.584518e-01 4.187326e+02 +9.580141e-01 -1.317850e-02 -2.864180e-01 6.987920e+01 1.411031e-02 9.998997e-01 1.189494e-03 -3.191565e+01 2.863736e-01 -5.180995e-03 9.581040e-01 4.198042e+02 +9.576187e-01 -1.432052e-02 -2.876828e-01 6.955540e+01 1.556116e-02 9.998768e-01 2.026189e-03 -3.193043e+01 2.876183e-01 -6.416991e-03 9.577236e-01 4.208789e+02 +9.572469e-01 -1.303738e-02 -2.889783e-01 6.922650e+01 1.480031e-02 9.998828e-01 3.916177e-03 -3.194570e+01 2.888934e-01 -8.025713e-03 9.573276e-01 4.219547e+02 +9.569336e-01 -1.037181e-02 -2.901216e-01 6.889716e+01 1.277627e-02 9.998979e-01 6.394868e-03 -3.195867e+01 2.900257e-01 -9.826133e-03 9.569684e-01 4.230276e+02 +9.567188e-01 -8.787389e-03 -2.908815e-01 6.856748e+01 1.180594e-02 9.998931e-01 8.623822e-03 -3.197007e+01 2.907746e-01 -1.168470e-02 9.567202e-01 4.240987e+02 +9.565999e-01 -5.337119e-03 -2.913557e-01 6.823610e+01 8.936102e-03 9.998993e-01 1.102327e-02 -3.197932e+01 2.912675e-01 -1.314844e-02 9.565513e-01 4.251672e+02 +9.567055e-01 -3.595208e-03 -2.910354e-01 6.790725e+01 7.621844e-03 9.998902e-01 1.270308e-02 -3.198673e+01 2.909578e-01 -1.437133e-02 9.566280e-01 4.262316e+02 +9.570759e-01 -2.083915e-03 -2.898298e-01 6.758285e+01 6.398305e-03 9.998823e-01 1.393919e-02 -3.199085e+01 2.897667e-01 -1.519528e-02 9.569767e-01 4.272967e+02 +9.576109e-01 -1.040110e-03 -2.880631e-01 6.726082e+01 5.849658e-03 9.998575e-01 1.583589e-02 -3.199343e+01 2.880056e-01 -1.684968e-02 9.574805e-01 4.283636e+02 +9.580905e-01 -1.076367e-03 -2.864636e-01 6.694492e+01 6.502879e-03 9.998170e-01 1.799243e-02 -3.199838e+01 2.863918e-01 -1.910121e-02 9.579222e-01 4.294275e+02 +9.585171e-01 5.580602e-04 -2.850346e-01 6.663004e+01 5.463129e-03 9.997784e-01 2.032890e-02 -3.200244e+01 2.849828e-01 -2.104277e-02 9.583016e-01 4.304897e+02 +9.589795e-01 2.692731e-03 -2.834625e-01 6.631324e+01 3.930230e-03 9.997325e-01 2.279321e-02 -3.200341e+01 2.834481e-01 -2.297229e-02 9.587124e-01 4.315526e+02 +9.594518e-01 5.651903e-03 -2.818160e-01 6.599975e+01 1.355576e-03 9.996948e-01 2.466428e-02 -3.200405e+01 2.818694e-01 -2.404621e-02 9.591514e-01 4.326125e+02 +9.598513e-01 5.515240e-03 -2.804552e-01 6.569263e+01 1.479793e-03 9.996932e-01 2.472385e-02 -3.200540e+01 2.805055e-01 -2.414623e-02 9.595487e-01 4.336679e+02 +9.602609e-01 5.169796e-03 -2.790560e-01 6.539174e+01 1.606547e-03 9.997095e-01 2.404894e-02 -3.200794e+01 2.790993e-01 -2.354156e-02 9.599737e-01 4.347180e+02 +9.605826e-01 4.132176e-03 -2.779641e-01 6.509184e+01 3.015121e-03 9.996758e-01 2.528063e-02 -3.200684e+01 2.779785e-01 -2.512223e-02 9.602587e-01 4.357636e+02 +9.608670e-01 3.463384e-03 -2.769884e-01 6.479530e+01 4.680217e-03 9.995761e-01 2.873400e-02 -3.200634e+01 2.769705e-01 -2.890591e-02 9.604436e-01 4.368145e+02 +9.611880e-01 1.883028e-03 -2.758879e-01 6.450167e+01 7.204365e-03 9.994644e-01 3.192154e-02 -3.200146e+01 2.758003e-01 -3.267019e-02 9.606596e-01 4.378569e+02 +9.614828e-01 3.900106e-04 -2.748650e-01 6.420944e+01 9.156224e-03 9.993985e-01 3.344670e-02 -3.199374e+01 2.747127e-01 -3.467515e-02 9.609009e-01 4.388958e+02 +9.618114e-01 -3.063960e-04 -2.737128e-01 6.391835e+01 1.003821e-02 9.993661e-01 3.415501e-02 -3.198437e+01 2.735288e-01 -3.559826e-02 9.612049e-01 4.399266e+02 +9.620589e-01 -4.284243e-03 -2.728082e-01 6.363492e+01 1.394311e-02 9.993422e-01 3.347652e-02 -3.197432e+01 2.724854e-01 -3.601017e-02 9.614858e-01 4.409510e+02 +9.622389e-01 -4.862723e-03 -2.721631e-01 6.334747e+01 1.490548e-02 9.992816e-01 3.484456e-02 -3.196290e+01 2.717981e-01 -3.758550e-02 9.616201e-01 4.419773e+02 +9.620955e-01 -1.075145e-02 -2.725007e-01 6.306845e+01 2.094413e-02 9.991844e-01 3.452308e-02 -3.195175e+01 2.719073e-01 -3.892178e-02 9.615360e-01 4.429952e+02 +9.620053e-01 -1.236964e-02 -2.727505e-01 6.278947e+01 2.226969e-02 9.991995e-01 3.323118e-02 -3.194208e+01 2.721211e-01 -3.804263e-02 9.615107e-01 4.440057e+02 +9.620686e-01 -1.367659e-02 -2.724646e-01 6.251137e+01 2.370368e-02 9.991561e-01 3.354387e-02 -3.193323e+01 2.717759e-01 -3.872991e-02 9.615809e-01 4.450131e+02 +9.619395e-01 -1.345342e-02 -2.729313e-01 6.223499e+01 2.430938e-02 9.990404e-01 3.643275e-02 -3.192276e+01 2.721793e-01 -4.168088e-02 9.613434e-01 4.460174e+02 +9.617896e-01 -1.392469e-02 -2.734352e-01 6.195669e+01 2.529313e-02 9.989539e-01 3.809509e-02 -3.191215e+01 2.726188e-01 -4.355549e-02 9.611358e-01 4.470157e+02 +9.616891e-01 -1.307475e-02 -2.738304e-01 6.168102e+01 2.482533e-02 9.989115e-01 3.949061e-02 -3.190034e+01 2.730160e-01 -4.477561e-02 9.609669e-01 4.480051e+02 +9.615732e-01 -1.335312e-02 -2.742239e-01 6.140554e+01 2.497384e-02 9.989298e-01 3.892926e-02 -3.188699e+01 2.734107e-01 -4.428175e-02 9.608776e-01 4.489871e+02 +9.614737e-01 -1.409568e-02 -2.745354e-01 6.113348e+01 2.552746e-02 9.989473e-01 3.811215e-02 -3.187437e+01 2.737092e-01 -4.365201e-02 9.608214e-01 4.499612e+02 +9.613935e-01 -1.446710e-02 -2.747967e-01 6.085985e+01 2.611846e-02 9.989060e-01 3.878810e-02 -3.185869e+01 2.739350e-01 -4.446789e-02 9.607197e-01 4.509360e+02 +9.612217e-01 -1.438168e-02 -2.754014e-01 6.058852e+01 2.668669e-02 9.988033e-01 4.098509e-02 -3.183939e+01 2.744824e-01 -4.674530e-02 9.604552e-01 4.519056e+02 +9.610122e-01 -1.493375e-02 -2.761023e-01 6.031862e+01 2.760938e-02 9.987327e-01 4.207906e-02 -3.182137e+01 2.751240e-01 -4.806149e-02 9.602067e-01 4.528672e+02 +9.608324e-01 -1.530677e-02 -2.767070e-01 6.004749e+01 2.804905e-02 9.987175e-01 4.215035e-02 -3.180084e+01 2.757069e-01 -4.826078e-02 9.600295e-01 4.538214e+02 +9.607495e-01 -1.481606e-02 -2.770214e-01 5.977363e+01 2.751261e-02 9.987386e-01 4.200163e-02 -3.177269e+01 2.760497e-01 -4.797462e-02 9.599453e-01 4.547706e+02 +9.607783e-01 -1.250984e-02 -2.770352e-01 5.949952e+01 2.538946e-02 9.987544e-01 4.295259e-02 -3.174500e+01 2.761529e-01 -4.830169e-02 9.598992e-01 4.557181e+02 +9.608376e-01 -1.063014e-02 -2.769083e-01 5.922788e+01 2.392634e-02 9.987147e-01 4.468214e-02 -3.171546e+01 2.760774e-01 -4.955767e-02 9.598569e-01 4.566613e+02 +9.608998e-01 -9.555925e-03 -2.767314e-01 5.895936e+01 2.335196e-02 9.986406e-01 4.660099e-02 -3.168792e+01 2.759100e-01 -5.124109e-02 9.598167e-01 4.575985e+02 +9.609437e-01 -8.070014e-03 -2.766262e-01 5.868217e+01 2.242701e-02 9.985579e-01 4.877597e-02 -3.165710e+01 2.758337e-01 -5.307485e-02 9.597389e-01 4.585292e+02 +9.609169e-01 -7.149143e-03 -2.767447e-01 5.841123e+01 2.215479e-02 9.984460e-01 5.113333e-02 -3.162677e+01 2.759492e-01 -5.526609e-02 9.595821e-01 4.594540e+02 +9.607653e-01 -6.558182e-03 -2.772853e-01 5.813871e+01 2.267876e-02 9.982304e-01 5.497006e-02 -3.159279e+01 2.764341e-01 -5.910179e-02 9.592138e-01 4.603793e+02 +9.603464e-01 -6.649247e-03 -2.787305e-01 5.786716e+01 2.403459e-02 9.979684e-01 5.900249e-02 -3.155486e+01 2.777719e-01 -6.336198e-02 9.585552e-01 4.612989e+02 +9.598033e-01 -5.968610e-03 -2.806101e-01 5.759517e+01 2.446551e-02 9.977475e-01 6.245999e-02 -3.151624e+01 2.796053e-01 -6.681456e-02 9.577874e-01 4.622195e+02 +9.592298e-01 -7.083787e-03 -2.825385e-01 5.732346e+01 2.645573e-02 9.975470e-01 6.480783e-02 -3.147316e+01 2.813864e-01 -6.964035e-02 9.570642e-01 4.631328e+02 +9.587045e-01 -8.306283e-03 -2.842828e-01 5.705466e+01 2.829094e-02 9.974009e-01 6.626482e-02 -3.143032e+01 2.829935e-01 -7.157099e-02 9.564477e-01 4.640352e+02 +9.581587e-01 -9.671724e-03 -2.860739e-01 5.678473e+01 3.023503e-02 9.972575e-01 6.755161e-02 -3.139085e+01 2.846361e-01 -7.337460e-02 9.558235e-01 4.649402e+02 +9.576250e-01 -9.371747e-03 -2.878656e-01 5.651312e+01 3.036428e-02 9.971857e-01 6.854664e-02 -3.135051e+01 2.864131e-01 -7.438279e-02 9.552145e-01 4.658380e+02 +9.572023e-01 -1.059865e-02 -2.892256e-01 5.624359e+01 3.182644e-02 9.971233e-01 6.879120e-02 -3.131104e+01 2.876645e-01 -7.505210e-02 9.547860e-01 4.667311e+02 +9.571066e-01 -1.159583e-02 -2.895039e-01 5.597516e+01 3.312645e-02 9.970261e-01 6.958175e-02 -3.126845e+01 2.878361e-01 -7.618738e-02 9.546444e-01 4.676161e+02 +9.573283e-01 -1.026314e-02 -2.888203e-01 5.570642e+01 3.178866e-02 9.970447e-01 6.993753e-02 -3.122947e+01 2.872490e-01 -7.613437e-02 9.548254e-01 4.684902e+02 +9.576091e-01 -1.130007e-02 -2.878490e-01 5.544306e+01 3.287388e-02 9.969893e-01 7.022528e-02 -3.118950e+01 2.861889e-01 -7.671107e-02 9.550976e-01 4.693590e+02 +9.577366e-01 -1.620599e-02 -2.871899e-01 5.519015e+01 3.786796e-02 9.968256e-01 7.003371e-02 -3.114825e+01 2.851433e-01 -7.794912e-02 9.553100e-01 4.702193e+02 +9.578610e-01 -1.754471e-02 -2.866960e-01 5.493808e+01 3.963077e-02 9.966590e-01 7.141594e-02 -3.110661e+01 2.844852e-01 -7.976851e-02 9.553561e-01 4.710680e+02 +9.580893e-01 -1.703452e-02 -2.859628e-01 5.468622e+01 3.927122e-02 9.966162e-01 7.220674e-02 -3.106783e+01 2.837652e-01 -8.041059e-02 9.555163e-01 4.719076e+02 +9.581123e-01 -1.858824e-02 -2.857889e-01 5.443976e+01 4.050353e-02 9.966561e-01 7.096440e-02 -3.102890e+01 2.835142e-01 -7.956730e-02 9.556614e-01 4.727303e+02 +9.583442e-01 -1.935752e-02 -2.849591e-01 5.419609e+01 4.060583e-02 9.968004e-01 6.884768e-02 -3.098990e+01 2.827147e-01 -7.755076e-02 9.560640e-01 4.735398e+02 +9.585652e-01 -2.027615e-02 -2.841507e-01 5.395765e+01 4.095299e-02 9.969111e-01 6.701580e-02 -3.095139e+01 2.819142e-01 -7.587582e-02 9.564347e-01 4.743351e+02 +9.588505e-01 -1.913804e-02 -2.832658e-01 5.372093e+01 3.952571e-02 9.970076e-01 6.643397e-02 -3.091411e+01 2.811467e-01 -7.489651e-02 9.567377e-01 4.751187e+02 +9.591229e-01 -1.881507e-02 -2.823638e-01 5.348669e+01 3.888567e-02 9.970850e-01 6.564546e-02 -3.087727e+01 2.803056e-01 -7.394196e-02 9.570587e-01 4.758951e+02 +9.593160e-01 -2.006491e-02 -2.816207e-01 5.325673e+01 3.993959e-02 9.970850e-01 6.501036e-02 -3.084191e+01 2.794954e-01 -7.361328e-02 9.573210e-01 4.766670e+02 +9.595631e-01 -2.253665e-02 -2.805899e-01 5.302994e+01 4.210843e-02 9.970663e-01 6.391949e-02 -3.080574e+01 2.783262e-01 -7.314997e-02 9.576970e-01 4.774350e+02 +9.600612e-01 -2.352099e-02 -2.787996e-01 5.280553e+01 4.281214e-02 9.970753e-01 6.330738e-02 -3.077058e+01 2.764951e-01 -7.271495e-02 9.582604e-01 4.782003e+02 +9.610486e-01 -2.246948e-02 -2.754645e-01 5.258238e+01 4.138936e-02 9.971509e-01 6.306337e-02 -3.073711e+01 2.732626e-01 -7.200825e-02 9.592405e-01 4.789637e+02 +9.623911e-01 -2.458798e-02 -2.705530e-01 5.236818e+01 4.284777e-02 9.971689e-01 6.179170e-02 -3.070384e+01 2.682677e-01 -7.106036e-02 9.607200e-01 4.797274e+02 +9.642928e-01 -2.449316e-02 -2.637033e-01 5.215897e+01 4.203804e-02 9.972462e-01 6.109616e-02 -3.067249e+01 2.614807e-01 -7.000014e-02 9.626670e-01 4.804948e+02 +9.669527e-01 -2.194001e-02 -2.540100e-01 5.195650e+01 3.902171e-02 9.972877e-01 6.240559e-02 -3.063856e+01 2.519518e-01 -7.025515e-02 9.651863e-01 4.812619e+02 +9.700038e-01 -1.822748e-02 -2.424053e-01 5.176125e+01 3.528474e-02 9.971815e-01 6.621233e-02 -3.060419e+01 2.405152e-01 -7.277941e-02 9.679130e-01 4.820291e+02 +9.733897e-01 -1.551414e-02 -2.286304e-01 5.157938e+01 3.304705e-02 9.967799e-01 7.305880e-02 -3.056469e+01 2.267608e-01 -7.867023e-02 9.707680e-01 4.828083e+02 +9.770299e-01 -1.448378e-02 -2.126095e-01 5.141261e+01 3.181455e-02 9.964204e-01 7.832116e-02 -3.052561e+01 2.107141e-01 -8.328617e-02 9.739933e-01 4.835742e+02 +9.808836e-01 -1.470409e-02 -1.940390e-01 5.126480e+01 3.065842e-02 9.963651e-01 7.947731e-02 -3.048336e+01 1.921650e-01 -8.390691e-02 9.777690e-01 4.843504e+02 +9.848218e-01 -1.203411e-02 -1.731506e-01 5.112985e+01 2.655881e-02 9.962936e-01 8.181424e-02 -3.043579e+01 1.715243e-01 -8.517111e-02 9.814914e-01 4.851306e+02 +9.886026e-01 -1.073292e-02 -1.501657e-01 5.101388e+01 2.351401e-02 9.962220e-01 8.359851e-02 -3.038739e+01 1.487012e-01 -8.617669e-02 9.851201e-01 4.858993e+02 +9.920422e-01 -1.046652e-02 -1.254703e-01 5.092373e+01 2.152125e-02 9.959690e-01 8.707766e-02 -3.033843e+01 1.240531e-01 -8.908497e-02 9.882685e-01 4.866859e+02 +9.949893e-01 -1.166682e-02 -9.929854e-02 5.085612e+01 2.036642e-02 9.959954e-01 8.705330e-02 -3.029042e+01 9.788526e-02 -8.863944e-02 9.912424e-01 4.874558e+02 +9.973026e-01 -1.365264e-02 -7.211948e-02 5.081291e+01 1.988573e-02 9.960595e-01 8.642949e-02 -3.023839e+01 7.065530e-02 -8.763048e-02 9.936442e-01 4.882488e+02 +9.988579e-01 -1.498692e-02 -4.536840e-02 5.078958e+01 1.877961e-02 9.962583e-01 8.436077e-02 -3.018975e+01 4.393434e-02 -8.511641e-02 9.954019e-01 4.890397e+02 +9.996861e-01 -1.676163e-02 -1.862200e-02 5.078273e+01 1.826288e-02 9.963310e-01 8.361138e-02 -3.014069e+01 1.715221e-02 -8.392521e-02 9.963244e-01 4.898147e+02 +9.997948e-01 -1.851778e-02 8.218238e-03 5.079808e+01 1.776015e-02 9.962852e-01 8.426346e-02 -3.009257e+01 -9.748082e-03 -8.410019e-02 9.964096e-01 4.906097e+02 +9.991819e-01 -2.077277e-02 3.469834e-02 5.083755e+01 1.774105e-02 9.961798e-01 8.550494e-02 -3.004458e+01 -3.634196e-02 -8.481939e-02 9.957334e-01 4.914043e+02 +9.978611e-01 -2.426959e-02 6.069759e-02 5.089584e+01 1.891304e-02 9.960010e-01 8.731739e-02 -2.999420e+01 -6.257402e-02 -8.598264e-02 9.943297e-01 4.921865e+02 +9.959342e-01 -2.762675e-02 8.574329e-02 5.097871e+01 1.999591e-02 9.958654e-01 8.861240e-02 -2.994151e+01 -8.783685e-02 -8.653759e-02 9.923689e-01 4.929845e+02 +9.934049e-01 -2.938881e-02 1.108285e-01 5.107691e+01 1.951275e-02 9.958256e-01 8.916551e-02 -2.988899e+01 -1.129863e-01 -8.641487e-02 9.898316e-01 4.937676e+02 +9.901522e-01 -3.239009e-02 1.361967e-01 5.120034e+01 2.027135e-02 9.957856e-01 8.944320e-02 -2.983565e+01 -1.385198e-01 -8.580147e-02 9.866359e-01 4.945665e+02 +9.863423e-01 -3.467975e-02 1.610159e-01 5.134527e+01 2.039271e-02 9.957735e-01 8.955009e-02 -2.978214e+01 -1.634409e-01 -8.504348e-02 9.828808e-01 4.953675e+02 +9.819802e-01 -3.597643e-02 1.855278e-01 5.150743e+01 1.977243e-02 9.958832e-01 8.846222e-02 -2.973015e+01 -1.879466e-01 -8.319980e-02 9.786490e-01 4.961540e+02 +9.772736e-01 -3.814455e-02 2.085217e-01 5.169023e+01 2.024571e-02 9.959757e-01 8.730727e-02 -2.967656e+01 -2.110128e-01 -8.110141e-02 9.741130e-01 4.969540e+02 +9.724904e-01 -4.002615e-02 2.294785e-01 5.188905e+01 2.079878e-02 9.961122e-01 8.560247e-02 -2.962201e+01 -2.320127e-01 -7.847469e-02 9.695421e-01 4.977384e+02 +9.675294e-01 -4.233541e-02 2.491878e-01 5.210391e+01 2.162195e-02 9.961221e-01 8.528261e-02 -2.956599e+01 -2.518320e-01 -7.712549e-02 9.646929e-01 4.985380e+02 +9.625207e-01 -4.252835e-02 2.678531e-01 5.233480e+01 2.034278e-02 9.961677e-01 8.506538e-02 -2.951232e+01 -2.704443e-01 -7.642829e-02 9.596971e-01 4.993404e+02 +9.573276e-01 -4.219142e-02 2.859086e-01 5.257730e+01 1.878730e-02 9.962790e-01 8.411370e-02 -2.945884e+01 -2.883937e-01 -7.515290e-02 9.545581e-01 5.001304e+02 +9.519771e-01 -4.229293e-02 3.032340e-01 5.283706e+01 1.752415e-02 9.963164e-01 8.394362e-02 -2.940357e+01 -3.056672e-01 -7.459847e-02 9.492116e-01 5.009295e+02 +9.461589e-01 -4.362132e-02 3.207498e-01 5.311500e+01 1.766347e-02 9.963597e-01 8.339859e-02 -2.934870e+01 -3.232202e-01 -7.324276e-02 9.434852e-01 5.017272e+02 +9.399810e-01 -4.437076e-02 3.383298e-01 5.340723e+01 1.702433e-02 9.963730e-01 8.337217e-02 -2.929596e+01 -3.408020e-01 -7.260840e-02 9.373271e-01 5.025154e+02 +9.333724e-01 -4.489056e-02 3.560909e-01 5.371836e+01 1.599630e-02 9.963644e-01 8.367768e-02 -2.924292e+01 -3.585527e-01 -7.240629e-02 9.306972e-01 5.033105e+02 +9.263231e-01 -4.873571e-02 3.735644e-01 5.404875e+01 1.786562e-02 9.961642e-01 8.565978e-02 -2.918701e+01 -3.763063e-01 -7.267466e-02 9.236406e-01 5.040955e+02 +9.193175e-01 -5.051481e-02 3.902610e-01 5.439704e+01 1.760389e-02 9.960130e-01 8.745390e-02 -2.913444e+01 -3.931228e-01 -7.352777e-02 9.165414e-01 5.048849e+02 +9.121114e-01 -4.963176e-02 4.069268e-01 5.475466e+01 1.529972e-02 9.960738e-01 8.719469e-02 -2.908324e+01 -4.096568e-01 -7.330539e-02 9.092897e-01 5.056708e+02 +9.045489e-01 -5.038952e-02 4.233818e-01 5.512853e+01 1.532994e-02 9.961934e-01 8.581153e-02 -2.902950e+01 -4.260942e-01 -7.113030e-02 9.018782e-01 5.064413e+02 +8.969988e-01 -5.020373e-02 4.391728e-01 5.551857e+01 1.587327e-02 9.965470e-01 8.149887e-02 -2.897454e+01 -4.417479e-01 -6.613327e-02 8.946984e-01 5.072150e+02 +8.888782e-01 -4.834803e-02 4.555854e-01 5.592001e+01 1.254110e-02 9.966112e-01 8.129470e-02 -2.892099e+01 -4.579720e-01 -6.654753e-02 8.864723e-01 5.079885e+02 +8.799400e-01 -4.338132e-02 4.731001e-01 5.633078e+01 7.189861e-03 9.969242e-01 7.804109e-02 -2.887181e+01 -4.750305e-01 -6.526994e-02 8.775454e-01 5.087464e+02 +8.698170e-01 -4.173764e-02 4.916058e-01 5.676502e+01 3.726718e-03 9.969427e-01 7.804723e-02 -2.881938e+01 -4.933604e-01 -6.605472e-02 8.673133e-01 5.095093e+02 +8.587988e-01 -4.398081e-02 5.104216e-01 5.722092e+01 3.007884e-03 9.967239e-01 8.082254e-02 -2.876947e+01 -5.123041e-01 -6.787500e-02 8.561177e-01 5.102608e+02 +8.469445e-01 -4.613936e-02 5.296755e-01 5.769773e+01 1.917738e-03 9.964861e-01 8.373622e-02 -2.872154e+01 -5.316779e-01 -6.990414e-02 8.440569e-01 5.109963e+02 +8.336338e-01 -4.692223e-02 5.503208e-01 5.819202e+01 9.129555e-05 9.963964e-01 8.481789e-02 -2.867046e+01 -5.523176e-01 -7.065680e-02 8.306341e-01 5.117304e+02 +8.187790e-01 -4.807271e-02 5.720927e-01 5.870363e+01 -9.238594e-04 9.963765e-01 8.504735e-02 -2.862006e+01 -5.741082e-01 -7.016350e-02 8.157677e-01 5.124344e+02 +8.026191e-01 -4.975428e-02 5.944132e-01 5.923643e+01 -1.330563e-03 9.963633e-01 8.519542e-02 -2.856822e+01 -5.964904e-01 -6.917036e-02 7.996341e-01 5.131364e+02 +7.858002e-01 -5.154619e-02 6.163286e-01 5.978904e+01 -1.435374e-03 9.963662e-01 8.516043e-02 -2.851717e+01 -6.184788e-01 -6.780374e-02 7.828708e-01 5.138240e+02 +7.686883e-01 -5.371489e-02 6.373641e-01 6.035691e+01 -9.361084e-04 9.963720e-01 8.509986e-02 -2.846556e+01 -6.396229e-01 -6.601189e-02 7.658492e-01 5.144741e+02 +7.511916e-01 -5.704359e-02 6.576148e-01 6.094103e+01 7.648312e-04 9.963334e-01 8.555148e-02 -2.841393e+01 -6.600838e-01 -6.376258e-02 7.484810e-01 5.151230e+02 +7.336238e-01 -6.008988e-02 6.768938e-01 6.154043e+01 1.406592e-03 9.962149e-01 8.691251e-02 -2.836362e+01 -6.795544e-01 -6.280896e-02 7.309316e-01 5.157527e+02 +7.162854e-01 -6.237021e-02 6.950146e-01 6.214796e+01 2.012411e-03 9.961780e-01 8.732246e-02 -2.831325e+01 -6.978046e-01 -6.114914e-02 7.136733e-01 5.163489e+02 +6.998847e-01 -6.268155e-02 7.115001e-01 6.277411e+01 1.563024e-03 9.962738e-01 8.623198e-02 -2.826593e+01 -7.142541e-01 -5.924034e-02 6.973748e-01 5.169483e+02 +6.846843e-01 -6.383124e-02 7.260392e-01 6.341000e+01 2.537211e-03 9.963602e-01 8.520440e-02 -2.821523e+01 -7.288354e-01 -5.649599e-02 6.823542e-01 5.175230e+02 +6.702881e-01 -6.707434e-02 7.390635e-01 6.406358e+01 3.866877e-03 9.962091e-01 8.690479e-02 -2.816320e+01 -7.420909e-01 -5.539337e-02 6.680065e-01 5.180987e+02 +6.558814e-01 -6.974241e-02 7.516352e-01 6.472637e+01 2.732235e-03 9.959356e-01 9.002630e-02 -2.810952e+01 -7.548590e-01 -5.699293e-02 6.534063e-01 5.186677e+02 +6.412539e-01 -7.015009e-02 7.641154e-01 6.539789e+01 1.103225e-03 9.958955e-01 9.050299e-02 -2.805897e+01 -7.673280e-01 -5.719239e-02 6.386993e-01 5.192173e+02 +6.266821e-01 -6.779322e-02 7.763205e-01 6.608128e+01 -1.025086e-03 9.961361e-01 8.781642e-02 -2.800302e+01 -7.792743e-01 -5.582877e-02 6.241912e-01 5.197634e+02 +6.114584e-01 -6.879987e-02 7.882799e-01 6.678150e+01 1.875651e-04 9.962254e-01 8.680356e-02 -2.794340e+01 -7.912766e-01 -5.292890e-02 6.091633e-01 5.202979e+02 +5.957207e-01 -7.231683e-02 7.999294e-01 6.749669e+01 -3.684137e-04 9.959137e-01 9.030898e-02 -2.788382e+01 -8.031916e-01 -5.409363e-02 5.932598e-01 5.208146e+02 +5.793971e-01 -7.700612e-02 8.113994e-01 6.822668e+01 -3.268039e-03 9.952992e-01 9.679281e-02 -2.782480e+01 -8.150388e-01 -5.873315e-02 5.764218e-01 5.213332e+02 +5.616243e-01 -7.892540e-02 8.236194e-01 6.896467e+01 -5.689158e-03 9.950480e-01 9.923242e-02 -2.776260e+01 -8.273728e-01 -6.041703e-02 5.583941e-01 5.218221e+02 +5.425835e-01 -7.957092e-02 8.362246e-01 6.972064e+01 -7.006533e-03 9.950399e-01 9.922918e-02 -2.769845e+01 -8.399727e-01 -5.969914e-02 5.393347e-01 5.223072e+02 +5.223914e-01 -8.023581e-02 8.489225e-01 7.049014e+01 -6.883082e-03 9.951339e-01 9.829054e-02 -2.763187e+01 -8.526781e-01 -5.718933e-02 5.192971e-01 5.227752e+02 +5.017352e-01 -8.106770e-02 8.612142e-01 7.126995e+01 -6.118346e-03 9.952413e-01 9.724843e-02 -2.756393e+01 -8.649997e-01 -5.406215e-02 4.988516e-01 5.232094e+02 +4.802261e-01 -8.290379e-02 8.732181e-01 7.206765e+01 -5.316207e-03 9.952300e-01 9.741132e-02 -2.749619e+01 -8.771287e-01 -5.142166e-02 4.774947e-01 5.236424e+02 +4.579942e-01 -8.559500e-02 8.848247e-01 7.288195e+01 -2.770623e-03 9.952113e-01 9.770755e-02 -2.743168e+01 -8.889509e-01 -4.720101e-02 4.555639e-01 5.240537e+02 +4.351263e-01 -8.822542e-02 8.960365e-01 7.370685e+01 -3.289653e-04 9.951719e-01 9.814625e-02 -2.736328e+01 -9.003694e-01 -4.300078e-02 4.329965e-01 5.244314e+02 +4.119126e-01 -8.963961e-02 9.068036e-01 7.454929e+01 -3.012796e-04 9.951362e-01 9.850836e-02 -2.729490e+01 -9.112233e-01 -4.085004e-02 4.098822e-01 5.248091e+02 +3.883198e-01 -9.093247e-02 9.170273e-01 7.540261e+01 -9.814549e-04 9.950782e-01 9.908763e-02 -2.722692e+01 -9.215242e-01 -3.937770e-02 3.863193e-01 5.251532e+02 +3.643104e-01 -9.014796e-02 9.269041e-01 7.627214e+01 -2.656263e-03 9.951992e-01 9.783417e-02 -2.715831e+01 -9.312738e-01 -3.810410e-02 3.623219e-01 5.254938e+02 +3.399194e-01 -8.837757e-02 9.362928e-01 7.715385e+01 -4.657703e-03 9.954043e-01 9.564815e-02 -2.709050e+01 -9.404431e-01 -3.687363e-02 3.379456e-01 5.258152e+02 +3.149723e-01 -8.700860e-02 9.451042e-01 7.804891e+01 -8.317952e-03 9.954977e-01 9.442006e-02 -2.702582e+01 -9.490645e-01 -3.760103e-02 3.128304e-01 5.260993e+02 +2.898416e-01 -8.659132e-02 9.531494e-01 7.895806e+01 -1.110210e-02 9.955275e-01 9.381731e-02 -2.696030e+01 -9.570103e-01 -3.777411e-02 2.875839e-01 5.263779e+02 +2.638995e-01 -8.710383e-02 9.606092e-01 7.988199e+01 -1.334692e-02 9.954890e-01 9.393328e-02 -2.689512e+01 -9.644579e-01 -3.761011e-02 2.615464e-01 5.266331e+02 +2.377658e-01 -8.809542e-02 9.673193e-01 8.081229e+01 -1.466214e-02 9.954396e-01 9.426033e-02 -2.682926e+01 -9.712119e-01 -3.659485e-02 2.353898e-01 5.268463e+02 +2.110240e-01 -8.891862e-02 9.734281e-01 8.175988e+01 -1.451230e-02 9.954591e-01 9.407711e-02 -2.676321e+01 -9.773732e-01 -3.397921e-02 2.087753e-01 5.270519e+02 +1.844229e-01 -8.938013e-02 9.787744e-01 8.271544e+01 -1.234259e-02 9.955672e-01 9.323926e-02 -2.669427e+01 -9.827695e-01 -2.927606e-02 1.825022e-01 5.272117e+02 +1.579447e-01 -9.042576e-02 9.832988e-01 8.368379e+01 -1.233158e-02 9.955399e-01 9.353227e-02 -2.662491e+01 -9.873710e-01 -2.689855e-02 1.561251e-01 5.273659e+02 +1.320895e-01 -9.215117e-02 9.869450e-01 8.466200e+01 -1.155843e-02 9.954584e-01 9.449302e-02 -2.655209e+01 -9.911704e-01 -2.388906e-02 1.304244e-01 5.274958e+02 +1.067296e-01 -9.114857e-02 9.901014e-01 8.564079e+01 -1.106997e-02 9.956186e-01 9.284981e-02 -2.648066e+01 -9.942265e-01 -2.087022e-02 1.052530e-01 5.275862e+02 +8.153318e-02 -8.991642e-02 9.926063e-01 8.663440e+01 -1.154474e-02 9.957701e-01 9.115132e-02 -2.640934e+01 -9.966038e-01 -1.889124e-02 8.015024e-02 5.276691e+02 +5.621237e-02 -9.039480e-02 9.943183e-01 8.763562e+01 -1.201494e-02 9.957596e-01 9.120509e-02 -2.634008e+01 -9.983466e-01 -1.707353e-02 5.488792e-02 5.277282e+02 +3.133212e-02 -9.268421e-02 9.952024e-01 8.864429e+01 -1.347516e-02 9.955616e-01 9.314192e-02 -2.626934e+01 -9.994182e-01 -1.632885e-02 2.994412e-02 5.277485e+02 +6.820303e-03 -9.581889e-02 9.953754e-01 8.966475e+01 -1.423294e-02 9.952884e-01 9.590806e-02 -2.619854e+01 -9.998755e-01 -1.482124e-02 5.424383e-03 5.277594e+02 +-1.723630e-02 -9.716775e-02 9.951187e-01 9.068595e+01 -1.577031e-02 9.951692e-01 9.689953e-02 -2.612429e+01 -9.997271e-01 -1.402314e-02 -1.868540e-02 5.277447e+02 +-4.183051e-02 -9.657055e-02 9.944467e-01 9.171062e+01 -1.824959e-02 9.952257e-01 9.587856e-02 -2.605169e+01 -9.989581e-01 -1.413760e-02 -4.339317e-02 5.276937e+02 +-6.677370e-02 -9.523864e-02 9.932124e-01 9.274240e+01 -2.096616e-02 9.953482e-01 9.403390e-02 -2.597886e+01 -9.975479e-01 -1.454485e-02 -6.845987e-02 5.276320e+02 +-9.210456e-02 -9.422076e-02 9.912816e-01 9.377225e+01 -2.262117e-02 9.954542e-01 9.251554e-02 -2.590658e+01 -9.954924e-01 -1.390284e-02 -9.381727e-02 5.275293e+02 +-1.169308e-01 -9.296716e-02 9.887792e-01 9.481179e+01 -2.326534e-02 9.955922e-01 9.085644e-02 -2.583551e+01 -9.928675e-01 -1.238037e-02 -1.185783e-01 5.274118e+02 +-1.411964e-01 -9.340572e-02 9.855653e-01 9.584775e+01 -2.241512e-02 9.955854e-01 9.114409e-02 -2.576414e+01 -9.897278e-01 -9.222351e-03 -1.426668e-01 5.272660e+02 +-1.646271e-01 -9.490025e-02 9.817799e-01 9.689231e+01 -2.264899e-02 9.954620e-01 9.242496e-02 -2.569147e+01 -9.860958e-01 -7.020670e-03 -1.660294e-01 5.270839e+02 +-1.870493e-01 -9.386705e-02 9.778556e-01 9.793530e+01 -1.988224e-02 9.955821e-01 9.176551e-02 -2.561970e+01 -9.821493e-01 -2.277289e-03 -1.880892e-01 5.268865e+02 +-2.077278e-01 -9.029717e-02 9.740100e-01 9.897594e+01 -1.942100e-02 9.959147e-01 8.818596e-02 -2.554936e+01 -9.779939e-01 -5.975765e-04 -2.086328e-01 5.266691e+02 +-2.280684e-01 -8.903535e-02 9.695656e-01 1.000166e+02 -2.083263e-02 9.960283e-01 8.656503e-02 -2.547932e+01 -9.734222e-01 -4.558584e-04 -2.290174e-01 5.264202e+02 +-2.480697e-01 -8.963567e-02 9.645863e-01 1.010631e+02 -2.237527e-02 9.959746e-01 8.679807e-02 -2.541253e+01 -9.684838e-01 -5.091079e-05 -2.490768e-01 5.261579e+02 +-2.685678e-01 -8.858940e-02 9.591784e-01 1.021114e+02 -2.484742e-02 9.960677e-01 8.503927e-02 -2.534905e+01 -9.629403e-01 -9.943014e-04 -2.697129e-01 5.258619e+02 +-2.892112e-01 -8.466900e-02 9.535135e-01 1.031527e+02 -2.605909e-02 9.964079e-01 8.057389e-02 -2.528497e+01 -9.569106e-01 -1.544829e-03 -2.903787e-01 5.255551e+02 +-3.091210e-01 -8.310820e-02 9.473844e-01 1.041946e+02 -2.998982e-02 9.965307e-01 7.763418e-02 -2.522449e+01 -9.505498e-01 -4.413534e-03 -3.105410e-01 5.252250e+02 +-3.291893e-01 -8.395078e-02 9.405247e-01 1.052323e+02 -3.261181e-02 9.964566e-01 7.752892e-02 -2.516476e+01 -9.437007e-01 -5.150517e-03 -3.307606e-01 5.248601e+02 +-3.487200e-01 -8.590455e-02 9.332817e-01 1.062708e+02 -3.522791e-02 9.962882e-01 7.854117e-02 -2.510817e+01 -9.365647e-01 -5.488686e-03 -3.504519e-01 5.244816e+02 +-3.676567e-01 -8.642687e-02 9.259368e-01 1.073057e+02 -3.657162e-02 9.962456e-01 7.846820e-02 -2.504722e+01 -9.292422e-01 -5.013656e-03 -3.694371e-01 5.240790e+02 +-3.846432e-01 -8.716496e-02 9.189406e-01 1.083359e+02 -3.793609e-02 9.961831e-01 7.861272e-02 -2.498332e+01 -9.222855e-01 -4.623167e-03 -3.864817e-01 5.236486e+02 +-3.991250e-01 -8.824243e-02 9.126404e-01 1.093625e+02 -3.680303e-02 9.960978e-01 8.021680e-02 -2.491895e+01 -9.161577e-01 -1.571398e-03 -4.008151e-01 5.232035e+02 +-4.103575e-01 -8.708652e-02 9.077569e-01 1.103854e+02 -3.500615e-02 9.962003e-01 7.974668e-02 -2.485501e+01 -9.112526e-01 9.475732e-04 -4.118469e-01 5.227436e+02 +-4.193078e-01 -8.320064e-02 9.040236e-01 1.114089e+02 -3.122122e-02 9.965241e-01 7.723267e-02 -2.479060e+01 -9.073072e-01 4.159537e-03 -4.204479e-01 5.222678e+02 +-4.258893e-01 -8.037774e-02 9.011979e-01 1.124335e+02 -2.575049e-02 9.967194e-01 7.672811e-02 -2.472596e+01 -9.044088e-01 9.471387e-03 -4.265619e-01 5.217800e+02 +-4.307874e-01 -7.986931e-02 8.989122e-01 1.134596e+02 -2.118111e-02 9.966964e-01 7.840689e-02 -2.466148e+01 -9.022049e-01 1.473673e-02 -4.310559e-01 5.212823e+02 +-4.342414e-01 -7.932662e-02 8.972968e-01 1.144887e+02 -1.664233e-02 9.966514e-01 8.005623e-02 -2.459501e+01 -9.006428e-01 1.983062e-02 -4.341075e-01 5.207805e+02 +-4.362918e-01 -7.958427e-02 8.962789e-01 1.155241e+02 -1.372691e-02 9.965537e-01 8.180610e-02 -2.452533e+01 -8.997006e-01 2.338819e-02 -4.358806e-01 5.202755e+02 +-4.375893e-01 -8.093872e-02 8.955247e-01 1.165671e+02 -1.317836e-02 9.964108e-01 8.361747e-02 -2.445513e+01 -8.990784e-01 2.478856e-02 -4.370853e-01 5.197695e+02 +-4.385947e-01 -8.308275e-02 8.948363e-01 1.176188e+02 -1.413980e-02 9.962321e-01 8.556658e-02 -2.438187e+01 -8.985738e-01 2.487623e-02 -4.381169e-01 5.192618e+02 +-4.395435e-01 -8.685190e-02 8.940124e-01 1.186731e+02 -1.610584e-02 9.959163e-01 8.883323e-02 -2.430554e+01 -8.980769e-01 2.464725e-02 -4.391474e-01 5.187529e+02 +-4.408842e-01 -9.038989e-02 8.930010e-01 1.197393e+02 -1.696852e-02 9.955778e-01 9.239523e-02 -2.422602e+01 -8.974036e-01 2.558269e-02 -4.404683e-01 5.182372e+02 +-4.420270e-01 -9.062806e-02 8.924117e-01 1.207926e+02 -1.641747e-02 9.955336e-01 9.296868e-02 -2.414628e+01 -8.968515e-01 2.644352e-02 -4.415407e-01 5.177198e+02 +-4.428963e-01 -8.843444e-02 8.922008e-01 1.218562e+02 -1.627703e-02 9.957526e-01 9.061839e-02 -2.406527e+01 -8.964251e-01 2.561216e-02 -4.424546e-01 5.171981e+02 +-4.438597e-01 -8.568579e-02 8.919902e-01 1.229823e+02 -1.395791e-02 9.959581e-01 8.872757e-02 -2.398083e+01 -8.959876e-01 2.693227e-02 -4.432617e-01 5.166406e+02 +-4.447736e-01 -8.448679e-02 8.916493e-01 1.239987e+02 -1.266765e-02 9.960347e-01 8.805878e-02 -2.390695e+01 -8.955535e-01 2.787111e-02 -4.440802e-01 5.161368e+02 +-4.459469e-01 -8.369968e-02 8.911373e-01 1.250778e+02 -1.184675e-02 9.960828e-01 8.762825e-02 -2.383069e+01 -8.949810e-01 2.852046e-02 -4.451916e-01 5.156010e+02 +-4.470843e-01 -8.490296e-02 8.904533e-01 1.261655e+02 -1.209683e-02 9.959680e-01 8.888994e-02 -2.375369e+01 -8.944101e-01 2.896962e-02 -4.463087e-01 5.150610e+02 +-4.480506e-01 -8.798346e-02 8.896682e-01 1.272602e+02 -1.290603e-02 9.956783e-01 9.196763e-02 -2.367277e+01 -8.939150e-01 2.972406e-02 -4.472499e-01 5.145161e+02 +-4.492735e-01 -9.048296e-02 8.888004e-01 1.283584e+02 -1.369602e-02 9.954386e-01 9.441601e-02 -2.358790e+01 -8.932893e-01 3.024558e-02 -4.484635e-01 5.139694e+02 +-4.504091e-01 -9.179255e-02 8.880911e-01 1.294592e+02 -1.401456e-02 9.953051e-01 9.576644e-02 -2.350028e+01 -8.927123e-01 3.068786e-02 -4.495809e-01 5.134194e+02 +-4.514146e-01 -9.210661e-02 8.875478e-01 1.305636e+02 -1.361780e-02 9.952536e-01 9.635782e-02 -2.341113e+01 -8.922104e-01 3.141087e-02 -4.505263e-01 5.128629e+02 +-4.521937e-01 -9.225802e-02 8.871354e-01 1.316737e+02 -1.376439e-02 9.952393e-01 9.648431e-02 -2.332100e+01 -8.918136e-01 3.141871e-02 -4.513108e-01 5.123036e+02 +-4.530762e-01 -8.985149e-02 8.869321e-01 1.327854e+02 -1.164632e-02 9.954194e-01 9.489255e-02 -2.323155e+01 -8.913957e-01 3.266406e-02 -4.520473e-01 5.117395e+02 +-4.536387e-01 -8.599849e-02 8.870266e-01 1.339003e+02 -8.358275e-03 9.956998e-01 9.225998e-02 -2.314183e+01 -8.911465e-01 3.443868e-02 -4.524068e-01 5.111717e+02 +-4.534274e-01 -8.747177e-02 8.869906e-01 1.350274e+02 -9.491492e-03 9.955900e-01 9.332944e-02 -2.305305e+01 -8.912427e-01 3.389926e-02 -4.522581e-01 5.106026e+02 +-4.529675e-01 -9.011387e-02 8.869611e-01 1.361645e+02 -9.575890e-03 9.953129e-01 9.623189e-02 -2.296281e+01 -8.914756e-01 3.509647e-02 -4.517073e-01 5.100303e+02 +-4.527682e-01 -9.071574e-02 8.870014e-01 1.373043e+02 -1.239456e-02 9.953551e-01 9.547056e-02 -2.287414e+01 -8.915421e-01 3.223204e-02 -4.517895e-01 5.094620e+02 +-4.529642e-01 -8.781174e-02 8.871936e-01 1.384492e+02 -1.245647e-02 9.956637e-01 9.218804e-02 -2.278217e+01 -8.914417e-01 3.070658e-02 -4.520938e-01 5.088889e+02 +-4.523222e-01 -8.406768e-02 8.878836e-01 1.396002e+02 -1.237871e-02 9.960433e-01 8.800241e-02 -2.269558e+01 -8.917687e-01 2.881458e-02 -4.515732e-01 5.083114e+02 +-4.523545e-01 -8.062724e-02 8.881862e-01 1.407566e+02 -1.089979e-02 9.963304e-01 8.489303e-02 -2.261062e+01 -8.917717e-01 2.872069e-02 -4.515733e-01 5.077301e+02 +-4.525935e-01 -8.294462e-02 8.878509e-01 1.419268e+02 -9.636845e-03 9.960613e-01 8.814134e-02 -2.252507e+01 -8.916649e-01 3.133611e-02 -4.516102e-01 5.071428e+02 +-4.529942e-01 -8.592360e-02 8.873631e-01 1.431097e+02 -1.016747e-02 9.957778e-01 9.123100e-02 -2.243970e+01 -8.914555e-01 3.230487e-02 -4.519553e-01 5.065487e+02 +-4.532546e-01 -8.640721e-02 8.871832e-01 1.442912e+02 -9.824858e-03 9.957144e-01 9.195818e-02 -2.234865e+01 -8.913270e-01 3.296401e-02 -4.521611e-01 5.059553e+02 +-4.534149e-01 -8.569675e-02 8.871702e-01 1.454780e+02 -1.112713e-02 9.958337e-01 9.050632e-02 -2.225641e+01 -8.912301e-01 3.116525e-02 -4.524794e-01 5.053604e+02 +-4.536655e-01 -8.626893e-02 8.869866e-01 1.466725e+02 -1.266516e-02 9.958271e-01 9.037702e-02 -2.216569e+01 -8.910821e-01 2.976710e-02 -4.528650e-01 5.047613e+02 +-4.538993e-01 -8.758229e-02 8.867382e-01 1.478734e+02 -1.336238e-02 9.957148e-01 9.150595e-02 -2.207507e+01 -8.909528e-01 2.968555e-02 -4.531246e-01 5.041583e+02 +-4.542406e-01 -8.795357e-02 8.865267e-01 1.490829e+02 -1.323429e-02 9.956709e-01 9.200092e-02 -2.198248e+01 -8.907808e-01 3.005799e-02 -4.534382e-01 5.035505e+02 +-4.545314e-01 -8.653856e-02 8.865169e-01 1.502950e+02 -1.183661e-02 9.957682e-01 9.113447e-02 -2.188966e+01 -8.906521e-01 3.093012e-02 -4.536322e-01 5.029378e+02 +-4.548794e-01 -8.566704e-02 8.864231e-01 1.515134e+02 -1.149839e-02 9.958445e-01 9.034138e-02 -2.179762e+01 -8.904788e-01 3.090199e-02 -4.539742e-01 5.023224e+02 +-4.554055e-01 -8.503055e-02 8.862142e-01 1.527381e+02 -1.121760e-02 9.958975e-01 8.979000e-02 -2.170561e+01 -8.902135e-01 3.094966e-02 -4.544911e-01 5.017039e+02 +-4.557207e-01 -8.618213e-02 8.859409e-01 1.539671e+02 -1.066391e-02 9.957590e-01 9.137955e-02 -2.161081e+01 -8.900590e-01 3.219595e-02 -4.547070e-01 5.010819e+02 +-4.559623e-01 -8.784141e-02 8.856536e-01 1.552051e+02 -1.157973e-02 9.956187e-01 9.278643e-02 -2.151361e+01 -8.899238e-01 3.205147e-02 -4.549817e-01 5.004592e+02 +-4.562508e-01 -8.799622e-02 8.854896e-01 1.564480e+02 -1.378932e-02 9.956781e-01 9.184132e-02 -2.141661e+01 -8.897444e-01 2.969236e-02 -4.554923e-01 4.998347e+02 +-4.563689e-01 -8.827588e-02 8.854009e-01 1.576962e+02 -1.879120e-02 9.958008e-01 8.959725e-02 -2.131784e+01 -8.895923e-01 2.425164e-02 -4.561113e-01 4.992141e+02 +-4.567376e-01 -9.035439e-02 8.850010e-01 1.589485e+02 -2.340102e-02 9.957047e-01 8.957976e-02 -2.122163e+01 -8.892937e-01 2.020451e-02 -4.568901e-01 4.985909e+02 +-4.568450e-01 -9.305632e-02 8.846656e-01 1.602015e+02 -2.754394e-02 9.955161e-01 9.049270e-02 -2.112500e+01 -8.891198e-01 1.697395e-02 -4.573597e-01 4.979678e+02 +-4.570335e-01 -9.215515e-02 8.846625e-01 1.614577e+02 -2.731148e-02 9.956031e-01 8.960220e-02 -2.102669e+01 -8.890301e-01 1.678976e-02 -4.575409e-01 4.973338e+02 +-4.568558e-01 -9.056195e-02 8.849188e-01 1.627095e+02 -2.443070e-02 9.957062e-01 8.928707e-02 -2.092957e+01 -8.892053e-01 1.917212e-02 -4.571066e-01 4.966974e+02 +-4.567382e-01 -8.829710e-02 8.852083e-01 1.639639e+02 -1.961257e-02 9.958196e-01 8.921085e-02 -2.083478e+01 -8.893850e-01 2.338479e-02 -4.565606e-01 4.960560e+02 +-4.564451e-01 -8.732959e-02 8.854554e-01 1.652167e+02 -1.594528e-02 9.958146e-01 8.999431e-02 -2.074087e+01 -8.896087e-01 2.695862e-02 -4.559272e-01 4.954166e+02 +-4.564550e-01 -8.828777e-02 8.853553e-01 1.664725e+02 -1.392613e-02 9.956517e-01 9.210678e-02 -2.064426e+01 -8.896375e-01 2.971302e-02 -4.556997e-01 4.947775e+02 +-4.562886e-01 -8.992426e-02 8.852764e-01 1.677294e+02 -1.498239e-02 9.955159e-01 9.339993e-02 -2.054888e+01 -8.897057e-01 2.935376e-02 -4.555899e-01 4.941397e+02 +-4.561580e-01 -9.024954e-02 8.853106e-01 1.689848e+02 -1.534102e-02 9.954938e-01 9.357726e-02 -2.045392e+01 -8.897666e-01 2.910445e-02 -4.554870e-01 4.935010e+02 +-4.557699e-01 -9.139493e-02 8.853930e-01 1.702407e+02 -1.722435e-02 9.954338e-01 9.388743e-02 -2.035761e+01 -8.899310e-01 2.754073e-02 -4.552629e-01 4.928660e+02 +-4.561880e-01 -8.817518e-02 8.855042e-01 1.714922e+02 -1.488854e-02 9.956958e-01 9.147749e-02 -2.026448e+01 -8.897589e-01 2.854705e-02 -4.555373e-01 4.922268e+02 +-4.560773e-01 -8.622305e-02 8.857534e-01 1.727464e+02 -1.204836e-02 9.958024e-01 9.073197e-02 -2.016956e+01 -8.898586e-01 3.070891e-02 -4.552017e-01 4.915867e+02 +-4.552664e-01 -8.379582e-02 8.864033e-01 1.740021e+02 -8.907621e-03 9.959401e-01 8.957581e-02 -2.007505e+01 -8.903107e-01 3.288510e-02 -4.541645e-01 4.909488e+02 +-4.541920e-01 -8.107110e-02 8.872075e-01 1.752552e+02 -7.031312e-03 9.961462e-01 8.742613e-02 -1.998350e+01 -8.908761e-01 3.347001e-02 -4.530117e-01 4.903149e+02 +-4.530650e-01 -8.777998e-02 8.871453e-01 1.765180e+02 -1.236037e-02 9.956633e-01 9.220504e-02 -1.989030e+01 -8.913918e-01 3.080943e-02 -4.521852e-01 4.896888e+02 +-4.520410e-01 -9.494281e-02 8.869300e-01 1.777846e+02 -1.538593e-02 9.950013e-01 9.866975e-02 -1.979189e+01 -8.918645e-01 3.095652e-02 -4.512422e-01 4.890623e+02 +-4.499895e-01 -9.572069e-02 8.878890e-01 1.790424e+02 -1.978187e-02 9.950634e-01 9.724925e-02 -1.968856e+01 -8.928147e-01 2.619703e-02 -4.496616e-01 4.884414e+02 +-4.482039e-01 -9.220087e-02 8.891638e-01 1.802952e+02 -1.810940e-02 9.953991e-01 9.408837e-02 -1.958514e+01 -8.937479e-01 2.606855e-02 -4.478115e-01 4.878199e+02 +-4.457296e-01 -9.134271e-02 8.904951e-01 1.815442e+02 -1.886010e-02 9.955177e-01 9.267518e-02 -1.949063e+01 -8.949690e-01 2.451324e-02 -4.454545e-01 4.871991e+02 +-4.441642e-01 -8.914138e-02 8.914999e-01 1.827910e+02 -1.873050e-02 9.957445e-01 9.023292e-02 -1.940045e+01 -8.957496e-01 2.337998e-02 -4.439437e-01 4.865821e+02 +-4.430596e-01 -8.830413e-02 8.921326e-01 1.840367e+02 -1.968810e-02 9.958555e-01 8.879304e-02 -1.931218e+01 -8.962760e-01 2.177620e-02 -4.429618e-01 4.859705e+02 +-4.425039e-01 -9.053581e-02 8.921847e-01 1.852871e+02 -2.083805e-02 9.956601e-01 9.070094e-02 -1.922132e+01 -8.965245e-01 2.154413e-02 -4.424701e-01 4.853579e+02 +-4.418096e-01 -9.318258e-02 8.922563e-01 1.865353e+02 -2.127830e-02 9.953995e-01 9.341818e-02 -1.912833e+01 -8.968565e-01 2.228735e-02 -4.417598e-01 4.847464e+02 +-4.416992e-01 -9.236737e-02 8.923957e-01 1.877792e+02 -2.073300e-02 9.954713e-01 9.277424e-02 -1.903249e+01 -8.969237e-01 2.247626e-02 -4.416139e-01 4.841357e+02 +-4.420910e-01 -9.209085e-02 8.922302e-01 1.890229e+02 -2.210162e-02 9.955320e-01 9.180195e-02 -1.893513e+01 -8.966979e-01 2.086508e-02 -4.421511e-01 4.835291e+02 +-4.434980e-01 -9.006465e-02 8.917386e-01 1.902601e+02 -2.119886e-02 9.957140e-01 9.002301e-02 -1.883965e+01 -8.960246e-01 2.102118e-02 -4.435065e-01 4.829202e+02 +-4.451501e-01 -8.705848e-02 8.912139e-01 1.915002e+02 -1.972059e-02 9.959744e-01 8.744187e-02 -1.874797e+01 -8.952388e-01 2.134949e-02 -4.450749e-01 4.823065e+02 +-4.470440e-01 -8.572466e-02 8.903948e-01 1.927302e+02 -1.736391e-02 9.960414e-01 8.717805e-02 -1.865898e+01 -8.943435e-01 2.351168e-02 -4.467629e-01 4.816950e+02 +-4.494748e-01 -8.584229e-02 8.891589e-01 1.939589e+02 -1.596185e-02 9.959849e-01 8.808684e-02 -1.857151e+01 -8.931504e-01 2.540019e-02 -4.490403e-01 4.810822e+02 +-4.524240e-01 -8.694940e-02 8.875541e-01 1.951802e+02 -1.492737e-02 9.958346e-01 8.994801e-02 -1.848166e+01 -8.916780e-01 2.744578e-02 -4.518374e-01 4.804696e+02 +-4.553565e-01 -8.950864e-02 8.857983e-01 1.963987e+02 -1.677654e-02 9.956193e-01 9.198171e-02 -1.838982e+01 -8.901512e-01 2.702383e-02 -4.548634e-01 4.798577e+02 +-4.585754e-01 -9.004093e-02 8.840821e-01 1.976125e+02 -1.576788e-02 9.955214e-01 9.321184e-02 -1.829661e+01 -8.885156e-01 2.880455e-02 -4.579414e-01 4.792386e+02 +-4.611944e-01 -8.857982e-02 8.828665e-01 1.988153e+02 -1.505300e-02 9.956423e-01 9.203143e-02 -1.820177e+01 -8.871714e-01 2.915458e-02 -4.605181e-01 4.786213e+02 +-4.640859e-01 -8.476972e-02 8.817247e-01 2.000113e+02 -1.158575e-02 9.959060e-01 8.964919e-02 -1.811021e+01 -8.857145e-01 3.138947e-02 -4.631680e-01 4.779980e+02 +-4.669199e-01 -8.222544e-02 8.804685e-01 2.012039e+02 -1.081344e-02 9.961241e-01 8.729187e-02 -1.802120e+01 -8.842335e-01 3.123741e-02 -4.659993e-01 4.773755e+02 +-4.698551e-01 -8.296144e-02 8.788365e-01 2.023936e+02 -1.254921e-02 9.961011e-01 8.732192e-02 -1.793582e+01 -8.826544e-01 2.999995e-02 -4.690643e-01 4.767531e+02 +-4.724427e-01 -8.499653e-02 8.772534e-01 2.035745e+02 -1.411093e-02 9.959409e-01 8.889669e-02 -1.784839e+01 -8.812485e-01 2.961972e-02 -4.717244e-01 4.761272e+02 +-4.749657e-01 -8.804948e-02 8.755883e-01 2.047495e+02 -1.723816e-02 9.957218e-01 9.077927e-02 -1.776134e+01 -8.798355e-01 2.802350e-02 -4.744516e-01 4.755031e+02 +-4.775804e-01 -9.023732e-02 8.739417e-01 2.059120e+02 -1.987224e-02 9.955666e-01 9.193598e-02 -1.767386e+01 -8.783633e-01 2.653964e-02 -4.772563e-01 4.748804e+02 +-4.798595e-01 -9.105277e-02 8.726077e-01 2.070547e+02 -2.115761e-02 9.955118e-01 9.224241e-02 -1.758872e+01 -8.770903e-01 2.580110e-02 -4.796322e-01 4.742634e+02 +-4.818327e-01 -9.241398e-02 8.713764e-01 2.081847e+02 -2.206235e-02 9.953873e-01 9.336648e-02 -1.750379e+01 -8.759855e-01 2.576241e-02 -4.816491e-01 4.736495e+02 +-4.835119e-01 -9.462118e-02 8.702086e-01 2.092965e+02 -2.226053e-02 9.951480e-01 9.583778e-02 -1.741982e+01 -8.750547e-01 2.696739e-02 -4.832722e-01 4.730410e+02 +-4.850726e-01 -9.526025e-02 8.692698e-01 2.103879e+02 -2.391193e-02 9.951221e-01 9.570857e-02 -1.733782e+01 -8.741469e-01 2.563968e-02 -4.849844e-01 4.724427e+02 +-4.866868e-01 -9.564761e-02 8.683245e-01 2.114603e+02 -2.608225e-02 9.951358e-01 9.499730e-02 -1.725655e+01 -8.731871e-01 2.358607e-02 -4.868142e-01 4.718533e+02 +-4.877399e-01 -9.630173e-02 8.676611e-01 2.125154e+02 -2.956018e-02 9.951488e-01 9.383490e-02 -1.717684e+01 -8.724884e-01 2.011880e-02 -4.882205e-01 4.712747e+02 +-4.880635e-01 -9.749874e-02 8.673454e-01 2.135570e+02 -3.197477e-02 9.950714e-01 9.386400e-02 -1.709841e+01 -8.722223e-01 1.807841e-02 -4.887755e-01 4.707007e+02 +-4.877778e-01 -9.900817e-02 8.673351e-01 2.145775e+02 -3.367240e-02 9.949421e-01 9.463788e-02 -1.702312e+01 -8.723182e-01 1.695699e-02 -4.886445e-01 4.701384e+02 +-4.862887e-01 -9.968996e-02 8.680929e-01 2.155806e+02 -3.505880e-02 9.948966e-01 9.461260e-02 -1.694907e+01 -8.730946e-01 1.557474e-02 -4.873020e-01 4.695866e+02 +-4.834250e-01 -9.968812e-02 8.696911e-01 2.165643e+02 -3.570624e-02 9.949133e-01 9.419410e-02 -1.687651e+01 -8.746573e-01 1.448238e-02 -4.845254e-01 4.690499e+02 +-4.788572e-01 -9.980611e-02 8.722009e-01 2.175320e+02 -3.640586e-02 9.949194e-01 9.386121e-02 -1.680430e+01 -8.771376e-01 1.319289e-02 -4.800579e-01 4.685258e+02 +-4.719956e-01 -1.001877e-01 8.758896e-01 2.184892e+02 -3.636751e-02 9.948886e-01 9.420173e-02 -1.673272e+01 -8.808505e-01 1.260887e-02 -4.732266e-01 4.680190e+02 +-4.628713e-01 -1.000878e-01 8.807568e-01 2.194374e+02 -3.568875e-02 9.949036e-01 9.430348e-02 -1.666257e+01 -8.857068e-01 1.221726e-02 -4.640844e-01 4.675300e+02 +-4.510550e-01 -1.000988e-01 8.868651e-01 2.203833e+02 -3.486132e-02 9.949083e-01 9.456317e-02 -1.659176e+01 -8.918151e-01 1.173590e-02 -4.522479e-01 4.670521e+02 +-4.371933e-01 -9.911107e-02 8.938898e-01 2.213283e+02 -3.360667e-02 9.950155e-01 9.388680e-02 -1.652190e+01 -8.987395e-01 1.100602e-02 -4.383449e-01 4.665992e+02 +-4.219347e-01 -9.747969e-02 9.013705e-01 2.222667e+02 -3.257890e-02 9.951911e-01 9.237574e-02 -1.645181e+01 -9.060407e-01 9.610863e-03 -4.230814e-01 4.661579e+02 +-4.053796e-01 -9.819255e-02 9.088595e-01 2.232143e+02 -3.674134e-02 9.951611e-01 9.112875e-02 -1.638216e+01 -9.134098e-01 3.549015e-03 -4.070257e-01 4.657518e+02 +-3.885634e-01 -9.774017e-02 9.162234e-01 2.241568e+02 -4.018480e-02 9.952095e-01 8.912414e-02 -1.631656e+01 -9.205454e-01 -2.187878e-03 -3.906297e-01 4.653685e+02 +-3.716948e-01 -9.456823e-02 9.235257e-01 2.250949e+02 -3.860796e-02 9.955121e-01 8.640090e-02 -1.625136e+01 -9.275519e-01 -3.540677e-03 -3.736778e-01 4.649901e+02 +-3.530686e-01 -9.331444e-02 9.309323e-01 2.260385e+02 -4.100678e-02 9.956010e-01 8.424431e-02 -1.618780e+01 -9.346984e-01 -8.430513e-03 -3.553420e-01 4.646450e+02 +-3.342510e-01 -9.374803e-02 9.378100e-01 2.269918e+02 -4.019029e-02 9.955533e-01 8.519587e-02 -1.612171e+01 -9.416268e-01 -9.214052e-03 -3.365325e-01 4.643162e+02 +-3.144265e-01 -9.423406e-02 9.445930e-01 2.279467e+02 -4.032401e-02 9.954883e-01 8.588884e-02 -1.605768e+01 -9.484250e-01 -1.108405e-02 -3.168078e-01 4.639940e+02 +-2.950900e-01 -9.669133e-02 9.505644e-01 2.289161e+02 -4.003930e-02 9.952438e-01 8.880647e-02 -1.598694e+01 -9.546302e-01 -1.185402e-02 -2.975580e-01 4.637049e+02 +-2.750606e-01 -1.004158e-01 9.561685e-01 2.298835e+02 -4.261740e-02 9.948266e-01 9.221595e-02 -1.591882e+01 -9.604819e-01 -1.538443e-02 -2.779171e-01 4.634247e+02 +-2.549025e-01 -1.040685e-01 9.613503e-01 2.308615e+02 -4.316720e-02 9.944252e-01 9.620315e-02 -1.584521e+01 -9.660028e-01 -1.697638e-02 -2.579738e-01 4.631732e+02 +-2.345433e-01 -1.060698e-01 9.663015e-01 2.318455e+02 -4.676097e-02 9.941096e-01 9.777232e-02 -1.576834e+01 -9.709804e-01 -2.225335e-02 -2.381217e-01 4.629466e+02 +-2.145591e-01 -1.072767e-01 9.708018e-01 2.328208e+02 -4.995258e-02 9.938543e-01 9.878402e-02 -1.568945e+01 -9.754328e-01 -2.729904e-02 -2.185992e-01 4.627313e+02 +-1.941175e-01 -1.070115e-01 9.751240e-01 2.338021e+02 -5.279848e-02 9.937311e-01 9.854296e-02 -1.561062e+01 -9.795564e-01 -3.235615e-02 -1.985507e-01 4.625511e+02 +-1.734365e-01 -1.072151e-01 9.789917e-01 2.347905e+02 -5.452316e-02 9.935773e-01 9.915329e-02 -1.553122e+01 -9.833347e-01 -3.618091e-02 -1.781682e-01 4.623968e+02 +-1.518582e-01 -1.073436e-01 9.825561e-01 2.357801e+02 -5.282907e-02 9.935457e-01 1.003793e-01 -1.545256e+01 -9.869895e-01 -3.666410e-02 -1.565489e-01 4.622433e+02 +-1.281726e-01 -1.055786e-01 9.861161e-01 2.367819e+02 -5.100908e-02 9.937031e-01 9.976088e-02 -1.537374e+01 -9.904393e-01 -3.751426e-02 -1.327510e-01 4.621270e+02 +-1.034287e-01 -1.002976e-01 9.895670e-01 2.377754e+02 -4.525883e-02 9.943469e-01 9.605164e-02 -1.529603e+01 -9.936067e-01 -3.485215e-02 -1.073834e-01 4.620136e+02 +-7.722034e-02 -9.538017e-02 9.924412e-01 2.387822e+02 -4.004302e-02 9.949070e-01 9.250148e-02 -1.522098e+01 -9.962096e-01 -3.259735e-02 -8.064637e-02 4.619458e+02 +-5.014585e-02 -9.263785e-02 9.944363e-01 2.398015e+02 -3.554678e-02 9.952237e-01 9.091872e-02 -1.514871e+01 -9.981092e-01 -3.078981e-02 -5.319932e-02 4.619088e+02 +-2.224507e-02 -9.198728e-02 9.955117e-01 2.408171e+02 -3.276631e-02 9.952902e-01 9.123466e-02 -1.507971e+01 -9.992155e-01 -3.058972e-02 -2.515439e-02 4.618821e+02 +6.126216e-03 -9.185568e-02 9.957535e-01 2.418484e+02 -3.182340e-02 9.952499e-01 9.200503e-02 -1.500872e+01 -9.994748e-01 -3.225190e-02 3.173954e-03 4.619056e+02 +3.513718e-02 -9.168354e-02 9.951681e-01 2.428871e+02 -3.089063e-02 9.952075e-01 9.277787e-02 -1.493785e+01 -9.989050e-01 -3.400132e-02 3.213663e-02 4.619587e+02 +6.504958e-02 -9.191732e-02 9.936396e-01 2.439215e+02 -3.117396e-02 9.950754e-01 9.409099e-02 -1.486791e+01 -9.973950e-01 -3.709625e-02 6.186381e-02 4.620253e+02 +9.531524e-02 -9.335646e-02 9.910598e-01 2.449679e+02 -3.425417e-02 9.946954e-01 9.699334e-02 -1.479224e+01 -9.948576e-01 -4.319287e-02 9.161178e-02 4.621475e+02 +1.251569e-01 -9.393295e-02 9.876803e-01 2.460147e+02 -3.604164e-02 9.944204e-01 9.914111e-02 -1.471717e+01 -9.914821e-01 -4.800580e-02 1.210731e-01 4.623013e+02 +1.550714e-01 -9.142968e-02 9.836633e-01 2.470455e+02 -4.105518e-02 9.942515e-01 9.888607e-02 -1.463499e+01 -9.870498e-01 -5.571887e-02 1.504263e-01 4.624662e+02 +1.836938e-01 -8.693272e-02 9.791319e-01 2.480862e+02 -4.345696e-02 9.943896e-01 9.644031e-02 -1.455321e+01 -9.820225e-01 -6.026557e-02 1.788854e-01 4.626823e+02 +2.118045e-01 -8.427786e-02 9.736714e-01 2.491163e+02 -4.514676e-02 9.943675e-01 9.589011e-02 -1.447276e+01 -9.762688e-01 -6.426806e-02 2.068066e-01 4.629047e+02 +2.397331e-01 -8.036845e-02 9.675066e-01 2.501535e+02 -4.687700e-02 9.944470e-01 9.422173e-02 -1.439499e+01 -9.697065e-01 -6.794186e-02 2.346344e-01 4.631846e+02 +2.675314e-01 -7.714103e-02 9.604562e-01 2.511869e+02 -4.849510e-02 9.944488e-01 9.337935e-02 -1.431785e+01 -9.623280e-01 -7.155932e-02 2.623053e-01 4.634958e+02 +2.951027e-01 -7.736564e-02 9.523282e-01 2.522181e+02 -4.819419e-02 9.942423e-01 9.570487e-02 -1.424214e+01 -9.542493e-01 -7.413943e-02 2.896750e-01 4.638149e+02 +3.225516e-01 -7.922375e-02 9.432306e-01 2.532511e+02 -4.776848e-02 9.938591e-01 9.981128e-02 -1.415996e+01 -9.453458e-01 -7.725097e-02 3.167865e-01 4.641837e+02 +3.495485e-01 -8.009105e-02 9.334888e-01 2.542780e+02 -4.500131e-02 9.937544e-01 1.021126e-01 -1.407993e+01 -9.358370e-01 -7.770152e-02 3.437611e-01 4.645801e+02 +3.770197e-01 -7.498827e-02 9.231646e-01 2.552844e+02 -4.697161e-02 9.938865e-01 9.991617e-02 -1.399854e+01 -9.250134e-01 -8.103288e-02 3.711925e-01 4.649924e+02 +4.025807e-01 -7.244542e-02 9.125133e-01 2.562915e+02 -4.128007e-02 9.944124e-01 9.715935e-02 -1.391361e+01 -9.144533e-01 -7.678307e-02 3.973407e-01 4.654443e+02 +4.276512e-01 -7.080429e-02 9.011666e-01 2.572879e+02 -4.156376e-02 9.943330e-01 9.784855e-02 -1.383281e+01 -9.029878e-01 -7.930091e-02 4.222848e-01 4.659152e+02 +4.512259e-01 -7.062396e-02 8.896108e-01 2.582838e+02 -4.343542e-02 9.939441e-01 1.009379e-01 -1.375046e+01 -8.913521e-01 -8.418642e-02 4.454258e-01 4.664310e+02 +4.742316e-01 -7.324883e-02 8.773477e-01 2.592720e+02 -4.300484e-02 9.934160e-01 1.061846e-01 -1.366058e+01 -8.793492e-01 -8.808629e-02 4.679593e-01 4.669735e+02 +4.962536e-01 -7.744958e-02 8.647161e-01 2.602420e+02 -3.923481e-02 9.929946e-01 1.114556e-01 -1.356759e+01 -8.672906e-01 -8.923720e-02 4.897385e-01 4.675231e+02 +5.175980e-01 -7.808586e-02 8.520533e-01 2.612129e+02 -3.765901e-02 9.927828e-01 1.138597e-01 -1.346845e+01 -8.547948e-01 -9.102104e-02 5.109218e-01 4.681150e+02 +5.380325e-01 -7.634260e-02 8.394598e-01 2.621670e+02 -3.813270e-02 9.926662e-01 1.147159e-01 -1.336576e+01 -8.420611e-01 -9.373173e-02 5.311756e-01 4.687278e+02 +5.568931e-01 -7.562687e-02 8.271340e-01 2.631069e+02 -3.634735e-02 9.926731e-01 1.152345e-01 -1.326249e+01 -8.297885e-01 -9.423740e-02 5.500640e-01 4.693511e+02 +5.739707e-01 -7.388080e-02 8.155362e-01 2.640386e+02 -3.616953e-02 9.926623e-01 1.153829e-01 -1.315686e+01 -8.180767e-01 -9.572397e-02 5.670869e-01 4.700093e+02 +5.890966e-01 -6.966653e-02 8.050539e-01 2.649501e+02 -4.075530e-02 9.924471e-01 1.157055e-01 -1.304700e+01 -8.070342e-01 -1.009719e-01 5.818080e-01 4.706824e+02 +6.026184e-01 -6.712300e-02 7.952016e-01 2.658661e+02 -4.245699e-02 9.923485e-01 1.159389e-01 -1.293644e+01 -7.968993e-01 -1.036287e-01 5.951576e-01 4.713814e+02 +6.148378e-01 -6.426561e-02 7.860308e-01 2.667707e+02 -4.526581e-02 9.921556e-01 1.165255e-01 -1.282445e+01 -7.873535e-01 -1.072246e-01 6.071057e-01 4.720954e+02 +6.255609e-01 -6.311042e-02 7.776186e-01 2.676648e+02 -4.631343e-02 9.919611e-01 1.177633e-01 -1.270881e+01 -7.787995e-01 -1.096823e-01 6.176092e-01 4.728167e+02 +6.357080e-01 -6.122915e-02 7.694974e-01 2.685593e+02 -4.703050e-02 9.919252e-01 1.177813e-01 -1.259549e+01 -7.704956e-01 -1.110643e-01 6.276952e-01 4.735560e+02 +6.451334e-01 -5.990006e-02 7.617184e-01 2.694451e+02 -4.539984e-02 9.921557e-01 1.164724e-01 -1.248224e+01 -7.627200e-01 -1.097221e-01 6.373533e-01 4.743022e+02 +6.542273e-01 -5.684377e-02 7.541588e-01 2.703268e+02 -4.461716e-02 9.925338e-01 1.135161e-01 -1.237190e+01 -7.549808e-01 -1.079137e-01 6.468065e-01 4.750662e+02 +6.623058e-01 -5.506404e-02 7.472075e-01 2.712044e+02 -4.283555e-02 9.928815e-01 1.111369e-01 -1.226437e+01 -7.480082e-01 -1.056136e-01 6.552325e-01 4.758400e+02 +6.686752e-01 -5.452873e-02 7.415525e-01 2.720801e+02 -4.262897e-02 9.928556e-01 1.114474e-01 -1.216173e+01 -7.423317e-01 -1.061337e-01 6.615734e-01 4.766250e+02 +6.728879e-01 -5.508553e-02 7.376906e-01 2.729566e+02 -4.218770e-02 9.927429e-01 1.126128e-01 -1.206642e+01 -7.385405e-01 -1.068972e-01 6.656808e-01 4.774157e+02 +6.763105e-01 -5.497134e-02 7.345626e-01 2.738199e+02 -4.316853e-02 9.925398e-01 1.140224e-01 -1.196704e+01 -7.353506e-01 -1.088245e-01 6.688921e-01 4.782067e+02 +6.788663e-01 -5.683033e-02 7.320593e-01 2.746794e+02 -4.251230e-02 9.922857e-01 1.164552e-01 -1.186470e+01 -7.330302e-01 -1.101790e-01 6.712134e-01 4.790004e+02 +6.813117e-01 -5.710372e-02 7.297627e-01 2.755328e+02 -4.274169e-02 9.921480e-01 1.175393e-01 -1.176170e+01 -7.307445e-01 -1.112721e-01 6.735213e-01 4.797940e+02 +6.831926e-01 -5.790315e-02 7.279389e-01 2.763851e+02 -4.219380e-02 9.920557e-01 1.185122e-01 -1.165563e+01 -7.290183e-01 -1.116812e-01 6.753220e-01 4.805908e+02 +6.853112e-01 -5.727161e-02 7.259948e-01 2.772328e+02 -4.253017e-02 9.920539e-01 1.184071e-01 -1.154923e+01 -7.270074e-01 -1.120224e-01 6.774299e-01 4.813873e+02 +6.870893e-01 -5.454713e-02 7.245226e-01 2.780737e+02 -4.385957e-02 9.922456e-01 1.162967e-01 -1.144208e+01 -7.252481e-01 -1.116835e-01 6.793689e-01 4.821839e+02 +6.882698e-01 -5.416945e-02 7.234295e-01 2.789155e+02 -4.152740e-02 9.926312e-01 1.138361e-01 -1.133729e+01 -7.242652e-01 -1.083921e-01 6.809486e-01 4.829771e+02 +6.892745e-01 -5.381719e-02 7.224987e-01 2.797479e+02 -3.962310e-02 9.929446e-01 1.117631e-01 -1.123688e+01 -7.234161e-01 -1.056631e-01 6.822790e-01 4.837711e+02 +6.894969e-01 -5.471316e-02 7.222191e-01 2.805737e+02 -3.808424e-02 9.930246e-01 1.115873e-01 -1.113740e+01 -7.232867e-01 -1.044442e-01 6.826037e-01 4.845659e+02 +6.888475e-01 -5.549170e-02 7.227792e-01 2.813909e+02 -3.789806e-02 9.929454e-01 1.123527e-01 -1.104233e+01 -7.239150e-01 -1.047858e-01 6.818849e-01 4.853468e+02 +6.870818e-01 -5.661983e-02 7.243706e-01 2.822015e+02 -3.865866e-02 9.926982e-01 1.142621e-01 -1.094613e+01 -7.255509e-01 -1.065106e-01 6.798760e-01 4.861210e+02 +6.839381e-01 -5.691963e-02 7.273162e-01 2.830065e+02 -4.073181e-02 9.924173e-01 1.159689e-01 -1.085061e+01 -7.284021e-01 -1.089405e-01 6.764336e-01 4.868821e+02 +6.797187e-01 -5.722166e-02 7.312374e-01 2.838095e+02 -4.326497e-02 9.920883e-01 1.178509e-01 -1.075496e+01 -7.321957e-01 -1.117424e-01 6.718654e-01 4.876331e+02 +6.745775e-01 -5.726308e-02 7.359797e-01 2.846001e+02 -4.507016e-02 9.919321e-01 1.184875e-01 -1.065661e+01 -7.368269e-01 -1.130997e-01 6.665543e-01 4.883623e+02 +6.689039e-01 -5.638532e-02 7.412073e-01 2.853834e+02 -4.675885e-02 9.919527e-01 1.176577e-01 -1.056449e+01 -7.418768e-01 -1.133597e-01 6.608846e-01 4.890697e+02 +6.617940e-01 -5.323730e-02 7.477931e-01 2.861655e+02 -4.905327e-02 9.922628e-01 1.140537e-01 -1.047556e+01 -7.480792e-01 -1.121617e-01 6.540621e-01 4.897597e+02 +6.532210e-01 -5.059435e-02 7.554750e-01 2.869345e+02 -5.199178e-02 9.924128e-01 1.114168e-01 -1.038547e+01 -7.553802e-01 -1.120583e-01 6.456344e-01 4.904284e+02 +6.431700e-01 -5.184632e-02 7.639661e-01 2.877098e+02 -4.963424e-02 9.927841e-01 1.091612e-01 -1.030407e+01 -7.641131e-01 -1.081281e-01 6.359556e-01 4.910749e+02 +6.329300e-01 -5.187127e-02 7.724694e-01 2.884793e+02 -4.883177e-02 9.930917e-01 1.066968e-01 -1.022701e+01 -7.726676e-01 -1.052526e-01 6.260246e-01 4.916995e+02 +6.218646e-01 -5.323786e-02 7.813131e-01 2.892397e+02 -4.609908e-02 9.934679e-01 1.043852e-01 -1.015259e+01 -7.817668e-01 -1.009312e-01 6.153484e-01 4.922937e+02 +6.106474e-01 -5.367163e-02 7.900817e-01 2.900002e+02 -4.466331e-02 9.937783e-01 1.020290e-01 -1.008408e+01 -7.906422e-01 -9.759138e-02 6.044509e-01 4.928736e+02 +5.985989e-01 -5.612909e-02 7.990800e-01 2.907534e+02 -4.165276e-02 9.940116e-01 1.010240e-01 -1.001717e+01 -7.999653e-01 -9.375674e-02 5.926763e-01 4.934252e+02 +5.861755e-01 -5.576782e-02 8.082624e-01 2.914972e+02 -3.732151e-02 9.947104e-01 9.569886e-02 -9.957206e+00 -8.093240e-01 -8.626189e-02 5.809936e-01 4.939478e+02 +5.727955e-01 -5.366012e-02 8.179400e-01 2.922322e+02 -3.240679e-02 9.955924e-01 8.800900e-02 -9.901449e+00 -8.190575e-01 -7.691796e-02 5.685319e-01 4.944459e+02 +5.592729e-01 -4.519999e-02 8.277504e-01 2.929439e+02 -2.970955e-02 9.967781e-01 7.450327e-02 -9.856274e+00 -8.284511e-01 -6.625974e-02 5.561282e-01 4.949094e+02 +5.446673e-01 -3.261630e-02 8.380177e-01 2.936522e+02 -3.473996e-02 9.975083e-01 6.140294e-02 -9.817235e+00 -8.379324e-01 -6.255687e-02 5.421771e-01 4.953669e+02 +5.279674e-01 -2.366517e-02 8.489349e-01 2.943461e+02 -3.680968e-02 9.980346e-01 5.071410e-02 -9.779102e+00 -8.484666e-01 -5.802440e-02 5.260586e-01 4.957951e+02 +5.094053e-01 -2.279676e-02 8.602247e-01 2.950500e+02 -3.578667e-02 9.982230e-01 4.764590e-02 -9.747383e+00 -8.597823e-01 -5.505564e-02 5.076843e-01 4.962082e+02 +4.879368e-01 -2.265630e-02 8.725849e-01 2.957561e+02 -4.251496e-02 9.978597e-01 4.968276e-02 -9.728772e+00 -8.718430e-01 -6.133995e-02 4.859293e-01 4.966063e+02 +4.638930e-01 -2.503114e-02 8.855375e-01 2.964480e+02 -4.380984e-02 9.977295e-01 5.115241e-02 -9.708025e+00 -8.848074e-01 -6.252449e-02 4.617431e-01 4.969567e+02 +4.371755e-01 -2.891770e-02 8.989112e-01 2.971576e+02 -4.342298e-02 9.976387e-01 5.321203e-02 -9.687419e+00 -8.983274e-01 -6.229639e-02 4.348875e-01 4.972955e+02 +4.074430e-01 -3.515317e-02 9.125538e-01 2.978504e+02 -4.096065e-02 9.975497e-01 5.671575e-02 -9.667756e+00 -9.123116e-01 -6.048723e-02 4.050048e-01 4.975729e+02 +3.730456e-01 -3.548705e-02 9.271341e-01 2.985559e+02 -3.739072e-02 9.978815e-01 5.323967e-02 -9.648325e+00 -9.270593e-01 -5.452703e-02 3.709284e-01 4.978401e+02 +3.358506e-01 -3.229546e-02 9.413614e-01 2.992753e+02 -3.207492e-02 9.984402e-01 4.569709e-02 -9.634008e+00 -9.413690e-01 -4.554148e-02 3.342909e-01 4.980804e+02 +2.974857e-01 -2.587729e-02 9.543755e-01 2.999726e+02 -2.657433e-02 9.990208e-01 3.537123e-02 -9.625312e+00 -9.543564e-01 -3.588432e-02 2.965068e-01 4.982481e+02 +2.577819e-01 -1.829086e-02 9.660300e-01 3.007031e+02 -2.710912e-02 9.992902e-01 2.615459e-02 -9.616258e+00 -9.658228e-01 -3.293040e-02 2.571031e-01 4.984362e+02 +2.168926e-01 -1.276483e-02 9.761120e-01 3.014093e+02 -2.690604e-02 9.994564e-01 1.904865e-02 -9.612974e+00 -9.758246e-01 -3.039481e-02 2.164312e-01 4.985528e+02 +1.760907e-01 -1.314235e-02 9.842862e-01 3.021578e+02 -2.471269e-02 9.995367e-01 1.776712e-02 -9.612934e+00 -9.840637e-01 -2.745299e-02 1.756844e-01 4.986800e+02 +1.352768e-01 -1.734759e-02 9.906560e-01 3.029123e+02 -2.358746e-02 9.995069e-01 2.072352e-02 -9.616508e+00 -9.905271e-01 -2.617047e-02 1.348009e-01 4.987757e+02 +9.357906e-02 -2.438017e-02 9.953133e-01 3.036385e+02 -2.495862e-02 9.993285e-01 2.682513e-02 -9.614262e+00 -9.952990e-01 -2.735191e-02 9.290773e-02 4.988063e+02 +5.019233e-02 -2.962132e-02 9.983002e-01 3.043832e+02 -2.633240e-02 9.991733e-01 3.097117e-02 -9.609024e+00 -9.983924e-01 -2.784215e-02 4.937084e-02 4.988473e+02 +5.566521e-03 -2.972754e-02 9.995425e-01 3.050947e+02 -2.015380e-02 9.993516e-01 2.983410e-02 -9.599674e+00 -9.997814e-01 -2.031065e-02 4.963787e-03 4.988004e+02 +-3.820643e-02 -3.081664e-02 9.987946e-01 3.058255e+02 -1.776641e-02 9.993873e-01 3.015532e-02 -9.581026e+00 -9.991120e-01 -1.659287e-02 -3.873053e-02 4.987558e+02 +-8.118585e-02 -2.781632e-02 9.963107e-01 3.065495e+02 -1.882866e-02 9.994749e-01 2.637039e-02 -9.570230e+00 -9.965212e-01 -1.661830e-02 -8.166696e-02 4.986880e+02 +-1.222233e-01 -2.479975e-02 9.921927e-01 3.072496e+02 -1.598406e-02 9.996073e-01 2.301608e-02 -9.563955e+00 -9.923739e-01 -1.304617e-02 -1.225717e-01 4.985511e+02 +-1.586051e-01 -2.039937e-02 9.871313e-01 3.079695e+02 -8.231058e-03 9.997791e-01 1.933824e-02 -9.557759e+00 -9.873078e-01 -5.057993e-03 -1.587380e-01 4.984134e+02 +-1.910622e-01 -1.730539e-02 9.814254e-01 3.086652e+02 -3.248899e-03 9.998502e-01 1.699778e-02 -9.547326e+00 -9.815726e-01 5.908006e-05 -1.910898e-01 4.982296e+02 +-2.203165e-01 -1.892417e-02 9.752448e-01 3.093754e+02 -4.142445e-03 9.998209e-01 1.846525e-02 -9.541535e+00 -9.754197e-01 2.829785e-05 -2.203554e-01 4.980587e+02 +-2.455083e-01 -2.212333e-02 9.691420e-01 3.100827e+02 -3.787656e-03 9.997538e-01 2.186262e-02 -9.533965e+00 -9.693871e-01 1.696675e-03 -2.455317e-01 4.978664e+02 +-2.667933e-01 -2.199485e-02 9.635027e-01 3.107757e+02 -1.658514e-03 9.997485e-01 2.236303e-02 -9.520400e+00 -9.637524e-01 4.368321e-03 -2.667627e-01 4.976412e+02 +-2.851523e-01 -2.128406e-02 9.582459e-01 3.114724e+02 1.907203e-03 9.997388e-01 2.277322e-02 -9.507541e+00 -9.584804e-01 8.321402e-03 -2.850372e-01 4.974115e+02 +-3.023302e-01 -2.144682e-02 9.529619e-01 3.121685e+02 2.690432e-03 9.997236e-01 2.335276e-02 -9.490480e+00 -9.531995e-01 9.624121e-03 -3.021889e-01 4.971695e+02 +-3.199639e-01 -2.096659e-02 9.471977e-01 3.128596e+02 5.339174e-03 9.996993e-01 2.393231e-02 -9.469890e+00 -9.474147e-01 1.271472e-02 -3.197557e-01 4.969065e+02 +-3.368511e-01 -2.134365e-02 9.413160e-01 3.135514e+02 6.520088e-03 9.996662e-01 2.499991e-02 -9.450217e+00 -9.415354e-01 1.455871e-02 -3.365995e-01 4.966343e+02 +-3.543837e-01 -2.087567e-02 9.348670e-01 3.142425e+02 9.601989e-03 9.996168e-01 2.596140e-02 -9.434712e+00 -9.350508e-01 1.817687e-02 -3.540474e-01 4.963450e+02 +-3.729657e-01 -2.046942e-02 9.276193e-01 3.149309e+02 1.026086e-02 9.996045e-01 2.618345e-02 -9.416673e+00 -9.277884e-01 1.928369e-02 -3.726081e-01 4.960490e+02 +-3.940922e-01 -2.106340e-02 9.188295e-01 3.156175e+02 8.042266e-03 9.996200e-01 2.636484e-02 -9.401439e+00 -9.190358e-01 1.777964e-02 -3.937731e-01 4.957436e+02 +-4.175677e-01 -2.171283e-02 9.083863e-01 3.162872e+02 6.092618e-03 9.996251e-01 2.669433e-02 -9.389864e+00 -9.086254e-01 1.668114e-02 -4.172789e-01 4.954040e+02 +-4.422048e-01 -2.044178e-02 8.966811e-01 3.169590e+02 4.633914e-03 9.996748e-01 2.507499e-02 -9.386532e+00 -8.969022e-01 1.524342e-02 -4.419663e-01 4.950638e+02 +-4.688260e-01 -1.737176e-02 8.831197e-01 3.175986e+02 6.287588e-03 9.997156e-01 2.300323e-02 -9.378597e+00 -8.832682e-01 1.633720e-02 -4.685834e-01 4.946783e+02 +-4.985645e-01 -1.511851e-02 8.667208e-01 3.182422e+02 5.639423e-03 9.997701e-01 2.068330e-02 -9.364049e+00 -8.668343e-01 1.519976e-02 -4.983646e-01 4.942939e+02 +-5.296889e-01 -1.749648e-02 8.480115e-01 3.188772e+02 3.828857e-03 9.997277e-01 2.301834e-02 -9.353565e+00 -8.481834e-01 1.543947e-02 -5.294777e-01 4.938905e+02 +-5.628100e-01 -1.863778e-02 8.263761e-01 3.194693e+02 5.244960e-03 9.996451e-01 2.611774e-02 -9.344713e+00 -8.265697e-01 1.903363e-02 -5.625125e-01 4.934190e+02 +-5.961021e-01 -1.841639e-02 8.026974e-01 3.200678e+02 8.942118e-03 9.995226e-01 2.957281e-02 -9.337214e+00 -8.028589e-01 2.480622e-02 -5.956528e-01 4.929593e+02 +-6.289618e-01 -1.392540e-02 7.773115e-01 3.206151e+02 1.282683e-02 9.995176e-01 2.828501e-02 -9.329423e+00 -7.773304e-01 2.776063e-02 -6.284798e-01 4.924378e+02 +-6.613693e-01 -1.265352e-02 7.499537e-01 3.211700e+02 1.272578e-02 9.995245e-01 2.808698e-02 -9.318911e+00 -7.499525e-01 2.811961e-02 -6.608938e-01 4.919416e+02 +-6.925526e-01 -1.122036e-02 7.212801e-01 3.216918e+02 1.294717e-02 9.995246e-01 2.798029e-02 -9.305044e+00 -7.212512e-01 2.871635e-02 -6.920781e-01 4.914229e+02 +-7.226164e-01 -8.306048e-03 6.911994e-01 3.221597e+02 1.613540e-02 9.994526e-01 2.887908e-02 -9.290593e+00 -6.910610e-01 3.202126e-02 -7.220868e-01 4.908429e+02 +-7.515649e-01 -6.964726e-03 6.596224e-01 3.226207e+02 1.778212e-02 9.993670e-01 3.081268e-02 -9.270096e+00 -6.594195e-01 3.488720e-02 -7.509653e-01 4.902864e+02 +-7.789429e-01 -5.007138e-03 6.270749e-01 3.230279e+02 2.059616e-02 9.992243e-01 3.356294e-02 -9.252765e+00 -6.267566e-01 3.905894e-02 -7.782356e-01 4.896796e+02 +-8.039144e-01 -2.765514e-03 5.947386e-01 3.234246e+02 2.281870e-02 9.991095e-01 3.549009e-02 -9.235231e+00 -5.943072e-01 4.210215e-02 -8.031354e-01 4.891022e+02 +-8.259922e-01 -1.900216e-04 5.636816e-01 3.237955e+02 2.391955e-02 9.990874e-01 3.538736e-02 -9.221189e+00 -5.631739e-01 4.271268e-02 -8.252338e-01 4.885201e+02 +-8.454713e-01 3.858172e-03 5.340068e-01 3.241280e+02 2.564669e-02 9.991134e-01 3.338681e-02 -9.214534e+00 -5.334046e-01 4.192309e-02 -8.448207e-01 4.879074e+02 +-8.624944e-01 8.861879e-03 5.059891e-01 3.244613e+02 2.815201e-02 9.991386e-01 3.048820e-02 -9.206199e+00 -5.052831e-01 4.054050e-02 -8.620009e-01 4.873102e+02 +-8.773421e-01 1.295951e-02 4.796905e-01 3.247836e+02 3.038066e-02 9.991299e-01 2.857256e-02 -9.202119e+00 -4.789029e-01 3.964121e-02 -8.769724e-01 4.867042e+02 +-8.907171e-01 1.578717e-02 4.542838e-01 3.250831e+02 3.210305e-02 9.990859e-01 2.822463e-02 -9.202982e+00 -4.534230e-01 3.972405e-02 -8.904098e-01 4.860741e+02 +-9.034158e-01 1.584621e-02 4.284726e-01 3.253807e+02 3.177522e-02 9.990432e-01 3.004901e-02 -9.203970e+00 -4.275866e-01 4.076156e-02 -9.030550e-01 4.854510e+02 +-9.152892e-01 1.765119e-02 4.024104e-01 3.256448e+02 3.314265e-02 9.989520e-01 3.156581e-02 -9.204579e+00 -4.014315e-01 4.222878e-02 -9.149150e-01 4.848005e+02 +-9.262872e-01 2.098655e-02 3.762334e-01 3.259016e+02 3.637323e-02 9.987652e-01 3.383914e-02 -9.196251e+00 -3.750586e-01 4.502958e-02 -9.259068e-01 4.841562e+02 +-9.367802e-01 2.192199e-02 3.492310e-01 3.261455e+02 3.667694e-02 9.986895e-01 3.569258e-02 -9.186176e+00 -3.479910e-01 4.624482e-02 -9.363566e-01 4.835100e+02 +-9.469528e-01 2.408522e-02 3.204690e-01 3.263499e+02 3.855015e-02 9.985004e-01 3.886823e-02 -9.172831e+00 -3.190523e-01 4.916050e-02 -9.464612e-01 4.828301e+02 +-9.563205e-01 2.566823e-02 2.911912e-01 3.265415e+02 3.891007e-02 9.984508e-01 3.977464e-02 -9.163635e+00 -2.897191e-01 4.936756e-02 -9.558377e-01 4.821612e+02 +-9.649795e-01 2.904619e-02 2.607121e-01 3.267128e+02 4.018248e-02 9.984889e-01 3.748562e-02 -9.156698e+00 -2.592294e-01 4.664891e-02 -9.646886e-01 4.814905e+02 +-9.730607e-01 3.170467e-02 2.283587e-01 3.268481e+02 4.058914e-02 9.985865e-01 3.431365e-02 -9.148354e+00 -2.269480e-01 4.265814e-02 -9.729722e-01 4.807896e+02 +-9.799889e-01 3.538794e-02 1.958813e-01 3.269750e+02 4.278577e-02 9.985169e-01 3.366380e-02 -9.131456e+00 -1.943996e-01 4.137108e-02 -9.800496e-01 4.801106e+02 +-9.858623e-01 3.819664e-02 1.631461e-01 3.270584e+02 4.496259e-02 9.982664e-01 3.798122e-02 -9.116752e+00 -1.614125e-01 4.477971e-02 -9.858706e-01 4.793865e+02 +-9.907000e-01 4.027813e-02 1.299661e-01 3.271361e+02 4.659103e-02 9.978588e-01 4.590295e-02 -9.109399e+00 -1.278390e-01 5.153130e-02 -9.904553e-01 4.786836e+02 +-9.946206e-01 3.812918e-02 9.631200e-02 3.271999e+02 4.298367e-02 9.978812e-01 4.884169e-02 -9.098587e+00 -9.424565e-02 5.271879e-02 -9.941522e-01 4.779813e+02 +-9.972815e-01 3.966035e-02 6.210180e-02 3.272181e+02 4.269978e-02 9.979146e-01 4.840509e-02 -9.084421e+00 -6.005254e-02 5.092523e-02 -9.968953e-01 4.772493e+02 +-9.987872e-01 3.993354e-02 2.880060e-02 3.272265e+02 4.124162e-02 9.980734e-01 4.635255e-02 -9.065107e+00 -2.689410e-02 4.748411e-02 -9.985099e-01 4.765385e+02 +-9.991361e-01 4.129108e-02 -4.692641e-03 3.272076e+02 4.103765e-02 9.981363e-01 4.516455e-02 -9.041306e+00 6.548788e-03 4.493295e-02 -9.989685e-01 4.758161e+02 +-9.984232e-01 4.229969e-02 -3.690245e-02 3.271497e+02 4.057931e-02 9.981083e-01 4.618560e-02 -9.017436e+00 3.878628e-02 4.461529e-02 -9.982510e-01 4.750643e+02 +-9.966968e-01 4.606741e-02 -6.688252e-02 3.270832e+02 4.309279e-02 9.980454e-01 4.525754e-02 -8.998575e+00 6.883669e-02 4.222588e-02 -9.967339e-01 4.743306e+02 +-9.941910e-01 4.918461e-02 -9.573439e-02 3.269871e+02 4.502223e-02 9.979645e-01 4.516468e-02 -8.977902e+00 9.776094e-02 4.059214e-02 -9.943818e-01 4.735749e+02 +-9.912359e-01 5.006668e-02 -1.222487e-01 3.268870e+02 4.486502e-02 9.979817e-01 4.493980e-02 -8.955119e+00 1.242520e-01 3.906125e-02 -9.914816e-01 4.728295e+02 +-9.879206e-01 5.247540e-02 -1.458055e-01 3.267610e+02 4.647917e-02 9.979394e-01 4.423398e-02 -8.927932e+00 1.478263e-01 3.692274e-02 -9.883239e-01 4.720781e+02 +-9.845525e-01 5.327078e-02 -1.667893e-01 3.266126e+02 4.652338e-02 9.979430e-01 4.410661e-02 -8.900792e+00 1.687959e-01 3.566566e-02 -9.850056e-01 4.713125e+02 +-9.813504e-01 5.160280e-02 -1.851718e-01 3.264560e+02 4.464006e-02 9.981375e-01 4.157850e-02 -8.877903e+00 1.869725e-01 3.253699e-02 -9.818262e-01 4.705453e+02 +-9.781142e-01 5.093442e-02 -2.017381e-01 3.262859e+02 4.383127e-02 9.982568e-01 3.952481e-02 -8.859804e+00 2.033996e-01 2.981733e-02 -9.786417e-01 4.697695e+02 +-9.748970e-01 5.101674e-02 -2.167328e-01 3.261017e+02 4.364995e-02 9.982991e-01 3.864563e-02 -8.844980e+00 2.183358e-01 2.821512e-02 -9.754657e-01 4.689843e+02 +-9.718264e-01 4.828372e-02 -2.306991e-01 3.259112e+02 4.017929e-02 9.984034e-01 3.970254e-02 -8.829540e+00 2.322478e-01 2.931464e-02 -9.722148e-01 4.681946e+02 +-9.686703e-01 4.714242e-02 -2.438349e-01 3.257050e+02 3.827204e-02 9.984262e-01 4.099192e-02 -8.821245e+00 2.453836e-01 3.037560e-02 -9.689501e-01 4.673931e+02 +-9.659549e-01 4.756921e-02 -2.542997e-01 3.254850e+02 3.781512e-02 9.983543e-01 4.311151e-02 -8.806233e+00 2.559320e-01 3.202740e-02 -9.661641e-01 4.665847e+02 +-9.637376e-01 4.990032e-02 -2.621447e-01 3.252531e+02 3.978432e-02 9.982496e-01 4.375959e-02 -8.784192e+00 2.638694e-01 3.174351e-02 -9.640359e-01 4.657709e+02 +-9.622575e-01 5.263725e-02 -2.670015e-01 3.250129e+02 4.203722e-02 9.980901e-01 4.526606e-02 -8.766277e+00 2.688743e-01 3.233360e-02 -9.626324e-01 4.649475e+02 +-9.613851e-01 5.297821e-02 -2.700591e-01 3.247709e+02 4.280732e-02 9.981395e-01 4.341768e-02 -8.745386e+00 2.718569e-01 3.018060e-02 -9.618643e-01 4.641173e+02 +-9.606896e-01 5.234164e-02 -2.726461e-01 3.245258e+02 4.345460e-02 9.983119e-01 3.853682e-02 -8.719498e+00 2.742029e-01 2.517419e-02 -9.613423e-01 4.632831e+02 +-9.601518e-01 5.247384e-02 -2.745089e-01 3.242709e+02 4.408491e-02 9.983555e-01 3.664494e-02 -8.692468e+00 2.759803e-01 2.308301e-02 -9.608861e-01 4.624301e+02 +-9.594795e-01 5.551530e-02 -2.762557e-01 3.240153e+02 4.677707e-02 9.981775e-01 3.812593e-02 -8.668447e+00 2.778688e-01 2.365861e-02 -9.603277e-01 4.615688e+02 +-9.590292e-01 5.708260e-02 -2.774969e-01 3.237604e+02 4.715455e-02 9.979904e-01 4.232595e-02 -8.642691e+00 2.793554e-01 2.750657e-02 -9.597937e-01 4.606986e+02 +-9.585692e-01 5.803896e-02 -2.788845e-01 3.235030e+02 4.721644e-02 9.978536e-01 4.537425e-02 -8.617596e+00 2.809194e-01 3.032642e-02 -9.592521e-01 4.598214e+02 +-9.581239e-01 5.923091e-02 -2.801611e-01 3.232415e+02 4.849799e-02 9.978048e-01 4.509483e-02 -8.589860e+00 2.822171e-01 2.961918e-02 -9.588932e-01 4.589371e+02 +-9.575657e-01 6.048062e-02 -2.817979e-01 3.229725e+02 5.018020e-02 9.977865e-01 4.363388e-02 -8.552894e+00 2.838132e-01 2.764162e-02 -9.584811e-01 4.580422e+02 +-9.571539e-01 5.872921e-02 -2.835620e-01 3.227021e+02 4.859735e-02 9.979078e-01 4.264051e-02 -8.516222e+00 2.854730e-01 2.703316e-02 -9.580054e-01 4.571378e+02 +-9.567467e-01 5.699176e-02 -2.852852e-01 3.224281e+02 4.698706e-02 9.980206e-01 4.179767e-02 -8.476687e+00 2.871027e-01 2.658507e-02 -9.575308e-01 4.562216e+02 +-9.562224e-01 5.794789e-02 -2.868464e-01 3.221498e+02 4.816208e-02 9.979952e-01 4.106058e-02 -8.447955e+00 2.886507e-01 2.544792e-02 -9.570962e-01 4.553051e+02 +-9.557326e-01 5.887996e-02 -2.882853e-01 3.218673e+02 4.883122e-02 9.979264e-01 4.193173e-02 -8.420723e+00 2.901565e-01 2.599820e-02 -9.566260e-01 4.543759e+02 +-9.551993e-01 5.897287e-02 -2.900286e-01 3.215822e+02 4.859729e-02 9.978987e-01 4.285397e-02 -8.396462e+00 2.919464e-01 2.683948e-02 -9.560580e-01 4.534387e+02 +-9.545759e-01 6.016419e-02 -2.918307e-01 3.212933e+02 5.002091e-02 9.978603e-01 4.210224e-02 -8.372725e+00 2.937394e-01 2.559214e-02 -9.555429e-01 4.524964e+02 +-9.540808e-01 6.071010e-02 -2.933329e-01 3.209976e+02 5.055771e-02 9.978344e-01 4.207677e-02 -8.341981e+00 2.952521e-01 2.531440e-02 -9.550840e-01 4.515472e+02 +-9.535191e-01 6.179198e-02 -2.949289e-01 3.207005e+02 5.116950e-02 9.977375e-01 4.360746e-02 -8.317658e+00 2.969562e-01 2.648918e-02 -9.545236e-01 4.505902e+02 +-9.530269e-01 6.222951e-02 -2.964241e-01 3.204014e+02 5.152883e-02 9.977112e-01 4.378435e-02 -8.296810e+00 2.984704e-01 2.645327e-02 -9.540522e-01 4.496333e+02 +-9.525783e-01 6.117503e-02 -2.980808e-01 3.201023e+02 5.019137e-02 9.977534e-01 4.437186e-02 -8.275990e+00 3.001256e-01 2.730659e-02 -9.535088e-01 4.486726e+02 +-9.520933e-01 6.103558e-02 -2.996549e-01 3.198033e+02 4.950814e-02 9.977176e-01 4.591923e-02 -8.257096e+00 3.017737e-01 2.888403e-02 -9.529420e-01 4.477094e+02 +-9.516698e-01 5.985162e-02 -3.012346e-01 3.194999e+02 4.760589e-02 9.977200e-01 4.783677e-02 -8.230078e+00 3.034109e-01 3.118427e-02 -9.523494e-01 4.467430e+02 +-9.512326e-01 5.711956e-02 -3.031401e-01 3.191953e+02 4.480562e-02 9.978692e-01 4.742789e-02 -8.199201e+00 3.052033e-01 3.153257e-02 -9.517650e-01 4.457773e+02 +-9.506394e-01 5.837303e-02 -3.047579e-01 3.188823e+02 4.761765e-02 9.979562e-01 4.261262e-02 -8.171181e+00 3.066225e-01 2.599737e-02 -9.514761e-01 4.448127e+02 +-9.502698e-01 5.837086e-02 -3.059088e-01 3.185658e+02 4.684343e-02 9.978928e-01 4.489567e-02 -8.141815e+00 3.078848e-01 2.833318e-02 -9.510017e-01 4.438413e+02 +-9.499341e-01 6.108074e-02 -3.064220e-01 3.182459e+02 4.895897e-02 9.976897e-01 4.709797e-02 -8.116386e+00 3.085908e-01 2.973786e-02 -9.507299e-01 4.428700e+02 +-9.502426e-01 6.095095e-02 -3.054897e-01 3.179336e+02 4.863069e-02 9.976730e-01 4.778616e-02 -8.093347e+00 3.076915e-01 3.055226e-02 -9.509955e-01 4.419020e+02 +-9.509719e-01 5.917830e-02 -3.035627e-01 3.176255e+02 4.730029e-02 9.978052e-01 4.634029e-02 -8.071373e+00 3.056388e-01 2.970970e-02 -9.516839e-01 4.409323e+02 +-9.520256e-01 5.605882e-02 -3.008401e-01 3.173225e+02 4.467692e-02 9.980060e-01 4.458677e-02 -8.050251e+00 3.027397e-01 2.900713e-02 -9.526318e-01 4.399589e+02 +-9.532695e-01 5.136648e-02 -2.977225e-01 3.170265e+02 4.035130e-02 9.982585e-01 4.303125e-02 -8.029805e+00 2.994144e-01 2.900689e-02 -9.536822e-01 4.389827e+02 +-9.545113e-01 5.024117e-02 -2.939115e-01 3.167304e+02 4.005548e-02 9.983732e-01 4.057700e-02 -8.006388e+00 2.954720e-01 2.695844e-02 -9.549710e-01 4.380064e+02 +-9.561639e-01 4.579989e-02 -2.892283e-01 3.164413e+02 3.646412e-02 9.986278e-01 3.758758e-02 -7.988243e+00 2.905529e-01 2.539343e-02 -9.565219e-01 4.370287e+02 +-9.578296e-01 4.134721e-02 -2.843464e-01 3.161595e+02 3.327130e-02 9.988956e-01 3.317545e-02 -7.976289e+00 2.854041e-01 2.231585e-02 -9.581474e-01 4.360527e+02 +-9.596357e-01 3.791397e-02 -2.786786e-01 3.158812e+02 3.098217e-02 9.990922e-01 2.923784e-02 -7.969702e+00 2.795342e-01 1.942361e-02 -9.599393e-01 4.350726e+02 +-9.616044e-01 3.261970e-02 -2.724941e-01 3.156145e+02 2.612045e-02 9.992819e-01 2.744559e-02 -7.966527e+00 2.731937e-01 1.927413e-02 -9.617659e-01 4.340928e+02 +-9.636717e-01 2.701361e-02 -2.657200e-01 3.153574e+02 1.999758e-02 9.993772e-01 2.907459e-02 -7.966772e+00 2.663399e-01 2.270460e-02 -9.636117e-01 4.331048e+02 +-9.659602e-01 2.428997e-02 -2.575479e-01 3.151057e+02 1.699881e-02 9.993902e-01 3.049915e-02 -7.967969e+00 2.581317e-01 2.508295e-02 -9.657841e-01 4.321196e+02 +-9.686601e-01 2.334447e-02 -2.472905e-01 3.148670e+02 1.540603e-02 9.993035e-01 3.398841e-02 -7.972304e+00 2.479117e-01 2.911345e-02 -9.683451e-01 4.311326e+02 +-9.717060e-01 2.479462e-02 -2.348888e-01 3.146335e+02 1.652246e-02 9.991742e-01 3.712046e-02 -7.968748e+00 2.356152e-01 3.218923e-02 -9.713132e-01 4.301386e+02 +-9.751172e-01 2.712050e-02 -2.200248e-01 3.144162e+02 1.902535e-02 9.990647e-01 3.882836e-02 -7.969385e+00 2.208721e-01 3.367615e-02 -9.747212e-01 4.291517e+02 +-9.784377e-01 2.758760e-02 -2.046915e-01 3.142136e+02 2.033088e-02 9.990908e-01 3.747119e-02 -7.964300e+00 2.055392e-01 3.250167e-02 -9.781091e-01 4.281654e+02 +-9.814272e-01 2.667661e-02 -1.899713e-01 3.140237e+02 2.066463e-02 9.992231e-01 3.355809e-02 -7.961579e+00 1.907190e-01 2.900913e-02 -9.812160e-01 4.271748e+02 +-9.842342e-01 2.306747e-02 -1.753592e-01 3.138513e+02 1.820247e-02 9.994048e-01 2.930134e-02 -7.947662e+00 1.759308e-01 2.564740e-02 -9.840684e-01 4.261826e+02 +-9.865817e-01 2.048486e-02 -1.619781e-01 3.136951e+02 1.613470e-02 9.994741e-01 2.812663e-02 -7.944008e+00 1.624691e-01 2.513575e-02 -9.863934e-01 4.251884e+02 +-9.886981e-01 2.060461e-02 -1.484978e-01 3.135461e+02 1.657955e-02 9.994622e-01 2.829247e-02 -7.942327e+00 1.490009e-01 2.551068e-02 -9.885079e-01 4.241888e+02 +-9.906081e-01 2.241416e-02 -1.348819e-01 3.134112e+02 1.860279e-02 9.993931e-01 2.945161e-02 -7.939799e+00 1.354602e-01 2.666582e-02 -9.904239e-01 4.231903e+02 +-9.923961e-01 2.360263e-02 -1.208013e-01 3.132937e+02 1.983726e-02 9.992820e-01 3.227843e-02 -7.940858e+00 1.214764e-01 2.963662e-02 -9.921518e-01 4.221950e+02 +-9.939857e-01 2.384747e-02 -1.068817e-01 3.131860e+02 2.054129e-02 9.992790e-01 3.192817e-02 -7.934332e+00 1.075660e-01 2.954065e-02 -9.937590e-01 4.211917e+02 +-9.954179e-01 2.065836e-02 -9.336155e-02 3.131010e+02 1.771459e-02 9.993228e-01 3.225050e-02 -7.929527e+00 9.396458e-02 3.044886e-02 -9.951098e-01 4.201926e+02 +-9.966242e-01 1.662222e-02 -8.039880e-02 3.130266e+02 1.382461e-02 9.992836e-01 3.522926e-02 -7.923389e+00 8.092680e-02 3.399885e-02 -9.961400e-01 4.191863e+02 +-9.976247e-01 1.282030e-02 -6.768022e-02 3.129673e+02 1.027761e-02 9.992330e-01 3.778480e-02 -7.916512e+00 6.811273e-02 3.699946e-02 -9.969913e-01 4.181842e+02 +-9.984102e-01 1.168520e-02 -5.514029e-02 3.129180e+02 9.544606e-03 9.991965e-01 3.892588e-02 -7.904677e+00 5.555085e-02 3.833770e-02 -9.977196e-01 4.171852e+02 +-9.990690e-01 9.614950e-03 -4.205591e-02 3.128816e+02 8.011057e-03 9.992402e-01 3.814100e-02 -7.897393e+00 4.239068e-02 3.776857e-02 -9.983870e-01 4.161802e+02 +-9.995451e-01 7.957098e-03 -2.909145e-02 3.128645e+02 6.842357e-03 9.992459e-01 3.821952e-02 -7.882213e+00 2.937363e-02 3.800308e-02 -9.988458e-01 4.151799e+02 +-9.998366e-01 8.322258e-03 -1.605061e-02 3.128515e+02 7.698735e-03 9.992279e-01 3.852588e-02 -7.864187e+00 1.635884e-02 3.839601e-02 -9.991287e-01 4.141736e+02 +-9.999587e-01 8.464164e-03 -3.306039e-03 3.128537e+02 8.322309e-03 9.991329e-01 4.079434e-02 -7.836788e+00 3.648462e-03 4.076514e-02 -9.991621e-01 4.131682e+02 +-9.999369e-01 6.125116e-03 9.419909e-03 3.128726e+02 6.534903e-03 9.990055e-01 4.410420e-02 -7.809641e+00 -9.140399e-03 4.416297e-02 -9.989825e-01 4.121555e+02 +-9.997397e-01 6.038812e-03 2.200098e-02 3.129004e+02 7.031226e-03 9.989481e-01 4.531288e-02 -7.788164e+00 -2.170421e-02 4.545577e-02 -9.987306e-01 4.111602e+02 +-9.993711e-01 8.107217e-03 3.451971e-02 3.129384e+02 9.656928e-03 9.989418e-01 4.496587e-02 -7.770852e+00 -3.411864e-02 4.527094e-02 -9.983919e-01 4.101608e+02 +-9.988673e-01 9.282398e-03 4.666833e-02 3.129904e+02 1.128179e-02 9.990215e-01 4.276314e-02 -7.751320e+00 -4.622573e-02 4.324120e-02 -9.979947e-01 4.091621e+02 +-9.982344e-01 9.877001e-03 5.857135e-02 3.130478e+02 1.222624e-02 9.991294e-01 3.988712e-02 -7.727473e+00 -5.812639e-02 4.053280e-02 -9.974861e-01 4.081610e+02 +-9.974476e-01 1.038562e-02 7.064262e-02 3.131205e+02 1.309212e-02 9.991935e-01 3.795803e-02 -7.703911e+00 -7.019144e-02 3.878600e-02 -9.967792e-01 4.071622e+02 +-9.965652e-01 8.589957e-03 8.236492e-02 3.132035e+02 1.176070e-02 9.992051e-01 3.808863e-02 -7.680434e+00 -8.197228e-02 3.892646e-02 -9.958741e-01 4.061594e+02 +-9.956274e-01 7.471230e-03 9.311481e-02 3.132979e+02 1.105795e-02 9.992141e-01 3.806301e-02 -7.656495e+00 -9.275726e-02 3.892623e-02 -9.949276e-01 4.051567e+02 +-9.946628e-01 6.590418e-03 1.029683e-01 3.134058e+02 1.035087e-02 9.992971e-01 3.602887e-02 -7.636293e+00 -1.026585e-01 3.690238e-02 -9.940319e-01 4.041588e+02 +-9.936384e-01 6.069816e-03 1.124544e-01 3.135203e+02 9.935014e-03 9.993778e-01 3.384274e-02 -7.617968e+00 -1.121790e-01 3.474467e-02 -9.930804e-01 4.031635e+02 +-9.925139e-01 5.250763e-03 1.220189e-01 3.136460e+02 9.290593e-03 9.994265e-01 3.256285e-02 -7.603233e+00 -1.217779e-01 3.345271e-02 -9.919935e-01 4.021697e+02 +-9.913466e-01 3.776978e-03 1.312161e-01 3.137817e+02 8.123781e-03 9.994352e-01 3.260750e-02 -7.590841e+00 -1.310189e-01 3.339131e-02 -9.908174e-01 4.011770e+02 +-9.901637e-01 3.388119e-03 1.398731e-01 3.139238e+02 8.067288e-03 9.994261e-01 3.289949e-02 -7.578294e+00 -1.396814e-01 3.370427e-02 -9.896227e-01 4.001891e+02 +-9.889606e-01 2.303989e-03 1.481607e-01 3.140758e+02 7.598525e-03 9.993521e-01 3.517896e-02 -7.564827e+00 -1.479837e-01 3.591641e-02 -9.883374e-01 3.992065e+02 +-9.876848e-01 -1.280993e-03 1.564513e-01 3.142420e+02 4.743532e-03 9.992616e-01 3.812787e-02 -7.556412e+00 -1.563846e-01 3.840045e-02 -9.869495e-01 3.982277e+02 +-9.863338e-01 -2.021560e-03 1.647471e-01 3.144105e+02 4.314618e-03 9.992649e-01 3.809307e-02 -7.544788e+00 -1.647030e-01 3.828329e-02 -9.856000e-01 3.972525e+02 +-9.849074e-01 -2.089644e-03 1.730697e-01 3.145829e+02 4.406238e-03 9.993003e-01 3.714060e-02 -7.533432e+00 -1.730262e-01 3.734264e-02 -9.842091e-01 3.962813e+02 +-9.835459e-01 -3.932855e-03 1.806155e-01 3.147637e+02 2.894843e-03 9.992915e-01 3.752322e-02 -7.519799e+00 -1.806351e-01 3.742866e-02 -9.828378e-01 3.953134e+02 +-9.821739e-01 -6.874547e-03 1.878488e-01 3.149572e+02 5.311345e-04 9.992255e-01 3.934485e-02 -7.509055e+00 -1.879738e-01 3.874325e-02 -9.814096e-01 3.943507e+02 +-9.807939e-01 -8.102166e-03 1.948788e-01 3.151557e+02 -2.670565e-04 9.991917e-01 4.019772e-02 -7.495438e+00 -1.950470e-01 3.937363e-02 -9.800033e-01 3.933960e+02 +-9.793924e-01 -9.306265e-03 2.017520e-01 3.153571e+02 -9.358565e-04 9.991362e-01 4.154432e-02 -7.480266e+00 -2.019644e-01 4.049938e-02 -9.785552e-01 3.924386e+02 +-9.779715e-01 -1.035820e-02 2.084813e-01 3.155637e+02 -1.160842e-03 9.990224e-01 4.419004e-02 -7.463247e+00 -2.087353e-01 4.297457e-02 -9.770275e-01 3.914864e+02 +-9.764483e-01 -1.148378e-02 2.154456e-01 3.157787e+02 -1.828369e-03 9.989870e-01 4.496185e-02 -7.446897e+00 -2.157437e-01 4.350900e-02 -9.754802e-01 3.905423e+02 +-9.749368e-01 -1.140835e-02 2.221891e-01 3.159974e+02 -1.762504e-03 9.990491e-01 4.356275e-02 -7.423038e+00 -2.224748e-01 4.207931e-02 -9.740299e-01 3.895889e+02 +-9.733567e-01 -1.101077e-02 2.290319e-01 3.162107e+02 -1.876099e-03 9.991954e-01 4.006339e-02 -7.397839e+00 -2.292887e-01 3.856628e-02 -9.725941e-01 3.886826e+02 +-9.717408e-01 -1.160591e-02 2.357650e-01 3.164277e+02 -2.949236e-03 9.993095e-01 3.703688e-02 -7.369106e+00 -2.360321e-01 3.529491e-02 -9.711041e-01 3.877649e+02 +-9.701113e-01 -1.106656e-02 2.424081e-01 3.166495e+02 -2.806737e-03 9.994044e-01 3.439292e-02 -7.347796e+00 -2.426443e-01 3.268457e-02 -9.695646e-01 3.868615e+02 +-9.683855e-01 -1.024282e-02 2.492483e-01 3.168756e+02 -2.111232e-03 9.994574e-01 3.286992e-02 -7.325785e+00 -2.494498e-01 3.130453e-02 -9.678816e-01 3.859696e+02 +-9.665331e-01 -9.716963e-03 2.563579e-01 3.171058e+02 -1.873934e-03 9.995232e-01 3.082061e-02 -7.311971e+00 -2.565352e-01 2.930873e-02 -9.660904e-01 3.850954e+02 +-9.645393e-01 -7.029461e-03 2.638458e-01 3.173378e+02 2.788370e-04 9.996176e-01 2.765145e-02 -7.302981e+00 -2.639393e-01 2.674447e-02 -9.641685e-01 3.842427e+02 +-9.624241e-01 -5.985893e-03 2.714849e-01 3.175754e+02 8.316296e-05 9.997504e-01 2.233801e-02 -7.303376e+00 -2.715509e-01 2.152121e-02 -9.621834e-01 3.834117e+02 +-9.604643e-01 -4.949882e-03 2.783593e-01 3.178160e+02 -1.363772e-03 9.999136e-01 1.307517e-02 -7.311934e+00 -2.784000e-01 1.217861e-02 -9.603880e-01 3.826135e+02 +-9.586514e-01 -3.889692e-03 2.845564e-01 3.180493e+02 -3.324705e-03 9.999914e-01 2.468475e-03 -7.315700e+00 -2.845636e-01 1.420341e-03 -9.586561e-01 3.818405e+02 +-9.570647e-01 -4.190533e-03 2.898441e-01 3.182783e+02 -6.366369e-03 9.999582e-01 -6.564474e-03 -7.317945e+00 -2.898045e-01 -8.127878e-03 -9.570514e-01 3.810826e+02 +-9.557182e-01 -5.098421e-03 2.942391e-01 3.185019e+02 -9.300886e-03 9.998737e-01 -1.288494e-02 -7.326887e+00 -2.941363e-01 -1.505106e-02 -9.556450e-01 3.803531e+02 +-9.546414e-01 -3.990756e-03 2.977313e-01 3.187247e+02 -9.989385e-03 9.997765e-01 -1.862895e-02 -7.349644e+00 -2.975904e-01 -2.075811e-02 -9.544679e-01 3.796487e+02 +-9.538069e-01 -1.998405e-03 3.004136e-01 3.189406e+02 -1.031065e-02 9.996065e-01 -2.608655e-02 -7.375780e+00 -3.002433e-01 -2.797898e-02 -9.534522e-01 3.789647e+02 +-9.533818e-01 -1.941666e-04 3.017666e-01 3.191500e+02 -1.086645e-02 9.993733e-01 -3.368776e-02 -7.405085e+00 -3.015710e-01 -3.539642e-02 -9.527865e-01 3.782973e+02 +-9.532783e-01 2.471174e-03 3.020834e-01 3.193464e+02 -9.409537e-03 9.992384e-01 -3.786770e-02 -7.428682e+00 -3.019470e-01 -3.894092e-02 -9.525291e-01 3.776312e+02 +-9.534961e-01 5.156682e-03 3.013614e-01 3.195361e+02 -5.954562e-03 9.993362e-01 -3.593996e-02 -7.449147e+00 -3.013467e-01 -3.606308e-02 -9.528324e-01 3.769608e+02 +-9.546073e-01 8.104294e-03 2.977570e-01 3.197158e+02 -1.150366e-03 9.995220e-01 -3.089290e-02 -7.469043e+00 -2.978651e-01 -2.983311e-02 -9.541417e-01 3.762906e+02 +-9.565805e-01 1.115701e-02 2.912548e-01 3.198904e+02 2.892188e-03 9.995812e-01 -2.879176e-02 -7.494632e+00 -2.914541e-01 -2.669926e-02 -9.562121e-01 3.756302e+02 +-9.595668e-01 1.265700e-02 2.811963e-01 3.200516e+02 4.209339e-03 9.995220e-01 -3.062565e-02 -7.510150e+00 -2.814495e-01 -2.820370e-02 -9.591615e-01 3.749768e+02 +-9.636165e-01 1.358644e-02 2.669433e-01 3.202030e+02 5.254156e-03 9.994771e-01 -3.190322e-02 -7.526334e+00 -2.672372e-01 -2.933990e-02 -9.631840e-01 3.743240e+02 +-9.687548e-01 1.538171e-02 2.475430e-01 3.203352e+02 8.113065e-03 9.995062e-01 -3.035656e-02 -7.535126e+00 -2.478877e-01 -2.739973e-02 -9.684012e-01 3.736749e+02 +-9.746048e-01 1.823121e-02 2.231883e-01 3.204552e+02 1.353955e-02 9.996544e-01 -2.253345e-02 -7.552413e+00 -2.235220e-01 -1.893933e-02 -9.745149e-01 3.730304e+02 +-9.808411e-01 1.922720e-02 1.938583e-01 3.205484e+02 1.687352e-02 9.997626e-01 -1.378535e-02 -7.565890e+00 -1.940774e-01 -1.025016e-02 -9.809327e-01 3.723715e+02 +-9.867637e-01 2.136401e-02 1.607514e-01 3.206328e+02 2.061801e-02 9.997675e-01 -6.307549e-03 -7.582058e+00 -1.608488e-01 -2.909685e-03 -9.869748e-01 3.717375e+02 +-9.920334e-01 2.246186e-02 1.239562e-01 3.206679e+02 2.247902e-02 9.997465e-01 -1.260431e-03 -7.593814e+00 -1.239531e-01 1.536025e-03 -9.922869e-01 3.710836e+02 +-9.961978e-01 2.313685e-02 8.399145e-02 3.206983e+02 2.355502e-02 9.997146e-01 3.990964e-03 -7.604115e+00 -8.387514e-02 5.954210e-03 -9.964585e-01 3.704585e+02 +-9.987909e-01 2.489046e-02 4.239248e-02 3.206692e+02 2.529557e-02 9.996391e-01 9.046524e-03 -7.604099e+00 -4.215201e-02 1.010793e-02 -9.990601e-01 3.698013e+02 +-9.996006e-01 2.826155e-02 -2.627677e-05 3.206393e+02 2.825849e-02 9.995045e-01 1.385910e-02 -7.603151e+00 4.179432e-04 1.385282e-02 -9.999040e-01 3.691789e+02 +-9.985703e-01 3.068712e-02 -4.376817e-02 3.205855e+02 2.996804e-02 9.994064e-01 1.699231e-02 -7.605148e+00 4.426364e-02 1.565637e-02 -9.988972e-01 3.685646e+02 +-9.956007e-01 2.982483e-02 -8.882369e-02 3.204715e+02 2.813147e-02 9.993990e-01 2.025586e-02 -7.596182e+00 8.937444e-02 1.766800e-02 -9.958414e-01 3.679171e+02 +-9.905258e-01 2.692120e-02 -1.346621e-01 3.203672e+02 2.406381e-02 9.994503e-01 2.280218e-02 -7.583856e+00 1.352020e-01 1.934566e-02 -9.906292e-01 3.673082e+02 +-9.833576e-01 2.867196e-02 -1.794038e-01 3.201935e+02 2.430385e-02 9.993533e-01 2.649921e-02 -7.563603e+00 1.800476e-01 2.169800e-02 -9.834186e-01 3.666656e+02 +-9.741864e-01 3.248397e-02 -2.233958e-01 3.200191e+02 2.548319e-02 9.990917e-01 3.415061e-02 -7.544896e+00 2.243023e-01 2.757622e-02 -9.741294e-01 3.660576e+02 +-9.629552e-01 3.385315e-02 -2.675281e-01 3.198122e+02 2.412507e-02 9.989256e-01 3.956754e-02 -7.523562e+00 2.685801e-01 3.164763e-02 -9.627373e-01 3.654519e+02 +-9.495224e-01 3.144966e-02 -3.121187e-01 3.195555e+02 1.923180e-02 9.989263e-01 4.214705e-02 -7.495768e+00 3.131091e-01 3.401696e-02 -9.491078e-01 3.648183e+02 +-9.341337e-01 2.958150e-02 -3.556954e-01 3.192952e+02 1.510414e-02 9.989431e-01 4.341064e-02 -7.464192e+00 3.566036e-01 3.517887e-02 -9.335932e-01 3.642279e+02 +-9.170540e-01 3.065497e-02 -3.975829e-01 3.189776e+02 1.482389e-02 9.989723e-01 4.283175e-02 -7.434877e+00 3.984874e-01 3.338529e-02 -9.165660e-01 3.636125e+02 +-8.981012e-01 3.465610e-02 -4.384213e-01 3.186551e+02 1.693656e-02 9.988763e-01 4.426434e-02 -7.401822e+00 4.394627e-01 3.232850e-02 -8.976789e-01 3.630385e+02 +-8.785100e-01 3.915650e-02 -4.761165e-01 3.183109e+02 1.968897e-02 9.987561e-01 4.580990e-02 -7.369725e+00 4.773180e-01 3.087022e-02 -8.781882e-01 3.624796e+02 +-8.581260e-01 4.346747e-02 -5.115959e-01 3.179172e+02 2.236052e-02 9.986284e-01 4.734152e-02 -7.339697e+00 5.129520e-01 2.918544e-02 -8.579210e-01 3.618994e+02 +-8.377864e-01 4.723231e-02 -5.439514e-01 3.175272e+02 2.459515e-02 9.985047e-01 4.882095e-02 -7.315453e+00 5.454439e-01 2.752296e-02 -8.376953e-01 3.613535e+02 +-8.178752e-01 4.900288e-02 -5.733053e-01 3.170958e+02 2.572506e-02 9.984847e-01 4.864557e-02 -7.287524e+00 5.748204e-01 2.503769e-02 -8.178965e-01 3.607945e+02 +-7.986297e-01 5.198886e-02 -5.995730e-01 3.166532e+02 2.948159e-02 9.984453e-01 4.730562e-02 -7.249582e+00 6.011002e-01 2.010330e-02 -7.989208e-01 3.602598e+02 +-7.809406e-01 5.411009e-02 -6.222571e-01 3.161877e+02 3.343018e-02 9.984335e-01 4.486628e-02 -7.212206e+00 6.237100e-01 1.423574e-02 -7.815262e-01 3.597278e+02 +-7.648496e-01 5.766375e-02 -6.416230e-01 3.156878e+02 3.875154e-02 9.983005e-01 4.352505e-02 -7.180588e+00 6.430424e-01 8.426235e-03 -7.657843e-01 3.591849e+02 +-7.508646e-01 6.039439e-02 -6.576890e-01 3.151831e+02 4.290769e-02 9.981672e-01 4.267345e-02 -7.154711e+00 6.590609e-01 3.822072e-03 -7.520799e-01 3.586493e+02 +-7.387637e-01 6.178867e-02 -6.711262e-01 3.146596e+02 4.463555e-02 9.980879e-01 4.275712e-02 -7.126823e+00 6.724849e-01 1.631328e-03 -7.401091e-01 3.581061e+02 +-7.273949e-01 6.242984e-02 -6.833733e-01 3.141234e+02 4.581953e-02 9.980492e-01 4.240607e-02 -7.103704e+00 6.846877e-01 -4.658760e-04 -7.288365e-01 3.575550e+02 +-7.169134e-01 6.229552e-02 -6.943734e-01 3.135730e+02 4.632148e-02 9.980552e-01 4.171515e-02 -7.080791e+00 6.956216e-01 -2.258243e-03 -7.184048e-01 3.570065e+02 +-7.068535e-01 6.238193e-02 -7.046039e-01 3.129961e+02 4.653392e-02 9.980468e-01 4.167936e-02 -7.049674e+00 7.058278e-01 -3.326780e-03 -7.083757e-01 3.564444e+02 +-6.974409e-01 6.231518e-02 -7.139279e-01 3.124105e+02 4.760662e-02 9.980404e-01 4.060675e-02 -7.020329e+00 7.150593e-01 -5.666879e-03 -6.990408e-01 3.558899e+02 +-6.903499e-01 6.369001e-02 -7.206668e-01 3.118030e+02 4.983079e-02 9.979378e-01 4.045977e-02 -6.995473e+00 7.217575e-01 -7.979996e-03 -6.921000e-01 3.553259e+02 +-6.860110e-01 6.528009e-02 -7.246567e-01 3.111829e+02 5.172002e-02 9.978226e-01 4.092623e-02 -6.969965e+00 7.257506e-01 -9.403404e-03 -6.878937e-01 3.547555e+02 +-6.855721e-01 6.791329e-02 -7.248301e-01 3.105501e+02 5.513195e-02 9.976234e-01 4.132689e-02 -6.941787e+00 7.259142e-01 -1.162873e-02 -6.876870e-01 3.541721e+02 +-6.884269e-01 7.027619e-02 -7.218931e-01 3.099116e+02 5.692208e-02 9.974599e-01 4.281938e-02 -6.909712e+00 7.230687e-01 -1.161363e-02 -6.906786e-01 3.535723e+02 +-6.920579e-01 6.965690e-02 -7.184732e-01 3.092680e+02 5.463248e-02 9.975327e-01 4.408823e-02 -6.873301e+00 7.197716e-01 -8.740358e-03 -6.941560e-01 3.529546e+02 +-6.946341e-01 6.721918e-02 -7.162158e-01 3.086152e+02 5.144156e-02 9.977173e-01 4.374758e-02 -6.834781e+00 7.175216e-01 -6.454693e-03 -6.965063e-01 3.523219e+02 +-6.962638e-01 6.408931e-02 -7.149191e-01 3.079541e+02 4.766525e-02 9.979357e-01 4.303905e-02 -6.791068e+00 7.162017e-01 -4.110260e-03 -6.978813e-01 3.516811e+02 +-6.971528e-01 6.293764e-02 -7.141547e-01 3.072817e+02 4.690536e-02 9.980090e-01 4.216474e-02 -6.750734e+00 7.153866e-01 -4.102417e-03 -6.987169e-01 3.510309e+02 +-6.979927e-01 6.256341e-02 -7.133667e-01 3.066049e+02 4.589620e-02 9.980365e-01 4.262237e-02 -6.711582e+00 7.146326e-01 -2.990713e-03 -6.994936e-01 3.503780e+02 +-6.990904e-01 6.215657e-02 -7.123266e-01 3.059188e+02 4.502175e-02 9.980642e-01 4.290448e-02 -6.671134e+00 7.136145e-01 -2.076079e-03 -7.005355e-01 3.497099e+02 +-7.001225e-01 6.177352e-02 -7.113456e-01 3.052211e+02 4.584000e-02 9.980840e-01 4.155725e-02 -6.627276e+00 7.125498e-01 -3.512917e-03 -7.016128e-01 3.490373e+02 +-7.014838e-01 6.077333e-02 -7.100895e-01 3.045232e+02 4.549351e-02 9.981439e-01 4.048446e-02 -6.591876e+00 7.112319e-01 -3.905266e-03 -7.029466e-01 3.483554e+02 +-7.025879e-01 5.968935e-02 -7.090891e-01 3.038151e+02 4.384939e-02 9.982136e-01 4.057979e-02 -6.556623e+00 7.102446e-01 -2.582244e-03 -7.039502e-01 3.476608e+02 +-7.039089e-01 5.883424e-02 -7.078494e-01 3.031055e+02 4.394509e-02 9.982617e-01 3.927198e-02 -6.530925e+00 7.089295e-01 -3.462599e-03 -7.052709e-01 3.469593e+02 +-7.052990e-01 5.755829e-02 -7.065695e-01 3.023918e+02 4.484498e-02 9.983247e-01 3.656082e-02 -6.507199e+00 7.074902e-01 -5.899786e-03 -7.066986e-01 3.462502e+02 +-7.068156e-01 5.466316e-02 -7.052826e-01 3.016714e+02 4.384597e-02 9.984783e-01 3.344614e-02 -6.481575e+00 7.060377e-01 -7.283539e-03 -7.081368e-01 3.455306e+02 +-7.085380e-01 5.212551e-02 -7.037449e-01 3.009474e+02 4.254658e-02 9.986094e-01 3.112942e-02 -6.455473e+00 7.043889e-01 -7.885560e-03 -7.097704e-01 3.448005e+02 +-7.102297e-01 4.988757e-02 -7.022001e-01 3.002216e+02 4.259423e-02 9.987036e-01 2.787128e-02 -6.434746e+00 7.026803e-01 -1.011466e-02 -7.114339e-01 3.440664e+02 +-7.118268e-01 4.728981e-02 -7.007612e-01 2.994935e+02 4.032103e-02 9.988367e-01 2.644727e-02 -6.415862e+00 7.011967e-01 -9.429532e-03 -7.129055e-01 3.433218e+02 +-7.135311e-01 4.768222e-02 -6.989991e-01 2.987683e+02 4.001794e-02 9.988263e-01 2.728506e-02 -6.406086e+00 6.994798e-01 -8.503766e-03 -7.146018e-01 3.425763e+02 +-7.155970e-01 4.925100e-02 -6.967749e-01 2.980376e+02 3.938859e-02 9.987691e-01 3.014466e-02 -6.395720e+00 6.974019e-01 -5.873548e-03 -7.166562e-01 3.418200e+02 +-7.178301e-01 5.145450e-02 -6.943143e-01 2.973116e+02 4.073031e-02 9.986608e-01 3.189934e-02 -6.388140e+00 6.950259e-01 -5.381326e-03 -7.189646e-01 3.410638e+02 +-7.212338e-01 5.153081e-02 -6.907723e-01 2.965859e+02 4.031411e-02 9.986614e-01 3.240713e-02 -6.375940e+00 6.915176e-01 -4.474745e-03 -7.223458e-01 3.403005e+02 +-7.251739e-01 5.279307e-02 -6.865389e-01 2.958644e+02 3.981242e-02 9.986032e-01 3.473717e-02 -6.365722e+00 6.874138e-01 -2.142276e-03 -7.262628e-01 3.395305e+02 +-7.294289e-01 5.387958e-02 -6.819315e-01 2.951442e+02 3.851168e-02 9.985466e-01 3.770138e-02 -6.355388e+00 6.829718e-01 1.238149e-03 -7.304438e-01 3.387508e+02 +-7.337908e-01 5.340523e-02 -6.772732e-01 2.944300e+02 3.801662e-02 9.985713e-01 3.755161e-02 -6.342623e+00 6.783110e-01 1.807393e-03 -7.347727e-01 3.379678e+02 +-7.388330e-01 5.193719e-02 -6.718842e-01 2.937212e+02 3.779892e-02 9.986499e-01 3.563115e-02 -6.328430e+00 6.728277e-01 9.289757e-04 -7.397987e-01 3.371799e+02 +-7.447337e-01 5.309403e-02 -6.652464e-01 2.930109e+02 4.028735e-02 9.985890e-01 3.459738e-02 -6.313455e+00 6.661447e-01 -1.035173e-03 -7.458219e-01 3.363838e+02 +-7.519253e-01 5.419569e-02 -6.570168e-01 2.923061e+02 4.241988e-02 9.985273e-01 3.381848e-02 -6.298162e+00 6.578821e-01 -2.441606e-03 -7.531170e-01 3.355793e+02 +-7.605801e-01 5.429374e-02 -6.469699e-01 2.916138e+02 4.402438e-02 9.985165e-01 3.204036e-02 -6.279523e+00 6.477498e-01 -4.113182e-03 -7.618421e-01 3.347655e+02 +-7.700027e-01 5.602570e-02 -6.355760e-01 2.909370e+02 4.804895e-02 9.984004e-01 2.979703e-02 -6.266510e+00 6.362288e-01 -7.594956e-03 -7.714630e-01 3.339451e+02 +-7.799937e-01 5.579001e-02 -6.232955e-01 2.902666e+02 4.882200e-02 9.984073e-01 2.826961e-02 -6.257418e+00 6.238800e-01 -8.380409e-03 -7.814753e-01 3.331077e+02 +-7.901788e-01 5.541932e-02 -6.103656e-01 2.896251e+02 4.898966e-02 9.984279e-01 2.723225e-02 -6.258946e+00 6.109153e-01 -8.383257e-03 -7.916516e-01 3.322652e+02 +-8.001980e-01 5.439353e-02 -5.972642e-01 2.889917e+02 4.764954e-02 9.984965e-01 2.709471e-02 -6.253835e+00 5.978401e-01 -6.778235e-03 -8.015868e-01 3.314052e+02 +-8.097888e-01 5.065239e-02 -5.845309e-01 2.883694e+02 4.469603e-02 9.986971e-01 2.462157e-02 -6.246780e+00 5.850165e-01 -6.187934e-03 -8.109978e-01 3.305313e+02 +-8.180312e-01 4.911775e-02 -5.730728e-01 2.877655e+02 4.296861e-02 9.987816e-01 2.426961e-02 -6.246550e+00 5.735666e-01 -4.770841e-03 -8.191450e-01 3.296505e+02 +-8.254939e-01 4.946346e-02 -5.622395e-01 2.871709e+02 4.077915e-02 9.987759e-01 2.799517e-02 -6.248509e+00 5.629360e-01 1.821942e-04 -8.265005e-01 3.287590e+02 +-8.327015e-01 4.986960e-02 -5.514719e-01 2.865931e+02 3.864925e-02 9.987417e-01 3.195735e-02 -6.253438e+00 5.523717e-01 5.296954e-03 -8.335811e-01 3.278609e+02 +-8.402210e-01 4.895347e-02 -5.400299e-01 2.860267e+02 3.911586e-02 9.987938e-01 2.968070e-02 -6.254569e+00 5.408315e-01 3.814612e-03 -8.411223e-01 3.269603e+02 +-8.471620e-01 4.974790e-02 -5.290007e-01 2.854620e+02 4.096650e-02 9.987591e-01 2.831929e-02 -6.252325e+00 5.297531e-01 2.319720e-03 -8.481487e-01 3.260456e+02 +-8.538889e-01 4.785119e-02 -5.182510e-01 2.849108e+02 3.959170e-02 9.988512e-01 2.699334e-02 -6.255361e+00 5.189473e-01 2.530883e-03 -8.548025e-01 3.251233e+02 +-8.604710e-01 4.679285e-02 -5.073461e-01 2.843683e+02 3.932056e-02 9.989027e-01 2.544086e-02 -6.262423e+00 5.079798e-01 1.941997e-03 -8.613668e-01 3.241909e+02 +-8.669688e-01 4.570672e-02 -4.962621e-01 2.838308e+02 3.956513e-02 9.989549e-01 2.288555e-02 -6.263385e+00 4.967895e-01 2.063870e-04 -8.678711e-01 3.232464e+02 +-8.730391e-01 4.643651e-02 -4.854342e-01 2.833057e+02 4.142396e-02 9.989197e-01 2.105666e-02 -6.267547e+00 4.858877e-01 -1.725314e-03 -8.740196e-01 3.222960e+02 +-8.785445e-01 4.646239e-02 -4.753954e-01 2.827831e+02 4.228475e-02 9.989156e-01 1.948480e-02 -6.266548e+00 4.757852e-01 -2.983703e-03 -8.795565e-01 3.213332e+02 +-8.831620e-01 4.913591e-02 -4.664875e-01 2.822688e+02 4.446284e-02 9.987897e-01 2.102644e-02 -6.260451e+00 4.669561e-01 -2.171606e-03 -8.842778e-01 3.203633e+02 +-8.869982e-01 5.231556e-02 -4.587999e-01 2.817584e+02 4.656317e-02 9.986306e-01 2.385024e-02 -6.256896e+00 4.594194e-01 -2.080607e-04 -8.882195e-01 3.193793e+02 +-8.900650e-01 5.337643e-02 -4.526977e-01 2.812544e+02 4.793438e-02 9.985741e-01 2.349388e-02 -6.253202e+00 4.533062e-01 -7.887029e-04 -8.913545e-01 3.183888e+02 +-8.923709e-01 5.379150e-02 -4.480855e-01 2.807553e+02 4.858752e-02 9.985515e-01 2.311058e-02 -6.247107e+00 4.486796e-01 -1.148151e-03 -8.936920e-01 3.173915e+02 +-8.939748e-01 5.234764e-02 -4.450491e-01 2.802623e+02 4.628731e-02 9.986281e-01 2.448303e-02 -6.245113e+00 4.457202e-01 1.287087e-03 -8.951714e-01 3.163874e+02 +-8.947416e-01 5.127203e-02 -4.436312e-01 2.797697e+02 4.474510e-02 9.986811e-01 2.517658e-02 -6.246545e+00 4.443370e-01 2.676216e-03 -8.958557e-01 3.153803e+02 +-8.954119e-01 4.959514e-02 -4.424679e-01 2.792737e+02 4.370207e-02 9.987679e-01 2.351064e-02 -6.237328e+00 4.430888e-01 1.714949e-03 -8.964761e-01 3.143712e+02 +-8.960501e-01 4.833165e-02 -4.413142e-01 2.787756e+02 4.301650e-02 9.988310e-01 2.204830e-02 -6.230924e+00 4.418640e-01 7.725906e-04 -8.970817e-01 3.133551e+02 +-8.970755e-01 4.804538e-02 -4.392576e-01 2.782765e+02 4.291812e-02 9.988450e-01 2.160260e-02 -6.225841e+00 4.397882e-01 5.270555e-04 -8.981014e-01 3.123343e+02 +-8.983948e-01 4.928174e-02 -4.364150e-01 2.777746e+02 4.442022e-02 9.987849e-01 2.134432e-02 -6.219071e+00 4.369366e-01 -2.100168e-04 -8.994923e-01 3.113089e+02 +-8.998492e-01 5.172694e-02 -4.331233e-01 2.772736e+02 4.607591e-02 9.986605e-01 2.354132e-02 -6.210278e+00 4.337608e-01 1.227092e-03 -9.010272e-01 3.102779e+02 +-9.011470e-01 5.614749e-02 -4.298622e-01 2.767669e+02 4.977398e-02 9.984203e-01 2.606681e-02 -6.202222e+00 4.306468e-01 2.094073e-03 -9.025181e-01 3.092348e+02 +-9.022378e-01 5.925681e-02 -4.271482e-01 2.762642e+02 5.425785e-02 9.982414e-01 2.387728e-02 -6.192530e+00 4.278120e-01 -1.633158e-03 -9.038663e-01 3.081930e+02 +-9.033140e-01 5.799357e-02 -4.250419e-01 2.757614e+02 5.518701e-02 9.982967e-01 1.892427e-02 -6.178870e+00 4.254154e-01 -6.362232e-03 -9.049759e-01 3.071437e+02 +-9.037670e-01 5.871917e-02 -4.239779e-01 2.752612e+02 5.682440e-02 9.982373e-01 1.712277e-02 -6.172594e+00 4.242360e-01 -8.617291e-03 -9.055107e-01 3.060879e+02 +-9.040938e-01 5.977936e-02 -4.231323e-01 2.747571e+02 5.661977e-02 9.981945e-01 2.004544e-02 -6.167462e+00 4.235667e-01 -5.834692e-03 -9.058462e-01 3.050224e+02 +-9.042909e-01 6.106776e-02 -4.225265e-01 2.742497e+02 5.557007e-02 9.981334e-01 2.532925e-02 -6.155320e+00 4.232846e-01 -5.748121e-04 -9.059966e-01 3.039501e+02 +-9.041006e-01 6.633247e-02 -4.221399e-01 2.737329e+02 5.970070e-02 9.977971e-01 2.892625e-02 -6.132891e+00 4.231287e-01 9.501916e-04 -9.060691e-01 3.028737e+02 +-9.037250e-01 7.138555e-02 -4.221198e-01 2.732074e+02 6.470292e-02 9.974488e-01 3.015684e-02 -6.104603e+00 4.231957e-01 -5.889258e-05 -9.060383e-01 3.017936e+02 +-9.032418e-01 7.486830e-02 -4.225506e-01 2.726821e+02 6.956191e-02 9.971849e-01 2.798798e-02 -6.074917e+00 4.234565e-01 -4.113504e-03 -9.059071e-01 3.007149e+02 +-9.027158e-01 7.694415e-02 -4.233011e-01 2.721504e+02 7.317277e-02 9.970013e-01 2.518119e-02 -6.047468e+00 4.239693e-01 -8.242658e-03 -9.056390e-01 2.996269e+02 +-9.021592e-01 7.828426e-02 -4.242409e-01 2.716196e+02 7.432450e-02 9.968976e-01 2.590247e-02 -6.031263e+00 4.249526e-01 -8.163343e-03 -9.051788e-01 2.985319e+02 +-9.015571e-01 7.742662e-02 -4.256758e-01 2.710884e+02 7.268283e-02 9.969785e-01 2.740344e-02 -6.015913e+00 4.265114e-01 -6.233549e-03 -9.044607e-01 2.974265e+02 +-9.008084e-01 7.370343e-02 -4.279159e-01 2.705583e+02 6.796444e-02 9.972749e-01 2.869646e-02 -5.995819e+00 4.288648e-01 -3.233046e-03 -9.033629e-01 2.963192e+02 +-8.995880e-01 6.767848e-02 -4.314639e-01 2.700244e+02 6.123527e-02 9.977070e-01 2.882467e-02 -5.973983e+00 4.324254e-01 -4.904797e-04 -9.016696e-01 2.952057e+02 +-8.975389e-01 6.334888e-02 -4.363609e-01 2.694809e+02 5.547385e-02 9.979856e-01 3.078036e-02 -5.950288e+00 4.374318e-01 3.419950e-03 -8.992451e-01 2.940850e+02 +-8.952662e-01 5.727789e-02 -4.418345e-01 2.689275e+02 4.787044e-02 9.983272e-01 3.242234e-02 -5.918089e+00 4.429525e-01 7.875812e-03 -8.965105e-01 2.929582e+02 +-8.923206e-01 5.366846e-02 -4.482004e-01 2.683638e+02 4.446031e-02 9.985285e-01 3.105007e-02 -5.891283e+00 4.492073e-01 7.779484e-03 -8.933937e-01 2.918360e+02 +-8.891300e-01 4.944362e-02 -4.549759e-01 2.677911e+02 4.098895e-02 9.987549e-01 2.843572e-02 -5.865611e+00 4.558154e-01 6.634072e-03 -8.900496e-01 2.907161e+02 +-8.854176e-01 4.747641e-02 -4.623652e-01 2.672086e+02 3.934805e-02 9.988549e-01 2.721357e-02 -5.843987e+00 4.631278e-01 5.902203e-03 -8.862719e-01 2.895972e+02 +-8.814965e-01 5.004647e-02 -4.695309e-01 2.666116e+02 4.053792e-02 9.987171e-01 3.034571e-02 -5.821991e+00 4.704472e-01 7.715835e-03 -8.823944e-01 2.884772e+02 +-8.773487e-01 5.507591e-02 -4.766821e-01 2.659998e+02 4.436966e-02 9.984467e-01 3.369691e-02 -5.798888e+00 4.777976e-01 8.413714e-03 -8.784297e-01 2.873607e+02 +-8.728797e-01 5.965390e-02 -4.842752e-01 2.653708e+02 4.903663e-02 9.981984e-01 3.457409e-02 -5.766157e+00 4.854653e-01 6.431796e-03 -8.742323e-01 2.862456e+02 +-8.682714e-01 6.427226e-02 -4.919083e-01 2.647275e+02 5.508276e-02 9.979309e-01 3.316169e-02 -5.735854e+00 4.930220e-01 1.697682e-03 -8.700152e-01 2.851321e+02 +-8.638225e-01 6.667247e-02 -4.993650e-01 2.640779e+02 6.039632e-02 9.977606e-01 2.873947e-02 -5.713348e+00 5.001629e-01 -5.334004e-03 -8.659149e-01 2.840260e+02 +-8.603225e-01 6.562000e-02 -5.055089e-01 2.634262e+02 6.042773e-02 9.978158e-01 2.668472e-02 -5.699383e+00 5.061558e-01 -7.589289e-03 -8.624087e-01 2.829142e+02 +-8.562507e-01 6.856313e-02 -5.119900e-01 2.627592e+02 6.134100e-02 9.976350e-01 3.101177e-02 -5.678579e+00 5.129055e-01 -4.852123e-03 -8.584314e-01 2.818001e+02 +-8.522218e-01 7.075028e-02 -5.183747e-01 2.620850e+02 6.066850e-02 9.974939e-01 3.640221e-02 -5.650502e+00 5.196512e-01 -4.262563e-04 -8.543784e-01 2.806824e+02 +-8.484455e-01 7.618873e-02 -5.237704e-01 2.613981e+02 6.415119e-02 9.970926e-01 4.112192e-02 -5.615581e+00 5.253806e-01 1.289218e-03 -8.508664e-01 2.795749e+02 +-8.454174e-01 8.287708e-02 -5.276370e-01 2.607017e+02 6.982619e-02 9.965593e-01 4.465129e-02 -5.580890e+00 5.295222e-01 9.060968e-04 -8.482956e-01 2.784716e+02 +-8.436768e-01 8.340418e-02 -5.303332e-01 2.600079e+02 7.360722e-02 9.965000e-01 3.961960e-02 -5.552909e+00 5.317815e-01 -5.610213e-03 -8.468631e-01 2.773788e+02 +-8.422105e-01 8.393346e-02 -5.325755e-01 2.593100e+02 7.699876e-02 9.964072e-01 3.526779e-02 -5.524957e+00 5.336223e-01 -1.130475e-02 -8.456474e-01 2.762824e+02 +-8.415617e-01 7.886660e-02 -5.343726e-01 2.586205e+02 7.045943e-02 9.968590e-01 3.616007e-02 -5.507853e+00 5.355460e-01 -7.220657e-03 -8.444752e-01 2.751763e+02 +-8.405671e-01 7.746499e-02 -5.361400e-01 2.579216e+02 6.845378e-02 9.969780e-01 3.672720e-02 -5.481663e+00 5.373649e-01 -5.829128e-03 -8.433297e-01 2.740682e+02 +-8.403847e-01 7.249271e-02 -5.371205e-01 2.572191e+02 6.243674e-02 9.973658e-01 3.692075e-02 -5.441580e+00 5.383821e-01 -2.508419e-03 -8.426971e-01 2.729511e+02 +-8.394711e-01 7.313072e-02 -5.384609e-01 2.565064e+02 6.251026e-02 9.973208e-01 3.799581e-02 -5.405962e+00 5.397970e-01 -1.762937e-03 -8.417934e-01 2.718377e+02 +-8.393124e-01 7.355515e-02 -5.386504e-01 2.557891e+02 6.128197e-02 9.972905e-01 4.069644e-02 -5.369266e+00 5.401844e-01 1.147475e-03 -8.415459e-01 2.707199e+02 +-8.391100e-01 7.504548e-02 -5.387602e-01 2.550632e+02 6.207627e-02 9.971781e-01 4.221715e-02 -5.336740e+00 5.404081e-01 1.980619e-03 -8.414007e-01 2.696047e+02 +-8.391748e-01 7.440227e-02 -5.387486e-01 2.543441e+02 6.156559e-02 9.972264e-01 4.182219e-02 -5.309147e+00 5.403660e-01 1.927755e-03 -8.414279e-01 2.684880e+02 +-8.392640e-01 7.334804e-02 -5.387542e-01 2.536233e+02 6.078927e-02 9.973049e-01 4.108023e-02 -5.278394e+00 5.403154e-01 1.726684e-03 -8.414608e-01 2.673677e+02 +-8.393897e-01 7.175603e-02 -5.387726e-01 2.528996e+02 5.865417e-02 9.974171e-01 4.145905e-02 -5.238637e+00 5.403560e-01 3.199043e-03 -8.414305e-01 2.662339e+02 +-8.392575e-01 6.931169e-02 -5.392984e-01 2.521739e+02 5.565435e-02 9.975830e-01 4.160194e-02 -5.198777e+00 5.408785e-01 4.900437e-03 -8.410865e-01 2.650970e+02 +-8.381963e-01 7.025822e-02 -5.408242e-01 2.514380e+02 5.570810e-02 9.975100e-01 4.324692e-02 -5.156093e+00 5.425161e-01 6.121121e-03 -8.400231e-01 2.639581e+02 +-8.369527e-01 7.149438e-02 -5.425852e-01 2.506944e+02 5.561690e-02 9.974088e-01 4.563419e-02 -5.106039e+00 5.444418e-01 8.016759e-03 -8.387603e-01 2.628188e+02 +-8.359746e-01 7.291528e-02 -5.439024e-01 2.499447e+02 5.707859e-02 9.973108e-01 4.596958e-02 -5.055052e+00 5.457916e-01 7.384219e-03 -8.378884e-01 2.616787e+02 +-8.351452e-01 7.271041e-02 -5.452024e-01 2.491941e+02 5.802736e-02 9.973395e-01 4.412253e-02 -5.006734e+00 5.469601e-01 5.212067e-03 -8.371425e-01 2.605417e+02 +-8.344639e-01 7.160077e-02 -5.463912e-01 2.484445e+02 5.677828e-02 9.974171e-01 4.399125e-02 -4.962316e+00 5.481298e-01 5.685966e-03 -8.363740e-01 2.593997e+02 +-8.340699e-01 7.057806e-02 -5.471254e-01 2.476968e+02 5.524232e-02 9.974827e-01 4.445866e-02 -4.923627e+00 5.488859e-01 6.857152e-03 -8.358692e-01 2.582539e+02 +-8.339589e-01 7.020059e-02 -5.473431e-01 2.469500e+02 5.423145e-02 9.975000e-01 4.530671e-02 -4.888359e+00 5.491554e-01 8.100729e-03 -8.356810e-01 2.571102e+02 +-8.341908e-01 7.152160e-02 -5.468185e-01 2.461994e+02 5.534538e-02 9.974059e-01 4.602531e-02 -4.849057e+00 5.486918e-01 8.130014e-03 -8.359852e-01 2.559586e+02 +-8.343967e-01 7.326092e-02 -5.462737e-01 2.454483e+02 5.776510e-02 9.972921e-01 4.551482e-02 -4.811242e+00 5.481289e-01 6.421867e-03 -8.363692e-01 2.548080e+02 +-8.346918e-01 7.318902e-02 -5.458323e-01 2.446968e+02 5.855420e-02 9.973059e-01 4.418418e-02 -4.782586e+00 5.475956e-01 4.919402e-03 -8.367287e-01 2.536505e+02 +-8.349647e-01 7.263637e-02 -5.454887e-01 2.439447e+02 5.850982e-02 9.973497e-01 4.324607e-02 -4.757824e+00 5.471842e-01 4.192496e-03 -8.370017e-01 2.524940e+02 +-8.353134e-01 7.194459e-02 -5.450463e-01 2.431934e+02 5.740441e-02 9.973951e-01 4.367800e-02 -4.733649e+00 5.467689e-01 5.196766e-03 -8.372675e-01 2.513346e+02 +-8.354766e-01 7.151444e-02 -5.448527e-01 2.424331e+02 5.621906e-02 9.974169e-01 4.470937e-02 -4.700391e+00 5.466427e-01 6.722527e-03 -8.373390e-01 2.501627e+02 +-8.356748e-01 7.146343e-02 -5.445555e-01 2.416681e+02 5.598503e-02 9.974179e-01 4.497917e-02 -4.669544e+00 5.463638e-01 7.101002e-03 -8.375179e-01 2.489953e+02 +-8.358609e-01 7.128616e-02 -5.442930e-01 2.408965e+02 5.608355e-02 9.974335e-01 4.450762e-02 -4.641583e+00 5.460689e-01 6.676299e-03 -8.377137e-01 2.478245e+02 +-8.359020e-01 7.160195e-02 -5.441884e-01 2.401220e+02 5.723851e-02 9.974204e-01 4.331493e-02 -4.609645e+00 5.458861e-01 5.058497e-03 -8.378441e-01 2.466494e+02 +-8.359638e-01 7.102442e-02 -5.441691e-01 2.393400e+02 5.726694e-02 9.974660e-01 4.221367e-02 -4.572481e+00 5.457884e-01 4.126203e-03 -8.379129e-01 2.454664e+02 +-8.360310e-01 7.159834e-02 -5.439907e-01 2.385567e+02 5.786306e-02 9.974258e-01 4.235135e-02 -4.533264e+00 5.456227e-01 3.930073e-03 -8.380218e-01 2.442774e+02 +-8.360472e-01 7.303779e-02 -5.437744e-01 2.377624e+02 5.900037e-02 9.973208e-01 4.324412e-02 -4.481768e+00 5.454760e-01 4.071238e-03 -8.381166e-01 2.430827e+02 +-8.359415e-01 7.468649e-02 -5.437129e-01 2.369720e+02 6.029722e-02 9.971981e-01 4.427392e-02 -4.434610e+00 5.454962e-01 4.226025e-03 -8.381027e-01 2.418870e+02 +-8.356078e-01 7.649730e-02 -5.439740e-01 2.361747e+02 6.230231e-02 9.970643e-01 4.451031e-02 -4.372865e+00 5.457820e-01 3.302324e-03 -8.379207e-01 2.406907e+02 +-8.353020e-01 7.767272e-02 -5.442771e-01 2.353731e+02 6.387974e-02 9.969765e-01 4.424039e-02 -4.312583e+00 5.460677e-01 2.185810e-03 -8.377382e-01 2.394897e+02 +-8.348003e-01 7.930841e-02 -5.448106e-01 2.345670e+02 6.669801e-02 9.968500e-01 4.291231e-02 -4.256278e+00 5.464978e-01 -5.145668e-04 -8.374604e-01 2.382906e+02 +-8.343157e-01 8.044212e-02 -5.453864e-01 2.337630e+02 6.988911e-02 9.967484e-01 4.010183e-02 -4.207516e+00 5.468389e-01 -4.658983e-03 -8.372249e-01 2.370915e+02 +-8.336597e-01 8.038696e-02 -5.463967e-01 2.329552e+02 6.942122e-02 9.967558e-01 4.072592e-02 -4.155400e+00 5.478980e-01 -3.979968e-03 -8.365357e-01 2.358834e+02 +-8.329051e-01 7.970906e-02 -5.476454e-01 2.321451e+02 6.722724e-02 9.968175e-01 4.284066e-02 -4.096135e+00 5.493173e-01 -1.134478e-03 -8.356131e-01 2.346727e+02 +-8.315409e-01 7.756522e-02 -5.500213e-01 2.313328e+02 6.531508e-02 9.969866e-01 4.185175e-02 -4.044611e+00 5.516102e-01 -1.123242e-03 -8.341013e-01 2.334576e+02 +-8.301769e-01 7.532081e-02 -5.523885e-01 2.305080e+02 6.130200e-02 9.971561e-01 4.383712e-02 -3.988775e+00 5.541194e-01 2.530049e-03 -8.324334e-01 2.322376e+02 +-8.285032e-01 7.743265e-02 -5.546049e-01 2.296780e+02 6.160388e-02 9.969854e-01 4.716915e-02 -3.935581e+00 5.565855e-01 4.913981e-03 -8.307758e-01 2.310254e+02 +-8.273640e-01 7.727603e-02 -5.563248e-01 2.288383e+02 6.166236e-02 9.970000e-01 4.678385e-02 -3.878331e+00 5.582711e-01 4.402973e-03 -8.296469e-01 2.298080e+02 +-8.261106e-01 7.595518e-02 -5.583655e-01 2.280110e+02 6.225761e-02 9.971105e-01 4.352715e-02 -3.828230e+00 5.600582e-01 1.195743e-03 -8.284524e-01 2.286000e+02 +-8.253044e-01 7.413242e-02 -5.598009e-01 2.271768e+02 6.086250e-02 9.972480e-01 4.233351e-02 -3.776462e+00 5.613987e-01 8.671534e-04 -8.275450e-01 2.273834e+02 +-8.244763e-01 7.368077e-02 -5.610793e-01 2.263429e+02 6.047309e-02 9.972815e-01 4.210075e-02 -3.730173e+00 5.626561e-01 7.808687e-04 -8.266907e-01 2.261691e+02 +-8.237673e-01 7.519617e-02 -5.619190e-01 2.255023e+02 6.124864e-02 9.971675e-01 4.365145e-02 -3.683781e+00 5.636098e-01 1.541867e-03 -8.260397e-01 2.249543e+02 +-8.230227e-01 7.843233e-02 -5.625673e-01 2.246597e+02 6.269722e-02 9.969128e-01 4.726365e-02 -3.642590e+00 5.645376e-01 3.627661e-03 -8.253994e-01 2.237400e+02 +-8.225294e-01 8.073553e-02 -5.629629e-01 2.238188e+02 6.487525e-02 9.967308e-01 4.815558e-02 -3.599783e+00 5.650103e-01 3.087028e-03 -8.250781e-01 2.225338e+02 +-8.219576e-01 8.268324e-02 -5.635150e-01 2.229726e+02 6.732684e-02 9.965747e-01 4.802046e-02 -3.553368e+00 5.655553e-01 1.531102e-03 -8.247090e-01 2.213224e+02 +-8.214204e-01 8.419771e-02 -5.640738e-01 2.221312e+02 6.879686e-02 9.964485e-01 4.855314e-02 -3.508581e+00 5.661586e-01 1.076033e-03 -8.242956e-01 2.201143e+02 +-8.208611e-01 8.701701e-02 -5.644600e-01 2.212857e+02 7.095651e-02 9.962059e-01 5.038700e-02 -3.462206e+00 5.667030e-01 1.308618e-03 -8.239211e-01 2.189014e+02 +-8.207267e-01 8.873351e-02 -5.643882e-01 2.204415e+02 7.200611e-02 9.960535e-01 5.188985e-02 -3.413363e+00 5.667652e-01 1.947987e-03 -8.238771e-01 2.176895e+02 +-8.206710e-01 8.987959e-02 -5.642878e-01 2.195985e+02 7.427387e-02 9.959525e-01 5.061498e-02 -3.365423e+00 5.665532e-01 -3.735878e-04 -8.240251e-01 2.164823e+02 +-8.209124e-01 8.953831e-02 -5.639909e-01 2.187523e+02 7.469057e-02 9.959821e-01 4.940534e-02 -3.323911e+00 5.661486e-01 -1.567343e-03 -8.243018e-01 2.152650e+02 +-8.214882e-01 8.754850e-02 -5.634646e-01 2.179152e+02 7.257949e-02 9.961600e-01 4.896340e-02 -3.294830e+00 5.655876e-01 -6.731167e-04 -8.246880e-01 2.140527e+02 +-8.222674e-01 8.679603e-02 -5.624436e-01 2.170823e+02 7.140150e-02 9.962260e-01 4.935136e-02 -3.261457e+00 5.646044e-01 4.207078e-04 -8.253616e-01 2.128457e+02 +-8.230883e-01 8.602853e-02 -5.613597e-01 2.162496e+02 7.006507e-02 9.962911e-01 4.994968e-02 -3.228696e+00 5.635748e-01 1.781294e-03 -8.260631e-01 2.116349e+02 +-8.240416e-01 8.540777e-02 -5.600544e-01 2.154206e+02 6.879136e-02 9.963407e-01 5.072421e-02 -3.192635e+00 5.623373e-01 3.271948e-03 -8.269015e-01 2.104252e+02 +-8.251835e-01 8.507933e-02 -5.584207e-01 2.145888e+02 6.763467e-02 9.963615e-01 5.185836e-02 -3.153158e+00 5.608010e-01 5.024072e-03 -8.279354e-01 2.092121e+02 +-8.262811e-01 8.427894e-02 -5.569171e-01 2.137621e+02 6.689205e-02 9.964279e-01 5.154498e-02 -3.109303e+00 5.592719e-01 5.337315e-03 -8.289671e-01 2.079977e+02 +-8.275933e-01 8.018811e-02 -5.555710e-01 2.129442e+02 6.499731e-02 9.967757e-01 4.704754e-02 -3.072154e+00 5.575524e-01 2.825618e-03 -8.301370e-01 2.067867e+02 +-8.291064e-01 7.434181e-02 -5.541263e-01 2.121282e+02 6.076407e-02 9.972310e-01 4.287130e-02 -3.043407e+00 5.557791e-01 1.873899e-03 -8.313279e-01 2.055715e+02 +-8.306242e-01 7.178885e-02 -5.521864e-01 2.113168e+02 5.764607e-02 9.974124e-01 4.295812e-02 -3.008559e+00 5.538415e-01 3.850686e-03 -8.326133e-01 2.043514e+02 +-8.321954e-01 7.065569e-02 -5.499624e-01 2.105077e+02 5.415290e-02 9.974631e-01 4.620439e-02 -2.973449e+00 5.518318e-01 8.669022e-03 -8.339104e-01 2.031273e+02 +-8.336440e-01 7.022476e-02 -5.478194e-01 2.096971e+02 5.276251e-02 9.974732e-01 4.757442e-02 -2.926410e+00 5.497761e-01 1.075580e-02 -8.352428e-01 2.019025e+02 +-8.350362e-01 7.147063e-02 -5.455332e-01 2.088938e+02 5.322343e-02 9.973699e-01 4.919809e-02 -2.877598e+00 5.476146e-01 1.204704e-02 -8.366440e-01 2.006766e+02 +-8.364829e-01 7.274593e-02 -5.431431e-01 2.080912e+02 5.509202e-02 9.972916e-01 4.872638e-02 -2.830389e+00 5.452168e-01 1.083594e-02 -8.382251e-01 1.994486e+02 +-8.381431e-01 7.582430e-02 -5.401544e-01 2.072968e+02 5.823237e-02 9.970698e-01 4.960634e-02 -2.782306e+00 5.423330e-01 1.012275e-02 -8.401026e-01 1.982190e+02 +-8.399410e-01 7.768546e-02 -5.370885e-01 2.065083e+02 5.940868e-02 9.969153e-01 5.128775e-02 -2.739469e+00 5.394161e-01 1.117097e-02 -8.419653e-01 1.969898e+02 +-8.419445e-01 7.926987e-02 -5.337094e-01 2.057261e+02 6.204032e-02 9.968113e-01 5.018203e-02 -2.692264e+00 5.359856e-01 9.138979e-03 -8.441777e-01 1.957626e+02 +-8.448038e-01 7.989996e-02 -5.290771e-01 2.049474e+02 6.351562e-02 9.967717e-01 4.911158e-02 -2.649982e+00 5.312932e-01 7.884985e-03 -8.471514e-01 1.945269e+02 +-8.482508e-01 8.135248e-02 -5.233090e-01 2.041777e+02 6.518645e-02 9.966557e-01 4.927486e-02 -2.609983e+00 5.255676e-01 7.684789e-03 -8.507172e-01 1.932912e+02 +-8.520227e-01 7.950032e-02 -5.174331e-01 2.034180e+02 6.501395e-02 9.968189e-01 4.610080e-02 -2.566175e+00 5.194521e-01 5.638564e-03 -8.544810e-01 1.920507e+02 +-8.558915e-01 7.491214e-02 -5.117011e-01 2.026710e+02 6.140036e-02 9.971742e-01 4.328395e-02 -2.525670e+00 5.134976e-01 5.627738e-03 -8.580726e-01 1.908019e+02 +-8.595604e-01 7.322885e-02 -5.057603e-01 2.019276e+02 5.838280e-02 9.972718e-01 4.517070e-02 -2.495624e+00 5.076883e-01 9.299245e-03 -8.614907e-01 1.895477e+02 +-8.632456e-01 7.165523e-02 -4.996725e-01 2.011914e+02 5.685893e-02 9.973767e-01 4.479746e-02 -2.463144e+00 5.015717e-01 1.026037e-02 -8.650553e-01 1.882897e+02 +-8.669950e-01 7.038727e-02 -4.933207e-01 2.004643e+02 5.504726e-02 9.974432e-01 4.557203e-02 -2.432069e+00 4.952671e-01 1.235477e-02 -8.686529e-01 1.870286e+02 +-8.702097e-01 7.299106e-02 -4.872446e-01 1.997399e+02 5.661486e-02 9.972283e-01 4.827548e-02 -2.396516e+00 4.894178e-01 1.442451e-02 -8.719301e-01 1.857593e+02 +-8.735174e-01 7.036193e-02 -4.816810e-01 1.990360e+02 5.516084e-02 9.974325e-01 4.566787e-02 -2.365728e+00 4.836577e-01 1.332175e-02 -8.751559e-01 1.844947e+02 +-8.765373e-01 6.998191e-02 -4.762194e-01 1.983350e+02 5.753889e-02 9.975141e-01 4.068077e-02 -2.332138e+00 4.778825e-01 8.257084e-03 -8.783850e-01 1.832268e+02 +-8.790918e-01 7.068422e-02 -4.713825e-01 1.976340e+02 5.785444e-02 9.974548e-01 4.167524e-02 -2.296499e+00 4.731285e-01 9.364789e-03 -8.809437e-01 1.819505e+02 +-8.810434e-01 7.188916e-02 -4.675408e-01 1.969379e+02 5.874698e-02 9.973614e-01 4.265049e-02 -2.259709e+00 4.693733e-01 1.011033e-02 -8.829420e-01 1.806706e+02 +-8.826940e-01 7.446654e-02 -4.640108e-01 1.962460e+02 6.127761e-02 9.971740e-01 4.346181e-02 -2.222020e+00 4.659360e-01 9.930003e-03 -8.847627e-01 1.793892e+02 +-8.838590e-01 7.671450e-02 -4.614197e-01 1.955681e+02 6.290070e-02 9.969925e-01 4.526997e-02 -2.192337e+00 4.635048e-01 1.098866e-02 -8.860263e-01 1.781185e+02 +-8.848656e-01 7.670394e-02 -4.594882e-01 1.948931e+02 6.399639e-02 9.970149e-01 4.319328e-02 -2.163373e+00 4.614297e-01 8.814664e-03 -8.871330e-01 1.768447e+02 +-8.860039e-01 7.612170e-02 -4.573867e-01 1.942255e+02 6.484825e-02 9.970801e-01 4.032399e-02 -2.140475e+00 4.591207e-01 6.066485e-03 -8.883532e-01 1.755669e+02 +-8.872465e-01 7.516758e-02 -4.551302e-01 1.935614e+02 6.427075e-02 9.971546e-01 3.939470e-02 -2.118641e+00 4.567964e-01 5.701248e-03 -8.895530e-01 1.742819e+02 +-8.886165e-01 7.375805e-02 -4.526814e-01 1.929115e+02 6.214268e-02 9.972452e-01 4.050061e-02 -2.097190e+00 4.544216e-01 7.858675e-03 -8.907521e-01 1.729934e+02 +-8.899063e-01 7.352605e-02 -4.501786e-01 1.922624e+02 6.133111e-02 9.972485e-01 4.163866e-02 -2.074170e+00 4.520015e-01 9.444556e-03 -8.919672e-01 1.717007e+02 +-8.911928e-01 7.318974e-02 -4.476814e-01 1.916241e+02 6.062180e-02 9.972616e-01 4.235964e-02 -2.057262e+00 4.495558e-01 1.061135e-02 -8.931893e-01 1.704083e+02 +-8.924915e-01 7.279541e-02 -4.451513e-01 1.909825e+02 6.028787e-02 9.972880e-01 4.221395e-02 -2.034913e+00 4.470171e-01 1.083837e-02 -8.944598e-01 1.691148e+02 +-8.936639e-01 7.327609e-02 -4.427138e-01 1.903511e+02 6.137728e-02 9.972653e-01 4.116670e-02 -2.020580e+00 4.445196e-01 9.616628e-03 -8.957175e-01 1.678245e+02 +-8.946869e-01 7.559667e-02 -4.402505e-01 1.897169e+02 6.390820e-02 9.970992e-01 4.133913e-02 -2.001701e+00 4.420985e-01 8.849961e-03 -8.969229e-01 1.665277e+02 +-8.957902e-01 7.754814e-02 -4.376598e-01 1.890788e+02 6.606217e-02 9.969548e-01 4.143441e-02 -1.973567e+00 4.395403e-01 8.203789e-03 -8.981854e-01 1.652293e+02 +-8.967517e-01 7.889996e-02 -4.354436e-01 1.884436e+02 6.789400e-02 9.968577e-01 4.080437e-02 -1.943196e+00 4.372949e-01 7.027382e-03 -8.992907e-01 1.639267e+02 +-8.977014e-01 7.685789e-02 -4.338491e-01 1.878155e+02 6.679140e-02 9.970268e-01 3.842502e-02 -1.916448e+00 4.355125e-01 5.516813e-03 -9.001658e-01 1.626218e+02 +-8.987551e-01 7.331569e-02 -4.322777e-01 1.871967e+02 6.294392e-02 9.972828e-01 3.827478e-02 -1.897174e+00 4.339093e-01 7.190400e-03 -9.009279e-01 1.613122e+02 +-8.996774e-01 7.036514e-02 -4.308472e-01 1.865774e+02 5.750957e-02 9.974267e-01 4.280873e-02 -1.867717e+00 4.327507e-01 1.373622e-02 -9.014090e-01 1.599954e+02 +-9.002713e-01 6.855483e-02 -4.298975e-01 1.859593e+02 5.482691e-02 9.975146e-01 4.425561e-02 -1.830138e+00 4.318630e-01 1.627210e-02 -9.017924e-01 1.586816e+02 +-9.008757e-01 6.674094e-02 -4.289157e-01 1.853379e+02 5.295827e-02 9.976267e-01 4.400340e-02 -1.793453e+00 4.308346e-01 1.692696e-02 -9.022722e-01 1.573672e+02 +-9.011685e-01 6.717102e-02 -4.282328e-01 1.847174e+02 5.337545e-02 9.975977e-01 4.415682e-02 -1.759653e+00 4.301702e-01 1.693562e-02 -9.025890e-01 1.560529e+02 +-9.015095e-01 6.873337e-02 -4.272661e-01 1.840940e+02 5.471581e-02 9.974867e-01 4.501602e-02 -1.723898e+00 4.292863e-01 1.720416e-02 -9.030046e-01 1.547379e+02 +-9.018935e-01 6.901115e-02 -4.264100e-01 1.834754e+02 5.533306e-02 9.974802e-01 4.440034e-02 -1.691006e+00 4.283997e-01 1.644981e-02 -9.034396e-01 1.534234e+02 +-9.022434e-01 6.891141e-02 -4.256854e-01 1.828561e+02 5.663415e-02 9.975343e-01 4.144782e-02 -1.658461e+00 4.274920e-01 1.328769e-02 -9.039215e-01 1.521113e+02 +-9.026764e-01 6.739116e-02 -4.250102e-01 1.822396e+02 5.579145e-02 9.976530e-01 3.969643e-02 -1.628241e+00 4.266879e-01 1.212110e-02 -9.043177e-01 1.507945e+02 +-9.032096e-01 6.580403e-02 -4.241252e-01 1.816264e+02 5.428192e-02 9.977556e-01 3.920638e-02 -1.599462e+00 4.257533e-01 1.238925e-02 -9.047545e-01 1.494822e+02 +-9.036507e-01 6.591464e-02 -4.231675e-01 1.810079e+02 5.419613e-02 9.977416e-01 3.968033e-02 -1.567602e+00 4.248274e-01 1.292312e-02 -9.051822e-01 1.481610e+02 +-9.043364e-01 6.440909e-02 -4.219327e-01 1.803984e+02 5.238248e-02 9.978237e-01 4.004801e-02 -1.538408e+00 4.235939e-01 1.411499e-02 -9.057422e-01 1.468462e+02 +-9.050003e-01 6.557055e-02 -4.203273e-01 1.797913e+02 5.400966e-02 9.977642e-01 3.936269e-02 -1.513016e+00 4.219686e-01 1.292151e-02 -9.065184e-01 1.455320e+02 +-9.058615e-01 6.514793e-02 -4.185340e-01 1.791934e+02 5.333701e-02 9.977802e-01 3.987106e-02 -1.493297e+00 4.202025e-01 1.379430e-02 -9.073255e-01 1.442183e+02 +-9.063892e-01 6.662174e-02 -4.171572e-01 1.785921e+02 5.498188e-02 9.976909e-01 3.987212e-02 -1.469178e+00 4.188504e-01 1.320357e-02 -9.079593e-01 1.429000e+02 +-9.069569e-01 6.718552e-02 -4.158309e-01 1.779971e+02 5.616391e-02 9.976714e-01 3.869567e-02 -1.448292e+00 4.174624e-01 1.174062e-02 -9.086184e-01 1.415813e+02 +-9.073883e-01 6.772254e-02 -4.148013e-01 1.773991e+02 5.770503e-02 9.976606e-01 3.665192e-02 -1.429391e+00 4.163131e-01 9.321406e-03 -9.091735e-01 1.402613e+02 +-9.073894e-01 6.954409e-02 -4.144975e-01 1.767950e+02 5.991525e-02 9.975466e-01 3.620538e-02 -1.403805e+00 4.159985e-01 8.017660e-03 -9.093300e-01 1.389334e+02 +-9.071036e-01 6.932708e-02 -4.151588e-01 1.761909e+02 5.960111e-02 9.975600e-01 3.635611e-02 -1.378192e+00 4.166663e-01 8.234832e-03 -9.090222e-01 1.376093e+02 +-9.061817e-01 6.872212e-02 -4.172674e-01 1.755805e+02 5.897646e-02 9.976020e-01 3.622129e-02 -1.356294e+00 4.187560e-01 8.214112e-03 -9.080616e-01 1.362825e+02 +-9.047567e-01 6.697143e-02 -4.206308e-01 1.749745e+02 5.676019e-02 9.977107e-01 3.676379e-02 -1.339824e+00 4.221300e-01 9.387199e-03 -9.064867e-01 1.349677e+02 +-9.028955e-01 6.532034e-02 -4.248682e-01 1.743678e+02 5.382342e-02 9.977877e-01 3.902136e-02 -1.338454e+00 4.264772e-01 1.236435e-02 -9.044138e-01 1.336595e+02 +-9.005833e-01 6.373239e-02 -4.299860e-01 1.737570e+02 5.107090e-02 9.978557e-01 4.093655e-02 -1.333086e+00 4.316730e-01 1.490699e-02 -9.019070e-01 1.323552e+02 +-8.977117e-01 6.318934e-02 -4.360284e-01 1.731371e+02 4.898327e-02 9.978405e-01 4.375874e-02 -1.319906e+00 4.378519e-01 1.792464e-02 -8.988684e-01 1.310518e+02 +-8.944411e-01 6.309100e-02 -4.427128e-01 1.725081e+02 4.747104e-02 9.977995e-01 4.628765e-02 -1.314911e+00 4.446590e-01 2.038554e-02 -8.954680e-01 1.297562e+02 +-8.904618e-01 6.234432e-02 -4.507671e-01 1.718688e+02 4.568308e-02 9.978136e-01 4.776078e-02 -1.301640e+00 4.527592e-01 2.193672e-02 -8.913629e-01 1.284701e+02 +-8.861893e-01 5.950836e-02 -4.594859e-01 1.712217e+02 4.302662e-02 9.980019e-01 4.626855e-02 -1.291648e+00 4.613212e-01 2.123257e-02 -8.869791e-01 1.271942e+02 +-8.815786e-01 5.651076e-02 -4.686424e-01 1.705599e+02 4.060381e-02 9.982066e-01 4.398661e-02 -1.269147e+00 4.702877e-01 1.974899e-02 -8.822922e-01 1.259232e+02 +-8.766860e-01 5.405509e-02 -4.780164e-01 1.698906e+02 3.756246e-02 9.983250e-01 4.400284e-02 -1.252480e+00 4.795943e-01 2.062120e-02 -8.772480e-01 1.246632e+02 +-8.716465e-01 5.222252e-02 -4.873450e-01 1.692041e+02 3.477097e-02 9.983909e-01 4.479477e-02 -1.225261e+00 4.889001e-01 2.209975e-02 -8.720598e-01 1.234037e+02 +-8.663365e-01 5.291215e-02 -4.966501e-01 1.685037e+02 3.513749e-02 9.983656e-01 4.507157e-02 -1.187189e+00 4.982233e-01 2.159611e-02 -8.667798e-01 1.221584e+02 +-8.609350e-01 5.393929e-02 -5.058473e-01 1.677891e+02 3.595967e-02 9.983282e-01 4.525119e-02 -1.147426e+00 5.074424e-01 2.076824e-02 -8.614354e-01 1.209254e+02 +-8.552869e-01 5.547654e-02 -5.151763e-01 1.670593e+02 3.697560e-02 9.982518e-01 4.611010e-02 -1.099363e+00 5.168337e-01 2.038842e-02 -8.558430e-01 1.196982e+02 +-8.494682e-01 5.633122e-02 -5.246243e-01 1.663130e+02 3.759195e-02 9.982193e-01 4.631461e-02 -1.050423e+00 5.262991e-01 1.962114e-02 -8.500731e-01 1.184798e+02 +-8.431222e-01 5.832446e-02 -5.345496e-01 1.655516e+02 3.975068e-02 9.981405e-01 4.620964e-02 -1.000403e+00 5.362508e-01 1.771166e-02 -8.438729e-01 1.172712e+02 +-8.363705e-01 5.926961e-02 -5.449510e-01 1.647788e+02 4.117774e-02 9.981217e-01 4.535905e-02 -9.559157e-01 5.466158e-01 1.549712e-02 -8.372401e-01 1.160757e+02 +-8.293000e-01 6.327404e-02 -5.552097e-01 1.639882e+02 4.510394e-02 9.979062e-01 4.635524e-02 -9.072749e-01 5.569804e-01 1.340026e-02 -8.304176e-01 1.148861e+02 +-8.223615e-01 6.692907e-02 -5.650151e-01 1.631839e+02 4.766682e-02 9.976704e-01 4.880189e-02 -8.530526e-01 5.669652e-01 1.320032e-02 -8.236360e-01 1.136987e+02 +-8.151020e-01 7.093877e-02 -5.749577e-01 1.623689e+02 5.058589e-02 9.973989e-01 5.134572e-02 -7.970086e-01 5.771047e-01 1.276725e-02 -8.165704e-01 1.125249e+02 +-8.081293e-01 7.323609e-02 -5.844344e-01 1.615379e+02 5.312542e-02 9.972585e-01 5.150814e-02 -7.319776e-01 5.866045e-01 1.057691e-02 -8.098045e-01 1.113593e+02 +-8.017021e-01 7.391794e-02 -5.931356e-01 1.606957e+02 5.457222e-02 9.972312e-01 5.051565e-02 -6.740054e-01 5.952274e-01 8.129779e-03 -8.035162e-01 1.102072e+02 +-7.958682e-01 7.432307e-02 -6.008910e-01 1.598427e+02 5.716497e-02 9.972278e-01 4.763140e-02 -6.211831e-01 6.027654e-01 3.558405e-03 -7.979106e-01 1.090673e+02 +-7.910180e-01 7.405812e-02 -6.072939e-01 1.589856e+02 5.706647e-02 9.972501e-01 4.728170e-02 -5.765532e-01 6.091256e-01 2.744565e-03 -7.930691e-01 1.079364e+02 +-7.866383e-01 7.542768e-02 -6.127894e-01 1.581195e+02 5.958465e-02 9.971512e-01 4.624960e-02 -5.347641e-01 6.145323e-01 -1.311339e-04 -7.888917e-01 1.068144e+02 +-7.817809e-01 8.326866e-02 -6.179684e-01 1.572435e+02 6.932114e-02 9.965064e-01 4.657816e-02 -4.927866e-01 6.196880e-01 -6.424356e-03 -7.848220e-01 1.057015e+02 +-7.780186e-01 8.291919e-02 -6.227451e-01 1.563646e+02 6.745975e-02 9.965468e-01 4.841135e-02 -4.529211e-01 6.246089e-01 -4.345290e-03 -7.809257e-01 1.045828e+02 +-7.735804e-01 8.502973e-02 -6.279676e-01 1.554772e+02 7.141975e-02 9.963417e-01 4.692881e-02 -4.077761e-01 6.296607e-01 -8.546080e-03 -7.768233e-01 1.034761e+02 +-7.698016e-01 8.429116e-02 -6.326930e-01 1.545860e+02 7.116919e-02 9.963959e-01 4.615387e-02 -3.679821e-01 6.343031e-01 -9.498914e-03 -7.730261e-01 1.023734e+02 +-7.669190e-01 7.972096e-02 -6.367730e-01 1.536880e+02 6.560614e-02 9.967949e-01 4.577908e-02 -3.334109e-01 6.383817e-01 -6.667371e-03 -7.696911e-01 1.012674e+02 +-7.631023e-01 8.229691e-02 -6.410165e-01 1.527745e+02 6.844955e-02 9.965722e-01 4.645878e-02 -2.892147e-01 6.426427e-01 -8.424487e-03 -7.661197e-01 1.001709e+02 +-7.601341e-01 8.190277e-02 -6.445836e-01 1.518524e+02 6.639836e-02 9.966219e-01 4.833268e-02 -2.442347e-01 6.463648e-01 -6.059971e-03 -7.630045e-01 9.907539e+01 +-7.571017e-01 8.487139e-02 -6.477606e-01 1.509254e+02 6.689526e-02 9.963851e-01 5.236208e-02 -1.973161e-01 6.498631e-01 -3.688688e-03 -7.600424e-01 9.798333e+01 +-7.551083e-01 8.288132e-02 -6.503400e-01 1.499968e+02 6.545136e-02 9.965512e-01 5.100813e-02 -1.608566e-01 6.523248e-01 -4.048976e-03 -7.579288e-01 9.689467e+01 +-7.525776e-01 8.042325e-02 -6.535741e-01 1.490651e+02 6.378605e-02 9.967499e-01 4.920321e-02 -1.242710e-01 6.554070e-01 -4.659675e-03 -7.552615e-01 9.581217e+01 +-7.497644e-01 8.022388e-02 -6.568238e-01 1.481228e+02 6.210045e-02 9.967733e-01 5.085739e-02 -8.815912e-02 6.587845e-01 -2.657990e-03 -7.523271e-01 9.473231e+01 +-7.460048e-01 8.198716e-02 -6.608744e-01 1.471724e+02 6.066746e-02 9.966328e-01 5.515859e-02 -4.870237e-02 6.631714e-01 1.055009e-03 -7.484668e-01 9.365294e+01 +-7.410215e-01 8.285961e-02 -6.663493e-01 1.462110e+02 6.275869e-02 9.965597e-01 5.412933e-02 -9.133589e-03 6.685420e-01 -1.708207e-03 -7.436724e-01 9.258995e+01 +-7.354617e-01 8.183942e-02 -6.726057e-01 1.452437e+02 6.244496e-02 9.966409e-01 5.298596e-02 3.354205e-02 6.746827e-01 -3.031691e-03 -7.381016e-01 9.153357e+01 +-7.294443e-01 8.043401e-02 -6.792948e-01 1.442674e+02 6.195308e-02 9.967497e-01 5.149646e-02 7.418165e-02 6.812290e-01 -4.520607e-03 -7.320565e-01 9.048009e+01 +-7.238230e-01 8.117976e-02 -6.851935e-01 1.432904e+02 6.394308e-02 9.966732e-01 5.053499e-02 1.062278e-01 6.870164e-01 -7.234983e-03 -7.266059e-01 8.943889e+01 +-7.201385e-01 8.165724e-02 -6.890085e-01 1.423027e+02 6.436666e-02 9.966304e-01 5.084002e-02 1.411781e-01 6.908383e-01 -7.737312e-03 -7.229679e-01 8.839577e+01 +-7.174781e-01 8.327108e-02 -6.915859e-01 1.413079e+02 6.548759e-02 9.964952e-01 5.204465e-02 1.771185e-01 6.934959e-01 -7.949397e-03 -7.204167e-01 8.735817e+01 +-7.155010e-01 8.311830e-02 -6.936495e-01 1.403139e+02 6.352381e-02 9.965244e-01 5.388614e-02 2.174687e-01 6.957177e-01 -5.507672e-03 -7.182942e-01 8.631851e+01 +-7.140149e-01 8.334587e-02 -6.951519e-01 1.393137e+02 6.242863e-02 9.965131e-01 5.535524e-02 2.617249e-01 6.973417e-01 -3.872916e-03 -7.167284e-01 8.527435e+01 +-7.138191e-01 8.314616e-02 -6.953769e-01 1.383142e+02 6.179530e-02 9.965322e-01 5.572114e-02 3.120142e-01 6.975985e-01 -3.196205e-03 -7.164818e-01 8.423145e+01 +-7.148367e-01 8.418998e-02 -6.942049e-01 1.373153e+02 6.201580e-02 9.964470e-01 5.698563e-02 3.567841e-01 6.965361e-01 -2.316246e-03 -7.175181e-01 8.318854e+01 +-7.164653e-01 8.353893e-02 -6.926029e-01 1.363147e+02 6.032979e-02 9.965044e-01 5.778598e-02 4.013861e-01 6.950092e-01 -3.829371e-04 -7.190007e-01 8.213856e+01 +-7.179351e-01 8.286799e-02 -6.911600e-01 1.353103e+02 5.953763e-02 9.965605e-01 5.764054e-02 4.566198e-01 6.935593e-01 2.321419e-04 -7.203995e-01 8.108492e+01 +-7.195728e-01 7.804806e-02 -6.900170e-01 1.343094e+02 5.601636e-02 9.969495e-01 5.434960e-02 5.125537e-01 6.921540e-01 4.562584e-04 -7.217497e-01 8.002269e+01 +-7.203942e-01 7.407905e-02 -6.895973e-01 1.333064e+02 5.720976e-02 9.972381e-01 4.736227e-02 5.657173e-01 6.912013e-01 -5.332185e-03 -7.226426e-01 7.896729e+01 +-7.210188e-01 7.317189e-02 -6.890412e-01 1.322985e+02 5.759628e-02 9.972963e-01 4.563745e-02 6.153770e-01 6.905176e-01 -6.780744e-03 -7.232838e-01 7.790983e+01 +-7.214751e-01 7.606229e-02 -6.882501e-01 1.312937e+02 6.008219e-02 9.970764e-01 4.720978e-02 6.605680e-01 6.898289e-01 -7.290893e-03 -7.239358e-01 7.685485e+01 +-7.220112e-01 7.996138e-02 -6.872452e-01 1.302785e+02 6.379703e-02 9.967617e-01 4.894948e-02 7.034505e-01 6.889338e-01 -8.502130e-03 -7.247744e-01 7.579851e+01 +-7.221122e-01 8.304786e-02 -6.867729e-01 1.292668e+02 6.587029e-02 9.965115e-01 5.124318e-02 7.491655e-01 6.886328e-01 -8.234595e-03 -7.250635e-01 7.473742e+01 +-7.219661e-01 8.272952e-02 -6.869649e-01 1.282570e+02 6.585030e-02 9.965353e-01 5.080497e-02 7.936834e-01 6.887879e-01 -8.557376e-03 -7.249125e-01 7.368027e+01 +-7.217536e-01 8.098674e-02 -6.873958e-01 1.272497e+02 6.505227e-02 9.966721e-01 4.912097e-02 8.404890e-01 6.890864e-01 -9.263417e-03 -7.246200e-01 7.262571e+01 +-7.212928e-01 7.897258e-02 -6.881133e-01 1.262377e+02 6.379899e-02 9.968303e-01 4.752783e-02 8.852947e-01 6.896857e-01 -9.619449e-03 -7.240450e-01 7.157194e+01 +-7.207012e-01 7.828972e-02 -6.888109e-01 1.252240e+02 6.235439e-02 9.968960e-01 4.806522e-02 9.298618e-01 6.904359e-01 -8.309720e-03 -7.233459e-01 7.051005e+01 +-7.198700e-01 7.865828e-02 -6.896376e-01 1.242085e+02 6.150943e-02 9.968785e-01 4.949553e-02 9.752163e-01 6.913782e-01 -6.788867e-03 -7.224612e-01 6.945053e+01 +-7.190312e-01 7.984604e-02 -6.903757e-01 1.231901e+02 6.120461e-02 9.967936e-01 5.154009e-02 1.022705e+00 6.922775e-01 -5.195243e-03 -7.216127e-01 6.838762e+01 +-7.181525e-01 8.022173e-02 -6.912463e-01 1.221716e+02 6.018154e-02 9.967711e-01 5.315501e-02 1.071057e+00 6.932786e-01 -3.426858e-03 -7.206616e-01 6.732586e+01 +-7.166091e-01 7.967913e-02 -6.929088e-01 1.211533e+02 6.010259e-02 9.968123e-01 5.246736e-02 1.120069e+00 6.948807e-01 -4.047025e-03 -7.191137e-01 6.626941e+01 +-7.145146e-01 7.825262e-02 -6.952305e-01 1.201303e+02 5.975405e-02 9.969197e-01 5.079821e-02 1.165661e+00 6.970642e-01 -5.246773e-03 -7.169896e-01 6.520837e+01 +-7.124096e-01 7.783665e-02 -6.974339e-01 1.191042e+02 5.940893e-02 9.969515e-01 5.057955e-02 1.209751e+00 6.992448e-01 -5.400439e-03 -7.148620e-01 6.415115e+01 +-7.104935e-01 7.973309e-02 -6.991720e-01 1.180723e+02 5.999491e-02 9.968061e-01 5.270871e-02 1.255636e+00 7.011416e-01 -4.497558e-03 -7.130079e-01 6.309459e+01 +-7.086540e-01 7.991840e-02 -7.010153e-01 1.170374e+02 5.905408e-02 9.967963e-01 5.394101e-02 1.302688e+00 7.030805e-01 -3.172297e-03 -7.111033e-01 6.203938e+01 +-7.069052e-01 7.926146e-02 -7.028532e-01 1.160037e+02 5.810932e-02 9.968502e-01 5.397150e-02 1.350429e+00 7.049173e-01 -2.689586e-03 -7.092845e-01 6.098618e+01 +-7.053287e-01 7.969043e-02 -7.043868e-01 1.149644e+02 5.676033e-02 9.968195e-01 5.593845e-02 1.396610e+00 7.066043e-01 -5.262252e-04 -7.076087e-01 5.993066e+01 +-7.038735e-01 8.111721e-02 -7.056784e-01 1.139160e+02 5.657740e-02 9.967040e-01 5.813774e-02 1.447362e+00 7.080686e-01 9.961680e-04 -7.061430e-01 5.887252e+01 +-7.024477e-01 8.161254e-02 -7.070407e-01 1.128614e+02 5.810358e-02 9.966638e-01 5.731715e-02 1.501676e+00 7.093597e-01 -8.192961e-04 -7.048462e-01 5.781724e+01 +-7.013997e-01 8.062119e-02 -7.081940e-01 1.117995e+02 5.918690e-02 9.967388e-01 5.485026e-02 1.557839e+00 7.103066e-01 -3.443850e-03 -7.038840e-01 5.676266e+01 +-7.004706e-01 8.124234e-02 -7.090420e-01 1.107301e+02 6.047375e-02 9.966831e-01 5.445772e-02 1.619507e+00 7.111145e-01 -4.732389e-03 -7.030603e-01 5.570318e+01 +-6.999090e-01 8.272734e-02 -7.094248e-01 1.096673e+02 6.039382e-02 9.965670e-01 5.662783e-02 1.669154e+00 7.116741e-01 -3.210542e-03 -7.025025e-01 5.464794e+01 +-6.995848e-01 8.275711e-02 -7.097411e-01 1.086092e+02 5.924154e-02 9.965684e-01 5.780793e-02 1.723896e+00 7.120896e-01 -1.604604e-03 -7.020868e-01 5.359484e+01 +-6.995025e-01 8.083553e-02 -7.100436e-01 1.075540e+02 5.599127e-02 9.967269e-01 5.831323e-02 1.770787e+00 7.124334e-01 1.034011e-03 -7.017390e-01 5.253619e+01 +-6.991618e-01 7.897100e-02 -7.105888e-01 1.064947e+02 5.303793e-02 9.968715e-01 5.860192e-02 1.818094e+00 7.129936e-01 3.284065e-03 -7.011629e-01 5.146890e+01 +-6.988268e-01 7.945825e-02 -7.108639e-01 1.054273e+02 5.226155e-02 9.968266e-01 6.004575e-02 1.866209e+00 7.133792e-01 4.810737e-03 -7.007618e-01 5.039425e+01 +-6.983077e-01 8.379052e-02 -7.108765e-01 1.043546e+02 5.616069e-02 9.964770e-01 6.228635e-02 1.929989e+00 7.135911e-01 3.571727e-03 -7.005533e-01 4.933792e+01 +-6.988514e-01 8.244614e-02 -7.104994e-01 1.032944e+02 5.952900e-02 9.965926e-01 5.709127e-02 1.986764e+00 7.127855e-01 -2.397000e-03 -7.013781e-01 4.829297e+01 +-6.996183e-01 7.655446e-02 -7.104039e-01 1.022413e+02 6.053999e-02 9.970196e-01 4.781989e-02 2.038214e+00 7.119475e-01 -9.552164e-03 -7.021678e-01 4.725024e+01 +-6.999592e-01 7.489533e-02 -7.102449e-01 1.011861e+02 5.776500e-02 9.971648e-01 4.822261e-02 2.080422e+00 7.118430e-01 -7.273435e-03 -7.023010e-01 4.619478e+01 +-7.001854e-01 7.664551e-02 -7.098351e-01 1.001264e+02 5.497249e-02 9.970571e-01 5.343359e-02 2.126949e+00 7.118416e-01 -1.607974e-03 -7.023383e-01 4.513248e+01 +-7.005527e-01 7.783209e-02 -7.093434e-01 9.906794e+01 5.543696e-02 9.969659e-01 5.464131e-02 2.177631e+00 7.114441e-01 -1.044722e-03 -7.027420e-01 4.407813e+01 +-7.007117e-01 8.045098e-02 -7.088940e-01 9.800747e+01 5.925343e-02 9.967514e-01 5.454986e-02 2.232330e+00 7.109797e-01 -3.780670e-03 -7.032024e-01 4.302679e+01 +-7.008569e-01 8.151134e-02 -7.086293e-01 9.695046e+01 6.110179e-02 9.966583e-01 5.421080e-02 2.284049e+00 7.106801e-01 -5.304499e-03 -7.034953e-01 4.197716e+01 +-7.006727e-01 8.325528e-02 -7.086087e-01 9.588352e+01 6.372672e-02 9.965017e-01 5.406718e-02 2.336259e+00 7.106312e-01 -7.273909e-03 -7.035271e-01 4.092257e+01 +-7.005236e-01 8.529065e-02 -7.085140e-01 9.481114e+01 6.607193e-02 9.963193e-01 5.460980e-02 2.393653e+00 7.105640e-01 -8.557429e-03 -7.035806e-01 3.986378e+01 +-7.005014e-01 8.588118e-02 -7.084646e-01 9.373932e+01 6.780896e-02 9.962510e-01 5.372034e-02 2.457325e+00 7.104222e-01 -1.040907e-02 -7.036988e-01 3.880375e+01 +-7.011986e-01 8.555260e-02 -7.078144e-01 9.267612e+01 6.841350e-02 9.962671e-01 5.264349e-02 2.514323e+00 7.096761e-01 -1.151051e-02 -7.044341e-01 3.774654e+01 +-7.017592e-01 8.635636e-02 -7.071609e-01 9.161683e+01 6.783740e-02 9.962157e-01 5.433567e-02 2.568850e+00 7.091771e-01 -9.841386e-03 -7.049618e-01 3.668818e+01 +-7.024330e-01 8.547277e-02 -7.065991e-01 9.056783e+01 6.539317e-02 9.963144e-01 5.551020e-02 2.614259e+00 7.087395e-01 -7.214554e-03 -7.054334e-01 3.563210e+01 +-7.030114e-01 8.294063e-02 -7.063256e-01 8.951786e+01 6.289991e-02 9.965353e-01 5.441392e-02 2.669990e+00 7.083916e-01 -6.174209e-03 -7.057927e-01 3.457590e+01 +-7.035844e-01 8.152497e-02 -7.059197e-01 8.846856e+01 5.971269e-02 9.966666e-01 5.558752e-02 2.728871e+00 7.080984e-01 -3.041849e-03 -7.061072e-01 3.351764e+01 +-7.040031e-01 8.194879e-02 -7.054530e-01 8.741579e+01 5.873776e-02 9.966358e-01 5.715697e-02 2.793597e+00 7.077637e-01 -1.198039e-03 -7.064482e-01 3.245897e+01 +-7.045754e-01 8.218016e-02 -7.048545e-01 8.636382e+01 5.923818e-02 9.966162e-01 5.698245e-02 2.860970e+00 7.071523e-01 -1.605861e-03 -7.070595e-01 3.140185e+01 +-7.051815e-01 8.189032e-02 -7.042819e-01 8.531517e+01 6.023356e-02 9.966361e-01 5.557331e-02 2.930328e+00 7.064637e-01 -3.232137e-03 -7.077419e-01 3.035063e+01 +-7.059207e-01 8.039266e-02 -7.037137e-01 8.426004e+01 5.992052e-02 9.967543e-01 5.376138e-02 3.003691e+00 7.057517e-01 -4.215617e-03 -7.084467e-01 2.929585e+01 +-7.065355e-01 7.912111e-02 -7.032406e-01 8.321354e+01 5.925772e-02 9.968549e-01 5.262011e-02 3.066811e+00 7.051922e-01 -4.494455e-03 -7.090019e-01 2.824202e+01 +-7.071929e-01 7.700247e-02 -7.028149e-01 8.216795e+01 5.753784e-02 9.970223e-01 5.134048e-02 3.127446e+00 7.046756e-01 -4.130825e-03 -7.095177e-01 2.718689e+01 +-7.076923e-01 7.721751e-02 -7.022884e-01 8.112354e+01 5.668639e-02 9.970107e-01 5.250007e-02 3.184640e+00 7.042431e-01 -2.656292e-03 -7.099540e-01 2.612944e+01 +-7.081811e-01 7.770944e-02 -7.017412e-01 8.007903e+01 5.624861e-02 9.969749e-01 5.363827e-02 3.244147e+00 7.037867e-01 -1.486359e-03 -7.104098e-01 2.507355e+01 +-7.088451e-01 7.698023e-02 -7.011509e-01 7.903821e+01 5.449049e-02 9.970325e-01 5.437702e-02 3.300776e+00 7.032563e-01 3.388291e-04 -7.109364e-01 2.401402e+01 +-7.087441e-01 7.983124e-02 -7.009343e-01 7.799268e+01 5.741401e-02 9.968079e-01 5.547539e-02 3.361621e+00 7.031256e-01 -9.255916e-04 -7.110651e-01 2.295797e+01 +-7.095660e-01 7.590212e-02 -7.005391e-01 7.695700e+01 5.215276e-02 9.971118e-01 5.521047e-02 3.417360e+00 7.027064e-01 2.640431e-03 -7.114751e-01 2.189557e+01 +-7.095525e-01 7.273468e-02 -7.008886e-01 7.592236e+01 5.070832e-02 9.973502e-01 5.216485e-02 3.474271e+00 7.028257e-01 1.472820e-03 -7.113606e-01 2.083925e+01 +-7.103097e-01 6.705837e-02 -7.006878e-01 7.489060e+01 4.477969e-02 9.977402e-01 5.009279e-02 3.526776e+00 7.024635e-01 4.204810e-03 -7.117074e-01 1.977483e+01 +-7.105939e-01 6.716789e-02 -7.003891e-01 7.385395e+01 4.169543e-02 9.977035e-01 5.337768e-02 3.579864e+00 7.023659e-01 8.726829e-03 -7.117626e-01 1.870784e+01 +-7.106449e-01 7.088616e-02 -6.999707e-01 7.281577e+01 4.325450e-02 9.974312e-01 5.709597e-02 3.635914e+00 7.022200e-01 1.029808e-02 -7.118856e-01 1.764779e+01 +-7.114232e-01 6.924053e-02 -6.993445e-01 7.178037e+01 4.358726e-02 9.975660e-01 5.442672e-02 3.690611e+00 7.014109e-01 8.237915e-03 -7.127096e-01 1.659036e+01 +-7.117335e-01 6.984294e-02 -6.989688e-01 7.072252e+01 4.697141e-02 9.975497e-01 5.184881e-02 3.757813e+00 7.008775e-01 4.070980e-03 -7.132701e-01 1.553332e+01 +-7.118054e-01 6.912210e-02 -6.989673e-01 6.968062e+01 4.366584e-02 9.975757e-01 5.418419e-02 3.812619e+00 7.010182e-01 8.047604e-03 -7.130980e-01 1.446538e+01 +-7.118141e-01 6.825340e-02 -6.990437e-01 6.863043e+01 4.185523e-02 9.976205e-01 5.478608e-02 3.874987e+00 7.011197e-01 9.738868e-03 -7.129771e-01 1.339651e+01 +-7.121041e-01 6.645603e-02 -6.989216e-01 6.758836e+01 4.137235e-02 9.977521e-01 5.271728e-02 3.933439e+00 7.008539e-01 8.624164e-03 -7.132528e-01 1.233276e+01 +-7.124001e-01 6.673751e-02 -6.985930e-01 6.652367e+01 4.277059e-02 9.977463e-01 5.170014e-02 4.001212e+00 7.004690e-01 6.951946e-03 -7.136490e-01 1.126661e+01 +-7.128010e-01 6.710882e-02 -6.981483e-01 6.547180e+01 4.467006e-02 9.977347e-01 5.029870e-02 4.057864e+00 6.999424e-01 4.666644e-03 -7.141841e-01 1.020597e+01 +-7.129006e-01 6.991621e-02 -6.977711e-01 6.440911e+01 4.720571e-02 9.975451e-01 5.172415e-02 4.117765e+00 6.996745e-01 3.935399e-03 -7.144509e-01 9.139006e+00 +-7.136760e-01 7.008310e-02 -6.969612e-01 6.336275e+01 4.602284e-02 9.975238e-01 5.317969e-02 4.172733e+00 6.989624e-01 5.876939e-03 -7.151343e-01 8.072657e+00 +-7.140534e-01 7.034862e-02 -6.965477e-01 6.231433e+01 4.671321e-02 9.975089e-01 5.285735e-02 4.230049e+00 6.985310e-01 5.205000e-03 -7.155609e-01 7.007367e+00 +-7.148407e-01 6.800138e-02 -6.959731e-01 6.127686e+01 4.354949e-02 9.976578e-01 5.274799e-02 4.285376e+00 6.979299e-01 7.397138e-03 -7.161279e-01 5.939202e+00 +-7.151947e-01 6.451846e-02 -6.959410e-01 6.024056e+01 4.124134e-02 9.978909e-01 5.012898e-02 4.335803e+00 6.977075e-01 7.150445e-03 -7.163471e-01 4.874804e+00 +-7.156826e-01 6.048688e-02 -6.958015e-01 5.920617e+01 3.691909e-02 9.981263e-01 4.879440e-02 4.385077e+00 6.974493e-01 9.232949e-03 -7.165747e-01 3.808043e+00 +-7.157864e-01 5.930633e-02 -6.957964e-01 5.816723e+01 3.592265e-02 9.981950e-01 4.812667e-02 4.441645e+00 6.973948e-01 9.453565e-03 -7.166249e-01 2.733559e+00 +-7.162520e-01 5.651645e-02 -6.955494e-01 5.712749e+01 3.332002e-02 9.983480e-01 4.680842e-02 4.503137e+00 6.970459e-01 1.035090e-02 -7.169519e-01 1.655679e+00 +-7.163236e-01 5.693943e-02 -6.954412e-01 5.609186e+01 3.355125e-02 9.983228e-01 4.717925e-02 4.557136e+00 6.969612e-01 1.046269e-02 -7.170325e-01 5.847543e-01 +-7.169294e-01 5.540577e-02 -6.949406e-01 5.505595e+01 3.289199e-02 9.984150e-01 4.566826e-02 4.611628e+00 6.963695e-01 9.882938e-03 -7.176154e-01 -4.860185e-01 +-7.172191e-01 5.401189e-02 -6.947514e-01 5.402887e+01 3.352691e-02 9.985117e-01 4.301593e-02 4.655655e+00 6.960408e-01 7.558977e-03 -7.179625e-01 -1.555701e+00 +-7.174215e-01 5.292660e-02 -6.946259e-01 5.300812e+01 3.351122e-02 9.985774e-01 4.147506e-02 4.695041e+00 6.958329e-01 6.477350e-03 -7.181746e-01 -2.625659e+00 +-7.175409e-01 5.278862e-02 -6.945131e-01 5.198736e+01 3.386013e-02 9.985886e-01 4.091802e-02 4.730281e+00 6.956929e-01 5.844056e-03 -7.183156e-01 -3.692204e+00 +-7.176864e-01 5.179289e-02 -6.944377e-01 5.096679e+01 3.310065e-02 9.986403e-01 4.027228e-02 4.764474e+00 6.955794e-01 5.916531e-03 -7.184249e-01 -4.761087e+00 +-7.178657e-01 4.680799e-02 -6.946063e-01 4.995573e+01 3.036622e-02 9.988928e-01 3.593016e-02 4.792619e+00 6.955191e-01 4.700459e-03 -7.184922e-01 -5.822352e+00 +-7.176909e-01 4.093440e-02 -6.951576e-01 4.894737e+01 2.603780e-02 9.991501e-01 3.195323e-02 4.816112e+00 6.958749e-01 4.832170e-03 -7.181468e-01 -6.885328e+00 +-7.175406e-01 3.529960e-02 -6.956216e-01 4.794247e+01 2.052248e-02 9.993528e-01 2.954344e-02 4.832810e+00 6.962143e-01 6.922748e-03 -7.178007e-01 -7.950469e+00 +-7.174337e-01 3.282315e-02 -6.958531e-01 4.693507e+01 1.618698e-02 9.994051e-01 3.045262e-02 4.844236e+00 6.964387e-01 1.058398e-02 -7.175382e-01 -9.021045e+00 +-7.176163e-01 3.225679e-02 -6.956913e-01 4.591875e+01 1.369103e-02 9.993871e-01 3.221562e-02 4.868041e+00 6.963042e-01 1.359372e-02 -7.176181e-01 -1.010293e+01 +-7.183558e-01 3.321040e-02 -6.948827e-01 4.490240e+01 1.305464e-02 9.993275e-01 3.426506e-02 4.905350e+00 6.955534e-01 1.554306e-02 -7.183063e-01 -1.116302e+01 +-7.196465e-01 3.428621e-02 -6.934936e-01 4.389300e+01 1.338152e-02 9.992794e-01 3.551807e-02 4.944611e+00 6.942117e-01 1.628046e-02 -7.195868e-01 -1.221655e+01 +-7.214079e-01 3.065212e-02 -6.918317e-01 4.289962e+01 1.385015e-02 9.994587e-01 2.983953e-02 4.971141e+00 6.923719e-01 1.194450e-02 -7.214420e-01 -1.325097e+01 +-7.229976e-01 2.937714e-02 -6.902257e-01 4.191066e+01 1.874717e-02 9.995618e-01 2.290573e-02 4.990965e+00 6.905962e-01 3.621018e-03 -7.232315e-01 -1.427421e+01 +-7.247023e-01 3.408401e-02 -6.882186e-01 4.092934e+01 2.499387e-02 9.994189e-01 2.317737e-02 5.000309e+00 6.886087e-01 -4.045530e-04 -7.251330e-01 -1.529368e+01 +-7.266854e-01 4.200494e-02 -6.856850e-01 3.995858e+01 3.293508e-02 9.991114e-01 2.630098e-02 5.011392e+00 6.861804e-01 -3.470546e-03 -7.274231e-01 -1.630718e+01 +-7.293345e-01 4.652565e-02 -6.825734e-01 3.901008e+01 3.699364e-02 9.989073e-01 2.855970e-02 5.019810e+00 6.831564e-01 -4.421293e-03 -7.302588e-01 -1.731370e+01 +-7.323036e-01 4.683378e-02 -6.793659e-01 3.808953e+01 3.558080e-02 9.989010e-01 3.050842e-02 5.023344e+00 6.800481e-01 -1.830946e-03 -7.331652e-01 -1.831743e+01 +-7.345648e-01 4.604645e-02 -6.769743e-01 3.718542e+01 3.285207e-02 9.989382e-01 3.229900e-02 5.023351e+00 6.777428e-01 1.485699e-03 -7.352976e-01 -1.931810e+01 +-7.367978e-01 4.263635e-02 -6.747674e-01 3.629566e+01 2.971216e-02 9.990874e-01 3.068553e-02 5.026359e+00 6.754600e-01 2.560239e-03 -7.373922e-01 -2.031000e+01 +-7.391603e-01 4.099750e-02 -6.722806e-01 3.541875e+01 3.152528e-02 9.991576e-01 2.626990e-02 5.036353e+00 6.727914e-01 -1.776165e-03 -7.398301e-01 -2.129163e+01 +-7.412916e-01 4.086444e-02 -6.699379e-01 3.455447e+01 3.583142e-02 9.991309e-01 2.129661e-02 5.037946e+00 6.702260e-01 -8.217823e-03 -7.421116e-01 -2.225036e+01 +-7.430614e-01 4.082653e-02 -6.679767e-01 3.370492e+01 3.789906e-02 9.991027e-01 1.890572e-02 5.035071e+00 6.681493e-01 -1.126757e-02 -7.439420e-01 -2.320301e+01 +-7.447488e-01 3.938410e-02 -6.661818e-01 3.286682e+01 3.447942e-02 9.991946e-01 2.052576e-02 5.035514e+00 6.664536e-01 -7.683023e-03 -7.455069e-01 -2.415729e+01 +-7.462133e-01 3.254885e-02 -6.649107e-01 3.207300e+01 2.690925e-02 9.994624e-01 1.872630e-02 5.036634e+00 6.651629e-01 -3.918432e-03 -7.466880e-01 -2.509746e+01 +-7.473855e-01 2.574874e-02 -6.638915e-01 3.129007e+01 1.965514e-02 9.996682e-01 1.664465e-02 5.032932e+00 6.640999e-01 -6.089029e-04 -7.476436e-01 -2.602382e+01 +-7.481792e-01 2.103048e-02 -6.631633e-01 3.051161e+01 1.158472e-02 9.997592e-01 1.863490e-02 5.030582e+00 6.633956e-01 6.259685e-03 -7.482427e-01 -2.694303e+01 +-7.493921e-01 1.781990e-02 -6.618866e-01 2.974294e+01 3.143223e-03 9.997222e-01 2.335664e-02 5.025220e+00 6.621190e-01 1.542283e-02 -7.492400e-01 -2.784011e+01 +-7.504138e-01 1.423643e-02 -6.608149e-01 2.899438e+01 -2.406234e-03 9.997025e-01 2.426984e-02 5.012866e+00 6.609639e-01 1.980250e-02 -7.501564e-01 -2.870857e+01 +-7.510952e-01 4.334683e-03 -6.601797e-01 2.828277e+01 -1.009870e-02 9.997860e-01 1.805394e-02 5.001018e+00 6.601167e-01 2.022719e-02 -7.508907e-01 -2.955280e+01 +-7.504836e-01 -6.014183e-03 -6.608617e-01 2.759440e+01 -2.100635e-02 9.996704e-01 1.475758e-02 4.988123e+00 6.605552e-01 2.495761e-02 -7.503626e-01 -3.038265e+01 +-7.484535e-01 -1.376503e-02 -6.630444e-01 2.692794e+01 -3.396145e-02 9.992683e-01 1.759099e-02 4.960921e+00 6.623171e-01 3.568398e-02 -7.483734e-01 -3.119636e+01 +-7.443035e-01 -1.865400e-02 -6.675809e-01 2.627091e+01 -4.416943e-02 9.987962e-01 2.133661e-02 4.937344e+00 6.663793e-01 4.536758e-02 -7.442315e-01 -3.198116e+01 +-7.386142e-01 -2.489222e-02 -6.736686e-01 2.563589e+01 -5.434496e-02 9.982642e-01 2.269802e-02 4.911415e+00 6.719343e-01 5.337557e-02 -7.386849e-01 -3.273008e+01 +-7.310049e-01 -3.222786e-02 -6.816107e-01 2.501530e+01 -6.340459e-02 9.977706e-01 2.082281e-02 4.883203e+00 6.794201e-01 5.843882e-02 -7.314186e-01 -3.344474e+01 +-7.214474e-01 -4.014856e-02 -6.913044e-01 2.440647e+01 -7.245697e-02 9.972144e-01 1.770155e-02 4.868599e+00 6.886681e-01 6.286055e-02 -7.223468e-01 -3.411914e+01 +-7.100231e-01 -4.864285e-02 -7.024963e-01 2.380214e+01 -8.342360e-02 9.963963e-01 1.532409e-02 4.863346e+00 6.992194e-01 6.948522e-02 -7.115224e-01 -3.476408e+01 +-6.968652e-01 -5.326536e-02 -7.152214e-01 2.320841e+01 -8.939890e-02 9.959119e-01 1.293498e-02 4.857973e+00 7.116085e-01 7.295394e-02 -6.987782e-01 -3.536771e+01 +-6.811684e-01 -5.741832e-02 -7.298717e-01 2.262116e+01 -9.403971e-02 9.955236e-01 9.447648e-03 4.849439e+00 7.260621e-01 7.507235e-02 -6.835188e-01 -3.593490e+01 +-6.613276e-01 -6.298422e-02 -7.474482e-01 2.204002e+01 -1.032530e-01 9.946265e-01 7.543374e-03 4.839517e+00 7.429567e-01 8.216490e-02 -6.642773e-01 -3.646916e+01 +-6.369833e-01 -6.629914e-02 -7.680213e-01 2.146476e+01 -1.108563e-01 9.938174e-01 6.151326e-03 4.829678e+00 7.628651e-01 8.905826e-02 -6.403948e-01 -3.696672e+01 +-6.099886e-01 -6.471177e-02 -7.897634e-01 2.088345e+01 -1.121982e-01 9.936720e-01 5.238722e-03 4.829241e+00 7.844268e-01 9.180560e-02 -6.133892e-01 -3.741560e+01 +-5.810404e-01 -6.123614e-02 -8.115677e-01 2.030329e+01 -1.094838e-01 9.939828e-01 3.384636e-03 4.821699e+00 8.064771e-01 9.082015e-02 -5.842486e-01 -3.782091e+01 +-5.494269e-01 -6.118348e-02 -8.332987e-01 1.973431e+01 -1.116370e-01 9.937488e-01 6.424125e-04 4.809316e+00 8.280503e-01 9.337987e-02 -5.528227e-01 -3.818645e+01 +-5.144597e-01 -6.138916e-02 -8.553143e-01 1.917490e+01 -1.112642e-01 9.937811e-01 -4.403591e-03 4.788276e+00 8.502656e-01 9.290038e-02 -5.180907e-01 -3.851376e+01 +-4.780984e-01 -5.958754e-02 -8.762826e-01 1.862495e+01 -1.091966e-01 9.939878e-01 -8.014043e-03 4.765293e+00 8.714919e-01 9.185559e-02 -4.817308e-01 -3.880134e+01 +-4.414171e-01 -5.483467e-02 -8.956250e-01 1.807401e+01 -1.033468e-01 9.945955e-01 -9.958704e-03 4.745044e+00 8.913307e-01 8.816405e-02 -4.446985e-01 -3.904398e+01 +-4.027517e-01 -4.741849e-02 -9.140802e-01 1.751605e+01 -9.643325e-02 9.952974e-01 -9.142366e-03 4.729289e+00 9.102152e-01 8.446560e-02 -4.054305e-01 -3.926055e+01 +-3.602907e-01 -3.913854e-02 -9.320186e-01 1.695707e+01 -9.024465e-02 9.958955e-01 -6.935045e-03 4.710410e+00 9.284646e-01 8.161105e-02 -3.623439e-01 -3.944202e+01 +-3.132652e-01 -3.016270e-02 -9.491865e-01 1.639659e+01 -8.763865e-02 9.961486e-01 -2.731177e-03 4.684822e+00 9.456133e-01 8.232984e-02 -3.147021e-01 -3.959769e+01 +-2.614082e-01 -1.976426e-02 -9.650260e-01 1.583889e+01 -8.699761e-02 9.962035e-01 3.163296e-03 4.661222e+00 9.612998e-01 8.478185e-02 -2.621352e-01 -3.971458e+01 +-2.049114e-01 -9.099087e-03 -9.787382e-01 1.527935e+01 -8.442239e-02 9.963945e-01 8.411680e-03 4.645931e+00 9.751329e-01 8.435106e-02 -2.049408e-01 -3.979480e+01 +-1.464708e-01 1.005805e-03 -9.892145e-01 1.473340e+01 -7.953489e-02 9.967500e-01 1.279003e-02 4.620685e+00 9.860125e-01 8.055042e-02 -1.459148e-01 -3.983135e+01 +-8.837968e-02 9.369087e-03 -9.960428e-01 1.419136e+01 -7.479137e-02 9.970706e-01 1.601506e-02 4.600733e+00 9.932751e-01 7.591080e-02 -8.742005e-02 -3.982978e+01 +-3.000358e-02 1.491702e-02 -9.994385e-01 1.365742e+01 -7.302747e-02 9.971837e-01 1.707569e-02 4.594101e+00 9.968785e-01 7.349878e-02 -2.882973e-02 -3.980561e+01 +2.826006e-02 1.822843e-02 -9.994344e-01 1.313394e+01 -7.413022e-02 9.971187e-01 1.609009e-02 4.591217e+00 9.968481e-01 7.363357e-02 2.952992e-02 -3.975563e+01 +8.538452e-02 2.087301e-02 -9.961294e-01 1.263427e+01 -7.557208e-02 9.970361e-01 1.441425e-02 4.572501e+00 9.934779e-01 7.404881e-02 8.670888e-02 -3.967236e+01 +1.420652e-01 2.255334e-02 -9.896003e-01 1.213735e+01 -7.527357e-02 9.970917e-01 1.191794e-02 4.570481e+00 9.869911e-01 7.279762e-02 1.433497e-01 -3.956702e+01 +1.985196e-01 2.341048e-02 -9.798173e-01 1.164903e+01 -7.349240e-02 9.972557e-01 8.936933e-03 4.569883e+00 9.773377e-01 7.023495e-02 1.996953e-01 -3.942411e+01 +2.537725e-01 2.437099e-02 -9.669568e-01 1.117231e+01 -7.344789e-02 9.972818e-01 5.859305e-03 4.559489e+00 9.644713e-01 6.953400e-02 2.548728e-01 -3.926055e+01 +3.080044e-01 2.456673e-02 -9.510677e-01 1.070045e+01 -7.464827e-02 9.972086e-01 1.583668e-03 4.562188e+00 9.484519e-01 7.050777e-02 3.089785e-01 -3.907124e+01 +3.614380e-01 2.390612e-02 -9.320896e-01 1.023998e+01 -7.697001e-02 9.970242e-01 -4.275233e-03 4.558096e+00 9.292138e-01 7.328817e-02 3.622025e-01 -3.886313e+01 +4.132616e-01 2.362759e-02 -9.103057e-01 9.789695e+00 -7.724566e-02 9.969697e-01 -9.191046e-03 4.558073e+00 9.073301e-01 7.411546e-02 4.138345e-01 -3.862980e+01 +4.636159e-01 2.536311e-02 -8.856732e-01 9.346772e+00 -7.637444e-02 9.970137e-01 -1.142749e-02 4.558865e+00 8.827385e-01 7.294075e-02 4.641685e-01 -3.835721e+01 +5.127193e-01 2.924695e-02 -8.580580e-01 8.918192e+00 -7.631892e-02 9.970157e-01 -1.161985e-02 4.555772e+00 8.551575e-01 7.144377e-02 5.134213e-01 -3.806253e+01 +5.601875e-01 3.307597e-02 -8.277053e-01 8.497673e+00 -7.443200e-02 9.971705e-01 -1.052727e-02 4.557479e+00 8.250151e-01 6.750499e-02 5.610643e-01 -3.773849e+01 +6.049226e-01 3.819802e-02 -7.953676e-01 8.088430e+00 -7.429306e-02 9.971992e-01 -8.613005e-03 4.554056e+00 7.928110e-01 6.430048e-02 6.060662e-01 -3.738994e+01 +6.471952e-01 4.181403e-02 -7.611767e-01 7.694448e+00 -7.351803e-02 9.972639e-01 -7.726041e-03 4.557188e+00 7.587710e-01 6.096045e-02 6.484986e-01 -3.701386e+01 +6.872246e-01 4.457623e-02 -7.250761e-01 7.308945e+00 -7.479240e-02 9.971530e-01 -9.584984e-03 4.562789e+00 7.225846e-01 6.081720e-02 6.886021e-01 -3.661689e+01 +7.244476e-01 4.487619e-02 -6.878675e-01 6.938250e+00 -7.473407e-02 9.971099e-01 -1.365729e-02 4.579774e+00 6.852667e-01 6.130112e-02 7.257078e-01 -3.619875e+01 +7.589259e-01 4.426893e-02 -6.496705e-01 6.587902e+00 -7.316065e-02 9.971663e-01 -1.751658e-02 4.590754e+00 6.470542e-01 6.082410e-02 7.600141e-01 -3.575589e+01 +7.910008e-01 4.278400e-02 -6.103174e-01 6.256320e+00 -6.992305e-02 9.973374e-01 -2.070905e-02 4.593195e+00 6.078064e-01 5.905612e-02 7.918862e-01 -3.528263e+01 +8.203784e-01 4.075199e-02 -5.703670e-01 5.946327e+00 -6.586107e-02 9.975530e-01 -2.345632e-02 4.589196e+00 5.680155e-01 5.680803e-02 8.210550e-01 -3.478822e+01 +8.472057e-01 3.897425e-02 -5.298335e-01 5.653599e+00 -6.209536e-02 9.977341e-01 -2.589793e-02 4.581954e+00 5.276237e-01 5.484107e-02 8.477062e-01 -3.427208e+01 +8.717006e-01 3.675286e-02 -4.886586e-01 5.377697e+00 -5.729952e-02 9.979877e-01 -2.715416e-02 4.574692e+00 4.866773e-01 5.167019e-02 8.720524e-01 -3.372956e+01 +8.931302e-01 3.448294e-02 -4.484744e-01 5.122507e+00 -5.257763e-02 9.982255e-01 -2.795458e-02 4.565832e+00 4.467147e-01 4.854679e-02 8.933584e-01 -3.317164e+01 +9.116715e-01 3.298949e-02 -4.095935e-01 4.885552e+00 -4.888649e-02 9.984005e-01 -2.839813e-02 4.558254e+00 4.080015e-01 4.591335e-02 9.118261e-01 -3.258986e+01 +9.273577e-01 3.200127e-02 -3.728052e-01 4.666734e+00 -4.662114e-02 9.984541e-01 -3.026423e-02 4.543817e+00 3.712604e-01 4.544637e-02 9.274160e-01 -3.199497e+01 +9.403991e-01 3.042754e-02 -3.387090e-01 4.467981e+00 -4.412624e-02 9.984869e-01 -3.281511e-02 4.521503e+00 3.371980e-01 4.580525e-02 9.403188e-01 -3.137181e+01 +9.509425e-01 2.638684e-02 -3.082403e-01 4.285109e+00 -3.946876e-02 9.985619e-01 -3.628214e-02 4.492915e+00 3.068397e-01 4.666809e-02 9.506164e-01 -3.073791e+01 +9.595847e-01 2.172028e-02 -2.805805e-01 4.118069e+00 -3.420133e-02 9.986276e-01 -3.966273e-02 4.450932e+00 2.793340e-01 4.765597e-02 9.590107e-01 -3.008740e+01 +9.666064e-01 2.001028e-02 -2.554832e-01 3.955962e+00 -3.203187e-02 9.985623e-01 -4.298012e-02 4.413564e+00 2.542559e-01 4.972846e-02 9.658577e-01 -2.942723e+01 +9.721189e-01 1.893689e-02 -2.337228e-01 3.805573e+00 -3.051279e-02 9.984747e-01 -4.601196e-02 4.360478e+00 2.324950e-01 5.186062e-02 9.712140e-01 -2.875091e+01 +9.766010e-01 1.578682e-02 -2.144793e-01 3.675026e+00 -2.643928e-02 9.985501e-01 -4.688888e-02 4.304388e+00 2.134281e-01 5.146240e-02 9.756024e-01 -2.805891e+01 +9.799933e-01 1.306696e-02 -1.986013e-01 3.550010e+00 -2.277731e-02 9.986498e-01 -4.668797e-02 4.250514e+00 1.977231e-01 5.027749e-02 9.789677e-01 -2.735427e+01 +9.824889e-01 1.067494e-02 -1.860149e-01 3.428575e+00 -1.936939e-02 9.987998e-01 -4.498605e-02 4.201515e+00 1.853115e-01 4.780128e-02 9.815165e-01 -2.663704e+01 +9.841653e-01 8.573865e-03 -1.770458e-01 3.306982e+00 -1.651278e-02 9.989206e-01 -4.341641e-02 4.155074e+00 1.764824e-01 4.565243e-02 9.832445e-01 -2.591355e+01 +9.852610e-01 4.502193e-03 -1.709986e-01 3.190054e+00 -1.176521e-02 9.990698e-01 -4.148453e-02 4.110455e+00 1.706528e-01 4.288492e-02 9.843975e-01 -2.517514e+01 +9.860367e-01 5.286025e-04 -1.665276e-01 3.070532e+00 -6.970902e-03 9.992494e-01 -3.810395e-02 4.067978e+00 1.663825e-01 3.873273e-02 9.853003e-01 -2.442867e+01 +9.864786e-01 6.564552e-04 -1.638889e-01 2.950683e+00 -6.611761e-03 9.993373e-01 -3.579461e-02 4.013361e+00 1.637568e-01 3.639421e-02 9.858292e-01 -2.367167e+01 +9.867374e-01 2.590475e-03 -1.623038e-01 2.824133e+00 -8.366176e-03 9.993553e-01 -3.491239e-02 3.969054e+00 1.621087e-01 3.580722e-02 9.861230e-01 -2.291188e+01 +9.869328e-01 1.858947e-03 -1.611217e-01 2.703838e+00 -7.806118e-03 9.993109e-01 -3.628591e-02 3.925284e+00 1.609432e-01 3.706948e-02 9.862673e-01 -2.213884e+01 +9.871684e-01 -8.924148e-04 -1.596800e-01 2.589654e+00 -4.893816e-03 9.993456e-01 -3.583950e-02 3.885707e+00 1.596075e-01 3.616106e-02 9.865180e-01 -2.135423e+01 +9.874773e-01 -2.819649e-03 -1.577358e-01 2.477719e+00 -2.667274e-03 9.993989e-01 -3.456303e-02 3.836418e+00 1.577385e-01 3.455092e-02 9.868763e-01 -2.055891e+01 +9.877755e-01 -9.197106e-04 -1.558805e-01 2.355843e+00 -4.206054e-03 9.994612e-01 -3.254963e-02 3.790891e+00 1.558264e-01 3.280737e-02 9.872395e-01 -1.975481e+01 +9.879911e-01 -1.270272e-03 -1.545058e-01 2.235350e+00 -3.671099e-03 9.994909e-01 -3.169227e-02 3.749982e+00 1.544674e-01 3.187888e-02 9.874835e-01 -1.894191e+01 +9.881933e-01 -3.407229e-03 -1.531747e-01 2.119854e+00 -1.473372e-03 9.994951e-01 -3.173818e-02 3.709293e+00 1.532055e-01 3.158913e-02 9.876893e-01 -1.811974e+01 +9.884054e-01 -5.461543e-03 -1.517399e-01 2.001010e+00 8.247124e-04 9.995312e-01 -3.060389e-02 3.670735e+00 1.518360e-01 3.012391e-02 9.879466e-01 -1.728392e+01 +9.887003e-01 -7.396698e-03 -1.497228e-01 1.883217e+00 3.158149e-03 9.995880e-01 -2.852730e-02 3.631509e+00 1.498722e-01 2.773210e-02 9.883164e-01 -1.643897e+01 +9.889127e-01 -9.870852e-03 -1.481697e-01 1.764067e+00 6.131684e-03 9.996516e-01 -2.567134e-02 3.597017e+00 1.483715e-01 2.447818e-02 9.886287e-01 -1.558906e+01 +9.891341e-01 -1.147728e-02 -1.465678e-01 1.651780e+00 8.182194e-03 9.997005e-01 -2.306478e-02 3.548182e+00 1.467886e-01 2.161492e-02 9.889317e-01 -1.473308e+01 +9.893365e-01 -1.348257e-02 -1.450223e-01 1.539703e+00 1.044971e-02 9.997109e-01 -2.165460e-02 3.501263e+00 1.452723e-01 1.990825e-02 9.891914e-01 -1.388343e+01 +9.894854e-01 -1.718952e-02 -1.436074e-01 1.437817e+00 1.416707e-02 9.996566e-01 -2.204284e-02 3.446710e+00 1.439370e-01 1.977657e-02 9.893892e-01 -1.303953e+01 +9.896591e-01 -2.019845e-02 -1.420102e-01 1.332990e+00 1.736653e-02 9.996254e-01 -2.115304e-02 3.402079e+00 1.423843e-01 1.846807e-02 9.896392e-01 -1.220518e+01 +9.898349e-01 -2.173588e-02 -1.405505e-01 1.229057e+00 1.947657e-02 9.996583e-01 -1.743057e-02 3.357583e+00 1.408814e-01 1.451594e-02 9.899201e-01 -1.137420e+01 +9.899480e-01 -2.375886e-02 -1.394219e-01 1.124698e+00 2.218724e-02 9.996717e-01 -1.281617e-02 3.319838e+00 1.396806e-01 9.593957e-03 9.901501e-01 -1.055262e+01 +9.899730e-01 -2.413360e-02 -1.391796e-01 1.021769e+00 2.307639e-02 9.996913e-01 -9.205023e-03 3.282209e+00 1.393588e-01 5.900961e-03 9.902244e-01 -9.738292e+00 +9.899014e-01 -2.506050e-02 -1.395246e-01 9.140285e-01 2.415573e-02 9.996748e-01 -8.174668e-03 3.255862e+00 1.396841e-01 4.721798e-03 9.901849e-01 -8.934948e+00 +9.896795e-01 -2.634804e-02 -1.408557e-01 8.089844e-01 2.529646e-02 9.996372e-01 -9.251249e-03 3.231920e+00 1.410484e-01 5.592620e-03 9.899869e-01 -8.142150e+00 +9.893334e-01 -2.751812e-02 -1.430462e-01 6.976696e-01 2.610468e-02 9.995901e-01 -1.174876e-02 3.213944e+00 1.433109e-01 7.889268e-03 9.896463e-01 -7.359806e+00 +9.890921e-01 -2.538244e-02 -1.450948e-01 5.724670e-01 2.348796e-02 9.996152e-01 -1.475536e-02 3.198536e+00 1.454135e-01 1.118643e-02 9.893077e-01 -6.591425e+00 +9.887771e-01 -2.163158e-02 -1.478239e-01 4.329746e-01 1.938684e-02 9.996741e-01 -1.660943e-02 3.192339e+00 1.481350e-01 1.355718e-02 9.888742e-01 -5.834565e+00 +9.883756e-01 -1.932055e-02 -1.507995e-01 3.028311e-01 1.735180e-02 9.997463e-01 -1.436054e-02 3.180074e+00 1.510387e-01 1.157696e-02 9.884601e-01 -5.080036e+00 +9.878649e-01 -1.824123e-02 -1.542405e-01 1.724620e-01 1.727270e-02 9.998218e-01 -7.617239e-03 3.166402e+00 1.543520e-01 4.860654e-03 9.880040e-01 -4.328516e+00 +9.873695e-01 -1.781200e-02 -1.574299e-01 4.170446e-02 1.778282e-02 9.998406e-01 -1.594054e-03 3.150253e+00 1.574332e-01 -1.225625e-03 9.875289e-01 -3.587435e+00 +9.868111e-01 -1.612479e-02 -1.610710e-01 -9.383378e-02 1.611063e-02 9.998692e-01 -1.394024e-03 3.129508e+00 1.610724e-01 -1.219316e-03 9.869418e-01 -2.862004e+00 +9.861268e-01 -1.316405e-02 -1.654709e-01 -2.338140e-01 1.265482e-02 9.999114e-01 -4.131458e-03 3.119866e+00 1.655106e-01 1.980139e-03 9.862060e-01 -2.148095e+00 +9.853249e-01 -9.085180e-03 -1.704471e-01 -3.787351e-01 8.528939e-03 9.999556e-01 -3.995389e-03 3.114533e+00 1.704759e-01 2.483025e-03 9.853587e-01 -1.437432e+00 +9.843764e-01 -9.106735e-03 -1.758416e-01 -5.153242e-01 9.460846e-03 9.999545e-01 1.175541e-03 3.107244e+00 1.758229e-01 -2.820784e-03 9.844178e-01 -7.281130e-01 +9.831696e-01 -9.580070e-03 -1.824437e-01 -6.525002e-01 1.101065e-02 9.999160e-01 6.829880e-03 3.094228e+00 1.823630e-01 -8.723752e-03 9.831926e-01 -2.723748e-02 +9.818511e-01 -8.427701e-03 -1.894663e-01 -8.003764e-01 1.037538e-02 9.999030e-01 9.290274e-03 3.082507e+00 1.893697e-01 -1.108745e-02 9.818433e-01 6.669401e-01 +9.801173e-01 -1.061413e-02 -1.981350e-01 -9.575037e-01 1.155781e-02 9.999267e-01 3.606903e-03 3.085825e+00 1.980823e-01 -5.825193e-03 9.801681e-01 1.349238e+00 +9.778802e-01 -1.212506e-02 -2.088141e-01 -1.128803e+00 1.175085e-02 9.999263e-01 -3.032563e-03 3.097159e+00 2.088355e-01 5.117409e-04 9.779507e-01 2.027763e+00 +9.755520e-01 -1.455432e-02 -2.192862e-01 -1.304476e+00 1.370294e-02 9.998915e-01 -5.403065e-03 3.098012e+00 2.193410e-01 2.266108e-03 9.756456e-01 2.711778e+00 +9.728262e-01 -1.512759e-02 -2.310418e-01 -1.492523e+00 1.425146e-02 9.998835e-01 -5.460667e-03 3.094641e+00 2.310976e-01 2.019599e-03 9.729285e-01 3.399382e+00 +9.700470e-01 -1.508222e-02 -2.424488e-01 -1.682534e+00 1.489808e-02 9.998856e-01 -2.592954e-03 3.087422e+00 2.424602e-01 -1.096732e-03 9.701608e-01 4.091749e+00 +9.672978e-01 -1.463642e-02 -2.532208e-01 -1.890708e+00 1.528079e-02 9.998830e-01 5.780224e-04 3.077220e+00 2.531827e-01 -4.428531e-03 9.674084e-01 4.783150e+00 +9.642825e-01 -1.475269e-02 -2.644649e-01 -2.102925e+00 1.573973e-02 9.998748e-01 1.613444e-03 3.072107e+00 2.644080e-01 -5.718420e-03 9.643940e-01 5.471108e+00 +9.612605e-01 -1.339029e-02 -2.753163e-01 -2.326851e+00 1.398537e-02 9.999022e-01 1.983378e-04 3.074640e+00 2.752867e-01 -4.041053e-03 9.613537e-01 6.156888e+00 +9.581635e-01 -1.409210e-02 -2.858744e-01 -2.549688e+00 1.329121e-02 9.999004e-01 -4.741749e-03 3.071295e+00 2.859128e-01 7.437561e-04 9.582554e-01 6.841526e+00 +9.549924e-01 -1.561857e-02 -2.962188e-01 -2.775305e+00 1.332215e-02 9.998635e-01 -9.769438e-03 3.058171e+00 2.963310e-01 5.383469e-03 9.550701e-01 7.528465e+00 +9.519238e-01 -1.898118e-02 -3.057463e-01 -3.006582e+00 1.575551e-02 9.997911e-01 -1.301464e-02 3.045729e+00 3.059295e-01 7.571755e-03 9.520241e-01 8.222648e+00 diff --git a/tools/Ground-Truth/dataset/poses/10.txt b/tools/Ground-Truth/dataset/poses/10.txt new file mode 100644 index 0000000..047e494 --- /dev/null +++ b/tools/Ground-Truth/dataset/poses/10.txt @@ -0,0 +1,1201 @@ +1.000000e+00 1.197625e-11 1.704638e-10 1.665335e-16 1.197625e-11 1.000000e+00 3.562503e-10 -1.110223e-16 1.704638e-10 3.562503e-10 1.000000e+00 2.220446e-16 +9.998804e-01 1.381571e-03 1.540756e-02 1.210187e-02 -1.365955e-03 9.999985e-01 -1.023970e-03 4.468736e-04 -1.540895e-02 1.002801e-03 9.998808e-01 1.267281e-01 +9.993411e-01 4.139270e-03 3.605873e-02 3.021791e-02 -4.118323e-03 9.999913e-01 -6.552072e-04 9.791738e-04 -3.606113e-02 5.062745e-04 9.993495e-01 2.686230e-01 +9.980124e-01 5.708759e-03 6.275818e-02 5.987546e-02 -5.760680e-03 9.999832e-01 6.463838e-04 2.308105e-03 -6.275344e-02 -1.006628e-03 9.980286e-01 4.305403e-01 +9.953527e-01 5.411577e-03 9.614398e-02 1.050408e-01 -5.718903e-03 9.999794e-01 2.921236e-03 3.322381e-03 -9.612619e-02 -3.457497e-03 9.953632e-01 6.034613e-01 +9.909970e-01 2.437994e-03 1.338620e-01 1.652963e-01 -3.155109e-03 9.999818e-01 5.145250e-03 5.264528e-03 -1.338470e-01 -5.521275e-03 9.909866e-01 7.870087e-01 +9.848812e-01 -8.797585e-04 1.732288e-01 2.401943e-01 -1.148614e-04 9.999835e-01 5.731548e-03 7.625042e-03 -1.732310e-01 -5.664790e-03 9.848649e-01 9.812571e-01 +9.763389e-01 -1.209269e-03 2.162426e-01 3.220547e-01 -3.105266e-04 9.999755e-01 6.994083e-03 1.121243e-02 -2.162458e-01 -6.895743e-03 9.763146e-01 1.185453e+00 +9.644808e-01 -1.175212e-03 2.641504e-01 4.170054e-01 -1.347063e-03 9.999552e-01 9.367301e-03 1.474470e-02 -2.641496e-01 -9.390408e-03 9.644360e-01 1.399473e+00 +9.500987e-01 -4.177904e-03 3.119216e-01 5.318267e-01 -1.009852e-03 9.998639e-01 1.646823e-02 1.361741e-02 -3.119479e-01 -1.596143e-02 9.499651e-01 1.620036e+00 +9.333565e-01 -1.416072e-02 3.586714e-01 6.772189e-01 5.593755e-03 9.996740e-01 2.491176e-02 1.304237e-02 -3.589072e-01 -2.124523e-02 9.331314e-01 1.841928e+00 +9.123320e-01 -2.014890e-02 4.089552e-01 8.328051e-01 8.864985e-03 9.995264e-01 2.946912e-02 1.601613e-02 -4.093553e-01 -2.326024e-02 9.120785e-01 2.063052e+00 +8.872656e-01 -2.177657e-02 4.607445e-01 9.991018e-01 7.355619e-03 9.994259e-01 3.307187e-02 1.908196e-02 -4.612002e-01 -2.595447e-02 8.869164e-01 2.286905e+00 +8.590210e-01 -2.409304e-02 5.113731e-01 1.188050e+00 5.460112e-03 9.992663e-01 3.790778e-02 2.416489e-02 -5.119112e-01 -2.977142e-02 8.585223e-01 2.512800e+00 +8.270453e-01 -2.918261e-02 5.613773e-01 1.399778e+00 6.631357e-03 9.990885e-01 4.216697e-02 3.070196e-02 -5.620962e-01 -3.115130e-02 8.264850e-01 2.733367e+00 +7.911863e-01 -3.486678e-02 6.105806e-01 1.634196e+00 8.791727e-03 9.989188e-01 4.565031e-02 3.653765e-02 -6.115121e-01 -3.074984e-02 7.906374e-01 2.948016e+00 +7.532744e-01 -3.928513e-02 6.565321e-01 1.890112e+00 9.846352e-03 9.987762e-01 4.846688e-02 4.599883e-02 -6.576327e-01 -3.004440e-02 7.527394e-01 3.160521e+00 +7.135453e-01 -4.262496e-02 6.993113e-01 2.166152e+00 1.112298e-02 9.987109e-01 4.952483e-02 5.994960e-02 -7.005209e-01 -2.755978e-02 7.130996e-01 3.369735e+00 +6.716420e-01 -4.460763e-02 7.395317e-01 2.465897e+00 1.077426e-02 9.986683e-01 5.045326e-02 7.581133e-02 -7.407975e-01 -2.591862e-02 6.712282e-01 3.579897e+00 +6.289069e-01 -4.493066e-02 7.761812e-01 2.784666e+00 6.144236e-03 9.985848e-01 5.282648e-02 9.232525e-02 -7.774563e-01 -2.845390e-02 6.282930e-01 3.792151e+00 +5.870428e-01 -4.577422e-02 8.082608e-01 3.131897e+00 3.200808e-03 9.985236e-01 5.422462e-02 1.077991e-01 -8.095496e-01 -2.924508e-02 5.863226e-01 4.000366e+00 +5.468504e-01 -4.700298e-02 8.359099e-01 3.507611e+00 1.579470e-03 9.984790e-01 5.511092e-02 1.241318e-01 -8.372289e-01 -2.881713e-02 5.460929e-01 4.202254e+00 +5.079969e-01 -4.952766e-02 8.599338e-01 3.909356e+00 3.120507e-04 9.983560e-01 5.731572e-02 1.392366e-01 -8.613589e-01 -2.884786e-02 5.071772e-01 4.402127e+00 +4.705742e-01 -4.939765e-02 8.809766e-01 4.338561e+00 -2.506181e-03 9.983528e-01 5.731779e-02 1.575565e-01 -8.823569e-01 -2.918016e-02 4.696753e-01 4.600410e+00 +4.341107e-01 -4.876219e-02 8.995388e-01 4.794196e+00 -3.833407e-03 9.984249e-01 5.597259e-02 1.775272e-01 -9.008514e-01 -2.774660e-02 4.332400e-01 4.791823e+00 +4.001985e-01 -4.738002e-02 9.152029e-01 5.277728e+00 -2.459822e-03 9.986035e-01 5.277330e-02 1.987946e-01 -9.164252e-01 -2.337103e-02 3.995230e-01 4.974126e+00 +3.705133e-01 -4.579345e-02 9.276976e-01 5.789743e+00 -3.407336e-04 9.987771e-01 4.943820e-02 2.220149e-01 -9.288271e-01 -1.863361e-02 3.700446e-01 5.152037e+00 +3.447498e-01 -4.391011e-02 9.376670e-01 6.329744e+00 1.047874e-03 9.989227e-01 4.639340e-02 2.453956e-01 -9.386940e-01 -1.501156e-02 3.444245e-01 5.330723e+00 +3.239119e-01 -4.320487e-02 9.451002e-01 6.895352e+00 2.240032e-03 9.989889e-01 4.490066e-02 2.686406e-01 -9.460846e-01 -1.242680e-02 3.236812e-01 5.510973e+00 +3.087526e-01 -4.375508e-02 9.501354e-01 7.490216e+00 3.193237e-03 9.989833e-01 4.496694e-02 2.909019e-01 -9.511371e-01 -1.084965e-02 3.085784e-01 5.692965e+00 +2.971358e-01 -4.535063e-02 9.537576e-01 8.109243e+00 4.506657e-03 9.989269e-01 4.609440e-02 3.131206e-01 -9.548246e-01 -9.398038e-03 2.970213e-01 5.878028e+00 +2.861734e-01 -4.734783e-02 9.570073e-01 8.752695e+00 3.322596e-03 9.988214e-01 4.842303e-02 3.367873e-01 -9.581721e-01 -1.067764e-02 2.859935e-01 6.068197e+00 +2.755822e-01 -4.911161e-02 9.600221e-01 9.421853e+00 1.669367e-03 9.987170e-01 5.061191e-02 3.626882e-01 -9.612761e-01 -1.234511e-02 2.753106e-01 6.260273e+00 +2.654907e-01 -5.082935e-02 9.627726e-01 1.011201e+01 9.290294e-04 9.986223e-01 5.246585e-02 3.902645e-01 -9.641130e-01 -1.303475e-02 2.651722e-01 6.449695e+00 +2.552866e-01 -5.276707e-02 9.654245e-01 1.082597e+01 -1.024058e-04 9.985081e-01 5.460241e-02 4.193165e-01 -9.668655e-01 -1.403813e-02 2.549003e-01 6.636983e+00 +2.447070e-01 -5.444156e-02 9.680674e-01 1.155971e+01 -2.433160e-04 9.984189e-01 5.620996e-02 4.514517e-01 -9.695971e-01 -1.399052e-02 2.443069e-01 6.820541e+00 +2.344779e-01 -5.557489e-02 9.705316e-01 1.231146e+01 -2.675058e-04 9.983608e-01 5.723309e-02 4.861180e-01 -9.721215e-01 -1.367952e-02 2.340787e-01 7.000760e+00 +2.239597e-01 -5.876757e-02 9.728250e-01 1.308227e+01 -1.673765e-03 9.981557e-01 6.068311e-02 5.233622e-01 -9.745970e-01 -1.521885e-02 2.234483e-01 7.178249e+00 +2.126916e-01 -6.187357e-02 9.751584e-01 1.386203e+01 -3.499256e-03 9.979385e-01 6.408219e-02 5.631455e-01 -9.771131e-01 -1.704207e-02 2.120367e-01 7.350290e+00 +2.005651e-01 -6.644519e-02 9.774245e-01 1.464994e+01 -4.535082e-03 9.976237e-01 6.874892e-02 6.034900e-01 -9.796699e-01 -1.822133e-02 1.997872e-01 7.512325e+00 +1.876917e-01 -6.885220e-02 9.798118e-01 1.544431e+01 -5.479795e-03 9.974512e-01 7.114144e-02 6.443426e-01 -9.822127e-01 -1.872182e-02 1.868360e-01 7.663696e+00 +1.736602e-01 -6.949137e-02 9.823508e-01 1.624124e+01 -5.967304e-03 9.974147e-01 7.161190e-02 6.849788e-01 -9.847876e-01 -1.829812e-02 1.727966e-01 7.803818e+00 +1.593308e-01 -6.850007e-02 9.848459e-01 1.704599e+01 -7.306808e-03 9.974807e-01 7.056100e-02 7.272439e-01 -9.871982e-01 -1.843862e-02 1.584289e-01 7.933466e+00 +1.429603e-01 -6.748327e-02 9.874251e-01 1.785699e+01 -7.923195e-03 9.975628e-01 6.932325e-02 7.679911e-01 -9.896967e-01 -1.773403e-02 1.420772e-01 8.048258e+00 +1.227354e-01 -6.585881e-02 9.902518e-01 1.867273e+01 -1.036799e-02 9.976561e-01 6.763631e-02 8.064539e-01 -9.923853e-01 -1.856829e-02 1.217649e-01 8.147356e+00 +9.757047e-02 -6.460911e-02 9.931292e-01 1.949576e+01 -1.483434e-02 9.976852e-01 6.636292e-02 8.456493e-01 -9.951181e-01 -2.120748e-02 9.638618e-02 8.228210e+00 +6.770294e-02 -6.432262e-02 9.956299e-01 2.032201e+01 -1.914779e-02 9.976520e-01 6.575532e-02 8.850078e-01 -9.975218e-01 -2.351593e-02 6.631234e-02 8.284769e+00 +3.479944e-02 -6.389870e-02 9.973494e-01 2.115627e+01 -2.241608e-02 9.976529e-01 6.470029e-02 9.232781e-01 -9.991429e-01 -2.460820e-02 3.328541e-02 8.311045e+00 +5.546900e-04 -6.357691e-02 9.979768e-01 2.199272e+01 -2.432321e-02 9.976808e-01 6.357158e-02 9.585630e-01 -9.997040e-01 -2.430926e-02 -9.929930e-04 8.306307e+00 +-3.340201e-02 -6.247780e-02 9.974872e-01 2.283006e+01 -2.520042e-02 9.977795e-01 6.165225e-02 9.929263e-01 -9.991243e-01 -2.307779e-02 -3.490231e-02 8.271717e+00 +-6.618836e-02 -6.032882e-02 9.959817e-01 2.366830e+01 -2.699712e-02 9.979134e-01 5.865173e-02 1.025646e+00 -9.974419e-01 -2.300657e-02 -6.767896e-02 8.211107e+00 +-9.850067e-02 -5.772373e-02 9.934614e-01 2.450483e+01 -2.971433e-02 9.980417e-01 5.504372e-02 1.056280e+00 -9.946933e-01 -2.409820e-02 -1.000230e-01 8.124873e+00 +-1.309164e-01 -5.342831e-02 9.899527e-01 2.533863e+01 -2.760771e-02 9.983560e-01 5.023087e-02 1.084175e+00 -9.910090e-01 -2.075428e-02 -1.321762e-01 8.006449e+00 +-1.625338e-01 -4.777256e-02 9.855458e-01 2.616891e+01 -2.228189e-02 9.987502e-01 4.473795e-02 1.109162e+00 -9.864514e-01 -1.468840e-02 -1.633951e-01 7.855574e+00 +-1.929807e-01 -4.087264e-02 9.803509e-01 2.699155e+01 -1.639380e-02 9.991268e-01 3.842835e-02 1.128261e+00 -9.810656e-01 -8.655744e-03 -1.934823e-01 7.679836e+00 +-2.217761e-01 -3.548258e-02 9.744518e-01 2.781161e+01 -1.032218e-02 9.993671e-01 3.404059e-02 1.143099e+00 -9.750430e-01 -2.509075e-03 -2.220020e-01 7.478533e+00 +-2.497958e-01 -2.943698e-02 9.678510e-01 2.863097e+01 -2.214569e-03 9.995525e-01 2.982961e-02 1.152061e+00 -9.682960e-01 5.307937e-03 -2.497493e-01 7.246691e+00 +-2.760849e-01 -2.011543e-02 9.609227e-01 2.943803e+01 3.834841e-03 9.997499e-01 2.203001e-02 1.152695e+00 -9.611256e-01 9.767135e-03 -2.759387e-01 6.997717e+00 +-3.015542e-01 -4.619937e-03 9.534378e-01 3.023007e+01 8.514457e-03 9.999353e-01 7.538199e-03 1.146023e+00 -9.534111e-01 1.039118e-02 -3.014953e-01 6.731675e+00 +-3.263613e-01 1.306862e-02 9.451547e-01 3.101165e+01 9.918866e-03 9.998967e-01 -1.040056e-02 1.131823e+00 -9.451931e-01 5.980519e-03 -3.264572e-01 6.452447e+00 +-3.514700e-01 2.863449e-02 9.357611e-01 3.178304e+01 9.904458e-03 9.995899e-01 -2.686759e-02 1.108614e+00 -9.361468e-01 -1.749435e-04 -3.516094e-01 6.157692e+00 +-3.762472e-01 3.929353e-02 9.256857e-01 3.255086e+01 1.331029e-02 9.992264e-01 -3.700520e-02 1.070947e+00 -9.264237e-01 -1.601956e-03 -3.764792e-01 5.836955e+00 +-3.998266e-01 4.341498e-02 9.155620e-01 3.331009e+01 1.623309e-02 9.990563e-01 -4.028520e-02 1.026378e+00 -9.164471e-01 -1.244695e-03 -4.001541e-01 5.495463e+00 +-4.223468e-01 4.311262e-02 9.054085e-01 3.406148e+01 1.953336e-02 9.990692e-01 -3.846071e-02 9.790894e-01 -9.062239e-01 1.441909e-03 -4.227958e-01 5.135804e+00 +-4.426797e-01 3.912393e-02 8.958259e-01 3.480410e+01 2.306832e-02 9.992139e-01 -3.223987e-02 9.319901e-01 -8.963831e-01 6.393259e-03 -4.432343e-01 4.758144e+00 +-4.606858e-01 3.664421e-02 8.868065e-01 3.553210e+01 2.965531e-02 9.992250e-01 -2.588393e-02 8.869767e-01 -8.870678e-01 1.437416e-02 -4.614155e-01 4.363872e+00 +-4.745911e-01 3.835757e-02 8.793702e-01 3.624909e+01 3.368186e-02 9.991097e-01 -2.540263e-02 8.426907e-01 -8.795617e-01 1.756296e-02 -4.754606e-01 3.963231e+00 +-4.858028e-01 4.150123e-02 8.730826e-01 3.695412e+01 3.666324e-02 9.989606e-01 -2.708449e-02 8.025500e-01 -8.732992e-01 1.885231e-02 -4.868194e-01 3.562206e+00 +-4.957198e-01 4.472549e-02 8.673301e-01 3.764822e+01 3.863947e-02 9.988200e-01 -2.942176e-02 7.630243e-01 -8.676226e-01 1.892822e-02 -4.968630e-01 3.157985e+00 +-5.063042e-01 4.474437e-02 8.611933e-01 3.833941e+01 3.299499e-02 9.989269e-01 -3.250242e-02 7.189929e-01 -8.617235e-01 1.195895e-02 -5.072372e-01 2.756405e+00 +-5.178818e-01 4.212198e-02 8.544145e-01 3.902884e+01 3.066636e-02 9.990591e-01 -3.066523e-02 6.757535e-01 -8.549024e-01 1.032081e-02 -5.186863e-01 2.346023e+00 +-5.266306e-01 4.415413e-02 8.489468e-01 3.970737e+01 3.331460e-02 9.989550e-01 -3.128996e-02 6.348350e-01 -8.494412e-01 1.180406e-02 -5.275513e-01 1.915654e+00 +-5.337535e-01 4.751282e-02 8.443043e-01 4.038700e+01 3.698339e-02 9.987766e-01 -3.282548e-02 5.915961e-01 -8.448310e-01 1.370451e-02 -5.348577e-01 1.476584e+00 +-5.377401e-01 5.089544e-02 8.415731e-01 4.107846e+01 3.782421e-02 9.986276e-01 -3.622503e-02 5.487043e-01 -8.422618e-01 1.235218e-02 -5.389272e-01 1.032647e+00 +-5.375855e-01 5.280509e-02 8.415542e-01 4.178415e+01 3.775591e-02 9.985436e-01 -3.853724e-02 5.077496e-01 -8.423635e-01 1.105657e-02 -5.387963e-01 5.810905e-01 +-5.344232e-01 5.341072e-02 8.435278e-01 4.250745e+01 3.972003e-02 9.984858e-01 -3.805750e-02 4.621972e-01 -8.442832e-01 1.316614e-02 -5.357355e-01 1.215434e-01 +-5.288197e-01 5.163411e-02 8.471621e-01 4.325224e+01 3.804206e-02 9.985866e-01 -3.711657e-02 4.157685e-01 -8.478812e-01 1.259982e-02 -5.300365e-01 -3.378365e-01 +-5.220723e-01 5.058524e-02 8.513998e-01 4.401652e+01 3.598416e-02 9.986571e-01 -3.726920e-02 3.696084e-01 -8.521418e-01 1.117969e-02 -5.231915e-01 -7.952287e-01 +-5.150921e-01 5.001533e-02 8.556743e-01 4.479847e+01 3.429061e-02 9.986993e-01 -3.773337e-02 3.229204e-01 -8.564487e-01 9.905426e-03 -5.161372e-01 -1.255569e+00 +-5.088807e-01 4.844952e-02 8.594725e-01 4.559797e+01 3.153601e-02 9.987939e-01 -3.763126e-02 2.752422e-01 -8.602592e-01 7.954512e-03 -5.097949e-01 -1.718077e+00 +-5.044189e-01 4.647981e-02 8.622072e-01 4.641671e+01 2.735822e-02 9.989091e-01 -3.784371e-02 2.251199e-01 -8.630256e-01 4.499376e-03 -5.051402e-01 -2.182613e+00 +-5.029009e-01 4.338914e-02 8.632543e-01 4.725344e+01 2.275913e-02 9.990577e-01 -3.695629e-02 1.721279e-01 -8.640444e-01 1.061566e-03 -5.034145e-01 -2.652713e+00 +-5.033481e-01 4.071247e-02 8.631241e-01 4.810244e+01 1.953136e-02 9.991702e-01 -3.573950e-02 1.191937e-01 -8.638630e-01 -1.131428e-03 -5.037257e-01 -3.132580e+00 +-5.044132e-01 3.921978e-02 8.625712e-01 4.896156e+01 1.799253e-02 9.992284e-01 -3.491174e-02 6.614438e-02 -8.632750e-01 -2.090104e-03 -5.047297e-01 -3.622610e+00 +-5.048517e-01 3.860670e-02 8.623423e-01 4.982913e+01 1.791862e-02 9.992528e-01 -3.424582e-02 1.543395e-02 -8.630201e-01 -1.837075e-03 -5.051663e-01 -4.119797e+00 +-5.050504e-01 3.780329e-02 8.622616e-01 5.070986e+01 1.785762e-02 9.992841e-01 -3.335095e-02 -3.397462e-02 -8.629051e-01 -1.445966e-03 -5.053639e-01 -4.626524e+00 +-5.050733e-01 3.726614e-02 8.622715e-01 5.160092e+01 1.804432e-02 9.993049e-01 -3.261913e-02 -8.461152e-02 -8.628878e-01 -9.159473e-04 -5.053947e-01 -5.138527e+00 +-5.051532e-01 3.675080e-02 8.622469e-01 5.249660e+01 1.772603e-02 9.993239e-01 -3.220842e-02 -1.359794e-01 -8.628477e-01 -9.859714e-04 -5.054631e-01 -5.654198e+00 +-5.053926e-01 3.521010e-02 8.621708e-01 5.339938e+01 1.608035e-02 9.993779e-01 -3.138742e-02 -1.889423e-01 -8.627397e-01 -1.998966e-03 -5.056444e-01 -6.170360e+00 +-5.053618e-01 3.420743e-02 8.622293e-01 5.429898e+01 1.557393e-02 9.994127e-01 -3.052190e-02 -2.428121e-01 -8.627670e-01 -1.996305e-03 -5.055978e-01 -6.686856e+00 +-5.048319e-01 3.357890e-02 8.625643e-01 5.519750e+01 1.438190e-02 9.994316e-01 -3.048977e-02 -2.987033e-01 -8.630979e-01 -2.986898e-03 -5.050279e-01 -7.201418e+00 +-5.036775e-01 3.212028e-02 8.632944e-01 5.609471e+01 1.388352e-02 9.994804e-01 -2.908717e-02 -3.531245e-01 -8.637802e-01 -2.664987e-03 -5.038618e-01 -7.714224e+00 +-5.016360e-01 2.992057e-02 8.645612e-01 5.699227e+01 1.431070e-02 9.995519e-01 -2.628895e-02 -4.067709e-01 -8.649605e-01 -8.150146e-04 -5.018394e-01 -8.225644e+00 +-4.992242e-01 2.838957e-02 8.660076e-01 5.788905e+01 1.463781e-02 9.995968e-01 -2.433071e-02 -4.587551e-01 -8.663492e-01 5.299693e-04 -4.994385e-01 -8.733355e+00 +-4.969069e-01 2.798481e-02 8.673525e-01 5.878294e+01 1.489235e-02 9.996077e-01 -2.372015e-02 -5.090484e-01 -8.676761e-01 1.130207e-03 -4.971287e-01 -9.236703e+00 +-4.947333e-01 2.852664e-02 8.685765e-01 5.967603e+01 1.553885e-02 9.995917e-01 -2.397879e-02 -5.592501e-01 -8.689059e-01 1.633571e-03 -4.949746e-01 -9.738335e+00 +-4.938511e-01 2.886037e-02 8.690674e-01 6.056830e+01 1.538354e-02 9.995826e-01 -2.445283e-02 -6.093983e-01 -8.694104e-01 1.293278e-03 -4.940889e-01 -1.023718e+01 +-4.943765e-01 3.022571e-02 8.687222e-01 6.145389e+01 1.478575e-02 9.995431e-01 -2.636307e-02 -6.617839e-01 -8.691222e-01 -1.885739e-04 -4.945975e-01 -1.073111e+01 +-4.972170e-01 3.192219e-02 8.670388e-01 6.233532e+01 1.346887e-02 9.994865e-01 -2.907467e-02 -7.144474e-01 -8.675217e-01 -2.778388e-03 -4.973916e-01 -1.122461e+01 +-5.016094e-01 3.254093e-02 8.644820e-01 6.320903e+01 1.236763e-02 9.994599e-01 -3.044557e-02 -7.673912e-01 -8.650059e-01 -4.580190e-03 -5.017409e-01 -1.172056e+01 +-5.070402e-01 3.135650e-02 8.613519e-01 6.407973e+01 1.295155e-02 9.995024e-01 -2.876170e-02 -8.195839e-01 -8.618252e-01 -3.427495e-03 -5.071940e-01 -1.222485e+01 +-5.125311e-01 2.874164e-02 8.581875e-01 6.494007e+01 1.437747e-02 9.995868e-01 -2.489068e-02 -8.749911e-01 -8.585483e-01 -4.186835e-04 -5.127325e-01 -1.273747e+01 +-5.177335e-01 2.656506e-02 8.551294e-01 6.579473e+01 1.185191e-02 9.996446e-01 -2.387884e-02 -9.282033e-01 -8.554599e-01 -2.227959e-03 -5.178643e-01 -1.324559e+01 +-5.226363e-01 2.941155e-02 8.520482e-01 6.663750e+01 1.399654e-02 9.995660e-01 -2.591837e-02 -9.805354e-01 -8.524408e-01 -1.620158e-03 -5.228212e-01 -1.375919e+01 +-5.274222e-01 3.189323e-02 8.490045e-01 6.747269e+01 1.432573e-02 9.994869e-01 -2.864670e-02 -1.033058e+00 -8.494826e-01 -2.946299e-03 -5.276085e-01 -1.427378e+01 +-5.323119e-01 3.183277e-02 8.459496e-01 6.830616e+01 1.267510e-02 9.994804e-01 -2.963431e-02 -1.087156e+00 -8.464535e-01 -5.052202e-03 -5.324388e-01 -1.478945e+01 +-5.360908e-01 3.225966e-02 8.435437e-01 6.913168e+01 1.171101e-02 9.994576e-01 -3.077968e-02 -1.141061e+00 -8.440791e-01 -6.621957e-03 -5.361778e-01 -1.530806e+01 +-5.393463e-01 3.139766e-02 8.414985e-01 6.995241e+01 1.242015e-02 9.994925e-01 -2.933216e-02 -1.192211e+00 -8.419925e-01 -5.368650e-03 -5.394625e-01 -1.583039e+01 +-5.418385e-01 2.556549e-02 8.400937e-01 7.077487e+01 1.359325e-02 9.996731e-01 -2.165448e-02 -1.238526e+00 -8.403727e-01 -3.136271e-04 -5.420089e-01 -1.635928e+01 +-5.439621e-01 1.656099e-02 8.389463e-01 7.159496e+01 1.328968e-02 9.998498e-01 -1.112041e-02 -1.282215e+00 -8.390046e-01 5.100239e-03 -5.441005e-01 -1.688675e+01 +-5.457263e-01 1.194765e-02 8.378783e-01 7.240886e+01 1.266240e-02 9.999017e-01 -6.010750e-03 -1.318045e+00 -8.378678e-01 7.329323e-03 -5.458240e-01 -1.741131e+01 +-5.467919e-01 1.945582e-02 8.370425e-01 7.320718e+01 1.388613e-02 9.998032e-01 -1.416795e-02 -1.352730e+00 -8.371534e-01 3.876361e-03 -5.469545e-01 -1.793042e+01 +-5.478065e-01 2.543605e-02 8.362183e-01 7.399928e+01 1.563674e-02 9.996744e-01 -2.016444e-02 -1.391231e+00 -8.364589e-01 2.029515e-03 -5.480259e-01 -1.845101e+01 +-5.482496e-01 3.003017e-02 8.357754e-01 7.479183e+01 2.118694e-02 9.995331e-01 -2.201599e-02 -1.430026e+00 -8.360464e-01 5.637266e-03 -5.486298e-01 -1.897578e+01 +-5.479916e-01 3.041695e-02 8.359306e-01 7.558518e+01 2.480583e-02 9.994900e-01 -2.010701e-02 -1.475622e+00 -8.361160e-01 9.717477e-03 -5.484666e-01 -1.950011e+01 +-5.474528e-01 2.758302e-02 8.363819e-01 7.638160e+01 2.401024e-02 9.995629e-01 -1.724870e-02 -1.517748e+00 -8.364921e-01 1.063888e-02 -5.478757e-01 -2.001769e+01 +-5.467379e-01 2.340864e-02 8.369765e-01 7.717766e+01 2.306230e-02 9.996509e-01 -1.289336e-02 -1.553839e+00 -8.369861e-01 1.225331e-02 -5.470869e-01 -2.053358e+01 +-5.459641e-01 1.677805e-02 8.376405e-01 7.797620e+01 2.007551e-02 9.997744e-01 -6.940643e-03 -1.590768e+00 -8.375680e-01 1.302671e-02 -5.461778e-01 -2.104565e+01 +-5.455092e-01 1.006165e-02 8.380444e-01 7.877335e+01 1.161550e-02 9.999226e-01 -4.444298e-03 -1.622926e+00 -8.380244e-01 7.309898e-03 -5.455839e-01 -2.154511e+01 +-5.440667e-01 5.812895e-03 8.390218e-01 7.957091e+01 4.337534e-03 9.999821e-01 -4.115375e-03 -1.647452e+00 -8.390308e-01 1.400245e-03 -5.440822e-01 -2.204329e+01 +-5.420740e-01 5.488407e-03 8.403128e-01 8.035975e+01 6.576327e-03 9.999757e-01 -2.288938e-03 -1.672576e+00 -8.403051e-01 4.285396e-03 -5.420969e-01 -2.255003e+01 +-5.389628e-01 7.989060e-03 8.422917e-01 8.114486e+01 1.078112e-02 9.999385e-01 -2.585744e-03 -1.699977e+00 -8.422606e-01 7.687229e-03 -5.390158e-01 -2.305551e+01 +-5.339357e-01 1.250467e-02 8.454326e-01 8.193166e+01 1.321294e-02 9.998919e-01 -6.444587e-03 -1.723704e+00 -8.454219e-01 7.729654e-03 -5.340432e-01 -2.355204e+01 +-5.262425e-01 1.515726e-02 8.501994e-01 8.272160e+01 1.899031e-02 9.998012e-01 -6.070036e-03 -1.744715e+00 -8.501225e-01 1.295124e-02 -5.264258e-01 -2.404556e+01 +-5.181164e-01 1.686560e-02 8.551438e-01 8.351715e+01 2.586392e-02 9.996573e-01 -4.045287e-03 -1.770218e+00 -8.549190e-01 2.002144e-02 -5.183751e-01 -2.453507e+01 +-5.083152e-01 1.723890e-02 8.609985e-01 8.431881e+01 2.451954e-02 9.996840e-01 -5.539851e-03 -1.788533e+00 -8.608220e-01 1.829529e-02 -5.085773e-01 -2.500280e+01 +-4.974733e-01 1.516480e-02 8.673467e-01 8.513089e+01 2.234398e-02 9.997394e-01 -4.664016e-03 -1.805753e+00 -8.671915e-01 1.705975e-02 -4.976825e-01 -2.545724e+01 +-4.858919e-01 1.153787e-02 8.739427e-01 8.594484e+01 2.212486e-02 9.997548e-01 -8.979555e-04 -1.822552e+00 -8.737389e-01 1.889955e-02 -4.860280e-01 -2.590591e+01 +-4.747080e-01 1.005332e-02 8.800859e-01 8.675945e+01 2.184015e-02 9.997614e-01 3.599212e-04 -1.839846e+00 -8.798723e-01 1.939206e-02 -4.748143e-01 -2.633928e+01 +-4.628420e-01 9.424718e-03 8.863907e-01 8.758352e+01 2.261341e-02 9.997436e-01 1.177951e-03 -1.851770e+00 -8.861524e-01 2.058951e-02 -4.629364e-01 -2.676347e+01 +-4.508179e-01 1.059844e-02 8.925530e-01 8.840537e+01 2.496485e-02 9.996880e-01 7.388452e-04 -1.869075e+00 -8.922668e-01 2.261553e-02 -4.509418e-01 -2.717759e+01 +-4.386412e-01 1.304329e-02 8.985676e-01 8.923085e+01 2.421538e-02 9.997031e-01 -2.690457e-03 -1.893883e+00 -8.983360e-01 2.057901e-02 -4.388269e-01 -2.757508e+01 +-4.268339e-01 2.386630e-02 9.040150e-01 9.005203e+01 2.785083e-02 9.995244e-01 -1.323792e-02 -1.917750e+00 -9.039011e-01 1.952717e-02 -4.272957e-01 -2.796252e+01 +-4.141655e-01 2.921613e-02 9.097326e-01 9.088071e+01 2.820888e-02 9.994166e-01 -1.925396e-02 -1.943851e+00 -9.097644e-01 1.768821e-02 -4.147480e-01 -2.833927e+01 +-4.025051e-01 2.517720e-02 9.150714e-01 9.172222e+01 2.639237e-02 9.995253e-01 -1.589187e-02 -1.977509e+00 -9.150372e-01 1.775434e-02 -4.029785e-01 -2.870201e+01 +-3.905536e-01 2.123822e-02 9.203352e-01 9.256728e+01 2.516643e-02 9.996065e-01 -1.238791e-02 -2.011590e+00 -9.202362e-01 1.832341e-02 -3.909344e-01 -2.905556e+01 +-3.805729e-01 2.196923e-02 9.244899e-01 9.340903e+01 2.221502e-02 9.996464e-01 -1.461026e-02 -2.046250e+00 -9.244841e-01 1.497729e-02 -3.809264e-01 -2.939508e+01 +-3.733046e-01 2.566433e-02 9.273538e-01 9.424877e+01 1.804085e-02 9.996290e-01 -2.040224e-02 -2.082058e+00 -9.275334e-01 9.113996e-03 -3.736291e-01 -2.972193e+01 +-3.683183e-01 3.118118e-02 9.291767e-01 9.509156e+01 1.232014e-02 9.995133e-01 -2.865793e-02 -2.119871e+00 -9.296181e-01 8.923471e-04 -3.685233e-01 -3.004218e+01 +-3.647887e-01 3.303496e-02 9.305041e-01 9.593682e+01 9.476799e-03 9.994503e-01 -3.176750e-02 -2.163160e+00 -9.310421e-01 -2.770224e-03 -3.649012e-01 -3.036357e+01 +-3.610781e-01 3.266680e-02 9.319632e-01 9.678367e+01 7.428916e-03 9.994553e-01 -3.215427e-02 -2.209948e+00 -9.325060e-01 -4.686727e-03 -3.611241e-01 -3.068310e+01 +-3.562009e-01 3.299304e-02 9.338267e-01 9.762797e+01 7.842455e-03 9.994468e-01 -3.232003e-02 -2.254489e+00 -9.343765e-01 -4.188933e-03 -3.562626e-01 -3.099995e+01 +-3.505397e-01 2.979465e-02 9.360738e-01 9.847826e+01 5.777884e-03 9.995436e-01 -2.965117e-02 -2.300639e+00 -9.365301e-01 -4.985387e-03 -3.505519e-01 -3.131096e+01 +-3.452582e-01 2.514112e-02 9.381709e-01 9.933337e+01 4.706859e-03 9.996749e-01 -2.505714e-02 -2.347890e+00 -9.384960e-01 -4.235346e-03 -3.452643e-01 -3.161656e+01 +-3.394918e-01 2.250644e-02 9.403397e-01 1.001848e+02 3.820552e-03 9.997384e-01 -2.254878e-02 -2.394151e+00 -9.406013e-01 -4.062511e-03 -3.394890e-01 -3.191408e+01 +-3.337775e-01 2.063786e-02 9.424259e-01 1.010383e+02 -3.821443e-03 9.997224e-01 -2.324602e-02 -2.436801e+00 -9.426442e-01 -1.136043e-02 -3.336060e-01 -3.219559e+01 +-3.277148e-01 2.098731e-02 9.445436e-01 1.018913e+02 -1.177247e-02 9.995849e-01 -2.629484e-02 -2.479664e+00 -9.447034e-01 -1.973682e-02 -3.273317e-01 -3.246899e+01 +-3.209593e-01 2.394099e-02 9.467903e-01 1.027387e+02 -1.075982e-02 9.995237e-01 -2.892199e-02 -2.524306e+00 -9.470319e-01 -1.947007e-02 -3.205488e-01 -3.274622e+01 +-3.137758e-01 2.794270e-02 9.490858e-01 1.035885e+02 -7.876338e-03 9.994559e-01 -3.202967e-02 -2.567807e+00 -9.494645e-01 -1.752545e-02 -3.133850e-01 -3.302355e+01 +-3.071515e-01 2.636724e-02 9.512953e-01 1.044455e+02 -8.735291e-03 9.994958e-01 -3.052366e-02 -2.610933e+00 -9.516206e-01 -1.768523e-02 -3.067663e-01 -3.328918e+01 +-3.003027e-01 2.118723e-02 9.536086e-01 1.053065e+02 -9.618011e-03 9.996352e-01 -2.523868e-02 -2.657199e+00 -9.537955e-01 -1.675106e-02 -2.999894e-01 -3.355357e+01 +-2.932163e-01 1.801806e-02 9.558763e-01 1.061709e+02 -1.095002e-02 9.996935e-01 -2.220294e-02 -2.704158e+00 -9.559835e-01 -1.697713e-02 -2.929291e-01 -3.380988e+01 +-2.867608e-01 2.111858e-02 9.577694e-01 1.070286e+02 -1.249763e-02 9.995894e-01 -2.578256e-02 -2.745462e+00 -9.579207e-01 -1.936328e-02 -2.863791e-01 -3.405765e+01 +-2.804609e-01 2.379786e-02 9.595704e-01 1.078896e+02 -1.253753e-02 9.995165e-01 -2.845300e-02 -2.790316e+00 -9.597836e-01 -2.001059e-02 -2.800269e-01 -3.429846e+01 +-2.737320e-01 2.547350e-02 9.614686e-01 1.087523e+02 -1.377364e-02 9.994429e-01 -3.040099e-02 -2.835895e+00 -9.617074e-01 -2.156465e-02 -2.732286e-01 -3.453399e+01 +-2.668961e-01 2.401130e-02 9.634261e-01 1.096205e+02 -1.457336e-02 9.994747e-01 -2.894697e-02 -2.882830e+00 -9.636151e-01 -2.176619e-02 -2.664060e-01 -3.476364e+01 +-2.589284e-01 2.418283e-02 9.655937e-01 1.104870e+02 -1.125545e-02 9.995431e-01 -2.805129e-02 -2.928512e+00 -9.658310e-01 -1.813147e-02 -2.585379e-01 -3.499323e+01 +-2.511015e-01 2.499321e-02 9.676380e-01 1.113535e+02 -7.608843e-03 9.995847e-01 -2.779286e-02 -2.973590e+00 -9.679309e-01 -1.434143e-02 -2.508071e-01 -3.521847e+01 +-2.444176e-01 2.539490e-02 9.693375e-01 1.122223e+02 -5.921582e-03 9.995992e-01 -2.768083e-02 -3.017837e+00 -9.696520e-01 -1.250569e-02 -2.441693e-01 -3.543239e+01 +-2.378125e-01 2.455726e-02 9.710006e-01 1.130945e+02 -1.164016e-02 9.995365e-01 -2.812981e-02 -3.062720e+00 -9.712414e-01 -1.799222e-02 -2.374164e-01 -3.563108e+01 +-2.319982e-01 2.287074e-02 9.724473e-01 1.139689e+02 -1.557129e-02 9.995081e-01 -2.722205e-02 -3.106520e+00 -9.725916e-01 -2.145772e-02 -2.315279e-01 -3.582432e+01 +-2.272133e-01 2.240141e-02 9.735873e-01 1.148418e+02 -1.347358e-02 9.995674e-01 -2.614362e-02 -3.150123e+00 -9.737518e-01 -1.905788e-02 -2.268132e-01 -3.602323e+01 +-2.224437e-01 2.249694e-02 9.746859e-01 1.157147e+02 -1.189422e-02 9.995967e-01 -2.578643e-02 -3.193868e+00 -9.748730e-01 -1.732916e-02 -2.220865e-01 -3.621819e+01 +-2.178083e-01 2.499013e-02 9.756716e-01 1.165857e+02 -1.117689e-02 9.995427e-01 -2.809667e-02 -3.239438e+00 -9.759276e-01 -1.702466e-02 -2.174294e-01 -3.640785e+01 +-2.119260e-01 2.342173e-02 9.770050e-01 1.174624e+02 -5.456451e-03 9.996688e-01 -2.514864e-02 -3.279199e+00 -9.772705e-01 -1.066063e-02 -2.117280e-01 -3.660169e+01 +-2.065606e-01 2.222651e-02 9.781813e-01 1.183368e+02 1.707797e-03 9.997486e-01 -2.235594e-02 -3.318375e+00 -9.784323e-01 -2.947323e-03 -2.065467e-01 -3.679450e+01 +-2.015798e-01 2.103207e-02 9.792463e-01 1.192101e+02 4.223693e-03 9.997788e-01 -2.060362e-02 -3.361858e+00 -9.794630e-01 -1.723813e-05 -2.016240e-01 -3.697484e+01 +-1.973516e-01 2.314005e-02 9.800596e-01 1.200850e+02 2.787658e-03 9.997306e-01 -2.304316e-02 -3.401094e+00 -9.803288e-01 -1.815536e-03 -1.973629e-01 -3.714466e+01 +-1.937151e-01 2.500661e-02 9.807391e-01 1.209561e+02 1.453140e-03 9.996813e-01 -2.520258e-02 -3.438516e+00 -9.810568e-01 -3.456971e-03 -1.936897e-01 -3.731126e+01 +-1.918428e-01 2.395892e-02 9.811332e-01 1.218304e+02 -1.259154e-03 9.996951e-01 -2.465841e-02 -3.481415e+00 -9.814249e-01 -5.965936e-03 -1.917541e-01 -3.747460e+01 +-1.909599e-01 2.259668e-02 9.813377e-01 1.227039e+02 -1.834021e-03 9.997250e-01 -2.337697e-02 -3.521474e+00 -9.815962e-01 -6.263858e-03 -1.908659e-01 -3.763878e+01 +-1.897881e-01 1.940018e-02 9.816334e-01 1.235754e+02 1.819514e-04 9.998054e-01 -1.972415e-02 -3.558368e+00 -9.818251e-01 -3.564802e-03 -1.897548e-01 -3.780867e+01 +-1.886932e-01 1.352981e-02 9.819429e-01 1.244524e+02 -7.890136e-04 9.999027e-01 -1.392890e-02 -3.596100e+00 -9.820358e-01 -3.403055e-03 -1.886641e-01 -3.797627e+01 +-1.878979e-01 1.059726e-02 9.821314e-01 1.253205e+02 -1.241330e-03 9.999384e-01 -1.102690e-02 -3.631060e+00 -9.821878e-01 -3.291082e-03 -1.878732e-01 -3.814146e+01 +-1.864555e-01 1.582892e-02 9.823359e-01 1.261781e+02 -7.433190e-04 9.998676e-01 -1.625252e-02 -3.664261e+00 -9.824632e-01 -3.760562e-03 -1.864191e-01 -3.830594e+01 +-1.863838e-01 2.013241e-02 9.822707e-01 1.270337e+02 -5.057937e-04 9.997879e-01 -2.058742e-02 -3.697685e+00 -9.824769e-01 -4.333989e-03 -1.863341e-01 -3.846973e+01 +-1.865559e-01 1.904350e-02 9.822597e-01 1.278916e+02 -3.457152e-03 9.997932e-01 -2.004004e-02 -3.731608e+00 -9.824383e-01 -7.134410e-03 -1.864515e-01 -3.862938e+01 +-1.859169e-01 1.858096e-02 9.823898e-01 1.287490e+02 -5.010791e-03 9.997902e-01 -1.985837e-02 -3.773125e+00 -9.825527e-01 -8.614557e-03 -1.857848e-01 -3.878916e+01 +-1.854941e-01 1.781189e-02 9.824839e-01 1.296019e+02 -2.315256e-03 9.998250e-01 -1.856340e-02 -3.812511e+00 -9.826427e-01 -5.718104e-03 -1.854204e-01 -3.895463e+01 +-1.844108e-01 2.100880e-02 9.826247e-01 1.304485e+02 -2.083493e-03 9.997609e-01 -2.176619e-02 -3.847217e+00 -9.828471e-01 -6.061214e-03 -1.843230e-01 -3.911538e+01 +-1.847210e-01 2.266165e-02 9.825297e-01 1.312944e+02 -1.027674e-02 9.996349e-01 -2.498827e-02 -3.890191e+00 -9.827373e-01 -1.471305e-02 -1.844207e-01 -3.925481e+01 +-1.845558e-01 2.340401e-02 9.825433e-01 1.321343e+02 -1.690605e-02 9.994929e-01 -2.698330e-02 -3.932338e+00 -9.826767e-01 -2.159085e-02 -1.840665e-01 -3.939553e+01 +-1.840457e-01 2.731460e-02 9.825381e-01 1.329698e+02 -1.452944e-02 9.994290e-01 -3.050578e-02 -3.974607e+00 -9.828103e-01 -1.989018e-02 -1.835437e-01 -3.954593e+01 +-1.836688e-01 2.765970e-02 9.825989e-01 1.338003e+02 -1.295262e-02 9.994491e-01 -3.055516e-02 -4.018902e+00 -9.829029e-01 -1.833926e-02 -1.832094e-01 -3.969762e+01 +-1.819559e-01 2.942864e-02 9.828662e-01 1.346231e+02 -1.360384e-02 9.993810e-01 -3.244158e-02 -4.063364e+00 -9.832126e-01 -1.927369e-02 -1.814430e-01 -3.984431e+01 +-1.801141e-01 2.846824e-02 9.832337e-01 1.354495e+02 -6.217937e-03 9.995282e-01 -3.007907e-02 -4.105477e+00 -9.836261e-01 -1.153135e-02 -1.798521e-01 -3.999979e+01 +-1.765192e-01 2.590211e-02 9.839563e-01 1.362673e+02 -3.216046e-05 9.996535e-01 -2.632111e-02 -4.146973e+00 -9.842972e-01 -4.677825e-03 -1.764572e-01 -4.015282e+01 +-1.745228e-01 2.003470e-02 9.844493e-01 1.370908e+02 3.831228e-03 9.997992e-01 -1.966789e-02 -4.188573e+00 -9.846457e-01 3.391515e-04 -1.745645e-01 -4.030057e+01 +-1.709157e-01 1.984713e-02 9.850857e-01 1.379023e+02 4.990895e-03 9.998017e-01 -1.927769e-02 -4.226372e+00 -9.852730e-01 1.621597e-03 -1.709809e-01 -4.043780e+01 +-1.657101e-01 2.461578e-02 9.858672e-01 1.387057e+02 7.087553e-03 9.996923e-01 -2.376967e-02 -4.266655e+00 -9.861491e-01 3.048509e-03 -1.658336e-01 -4.057118e+01 +-1.595131e-01 2.741188e-02 9.868151e-01 1.395060e+02 7.560578e-03 9.996190e-01 -2.654543e-02 -4.303913e+00 -9.871669e-01 3.226546e-03 -1.596596e-01 -4.069614e+01 +-1.510622e-01 2.978881e-02 9.880753e-01 1.403054e+02 8.529771e-03 9.995479e-01 -2.883062e-02 -4.337506e+00 -9.884875e-01 4.072837e-03 -1.512480e-01 -4.081224e+01 +-1.414671e-01 2.471475e-02 9.896344e-01 1.411082e+02 9.549968e-03 9.996758e-01 -2.360038e-02 -4.377901e+00 -9.898969e-01 6.112296e-03 -1.416573e-01 -4.091861e+01 +-1.295920e-01 2.265996e-02 9.913084e-01 1.419062e+02 1.329475e-02 9.996887e-01 -2.111353e-02 -4.419464e+00 -9.914783e-01 1.044305e-02 -1.298529e-01 -4.101862e+01 +-1.158117e-01 2.562887e-02 9.929405e-01 1.426964e+02 1.816665e-02 9.995545e-01 -2.368073e-02 -4.456348e+00 -9.931051e-01 1.529589e-02 -1.162257e-01 -4.110993e+01 +-1.015031e-01 2.677699e-02 9.944748e-01 1.434862e+02 1.785896e-02 9.995256e-01 -2.509018e-02 -4.491871e+00 -9.946749e-01 1.521355e-02 -1.019332e-01 -4.118413e+01 +-8.754946e-02 2.669749e-02 9.958023e-01 1.442760e+02 1.966065e-02 9.994924e-01 -2.506790e-02 -4.527880e+00 -9.959662e-01 1.738343e-02 -8.802991e-02 -4.124845e+01 +-7.378080e-02 2.871236e-02 9.968611e-01 1.450550e+02 2.087230e-02 9.994109e-01 -2.724099e-02 -4.567642e+00 -9.970561e-01 1.879692e-02 -7.433664e-02 -4.130354e+01 +-6.007383e-02 3.396391e-02 9.976159e-01 1.458274e+02 1.817545e-02 9.992925e-01 -3.292652e-02 -4.612403e+00 -9.980285e-01 1.615409e-02 -6.064864e-02 -4.134484e+01 +-4.729335e-02 4.371848e-02 9.979238e-01 1.465903e+02 1.185184e-02 9.989960e-01 -4.320378e-02 -4.657895e+00 -9.988108e-01 9.783979e-03 -4.776401e-02 -4.136686e+01 +-3.365131e-02 5.194575e-02 9.980828e-01 1.473502e+02 7.775331e-03 9.986317e-01 -5.171219e-02 -4.704613e+00 -9.994034e-01 6.020237e-03 -3.400917e-02 -4.138182e+01 +-2.002613e-02 5.368971e-02 9.983568e-01 1.481169e+02 7.113446e-03 9.985394e-01 -5.355686e-02 -4.754981e+00 -9.997742e-01 6.029218e-03 -2.037880e-02 -4.139015e+01 +-8.163869e-03 4.952903e-02 9.987393e-01 1.488864e+02 3.500342e-03 9.987679e-01 -4.950185e-02 -4.810016e+00 -9.999606e-01 3.091800e-03 -8.327181e-03 -4.138452e+01 +2.646406e-03 4.615038e-02 9.989310e-01 1.496472e+02 -9.327185e-04 9.989342e-01 -4.614806e-02 -4.866196e+00 -9.999961e-01 -8.095969e-04 2.686629e-03 -4.136492e+01 +1.192390e-02 5.225100e-02 9.985628e-01 1.503945e+02 -4.532445e-03 9.986263e-01 -5.220021e-02 -4.922570e+00 -9.999187e-01 -3.903502e-03 1.214434e-02 -4.133785e+01 +1.878440e-02 6.076957e-02 9.979750e-01 1.511367e+02 -7.115607e-03 9.981340e-01 -6.064534e-02 -4.975189e+00 -9.997983e-01 -5.962013e-03 1.918176e-02 -4.130745e+01 +2.218974e-02 6.436398e-02 9.976797e-01 1.518836e+02 -1.067848e-02 9.978838e-01 -6.413966e-02 -5.025972e+00 -9.996968e-01 -9.230458e-03 2.283008e-02 -4.127171e+01 +2.219372e-02 6.086016e-02 9.978995e-01 1.526403e+02 -1.256480e-02 9.980835e-01 -6.059195e-02 -5.085267e+00 -9.996748e-01 -1.119365e-02 2.291588e-02 -4.124316e+01 +2.045747e-02 5.497074e-02 9.982784e-01 1.533945e+02 -1.520047e-02 9.983890e-01 -5.466535e-02 -5.150084e+00 -9.996752e-01 -1.405598e-02 2.126009e-02 -4.121665e+01 +1.756130e-02 5.215584e-02 9.984845e-01 1.541484e+02 -1.364942e-02 9.985580e-01 -5.191963e-02 -5.204637e+00 -9.997526e-01 -1.271696e-02 1.824787e-02 -4.119287e+01 +1.481687e-02 5.255732e-02 9.985080e-01 1.548963e+02 -1.108381e-02 9.985649e-01 -5.239586e-02 -5.253941e+00 -9.998288e-01 -1.029093e-02 1.537814e-02 -4.117199e+01 +1.124625e-02 5.286943e-02 9.985381e-01 1.556412e+02 -9.789684e-03 9.985592e-01 -5.276030e-02 -5.309298e+00 -9.998889e-01 -9.182017e-03 1.174762e-02 -4.115767e+01 +6.389337e-03 5.045509e-02 9.987059e-01 1.563926e+02 -1.101256e-02 9.986692e-01 -5.038280e-02 -5.366278e+00 -9.999190e-01 -1.067639e-02 6.936472e-03 -4.113867e+01 +1.199615e-03 5.169393e-02 9.986622e-01 1.571395e+02 -1.082611e-02 9.986051e-01 -5.167798e-02 -5.416962e+00 -9.999407e-01 -1.074963e-02 1.757583e-03 -4.112929e+01 +-4.773199e-03 4.970055e-02 9.987527e-01 1.578857e+02 -1.210913e-02 9.986880e-01 -4.975521e-02 -5.470893e+00 -9.999153e-01 -1.233152e-02 -4.165108e-03 -4.112225e+01 +-1.074993e-02 4.589409e-02 9.988885e-01 1.586302e+02 -1.067932e-02 9.988839e-01 -4.600882e-02 -5.528080e+00 -9.998852e-01 -1.116204e-02 -1.024781e-02 -4.112149e+01 +-1.593767e-02 4.683018e-02 9.987757e-01 1.593643e+02 -1.069640e-02 9.988374e-01 -4.700378e-02 -5.577823e+00 -9.998158e-01 -1.143244e-02 -1.541823e-02 -4.112304e+01 +-2.139593e-02 4.793854e-02 9.986211e-01 1.600952e+02 -1.220626e-02 9.987628e-01 -4.820688e-02 -5.628365e+00 -9.996966e-01 -1.322085e-02 -2.078431e-02 -4.112638e+01 +-2.558249e-02 4.989856e-02 9.984266e-01 1.608215e+02 -1.305593e-02 9.986516e-01 -5.024435e-02 -5.683305e+00 -9.995875e-01 -1.432077e-02 -2.489653e-02 -4.113308e+01 +-2.820504e-02 5.178909e-02 9.982597e-01 1.615415e+02 -1.324531e-02 9.985499e-01 -5.217840e-02 -5.738588e+00 -9.995144e-01 -1.469396e-02 -2.747818e-02 -4.114341e+01 +-2.992572e-02 5.385780e-02 9.981001e-01 1.622559e+02 -1.048767e-02 9.984754e-01 -5.419251e-02 -5.787286e+00 -9.994971e-01 -1.208949e-02 -2.931525e-02 -4.115910e+01 +-2.940260e-02 5.265598e-02 9.981797e-01 1.629748e+02 -6.988320e-03 9.985763e-01 -5.288276e-02 -5.840496e+00 -9.995433e-01 -8.530491e-03 -2.899277e-02 -4.117304e+01 +-2.561126e-02 4.858595e-02 9.984906e-01 1.636911e+02 -4.532311e-03 9.988023e-01 -4.871738e-02 -5.895410e+00 -9.996617e-01 -5.773185e-03 -2.536039e-02 -4.118458e+01 +-1.844503e-02 4.780467e-02 9.986864e-01 1.643994e+02 -3.509500e-03 9.988470e-01 -4.787719e-02 -5.950404e+00 -9.998238e-01 -4.387988e-03 -1.825599e-02 -4.118595e+01 +-7.418425e-03 4.895510e-02 9.987734e-01 1.650989e+02 -6.486812e-04 9.988004e-01 -4.896126e-02 -6.001598e+00 -9.999723e-01 -1.011103e-03 -7.377772e-03 -4.118391e+01 +7.121354e-03 4.909733e-02 9.987686e-01 1.657946e+02 2.005095e-03 9.987912e-01 -4.911275e-02 -6.048437e+00 -9.999727e-01 2.352372e-03 7.014299e-03 -4.116984e+01 +2.243953e-02 4.734927e-02 9.986263e-01 1.664858e+02 1.627255e-03 9.988748e-01 -4.739763e-02 -6.093238e+00 -9.997469e-01 2.688598e-03 2.233723e-02 -4.113991e+01 +3.841718e-02 4.215945e-02 9.983720e-01 1.671705e+02 -3.668784e-03 9.991088e-01 -4.204940e-02 -6.137223e+00 -9.992551e-01 -2.047394e-03 3.853761e-02 -4.109075e+01 +5.491856e-02 3.570845e-02 9.978521e-01 1.678530e+02 -4.640811e-03 9.993586e-01 -3.550696e-02 -6.181673e+00 -9.984801e-01 -2.680854e-03 5.504906e-02 -4.103668e+01 +7.192452e-02 2.868837e-02 9.969974e-01 1.685301e+02 -4.992049e-03 9.995841e-01 -2.840267e-02 -6.221562e+00 -9.973976e-01 -2.934213e-03 7.203782e-02 -4.097530e+01 +8.957989e-02 2.108529e-02 9.957564e-01 1.692001e+02 -5.085528e-03 9.997725e-01 -2.071284e-02 -6.257878e+00 -9.959667e-01 -3.208495e-03 8.966674e-02 -4.090154e+01 +1.069088e-01 1.506815e-02 9.941546e-01 1.698614e+02 -7.268466e-03 9.998703e-01 -1.437315e-02 -6.291791e+00 -9.942423e-01 -5.689364e-03 1.070044e-01 -4.081430e+01 +1.247290e-01 1.224565e-02 9.921153e-01 1.705106e+02 -8.080796e-03 9.999032e-01 -1.132586e-02 -6.321698e+00 -9.921580e-01 -6.604419e-03 1.248159e-01 -4.071802e+01 +1.428784e-01 1.125809e-02 9.896762e-01 1.711577e+02 -5.929431e-03 9.999271e-01 -1.051867e-02 -6.345942e+00 -9.897225e-01 -4.365327e-03 1.429347e-01 -4.061474e+01 +1.603230e-01 1.051115e-02 9.870086e-01 1.717857e+02 -7.327816e-03 9.999284e-01 -9.458462e-03 -6.364809e+00 -9.870374e-01 -5.716209e-03 1.603886e-01 -4.049872e+01 +1.765370e-01 1.027542e-02 9.842403e-01 1.724136e+02 -1.141853e-02 9.998996e-01 -8.390840e-03 -6.383917e+00 -9.842278e-01 -9.757280e-03 1.766366e-01 -4.036841e+01 +1.909880e-01 6.265987e-03 9.815724e-01 1.730350e+02 -1.417264e-02 9.998930e-01 -3.625324e-03 -6.398487e+00 -9.814901e-01 -1.321907e-02 1.910563e-01 -4.023437e+01 +2.033735e-01 2.554637e-03 9.790979e-01 1.736569e+02 -1.121446e-02 9.999371e-01 -2.796009e-04 -6.414475e+00 -9.790370e-01 -1.092319e-02 2.033893e-01 -4.010085e+01 +2.143717e-01 1.172231e-03 9.767514e-01 1.742720e+02 -8.049952e-03 9.999674e-01 5.666596e-04 -6.429852e+00 -9.767190e-01 -7.984279e-03 2.143741e-01 -3.996162e+01 +2.242966e-01 4.603043e-03 9.745101e-01 1.748735e+02 -1.242665e-02 9.999210e-01 -1.862913e-03 -6.445461e+00 -9.744417e-01 -1.169205e-02 2.243360e-01 -3.980478e+01 +2.330915e-01 1.127706e-02 9.723894e-01 1.754661e+02 -1.734422e-02 9.998219e-01 -7.437628e-03 -6.462030e+00 -9.723001e-01 -1.513168e-02 2.332456e-01 -3.964344e+01 +2.422731e-01 2.126941e-02 9.699749e-01 1.760534e+02 -1.682542e-02 9.997014e-01 -1.771872e-02 -6.476780e+00 -9.700622e-01 -1.202746e-02 2.425587e-01 -3.948936e+01 +2.507408e-01 2.761383e-02 9.676603e-01 1.766443e+02 -1.156988e-02 9.996071e-01 -2.552750e-02 -6.491511e+00 -9.679852e-01 -4.794929e-03 2.509618e-01 -3.933728e+01 +2.574235e-01 2.646994e-02 9.659361e-01 1.772384e+02 -9.983700e-03 9.996442e-01 -2.473300e-02 -6.503706e+00 -9.662471e-01 -3.276763e-03 2.575962e-01 -3.917670e+01 +2.633123e-01 1.927849e-02 9.645180e-01 1.778409e+02 -1.299897e-02 9.997804e-01 -1.643461e-02 -6.523425e+00 -9.646231e-01 -8.210305e-03 2.635051e-01 -3.899819e+01 +2.676021e-01 8.850193e-03 9.634888e-01 1.784457e+02 -1.648521e-02 9.998535e-01 -4.605580e-03 -6.542753e+00 -9.633885e-01 -1.465085e-02 2.677088e-01 -3.881772e+01 +2.697649e-01 -2.181280e-04 9.629262e-01 1.790512e+02 -1.869834e-02 9.998102e-01 5.464843e-03 -6.563672e+00 -9.627447e-01 -1.947935e-02 2.697096e-01 -3.863782e+01 +2.708099e-01 -1.355699e-03 9.626319e-01 1.796497e+02 -1.465690e-02 9.998773e-01 5.531463e-03 -6.577018e+00 -9.625213e-01 -1.560717e-02 2.707568e-01 -3.846824e+01 +2.721595e-01 1.350028e-03 9.622512e-01 1.802453e+02 -1.118572e-02 9.999359e-01 1.760825e-03 -6.587494e+00 -9.621872e-01 -1.124270e-02 2.721571e-01 -3.829850e+01 +2.737821e-01 6.608061e-04 9.617915e-01 1.808424e+02 -7.395574e-03 9.999716e-01 1.418172e-03 -6.589823e+00 -9.617633e-01 -7.501271e-03 2.737792e-01 -3.813009e+01 +2.755044e-01 -5.198351e-04 9.612997e-01 1.814417e+02 -9.752904e-03 9.999468e-01 3.335872e-03 -6.592495e+00 -9.612504e-01 -1.029451e-02 2.754847e-01 -3.795387e+01 +2.781485e-01 -4.482085e-03 9.605276e-01 1.820434e+02 -9.572413e-03 9.999265e-01 7.437898e-03 -6.599489e+00 -9.604904e-01 -1.126341e-02 2.780852e-01 -3.777364e+01 +2.812820e-01 -9.933839e-03 9.595737e-01 1.826545e+02 -9.451389e-03 9.998692e-01 1.312150e-02 -6.610135e+00 -9.595786e-01 -1.276015e-02 2.811513e-01 -3.758509e+01 +2.854496e-01 -1.319170e-02 9.583029e-01 1.832678e+02 -8.168759e-03 9.998354e-01 1.619665e-02 -6.618163e+00 -9.583590e-01 -1.245147e-02 2.852948e-01 -3.739323e+01 +2.915850e-01 -1.483620e-02 9.564299e-01 1.838831e+02 -6.154848e-03 9.998299e-01 1.738584e-02 -6.622539e+00 -9.565252e-01 -1.095613e-02 2.914440e-01 -3.719587e+01 +2.995581e-01 -1.794856e-02 9.539092e-01 1.844992e+02 -4.142437e-03 9.997891e-01 2.011269e-02 -6.624971e+00 -9.540691e-01 -9.976427e-03 2.994206e-01 -3.699420e+01 +3.090409e-01 -2.005231e-02 9.508373e-01 1.851118e+02 -1.794040e-03 9.997636e-01 2.166722e-02 -6.625315e+00 -9.510471e-01 -8.401897e-03 3.089318e-01 -3.678729e+01 +3.201495e-01 -1.842127e-02 9.471879e-01 1.857206e+02 -2.834842e-03 9.997878e-01 2.040244e-02 -6.626474e+00 -9.473628e-01 -9.216958e-03 3.200293e-01 -3.656856e+01 +3.316651e-01 -1.467498e-02 9.432830e-01 1.863264e+02 -4.382711e-03 9.998442e-01 1.709592e-02 -6.629118e+00 -9.433870e-01 -9.804256e-03 3.315492e-01 -3.633625e+01 +3.432085e-01 -1.111094e-02 9.391935e-01 1.869372e+02 -5.265825e-03 9.998915e-01 1.375330e-02 -6.630873e+00 -9.392445e-01 -9.665878e-03 3.431128e-01 -3.609759e+01 +3.549344e-01 -1.035464e-02 9.348339e-01 1.875555e+02 -4.155489e-03 9.999113e-01 1.265321e-02 -6.636302e+00 -9.348820e-01 -8.375752e-03 3.548599e-01 -3.584729e+01 +3.663260e-01 -1.341959e-02 9.303898e-01 1.881796e+02 -2.982954e-03 9.998739e-01 1.559630e-02 -6.641727e+00 -9.304818e-01 -8.488640e-03 3.662398e-01 -3.558666e+01 +3.773306e-01 -1.499536e-02 9.259572e-01 1.887952e+02 -4.478456e-03 9.998276e-01 1.801664e-02 -6.647005e+00 -9.260678e-01 -1.094509e-02 3.771984e-01 -3.531167e+01 +3.887283e-01 -1.568235e-02 9.212190e-01 1.894089e+02 -5.481008e-03 9.997981e-01 1.933287e-02 -6.647317e+00 -9.213362e-01 -1.256444e-02 3.885638e-01 -3.503211e+01 +3.983480e-01 -1.704230e-02 9.170760e-01 1.900333e+02 -9.711319e-03 9.996929e-01 2.279587e-02 -6.646563e+00 -9.171830e-01 -1.798671e-02 3.980602e-01 -3.474499e+01 +4.055952e-01 -1.546073e-02 9.139220e-01 1.906582e+02 -1.296926e-02 9.996589e-01 2.266684e-02 -6.645353e+00 -9.139608e-01 -2.104645e-02 4.052563e-01 -3.445351e+01 +4.100166e-01 -1.801138e-02 9.119002e-01 1.912983e+02 -1.376782e-02 9.995688e-01 2.593337e-02 -6.646441e+00 -9.119742e-01 -2.318799e-02 4.095918e-01 -3.415828e+01 +4.125364e-01 -2.260343e-02 9.106606e-01 1.919509e+02 -1.115059e-02 9.994919e-01 2.985961e-02 -6.642430e+00 -9.108729e-01 -2.247258e-02 4.120748e-01 -3.386698e+01 +4.128004e-01 -2.084626e-02 9.105829e-01 1.925985e+02 -6.834500e-03 9.996390e-01 2.598338e-02 -6.636461e+00 -9.107959e-01 -1.694933e-02 4.125089e-01 -3.357701e+01 +4.116063e-01 -2.110116e-02 9.111174e-01 1.932543e+02 -5.652744e-03 9.996536e-01 2.570531e-02 -6.629339e+00 -9.113443e-01 -1.573078e-02 4.113444e-01 -3.328043e+01 +4.108463e-01 -1.998333e-02 9.114856e-01 1.939224e+02 -2.138460e-03 9.997359e-01 2.288202e-02 -6.624605e+00 -9.117021e-01 -1.135017e-02 4.106951e-01 -3.298431e+01 +4.106521e-01 -2.116231e-02 9.115465e-01 1.946076e+02 1.910107e-03 9.997484e-01 2.234948e-02 -6.620022e+00 -9.117901e-01 -7.436712e-03 4.105892e-01 -3.268987e+01 +4.099903e-01 -2.768885e-02 9.116695e-01 1.952935e+02 5.156070e-03 9.995935e-01 2.804049e-02 -6.613679e+00 -9.120753e-01 -6.795698e-03 4.099664e-01 -3.239218e+01 +4.089264e-01 -3.061864e-02 9.120535e-01 1.959819e+02 5.803287e-03 9.995040e-01 3.095250e-02 -6.607632e+00 -9.125489e-01 -7.364387e-03 4.089013e-01 -3.209196e+01 +4.073120e-01 -3.308073e-02 9.126897e-01 1.966689e+02 5.723554e-03 9.994166e-01 3.366989e-02 -6.601884e+00 -9.132712e-01 -8.490324e-03 4.072638e-01 -3.178881e+01 +4.059481e-01 -3.360882e-02 9.132779e-01 1.973577e+02 5.665259e-03 9.993969e-01 3.425984e-02 -6.590085e+00 -9.138786e-01 -8.733760e-03 4.058937e-01 -3.148450e+01 +4.040100e-01 -3.358043e-02 9.141380e-01 1.980447e+02 4.209339e-03 9.993836e-01 3.485154e-02 -6.577998e+00 -9.147449e-01 -1.023246e-02 4.039023e-01 -3.117947e+01 +4.022820e-01 -3.283317e-02 9.149269e-01 1.987286e+02 3.350705e-03 9.994028e-01 3.439143e-02 -6.568027e+00 -9.155097e-01 -1.076940e-02 4.021517e-01 -3.087810e+01 +4.010300e-01 -2.985148e-02 9.155784e-01 1.994136e+02 3.828128e-03 9.995148e-01 3.091139e-02 -6.558335e+00 -9.160570e-01 -8.891445e-03 4.009497e-01 -3.057849e+01 +4.002981e-01 -2.379988e-02 9.160759e-01 2.000964e+02 4.663276e-03 9.997026e-01 2.393481e-02 -6.544179e+00 -9.163732e-01 -5.309144e-03 4.002900e-01 -3.028273e+01 +3.993286e-01 -1.998389e-02 9.165900e-01 2.007784e+02 2.298429e-03 9.997811e-01 2.079631e-02 -6.530959e+00 -9.168050e-01 -6.197846e-03 3.992871e-01 -2.998209e+01 +3.978412e-01 -2.255812e-02 9.171769e-01 2.014645e+02 9.054686e-04 9.997068e-01 2.419520e-02 -6.520036e+00 -9.174539e-01 -8.795372e-03 3.977450e-01 -2.967879e+01 +3.967251e-01 -2.587147e-02 9.175728e-01 2.021490e+02 -1.166700e-03 9.995877e-01 2.868837e-02 -6.508843e+00 -9.179368e-01 -1.245193e-02 3.965313e-01 -2.937762e+01 +3.943686e-01 -2.589240e-02 9.185875e-01 2.028328e+02 -4.853155e-03 9.995303e-01 3.025751e-02 -6.500732e+00 -9.189396e-01 -1.639066e-02 3.940577e-01 -2.907468e+01 +3.896662e-01 -2.534916e-02 9.206072e-01 2.035186e+02 -7.896098e-03 9.994924e-01 3.086348e-02 -6.489796e+00 -9.209224e-01 -1.929566e-02 3.892682e-01 -2.877610e+01 +3.833293e-01 -2.641000e-02 9.232341e-01 2.042052e+02 -7.201342e-03 9.994752e-01 3.158097e-02 -6.476282e+00 -9.235837e-01 -1.875443e-02 3.829380e-01 -2.849044e+01 +3.746191e-01 -2.683420e-02 9.267904e-01 2.048965e+02 -7.432096e-03 9.994621e-01 3.194247e-02 -6.466747e+00 -9.271491e-01 -1.885425e-02 3.742181e-01 -2.821234e+01 +3.647463e-01 -2.635402e-02 9.307339e-01 2.055855e+02 -5.491692e-03 9.995211e-01 3.045390e-02 -6.460876e+00 -9.310908e-01 -1.621925e-02 3.644269e-01 -2.794682e+01 +3.542582e-01 -2.316800e-02 9.348606e-01 2.062804e+02 -5.509685e-03 9.996240e-01 2.686084e-02 -6.457291e+00 -9.351314e-01 -1.466646e-02 3.539974e-01 -2.768336e+01 +3.427197e-01 -2.215805e-02 9.391763e-01 2.069776e+02 -8.461807e-03 9.996084e-01 2.667167e-02 -6.451620e+00 -9.393996e-01 -1.708803e-02 3.423980e-01 -2.742532e+01 +3.317271e-01 -3.012798e-02 9.428942e-01 2.076847e+02 -4.646319e-03 9.994256e-01 3.356897e-02 -6.442866e+00 -9.433640e-01 -1.551672e-02 3.313966e-01 -2.718172e+01 +3.230834e-01 -3.965624e-02 9.455392e-01 2.083951e+02 4.992930e-04 9.991286e-01 4.173320e-02 -6.431564e+00 -9.463704e-01 -1.301120e-02 3.228217e-01 -2.694940e+01 +3.158376e-01 -4.520750e-02 9.477357e-01 2.090997e+02 1.448764e-03 9.988861e-01 4.716460e-02 -6.412693e+00 -9.488122e-01 -1.352331e-02 3.155513e-01 -2.671654e+01 +3.111929e-01 -4.623932e-02 9.492212e-01 2.098040e+02 -4.290689e-03 9.987371e-01 5.005805e-02 -6.390837e+00 -9.503371e-01 -1.965052e-02 3.106015e-01 -2.647707e+01 +3.087288e-01 -4.828838e-02 9.499235e-01 2.105114e+02 -3.849933e-03 9.986388e-01 5.201602e-02 -6.368113e+00 -9.511423e-01 -1.971599e-02 3.081227e-01 -2.624826e+01 +3.070539e-01 -4.906204e-02 9.504266e-01 2.112267e+02 -2.654330e-03 9.986222e-01 5.240749e-02 -6.344077e+00 -9.516885e-01 -1.861467e-02 3.065006e-01 -2.601616e+01 +3.060417e-01 -4.754023e-02 9.508304e-01 2.119378e+02 -2.550289e-03 9.987079e-01 5.075491e-02 -6.316282e+00 -9.520147e-01 -1.795801e-02 3.055251e-01 -2.578235e+01 +3.056395e-01 -4.495687e-02 9.510854e-01 2.126531e+02 -5.827151e-03 9.987776e-01 4.908385e-02 -6.288388e+00 -9.521295e-01 -2.054408e-02 3.050039e-01 -2.554273e+01 +3.060927e-01 -4.594010e-02 9.508926e-01 2.133746e+02 -6.699474e-03 9.987063e-01 5.040668e-02 -6.266484e+00 -9.519782e-01 -2.179959e-02 3.053890e-01 -2.530655e+01 +3.078653e-01 -4.698159e-02 9.502693e-01 2.140992e+02 -7.345132e-03 9.986329e-01 5.175237e-02 -6.250693e+00 -9.514016e-01 -2.291261e-02 3.070993e-01 -2.507414e+01 +3.092072e-01 -4.879533e-02 9.497420e-01 2.148260e+02 -5.912039e-03 9.985648e-01 5.322851e-02 -6.233950e+00 -9.509764e-01 -2.207354e-02 3.084749e-01 -2.484157e+01 +3.107108e-01 -4.984750e-02 9.491965e-01 2.155565e+02 -2.315998e-03 9.985812e-01 5.319909e-02 -6.215613e+00 -9.505017e-01 -1.872787e-02 3.101545e-01 -2.461008e+01 +3.137378e-01 -5.111714e-02 9.481327e-01 2.162920e+02 -1.125066e-03 9.985291e-01 5.420648e-02 -6.192151e+00 -9.495090e-01 -1.807333e-02 3.132188e-01 -2.436727e+01 +3.180156e-01 -5.286120e-02 9.466107e-01 2.170259e+02 -1.996011e-03 9.984049e-01 5.642410e-02 -6.170889e+00 -9.480834e-01 -1.983319e-02 3.174028e-01 -2.411545e+01 +3.230288e-01 -5.689908e-02 9.446771e-01 2.177641e+02 -4.223889e-03 9.980944e-01 6.156082e-02 -6.141465e+00 -9.463797e-01 -2.387613e-02 3.221729e-01 -2.385283e+01 +3.282599e-01 -6.053182e-02 9.426459e-01 2.184996e+02 -4.871244e-03 9.978228e-01 6.577132e-02 -6.107629e+00 -9.445749e-01 -2.618194e-02 3.272503e-01 -2.358866e+01 +3.327024e-01 -6.076179e-02 9.410723e-01 2.192373e+02 -5.425419e-03 9.977822e-01 6.634144e-02 -6.076588e+00 -9.430163e-01 -2.717766e-02 3.316349e-01 -2.331785e+01 +3.371821e-01 -5.710597e-02 9.397059e-01 2.199730e+02 -1.173154e-02 9.978262e-01 6.484743e-02 -6.048783e+00 -9.413664e-01 -3.288959e-02 3.357792e-01 -2.303739e+01 +3.418597e-01 -5.038622e-02 9.383993e-01 2.207081e+02 -1.520605e-02 9.981343e-01 5.913321e-02 -6.010950e+00 -9.396280e-01 -3.448460e-02 3.404557e-01 -2.275294e+01 +3.464712e-01 -4.688015e-02 9.368884e-01 2.214455e+02 -1.903753e-02 9.981933e-01 5.698802e-02 -5.978570e+00 -9.378674e-01 -3.758074e-02 3.449528e-01 -2.246604e+01 +3.510153e-01 -4.710914e-02 9.351839e-01 2.221872e+02 -2.139032e-02 9.980696e-01 5.830568e-02 -5.953439e+00 -9.361254e-01 -4.047007e-02 3.493300e-01 -2.217504e+01 +3.550355e-01 -4.539201e-02 9.337501e-01 2.229246e+02 -2.339810e-02 9.980761e-01 5.741562e-02 -5.925935e+00 -9.345600e-01 -4.223256e-02 3.532904e-01 -2.188097e+01 +3.590748e-01 -4.244954e-02 9.323429e-01 2.236673e+02 -2.359062e-02 9.982331e-01 5.453502e-02 -5.900824e+00 -9.330106e-01 -4.157670e-02 3.574389e-01 -2.158401e+01 +3.636809e-01 -4.191318e-02 9.305802e-01 2.244110e+02 -2.353902e-02 9.982547e-01 5.416054e-02 -5.878524e+00 -9.312262e-01 -4.160210e-02 3.620596e-01 -2.128566e+01 +3.682591e-01 -4.356725e-02 9.287018e-01 2.251519e+02 -2.357618e-02 9.981426e-01 5.617355e-02 -5.852608e+00 -9.294243e-01 -4.258166e-02 3.665480e-01 -2.098574e+01 +3.725662e-01 -4.408715e-02 9.269578e-01 2.258876e+02 -2.003802e-02 9.982558e-01 5.553192e-02 -5.821468e+00 -9.277893e-01 -3.926371e-02 3.710330e-01 -2.068760e+01 +3.768692e-01 -4.400715e-02 9.252205e-01 2.266172e+02 -1.680582e-02 9.983814e-01 5.433248e-02 -5.786416e+00 -9.261141e-01 -3.602532e-02 3.755196e-01 -2.038914e+01 +3.810629e-01 -4.139743e-02 9.236218e-01 2.273444e+02 -1.705246e-02 9.985124e-01 5.178950e-02 -5.748608e+00 -9.243919e-01 -3.548508e-02 3.797901e-01 -2.008115e+01 +3.853593e-01 -4.194035e-02 9.218130e-01 2.280720e+02 -2.167999e-02 9.982793e-01 5.448261e-02 -5.713135e+00 -9.225119e-01 -4.098027e-02 3.837870e-01 -1.976164e+01 +3.900093e-01 -4.235278e-02 9.198364e-01 2.287943e+02 -2.485670e-02 9.980934e-01 5.649524e-02 -5.670054e+00 -9.204754e-01 -4.489775e-02 3.882129e-01 -1.944196e+01 +3.940139e-01 -4.017104e-02 9.182262e-01 2.295083e+02 -2.259501e-02 9.983191e-01 5.337059e-02 -5.635042e+00 -9.188267e-01 -4.177608e-02 3.924440e-01 -1.912990e+01 +3.980192e-01 -3.372531e-02 9.167569e-01 2.302202e+02 -2.120418e-02 9.987188e-01 4.594651e-02 -5.598456e+00 -9.171320e-01 -3.772667e-02 3.967942e-01 -1.881336e+01 +4.012920e-01 -2.706310e-02 9.155503e-01 2.309318e+02 -2.680599e-02 9.987882e-01 4.127281e-02 -5.563405e+00 -9.155579e-01 -4.110468e-02 4.000803e-01 -1.848487e+01 +4.043258e-01 -2.712394e-02 9.142127e-01 2.316515e+02 -3.360268e-02 9.984448e-01 4.448438e-02 -5.531661e+00 -9.139976e-01 -4.870618e-02 4.027855e-01 -1.814959e+01 +4.070088e-01 -3.717350e-02 9.126675e-01 2.323801e+02 -3.365391e-02 9.978828e-01 5.565252e-02 -5.500836e+00 -9.128041e-01 -5.336589e-02 4.048961e-01 -1.781958e+01 +4.088937e-01 -4.922212e-02 9.112536e-01 2.331128e+02 -2.952598e-02 9.973080e-01 6.711920e-02 -5.462204e+00 -9.121043e-01 -5.435027e-02 4.063396e-01 -1.749136e+01 +4.105196e-01 -5.744662e-02 9.100404e-01 2.338426e+02 -3.020588e-02 9.966091e-01 7.653720e-02 -5.421735e+00 -9.113514e-01 -5.890858e-02 4.073923e-01 -1.715509e+01 +4.126278e-01 -6.019533e-02 9.089086e-01 2.345679e+02 -3.229844e-02 9.962198e-01 8.064069e-02 -5.383327e+00 -9.103270e-01 -6.263091e-02 4.091237e-01 -1.681799e+01 +4.153935e-01 -5.591546e-02 9.079216e-01 2.352837e+02 -3.137485e-02 9.966343e-01 7.573362e-02 -5.338707e+00 -9.091006e-01 -5.994514e-02 4.122411e-01 -1.648612e+01 +4.195373e-01 -4.978536e-02 9.063718e-01 2.359993e+02 -2.995997e-02 9.971914e-01 6.864166e-02 -5.291877e+00 -9.072436e-01 -5.595260e-02 4.168674e-01 -1.615219e+01 +4.237905e-01 -4.537694e-02 9.046229e-01 2.367130e+02 -2.966153e-02 9.975133e-01 6.393204e-02 -5.248129e+00 -9.052745e-01 -5.392628e-02 4.213907e-01 -1.580991e+01 +4.279680e-01 -4.341347e-02 9.027506e-01 2.374264e+02 -2.812720e-02 9.977220e-01 6.131496e-02 -5.210063e+00 -9.033562e-01 -5.163268e-02 4.257720e-01 -1.546516e+01 +4.320457e-01 -4.109249e-02 9.009150e-01 2.381367e+02 -2.748834e-02 9.978972e-01 5.869844e-02 -5.166998e+00 -9.014327e-01 -5.012507e-02 4.300077e-01 -1.511758e+01 +4.359106e-01 -4.248065e-02 8.989868e-01 2.388518e+02 -2.558671e-02 9.978966e-01 5.956129e-02 -5.126556e+00 -8.996262e-01 -4.896550e-02 4.339068e-01 -1.476521e+01 +4.393196e-01 -4.734676e-02 8.970822e-01 2.395718e+02 -2.499979e-02 9.975790e-01 6.489375e-02 -5.089701e+00 -8.979829e-01 -5.093596e-02 4.370724e-01 -1.440661e+01 +4.422831e-01 -5.300698e-02 8.953077e-01 2.402931e+02 -2.285280e-02 9.972618e-01 7.033252e-02 -5.054711e+00 -8.965844e-01 -5.156716e-02 4.398606e-01 -1.404673e+01 +4.447832e-01 -5.855616e-02 8.937220e-01 2.410170e+02 -2.093866e-02 9.969079e-01 7.573751e-02 -5.014917e+00 -8.953935e-01 -5.240011e-02 4.421819e-01 -1.368347e+01 +4.467101e-01 -6.400536e-02 8.923863e-01 2.417404e+02 -1.891004e-02 9.965394e-01 8.094161e-02 -4.967915e+00 -8.944789e-01 -5.303249e-02 4.439539e-01 -1.331751e+01 +4.482185e-01 -7.073476e-02 8.911211e-01 2.424684e+02 -1.738210e-02 9.959863e-01 8.780159e-02 -4.919889e+00 -8.937551e-01 -5.484384e-02 4.451900e-01 -1.294865e+01 +4.499426e-01 -7.212526e-02 8.901402e-01 2.431894e+02 -1.735029e-02 9.958393e-01 8.945985e-02 -4.866153e+00 -8.928890e-01 -5.569598e-02 4.468191e-01 -1.257871e+01 +4.517406e-01 -6.156375e-02 8.900226e-01 2.438927e+02 -2.573646e-02 9.963018e-01 8.197801e-02 -4.820597e+00 -8.917780e-01 -5.993882e-02 4.484856e-01 -1.220269e+01 +4.526185e-01 -4.821999e-02 8.903995e-01 2.445980e+02 -2.810887e-02 9.972690e-01 6.829619e-02 -4.768203e+00 -8.912612e-01 -5.594024e-02 4.500270e-01 -1.183273e+01 +4.534854e-01 -3.867468e-02 8.904242e-01 2.453039e+02 -2.781570e-02 9.979572e-01 5.751158e-02 -4.715412e+00 -8.908296e-01 -5.084842e-02 4.514833e-01 -1.146869e+01 +4.534387e-01 -4.106321e-02 8.903410e-01 2.460241e+02 -2.764379e-02 9.978096e-01 6.009836e-02 -4.666974e+00 -8.908587e-01 -5.186331e-02 4.513104e-01 -1.109793e+01 +4.536502e-01 -4.714908e-02 8.899317e-01 2.467476e+02 -2.886671e-02 9.972980e-01 6.755246e-02 -4.628331e+00 -8.907122e-01 -5.633458e-02 4.510634e-01 -1.072107e+01 +4.550436e-01 -4.892877e-02 8.891239e-01 2.474682e+02 -2.710753e-02 9.972653e-01 6.875317e-02 -4.585009e+00 -8.900565e-01 -5.538763e-02 4.524729e-01 -1.034967e+01 +4.560439e-01 -4.876126e-02 8.886204e-01 2.481891e+02 -2.402686e-02 9.974593e-01 6.706427e-02 -4.542905e+00 -8.896329e-01 -5.193501e-02 4.537137e-01 -9.979828e+00 +4.574115e-01 -5.023619e-02 8.878350e-01 2.489165e+02 -1.948473e-02 9.975971e-01 6.648535e-02 -4.506301e+00 -8.890417e-01 -4.771038e-02 4.553336e-01 -9.608053e+00 +4.588987e-01 -5.508335e-02 8.867795e-01 2.496451e+02 -1.905426e-02 9.972367e-01 7.180491e-02 -4.465693e+00 -8.882843e-01 -4.984810e-02 4.565810e-01 -9.231011e+00 +4.599218e-01 -5.783246e-02 8.860741e-01 2.503674e+02 -2.092992e-02 9.968935e-01 7.592925e-02 -4.419715e+00 -8.877127e-01 -5.346697e-02 4.572827e-01 -8.851415e+00 +4.609865e-01 -5.645078e-02 8.856098e-01 2.510879e+02 -2.218522e-02 9.969296e-01 7.509463e-02 -4.371330e+00 -8.871298e-01 -5.426505e-02 4.583187e-01 -8.470395e+00 +4.621717e-01 -5.341419e-02 8.851803e-01 2.518063e+02 -2.111488e-02 9.972385e-01 7.120063e-02 -4.325524e+00 -8.865391e-01 -5.159738e-02 4.597676e-01 -8.090111e+00 +4.637157e-01 -5.100456e-02 8.845147e-01 2.525224e+02 -2.060139e-02 9.974509e-01 6.831739e-02 -4.275557e+00 -8.857446e-01 -4.990207e-02 4.614828e-01 -7.707069e+00 +4.655263e-01 -5.392137e-02 8.833899e-01 2.532425e+02 -1.732092e-02 9.973960e-01 7.000795e-02 -4.220724e+00 -8.848646e-01 -4.789166e-02 4.633801e-01 -7.325540e+00 +4.689183e-01 -5.721110e-02 8.813867e-01 2.539607e+02 -1.701176e-02 9.971298e-01 7.377469e-02 -4.161421e+00 -8.830777e-01 -4.958824e-02 4.665992e-01 -6.938930e+00 +4.725341e-01 -5.907706e-02 8.793301e-01 2.546779e+02 -1.650001e-02 9.969828e-01 7.584824e-02 -4.110352e+00 -8.811579e-01 -5.034983e-02 4.701336e-01 -6.545579e+00 +4.767470e-01 -5.969675e-02 8.770112e-01 2.553919e+02 -1.410328e-02 9.970435e-01 7.553377e-02 -4.048806e+00 -8.789275e-01 -4.837922e-02 4.744955e-01 -6.152612e+00 +4.809341e-01 -5.780977e-02 8.748488e-01 2.561011e+02 -1.468864e-02 9.971525e-01 7.396642e-02 -3.990384e+00 -8.766337e-01 -4.842331e-02 4.787155e-01 -5.755645e+00 +4.849795e-01 -5.356906e-02 8.728833e-01 2.568048e+02 -1.933875e-02 9.972211e-01 7.194445e-02 -3.930085e+00 -8.743117e-01 -5.177205e-02 4.825959e-01 -5.350577e+00 +4.900523e-01 -4.913208e-02 8.703073e-01 2.575076e+02 -1.885016e-02 9.975795e-01 6.693121e-02 -3.878397e+00 -8.714892e-01 -4.920521e-02 4.879400e-01 -4.948904e+00 +4.972845e-01 -4.888727e-02 8.662091e-01 2.582150e+02 -1.424027e-02 9.978167e-01 6.449021e-02 -3.826391e+00 -8.674707e-01 -4.440502e-02 4.955026e-01 -4.543629e+00 +5.057966e-01 -4.954606e-02 8.612287e-01 2.589184e+02 -9.935480e-03 9.979485e-01 6.324655e-02 -3.779890e+00 -8.625956e-01 -4.054661e-02 5.042667e-01 -4.128435e+00 +5.156445e-01 -5.274343e-02 8.551777e-01 2.596187e+02 -4.228533e-03 9.979346e-01 6.409771e-02 -3.733326e+00 -8.567922e-01 -3.666777e-02 5.143565e-01 -3.705256e+00 +5.281311e-01 -5.326178e-02 8.474908e-01 2.603076e+02 -1.022012e-03 9.979904e-01 6.335705e-02 -3.683134e+00 -8.491622e-01 -3.432697e-02 5.270154e-01 -3.272954e+00 +5.412294e-01 -5.432145e-02 8.391185e-01 2.609917e+02 -1.111302e-03 9.978641e-01 6.531485e-02 -3.633918e+00 -8.408743e-01 -3.628282e-02 5.400130e-01 -2.820165e+00 +5.542154e-01 -5.854683e-02 8.303117e-01 2.616731e+02 9.746011e-04 9.975682e-01 6.968988e-02 -3.580981e+00 -8.323728e-01 -3.781397e-02 5.529247e-01 -2.357593e+00 +5.668480e-01 -6.147190e-02 8.215257e-01 2.623444e+02 -2.856384e-04 9.971974e-01 7.481390e-02 -3.531769e+00 -8.238224e-01 -4.264277e-02 5.652419e-01 -1.883065e+00 +5.776212e-01 -5.889584e-02 8.141775e-01 2.630049e+02 -4.370990e-03 9.971564e-01 7.523316e-02 -3.480155e+00 -8.162933e-01 -4.701503e-02 5.757212e-01 -1.397703e+00 +5.864564e-01 -5.321575e-02 8.082308e-01 2.636556e+02 -9.523181e-03 9.973174e-01 7.257573e-02 -3.427591e+00 -8.099248e-01 -5.025942e-02 5.843764e-01 -9.077904e-01 +5.926812e-01 -4.779757e-02 8.040176e-01 2.643027e+02 -1.453795e-02 9.974401e-01 7.001289e-02 -3.373096e+00 -8.053059e-01 -5.318408e-02 5.904692e-01 -4.142628e-01 +5.946556e-01 -4.407459e-02 8.027716e-01 2.649518e+02 -2.023195e-02 9.973596e-01 6.974496e-02 -3.320578e+00 -8.037260e-01 -5.771585e-02 5.921938e-01 8.421701e-02 +5.922340e-01 -3.778080e-02 8.048798e-01 2.656004e+02 -2.829378e-02 9.973090e-01 6.763205e-02 -3.277874e+00 -8.052691e-01 -6.282708e-02 5.895714e-01 5.815620e-01 +5.853289e-01 -3.061825e-02 8.102176e-01 2.662521e+02 -3.628460e-02 9.972964e-01 6.390123e-02 -3.231419e+00 -8.099837e-01 -6.680165e-02 5.826354e-01 1.068534e+00 +5.761849e-01 -2.499829e-02 8.169370e-01 2.669119e+02 -3.996739e-02 9.974746e-01 5.871170e-02 -3.186902e+00 -8.163416e-01 -6.647963e-02 5.737307e-01 1.539702e+00 +5.656359e-01 -2.598869e-02 8.242455e-01 2.675830e+02 -3.503006e-02 9.978439e-01 5.550157e-02 -3.138958e+00 -8.239108e-01 -6.026704e-02 5.635059e-01 1.995215e+00 +5.558069e-01 -3.000140e-02 8.307699e-01 2.682659e+02 -3.320856e-02 9.977496e-01 5.824891e-02 -3.095292e+00 -8.306479e-01 -5.996381e-02 5.535598e-01 2.447327e+00 +5.459804e-01 -2.916667e-02 8.372901e-01 2.689438e+02 -3.771547e-02 9.975250e-01 5.934191e-02 -3.057266e+00 -8.369486e-01 -6.397831e-02 5.435291e-01 2.900508e+00 +5.365247e-01 -3.174459e-02 8.432873e-01 2.696322e+02 -3.595926e-02 9.975245e-01 6.042904e-02 -3.014796e+00 -8.431181e-01 -6.274565e-02 5.340551e-01 3.337088e+00 +5.283477e-01 -3.237317e-02 8.484107e-01 2.703249e+02 -3.129404e-02 9.978512e-01 5.756380e-02 -2.971910e+00 -8.484512e-01 -5.696389e-02 5.261993e-01 3.759467e+00 +5.194005e-01 -3.215099e-02 8.539259e-01 2.710177e+02 -2.861656e-02 9.980770e-01 5.498443e-02 -2.933541e+00 -8.540517e-01 -5.299536e-02 5.174817e-01 4.180200e+00 +5.119463e-01 -3.011495e-02 8.584894e-01 2.717172e+02 -3.137230e-02 9.980631e-01 5.371943e-02 -2.897192e+00 -8.584444e-01 -5.443424e-02 5.100100e-01 4.604376e+00 +5.054989e-01 -3.047835e-02 8.622887e-01 2.724197e+02 -3.372885e-02 9.979140e-01 5.504499e-02 -2.857745e+00 -8.621678e-01 -5.690918e-02 5.034165e-01 5.022290e+00 +5.003166e-01 -3.376182e-02 8.651840e-01 2.731286e+02 -3.707283e-02 9.974878e-01 6.036306e-02 -2.814492e+00 -8.650485e-01 -6.227546e-02 4.978081e-01 5.441538e+00 +4.952874e-01 -3.802937e-02 8.678964e-01 2.738426e+02 -3.878304e-02 9.970774e-01 6.582235e-02 -2.772449e+00 -8.678631e-01 -6.626063e-02 4.923650e-01 5.855792e+00 +4.911350e-01 -4.299079e-02 8.700220e-01 2.745609e+02 -3.858977e-02 9.967270e-01 7.103600e-02 -2.721918e+00 -8.702283e-01 -6.846220e-02 4.878685e-01 6.266911e+00 +4.882423e-01 -3.974586e-02 8.718026e-01 2.752745e+02 -4.200052e-02 9.967346e-01 6.896345e-02 -2.673153e+00 -8.716969e-01 -7.028702e-02 4.849786e-01 6.675117e+00 +4.856588e-01 -2.973000e-02 8.736427e-01 2.759847e+02 -4.794738e-02 9.970109e-01 6.058221e-02 -2.628431e+00 -8.728325e-01 -7.131115e-02 4.827817e-01 7.082604e+00 +4.839855e-01 -1.764901e-02 8.748980e-01 2.766939e+02 -4.997074e-02 9.976077e-01 4.776775e-02 -2.585559e+00 -8.736481e-01 -6.683819e-02 4.819458e-01 7.483336e+00 +4.825352e-01 -1.147005e-02 8.758014e-01 2.774117e+02 -4.926215e-02 9.979761e-01 4.021181e-02 -2.538301e+00 -8.744902e-01 -6.254747e-02 4.809936e-01 7.884799e+00 +4.811582e-01 -1.025984e-02 8.765737e-01 2.781377e+02 -5.117819e-02 9.978973e-01 3.977198e-02 -2.495085e+00 -8.751386e-01 -6.399806e-02 4.796214e-01 8.291747e+00 +4.801612e-01 -1.374213e-02 8.770726e-01 2.788724e+02 -5.340214e-02 9.975647e-01 4.486550e-02 -2.463622e+00 -8.755533e-01 -6.838022e-02 4.782580e-01 8.703796e+00 +4.801214e-01 -1.650999e-02 8.770467e-01 2.796088e+02 -5.127989e-02 9.975847e-01 4.685120e-02 -2.427851e+00 -8.757019e-01 -6.746911e-02 4.781152e-01 9.109342e+00 +4.809437e-01 -1.991722e-02 8.765252e-01 2.803533e+02 -4.751332e-02 9.976807e-01 4.874048e-02 -2.392970e+00 -8.754631e-01 -6.508803e-02 4.788819e-01 9.516225e+00 +4.826335e-01 -2.267670e-02 8.755288e-01 2.810976e+02 -4.698729e-02 9.975546e-01 5.173890e-02 -2.361052e+00 -8.745611e-01 -6.610964e-02 4.803878e-01 9.935075e+00 +4.860385e-01 -2.433594e-02 8.735985e-01 2.818429e+02 -4.604933e-02 9.975104e-01 5.340795e-02 -2.327550e+00 -8.727234e-01 -6.618694e-02 4.837078e-01 1.035908e+01 +4.902128e-01 -2.375205e-02 8.712791e-01 2.825899e+02 -4.556144e-02 9.975636e-01 5.282921e-02 -2.293190e+00 -8.704112e-01 -6.559428e-02 4.879363e-01 1.078580e+01 +4.939955e-01 -2.387450e-02 8.691366e-01 2.833375e+02 -4.600043e-02 9.975052e-01 5.354618e-02 -2.259848e+00 -8.682468e-01 -6.643221e-02 4.916649e-01 1.121977e+01 +4.975029e-01 -2.202353e-02 8.671827e-01 2.840848e+02 -4.963709e-02 9.973169e-01 5.380531e-02 -2.234216e+00 -8.660410e-01 -6.981272e-02 4.950749e-01 1.166325e+01 +5.016344e-01 -1.975805e-02 8.648540e-01 2.848272e+02 -5.059172e-02 9.973580e-01 5.212948e-02 -2.201768e+00 -8.635991e-01 -6.990438e-02 4.993095e-01 1.210499e+01 +5.060664e-01 -1.857207e-02 8.622945e-01 2.855784e+02 -4.547997e-02 9.978026e-01 4.818208e-02 -2.174731e+00 -8.612946e-01 -6.360045e-02 5.041098e-01 1.254485e+01 +5.112701e-01 -1.607064e-02 8.592698e-01 2.863278e+02 -4.316660e-02 9.980829e-01 4.435118e-02 -2.157485e+00 -8.583353e-01 -5.976718e-02 5.095963e-01 1.298766e+01 +5.177701e-01 -1.455636e-02 8.553960e-01 2.870798e+02 -4.148707e-02 9.982517e-01 4.209942e-02 -2.141208e+00 -8.545133e-01 -5.728569e-02 5.162610e-01 1.344201e+01 +5.254471e-01 -1.602518e-02 8.506753e-01 2.878316e+02 -4.142560e-02 9.981549e-01 4.439129e-02 -2.116997e+00 -8.498172e-01 -5.856500e-02 5.238138e-01 1.391153e+01 +5.323699e-01 -1.889835e-02 8.463008e-01 2.885810e+02 -4.451026e-02 9.977428e-01 5.027955e-02 -2.092276e+00 -8.453408e-01 -6.443638e-02 5.303271e-01 1.439510e+01 +5.392974e-01 -2.270148e-02 8.418093e-01 2.893351e+02 -4.694475e-02 9.972716e-01 5.696863e-02 -2.064174e+00 -8.408059e-01 -7.024155e-02 5.367603e-01 1.488867e+01 +5.463262e-01 -2.671994e-02 8.371462e-01 2.900887e+02 -5.024852e-02 9.966451e-01 6.460327e-02 -2.028438e+00 -8.360639e-01 -7.735980e-02 5.431507e-01 1.539635e+01 +5.532461e-01 -2.825027e-02 8.325387e-01 2.908382e+02 -5.175452e-02 9.963283e-01 6.820047e-02 -1.994986e+00 -8.314086e-01 -8.081927e-02 5.497526e-01 1.590519e+01 +5.608227e-01 -2.588634e-02 8.275312e-01 2.915808e+02 -5.138581e-02 9.964958e-01 6.599626e-02 -1.953998e+00 -8.263398e-01 -7.953554e-02 5.575273e-01 1.641665e+01 +5.683204e-01 -2.044952e-02 8.225532e-01 2.923119e+02 -4.939916e-02 9.970398e-01 5.891843e-02 -1.909983e+00 -8.213231e-01 -7.411797e-02 5.656279e-01 1.693296e+01 +5.758419e-01 -1.320909e-02 8.174543e-01 2.930391e+02 -4.893020e-02 9.975203e-01 5.058680e-02 -1.864125e+00 -8.160956e-01 -6.912819e-02 5.737677e-01 1.744383e+01 +5.826618e-01 -1.010083e-02 8.126519e-01 2.937666e+02 -4.424486e-02 9.980456e-01 4.412822e-02 -1.824438e+00 -8.115095e-01 -6.166749e-02 5.810762e-01 1.795966e+01 +5.895851e-01 -9.109082e-03 8.076549e-01 2.944939e+02 -3.839154e-02 9.984901e-01 3.928709e-02 -1.789217e+00 -8.067934e-01 -5.417019e-02 5.883452e-01 1.848161e+01 +5.961290e-01 -1.514967e-02 8.027457e-01 2.952267e+02 -3.015847e-02 9.986938e-01 4.124373e-02 -1.755458e+00 -8.023221e-01 -4.879616e-02 5.948935e-01 1.901274e+01 +6.036051e-01 -2.152690e-02 7.969928e-01 2.959760e+02 -2.500545e-02 9.986325e-01 4.591118e-02 -1.733893e+00 -7.968912e-01 -4.764138e-02 6.022414e-01 1.954372e+01 +6.109151e-01 -3.001720e-02 7.911269e-01 2.967209e+02 -2.065474e-02 9.983365e-01 5.382899e-02 -1.707063e+00 -7.914267e-01 -4.922546e-02 6.092788e-01 2.009092e+01 +6.180611e-01 -3.454457e-02 7.853707e-01 2.974645e+02 -1.769378e-02 9.981697e-01 5.782898e-02 -1.676369e+00 -7.859309e-01 -4.963802e-02 6.163187e-01 2.064190e+01 +6.243285e-01 -3.673856e-02 7.802975e-01 2.981922e+02 -1.761822e-02 9.979771e-01 6.108415e-02 -1.635982e+00 -7.809632e-01 -5.188402e-02 6.224183e-01 2.121228e+01 +6.308958e-01 -3.437648e-02 7.751056e-01 2.989783e+02 -2.164473e-02 9.978493e-01 6.187302e-02 -1.657067e+00 -7.755656e-01 -5.581237e-02 6.287949e-01 2.180486e+01 +6.369531e-01 -3.262160e-02 7.702120e-01 2.997788e+02 -2.645524e-02 9.975908e-01 6.413008e-02 -1.693639e+00 -7.704485e-01 -6.122398e-02 6.345556e-01 2.241695e+01 +6.413484e-01 -3.540776e-02 7.664323e-01 3.005852e+02 -2.347258e-02 9.975615e-01 6.572729e-02 -1.732539e+00 -7.668907e-01 -6.014422e-02 6.389533e-01 2.302434e+01 +6.456476e-01 -3.398362e-02 7.628789e-01 3.013610e+02 -2.437635e-02 9.975829e-01 6.506933e-02 -1.747050e+00 -7.632464e-01 -6.060805e-02 6.432587e-01 2.363381e+01 +6.497788e-01 -3.228642e-02 7.594373e-01 3.021279e+02 -2.202621e-02 9.978782e-01 6.126916e-02 -1.749939e+00 -7.598042e-01 -5.653892e-02 6.476890e-01 2.424501e+01 +6.547488e-01 -2.877270e-02 7.552987e-01 3.028926e+02 -2.040539e-02 9.982381e-01 5.571625e-02 -1.762461e+00 -7.555710e-01 -5.189230e-02 6.530081e-01 2.486059e+01 +6.586639e-01 -2.976020e-02 7.518485e-01 3.036453e+02 -1.953136e-02 9.982046e-01 5.662227e-02 -1.757056e+00 -7.521838e-01 -5.197966e-02 6.569001e-01 2.548753e+01 +6.626558e-01 -3.064605e-02 7.482968e-01 3.043940e+02 -2.313429e-02 9.978480e-01 6.135290e-02 -1.753708e+00 -7.485667e-01 -5.796716e-02 6.605208e-01 2.612871e+01 +6.665094e-01 -3.384938e-02 7.447278e-01 3.051332e+02 -2.522013e-02 9.973730e-01 6.790390e-02 -1.736061e+00 -7.450700e-01 -6.404071e-02 6.639048e-01 2.677897e+01 +6.707627e-01 -3.321535e-02 7.409279e-01 3.058703e+02 -2.410462e-02 9.974926e-01 6.653893e-02 -1.718076e+00 -7.412803e-01 -6.249161e-02 6.682802e-01 2.742763e+01 +6.748937e-01 -2.769889e-02 7.373949e-01 3.065830e+02 -2.659914e-02 9.977326e-01 6.182261e-02 -1.694224e+00 -7.374355e-01 -6.133775e-02 6.726267e-01 2.807634e+01 +6.790832e-01 -2.391463e-02 7.336716e-01 3.073026e+02 -2.665583e-02 9.980066e-01 5.720337e-02 -1.677575e+00 -7.335772e-01 -5.840246e-02 6.770921e-01 2.873554e+01 +6.831266e-01 -2.639334e-02 7.298229e-01 3.080194e+02 -2.041417e-02 9.982661e-01 5.520935e-02 -1.655528e+00 -7.300146e-01 -5.261370e-02 6.814033e-01 2.938700e+01 +6.872044e-01 -3.069495e-02 7.258154e-01 3.087355e+02 -1.606567e-02 9.982205e-01 5.742607e-02 -1.635678e+00 -7.262865e-01 -5.112415e-02 6.854883e-01 3.004649e+01 +6.913855e-01 -3.529827e-02 7.216232e-01 3.094386e+02 -9.641867e-03 9.982660e-01 5.806814e-02 -1.610963e+00 -7.224217e-01 -4.710526e-02 6.898464e-01 3.070690e+01 +6.962286e-01 -3.828715e-02 7.167984e-01 3.101407e+02 -4.580740e-03 9.983192e-01 5.777363e-02 -1.585427e+00 -7.178056e-01 -4.350711e-02 6.948829e-01 3.137448e+01 +7.003373e-01 -4.387867e-02 7.124621e-01 3.108359e+02 2.317497e-03 9.982434e-01 5.920114e-02 -1.557699e+00 -7.138083e-01 -3.980964e-02 6.992088e-01 3.204009e+01 +7.044055e-01 -4.415641e-02 7.084229e-01 3.115197e+02 1.498531e-03 9.981534e-01 6.072545e-02 -1.531653e+00 -7.097962e-01 -4.171375e-02 7.031709e-01 3.271633e+01 +7.076251e-01 -4.369710e-02 7.052356e-01 3.121948e+02 -1.482076e-04 9.980767e-01 6.199054e-02 -1.502226e+00 -7.065881e-01 -4.397058e-02 7.062577e-01 3.339942e+01 +7.116822e-01 -4.244890e-02 7.012179e-01 3.128629e+02 1.066596e-03 9.982368e-01 5.934672e-02 -1.471946e+00 -7.025008e-01 -4.148808e-02 7.104727e-01 3.407583e+01 +7.154666e-01 -3.978370e-02 6.975133e-01 3.135266e+02 -1.535167e-03 9.982854e-01 5.851338e-02 -1.442106e+00 -6.986453e-01 -4.293516e-02 7.141788e-01 3.476541e+01 +7.191300e-01 -4.455700e-02 6.934455e-01 3.141892e+02 4.010424e-03 9.981915e-01 5.997936e-02 -1.405865e+00 -6.948640e-01 -4.035194e-02 7.180082e-01 3.544723e+01 +7.238531e-01 -4.465185e-02 6.885077e-01 3.148435e+02 2.703820e-03 9.980795e-01 6.188593e-02 -1.378314e+00 -6.899489e-01 -4.293471e-02 7.225837e-01 3.613799e+01 +7.271832e-01 -4.346411e-02 6.850660e-01 3.154894e+02 3.627232e-03 9.982228e-01 5.948216e-02 -1.346387e+00 -6.864339e-01 -4.076953e-02 7.260485e-01 3.682740e+01 +7.311242e-01 -4.614559e-02 6.806820e-01 3.161388e+02 7.954301e-03 9.982187e-01 5.912866e-02 -1.312849e+00 -6.821981e-01 -3.781604e-02 7.301889e-01 3.751735e+01 +7.342365e-01 -4.643443e-02 6.773039e-01 3.167807e+02 5.424386e-03 9.980276e-01 6.254218e-02 -1.280517e+00 -6.788721e-01 -4.224679e-02 7.330402e-01 3.821802e+01 +7.369502e-01 -4.334372e-02 6.745560e-01 3.174141e+02 -1.518780e-03 9.978333e-01 6.577524e-02 -1.250716e+00 -6.759454e-01 -4.949757e-02 7.352876e-01 3.892525e+01 +7.397091e-01 -4.321833e-02 6.715375e-01 3.180491e+02 -2.442881e-03 9.977564e-01 6.690378e-02 -1.209970e+00 -6.729223e-01 -5.112981e-02 7.379440e-01 3.962810e+01 +7.414072e-01 -4.827190e-02 6.693169e-01 3.186872e+02 3.698828e-04 9.974386e-01 7.152670e-02 -1.166319e+00 -6.710553e-01 -5.278283e-02 7.395260e-01 4.032863e+01 +7.434182e-01 -4.754144e-02 6.671351e-01 3.193144e+02 -2.349887e-03 9.972786e-01 7.368676e-02 -1.130942e+00 -6.688228e-01 -5.634776e-02 7.412834e-01 4.102951e+01 +7.447923e-01 -4.316427e-02 6.658988e-01 3.199432e+02 -1.898620e-03 9.977646e-01 6.679974e-02 -1.094331e+00 -6.672937e-01 -5.101621e-02 7.430455e-01 4.172857e+01 +7.454889e-01 -3.997917e-02 6.653180e-01 3.205699e+02 4.794114e-04 9.982313e-01 5.944687e-02 -1.055116e+00 -6.665179e-01 -4.399801e-02 7.441895e-01 4.242029e+01 +7.450255e-01 -3.981065e-02 6.658470e-01 3.211979e+02 8.200026e-04 9.982713e-01 5.876862e-02 -1.019788e+00 -6.670356e-01 -4.323812e-02 7.437702e-01 4.311884e+01 +7.441825e-01 -4.100230e-02 6.667168e-01 3.218286e+02 -5.685317e-04 9.980750e-01 6.201505e-02 -9.855898e-01 -6.679762e-01 -4.652956e-02 7.427267e-01 4.382261e+01 +7.429743e-01 -4.369747e-02 6.678920e-01 3.224645e+02 -1.029784e-03 9.977907e-01 6.642698e-02 -9.469468e-01 -6.693192e-01 -5.004132e-02 7.412879e-01 4.452778e+01 +7.406686e-01 -4.518882e-02 6.703492e-01 3.231058e+02 -1.102219e-03 9.976525e-01 6.847048e-02 -9.061778e-01 -6.718697e-01 -5.145280e-02 7.388801e-01 4.523347e+01 +7.372966e-01 -4.455575e-02 6.740983e-01 3.237484e+02 -1.958221e-03 9.976776e-01 6.808512e-02 -8.650478e-01 -6.755664e-01 -5.151895e-02 7.354970e-01 4.593426e+01 +7.331284e-01 -3.883265e-02 6.789806e-01 3.243921e+02 -6.313597e-03 9.979368e-01 6.389169e-02 -8.250807e-01 -6.800609e-01 -5.112762e-02 7.313707e-01 4.663318e+01 +7.281671e-01 -3.435201e-02 6.845383e-01 3.250437e+02 -8.970276e-03 9.981800e-01 5.963342e-02 -7.865276e-01 -6.853410e-01 -4.956358e-02 7.265337e-01 4.732677e+01 +7.230892e-01 -3.359325e-02 6.899374e-01 3.257065e+02 -8.095180e-03 9.983360e-01 5.709344e-02 -7.496238e-01 -6.907073e-01 -4.686881e-02 7.216140e-01 4.801802e+01 +7.172576e-01 -3.329706e-02 6.960121e-01 3.263766e+02 -9.763156e-03 9.982793e-01 5.781864e-02 -7.157939e-01 -6.967398e-01 -4.826612e-02 7.156983e-01 4.870917e+01 +7.114040e-01 -3.404993e-02 7.019579e-01 3.270557e+02 -9.372023e-03 9.982771e-01 5.792165e-02 -6.821795e-01 -7.027208e-01 -4.778446e-02 7.098592e-01 4.939482e+01 +7.059443e-01 -3.421948e-02 7.074402e-01 3.277396e+02 -1.304876e-02 9.980343e-01 6.129693e-02 -6.437965e-01 -7.081471e-01 -5.250343e-02 7.041101e-01 5.008093e+01 +6.995732e-01 -3.877274e-02 7.135082e-01 3.284377e+02 -1.427534e-02 9.975691e-01 6.820544e-02 -6.002114e-01 -7.144183e-01 -5.790026e-02 6.973192e-01 5.076531e+01 +6.931272e-01 -4.159558e-02 7.196141e-01 3.291391e+02 -1.845669e-02 9.969821e-01 7.540553e-02 -5.560634e-01 -7.205790e-01 -6.554731e-02 6.902677e-01 5.144859e+01 +6.865430e-01 -3.811103e-02 7.260897e-01 3.298404e+02 -2.130062e-02 9.971425e-01 7.247855e-02 -5.082701e-01 -7.267772e-01 -6.522579e-02 6.837694e-01 5.211788e+01 +6.808789e-01 -3.209271e-02 7.316925e-01 3.305487e+02 -2.194347e-02 9.976971e-01 6.417948e-02 -4.610597e-01 -7.320672e-01 -5.975432e-02 6.786067e-01 5.277800e+01 +6.753575e-01 -2.878810e-02 7.369284e-01 3.312668e+02 -2.111256e-02 9.980736e-01 5.833833e-02 -4.174988e-01 -7.371883e-01 -5.495766e-02 6.734487e-01 5.343409e+01 +6.698515e-01 -3.055392e-02 7.418662e-01 3.319976e+02 -1.921554e-02 9.981049e-01 5.845741e-02 -3.786882e-01 -7.422465e-01 -5.341314e-02 6.679950e-01 5.408875e+01 +6.646906e-01 -3.320904e-02 7.463803e-01 3.327368e+02 -1.911622e-02 9.979286e-01 6.142529e-02 -3.411610e-01 -7.468741e-01 -5.509677e-02 6.626790e-01 5.474402e+01 +6.599524e-01 -3.448647e-02 7.505155e-01 3.334791e+02 -1.974160e-02 9.978050e-01 6.320895e-02 -3.033084e-01 -7.510480e-01 -5.653127e-02 6.578230e-01 5.539719e+01 +6.555871e-01 -3.640435e-02 7.542415e-01 3.342300e+02 -1.884466e-02 9.977374e-01 6.453676e-02 -2.608018e-01 -7.548844e-01 -5.652288e-02 6.534178e-01 5.604605e+01 +6.514050e-01 -3.661660e-02 7.578461e-01 3.349826e+02 -2.053106e-02 9.976183e-01 6.584903e-02 -2.177423e-01 -7.584524e-01 -5.845376e-02 6.491018e-01 5.669610e+01 +6.472036e-01 -3.517831e-02 7.615051e-01 3.357387e+02 -2.441256e-02 9.974659e-01 6.682695e-02 -1.730481e-01 -7.619262e-01 -6.184092e-02 6.447047e-01 5.734950e+01 +6.433333e-01 -3.411996e-02 7.648255e-01 3.364998e+02 -2.673635e-02 9.973957e-01 6.698455e-02 -1.280985e-01 -7.651192e-01 -6.354202e-02 6.407457e-01 5.799518e+01 +6.398111e-01 -3.284732e-02 7.678299e-01 3.372672e+02 -2.903377e-02 9.973399e-01 6.685866e-02 -8.432989e-02 -7.679836e-01 -6.506990e-02 6.371555e-01 5.864049e+01 +6.361961e-01 -3.142774e-02 7.708870e-01 3.380396e+02 -3.077316e-02 9.973412e-01 6.605630e-02 -3.922766e-02 -7.709135e-01 -6.574738e-02 6.335375e-01 5.928309e+01 +6.326658e-01 -2.965301e-02 7.738570e-01 3.388169e+02 -3.313603e-02 9.973149e-01 6.530590e-02 7.915830e-03 -7.737157e-01 -6.695934e-02 6.299845e-01 5.992562e+01 +6.294698e-01 -3.092761e-02 7.764092e-01 3.395995e+02 -3.187710e-02 9.973385e-01 6.557234e-02 5.390482e-02 -7.763708e-01 -6.602547e-02 6.268086e-01 6.056028e+01 +6.265054e-01 -3.141264e-02 7.787838e-01 3.403890e+02 -3.204177e-02 9.973048e-01 6.600333e-02 1.011524e-01 -7.787582e-01 -6.630504e-02 6.238103e-01 6.119943e+01 +6.235106e-01 -3.209981e-02 7.811556e-01 3.411781e+02 -3.247496e-02 9.972310e-01 6.690013e-02 1.502289e-01 -7.811401e-01 -6.708093e-02 6.207417e-01 6.183344e+01 +6.207911e-01 -3.144423e-02 7.833452e-01 3.419688e+02 -3.528275e-02 9.970623e-01 6.798417e-02 1.971761e-01 -7.831817e-01 -6.984253e-02 6.178580e-01 6.246632e+01 +6.176438e-01 -3.198836e-02 7.858071e-01 3.427628e+02 -3.696143e-02 9.968877e-01 6.963261e-02 2.432714e-01 -7.855890e-01 -7.205270e-02 6.145392e-01 6.309758e+01 +6.146541e-01 -3.072091e-02 7.881983e-01 3.435549e+02 -3.881736e-02 9.968526e-01 6.912407e-02 2.876121e-01 -7.878411e-01 -7.308316e-02 6.115271e-01 6.372230e+01 +6.115778e-01 -2.808429e-02 7.906857e-01 3.443514e+02 -3.906280e-02 9.970792e-01 6.562937e-02 3.315807e-01 -7.902194e-01 -7.102385e-02 6.086945e-01 6.434145e+01 +6.095860e-01 -2.855430e-02 7.922055e-01 3.451509e+02 -3.853996e-02 9.971017e-01 6.559531e-02 3.770411e-01 -7.917826e-01 -7.051754e-02 6.067188e-01 6.495923e+01 +6.085527e-01 -3.468806e-02 7.927549e-01 3.459578e+02 -3.478824e-02 9.969172e-01 7.032641e-02 4.211189e-01 -7.927505e-01 -7.037587e-02 6.054699e-01 6.557679e+01 +6.080276e-01 -4.413272e-02 7.926883e-01 3.467695e+02 -3.030049e-02 9.964363e-01 7.871818e-02 4.707702e-01 -7.933375e-01 -7.188166e-02 6.045235e-01 6.619159e+01 +6.073378e-01 -4.979231e-02 7.928818e-01 3.475814e+02 -2.858037e-02 9.960185e-01 8.444135e-02 5.273584e-01 -7.939295e-01 -7.394526e-02 6.034966e-01 6.680720e+01 +6.064482e-01 -4.968834e-02 7.935690e-01 3.483865e+02 -2.752721e-02 9.961352e-01 8.340818e-02 5.831376e-01 -7.946464e-01 -7.242746e-02 6.027366e-01 6.741820e+01 +6.058335e-01 -4.527114e-02 7.943023e-01 3.491896e+02 -2.519811e-02 9.967870e-01 7.603094e-02 6.373941e-01 -7.951923e-01 -6.607700e-02 6.027463e-01 6.802224e+01 +6.051261e-01 -4.002277e-02 7.951230e-01 3.499934e+02 -2.373252e-02 9.973849e-01 6.826526e-02 6.867561e-01 -7.957758e-01 -6.017936e-02 6.025938e-01 6.862683e+01 +6.040625e-01 -3.946343e-02 7.959592e-01 3.508015e+02 -2.078249e-02 9.976534e-01 6.523544e-02 7.306963e-01 -7.966659e-01 -5.594829e-02 6.018249e-01 6.922924e+01 +6.029019e-01 -4.279891e-02 7.966665e-01 3.516181e+02 -1.807032e-02 9.975713e-01 6.726729e-02 7.719350e-01 -7.976107e-01 -5.495159e-02 6.006642e-01 6.983576e+01 +6.017194e-01 -4.876742e-02 7.972173e-01 3.524363e+02 -1.421366e-02 9.973223e-01 7.173638e-02 8.118633e-01 -7.985811e-01 -5.449654e-02 5.994151e-01 7.043699e+01 +6.009886e-01 -5.395396e-02 7.974344e-01 3.532541e+02 -1.121965e-02 9.970511e-01 7.591564e-02 8.570171e-01 -7.991789e-01 -5.457136e-02 5.986110e-01 7.103883e+01 +6.002911e-01 -5.775368e-02 7.976936e-01 3.540720e+02 -8.728209e-03 9.968568e-01 7.874155e-02 9.061182e-01 -7.997340e-01 -5.423028e-02 5.979003e-01 7.164191e+01 +5.998610e-01 -5.933165e-02 7.979014e-01 3.548849e+02 -7.637015e-03 9.967767e-01 7.986146e-02 9.553822e-01 -8.000678e-01 -5.399935e-02 5.974743e-01 7.224224e+01 +5.998222e-01 -5.831621e-02 7.980053e-01 3.556986e+02 -6.321807e-03 9.969639e-01 7.760742e-02 1.004715e+00 -8.001084e-01 -5.159548e-02 5.976325e-01 7.284490e+01 +5.998860e-01 -5.668846e-02 7.980747e-01 3.565095e+02 -4.499765e-03 9.972319e-01 7.421724e-02 1.054302e+00 -8.000728e-01 -4.811303e-02 5.979704e-01 7.344368e+01 +6.000183e-01 -5.743246e-02 7.979220e-01 3.573241e+02 -3.837466e-03 9.972015e-01 7.466181e-02 1.105041e+00 -7.999771e-01 -4.786044e-02 5.981188e-01 7.404848e+01 +5.996718e-01 -6.118173e-02 7.979038e-01 3.581418e+02 -1.968578e-03 9.969573e-01 7.792428e-02 1.154416e+00 -8.002436e-01 -4.829973e-02 5.977268e-01 7.465095e+01 +5.992385e-01 -6.322530e-02 7.980700e-01 3.589549e+02 -1.214483e-03 9.968036e-01 7.988145e-02 1.205514e+00 -8.005696e-01 -4.883728e-02 5.972464e-01 7.525210e+01 +5.985852e-01 -6.212440e-02 7.986465e-01 3.597704e+02 1.349730e-04 9.969960e-01 7.745229e-02 1.255258e+00 -8.010591e-01 -4.625399e-02 5.967955e-01 7.585261e+01 +5.980991e-01 -6.136596e-02 7.990693e-01 3.605831e+02 1.211253e-03 9.971322e-01 7.566995e-02 1.307541e+00 -8.014213e-01 -4.429024e-02 5.964582e-01 7.645292e+01 +5.975805e-01 -6.263808e-02 7.993585e-01 3.613986e+02 2.872640e-03 9.971047e-01 7.598606e-02 1.358613e+00 -8.018038e-01 -4.311151e-02 5.960303e-01 7.705344e+01 +5.974969e-01 -6.530505e-02 7.992076e-01 3.622130e+02 3.628878e-03 9.968882e-01 7.874500e-02 1.409611e+00 -8.018631e-01 -4.414966e-02 5.958746e-01 7.765593e+01 +5.975513e-01 -6.773831e-02 7.989643e-01 3.630263e+02 6.607541e-03 9.968073e-01 7.957016e-02 1.463455e+00 -8.018035e-01 -4.226806e-02 5.960911e-01 7.825590e+01 +5.978009e-01 -7.098657e-02 7.984955e-01 3.638376e+02 1.035328e-02 9.966722e-01 8.085350e-02 1.518440e+00 -8.015778e-01 -4.006724e-02 5.965465e-01 7.885458e+01 +5.979506e-01 -7.513174e-02 7.980040e-01 3.646465e+02 1.538803e-02 9.964897e-01 8.228874e-02 1.575087e+00 -8.013853e-01 -3.692488e-02 5.970077e-01 7.945174e+01 +5.982385e-01 -8.043474e-02 7.972709e-01 3.654522e+02 2.156288e-02 9.962050e-01 8.432485e-02 1.632868e+00 -8.010280e-01 -3.325491e-02 5.977026e-01 8.004472e+01 +5.984444e-01 -8.530892e-02 7.966095e-01 3.662568e+02 2.887638e-02 9.959654e-01 8.496489e-02 1.693095e+00 -8.006438e-01 -2.784356e-02 5.984934e-01 8.063483e+01 +5.993558e-01 -8.842790e-02 7.955835e-01 3.670527e+02 3.211076e-02 9.957356e-01 8.648376e-02 1.755061e+00 -7.998385e-01 -2.628775e-02 5.996394e-01 8.122981e+01 +6.001016e-01 -9.150953e-02 7.946723e-01 3.678450e+02 3.558819e-02 9.955056e-01 8.776163e-02 1.818981e+00 -7.991318e-01 -2.438494e-02 6.006612e-01 8.182341e+01 +6.011409e-01 -9.358427e-02 7.936445e-01 3.686274e+02 3.662952e-02 9.953024e-01 8.961841e-02 1.881295e+00 -7.983031e-01 -2.480248e-02 6.017450e-01 8.241447e+01 +6.023045e-01 -9.503952e-02 7.925887e-01 3.694018e+02 3.717329e-02 9.951495e-01 9.107992e-02 1.943287e+00 -7.974005e-01 -2.539472e-02 6.029160e-01 8.299951e+01 +6.035026e-01 -9.576110e-02 7.915898e-01 3.701664e+02 3.907438e-02 9.951211e-01 9.059291e-02 2.005374e+00 -7.964031e-01 -2.374217e-02 6.043000e-01 8.357975e+01 +6.047959e-01 -9.728033e-02 7.904166e-01 3.709204e+02 4.032043e-02 9.949787e-01 9.160518e-02 2.065452e+00 -7.953592e-01 -2.353250e-02 6.056815e-01 8.415507e+01 +6.060398e-01 -9.975098e-02 7.891549e-01 3.716627e+02 4.116245e-02 9.947093e-01 9.412242e-02 2.125331e+00 -7.943686e-01 -2.455838e-02 6.069394e-01 8.472436e+01 +6.069261e-01 -1.017592e-01 7.882168e-01 3.723933e+02 3.954276e-02 9.944073e-01 9.793061e-02 2.185990e+00 -7.937739e-01 -2.826838e-02 6.075557e-01 8.528816e+01 +6.073216e-01 -1.048921e-01 7.875012e-01 3.731107e+02 3.515620e-02 9.938230e-01 1.052609e-01 2.251081e+00 -7.936779e-01 -3.624165e-02 6.072577e-01 8.584868e+01 +6.075092e-01 -1.055913e-01 7.872630e-01 3.738107e+02 2.810799e-02 9.933619e-01 1.115441e-01 2.316552e+00 -7.938152e-01 -4.563570e-02 6.064445e-01 8.640180e+01 +6.074550e-01 -1.037687e-01 7.875471e-01 3.744976e+02 2.136876e-02 9.932067e-01 1.143846e-01 2.384074e+00 -7.940667e-01 -5.265456e-02 6.055458e-01 8.694454e+01 +6.073842e-01 -1.011569e-01 7.879415e-01 3.751693e+02 1.478535e-02 9.931273e-01 1.161017e-01 2.455947e+00 -7.942707e-01 -5.886832e-02 6.047054e-01 8.747500e+01 +6.070655e-01 -9.781602e-02 7.886086e-01 3.758296e+02 8.632362e-03 9.931483e-01 1.165413e-01 2.525397e+00 -7.946049e-01 -6.394061e-02 6.037505e-01 8.799199e+01 +6.064800e-01 -9.495393e-02 7.894085e-01 3.764780e+02 4.765197e-03 9.932596e-01 1.158132e-01 2.593374e+00 -7.950845e-01 -6.647668e-02 6.028445e-01 8.849556e+01 +6.060018e-01 -9.278193e-02 7.900337e-01 3.771159e+02 2.919314e-03 9.934271e-01 1.144293e-01 2.658386e+00 -7.954579e-01 -6.703799e-02 6.022895e-01 8.898482e+01 +6.054993e-01 -9.146038e-02 7.905729e-01 3.777468e+02 3.547063e-03 9.936747e-01 1.122403e-01 2.722154e+00 -7.958380e-01 -6.515720e-02 6.019938e-01 8.946349e+01 +6.050099e-01 -9.193372e-02 7.908926e-01 3.783710e+02 4.340029e-03 9.936778e-01 1.121856e-01 2.782431e+00 -7.962061e-01 -6.444088e-02 6.015839e-01 8.993373e+01 +6.045966e-01 -9.114828e-02 7.912995e-01 3.789847e+02 3.779040e-03 9.937482e-01 1.115806e-01 2.839420e+00 -7.965229e-01 -6.447087e-02 6.011612e-01 9.039767e+01 +6.031009e-01 -9.069383e-02 7.924922e-01 3.795884e+02 2.833208e-03 9.937525e-01 1.115702e-01 2.895644e+00 -7.976599e-01 -6.504280e-02 5.995900e-01 9.085453e+01 +6.003021e-01 -9.063751e-02 7.946208e-01 3.801834e+02 1.395973e-03 9.936747e-01 1.122878e-01 2.953651e+00 -7.997721e-01 -6.629732e-02 5.966316e-01 9.130094e+01 +5.960463e-01 -8.951693e-02 7.979445e-01 3.807729e+02 -2.795116e-03 9.935287e-01 1.135463e-01 3.009361e+00 -8.029452e-01 -6.990922e-02 5.919390e-01 9.174008e+01 +5.904110e-01 -9.032450e-02 8.020326e-01 3.813576e+02 -4.361162e-03 9.933466e-01 1.150806e-01 3.062328e+00 -8.070910e-01 -7.144266e-02 5.860888e-01 9.216341e+01 +5.851683e-01 -8.854865e-02 8.060627e-01 3.819330e+02 -7.507562e-03 9.933860e-01 1.145769e-01 3.112642e+00 -8.108771e-01 -7.309834e-02 5.806332e-01 9.257369e+01 +5.793681e-01 -8.306073e-02 8.108227e-01 3.825049e+02 -1.054397e-02 9.939469e-01 1.093541e-01 3.160924e+00 -8.149978e-01 -7.190557e-02 5.749854e-01 9.297641e+01 +5.728861e-01 -7.628126e-02 8.160776e-01 3.830793e+02 -1.451187e-02 9.945597e-01 1.031519e-01 3.210042e+00 -8.195066e-01 -7.093707e-02 5.686624e-01 9.337300e+01 +5.648829e-01 -7.320741e-02 8.219172e-01 3.836609e+02 -1.657667e-02 9.948490e-01 1.000030e-01 3.261727e+00 -8.250046e-01 -7.011465e-02 5.607597e-01 9.376359e+01 +5.550968e-01 -7.411340e-02 8.284774e-01 3.842584e+02 -1.839945e-02 9.946847e-01 1.013099e-01 3.311365e+00 -8.315823e-01 -7.148032e-02 5.507827e-01 9.415217e+01 +5.449432e-01 -7.820795e-02 8.348176e-01 3.848622e+02 -2.278707e-02 9.938913e-01 1.079851e-01 3.360853e+00 -8.381633e-01 -7.786879e-02 5.398322e-01 9.454098e+01 +5.353434e-01 -8.348276e-02 8.404987e-01 3.854764e+02 -2.387576e-02 9.932101e-01 1.138582e-01 3.416745e+00 -8.442970e-01 -8.102075e-02 5.297152e-01 9.492187e+01 +5.253797e-01 -8.796219e-02 8.463089e-01 3.861003e+02 -2.448596e-02 9.926670e-01 1.183747e-01 3.475179e+00 -8.505155e-01 -8.291436e-02 5.193733e-01 9.529750e+01 +5.155144e-01 -9.069877e-02 8.520673e-01 3.867256e+02 -2.389548e-02 9.924740e-01 1.201016e-01 3.536985e+00 -8.565477e-01 -8.227464e-02 5.094673e-01 9.566617e+01 +5.059644e-01 -9.091314e-02 8.577498e-01 3.873588e+02 -2.225691e-02 9.927227e-01 1.183478e-01 3.601461e+00 -8.622672e-01 -7.897060e-02 5.002590e-01 9.602935e+01 +4.980296e-01 -8.981031e-02 8.624967e-01 3.879960e+02 -1.904716e-02 9.932494e-01 1.144237e-01 3.664976e+00 -8.669509e-01 -7.341450e-02 4.929570e-01 9.638488e+01 +4.909707e-01 -8.830486e-02 8.666891e-01 3.886418e+02 -1.358240e-02 9.939527e-01 1.089657e-01 3.731560e+00 -8.710702e-01 -6.527069e-02 4.868022e-01 9.673499e+01 +4.849313e-01 -8.948504e-02 8.699621e-01 3.892979e+02 -7.527502e-03 9.942875e-01 1.064692e-01 3.798926e+00 -8.745199e-01 -5.817889e-02 4.814875e-01 9.708630e+01 +4.793476e-01 -9.578809e-02 8.723821e-01 3.899619e+02 -2.327362e-03 9.938836e-01 1.104079e-01 3.869983e+00 -8.776221e-01 -5.495410e-02 4.761928e-01 9.744102e+01 +4.743914e-01 -1.096168e-01 8.734626e-01 3.906449e+02 9.621121e-05 9.922235e-01 1.244687e-01 3.945355e+00 -8.803141e-01 -5.896283e-02 4.707128e-01 9.780232e+01 +4.704719e-01 -1.232648e-01 8.737631e-01 3.913339e+02 -1.450796e-03 9.900858e-01 1.404561e-01 4.027034e+00 -8.824138e-01 -6.734829e-02 4.656288e-01 9.817505e+01 +4.655633e-01 -1.365143e-01 8.744225e-01 3.920249e+02 -4.533654e-03 9.876508e-01 1.566053e-01 4.116231e+00 -8.850030e-01 -7.687398e-02 4.591950e-01 9.854535e+01 +4.600427e-01 -1.405238e-01 8.767062e-01 3.927178e+02 -4.722003e-03 9.869953e-01 1.606794e-01 4.211579e+00 -8.878843e-01 -7.805919e-02 4.533964e-01 9.890721e+01 +4.549754e-01 -1.378729e-01 8.797661e-01 3.934140e+02 -6.395519e-03 9.874104e-01 1.580499e-01 4.312938e+00 -8.904811e-01 -7.753536e-02 4.483657e-01 9.926698e+01 +4.491424e-01 -1.362613e-01 8.830085e-01 3.941151e+02 -7.041302e-03 9.877314e-01 1.560032e-01 4.416686e+00 -8.934325e-01 -7.628518e-02 4.426726e-01 9.962394e+01 +4.430048e-01 -1.424287e-01 8.851332e-01 3.948314e+02 -2.797588e-03 9.870753e-01 1.602327e-01 4.526817e+00 -8.965149e-01 -7.346007e-02 4.368807e-01 9.997536e+01 +4.369239e-01 -1.496538e-01 8.869618e-01 3.955498e+02 -3.871759e-04 9.860312e-01 1.665602e-01 4.640894e+00 -8.994984e-01 -7.311754e-02 4.307627e-01 1.003225e+02 +4.302634e-01 -1.553473e-01 8.892360e-01 3.962758e+02 3.610727e-03 9.853693e-01 1.703945e-01 4.754188e+00 -9.026962e-01 -7.010372e-02 4.245293e-01 1.006607e+02 +4.247975e-01 -1.589517e-01 8.912247e-01 3.969938e+02 6.605355e-03 9.849829e-01 1.725252e-01 4.868321e+00 -9.052643e-01 -6.740143e-02 4.194682e-01 1.009936e+02 +4.189650e-01 -1.587218e-01 8.940222e-01 3.977045e+02 8.122677e-03 9.852191e-01 1.711061e-01 4.987048e+00 -9.079661e-01 -6.442561e-02 4.140616e-01 1.013225e+02 +4.131386e-01 -1.579036e-01 8.968740e-01 3.984144e+02 8.201880e-03 9.854579e-01 1.697216e-01 5.103503e+00 -9.106313e-01 -6.276248e-02 4.084258e-01 1.016473e+02 +4.069813e-01 -1.583458e-01 8.996070e-01 3.991214e+02 6.731221e-03 9.853531e-01 1.703934e-01 5.219817e+00 -9.134117e-01 -6.329148e-02 4.020862e-01 1.019680e+02 +3.993633e-01 -1.587640e-01 9.029413e-01 3.998242e+02 4.274363e-03 9.852031e-01 1.713376e-01 5.332589e+00 -9.167828e-01 -6.456644e-02 3.941325e-01 1.022796e+02 +3.903290e-01 -1.591420e-01 9.068170e-01 4.005261e+02 3.806304e-03 9.852180e-01 1.712626e-01 5.443658e+00 -9.206676e-01 -6.339714e-02 3.851649e-01 1.025786e+02 +3.802632e-01 -1.601029e-01 9.109154e-01 4.012227e+02 4.912495e-03 9.852387e-01 1.711153e-01 5.551546e+00 -9.248653e-01 -6.059398e-02 3.754366e-01 1.028625e+02 +3.701451e-01 -1.613206e-01 9.148597e-01 4.019166e+02 4.370984e-03 9.850981e-01 1.719376e-01 5.657436e+00 -9.289637e-01 -5.964302e-02 3.653344e-01 1.031409e+02 +3.604258e-01 -1.623738e-01 9.185467e-01 4.026027e+02 2.700767e-03 9.849101e-01 1.730453e-01 5.762673e+00 -9.327840e-01 -5.988922e-02 3.554256e-01 1.034080e+02 +3.502305e-01 -1.625484e-01 9.224514e-01 4.032798e+02 4.653159e-03 9.851166e-01 1.718242e-01 5.866325e+00 -9.366520e-01 -5.588574e-02 3.457742e-01 1.036591e+02 +3.401765e-01 -1.583437e-01 9.269343e-01 4.039506e+02 3.160511e-03 9.859081e-01 1.672581e-01 5.964650e+00 -9.403563e-01 -5.396767e-02 3.358832e-01 1.039027e+02 +3.288165e-01 -1.487348e-01 9.326080e-01 4.046170e+02 -2.486386e-03 9.873804e-01 1.583468e-01 6.061249e+00 -9.443906e-01 -5.438584e-02 3.242971e-01 1.041420e+02 +3.160335e-01 -1.389426e-01 9.385189e-01 4.052801e+02 -1.185209e-02 9.885629e-01 1.503424e-01 6.151740e+00 -9.486740e-01 -5.863662e-02 3.107722e-01 1.043753e+02 +3.000833e-01 -1.331180e-01 9.445791e-01 4.059597e+02 -1.646220e-02 9.893449e-01 1.446566e-01 6.239906e+00 -9.537710e-01 -5.895887e-02 2.946945e-01 1.045908e+02 +2.813717e-01 -1.305686e-01 9.506744e-01 4.066318e+02 -1.589774e-02 9.899295e-01 1.406653e-01 6.325233e+00 -9.594672e-01 -5.469281e-02 2.764624e-01 1.047799e+02 +2.610528e-01 -1.275602e-01 9.568593e-01 4.073170e+02 -1.524523e-02 9.905623e-01 1.362125e-01 6.405908e+00 -9.652042e-01 -5.014619e-02 2.566444e-01 1.049530e+02 +2.399132e-01 -1.224740e-01 9.630378e-01 4.080110e+02 -1.241082e-02 9.915421e-01 1.291908e-01 6.481032e+00 -9.707150e-01 -4.294666e-02 2.363640e-01 1.051082e+02 +2.192026e-01 -1.169665e-01 9.686429e-01 4.087023e+02 -8.559139e-03 9.925194e-01 1.217866e-01 6.551585e+00 -9.756419e-01 -3.498669e-02 2.165617e-01 1.052460e+02 +1.985298e-01 -1.137121e-01 9.734760e-01 4.094193e+02 -2.890252e-03 9.931744e-01 1.166026e-01 6.619282e+00 -9.800906e-01 -2.596268e-02 1.968461e-01 1.053713e+02 +1.788541e-01 -1.127523e-01 9.773935e-01 4.101351e+02 4.003258e-04 9.934199e-01 1.145278e-01 6.691065e+00 -9.838756e-01 -2.009250e-02 1.777224e-01 1.054854e+02 +1.606140e-01 -1.173070e-01 9.800215e-01 4.108725e+02 6.710304e-04 9.929249e-01 1.187416e-01 6.763749e+00 -9.870171e-01 -1.841394e-02 1.595564e-01 1.055946e+02 +1.453485e-01 -1.251070e-01 9.814387e-01 4.116172e+02 -1.924457e-03 9.919353e-01 1.267301e-01 6.838057e+00 -9.893787e-01 -2.030877e-02 1.439356e-01 1.057000e+02 +1.317574e-01 -1.356793e-01 9.819527e-01 4.123610e+02 1.167440e-05 9.905888e-01 1.368711e-01 6.919003e+00 -9.912820e-01 -1.802231e-02 1.305190e-01 1.057908e+02 +1.216579e-01 -1.413469e-01 9.824563e-01 4.131125e+02 1.230628e-04 9.898106e-01 1.423897e-01 7.000377e+00 -9.925721e-01 -1.720193e-02 1.204357e-01 1.058794e+02 +1.136936e-01 -1.437966e-01 9.830545e-01 4.138665e+02 -2.791291e-03 9.894203e-01 1.450506e-01 7.082022e+00 -9.935120e-01 -1.923533e-02 1.120894e-01 1.059700e+02 +1.063391e-01 -1.453768e-01 9.836450e-01 4.146247e+02 -7.700614e-03 9.891041e-01 1.470162e-01 7.167742e+00 -9.943001e-01 -2.320824e-02 1.040610e-01 1.060586e+02 +9.860270e-02 -1.505317e-01 9.836756e-01 4.153892e+02 -9.247338e-03 9.883113e-01 1.521681e-01 7.261742e+00 -9.950839e-01 -2.410056e-02 9.605815e-02 1.061371e+02 +9.201418e-02 -1.524926e-01 9.840119e-01 4.161484e+02 -1.406124e-02 9.879066e-01 1.544110e-01 7.350541e+00 -9.956584e-01 -2.804443e-02 8.875719e-02 1.062120e+02 +8.664806e-02 -1.418914e-01 9.860826e-01 4.168974e+02 -2.975908e-02 9.889949e-01 1.449255e-01 7.427760e+00 -9.957944e-01 -4.190242e-02 8.147193e-02 1.062978e+02 +8.105048e-02 -1.222316e-01 9.891866e-01 4.176432e+02 -3.815885e-02 9.913437e-01 1.256248e-01 7.505022e+00 -9.959793e-01 -4.792817e-02 7.568466e-02 1.063750e+02 +7.679643e-02 -1.049671e-01 9.915060e-01 4.183920e+02 -3.547326e-02 9.935256e-01 1.079285e-01 7.589414e+00 -9.964156e-01 -4.346047e-02 7.257569e-02 1.064346e+02 +7.321024e-02 -1.036450e-01 9.919163e-01 4.191639e+02 -4.153907e-02 9.934053e-01 1.068665e-01 7.668172e+00 -9.964511e-01 -4.902700e-02 6.842212e-02 1.065066e+02 +7.282310e-02 -1.142325e-01 9.907814e-01 4.199504e+02 -5.122271e-02 9.916796e-01 1.181010e-01 7.739703e+00 -9.960287e-01 -5.935098e-02 6.636588e-02 1.065859e+02 +7.467769e-02 -1.219647e-01 9.897211e-01 4.207323e+02 -5.305876e-02 9.906005e-01 1.260766e-01 7.809960e+00 -9.957952e-01 -6.192847e-02 6.750446e-02 1.066555e+02 +7.756049e-02 -1.071565e-01 9.912123e-01 4.214933e+02 -5.716881e-02 9.920933e-01 1.117251e-01 7.865259e+00 -9.953473e-01 -6.533187e-02 7.082124e-02 1.067270e+02 +8.058449e-02 -8.102776e-02 9.934488e-01 4.222299e+02 -5.842942e-02 9.945923e-01 8.586060e-02 7.916668e+00 -9.950338e-01 -6.496566e-02 7.541431e-02 1.068000e+02 +8.626061e-02 -5.925487e-02 9.945089e-01 4.229770e+02 -5.928966e-02 9.961551e-01 6.449557e-02 7.971700e+00 -9.945069e-01 -6.452751e-02 8.241575e-02 1.068715e+02 +9.082572e-02 -5.858121e-02 9.941423e-01 4.237372e+02 -6.264264e-02 9.959553e-01 6.441114e-02 8.020692e+00 -9.938947e-01 -6.812588e-02 8.678868e-02 1.069478e+02 +9.421481e-02 -7.308939e-02 9.928653e-01 4.245012e+02 -6.863401e-02 9.944517e-01 7.971899e-02 8.059333e+00 -9.931833e-01 -7.565503e-02 8.867567e-02 1.070352e+02 +9.679852e-02 -8.133984e-02 9.919747e-01 4.252498e+02 -7.020093e-02 9.936149e-01 8.832467e-02 8.093652e+00 -9.928252e-01 -7.818724e-02 9.047032e-02 1.071189e+02 +9.891056e-02 -7.797460e-02 9.920366e-01 4.259771e+02 -6.505976e-02 9.942855e-01 8.463813e-02 8.129462e+00 -9.929673e-01 -7.291326e-02 9.327232e-02 1.071916e+02 +1.018254e-01 -6.813637e-02 9.924661e-01 4.266891e+02 -6.023073e-02 9.953991e-01 7.451731e-02 8.167187e+00 -9.929773e-01 -6.736470e-02 9.725299e-02 1.072626e+02 +1.041878e-01 -6.182958e-02 9.926339e-01 4.273978e+02 -5.669681e-02 9.960734e-01 6.799478e-02 8.202315e+00 -9.929403e-01 -6.336339e-02 1.002731e-01 1.073393e+02 +1.068290e-01 -5.988885e-02 9.924721e-01 4.281028e+02 -5.368647e-02 9.963807e-01 6.590349e-02 8.233718e+00 -9.928270e-01 -6.032272e-02 1.032271e-01 1.074201e+02 +1.072243e-01 -5.654289e-02 9.926257e-01 4.287973e+02 -5.034621e-02 9.967919e-01 6.221866e-02 8.264055e+00 -9.929593e-01 -5.664628e-02 1.040336e-01 1.075012e+02 +1.066073e-01 -5.021526e-02 9.930324e-01 4.294784e+02 -5.044442e-02 9.971646e-01 5.583970e-02 8.290819e+00 -9.930208e-01 -5.604585e-02 1.037720e-01 1.075837e+02 +1.059295e-01 -4.572161e-02 9.933219e-01 4.301492e+02 -5.257318e-02 9.972877e-01 5.151065e-02 8.313589e+00 -9.929829e-01 -5.767858e-02 1.032384e-01 1.076708e+02 +1.042889e-01 -4.136689e-02 9.936864e-01 4.308100e+02 -5.797427e-02 9.971828e-01 4.759694e-02 8.332906e+00 -9.928559e-01 -6.257207e-02 1.015969e-01 1.077570e+02 +9.811654e-02 -3.886389e-02 9.944158e-01 4.314674e+02 -6.299690e-02 9.969905e-01 4.518027e-02 8.346583e+00 -9.931790e-01 -6.707803e-02 9.537295e-02 1.078376e+02 +8.586484e-02 -3.766662e-02 9.955945e-01 4.321175e+02 -6.821838e-02 9.967176e-01 4.359260e-02 8.355373e+00 -9.939686e-01 -7.166090e-02 8.301343e-02 1.079076e+02 +6.919224e-02 -3.580094e-02 9.969607e-01 4.327650e+02 -7.139301e-02 9.966158e-01 4.074345e-02 8.365156e+00 -9.950455e-01 -7.399515e-02 6.640214e-02 1.079600e+02 +5.058588e-02 -3.496346e-02 9.981075e-01 4.333982e+02 -7.003625e-02 9.968025e-01 3.846731e-02 8.376060e+00 -9.962610e-01 -7.184960e-02 4.797542e-02 1.079914e+02 +3.170725e-02 -3.628207e-02 9.988384e-01 4.340258e+02 -6.632585e-02 9.970618e-01 3.832299e-02 8.381937e+00 -9.972941e-01 -6.746392e-02 2.920764e-02 1.080081e+02 +1.378998e-02 -3.612994e-02 9.992519e-01 4.346248e+02 -6.356890e-02 9.972937e-01 3.693640e-02 8.387456e+00 -9.978822e-01 -6.403069e-02 1.145592e-02 1.080189e+02 +-3.811931e-03 -3.517352e-02 9.993739e-01 4.351999e+02 -6.115629e-02 9.975187e-01 3.487496e-02 8.390719e+00 -9.981210e-01 -6.098505e-02 -5.953557e-03 1.080164e+02 +-2.156527e-02 -3.485746e-02 9.991596e-01 4.357582e+02 -6.043160e-02 9.976100e-01 3.349909e-02 8.395461e+00 -9.979394e-01 -5.965839e-02 -2.362022e-02 1.080091e+02 +-3.938152e-02 -3.595553e-02 9.985771e-01 4.362915e+02 -6.246428e-02 9.974864e-01 3.345282e-02 8.399452e+00 -9.972700e-01 -6.105797e-02 -4.152847e-02 1.079901e+02 +-5.846796e-02 -3.804433e-02 9.975641e-01 4.368089e+02 -6.609014e-02 9.972288e-01 3.415796e-02 8.403295e+00 -9.960992e-01 -6.393199e-02 -6.082029e-02 1.079684e+02 +-7.759442e-02 -3.813227e-02 9.962555e-01 4.372990e+02 -6.420554e-02 9.973851e-01 3.317480e-02 8.401479e+00 -9.949155e-01 -6.139093e-02 -7.983983e-02 1.079305e+02 +-9.458754e-02 -3.377515e-02 9.949434e-01 4.377525e+02 -6.117388e-02 9.977328e-01 2.805415e-02 8.394344e+00 -9.936353e-01 -5.821096e-02 -9.643925e-02 1.078831e+02 +-1.108349e-01 -2.413405e-02 9.935457e-01 4.381792e+02 -5.403185e-02 9.983729e-01 1.822378e-02 8.385082e+00 -9.923690e-01 -5.166327e-02 -1.119586e-01 1.078263e+02 +-1.257869e-01 -1.295549e-02 9.919727e-01 4.385810e+02 -4.853257e-02 9.987978e-01 6.890463e-03 8.378120e+00 -9.908695e-01 -4.727624e-02 -1.262644e-01 1.077694e+02 +-1.388419e-01 -4.147506e-03 9.903059e-01 4.389558e+02 -4.681446e-02 9.989007e-01 -2.379938e-03 8.371887e+00 -9.892075e-01 -4.669106e-02 -1.388835e-01 1.077178e+02 +-1.496289e-01 2.409113e-03 9.887393e-01 4.393196e+02 -4.969733e-02 9.987147e-01 -9.954269e-03 8.371096e+00 -9.874925e-01 -5.062714e-02 -1.493168e-01 1.076669e+02 +-1.592766e-01 6.282617e-03 9.872140e-01 4.396662e+02 -4.876287e-02 9.987091e-01 -1.422315e-02 8.368543e+00 -9.860290e-01 -5.040479e-02 -1.587647e-01 1.076070e+02 +-1.677023e-01 8.454190e-03 9.858014e-01 4.399972e+02 -4.500105e-02 9.988552e-01 -1.622162e-02 8.358794e+00 -9.848101e-01 -4.708249e-02 -1.671299e-01 1.075448e+02 +-1.739557e-01 8.586443e-03 9.847160e-01 4.403117e+02 -3.714833e-02 9.991930e-01 -1.527515e-02 8.348141e+00 -9.840526e-01 -3.923775e-02 -1.734963e-01 1.074760e+02 +-1.790062e-01 8.305676e-03 9.838129e-01 4.406089e+02 -2.776391e-02 9.995235e-01 -1.349000e-02 8.339225e+00 -9.834561e-01 -2.972928e-02 -1.786903e-01 1.074090e+02 +-1.840637e-01 5.723853e-03 9.828976e-01 4.408912e+02 -2.895896e-02 9.995173e-01 -1.124368e-02 8.330838e+00 -9.824877e-01 -3.053324e-02 -1.838091e-01 1.073598e+02 +-1.890667e-01 3.272083e-03 9.819588e-01 4.411539e+02 -3.487886e-02 9.993410e-01 -1.004560e-02 8.320060e+00 -9.813446e-01 -3.614889e-02 -1.888280e-01 1.073234e+02 +-1.927184e-01 1.871383e-04 9.812541e-01 4.413987e+02 -4.176623e-02 9.990921e-01 -8.393437e-03 8.312378e+00 -9.803649e-01 -4.260085e-02 -1.925357e-01 1.072894e+02 +-1.957530e-01 -1.723217e-03 9.806517e-01 4.416215e+02 -4.416546e-02 9.989993e-01 -7.060643e-03 8.308381e+00 -9.796582e-01 -4.469307e-02 -1.956332e-01 1.072539e+02 +-1.979803e-01 -5.835540e-04 9.802058e-01 4.418197e+02 -4.248788e-02 9.990650e-01 -7.986853e-03 8.302167e+00 -9.792848e-01 -4.322810e-02 -1.978200e-01 1.072159e+02 +-1.998675e-01 1.785404e-03 9.798213e-01 4.419929e+02 -3.808652e-02 9.992284e-01 -9.589799e-03 8.292936e+00 -9.790825e-01 -3.923467e-02 -1.996453e-01 1.071791e+02 +-2.006761e-01 3.939045e-03 9.796497e-01 4.421489e+02 -3.361325e-02 9.993754e-01 -1.090386e-02 8.284685e+00 -9.790809e-01 -3.511735e-02 -2.004183e-01 1.071466e+02 +-2.005200e-01 6.867038e-03 9.796655e-01 4.422988e+02 -3.134515e-02 9.994185e-01 -1.342129e-02 8.284115e+00 -9.791881e-01 -3.339899e-02 -2.001881e-01 1.071254e+02 +-1.990182e-01 8.974308e-03 9.799547e-01 4.424486e+02 -3.313403e-02 9.993247e-01 -1.588087e-02 8.281336e+00 -9.794355e-01 -3.563042e-02 -1.985865e-01 1.071107e+02 +-1.966522e-01 9.012374e-03 9.804319e-01 4.426003e+02 -3.145277e-02 9.993851e-01 -1.549531e-02 8.281351e+00 -9.799687e-01 -3.388448e-02 -1.962478e-01 1.070931e+02 +-1.924504e-01 6.334441e-03 9.812862e-01 4.427548e+02 -2.301449e-02 9.996750e-01 -1.096677e-02 8.282708e+00 -9.810368e-01 -2.469436e-02 -1.922421e-01 1.070634e+02 +-1.871240e-01 4.944993e-03 9.823238e-01 4.429059e+02 -1.708605e-02 9.998196e-01 -8.287814e-03 8.285099e+00 -9.821877e-01 -1.833488e-02 -1.870058e-01 1.070386e+02 +-1.830160e-01 6.800071e-03 9.830864e-01 4.430529e+02 -1.445206e-02 9.998494e-01 -9.606491e-03 8.283272e+00 -9.830037e-01 -1.596576e-02 -1.828901e-01 1.070229e+02 +-1.792908e-01 8.078018e-03 9.837629e-01 4.431997e+02 -1.725191e-02 9.997867e-01 -1.135376e-02 8.280202e+00 -9.836449e-01 -1.900741e-02 -1.791132e-01 1.070169e+02 +-1.747448e-01 8.959667e-03 9.845730e-01 4.433468e+02 -2.096651e-02 9.996980e-01 -1.281851e-02 8.276204e+00 -9.843905e-01 -2.288303e-02 -1.745041e-01 1.070141e+02 +-1.695297e-01 1.055512e-02 9.854685e-01 4.434966e+02 -2.364492e-02 9.996112e-01 -1.477423e-02 8.273670e+00 -9.852414e-01 -2.580600e-02 -1.692142e-01 1.070092e+02 +-1.636560e-01 1.129711e-02 9.864528e-01 4.436589e+02 -2.395622e-02 9.995940e-01 -1.542204e-02 8.271518e+00 -9.862266e-01 -2.615558e-02 -1.633190e-01 1.069995e+02 +-1.573105e-01 1.104146e-02 9.874875e-01 4.438360e+02 -2.419335e-02 9.995943e-01 -1.503093e-02 8.270710e+00 -9.872528e-01 -2.625515e-02 -1.569795e-01 1.069893e+02 +-1.508982e-01 8.760603e-03 9.885105e-01 4.440318e+02 -2.942975e-02 9.994777e-01 -1.335032e-02 8.272879e+00 -9.881112e-01 -3.110615e-02 -1.505616e-01 1.069847e+02 +-1.421527e-01 5.623549e-03 9.898287e-01 4.442467e+02 -3.778243e-02 9.992243e-01 -1.110300e-02 8.274685e+00 -9.891234e-01 -3.897645e-02 -1.418300e-01 1.069889e+02 +-1.331873e-01 3.197064e-03 9.910857e-01 4.444730e+02 -4.390593e-02 9.989940e-01 -9.122888e-03 8.271421e+00 -9.901179e-01 -4.472959e-02 -1.329129e-01 1.069895e+02 +-1.238076e-01 1.014070e-03 9.923057e-01 4.447070e+02 -4.156003e-02 9.991167e-01 -6.206380e-03 8.261392e+00 -9.914356e-01 -4.200865e-02 -1.236561e-01 1.069764e+02 +-1.125855e-01 -1.562084e-04 9.936420e-01 4.449541e+02 -3.466970e-02 9.993917e-01 -3.771172e-03 8.252821e+00 -9.930371e-01 -3.487385e-02 -1.125224e-01 1.069578e+02 +-1.010513e-01 -1.028935e-03 9.948807e-01 4.452055e+02 -2.992429e-02 9.995501e-01 -2.005689e-03 8.244671e+00 -9.944311e-01 -2.997377e-02 -1.010367e-01 1.069463e+02 +-8.593297e-02 -7.179472e-04 9.963006e-01 4.454699e+02 -2.674592e-02 9.996410e-01 -1.586539e-03 8.242657e+00 -9.959419e-01 -2.678331e-02 -8.592132e-02 1.069428e+02 +-6.962040e-02 -4.220364e-05 9.975735e-01 4.457410e+02 -2.234928e-02 9.997490e-01 -1.517458e-03 8.242741e+00 -9.973232e-01 -2.240069e-02 -6.960388e-02 1.069431e+02 +-5.210790e-02 -9.815638e-04 9.986410e-01 4.460129e+02 -2.192638e-02 9.997596e-01 -1.614327e-04 8.236481e+00 -9.984008e-01 -2.190499e-02 -5.211690e-02 1.069533e+02 +-3.133338e-02 -2.033151e-03 9.995069e-01 4.463024e+02 -2.121209e-02 9.997740e-01 1.368717e-03 8.230851e+00 -9.992839e-01 -2.115874e-02 -3.136942e-02 1.069727e+02 +-9.410041e-03 -1.512669e-03 9.999546e-01 4.466028e+02 -2.099284e-02 9.997787e-01 1.314847e-03 8.226772e+00 -9.997354e-01 -2.097952e-02 -9.439717e-03 1.069995e+02 +1.243458e-02 5.589619e-04 9.999225e-01 4.469028e+02 -2.211826e-02 9.997553e-01 -2.838195e-04 8.225666e+00 -9.996781e-01 -2.211301e-02 1.244390e-02 1.070336e+02 +3.552485e-02 4.545351e-03 9.993584e-01 4.472256e+02 -2.877736e-02 9.995796e-01 -3.523393e-03 8.225759e+00 -9.989544e-01 -2.863373e-02 3.564072e-02 1.070867e+02 +5.851293e-02 8.215843e-03 9.982528e-01 4.475585e+02 -3.376975e-02 9.994101e-01 -6.245947e-03 8.226509e+00 -9.977153e-01 -3.334528e-02 5.875586e-02 1.071497e+02 +8.414822e-02 8.445045e-03 9.964174e-01 4.478898e+02 -3.669133e-02 9.993122e-01 -5.370973e-03 8.222854e+00 -9.957775e-01 -3.610792e-02 8.440020e-02 1.072100e+02 +1.097230e-01 7.108325e-03 9.939368e-01 4.482499e+02 -3.292616e-02 9.994516e-01 -3.512974e-03 8.217450e+00 -9.934167e-01 -3.234106e-02 1.098969e-01 1.072771e+02 +1.349697e-01 5.557627e-03 9.908341e-01 4.486050e+02 -3.002770e-02 9.995479e-01 -1.516187e-03 8.211699e+00 -9.903947e-01 -2.954782e-02 1.350756e-01 1.073516e+02 +1.609063e-01 5.247839e-03 9.869557e-01 4.489874e+02 -2.994403e-02 9.995515e-01 -4.329532e-04 8.207744e+00 -9.865154e-01 -2.948376e-02 1.609913e-01 1.074465e+02 +1.868730e-01 5.287978e-03 9.823698e-01 4.493814e+02 -3.058430e-02 9.995321e-01 4.375858e-04 8.204227e+00 -9.819079e-01 -3.012686e-02 1.869473e-01 1.075566e+02 +2.126458e-01 5.612588e-03 9.771132e-01 4.497735e+02 -3.229593e-02 9.994775e-01 1.287397e-03 8.201329e+00 -9.765955e-01 -3.183053e-02 2.127159e-01 1.076756e+02 +2.378631e-01 6.244046e-03 9.712786e-01 4.501895e+02 -3.101582e-02 9.995182e-01 1.170084e-03 8.198927e+00 -9.708034e-01 -3.040332e-02 2.379422e-01 1.078222e+02 +2.616197e-01 6.025441e-03 9.651522e-01 4.506113e+02 -3.027009e-02 9.995398e-01 1.965057e-03 8.195762e+00 -9.646963e-01 -2.972934e-02 2.616817e-01 1.080041e+02 +2.833287e-01 5.155084e-03 9.590090e-01 4.510376e+02 -2.878196e-02 9.995808e-01 3.130136e-03 8.192056e+00 -9.585909e-01 -2.848902e-02 2.833583e-01 1.081997e+02 +3.033003e-01 5.045384e-03 9.528816e-01 4.514911e+02 -2.842412e-02 9.995889e-01 3.754645e-03 8.188818e+00 -9.524710e-01 -2.822361e-02 3.033190e-01 1.084021e+02 +3.219205e-01 4.762178e-03 9.467547e-01 4.519494e+02 -2.783707e-02 9.996026e-01 4.437303e-03 8.186495e+00 -9.463574e-01 -2.778334e-02 3.219252e-01 1.086181e+02 +3.395005e-01 5.426540e-03 9.405902e-01 4.524322e+02 -2.821733e-02 9.995920e-01 4.417933e-03 8.183530e+00 -9.401826e-01 -2.804083e-02 3.395151e-01 1.088440e+02 +3.567146e-01 4.955625e-03 9.342003e-01 4.529289e+02 -2.582935e-02 9.996559e-01 4.559816e-03 8.181836e+00 -9.338563e-01 -2.575634e-02 3.567198e-01 1.090848e+02 +3.739717e-01 3.386100e-03 9.274339e-01 4.534353e+02 -2.207213e-02 9.997426e-01 5.250101e-03 8.179648e+00 -9.271775e-01 -2.243383e-02 3.739502e-01 1.093187e+02 +3.915617e-01 1.925642e-03 9.201498e-01 4.539636e+02 -1.772895e-02 9.998279e-01 5.452006e-03 8.182570e+00 -9.199811e-01 -1.844808e-02 3.915284e-01 1.095466e+02 +4.090249e-01 8.818277e-04 9.125228e-01 4.545022e+02 -1.310452e-02 9.999021e-01 4.907635e-03 8.183837e+00 -9.124292e-01 -1.396551e-02 4.089964e-01 1.097981e+02 +4.252686e-01 8.348513e-04 9.050668e-01 4.550427e+02 -1.210746e-02 9.999153e-01 4.766652e-03 8.183922e+00 -9.049862e-01 -1.298516e-02 4.252427e-01 1.100667e+02 +4.399950e-01 2.344311e-03 8.979972e-01 4.555975e+02 -1.322242e-02 9.999051e-01 3.868282e-03 8.182013e+00 -8.979029e-01 -1.357572e-02 4.399842e-01 1.103603e+02 +4.532749e-01 3.562361e-03 8.913636e-01 4.561582e+02 -1.493016e-02 9.998820e-01 3.596203e-03 8.181664e+00 -8.912458e-01 -1.493827e-02 4.532746e-01 1.106666e+02 +4.647687e-01 2.482137e-03 8.854286e-01 4.567493e+02 -1.540063e-02 9.998674e-01 5.280971e-03 8.169620e+00 -8.852982e-01 -1.609059e-02 4.647454e-01 1.109831e+02 +4.746126e-01 1.267987e-03 8.801939e-01 4.573544e+02 -1.560556e-02 9.998539e-01 6.974365e-03 8.152796e+00 -8.800565e-01 -1.704604e-02 4.745631e-01 1.113083e+02 +4.823524e-01 -7.561748e-04 8.759769e-01 4.579719e+02 -1.652209e-02 9.998139e-01 9.960882e-03 8.132884e+00 -8.758215e-01 -1.927762e-02 4.822502e-01 1.116461e+02 +4.885472e-01 -2.429586e-03 8.725341e-01 4.585971e+02 -1.709877e-02 9.997774e-01 1.235780e-02 8.119070e+00 -8.723699e-01 -2.095662e-02 4.883969e-01 1.119988e+02 +4.932344e-01 -2.251780e-03 8.698935e-01 4.592335e+02 -1.796569e-02 9.997570e-01 1.277458e-02 8.106465e+00 -8.697109e-01 -2.192910e-02 4.930741e-01 1.123592e+02 +4.968743e-01 -2.099030e-03 8.678200e-01 4.598774e+02 -1.898362e-02 9.997315e-01 1.328724e-02 8.100209e+00 -8.676149e-01 -2.307645e-02 4.967010e-01 1.127358e+02 +4.998223e-01 -1.844372e-03 8.661260e-01 4.605356e+02 -2.008019e-02 9.997043e-01 1.371665e-02 8.092042e+00 -8.658952e-01 -2.424786e-02 4.996374e-01 1.131184e+02 +5.024161e-01 -7.459135e-04 8.646257e-01 4.612016e+02 -2.088841e-02 9.996973e-01 1.300026e-02 8.086262e+00 -8.643737e-01 -2.459219e-02 5.022484e-01 1.135145e+02 +5.049623e-01 -9.956315e-04 8.631408e-01 4.618832e+02 -1.955894e-02 9.997293e-01 1.259573e-02 8.079735e+00 -8.629198e-01 -2.324248e-02 5.048061e-01 1.139149e+02 +5.075098e-01 -7.153908e-04 8.616457e-01 4.625741e+02 -1.792805e-02 9.997744e-01 1.138970e-02 8.076379e+00 -8.614595e-01 -2.122801e-02 5.073825e-01 1.143268e+02 +5.099040e-01 1.791335e-04 8.602313e-01 4.632776e+02 -1.706826e-02 9.998052e-01 9.909048e-03 8.070543e+00 -8.600620e-01 -1.973531e-02 5.098077e-01 1.147487e+02 +5.123957e-01 1.265019e-03 8.587486e-01 4.639887e+02 -1.676527e-02 9.998230e-01 8.530618e-03 8.064325e+00 -8.585859e-01 -1.876820e-02 5.123262e-01 1.151820e+02 +5.147272e-01 2.188523e-03 8.573512e-01 4.647101e+02 -1.555329e-02 9.998560e-01 6.785421e-03 8.056835e+00 -8.572130e-01 -1.682727e-02 5.146871e-01 1.156225e+02 +5.168553e-01 1.502212e-03 8.560714e-01 4.654401e+02 -1.295731e-02 9.998976e-01 6.068412e-03 8.048223e+00 -8.559747e-01 -1.422887e-02 5.168219e-01 1.160673e+02 +5.185422e-01 6.470337e-04 8.550518e-01 4.661755e+02 -9.988831e-03 9.999360e-01 5.301008e-03 8.039721e+00 -8.549937e-01 -1.128976e-02 5.185155e-01 1.165177e+02 +5.203657e-01 3.368226e-05 8.539435e-01 4.669232e+02 -8.370892e-03 9.999521e-01 5.061509e-03 8.029741e+00 -8.539025e-01 -9.782104e-03 5.203411e-01 1.169794e+02 +5.217843e-01 2.846178e-03 8.530727e-01 4.676730e+02 -9.580685e-03 9.999509e-01 2.523830e-03 8.017194e+00 -8.530237e-01 -9.489916e-03 5.217860e-01 1.174495e+02 +5.229485e-01 5.339563e-03 8.523476e-01 4.684354e+02 -8.588703e-03 9.999626e-01 -9.948030e-04 8.005046e+00 -8.523211e-01 -6.800329e-03 5.229748e-01 1.179247e+02 +5.232249e-01 7.591933e-03 8.521608e-01 4.692057e+02 -8.357035e-03 9.999579e-01 -3.777466e-03 7.993850e+00 -8.521537e-01 -5.145074e-03 5.232664e-01 1.184087e+02 +5.236511e-01 7.491150e-03 8.518998e-01 4.699870e+02 -1.081503e-02 9.999392e-01 -2.145081e-03 7.980812e+00 -8.518642e-01 -8.090050e-03 5.237003e-01 1.189038e+02 +5.236354e-01 5.075090e-03 8.519274e-01 4.707811e+02 -1.068026e-02 9.999428e-01 6.077521e-04 7.967282e+00 -8.518756e-01 -9.417048e-03 5.236596e-01 1.194044e+02 +5.242426e-01 3.232545e-03 8.515628e-01 4.715837e+02 -1.137083e-02 9.999302e-01 3.204403e-03 7.952083e+00 -8.514930e-01 -1.136286e-02 5.242428e-01 1.199093e+02 +5.247027e-01 2.263810e-03 8.512825e-01 4.723974e+02 -8.746378e-03 9.999580e-01 2.731797e-03 7.942587e+00 -8.512406e-01 -8.879020e-03 5.247005e-01 1.204162e+02 +5.255726e-01 2.224897e-03 8.507458e-01 4.732194e+02 -6.056693e-03 9.999810e-01 1.126512e-03 7.932442e+00 -8.507272e-01 -5.744771e-03 5.255761e-01 1.209268e+02 +5.261408e-01 1.307874e-03 8.503965e-01 4.740519e+02 -3.380334e-03 9.999941e-01 5.534633e-04 7.920100e+00 -8.503908e-01 -3.165825e-03 5.261421e-01 1.214472e+02 +5.269130e-01 3.802221e-04 8.499191e-01 4.748921e+02 -2.018297e-03 9.999976e-01 8.038926e-04 7.908537e+00 -8.499169e-01 -2.138972e-03 5.269125e-01 1.219754e+02 +5.276915e-01 -7.951455e-04 8.494357e-01 4.757434e+02 -2.779293e-04 9.999993e-01 1.108741e-03 7.896328e+00 -8.494361e-01 -8.211580e-04 5.276909e-01 1.225108e+02 +5.284395e-01 -1.451757e-03 8.489697e-01 4.766013e+02 4.596040e-04 9.999989e-01 1.423939e-03 7.882709e+00 -8.489709e-01 -3.622775e-04 5.284395e-01 1.230538e+02 +5.290717e-01 -6.977014e-04 8.485768e-01 4.774675e+02 4.598727e-04 9.999997e-01 5.354777e-04 7.870021e+00 -8.485770e-01 1.069294e-04 5.290719e-01 1.236020e+02 +5.299460e-01 7.697474e-04 8.480310e-01 4.783443e+02 -8.501458e-04 9.999995e-01 -3.764221e-04 7.856526e+00 -8.480310e-01 -5.214683e-04 5.299464e-01 1.241604e+02 +5.302954e-01 1.024500e-03 8.478123e-01 4.792297e+02 -1.615796e-03 9.999987e-01 -1.977459e-04 7.842703e+00 -8.478114e-01 -1.265029e-03 5.302964e-01 1.247229e+02 +5.300079e-01 -3.173918e-04 8.479926e-01 4.801181e+02 -1.349258e-03 9.999983e-01 1.217589e-03 7.816016e+00 -8.479917e-01 -1.789494e-03 5.300066e-01 1.252863e+02 +5.291993e-01 1.649191e-03 8.484960e-01 4.809920e+02 -6.063136e-03 9.999799e-01 1.837896e-03 7.799868e+00 -8.484760e-01 -6.117160e-03 5.291986e-01 1.258640e+02 +5.273607e-01 4.745507e-03 8.496282e-01 4.818789e+02 -9.418954e-03 9.999556e-01 2.611577e-04 7.784641e+00 -8.495893e-01 -8.140333e-03 5.273820e-01 1.264407e+02 +5.240193e-01 8.496522e-03 8.516640e-01 4.827725e+02 -1.156763e-02 9.999290e-01 -2.858242e-03 7.768610e+00 -8.516279e-01 -8.353959e-03 5.240804e-01 1.270159e+02 +5.177804e-01 1.245791e-02 8.554228e-01 4.836799e+02 -1.652157e-02 9.998531e-01 -4.560949e-03 7.748165e+00 -8.553540e-01 -1.177136e-02 5.179102e-01 1.275929e+02 +5.091272e-01 1.740698e-02 8.605152e-01 4.845909e+02 -2.292471e-02 9.997150e-01 -6.659298e-03 7.723347e+00 -8.603859e-01 -1.633663e-02 5.093812e-01 1.281647e+02 +4.977689e-01 2.148898e-02 8.670434e-01 4.855159e+02 -2.763095e-02 9.995784e-01 -8.910860e-03 7.702777e+00 -8.668695e-01 -1.952168e-02 4.981529e-01 1.287246e+02 +4.845266e-01 2.320912e-02 8.744686e-01 4.864476e+02 -3.119041e-02 9.994707e-01 -9.244770e-03 7.689090e+00 -8.742203e-01 -2.279569e-02 4.849941e-01 1.292736e+02 +4.700314e-01 2.203629e-02 8.823746e-01 4.873873e+02 -3.304477e-02 9.994268e-01 -7.356951e-03 7.675900e+00 -8.820309e-01 -2.569986e-02 4.704902e-01 1.298063e+02 +4.547892e-01 1.979872e-02 8.903790e-01 4.883500e+02 -3.537580e-02 9.993654e-01 -4.152875e-03 7.659760e+00 -8.898963e-01 -2.960918e-02 4.552010e-01 1.303251e+02 +4.386957e-01 1.965178e-02 8.984208e-01 4.893200e+02 -3.815878e-02 9.992665e-01 -3.224851e-03 7.644658e+00 -8.978252e-01 -3.286791e-02 4.391238e-01 1.308265e+02 +4.220316e-01 2.186832e-02 9.063173e-01 4.902959e+02 -3.821465e-02 9.992496e-01 -6.315812e-03 7.627582e+00 -9.057754e-01 -3.196912e-02 4.225506e-01 1.313053e+02 +4.043249e-01 2.603608e-02 9.142448e-01 4.912861e+02 -4.032782e-02 9.991301e-01 -1.061849e-02 7.608299e+00 -9.137259e-01 -3.257617e-02 4.050232e-01 1.317682e+02 +3.853192e-01 2.784540e-02 9.223631e-01 4.922829e+02 -4.085032e-02 9.990794e-01 -1.309610e-02 7.577623e+00 -9.218787e-01 -3.263264e-02 3.861020e-01 1.322132e+02 +3.649839e-01 2.599963e-02 9.306507e-01 4.933018e+02 -4.252735e-02 9.990321e-01 -1.123158e-02 7.529603e+00 -9.300421e-01 -3.547876e-02 3.657363e-01 1.326530e+02 +3.431572e-01 2.373053e-02 9.389782e-01 4.943350e+02 -4.172935e-02 9.990789e-01 -9.999122e-03 7.486674e+00 -9.383506e-01 -3.575167e-02 3.438314e-01 1.330594e+02 +3.197498e-01 2.627238e-02 9.471377e-01 4.953580e+02 -4.185578e-02 9.990313e-01 -1.358151e-02 7.441737e+00 -9.465771e-01 -3.530050e-02 3.205398e-01 1.334382e+02 +2.946617e-01 3.386657e-02 9.550013e-01 4.964058e+02 -4.535801e-02 9.987410e-01 -2.142267e-02 7.395897e+00 -9.545246e-01 -3.700452e-02 2.958269e-01 1.337937e+02 +2.686310e-01 3.849994e-02 9.624734e-01 4.974462e+02 -4.491010e-02 9.986149e-01 -2.741102e-02 7.343661e+00 -9.621957e-01 -3.586133e-02 2.699880e-01 1.341159e+02 +2.397432e-01 4.397270e-02 9.698400e-01 4.985138e+02 -5.269696e-02 9.980904e-01 -3.222697e-02 7.291952e+00 -9.694051e-01 -4.338141e-02 2.416026e-01 1.344098e+02 +2.094664e-01 4.683227e-02 9.766937e-01 4.995934e+02 -4.850279e-02 9.981204e-01 -3.745755e-02 7.239981e+00 -9.766122e-01 -3.952627e-02 2.113442e-01 1.346606e+02 +1.790660e-01 4.908971e-02 9.826116e-01 5.006561e+02 -5.368646e-02 9.977538e-01 -4.006267e-02 7.179209e+00 -9.823712e-01 -4.557907e-02 1.812993e-01 1.348781e+02 +1.499665e-01 5.172741e-02 9.873370e-01 5.017511e+02 -5.086174e-02 9.977117e-01 -4.454559e-02 7.107864e+00 -9.873820e-01 -4.353733e-02 1.522542e-01 1.350642e+02 +1.219991e-01 5.750307e-02 9.908631e-01 5.028308e+02 -4.753378e-02 9.975133e-01 -5.203646e-02 7.030874e+00 -9.913914e-01 -4.075106e-02 1.244290e-01 1.352112e+02 +9.579815e-02 6.062645e-02 9.935528e-01 5.039342e+02 -4.318791e-02 9.974567e-01 -5.670052e-02 6.948783e+00 -9.944635e-01 -3.747766e-02 9.817283e-02 1.353334e+02 +7.162029e-02 6.119781e-02 9.955528e-01 5.050423e+02 -3.985105e-02 9.974946e-01 -5.845030e-02 6.859950e+00 -9.966356e-01 -3.548759e-02 7.387965e-02 1.354277e+02 +4.887828e-02 6.145538e-02 9.969123e-01 5.061472e+02 -3.776943e-02 9.975051e-01 -5.964012e-02 6.768053e+00 -9.980904e-01 -3.473770e-02 5.107747e-02 1.354921e+02 +2.646709e-02 6.297633e-02 9.976640e-01 5.072723e+02 -3.819943e-02 9.973484e-01 -6.194303e-02 6.675050e+00 -9.989196e-01 -3.647074e-02 2.880257e-02 1.355359e+02 +4.133192e-03 6.588100e-02 9.978189e-01 5.083950e+02 -3.759705e-02 9.971322e-01 -6.567994e-02 6.580157e+00 -9.992845e-01 -3.724358e-02 6.598269e-03 1.355569e+02 +-1.702794e-02 6.687504e-02 9.976160e-01 5.095108e+02 -3.571142e-02 9.970834e-01 -6.744890e-02 6.485308e+00 -9.992171e-01 -3.677480e-02 -1.459008e-02 1.355511e+02 +-3.510000e-02 6.316810e-02 9.973855e-01 5.106424e+02 -3.161508e-02 9.974307e-01 -6.428358e-02 6.389289e+00 -9.988836e-01 -3.378877e-02 -3.301276e-02 1.355229e+02 +-4.841493e-02 6.172142e-02 9.969185e-01 5.117704e+02 -2.602277e-02 9.976722e-01 -6.303188e-02 6.294291e+00 -9.984883e-01 -2.899426e-02 -4.669607e-02 1.354757e+02 +-5.724012e-02 6.427158e-02 9.962895e-01 5.129071e+02 -1.846947e-02 9.976867e-01 -6.542287e-02 6.208165e+00 -9.981896e-01 -2.214575e-02 -5.592065e-02 1.354162e+02 +-6.323805e-02 6.810006e-02 9.956723e-01 5.140440e+02 -1.490815e-02 9.974934e-01 -6.917149e-02 6.119894e+00 -9.978871e-01 -1.921790e-02 -6.206429e-02 1.353570e+02 +-6.769452e-02 6.853017e-02 9.953497e-01 5.151850e+02 -1.571656e-02 9.974411e-01 -6.974308e-02 6.025495e+00 -9.975823e-01 -2.036469e-02 -6.644424e-02 1.352992e+02 +-7.127552e-02 6.836246e-02 9.951112e-01 5.163261e+02 -1.694131e-02 9.974217e-01 -6.973463e-02 5.928454e+00 -9.973128e-01 -2.182886e-02 -6.993360e-02 1.352386e+02 +-7.456552e-02 7.040811e-02 9.947274e-01 5.174718e+02 -1.720223e-02 9.972651e-01 -7.187724e-02 5.832641e+00 -9.970678e-01 -2.247109e-02 -7.315042e-02 1.351718e+02 +-7.798605e-02 7.384837e-02 9.942156e-01 5.186230e+02 -1.589207e-02 9.970339e-01 -7.530430e-02 5.734027e+00 -9.968278e-01 -2.167282e-02 -7.658114e-02 1.350979e+02 +-8.120607e-02 7.675645e-02 9.937374e-01 5.197856e+02 -1.350542e-02 9.968540e-01 -7.810083e-02 5.634750e+00 -9.966059e-01 -1.976310e-02 -7.991397e-02 1.350173e+02 +-8.417801e-02 7.634601e-02 9.935217e-01 5.209588e+02 -1.236878e-02 9.969036e-01 -7.765388e-02 5.532390e+00 -9.963740e-01 -1.882540e-02 -8.297306e-02 1.349329e+02 +-8.702695e-02 7.207125e-02 9.935955e-01 5.221448e+02 -1.298981e-02 9.972127e-01 -7.347139e-02 5.430448e+00 -9.961213e-01 -1.930060e-02 -8.584819e-02 1.348470e+02 +-8.914649e-02 6.917486e-02 9.936135e-01 5.233374e+02 -1.333057e-02 9.974131e-01 -7.063542e-02 5.330952e+00 -9.959293e-01 -1.954233e-02 -8.799374e-02 1.347574e+02 +-9.069117e-02 6.943865e-02 9.934553e-01 5.245354e+02 -1.571220e-02 9.973422e-01 -7.114470e-02 5.231821e+00 -9.957551e-01 -2.206156e-02 -8.935910e-02 1.346696e+02 +-9.129014e-02 7.379891e-02 9.930860e-01 5.257344e+02 -1.655354e-02 9.969999e-01 -7.561148e-02 5.131118e+00 -9.956868e-01 -2.334166e-02 -8.979463e-02 1.345788e+02 +-9.120783e-02 7.685621e-02 9.928616e-01 5.269472e+02 -1.618822e-02 9.967711e-01 -7.864597e-02 5.024148e+00 -9.957003e-01 -2.324579e-02 -8.966917e-02 1.344845e+02 +-9.071334e-02 7.693208e-02 9.929011e-01 5.281671e+02 -1.430178e-02 9.968082e-01 -7.854148e-02 4.913715e+00 -9.957744e-01 -2.132501e-02 -8.932354e-02 1.343884e+02 +-9.070650e-02 7.635360e-02 9.929463e-01 5.293991e+02 -1.534125e-02 9.968311e-01 -7.805378e-02 4.801178e+00 -9.957595e-01 -2.231302e-02 -8.924770e-02 1.342938e+02 +-9.105983e-02 7.700082e-02 9.928640e-01 5.306378e+02 -1.762053e-02 9.967255e-01 -7.891637e-02 4.687869e+00 -9.956896e-01 -2.468090e-02 -8.940486e-02 1.342008e+02 +-9.177071e-02 7.732119e-02 9.927737e-01 5.318804e+02 -2.019240e-02 9.966312e-01 -7.948822e-02 4.575691e+00 -9.955754e-01 -2.734117e-02 -8.990027e-02 1.341087e+02 +-9.389756e-02 7.610859e-02 9.926685e-01 5.331337e+02 -2.057299e-02 9.967124e-01 -7.836468e-02 4.462482e+00 -9.953693e-01 -2.778040e-02 -9.202309e-02 1.340104e+02 +-9.684277e-02 7.438248e-02 9.925163e-01 5.343975e+02 -2.225565e-02 9.967923e-01 -7.687451e-02 4.347459e+00 -9.950509e-01 -2.953383e-02 -9.487670e-02 1.339097e+02 +-9.873109e-02 7.651742e-02 9.921679e-01 5.356613e+02 -1.985196e-02 9.966894e-01 -7.884162e-02 4.234970e+00 -9.949161e-01 -2.748060e-02 -9.688522e-02 1.337995e+02 +-1.010393e-01 7.684904e-02 9.919099e-01 5.369366e+02 -1.915636e-02 9.966770e-01 -7.916973e-02 4.119557e+00 -9.946980e-01 -2.700063e-02 -9.923137e-02 1.336863e+02 +-1.040957e-01 7.614744e-02 9.916479e-01 5.382185e+02 -2.037850e-02 9.966921e-01 -7.867398e-02 4.003077e+00 -9.943585e-01 -2.839792e-02 -1.021996e-01 1.335721e+02 +-1.075958e-01 7.533443e-02 9.913364e-01 5.395087e+02 -1.955447e-02 9.967717e-01 -7.786987e-02 3.885044e+00 -9.940024e-01 -2.776353e-02 -1.057753e-01 1.334504e+02 +-1.112585e-01 7.458574e-02 9.909886e-01 5.408060e+02 -2.169425e-02 9.967597e-01 -7.745573e-02 3.768101e+00 -9.935547e-01 -3.011636e-02 -1.092799e-01 1.333260e+02 +-1.147311e-01 7.265769e-02 9.907359e-01 5.421306e+02 -2.159340e-02 9.969036e-01 -7.561063e-02 3.670993e+00 -9.931619e-01 -3.006825e-02 -1.128070e-01 1.331855e+02 +-1.178711e-01 7.232361e-02 9.903917e-01 5.434628e+02 -2.291402e-02 9.968806e-01 -7.552458e-02 3.573109e+00 -9.927645e-01 -3.159601e-02 -1.158461e-01 1.330424e+02 +-1.207133e-01 7.328996e-02 9.899782e-01 5.448020e+02 -2.316212e-02 9.967914e-01 -7.661865e-02 3.476816e+00 -9.924172e-01 -3.217888e-02 -1.186284e-01 1.328923e+02 +-1.233970e-01 7.369294e-02 9.896174e-01 5.461426e+02 -2.283390e-02 9.967640e-01 -7.707233e-02 3.370720e+00 -9.920947e-01 -3.210732e-02 -1.213150e-01 1.327403e+02 +-1.258123e-01 7.325253e-02 9.893459e-01 5.474929e+02 -2.211192e-02 9.968153e-01 -7.661750e-02 3.267103e+00 -9.918076e-01 -3.151575e-02 -1.237919e-01 1.325792e+02 +-1.282686e-01 7.474406e-02 9.889188e-01 5.488484e+02 -2.143574e-02 9.967140e-01 -7.811359e-02 3.156546e+00 -9.915078e-01 -3.121772e-02 -1.262449e-01 1.324159e+02 +-1.309596e-01 7.522254e-02 9.885298e-01 5.502099e+02 -2.106840e-02 9.966809e-01 -7.863394e-02 3.041963e+00 -9.911639e-01 -3.112460e-02 -1.289401e-01 1.322485e+02 +-1.340795e-01 7.504056e-02 9.881253e-01 5.515752e+02 -2.148835e-02 9.966742e-01 -7.860557e-02 2.913270e+00 -9.907376e-01 -3.177257e-02 -1.320211e-01 1.320777e+02 +-1.376866e-01 7.457743e-02 9.876642e-01 5.529480e+02 -2.225858e-02 9.966765e-01 -7.836095e-02 2.783757e+00 -9.902257e-01 -3.277325e-02 -1.355690e-01 1.319008e+02 +-1.416777e-01 7.411901e-02 9.871341e-01 5.543261e+02 -2.144556e-02 9.967291e-01 -7.791743e-02 2.656796e+00 -9.896805e-01 -3.220881e-02 -1.396248e-01 1.317159e+02 +-1.455157e-01 7.409029e-02 9.865778e-01 5.557118e+02 -2.152568e-02 9.967188e-01 -7.802682e-02 2.528567e+00 -9.891218e-01 -3.259087e-02 -1.434434e-01 1.315261e+02 +-1.491694e-01 7.447722e-02 9.860028e-01 5.571041e+02 -2.049759e-02 9.967122e-01 -7.838719e-02 2.399866e+00 -9.885992e-01 -3.190365e-02 -1.471524e-01 1.313279e+02 +-1.517677e-01 7.544703e-02 9.855325e-01 5.584998e+02 -1.999672e-02 9.966440e-01 -7.937710e-02 2.269903e+00 -9.882139e-01 -3.175429e-02 -1.497497e-01 1.311262e+02 +-1.539634e-01 7.603548e-02 9.851466e-01 5.599076e+02 -1.901021e-02 9.966222e-01 -7.989221e-02 2.138770e+00 -9.878937e-01 -3.102831e-02 -1.519979e-01 1.309168e+02 +-1.559006e-01 7.605786e-02 9.848402e-01 5.613175e+02 -1.878093e-02 9.966226e-01 -7.994085e-02 2.008314e+00 -9.875942e-01 -3.095903e-02 -1.539456e-01 1.307066e+02 +-1.573760e-01 7.619843e-02 9.845946e-01 5.627394e+02 -1.829898e-02 9.966225e-01 -8.005418e-02 1.875610e+00 -9.873692e-01 -3.061568e-02 -1.554501e-01 1.304905e+02 +-1.585686e-01 7.614049e-02 9.844077e-01 5.641657e+02 -1.767351e-02 9.966435e-01 -7.993375e-02 1.742310e+00 -9.871898e-01 -3.007292e-02 -1.566907e-01 1.302739e+02 +-1.598198e-01 7.681821e-02 9.841527e-01 5.655998e+02 -1.649526e-02 9.966205e-01 -8.047012e-02 1.607277e+00 -9.870084e-01 -2.909457e-02 -1.580125e-01 1.300512e+02 +-1.608934e-01 7.744758e-02 9.839284e-01 5.670384e+02 -1.514662e-02 9.966053e-01 -8.092223e-02 1.473204e+00 -9.868556e-01 -2.792304e-02 -1.591741e-01 1.298258e+02 +-1.618757e-01 7.555617e-02 9.839144e-01 5.684892e+02 -1.405334e-02 9.967869e-01 -7.885677e-02 1.338244e+00 -9.867111e-01 -2.659227e-02 -1.602937e-01 1.295962e+02 +-1.629016e-01 7.649828e-02 9.836722e-01 5.699415e+02 -1.447468e-02 9.966971e-01 -7.990830e-02 1.204765e+00 -9.865362e-01 -2.725553e-02 -1.612563e-01 1.293673e+02 +-1.640658e-01 7.591233e-02 9.835241e-01 5.714033e+02 -1.487541e-02 9.967308e-01 -7.941312e-02 1.070450e+00 -9.863373e-01 -2.765929e-02 -1.624002e-01 1.291365e+02 +-1.652607e-01 7.441181e-02 9.834387e-01 5.728707e+02 -1.609656e-02 9.968133e-01 -7.812874e-02 9.347147e-01 -9.861186e-01 -2.874159e-02 -1.635363e-01 1.289047e+02 +-1.664451e-01 7.183422e-02 9.834306e-01 5.743517e+02 -1.579909e-02 9.970205e-01 -7.550089e-02 7.948708e-01 -9.859242e-01 -2.810406e-02 -1.648143e-01 1.286665e+02 +-1.671965e-01 7.202273e-02 9.832894e-01 5.758281e+02 -1.440338e-02 9.970433e-01 -7.547931e-02 6.596113e-01 -9.858184e-01 -2.678257e-02 -1.656648e-01 1.284282e+02 +-1.673512e-01 7.461510e-02 9.830697e-01 5.773012e+02 -1.364160e-02 9.968612e-01 -7.798415e-02 5.265952e-01 -9.858030e-01 -2.646138e-02 -1.658081e-01 1.281909e+02 +-1.673285e-01 7.441150e-02 9.830890e-01 5.787797e+02 -1.321339e-02 9.968888e-01 -7.770506e-02 3.911611e-01 -9.858127e-01 -2.599221e-02 -1.658247e-01 1.279538e+02 +-1.676981e-01 7.488783e-02 9.829899e-01 5.802597e+02 -1.415233e-02 9.968249e-01 -7.835624e-02 2.527980e-01 -9.857369e-01 -2.705178e-02 -1.661058e-01 1.277179e+02 +-1.675394e-01 7.434870e-02 9.830579e-01 5.817458e+02 -1.355623e-02 9.968842e-01 -7.770475e-02 1.016155e-01 -9.857722e-01 -2.634517e-02 -1.660095e-01 1.274871e+02 +-1.672214e-01 7.535076e-02 9.830357e-01 5.832371e+02 -1.423537e-02 9.967867e-01 -7.882635e-02 -5.588021e-02 -9.858166e-01 -2.717532e-02 -1.656114e-01 1.272589e+02 +-1.665788e-01 7.699662e-02 9.830173e-01 5.847273e+02 -1.386405e-02 9.966650e-01 -8.041498e-02 -2.157308e-01 -9.859307e-01 -2.702402e-02 -1.649558e-01 1.270310e+02 +-1.655810e-01 7.877950e-02 9.830446e-01 5.862192e+02 -1.115435e-02 9.965909e-01 -8.174390e-02 -3.728685e-01 -9.861331e-01 -2.450046e-02 -1.641378e-01 1.267986e+02 +-1.638536e-01 7.829936e-02 9.833724e-01 5.877130e+02 -9.504147e-03 9.966735e-01 -8.094208e-02 -5.291253e-01 -9.864389e-01 -2.260876e-02 -1.625644e-01 1.265673e+02 +-1.614580e-01 7.636019e-02 9.839209e-01 5.892056e+02 -6.783378e-03 9.968926e-01 -7.848004e-02 -6.839355e-01 -9.868563e-01 -1.934554e-02 -1.604383e-01 1.263366e+02 +-1.594896e-01 7.554394e-02 9.843049e-01 5.907063e+02 -6.515652e-03 9.969655e-01 -7.757139e-02 -8.349537e-01 -9.871781e-01 -1.878522e-02 -1.585134e-01 1.261075e+02 +-1.582649e-01 7.622288e-02 9.844502e-01 5.922020e+02 -7.131814e-03 9.969017e-01 -7.833352e-02 -9.855955e-01 -9.873710e-01 -1.941836e-02 -1.572309e-01 1.258847e+02 +-1.575652e-01 7.504898e-02 9.846526e-01 5.936965e+02 -5.749370e-03 9.970213e-01 -7.691174e-02 -1.133189e+00 -9.874919e-01 -1.777975e-02 -1.566644e-01 1.256604e+02 +-1.566245e-01 7.542410e-02 9.847740e-01 5.951894e+02 -6.373586e-03 9.969818e-01 -7.737281e-02 -1.279919e+00 -9.876377e-01 -1.839502e-02 -1.556711e-01 1.254396e+02 +-1.557004e-01 7.626897e-02 9.848555e-01 5.966838e+02 -5.210902e-03 9.969375e-01 -7.802846e-02 -1.425223e+00 -9.877906e-01 -1.728104e-02 -1.548261e-01 1.252152e+02 +-1.548985e-01 7.562389e-02 9.850317e-01 5.981765e+02 -5.920319e-03 9.969769e-01 -7.747196e-02 -1.569485e+00 -9.879127e-01 -1.783199e-02 -1.539826e-01 1.249935e+02 +-1.542199e-01 7.608886e-02 9.851024e-01 5.996656e+02 -7.430799e-03 9.969128e-01 -7.816442e-02 -1.713634e+00 -9.880086e-01 -1.937461e-02 -1.531784e-01 1.247758e+02 +-1.537938e-01 7.461386e-02 9.852818e-01 6.011497e+02 -1.007351e-02 9.969746e-01 -7.707174e-02 -1.855775e+00 -9.880516e-01 -2.177841e-02 -1.525769e-01 1.245584e+02 +-1.534651e-01 7.355380e-02 9.854127e-01 6.026348e+02 -8.082658e-03 9.970990e-01 -7.568488e-02 -1.996259e+00 -9.881210e-01 -1.957974e-02 -1.524254e-01 1.243339e+02 +-1.525501e-01 7.305531e-02 9.855919e-01 6.041193e+02 -6.256903e-03 9.971727e-01 -7.488218e-02 -2.134326e+00 -9.882760e-01 -1.759003e-02 -1.516617e-01 1.241054e+02 +-1.513552e-01 7.261015e-02 9.858090e-01 6.056015e+02 1.241605e-03 9.973116e-01 -7.326677e-02 -2.266799e+00 -9.884787e-01 -9.865324e-03 -1.510385e-01 1.238702e+02 +-1.503483e-01 7.491239e-02 9.857908e-01 6.070799e+02 3.427176e-03 9.971585e-01 -7.525358e-02 -2.402032e+00 -9.886272e-01 -7.935769e-03 -1.501778e-01 1.236385e+02 +-1.496771e-01 7.861561e-02 9.856045e-01 6.085550e+02 3.847843e-03 9.968727e-01 -7.893008e-02 -2.539860e+00 -9.887275e-01 -8.021577e-03 -1.495116e-01 1.234126e+02 +-1.495769e-01 7.831022e-02 9.856441e-01 6.100387e+02 8.364754e-04 9.968683e-01 -7.907508e-02 -2.682651e+00 -9.887498e-01 -1.100334e-02 -1.491740e-01 1.231942e+02 +-1.488250e-01 7.578455e-02 9.859553e-01 6.115210e+02 -2.081215e-03 9.970327e-01 -7.695018e-02 -2.824801e+00 -9.888614e-01 -1.350410e-02 -1.482257e-01 1.229770e+02 +-1.477210e-01 7.503530e-02 9.861786e-01 6.130022e+02 -3.800152e-03 9.970674e-01 -7.643305e-02 -2.963844e+00 -9.890218e-01 -1.503839e-02 -1.470026e-01 1.227629e+02 +-1.468298e-01 7.526683e-02 9.862940e-01 6.144836e+02 -5.300252e-03 9.970266e-01 -7.687494e-02 -3.099679e+00 -9.891476e-01 -1.651514e-02 -1.459943e-01 1.225471e+02 +-1.459918e-01 7.566124e-02 9.863882e-01 6.159658e+02 -7.682821e-03 9.969543e-01 -7.760884e-02 -3.235243e+00 -9.892560e-01 -1.890849e-02 -1.449658e-01 1.223354e+02 +-1.453343e-01 7.492462e-02 9.865415e-01 6.174445e+02 -8.493707e-03 9.969972e-01 -7.696998e-02 -3.370905e+00 -9.893462e-01 -1.956577e-02 -1.442615e-01 1.221166e+02 +-1.452871e-01 7.387913e-02 9.866273e-01 6.189264e+02 -1.026597e-02 9.970419e-01 -7.617073e-02 -3.509590e+00 -9.893363e-01 -2.119531e-02 -1.440989e-01 1.219034e+02 +-1.455795e-01 7.477061e-02 9.865171e-01 6.204019e+02 -7.950932e-03 9.970194e-01 -7.673994e-02 -3.644953e+00 -9.893146e-01 -1.901549e-02 -1.445511e-01 1.216860e+02 +-1.453987e-01 7.549331e-02 9.864887e-01 6.218775e+02 -6.998586e-03 9.969811e-01 -7.732781e-02 -3.782481e+00 -9.893484e-01 -1.814739e-02 -1.444314e-01 1.214710e+02 +-1.449889e-01 7.513923e-02 9.865760e-01 6.233503e+02 -3.976254e-03 9.970599e-01 -7.652208e-02 -3.919619e+00 -9.894253e-01 -1.501773e-02 -1.442639e-01 1.212544e+02 +-1.438153e-01 7.347773e-02 9.868729e-01 6.248239e+02 -2.560349e-03 9.972087e-01 -7.462042e-02 -4.058322e+00 -9.896013e-01 -1.325829e-02 -1.432257e-01 1.210352e+02 +-1.420977e-01 7.491911e-02 9.870133e-01 6.262881e+02 -2.089217e-03 9.971067e-01 -7.598604e-02 -4.197430e+00 -9.898505e-01 -1.285953e-02 -1.415301e-01 1.208229e+02 +-1.406262e-01 7.863780e-02 9.869348e-01 6.277419e+02 -3.931929e-03 9.967884e-01 -7.998320e-02 -4.339425e+00 -9.900550e-01 -1.512829e-02 -1.398653e-01 1.206154e+02 +-1.399748e-01 7.764545e-02 9.871060e-01 6.291950e+02 -6.824645e-03 9.968212e-01 -7.937742e-02 -4.485251e+00 -9.901316e-01 -1.784748e-02 -1.389999e-01 1.204151e+02 +-1.388576e-01 7.504668e-02 9.874647e-01 6.306377e+02 -1.140527e-02 9.969372e-01 -7.737041e-02 -4.631806e+00 -9.902467e-01 -2.200578e-02 -1.375764e-01 1.202160e+02 +-1.378093e-01 7.310941e-02 9.877568e-01 6.320716e+02 -1.114035e-02 9.970945e-01 -7.535484e-02 -4.772113e+00 -9.903962e-01 -2.138855e-02 -1.365944e-01 1.200166e+02 +-1.375322e-01 7.023104e-02 9.880043e-01 6.334936e+02 -1.021221e-02 9.973295e-01 -7.231549e-02 -4.906253e+00 -9.904447e-01 -2.003542e-02 -1.364478e-01 1.198122e+02 +-1.371780e-01 7.009597e-02 9.880631e-01 6.349104e+02 -7.618388e-03 9.973888e-01 -7.181528e-02 -5.039168e+00 -9.905172e-01 -1.737892e-02 -1.362858e-01 1.196107e+02 +-1.370424e-01 6.998474e-02 9.880898e-01 6.363188e+02 -7.772762e-03 9.973944e-01 -7.172182e-02 -5.173869e+00 -9.905347e-01 -1.750912e-02 -1.361414e-01 1.194126e+02 +-1.377030e-01 7.087567e-02 9.879345e-01 6.377168e+02 -7.383334e-03 9.973353e-01 -7.257924e-02 -5.306799e+00 -9.904461e-01 -1.728863e-02 -1.368128e-01 1.192158e+02 +-1.386907e-01 7.019029e-02 9.878452e-01 6.391077e+02 -8.004110e-03 9.973731e-01 -7.199106e-02 -5.440214e+00 -9.903034e-01 -1.789131e-02 -1.377645e-01 1.190205e+02 +-1.395658e-01 6.952549e-02 9.877690e-01 6.404840e+02 -9.094947e-03 9.973999e-01 -7.148846e-02 -5.573172e+00 -9.901711e-01 -1.896105e-02 -1.385706e-01 1.188251e+02 +-1.401837e-01 6.907541e-02 9.877131e-01 6.418446e+02 -1.037412e-02 9.974063e-01 -7.122570e-02 -5.704481e+00 -9.900712e-01 -2.023134e-02 -1.391035e-01 1.186326e+02 +-1.408634e-01 6.815384e-02 9.876804e-01 6.431805e+02 -1.031856e-02 9.974724e-01 -7.030119e-02 -5.829779e+00 -9.899753e-01 -2.009430e-02 -1.398041e-01 1.184422e+02 +-1.418027e-01 6.480142e-02 9.877716e-01 6.444976e+02 -1.120124e-02 9.976860e-01 -6.705990e-02 -5.952741e+00 -9.898316e-01 -2.057354e-02 -1.407488e-01 1.182561e+02 +-1.427304e-01 6.176904e-02 9.878323e-01 6.457878e+02 -1.188290e-02 9.978718e-01 -6.411377e-02 -6.069315e+00 -9.896903e-01 -2.088929e-02 -1.416927e-01 1.180703e+02 +-1.431740e-01 6.260695e-02 9.877153e-01 6.470504e+02 -1.174755e-02 9.978193e-01 -6.495027e-02 -6.180966e+00 -9.896278e-01 -2.090243e-02 -1.421263e-01 1.178844e+02 +-1.435374e-01 6.787195e-02 9.873147e-01 6.482784e+02 -9.742383e-03 9.975002e-01 -6.998852e-02 -6.293647e+00 -9.895970e-01 -1.966477e-02 -1.425174e-01 1.176984e+02 +-1.437283e-01 6.948604e-02 9.871747e-01 6.494851e+02 -9.238831e-03 9.973942e-01 -7.155053e-02 -6.410502e+00 -9.895741e-01 -1.940418e-02 -1.427118e-01 1.175205e+02 +-1.432439e-01 6.594051e-02 9.874882e-01 6.506695e+02 -8.481540e-03 9.976595e-01 -6.785004e-02 -6.526455e+00 -9.896511e-01 -1.809453e-02 -1.423494e-01 1.173448e+02 +-1.418590e-01 6.419165e-02 9.878033e-01 6.518174e+02 -8.083942e-03 9.977868e-01 -6.600137e-02 -6.633894e+00 -9.898539e-01 -1.734823e-02 -1.410261e-01 1.171760e+02 +-1.402468e-01 6.351985e-02 9.880769e-01 6.529332e+02 -8.712592e-03 9.978222e-01 -6.538301e-02 -6.736937e+00 -9.900783e-01 -1.777846e-02 -1.393879e-01 1.170159e+02 +-1.383788e-01 6.209912e-02 9.884306e-01 6.540157e+02 -1.012956e-02 9.978913e-01 -6.411164e-02 -6.834140e+00 -9.903276e-01 -1.888405e-02 -1.374579e-01 1.168630e+02 +-1.359375e-01 5.964993e-02 9.889200e-01 6.550645e+02 -9.222854e-03 9.980663e-01 -6.146942e-02 -6.928940e+00 -9.906745e-01 -1.747666e-02 -1.351245e-01 1.167124e+02 +-1.337453e-01 5.607048e-02 9.894283e-01 6.560738e+02 -8.634110e-03 9.982943e-01 -5.774004e-02 -7.019342e+00 -9.909782e-01 -1.626529e-02 -1.330330e-01 1.165666e+02 +-1.328421e-01 5.407817e-02 9.896608e-01 6.570509e+02 -1.180477e-02 9.983532e-01 -5.613772e-02 -7.109623e+00 -9.910669e-01 -1.914017e-02 -1.319850e-01 1.164399e+02 +-1.323162e-01 5.483033e-02 9.896899e-01 6.579807e+02 -1.053115e-02 9.983347e-01 -5.671724e-02 -7.194317e+00 -9.911516e-01 -1.792719e-02 -1.315185e-01 1.163142e+02 +-1.315064e-01 5.743928e-02 9.896498e-01 6.588703e+02 -9.438351e-03 9.982021e-01 -5.918985e-02 -7.275101e+00 -9.912704e-01 -1.712450e-02 -1.307278e-01 1.161936e+02 +-1.313824e-01 5.751257e-02 9.896620e-01 6.597211e+02 -1.026214e-02 9.981833e-01 -5.937013e-02 -7.356354e+00 -9.912787e-01 -1.795624e-02 -1.305535e-01 1.160767e+02 +-1.313258e-01 5.761171e-02 9.896638e-01 6.605264e+02 -1.199953e-02 9.981444e-01 -5.969771e-02 -7.432865e+00 -9.912667e-01 -1.971535e-02 -1.303908e-01 1.159646e+02 +-1.340778e-01 5.693583e-02 9.893338e-01 6.612929e+02 -1.574419e-02 9.980997e-01 -5.957403e-02 -7.506423e+00 -9.908458e-01 -2.356381e-02 -1.329266e-01 1.158579e+02 +-1.430611e-01 5.704748e-02 9.880684e-01 6.620203e+02 -1.915244e-02 9.979909e-01 -6.039344e-02 -7.573766e+00 -9.895286e-01 -2.756387e-02 -1.416810e-01 1.157505e+02 +-1.590296e-01 5.674842e-02 9.856415e-01 6.627011e+02 -2.280356e-02 9.978692e-01 -6.113171e-02 -7.640330e+00 -9.870105e-01 -3.219788e-02 -1.573967e-01 1.156308e+02 +-1.822605e-01 5.612534e-02 9.816471e-01 6.633550e+02 -2.692243e-02 9.977103e-01 -6.204240e-02 -7.700834e+00 -9.828817e-01 -3.773620e-02 -1.803322e-01 1.155058e+02 +-2.104577e-01 5.779421e-02 9.758931e-01 6.639799e+02 -2.712415e-02 9.975214e-01 -6.492459e-02 -7.758066e+00 -9.772266e-01 -4.013414e-02 -2.083684e-01 1.153586e+02 +-2.425576e-01 6.022132e-02 9.682661e-01 6.645440e+02 -2.541234e-02 9.973346e-01 -6.839523e-02 -7.812578e+00 -9.698042e-01 -4.119568e-02 -2.403807e-01 1.151851e+02 +-2.797884e-01 6.314853e-02 9.579826e-01 6.651394e+02 -1.977097e-02 9.972438e-01 -7.151089e-02 -7.870549e+00 -9.598581e-01 -3.894816e-02 -2.777688e-01 1.149993e+02 +-3.226473e-01 6.275468e-02 9.444366e-01 6.656528e+02 -1.798533e-02 9.972131e-01 -7.240584e-02 -7.927666e+00 -9.463484e-01 -4.034755e-02 -3.206195e-01 1.147870e+02 +-3.695533e-01 6.095360e-02 9.272082e-01 6.662207e+02 -1.622366e-02 9.972708e-01 -7.202566e-02 -7.985695e+00 -9.290679e-01 -4.166003e-02 -3.675559e-01 1.145578e+02 +-4.181999e-01 5.909287e-02 9.064308e-01 6.667809e+02 -1.416937e-02 9.973359e-01 -7.155658e-02 -8.042231e+00 -9.082445e-01 -4.276851e-02 -4.162485e-01 1.143064e+02 +-4.682378e-01 5.616713e-02 8.818155e-01 6.672164e+02 -1.227118e-02 9.974680e-01 -7.004953e-02 -8.095726e+00 -8.835173e-01 -4.362075e-02 -4.663630e-01 1.140165e+02 +-5.202411e-01 5.608996e-02 8.521755e-01 6.677314e+02 -9.263195e-03 9.974116e-01 -7.130443e-02 -8.155080e+00 -8.539692e-01 -4.498936e-02 -5.183750e-01 1.137224e+02 +-5.728201e-01 5.788257e-02 8.176348e-01 6.680814e+02 -5.453275e-03 9.972124e-01 -7.441583e-02 -8.211820e+00 -8.196630e-01 -4.708567e-02 -5.709077e-01 1.133811e+02 +-6.251709e-01 5.817084e-02 7.783171e-01 6.685395e+02 -4.015138e-03 9.969657e-01 -7.773759e-02 -8.265600e+00 -7.804776e-01 -5.172432e-02 -6.230404e-01 1.130421e+02 +-6.753574e-01 6.032681e-02 7.350191e-01 6.688155e+02 -4.353316e-04 9.966159e-01 -8.219743e-02 -8.309868e+00 -7.374905e-01 -5.583261e-02 -6.730457e-01 1.126521e+02 +-7.216442e-01 6.612135e-02 6.890992e-01 6.691895e+02 8.960554e-03 9.962368e-01 -8.620851e-02 -8.364714e+00 -6.922062e-01 -5.603715e-02 -7.195210e-01 1.122683e+02 +-7.642421e-01 7.180641e-02 6.409196e-01 6.695344e+02 2.063087e-02 9.959957e-01 -8.698739e-02 -8.419548e+00 -6.445994e-01 -5.325669e-02 -7.626633e-01 1.118590e+02 +-8.046787e-01 7.140012e-02 5.894016e-01 6.697217e+02 2.489268e-02 9.959267e-01 -8.666197e-02 -8.469077e+00 -5.931885e-01 -5.506325e-02 -8.031784e-01 1.114206e+02 +-8.413933e-01 6.847417e-02 5.360678e-01 6.700173e+02 2.668669e-02 9.959947e-01 -8.533609e-02 -8.521558e+00 -5.397641e-01 -5.749533e-02 -8.398506e-01 1.109860e+02 +-8.746252e-01 6.711189e-02 4.801321e-01 6.701506e+02 3.072727e-02 9.960546e-01 -8.325269e-02 -8.567497e+00 -4.838251e-01 -5.806174e-02 -8.732366e-01 1.105132e+02 +-9.035755e-01 7.088889e-02 4.225234e-01 6.703750e+02 3.980745e-02 9.958413e-01 -8.194829e-02 -8.624582e+00 -4.265755e-01 -5.722688e-02 -9.026397e-01 1.100400e+02 +-9.287189e-01 7.545170e-02 3.630265e-01 6.705715e+02 4.827711e-02 9.953487e-01 -8.336832e-02 -8.670623e+00 -3.676282e-01 -5.989986e-02 -9.280418e-01 1.095531e+02 +-9.504422e-01 7.772534e-02 3.010290e-01 6.706002e+02 5.307034e-02 9.945949e-01 -8.924376e-02 -8.721843e+00 -3.063384e-01 -6.884531e-02 -9.494299e-01 1.090393e+02 +-9.685394e-01 7.699005e-02 2.366515e-01 6.707435e+02 5.581335e-02 9.939184e-01 -9.492619e-02 -8.762155e+00 -2.425206e-01 -7.873144e-02 -9.669463e-01 1.085321e+02 +-9.821453e-01 7.677478e-02 1.717447e-01 6.707193e+02 6.059497e-02 9.933841e-01 -9.755068e-02 -8.809700e+00 -1.780979e-01 -8.540207e-02 -9.802998e-01 1.079914e+02 +-9.915391e-01 7.296518e-02 1.073603e-01 6.707989e+02 6.303171e-02 9.936523e-01 -9.317813e-02 -8.866096e+00 -1.134776e-01 -8.562264e-02 -9.898442e-01 1.074536e+02 +-9.966656e-01 7.032458e-02 4.137727e-02 6.708537e+02 6.645163e-02 9.938558e-01 -8.851382e-02 -8.926874e+00 -4.734774e-02 -8.546908e-02 -9.952152e-01 1.069058e+02 +-9.973297e-01 6.828218e-02 -2.590486e-02 6.707208e+02 7.032035e-02 9.936114e-01 -8.826934e-02 -8.988273e+00 1.971214e-02 -8.985525e-02 -9.957598e-01 1.063349e+02 +-9.933700e-01 6.659319e-02 -9.370898e-02 6.706915e+02 7.514041e-02 9.930258e-01 -9.084999e-02 -9.044011e+00 8.700544e-02 -9.728897e-02 -9.914459e-01 1.057796e+02 +-9.849364e-01 6.258508e-02 -1.611939e-01 6.704796e+02 7.829631e-02 9.925798e-01 -9.303189e-02 -9.110009e+00 1.541754e-01 -1.042514e-01 -9.825282e-01 1.052037e+02 +-9.718299e-01 5.879813e-02 -2.282313e-01 6.703759e+02 8.237350e-02 9.920462e-01 -9.517777e-02 -9.163384e+00 2.208197e-01 -1.112968e-01 -9.689436e-01 1.046460e+02 +-9.549874e-01 5.538843e-02 -2.914295e-01 6.702121e+02 8.652170e-02 9.917061e-01 -9.504210e-02 -9.217767e+00 2.837482e-01 -1.159790e-01 -9.518592e-01 1.040834e+02 +-9.347091e-01 5.492258e-02 -3.511444e-01 6.698862e+02 9.285538e-02 9.914104e-01 -9.210437e-02 -9.275436e+00 3.430696e-01 -1.186964e-01 -9.317802e-01 1.035050e+02 +-9.122257e-01 5.220539e-02 -4.063482e-01 6.696374e+02 9.691369e-02 9.911951e-01 -9.022165e-02 -9.333919e+00 3.980603e-01 -1.216832e-01 -9.092531e-01 1.029431e+02 +-8.887327e-01 5.002448e-02 -4.556881e-01 6.693414e+02 1.006381e-01 9.910699e-01 -8.747773e-02 -9.389779e+00 4.472428e-01 -1.236039e-01 -8.858307e-01 1.023805e+02 +-8.648650e-01 4.773039e-02 -4.997302e-01 6.689340e+02 1.049277e-01 9.906694e-01 -8.697333e-02 -9.442521e+00 4.909162e-01 -1.276557e-01 -8.618035e-01 1.018117e+02 +-8.418699e-01 4.598955e-02 -5.377175e-01 6.685705e+02 1.102645e-01 9.900022e-01 -8.796178e-02 -9.490074e+00 5.282962e-01 -1.333435e-01 -8.385241e-01 1.012535e+02 +-8.212144e-01 4.357571e-02 -5.689535e-01 6.681707e+02 1.130985e-01 9.897286e-01 -8.744113e-02 -9.542441e+00 5.592993e-01 -1.361557e-01 -8.177077e-01 1.006959e+02 +-8.027332e-01 4.404680e-02 -5.947095e-01 6.677134e+02 1.159311e-01 9.897685e-01 -8.317610e-02 -9.598010e+00 5.849611e-01 -1.357135e-01 -7.996264e-01 1.001285e+02 +-7.867294e-01 4.463348e-02 -6.156823e-01 6.672570e+02 1.161018e-01 9.902817e-01 -7.656708e-02 -9.654688e+00 6.062815e-01 -1.317194e-01 -7.842658e-01 9.956918e+01 +-7.726241e-01 4.196240e-02 -6.334754e-01 6.667840e+02 1.117527e-01 9.912221e-01 -7.064007e-02 -9.711829e+00 6.249507e-01 -1.253708e-01 -7.705316e-01 9.899997e+01 +-7.594761e-01 3.865510e-02 -6.493858e-01 6.662846e+02 1.073194e-01 9.920005e-01 -6.646373e-02 -9.763801e+00 6.416219e-01 -1.201693e-01 -7.575491e-01 9.843179e+01 +-7.464320e-01 3.717298e-02 -6.644226e-01 6.657788e+02 1.054821e-01 9.924250e-01 -6.297765e-02 -9.817338e+00 6.570485e-01 -1.170932e-01 -7.446989e-01 9.787203e+01 +-7.330503e-01 3.533989e-02 -6.792557e-01 6.652332e+02 1.020260e-01 9.930637e-01 -5.843959e-02 -9.854248e+00 6.724790e-01 -1.121409e-01 -7.315712e-01 9.730181e+01 +-7.186117e-01 2.976077e-02 -6.947745e-01 6.646919e+02 9.310857e-02 9.942059e-01 -5.371608e-02 -9.902523e+00 6.891503e-01 -1.032904e-01 -7.172189e-01 9.673017e+01 +-7.037171e-01 2.544713e-02 -7.100245e-01 6.641406e+02 8.394656e-02 9.953361e-01 -4.752818e-02 -9.951545e+00 7.055036e-01 -9.305049e-02 -7.025712e-01 9.616703e+01 +-6.874673e-01 2.498717e-02 -7.257853e-01 6.635480e+02 8.057410e-02 9.958619e-01 -4.203485e-02 -9.983917e+00 7.217316e-01 -8.737706e-02 -6.866358e-01 9.561348e+01 +-6.700028e-01 2.370287e-02 -7.419801e-01 6.629511e+02 7.251518e-02 9.967999e-01 -3.363749e-02 -1.001919e+01 7.388084e-01 -7.634201e-02 -6.695776e-01 9.506952e+01 +-6.510249e-01 2.137559e-02 -7.587553e-01 6.623373e+02 6.312538e-02 9.976654e-01 -2.605649e-02 -1.005144e+01 7.564270e-01 -6.486013e-02 -6.508544e-01 9.453464e+01 +-6.310920e-01 1.821553e-02 -7.754941e-01 6.616931e+02 5.470138e-02 9.982805e-01 -2.106707e-02 -1.007472e+01 7.737769e-01 -5.571584e-02 -6.310032e-01 9.400972e+01 +-6.099870e-01 1.839494e-02 -7.921979e-01 6.610454e+02 5.376118e-02 9.983877e-01 -1.821304e-02 -1.009293e+01 7.905856e-01 -5.369920e-02 -6.099925e-01 9.351509e+01 +-5.880642e-01 1.941866e-02 -8.085811e-01 6.603612e+02 5.354566e-02 9.984532e-01 -1.496405e-02 -1.010891e+01 8.070399e-01 -5.209582e-02 -5.881944e-01 9.303188e+01 +-5.656126e-01 2.295489e-02 -8.243516e-01 6.596812e+02 5.370299e-02 9.985160e-01 -9.042563e-03 -1.012551e+01 8.229207e-01 -4.938471e-02 -5.660059e-01 9.256889e+01 +-5.443340e-01 2.835202e-02 -8.383893e-01 6.589781e+02 5.494544e-02 9.984875e-01 -1.907851e-03 -1.013214e+01 8.370672e-01 -4.710416e-02 -5.450685e-01 9.210808e+01 +-5.254016e-01 3.320865e-02 -8.502060e-01 6.582498e+02 5.849411e-02 9.982837e-01 2.844918e-03 -1.014038e+01 8.488413e-01 -4.823731e-02 -5.264424e-01 9.166145e+01 +-5.102269e-01 3.774679e-02 -8.592111e-01 6.575207e+02 6.084380e-02 9.981174e-01 7.718237e-03 -1.014228e+01 8.578849e-01 -4.833960e-02 -5.115631e-01 9.123078e+01 +-4.998635e-01 3.964569e-02 -8.651963e-01 6.567840e+02 5.975191e-02 9.981502e-01 1.121660e-02 -1.014771e+01 8.640407e-01 -4.609035e-02 -5.013078e-01 9.079684e+01 +-4.932803e-01 4.362236e-02 -8.687760e-01 6.560269e+02 5.844760e-02 9.981468e-01 1.693243e-02 -1.014631e+01 8.679047e-01 -4.242542e-02 -4.949158e-01 9.035545e+01 +-4.905895e-01 4.655407e-02 -8.701463e-01 6.552651e+02 5.513483e-02 9.982294e-01 2.232163e-02 -1.014500e+01 8.696448e-01 -3.702460e-02 -4.922876e-01 8.990592e+01 +-4.899546e-01 4.569446e-02 -8.705496e-01 6.545015e+02 4.675005e-02 9.985655e-01 2.610251e-02 -1.014401e+01 8.704936e-01 -2.790918e-02 -4.913879e-01 8.944510e+01 +-4.909372e-01 4.180163e-02 -8.701915e-01 6.537332e+02 4.011262e-02 9.988734e-01 2.535278e-02 -1.014159e+01 8.702710e-01 -2.245902e-02 -4.920610e-01 8.898224e+01 +-4.933263e-01 3.463569e-02 -8.691545e-01 6.529631e+02 3.577480e-02 9.991694e-01 1.951124e-02 -1.013661e+01 8.691084e-01 -2.146841e-02 -4.941556e-01 8.852370e+01 +-4.969439e-01 2.710487e-02 -8.673592e-01 6.521783e+02 3.580712e-02 9.993013e-01 1.071275e-02 -1.013302e+01 8.670436e-01 -2.573399e-02 -4.975673e-01 8.806058e+01 +-5.021236e-01 2.064788e-02 -8.645493e-01 6.513922e+02 3.428307e-02 9.994043e-01 3.957258e-03 -1.013577e+01 8.641161e-01 -2.765237e-02 -5.025324e-01 8.759251e+01 +-5.069264e-01 2.052318e-02 -8.617449e-01 6.505920e+02 3.645393e-02 9.993325e-01 2.355718e-03 -1.014452e+01 8.612182e-01 -3.021981e-02 -5.073363e-01 8.711193e+01 +-5.122853e-01 2.164531e-02 -8.585425e-01 6.497873e+02 3.446435e-02 9.993952e-01 4.631853e-03 -1.016222e+01 8.581236e-01 -2.721628e-02 -5.127214e-01 8.662273e+01 +-5.156733e-01 1.878346e-02 -8.565793e-01 6.489838e+02 3.129604e-02 9.995054e-01 3.076939e-03 -1.018136e+01 8.562135e-01 -2.522084e-02 -5.160061e-01 8.611908e+01 +-5.174773e-01 1.172028e-02 -8.556166e-01 6.481788e+02 2.677316e-02 9.996384e-01 -2.499321e-03 -1.020660e+01 8.552780e-01 -2.420090e-02 -5.176040e-01 8.561030e+01 +-5.171674e-01 7.343275e-03 -8.558527e-01 6.473616e+02 2.656698e-02 9.996190e-01 -7.476862e-03 -1.023491e+01 8.554718e-01 -2.660420e-02 -5.171655e-01 8.510861e+01 +-5.176611e-01 5.185426e-03 -8.555700e-01 6.465313e+02 2.403844e-02 9.996750e-01 -8.485590e-03 -1.026526e+01 8.552480e-01 -2.495922e-02 -5.176175e-01 8.459392e+01 +-5.181485e-01 4.295080e-03 -8.552799e-01 6.456934e+02 2.188611e-02 9.997265e-01 -8.238640e-03 -1.029976e+01 8.550106e-01 -2.298758e-02 -5.181008e-01 8.407343e+01 +-5.194761e-01 8.132054e-03 -8.544463e-01 6.448424e+02 2.426058e-02 9.996919e-01 -5.235243e-03 -1.032492e+01 8.541406e-01 -2.344894e-02 -5.195133e-01 8.354987e+01 +-5.206476e-01 1.230231e-02 -8.536830e-01 6.439805e+02 2.830113e-02 9.995953e-01 -2.855368e-03 -1.035283e+01 8.533025e-01 -2.564683e-02 -5.207851e-01 8.302190e+01 +-5.230508e-01 1.529571e-02 -8.521642e-01 6.431181e+02 2.715558e-02 9.996304e-01 1.274772e-03 -1.037586e+01 8.518688e-01 -2.247423e-02 -5.232728e-01 8.248284e+01 +-5.256310e-01 1.695477e-02 -8.505437e-01 6.422520e+02 2.899085e-02 9.995776e-01 2.009446e-03 -1.039451e+01 8.502186e-01 -2.360175e-02 -5.259006e-01 8.194828e+01 +-5.287789e-01 1.822432e-02 -8.485639e-01 6.413927e+02 3.059137e-02 9.995291e-01 2.403678e-03 -1.041407e+01 8.482082e-01 -2.468771e-02 -5.290874e-01 8.141052e+01 +-5.321793e-01 1.939733e-02 -8.464094e-01 6.405350e+02 3.270456e-02 9.994623e-01 2.341922e-03 -1.043270e+01 8.459998e-01 -2.643512e-02 -5.325275e-01 8.086911e+01 +-5.357203e-01 2.273988e-02 -8.440892e-01 6.396813e+02 3.559328e-02 9.993569e-01 4.332745e-03 -1.045077e+01 8.436450e-01 -2.772276e-02 -5.361852e-01 8.032439e+01 +-5.399153e-01 2.339591e-02 -8.413941e-01 6.388312e+02 3.723367e-02 9.992990e-01 3.894121e-03 -1.046791e+01 8.408955e-01 -2.922568e-02 -5.404079e-01 7.976797e+01 +-5.435564e-01 2.053710e-02 -8.391214e-01 6.379859e+02 3.626349e-02 9.993418e-01 9.680864e-04 -1.048472e+01 8.385890e-01 -2.990325e-02 -5.439434e-01 7.921210e+01 +-5.462563e-01 2.023260e-02 -8.373737e-01 6.371493e+02 3.734254e-02 9.993025e-01 -2.150747e-04 -1.050813e+01 8.367853e-01 -3.138713e-02 -5.466309e-01 7.865837e+01 +-5.481044e-01 2.221977e-02 -8.361147e-01 6.363150e+02 3.658003e-02 9.993274e-01 2.577593e-03 -1.053704e+01 8.356096e-01 -2.917230e-02 -5.485486e-01 7.809906e+01 +-5.494082e-01 2.404203e-02 -8.352081e-01 6.354874e+02 3.733800e-02 9.992938e-01 4.204055e-03 -1.056509e+01 8.347194e-01 -2.887525e-02 -5.499179e-01 7.754032e+01 +-5.509805e-01 2.226317e-02 -8.342211e-01 6.346665e+02 3.631386e-02 9.993368e-01 2.685356e-03 -1.058281e+01 8.337277e-01 -2.881420e-02 -5.514236e-01 7.699384e+01 +-5.518853e-01 2.000535e-02 -8.336800e-01 6.338524e+02 3.689377e-02 9.993191e-01 -4.430953e-04 -1.060249e+01 8.331035e-01 -3.100213e-02 -5.522476e-01 7.644864e+01 +-5.524491e-01 2.063119e-02 -8.332913e-01 6.330517e+02 3.582686e-02 9.993575e-01 9.905732e-04 -1.063017e+01 8.327764e-01 -2.930696e-02 -5.528333e-01 7.590526e+01 +-5.519303e-01 2.488978e-02 -8.335187e-01 6.322519e+02 3.561458e-02 9.993460e-01 6.258700e-03 -1.064811e+01 8.331294e-01 -2.623104e-02 -5.524558e-01 7.535515e+01 +-5.523929e-01 2.398724e-02 -8.332387e-01 6.314568e+02 3.402112e-02 9.994018e-01 6.216564e-03 -1.065785e+01 8.328894e-01 -2.491372e-02 -5.528785e-01 7.480841e+01 +-5.529905e-01 2.204978e-02 -8.328957e-01 6.306658e+02 3.467605e-02 9.993927e-01 3.434852e-03 -1.066245e+01 8.324657e-01 -2.698209e-02 -5.534193e-01 7.427009e+01 +-5.535982e-01 2.224282e-02 -8.324868e-01 6.298795e+02 3.695414e-02 9.993147e-01 2.125975e-03 -1.067161e+01 8.319636e-01 -2.958689e-02 -5.540408e-01 7.373857e+01 +-5.549657e-01 2.265438e-02 -8.315647e-01 6.291065e+02 3.696632e-02 9.993132e-01 2.553970e-03 -1.068866e+01 8.310515e-01 -2.932251e-02 -5.554220e-01 7.321100e+01 +-5.571149e-01 2.285053e-02 -8.301210e-01 6.283434e+02 3.772738e-02 9.992857e-01 2.187308e-03 -1.070814e+01 8.295780e-01 -3.009970e-02 -5.575790e-01 7.268462e+01 +-5.595744e-01 2.152435e-02 -8.285006e-01 6.275905e+02 3.831602e-02 9.992656e-01 8.194623e-05 -1.072130e+01 8.278940e-01 -3.169898e-02 -5.599882e-01 7.216355e+01 +-5.616613e-01 2.225835e-02 -8.270678e-01 6.268447e+02 3.673508e-02 9.993231e-01 1.947388e-03 -1.073087e+01 8.265513e-01 -2.928862e-02 -5.620988e-01 7.163711e+01 +-5.638191e-01 2.593636e-02 -8.254910e-01 6.261107e+02 3.834622e-02 9.992509e-01 5.204922e-03 -1.073910e+01 8.250077e-01 -2.871981e-02 -5.643913e-01 7.112089e+01 +-5.665703e-01 2.704491e-02 -8.235694e-01 6.253872e+02 3.736404e-02 9.992764e-01 7.110497e-03 -1.074782e+01 8.231659e-01 -2.674328e-02 -5.671709e-01 7.061005e+01 +-5.687962e-01 2.254226e-02 -8.221695e-01 6.246843e+02 3.544747e-02 9.993674e-01 2.877294e-03 -1.075119e+01 8.217143e-01 -2.750723e-02 -5.692354e-01 7.010311e+01 +-5.709124e-01 2.077061e-02 -8.207482e-01 6.239951e+02 3.446468e-02 9.994050e-01 1.318254e-03 -1.075593e+01 8.202873e-01 -2.753420e-02 -5.712886e-01 6.960583e+01 +-5.723389e-01 2.096456e-02 -8.197491e-01 6.233185e+02 3.403199e-02 9.994191e-01 1.798798e-03 -1.075717e+01 8.193107e-01 -2.686816e-02 -5.727200e-01 6.911566e+01 +-5.730789e-01 2.192998e-02 -8.192067e-01 6.226615e+02 3.341156e-02 9.994359e-01 3.381521e-03 -1.075900e+01 8.188188e-01 -2.543308e-02 -5.734884e-01 6.863581e+01 +-5.736792e-01 2.035206e-02 -8.188272e-01 6.220271e+02 3.048945e-02 9.995290e-01 3.482196e-03 -1.075355e+01 8.185124e-01 -2.296792e-02 -5.740295e-01 6.816600e+01 +-5.748052e-01 1.762959e-02 -8.181003e-01 6.214105e+02 2.771047e-02 9.996138e-01 2.071474e-03 -1.075959e+01 8.178210e-01 -2.147924e-02 -5.750718e-01 6.770924e+01 +-5.760171e-01 2.140790e-02 -8.171573e-01 6.208086e+02 3.002740e-02 9.995364e-01 5.019466e-03 -1.076815e+01 8.168860e-01 -2.164580e-02 -5.763929e-01 6.727259e+01 +-5.779511e-01 2.531529e-02 -8.156787e-01 6.202264e+02 3.414856e-02 9.993935e-01 6.821009e-03 -1.077507e+01 8.153567e-01 -2.391204e-02 -5.784650e-01 6.685124e+01 +-5.795313e-01 2.749158e-02 -8.144862e-01 6.196701e+02 3.215759e-02 9.994239e-01 1.085276e-02 -1.078381e+01 8.143153e-01 -1.990239e-02 -5.800814e-01 6.643697e+01 +-5.810567e-01 2.648818e-02 -8.134319e-01 6.191421e+02 2.907267e-02 9.995079e-01 1.178007e-02 -1.079462e+01 8.133437e-01 -1.680374e-02 -5.815409e-01 6.603572e+01 +-5.827826e-01 2.721465e-02 -8.121722e-01 6.186337e+02 3.042426e-02 9.994690e-01 1.165945e-02 -1.080289e+01 8.120584e-01 -1.791481e-02 -5.833012e-01 6.565583e+01 +-5.843661e-01 2.653584e-02 -8.110562e-01 6.181539e+02 2.913307e-02 9.995069e-01 1.171113e-02 -1.081550e+01 8.109671e-01 -1.678496e-02 -5.848510e-01 6.528911e+01 +-5.857860e-01 2.546061e-02 -8.100657e-01 6.176970e+02 3.007000e-02 9.995010e-01 9.669998e-03 -1.082404e+01 8.099078e-01 -1.869412e-02 -5.862593e-01 6.494478e+01 +-5.868472e-01 2.593083e-02 -8.092823e-01 6.172685e+02 3.291817e-02 9.994248e-01 8.152889e-03 -1.083564e+01 8.090283e-01 -2.185558e-02 -5.873633e-01 6.462793e+01 +-5.875913e-01 2.757482e-02 -8.086879e-01 6.168671e+02 3.500145e-02 9.993499e-01 8.644071e-03 -1.084459e+01 8.084006e-01 -2.322606e-02 -5.881744e-01 6.432758e+01 +-5.885092e-01 2.588011e-02 -8.080762e-01 6.164909e+02 3.628297e-02 9.993259e-01 5.580928e-03 -1.085055e+01 8.076760e-01 -2.603497e-02 -5.890515e-01 6.404612e+01 +-5.887640e-01 2.251211e-02 -8.079915e-01 6.161466e+02 3.174843e-02 9.994848e-01 4.713158e-03 -1.085254e+01 8.076813e-01 -2.287751e-02 -5.891753e-01 6.377847e+01 +-5.886684e-01 2.128261e-02 -8.080944e-01 6.158196e+02 2.828787e-02 9.995834e-01 5.719114e-03 -1.084752e+01 8.078796e-01 -1.949260e-02 -5.890252e-01 6.353086e+01 +-5.900284e-01 2.380997e-02 -8.070313e-01 6.155139e+02 3.070002e-02 9.995038e-01 7.043445e-03 -1.084264e+01 8.067986e-01 -2.062004e-02 -5.904666e-01 6.331555e+01 +-5.913783e-01 2.790495e-02 -8.059113e-01 6.152297e+02 3.727447e-02 9.992788e-01 7.248344e-03 -1.084514e+01 8.055324e-01 -2.575339e-02 -5.919919e-01 6.311774e+01 +-5.912593e-01 2.707243e-02 -8.060270e-01 6.149738e+02 3.828478e-02 9.992518e-01 5.478666e-03 -1.084148e+01 8.055723e-01 -2.761924e-02 -5.918534e-01 6.293212e+01 +-5.921048e-01 2.491408e-02 -8.054758e-01 6.147441e+02 3.656719e-02 9.993230e-01 4.029442e-03 -1.084211e+01 8.050309e-01 -2.706812e-02 -5.926150e-01 6.275796e+01 +-5.938043e-01 2.441548e-02 -8.042390e-01 6.145303e+02 3.583471e-02 9.993502e-01 3.880460e-03 -1.083600e+01 8.038112e-01 -2.651543e-02 -5.942933e-01 6.260420e+01 +-5.939757e-01 2.615551e-02 -8.040577e-01 6.143308e+02 3.716288e-02 9.992964e-01 5.053460e-03 -1.083889e+01 8.036242e-01 -2.687945e-02 -5.945298e-01 6.246162e+01 +-5.938996e-01 2.663189e-02 -8.040983e-01 6.141529e+02 3.712016e-02 9.992946e-01 5.680238e-03 -1.083935e+01 8.036824e-01 -2.647475e-02 -5.944693e-01 6.232641e+01 +-5.948834e-01 2.399536e-02 -8.034537e-01 6.139794e+02 3.791810e-02 9.992793e-01 1.768902e-03 -1.083308e+01 8.029172e-01 -2.941314e-02 -5.953645e-01 6.219637e+01 +-5.955525e-01 2.168356e-02 -8.030237e-01 6.138111e+02 3.853096e-02 9.992561e-01 -1.593686e-03 -1.082475e+01 8.023918e-01 -3.189039e-02 -5.959449e-01 6.206930e+01 +-5.949362e-01 2.129948e-02 -8.034907e-01 6.136452e+02 3.959457e-02 9.992118e-01 -2.829576e-03 -1.082308e+01 8.027972e-01 -3.349728e-02 -5.953106e-01 6.194494e+01 +-5.952631e-01 2.157974e-02 -8.032410e-01 6.134789e+02 4.059464e-02 9.991704e-01 -3.240177e-03 -1.081330e+01 8.025048e-01 -3.453603e-02 -5.956453e-01 6.182100e+01 +-5.956436e-01 2.249599e-02 -8.029338e-01 6.133132e+02 4.125633e-02 9.991452e-01 -2.612052e-03 -1.080582e+01 8.021887e-01 -3.468195e-02 -5.960625e-01 6.169425e+01 +-5.954943e-01 2.220131e-02 -8.030527e-01 6.131522e+02 4.080173e-02 9.991638e-01 -2.633006e-03 -1.080397e+01 8.023227e-01 -3.433387e-02 -5.959022e-01 6.156966e+01 +-5.953729e-01 2.129884e-02 -8.031671e-01 6.129910e+02 4.022453e-02 9.991851e-01 -3.320738e-03 -1.079800e+01 8.024420e-01 -3.428409e-02 -5.957445e-01 6.144762e+01 +-5.956074e-01 1.925619e-02 -8.030448e-01 6.128304e+02 3.876870e-02 9.992367e-01 -4.793538e-03 -1.079146e+01 8.023396e-01 -3.398806e-02 -5.958993e-01 6.132249e+01 +-5.958549e-01 1.848997e-02 -8.028792e-01 6.126714e+02 3.781808e-02 9.992718e-01 -5.053782e-03 -1.078498e+01 8.022012e-01 -3.337466e-02 -5.961203e-01 6.119808e+01 +-5.959575e-01 1.976100e-02 -8.027728e-01 6.125071e+02 3.797438e-02 9.992722e-01 -3.593157e-03 -1.078137e+01 8.021176e-01 -3.262616e-02 -5.962742e-01 6.107369e+01 +-5.960490e-01 2.100963e-02 -8.026731e-01 6.123480e+02 3.934346e-02 9.992210e-01 -3.061461e-03 -1.078161e+01 8.019836e-01 -3.340471e-02 -5.964113e-01 6.095679e+01 +-5.964138e-01 2.214273e-02 -8.023716e-01 6.121916e+02 4.107880e-02 9.991515e-01 -2.961245e-03 -1.078752e+01 8.016253e-01 -3.472658e-02 -5.968174e-01 6.084182e+01 +-5.964489e-01 2.230769e-02 -8.023410e-01 6.120437e+02 4.148109e-02 9.991346e-01 -3.057242e-03 -1.079376e+01 8.015785e-01 -3.510546e-02 -5.968580e-01 6.073134e+01 +-5.963955e-01 2.149369e-02 -8.024029e-01 6.119005e+02 4.032709e-02 9.991814e-01 -3.208858e-03 -1.080293e+01 8.016771e-01 -3.427231e-02 -5.967741e-01 6.061897e+01 +-5.966333e-01 2.064705e-02 -8.022483e-01 6.117571e+02 3.949415e-02 9.992131e-01 -3.655620e-03 -1.080545e+01 8.015416e-01 -3.386517e-02 -5.969793e-01 6.050642e+01 +-5.968679e-01 2.126865e-02 -8.020576e-01 6.116151e+02 3.998307e-02 9.991950e-01 -3.257964e-03 -1.081255e+01 8.013427e-01 -3.401329e-02 -5.972378e-01 6.040031e+01 +-5.967324e-01 2.276226e-02 -8.021174e-01 6.114761e+02 4.121168e-02 9.991478e-01 -2.305744e-03 -1.081876e+01 8.013814e-01 -3.443251e-02 -5.971619e-01 6.029891e+01 +-5.967165e-01 2.348119e-02 -8.021085e-01 6.113439e+02 4.139156e-02 9.991418e-01 -1.543402e-03 -1.081989e+01 8.013839e-01 -3.412148e-02 -5.971763e-01 6.020132e+01 +-5.967222e-01 2.257342e-02 -8.021303e-01 6.112231e+02 4.021935e-02 9.991892e-01 -1.801014e-03 -1.081783e+01 8.014394e-01 -3.333585e-02 -5.971463e-01 6.010489e+01 +-5.967627e-01 2.047729e-02 -8.021564e-01 6.111093e+02 3.850119e-02 9.992536e-01 -3.134133e-03 -1.082428e+01 8.014936e-01 -3.275430e-02 -5.971057e-01 6.001185e+01 +-5.969434e-01 1.969388e-02 -8.020416e-01 6.109958e+02 3.863292e-02 9.992445e-01 -4.217559e-03 -1.083316e+01 8.013527e-01 -3.350284e-02 -5.972533e-01 5.992384e+01 +-5.969639e-01 2.068400e-02 -8.020014e-01 6.108817e+02 4.090451e-02 9.991521e-01 -4.678348e-03 -1.083923e+01 8.012247e-01 -3.559827e-02 -5.973038e-01 5.984108e+01 +-5.967815e-01 2.227846e-02 -8.020945e-01 6.107661e+02 4.383733e-02 9.990268e-01 -4.867896e-03 -1.084023e+01 8.012055e-01 -3.806674e-02 -5.971773e-01 5.975840e+01 +-5.964777e-01 2.256854e-02 -8.023123e-01 6.106572e+02 4.397921e-02 9.990219e-01 -4.594394e-03 -1.084191e+01 8.014239e-01 -3.802551e-02 -5.968868e-01 5.967128e+01 +-5.968017e-01 2.312042e-02 -8.020556e-01 6.105440e+02 4.124701e-02 9.991472e-01 -1.889617e-03 -1.083560e+01 8.013279e-01 -3.421011e-02 -5.972464e-01 5.957761e+01 +-5.969164e-01 2.269891e-02 -8.019823e-01 6.104340e+02 3.742850e-02 9.992992e-01 4.256092e-04 -1.083002e+01 8.014300e-01 -2.976293e-02 -5.973476e-01 5.948389e+01 +-5.967721e-01 2.095150e-02 -8.021372e-01 6.103302e+02 3.519448e-02 9.993805e-01 -8.047431e-05 -1.083372e+01 8.016386e-01 -2.827882e-02 -5.971397e-01 5.939758e+01 +-5.969052e-01 1.947368e-02 -8.020754e-01 6.102291e+02 3.520506e-02 9.993782e-01 -1.935610e-03 -1.084160e+01 8.015391e-01 -2.939248e-02 -5.972196e-01 5.931664e+01 +-5.970564e-01 1.874930e-02 -8.019802e-01 6.101273e+02 3.616595e-02 9.993394e-01 -3.561422e-03 -1.085035e+01 8.013837e-01 -3.113073e-02 -5.973401e-01 5.923631e+01 +-5.970311e-01 1.870595e-02 -8.020000e-01 6.100250e+02 3.656085e-02 9.993238e-01 -3.908554e-03 -1.085672e+01 8.013846e-01 -3.165532e-02 -5.973113e-01 5.915471e+01 +-5.972291e-01 1.837996e-02 -8.018601e-01 6.099206e+02 3.631232e-02 9.993319e-01 -4.139223e-03 -1.085800e+01 8.012483e-01 -3.158945e-02 -5.974975e-01 5.906999e+01 +-5.975144e-01 1.741453e-02 -8.016691e-01 6.098106e+02 3.602575e-02 9.993376e-01 -5.142896e-03 -1.085383e+01 8.010485e-01 -3.195367e-02 -5.977460e-01 5.898320e+01 +-5.977829e-01 1.594164e-02 -8.014995e-01 6.096925e+02 3.578930e-02 9.993361e-01 -6.816171e-03 -1.084677e+01 8.008588e-01 -3.275968e-02 -5.979565e-01 5.889047e+01 +-5.985627e-01 1.389851e-02 -8.009554e-01 6.095668e+02 3.635794e-02 9.992905e-01 -9.830563e-03 -1.084532e+01 8.002505e-01 -3.500528e-02 -5.986433e-01 5.879275e+01 +-5.996039e-01 1.145073e-02 -8.002150e-01 6.094269e+02 3.733446e-02 9.992092e-01 -1.367659e-02 -1.084530e+01 7.994256e-01 -3.807612e-02 -5.995573e-01 5.868324e+01 +-6.009960e-01 9.424697e-03 -7.991965e-01 6.092668e+02 3.812601e-02 9.991302e-01 -1.688830e-02 -1.084724e+01 7.983422e-01 -4.061996e-02 -6.008326e-01 5.855681e+01 +-6.032812e-01 7.531370e-03 -7.974930e-01 6.090866e+02 3.744874e-02 9.991199e-01 -1.889342e-02 -1.085141e+01 7.966489e-01 -4.126314e-02 -6.030323e-01 5.841027e+01 +-6.065765e-01 5.629727e-03 -7.950052e-01 6.088850e+02 3.655084e-02 9.991150e-01 -2.081261e-02 -1.085837e+01 7.941845e-01 -4.168254e-02 -6.062455e-01 5.824501e+01 +-6.108501e-01 5.921231e-03 -7.917242e-01 6.086581e+02 3.778525e-02 9.990506e-01 -2.168117e-02 -1.086268e+01 7.908442e-01 -4.315942e-02 -6.104939e-01 5.806365e+01 +-6.154905e-01 6.548639e-03 -7.881171e-01 6.084078e+02 4.085270e-02 9.988863e-01 -2.360449e-02 -1.085940e+01 7.870848e-01 -4.672504e-02 -6.150726e-01 5.786475e+01 +-6.208312e-01 5.020111e-03 -7.839282e-01 6.081414e+02 4.177337e-02 9.987706e-01 -2.668645e-02 -1.085098e+01 7.828305e-01 -4.931509e-02 -6.202777e-01 5.764325e+01 +-6.276233e-01 3.695327e-03 -7.785084e-01 6.078549e+02 3.903623e-02 9.988802e-01 -2.672913e-02 -1.085104e+01 7.775379e-01 -4.716585e-02 -6.270647e-01 5.739812e+01 +-6.349994e-01 4.912246e-03 -7.724970e-01 6.075536e+02 4.151918e-02 9.987515e-01 -2.777814e-02 -1.085729e+01 7.713961e-01 -4.971253e-02 -6.344105e-01 5.714145e+01 +-6.425013e-01 7.550149e-03 -7.662474e-01 6.072262e+02 4.526365e-02 9.985794e-01 -2.811432e-02 -1.084763e+01 7.649466e-01 -5.274663e-02 -6.419303e-01 5.686485e+01 +-6.501649e-01 1.079907e-02 -7.597164e-01 6.068856e+02 4.760207e-02 9.985136e-01 -2.654433e-02 -1.084516e+01 7.583006e-01 -5.342225e-02 -6.497125e-01 5.657174e+01 +-6.579294e-01 1.381673e-02 -7.529528e-01 6.065341e+02 4.794939e-02 9.985715e-01 -2.357428e-02 -1.084757e+01 7.515516e-01 -5.161383e-02 -6.576521e-01 5.625489e+01 +-6.661731e-01 1.114207e-02 -7.457139e-01 6.061751e+02 4.602035e-02 9.985971e-01 -2.619111e-02 -1.085240e+01 7.443759e-01 -5.176582e-02 -6.657513e-01 5.592283e+01 +-6.738117e-01 1.053538e-02 -7.388279e-01 6.057989e+02 4.609699e-02 9.985500e-01 -2.780158e-02 -1.085192e+01 7.374638e-01 -5.279076e-02 -6.733204e-01 5.557109e+01 +-6.808362e-01 1.604412e-02 -7.322600e-01 6.054022e+02 4.874415e-02 9.985361e-01 -2.344267e-02 -1.085101e+01 7.308120e-01 -5.165399e-02 -6.806216e-01 5.520007e+01 +-6.875419e-01 2.165847e-02 -7.258216e-01 6.049888e+02 5.239354e-02 9.984294e-01 -1.983723e-02 -1.084809e+01 7.242521e-01 -5.166728e-02 -6.875969e-01 5.481576e+01 +-6.941966e-01 2.331629e-02 -7.194077e-01 6.045756e+02 5.234638e-02 9.984640e-01 -1.815130e-02 -1.084914e+01 7.178795e-01 -5.025895e-02 -6.943508e-01 5.441248e+01 +-6.993253e-01 2.243719e-02 -7.144513e-01 6.041571e+02 4.687279e-02 9.987954e-01 -1.451345e-02 -1.084897e+01 7.132651e-01 -4.363794e-02 -6.995347e-01 5.398360e+01 +-7.034210e-01 2.428347e-02 -7.103585e-01 6.037210e+02 4.457108e-02 9.989563e-01 -9.986640e-03 -1.084900e+01 7.093746e-01 -3.868624e-02 -7.037692e-01 5.353979e+01 +-7.071603e-01 2.113340e-02 -7.067374e-01 6.032807e+02 4.059847e-02 9.991177e-01 -1.074636e-02 -1.085762e+01 7.058868e-01 -3.629185e-02 -7.073943e-01 5.308678e+01 +-7.085821e-01 1.966788e-02 -7.053542e-01 6.028244e+02 3.672796e-02 9.992845e-01 -9.032279e-03 -1.086177e+01 7.046719e-01 -3.230632e-02 -7.087974e-01 5.261497e+01 +-7.098314e-01 1.722167e-02 -7.041611e-01 6.023576e+02 3.107686e-02 9.994933e-01 -6.882484e-03 -1.086318e+01 7.036858e-01 -2.676851e-02 -7.100069e-01 5.212981e+01 +-7.118773e-01 1.785349e-02 -7.020769e-01 6.018734e+02 3.203443e-02 9.994618e-01 -7.065743e-03 -1.086370e+01 7.015729e-01 -2.752057e-02 -7.120661e-01 5.163483e+01 +-7.131645e-01 1.841389e-02 -7.007548e-01 6.013777e+02 3.206450e-02 9.994655e-01 -6.369142e-03 -1.086860e+01 7.002630e-01 -2.701159e-02 -7.133738e-01 5.112461e+01 +-7.139192e-01 1.924606e-02 -6.999636e-01 6.008722e+02 3.426314e-02 9.993849e-01 -7.467361e-03 -1.087876e+01 6.993894e-01 -2.931404e-02 -7.141395e-01 5.059895e+01 +-7.160014e-01 1.007426e-02 -6.980261e-01 6.003665e+02 2.745272e-02 9.995287e-01 -1.373397e-02 -1.089051e+01 6.975589e-01 -2.899625e-02 -7.159406e-01 5.005776e+01 +-7.170877e-01 1.578977e-03 -6.969811e-01 5.998496e+02 2.130503e-02 9.995798e-01 -1.965513e-02 -1.090722e+01 6.966572e-01 -2.894365e-02 -7.168201e-01 4.950071e+01 +-7.183870e-01 -9.884114e-04 -6.956430e-01 5.993131e+02 2.339173e-02 9.993991e-01 -2.557652e-02 -1.092426e+01 6.952503e-01 -3.464613e-02 -7.179323e-01 4.894080e+01 +-7.198182e-01 3.797116e-03 -6.941522e-01 5.987574e+02 3.039708e-02 9.991982e-01 -2.605523e-02 -1.094563e+01 6.934968e-01 -3.985522e-02 -7.193565e-01 4.836507e+01 +-7.203310e-01 4.433188e-03 -6.936163e-01 5.981997e+02 2.688962e-02 9.994063e-01 -2.153765e-02 -1.097494e+01 6.931091e-01 -3.416531e-02 -7.200226e-01 4.776481e+01 +-7.212024e-01 3.393780e-03 -6.927161e-01 5.976365e+02 2.369484e-02 9.995237e-01 -1.977232e-02 -1.100894e+01 6.923191e-01 -3.067363e-02 -7.209393e-01 4.715386e+01 +-7.228453e-01 4.137346e-03 -6.909975e-01 5.970613e+02 2.191671e-02 9.996162e-01 -1.694164e-02 -1.104019e+01 6.906622e-01 -2.739057e-02 -7.226586e-01 4.653114e+01 +-7.246507e-01 3.970665e-03 -6.891049e-01 5.964781e+02 2.292255e-02 9.995689e-01 -1.834537e-02 -1.106657e+01 6.887351e-01 -2.909002e-02 -7.244293e-01 4.590216e+01 +-7.267578e-01 7.361762e-03 -6.868544e-01 5.958811e+02 2.479738e-02 9.995719e-01 -1.552450e-02 -1.109864e+01 6.864461e-01 -2.831473e-02 -7.266292e-01 4.524823e+01 +-7.296673e-01 9.606365e-03 -6.837349e-01 5.952758e+02 2.664170e-02 9.995415e-01 -1.438805e-02 -1.112293e+01 6.832832e-01 -2.871434e-02 -7.295887e-01 4.458974e+01 +-7.332413e-01 1.006491e-02 -6.798941e-01 5.946712e+02 2.698389e-02 9.995335e-01 -1.430440e-02 -1.115506e+01 6.794330e-01 -2.883475e-02 -7.331708e-01 4.391619e+01 +-7.371188e-01 1.413464e-02 -6.756154e-01 5.940578e+02 3.056738e-02 9.994553e-01 -1.244027e-02 -1.118162e+01 6.750715e-01 -2.982174e-02 -7.371493e-01 4.323660e+01 +-7.410210e-01 1.809570e-02 -6.712380e-01 5.934438e+02 3.382232e-02 9.993738e-01 -1.039672e-02 -1.121685e+01 6.706295e-01 -3.040700e-02 -7.411690e-01 4.254869e+01 +-7.441723e-01 1.992561e-02 -6.676905e-01 5.928339e+02 3.622991e-02 9.992877e-01 -1.055859e-02 -1.124681e+01 6.670046e-01 -3.204777e-02 -7.443641e-01 4.185865e+01 +-7.469843e-01 1.840045e-02 -6.645870e-01 5.922286e+02 3.593295e-02 9.992732e-01 -1.272108e-02 -1.127914e+01 6.638700e-01 -3.338301e-02 -7.471026e-01 4.116615e+01 +-7.487295e-01 1.807712e-02 -6.626292e-01 5.916198e+02 3.762668e-02 9.991754e-01 -1.525738e-02 -1.131105e+01 6.618070e-01 -3.635618e-02 -7.487922e-01 4.047923e+01 +-7.498303e-01 1.300910e-02 -6.615023e-01 5.910189e+02 3.352279e-02 9.992695e-01 -1.834734e-02 -1.134770e+01 6.607804e-01 -3.593279e-02 -7.497187e-01 3.979061e+01 +-7.492833e-01 1.031958e-02 -6.621692e-01 5.904165e+02 3.203294e-02 9.992729e-01 -2.067397e-02 -1.138702e+01 6.614744e-01 -3.670188e-02 -7.490691e-01 3.909726e+01 +-7.487489e-01 6.609072e-03 -6.628208e-01 5.898115e+02 2.859818e-02 9.993413e-01 -2.234108e-02 -1.141673e+01 6.622366e-01 -3.568331e-02 -7.484447e-01 3.840761e+01 +-7.472365e-01 2.974616e-03 -6.645516e-01 5.892034e+02 2.344810e-02 9.994853e-01 -2.189173e-02 -1.144789e+01 6.641445e-01 -3.194076e-02 -7.469217e-01 3.771988e+01 +-7.460979e-01 4.752949e-03 -6.658193e-01 5.885897e+02 2.408749e-02 9.995126e-01 -1.985672e-02 -1.147534e+01 6.654004e-01 -3.085296e-02 -7.458488e-01 3.703595e+01 +-7.447574e-01 7.952666e-03 -6.672879e-01 5.879705e+02 2.796698e-02 9.994224e-01 -1.930282e-02 -1.150494e+01 6.667490e-01 -3.303793e-02 -7.445497e-01 3.634581e+01 +-7.429534e-01 9.811170e-03 -6.692712e-01 5.873486e+02 2.908055e-02 9.994215e-01 -1.763110e-02 -1.154032e+01 6.687111e-01 -3.256185e-02 -7.428090e-01 3.565009e+01 +-7.411952e-01 7.434800e-03 -6.712483e-01 5.867274e+02 2.879884e-02 9.993702e-01 -2.073068e-02 -1.157309e+01 6.706715e-01 -3.469665e-02 -7.409426e-01 3.495300e+01 +-7.394726e-01 6.520714e-03 -6.731551e-01 5.861016e+02 2.915584e-02 9.993250e-01 -2.234794e-02 -1.160601e+01 6.725550e-01 -3.615208e-02 -7.391636e-01 3.425941e+01 +-7.377600e-01 6.731315e-03 -6.750296e-01 5.854709e+02 2.980700e-02 9.992998e-01 -2.261205e-02 -1.163827e+01 6.744048e-01 -3.680286e-02 -7.374441e-01 3.356322e+01 +-7.356899e-01 6.725096e-03 -6.772851e-01 5.848353e+02 2.987265e-02 9.992998e-01 -2.252613e-02 -1.167232e+01 6.766594e-01 -3.680453e-02 -7.353757e-01 3.286909e+01 +-7.339118e-01 5.885337e-03 -6.792193e-01 5.841966e+02 2.880444e-02 9.993326e-01 -2.246476e-02 -1.170604e+01 6.786338e-01 -3.605168e-02 -7.335915e-01 3.217088e+01 +-7.320401e-01 6.070089e-03 -6.812345e-01 5.835539e+02 2.999289e-02 9.992779e-01 -2.332572e-02 -1.174538e+01 6.806010e-01 -3.750754e-02 -7.316935e-01 3.147256e+01 +-7.304156e-01 5.971683e-03 -6.829768e-01 5.829099e+02 3.041529e-02 9.992542e-01 -2.379080e-02 -1.177970e+01 6.823254e-01 -3.815010e-02 -7.300525e-01 3.077846e+01 +-7.287296e-01 4.175653e-03 -6.847888e-01 5.822613e+02 3.093936e-02 9.991610e-01 -2.683202e-02 -1.181017e+01 6.841023e-01 -4.074020e-02 -7.282474e-01 3.008245e+01 +-7.278310e-01 4.211614e-03 -6.857436e-01 5.816089e+02 3.047605e-02 9.991918e-01 -2.620980e-02 -1.184302e+01 6.850790e-01 -3.997505e-02 -7.273712e-01 2.938262e+01 +-7.273814e-01 4.034178e-03 -6.862216e-01 5.809564e+02 3.080447e-02 9.991666e-01 -2.677819e-02 -1.188154e+01 6.855417e-01 -4.061664e-02 -7.268995e-01 2.868287e+01 +-7.272252e-01 4.851457e-03 -6.863818e-01 5.802979e+02 2.941930e-02 9.992764e-01 -2.410685e-02 -1.192518e+01 6.857682e-01 -3.772398e-02 -7.268417e-01 2.797705e+01 +-7.272455e-01 3.805783e-03 -6.863669e-01 5.796399e+02 2.888365e-02 9.992685e-01 -2.506312e-02 -1.196837e+01 6.857695e-01 -3.805181e-02 -7.268234e-01 2.726971e+01 +-7.274614e-01 2.191051e-03 -6.861452e-01 5.789819e+02 2.733856e-02 9.992934e-01 -2.579372e-02 -1.200728e+01 6.856038e-01 -3.752215e-02 -7.270072e-01 2.655966e+01 +-7.282441e-01 3.724066e-04 -6.853177e-01 5.783215e+02 2.666734e-02 9.992579e-01 -2.779470e-02 -1.204305e+01 6.847988e-01 -3.851692e-02 -7.277136e-01 2.584731e+01 +-7.293007e-01 1.824487e-03 -6.841909e-01 5.776565e+02 2.770890e-02 9.992548e-01 -2.687113e-02 -1.208468e+01 6.836320e-01 -3.855530e-02 -7.288078e-01 2.513063e+01 +-7.303412e-01 3.460958e-03 -6.830737e-01 5.769896e+02 2.883654e-02 9.992519e-01 -2.576902e-02 -1.212757e+01 6.824736e-01 -3.851765e-02 -7.298947e-01 2.441211e+01 +-7.313077e-01 2.312740e-04 -6.820476e-01 5.763293e+02 2.773788e-02 9.991827e-01 -2.940240e-02 -1.217159e+01 6.814834e-01 -4.042075e-02 -7.307165e-01 2.369459e+01 +-7.325549e-01 -1.605710e-03 -6.807060e-01 5.756697e+02 2.704423e-02 9.991390e-01 -3.146102e-02 -1.221780e+01 6.801705e-01 -4.145609e-02 -7.318808e-01 2.297735e+01 +-7.340705e-01 -3.507362e-03 -6.790642e-01 5.750134e+02 2.745142e-02 9.990160e-01 -3.483497e-02 -1.226829e+01 6.785182e-01 -4.421259e-02 -7.332519e-01 2.226179e+01 +-7.356502e-01 -1.996564e-03 -6.773587e-01 5.743601e+02 2.505278e-02 9.992312e-01 -3.015404e-02 -1.232193e+01 6.768982e-01 -3.915253e-02 -7.350347e-01 2.153752e+01 +-7.373096e-01 3.263130e-04 -6.755549e-01 5.737105e+02 2.545350e-02 9.993032e-01 -2.729759e-02 -1.237404e+01 6.750753e-01 -3.732200e-02 -7.368042e-01 2.081582e+01 +-7.389978e-01 2.105842e-03 -6.737046e-01 5.730610e+02 2.444067e-02 9.994206e-01 -2.368542e-02 -1.242000e+01 6.732644e-01 -3.396926e-02 -7.386211e-01 2.009230e+01 +-7.401895e-01 2.616078e-03 -6.723933e-01 5.724145e+02 2.657129e-02 9.993251e-01 -2.536234e-02 -1.245957e+01 6.718732e-01 -3.663928e-02 -7.397595e-01 1.937693e+01 +-7.418849e-01 2.206993e-03 -6.705236e-01 5.717728e+02 2.668484e-02 9.992995e-01 -2.623566e-02 -1.249786e+01 6.699961e-01 -3.735665e-02 -7.414242e-01 1.865815e+01 +-7.432837e-01 2.523786e-03 -6.689716e-01 5.711353e+02 2.811460e-02 9.992272e-01 -2.746795e-02 -1.253619e+01 6.683853e-01 -3.922434e-02 -7.427803e-01 1.794196e+01 +-7.450089e-01 3.067544e-03 -6.670475e-01 5.705015e+02 2.907355e-02 9.991885e-01 -2.787656e-02 -1.257914e+01 6.664207e-01 -4.016171e-02 -7.444935e-01 1.722896e+01 +-7.462280e-01 1.933837e-03 -6.656877e-01 5.698728e+02 3.040023e-02 9.990515e-01 -3.117602e-02 -1.262044e+01 6.649960e-01 -4.350147e-02 -7.455790e-01 1.652128e+01 +-7.476201e-01 -3.660577e-04 -6.641266e-01 5.692530e+02 2.898550e-02 9.990290e-01 -3.318018e-02 -1.266639e+01 6.634939e-01 -4.405619e-02 -7.468835e-01 1.581237e+01 +-7.490362e-01 -7.964299e-04 -6.625286e-01 5.686346e+02 2.755648e-02 9.990964e-01 -3.235559e-02 -1.271147e+01 6.619558e-01 -4.249246e-02 -7.483374e-01 1.510270e+01 +-7.502665e-01 7.669555e-04 -6.611351e-01 5.680181e+02 2.586468e-02 9.992678e-01 -2.819243e-02 -1.275310e+01 6.606294e-01 -3.825188e-02 -7.497370e-01 1.439283e+01 +-7.507624e-01 3.913036e-03 -6.605607e-01 5.674028e+02 2.525151e-02 9.994215e-01 -2.277930e-02 -1.279528e+01 6.600895e-01 -3.378199e-02 -7.504270e-01 1.368455e+01 +-7.508166e-01 1.003332e-03 -6.605099e-01 5.667964e+02 2.199562e-02 9.994822e-01 -2.348467e-02 -1.283587e+01 6.601444e-01 -3.216099e-02 -7.504499e-01 1.298106e+01 +-7.499897e-01 -3.762714e-03 -6.614388e-01 5.661990e+02 1.936850e-02 9.994301e-01 -2.764691e-02 -1.288189e+01 6.611659e-01 -3.354597e-02 -7.494894e-01 1.228701e+01 +-7.489816e-01 -5.998652e-03 -6.625636e-01 5.655970e+02 1.878508e-02 9.993648e-01 -3.028315e-02 -1.292698e+01 6.623245e-01 -3.512782e-02 -7.483932e-01 1.159476e+01 +-7.474041e-01 -3.957239e-03 -6.643580e-01 5.649902e+02 2.304684e-02 9.992259e-01 -3.187961e-02 -1.296750e+01 6.639699e-01 -3.913829e-02 -7.467343e-01 1.091187e+01 +-7.456865e-01 1.465452e-03 -6.662954e-01 5.643812e+02 2.904904e-02 9.991182e-01 -3.031285e-02 -1.300929e+01 6.656635e-01 -4.195911e-02 -7.450715e-01 1.023610e+01 +-7.443831e-01 3.610268e-03 -6.677430e-01 5.637768e+02 3.276596e-02 9.989783e-01 -3.112551e-02 -1.305035e+01 6.669484e-01 -4.504853e-02 -7.437409e-01 9.568871e+00 +-7.429975e-01 4.365361e-03 -6.692800e-01 5.631841e+02 3.430547e-02 9.989127e-01 -3.156863e-02 -1.309917e+01 6.684145e-01 -4.641536e-02 -7.423393e-01 8.909222e+00 +-7.417388e-01 6.031702e-03 -6.706617e-01 5.625935e+02 3.710135e-02 9.987974e-01 -3.205051e-02 -1.314778e+01 6.696619e-01 -4.865555e-02 -7.410706e-01 8.255447e+00 +-7.402123e-01 3.698990e-03 -6.723631e-01 5.620162e+02 3.523788e-02 9.988240e-01 -3.329877e-02 -1.319798e+01 6.714493e-01 -4.834079e-02 -7.394722e-01 7.610878e+00 +-7.384944e-01 -4.613615e-04 -6.742595e-01 5.614478e+02 3.215971e-02 9.988375e-01 -3.590693e-02 -1.324838e+01 6.734923e-01 -4.820104e-02 -7.376211e-01 6.973817e+00 +-7.369893e-01 -9.786280e-03 -6.758336e-01 5.608969e+02 2.912194e-02 9.985069e-01 -4.621585e-02 -1.329868e+01 6.752768e-01 -5.374216e-02 -7.356039e-01 6.359508e+00 +-7.354529e-01 -1.515575e-02 -6.774063e-01 5.603578e+02 2.763736e-02 9.982468e-01 -5.233957e-02 -1.335478e+01 6.770120e-01 -5.721500e-02 -7.337447e-01 5.761759e+00 +-7.344677e-01 -2.000385e-02 -6.783487e-01 5.598303e+02 2.299582e-02 9.982579e-01 -5.433589e-02 -1.341042e+01 6.782539e-01 -5.550713e-02 -7.327282e-01 5.174447e+00 +-7.334502e-01 -1.550130e-02 -6.795664e-01 5.593052e+02 2.624232e-02 9.983489e-01 -5.109601e-02 -1.345738e+01 6.792365e-01 -5.530977e-02 -7.318324e-01 4.607283e+00 +-7.329837e-01 -1.032177e-02 -6.801679e-01 5.587906e+02 2.953275e-02 9.984592e-01 -4.697793e-02 -1.350263e+01 6.796049e-01 -5.452126e-02 -7.315495e-01 4.059161e+00 +-7.324668e-01 -8.486092e-03 -6.807498e-01 5.583010e+02 3.267231e-02 9.983320e-01 -4.759945e-02 -1.354744e+01 6.800183e-01 -5.710667e-02 -7.309678e-01 3.537414e+00 +-7.320279e-01 -9.202679e-03 -6.812125e-01 5.578372e+02 3.286569e-02 9.982675e-01 -4.880318e-02 -1.359863e+01 6.804815e-01 -5.811380e-02 -7.304572e-01 3.031586e+00 +-7.319770e-01 -7.866362e-03 -6.812839e-01 5.573888e+02 3.968750e-02 9.977432e-01 -5.416089e-02 -1.364868e+01 6.801725e-01 -6.668297e-02 -7.300129e-01 2.556647e+00 +-7.324841e-01 -9.799442e-03 -6.807136e-01 5.569636e+02 4.064882e-02 9.974828e-01 -5.809989e-02 -1.369656e+01 6.795695e-01 -7.022744e-02 -7.302420e-01 2.098999e+00 +-7.322155e-01 -9.906345e-03 -6.810010e-01 5.565559e+02 3.969413e-02 9.975738e-01 -5.719076e-02 -1.374547e+01 6.799154e-01 -6.890769e-02 -7.300458e-01 1.653286e+00 +-7.320172e-01 -1.125641e-02 -6.811931e-01 5.561663e+02 3.647300e-02 9.977821e-01 -5.568215e-02 -1.379439e+01 6.803092e-01 -6.560543e-02 -7.299832e-01 1.224300e+00 +-7.327835e-01 -8.793610e-03 -6.804050e-01 5.557882e+02 3.876650e-02 9.977529e-01 -5.464583e-02 -1.384594e+01 6.793567e-01 -6.642047e-02 -7.307961e-01 8.169201e-01 +-7.328658e-01 -1.072426e-02 -6.802887e-01 5.554289e+02 3.775710e-02 9.976939e-01 -5.640314e-02 -1.390309e+01 6.793248e-01 -6.702164e-02 -7.307708e-01 4.233178e-01 +-7.324333e-01 -1.714381e-02 -6.806230e-01 5.550868e+02 3.422375e-02 9.974920e-01 -6.195415e-02 -1.395315e+01 6.799782e-01 -6.867073e-02 -7.300096e-01 3.811962e-02 +-7.323290e-01 -2.187466e-02 -6.805996e-01 5.547515e+02 2.971288e-02 9.975054e-01 -6.403133e-02 -1.400156e+01 6.803025e-01 -6.711455e-02 -7.298522e-01 -3.399935e-01 +-7.321704e-01 -2.183077e-02 -6.807716e-01 5.544192e+02 2.908841e-02 9.975721e-01 -6.327443e-02 -1.404377e+01 6.805001e-01 -6.613021e-02 -7.297578e-01 -7.073627e-01 +-7.322187e-01 -2.013431e-02 -6.807719e-01 5.540919e+02 2.957834e-02 9.976797e-01 -6.132070e-02 -1.409013e+01 6.804270e-01 -6.503625e-02 -7.299243e-01 -1.065239e+00 +-7.317458e-01 -1.768778e-02 -6.813481e-01 5.537707e+02 3.015264e-02 9.978444e-01 -5.828697e-02 -1.413144e+01 6.809104e-01 -6.319568e-02 -7.296351e-01 -1.417053e+00 +-7.315042e-01 -2.048834e-02 -6.815290e-01 5.534605e+02 2.598439e-02 9.979846e-01 -5.789150e-02 -1.417213e+01 6.813416e-01 -6.005697e-02 -7.294976e-01 -1.759813e+00 +-7.308758e-01 -2.173412e-02 -6.821644e-01 5.531562e+02 2.437832e-02 9.980237e-01 -5.791666e-02 -1.420641e+01 6.820750e-01 -5.895989e-02 -7.289015e-01 -2.093206e+00 +-7.305758e-01 -2.155185e-02 -6.824914e-01 5.528539e+02 2.476447e-02 9.980079e-01 -5.802453e-02 -1.423971e+01 6.823824e-01 -5.929284e-02 -7.285867e-01 -2.416138e+00 +-7.299666e-01 -1.875047e-02 -6.832255e-01 5.525559e+02 2.896710e-02 9.978767e-01 -5.833458e-02 -1.427067e+01 6.828687e-01 -6.237335e-02 -7.278736e-01 -2.730761e+00 +-7.297859e-01 -1.650558e-02 -6.834765e-01 5.522654e+02 3.190156e-02 9.977974e-01 -5.815932e-02 -1.430044e+01 6.829311e-01 -6.424780e-02 -7.276520e-01 -3.039119e+00 +-7.297652e-01 -1.510087e-02 -6.835310e-01 5.519811e+02 3.424433e-02 9.976939e-01 -5.860212e-02 -1.433004e+01 6.828397e-01 -6.617283e-02 -7.275652e-01 -3.341352e+00 +-7.296876e-01 -1.468193e-02 -6.836230e-01 5.517084e+02 3.445323e-02 9.977101e-01 -5.820227e-02 -1.435767e+01 6.829122e-01 -6.602248e-02 -7.275109e-01 -3.635664e+00 +-7.296178e-01 -1.420860e-02 -6.837075e-01 5.514462e+02 3.596392e-02 9.976034e-01 -5.911074e-02 -1.439062e+01 6.829089e-01 -6.771703e-02 -7.273582e-01 -3.918816e+00 +-7.302655e-01 -1.357713e-02 -6.830285e-01 5.511921e+02 3.772801e-02 9.974752e-01 -6.016486e-02 -1.442524e+01 6.821209e-01 -6.970561e-02 -7.279095e-01 -4.191369e+00 +-7.304961e-01 -1.278138e-02 -6.827973e-01 5.509485e+02 3.915432e-02 9.973963e-01 -6.055995e-02 -1.446942e+01 6.817936e-01 -7.097325e-02 -7.280937e-01 -4.451915e+00 +-7.307629e-01 -1.505120e-02 -6.824655e-01 5.507149e+02 3.764061e-02 9.973474e-01 -6.230005e-02 -1.450686e+01 6.815929e-01 -7.121496e-02 -7.282579e-01 -4.709150e+00 +-7.312988e-01 -1.696913e-02 -6.818461e-01 5.504909e+02 3.785055e-02 9.971402e-01 -6.541162e-02 -1.454971e+01 6.810062e-01 -7.364368e-02 -7.285652e-01 -4.953978e+00 +-7.322311e-01 -1.721391e-02 -6.808387e-01 5.502700e+02 4.101980e-02 9.967509e-01 -6.931738e-02 -1.458897e+01 6.798198e-01 -7.868419e-02 -7.291459e-01 -5.187168e+00 +-7.333745e-01 -1.575599e-02 -6.796422e-01 5.500554e+02 4.514141e-02 9.963963e-01 -7.180949e-02 -1.462769e+01 6.783245e-01 -8.334324e-02 -7.300204e-01 -5.411455e+00 +-7.354723e-01 -1.413992e-02 -6.774073e-01 5.498482e+02 4.717055e-02 9.962878e-01 -7.200995e-02 -1.465601e+01 6.759109e-01 -8.491498e-02 -7.320751e-01 -5.634374e+00 +-7.381073e-01 -1.589283e-02 -6.744961e-01 5.496541e+02 4.585638e-02 9.962290e-01 -7.365473e-02 -1.468342e+01 6.731232e-01 -8.529503e-02 -7.345951e-01 -5.853434e+00 +-7.396593e-01 -1.816195e-02 -6.727364e-01 5.494722e+02 4.353428e-02 9.962507e-01 -7.476091e-02 -1.470996e+01 6.715720e-01 -8.458468e-02 -7.360955e-01 -6.063502e+00 +-7.413028e-01 -2.107158e-02 -6.708398e-01 5.493020e+02 4.061461e-02 9.962670e-01 -7.617413e-02 -1.473540e+01 6.699408e-01 -8.371397e-02 -7.376797e-01 -6.264490e+00 +-7.432676e-01 -2.196605e-02 -6.686335e-01 5.491413e+02 3.860159e-02 9.963874e-01 -7.564384e-02 -1.476442e+01 6.678797e-01 -8.203391e-02 -7.397346e-01 -6.454319e+00 +-7.449860e-01 -2.197103e-02 -6.667182e-01 5.489914e+02 3.822636e-02 9.964090e-01 -7.554951e-02 -1.479272e+01 6.659840e-01 -8.176952e-02 -7.414709e-01 -6.627882e+00 +-7.466473e-01 -2.119940e-02 -6.648822e-01 5.488455e+02 3.925694e-02 9.963459e-01 -7.585257e-02 -1.481427e+01 6.640608e-01 -8.273634e-02 -7.430868e-01 -6.789741e+00 +-7.483367e-01 -2.036388e-02 -6.630064e-01 5.487101e+02 4.037817e-02 9.962765e-01 -7.617500e-02 -1.483607e+01 6.620890e-01 -8.377552e-02 -7.447280e-01 -6.943462e+00 +-7.494469e-01 -1.984353e-02 -6.617670e-01 5.485821e+02 4.142209e-02 9.961871e-01 -7.678158e-02 -1.485933e+01 6.607674e-01 -8.495547e-02 -7.457674e-01 -7.090666e+00 +-7.495949e-01 -2.138885e-02 -6.615512e-01 5.484668e+02 4.083203e-02 9.960798e-01 -7.847085e-02 -1.488391e+01 6.606362e-01 -8.583381e-02 -7.457831e-01 -7.227784e+00 +-7.493982e-01 -2.465580e-02 -6.616604e-01 5.483601e+02 3.853946e-02 9.959879e-01 -8.076391e-02 -1.490623e+01 6.609971e-01 -8.602434e-02 -7.454413e-01 -7.359144e+00 +-7.490146e-01 -2.550254e-02 -6.620625e-01 5.482576e+02 3.888181e-02 9.958448e-01 -8.234812e-02 -1.492158e+01 6.614117e-01 -8.742211e-02 -7.449107e-01 -7.479973e+00 +-7.485930e-01 -2.517037e-02 -6.625519e-01 5.481601e+02 4.007621e-02 9.957343e-01 -8.310861e-02 -1.493536e+01 6.618176e-01 -8.876707e-02 -7.443910e-01 -7.592526e+00 +-7.481094e-01 -2.535441e-02 -6.630908e-01 5.480696e+02 4.080461e-02 9.956210e-01 -8.410567e-02 -1.494831e+01 6.623197e-01 -8.997739e-02 -7.437989e-01 -7.701283e+00 +-7.484154e-01 -2.643416e-02 -6.627033e-01 5.479875e+02 4.048698e-02 9.955209e-01 -8.543316e-02 -1.496149e+01 6.619934e-01 -9.077032e-02 -7.439930e-01 -7.803179e+00 +-7.492064e-01 -2.710711e-02 -6.617816e-01 5.479093e+02 4.013519e-02 9.954680e-01 -8.621243e-02 -1.497381e+01 6.611195e-01 -9.115161e-02 -7.447231e-01 -7.899460e+00 +-7.493884e-01 -2.673567e-02 -6.615907e-01 5.478349e+02 4.040336e-02 9.954761e-01 -8.599355e-02 -1.498586e+01 6.608968e-01 -9.117303e-02 -7.449181e-01 -7.988359e+00 +-7.495688e-01 -2.716445e-02 -6.613688e-01 5.477689e+02 4.019787e-02 9.954453e-01 -8.644466e-02 -1.499990e+01 6.607047e-01 -9.138182e-02 -7.450628e-01 -8.070234e+00 +-7.498330e-01 -2.897316e-02 -6.609924e-01 5.477082e+02 3.887121e-02 9.953859e-01 -8.772626e-02 -1.501146e+01 6.604843e-01 -9.147360e-02 -7.452470e-01 -8.149215e+00 +-7.501165e-01 -3.111109e-02 -6.605735e-01 5.476514e+02 3.676171e-02 9.953865e-01 -8.862469e-02 -1.502425e+01 6.602832e-01 -9.076264e-02 -7.455121e-01 -8.224501e+00 +-7.504297e-01 -3.150549e-02 -6.601990e-01 5.475926e+02 3.645838e-02 9.953694e-01 -8.894144e-02 -1.503338e+01 6.599440e-01 -9.081406e-02 -7.458061e-01 -8.293718e+00 +-7.507402e-01 -3.048177e-02 -6.598940e-01 5.475348e+02 3.775101e-02 9.953227e-01 -8.892397e-02 -1.504238e+01 6.595181e-01 -9.167044e-02 -7.460780e-01 -8.355707e+00 +-7.510069e-01 -3.004570e-02 -6.596104e-01 5.474854e+02 3.849457e-02 9.952728e-01 -8.916377e-02 -1.505129e+01 6.591714e-01 -9.235400e-02 -7.463001e-01 -8.414013e+00 +-7.513826e-01 -3.100876e-02 -6.591378e-01 5.474387e+02 3.763652e-02 9.952552e-01 -8.972487e-02 -1.505801e+01 6.587926e-01 -9.222534e-02 -7.466504e-01 -8.468806e+00 +-7.516331e-01 -3.197586e-02 -6.588059e-01 5.473920e+02 3.696206e-02 9.952127e-01 -9.047382e-02 -1.505839e+01 6.585450e-01 -9.235393e-02 -7.468529e-01 -8.519784e+00 +-7.519000e-01 -3.238333e-02 -6.584814e-01 5.473512e+02 3.691082e-02 9.951585e-01 -9.108806e-02 -1.506466e+01 6.582432e-01 -9.279418e-02 -7.470644e-01 -8.566595e+00 +-7.521595e-01 -3.192181e-02 -6.582075e-01 5.473123e+02 3.761343e-02 9.951180e-01 -9.124367e-02 -1.507540e+01 6.579068e-01 -9.338721e-02 -7.472867e-01 -8.609266e+00 +-7.523580e-01 -3.177347e-02 -6.579877e-01 5.472762e+02 3.799452e-02 9.950804e-01 -9.149509e-02 -1.508357e+01 6.576578e-01 -9.383698e-02 -7.474495e-01 -8.650922e+00 +-7.525963e-01 -3.180879e-02 -6.577135e-01 5.472431e+02 3.836009e-02 9.950184e-01 -9.201574e-02 -1.509153e+01 6.573640e-01 -9.448063e-02 -7.476270e-01 -8.690682e+00 +-7.527704e-01 -3.216382e-02 -6.574969e-01 5.472128e+02 3.817896e-02 9.949911e-01 -9.238478e-02 -1.509721e+01 6.571751e-01 -9.464705e-02 -7.477719e-01 -8.727030e+00 +-7.529680e-01 -3.235819e-02 -6.572611e-01 5.471848e+02 3.821774e-02 9.949542e-01 -9.276626e-02 -1.510418e+01 6.569464e-01 -9.496904e-02 -7.479320e-01 -8.759968e+00 +-7.531569e-01 -3.243135e-02 -6.570410e-01 5.471603e+02 3.845242e-02 9.949059e-01 -9.318574e-02 -1.511054e+01 6.567161e-01 -9.544828e-02 -7.480732e-01 -8.788951e+00 +-7.532749e-01 -3.236957e-02 -6.569088e-01 5.471379e+02 3.866708e-02 9.948810e-01 -9.336274e-02 -1.511792e+01 6.565683e-01 -9.572853e-02 -7.481672e-01 -8.816118e+00 +-7.533679e-01 -3.254130e-02 -6.567936e-01 5.471198e+02 3.854064e-02 9.948731e-01 -9.349931e-02 -1.512423e+01 6.564689e-01 -9.575260e-02 -7.482513e-01 -8.840305e+00 +-7.534370e-01 -3.273971e-02 -6.567045e-01 5.471045e+02 3.840649e-02 9.948629e-01 -9.366221e-02 -1.513047e+01 6.563975e-01 -9.579026e-02 -7.483092e-01 -8.861118e+00 +-7.535444e-01 -3.326226e-02 -6.565550e-01 5.470930e+02 3.798678e-02 9.948473e-01 -9.399913e-02 -1.513445e+01 6.562986e-01 -9.577291e-02 -7.483981e-01 -8.878200e+00 +-7.536435e-01 -3.354829e-02 -6.564267e-01 5.470839e+02 3.772584e-02 9.948423e-01 -9.415688e-02 -1.513715e+01 6.561999e-01 -9.572495e-02 -7.484908e-01 -8.892504e+00 +-7.536860e-01 -3.372434e-02 -6.563689e-01 5.470765e+02 3.759051e-02 9.948359e-01 -9.427874e-02 -1.513958e+01 6.561588e-01 -9.572979e-02 -7.485262e-01 -8.904703e+00 +-7.536825e-01 -3.385513e-02 -6.563661e-01 5.470695e+02 3.767062e-02 9.948054e-01 -9.456758e-02 -1.513853e+01 6.561582e-01 -9.599963e-02 -7.484921e-01 -8.915003e+00 +-7.537628e-01 -3.424299e-02 -6.562538e-01 5.470626e+02 3.761401e-02 9.947560e-01 -9.510872e-02 -1.513608e+01 6.560693e-01 -9.637373e-02 -7.485220e-01 -8.925013e+00 +-7.538900e-01 -3.483846e-02 -6.560763e-01 5.470561e+02 3.749676e-02 9.946839e-01 -9.590605e-02 -1.513392e+01 6.559298e-01 -9.690333e-02 -7.485759e-01 -8.935045e+00 +-7.539395e-01 -3.538551e-02 -6.559902e-01 5.470403e+02 3.743900e-02 9.946110e-01 -9.668065e-02 -1.512626e+01 6.558762e-01 -9.745095e-02 -7.485517e-01 -8.948208e+00 +-7.540158e-01 -3.564216e-02 -6.558886e-01 5.470253e+02 3.744143e-02 9.945711e-01 -9.708980e-02 -1.511998e+01 6.557884e-01 -9.776463e-02 -7.485878e-01 -8.962217e+00 +-7.540505e-01 -3.574525e-02 -6.558430e-01 5.470010e+02 3.747880e-02 9.945495e-01 -9.729666e-02 -1.510952e+01 6.557463e-01 -9.794679e-02 -7.486009e-01 -8.980742e+00 +-7.541183e-01 -3.559709e-02 -6.557731e-01 5.469775e+02 3.743549e-02 9.945764e-01 -9.703786e-02 -1.510246e+01 6.556708e-01 -9.772720e-02 -7.486957e-01 -9.002351e+00 +-7.542569e-01 -3.551976e-02 -6.556179e-01 5.469518e+02 3.740767e-02 9.945889e-01 -9.692010e-02 -1.509710e+01 6.555129e-01 -9.762777e-02 -7.488469e-01 -9.025308e+00 +-7.541697e-01 -3.530982e-02 -6.557295e-01 5.469287e+02 3.754044e-02 9.946021e-01 -9.673360e-02 -1.509580e+01 6.556057e-01 -9.756990e-02 -7.487732e-01 -9.049068e+00 +-7.541294e-01 -3.539282e-02 -6.557714e-01 5.469063e+02 3.722492e-02 9.946376e-01 -9.649008e-02 -1.509607e+01 6.556700e-01 -9.717703e-02 -7.487680e-01 -9.075048e+00 +-7.542166e-01 -3.540170e-02 -6.556707e-01 5.468811e+02 3.726979e-02 9.946277e-01 -9.657439e-02 -1.509673e+01 6.555672e-01 -9.727469e-02 -7.488453e-01 -9.104930e+00 +-7.542172e-01 -3.530763e-02 -6.556751e-01 5.468532e+02 3.720266e-02 9.946515e-01 -9.635514e-02 -1.509810e+01 6.555704e-01 -9.706554e-02 -7.488697e-01 -9.137999e+00 +-7.540697e-01 -3.515154e-02 -6.558531e-01 5.468233e+02 3.716611e-02 9.946830e-01 -9.604356e-02 -1.509999e+01 6.557421e-01 -9.679902e-02 -7.487539e-01 -9.175395e+00 +-7.540193e-01 -3.508931e-02 -6.559143e-01 5.467919e+02 3.691236e-02 9.947305e-01 -9.564823e-02 -1.510353e+01 6.558143e-01 -9.633194e-02 -7.487508e-01 -9.215737e+00 +-7.541062e-01 -3.542066e-02 -6.557967e-01 5.467561e+02 3.643606e-02 9.947502e-01 -9.562624e-02 -1.511178e+01 6.557411e-01 -9.600696e-02 -7.488567e-01 -9.260733e+00 +-7.541258e-01 -3.567656e-02 -6.557602e-01 5.467179e+02 3.610870e-02 9.947604e-01 -9.564491e-02 -1.511966e+01 6.557366e-01 -9.580692e-02 -7.488862e-01 -9.307750e+00 +-7.542913e-01 -3.577040e-02 -6.555648e-01 5.466735e+02 3.607893e-02 9.947475e-01 -9.578999e-02 -1.513096e+01 6.555479e-01 -9.590561e-02 -7.490388e-01 -9.359431e+00 +-7.545094e-01 -3.550702e-02 -6.553281e-01 5.466270e+02 3.648797e-02 9.947213e-01 -9.590632e-02 -1.514222e+01 6.552742e-01 -9.627379e-02 -7.492310e-01 -9.413047e+00 +-7.545105e-01 -3.509751e-02 -6.553488e-01 5.465777e+02 3.695210e-02 9.947129e-01 -9.581568e-02 -1.515641e+01 6.552469e-01 -9.651043e-02 -7.492244e-01 -9.471357e+00 +-7.544032e-01 -3.491240e-02 -6.554823e-01 5.465255e+02 3.738936e-02 9.946778e-01 -9.601060e-02 -1.517102e+01 6.553457e-01 -9.693874e-02 -7.490828e-01 -9.532990e+00 +-7.544271e-01 -3.488434e-02 -6.554562e-01 5.464698e+02 3.756251e-02 9.946558e-01 -9.617132e-02 -1.518833e+01 6.553082e-01 -9.717481e-02 -7.490849e-01 -9.598824e+00 +-7.545844e-01 -3.503033e-02 -6.552673e-01 5.464115e+02 3.738498e-02 9.946572e-01 -9.622531e-02 -1.520466e+01 6.551372e-01 -9.710725e-02 -7.492433e-01 -9.667371e+00 +-7.546721e-01 -3.468052e-02 -6.551849e-01 5.463500e+02 3.768011e-02 9.946629e-01 -9.605160e-02 -1.522117e+01 6.550193e-01 -9.717488e-02 -7.493376e-01 -9.738525e+00 +-7.546355e-01 -3.459984e-02 -6.552313e-01 5.462866e+02 3.737200e-02 9.947210e-01 -9.556843e-02 -1.523978e+01 6.550791e-01 -9.660662e-02 -7.493588e-01 -9.816256e+00 +-7.547163e-01 -3.483725e-02 -6.551257e-01 5.462224e+02 3.659247e-02 9.947992e-01 -9.505505e-02 -1.525557e+01 6.550301e-01 -9.571224e-02 -7.495164e-01 -9.896104e+00 +-7.546719e-01 -3.515471e-02 -6.551599e-01 5.461573e+02 3.597705e-02 9.948438e-01 -9.482312e-02 -1.527589e+01 6.551153e-01 -9.513104e-02 -7.495159e-01 -9.976974e+00 +-7.547649e-01 -3.540548e-02 -6.550392e-01 5.460880e+02 3.619574e-02 9.947735e-01 -9.547476e-02 -1.529090e+01 6.549960e-01 -9.577061e-02 -7.495387e-01 -1.005776e+01 +-7.547628e-01 -3.466494e-02 -6.550812e-01 5.460136e+02 3.743926e-02 9.946989e-01 -9.577277e-02 -1.530813e+01 6.549286e-01 -9.681146e-02 -7.494639e-01 -1.014183e+01 +-7.545242e-01 -3.428325e-02 -6.553761e-01 5.459390e+02 3.818249e-02 9.946497e-01 -9.598982e-02 -1.532616e+01 6.551605e-01 -9.745051e-02 -7.491783e-01 -1.022762e+01 +-7.546515e-01 -3.354342e-02 -6.552678e-01 5.458625e+02 3.894975e-02 9.946408e-01 -9.577328e-02 -1.534651e+01 6.549687e-01 -9.779795e-02 -7.493007e-01 -1.031362e+01 +-7.548477e-01 -3.119225e-02 -6.551579e-01 5.457834e+02 4.182412e-02 9.945466e-01 -9.553879e-02 -1.536452e+01 6.545653e-01 -9.951862e-02 -7.494267e-01 -1.039832e+01 +-7.545625e-01 -2.864377e-02 -6.556027e-01 5.457058e+02 4.445095e-02 9.945213e-01 -9.461197e-02 -1.538555e+01 6.547210e-01 -1.005328e-01 -7.491553e-01 -1.048253e+01 +-7.545561e-01 -2.806020e-02 -6.556353e-01 5.456352e+02 4.443343e-02 9.946079e-01 -9.370517e-02 -1.540939e+01 6.547295e-01 -9.983792e-02 -7.492407e-01 -1.056600e+01 +-7.546962e-01 -2.850950e-02 -6.554547e-01 5.455695e+02 4.342215e-02 9.946943e-01 -9.326161e-02 -1.543089e+01 6.546360e-01 -9.884541e-02 -7.494540e-01 -1.064666e+01 +-7.544948e-01 -2.902322e-02 -6.556639e-01 5.455070e+02 4.304613e-02 9.946822e-01 -9.356464e-02 -1.545107e+01 6.548928e-01 -9.881781e-02 -7.492333e-01 -1.072449e+01 +-7.546417e-01 -2.875970e-02 -6.555065e-01 5.454452e+02 4.330867e-02 9.946770e-01 -9.349890e-02 -1.546603e+01 6.547063e-01 -9.894726e-02 -7.493792e-01 -1.079801e+01 +-7.551393e-01 -2.843622e-02 -6.549473e-01 5.453877e+02 4.326719e-02 9.947186e-01 -9.307436e-02 -1.548370e+01 6.541350e-01 -9.862182e-02 -7.499208e-01 -1.086851e+01 +-7.554524e-01 -2.776840e-02 -6.546148e-01 5.453342e+02 4.347488e-02 9.947752e-01 -9.236962e-02 -1.549952e+01 6.537596e-01 -9.824013e-02 -7.502982e-01 -1.093349e+01 +-7.556424e-01 -2.740798e-02 -6.544107e-01 5.452863e+02 4.297448e-02 9.948966e-01 -9.129044e-02 -1.551831e+01 6.535731e-01 -9.710587e-02 -7.506082e-01 -1.099491e+01 +-7.561071e-01 -2.709085e-02 -6.538869e-01 5.452426e+02 4.279155e-02 9.949582e-01 -9.070262e-02 -1.553084e+01 6.530474e-01 -9.656171e-02 -7.511358e-01 -1.104965e+01 diff --git a/tools/evaluate_odometry b/tools/evaluate_odometry new file mode 100755 index 0000000..589eaa0 Binary files /dev/null and b/tools/evaluate_odometry differ diff --git a/tools/plot-trajectory.py b/tools/plot-trajectory.py new file mode 100644 index 0000000..f012997 --- /dev/null +++ b/tools/plot-trajectory.py @@ -0,0 +1,129 @@ +import matplotlib.pyplot as plt +import sys +import time +import math + +''' + PLOT: + trajectory + error in 3 axes +''' + +# path to the ground truth +fname="../../Kitti/Ground-Truth/dataset/poses/00.txt" +# results +#gname='../pc-pipeline-lab/result' + sys.argv[1] + '/pose_result_kitti.txt' + +fname="../../Kitti/Ground-Truth/dataset/poses/00.txt" +#gname="./pc-code-examination-lab/result" + sys.argv[1] + "/pose_result_kitti.txt" + +gname="./result" + sys.argv[1] + "/pose_result_kitti.txt" +sname="./result" + sys.argv[1] + "/params.txt" + +with open(sname) as f: + specs = f.readlines() +# you may also want to remove whitespace characters like `\n` at the end of each line +specs = [x.strip() for x in specs] +print(specs) + +fig=plt.figure() +# # gt_xyz = fig.add_subplot(2,1,1) +# # ours_xyz = fig.add_subplot(2,1,2) +trajectory = fig.add_subplot(2,2,1) +z_com = fig.add_subplot(2,2,2) +y_com = fig.add_subplot(2,2,3) +x_com = fig.add_subplot(2,2,4) + +x=[] +y=[] +z=[] +d=[] +err=[] + +with open(fname) as f: + gt_content = f.readlines() +# you may also want to remove whitespace characters like `\n` at the end of each line +gt_content = [x.strip() for x in gt_content] + +with open(gname) as f: + ours_content2 = f.readlines() +ours_content2 = [x.strip() for x in ours_content2] + +n=len(ours_content2) +print(n) +if len(sys.argv) == 3: + n = int(sys.argv[2]) + +#groudtruth +for i, v in enumerate(gt_content[:n]): + # print(i.split(' ')[3], i.split(' ')[7], i.split(' ')[11]) + d.append(i) + # refer to the gt result files + x_gt = float(v.split(' ')[3]) + y_gt = float(v.split(' ')[7]) + z_gt = float(v.split(' ')[11]) + + x.append(x_gt) + y.append(y_gt) + z.append(z_gt) + +x1=[] +y1=[] +z1=[] +d1 =[] + +#ours +for i, v in enumerate(ours_content2[:n]): + d1.append(i) + x_ = float(v.split(' ')[3]) + y_ = float(v.split(' ')[7]) + z_ = float(v.split(' ')[11]) + + x1.append(x_) + y1.append(y_) + z1.append(z_) + +# ours_xyz.clear() +# gt_xyz.clear() +# trajectory.clear() + +# plt.subplot(221) +# gt_xyz.set_title('Position(xyz) - Ground Truth') +# gt_xyz.axis([0, n + 100, -200, 600]) + +# gt_xyz.plot(d, x, 'r', label='x') +# gt_xyz.plot(d, y, 'g', label='y') +# gt_xyz.plot(d, z,'b', label='z') +# gt_xyz.legend(bbox_to_anchor=(1.06, 0.60)) + +# ours_xyz.set_title('Position(xyz) - Estimated Result') +# ours_xyz.axis([0, n + 100, -200, 600]) +# ours_xyz.plot(d1, x1, 'r', label='x') +# ours_xyz.plot(d1, y1, 'g', label='y') +# ours_xyz.plot(d1, z1,'b', label='z') +# ours_xyz.legend(bbox_to_anchor=(1.06, 0.60)) + +trajectory.set_title("Trajectory") +trajectory.plot(z, x, 'r--', label='GT') +trajectory.plot(z1, x1, 'g--', label='EST') +# trajectory.legend(loc='upper right') +# trajectory.legend(bbox_to_anchor=(1.08, 0.60)) +trajectory.legend() + + +z_com.set_title("Z value comparison") +z_com.plot(d, z, 'r', label='z - GT') +z_com.plot(d1, z1, 'g', label='z - EST') +z_com.legend() + +y_com.set_title("Y value comparison") +y_com.plot(d, y, 'r', label='y - GT') +y_com.plot(d1, y1, 'g', label='y - EST') +y_com.legend() + +x_com.set_title("X value comparison") +x_com.plot(d, x, 'r', label='x - GT') +x_com.plot(d1, x1, 'g', label='x - EST') +x_com.legend() + +plt.show() \ No newline at end of file diff --git a/utils/000000.txt b/utils/000000.txt deleted file mode 100644 index f9bcb70..0000000 --- a/utils/000000.txt +++ /dev/null @@ -1,124668 +0,0 @@ --0.0229897387326,-1.99799454212,52.8979415894 --0.192914292216,-2.02695393562,53.7505264282 --0.361839264631,-2.02891373634,53.8031158447 --1.29646635056,-2.66471171379,72.6006622314 --1.51337611675,-2.64766335487,72.1182556152 --1.79826390743,-2.72760295868,74.4768447876 --1.9991787672,-2.6875576973,73.2674407959 --2.19309592247,-2.64851379395,72.1100234985 --2.44999289513,-2.67745876312,72.9786224365 --2.67789888382,-2.67640924454,72.9362106323 --11.1593084335,-2.39561200142,63.744846344 --11.2702636719,-2.39759063721,63.7866477966 --11.587143898,-2.4195318222,64.3972625732 --11.7840614319,-2.41849350929,64.330871582 --11.9010057449,-2.4034678936,63.8394851685 --12.0139503479,-2.38744354248,63.3400878906 --12.1928739548,-2.38340806961,63.1996994019 --12.4007892609,-2.38536810875,63.2053108215 --12.5437345505,-2.39334177971,63.4091186523 --11.1761455536,-2.12455773354,55.5896339417 --11.3540697098,-2.12552261353,55.5712432861 --11.5349931717,-2.12648701668,55.5648498535 --11.6899251938,-2.12345576286,55.4354629517 --11.86784935,-2.12342095375,55.4140739441 --11.976805687,-2.12740063667,55.498878479 --14.7948999405,-2.54394245148,67.5026702881 --14.6839160919,-2.49395537376,66.0092697144 --14.6908950806,-2.46294903755,65.0738677979 --14.8908138275,-2.46191191673,65.0094909668 --10.0883016586,-1.71567070484,43.44373703 --10.1932487488,-1.71164739132,43.278339386 --10.2492208481,-1.70963525772,43.2141456604 --10.3491706848,-1.70461285114,43.029750824 --10.312163353,-1.67961227894,42.2913398743 --10.5140800476,-1.68957400322,42.5399551392 --10.5900373459,-1.68155562878,42.2755584717 --10.729973793,-1.68252718449,42.2711715698 --15.51445961,-2.3117723465,60.2901496887 --15.3674955368,-2.27979302406,59.3309402466 --11.5056638718,-1.72338438034,43.3178253174 --15.2154884338,-2.18680262566,56.5457344055 --15.1724824905,-2.15880441666,55.6893310547 --11.6445627213,-1.68934512138,42.2326278687 --15.3683853149,-2.13976478577,55.0415534973 --15.4453516006,-2.13775062561,54.9823608398 --15.6442718506,-2.14171552658,55.0259819031 --8.74439907074,-1.2787694931,30.4229774475 --8.82835388184,-1.27674973011,30.3545818329 --9.8160276413,-1.38359200954,33.3532600403 --9.91397762299,-1.38257050514,33.2968635559 --16.4759311676,-2.14756917953,54.9822731018 --9.73100566864,-1.34358859062,32.1282424927 --9.74398231506,-1.33258020878,31.810842514 --9.84193325043,-1.33255898952,31.7754497528 --9.5999879837,-1.29458904266,30.6530227661 --9.68894195557,-1.29356908798,30.5976257324 --11.7232847214,-1.50125455856,36.4142150879 --11.7322626114,-1.49024760723,36.053817749 --14.2384710312,-1.74786841869,43.2826690674 --14.2284555435,-1.73286509514,42.7992668152 --14.1944484711,-1.7148655653,42.2528648376 --14.1624403,-1.69686555862,41.7234611511 --14.1274328232,-1.67986595631,41.1940612793 --14.0444488525,-1.66487574577,40.7428512573 --14.0234375,-1.64987421036,40.2714500427 --11.5681743622,-1.3872294426,32.8947906494 --13.96641922,-1.61787319183,39.3096466064 --13.9733991623,-1.60686743259,38.9422492981 --13.9633846283,-1.59286403656,38.5308456421 --13.8804016113,-1.57887387276,38.1166381836 --13.8613891602,-1.56587195396,37.6952400208 --13.8393774033,-1.55187034607,37.2728347778 --13.8223657608,-1.53886818886,36.8714332581 --13.8003549576,-1.5258667469,36.4630317688 --13.7853412628,-1.51386415958,36.0806312561 --13.7623310089,-1.50086271763,35.6842269897 --13.6933422089,-1.48887038231,35.3400230408 --13.6693315506,-1.47686910629,34.9506187439 --13.6443223953,-1.46386802197,34.5662155151 --13.6463041306,-1.45486307144,34.2558174133 --13.6682796478,-1.44685542583,33.999420166 --13.6982526779,-1.43984651566,33.7650222778 --13.7362241745,-1.43383669853,33.5566291809 --13.5022859573,-1.40786719322,32.8364028931 --13.4942712784,-1.398863554,32.5249977112 --13.4822568893,-1.38886070251,32.2116012573 --13.4662437439,-1.37785840034,31.8901977539 --13.4502315521,-1.3678560257,31.5757980347 --13.4312200546,-1.35785400867,31.2573947906 --13.3672304153,-1.34886062145,30.9731845856 --13.3452196121,-1.33785903454,30.6557807922 --13.3911876678,-1.33384823799,30.5003890991 --13.4971389771,-1.33482921124,30.4790000916 --13.4981212616,-1.32682454586,30.224603653 --13.489107132,-1.318821311,29.9502010345 --13.3291378021,-1.29783856869,29.3487815857 --13.2281589508,-1.28584992886,29.0035648346 --13.2201442719,-1.27784657478,28.7471656799 --13.2081308365,-1.26984357834,28.4837627411 --13.1941175461,-1.260841012,28.2213630676 --13.1851034164,-1.25383770466,27.9709606171 --13.1770877838,-1.24583423138,27.7265586853 --13.1590766907,-1.23783230782,27.4671592712 --13.1090831757,-1.23083662987,27.2519512177 --13.1070661545,-1.22383236885,27.0295505524 --9.11023807526,-0.909355461597,18.6385993958 --9.15120697021,-0.908343970776,18.5732002258 --9.20617294312,-0.908330619335,18.5368041992 --9.27813434601,-0.909315228462,18.5364151001 --13.2079601288,-1.20279932022,26.2807636261 --13.1989459991,-1.19579613209,26.0573616028 --9.08014678955,-0.883325755596,17.7863712311 --9.11511802673,-0.882315218449,17.7169742584 --9.16808414459,-0.882302343845,17.6825771332 --9.24604320526,-0.883286356926,17.6971893311 --9.5789270401,-0.903237760067,18.1928272247 --9.64090061188,-0.906226933002,18.2416400909 --9.88480949402,-0.919190049171,18.5602664948 --9.96776771545,-0.921173870564,18.5738754272 --12.8928918839,-1.12479865551,23.845916748 --12.8998727798,-1.11979353428,23.6805171967 --12.9938297272,-1.12077724934,23.6741313934 --13.0667915344,-1.12076401711,23.6307430267 --9.7107629776,-0.885180950165,17.4950275421 --9.75073337555,-0.884170234203,17.4356269836 --9.7937040329,-0.883159220219,17.3832302094 --9.86266613007,-0.884145259857,17.3788433075 --13.5065889359,-1.12769126892,23.6280136108 --13.5895490646,-1.12867712975,23.6006278992 --13.6555213928,-1.13066709042,23.6274356842 --13.7394800186,-1.13165307045,23.6010494232 --13.818441391,-1.13163971901,23.5656642914 --13.8954029083,-1.1316267252,23.5252761841 --13.9923591614,-1.13361144066,23.5208950043 --14.0903148651,-1.13459610939,23.5155105591 --14.1362857819,-1.13258707523,23.4251194 --14.216255188,-1.13557589054,23.4739341736 --14.3691949844,-1.14055418968,23.5585613251 --14.4591531754,-1.14154016972,23.5381774902 --14.534116745,-1.14152801037,23.4947948456 --14.6320734024,-1.14351320267,23.4854068756 --14.7180328369,-1.14450001717,23.4590263367 --14.8479804993,-1.14748179913,23.5006504059 --14.8959589005,-1.1484746933,23.4954605103 --14.9949159622,-1.15046036243,23.4870796204 --15.1128664017,-1.15244376659,23.5077018738 --15.1938276291,-1.15343153477,23.4703159332 --15.2837877274,-1.15441846848,23.4469356537 --15.3967409134,-1.15640282631,23.4585590363 --15.4557161331,-1.15839481354,23.4673709869 --15.561671257,-1.16038024426,23.4669933319 --15.6466331482,-1.16036820412,23.4346122742 --11.5207805634,-0.905828952789,17.1304569244 --15.8575439453,-1.16433954239,23.4288539886 --15.9575014114,-1.16632604599,23.416475296 --11.7246751785,-0.908793032169,17.0822925568 --16.1244316101,-1.16930425167,23.4229125977 --16.2243900299,-1.1712911129,23.409532547 --12.6113862991,-0.952684998512,18.0674495697 --12.6223669052,-0.950680017471,17.962053299 --11.9325437546,-0.906751275063,16.8655223846 --11.9985084534,-0.907739937305,16.8451328278 --12.0734729767,-0.908727765083,16.8377456665 --12.0874614716,-0.907724320889,16.8015499115 --12.0974416733,-0.905719161034,16.7031497955 --16.9810752869,-1.18219554424,23.3037033081 --12.0474243164,-0.896716535091,16.4143390656 --12.1333847046,-0.89870351553,16.4229545593 --12.1143741608,-0.89470154047,16.2875442505 --12.3513011932,-0.906674802303,16.5523929596 --12.4622554779,-0.909659385681,16.5910129547 --12.6891765594,-0.919632136822,16.7826557159 --12.7501449585,-0.919622302055,16.7542724609 --12.5321893692,-0.904641151428,16.3588256836 --12.6231489182,-0.907628297806,16.3704452515 --8.89514255524,-0.698001563549,11.4111061096 --8.92611694336,-0.697993040085,11.3767108917 --8.96009063721,-0.696984171867,11.3453102112 --9.00206184387,-0.69797462225,11.3249177933 --9.05503177643,-0.698964059353,11.3175230026 --12.0941925049,-0.86065775156,15.0317296982 --12.213145256,-0.864642322063,15.0823545456 --12.1321601868,-0.858648478985,14.9341392517 --12.9389266968,-0.899566054344,15.8259019852 --13.0518827438,-0.90255188942,15.862528801 --12.8909101486,-0.891564190388,15.5650930405 --12.77592659,-0.882572054863,15.3276720047 --12.9018774033,-0.886556744576,15.3782920837 --12.7149200439,-0.87557297945,15.1070556641 --12.7498960495,-0.875566422939,15.0516633987 --13.4856863022,-0.911493897438,15.8214235306 --13.5226612091,-0.91048759222,15.7630300522 --13.3546915054,-0.89950042963,15.466591835 --14.5143709183,-0.956390321255,16.7074508667 --13.7145671844,-0.912461638451,15.6828718185 --13.6685733795,-0.908464550972,15.580663681 --13.3046541214,-0.887495100498,15.0671806335 --20.4947547913,-1.25184118748,23.0904197693 --13.6085453033,-0.898462116718,15.2164468765 --15.6949872971,-1.00127267838,17.4475288391 --14.3103351593,-0.929394483566,15.8018102646 --13.5195264816,-0.886462211609,14.8302268982 --13.5345163345,-0.886459589005,14.8000335693 --13.6934604645,-0.89144307375,14.8796701431 --13.7874221802,-0.894432425499,14.8872938156 --15.9928398132,-1.00123929977,17.1684093475 --12.0948314667,-0.805573344231,12.8881053925 --12.0938177109,-0.803570091724,12.8047018051 --12.0928030014,-0.801566898823,12.7222995758 --12.073800087,-0.799566864967,12.6620950699 --12.1187744141,-0.800559818745,12.628704071 --12.1967401505,-0.801550149918,12.63032341 --12.214720726,-0.80054551363,12.5689268112 --12.2207050323,-0.799541831017,12.4955282211 --12.2296886444,-0.797537982464,12.4251270294 --12.195690155,-0.795539259911,12.3509178162 --12.1956758499,-0.793536126614,12.2725152969 --12.1896619797,-0.791533529758,12.1881103516 --12.1856498718,-0.789530754089,12.1077127457 --12.1886339188,-0.787527501583,12.0333089828 --12.1946191788,-0.785524010658,11.9639139175 --12.1726093292,-0.78352278471,11.8665084839 --12.1556072235,-0.781522631645,11.8123035431 --12.1855859756,-0.781517267227,11.7659072876 --12.1955699921,-0.779513537884,11.7015113831 --12.196554184,-0.778510570526,11.6281099319 --12.2135362625,-0.777506351471,11.5697097778 --12.1945266724,-0.774504840374,11.4783039093 --12.2035112381,-0.773501336575,11.4139051437 --12.1775102615,-0.771501779556,11.3537015915 --12.1744966507,-0.769499182701,11.2782974243 --12.1674842834,-0.767496883869,11.1998939514 --12.1824674606,-0.766492903233,11.1424970627 --12.1614589691,-0.763491630554,11.0520896912 --12.1664438248,-0.762488484383,10.9866924286 --12.1634302139,-0.760485947132,10.9132871628 --12.1434288025,-0.759485960007,10.8600797653 --12.1464138031,-0.757482945919,10.7936811447 --12.1533985138,-0.756479799747,10.7312831879 --12.1243925095,-0.753479063511,10.6368741989 --12.0843887329,-0.75047904253,10.5334625244 --12.0803756714,-0.748476624489,10.4630632401 --12.0533752441,-0.746477067471,10.4048490524 --12.102350235,-0.747471094131,10.3814668655 --12.1173334122,-0.746467471123,10.3270664215 --12.1093215942,-0.744465410709,10.253663063 --12.1123075485,-0.743462562561,10.1902627945 --12.1052951813,-0.741460442543,10.1188602448 --12.1052818298,-0.740457832813,10.0534591675 --12.0902786255,-0.738457500935,10.0082530975 --12.0922651291,-0.7374548316,9.94585704803 --12.0762548447,-0.735453307629,9.86744594574 --12.0902385712,-0.734449863434,9.8150510788 --12.0782279968,-0.732448160648,9.74164581299 --12.0812139511,-0.731445491314,9.68024253845 --12.0772027969,-0.730443298817,9.61484622955 --12.0691976547,-0.729442477226,9.57664108276 --12.054186821,-0.727440953255,9.5022354126 --12.0551738739,-0.726438462734,9.44083499908 --12.0481624603,-0.724436402321,9.37343120575 --12.0501489639,-0.7234339118,9.3130273819 --12.0351390839,-0.721432387829,9.24062538147 --11.9951353073,-0.718432247639,9.14921379089 --11.9791326523,-0.71743196249,9.10701084137 --11.9761199951,-0.715429723263,9.04460811615 --11.9711084366,-0.714427649975,8.98120689392 --12.013086319,-0.714423120022,8.95281505585 --12.0200719833,-0.713420450687,8.89841461182 --12.0130605698,-0.712418556213,8.83401107788 --5.562479496,-0.439746230841,4.00270462036 --12.0430412292,-0.712414801121,8.79762077332 --5.56546211243,-0.439739882946,3.97830986977 --5.58743953705,-0.439732372761,3.96690607071 --11.9969940186,-0.705407202244,8.50179862976 --11.9799861908,-0.703405916691,8.43239212036 --11.9789791107,-0.703404903412,8.40319156647 --11.9679698944,-0.701403260231,8.33878898621 --11.9629583359,-0.700401365757,8.27838420868 --11.9719429016,-0.699398875237,8.22798252106 --11.9649324417,-0.698397159576,8.16758441925 --11.9679193497,-0.697394907475,8.11317920685 --11.9609088898,-0.695393204689,8.052775383 --11.941906929,-0.69439303875,8.01257228851 --11.9408941269,-0.693391084671,7.95717334747 --11.9498796463,-0.692388653755,7.90777111053 --11.9298715591,-0.690387547016,7.8393611908 --11.8948669434,-0.688386976719,7.76195001602 --11.8838567734,-0.687385499477,7.70155191422 --11.8888435364,-0.68638330698,7.65014505386 --11.8808393478,-0.685382664204,7.61794042587 --11.8828268051,-0.684380710125,7.56654500961 --11.8788146973,-0.683378875256,7.51013755798 --11.8688058853,-0.682377398014,7.45073270798 --11.872792244,-0.681375384331,7.40033102036 --11.8687820435,-0.680373728275,7.34593343735 --11.8617715836,-0.678372144699,7.2895321846 --11.8597660065,-0.678371250629,7.261323452 --11.8517551422,-0.677369773388,7.20492362976 --11.845744133,-0.676368236542,7.14952087402 --11.8437328339,-0.675366520882,7.09611368179 --11.840722084,-0.674364864826,7.0437169075 --11.845708847,-0.673362970352,6.99531412125 --11.8486967087,-0.672361254692,6.94691991806 --11.8276948929,-0.671361029148,6.90870952606 --11.820684433,-0.670359551907,6.85330057144 --11.8246717453,-0.669357717037,6.8059053421 --11.8206615448,-0.668356239796,6.75350379944 --11.8176498413,-0.66735470295,6.70210361481 --11.8276367188,-0.667352855206,6.65669488907 --11.8226261139,-0.666351437569,6.60429239273 --11.8056230545,-0.664351046085,6.57008743286 --11.803612709,-0.664349555969,6.51968622208 --11.7986011505,-0.663348138332,6.46727895737 --11.7995910645,-0.662346661091,6.41988611221 --11.800579071,-0.661345124245,6.37148332596 --11.8475589752,-0.66234266758,6.34809446335 --11.8695487976,-0.663341462612,6.33590221405 --11.9515228271,-0.665338456631,6.3315281868 --12.0264978409,-0.667335689068,6.32315444946 --12.0924739838,-0.669333219528,6.30877161026 --12.2554225922,-0.673328101635,6.29602336884 --12.266409874,-0.673326969147,6.25262832642 --12.2764024734,-0.673326313496,6.2324256897 --12.3463792801,-0.675324320793,6.21904754639 --12.5053405762,-0.680321097374,6.25070095062 --12.3683547974,-0.67432230711,6.13225793839 --16.8705368042,-0.844262242317,8.33739471436 --19.4190635681,-0.935249567032,9.27151203156 --19.7149944305,-0.941269099712,9.07084369659 --14.8518047333,-0.757303774357,6.63391971588 --14.7858066559,-0.754305481911,6.54649066925 --14.7118120193,-0.751307070255,6.45807218552 --14.6188192368,-0.74730861187,6.36063718796 --14.4648418427,-0.740309536457,6.26538562775 --14.2798643112,-0.733310878277,6.12891387939 --14.2348632812,-0.731312036514,6.05650568008 --14.2438545227,-0.730313241482,6.00610399246 --14.2558441162,-0.730314433575,5.95770835876 --14.2138433456,-0.728315472603,5.88729858398 --14.1498498917,-0.725315868855,5.83307027817 --14.0818529129,-0.722316861153,5.7526512146 --14.0078573227,-0.718317687511,5.66922044754 --13.9428596497,-0.715318441391,5.59079885483 --11.6811962128,-0.632305264473,4.57717418671 --11.694185257,-0.631304740906,4.5397810936 --11.6791820526,-0.631304264069,4.51156806946 --11.6751728058,-0.630303680897,4.46716499329 --11.6711626053,-0.62930303812,4.42276096344 --11.6641550064,-0.629302382469,4.3783659935 --11.6731433868,-0.628301978111,4.33896398544 --11.6721343994,-0.628301441669,4.29656600952 --11.6691255569,-0.627300858498,4.25316333771 --11.6571216583,-0.62730050087,4.2269525528 --11.6541128159,-0.626299977303,4.18354845047 --11.6551036835,-0.625299572945,4.14214897156 --11.6490955353,-0.625299036503,4.09774255753 --11.6610832214,-0.625298857689,4.06034612656 --11.6510763168,-0.624298334122,4.014939785 --11.64706707,-0.623297870159,3.97254300117 --11.6440629959,-0.623297691345,3.95033717155 --11.6440534592,-0.623297393322,3.90893626213 --11.6340456009,-0.622296929359,3.86352491379 --11.643034935,-0.62229681015,3.82613444328 --11.6460256577,-0.621296703815,3.78573179245 --11.6370182037,-0.620296299458,3.74132394791 --11.6320104599,-0.620296001434,3.69892287254 --11.6350049973,-0.620296001434,3.67871618271 --11.6010007858,-0.6182949543,3.62730622292 --11.4910068512,-0.614292025566,3.55085754395 --11.4859981537,-0.613291680813,3.5094575882 --11.4779901505,-0.61329126358,3.46705508232 --11.4819803238,-0.61229121685,3.42764806747 --11.4829711914,-0.612291097641,3.38824939728 --11.4599704742,-0.61129039526,3.3610367775 --11.4689598083,-0.611290574074,3.32464504242 --11.4779500961,-0.611290752888,3.2872428894 --11.4509449005,-0.609289824963,3.23983263969 --11.4499359131,-0.609289765358,3.19942426682 --11.4599266052,-0.609290063381,3.16302776337 --11.4499187469,-0.608289778233,3.12062001228 --11.4589128494,-0.608290076256,3.10342168808 --11.45890522,-0.60829013586,3.06502890587 --11.4368991852,-0.607289433479,3.01961731911 --11.4538888931,-0.60729020834,2.98522233963 --11.434882164,-0.606289625168,2.94081068039 --11.436873436,-0.606289863586,2.90240955353 --11.4368648529,-0.6062900424,2.86300206184 --11.4378614426,-0.605290174484,2.84380102158 --11.4338541031,-0.605290234089,2.80440187454 --11.4198474884,-0.604289889336,2.76199269295 --11.4308376312,-0.604290604591,2.7265996933 --11.4518270493,-0.605291903019,2.69219589233 --11.4198226929,-0.60329079628,2.64578080177 --11.4048204422,-0.603290259838,2.6235806942 --11.4098119736,-0.602290868759,2.58617782593 --11.4487991333,-0.603293120861,2.55678868294 --11.486787796,-0.604295372963,2.52740359306 --11.504778862,-0.605296850204,2.49300837517 --11.5447673798,-0.606299459934,2.46362304688 --11.5797557831,-0.607301831245,2.43323922157 --11.5817518234,-0.607302308083,2.41403532028 --11.4827537537,-0.603297770023,2.35460042953 --11.5217428207,-0.604300498962,2.324208498 --11.6997184753,-0.610310971737,2.32388353348 --11.7487068176,-0.611314594746,2.29550457001 --11.7796964645,-0.612317323685,2.26210713387 --11.802687645,-0.613319694996,2.22771477699 --11.8346815109,-0.614322066307,2.21452641487 --11.8656721115,-0.615325093269,2.18214392662 --11.8966617584,-0.615328133106,2.14875245094 --11.9386520386,-0.617331981659,2.11736679077 --11.9736423492,-0.618335425854,2.08498358727 --11.9986333847,-0.618338465691,2.04958581924 --12.0306253433,-0.61934196949,2.01620030403 --12.0696182251,-0.620345234871,2.00402188301 --12.09760952,-0.621348619461,1.96963489056 --12.1436004639,-0.622353315353,1.93724572659 --12.1745920181,-0.623357057571,1.9028583765 --12.2025842667,-0.624360799789,1.86746621132 --12.2465744019,-0.625365674496,1.8350867033 --12.2745666504,-0.626369535923,1.7996981144 --12.3025617599,-0.627372443676,1.7845133543 --12.354552269,-0.628378272057,1.75213062763 --12.3825454712,-0.629382371902,1.71674704552 --12.4235372543,-0.630387544632,1.68236112595 --12.4535293579,-0.63139206171,1.64596879482 --12.4845228195,-0.632396638393,1.61058712006 --12.6165113449,-0.636407911777,1.60844027996 --12.6615037918,-0.638413906097,1.57406210899 --12.7104959488,-0.639420330524,1.53968286514 --12.7614889145,-0.6414270401,1.50530493259 --12.8024806976,-0.642433166504,1.46891820431 --12.835474968,-0.643438696861,1.43153035641 --12.8674688339,-0.644444227219,1.39414489269 --12.9204616547,-0.645451664925,1.35876595974 --12.9564580917,-0.647456228733,1.3425860405 --12.987452507,-0.648461997509,1.3041973114 --13.0414457321,-0.649469792843,1.26882505417 --13.0714406967,-0.650475740433,1.22943127155 --13.0944356918,-0.651481151581,1.19004297256 --13.1544294357,-0.653489887714,1.1546754837 --13.1864242554,-0.654496312141,1.11528646946 --13.2354211807,-0.65550249815,1.09911084175 --13.2714157104,-0.656509578228,1.05972385406 --13.3134117126,-0.658517181873,1.02134621143 --13.3414077759,-0.65852367878,0.980956375599 --13.3904027939,-0.660532176495,0.942580699921 --13.4433984756,-0.662541270256,0.904206633568 --13.4753952026,-0.663546383381,0.885019302368 --13.5123920441,-0.664554178715,0.844634830952 --13.5573883057,-0.665562927723,0.804250836372 --13.5903844833,-0.666570484638,0.76387155056 --13.6413812637,-0.668580055237,0.723491728306 --13.6763782501,-0.669588148594,0.68210709095 --13.736374855,-0.671598851681,0.642741024494 --13.7593736649,-0.672603607178,0.621546030045 --13.8163700104,-0.673614263535,0.58117556572 --13.8563680649,-0.675623416901,0.538790464401 --13.9183654785,-0.677634835243,0.498426437378 --13.9643640518,-0.678644895554,0.456046581268 --13.9763631821,-0.67965143919,0.411648154259 --14.0303611755,-0.680662453175,0.370282530785 --14.0893592834,-0.682671606541,0.350110113621 --14.1263580322,-0.683681070805,0.306729108095 --14.1903562546,-0.686693847179,0.263356089592 --14.2173557281,-0.686702549458,0.218968570232 --14.2683553696,-0.688714027405,0.175598189235 --14.3253555298,-0.690726459026,0.131223499775 --14.3463554382,-0.691734850407,0.0858315378428 --14.4053544998,-0.693744719028,0.0646657124162 --14.4613542557,-0.695757448673,0.0192897934467 --14.5163555145,-0.696770250797,-0.0260835886002 --14.5463562012,-0.697780072689,-0.071464329958 --14.6173563004,-0.70079523325,-0.11783323437 --14.6333580017,-0.700803756714,-0.16422508657 --14.6713590622,-0.702814996243,-0.210604384542 --14.7073602676,-0.703822851181,-0.233784452081 --14.7593622208,-0.705836176872,-0.281161040068 --14.8103637695,-0.706849515438,-0.328535556793 --14.8483657837,-0.708861351013,-0.375914722681 --14.9273681641,-0.710878610611,-0.424274504185 --14.9743709564,-0.712892055511,-0.472650825977 --15.0373744965,-0.71490752697,-0.521013617516 --15.0793762207,-0.71691685915,-0.546194493771 --12.6863574982,-0.635606229305,-0.528780639172 --12.7333583832,-0.63661724329,-0.570154905319 --12.7163572311,-0.636619925499,-0.610569179058 --15.2833909988,-0.72397518158,-0.744683265686 --15.3753957748,-0.726995944977,-0.797036767006 --12.5813531876,-0.631616175175,-0.725837051868 --12.5713529587,-0.631617307663,-0.746048986912 --15.5104084015,-0.732035398483,-0.924959421158 --15.5554141998,-0.733050405979,-0.977341473103 --15.6334209442,-0.736070096493,-1.03069746494 --15.6804265976,-0.738085627556,-1.08307147026 --15.7334337234,-0.739102244377,-1.13644516468 --15.7784395218,-0.741117835045,-1.18881571293 --15.8424444199,-0.743131756783,-1.21798121929 --15.9014511108,-0.745149731636,-1.27234816551 --15.9614591599,-0.748168170452,-1.32771837711 --16.0234680176,-0.750187039375,-1.38308334351 --16.0834751129,-0.752205729485,-1.43844735622 --16.1454849243,-0.75422501564,-1.49481344223 --16.1974906921,-0.756237983704,-1.52498626709 --16.2544975281,-0.758256793022,-1.58135271072 --16.3335094452,-0.761279463768,-1.64071249962 --16.3675174713,-0.762295126915,-1.69609296322 --16.4445285797,-0.765317797661,-1.75544786453 --16.5045394897,-0.767337918282,-1.81381297112 --16.5695495605,-0.770359218121,-1.87317550182 --16.6425590515,-0.772376477718,-1.90733683109 --16.6965694427,-0.774396240711,-1.96570050716 --16.7685813904,-0.77741920948,-2.02705931664 --16.8355941772,-0.779441654682,-2.08842158318 --16.8976078033,-0.782463550568,-2.14978647232 --16.9626197815,-0.784486234188,-2.21215176582 --17.0296344757,-0.787509322166,-2.27451038361 --17.0976428986,-0.789526939392,-2.3106751442 --17.1646556854,-0.791550517082,-2.37403535843 --14.6245031357,-0.705123126507,-2.09878611565 --14.7055130005,-0.708146333694,-2.15714526176 --17.377702713,-0.799624860287,-2.5691113472 --14.7255277634,-0.709168314934,-2.2549328804 --14.843542099,-0.7131986022,-2.31926751137 --14.7665405273,-0.711189687252,-2.3325111866 --14.7065420151,-0.709188222885,-2.37093806267 --14.3755226135,-0.698137581348,-2.36851382256 --14.3395261765,-0.697140157223,-2.40993523598 --14.07351017,-0.688100278378,-2.41447639465 --14.0255126953,-0.687100231647,-2.45290517807 --13.9395103455,-0.684092998505,-2.48435044289 --14.1565313339,-0.692137956619,-2.5424284935 --14.2455453873,-0.695163905621,-2.60378146172 --14.1275415421,-0.691150844097,-2.63024735451 --14.0595417023,-0.689146995544,-2.66468596458 --13.9665393829,-0.686138272285,-2.69413661957 --13.7665271759,-0.679108500481,-2.70364665985 --13.8625421524,-0.683136105537,-2.76598954201 --13.6525239944,-0.676099359989,-2.74930167198 --13.7095365524,-0.678119599819,-2.80567717552 --13.9525671005,-0.687176883221,-2.89693760872 --13.7635536194,-0.681148529053,-2.90644717216 --13.5975427628,-0.675124228001,-2.91894102097 --13.5755472183,-0.675128757954,-2.95935320854 --13.7135677338,-0.680166184902,-3.03267717361 --13.7425746918,-0.681176662445,-3.06085681915 --13.6825742722,-0.679173588753,-3.0932867527 --13.4025497437,-0.670124709606,-3.0788435936 --13.3305463791,-0.668118834496,-3.10828948021 --13.48757267,-0.673160851002,-3.186596632 --13.3925676346,-0.670149922371,-3.21004867554 --13.4295787811,-0.672167241573,-3.26343107224 --13.4345827103,-0.672172904015,-3.28662538528 --13.4015855789,-0.6721752882,-3.32404565811 --13.267575264,-0.667155623436,-3.33752346039 --13.3075876236,-0.669173777103,-3.39190459251 --13.295592308,-0.669180512428,-3.43330907822 --13.2375926971,-0.667177200317,-3.46374225616 --13.199590683,-0.666173577309,-3.47696709633 --13.0745811462,-0.662154853344,-3.48943209648 --13.0915899277,-0.663168072701,-3.53782296181 --12.8135576248,-0.654114544392,-3.51138901711 --12.9545850754,-0.659155726433,-3.59070253372 --13.0346040726,-0.662183642387,-3.65606069565 --12.8155784607,-0.655142426491,-3.64158439636 --12.8195829391,-0.655148088932,-3.66478586197 --12.7565803528,-0.653142750263,-3.69122242928 --13.263666153,-0.672271430492,-3.87433075905 --13.2716751099,-0.672283530235,-3.92172551155 --13.1526651382,-0.668265581131,-3.93420052528 --12.8446235657,-0.658201754093,-3.89077472687 --12.5835886002,-0.649148523808,-3.85932564735 --12.9366502762,-0.662238955498,-3.98432803154 --13.1937026978,-0.671311438084,-4.10357189178 --12.924665451,-0.662256002426,-4.06912994385 --12.919672966,-0.663264989853,-4.11253547668 --12.6726388931,-0.65421384573,-4.08208084106 --12.5516262054,-0.65019351244,-4.08855009079 --12.7626714706,-0.658256471157,-4.19782781601 --12.8016872406,-0.660276710987,-4.2552113533 --12.9667215347,-0.666323721409,-4.32931137085 --13.2227783203,-0.676399886608,-4.45656108856 --13.203783989,-0.676406264305,-4.49697542191 --13.1937932968,-0.676415026188,-4.54038524628 --13.5128641129,-0.688509225845,-4.69159221649 --13.1458044052,-0.675424814224,-4.61620664597 --12.8417510986,-0.664350688457,-4.53758955002 --12.8087539673,-0.664352953434,-4.57201194763 --12.8107643127,-0.664364278316,-4.61740636826 --12.8397808075,-0.666383385658,-4.67379808426 --12.9708175659,-0.671429872513,-4.76511955261 --13.6849756241,-0.69763481617,-5.06308841705 --13.7940120697,-0.702677488327,-5.15142774582 --13.7900180817,-0.70268291235,-5.1746301651 --13.6950101852,-0.699669718742,-5.18908309937 --13.6360111237,-0.69766664505,-5.21752595901 --13.7270441055,-0.701704919338,-5.29986810684 --17.4278774261,-0.83675634861,-6.72901344299 --17.4108963013,-0.836771190166,-6.78541946411 --17.3489055634,-0.835773348808,-6.82485389709 --17.0548496246,-0.825699567795,-6.74423408508 --17.0208644867,-0.824708998203,-6.7926492691 --17.1759223938,-0.830773115158,-6.91495132446 --17.1449394226,-0.830783903599,-6.96536588669 --17.2119789124,-0.83382332325,-7.05472230911 --24.3637256622,-1.09794318676,-9.97766590118 --25.1949710846,-1.12922155857,-10.4025354385 --24.4708175659,-1.10302424431,-10.1551828384 --25.474111557,-1.14135658741,-10.6559429169 --24.2268428802,-1.09701776505,-10.2351150513 --25.9263191223,-1.16056370735,-11.0324344635 --24.3730125427,-1.10516226292,-10.5661878586 --24.239025116,-1.10215544701,-10.6006660461 --25.4723701477,-1.14855206013,-11.1750774384 --25.267364502,-1.14152479172,-11.1815958023 --25.2324047089,-1.14154994488,-11.2610054016 --25.23645401,-1.14358735085,-11.3573894501 --25.7516422272,-1.16378617287,-11.6814489365 --24.9604740143,-1.13557291031,-11.4243421555 --23.4290981293,-1.08012104034,-10.8277111053 --23.7492103577,-1.09224033356,-11.0177021027 --23.7932682037,-1.09528875351,-11.1280622482 --23.7973175049,-1.09632456303,-11.2204475403 --23.2011909485,-1.0761654377,-11.0342187881 --24.6516609192,-1.13167417049,-11.8036756516 --23.3103141785,-1.08226943016,-11.2649307251 --23.2053279877,-1.07926893234,-11.3043851852 --24.3937072754,-1.12568116188,-11.9188146591 --24.695848465,-1.13781893253,-12.1590080261 --24.9479789734,-1.14894151688,-12.3782339096 --25.3091430664,-1.16410183907,-12.6523866653 --25.4282341003,-1.17018175125,-12.8106975555 --23.1845836639,-1.08645427227,-11.7925443649 --23.0395851135,-1.08243989944,-11.8110275269 --16.3524799347,-0.827152252197,-8.48657035828 --16.2974910736,-0.826155722141,-8.52400588989 --16.2845134735,-0.827173650265,-8.58241271973 --16.2585353851,-0.827187001705,-8.63382434845 --14.4849786758,-0.759584307671,-7.77737617493 --16.205575943,-0.827213644981,-8.73665428162 --14.4430112839,-0.759607970715,-7.87220287323 --16.1966152191,-0.828244805336,-8.8302564621 --16.2136516571,-0.830274164677,-8.90564632416 --22.6609039307,-1.08063066006,-12.4397954941 --22.5209064484,-1.07661604881,-12.4552745819 --22.3478946686,-1.0715893507,-12.4527788162 --22.5540180206,-1.08170175552,-12.658033371 --23.1802692413,-1.10695171356,-13.0508155823 --22.586107254,-1.08476948738,-12.8156003952 --22.5761566162,-1.08580350876,-12.9040002823 --23.196434021,-1.11207377911,-13.3469715118 --23.5116062164,-1.12623214722,-13.6231517792 --23.2125530243,-1.11615908146,-13.5507440567 --22.7464332581,-1.09902095795,-13.379447937 --23.0595779419,-1.11216032505,-13.6084318161 --22.6014595032,-1.09602344036,-13.4381284714 --22.7325649261,-1.10311353207,-13.6114330292 --22.8596687317,-1.10920250416,-13.7827348709 --22.7926998138,-1.1082161665,-13.8401699066 --19.5524787903,-0.980980217457,-11.9927501678 --22.5227050781,-1.10118985176,-13.8721323013 --22.4837188721,-1.1001945734,-13.8973550797 --19.4795665741,-0.982035040855,-12.159787178 --19.3795700073,-0.980028271675,-12.1822462082 --23.2281951904,-1.1356164217,-14.6510181427 --19.199590683,-0.975022673607,-12.239156723 --17.794052124,-0.920482456684,-11.4405078888 --17.6410312653,-0.91545021534,-11.4220066071 --18.8515625,-0.964964330196,-12.2303819656 --19.1087169647,-0.977103948593,-12.477596283 --17.5370922089,-0.914484083652,-11.5520715714 --17.6331748962,-0.920554637909,-11.6913948059 --17.6202144623,-0.921580731869,-11.762802124 --17.5222129822,-0.918570816517,-11.7782678604 --17.4072055817,-0.91555339098,-11.7817440033 --17.3241901398,-0.912533521652,-11.7659978867 --17.4052715302,-0.917599320412,-11.8983335495 --17.3753013611,-0.91761803627,-11.9577503204 --17.1862602234,-0.911568164825,-11.9102802277 --17.2073135376,-0.913608849049,-12.0036592484 --15.6696424484,-0.851965487003,-11.0271196365 --15.6586771011,-0.852989017963,-11.0925254822 --15.6907119751,-0.855017602444,-11.1517038345 --15.7417755127,-0.858069062233,-11.2610664368 --19.3125247955,-1.00869691372,-13.8459730148 --19.2675571442,-1.00871527195,-13.9064025879 --43.3123054504,-2.02064275742,-31.1308269501 --43.1883964539,-2.01868605614,-31.2482852936 --19.2357063293,-1.01281642914,-14.1586055756 --19.2477416992,-1.01484143734,-14.2137947083 --42.9666671753,-2.01983356476,-31.6043643951 --43.8662757874,-2.06235170364,-32.4720916748 --19.3600273132,-1.02705228329,-14.6702861786 --17.3460960388,-0.945178091526,-13.3435049057 --17.3831424713,-0.94721364975,-13.4146776199 --17.4692382812,-0.952290713787,-13.5660104752 --17.7094192505,-0.964442908764,-13.8372344971 --43.241153717,-2.06884098053,-33.6122970581 --43.0191993713,-2.063839674,-33.6578292847 --17.1573352814,-0.948323190212,-13.7622146606 --14.3147964478,-0.825938761234,-11.5634403229 --16.5770950317,-0.92609089613,-13.4332237244 --14.3228845596,-0.829001784325,-11.7172327042 --17.9119510651,-0.987832784653,-14.6780576706 --14.1048469543,-0.822951972485,-11.6901893616 --42.3830909729,-2.07133340836,-34.7960548401 --14.0138988495,-0.822979986668,-11.8002481461 --13.9989328384,-0.824002504349,-11.8626613617 --42.0464935303,-2.07354831696,-35.2995948792 --42.3578529358,-2.09282231331,-35.785736084 --30.8376979828,-1.59927201271,-27.051279068 --30.9008636475,-1.60638868809,-27.2766113281 --30.7879219055,-1.60441100597,-27.3490753174 --30.6229457855,-1.60140490532,-27.375579834 --30.6009979248,-1.602435112,-27.4427871704 --30.4130077362,-1.59741580486,-27.4473075867 --30.3891220093,-1.60048627853,-27.5977058411 --28.9924697876,-1.54387521744,-26.6755142212 --30.1813812256,-1.60262620449,-27.9320087433 --29.9653701782,-1.59658944607,-27.9075508118 --29.0007896423,-1.5540844202,-27.1024627686 --29.8645019531,-1.59866070747,-28.0761966705 --29.7195396423,-1.59566450119,-28.11769104 --28.997177124,-1.56533336639,-27.6116142273 --29.00831604,-1.57042479515,-27.7949886322 --28.5901603699,-1.55426645279,-27.5706882477 --28.7884311676,-1.56846797466,-27.9339237213 --28.5883579254,-1.56039297581,-27.8282661438 --29.779335022,-1.62218415737,-29.1567459106 --29.6814060211,-1.62121593952,-29.2432022095 --38.6386108398,-2.16494727135,-42.6392860413 --36.3219108582,-2.05354332924,-40.3534660339 --36.1880111694,-2.05358505249,-40.458946228 --36.0731201172,-2.05463933945,-40.5844078064 --37.5666046143,-2.13778543472,-42.520614624 --37.317615509,-2.13175535202,-42.507183075 --37.1055450439,-2.12468004227,-42.4005355835 --36.8605575562,-2.11865067482,-42.3880996704 --36.55651474,-2.10958003998,-42.3067131042 --35.8075256348,-2.09147429466,-42.2384262085 --35.667514801,-2.08744525909,-42.2077255249 --35.5496330261,-2.08850193024,-42.3371925354 --35.3046379089,-2.08246731758,-42.3147659302 --24.5550117493,-1.51387500763,-29.7096748352 --24.492105484,-1.51592493057,-29.8221092224 --24.369146347,-1.51393210888,-29.8635959625 --24.3873157501,-1.52004146576,-30.0749664307 --23.9890956879,-1.50384616852,-29.7786750793 --24.249420166,-1.52008640766,-30.1936588287 --23.8892326355,-1.50591719151,-29.9403343201 --24.069562912,-1.52114975452,-30.3575782776 --23.6863498688,-1.50496041775,-30.0702724457 --23.6184406281,-1.50700747967,-30.1777153015 --23.5345172882,-1.50704264641,-30.265171051 --23.3063697815,-1.49691772461,-30.0705471039 --22.6458702087,-1.46550905704,-29.4154682159 --22.588968277,-1.46756124496,-29.5309009552 --22.5110454559,-1.46859848499,-29.6213531494 --22.3390293121,-1.46356189251,-29.5878829956 --22.3792247772,-1.47169065475,-29.8312358856 --22.3773841858,-1.47678887844,-30.0236282349 --22.4685592651,-1.48491132259,-30.2427482605 --23.0453281403,-1.52247333527,-31.2126693726 --23.943447113,-1.58030152321,-32.6293258667 --22.3739528656,-1.4951403141,-30.7099933624 --13.3094711304,-0.977913618088,-18.6341457367 --13.10734272,-0.968805372715,-18.4757099152 --13.0443210602,-0.966782927513,-18.4499645233 --12.9443016052,-0.964757561684,-18.4304428101 --12.8542947769,-0.962740361691,-18.4249172211 --12.8413724899,-0.96578758955,-18.5273227692 --13.2068796158,-0.990157306194,-19.1724281311 --13.4001979828,-1.00538372993,-19.5766677856 --13.3652591705,-1.00741755962,-19.6570968628 --13.224146843,-1.00032711029,-19.5164108276 --13.0660638809,-0.994253098965,-19.4149360657 --13.0080966949,-0.99526566267,-19.4593849182 --12.9421215057,-0.994271695614,-19.4928398132 --12.8320913315,-0.991238057613,-19.4593315125 --12.7761268616,-0.991252481937,-19.5067768097 --12.7672195435,-0.995308995247,-19.6251850128 --12.6471252441,-0.989233016968,-19.5084819794 --12.2857866287,-0.97097080946,-19.0891819 --12.2388305664,-0.970991313457,-19.1466217041 --12.1828622818,-0.97100353241,-19.1900672913 --12.1298980713,-0.972018718719,-19.2385101318 --12.0949583054,-0.973051071167,-19.3159408569 --12.0849971771,-0.975074052811,-19.3661499023 --12.0340385437,-0.975092113018,-19.4195957184 --13.0804958344,-1.04714691639,-21.2251186371 --18.6038093567,-1.41047799587,-30.2608795166 --12.1556301117,-0.999477446079,-20.1620941162 --10.9961938858,-0.926420211792,-18.3954601288 --10.935213089,-0.926423847675,-18.4239139557 --10.9092302322,-0.926430284977,-18.4461402893 --10.8572616577,-0.927442729473,-18.4895858765 --11.9728984833,-1.00561606884,-20.4990463257 --10.7643413544,-0.928478419781,-18.5944671631 --10.7043609619,-0.92848277092,-18.6239185333 --10.7885856628,-0.93763333559,-18.9012470245 --12.4169454575,-1.0513266325,-21.7830696106 --14.6793050766,-1.21172821522,-25.8785457611 --17.4324302673,-1.40867161751,-30.8945903778 --17.2433490753,-1.40159153938,-30.7841434479 --14.5617752075,-1.2269963026,-26.4292316437 --14.4037036896,-1.22092819214,-26.33776474 --14.725268364,-1.24732220173,-27.0186901093 --13.6357927322,-1.17525327206,-25.2270202637 --12.4291133881,-1.09404289722,-23.1944561005 --12.3661613464,-1.09506309032,-23.2519130707 --12.4664611816,-1.10726106167,-23.6112232208 --12.3524312973,-1.10422539711,-23.573720932 --12.5078258514,-1.12048947811,-24.0459861755 --12.1493358612,-1.09713542461,-23.4554958344 --11.9972419739,-1.09105467796,-23.3410263062 --12.4761648178,-1.13268995285,-24.4450111389 --12.4723167419,-1.13778173923,-24.624414444 --11.9135599136,-1.10123467445,-23.7162971497 --11.7374229431,-1.09412407875,-23.5508499146 --11.8337392807,-1.10633087158,-23.9261684418 --5.67447948456,-0.636143147945,-11.6906719208 --5.64950227737,-0.637154519558,-11.7300987244 --5.62953329086,-0.638171374798,-11.7785158157 --5.603556633,-0.639183044434,-11.8189544678 --5.583589077,-0.640200912952,-11.8693761826 --5.56061792374,-0.641216218472,-11.915807724 --5.55464220047,-0.642230391502,-11.9500160217 --5.53467655182,-0.643249332905,-12.0024404526 --5.47463798523,-0.642218112946,-11.9688920975 --5.44265270233,-0.642222881317,-11.9973325729 --5.45674991608,-0.646285176277,-12.1237268448 --5.43578577042,-0.647305011749,-12.1781606674 --5.41281700134,-0.649321615696,-12.2265872955 --5.40283536911,-0.649331688881,-12.2537975311 --5.38988637924,-0.651361703873,-12.3252162933 --10.6309871674,-1.09728777409,-24.1840267181 --10.5680418015,-1.09831035137,-24.2454853058 --10.5101079941,-1.0993398428,-24.318939209 --10.4401473999,-1.10035264492,-24.363401413 --10.3802099228,-1.10137987137,-24.4328556061 --10.2470340729,-1.09325301647,-24.2271747589 --9.91254043579,-1.069901824,-23.6488761902 --13.714468956,-1.41327917576,-32.8738555908 --10.3858737946,-1.12577867508,-25.1952533722 --11.1757097244,-1.20300853252,-27.3239421844 --11.0546712875,-1.19996476173,-27.2724533081 --10.4526071548,-1.15322780609,-26.0333919525 --10.4116239548,-1.15323102474,-26.0506343842 --10.3697395325,-1.15629303455,-26.1800708771 --10.0183887482,-1.13902413845,-25.7651882172 --9.9213809967,-1.13700342178,-25.7526779175 --9.49563503265,-1.10448658466,-24.889465332 --9.37556648254,-1.10042572021,-24.8079776764 --9.31853866577,-1.09839940071,-24.7742290497 --9.22953987122,-1.09738457203,-24.7717132568 --9.14254570007,-1.09637320042,-24.7751960754 --9.06857967377,-1.09638118744,-24.8116645813 --9.00864601135,-1.0984108448,-24.8851184845 --8.97477817535,-1.10248327255,-25.0325527191 --6.94313383102,-0.907376110554,-19.729019165 --6.89217567444,-0.908392846584,-19.7794704437 --6.82718276978,-0.907386243343,-19.7899360657 --6.76218938828,-0.907379627228,-19.8003997803 --6.65107822418,-0.90229511261,-19.6769065857 --6.57705831528,-0.900270700455,-19.6563739777 --6.55408620834,-0.901283621788,-19.6896018982 --6.48909235001,-0.901276409626,-19.6990680695 --6.41406965256,-0.899250686169,-19.6765422821 --6.37213420868,-0.901281952858,-19.7519817352 --6.38033866882,-0.909404873848,-19.9853782654 --6.27824354172,-0.904330909252,-19.8798789978 --6.25837564468,-0.909406065941,-20.0313034058 --6.24944639206,-0.911446690559,-20.1125202179 --6.1724190712,-0.910417437553,-20.0839939117 --6.10040426254,-0.909396409988,-20.0694637299 --6.05246210098,-0.910422682762,-20.1369171143 --5.99448823929,-0.91142821312,-20.1683750153 --5.94554424286,-0.912452876568,-20.2328281403 --5.90362167358,-0.915491342545,-20.3212718964 --5.85959148407,-0.91346591711,-20.2885169983 --5.81967496872,-0.916508495808,-20.3839588165 --5.78076410294,-0.919554531574,-20.4853992462 --5.6656165123,-0.91244751215,-20.3229160309 --5.61868000031,-0.914476752281,-20.3953647614 --6.59607648849,-1.04865074158,-24.1718444824 --7.40601015091,-1.16452133656,-27.4254722595 --6.4580206871,-1.0455930233,-24.1065788269 --6.39407873154,-1.04661524296,-24.1680450439 --6.40739917755,-1.05880582333,-24.5204353333 --6.43176603317,-1.07202577591,-24.9238147736 --6.36682987213,-1.07405138016,-24.9912815094 --6.28985214233,-1.07405030727,-25.012758255 --8.04347515106,-1.33225429058,-32.3074607849 --7.40937232971,-1.24890518188,-29.9862785339 --8.24181079865,-1.38207268715,-33.7608680725 --7.21176624298,-1.26109814644,-30.3936710358 --7.14088630676,-1.26415455341,-30.5161399841 --7.24569559097,-1.29464685917,-31.3934383392 --6.23610496521,-1.15535855293,-27.454832077 --6.20315361023,-1.15638065338,-27.505065918 --4.99963140488,-0.981512308121,-22.5586452484 --5.02704715729,-0.996760606766,-23.0120220184 --4.62065458298,-0.942871153355,-21.4928226471 --4.56571769714,-0.944897949696,-21.5622825623 --4.56903266907,-0.956082820892,-21.9056854248 --4.54407691956,-0.958104074001,-21.9539108276 --4.48513269424,-0.959125518799,-22.014377594 --5.81848430634,-1.20008254051,-28.9054603577 --4.73995780945,-1.02723860741,-23.992937088 --4.13347768784,-0.932677924633,-21.3059387207 --4.08959388733,-0.936737477779,-21.4323863983 --3.99245834351,-0.931640386581,-21.2868919373 --3.99379682541,-0.943838059902,-21.6532917023 --3.89849472046,-0.931644022465,-21.3275909424 --3.83250546455,-0.931637942791,-21.3400630951 --3.76551175117,-0.931628882885,-21.3475379944 --3.71158528328,-0.93466180563,-21.4279975891 --3.64157390594,-0.933641910553,-21.4164714813 --3.58061003685,-0.934651315212,-21.4559364319 --3.52649903297,-0.929576396942,-21.3371944427 --3.46050691605,-0.929568529129,-21.3466663361 --3.38646912575,-0.928532481194,-21.307144165 --3.33355402946,-0.930571615696,-21.3986053467 --3.29976129532,-0.938685774803,-21.6210479736 --3.45413279533,-0.98851197958,-23.0842933655 --3.39723491669,-0.992560505867,-23.1927566528 --3.41155982018,-1.00375163555,-23.5379428864 --3.34410238266,-1.02305305004,-24.1118183136 --3.11204242706,-0.983392834663,-22.9844684601 --3.07226800919,-0.991515755653,-23.2229118347 --2.96905303001,-0.983371019363,-22.9944229126 --2.89302778244,-0.982341349125,-22.9669075012 --2.86407780647,-0.983364522457,-23.0191383362 --2.78200125694,-0.980304002762,-22.937625885 --1.81331026554,-0.735239028931,-15.8794393539 --1.77035093307,-0.737254738808,-15.9288854599 --2.50812578201,-0.983321428299,-23.0655345917 --2.60461473465,-1.03720164299,-24.6298294067 --2.55350279808,-1.03312671185,-24.5110855103 --2.47549772263,-1.03310799599,-24.5035762787 --2.39243197441,-1.03005301952,-24.4320640564 --2.32553267479,-1.03309774399,-24.5355396271 --2.26065301895,-1.03715384007,-24.6590118408 --2.17658233643,-1.03409576416,-24.5825080872 --2.08946299553,-1.03000926971,-24.4560012817 --2.27903056145,-1.12152957916,-27.1339893341 --2.1879594326,-1.11846935749,-27.0544891357 --2.11004114151,-1.12150037289,-27.1349754333 --2.03921532631,-1.12758588791,-27.3114509583 --1.95928835869,-1.12961101532,-27.3819389343 --1.8753207922,-1.13061213493,-27.4104347229 --2.56665420532,-1.53428578377,-39.1579971313 --2.51581501961,-1.54036724567,-39.3162498474 --2.38977432251,-1.53731620312,-39.2567825317 --2.27187204361,-1.54034626484,-39.3403053284 --2.13667321205,-1.5322022438,-39.117855072 --2.01570868492,-1.53319597244,-39.1373825073 --1.8916734457,-1.53114819527,-39.0839157104 --1.77786254883,-1.53623151779,-39.2614326477 --1.70972239971,-1.53113591671,-39.1087112427 --1.60617995262,-1.5463758707,-39.5622138977 --1.49140763283,-1.55348098278,-39.7787399292 --1.36742246151,-1.55346179008,-39.7762718201 --1.411647439,-1.73747348785,-45.1165504456 --1.24474406242,-1.7039167881,-44.1681404114 --1.1685128212,-1.69576668739,-43.9204292297 --1.03565979004,-1.69982075691,-44.0489654541 --0.899760901928,-1.70284795761,-44.1305122375 --0.759651720524,-1.6977533102,-43.9970664978 --0.626914799213,-1.70587396622,-44.2436027527 --0.492276519537,-1.71805083752,-44.5901451111 --0.396657973528,-1.90511775017,-50.0445594788 --0.321011960506,-1.91730356216,-50.3908348083 --0.153983622789,-1.81052672863,-47.2854690552 -0.0429303534329,-1.77455365658,-46.3790130615 -0.204803451896,-1.87294638157,-49.3253288269 -0.375542551279,-1.93299221992,-51.1236076355 -0.481679558754,-1.76881182194,-46.2008132935 -0.626561522484,-1.76591718197,-46.1060829163 -0.64413267374,-1.64989078045,-42.6212005615 -0.778070211411,-1.64896142483,-42.5794792175 -0.913015544415,-1.64802777767,-42.5457611084 -1.13365399837,-1.67071819305,-43.2321777344 -1.2675216198,-1.66782867908,-43.1194572449 -1.40347838402,-1.66688847542,-43.0977363586 -1.46733772755,-1.66298568249,-42.964881897 -1.59612751007,-1.6561396122,-42.7711639404 -1.72492396832,-1.65028953552,-42.5844497681 -1.78425419331,-1.59426414967,-40.8877716064 -1.91116452217,-1.59234809875,-40.8160591125 -2.03503847122,-1.58845210075,-40.7063522339 -2.15788698196,-1.58457040787,-40.5706443787 -2.22798609734,-1.58853149414,-40.6827850342 -2.34272480011,-1.57971072197,-40.4330825806 -2.46459650993,-1.57681548595,-40.3203773499 -2.5885117054,-1.57489550114,-40.2526702881 -2.71546769142,-1.57395303249,-40.2269630432 -2.8596663475,-1.58187520504,-40.4532432556 -3.00890469551,-1.59177553654,-40.7215194702 -3.11745858192,-1.61148440838,-41.307636261 -3.20084881783,-1.59085607529,-40.6939544678 -3.32981586456,-1.59090721607,-40.6802482605 -3.52048254013,-1.61557137966,-41.3964958191 -3.58876729012,-1.59099972248,-40.6708335876 -3.72278618813,-1.59302222729,-40.7111244202 -3.81404304504,-1.60289716721,-40.9902496338 -3.94704246521,-1.60393059254,-41.0105400085 -4.16990423203,-1.63549005985,-41.9347572327 -4.30589580536,-1.63652849197,-41.9480476379 -4.59325122833,-1.68481993675,-43.3932189941 -4.52945899963,-1.62283468246,-41.5326576233 -4.66041946411,-1.62288939953,-41.5129508972 -4.46119356155,-1.54512012005,-39.1803016663 -4.57205533981,-1.54122698307,-39.0536117554 -4.69703054428,-1.54127168655,-39.0469093323 -7.54690170288,-2.28296709061,-61.1100540161 -7.74386978149,-2.2840321064,-61.1182861328 -5.56554460526,-1.67046284676,-42.8234138489 -5.77805233002,-1.68922233582,-43.3846435547 -5.34350681305,-1.56415534019,-39.6381912231 -5.46242523193,-1.56223094463,-39.5714912415 -5.58335876465,-1.56129837036,-39.5207977295 -5.69825696945,-1.55938470364,-39.4321060181 -6.11422348022,-1.59592878819,-40.5015716553 -6.24117469788,-1.59598696232,-40.470867157 -6.30515193939,-1.59601533413,-40.4570198059 -6.46731710434,-1.60295903683,-40.6542892456 -6.5449795723,-1.5921715498,-40.3146324158 -6.66389322281,-1.59124922752,-40.2429351807 -6.72951030731,-1.57848489285,-39.8532867432 -6.81726264954,-1.57064807415,-39.6076202393 -6.9341750145,-1.56872594357,-39.5339279175 -6.99816274643,-1.5697479248,-39.5310783386 -7.12815093994,-1.57078516483,-39.5383758545 -7.27622652054,-1.57477676868,-39.6396598816 -7.39816713333,-1.57383930683,-39.5959663391 -8.11100006104,-1.67937839031,-42.6737823486 -8.1494884491,-1.66268134117,-42.1441612244 -8.83641719818,-1.77115905285,-45.3217926025 -9.85847663879,-1.92206466198,-49.7413520813 -9.10021209717,-1.76733744144,-45.1523895264 -8.09698104858,-1.57610845566,-39.5066337585 -8.22194004059,-1.57616102695,-39.4819335938 -8.32881736755,-1.57325637341,-39.3682556152 -8.44674777985,-1.57232356071,-39.3125686646 -8.52579402924,-1.57431483269,-39.3737030029 -8.64974784851,-1.5743701458,-39.3430137634 -8.77169513702,-1.57442784309,-39.3063201904 -8.90869998932,-1.57645654678,-39.331615448 -9.0015296936,-1.57157516479,-39.1659507751 -9.03412628174,-1.55781424046,-38.7443351746 -9.15206050873,-1.55687832832,-38.6926460266 -9.22207260132,-1.55888772011,-38.7147941589 -9.29383659363,-1.55103898048,-38.476146698 -9.40073680878,-1.5491206646,-38.385471344 -9.58090591431,-1.55706429482,-38.5907325745 -9.5653629303,-1.53837239742,-38.0121574402 -9.67828845978,-1.53744029999,-37.9494781494 -9.85745239258,-1.54538619518,-38.1497421265 -9.96961116791,-1.55232071877,-38.3338508606 -10.7558603287,-1.64020657539,-40.8396110535 -10.8888206482,-1.64025938511,-40.8169174194 -11.0047245026,-1.63833975792,-40.7332344055 -11.1386890411,-1.63938999176,-40.7155342102 -11.3007488251,-1.64339089394,-40.8048095703 -11.4688205719,-1.64838719368,-40.906085968 -11.6311073303,-1.66025865078,-41.2361602783 -11.8402996063,-1.67019367218,-41.4743995667 -14.8923664093,-2.02367305756,-51.6002693176 -15.0091514587,-2.01782107353,-51.3945846558 -15.4579496384,-2.05146169662,-52.3196258545 -15.6158542633,-2.0505502224,-52.2479095459 -16.5781440735,-2.14344835281,-54.8465232849 -16.8366088867,-2.16323781013,-55.386516571 -16.3536109924,-2.08827614784,-53.1833381653 -16.5586395264,-2.09230303764,-53.2525863647 -16.688451767,-2.08843684196,-53.0788955688 -16.81224823,-2.08357977867,-52.8852119446 -16.3955497742,-2.01945996284,-51.0089797974 -16.4544525146,-2.01752781868,-50.91614151 -16.5732631683,-2.01266145706,-50.7354621887 -16.8003635406,-2.01965093613,-50.8846893311 -13.5337648392,-1.64343631268,-40.0872497559 -13.5734806061,-1.63460683823,-39.7876319885 -13.6873931885,-1.63268077374,-39.7099571228 -13.5749158859,-1.61492931843,-39.1792602539 -13.6336965561,-1.60906684399,-38.950630188 -13.968167305,-1.62986838818,-39.507774353 -14.2274427414,-1.64376616478,-39.8419761658 -15.1493301392,-1.72188270092,-42.0166320801 -19.2689113617,-2.11328196526,-52.97864151 -20.244764328,-2.19243001938,-55.1302528381 -20.3988780975,-2.19839668274,-55.2803382874 -21.8578109741,-2.3220281601,-58.6775512695 -19.5163650513,-2.06621170044,-51.3693389893 -19.601102829,-2.05937814713,-51.1026954651 -20.8374462128,-2.15929865837,-53.8320960999 -21.4623718262,-2.20089960098,-54.9360046387 -19.8565635681,-2.04573512077,-50.5705413818 -21.1890583038,-2.15258860588,-53.4818649292 -20.1874237061,-2.04688262939,-50.4751167297 -20.3242893219,-2.0449860096,-50.3544311523 -20.8279380798,-2.07571935654,-51.1394424438 -15.6636104584,-1.60510599613,-38.0511131287 -15.7645101547,-1.60318315029,-37.9554519653 -21.211681366,-2.07394170761,-50.9291877747 -21.398645401,-2.07599878311,-50.9234657288 -20.9763698578,-2.02663755417,-49.4742393494 -21.5691642761,-2.06330513954,-50.433177948 -21.7851905823,-2.06833291054,-50.49842453 -22.0092277527,-2.07435512543,-50.5786705017 -22.1242542267,-2.0773639679,-50.6247901917 -22.3062057495,-2.07942676544,-50.6040687561 -22.3138217926,-2.066644907,-50.1904907227 -23.1770801544,-2.12410259247,-51.700214386 -22.5484886169,-2.05988025665,-49.8661575317 -23.5569972992,-2.12922477722,-51.6727600098 -23.22397995,-2.08873391151,-50.5134620667 -23.5994796753,-2.11252427101,-51.1203727722 -23.734336853,-2.11063098907,-50.9876899719 -23.9252986908,-2.11269021034,-50.9769668579 -24.0110683441,-2.10783576965,-50.7423248291 -24.0086860657,-2.0950512886,-50.3247566223 -24.6254005432,-2.12976789474,-51.2046890259 -18.5059051514,-1.63307011127,-37.6477127075 -18.6558933258,-1.63510620594,-37.6530189514 -25.5483016968,-2.14499950409,-51.2508773804 -18.9789028168,-1.64116287231,-37.7056121826 -25.7028236389,-2.13329720497,-50.7546157837 -28.30975914,-2.31357836723,-55.4909477234 -28.3936977386,-2.31362819672,-55.4390983582 -28.6336936951,-2.31867551804,-55.4763412476 -31.0852546692,-2.48413658142,-59.7837982178 -31.2420825958,-2.48226261139,-59.6241111755 -31.2316513062,-2.46850395203,-59.1495552063 -31.3594360352,-2.46364665031,-58.9398880005 -31.529291153,-2.4627597332,-58.8111915588 -31.579164505,-2.45983982086,-58.6813697815 -31.6288356781,-2.45003294945,-58.3307685852 -30.0159816742,-2.32433319092,-54.9284896851 -30.1147537231,-2.31947803497,-54.696849823 -30.2405719757,-2.31660318375,-54.5171890259 -30.3834171295,-2.31471633911,-54.3695106506 -30.5643196106,-2.31480431557,-54.2917976379 -30.6963291168,-2.31882214546,-54.3259124756 -30.9263000488,-2.3228802681,-54.3321685791 -31.2063465118,-2.32990694046,-54.4263839722 -33.7456092834,-2.4895465374,-58.4458045959 -34.3867416382,-2.50758814812,-58.7011795044 -34.489692688,-2.50863409042,-58.66431427 -36.4400177002,-2.62469244003,-61.5512084961 -35.2439689636,-2.53361701965,-59.0936012268 -35.1985244751,-2.51885652542,-58.5950775146 -34.9818534851,-2.49219036102,-57.818687439 -35.2328186035,-2.49725461006,-57.8219337463 -35.5078163147,-2.50330591202,-57.8631591797 -36.0052871704,-2.52913141251,-58.4689865112 -36.2372245789,-2.53220915794,-58.4342460632 -36.3389816284,-2.52736020088,-58.1856117249 -36.4307365417,-2.5215139389,-57.9259796143 -39.4852828979,-2.70208501816,-62.3650283813 -40.1377220154,-2.73095703125,-62.9599609375 -40.3205566406,-2.7300798893,-62.8092651367 -40.3463935852,-2.72517538071,-62.6314659119 -41.4910316467,-2.77202248573,-63.5304679871 -41.654838562,-2.77015709877,-63.3447875977 -42.2742042542,-2.79506492615,-63.8497543335 -42.360912323,-2.78823900223,-63.5441322327 -42.7359733582,-2.79927039146,-63.673286438 -42.8088684082,-2.79734253883,-63.5654563904 -23.5636386871,-1.40569221973,-26.0407066345 -23.6055450439,-1.40375041962,-25.9231052399 -54.8640022278,-2.81265974045,-53.9106140137 -50.3494682312,-2.59185004234,-49.1423301697 -54.7733764648,-2.79297971725,-53.1476020813 -53.7783927917,-2.73835110664,-51.8487815857 -52.1749954224,-2.65585041046,-49.9784011841 -50.6678085327,-2.58125138283,-48.374710083 -23.0352401733,-1.28644955158,-21.5763835907 -38.8517875671,-2.0092484951,-36.1079864502 -38.9486732483,-2.00832533836,-35.969367981 -23.5311737061,-1.29656207561,-21.4927692413 -10.7776174545,-0.711172163486,-9.67395401001 -10.5624408722,-0.700234055519,-9.41551876068 -10.3262519836,-0.688299298286,-9.13911151886 -10.1230888367,-0.677356302738,-8.89667224884 -9.93093395233,-0.667409777641,-8.66722106934 -9.73778152466,-0.657462775707,-8.43778324127 -9.56564426422,-0.648510038853,-8.23131656647 -9.36950683594,-0.639554023743,-8.03066444397 -9.20237636566,-0.630598604679,-7.83219480515 -9.03524875641,-0.621642529964,-7.63473463058 -8.88913536072,-0.614681243896,-7.45924663544 -8.73601913452,-0.606720507145,-7.2787694931 -8.60191726685,-0.599755585194,-7.11628103256 -8.46082019806,-0.592785835266,-6.97159337997 -8.30770874023,-0.58482247591,-6.79710674286 -8.17561149597,-0.577855169773,-6.64061975479 -8.0875415802,-0.572879552841,-6.52309989929 -8.11053943634,-0.572885334492,-6.49950361252 -8.13653850555,-0.573890805244,-6.47791051865 -8.16854000092,-0.573895156384,-6.46131181717 -8.18654251099,-0.573896825314,-6.45550203323 -8.22154712677,-0.574900865555,-6.44090461731 -8.25655174255,-0.575904607773,-6.42729616165 -8.27154350281,-0.574911594391,-6.39670753479 -8.31455135345,-0.575914442539,-6.38810539246 -8.32153987885,-0.575922429562,-6.35151863098 -8.37055110931,-0.576924324036,-6.34790802002 -8.39055538177,-0.57692605257,-6.3421087265 -8.41755485535,-0.577931046486,-6.32150650024 -8.46056175232,-0.578934133053,-6.31190633774 -8.53858852386,-0.58093225956,-6.33027219772 -8.5705909729,-0.580936968327,-6.31167936325 -8.61660003662,-0.581939518452,-6.30506324768 -8.7056312561,-0.584936916828,-6.32943153381 -8.74164199829,-0.585936665535,-6.33561515808 -8.88069915771,-0.590928077698,-6.39694738388 -9.73612308502,-0.626831710339,-6.98981189728 -9.82615089417,-0.628831505775,-7.0091753006 -9.84914302826,-0.628839492798,-6.97858333588 -9.99119567871,-0.63383346796,-7.03491306305 -10.0502052307,-0.635837376118,-7.03029489517 -10.0662031174,-0.635841012001,-7.01749944687 -10.1052026749,-0.636847317219,-6.99789571762 -10.301279068,-0.643836379051,-7.09018802643 -10.6364212036,-0.656811416149,-7.27839708328 -10.8244915009,-0.663802742958,-7.36169099808 -10.784450531,-0.660818517208,-7.28314208984 -10.7264127731,-0.657830297947,-7.21739435196 -10.6343488693,-0.652850866318,-7.10387897491 -10.5823049545,-0.649866819382,-7.01933479309 -14.5521192551,-0.811494708061,-9.6771736145 -14.5750961304,-0.811510622501,-9.62658405304 -14.6641016006,-0.813520491123,-9.61995410919 -14.1878538132,-0.792581558228,-9.23568916321 -14.2078456879,-0.793588221073,-9.21689033508 -14.1517896652,-0.789610147476,-9.11535644531 -14.4428873062,-0.800601661205,-9.24359035492 -9.26658916473,-0.590054571629,-5.80234098434 -9.23155975342,-0.588064670563,-5.73878192902 -9.25955963135,-0.589069604874,-5.71519517899 -9.28255748749,-0.589074671268,-5.68959760666 -14.0555801392,-0.779706716537,-8.70876121521 -14.0535497665,-0.778722524643,-8.64519405365 -13.8984556198,-0.770749270916,-8.48671913147 -13.7863807678,-0.765772283077,-8.35621833801 -13.4182024002,-0.749812662601,-8.06887722015 -13.4351835251,-0.749825239182,-8.02129364014 -13.4821767807,-0.749835848808,-7.99169301987 -13.6522321701,-0.756831228733,-8.06679344177 -13.5841789246,-0.752849340439,-7.96726465225 -13.5051212311,-0.748867869377,-7.86174297333 -13.5120992661,-0.747880518436,-7.80916023254 -13.5961065292,-0.749888658524,-7.80153512955 -13.6090869904,-0.749900996685,-7.751953125 -13.8421640396,-0.757894158363,-7.86001586914 -13.813126564,-0.755909204483,-7.78446626663 -13.3979454041,-0.738944232464,-7.48814964294 -13.3479042053,-0.735959112644,-7.40360927582 -13.3908967972,-0.736968934536,-7.37300634384 -13.4779062271,-0.738976716995,-7.36638116837 -13.4078569412,-0.735991954803,-7.27185058594 -13.3478250504,-0.733000516891,-7.21109962463 -13.3858156204,-0.734010577202,-7.17651033401 -13.4038000107,-0.733021259308,-7.13192462921 -13.3947753906,-0.732032835484,-7.0733499527 -13.4237632751,-0.732042908669,-7.03475904465 -13.4027347565,-0.731054842472,-6.9691991806 -13.3967113495,-0.730065882206,-6.91262531281 -13.4607229233,-0.732069075108,-6.91979837418 -13.456700325,-0.731080174446,-6.86323261261 -13.4046621323,-0.728092491627,-6.78268766403 -13.398639679,-0.727103292942,-6.72611951828 -13.464641571,-0.728111624718,-6.70750188828 -13.6616849899,-0.735116422176,-6.75480937958 -13.5886411667,-0.731128931046,-6.66427850723 -13.492600441,-0.727136671543,-6.58855485916 -13.5495986938,-0.729145228863,-6.56494140625 -13.58959198,-0.729154467583,-6.53134822845 -13.5995750427,-0.72916418314,-6.48376607895 -13.7506027222,-0.734170973301,-6.50509977341 -13.8716192245,-0.738178789616,-6.51045465469 -14.0086517334,-0.742181241512,-6.55058002472 -13.8675889969,-0.736193954945,-6.42809915543 -13.8475637436,-0.7352039814,-6.36553668976 -13.8195362091,-0.733214139938,-6.29898309708 -13.8775339127,-0.734222829342,-6.27436733246 -13.9095239639,-0.735232114792,-6.23578071594 -14.0225372314,-0.738240480423,-6.23513889313 -14.1125545502,-0.74124443531,-6.2502951622 -14.0395145416,-0.738254487514,-6.16376638412 -14.1205186844,-0.740263402462,-6.14714765549 -14.3305587769,-0.747271716595,-6.18844652176 -14.441570282,-0.750280916691,-6.18380880356 -14.6135978699,-0.756290018559,-6.20612955093 -14.6315822601,-0.756299674511,-6.15954637527 -14.7966165543,-0.762304544449,-6.20366477966 -14.8055992126,-0.761314213276,-6.15308380127 -15.565779686,-0.788325965405,-6.42305755615 -15.5647583008,-0.788336396217,-6.36548519135 -15.5807409286,-0.787347018719,-6.31391143799 -17.2401409149,-0.847368478775,-6.94734811783 -17.295129776,-0.849381029606,-6.90774011612 -17.3231258392,-0.849387347698,-6.8879365921 -17.3701095581,-0.850400149822,-6.84334230423 -17.4240989685,-0.851412951946,-6.80174160004 -17.4590816498,-0.852425515652,-6.75215387344 -17.5200710297,-0.853438258171,-6.71354484558 -17.5710601807,-0.854450821877,-6.67094087601 -17.6010551453,-0.855457365513,-6.65014410019 -17.6470413208,-0.856470048428,-6.60454797745 -17.6980285645,-0.857482731342,-6.56094741821 -17.7490139008,-0.858495354652,-6.51734542847 -17.810005188,-0.859508275986,-6.47674131393 -17.8589916229,-0.8605209589,-6.43114614487 -17.8969745636,-0.861533463001,-6.38155555725 -17.9349727631,-0.862539887428,-6.36474227905 -17.9949607849,-0.863552808762,-6.32313680649 -18.0139408112,-0.8635648489,-6.2655620575 -18.1269397736,-0.867579102516,-6.24292373657 -18.6310214996,-0.884604692459,-6.35706138611 -18.6860084534,-0.88561809063,-6.31046390533 -18.7210025787,-0.886625051498,-6.28966093063 -18.7549858093,-0.887637734413,-6.23607158661 -18.8219738007,-0.888651549816,-6.19346380234 -18.8519554138,-0.889664113522,-6.13787937164 -18.8949394226,-0.889676988125,-6.08728218079 -18.8959159851,-0.889688432217,-6.02171611786 -19.0539207458,-0.894705533981,-6.00805616379 -19.0309047699,-0.893710434437,-5.96728801727 -19.1188964844,-0.895724892616,-5.9306640625 -19.1518783569,-0.895737469196,-5.87507820129 -19.1828594208,-0.896749913692,-5.8184967041 -19.2988586426,-0.899765849113,-5.78886175156 -19.2278213501,-0.89677375555,-5.70133209229 -19.0207614899,-0.888775646687,-5.5718870163 -19.0067481995,-0.887780070305,-5.53610467911 -19.0177268982,-0.88779103756,-5.47453117371 -19.0467090607,-0.887802839279,-5.41794967651 -19.0836925507,-0.888814866543,-5.36435937881 -19.1436805725,-0.89082801342,-5.31675958633 -19.1916656494,-0.891840457916,-5.26616191864 -19.2476520538,-0.892853438854,-5.21656656265 -19.3076496124,-0.894861459732,-5.20174360275 -19.3466358185,-0.895873606205,-5.14715671539 -19.3936195374,-0.896886110306,-5.09456539154 -19.4526062012,-0.897899091244,-5.04596090317 -19.5045928955,-0.898911952972,-4.99436664581 -19.565580368,-0.900925219059,-4.9447684288 -19.6175785065,-0.902933061123,-4.92595386505 -19.6645622253,-0.90394538641,-4.87335586548 -19.717546463,-0.904958248138,-4.82076311111 -19.7775344849,-0.905971467495,-4.77016353607 -19.8225212097,-0.906983673573,-4.71656560898 -19.8865070343,-0.908997237682,-4.66596698761 -19.9464931488,-0.911010503769,-4.61436891556 -20.0044898987,-0.912018835545,-4.59555149078 -20.0454750061,-0.913030982018,-4.53896427155 -20.1104621887,-0.915044486523,-4.48835945129 -20.1564464569,-0.91605681181,-4.4327673912 -20.2264328003,-0.918070793152,-4.38216352463 -20.2894191742,-0.920084297657,-4.32956457138 -20.3424053192,-0.921097040176,-4.2749671936 -20.3924007416,-0.923105061054,-4.25315332413 -20.4513874054,-0.92411839962,-4.19855833054 -20.5103740692,-0.926131546497,-4.14495515823 -20.5613574982,-0.927144289017,-4.08836317062 -20.6313457489,-0.929158270359,-4.03575897217 -20.687330246,-0.930171310902,-3.9801607132 -20.7483158112,-0.932184815407,-3.92456507683 -20.8033123016,-0.934193313122,-3.90175199509 -20.8532981873,-0.935205876827,-3.84415769577 -20.9172821045,-0.937219619751,-3.78855919838 -20.9972705841,-0.939234554768,-3.73594975471 -21.0522556305,-0.941247582436,-3.67835354805 -21.1122398376,-0.942260980606,-3.62075853348 -21.1652336121,-0.944269418716,-3.59694266319 -21.2122192383,-0.945281803608,-3.53734970093 -21.2832050323,-0.947296142578,-3.4807498455 -21.3581924438,-0.949310779572,-3.42514371872 -21.4051761627,-0.950323164463,-3.36455202103 -21.4671611786,-0.952336728573,-3.30595397949 -21.5331459045,-0.954350709915,-3.24735569954 -21.6001434326,-0.956360638142,-3.22353744507 -21.6481266022,-0.957373023033,-3.16194605827 -21.7281131744,-0.960388183594,-3.10533618927 -21.7880973816,-0.962401628494,-3.04473996162 -21.8560810089,-0.963415920734,-2.98414468765 -21.913066864,-0.965429067612,-2.92354393005 -21.9880504608,-0.967443883419,-2.86394119263 -22.0310459137,-0.969451963902,-2.83414101601 -22.1190319061,-0.971467971802,-2.77652597427 -22.1780147552,-0.973481416702,-2.71393060684 -22.2409992218,-0.975495219231,-2.65133452415 -22.2919845581,-0.976507902145,-2.58674550056 -22.3739700317,-0.979523539543,-2.52613759041 -22.4299545288,-0.980536580086,-2.46253991127 -22.5139484406,-0.9835485816,-2.43671512604 -22.5789337158,-0.985562682152,-2.37212157249 -22.6489162445,-0.987577259541,-2.30852079391 -22.7049007416,-0.989590406418,-2.24292802811 -22.791885376,-0.991606652737,-2.18031859398 -22.8228683472,-0.992617309093,-2.11173725128 -22.911863327,-0.995629966259,-2.08490753174 -21.1007595062,-0.933453142643,-1.83826732635 -21.0557403564,-0.932454526424,-1.76772379875 -21.0377235413,-0.93145865202,-1.6991713047 -21.1137123108,-0.933472335339,-1.63956677914 -21.1036968231,-0.933477044106,-1.57200837135 -23.3367652893,-1.0087184906,-1.68531370163 -23.4067592621,-1.01172935963,-1.65449464321 -23.4527397156,-1.0127415657,-1.58391082287 -20.8446331024,-0.923468708992,-1.32165491581 -20.9136219025,-0.925481319427,-1.26105427742 -9.6912651062,-0.544265091419,-0.422415941954 -9.69727039337,-0.544262647629,-0.391846805811 -9.68327236176,-0.544259548187,-0.376063406467 -9.67527770996,-0.543255627155,-0.345490127802 -9.68728256226,-0.544253766537,-0.315909445286 -9.67728710175,-0.543249487877,-0.285336583853 -9.68429279327,-0.543247103691,-0.255753934383 -9.69029808044,-0.543244600296,-0.22617071867 -9.66330242157,-0.543238162994,-0.194612175226 -9.67030525208,-0.543237328529,-0.179821178317 -9.67531108856,-0.543234586716,-0.15023817122 -9.66231632233,-0.542229712009,-0.119668886065 -9.66732215881,-0.543226897717,-0.090086273849 -9.67032718658,-0.543223798275,-0.0605032518506 -9.65933322906,-0.542219042778,-0.0299358163029 -9.65933609009,-0.542217254639,-0.0151447001845 -9.66034126282,-0.542213797569,0.0154237747192 -9.65034770966,-0.542209088802,0.045003362 -9.65735340118,-0.542206168175,0.0755732357502 -9.65335845947,-0.542202115059,0.105153813958 -9.64236450195,-0.542197108269,0.134731322527 -9.64637088776,-0.542193770409,0.165300369263 -9.65037441254,-0.542192459106,0.18009288609 -9.64237976074,-0.542187690735,0.209670543671 -9.64238643646,-0.542183816433,0.240237832069 -9.64639186859,-0.542180478573,0.269821435213 -9.64139938354,-0.542176008224,0.299399763346 -9.63940525055,-0.541171908379,0.328979969025 -9.62740802765,-0.541168391705,0.343762338161 -9.62641525269,-0.541164219379,0.374328374863 -9.63842201233,-0.541161775589,0.403918355703 -9.63942813873,-0.542157769203,0.434486210346 -9.62243556976,-0.541151642799,0.463067263365 -9.62444210052,-0.541147708893,0.493635863066 -9.62344837189,-0.541143417358,0.523215830326 -9.6164522171,-0.541140437126,0.537999510765 -9.6294593811,-0.541137874126,0.568579316139 -9.61646556854,-0.541131913662,0.59814697504 -9.61347293854,-0.541127324104,0.627724587917 -9.61548042297,-0.541123330593,0.657307803631 -9.60848808289,-0.54111802578,0.686880588531 -9.60849475861,-0.541113734245,0.716461598873 -9.61949825287,-0.541112959385,0.732251822948 -9.61650466919,-0.541108191013,0.761829555035 -9.60051345825,-0.541101455688,0.791389882565 -9.60251998901,-0.541097342968,0.820973753929 -9.59652805328,-0.54109197855,0.850546658039 -9.59453487396,-0.541087210178,0.880124986172 -9.59553909302,-0.541085124016,0.894917190075 -9.59754657745,-0.541080713272,0.925487756729 -9.60855484009,-0.541077613831,0.956072866917 -9.69955730438,-0.545085549355,0.993689239025 -9.73156356812,-0.546085357666,1.02727293968 -9.70657253265,-0.545077264309,1.05484676361 -10.0005664825,-0.555113732815,1.1135392189 -9.9955701828,-0.555110812187,1.12833034992 -9.98657798767,-0.555104970932,1.15890049934 -9.97358703613,-0.554098546505,1.18847668171 -9.96959400177,-0.554093182087,1.22004139423 -9.96060180664,-0.554087340832,1.24962365627 -9.97161006927,-0.555084228516,1.28220331669 -9.97961616516,-0.555080592632,1.31477844715 -9.98362064362,-0.555078864098,1.33057308197 -10.016626358,-0.556078791618,1.36615991592 -10.0426330566,-0.557077765465,1.40074872971 -9.93964576721,-0.554058015347,1.41928362846 -9.91965579987,-0.554050028324,1.44884049892 -9.92366313934,-0.55404573679,1.48042178154 -9.90367221832,-0.553037881851,1.50899064541 -10.0026693344,-0.557050049305,1.53782463074 -10.0376758575,-0.558050215244,1.57441461086 -10.0476827621,-0.559046685696,1.60798966885 -10.0286922455,-0.558038949966,1.63656437397 -9.94570732117,-0.555021524429,1.65610408783 -9.94671440125,-0.556016564369,1.687682271 -9.94571971893,-0.556013822556,1.70346796513 -9.97272491455,-0.557012796402,1.7390588522 -14.4713993073,-0.71168756485,2.4974899292 -14.4814004898,-0.712686061859,2.54506874084 -14.4864025116,-0.712683796883,2.59164857864 -14.4724063873,-0.712678551674,2.63620901108 -14.4744091034,-0.712675690651,2.68278360367 -14.4644126892,-0.712672531605,2.70456218719 -14.4704151154,-0.712670266628,2.75213646889 -14.4804172516,-0.713668584824,2.80071043968 -9.67283248901,-0.547915995121,1.98590373993 -9.67884159088,-0.548911511898,2.01749110222 -9.66785240173,-0.547904133797,2.04705548286 -9.6678571701,-0.547901451588,2.06185436249 -9.66286659241,-0.547894954681,2.09242320061 -9.68187427521,-0.548892319202,2.12701320648 -9.66188526154,-0.54888343811,2.15457606316 -9.63789653778,-0.547873914242,2.18113875389 -14.9924020767,-0.734716951847,3.35485267639 -14.9654054642,-0.733710944653,3.37362599373 -9.91089439392,-0.557902991772,2.31819391251 -9.94790077209,-0.559903204441,2.35878229141 -9.88591575623,-0.557887494564,2.37733316422 -9.87492656708,-0.557880043983,2.4069070816 -9.92893028259,-0.559882998466,2.45150589943 -9.96793556213,-0.560883462429,2.49309754372 -9.97993946075,-0.561882376671,2.51288199425 -9.9589509964,-0.561873197556,2.54045128822 -9.91296577454,-0.559859931469,2.56200957298 -9.89297771454,-0.559850811958,2.5895793438 -9.89398765564,-0.559845089912,2.62215900421 -9.8719997406,-0.559835493565,2.64972019196 -9.888007164,-0.559832155704,2.68630409241 -9.9300069809,-0.561836063862,2.71311306953 -9.95701503754,-0.562834382057,2.75369095802 -9.96102428436,-0.563829183578,2.78727483749 -9.96603393555,-0.56382393837,2.82185125351 -9.93804645538,-0.562813222408,2.84741687775 -9.8560667038,-0.560793578625,2.85796284676 -9.84007835388,-0.560784757137,2.88653182983 -9.81108665466,-0.559776961803,2.89431643486 -9.81009674072,-0.559770584106,2.92689204216 -9.82610607147,-0.560766994953,2.96447277069 -9.92510414124,-0.564777374268,3.02608680725 -9.92411422729,-0.564770936966,3.05965685844 -9.90312767029,-0.564761042595,3.08722114563 -9.84313964844,-0.562747776508,3.08598780632 -9.83815097809,-0.562740683556,3.11756467819 -9.86315822601,-0.563738644123,3.15815496445 -9.5942029953,-0.554686665535,3.10863304138 -9.61121177673,-0.555682957172,3.14720726013 -9.54423141479,-0.553664982319,3.15875983238 -9.51024723053,-0.552652716637,3.18032646179 -9.44826030731,-0.550638973713,3.17610025406 -9.45427036285,-0.550633311272,3.21067523956 -9.44328308105,-0.550624847412,3.23925113678 -9.44629383087,-0.551618695259,3.27282714844 -9.44830513,-0.551612257957,3.30639982224 -9.44031715393,-0.551604270935,3.33597779274 -9.43532371521,-0.551600039005,3.35076236725 -9.43433570862,-0.551593065262,3.38333559036 -9.42834663391,-0.552585244179,3.41391086578 -9.44035720825,-0.552580654621,3.450496912 -9.43536949158,-0.553572893143,3.48206615448 -9.42338180542,-0.553564012051,3.51063990593 -9.4223947525,-0.553556978703,3.54321694374 -9.42240047455,-0.553553521633,3.56000185013 -9.41941165924,-0.553546190262,3.59158301353 -9.42142295837,-0.554539561272,3.62615156174 -9.4224357605,-0.554532825947,3.65972948074 -9.42044734955,-0.555525541306,3.69230532646 -9.41145992279,-0.555517077446,3.72188401222 -9.40147399902,-0.555508315563,3.75145769119 -9.40347957611,-0.555505096912,3.76924347878 -9.41648864746,-0.556500375271,3.80782461166 -9.40550327301,-0.556491374969,3.83739519119 -9.39751529694,-0.556482851505,3.86796855927 -9.40052700043,-0.557476401329,3.90255117416 -9.38654136658,-0.556466758251,3.93111872673 -9.38555431366,-0.557459414005,3.96469426155 -9.40355682373,-0.558459162712,3.9884955883 -9.39357089996,-0.558450102806,4.0190615654 -9.38858318329,-0.558442115784,4.05064249039 -9.385597229,-0.558434247971,4.08421087265 -9.3736114502,-0.558425009251,4.11279153824 -9.37562274933,-0.559418082237,4.14836406708 -9.38462734222,-0.560416162014,4.16915893555 -9.37664031982,-0.560407340527,4.20072698593 -9.37565326691,-0.560400009155,4.23431062698 -9.36966705322,-0.560391485691,4.26687908173 -9.36767959595,-0.561383843422,4.30045843124 -9.36569309235,-0.561376035213,4.33502721786 -9.36570549011,-0.562368690968,4.36960840225 -9.36970996857,-0.562365829945,4.38840484619 -9.36672401428,-0.562357723713,4.42297029495 -9.36973571777,-0.563350915909,4.45954847336 -9.34575176239,-0.563339173794,4.4831237793 -9.34776496887,-0.563332021236,4.51969766617 -9.34677791595,-0.564324259758,4.55526685715 -9.35278987885,-0.565317809582,4.59384346008 -9.47577476501,-0.569336950779,4.66968202591 -9.47078800201,-0.570328354836,4.70424795151 -9.45080471039,-0.570317149162,4.7308177948 -9.45481681824,-0.570310473442,4.7684044838 -9.45083045959,-0.571302175522,4.80297851562 -9.44684410095,-0.571293830872,4.83755397797 -9.44685077667,-0.57128995657,4.85633659363 -9.44786262512,-0.57228243351,4.89390945435 -9.4348783493,-0.572272539139,4.92349004745 -9.43389129639,-0.573264718056,4.96006393433 -9.43590354919,-0.57325732708,4.99863529205 -9.43191814423,-0.574248969555,5.03321647644 -9.42193222046,-0.574239492416,5.06479501724 -9.42993831635,-0.574236929417,5.08857536316 -9.41995239258,-0.575227439404,5.12015485764 -9.42296600342,-0.575220167637,5.15972757339 -9.42297840118,-0.576212406158,5.19730520248 -9.41299343109,-0.576202690601,5.22987651825 -9.41400718689,-0.577195107937,5.26845169067 -9.41501331329,-0.577191531658,5.28724908829 -9.39902973175,-0.577180564404,5.31681680679 -9.40904140472,-0.578174650669,5.36039829254 -9.42005252838,-0.579168856144,5.40497732162 -9.39706993103,-0.579156577587,5.43054628372 -9.41308021545,-0.580151677132,5.47812891006 -9.40709590912,-0.581142544746,5.51370096207 -9.41010093689,-0.581139028072,5.53548336029 -9.38811969757,-0.581127047539,5.56105995178 -9.43112373352,-0.583127200603,5.62564468384 -9.42813873291,-0.58411860466,5.66321992874 -9.40515613556,-0.584106266499,5.68879270554 -9.35917949677,-0.583089590073,5.70036125183 -9.31720161438,-0.582073450089,5.71492290497 -9.27921581268,-0.580062091351,5.71169996262 -9.28222942352,-0.581054508686,5.75327301025 -9.28224372864,-0.58204638958,5.79285001755 -9.26526069641,-0.582034945488,5.82241773605 -9.26527404785,-0.583026826382,5.86199617386 -9.26228904724,-0.583018183708,5.89957714081 -9.25730323792,-0.584008872509,5.93714570999 -9.2653093338,-0.584006428719,5.96193981171 -9.26532363892,-0.584998130798,6.0025138855 -9.2523393631,-0.584987521172,6.03409290314 -9.24535560608,-0.58597779274,6.07066202164 -9.24536895752,-0.586969614029,6.1112408638 -9.23938560486,-0.586960077286,6.14880943298 -9.25138950348,-0.587958335876,6.17660713196 -9.25640296936,-0.588950991631,6.22118377686 -9.23842048645,-0.588939130306,6.25075387955 -9.23643493652,-0.589930534363,6.29033565521 -9.23645019531,-0.590921998024,6.33290290833 -9.22346687317,-0.590911209583,6.36548042297 -9.22548103333,-0.591903150082,6.40905427933 -9.24048423767,-0.592901945114,6.4398522377 -9.22050380707,-0.592889606953,6.46842241287 -9.22551727295,-0.593882203102,6.51400279999 -9.21853351593,-0.593872189522,6.55256891251 -9.21154880524,-0.594862401485,6.59014606476 -9.21856212616,-0.595855414867,6.63772726059 -9.21257781982,-0.596845567226,6.67729520798 -9.21258449554,-0.596841514111,6.6980919838 -9.19960308075,-0.596830308437,6.73265981674 -9.20261669159,-0.597822368145,6.77823877335 -9.19863128662,-0.598813056946,6.818816185 -9.19764709473,-0.599804282188,6.86238908768 -9.19966125488,-0.600796103477,6.90796661377 -9.18467903137,-0.600784420967,6.94153547287 -9.19268512726,-0.601781785488,6.96932935715 -9.18570137024,-0.602771699429,7.00890207291 -9.1757183075,-0.602761209011,7.0454826355 -9.16473579407,-0.602750241756,7.08304738998 -9.13775634766,-0.60273617506,7.10761594772 -9.03579425812,-0.599707484245,7.07317495346 -9.08880519867,-0.603704750538,7.18254804611 -9.02483463287,-0.601683318615,7.17810678482 -8.96986198425,-0.599663734436,7.17967414856 -8.91489028931,-0.598644018173,7.1812376976 -8.9029083252,-0.598632633686,7.21780443192 -8.90491485596,-0.599628806114,7.24159765244 -8.90193080902,-0.600619256496,7.28517055511 -8.89694690704,-0.600609481335,7.32674789429 -8.89896202087,-0.602600991726,7.3743262291 -8.87498378754,-0.602587342262,7.40089702606 -9.11294364929,-0.613625884056,7.64453125 -9.1359539032,-0.615621685982,7.71111822128 -9.14695835114,-0.616619348526,7.74490499496 -9.12697887421,-0.616606295109,7.77746868134 -9.13999080658,-0.618600189686,7.83605766296 -9.12800884247,-0.618588864803,7.87463283539 -9.11502742767,-0.619577229023,7.91320133209 -9.11404323578,-0.620568037033,7.96177768707 -9.12205696106,-0.621560633183,8.01835536957 -9.116065979,-0.622554898262,8.03814220428 -9.31503391266,-0.632585883141,8.2627658844 -9.26906108856,-0.63156747818,8.27432537079 -9.24208259583,-0.631552994251,8.30189418793 -9.24209785461,-0.632544219494,8.35247993469 -9.23211574554,-0.633533060551,8.39604854584 -9.24512863159,-0.634526610374,8.45963096619 -9.2611322403,-0.636525332928,8.50042152405 -9.23215484619,-0.636510372162,8.52698898315 -9.22417259216,-0.637499630451,8.57256412506 -9.22418880463,-0.638490438461,8.62613773346 -9.20220947266,-0.638476967812,8.65871238708 -9.20422458649,-0.639468193054,8.71428871155 -9.21822834015,-0.64146655798,8.75408267975 -9.22024345398,-0.642457664013,8.81065559387 -9.20326423645,-0.642445027828,8.8492269516 -9.20627880096,-0.644436597824,8.90581226349 -9.21229362488,-0.646428406239,8.96837711334 -9.05134868622,-0.639386713505,8.86692428589 -9.10337543488,-0.645374119282,9.05587863922 -9.05840301514,-0.644355714321,9.06744480133 -9.03242588043,-0.644341111183,9.09801197052 -9.02844333649,-0.645330905914,9.15058612823 -9.02645969391,-0.647321224213,9.20516300201 -9.02447509766,-0.648311495781,9.25974178314 -9.03148174286,-0.649308264256,9.29553127289 -9.02449989319,-0.65029746294,9.34610462189 -9.02051734924,-0.651287138462,9.40067577362 -9.01353549957,-0.652276396751,9.45125389099 -9.01355171204,-0.654266953468,9.50983047485 -9.01156806946,-0.655257225037,9.56640911102 -9.01157665253,-0.656252503395,9.5961971283 -9.01759052277,-0.65824431181,9.66177749634 -8.99761295319,-0.658230662346,9.70134353638 -8.94864177704,-0.657211244106,9.70890903473 -8.89267253876,-0.656190395355,9.70847606659 -8.8397026062,-0.655170142651,9.71104240417 -8.7757358551,-0.653147578239,9.70160388947 -8.74175262451,-0.652135848999,9.69438552856 -8.71877479553,-0.653121709824,9.72896003723 -8.7137928009,-0.654111206532,9.78353977203 -8.71281051636,-0.655101537704,9.8431186676 -8.70782852173,-0.65709066391,9.90068340302 -8.69684791565,-0.658078789711,9.95025634766 -8.94279956818,-0.672119379044,10.2928876877 -8.9528055191,-0.67311668396,10.3366765976 -8.9508228302,-0.675106585026,10.3992538452 -8.95183944702,-0.677097141743,10.4658288956 -8.94085884094,-0.678085327148,10.5184059143 -8.9278793335,-0.679072916508,10.569975853 -8.92489719391,-0.680062711239,10.6325540543 -8.93390274048,-0.682059586048,10.6773405075 -8.92492198944,-0.683048069477,10.7339162827 -8.92593860626,-0.685038506985,10.8034887314 -8.92095661163,-0.686027824879,10.8650693893 -8.91497516632,-0.688016891479,10.9266433716 -8.90699386597,-0.689005494118,10.9862184525 -8.90101242065,-0.690994620323,11.0477991104 -8.91001796722,-0.691991567612,11.0945863724 -8.90303707123,-0.693980336189,11.156162262 -9.00502681732,-0.700991332531,11.355755806 -3.45152568817,-0.398853331804,4.41258049011 -3.41655445099,-0.397836238146,4.39615488052 -3.38258290291,-0.396819621325,4.37974262238 -3.39259076118,-0.397816240788,4.40751504898 -3.37961292267,-0.397804141045,4.41711616516 -9.00012207031,-0.711936116219,11.7564201355 -8.98214435577,-0.712922632694,11.8079967499 -8.98216152191,-0.714912772179,11.8845720291 -8.96818256378,-0.71590000391,11.9431447983 -8.96120071411,-0.717888653278,12.0107221603 -8.97320556641,-0.718886077404,12.0665082932 -8.98521995544,-0.7218785882,12.1610870361 -8.97424030304,-0.723866522312,12.2246665955 -8.97825622559,-0.725857377052,12.3102426529 -8.97727394104,-0.727847099304,12.3898162842 -8.96929264069,-0.729835569859,12.459394455 -8.94731712341,-0.730820953846,12.5119609833 -8.94832515717,-0.731816351414,12.5527572632 -8.89835643768,-0.731795966625,12.5663194656 -8.84138870239,-0.730774283409,12.5688858032 -8.80041885376,-0.729755938053,12.593457222 -8.78044128418,-0.731741786003,12.6480321884 -8.78145885468,-0.733731865883,12.7346038818 -8.773478508,-0.735720098019,12.8081789017 -8.78348350525,-0.737717330456,12.8639755249 -8.77150440216,-0.738704741001,12.9325504303 -8.76652336121,-0.741693437099,13.0131196976 -8.75254535675,-0.742680549622,13.0796957016 -8.75256347656,-0.745670378208,13.1682710648 -8.74458312988,-0.747658669949,13.244849205 -8.75159072876,-0.748654961586,13.3006372452 -8.74860858917,-0.751644253731,13.3862133026 -8.73962879181,-0.753632307053,13.4627933502 -8.72565078735,-0.755619227886,13.533367157 -8.72266864777,-0.757608294487,13.6229362488 -8.71468830109,-0.759596526623,13.7035140991 -8.70171070099,-0.76158362627,13.7780866623 -8.7127161026,-0.763580858707,13.841881752 -8.69174003601,-0.76556634903,13.9044551849 -8.80572509766,-0.77557939291,14.1840486526 -9.19363212585,-0.802648246288,14.9116783142 -9.15366172791,-0.803629755974,14.9512472153 -9.13868427277,-0.80561631918,15.0318212509 -10.563284874,-0.899902105331,17.4318180084 -10.4943227768,-0.898877620697,17.4403839111 -9.10373783112,-0.810583472252,15.2397584915 -9.11375331879,-0.814575135708,15.3653345108 -8.89283466339,-0.8035197258,15.1008777618 -8.78388404846,-0.799487292767,15.0214443207 -8.75690937042,-0.800471365452,15.0830173492 -8.76491641998,-0.802467763424,15.1518039703 -9.07584476471,-0.826520800591,15.8014240265 -9.06886482239,-0.829508900642,15.9039974213 -9.09687423706,-0.835504174232,16.0695762634 -9.09189319611,-0.838492810726,16.177154541 -9.07891559601,-0.840479671955,16.2737255096 -9.59178447723,-0.880573511124,17.3193683624 -9.58079719543,-0.881566166878,17.362159729 -9.50983524323,-0.880541205406,17.3617248535 -8.81905460358,-0.835390210152,16.2212104797 -8.71110439301,-0.831357598305,16.1437683105 -8.67613315582,-0.832340121269,16.1983451843 -8.62016773224,-0.831318199635,16.2159118652 -8.55120658875,-0.830293715,16.2074813843 -8.55021572113,-0.832288205624,16.2672691345 -8.54023647308,-0.83527559042,16.3728408813 -8.53325748444,-0.838263630867,16.4844169617 -8.51728057861,-0.841249883175,16.5799922943 -8.51430034637,-0.844238877296,16.7005729675 -8.49732398987,-0.847224712372,16.7981433868 -8.51732635498,-0.850223481655,16.9029331207 -8.50234985352,-0.853210031986,17.0035133362 -8.49537086487,-0.85719794035,17.1230888367 -8.47839355469,-0.86018383503,17.2246608734 -8.47141456604,-0.863171875477,17.3462371826 -8.46043586731,-0.86615896225,17.4618110657 -8.51043987274,-0.875158429146,17.7063922882 -11.4655723572,-1.10875177383,23.9475364685 -10.6758422852,-1.05757021904,22.6605892181 -11.1787109375,-1.10366106033,23.9232215881 -11.0997524261,-1.10363423824,23.9487857819 -10.6839208603,-1.08452284336,23.5316753387 -10.5839691162,-1.08249175549,23.5062389374 -10.4830179214,-1.08046042919,23.4788017273 -10.4070587158,-1.08043420315,23.5063667297 -10.3221025467,-1.07940614223,23.5129318237 -10.2331476212,-1.07837736607,23.5094966888 -10.1761741638,-1.07636034489,23.4772815704 -10.0892190933,-1.07533192635,23.4778461456 -10.0002632141,-1.07330298424,23.474407196 -9.91330814362,-1.07227468491,23.4719772339 -9.82635307312,-1.07124614716,23.471540451 -9.73939800262,-1.07021772861,23.4701061249 -9.65144252777,-1.06918907166,23.464673996 -9.59546947479,-1.06717228889,23.4334545135 -9.5175113678,-1.06614565849,23.4520225525 -9.42455863953,-1.06511616707,23.4315910339 -9.34260177612,-1.06408858299,23.4401569366 -9.25864696503,-1.0630607605,23.4427242279 -9.16869258881,-1.06103181839,23.4282932281 -9.08873558044,-1.06100475788,23.4398612976 -9.03176212311,-1.05898797512,23.4016418457 -8.95180606842,-1.05796098709,23.4112129211 -8.86585140228,-1.05693280697,23.4067802429 -8.78089618683,-1.05590474606,23.4043464661 -8.69594097137,-1.05487680435,23.3999137878 -8.61098670959,-1.05384886265,23.3944854736 -8.56101131439,-1.05183339119,23.3722686768 -8.48105430603,-1.05180644989,23.3798370361 -8.39709949493,-1.0507786274,23.3754081726 -8.31314468384,-1.04975104332,23.3709793091 -8.23018932343,-1.04872334003,23.3705463409 -8.14923381805,-1.04769635201,23.3711204529 -8.06127929688,-1.04566788673,23.3546867371 -8.01830196381,-1.04565370083,23.3504695892 -7.93434762955,-1.04362618923,23.3410453796 -7.85739088058,-1.04359984398,23.3536148071 -7.76743793488,-1.04157090187,23.3301811218 -7.68948125839,-1.04154443741,23.3397521973 -7.60552692413,-1.04051685333,23.3283252716 -7.52457141876,-1.03948974609,23.3278961182 -7.47459697723,-1.03747427464,23.2986793518 -4.13664150238,-0.671804010868,13.0150718689 -4.08367872238,-0.669782698154,12.9916410446 -4.04770994186,-0.670765221119,13.0172252655 -7.15377426147,-1.03436696529,23.2959690094 -7.06982040405,-1.03333938122,23.283536911 -6.99386358261,-1.03231346607,23.2931137085 -6.9498872757,-1.03129923344,23.2808971405 -6.86893224716,-1.03127229214,23.2754688263 -6.7849779129,-1.02924489975,23.2560462952 -6.71002149582,-1.02921903133,23.2716159821 -6.62706661224,-1.0281919241,23.255191803 -6.55011034012,-1.02716565132,23.2627620697 -6.50613451004,-1.0261516571,23.2455501556 -6.42817878723,-1.02612543106,23.2461242676 -6.34522438049,-1.02409815788,23.2287006378 -6.26826810837,-1.02407205105,23.2332725525 -6.18631410599,-1.02304506302,23.2198429108 -6.11435651779,-1.02302014828,23.2404193878 -6.03140258789,-1.0209928751,23.2219924927 -5.9884262085,-1.01997900009,23.2057800293 -5.90647172928,-1.01895201206,23.1873531342 -5.8335146904,-1.01892673969,23.2059288025 -5.75156068802,-1.01789999008,23.1865024567 -5.67760419846,-1.01787471771,23.1960811615 -5.59864902496,-1.01684832573,23.1886558533 -5.55867147446,-1.01583516598,23.1834411621 -5.47871685028,-1.01480865479,23.1670207977 -5.4037604332,-1.01478326321,23.1745948792 -5.32180643082,-1.01375627518,23.1541671753 -5.24784994125,-1.0127311945,23.1617450714 -5.16989469528,-1.01170516014,23.1523227692 -5.09493923187,-1.01167976856,23.1588973999 -5.05196237564,-1.01066589355,23.1366863251 -3.36351037025,-0.749329328537,15.6122303009 -3.30654859543,-0.748307883739,15.5808172226 -3.26158380508,-0.749288499355,15.6123914719 -3.21761822701,-0.749269545078,15.6439752579 -4.93910074234,-1.05358970165,24.4575767517 -3.0517115593,-0.73721653223,15.3201370239 -3.02273130417,-0.73720562458,15.3009243011 -2.96876883507,-0.736184716225,15.278506279 -2.92780256271,-0.737166404724,15.3220891953 -2.92382502556,-0.74515491724,15.5706634521 -2.87186217308,-0.744134366512,15.5622444153 -2.82489752769,-0.745114922523,15.5788288116 -2.82091975212,-0.753103613853,15.8384113312 -2.79193925858,-0.753092765808,15.8211994171 -2.74797415733,-0.754073917866,15.8607816696 -2.70001006126,-0.754054129124,15.881360054 -2.65604496002,-0.755035221577,15.9249401093 -2.61707830429,-0.758017241955,16.0015201569 -4.82240629196,-1.24342536926,30.1931037903 -4.78043031693,-1.24541187286,30.2358913422 -4.68648052216,-1.24538302422,30.2554702759 -4.58753252029,-1.24435341358,30.2420482635 -4.53057146072,-1.25333154202,30.515625 -4.49860239029,-1.26831459999,30.9682044983 -4.52861404419,-1.29830944538,31.8837833405 -4.59961223602,-1.34131193161,33.1353645325 -4.64060974121,-1.36431407928,33.8261528015 -4.54366111755,-1.36628484726,33.9107322693 -4.43371677399,-1.36525309086,33.8953056335 -4.38175392151,-1.38023233414,34.338886261 -4.31779527664,-1.39220952988,34.7044639587 -4.4007897377,-1.44721412659,36.3130455017 -4.41479587555,-1.46721124649,36.9118347168 -2.73734664917,-1.00788593292,23.4364204407 -2.6613919735,-1.00686109066,23.4270000458 -4.1639380455,-1.49713146687,37.8345718384 -2.58645796776,-1.02982580662,24.1201629639 -2.50450468063,-1.02779996395,24.0637435913 -2.43654751778,-1.02977669239,24.1513252258 -3.99306583405,-1.58206117153,40.3770942688 -2.29062533379,-1.01873362064,23.8236980438 -2.20967197418,-1.0167080164,23.7662792206 -3.81918430328,-1.65999627113,42.7268371582 -3.70024299622,-1.66696321964,42.9254150391 -3.7752404213,-1.75296628475,45.4729995728 -3.6363055706,-1.75492954254,45.5375747681 -3.61332345009,-1.77591991425,46.1653633118 -3.53436970711,-1.80589437485,47.0649452209 -3.53639030457,-1.87688398361,49.1705245972 -3.38745856285,-1.8798456192,49.2631034851 -3.29650855064,-1.91181814671,50.2416877747 -3.1805665493,-1.9347859621,50.9282646179 -3.13260316849,-1.99976623058,52.8468437195 -3.09562516212,-2.02675414085,53.655632019 -3.28758573532,-2.25277876854,60.3212127686 -3.09566783905,-2.25073242188,60.2947921753 -1.76411116123,-1.44147825241,36.3814048767 -2.71683073044,-2.2506415844,60.3049545288 -2.5399081707,-2.26059865952,60.6075401306 -1.52224123478,-1.47840797901,37.4893608093 -1.41129767895,-1.48437726498,37.6829452515 -1.29435610771,-1.48534560204,37.7235298157 -1.13442826271,-1.44030618668,36.3881111145 -1.01948595047,-1.43927502632,36.3547019958 -0.929535865784,-1.47224831581,37.3362846375 -1.60334455967,-2.74435925484,74.9368209839 -1.53237783909,-2.82534122467,77.3376083374 -0.872608244419,-1.96121180058,51.8032188416 -0.716679275036,-1.98017334938,52.3758010864 -0.550753176212,-1.97313320637,52.1553878784 -0.3848272264,-1.96209311485,51.835975647 --0.178926825523,-2.2539601326,74.4276885986 --0.412831217051,-2.25690817833,74.5282745361 --0.651734054089,-2.27285552025,75.1358642578 --1.46340155602,-2.25267624855,74.3774185181 --1.65831828117,-2.20463180542,72.6330108643 --11.3652276993,-1.98257088661,63.6093978882 --11.5741424561,-1.98353016376,63.6220092773 --11.8660306931,-1.99747610092,64.0866241455 --11.9269914627,-1.97645998001,63.3022270203 --12.1329059601,-1.97742021084,63.2988395691 --12.2468509674,-1.9653955698,62.8244400024 --12.3977937698,-1.97336792946,63.0722503662 --15.3158569336,-2.35488891602,76.6770629883 --11.3330898285,-1.77052819729,55.783367157 --11.4580307007,-1.76450157166,55.5019760132 --11.6319561005,-1.76446723938,55.465587616 --15.5896949768,-2.26382470131,73.2384796143 --12.0157966614,-1.76839327812,55.5528106689 --14.6419639587,-2.09696912766,67.2158050537 --14.5999574661,-2.06397080421,66.0234069824 --14.598938942,-2.03796553612,65.0420074463 --14.801856041,-2.0379281044,64.989616394 --15.0117721558,-2.03888988495,64.9722366333 --15.2246866226,-2.03985095024,64.9588546753 --15.4426002502,-2.0408115387,64.9704742432 --15.5435590744,-2.04079318047,64.940284729 --10.6520471573,-1.43155395985,43.256061554 --10.7559757233,-1.41252481937,42.5202636719 --15.4235029221,-1.91478836536,60.2332763672 --15.2745399475,-1.88780927658,59.2620658875 --15.2465305328,-1.86480891705,58.3886642456 --11.4316987991,-1.43439769745,43.188911438 --15.1425256729,-1.81481552124,56.5318527222 --11.5316286087,-1.41637003422,42.4821128845 --11.6645679474,-1.41634356976,42.4437255859 --15.295422554,-1.77577781677,55.0176696777 --15.3773870468,-1.77476274967,54.977481842 --15.5713090897,-1.77672839165,55.0041007996 --8.76040172577,-1.07976782322,30.5220184326 --8.85335254669,-1.07974672318,30.4826183319 --16.125082016,-1.78063035011,54.9759559631 --9.84000873566,-1.15658283234,33.110912323 --9.91696548462,-1.15356469154,32.991519928 --16.5858955383,-1.78354978561,54.9440040588 --16.768819809,-1.78451800346,54.9246292114 --9.50904369354,-1.09161007404,30.7454605103 --9.59699726105,-1.09059035778,30.6880645752 --11.625333786,-1.25627338886,36.3904800415 --11.6313228607,-1.25226962566,36.2122802734 --14.217508316,-1.47187769413,43.8161621094 --14.185500145,-1.45687770844,43.2497596741 --14.1474933624,-1.44187855721,42.6813545227 --14.1174840927,-1.42787826061,42.1449508667 --14.0764789581,-1.41287946701,41.5865440369 --14.0444698334,-1.39887940884,41.0651397705 --13.9494905472,-1.3858910799,40.5769309998 --13.932477951,-1.373888731,40.1135253906 --11.5281963348,-1.16323637962,32.8378410339 --13.9204454422,-1.35188102722,39.277721405 --13.9084310532,-1.3408780098,38.8533210754 --13.8874197006,-1.32887637615,38.4119186401 --13.8754053116,-1.31887340546,38.0055160522 --13.8024187088,-1.3078815937,37.6193084717 --13.7794075012,-1.296880126,37.1929016113 --13.7583961487,-1.28587853909,36.779499054 --13.7433824539,-1.27587592602,36.3890991211 --13.7133741379,-1.2648755312,35.9666938782 --13.6953611374,-1.25487339497,35.581287384 --13.6513662338,-1.24687731266,35.3000831604 --13.8442897797,-1.25284516811,35.4677085876 --13.7882890701,-1.23984849453,34.9952964783 --13.7632789612,-1.22984743118,34.6108932495 --13.7442674637,-1.22084546089,34.2484931946 --13.7422494888,-1.21284115314,33.93309021 --13.7442321777,-1.20483636856,33.6326904297 --13.4403142929,-1.17887675762,32.7394523621 --13.432299614,-1.17087316513,32.4260444641 --13.4252843857,-1.16386950016,32.1216430664 --13.4062719345,-1.15486752987,31.7952423096 --13.387260437,-1.1468654871,31.4708347321 --13.3712472916,-1.1388630867,31.1594333649 --13.3572340012,-1.13086032867,30.8560276031 --13.2842473984,-1.12286818027,30.5568199158 --13.3642063141,-1.1208524704,30.4754257202 --13.4771547318,-1.1228325367,30.4730415344 --13.5731086731,-1.12281501293,30.4306545258 --13.2181806564,-1.08585417271,29.1358032227 --13.1771831512,-1.0798573494,28.9215927124 --13.1651697159,-1.07385444641,28.6561927795 --13.1561546326,-1.06685113907,28.3987884521 --13.1361436844,-1.05984926224,28.1223831177 --13.1281290054,-1.05384588242,27.8749809265 --13.1181144714,-1.04684257507,27.6265773773 --13.1091003418,-1.04083931446,27.3841762543 --13.0531082153,-1.0348443985,27.1559638977 --13.0500917435,-1.02884030342,26.9315643311 --13.0600719452,-1.02483451366,26.737165451 --13.1360311508,-1.02382004261,26.677772522 --9.17418479919,-0.773333907127,18.4497261047 --9.16816806793,-0.769328534603,18.2913169861 --9.31010818481,-0.775304019451,18.4299354553 --13.150967598,-1.00680279732,25.9803752899 --9.06715202332,-0.755326449871,17.7372894287 --9.11411952972,-0.754314243793,17.6898880005 --9.18608093262,-0.75529897213,17.6924953461 --9.43498897552,-0.766261041164,18.0341320038 --9.59792423248,-0.773234426975,18.2077598572 --9.74986934662,-0.780212163925,18.4265823364 --9.8558216095,-0.783193051815,18.487197876 --12.8479290009,-0.95380884409,23.949306488 --12.843914032,-0.948804974556,23.7619075775 --12.8768873215,-0.946796476841,23.6435108185 --12.9578475952,-0.946781992912,23.6151237488 --9.67978286743,-0.7561866045,17.4801387787 --9.69976902008,-0.756181240082,17.4509410858 --9.7627325058,-0.756167709827,17.4335441589 --13.2946910858,-0.951725482941,23.6077766418 --13.3896474838,-0.95270973444,23.6013908386 --13.4826030731,-0.953694343567,23.5920085907 --13.5735607147,-0.954679310322,23.578622818 --13.6665172577,-0.955664038658,23.567237854 --13.7324905396,-0.956654071808,23.5950469971 --13.8154506683,-0.957640349865,23.5676651001 --13.8674192429,-0.956630289555,23.4852714539 --13.9153900146,-0.954620838165,23.3978805542 --14.0023488998,-0.955606818199,23.3764972687 --14.1282958984,-0.958588182926,23.4191207886 --14.2132635117,-0.960576295853,23.475933075 --14.3322143555,-0.963558733463,23.5055580139 --14.4141750336,-0.963545620441,23.4721698761 --14.5281267166,-0.965528905392,23.4927940369 --14.6310815811,-0.967513561249,23.4924106598 --14.7340364456,-0.96849834919,23.4930305481 --14.8090000153,-0.96848654747,23.4486484528 --14.8539800644,-0.969479739666,23.4364528656 --14.9669322968,-0.971463680267,23.4520778656 --15.0888824463,-0.973446667194,23.4787006378 --15.1838407516,-0.974432885647,23.4643211365 --15.2807970047,-0.976418972015,23.4509391785 --15.3787546158,-0.977405071259,23.4395599365 --15.4777116776,-0.978391170502,23.4291801453 --15.5386867523,-0.979382991791,23.440990448 --15.5196771622,-0.975382506847,23.2515888214 --15.7296037674,-0.981356501579,23.4072322845 --15.818564415,-0.982344090939,23.3798503876 --15.9225206375,-0.984330117702,23.3744735718 --16.0164794922,-0.985317468643,23.3540935516 --16.1034469604,-0.987306773663,23.4029140472 --12.3684749603,-0.80371516943,17.8257465363 --11.6616544724,-0.766788482666,16.6861934662 --11.9225664139,-0.776755750179,16.946844101 --12.49239254,-0.801689863205,17.6435642242 --12.083489418,-0.778730094433,16.9470710754 --12.5623407364,-0.799674630165,17.5067768097 --12.5743303299,-0.798671483994,17.4655799866 --12.4893379211,-0.791676819324,17.2311611176 --12.1944026947,-0.775704264641,16.7086906433 --12.0854177475,-0.767711877823,16.4482650757 --12.902176857,-0.803621947765,17.4510383606 --12.1643638611,-0.766695678234,16.3374767303 --12.1133623123,-0.762697041035,16.1610622406 --12.2143268585,-0.765684604645,16.2428836823 --12.3222818375,-0.76866966486,16.2805099487 --12.3802499771,-0.768659889698,16.2491168976 --12.3842334747,-0.766655743122,16.1477146149 --12.4292058945,-0.765647470951,16.100320816 --8.88814926147,-0.605002343655,11.4030990601 --8.89113998413,-0.603999376297,11.3698987961 --8.93011283875,-0.603989958763,11.3444976807 --8.99507808685,-0.605978131294,11.3541126251 --9.09003543854,-0.607963323593,11.4007329941 --12.1681909561,-0.742653369904,15.2030515671 --12.6670427322,-0.76260048151,15.7277622223 --12.3001251221,-0.743633031845,15.1702766418 --12.7789888382,-0.763584434986,15.7141857147 --12.740983963,-0.759584784508,15.5667800903 --12.7699613571,-0.758578658104,15.5013828278 --12.9748926163,-0.765555620193,15.6510324478 --12.8928995132,-0.760560274124,15.4506092072 --12.8578939438,-0.756560385227,15.3081960678 --12.9718484879,-0.759546399117,15.3458223343 --12.9648427963,-0.757545471191,15.2886219025 --13.214761734,-0.766518890858,15.4852781296 --13.3607091904,-0.770502269268,15.5569114685 --13.5406475067,-0.776482701302,15.6685590744 --13.112745285,-0.756519436836,15.0710487366 --13.1417226791,-0.755513846874,15.0086584091 --13.0807247162,-0.750516474247,14.8432435989 --13.1047115326,-0.750512778759,14.8220434189 --13.1436872482,-0.750506341457,14.7716531754 --13.187661171,-0.750499486923,14.7262592316 --13.332608223,-0.754483699799,14.7948951721 --13.3026027679,-0.751483678818,14.6684923172 --13.7594690323,-0.76844060421,15.0792016983 --15.5310049057,-0.839283466339,16.9834442139 --15.4040250778,-0.832293093204,16.7370147705 --14.6182136536,-0.798359870911,15.7754182816 --12.0388631821,-0.691580474377,12.8853578568 --12.043847084,-0.690576732159,12.8089580536 --12.0368337631,-0.68857395649,12.7195520401 --12.0318202972,-0.686571061611,12.633146286 --12.0498085022,-0.68656796217,12.6129560471 --12.1227750778,-0.687558531761,12.6095724106 --12.1727485657,-0.688551127911,12.5811815262 --12.159737587,-0.686549067497,12.4877767563 --12.1737194061,-0.685544788837,12.4233808517 --12.154709816,-0.682543158531,12.3239679337 --12.161693573,-0.681539475918,12.2525672913 --12.1346931458,-0.679540097713,12.1863594055 --12.1316795349,-0.678537249565,12.106962204 --12.1266670227,-0.676534533501,12.02455616 --12.1366500854,-0.675530672073,11.957151413 --12.1216392517,-0.673528790474,11.8667478561 --12.1206245422,-0.671525835991,11.790345192 --12.1366071701,-0.671521544456,11.7309474945 --12.1296014786,-0.670520603657,11.6867437363 --12.1485824585,-0.669516146183,11.6313505173 --12.1495685577,-0.668513119221,11.5579471588 --12.1445550919,-0.666510522366,11.4785375595 --12.1445417404,-0.665507614613,11.4061393738 --12.1455278397,-0.66350466013,11.3347396851 --12.1165275574,-0.66150534153,11.2715320587 --12.1185131073,-0.660502254963,11.2011270523 --12.1194992065,-0.659499287605,11.1297206879 --12.11348629,-0.657496929169,11.0533189774 --12.1104736328,-0.656494319439,10.9799156189 --12.1124591827,-0.655491292477,10.9115133286 --12.1114454269,-0.653488576412,10.8411130905 --12.0894432068,-0.652488768101,10.7869081497 --12.0914297104,-0.651485741138,10.7185001373 --12.0834169388,-0.649483561516,10.6430978775 --12.0334157944,-0.646484196186,10.5306825638 --12.0244045258,-0.645482063293,10.4552783966 --12.0293893814,-0.644478976727,10.391875267 --12.0443725586,-0.643475234509,10.3374729156 --12.0593614578,-0.643472909927,10.3172769547 --12.056347847,-0.642470479012,10.248878479 --12.0603342056,-0.641467511654,10.1864795685 --12.0543222427,-0.639465272427,10.1150722504 --12.0543079376,-0.638462662697,10.0496702194 --12.0492963791,-0.637460291386,9.98026561737 --12.0532827377,-0.636457502842,9.91886425018 --12.0322809219,-0.634457528591,9.8696603775 --12.0332660675,-0.633454859257,9.80525112152 --12.028254509,-0.632452607155,9.73785018921 --12.0242414474,-0.631450295448,9.67044353485 --12.0282278061,-0.630447566509,9.61104488373 --12.0192165375,-0.62844568491,9.54164409637 --12.0172042847,-0.627443253994,9.47723865509 --11.9962024689,-0.626443266869,9.42902851105 --11.9931898117,-0.625440955162,9.36462402344 --11.9931764603,-0.624438524246,9.30322265625 --11.983165741,-0.622436642647,9.23482227325 --11.9431610107,-0.620436489582,9.14240455627 --11.9421491623,-0.619434118271,9.08100032806 --11.9231462479,-0.618433892727,9.03679656982 --11.9221334457,-0.61743158102,8.97538948059 --11.9641113281,-0.617426931858,8.94800186157 --11.9551000595,-0.616425096989,8.88159561157 --11.9780826569,-0.616421580315,8.84020423889 --5.52748632431,-0.394746601582,3.97059440613 --5.55846214294,-0.394738644361,3.9661962986 --5.55645418167,-0.394735515118,3.95099020004 --11.9390335083,-0.610413372517,8.54737472534 --11.9400205612,-0.609411120415,8.49097633362 --11.9380073547,-0.608408987522,8.43156909943 --11.9299974442,-0.607407212257,8.36916637421 --11.928984642,-0.606405138969,8.3117647171 --11.912981987,-0.605404794216,8.27256202698 --11.9129695892,-0.604402601719,8.21615791321 --11.9129571915,-0.604400515556,8.15975475311 --11.9089450836,-0.603398561478,8.10135269165 --11.9009342194,-0.601396858692,8.03994464874 --11.9059209824,-0.601394593716,7.98854827881 --11.8969106674,-0.600392878056,7.92714166641 --11.8949050903,-0.599391937256,7.89793682098 --11.8788948059,-0.598390579224,7.83152198792 --11.8398914337,-0.59639018774,7.75211429596 --11.841878891,-0.595388054848,7.69870758057 --11.8438663483,-0.594386041164,7.64731407166 --11.8418540955,-0.59338414669,7.59190702438 --11.8358440399,-0.59238243103,7.53450202942 --11.8248386383,-0.591381847858,7.50029277802 --11.8228273392,-0.591380059719,7.4468960762 --11.8168172836,-0.590378284454,7.38948583603 --11.8118057251,-0.589376568794,7.33408355713 --11.812792778,-0.58837467432,7.28268384933 --11.8157806396,-0.587372779846,7.2322807312 --11.8127689362,-0.587371051311,7.17888021469 --11.7837696075,-0.585371017456,7.1346654892 --11.6887760162,-0.581372261047,7.02523326874 --11.6687688828,-0.580371081829,6.96182060242 --11.6667566299,-0.579369306564,6.91042041779 --11.6617450714,-0.578367590904,6.85600805283 --11.6627340317,-0.57836574316,6.8066072464 --11.6617279053,-0.577364861965,6.78140878677 --11.7097072601,-0.578361749649,6.76002454758 --11.7516870499,-0.579358875751,6.73463582993 --11.7766704559,-0.579356491566,6.69924211502 --11.7706594467,-0.578355014324,6.64583683014 --11.7656488419,-0.577353477478,6.59343290329 --11.7636375427,-0.577351987362,6.54303121567 --11.7496347427,-0.576351523399,6.51082801819 --11.7516231537,-0.575349926949,6.46242284775 --11.753610611,-0.575348317623,6.4140162468 --11.7386026382,-0.573347151279,6.35761404037 --11.7765846252,-0.574344754219,6.32921886444 --11.8475599289,-0.576341807842,6.31984472275 --11.924533844,-0.577338814735,6.31246566772 --12.0115127563,-0.580336511135,6.33630657196 --12.0674905777,-0.581334173679,6.31692123413 --12.1404657364,-0.58333170414,6.30654525757 --12.2154426575,-0.584329307079,6.29717206955 --12.2244300842,-0.584328114986,6.25277614594 --12.2284183502,-0.583327054977,6.20537376404 --12.3013944626,-0.585324943066,6.19399929047 --12.3043889999,-0.585324466228,6.1707983017 --12.3013782501,-0.584323644638,6.11939048767 --12.2943696976,-0.583322882652,6.0669875145 --12.2883605957,-0.583322167397,6.01558732986 --12.2913484573,-0.582321345806,5.96818447113 --12.2913389206,-0.581320524216,5.91978359222 --12.2793302536,-0.581319868565,5.86537647247 --12.2743263245,-0.580319583416,5.83917665482 --12.2733163834,-0.57931882143,5.79077577591 --12.2773046494,-0.579318106174,5.74437236786 --12.2742958069,-0.578317463398,5.69496822357 --12.2762851715,-0.578316807747,5.64857006073 --12.2782745361,-0.577316105366,5.60116195679 --12.2582731247,-0.576315939426,5.56896114349 --12.2582626343,-0.576315283775,5.52155780792 --12.2572536469,-0.575314760208,5.47415733337 --12.2482452393,-0.575314223766,5.42274904251 --12.2582330704,-0.574313640594,5.38035058975 --12.2532234192,-0.574313163757,5.3309431076 --12.249215126,-0.573312699795,5.28253889084 --12.2422113419,-0.573312461376,5.256336689 --12.23620224,-0.572311937809,5.20692873001 --12.2361927032,-0.571311533451,5.16153383255 --12.2341833115,-0.571311116219,5.11412715912 --12.2361736298,-0.570310771465,5.06872320175 --12.2321643829,-0.570310413837,5.02132081985 --12.2301549911,-0.569310069084,4.97491931915 --12.2271509171,-0.56930989027,4.95071601868 --12.2191429138,-0.568309545517,4.90231466293 --11.8571891785,-0.557307183743,4.70776796341 --11.6382131577,-0.550305247307,4.57427597046 --11.6392040253,-0.550304591656,4.53187608719 --11.632194519,-0.549303770065,4.48546409607 --11.6311845779,-0.549303114414,4.44306850433 --11.6201820374,-0.548302710056,4.41685771942 --11.6271705627,-0.548302173615,4.37746191025 --11.6221618652,-0.547301590443,4.33305740356 --11.6211519241,-0.547300994396,4.29065799713 --11.6201429367,-0.546300411224,4.24724769592 --11.6161346436,-0.546299874783,4.20384597778 --11.6101255417,-0.545299291611,4.15944004059 --11.6171197891,-0.545299172401,4.14124298096 --11.5991125107,-0.544298410416,4.09283447266 --11.5991029739,-0.544297933578,4.05042505264 --11.606092453,-0.544297635555,4.01203298569 --11.6060838699,-0.543297290802,3.97063159943 --11.5970754623,-0.54329675436,3.92521882057 --11.6070642471,-0.543296635151,3.88782477379 --11.5850629807,-0.542296051979,3.85961556435 --11.5900535583,-0.54229581356,3.82021594048 --11.5920438766,-0.541295588017,3.77880430222 --11.5850362778,-0.541295170784,3.73640871048 --11.5780277252,-0.540294826031,3.69300198555 --11.5900173187,-0.540294885635,3.65559887886 --11.5680103302,-0.53929412365,3.60819292068 --11.4240245819,-0.535290360451,3.53992080688 --11.4280147552,-0.535290181637,3.50152373314 --11.4260063171,-0.534289896488,3.46112251282 --11.4159984589,-0.534289419651,3.41771221161 --11.4249897003,-0.534289479256,3.38131952286 --11.4139814377,-0.533289015293,3.33790969849 --11.4109725952,-0.533288776875,3.29750752449 --11.4179677963,-0.533288896084,3.27930378914 --11.407959938,-0.532288491726,3.23689818382 --11.4029521942,-0.532288253307,3.19649887085 --11.4079427719,-0.531288385391,3.1580927372 --11.398935318,-0.531288027763,3.11669158936 --11.3979263306,-0.531287968159,3.07728934288 --11.3969221115,-0.530287921429,3.05708384514 --11.3839149475,-0.530287444592,3.0146791935 --11.3849067688,-0.529287576675,2.97526931763 --11.3948965073,-0.529288053513,2.93886852264 --11.3848905563,-0.529287755489,2.89746379852 --11.372882843,-0.528287410736,2.85606169701 --11.3828725815,-0.528288006783,2.81965970993 --11.3698701859,-0.528287529945,2.79644775391 --11.3698625565,-0.527287721634,2.75804686546 --11.4078502655,-0.528289556503,2.72966504097 --11.3838443756,-0.527288794518,2.6852543354 --11.3498392105,-0.52628749609,2.63783121109 --11.3588314056,-0.526288211346,2.60142874718 --11.3768215179,-0.526289403439,2.56803917885 --11.4198131561,-0.528291642666,2.55986332893 --11.449801445,-0.52829349041,2.52847242355 --11.4757909775,-0.529295265675,2.49608039856 --11.50578022,-0.529297292233,2.46469259262 --11.6837558746,-0.534307003021,2.46636605263 --11.5007658005,-0.529298245907,2.38688731194 --11.447763443,-0.527296125889,2.33645701408 --11.5187530518,-0.529300153255,2.33329129219 --11.6707305908,-0.533309161663,2.32795906067 --11.6977214813,-0.533311545849,2.29456520081 --11.7157125473,-0.534313440323,2.25916743279 --11.7507019043,-0.534316420555,2.22778320312 --11.7816925049,-0.535319268703,2.19539737701 --11.8186826706,-0.536322593689,2.16401362419 --11.8456764221,-0.537324786186,2.14982461929 --11.8876657486,-0.538328528404,2.11843681335 --11.9146575928,-0.538331449032,2.08505320549 --11.9576482773,-0.539335489273,2.05366802216 --11.9736404419,-0.539337873459,2.0172727108 --12.0276288986,-0.5413428545,1.98789703846 --12.0496244431,-0.541345059872,1.97170186043 --12.0976142883,-0.542349755764,1.94132828712 --12.1356048584,-0.543353974819,1.90794014931 --12.1675977707,-0.544357836246,1.87456178665 --12.2115879059,-0.545362651348,1.84218072891 --12.2455787659,-0.546366930008,1.80779361725 --12.2745714188,-0.546370923519,1.77240383625 --12.3165636063,-0.547375917435,1.73902153969 --12.3495578766,-0.548379302025,1.72383320332 --12.3805503845,-0.549383699894,1.68844664097 --12.4165430069,-0.5503885746,1.65406644344 --12.4635353088,-0.551394343376,1.62068736553 --12.5815219879,-0.55440568924,1.59734332561 --12.6235141754,-0.555411398411,1.56195676327 --12.6685066223,-0.55641746521,1.5275799036 --12.7285013199,-0.55842345953,1.51540982723 --12.7494955063,-0.558427870274,1.47701823711 --12.8024873734,-0.560434997082,1.4426420927 --12.8334817886,-0.5604403615,1.40525591373 --12.8774747849,-0.561446905136,1.36988162994 --12.9144697189,-0.56245303154,1.33249533176 --12.950466156,-0.563457608223,1.31631565094 --12.982460022,-0.564463555813,1.27792644501 --13.0334529877,-0.565471172333,1.24154698849 --13.067448616,-0.566477477551,1.20316076279 --13.1114425659,-0.567484676838,1.16679036617 --13.1474380493,-0.568491458893,1.12840723991 --13.2074317932,-0.57050037384,1.09203445911 --13.229429245,-0.570504248142,1.0728430748 --13.2884235382,-0.572513282299,1.03647565842 --13.3004198074,-0.572518229485,0.995081365108 --13.3514156342,-0.573526918888,0.956702888012 --13.3934116364,-0.574534893036,0.917320668697 --13.4344072342,-0.575542867184,0.877941131592 --13.4734039307,-0.576550722122,0.838564455509 --13.5094013214,-0.577556371689,0.819377958775 --13.5603971481,-0.578565716743,0.780002653599 --13.600394249,-0.580574035645,0.739623010159 --13.6433906555,-0.581582784653,0.699244916439 --13.6883878708,-0.582591950893,0.658869147301 --13.7383842468,-0.583601653576,0.61849552393 --13.7753820419,-0.584610342979,0.576106786728 --13.8303794861,-0.586618363857,0.557940483093 --13.8683776855,-0.586627304554,0.515555739403 --13.9183750153,-0.588637650013,0.474183350801 --13.9363737106,-0.588644683361,0.430792629719 --14.0063724518,-0.590657413006,0.389427036047 --14.0543699265,-0.591668009758,0.347053170204 --14.0933694839,-0.59267771244,0.303671509027 --14.1323680878,-0.593684792519,0.282489657402 --14.1933679581,-0.595697104931,0.240125745535 --14.2233667374,-0.596706211567,0.195739641786 --14.2683668137,-0.597717165947,0.151359289885 --12.9523849487,-0.561571002007,0.0752835944295 --14.3343667984,-0.599736511707,0.062598310411 --12.5893859863,-0.5515370965,-0.01270102337 --14.4713668823,-0.603761672974,-0.00292538199574 --14.5113668442,-0.604772686958,-0.0483038313687 --14.5563678741,-0.605784595013,-0.0946866199374 --12.8013782501,-0.557577550411,-0.152000769973 --12.2273788452,-0.54151147604,-0.193695411086 --14.6503715515,-0.607815623283,-0.232832446694 --12.1893749237,-0.540514647961,-0.271521091461 --14.7583742142,-0.610839307308,-0.303377717733 --12.0603723526,-0.536504268646,-0.329198092222 --12.1323699951,-0.53851723671,-0.367553561926 --12.0433673859,-0.536509811878,-0.405003964901 --12.2823677063,-0.542544841766,-0.447277128696 --12.330365181,-0.544555425644,-0.487656533718 --12.5563669205,-0.550589740276,-0.531934976578 --15.1423931122,-0.621936142445,-0.616763710976 --12.4433641434,-0.547581553459,-0.588596999645 --12.5613641739,-0.550602197647,-0.63193577528 --12.3323612213,-0.544575691223,-0.664465010166 --12.1813573837,-0.540559470654,-0.697947204113 --12.5313615799,-0.550612568855,-0.751161158085 --12.9353694916,-0.561671376228,-0.78814303875 --12.8803682327,-0.559669077396,-0.826571464539 --15.5974292755,-0.635059833527,-0.999509871006 --12.0613489151,-0.537562549114,-0.865814626217 --12.6283626556,-0.552648961544,-0.935912549496 --12.8413696289,-0.55868512392,-0.988194227219 --12.8843708038,-0.5606970191,-1.03156960011 --12.8873710632,-0.560700297356,-1.05277311802 --15.9284677505,-0.645157516003,-1.29452323914 --15.9814748764,-0.64617484808,-1.34889245033 --16.0454845428,-0.648194015026,-1.40425419807 --16.1014919281,-0.650212228298,-1.45962142944 --16.1615028381,-0.65123128891,-1.51598918438 --16.2245101929,-0.653250932693,-1.57234966755 --16.3025169373,-0.656268000603,-1.60450387001 --16.3215255737,-0.656281352043,-1.65889656544 --16.4065361023,-0.659305036068,-1.71824431419 --16.4715461731,-0.66132581234,-1.77660524845 --16.5325565338,-0.662346184254,-1.83496809006 --16.5925693512,-0.664366781712,-1.8943362236 --16.6545810699,-0.666387796402,-1.95369839668 --16.7315883636,-0.668405771255,-1.98785078526 --16.7855987549,-0.670425832272,-2.0472176075 --16.8536128998,-0.672448515892,-2.10857748985 --16.9246253967,-0.674471914768,-2.17093658447 --16.9856395721,-0.676493883133,-2.23229908943 --17.0566520691,-0.678517758846,-2.29565834999 --17.125667572,-0.68054163456,-2.35901689529 --17.2016773224,-0.682560741901,-2.39617371559 --17.2646923065,-0.684583842754,-2.45953464508 --17.3247051239,-0.686606764793,-2.52289700508 --15.2065706253,-0.628247797489,-2.29448103905 --14.7155418396,-0.614170730114,-2.27514839172 --14.9305639267,-0.620218455791,-2.35342979431 --14.5955457687,-0.611168146133,-2.35402202606 --14.7875642776,-0.617207288742,-2.40510845184 --14.4485435486,-0.607155382633,-2.40270066261 --14.3975458145,-0.606155395508,-2.44213151932 --14.6005687714,-0.612201929092,-2.52041530609 --14.598575592,-0.612210988998,-2.56680893898 --14.2225503922,-0.602150559425,-2.55443072319 --14.1325483322,-0.600142776966,-2.5858809948 --14.1325511932,-0.60014718771,-2.60807347298 --13.7385215759,-0.589081525803,-2.58770275116 --13.8725404739,-0.593115925789,-2.65602779388 --13.7825374603,-0.591107487679,-2.6854789257 --13.8355484009,-0.5921266675,-2.73984575272 --13.7925510406,-0.591127216816,-2.77726960182 --13.7255496979,-0.590123176575,-2.81071376801 --13.6815490723,-0.58911895752,-2.82493877411 --13.6265497208,-0.587116956711,-2.85937047005 --13.8205757141,-0.593164861202,-2.941655159 --13.7175712585,-0.59015339613,-2.96711730957 --13.6575717926,-0.589150488377,-3.00055408478 --13.6945819855,-0.590167224407,-3.05292963982 --13.6915845871,-0.590171277523,-3.07513284683 --13.4575653076,-0.584132313728,-3.07167100906 --13.2455463409,-0.578097224236,-3.07119488716 --13.6406002045,-0.590188980103,-3.20036292076 --13.4005784988,-0.583147764206,-3.19290184975 --13.4855947495,-0.586175024509,-3.25625061989 --13.6396207809,-0.590217351913,-3.33555650711 --13.6036205292,-0.589214622974,-3.35078334808 --13.5896263123,-0.589221119881,-3.39218473434 --13.5286254883,-0.588217675686,-3.42362260818 --13.2235927582,-0.580160737038,-3.39720892906 --13.0495767593,-0.575131714344,-3.39971256256 --13.1235933304,-0.577157199383,-3.46106410027 --13.268620491,-0.582199037075,-3.54138040543 --13.1876125336,-0.580185711384,-3.54362940788 --13.0045948029,-0.575154006481,-3.54214072227 --13.1186170578,-0.578189074993,-3.61446619034 --13.066617012,-0.577186942101,-3.64590239525 --12.8745965958,-0.572152495384,-3.6404235363 --12.9046087265,-0.573168754578,-3.69180297852 --12.8156023026,-0.571157634258,-3.71226167679 --12.7485990524,-0.56915140152,-3.73770332336 --12.6995954514,-0.568144261837,-3.74492311478 --12.7826156616,-0.571173548698,-3.812281847 --12.6946086884,-0.568161964417,-3.83073091507 --13.1946973801,-0.583291471004,-4.01582288742 --13.0036745071,-0.578255712986,-4.00634050369 --12.8366556168,-0.573225319386,-4.002846241 --12.9056711197,-0.576247096062,-4.04500293732 --12.960688591,-0.578270852566,-4.1063747406 --13.2127408981,-0.585343420506,-4.22662067413 --13.4827985764,-0.593421220779,-4.35385274887 --12.9217090607,-0.577292084694,-4.22859621048 --12.8287010193,-0.57527923584,-4.24505710602 --12.9707355499,-0.580325603485,-4.33437108994 --12.9257316589,-0.579319477081,-4.34259748459 --13.3508205414,-0.59143871069,-4.52273225784 --13.3108234406,-0.590440034866,-4.55716180801 --13.1378011703,-0.58640640974,-4.54666185379 --12.8997659683,-0.579355835915,-4.51521587372 --13.1368217468,-0.587428927422,-4.63946866989 --13.2028455734,-0.58945775032,-4.70782661438 --13.8099708557,-0.607624053955,-4.93564510345 --13.8039827347,-0.60763502121,-4.98204517365 --13.7309808731,-0.605628311634,-5.00649595261 --13.7179899216,-0.605637311935,-5.04989671707 --17.6318187714,-0.721710264683,-6.47284555435 --17.5348205566,-0.718703269958,-6.50130271912 --17.5828533173,-0.720735609531,-6.58066606522 --17.4898452759,-0.718719899654,-6.57892370224 --17.4718647003,-0.718734443188,-6.63533306122 --17.3558616638,-0.715721726418,-6.65580415726 --17.2868690491,-0.714721739292,-6.69224023819 --17.2128753662,-0.712720215321,-6.72668170929 --17.1588840485,-0.711724221706,-6.76811027527 --17.1098976135,-0.710730016232,-6.81254291534 --17.1929283142,-0.713763237,-6.8746843338 --17.1829490662,-0.714780330658,-6.93409109116 --17.3520126343,-0.71984899044,-7.06237792969 --17.2900218964,-0.718850970268,-7.10081005096 --24.3347434998,-0.929934561253,-9.96574115753 --24.6698684692,-0.941065788269,-10.1889152527 --25.0570068359,-0.95321393013,-10.4360589981 --25.6651821136,-0.972411990166,-10.7298679352 --25.678232193,-0.973451137543,-10.8292455673 --25.8133144379,-0.978527665138,-10.9805488586 --26.1094379425,-0.988653361797,-11.1997470856 --25.5063323975,-0.971506774426,-11.0425186157 --25.6154079437,-0.975576102734,-11.1838359833 --25.4854240417,-0.97257232666,-11.2233057022 --25.3544139862,-0.969550013542,-11.2145833969 --25.2794418335,-0.968562960625,-11.2770185471 --25.0364246368,-0.961523234844,-11.2655639648 --24.9884605408,-0.961544275284,-11.3389835358 --25.0195159912,-0.963590323925,-11.4473524094 --23.423122406,-0.916119098663,-10.8247718811 --23.7812671661,-0.92826718092,-11.075928688 --26.6431007385,-1.01620233059,-12.4232683182 --26.463104248,-1.01118421555,-12.442773819 --23.2112197876,-0.913168728352,-11.0392723083 --24.1045246124,-0.941494226456,-11.5450801849 --24.2226085663,-0.946569144726,-11.694396019 --24.0606098175,-0.942551791668,-11.7108898163 --24.7979068756,-0.966851353645,-12.2039880753 --24.7459430695,-0.966871798038,-12.2754096985 --16.4384365082,-0.711109995842,-8.32027339935 --16.3934497833,-0.710116803646,-8.36269950867 --16.3424606323,-0.710121572018,-8.4021320343 --16.3084774017,-0.7091319561,-8.44955062866 --16.2974872589,-0.709139108658,-8.47575283051 --16.2765102386,-0.710154235363,-8.53016471863 --16.2625331879,-0.710172057152,-8.58857536316 --16.2665634155,-0.711195707321,-8.6549654007 --16.2655925751,-0.712217926979,-8.71936130524 --14.392996788,-0.653577983379,-7.80902051926 --22.4917469025,-0.909479618073,-12.1209897995 --22.5788021088,-0.912528455257,-12.2121267319 --22.6368713379,-0.915585398674,-12.334479332 --22.2637939453,-0.904486954212,-12.2261171341 --22.2178287506,-0.904506325722,-12.2925415039 --22.0898323059,-0.901495635509,-12.3140192032 --22.876159668,-0.927820146084,-12.8348798752 --23.0432720184,-0.934919595718,-13.0211572647 --22.2750225067,-0.910654067993,-12.6428689957 --22.0200309753,-0.905632793903,-12.6848258972 --23.3155593872,-0.948157191277,-13.5093374252 --22.7233963013,-0.929972708225,-13.2691287994 --22.6634273529,-0.929988384247,-13.3295583725 --22.541437149,-0.926980376244,-13.3540306091 --22.5944843292,-0.929020404816,-13.4331922531 --22.4604854584,-0.926007390022,-13.4496707916 --20.5267944336,-0.865295469761,-12.4063835144 --20.4958305359,-0.865318417549,-12.4757986069 --20.4338550568,-0.865329146385,-12.5262327194 --20.3858852386,-0.864345550537,-12.5856609344 --22.4567623138,-0.933203458786,-13.9286289215 --19.4365768433,-0.836020350456,-12.1399011612 --20.5170612335,-0.872486948967,-12.886551857 --20.3790550232,-0.868467271328,-12.8900356293 --17.5289287567,-0.777348697186,-11.20840168 --23.4314289093,-0.971783339977,-14.9787120819 --23.19739151,-0.965731024742,-14.9342622757 --20.2832183838,-0.8715736866,-13.1876726151 --17.5660896301,-0.782469928265,-11.5037651062 --17.6551704407,-0.786537647247,-11.6390981674 --17.6342048645,-0.786559998989,-11.7045078278 --17.6563014984,-0.789631903172,-11.877281189 --17.3622150421,-0.781538963318,-11.7638845444 --17.3112354279,-0.780548155308,-11.8083143234 --17.2912483215,-0.78055524826,-11.834526062 --17.2082538605,-0.779550909996,-11.8579797745 --15.6405820847,-0.727903366089,-10.8794851303 --15.6786384583,-0.729947984219,-10.9778585434 --17.2574100494,-0.784667611122,-12.1301336288 --15.6457004547,-0.731989920139,-11.1006746292 --15.8218231201,-0.739096522331,-11.2959470749 --44.8786125183,-1.7250123024,-31.5416316986 --44.0993919373,-1.70176529884,-31.2055454254 --43.9474716187,-1.69979691505,-31.306022644 --19.4887485504,-0.867855548859,-14.1597194672 --43.0703468323,-1.67659926414,-31.0953788757 --43.0524902344,-1.67969059944,-31.2887611389 --43.0296287537,-1.68177950382,-31.4781455994 --42.9576721191,-1.68079638481,-31.5293827057 --42.8277549744,-1.67983615398,-31.6408424377 --42.1525688171,-1.66062247753,-31.3516921997 --41.9436149597,-1.65662419796,-31.4022121429 --41.5735740662,-1.64754915237,-31.3308448792 --17.3591327667,-0.807188510895,-13.3635978699 --18.7358779907,-0.855859816074,-14.4427986145 --17.476272583,-0.813298106194,-13.5811042786 --18.8330440521,-0.862986087799,-14.7035169601 --42.3336715698,-1.68936705589,-32.8419647217 --42.395866394,-1.6955010891,-33.1022911072 --14.3577899933,-0.709923863411,-11.5069637299 --16.8592014313,-0.79918050766,-13.537528038 --16.7451648712,-0.796142816544,-13.491812706 --16.5911331177,-0.792102396488,-13.4553184509 --42.4806442261,-1.71501922607,-34.1388893127 --42.5638580322,-1.72216916084,-34.4251976013 --42.3318977356,-1.71816134453,-34.4587364197 --40.3939590454,-1.65229022503,-33.1075172424 --40.2800521851,-1.65233647823,-33.2259712219 --40.2531166077,-1.65237462521,-33.3091773987 --40.1061935425,-1.65140414238,-33.4006538391 --39.9612693787,-1.6494345665,-33.4931335449 --42.0286598206,-1.72861218452,-35.4319915771 --39.3986701965,-1.6466165781,-33.9802207947 --31.8502082825,-1.37370824814,-27.7101631165 --30.8847427368,-1.34127748013,-27.0512599945 --30.78881073,-1.3403083086,-27.1377086639 --30.8499774933,-1.34642481804,-27.3630466461 --30.6539821625,-1.34140205383,-27.3625736237 --30.3639278412,-1.33432722092,-27.2771701813 --30.0738048553,-1.32520961761,-27.1045761108 --30.1840057373,-1.33235347271,-27.373878479 --29.5106983185,-1.31006371975,-26.9387607574 --29.0935516357,-1.29791331291,-26.7294559479 --28.9635925293,-1.29592216015,-26.7789363861 --28.9887371063,-1.30001854897,-26.9703025818 --29.2280254364,-1.31223642826,-27.3595046997 --29.0639781952,-1.30818486214,-27.2928180695 --28.8989963531,-1.3051738739,-27.3093223572 --28.8430900574,-1.30622553825,-27.4277477264 --29.2324886322,-1.32453536987,-27.9678401947 --29.2546367645,-1.32863402367,-28.1632041931 --29.7451152802,-1.35100769997,-28.808216095 --29.0717792511,-1.32870042324,-28.3401088715 --29.6542606354,-1.35308849812,-28.991859436 --29.3942146301,-1.34602332115,-28.9194374084 --39.4384765625,-1.81293809414,-42.477394104 --38.30078125,-1.77233612537,-41.5216445923 --39.963344574,-1.84555900097,-43.5797233582 --38.6446075439,-1.79990208149,-42.5513076782 --38.4456634521,-1.79690933228,-42.6008338928 --37.4102401733,-1.76549315453,-41.9863891602 --36.967086792,-1.75233137608,-41.7551078796 --35.7044219971,-1.73535478115,-42.0275344849 --35.5575180054,-1.73438978195,-42.1210250854 --35.2413444519,-1.72323513031,-41.8814620972 --35.3977088928,-1.73548591137,-42.3337173462 --36.0395202637,-1.77008616924,-43.3675804138 --24.4792613983,-1.27499163151,-29.956533432 --24.2712211609,-1.26993608475,-29.8930854797 --24.0862026215,-1.26589775085,-29.8586235046 --24.2704544067,-1.27608108521,-30.1786670685 --24.2716121674,-1.28018009663,-30.3730545044 --23.6603393555,-1.26192080975,-29.9983196259 --23.6645011902,-1.26602137089,-30.1947040558 --23.4804782867,-1.2619805336,-30.1552391052 --23.2964553833,-1.25793874264,-30.1137733459 --23.2665042877,-1.25896549225,-30.1729946136 --22.4099578857,-1.22850036621,-29.451461792 --22.6793899536,-1.24480772018,-29.9936332703 --22.7215919495,-1.25093996525,-30.2429866791 --22.6646957397,-1.25299572945,-30.3644237518 --23.6729106903,-1.30389750004,-31.9029903412 --22.158411026,-1.23574435711,-29.9854183197 --22.315738678,-1.24797034264,-30.3916778564 --22.4580535889,-1.25918650627,-30.7819480896 --22.3691253662,-1.25921797752,-30.862411499 --21.9077949524,-1.24194550514,-30.4331817627 --21.7537937164,-1.23892116547,-30.4196949005 --21.7079105377,-1.24098610878,-30.5561218262 --12.8962860107,-0.820722997189,-18.3745822906 --19.0093135834,-1.12197875977,-27.2513198853 --18.8302612305,-1.1179189682,-27.176858902 --18.2537536621,-1.09351980686,-26.5317287445 --13.1530504227,-0.847238659859,-19.3573627472 --13.1340789795,-0.848254323006,-19.3955821991 --13.0671024323,-0.848259150982,-19.4270362854 --12.9881105423,-0.847253322601,-19.4405002594 --12.951169014,-0.848284363747,-19.5159301758 --12.9002103806,-0.84830302,-19.5703716278 --13.8164110184,-0.898180663586,-21.0719985962 --13.830540657,-0.902263581753,-21.2353858948 --12.6351995468,-0.84425920248,-19.565788269 --12.3058481216,-0.828994512558,-19.1312675476 --12.1988182068,-0.826960504055,-19.0967559814 --12.1198225021,-0.825951933861,-19.1052246094 --12.068860054,-0.825968384743,-19.155664444 --12.0219049454,-0.826989412308,-19.2141075134 --11.9579257965,-0.826993525028,-19.2435569763 --13.1855478287,-0.892174899578,-21.2497138977 --12.9443540573,-0.883020102978,-21.0113143921 --12.9024162292,-0.884052753448,-21.0897521973 --12.8905191422,-0.887114405632,-21.2171592712 --17.9513225555,-1.16105163097,-29.5872516632 --10.960187912,-0.790394127369,-18.3546104431 --10.8751745224,-0.789374113083,-18.3430862427 --12.2481946945,-0.868820369244,-20.8235054016 --12.7630195618,-0.900404155254,-21.8344631195 --12.7331056595,-0.902452111244,-21.9388885498 --12.6701450348,-0.902466654778,-21.9863376617 --12.5551128387,-0.899429619312,-21.9468383789 --16.0421867371,-1.09806168079,-28.1242313385 --17.3391189575,-1.17343986034,-30.4723129272 --17.2521858215,-1.17346549034,-30.5407810211 --17.2393569946,-1.17856764793,-30.7391853333 --14.5517845154,-1.03597640991,-26.3932933807 --14.410738945,-1.03192663193,-26.3328113556 --13.6667881012,-0.994233131409,-25.1798553467 --12.433011055,-0.924960315228,-23.0311317444 --12.3790712357,-0.925988793373,-23.1025772095 --12.3661937714,-0.929061532021,-23.2489833832 --16.4706802368,-1.17564046383,-31.0508003235 --12.0519971848,-0.918893635273,-23.0100593567 --13.3351583481,-1.00040555,-25.6023292542 --12.1605367661,-0.936237573624,-23.6519603729 --12.894867897,-0.985159516335,-25.2427101135 --12.4713449478,-0.964776933193,-24.6154823303 --12.3793563843,-0.963768839836,-24.6249637604 --11.7775220871,-0.931169450283,-23.6278896332 --11.6564760208,-0.928122699261,-23.5713996887 --5.65851163864,-0.556150913239,-11.7169895172 --5.63453674316,-0.556163549423,-11.7584142685 --5.61256456375,-0.557178497314,-11.8038368225 --5.59059381485,-0.558193981647,-11.8502616882 --5.5706281662,-0.559212803841,-11.9026908875 --5.54264736176,-0.56022131443,-11.9371175766 --5.52067804337,-0.561237931252,-11.9855461121 --5.4866528511,-0.56021797657,-11.9617815018 --5.46268081665,-0.56023222208,-12.0062103271 --5.46876335144,-0.563284039497,-12.1146087646 --5.44278860092,-0.564296483994,-12.1560401917 --5.4178147316,-0.56530970335,-12.1984624863 --5.39885425568,-0.566331624985,-12.2558860779 --5.3698759079,-0.56634157896,-12.2933244705 --12.0164642334,-1.01997816563,-27.047454834 --11.9415187836,-1.02099871635,-27.1059207916 --11.8415260315,-1.01998639107,-27.1084098816 --10.7786626816,-0.951695144176,-24.9257736206 --10.6976861954,-0.951696157455,-24.9502429962 --10.3932695389,-0.935396969318,-24.4619235992 --10.3072786331,-0.934387564659,-24.4683971405 --10.2682924271,-0.934389710426,-24.4836349487 --10.192322731,-0.934395372868,-24.5161037445 --10.118355751,-0.934402823448,-24.551568985 --11.1476755142,-1.01495945454,-27.2380275726 --11.0516872406,-1.01495015621,-27.245513916 --10.8725223541,-1.00782179832,-27.0490760803 --10.7665119171,-1.00579726696,-27.0305747986 --10.7766389847,-1.0098747015,-27.1747608185 --11.9644327164,-1.10573863983,-30.3910732269 --10.42831707,-0.995623826981,-26.791885376 --9.80515384674,-0.954825997353,-25.4478549957 --9.62195110321,-0.946674048901,-25.2104244232 --9.35756111145,-0.932397842407,-24.7600746155 --9.30854988098,-0.931383192539,-24.7463188171 --9.21754646301,-0.930365502834,-24.7388057709 --9.13957118988,-0.930367052555,-24.7642784119 --9.07563018799,-0.931390702724,-24.8277378082 --9.02070999146,-0.932428896427,-24.9161891937 --8.76330471039,-0.918144524097,-24.4508285522 --8.63620662689,-0.914064586163,-24.33634758 --8.58218193054,-0.913040518761,-24.306602478 --6.86115407944,-0.775357723236,-19.7226295471 --6.80016994476,-0.77535700798,-19.7430877686 --6.75723266602,-0.777387559414,-19.8175354004 --6.6240644455,-0.770265340805,-19.6290607452 --6.54302883148,-0.769230782986,-19.5915412903 --6.49106693268,-0.769244611263,-19.6369953156 --6.48814678192,-0.772291839123,-19.7292003632 --6.43719053268,-0.773309051991,-19.7806549072 --6.39826488495,-0.775346636772,-19.8670921326 --6.34630632401,-0.775362670422,-19.9165458679 --6.90301895142,-0.832471609116,-21.8464126587 --6.85007715225,-0.833496749401,-21.911863327 --6.18441581726,-0.777400314808,-20.0469112396 --6.14840888977,-0.777390062809,-20.040145874 --6.08943414688,-0.777394890785,-20.070608139 --6.03246164322,-0.778401732445,-20.1040630341 --5.97148275375,-0.778403639793,-20.129529953 --5.92855358124,-0.780438184738,-20.2109718323 --5.86456251144,-0.779432177544,-20.2224349976 --5.83969449997,-0.783505916595,-20.3718681335 --5.79566049576,-0.78247833252,-20.3351078033 --5.7657790184,-0.785542845726,-20.468542099 --5.71282720566,-0.786562085152,-20.5240001678 --6.61391544342,-0.886538386345,-23.9555149078 --6.52187871933,-0.884500384331,-23.9130077362 --6.45592355728,-0.885514676571,-23.9604701996 --6.41405248642,-0.888582706451,-24.1009159088 --6.36602592468,-0.887558817863,-24.0711631775 --6.31613016129,-0.889610528946,-24.1836147308 --6.28229093552,-0.894698739052,-24.3590507507 --7.77777719498,-1.06918549538,-30.4069766998 --7.67176961899,-1.06816101074,-30.3894824982 --7.57378578186,-1.06715190411,-30.3979759216 --7.82186365128,-1.10182785988,-31.5789299011 --7.68676137924,-1.09674263,-31.4564647675 --7.31577920914,-1.06509912014,-30.3682289124 --5.98113441467,-0.917136907578,-25.2679576874 --5.90918016434,-0.918150126934,-25.3144321442 --5.81011867523,-0.915095925331,-25.2439289093 --6.94291305542,-1.06510603428,-30.4791965485 --5.69733524323,-0.921201348305,-25.4738483429 --4.95852184296,-0.832421302795,-22.4027957916 --4.9196639061,-0.836497068405,-22.5572395325 --4.83361053467,-0.834450006485,-22.4987297058 --4.70236492157,-0.826282382011,-22.2312679291 --4.55303096771,-0.815060019493,-21.8688201904 --4.48805332184,-0.815060973167,-21.8932876587 --4.46811962128,-0.817096114159,-21.9655075073 --4.37904071808,-0.814033389091,-21.8800067902 --4.16739606857,-0.793618142605,-21.1826267242 --4.10542392731,-0.794623076916,-21.2140960693 --4.05651187897,-0.796664953232,-21.309545517 --4.01061677933,-0.799717664719,-21.4239940643 --3.92453384399,-0.796653330326,-21.3354911804 --4.39502286911,-0.873190283775,-24.0161952972 --3.82755923271,-0.797649979591,-21.3641967773 --4.26112699509,-0.875225126743,-24.1241378784 --3.69457530975,-0.79663425684,-21.3831424713 --3.60948061943,-0.793563246727,-21.2826309204 --3.52237296104,-0.790484070778,-21.1681232452 --3.44330692291,-0.788430809975,-21.0986099243 --3.42338323593,-0.790471315384,-21.1808338165 --3.35135293007,-0.788439929485,-21.1493110657 --3.28435230255,-0.788426876068,-21.1497859955 --3.26765060425,-0.797596931458,-21.4692058563 --3.25096035004,-0.806773304939,-21.799621582 --3.71428084373,-0.906787693501,-25.3325233459 --3.6292526722,-0.904754400253,-25.2990150452 --3.29736971855,-0.848599016666,-23.2975730896 --3.22437334061,-0.847586631775,-23.3000545502 --3.15741825104,-0.848599493504,-23.3465270996 --3.06226968765,-0.844494760036,-23.1880302429 --2.96812462807,-0.839392244816,-23.033536911 --2.9072022438,-0.84142524004,-23.1149997711 --2.85234022141,-0.845494031906,-23.2594623566 --1.8413258791,-0.636239647865,-15.8672208786 --1.79434001446,-0.636239171028,-15.8886795044 --2.5640733242,-0.836282491684,-22.9751853943 --2.50820302963,-0.840346217155,-23.1106414795 --2.5623087883,-0.871995270252,-24.2699775696 --2.48732161522,-0.871987521648,-24.281463623 --2.43620157242,-0.868907988071,-24.1547203064 --2.36928534508,-0.870942592621,-24.2401924133 --2.30438995361,-0.87398982048,-24.3476638794 --2.23545885086,-0.875015258789,-24.4171390533 --2.15846014023,-0.875000417233,-24.4166297913 --2.08650326729,-0.876010358334,-24.4591064453 --2.24412512779,-0.952553033829,-27.1873092651 --2.21427679062,-0.956633985043,-27.3425426483 --2.13434171677,-0.958654761314,-27.4050292969 --2.04834222794,-0.95863711834,-27.4005260468 --1.96334969997,-0.958623528481,-27.4030170441 --1.87328898907,-0.955569446087,-27.3345184326 --3.08365392685,-1.49038648605,-46.3504180908 --2.51242589951,-1.27910852432,-38.855304718 --2.38128805161,-1.2750005722,-38.6958465576 --2.26335811615,-1.27601492405,-38.751373291 --2.1423637867,-1.27599167824,-38.740901947 --2.02037024498,-1.27496826649,-38.7304344177 --1.89835977554,-1.27393519878,-38.7029647827 --1.78552126884,-1.27800297737,-38.8524780273 --1.72554039955,-1.27800059319,-38.8637466431 --1.62401771545,-1.29125189781,-39.3372497559 --1.52152204514,-1.30551838875,-39.8377532959 --1.38725996017,-1.29733800888,-39.5513038635 --1.27047491074,-1.30243504047,-39.7538261414 --1.27252066135,-1.41875612736,-43.8761634827 --1.13866186142,-1.42180657387,-43.9987068176 --1.07069551945,-1.42181038857,-44.0219802856 --0.92954313755,-1.41669082642,-43.8445358276 --0.79252165556,-1.4156473875,-43.8010826111 --0.602523624897,-1.44317817688,-44.7888717651 --0.463574767113,-1.44417572021,-44.8184242249 --0.324711710215,-1.44722223282,-44.9349708557 --0.275679826736,-1.53191184998,-47.9381752014 --0.135058477521,-1.59824216366,-50.3256835938 -0.0697357803583,-1.41586041451,-44.0848731995 -0.209567993879,-1.41199314594,-43.9381484985 -0.349642693996,-1.41498684883,-44.0374221802 -0.544616222382,-1.5521863699,-49.1187133789 -0.616772055626,-1.39255547523,-43.197971344 -0.686854243279,-1.39552652836,-43.2931137085 -0.825930476189,-1.39751899242,-43.3933906555 -0.959748566151,-1.39365792274,-43.2306671143 -1.10084867477,-1.3976367712,-43.3559455872 -1.23263895512,-1.39179122448,-43.1642303467 -1.3685721159,-1.39086449146,-43.1185073853 -1.49837076664,-1.38601338863,-42.9347915649 -1.55710232258,-1.37918233871,-42.6709403992 -1.60796916485,-1.32141900063,-40.5042762756 -1.73286139965,-1.31851291656,-40.4135665894 -1.86492371559,-1.32151091099,-40.4978523254 -1.99696862698,-1.32351887226,-40.5641403198 -2.10759973526,-1.31375873089,-40.2044410706 -2.16751170158,-1.31182456017,-40.1235923767 -2.29550147057,-1.31186294556,-40.1328811646 -2.42348527908,-1.31290471554,-40.1361732483 -2.54741835594,-1.31097459793,-40.0864639282 -2.6825056076,-1.3149586916,-40.1967506409 -2.80743169785,-1.31303286552,-40.1400489807 -2.93643474579,-1.31406331062,-40.1633377075 -3.01358985901,-1.31899368763,-40.3344764709 -3.14460158348,-1.32001984119,-40.3667602539 -3.27965521812,-1.32302284241,-40.4430503845 -3.41471219063,-1.32502400875,-40.5223350525 -3.54469394684,-1.3250670433,-40.5236282349 -3.68781614304,-1.33003234863,-40.6719093323 -3.82285404205,-1.33204400539,-40.7321968079 -3.87066745758,-1.32716310024,-40.5473556519 -4.00165557861,-1.3272023201,-40.5556488037 -4.13770008087,-1.3302103281,-40.6229362488 -6.79488325119,-1.98955786228,-64.9381484985 -6.9332280159,-1.97296690941,-64.2964248657 -5.47884607315,-1.56486415863,-49.2390213013 -5.6287484169,-1.56295633316,-49.1662940979 -5.67648077011,-1.55612158775,-48.8994560242 -5.83647966385,-1.55716073513,-48.9277229309 -7.98501110077,-2.00376915932,-65.3263244629 -7.74253082275,-1.90570652485,-61.700920105 -7.9475440979,-1.90774738789,-61.7581481934 -8.16665077209,-1.91273844242,-61.9133644104 -6.91338205338,-1.619328022,-51.0888252258 -5.60569667816,-1.34057044983,-40.8491363525 -5.72257184982,-1.33867013454,-40.738445282 -5.82536411285,-1.33381414413,-40.5387611389 -5.94124174118,-1.33091199398,-40.4300727844 -6.06618785858,-1.33097290993,-40.3933677673 -6.19414710999,-1.33102703094,-40.3706703186 -6.26517057419,-1.33203065395,-40.4058113098 -6.45249032974,-1.3428914547,-40.7680587769 -6.58245515823,-1.34294271469,-40.7513580322 -6.68627119064,-1.33807313442,-40.5756759644 -6.7750043869,-1.33224701881,-40.3120079041 -6.88788223267,-1.32934355736,-40.2023200989 -7.02188158035,-1.33037590981,-40.2216148376 -7.73835277557,-1.43355309963,-43.95520401 -7.79286146164,-1.41984760761,-43.4525642395 -7.27946472168,-1.32167518139,-39.826423645 -7.43959474564,-1.32663810253,-39.9866943359 -7.88513612747,-1.37285852432,-41.666721344 -8.0110616684,-1.37293040752,-41.6090278625 -8.15808963776,-1.37494826317,-41.6623077393 -7.82517766953,-1.31896710396,-39.6088066101 -7.95113992691,-1.31901812553,-39.5881080627 -8.02285003662,-1.31120049953,-39.2954559326 -8.13073539734,-1.30929195881,-39.1897773743 -8.27879619598,-1.31229114532,-39.2760620117 -8.38768863678,-1.31037783623,-39.1793823242 -8.53474235535,-1.31338024139,-39.2586708069 -9.4664106369,-1.42449200153,-43.2570724487 -8.66946220398,-1.30657196045,-38.9831733704 -8.75727176666,-1.30270123482,-38.7955131531 -8.875207901,-1.30176508427,-38.7448272705 -6.15950679779,-0.949850857258,-25.99102211 -6.24148321152,-0.949883460999,-25.971364975 -6.27343320847,-0.948919713497,-25.9195480347 -6.34938526154,-0.947964847088,-25.8728961945 -6.4243350029,-0.947011351585,-25.8232460022 -6.46817111969,-0.943115830421,-25.6486244202 -9.66440486908,-1.28840327263,-38.0102653503 -9.77331829071,-1.28647744656,-37.9335899353 -9.88524436951,-1.28554439545,-37.8719062805 -9.96428775787,-1.28753781319,-37.9280471802 -10.1354169846,-1.29350173473,-38.0903167725 -10.2955055237,-1.29748642445,-38.2075958252 -11.0796766281,-1.36641907692,-40.6283378601 -11.2236776352,-1.36845004559,-40.6516304016 -11.3716859818,-1.37047743797,-40.683921814 -11.4607400894,-1.37246596813,-40.7550582886 -11.6117572784,-1.3744893074,-40.7963409424 -17.3754730225,-1.93062925339,-60.5158195496 -16.0727348328,-1.78505015373,-55.2863540649 -16.4723472595,-1.80678701401,-56.0064315796 -15.750535965,-1.72123479843,-52.9094734192 -15.9314994812,-1.72229361534,-52.9057388306 -16.0856742859,-1.72922694683,-53.1188163757 -16.212474823,-1.72536742687,-52.9321289062 -16.403465271,-1.72741401196,-52.9563903809 -16.6205310822,-1.73242223263,-53.0666275024 -16.1666908264,-1.67637395859,-51.0374336243 -16.3396453857,-1.67743623257,-51.0207099915 -18.0137557983,-1.81144976616,-55.6787071228 -18.1257820129,-1.81345880032,-55.7268218994 -19.2943935394,-1.9002187252,-58.7082519531 -16.9755744934,-1.68361067772,-51.0596466064 -13.4166135788,-1.36553132534,-39.8441047668 -13.5235099792,-1.3636136055,-39.7474327087 -13.5993213654,-1.35973703861,-39.5557899475 -13.6611042023,-1.35387408733,-39.3301582336 -13.7992677689,-1.36080956459,-39.5272521973 -14.0364942551,-1.36973071098,-39.8054733276 -14.8972702026,-1.42990040779,-41.8451652527 -15.1344661713,-1.43783831596,-42.0923843384 -18.9574069977,-1.73354971409,-52.2995681763 -19.1493873596,-1.73560035229,-52.3128356934 -19.2882404327,-1.73371219635,-52.1811408997 -19.4574050903,-1.74065387249,-52.38621521 -19.7365856171,-1.74960768223,-52.630405426 -19.9415874481,-1.75264811516,-52.6696624756 -19.5832958221,-1.71230781078,-51.2253875732 -19.7381954193,-1.71239697933,-51.1436843872 -19.9762840271,-1.71739566326,-51.2789115906 -20.0081310272,-1.71448755264,-51.1230964661 -20.1880874634,-1.71554887295,-51.1073722839 -20.414144516,-1.72056233883,-51.207611084 -20.6051197052,-1.72261500359,-51.2138824463 -20.6808509827,-1.71678245068,-50.9382400513 -20.518655777,-1.68242514133,-49.6272354126 -20.5835857391,-1.68147802353,-49.5623970032 -20.7485179901,-1.68155002594,-49.5156860352 -20.9004230499,-1.68163347244,-49.4399871826 -21.0473194122,-1.68072164059,-49.3522911072 -21.2292861938,-1.68277609348,-49.3475723267 -22.0234718323,-1.72626304626,-50.762336731 -22.1553287506,-1.72437012196,-50.6296539307 -22.1761646271,-1.72046637535,-50.4568557739 -22.3380813599,-1.72054576874,-50.3931503296 -22.4999980927,-1.72162461281,-50.3304443359 -22.5937843323,-1.71676397324,-50.1138000488 -22.7206325531,-1.71487343311,-49.9721221924 -22.9296398163,-1.71891093254,-50.013381958 -23.789850235,-1.76439547539,-51.4711036682 -23.4800815582,-1.7387689352,-50.5845718384 -23.7922687531,-1.74872457981,-50.8387489319 -23.9551792145,-1.74880588055,-50.7700462341 -24.073009491,-1.74592447281,-50.6043777466 -18.4079971313,-1.36403059959,-37.6753387451 -18.4429244995,-1.36207973957,-37.5965232849 -18.5488319397,-1.36115098,-37.5098724365 -18.656747818,-1.36121928692,-37.4302062988 -18.9079055786,-1.36917853355,-37.6384315491 -19.2361907959,-1.38208246231,-37.99559021 -29.7173347473,-2.0054473877,-58.442440033 -29.9072265625,-2.00554299355,-58.3597221375 -30.5871315002,-2.04116368294,-59.462387085 -30.765996933,-2.04027199745,-59.3486785889 -31.0129756927,-2.04433083534,-59.3679161072 -30.4346313477,-1.99897444248,-57.8058242798 -30.6491622925,-1.99127662182,-57.33152771 -31.4181632996,-2.02985930443,-58.5571212769 -31.4047374725,-2.01909565926,-58.0885734558 -29.9360847473,-1.92430710793,-54.9372024536 -30.0228424072,-1.91945874691,-54.6855659485 -30.1476573944,-1.91758489609,-54.50390625 -30.4804134369,-1.91678082943,-54.2935142517 -30.5903949738,-1.9178122282,-54.2896461487 -30.8273773193,-1.92186498642,-54.3098945618 -31.1014137268,-1.92789518833,-54.3941116333 -33.8690338135,-2.0693833828,-58.8323287964 -34.132019043,-2.07443881035,-58.8615570068 -33.9053077698,-2.05179286003,-58.043182373 -34.1973342896,-2.05783081055,-58.1213912964 -34.5476303101,-2.07172775269,-58.5093307495 -34.8576812744,-2.07875776291,-58.6125259399 -35.0655860901,-2.07984781265,-58.5428009033 -35.228427887,-2.07896518707,-58.395111084 -35.2661018372,-2.07115292549,-58.0415267944 -35.3618583679,-2.06630539894,-57.7878952026 -35.5397224426,-2.06641125679,-57.6691970825 -36.2304534912,-2.09812927246,-58.5898666382 -36.3372192383,-2.09427833557,-58.3482284546 -36.430973053,-2.08943152428,-58.0905952454 -37.0473976135,-2.11130332947,-58.6655540466 -40.4854316711,-2.2776787281,-63.6962776184 -39.437702179,-2.2144510746,-61.6085510254 -43.0150299072,-2.38968610764,-66.9949417114 -41.1642913818,-2.28687620163,-63.6538619995 -41.3671455383,-2.2869913578,-63.5281448364 -41.7191848755,-2.29403114319,-63.630317688 -41.7788619995,-2.28721904755,-63.2837219238 -42.119884491,-2.29426550865,-63.3659057617 -43.889629364,-2.37161159515,-65.593963623 -23.4896430969,-1.17870140076,-25.9875850677 -23.5585708618,-1.17775213718,-25.8989696503 -37.6996765137,-1.66563010216,-37.0417098999 -50.2215652466,-2.14182329178,-49.1440505981 -50.5125198364,-2.14689326286,-49.1192970276 -50.7094039917,-2.14798498154,-49.0006141663 -51.4917030334,-2.17194533348,-49.4495048523 -23.0634117126,-1.08838152885,-21.7587871552 -23.1033382416,-1.08742797375,-21.6581954956 -23.1492671967,-1.08647251129,-21.5645961761 -23.1611728668,-1.08452451229,-21.4380245209 -38.9127693176,-1.67130088806,-36.011100769 -38.9906425476,-1.66938066483,-35.8564910889 -23.3690643311,-1.08561503887,-21.2919635773 -23.7862434387,-1.0985840559,-21.5400981903 -23.7481174469,-1.09464526176,-21.368560791 -23.568901062,-1.08573365211,-21.0691280365 -15.93683815,-0.802260279655,-14.0510587692 -15.801692009,-0.796317815781,-13.8395872116 -15.795630455,-0.794350087643,-13.7450218201 -15.3903436661,-0.778440892696,-13.3415250778 -15.2962303162,-0.773487567902,-13.1730203629 -15.3462085724,-0.773507654667,-13.1314163208 -15.006942749,-0.759597241879,-12.7510890961 -15.0359096527,-0.75961959362,-12.6944942474 -15.1459274292,-0.762628018856,-12.7068452835 -15.5531244278,-0.775585591793,-12.9729814529 -15.4020061493,-0.769625365734,-12.8023033142 -15.2358541489,-0.761680960655,-12.5788497925 -15.2137918472,-0.759711682796,-12.4782972336 -12.0818862915,-0.64624863863,-9.77897262573 -12.0858535767,-0.645266890526,-9.71839523315 -14.7353649139,-0.738866567612,-11.84192276 -8.30960273743,-0.509890913963,-6.49598073959 -14.8493623734,-0.740885972977,-11.819483757 -14.915353775,-0.74190056324,-11.7958650589 -14.9983558655,-0.742912769318,-11.7852373123 -15.3435049057,-0.753886163235,-11.9854183197 -15.5025472641,-0.757888019085,-12.0337333679 -15.1613111496,-0.74496203661,-11.6844043732 -15.2373075485,-0.745975613594,-11.6667823792 -15.3813638687,-0.750967383385,-11.741891861 -15.5814275742,-0.755964159966,-11.8201808929 -11.6672716141,-0.619517982006,-8.7133731842 -11.712266922,-0.620527625084,-8.68976783752 -11.7232446671,-0.619541764259,-8.64018535614 -11.7422266006,-0.619554758072,-8.59659957886 -11.7572202682,-0.619560301304,-8.5797958374 -17.3981246948,-0.81186747551,-12.7612714767 -16.6416854858,-0.783988058567,-12.1112298965 -16.5565929413,-0.78002345562,-11.9677181244 -16.4134731293,-0.774065613747,-11.781252861 -16.5975208282,-0.779068112373,-11.8375520706 -14.2232885361,-0.697365522385,-10.0316295624 -14.2022600174,-0.696377515793,-9.98285484314 -14.3092775345,-0.69838476181,-9.99221038818 -14.4633159637,-0.702386975288,-10.0345315933 -14.4762868881,-0.702404737473,-9.97594928741 -14.1831092834,-0.691454708576,-9.70157718658 -14.149058342,-0.688476681709,-9.61103153229 -14.3020973206,-0.693479299545,-9.65135669708 -14.7032699585,-0.705447733402,-9.89729118347 -9.0135602951,-0.515035867691,-5.86510467529 -9.00954532623,-0.514043629169,-5.82152748108 -9.04054546356,-0.514048159122,-5.8009352684 -9.06654453278,-0.515053093433,-5.77734231949 -9.10554981232,-0.515056788921,-5.76273536682 -9.11454772949,-0.51505947113,-5.74893426895 -9.12553977966,-0.515065610409,-5.7153506279 -9.20056056976,-0.517066299915,-5.72372245789 -9.22455787659,-0.517071306705,-5.69912242889 -9.24855613708,-0.5170763731,-5.67353248596 -14.1536436081,-0.676696717739,-8.78059196472 -13.9805555344,-0.670718073845,-8.63892269135 -13.3992805481,-0.650777637959,-8.20874118805 -13.4102582932,-0.649790942669,-8.1571598053 -13.3612108231,-0.647808611393,-8.06762504578 -13.3901968002,-0.647820234299,-8.02803039551 -13.3991746902,-0.646833300591,-7.97545289993 -13.4221582413,-0.646845221519,-7.9318652153 -13.4361515045,-0.646850943565,-7.91206550598 -13.4401273727,-0.646864116192,-7.85649442673 -13.2860412598,-0.640887141228,-7.70602798462 -13.4020624161,-0.643892765045,-7.71937417984 -13.3200063705,-0.639910519123,-7.61385726929 -13.4880466461,-0.644913256168,-7.65716981888 -13.382982254,-0.640931725502,-7.53966236115 -13.5030155182,-0.643931508064,-7.58080291748 -13.6910629272,-0.648933768272,-7.63409900665 -13.4029302597,-0.639961600304,-7.41072463989 -13.2238407135,-0.632982611656,-7.25326824188 -13.2598314285,-0.632992565632,-7.21867370605 -13.3058261871,-0.634001970291,-7.19007015228 -13.3358154297,-0.634012043476,-7.15247583389 -13.4088306427,-0.636014521122,-7.16564273834 -13.3007707596,-0.632030487061,-7.05213499069 -13.3117523193,-0.632041275501,-7.00355911255 -13.3767528534,-0.633049726486,-6.98494386673 -13.3197126389,-0.631062924862,-6.9004073143 -13.4077215195,-0.633070468903,-6.89377784729 -13.4327201843,-0.633074879646,-6.88096904755 -13.328663826,-0.629089355469,-6.77146959305 -13.3486499786,-0.629099190235,-6.72888326645 -13.3666362762,-0.629109025002,-6.68529844284 -13.4366388321,-0.630117177963,-6.66867876053 -13.5726623535,-0.63412374258,-6.68502140045 -13.6496677399,-0.636131882668,-6.67139482498 -13.5836372375,-0.633138656616,-6.61164665222 -13.5175952911,-0.631150484085,-6.52511739731 -13.5925998688,-0.632158815861,-6.50949859619 -13.7466278076,-0.636165440083,-6.53282785416 -13.7716159821,-0.636174917221,-6.49223566055 -13.7275829315,-0.635185718536,-6.41768980026 -13.8926134109,-0.639192759991,-6.44401693344 -13.9716272354,-0.641196489334,-6.45518159866 -13.9876127243,-0.641206085682,-6.40959596634 -13.9015674591,-0.63821721077,-6.31508016586 -13.9075498581,-0.637226581573,-6.26549863815 -13.8975276947,-0.636236250401,-6.20793247223 -13.8835048676,-0.635245859623,-6.14837169647 -13.9485054016,-0.637254536152,-6.12575769424 -14.0365209579,-0.639258503914,-6.13991451263 -14.3625946045,-0.648265779018,-6.23513412476 -14.4556007385,-0.650275051594,-6.22250747681 -14.5366039276,-0.652284383774,-6.20488119125 -14.6736211777,-0.656293690205,-6.21122360229 -14.7696285248,-0.658303380013,-6.19859218597 -14.9676713943,-0.664308190346,-6.25768136978 -15.3317480087,-0.674318552017,-6.35988140106 -15.5287799835,-0.679329276085,-6.38818359375 -15.6047782898,-0.681340157986,-6.3625702858 -17.1411533356,-0.726358473301,-6.95403814316 -17.2131462097,-0.727371156216,-6.9214220047 -17.2531299591,-0.728383719921,-6.8748292923 -17.2841262817,-0.729390084743,-6.8560256958 -17.332113266,-0.729402720928,-6.81242752075 -17.3780994415,-0.73041510582,-6.76882505417 -17.4320888519,-0.731427848339,-6.7272233963 -17.4930782318,-0.732440769672,-6.68762207031 -17.5280628204,-0.73345297575,-6.63902664185 -17.5590572357,-0.733459472656,-6.61922550201 -17.6250495911,-0.734472334385,-6.58161687851 -17.6630325317,-0.735484719276,-6.53302431107 -17.7180194855,-0.736497342587,-6.49141740799 -17.7640075684,-0.737510025501,-6.44482564926 -17.8169937134,-0.738522648811,-6.40122556686 -17.8669815063,-0.738535225391,-6.35662460327 -17.9079780579,-0.739541947842,-6.33981704712 -17.9579639435,-0.740554511547,-6.29521465302 -17.9639415741,-0.740566015244,-6.23364448547 -18.4980335236,-0.755591571331,-6.36175346375 -18.6090316772,-0.757606387138,-6.33611774445 -18.6500148773,-0.758619248867,-6.28552293777 -18.6919994354,-0.7596321702,-6.23492908478 -18.7569999695,-0.760640084743,-6.2241101265 -18.8109855652,-0.7616533041,-6.17750740051 -18.841966629,-0.762665808201,-6.12291765213 -18.9019546509,-0.763679385185,-6.07731580734 -18.9029312134,-0.762690782547,-6.01174926758 -19.0189285278,-0.76570636034,-5.98411464691 -19.0259056091,-0.765717923641,-5.92054367065 -19.008890152,-0.764722764492,-5.88276672363 -19.1078853607,-0.766737699509,-5.84913873672 -19.1898765564,-0.768752098083,-5.80952215195 -19.1628475189,-0.767762005329,-5.73497247696 -18.9497623444,-0.759774506092,-5.53796672821 -18.9317474365,-0.759778916836,-5.50019359589 -18.9657325745,-0.759790897369,-5.4456076622 -19.0037155151,-0.760802805424,-5.39301395416 -19.0587024689,-0.761815667152,-5.34441566467 -19.0986862183,-0.761827647686,-5.29182195663 -19.1656742096,-0.763841152191,-5.24621725082 -19.2086601257,-0.763853371143,-5.19362545013 -19.2706604004,-0.76586151123,-5.17880535126 -19.3046417236,-0.766873240471,-5.12321949005 -19.3696308136,-0.767886579037,-5.0766119957 -19.4176158905,-0.768899023533,-5.02501440048 -19.4836044312,-0.769912481308,-4.97741127014 -19.5255889893,-0.770924627781,-4.92282390594 -19.5915775299,-0.771938085556,-4.87521648407 -19.6345710754,-0.772945284843,-4.85440397263 -19.6935577393,-0.774958431721,-4.80380535126 -19.7265415192,-0.774970054626,-4.74622297287 -19.802532196,-0.776984155178,-4.69961309433 -19.8405151367,-0.776995897293,-4.64402008057 -19.9105033875,-0.779009699821,-4.59541320801 -19.9584884644,-0.780022144318,-4.54082155228 -20.0204868317,-0.781030774117,-4.52300071716 -20.0664710999,-0.782043099403,-4.46741056442 -20.1334571838,-0.784056782722,-4.41680669785 -20.191444397,-0.785069823265,-4.36420536041 -20.2484302521,-0.786082863808,-4.31060791016 -20.3014163971,-0.787095606327,-4.25601100922 -20.3694133759,-0.789104819298,-4.23818731308 -20.4103984833,-0.790116727352,-4.18059682846 -20.4753856659,-0.791130423546,-4.1269993782 -20.5323696136,-0.792143523693,-4.07239961624 -20.602355957,-0.794157505035,-4.01979589462 -20.6503429413,-0.795169830322,-3.96319913864 -20.7223300934,-0.797183990479,-3.91059303284 -20.7723236084,-0.798192203045,-3.88678264618 -20.8323097229,-0.799205482006,-3.8311829567 -20.8722934723,-0.800217211246,-3.77159380913 -20.9632816315,-0.802233040333,-3.72097969055 -21.0052661896,-0.803245007992,-3.660394907 -21.0742530823,-0.805258929729,-3.60578751564 -21.1352386475,-0.806272387505,-3.54918551445 -21.1962337494,-0.80728161335,-3.52537298203 -21.2432193756,-0.808293879032,-3.46577906609 -21.316204071,-0.810308277607,-3.41017246246 -21.3711891174,-0.81132131815,-3.3505795002 -21.4431743622,-0.81333565712,-3.29397416115 -21.5071601868,-0.815349459648,-3.23537540436 -21.5601444244,-0.816362261772,-3.17478227615 -21.6241416931,-0.817371785641,-3.15096092224 -21.6921253204,-0.819386005402,-3.09136462212 -21.7441101074,-0.820398747921,-3.02977204323 -21.8130950928,-0.822412908077,-2.97116613388 -21.8870811462,-0.823427557945,-2.91255927086 -21.9480667114,-0.82544118166,-2.85096478462 -22.006061554,-0.826450407505,-2.8241508007 -22.0730457306,-0.828464448452,-2.76354837418 -22.1380310059,-0.830478429794,-2.70194935799 -22.2090148926,-0.831492960453,-2.64034962654 -22.2810001373,-0.833507597446,-2.57874798775 -22.3389854431,-0.834520816803,-2.51614689827 -22.4049701691,-0.836534917355,-2.45255231857 -22.4869632721,-0.838546693325,-2.42672681808 -22.5309467316,-0.839558660984,-2.36113619804 -22.6069335938,-0.841573655605,-2.29853105545 -22.6799163818,-0.843588531017,-2.23492884636 -22.7609004974,-0.84560418129,-2.17132544518 -22.8058853149,-0.846616089344,-2.10473370552 -22.878868103,-0.848630964756,-2.04013109207 -22.9448623657,-0.849641382694,-2.01031565666 -23.0308475494,-0.852657675743,-1.94570970535 -23.0918292999,-0.853671312332,-1.87911164761 -23.1738147736,-0.855687141418,-1.8135061264 -23.2117977142,-0.856698393822,-1.74392223358 -23.3257827759,-0.859717667103,-1.68029940128 -23.3787651062,-0.860730528831,-1.61071109772 -20.8526649475,-0.791465044022,-1.37823998928 -21.0406570435,-0.796490490437,-1.32657790184 -9.63326740265,-0.480261534452,-0.446039825678 -9.62327194214,-0.480257421732,-0.415466964245 -9.64927768707,-0.481257170439,-0.386880517006 -9.62328147888,-0.480251193047,-0.355316758156 -9.6262845993,-0.480249971151,-0.340526729822 -9.61928939819,-0.480246096849,-0.310943037271 -9.62329387665,-0.480243235826,-0.280376434326 -9.61829948425,-0.480239480734,-0.250794142485 -9.63030433655,-0.480237513781,-0.221214488149 -9.61731052399,-0.479232698679,-0.190645560622 -9.61831569672,-0.479229480028,-0.161064743996 -9.61331748962,-0.479227244854,-0.146274253726 -9.62232398987,-0.479224860668,-0.116693496704 -9.60132980347,-0.479218959808,-0.0861280411482 -9.6183347702,-0.479217410088,-0.0565463453531 -9.6033411026,-0.479212075472,-0.0259821210057 -9.61134624481,-0.479209452868,0.00359924440272 -9.60034942627,-0.479206413031,0.0183868966997 -9.6103553772,-0.47920396924,0.047969084233 -9.599360466,-0.479198932648,0.0785316899419 -9.60536670685,-0.479195982218,0.108113236725 -9.59437274933,-0.479190945625,0.137688621879 -9.59837913513,-0.479187697172,0.167269557714 -9.58638572693,-0.478182435036,0.196843490005 -9.59638881683,-0.47918176651,0.211637586355 -9.59839439392,-0.47917804122,0.242203906178 -9.58040046692,-0.478171944618,0.271773040295 -9.58540725708,-0.478168666363,0.301354765892 -9.58741378784,-0.478164970875,0.330934971571 -9.59342002869,-0.479161769152,0.360517919064 -9.57442760468,-0.478155314922,0.390083104372 -9.58043003082,-0.478154063225,0.404877007008 -9.57543754578,-0.478149354458,0.434451669455 -9.58244419098,-0.4781460464,0.465022325516 -9.56645011902,-0.478139936924,0.493600875139 -9.57945728302,-0.478137373924,0.52417755127 -9.57046508789,-0.478131949902,0.553747653961 -9.56146812439,-0.478128612041,0.568527877331 -9.57647514343,-0.478126436472,0.598122119904 -9.56748199463,-0.478120923042,0.62769138813 -9.56948947906,-0.478116869926,0.657272577286 -9.56049633026,-0.478111296892,0.686841011047 -9.56450366974,-0.478107482195,0.716424822807 -9.55451107025,-0.47810164094,0.745991230011 -9.55851459503,-0.478100001812,0.7607858181 -9.55452156067,-0.478094965219,0.79035961628 -9.55052947998,-0.478089898825,0.819933176041 -9.55053710938,-0.478085398674,0.849512338638 -9.55654525757,-0.478081583977,0.880086362362 -9.54655265808,-0.478075683117,0.908665120602 -9.55356025696,-0.478071957827,0.939241409302 -9.65056037903,-0.481083005667,0.962071359158 -9.7055644989,-0.483086198568,0.995687901974 -9.68557357788,-0.482078641653,1.02524209023 -9.68658065796,-0.482074230909,1.0548299551 -9.67158985138,-0.482067316771,1.08439040184 -9.66959762573,-0.482062399387,1.1139729023 -9.67060470581,-0.482057750225,1.14454710484 -9.67860889435,-0.482056498528,1.16034126282 -9.67561721802,-0.482051193714,1.19090878963 -9.65662574768,-0.482043743134,1.21848702431 -9.67763233185,-0.48204189539,1.25107336044 -9.66364192963,-0.482034862041,1.28063309193 -9.66664981842,-0.482030391693,1.3112128973 -9.65465450287,-0.482026159763,1.32499575615 -9.6706609726,-0.483023613691,1.35658931732 -9.65367031097,-0.482016116381,1.38515532017 -9.65967941284,-0.482011914253,1.41672897339 -9.65368747711,-0.482005983591,1.44630432129 -9.66369533539,-0.483002364635,1.47788822651 -9.65370368958,-0.482995718718,1.5074545145 -9.65170860291,-0.482992887497,1.52224457264 -9.64371776581,-0.4829865098,1.55181503296 -9.65872478485,-0.48298355937,1.58439981937 -9.64673423767,-0.482976585627,1.61297464371 -9.64374351501,-0.48297098279,1.642557621 -9.64175319672,-0.482965350151,1.67312955856 -9.65476036072,-0.482962042093,1.70571327209 -9.63476657867,-0.48295623064,1.7184844017 -9.63977432251,-0.482951790094,1.74907541275 -9.64378356934,-0.48294699192,1.78065085411 -9.63879299164,-0.48294070363,1.81121623516 -9.62980270386,-0.48293402791,1.83979773521 -9.63881111145,-0.483929902315,1.87237489223 -9.63181591034,-0.483926147223,1.88616526127 -9.63282489777,-0.483920693398,1.91773474216 -9.63283348083,-0.48391520977,1.948315382 -9.62784290314,-0.483908951283,1.97789514065 -9.63185310364,-0.483904033899,2.00947475433 -9.62386226654,-0.483897149563,2.03904628754 -9.61187267303,-0.483889460564,2.06860494614 -9.61287784576,-0.483886957169,2.08340573311 -9.64088439941,-0.484885692596,2.11999487877 -9.60489749908,-0.483874171972,2.14454579353 -9.60690593719,-0.483868896961,2.17513537407 -9.60591697693,-0.48486289382,2.20670223236 -9.60392665863,-0.484856814146,2.23727989197 -9.59893608093,-0.484850287437,2.26686167717 -9.60594081879,-0.484848380089,2.28464412689 -9.60494995117,-0.484842449427,2.31522631645 -9.59196186066,-0.484834462404,2.34379482269 -9.60696983337,-0.48583099246,2.37837958336 -9.58798122406,-0.484821885824,2.40594053268 -9.5909910202,-0.485816508532,2.43752503395 -9.59700107574,-0.485811561346,2.47010803223 -9.59200668335,-0.485807687044,2.48489117622 -9.58101654053,-0.48579993844,2.5134665966 -9.59502506256,-0.485796272755,2.54805421829 -9.57803821564,-0.48578736186,2.57562112808 -9.58204746246,-0.486781954765,2.60819983482 -9.58605670929,-0.486776530743,2.64077997208 -9.58406257629,-0.486773043871,2.65656161308 -9.5740737915,-0.486765176058,2.68612837791 -9.58508396149,-0.486760824919,2.72071099281 -9.56909656525,-0.486751973629,2.74828124046 -9.57310581207,-0.487746477127,2.78086423874 -9.57611560822,-0.487740755081,2.81344461441 -9.57212638855,-0.487733870745,2.84402370453 -9.57013225555,-0.487730324268,2.85980701447 -9.57814216614,-0.487725317478,2.89438390732 -9.55615520477,-0.4877153337,2.91995501518 -9.56116485596,-0.487709820271,2.95353388786 -9.56017494202,-0.488703370094,2.98511457443 -9.56118679047,-0.488697111607,3.01769161224 -9.55819225311,-0.488693296909,3.03347206116 -9.55720329285,-0.488686770201,3.06505441666 -9.55021572113,-0.488679081202,3.09562444687 -9.556224823,-0.489673525095,3.13020014763 -9.49324417114,-0.4876562953,3.14275503159 -9.42026519775,-0.485637187958,3.15229988098 -9.39827919006,-0.485626727343,3.17786240578 -9.41028308868,-0.486625522375,3.19765758514 -9.39329624176,-0.485615968704,3.22423005104 -9.40030670166,-0.486610531807,3.25880932808 -9.39831829071,-0.486603528261,3.29038691521 -9.39033031464,-0.486595451832,3.31996273994 -9.38634204865,-0.486587941647,3.35153222084 -9.38935375214,-0.487581670284,3.38510966301 -9.38635921478,-0.487577855587,3.39990305901 -9.38137149811,-0.487570285797,3.43048191071 -9.38338279724,-0.487563759089,3.46405744553 -9.38239479065,-0.48755672574,3.49663162231 -9.37940692902,-0.488549411297,3.52820944786 -9.37541866302,-0.488541811705,3.55978322029 -9.37243080139,-0.488534420729,3.59136271477 -9.37143611908,-0.488530874252,3.60715508461 -9.37544822693,-0.489524632692,3.64173293114 -9.37346076965,-0.489517271519,3.67430686951 -9.36847305298,-0.489509373903,3.70587873459 -9.35848617554,-0.489500582218,3.73545050621 -9.36249732971,-0.490494370461,3.77003264427 -9.3645029068,-0.490491122007,3.78781795502 -9.36651515961,-0.490484595299,3.82140421867 -9.35652828217,-0.490475744009,3.85097789764 -9.3615398407,-0.491469532251,3.88655686378 -9.3535528183,-0.491460978985,3.91712975502 -9.36156368256,-0.491455167532,3.95470285416 -9.34257888794,-0.491444706917,3.98027944565 -9.35858249664,-0.492443948984,4.00407028198 -9.35059547424,-0.492435336113,4.0346455574 -9.3436088562,-0.492426782846,4.06621456146 -9.34762096405,-0.493420362473,4.10179615021 -9.34263420105,-0.493412315845,4.13337755203 -9.34164619446,-0.493404954672,4.16695833206 -9.33965873718,-0.494397073984,4.20152139664 -9.33866500854,-0.494393229485,4.21830940247 -9.33367919922,-0.494385182858,4.24989414215 -9.33569049835,-0.494378179312,4.28547096252 -9.32570457458,-0.494368940592,4.3160405159 -9.32771682739,-0.495361953974,4.35161924362 -9.31773090363,-0.495352685452,4.38219022751 -9.33173465729,-0.496351748705,4.40499591827 -9.32674884796,-0.496343255043,4.43856096268 -9.31376361847,-0.496333539486,4.46714019775 -9.31577587128,-0.496326327324,4.50371217728 -9.31478881836,-0.497318744659,4.53829193115 -9.33779811859,-0.498315423727,4.5848736763 -9.44679164886,-0.502328336239,4.67150211334 -9.44679737091,-0.502324640751,4.68929338455 -9.44981002808,-0.502317488194,4.72786045074 -9.43782424927,-0.502307891846,4.7574429512 -9.44083690643,-0.503300726414,4.79601240158 -9.43385124207,-0.503291964531,4.82859182358 -9.43486404419,-0.504284441471,4.86616373062 -9.43287086487,-0.504280388355,4.88295793533 -9.4378824234,-0.50427365303,4.92253303528 -9.42989730835,-0.505264520645,4.95510959625 -9.42691040039,-0.505256295204,4.99068403244 -9.42092514038,-0.505247592926,5.02426338196 -9.41993713379,-0.506239712238,5.06084060669 -9.4129524231,-0.506230652332,5.09441566467 -9.42495632172,-0.507229089737,5.11921072006 -9.41397190094,-0.507219076157,5.1517739296 -9.41798400879,-0.507212102413,5.19135379791 -9.40899944305,-0.508202731609,5.22393083572 -9.40701293945,-0.508194625378,5.26050949097 -9.40302658081,-0.508186042309,5.29608678818 -9.40803909302,-0.509179234505,5.33666801453 -9.41204452515,-0.510175943375,5.3584523201 -9.40805912018,-0.51016741991,5.39403343201 -9.40407371521,-0.510158717632,5.43060493469 -9.39608764648,-0.511149346828,5.46418380737 -9.38810348511,-0.511139810085,5.49875259399 -9.40211391449,-0.512134611607,5.54533624649 -9.38213157654,-0.512122809887,5.57290506363 -9.40113353729,-0.513122618198,5.60270738602 -9.39614868164,-0.513113617897,5.63927936554 -9.36316871643,-0.512099325657,5.65884828568 -9.32019138336,-0.512083113194,5.67241382599 -9.27021503448,-0.511065363884,5.6819729805 -9.24423408508,-0.510052323341,5.70554113388 -9.23724269867,-0.510046839714,5.72132349014 -9.24625396729,-0.511040449142,5.76590490341 -9.23727035522,-0.512030541897,5.80047273636 -9.22928524017,-0.512020885944,5.8350481987 -9.23529815674,-0.513013839722,5.87862539291 -9.22731399536,-0.513004183769,5.91320323944 -9.22632789612,-0.513995707035,5.95277786255 -9.22933387756,-0.513992249966,5.97456979752 -9.21735095978,-0.513981699944,6.00714349747 -9.2093667984,-0.513972043991,6.04172515869 -9.22637653351,-0.515967071056,6.09330606461 -9.20939540863,-0.515955507755,6.12287902832 -9.21040821075,-0.515947401524,6.16445589066 -9.2084236145,-0.516938745975,6.20403385162 -9.21043014526,-0.516934990883,6.22582387924 -9.20744419098,-0.517926037312,6.265396595 -9.20945930481,-0.518918097019,6.30797672272 -9.20047473907,-0.51890796423,6.34355020523 -9.20248889923,-0.519900083542,6.38613367081 -9.19250583649,-0.519889593124,6.42170286179 -9.19151973724,-0.520881175995,6.46228742599 -9.19752597809,-0.520878016949,6.48807287216 -9.19354057312,-0.521868824959,6.52764892578 -9.19055652618,-0.521859765053,6.56822395325 -9.18357276917,-0.522849977016,6.6058011055 -9.17858791351,-0.522840440273,6.64537477493 -9.17160415649,-0.523830652237,6.68295383453 -9.18860721588,-0.524829685688,6.71674728394 -9.18462276459,-0.524820387363,6.75732278824 -9.17364025116,-0.524809658527,6.79289674759 -9.17165565491,-0.525800704956,6.83547019958 -9.1686706543,-0.526791751385,6.87605714798 -9.16668605804,-0.526782751083,6.91863441467 -9.16569328308,-0.527778148651,6.94041872025 -9.17170715332,-0.528770804405,6.9889998436 -9.15772533417,-0.528759300709,7.02356910706 -9.13574504852,-0.528746187687,7.05213546753 -9.06777477264,-0.526724159718,7.04469776154 -9.02879810333,-0.52670776844,7.05926609039 -9.05781459808,-0.52870029211,7.14963436127 -8.98984527588,-0.526678204536,7.1411986351 -8.92687511444,-0.525656759739,7.13774967194 -8.89089775085,-0.524640798569,7.15431785583 -8.87991523743,-0.525629997253,7.18989896774 -8.87893104553,-0.525620758533,7.23546600342 -8.86594867706,-0.526609420776,7.27004384995 -8.88495159149,-0.527608811855,7.30784130096 -8.87296962738,-0.527597665787,7.34342050552 -8.8589887619,-0.528585791588,7.37898492813 -9.12094306946,-0.538629591465,7.63964700699 -9.11296081543,-0.538619220257,7.6802277565 -9.11297607422,-0.53961032629,7.72880029678 -9.10599327087,-0.540599942207,7.77137422562 -9.11399841309,-0.540597140789,7.80216693878 -9.10801506042,-0.541587054729,7.84574270248 -9.10503101349,-0.542577445507,7.89231729507 -9.10704612732,-0.543568909168,7.94289779663 -9.09706306458,-0.543558001518,7.98347425461 -9.24604320526,-0.55057913065,8.16209602356 -9.14007663727,-0.546553313732,8.09485721588 -9.22007274628,-0.550560414791,8.21545505524 -9.22308731079,-0.551552057266,8.26903438568 -9.21310520172,-0.552540957928,8.31160736084 -9.19912433624,-0.552529215813,8.35018539429 -9.20013999939,-0.553520441055,8.4027633667 -9.20015525818,-0.554511249065,8.45533657074 -9.20216274261,-0.555507183075,8.48312759399 -9.19318008423,-0.55549621582,8.52770042419 -9.20819187164,-0.557490110397,8.59428119659 -9.19021224976,-0.557477355003,8.63085365295 -9.19322681427,-0.558468997478,8.68643665314 -9.19724178314,-0.559460818768,8.74302196503 -9.18026161194,-0.560448110104,8.78158950806 -9.18326854706,-0.560443997383,8.81237316132 -9.18629932404,-0.563426434994,8.92353534698 -9.1503238678,-0.562409937382,8.94410324097 -9.15533924103,-0.564401626587,9.00467777252 -9.09637737274,-0.563375890255,9.03003311157 -9.03840732574,-0.56235486269,9.02859592438 -9.02042770386,-0.562341988087,9.06617164612 -9.01644515991,-0.563331782818,9.11874294281 -9.01346206665,-0.564321994781,9.17132568359 -9.00747966766,-0.565311431885,9.22190189362 -9.00549602509,-0.566301584244,9.27747535706 -9.0115032196,-0.567298173904,9.31226539612 -9.00851917267,-0.568288326263,9.36584854126 -9.00453662872,-0.569278180599,9.41942691803 -8.99255561829,-0.56926625967,9.46599578857 -8.99157142639,-0.571256756783,9.52258014679 -8.9845905304,-0.572245836258,9.57514858246 -8.9866065979,-0.573236823082,9.63672637939 -8.98661518097,-0.57323205471,9.66651439667 -8.94464111328,-0.573214173317,9.68108558655 -8.87767505646,-0.57119089365,9.6696434021 -8.8247051239,-0.570170819759,9.67121601105 -8.7657365799,-0.569149136543,9.66777420044 -8.71576595306,-0.569129407406,9.6733379364 -8.70077896118,-0.569121658802,9.68612861633 -8.70279407501,-0.570112526417,9.74870586395 -8.68981456757,-0.571100234985,9.79527759552 -8.69083118439,-0.572090864182,9.85785388947 -8.68085002899,-0.57307934761,9.90743350983 -8.93180084229,-0.584121227264,10.2530765533 -8.92981815338,-0.586111187935,10.3156490326 -8.93582439423,-0.587107598782,10.3544416428 -8.92784404755,-0.588096499443,10.4090232849 -8.9328584671,-0.589087843895,10.4805984497 -8.91687965393,-0.590074896812,10.5281686783 -8.91989517212,-0.591066002846,10.5967540741 -8.90991401672,-0.592054307461,10.6513309479 -8.9139213562,-0.59305024147,10.6901168823 -8.91393852234,-0.595040559769,10.7576932907 -8.91295528412,-0.596030771732,10.8232765198 -8.89997577667,-0.597018301487,10.8768472672 -8.89399433136,-0.598007321358,10.9384222031 -8.88701343536,-0.598996341228,10.9980049133 -8.95901012421,-0.60400134325,11.1565971375 -8.8870382309,-0.601981639862,11.1033687592 -3.42954063416,-0.362845093012,4.39542245865 -3.40256786346,-0.361829549074,4.3889966011 -3.38659119606,-0.361816555262,4.39558410645 -3.38561058044,-0.362806677818,4.42117643356 -8.93011188507,-0.610941588879,11.5162687302 -8.99011230469,-0.61594414711,11.6668615341 -9.00011730194,-0.616941332817,11.7166547775 -8.98413944244,-0.617928087711,11.7722225189 -8.98315620422,-0.618918120861,11.8458051682 -8.97917461395,-0.620907485485,11.9163856506 -8.96719455719,-0.621895253658,11.9769630432 -8.95421600342,-0.622882664204,12.0375356674 -8.95423316956,-0.624872684479,12.1161108017 -9.72103023529,-0.661025345325,13.1850681305 -9.56709003448,-0.655983805656,13.0626125336 -9.46113586426,-0.652952134609,13.0031690598 -8.9942817688,-0.632846355438,12.4476499557 -8.93631458282,-0.631824374199,12.4502105713 -8.92833423615,-0.632812857628,12.5197906494 -8.88835430145,-0.631799638271,12.505569458 -8.84938240051,-0.631781637669,12.5331392288 -8.79041576385,-0.631759524345,12.5327033997 -8.77543735504,-0.632746398449,12.5942783356 -8.76545810699,-0.633734405041,12.6628570557 -8.76647472382,-0.63572460413,12.7484350204 -8.75549507141,-0.636712312698,12.8170127869 -8.76750087738,-0.638709664345,12.8777999878 -8.75852108002,-0.639697849751,12.9493837357 -8.75553894043,-0.641687095165,13.032954216 -8.74355983734,-0.643674612045,13.1015357971 -8.7375793457,-0.644663155079,13.1821060181 -8.7265996933,-0.646650910378,13.2536869049 -8.74460411072,-0.648649513721,13.3254795074 -8.7296257019,-0.649636387825,13.3930540085 -8.72764396667,-0.651625752449,13.4816303253 -8.71566486359,-0.653613328934,13.5532140732 -8.712682724,-0.655602395535,13.6427850723 -8.70170402527,-0.656590044498,13.7183647156 -8.69972229004,-0.658579528332,13.8089447021 -8.69773197174,-0.659573912621,13.8547277451 -8.79072284698,-0.66758275032,14.098323822 -9.18962669373,-0.68965446949,14.8339805603 -9.16665077209,-0.691639602184,14.89955616 -9.14267539978,-0.69262444973,14.964132309 -10.5702829361,-0.769906938076,17.4019756317 -10.5043182373,-0.769883155823,17.4155406952 -10.5833053589,-0.775894105434,17.608341217 -9.08875274658,-0.698577463627,15.2456455231 -9.07577419281,-0.70056450367,15.3322200775 -8.7998714447,-0.687497496605,14.9767417908 -8.76689910889,-0.688480556011,15.0263185501 -8.74792194366,-0.690466225147,15.1018924713 -8.76793479919,-0.693460047245,15.2444753647 -9.05486011505,-0.710513651371,15.7963151932 -9.08586978912,-0.715509593487,15.9648971558 -9.07489013672,-0.717497050762,16.0604763031 -9.0979013443,-0.721491277218,16.2190551758 -9.04993343353,-0.721471190453,16.250629425 -9.59279346466,-0.755571782589,17.3453006744 -9.55181312561,-0.754558265209,17.3340854645 -9.41187286377,-0.749519228935,17.2076396942 -8.7390871048,-0.714371204376,16.1051006317 -8.69211959839,-0.714351058006,16.139667511 -8.64215183258,-0.714330554008,16.1662425995 -8.57818889618,-0.713306903839,16.168806076 -8.52922153473,-0.713286399841,16.1983757019 -8.5412273407,-0.715283691883,16.2821674347 -8.53524780273,-0.718271970749,16.3937473297 -8.524269104,-0.72025924921,16.4983215332 -8.51429080963,-0.72324681282,16.6039047241 -8.50431156158,-0.725234270096,16.7124786377 -8.49233341217,-0.728221237659,16.8190517426 -8.48435401917,-0.731209039688,16.9336299896 -8.49736022949,-0.733206450939,17.0254211426 -8.49038028717,-0.736194550991,17.1430034637 -8.47440338135,-0.738180696964,17.2465744019 -8.47142314911,-0.741169512272,17.3761558533 -8.4514465332,-0.744154930115,17.4727325439 -8.53144168854,-0.752160608768,17.7783222198 -11.4555807114,-0.939749956131,23.9235572815 -10.6528377533,-0.893575906754,22.4360103607 -10.6758480072,-0.899569988251,22.6635951996 -11.1617212296,-0.935657680035,23.8842391968 -11.0777635574,-0.93462985754,23.8988037109 -10.7139091492,-0.92053437233,23.4999027252 -10.6639328003,-0.919518828392,23.4876861572 -10.5629816055,-0.917487502098,23.4602470398 -10.472026825,-0.916458189487,23.4548110962 -10.3930683136,-0.916431367397,23.4743766785 -10.3041133881,-0.915402531624,23.4709434509 -10.2141590118,-0.914373397827,23.4665031433 -10.1292028427,-0.913345396519,23.4710712433 -10.0722293854,-0.91132837534,23.4408493042 -9.98427391052,-0.91029971838,23.4384155273 -9.89631938934,-0.909271121025,23.4339809418 -9.80936336517,-0.90824252367,23.4335460663 -9.71840953827,-0.907213330269,23.4211120605 -9.63645267487,-0.906185984612,23.429681778 -9.5844783783,-0.905170023441,23.4074630737 -9.49952220917,-0.905142009258,23.409029007 -9.4105682373,-0.903113126755,23.3995952606 -9.32461261749,-0.902084887028,23.3971633911 -9.24165630341,-0.902057290077,23.4017295837 -9.15470218658,-0.901028871536,23.3962955475 -9.06774711609,-0.900000452995,23.3898620605 -9.01977062225,-0.898985385895,23.3736457825 -8.93381690979,-0.897957146168,23.3692131042 -8.85186100006,-0.896929681301,23.3747787476 -8.76390647888,-0.895901143551,23.3623466492 -8.67695140839,-0.894872844219,23.3519191742 -8.59799480438,-0.894846022129,23.3644828796 -8.51204109192,-0.893817782402,23.357049942 -8.4630651474,-0.892802536488,23.3358345032 -8.38310813904,-0.891775548458,23.3434047699 -8.29515457153,-0.890747010708,23.3279724121 -8.21419906616,-0.889719963074,23.3305435181 -8.1342420578,-0.889693081379,23.3351154327 -8.04828834534,-0.887664914131,23.3246822357 -7.96333360672,-0.887636959553,23.3152503967 -7.92135620117,-0.886623203754,23.3100395203 -7.83440256119,-0.885594904423,23.2946052551 -7.75644636154,-0.88456839323,23.3041763306 -7.67249155045,-0.883540689945,23.2957458496 -7.59053611755,-0.883513450623,23.2923164368 -7.50658178329,-0.882485806942,23.2818870544 -4.1366353035,-0.582808315754,12.9572505951 -4.09166955948,-0.58278876543,12.9568252563 -4.05270195007,-0.582770645618,12.9724092484 -7.22273826599,-0.879391133785,23.2713871002 -7.13778400421,-0.878363370895,23.2549571991 -7.05982780457,-0.878336966038,23.2605304718 -6.97687339783,-0.87730962038,23.2490997314 -6.93789482117,-0.876296579838,23.2478923798 -6.85194158554,-0.875268578529,23.2274589539 -6.77498531342,-0.87524241209,23.2350330353 -6.69203090668,-0.874215066433,23.2216033936 -6.61607408524,-0.873189151287,23.230178833 -6.53611898422,-0.873162567616,23.2237529755 -6.49314260483,-0.872148573399,23.2125377655 -6.41018819809,-0.871121287346,23.1961078644 -6.33623170853,-0.871095836163,23.2116832733 -6.25327682495,-0.870068669319,23.1902599335 -6.17732095718,-0.869042754173,23.1998310089 -6.09736585617,-0.869016170502,23.1914043427 -6.01941013336,-0.867990016937,23.1889801025 -5.97443437576,-0.866975784302,23.164768219 -5.89947795868,-0.866950154305,23.1753406525 -5.81852340698,-0.865923464298,23.158914566 -5.7435669899,-0.86589795351,23.1664924622 -5.66361188889,-0.864871382713,23.1550655365 -5.58865594864,-0.864845871925,23.1626415253 -5.50770139694,-0.863819181919,23.1452159882 -5.46872377396,-0.862806141376,23.1420040131 -5.38876914978,-0.861779689789,23.1275787354 -5.31281328201,-0.861754059792,23.130153656 -5.23585748672,-0.86072820425,23.1267280579 -5.15990209579,-0.860702633858,23.1273040771 -5.07994747162,-0.85967618227,23.1108798981 -5.01998662949,-0.86165368557,23.1854534149 -3.34452581406,-0.648321628571,15.615073204 -3.28456544876,-0.646299421787,15.5726528168 -3.23660135269,-0.646279513836,15.5882301331 -3.19363570213,-0.647260725498,15.6268110275 -4.95010042191,-0.896591603756,24.519575119 -3.03472685814,-0.639208972454,15.3379688263 -3.00574660301,-0.638198018074,15.3197536469 -2.95878243446,-0.638178348541,15.3363313675 -2.94580698013,-0.643165409565,15.5279169083 -2.89984226227,-0.644146025181,15.5504989624 -2.8528778553,-0.644126594067,15.5660829544 -2.82790637016,-0.648111224174,15.7086629868 -2.7839410305,-0.648092448711,15.7432489395 -2.76895618439,-0.650084257126,15.8040380478 -2.72799015045,-0.651065826416,15.8636169434 -4.74436998367,-0.989443957806,27.9673957825 -4.70240402222,-0.996425032616,28.259973526 -4.92135477066,-1.04845631123,30.1445732117 -4.83040475845,-1.04942786694,30.1851482391 -4.78842782974,-1.05041456223,30.2219409943 -4.69047927856,-1.04938495159,30.2165164948 -4.59652996063,-1.04935610294,30.2370948792 -4.5555639267,-1.06033754349,30.6126766205 -4.52259492874,-1.07232034206,31.0572566986 -4.54560804367,-1.09531390667,31.9128398895 -4.6146068573,-1.12831628323,33.1314315796 -4.65560388565,-1.14731872082,33.8082275391 -4.55665588379,-1.14828908443,33.8738021851 -4.45770788193,-1.15025949478,33.9433822632 -4.4117436409,-1.16323983669,34.4299621582 -4.32978963852,-1.16921365261,34.6455459595 -4.37981557846,-1.23120141029,36.918712616 -2.73035168648,-0.856884002686,23.4144001007 -2.64439964294,-0.853857278824,23.3109798431 -2.62342715263,-0.866842865944,23.7895641327 -2.56946539879,-0.871822178364,23.9921474457 -2.49650931358,-0.872797966003,24.0217266083 -2.31460905075,-0.863742887974,23.7158908844 -2.28962755203,-0.866733014584,23.8446846008 -3.93412351608,-1.37203133106,42.1413726807 -3.85816836357,-1.39000630379,42.7799491882 -3.81422400475,-1.4629765749,45.4621162415 -3.67728829384,-1.46494030952,45.5416946411 -3.66230368614,-1.48393213749,46.2524909973 -3.58135032654,-1.50690639019,47.1060714722 -3.58437013626,-1.5638961792,49.1626586914 -3.43743777275,-1.56685817242,49.2852401733 -3.35150694847,-1.66282081604,52.8064079285 -3.18757987022,-1.66377997398,52.8339881897 -3.1506023407,-1.68576776981,53.6277770996 -3.35555791855,-1.86779499054,60.2773742676 -3.16463947296,-1.86774909496,60.2699508667 -2.97472119331,-1.86670362949,60.2505340576 -1.6781566143,-1.21345412731,36.5280685425 -2.60987949371,-1.87561535835,60.5866966248 -1.54123175144,-1.23641347885,37.3684463501 -1.42828893661,-1.24038243294,37.5060272217 -1.27435898781,-1.2123439312,36.488609314 -1.16041648388,-1.21231293678,36.5021972656 -1.06646740437,-1.23228549957,37.2147789001 -1.84323906898,-2.16941761971,71.3174133301 -1.69730651379,-2.26238083839,74.703994751 -1.6343370676,-2.33036422729,77.2027893066 -0.927584350109,-1.63622510433,51.9513549805 -0.768656075001,-1.64418613911,52.2189407349 -0.604729354382,-1.64214622974,52.1805267334 -0.113949172199,-1.66002738476,52.8102836609 -0.031985796988,-1.6820076704,53.6180801392 --0.357853829861,-1.90592050552,74.517364502 --1.50038480759,-1.87566721439,73.1853179932 --11.7220849991,-1.6795014143,63.6087150574 --11.8680200577,-1.67247116566,63.2823181152 --12.1189203262,-1.67942416668,63.5169334412 --12.2878484726,-1.67539048195,63.3225440979 --12.4727706909,-1.67335438728,63.2131538391 --12.6886835098,-1.67531335354,63.2577667236 --11.4590396881,-1.50350344181,55.7760848999 --11.5959777832,-1.49947500229,55.5566940308 --11.8258867264,-1.50543177128,55.7803077698 --11.9568252563,-1.50040459633,55.5389175415 --12.1627416611,-1.50336563587,55.6455307007 --15.9594478607,-1.782730937,67.3856048584 --15.913444519,-1.75773358345,66.2641983032 --15.6165275574,-1.71877813339,64.5849838257 --15.6974840164,-1.70776057243,64.0355911255 --15.6334857941,-1.6827660799,62.9201889038 --10.8959445953,-1.22350525856,43.2984275818 --10.8849287033,-1.20950078964,42.6880226135 --11.0288648605,-1.21047210693,42.6886291504 --15.4044828415,-1.5907831192,58.831577301 --11.3707294464,-1.22340941429,43.1710510254 --11.4776763916,-1.22038686275,43.0266609192 --11.5366382599,-1.21437168121,42.7092628479 --15.1105089188,-1.50981247425,55.2271614075 --15.2484483719,-1.50678634644,55.0497741699 --15.4133787155,-1.50575625896,54.9743881226 --8.71544837952,-0.938785254955,30.9256248474 --8.77241134644,-0.935769677162,30.7592277527 --8.8673620224,-0.934748232365,30.7258319855 --8.9873046875,-0.936722993851,30.7754364014 --16.2620334625,-1.51160645485,54.9946746826 --16.4499588013,-1.51357364655,54.9942970276 --9.91495990753,-0.986561775208,32.7933044434 --9.89195823669,-0.981562018394,32.5331001282 --9.59101200104,-0.942594647408,30.8482685089 --9.69396209717,-0.942572593689,30.8348731995 --11.7093019485,-1.07825756073,36.4332542419 --11.7672653198,-1.07424330711,36.2228622437 --14.183511734,-1.24687969685,43.4178962708 --14.1565027237,-1.23487901688,42.8794937134 --14.1264944077,-1.22287869453,42.341091156 --14.1064815521,-1.21187698841,41.8416900635 --14.0814714432,-1.20087587833,41.3382911682 --14.05946064,-1.18987429142,40.8528900146 --13.9804763794,-1.17988359928,40.4166793823 --13.9644622803,-1.16988122463,39.9652786255 --11.5961694717,-1.00022351742,32.8616333008 --13.9634275436,-1.15287196636,39.1694831848 --13.9404153824,-1.14387047291,38.7180786133 --13.9174051285,-1.13386917114,38.2756767273 --13.8963937759,-1.12486755848,37.8482780457 --13.8144102097,-1.11487710476,37.4420661926 --13.7993965149,-1.10687458515,37.0416679382 --13.7753858566,-1.09787333012,36.6262664795 --13.7613716125,-1.08887064457,36.241859436 --13.7413606644,-1.08086884022,35.8484611511 --13.7233476639,-1.07286679745,35.4690589905 --13.7413253784,-1.06685960293,35.1856651306 --13.8262910843,-1.06784510612,35.2384681702 --13.8252735138,-1.06184077263,34.9130706787 --13.7942647934,-1.05284059048,34.5166664124 --13.7662553787,-1.04483997822,34.1352653503 --13.7622394562,-1.03783595562,33.8188667297 --13.4822978973,-1.01186835766,32.6892318726 --13.4622859955,-1.00386655331,32.3508338928 --13.4512720108,-0.997863531113,32.0384292603 --13.4322605133,-0.990861535072,31.7140274048 --13.4142475128,-0.983859419823,31.3956260681 --13.395236969,-0.976857483387,31.0792217255 --13.3792238235,-0.97085505724,30.7758197784 --13.3312301636,-0.964859366417,30.5336151123 --13.4391803741,-0.965839982033,30.5182266235 --13.6191091537,-0.970810890198,30.6658535004 --13.6790733337,-0.968798339367,30.5404605865 --13.2641630173,-0.934845805168,29.1226081848 --13.2501497269,-0.929843187332,28.8502063751 --13.1931581497,-0.923848569393,28.6069984436 --13.1841440201,-0.918845236301,28.3515949249 --13.1681318283,-0.912842929363,28.0861949921 --13.15711689,-0.907839894295,27.8327903748 --13.149102211,-0.902836501598,27.5913925171 --13.13808918,-0.8968334198,27.3459892273 --13.0850954056,-0.891838252544,27.126783371 --13.0670843124,-0.88683617115,26.8723812103 --13.1100540161,-0.88482606411,26.7469882965 --13.201010704,-0.884809672832,26.7196006775 --9.20517635345,-0.677328705788,18.4856491089 --9.25214385986,-0.67631649971,18.4332504272 --9.32010555267,-0.677301585674,18.4228534698 --13.0419979095,-0.862815082073,25.6801776886 --9.13813209534,-0.663316249847,17.8532238007 --9.17610263824,-0.662305295467,17.7888278961 --9.23706626892,-0.663291454315,17.7694320679 --9.34901428223,-0.665271043777,17.8460426331 --9.62491607666,-0.676229894161,18.2326774597 --9.76285743713,-0.680206537247,18.3532943726 --12.8779363632,-0.828807771206,24.119550705 --12.8779191971,-0.825803399086,23.9381523132 --12.8809013367,-0.821798682213,23.7627506256 --12.9258708954,-0.820788681507,23.6663551331 --9.66680622101,-0.663192987442,17.5664672852 --9.71377468109,-0.663181424141,17.5200691223 --9.74675559998,-0.663174510002,17.514875412 --13.2667140961,-0.824731528759,23.666009903 --13.3496742249,-0.82471716404,23.639623642 --13.4456300735,-0.825701355934,23.6352386475 --13.5365867615,-0.82668620348,23.6198501587 --13.6285438538,-0.827671051025,23.6084671021 --13.7245006561,-0.828655600548,23.6030845642 --13.7804756165,-0.828646838665,23.6118907928 --13.8734321594,-0.829631865025,23.6015110016 --13.9383983612,-0.829620361328,23.5411186218 --14.0113611221,-0.829607963562,23.4957332611 --14.0273399353,-0.826602399349,23.3533344269 --14.159286499,-0.82958316803,23.4059581757 --14.1932611465,-0.827575623989,23.2965660095 --14.3682031631,-0.833553135395,23.4983921051 --14.4871530533,-0.83553570509,23.526014328 --14.5481204987,-0.834525287151,23.4596271515 --14.5790958405,-0.833518445492,23.3442325592 --14.7800235748,-0.838491737843,23.500869751 --14.8579854965,-0.8384796381,23.460483551 --14.9559497833,-0.841466784477,23.5333023071 --15.0449104309,-0.841453552246,23.5099220276 --15.1228723526,-0.842441618443,23.4665317535 --15.2428236008,-0.844425022602,23.4911594391 --15.1798257828,-0.838429450989,23.232749939 --15.2567892075,-0.838417887688,23.1903648376 --11.6307954788,-0.685826122761,17.5523204803 --11.6677780151,-0.686819732189,17.5471229553 --11.7137479782,-0.685810148716,17.4967327118 --11.7267284393,-0.684804320335,17.3963317871 --11.753704071,-0.682796955109,17.3179340363 --11.7316942215,-0.679795086384,17.1675262451 --11.8676395416,-0.68377572298,17.2511558533 --11.8856182098,-0.681769549847,17.1607589722 --16.2753868103,-0.856284797192,23.4283695221 --11.9065885544,-0.679760932922,17.017156601 --16.4843006134,-0.858257949352,23.4136180878 --11.8015861511,-0.671764075756,16.6423397064 --11.8765487671,-0.671751737595,16.6359500885 --12.0604820251,-0.677727818489,16.7815818787 --12.055475235,-0.675726354122,16.7183799744 --16.9611034393,-0.864198684692,23.3779258728 --12.1674127579,-0.676706433296,16.6506004333 --12.2643709183,-0.677692234516,16.6722164154 --12.2073707581,-0.673694312572,16.4848022461 --12.2253494263,-0.672688603401,16.4014091492 --12.2093381882,-0.669686377048,16.2710018158 --12.2123298645,-0.668684184551,16.2218036652 --12.3202848434,-0.670669198036,16.2574195862 --12.3252677917,-0.669664859772,16.1580219269 --12.4792108536,-0.673645377159,16.2536525726 --12.2902460098,-0.664660990238,15.902215004 --8.93614196777,-0.537998318672,11.4761610031 --8.96011924744,-0.537990450859,11.431760788 --8.96810817719,-0.53698694706,11.4045591354 --9.0040807724,-0.536978006363,11.3761644363 --12.2161970139,-0.65365177393,15.3483934402 --12.4261245728,-0.659627199173,15.5110330582 --12.6800413132,-0.666598677635,15.7276887894 --12.6980218887,-0.665593504906,15.6482915878 --12.6910085678,-0.663590729237,15.5378866196 --12.5950260162,-0.65959841013,15.3706684113 --12.7129793167,-0.661583662033,15.4152927399 --12.6309862137,-0.656588196754,15.2168741226 --12.7149486542,-0.658576786518,15.2194890976 --12.9518718719,-0.664550900459,15.4041385651 --13.0568284988,-0.666537821293,15.4307641983 --13.0228309631,-0.664539456367,15.340555191 --12.9208431244,-0.659546017647,15.123134613 --12.9478216171,-0.65854036808,15.0577392578 --12.984796524,-0.658533871174,15.0043478012 --13.0097751617,-0.65752851963,14.9369506836 --13.268693924,-0.664501667023,15.1386089325 --13.4446325302,-0.669482767582,15.2422475815 --13.6005849838,-0.673467218876,15.3700809479 --13.5605812073,-0.670468211174,15.2266702652 --13.6765365601,-0.673455119133,15.2602987289 --13.5815477371,-0.668461024761,15.0578794479 --13.6115255356,-0.667455792427,14.9954862595 --13.6285066605,-0.666451752186,14.9180879593 --13.6844787598,-0.667444288731,14.8847017288 --14.5402498245,-0.695368230343,15.768696785 --14.6182165146,-0.695359408855,15.7533168793 --12.0648603439,-0.608578026295,12.9093332291 --12.071844101,-0.607574164867,12.8349332809 --12.0678310394,-0.60657119751,12.7495326996 --12.0608177185,-0.604568421841,12.6601247787 --12.1047916412,-0.604561507702,12.6267375946 --12.1537714005,-0.605555832386,12.6375465393 --12.2027454376,-0.606548547745,12.609161377 --12.1917333603,-0.604546248913,12.5167512894 --12.1957187653,-0.603542804718,12.4423561096 --12.1817073822,-0.601540923119,12.3499555588 --12.2056865692,-0.601535856724,12.2955579758 --12.161690712,-0.599537849426,12.2123479843 --12.1676750183,-0.598534286022,12.1409482956 --12.1606626511,-0.596531808376,12.0565423965 --12.1546497345,-0.595529139042,11.9741401672 --12.1576347351,-0.593525886536,11.9007368088 --12.1546220779,-0.592523157597,11.8233413696 --12.1736030579,-0.592518687248,11.7659397125 --12.1565999985,-0.590518414974,11.7117328644 --12.1815786362,-0.590513586998,11.6623430252 --12.1705684662,-0.58951151371,11.5779399872 --12.1655550003,-0.58750897646,11.4995365143 --12.1745386124,-0.586505353451,11.4341335297 --12.1755247116,-0.585502386093,11.3627338409 --12.1675128937,-0.584500133991,11.2833328247 --12.1595077515,-0.583499312401,11.2391252518 --12.1504964828,-0.582497119904,11.1597251892 --12.1524820328,-0.581494092941,11.0903234482 --12.1424703598,-0.579492032528,11.0109214783 --12.1464557648,-0.578489005566,10.9445228577 --12.1424427032,-0.577486455441,10.8711204529 --12.1414289474,-0.576483786106,10.8007192612 --12.1254262924,-0.575483500957,10.7515125275 --12.1294116974,-0.5744805336,10.6861104965 --12.0604152679,-0.571482479572,10.5566911697 --12.0643997192,-0.570479512215,10.4932956696 --12.0543889999,-0.569477438927,10.4168891907 --12.0843687057,-0.569472789764,10.376499176 --12.102350235,-0.568468868732,10.3240947723 --12.1003446579,-0.568467736244,10.2898979187 --12.1003313065,-0.56746506691,10.2245025635 --12.0953187943,-0.566462755203,10.1530923843 --12.0893058777,-0.565460562706,10.082690239 --12.0962905884,-0.564457535744,10.0232906342 --12.0862808228,-0.563455581665,9.95089054108 --12.0702781677,-0.562455296516,9.90468120575 --12.0672645569,-0.56145298481,9.8382806778 --12.0672521591,-0.560450494289,9.77488231659 --12.0612392426,-0.559448361397,9.70647907257 --12.0592269897,-0.558445930481,9.6410741806 --12.0572137833,-0.55744355917,9.57667160034 --12.0612001419,-0.556440889835,9.51727104187 --12.0381984711,-0.555441021919,9.46806621552 --12.0401849747,-0.554438531399,9.40766429901 --12.0271759033,-0.553436815739,9.33626270294 --12.0281620026,-0.552434384823,9.27586269379 --11.972161293,-0.550435125828,9.17144489288 --11.9841461182,-0.549432039261,9.1200466156 --11.9671363831,-0.548430562019,9.0466375351 --11.9621315002,-0.547429680824,9.01343917847 --11.9991102219,-0.547425329685,8.98104381561 --11.9970970154,-0.547423183918,8.92064666748 --12.0030832291,-0.546420574188,8.86524295807 --12.0100688934,-0.545417964458,8.81184673309 --5.56748723984,-0.362747251987,4.01177310944 --5.58846521378,-0.363739728928,3.99936509132 --5.57545948029,-0.362737178802,3.97615838051 --11.9860172272,-0.541409194469,8.53203296661 --11.9740066528,-0.540407598019,8.46562576294 --11.9729957581,-0.539405465126,8.40822696686 --11.9689826965,-0.538403511047,8.34782028198 --11.9609727859,-0.537401795387,8.28541564941 --11.9449701309,-0.537401497364,8.24621200562 --11.9459571838,-0.536399364471,8.19081115723 --11.9459447861,-0.535397231579,8.13541316986 --11.9369344711,-0.534395575523,8.0730047226 --11.9459199905,-0.534393191338,8.02461338043 --11.9289102554,-0.53339189291,7.95720100403 --11.9538936615,-0.533388853073,7.91880512238 --11.9068975449,-0.531389832497,7.86059522629 --11.8798904419,-0.530388891697,7.78818559647 --11.8798780441,-0.529386937618,7.73378229141 --11.8808660507,-0.528384923935,7.68037986755 --11.8688564301,-0.527383446693,7.61897468567 --11.8798418045,-0.527381122112,7.57257604599 --11.8548412323,-0.526381015778,7.52936410904 --11.8598279953,-0.52537894249,7.47996711731 --11.8638153076,-0.525376915932,7.42956638336 --11.8638029099,-0.524375081062,7.37716674805 --11.8497934341,-0.523373782635,7.31575965881 --11.8597803116,-0.523371577263,7.26935768127 --11.8467702866,-0.522370278835,7.2099571228 --11.82076931,-0.521370172501,7.16774559021 --11.7477722168,-0.518370807171,7.07232713699 --11.7037696838,-0.517370402813,6.99491405487 --11.6987581253,-0.516368687153,6.94050502777 --11.7017459869,-0.515366792679,6.89210653305 --11.708732605,-0.515364766121,6.84570455551 --11.69972229,-0.514363288879,6.79029989243 --11.7487077713,-0.515361011028,6.79411506653 --11.7876873016,-0.516358196735,6.76672458649 --11.8136711121,-0.516355872154,6.73233604431 --11.8116598129,-0.515354335308,6.68093061447 --11.8116483688,-0.514352738857,6.63153171539 --11.8116369247,-0.514351189137,6.5821313858 --11.8106250763,-0.51334965229,6.53172588348 --11.7986221313,-0.513349175453,6.50052261353 --11.78561306,-0.51234793663,6.44411563873 --11.7836027145,-0.511346459389,6.39370965958 --11.8285827637,-0.512344002724,6.37032794952 --11.868563652,-0.512341678143,6.34293556213 --11.9395399094,-0.51433891058,6.33255720139 --12.0355100632,-0.51633566618,6.33518743515 --12.0914945602,-0.51733404398,6.34100914001 --12.1754684448,-0.519331276417,6.33562994003 --12.2474441528,-0.520328938961,6.32425355911 --12.2834272385,-0.520327329636,6.29386711121 --12.2754173279,-0.520326495171,6.23945665359 --12.3483934402,-0.521324396133,6.2280831337 --12.3403902054,-0.520324110985,6.19988489151 --12.3463783264,-0.52032315731,6.15348434448 --12.3373699188,-0.519322454929,6.09907436371 --12.3423585892,-0.519321620464,6.05267524719 --12.3283510208,-0.518321037292,5.99727296829 --12.3383378983,-0.518320143223,5.95286941528 --12.3253307343,-0.517319560051,5.89846754074 --12.3253250122,-0.517319202423,5.87426710129 --12.3153162003,-0.516318559647,5.82085990906 --12.3083076477,-0.515317976475,5.77046442032 --12.3142967224,-0.515317261219,5.7250623703 --12.3152866364,-0.515316605568,5.67766094208 --12.3182764053,-0.514316022396,5.63125944138 --12.3132667542,-0.51431542635,5.58085155487 --12.2932653427,-0.513315320015,5.54865026474 --12.3002548218,-0.513314723969,5.50424861908 --12.3052425385,-0.512314081192,5.45985269547 --12.3002347946,-0.512313604355,5.41044855118 --12.2882270813,-0.511313199997,5.35804128647 --12.2932167053,-0.51131272316,5.31364202499 --12.2862071991,-0.510312259197,5.26424074173 --12.2822027206,-0.510312080383,5.23903656006 --12.2901926041,-0.510311663151,5.19563341141 --12.2841835022,-0.509311318398,5.14723348618 --12.2711763382,-0.508310973644,5.09582948685 --12.2881641388,-0.508310675621,5.05642843246 --12.2751560211,-0.508310317993,5.00603103638 --12.2801456451,-0.50730997324,4.96162414551 --12.2671442032,-0.507309794426,4.93442773819 --12.2701330185,-0.507309556007,4.89002609253 --11.6822156906,-0.492305725813,4.60641336441 --11.6842060089,-0.491305083036,4.56401109695 --11.674197197,-0.491304367781,4.51660203934 --11.6831855774,-0.491303831339,4.4772028923 --11.6811761856,-0.490303218365,4.433801651 --11.6661739349,-0.49030277133,4.40659570694 --11.6601648331,-0.489302158356,4.36118650436 --11.6791524887,-0.48930183053,4.3267993927 --11.6611452103,-0.489301115274,4.2773900032 --11.6551370621,-0.488300561905,4.2329864502 --11.6631269455,-0.488300204277,4.19358539581 --11.6501188278,-0.487299561501,4.14718294144 --11.6461143494,-0.48729929328,4.12397384644 --11.6571035385,-0.487299054861,4.08658075333 --11.6400966644,-0.486298412085,4.03917741776 --11.6400871277,-0.486298024654,3.99676799774 --11.644077301,-0.486297756433,3.95636534691 --11.6420688629,-0.48529741168,3.91396069527 --11.6260614395,-0.485296785831,3.86755800247 --11.6440553665,-0.48529702425,3.85336661339 --11.624048233,-0.484296381474,3.80495333672 --11.6250391006,-0.484296172857,3.76455569267 --11.6350288391,-0.484296172857,3.72716093063 --11.6280202866,-0.483295828104,3.68375515938 --11.5910167694,-0.482294768095,3.63033366203 --11.4810266495,-0.479291945696,3.57408738136 --11.4680185318,-0.479291379452,3.52968049049 --11.4600114822,-0.478290915489,3.4872777462 --11.4759998322,-0.479291170835,3.45187830925 --11.4579944611,-0.478290498257,3.40647053719 --11.4539852142,-0.47729024291,3.3660736084 --11.460975647,-0.477290332317,3.32867693901 --11.4439735413,-0.477289766073,3.30346703529 --11.4429645538,-0.477289646864,3.26305961609 --11.455953598,-0.477290004492,3.22766566277 --11.4489459991,-0.476289719343,3.18626236916 --11.4329395294,-0.476289182901,3.14184975624 --11.446928978,-0.476289689541,3.10645246506 --11.4259233475,-0.47528898716,3.0620496273 --11.4229192734,-0.475288897753,3.04083943367 --11.4279108047,-0.475289165974,3.00344252586 --11.4319019318,-0.474289387465,2.96503686905 --11.4218950272,-0.474289149046,2.92363381386 --11.4238862991,-0.474289387465,2.88523173332 --11.4158782959,-0.473289251328,2.84483170509 --11.425868988,-0.473289877176,2.80843091011 --11.4108667374,-0.473289340734,2.7852241993 --11.4378557205,-0.473290771246,2.75282621384 --11.4328479767,-0.473290830851,2.71342730522 --11.4168424606,-0.472290456295,2.67102003098 --11.372838974,-0.471288770437,2.62159776688 --11.4108257294,-0.472290873528,2.59220814705 --11.4488143921,-0.473293066025,2.56282091141 --11.4868068695,-0.473295092583,2.55263590813 --11.5067977905,-0.474296569824,2.51924705505 --11.5417861938,-0.474298834801,2.48886036873 --11.5597763062,-0.475300371647,2.45446705818 --11.5997648239,-0.475303113461,2.42407393456 --11.4987678528,-0.47329851985,2.36363363266 --11.5217609406,-0.473300069571,2.34944152832 --11.691737175,-0.477309972048,2.34710597992 --11.7327270508,-0.478313058615,2.31772971153 --11.7527179718,-0.478315144777,2.28232932091 --11.7857074738,-0.47931805253,2.24993920326 --11.8146982193,-0.479320764542,2.21755743027 --11.8556880951,-0.480324298143,2.18616819382 --11.8786792755,-0.480326861143,2.15177869797 --11.917673111,-0.481329858303,2.13959288597 --11.9466629028,-0.48233294487,2.10519719124 --11.9846534729,-0.482336610556,2.07381987572 --12.0156450272,-0.483340024948,2.0394244194 --12.0636348724,-0.484344571829,2.00904774666 --12.0866270065,-0.484347641468,1.97365665436 --12.1366167068,-0.485352575779,1.94227182865 --12.1536121368,-0.485354572535,1.92507565022 --12.2056026459,-0.486359804869,1.89470231533 --12.2415933609,-0.487364083529,1.86031162739 --12.2835845947,-0.488368868828,1.82793581486 --12.3035783768,-0.488372266293,1.79053759575 --12.3565683365,-0.489378035069,1.75916361809 --12.3695650101,-0.49038001895,1.74096775055 --12.4115571976,-0.490385234356,1.70657932758 --12.4435501099,-0.491389840841,1.67119419575 --12.4945411682,-0.492395937443,1.63781154156 --12.612528801,-0.495407223701,1.61446738243 --12.6605195999,-0.496413439512,1.58008575439 --12.6915140152,-0.4964184165,1.54370212555 --12.7555074692,-0.498424738646,1.5315284729 --12.7945013046,-0.498430609703,1.49514222145 --12.8194952011,-0.499435514212,1.45675003529 --12.8584890366,-0.500441551208,1.42036795616 --12.9164810181,-0.501449286938,1.38599383831 --12.9374761581,-0.501454114914,1.34659969807 --12.9784708023,-0.50246065855,1.31022310257 --13.0144662857,-0.503465414047,1.29303538799 --13.0624599457,-0.504472732544,1.25665831566 --13.0924549103,-0.504478752613,1.2172652483 --13.1434497833,-0.505486607552,1.18089151382 --13.177444458,-0.506493151188,1.1425100565 --13.2274389267,-0.50750118494,1.1051325798 --13.2664346695,-0.508508563042,1.06574368477 --13.3044309616,-0.50951385498,1.0485663414 --13.3424263,-0.510521173477,1.0091817379 --13.3714227676,-0.510527849197,0.968792676926 --13.4274177551,-0.511537134647,0.930415809155 --13.4684143066,-0.512545108795,0.891036987305 --13.4934101105,-0.513551771641,0.849645793438 --13.552406311,-0.514561712742,0.811276555061 --13.5864038467,-0.515567183495,0.792092442513 --13.6354007721,-0.516576468945,0.751711606979 --13.6723976135,-0.51758480072,0.710325837135 --13.7223939896,-0.518594443798,0.669950067997 --13.7633914948,-0.519603312016,0.628568589687 --13.8113889694,-0.520612955093,0.588198363781 --13.8523864746,-0.520622193813,0.545812249184 --13.8933858871,-0.521628975868,0.525629639626 --13.9613828659,-0.523641169071,0.485267490149 --13.9833812714,-0.523648679256,0.441878169775 --14.0273799896,-0.524658739567,0.398492574692 --14.063378334,-0.525667905807,0.356117457151 --14.1343774796,-0.527681171894,0.313750237226 --14.1783761978,-0.528691589832,0.270372658968 --12.8473997116,-0.497544914484,0.207535594702 --14.1463756561,-0.527696430683,0.201755836606 --12.8743963242,-0.498556345701,0.126748904586 --12.4054012299,-0.487506479025,0.0761236995459 --12.1484022141,-0.481480270624,0.0326038748026 --12.2703971863,-0.484498232603,-0.0047444854863 --12.5753927231,-0.491538226604,-0.0399965383112 --12.4173927307,-0.487521380186,-0.0612708292902 --12.2633914948,-0.48450678587,-0.101746290922 --14.6253767014,-0.538798332214,-0.13300549984 --12.2323875427,-0.483510673046,-0.179563179612 --12.2503843307,-0.484516859055,-0.218960851431 --14.7433815002,-0.540833055973,-0.273147702217 --12.4353818893,-0.488546073437,-0.278470575809 --12.623380661,-0.492574095726,-0.319778323174 --12.2833776474,-0.484535098076,-0.355347245932 --14.9693899155,-0.545886456966,-0.440430760384 --12.1183738708,-0.481521993876,-0.430232226849 --12.5693759918,-0.491585344076,-0.479414284229 --15.1524000168,-0.550932943821,-0.588542640209 --15.1814022064,-0.550940513611,-0.612722158432 --12.1343688965,-0.481538504362,-0.565630793571 --12.2113676071,-0.483553171158,-0.606995761395 --12.4723701477,-0.489593178034,-0.655264556408 --12.4743690491,-0.489598244429,-0.695671498775 --12.2513647079,-0.484571933746,-0.725179314613 --12.5273694992,-0.49061524868,-0.777446687222 --12.5003681183,-0.490613847971,-0.795656442642 --12.9133768082,-0.499677479267,-0.856851875782 --12.300362587,-0.485595107079,-0.864561796188 --15.7434520721,-0.565097868443,-1.10422980785 --12.6513710022,-0.493655800819,-0.96418607235 --12.2043581009,-0.483595430851,-0.975812375546 --12.0903539658,-0.480583369732,-1.00727367401 --12.0643529892,-0.480581820011,-1.02448439598 --12.0903530121,-0.48159044981,-1.06487286091 --16.080493927,-0.573198974133,-1.40524566174 --16.1425037384,-0.574218094349,-1.46060550213 --16.1985111237,-0.576236605644,-1.51697659492 --16.2705230713,-0.577257692814,-1.57433390617 --16.3335323334,-0.579277873039,-1.63270533085 --16.3625354767,-0.580287456512,-1.66088521481 --16.4475479126,-0.582311332226,-1.72124004364 --16.5045585632,-0.583331048489,-1.77961027622 --16.5755710602,-0.585353076458,-1.83896684647 --16.6355800629,-0.586373627186,-1.89833426476 --16.6945915222,-0.588394284248,-1.95769941807 --16.7776050568,-0.590418994427,-2.02005171776 --16.8306121826,-0.591433525085,-2.05322575569 --16.8946266174,-0.593455433846,-2.11358237267 --16.9756393433,-0.595480680466,-2.17794156075 --17.0296535492,-0.596501410007,-2.2383055687 --17.0946655273,-0.598524570465,-2.30167245865 --17.1706809998,-0.600549578667,-2.36602687836 --17.2296943665,-0.601571857929,-2.42838859558 --17.3057060242,-0.603591382504,-2.46654963493 --17.3917236328,-0.6056188941,-2.53390049934 --17.4417362213,-0.606640338898,-2.59626626968 --17.5047531128,-0.608664393425,-2.66163015366 --15.199593544,-0.55526560545,-2.38726782799 --15.2716054916,-0.557288467884,-2.44662427902 --15.3576202393,-0.559314250946,-2.50897622108 --17.8048191071,-0.616765022278,-2.90585875511 --14.718580246,-0.545212805271,-2.48492050171 --14.5865764618,-0.542198002338,-2.51138687134 --14.5105762482,-0.54019343853,-2.54682946205 --14.4455776215,-0.539190769196,-2.5832631588 --14.406580925,-0.538192868233,-2.62368297577 --14.452589035,-0.539206266403,-2.65485692024 --14.4145917892,-0.539208590984,-2.69527506828 --14.6396198273,-0.544261515141,-2.78255748749 --13.8485517502,-0.526118516922,-2.68838477135 --13.9545679092,-0.529148042202,-2.75272369385 --13.9775772095,-0.529161810875,-2.80311441422 --13.9715833664,-0.529169857502,-2.84751462936 --13.7635650635,-0.525133311749,-2.83082818985 --13.680562973,-0.523125886917,-2.86027598381 --13.7215738297,-0.524143218994,-2.9136557579 --13.7225799561,-0.524152576923,-2.95905518532 --13.7055835724,-0.524158239365,-3.00046110153 --13.6165809631,-0.522149384022,-3.02791523933 --13.5475797653,-0.521144330502,-3.0583524704 --13.413567543,-0.518121242523,-3.05262851715 --13.3895711899,-0.51712501049,-3.09103417397 --13.5615978241,-0.522170305252,-3.17334151268 --13.6076107025,-0.523189485073,-3.2287170887 --13.4686002731,-0.520169496536,-3.24319887161 --13.4476051331,-0.520174205303,-3.28260421753 --13.4496126175,-0.520184099674,-3.32800388336 --13.3216028214,-0.517165899277,-3.34348130226 --13.2535972595,-0.516155779362,-3.34971952438 --13.3276147842,-0.518181443214,-3.41208028793 --13.1565980911,-0.514153003693,-3.41457104683 --13.1155996323,-0.513153254986,-3.44899749756 --13.2346229553,-0.516189396381,-3.52333521843 --13.172621727,-0.515184879303,-3.55176615715 --12.994600296,-0.511149525642,-3.52907109261 --13.1876354218,-0.516202688217,-3.62235832214 --13.0546226501,-0.513182044029,-3.63284015656 --12.957616806,-0.51116925478,-3.65129470825 --12.9116163254,-0.510168015957,-3.68271946907 --12.8506145477,-0.509163320065,-3.71015572548 --13.0956602097,-0.515230417252,-3.8214173317 --12.801618576,-0.508165895939,-3.76178002357 --13.3907194138,-0.522315323353,-3.9708468914 --12.8766450882,-0.510203182697,-3.87154769897 --12.775636673,-0.508188486099,-3.8860001564 --12.5946140289,-0.504154443741,-3.87750649452 --12.5426139832,-0.503151357174,-3.9059407711 --12.4876117706,-0.502147257328,-3.93236923218 --12.5046186447,-0.503156304359,-3.95956492424 --13.4157838821,-0.525391161442,-4.27743196487 --12.9147062302,-0.51327753067,-4.1711268425 --12.9387197495,-0.514293968678,-4.22351503372 --13.1567678452,-0.519359469414,-4.33679056168 --13.1037683487,-0.518357038498,-4.36622476578 --13.0357637405,-0.517350375652,-4.38966035843 --13.0157651901,-0.517350614071,-4.40587091446 --12.8417425156,-0.513316750526,-4.39537763596 --12.7747392654,-0.512309908867,-4.41781234741 --13.0197954178,-0.518384575844,-4.544069767 --12.8417711258,-0.514348983765,-4.53057813644 --13.3448810577,-0.5264929533,-4.74668598175 --13.9360113144,-0.541661977768,-4.99573278427 --13.7789859772,-0.537626683712,-4.96703100204 --17.5777778625,-0.630659341812,-6.3351559639 --17.5337905884,-0.630666673183,-6.38258171082 --17.65583992,-0.633718848228,-6.4879026413 --13.3399448395,-0.528557896614,-5.0058927536 --13.0318899155,-0.521485209465,-4.94147014618 --12.9328794479,-0.519469678402,-4.95192861557 --17.4448738098,-0.630728781223,-6.63141727448 --17.2868614197,-0.62670391798,-6.63490581512 --17.2608795166,-0.626716196537,-6.68832349777 --17.2458972931,-0.626731336117,-6.74472761154 --17.1789054871,-0.62573158741,-6.78116226196 --17.0719032288,-0.6237205863,-6.8026266098 --17.0699272156,-0.623739480972,-6.86402511597 --17.2649841309,-0.628805577755,-6.97110319138 --17.2960147858,-0.630834639072,-7.04648160934 --24.4517631531,-0.808947622776,-9.95445919037 --24.3787899017,-0.807959020138,-10.0148944855 --24.8299446106,-0.819125473499,-10.2870035172 --26.7914772034,-0.869743287563,-11.1791677475 --26.5944786072,-0.865721821785,-11.1966772079 --25.720281601,-0.843477606773,-10.8834152222 --25.6553134918,-0.843493998051,-10.9518451691 --25.9864463806,-0.852630853653,-11.1870279312 --25.5243759155,-0.841526448727,-11.0877065659 --21.9585227966,-0.753495335579,-9.73572540283 --25.311466217,-0.838569104671,-11.2810049057 --25.1994590759,-0.836552143097,-11.2792692184 --25.1314907074,-0.835566878319,-11.3436975479 --24.9284820557,-0.831539094448,-11.3482151031 --23.7452468872,-0.803233683109,-11.0017461777 --23.5512390137,-0.799205541611,-11.0032587051 --25.756893158,-0.85593354702,-12.0600481033 --25.6889247894,-0.854950070381,-12.1274805069 --23.1842460632,-0.792171657085,-11.0574674606 --24.1265697479,-0.817514836788,-11.590256691 --24.1886367798,-0.819571256638,-11.7126064301 --16.5863990784,-0.626084804535,-8.17185401917 --16.5294113159,-0.625087797642,-8.20928955078 --16.4974155426,-0.625087797642,-8.22550487518 --16.4544277191,-0.624095261097,-8.26892948151 --16.4324493408,-0.624109685421,-8.32233905792 --16.3944644928,-0.62411904335,-8.36876487732 --16.3764877319,-0.624134898186,-8.42417240143 --16.3535079956,-0.62414932251,-8.47758579254 --16.3545379639,-0.625172019005,-8.54298210144 --22.9626960754,-0.796479165554,-11.940905571 --23.4218940735,-0.809675395489,-12.2679977417 --23.4059410095,-0.809706747532,-12.3533983231 --23.2399368286,-0.806684792042,-12.3598937988 --22.5747623444,-0.790485560894,-12.104722023 --22.4247608185,-0.787467718124,-12.1162099838 --22.7969379425,-0.798637211323,-12.4053573608 --22.4868564606,-0.790543794632,-12.2857570648 --22.3258514404,-0.787521541119,-12.2902526855 --22.359910965,-0.789569914341,-12.3996210098 --22.7601051331,-0.800753295422,-12.7107505798 --22.5110683441,-0.795698642731,-12.666302681 --22.3900756836,-0.793690741062,-12.6917734146 --21.934961319,-0.782558441162,-12.5304698944 --25.0151138306,-0.864728629589,-14.3056201935 --23.5876464844,-0.828234553337,-13.6019582748 --21.9060783386,-0.784638404846,-12.7414646149 --22.0261726379,-0.788721203804,-12.9027786255 --22.6614665985,-0.807001590729,-13.3627462387 --22.5704860687,-0.805005431175,-13.4051971436 --22.5775432587,-0.807047069073,-13.5045824051 --22.4685306549,-0.804024577141,-13.4888534546 --22.8187198639,-0.815200269222,-13.7920074463 --22.7557525635,-0.814215481281,-13.851439476 --22.7608127594,-0.815258026123,-13.952829361 --23.1560268402,-0.827455222607,-14.2899532318 --22.2667255402,-0.804141759872,-13.8469419479 --22.2747879028,-0.806185305119,-13.9493312836 --23.478307724,-0.839689552784,-14.7397108078 --23.1902503967,-0.83261603117,-14.6632966995 --17.4169063568,-0.676309049129,-11.153594017 --20.0771160126,-0.751463413239,-12.9945831299 --17.6621360779,-0.686500430107,-11.5416183472 --17.7011947632,-0.688547432423,-11.644985199 --17.6932125092,-0.688559651375,-11.6791887283 --20.0762958527,-0.75559091568,-13.3069601059 --17.6773357391,-0.690647304058,-11.9073858261 --19.8043327332,-0.751586794853,-13.3983259201 --17.5933876038,-0.690675377846,-12.0122356415 --17.4123516083,-0.686629295349,-11.9707546234 --17.4033679962,-0.686641454697,-12.0049610138 --15.729642868,-0.640944957733,-10.9475011826 --17.1053199768,-0.680575430393,-11.9619588852 --17.0453357697,-0.680580496788,-11.9993934631 --15.582690239,-0.639965057373,-11.0647954941 --15.4776802063,-0.63794708252,-11.0652694702 --15.6607866287,-0.644042730331,-11.2293395996 --43.9234542847,-1.44475436211,-31.2230205536 --43.3613319397,-1.43160009384,-31.0307826996 --43.0663414001,-1.42656505108,-31.0253582001 --43.0564842224,-1.42866003513,-31.2247371674 --43.1406784058,-1.4337978363,-31.4910469055 --42.9987602234,-1.4328327179,-31.5955162048 --42.8207473755,-1.42880046368,-31.5688266754 --42.5267524719,-1.42376434803,-31.5604038239 --42.6249542236,-1.4289098978,-31.8387031555 --17.2610607147,-0.701114416122,-13.223400116 --41.5578613281,-1.40670752525,-31.6605739594 --17.5013160706,-0.711318492889,-13.6202192307 --18.6279716492,-0.744898617268,-14.5728197098 --16.7640762329,-0.693070173264,-13.3109302521 --16.7020931244,-0.69207572937,-13.3483743668 --16.5470581055,-0.689034759998,-13.3108787537 --16.4590606689,-0.688026309013,-13.3253355026 --16.9653701782,-0.703296065331,-13.7711772919 --16.7312908173,-0.697215795517,-13.6707372665 --40.6929588318,-1.41230249405,-33.067905426 --40.4869995117,-1.40930294991,-33.1134262085 --40.2350158691,-1.4042788744,-33.1189804077 --40.0370635986,-1.40128231049,-33.1684989929 --40.0402259827,-1.40538787842,-33.3818626404 --39.8511924744,-1.40034282207,-33.3311882019 --39.8823776245,-1.40546393394,-33.5695381165 --39.785484314,-1.40551924706,-33.7019805908 --31.6017169952,-1.16033363342,-26.9963169098 --39.5596733093,-1.40461301804,-33.9388923645 --39.1716041565,-1.3965139389,-33.8215484619 --31.155828476,-1.15434622765,-27.1287879944 --38.9397087097,-1.39455008507,-33.9432792664 --30.9038639069,-1.15033602715,-27.167547226 --30.9009895325,-1.15341758728,-27.3359298706 --29.8824748993,-1.12394762039,-26.6110610962 --30.7061252594,-1.15247929096,-27.5088367462 --30.5031261444,-1.14845192432,-27.5003681183 --29.7757854462,-1.12913453579,-27.0212879181 --29.3655815125,-1.11694800854,-26.7357826233 --29.5208110809,-1.12511670589,-27.0450515747 --29.3178043365,-1.12108504772,-27.0285835266 --29.0757732391,-1.11603140831,-26.976146698 --29.1179294586,-1.12013804913,-27.1844978333 --29.30418396,-1.12932801247,-27.5287456512 --28.5658130646,-1.10798859596,-27.009677887 --28.7219848633,-1.11411988735,-27.2407512665 --28.6260471344,-1.11414813995,-27.3212089539 --28.8643455505,-1.12437057495,-27.718416214 --28.8814907074,-1.12746620178,-27.9087867737 --28.7825527191,-1.12749350071,-27.9872436523 --29.0028438568,-1.13771009445,-28.3754615784 --29.263168335,-1.14895319939,-28.8076515198 --29.6204948425,-1.1622107029,-29.2465724945 --38.6164855957,-1.50516438484,-41.1314659119 --39.0806121826,-1.53693938255,-42.5444145203 --35.7406578064,-1.4804751873,-42.2518768311 --35.5417060852,-1.47847402096,-42.28540802 --35.4018058777,-1.47851455212,-42.3878974915 --34.4920845032,-1.44793260098,-41.436794281 --34.1670074463,-1.44083607197,-41.3104286194 --24.4173240662,-1.09400010109,-29.9868793488 --24.1802558899,-1.08792293072,-29.8874530792 --24.1824150085,-1.09202194214,-30.0818405151 --24.1064987183,-1.0930634737,-30.1802883148 --24.2286949158,-1.09920346737,-30.4283847809 --24.5862007141,-1.11557078362,-31.0704898834 --23.6154155731,-1.08294034004,-30.0466480255 --23.5715312958,-1.08500552177,-30.1840724945 --23.5176353455,-1.08606290817,-30.3085002899 --23.3606395721,-1.08404242992,-30.3030185699 --23.2186584473,-1.08203244209,-30.3145179749 --23.1506690979,-1.08203005791,-30.3247680664 --23.5642528534,-1.10145282745,-31.0608272552 --22.9537944794,-1.08107745647,-30.4607048035 --22.5445327759,-1.06885516644,-30.1164207458 --23.4798412323,-1.11280453205,-31.7634487152 --22.4778709412,-1.07605457306,-30.520450592 --22.439994812,-1.07812595367,-30.6678714752 --22.1878910065,-1.07202410698,-30.5244617462 --22.0859470367,-1.0720436573,-30.5849342346 --21.7877902985,-1.06390190125,-30.3745670319 --21.3554821014,-1.05064725876,-29.9743061066 --21.1824550629,-1.04760503769,-29.9308376312 --21.1535873413,-1.04968261719,-30.0882549286 --21.0805873871,-1.04867196083,-30.0835056305 --21.5743122101,-1.07219231129,-30.985496521 --18.2837429047,-0.942498624325,-26.4825668335 --18.2027931213,-0.942518770695,-26.5420265198 --18.1318569183,-0.943547725677,-26.6164798737 --18.0679283142,-0.943582236767,-26.6999225616 --14.142408371,-0.78421163559,-21.0373210907 --13.0272054672,-0.740304350853,-19.5326251984 --12.9642333984,-0.74031329155,-19.5710792542 --12.9202842712,-0.74033844471,-19.6365146637 --12.7712068558,-0.737269937992,-19.5440349579 --12.6771965027,-0.735249996185,-19.5335121155 --12.6502685547,-0.737290501595,-19.6249351501 --12.7123966217,-0.741379201412,-19.7860832214 --12.4561843872,-0.73321133852,-19.5256938934 --12.1679296494,-0.723012030125,-19.2123336792 --13.2884483337,-0.7741137743,-21.0958137512 --12.0499858856,-0.723030745983,-19.289226532 --11.9850082397,-0.723034739494,-19.3186817169 --13.0374765396,-0.771094739437,-21.1332187653 --13.1566905975,-0.778244554996,-21.3983230591 --12.8784446716,-0.76905220747,-21.0959472656 --12.9406471252,-0.774185776711,-21.3452987671 --17.7792167664,-0.993940234184,-29.4116706848 --10.9593286514,-0.694468975067,-18.508140564 --15.5377674103,-0.906100511551,-26.3849315643 --15.366686821,-0.902025699615,-26.2824687958 --15.277721405,-0.902032911777,-26.3189430237 --15.177740097,-0.901028871536,-26.3364238739 --15.1158123016,-0.902063190937,-26.4188728333 --17.4402999878,-1.01454472542,-30.650308609 --26.084821701,-1.42150020599,-45.8481903076 --17.2863636017,-1.01355993748,-30.7140312195 --17.1213169098,-1.0105048418,-30.645565033 --14.6228275299,-0.895995378494,-26.4120769501 --14.996547699,-0.918491363525,-27.2781600952 --14.8945665359,-0.917486310005,-27.2936420441 --13.6528587341,-0.861257076263,-25.2300930023 --16.7035732269,-1.01159334183,-30.9086990356 --16.588596344,-1.01058900356,-30.9261894226 --16.5156860352,-1.01163089275,-31.022649765 --16.5679702759,-1.0188100338,-31.3519992828 --16.4339675903,-1.01678574085,-31.3355083466 --16.8538398743,-1.04338026047,-32.3715438843 --12.9998826981,-0.854169130325,-25.2332420349 --12.7215175629,-0.841904461384,-24.7946815491 --12.81483078,-0.851108372211,-25.1650028229 --12.4724340439,-0.836814284325,-24.6876926422 --12.3023166656,-0.832716345787,-24.5442409515 --12.2363681793,-0.832737147808,-24.6026973724 --11.9460439682,-0.821495473385,-24.2143497467 --12.3689231873,-0.848092973232,-25.2553844452 --5.66457986832,-0.497186422348,-11.7912931442 --5.63760042191,-0.498195976019,-11.8277235031 --5.60961961746,-0.498204410076,-11.862154007 --5.5856461525,-0.499218046665,-11.9055833817 --5.56868648529,-0.500240921974,-11.965010643 --5.53569793701,-0.500244021416,-11.990447998 --5.51272726059,-0.501259505749,-12.0368738174 --5.46567773819,-0.499222785234,-11.9841165543 --5.48478460312,-0.502291440964,-12.1215105057 --5.46181583405,-0.503307938576,-12.1699399948 --5.43684244156,-0.504321157932,-12.2123622894 --5.372797966,-0.502285599709,-12.1718292236 --12.0685787201,-0.885037660599,-27.1474475861 --11.0047388077,-0.828761816025,-24.9907817841 --11.0048284531,-0.830815553665,-25.0939788818 --10.7845859528,-0.822634398937,-24.8075771332 --10.7617235184,-0.825712621212,-24.9639968872 --11.6125965118,-0.879972577095,-27.1416492462 --11.6148042679,-0.885097146034,-27.3780460358 --11.5418672562,-0.88612216711,-27.4445133209 --11.478843689,-0.885097444057,-27.413766861 --10.1763830185,-0.811412870884,-24.5543231964 --10.0823745728,-0.810392320156,-24.5418052673 --10.0084095001,-0.810400903225,-24.5792732239 --9.93143844604,-0.810405313969,-24.609746933 --9.8634853363,-0.811422049999,-24.6612071991 --9.79954242706,-0.811445176601,-24.7236671448 --10.8038196564,-0.876968860626,-27.3459758759 --12.0116863251,-0.958877444267,-30.6402950287 --10.3833341599,-0.8616091609,-26.7761535645 --10.2993650436,-0.861612796783,-26.8056297302 --9.44264888763,-0.811448812485,-24.8327980042 --9.33761310577,-0.809409141541,-24.7872924805 --9.24560642242,-0.808389663696,-24.7767791748 --9.18957901001,-0.807363927364,-24.7440280914 --9.12764167786,-0.808390498161,-24.8124885559 --9.06871318817,-0.809422910213,-24.8909454346 --8.81632328033,-0.797148346901,-24.4425792694 --8.69724178314,-0.794080197811,-24.3480854034 --8.61224555969,-0.794067800045,-24.3495674133 --8.52724838257,-0.793055355549,-24.3510494232 --8.48725414276,-0.793051838875,-24.3562850952 --6.84633874893,-0.682452440262,-19.9111709595 --6.71217060089,-0.677330195904,-19.7226963043 --6.59805011749,-0.673239827156,-19.5892066956 --6.54007291794,-0.673243761063,-19.6176662445 --6.51016807556,-0.676295399666,-19.7280960083 --6.45921134949,-0.676312565804,-19.779548645 --6.38510131836,-0.673234939575,-19.6568183899 --6.40634155273,-0.679380953312,-19.9302101135 --6.35037326813,-0.680390000343,-19.967666626 --6.28838539124,-0.679386973381,-19.9841251373 --6.21035528183,-0.67835599184,-19.9526023865 --6.14736795425,-0.67835277319,-19.9690685272 --6.07535409927,-0.677332222462,-19.9555416107 --6.05539226532,-0.678351521492,-19.9997634888 --6.11175537109,-0.68757557869,-20.408121109 --5.96351671219,-0.681409478188,-20.143661499 --6.08809423447,-0.69677144289,-20.7899551392 --6.08329105377,-0.700886428356,-21.0103645325 --5.79762601852,-0.682445585728,-20.2720336914 --5.79171133041,-0.684494435787,-20.3672409058 --5.80697154999,-0.691650509834,-20.6586341858 --6.22351980209,-0.732633948326,-22.3786582947 --5.72815895081,-0.69574701786,-20.86951828 --5.70631313324,-0.699833989143,-21.0419445038 --5.69851827621,-0.704953253269,-21.2703590393 --5.58637857437,-0.70085144043,-21.1168708801 --6.28199052811,-0.769507050514,-24.0006351471 --6.32527589798,-0.776682198048,-24.3147945404 --7.97229146957,-0.936502575874,-30.9416484833 --8.08305358887,-0.955968022346,-31.7709465027 --7.97003507614,-0.953935980797,-31.7404556274 --7.61312866211,-0.929339885712,-30.7341957092 --7.52619123459,-0.930359899998,-30.7936820984 --7.45612478256,-0.928307831287,-30.7159500122 --7.37821865082,-0.929347634315,-30.809425354 --7.38564491272,-0.94059741497,-31.2668247223 --7.34288597107,-0.94572943449,-31.5202655792 --7.22082138062,-0.943668544292,-31.439786911 --7.14895391464,-0.945731699467,-31.5742588043 --4.97855710983,-0.726431310177,-22.4147338867 --4.91143131256,-0.722345769405,-22.2780036926 --4.863530159,-0.725394666195,-22.3854503632 --4.82166004181,-0.727462410927,-22.5258979797 --4.76473236084,-0.729494214058,-22.6043624878 --4.64452505112,-0.723351061344,-22.3788814545 --4.50623035431,-0.716153681278,-22.059419632 --4.28655958176,-0.697721838951,-21.3330383301 --4.25959062576,-0.698735058308,-21.3672637939 --4.29205989838,-0.710014641285,-21.8756427765 --4.21904706955,-0.709993541241,-21.862121582 --4.18120193481,-0.71307605505,-22.0285625458 --4.4759926796,-0.759172916412,-23.9576892853 --4.41909122467,-0.761219501495,-24.0621490479 --5.27986240387,-0.882153630257,-29.1867198944 --5.25095558167,-0.884201824665,-29.2829494476 --3.73553109169,-0.694602608681,-21.3098316193 --3.67255496979,-0.695604622364,-21.3362979889 --3.62868404388,-0.698671400547,-21.4757480621 --3.56370449066,-0.698670864105,-21.4982242584 --3.50173449516,-0.698676347733,-21.5306873322 --4.08349180222,-0.793966174126,-25.5415267944 --3.36553907394,-0.693537116051,-21.3234348297 --3.26735377312,-0.688410997391,-21.1269359589 --3.75824666023,-0.785760223866,-25.2682723999 --3.4316778183,-0.746788620949,-23.5990028381 --3.3617041111,-0.746790111065,-23.6254749298 --3.23233914375,-0.737553656101,-23.2370090485 --3.19936823845,-0.737564027309,-23.267250061 --3.13140773773,-0.738573312759,-23.3077259064 --3.02617669106,-0.732418954372,-23.0622329712 --2.96022439003,-0.733433544636,-23.11170578 --3.02022147179,-0.758021533489,-24.1630554199 --2.97646403313,-0.764152705669,-24.4165019989 --2.8934211731,-0.76211130619,-24.3689975739 --1.84736084938,-0.56325095892,-15.8852233887 --1.79836070538,-0.563241779804,-15.8916845322 --2.53399753571,-0.726217925549,-22.8683757782 --2.67081522942,-0.771293759346,-24.7746448517 --2.51814484596,-0.753876209259,-24.0692081451 --2.44819688797,-0.754891991615,-24.1216869354 --2.41523623466,-0.75590801239,-24.1619205475 --2.3452911377,-0.756925463676,-24.2173976898 --2.29757905006,-0.764081478119,-24.5158557892 --2.47927761078,-0.829672217369,-27.3280735016 --3.37186288834,-1.0879471302,-38.3505249023 --3.17399907112,-1.06640827656,-37.435131073 --2.22125840187,-0.828607439995,-27.292552948 --2.17016506195,-0.825542986393,-27.1928119659 --2.09934401512,-0.82963091135,-27.3732910156 --2.99099755287,-1.13709032536,-40.4897193909 --2.88225865364,-1.1422162056,-40.741230011 --2.7481815815,-1.14014267921,-40.6427726746 --2.56637620926,-1.11964046955,-39.7913665771 --2.79593634605,-1.25388097763,-45.5154953003 --2.701567173,-1.24464833736,-45.1227989197 --2.19540143013,-1.09499967098,-38.7417678833 --2.39516997337,-1.2333521843,-44.6669235229 --2.19336175919,-1.23641681671,-44.8297348022 --2.04112076759,-1.23024451733,-44.5592956543 --1.68521535397,-1.11235332489,-39.5021095276 --1.62422895432,-1.11234748363,-39.5073776245 --1.68185985088,-1.22201418877,-44.2356796265 --1.41531312466,-1.13692200184,-40.5823936462 --1.41210174561,-1.22709190845,-44.4387664795 --1.27413988113,-1.22708249092,-44.4553184509 --1.1372102499,-1.22809171677,-44.504863739 --1.00031507015,-1.23012053967,-44.5894088745 --0.9313352108,-1.23011624813,-44.5986824036 --0.794492483139,-1.23317503929,-44.7362289429 --0.656599700451,-1.23520481586,-44.8227767944 --0.517596840858,-1.23417115211,-44.797328949 --0.378778219223,-1.23824322224,-44.9588775635 --0.23876465857,-1.23720312119,-44.9224281311 --0.098730199039,-1.23615109921,-44.864982605 --0.0287356805056,-1.23613798618,-44.8592567444 -0.155751600862,-1.20590341091,-44.0629234314 -0.295746326447,-1.20694291592,-44.0811958313 -0.568172216415,-1.19534254074,-43.5447502136 -0.704010486603,-1.19147050381,-43.4030265808 -0.768811762333,-1.18760108948,-43.2121658325 -0.906819105148,-1.18863248825,-43.2424430847 -1.0406845808,-1.18574440479,-43.1277236938 -1.1735213995,-1.18287193775,-42.9840049744 -1.30740475655,-1.18097341061,-42.8872871399 -1.44236266613,-1.18003213406,-42.866569519 -1.58346772194,-1.18400800228,-42.9968490601 -1.8329846859,-1.28648412228,-47.6368789673 -1.68710136414,-1.13039052486,-40.6033325195 -1.8079097271,-1.12653136253,-40.4266242981 -1.93586885929,-1.12658751011,-40.404914856 -2.05977582932,-1.12467229366,-40.329208374 -2.19690108299,-1.12863540649,-40.4784965515 -2.31063961983,-1.12281429768,-40.2287940979 -2.35531282425,-1.11601281166,-39.9019546509 -2.48228645325,-1.11606025696,-39.8942451477 -2.60926389694,-1.11610543728,-39.8905410767 -2.75958037376,-1.1239618063,-40.2378120422 -2.89362978935,-1.12596726418,-40.3091011047 -3.00944375992,-1.12210297585,-40.1364021301 -3.16476869583,-1.13095569611,-40.4936752319 -3.22368764877,-1.12901687622,-40.4198226929 -3.36783671379,-1.13296747208,-40.5951042175 -3.48871827126,-1.13106560707,-40.492401123 -3.606580019,-1.12917423248,-40.3687019348 -3.73454737663,-1.12822473049,-40.3549957275 -3.87463736534,-1.13120794296,-40.4692802429 -3.98644948006,-1.12834322453,-40.2935905457 -4.046397686,-1.12738776207,-40.2497367859 -4.18042182922,-1.1284071207,-40.2950286865 -4.33361721039,-1.13433265686,-40.5203018188 -5.53448057175,-1.32011902332,-48.8161087036 -5.69246196747,-1.32116770744,-48.826374054 -5.80976724625,-1.32902133465,-49.1614761353 -7.49514436722,-1.57648146152,-60.1548576355 -7.68709421158,-1.57655584812,-60.1431007385 -7.87702989578,-1.57663786411,-60.1163406372 -8.07703876495,-1.57867980003,-60.1675682068 -5.66158008575,-1.1416772604,-40.6892242432 -5.77947378159,-1.13976669312,-40.5975265503 -5.88629198074,-1.13689637184,-40.4258422852 -5.98607778549,-1.13204312325,-40.2191619873 -6.11505031586,-1.13308978081,-40.2104606628 -6.29130792618,-1.13998401165,-40.5057182312 -6.42127752304,-1.14003252983,-40.4940185547 -6.33034849167,-1.11854326725,-39.5142974854 -6.46134519577,-1.11857628822,-39.5305938721 -6.59132909775,-1.11961627007,-39.5338935852 -6.72534322739,-1.12064027786,-39.5681838989 -7.10266304016,-1.15397298336,-41.0012741089 -6.97526025772,-1.12074673176,-39.5197906494 -7.10624742508,-1.12178492546,-39.5260925293 -7.19034099579,-1.12475061417,-39.63722229 -7.40072584152,-1.13457977772,-40.0704536438 -7.46738767624,-1.12778890133,-39.727809906 -7.59837198257,-1.12782859802,-39.7311058044 -7.82918977737,-1.12598645687,-39.5757331848 -7.94309473038,-1.12506747246,-39.4930458069 -7.9859828949,-1.12214148045,-39.3822174072 -8.06272411346,-1.11730730534,-39.1225624084 -8.18567657471,-1.11736309528,-39.0908699036 -8.37492179871,-1.12426590919,-39.377117157 -8.54507350922,-1.12921857834,-39.5613861084 -8.65295600891,-1.12731015682,-39.4547042847 -8.76285171509,-1.12539577484,-39.3600234985 -8.81076717377,-1.1244546175,-39.2791938782 -8.86945533752,-1.11764657497,-38.9595565796 -8.98638534546,-1.11671340466,-38.9028701782 -6.19354009628,-0.822856247425,-25.9980792999 -6.27149772644,-0.821898937225,-25.9574298859 -6.30646181107,-0.820927977562,-25.9206066132 -6.38241529465,-0.820972084999,-25.8759555817 -6.45535707474,-0.820022821426,-25.8173084259 -6.49919319153,-0.816126704216,-25.6436862946 -9.73944282532,-1.10242247581,-38.0163383484 -9.86340999603,-1.10246884823,-37.9996490479 -10.0413351059,-1.10255157948,-37.9451179504 -10.0910482407,-1.09572672844,-37.6474952698 -10.2019748688,-1.09579348564,-37.584815979 -10.3560419083,-1.09878921509,-37.6781044006 -11.3147363663,-1.16846191883,-40.6806983948 -11.4376649857,-1.16852998734,-40.6230163574 -11.8495140076,-1.19213593006,-41.5870780945 -13.0550851822,-1.28436160088,-45.5642547607 -16.1622600555,-1.52380549908,-55.7900123596 -16.1847057343,-1.51112520695,-55.2134132385 -17.5221614838,-1.60344529152,-59.0996894836 -16.4019813538,-1.47515320778,-53.438911438 -16.4548511505,-1.47223925591,-53.3100814819 -18.3968677521,-1.60579764843,-58.9638404846 -17.5488414764,-1.5293380022,-55.6159896851 -17.4830799103,-1.51175701618,-54.8004684448 -17.5215301514,-1.47764623165,-53.1697044373 -17.6455974579,-1.47963500023,-53.2618103027 -13.5186977386,-1.16753065586,-39.9011650085 -13.6065406799,-1.16463851929,-39.7455101013 -13.7134332657,-1.16372215748,-39.6458435059 -13.8504047394,-1.16476714611,-39.6351470947 -13.9554834366,-1.16774499416,-39.7342720032 -14.9963178635,-1.21991991997,-41.8622360229 -19.4157352448,-1.50392341614,-53.733921051 -19.9359931946,-1.51588380337,-54.1033325195 -21.2486076355,-1.58867156506,-57.1236495972 -19.8947505951,-1.46514630318,-51.7042922974 -20.02759552,-1.46326005459,-51.5636024475 -20.255657196,-1.46727180481,-51.6688346863 -20.5228004456,-1.47424578667,-51.8670425415 -20.6719036102,-1.47821736336,-52.0041351318 -20.8548564911,-1.47927987576,-51.9874038696 -21.2101802826,-1.49116873741,-52.3955345154 -22.0675640106,-1.53155863285,-54.0292472839 -21.2694282532,-1.47460579872,-51.5993423462 -22.9730987549,-1.55543673038,-54.7647781372 -21.1902065277,-1.44728076458,-50.271484375 -21.8918056488,-1.46908092499,-51.0377540588 -21.9725570679,-1.4642380476,-50.7821159363 -22.1805610657,-1.46727609634,-50.8233718872 -22.4516868591,-1.47325885296,-51.0045776367 -22.4753303528,-1.4654648304,-50.6229896545 -22.5412578583,-1.46551799774,-50.5571517944 -22.6711101532,-1.46362709999,-50.4184761047 -22.7638931274,-1.4597672224,-50.1998252869 -22.957868576,-1.46181917191,-50.2050971985 -23.1548480988,-1.46386873722,-50.2163658142 -23.3959102631,-1.46888077259,-50.3235969543 -23.619934082,-1.47191023827,-50.3878440857 -23.615737915,-1.46802031994,-50.1730613708 -23.828742981,-1.47105884552,-50.2133216858 -18.3740921021,-1.16499495506,-37.728099823 -18.4389305115,-1.16309797764,-37.5584754944 -18.5569972992,-1.16608285904,-37.6485939026 -18.650888443,-1.16416203976,-37.5399436951 -18.8529644012,-1.16915941238,-37.6482048035 -18.9658870697,-1.16822481155,-37.5765419006 -26.1856327057,-1.5220092535,-51.5720672607 -26.4276657104,-1.5260373354,-51.6463050842 -26.6676902771,-1.53006887436,-51.7125434875 -26.841791153,-1.53404557705,-51.8506164551 -27.0808086395,-1.53808033466,-51.9098625183 -27.3308448792,-1.54210710526,-51.9900894165 -27.5858840942,-1.54713213444,-52.0763206482 -27.8369197845,-1.55116057396,-52.153553009 -28.0909519196,-1.55518913269,-52.2317810059 -28.3519954681,-1.56021332741,-52.3220062256 -28.5220775604,-1.56419944763,-52.4390869141 -28.7821159363,-1.56922626495,-52.5233154297 -29.0281295776,-1.57226395607,-52.5785522461 -29.3001804352,-1.57728624344,-52.6777687073 -29.5822429657,-1.58330237865,-52.7939796448 -30.6334381104,-1.62383079529,-54.2755699158 -30.8333644867,-1.62490713596,-54.229850769 -31.0064353943,-1.62889933586,-54.3359298706 -38.1744041443,-1.94565999508,-66.4695892334 -38.3582191467,-1.9447940588,-66.3048858643 -38.6481895447,-1.94886398315,-66.3221054077 -39.0152664185,-1.95588696003,-66.4722518921 -34.6787872314,-1.7547018528,-58.6291809082 -36.5181846619,-1.79081189632,-59.3721504211 -36.9443664551,-1.80078661442,-59.6442565918 -38.4201164246,-1.86008107662,-61.8183059692 -36.6684417725,-1.77725064754,-58.5751457214 -39.1298599243,-1.8653485775,-61.654083252 -42.5608329773,-2.00075697899,-66.6168060303 -42.7306289673,-1.99989926815,-66.4211196899 -41.8350906372,-1.95359075069,-64.5732879639 -41.4293861389,-1.93290984631,-63.7238311768 -41.9946899414,-1.94784128666,-64.1538314819 -42.2486038208,-1.9499335289,-64.1000823975 -33.5823135376,-1.56019806862,-49.0203590393 -33.7271881104,-1.56029200554,-48.8996887207 -33.8990936279,-1.56037282944,-48.8189964294 -34.1560974121,-1.56541478634,-48.8602409363 -34.3280067444,-1.56549525261,-48.779548645 -23.5476570129,-1.0127209425,-25.9666957855 -23.622587204,-1.01277017593,-25.8840770721 -38.5845298767,-1.44733679295,-38.1155853271 -38.1521186829,-1.4314904213,-37.5671272278 -37.7636413574,-1.41568291187,-36.9478569031 -50.4956321716,-1.81486332417,-49.1790542603 -50.7805786133,-1.81893479824,-49.1473083496 -53.2820968628,-1.89251160622,-51.2559547424 -51.6056480408,-1.83502364159,-49.3226318359 -50.3234977722,-1.79043900967,-47.7880210876 -23.0153560638,-0.935417830944,-21.6479625702 -23.2594261169,-0.940420269966,-21.7412242889 -23.2323036194,-0.937480688095,-21.5776786804 -23.3682956696,-0.940506339073,-21.5680179596 -23.3291702271,-0.936568081379,-21.3954792023 -23.3620910645,-0.935614824295,-21.2898902893 -22.9216995239,-0.919756054878,-20.7506427765 -23.025718689,-0.922761023045,-20.7797851562 -23.0756568909,-0.921802461147,-20.6931838989 -15.7667913437,-0.697268486023,-13.9678039551 -15.7787418365,-0.69629752636,-13.8892240524 -15.8087024689,-0.695323169231,-13.826631546 -15.8406658173,-0.695347845554,-13.7670345306 -15.8636245728,-0.694374203682,-13.6994438171 -15.2952365875,-0.677493214607,-13.1560621262 -15.3222007751,-0.676517128944,-13.0954694748 -15.3851861954,-0.677534520626,-13.0658531189 -15.3951396942,-0.676561355591,-12.9902744293 -15.1969661713,-0.669623792171,-12.7368421555 -15.7912759781,-0.685550332069,-13.1598529816 -15.8252439499,-0.685573101044,-13.1042547226 -15.6861343384,-0.680610537529,-12.9445676804 -15.0096788406,-0.659749090672,-12.295463562 -8.2196187973,-0.458870977163,-6.57552623749 -8.22260379791,-0.457880109549,-6.53494262695 -8.24860286713,-0.457885563374,-6.51334428787 -8.27159881592,-0.457891523838,-6.48875284195 -8.29060173035,-0.457893490791,-6.48195838928 -8.3115978241,-0.457899600267,-6.45636224747 -8.33259391785,-0.457905679941,-6.43076610565 -8.36659622192,-0.458909898996,-6.41516542435 -8.3935956955,-0.45891520381,-6.39357233047 -8.41959476471,-0.458920449018,-6.37197065353 -8.44059085846,-0.458926588297,-6.3453836441 -8.45258903503,-0.458929389715,-6.33358573914 -8.4885931015,-0.459933131933,-6.31997489929 -8.51259040833,-0.459938853979,-6.2953877449 -8.53358650208,-0.459944665432,-6.26978969574 -8.5635881424,-0.459949463606,-6.25019407272 -8.58558368683,-0.459955245256,-6.22460222244 -8.6125831604,-0.459960311651,-6.20300483704 -8.62258148193,-0.459963351488,-6.1892118454 -8.65258216858,-0.460968077183,-6.16961431503 -8.68158245087,-0.460972934961,-6.1490187645 -8.7095823288,-0.460977733135,-6.1284160614 -8.72357463837,-0.460984319448,-6.09682941437 -8.75457572937,-0.460988938808,-6.07723522186 -8.77757358551,-0.460994303226,-6.05263757706 -8.79457473755,-0.460996448994,-6.04383993149 -8.82557582855,-0.462001025677,-6.0242433548 -8.85157489777,-0.462006032467,-6.00164413452 -8.87957382202,-0.462010860443,-5.98004722595 -8.8975687027,-0.462016731501,-5.95145606995 -8.92356777191,-0.462021827698,-5.92786550522 -8.94557094574,-0.463023483753,-5.92206668854 -8.97157001495,-0.463028371334,-5.8994641304 -8.99256706238,-0.463033825159,-5.87287092209 -9.02656841278,-0.463038176298,-5.85427713394 -9.04256343842,-0.463043957949,-5.82468271255 -9.08857059479,-0.464047163725,-5.81407976151 -9.10256385803,-0.464053183794,-5.78249263763 -9.12156581879,-0.464055120945,-5.77469062805 -9.14556407928,-0.464060127735,-5.75009298325 -9.18156719208,-0.465064257383,-5.73249530792 -9.24258136749,-0.466066360474,-5.73088264465 -9.27458190918,-0.466070741415,-5.71127748489 -9.30058097839,-0.466075748205,-5.68668699265 -14.0595874786,-0.593719542027,-8.65904903412 -13.8264751434,-0.586744725704,-8.48141288757 -13.562335968,-0.579778909683,-8.25600719452 -13.448261261,-0.575801432133,-8.12551212311 -13.5342712402,-0.576809227467,-8.12087917328 -13.4842233658,-0.574826657772,-8.03134155273 -13.462187767,-0.573841810226,-7.95978450775 -13.3651237488,-0.570861577988,-7.84327459335 -13.4671516418,-0.572861552238,-7.87642097473 -13.333073616,-0.568883180618,-7.73893356323 -13.3360509872,-0.567895770073,-7.68435716629 -13.3690385818,-0.568906545639,-7.64776039124 -13.3350019455,-0.566920936108,-7.57220363617 -13.3699913025,-0.56693148613,-7.53660869598 -13.3759822845,-0.56693738699,-7.51182031631 -13.3409452438,-0.56595146656,-7.43626689911 -13.3519258499,-0.564963102341,-7.38668966293 -13.3929185867,-0.565972983837,-7.35508728027 -13.2758512497,-0.561990559101,-7.23359107971 -13.4078769684,-0.564996004105,-7.25293254852 -13.4218597412,-0.565006911755,-7.20634651184 -13.3448209763,-0.562016248703,-7.13561439514 -13.4308300018,-0.564023852348,-7.12898206711 -13.4758234024,-0.564033508301,-7.09838533401 -13.4277858734,-0.563046455383,-7.01883554459 -13.4157590866,-0.562058210373,-6.95727729797 -13.3447141647,-0.559071660042,-6.86574649811 -13.4167175293,-0.561079740524,-6.8511223793 -13.353685379,-0.559087336063,-6.79038143158 -13.4306907654,-0.560095369816,-6.77775716782 -13.3886566162,-0.558107018471,-6.70320510864 -13.524682045,-0.561113536358,-6.71955251694 -13.5976848602,-0.563121795654,-6.70393037796 -13.6176710129,-0.563131690025,-6.66034698486 -13.6146497726,-0.562142014503,-6.60577297211 -13.5686254501,-0.56014829874,-6.55601596832 -13.514588356,-0.559159457684,-6.47647428513 -13.58959198,-0.560167789459,-6.46085500717 -14.1677522659,-0.574166417122,-6.68993234634 -13.6425704956,-0.560186505318,-6.38068199158 -13.848613739,-0.565192580223,-6.42797613144 -13.7925863266,-0.563198447227,-6.37422657013 -13.802570343,-0.563208043575,-6.32565069199 -13.9045810699,-0.565216362476,-6.32101488113 -13.9355716705,-0.565225422382,-6.28341627121 -13.9675617218,-0.566234707832,-6.24482774734 -14.0245599747,-0.566243708134,-6.21821928024 -14.0845575333,-0.567252635956,-6.19260978699 -14.0655422211,-0.567257642746,-6.15683984756 -14.4666366577,-0.576264679432,-6.28501987457 -14.5126304626,-0.5772742033,-6.25141859055 -14.7996892929,-0.584283053875,-6.32466983795 -15.2417898178,-0.594292521477,-6.46283531189 -15.4078130722,-0.59830302,-6.47816514969 -15.4918251038,-0.599308252335,-6.48632574081 -15.4577941895,-0.598318696022,-6.41477155685 -15.502784729,-0.599329411983,-6.37617778778 -15.5157670975,-0.598339796066,-6.32459783554 -17.2311878204,-0.640360116959,-6.98599147797 -17.2471675873,-0.640372574329,-6.92941188812 -17.3081550598,-0.641385495663,-6.89081001282 -17.3421516418,-0.64239192009,-6.873005867 -17.3921394348,-0.642404556274,-6.83040380478 -17.4251232147,-0.643417060375,-6.78081226349 -17.4921131134,-0.644429922104,-6.74420404434 -17.5230960846,-0.644442498684,-6.69261980057 -17.5840873718,-0.645455181599,-6.65400886536 -17.6240711212,-0.645467638969,-6.60641479492 -17.6720695496,-0.646474480629,-6.59260606766 -17.7180557251,-0.647487044334,-6.5470085144 -17.7730426788,-0.648499906063,-6.50440692902 -17.8150291443,-0.648512363434,-6.45681238174 -17.8660163879,-0.649525105953,-6.41221427917 -17.9150028229,-0.650537729263,-6.3666176796 -17.9709911346,-0.650550484657,-6.32401180267 -17.9929847717,-0.65155673027,-6.30021476746 -18.2220096588,-0.656574130058,-6.3185133934 -18.4200267792,-0.660591065884,-6.32482767105 -18.6690540314,-0.666610002518,-6.34711742401 -18.6930332184,-0.666622340679,-6.29053163528 -18.7340183258,-0.666635334492,-6.23894119263 -18.7840156555,-0.667642593384,-6.2241230011 -18.8480033875,-0.668656408787,-6.17952251434 -18.6139316559,-0.662659883499,-6.03608560562 -18.9129676819,-0.669681549072,-6.07034683228 -18.9629516602,-0.669694840908,-6.02075338364 -19.0599479675,-0.67170971632,-5.98712682724 -19.0689239502,-0.671721279621,-5.92455148697 -19.1009178162,-0.672728121281,-5.90175008774 -19.1849098206,-0.673742711544,-5.86213684082 -19.1588802338,-0.672752737999,-5.78858137131 -19.20586586,-0.673765778542,-5.73698997498 -18.9967823029,-0.667778074741,-5.54297018051 -19.0167598724,-0.667789578438,-5.48339605331 -19.0117492676,-0.667794346809,-5.45060825348 -19.0487346649,-0.667806565762,-5.39602518082 -19.1107215881,-0.668819725513,-5.34942245483 -19.1627082825,-0.669832468033,-5.29982376099 -19.2126941681,-0.670845091343,-5.24922847748 -19.2726802826,-0.67185819149,-5.20162439346 -19.3166656494,-0.671870470047,-5.14903116226 -19.3656616211,-0.672878026962,-5.13021850586 -19.4186477661,-0.673890769482,-5.07962179184 -19.4716358185,-0.674903512001,-5.02902269363 -19.5216197968,-0.67591625452,-4.97643184662 -19.584608078,-0.676929593086,-4.92782831192 -19.6355934143,-0.677942335606,-4.87523555756 -19.6815891266,-0.678949832916,-4.85442590714 -19.7485771179,-0.679963469505,-4.80582237244 -19.8005619049,-0.680976092815,-4.75421953201 -19.843547821,-0.680988371372,-4.69863176346 -19.8995342255,-0.682001233101,-4.64703035355 -19.9655208588,-0.683014929295,-4.59643173218 -20.0175075531,-0.684027612209,-4.54283571243 -20.0715026855,-0.685035705566,-4.52301931381 -20.1334896088,-0.686049163342,-4.47141742706 -20.1814746857,-0.687061667442,-4.41582679749 -20.2504615784,-0.689075529575,-4.3652215004 -20.3004455566,-0.68908816576,-4.30962944031 -20.3594322205,-0.690101385117,-4.2560300827 -20.4264202118,-0.69211524725,-4.20343017578 -20.4724159241,-0.693122923374,-4.18061733246 -20.5254001617,-0.693135738373,-4.12502098083 -20.5973873138,-0.695150017738,-4.07242012024 -20.6463718414,-0.696162462234,-4.01582431793 -20.7023582458,-0.697175443172,-3.96022582054 -20.7723445892,-0.698189556599,-3.90662288666 -20.8243293762,-0.699202299118,-3.84903073311 -20.8723239899,-0.70021045208,-3.82422375679 -20.9433097839,-0.701224625111,-3.77061629295 -20.9932956696,-0.702237188816,-3.7120244503 -21.0472793579,-0.703250050545,-3.6544277668 -21.1282672882,-0.705265164375,-3.60082006454 -21.1772518158,-0.705277681351,-3.54122877121 -21.2282466888,-0.707286000252,-3.51641654968 -21.3152351379,-0.708301663399,-3.4628059864 -21.3622169495,-0.70931404829,-3.40221524239 -21.4272041321,-0.710327863693,-3.34461379051 -21.493188858,-0.712341845036,-3.28601717949 -21.5551738739,-0.713355362415,-3.22741603851 -21.6001586914,-0.714367628098,-3.16483092308 -21.6901569366,-0.715379476547,-3.14499497414 -21.7341384888,-0.716391503811,-3.08240604401 -21.8041229248,-0.71840596199,-3.0228073597 -21.8731098175,-0.719420194626,-2.96320605278 -21.9390945435,-0.720434248447,-2.90260767937 -21.9900779724,-0.721446871758,-2.84001421928 -22.0650653839,-0.723461747169,-2.78040885925 -22.1190567017,-0.724470674992,-2.75259780884 -22.1860427856,-0.725484848022,-2.69099807739 -22.2590274811,-0.72749966383,-2.62939810753 -22.3170108795,-0.728512942791,-2.56580424309 -22.3789958954,-0.729526698589,-2.50220918655 -22.4649810791,-0.731542646885,-2.44159913063 -22.5089645386,-0.732554614544,-2.37600874901 -22.5889606476,-0.73356628418,-2.34918618202 -22.6549453735,-0.735580444336,-2.28459048271 -22.7219276428,-0.736594676971,-2.21999239922 -22.7869129181,-0.737608730793,-2.15539193153 -22.8818969727,-0.739625811577,-2.09278035164 -22.932882309,-0.740638494492,-2.02519226074 -21.495803833,-0.707495510578,-1.85314238071 -21.3947811127,-0.705491483212,-1.77563214302 -21.3667640686,-0.704494714737,-1.7060791254 -21.4877529144,-0.707513272762,-1.64945065975 -23.3078117371,-0.74871057272,-1.73096501827 -23.3627929688,-0.749723613262,-1.66237163544 -21.3537006378,-0.703516840935,-1.4358278513 -21.3316898346,-0.703517258167,-1.40105390549 -21.5026817322,-0.707541286945,-1.34640169144 -21.467666626,-0.706543207169,-1.27585840225 -9.67827606201,-0.435265600681,-0.441115528345 -9.68028068542,-0.435262769461,-0.410545557737 -9.67028522491,-0.435258626938,-0.379971534014 -9.66728782654,-0.435256808996,-0.36517855525 -9.68129348755,-0.435255199671,-0.335598826408 -9.65829753876,-0.435249477625,-0.304036974907 -9.67630290985,-0.435248345137,-0.275443553925 -9.66330718994,-0.435243666172,-0.244871810079 -9.67331314087,-0.435241550207,-0.21528993547 -9.66231822968,-0.435236990452,-0.18471981585 -9.65732097626,-0.435234665871,-0.168942123652 -9.66032600403,-0.435231685638,-0.139359682798 -9.65933132172,-0.435228228569,-0.109777249396 -9.6643371582,-0.435225307941,-0.0792083963752 -9.64934253693,-0.434220165014,-0.0496274791658 -9.65434837341,-0.43421715498,-0.0190588254482 -9.65435409546,-0.434213668108,0.010523095727 -9.64535713196,-0.434210836887,0.0253119654953 -9.64936256409,-0.434207648039,0.0558805577457 -9.64636802673,-0.43420368433,0.085461191833 -9.64637374878,-0.434200048447,0.115042626858 -9.6403799057,-0.434195518494,0.14560765028 -9.64238643646,-0.434192061424,0.175189673901 -9.63438987732,-0.434189230204,0.189976543188 -9.65839481354,-0.434188306332,0.220555663109 -9.62840175629,-0.434180796146,0.250120997429 -9.63240718842,-0.434177458286,0.279703974724 -9.63441467285,-0.434173822403,0.309286057949 -9.63042068481,-0.43416929245,0.339850276709 -9.62342739105,-0.434164464474,0.369426012039 -9.6414308548,-0.434164792299,0.384229660034 -9.62443733215,-0.434158593416,0.413797587156 -9.62844371796,-0.434154987335,0.444367587566 -9.61745071411,-0.434149473906,0.473938882351 -9.62645721436,-0.43414658308,0.503527641296 -9.60946369171,-0.433140158653,0.533092558384 -9.62447071075,-0.434137880802,0.563673615456 -9.61747455597,-0.434134840965,0.578456997871 -9.61648082733,-0.434130519629,0.608036756516 -9.61348819733,-0.434125870466,0.637614309788 -9.61549568176,-0.434121727943,0.668183505535 -9.59650325775,-0.433114886284,0.696756124496 -9.62050914764,-0.434113800526,0.72735196352 -9.60551738739,-0.434107333422,0.756914317608 -9.6125202179,-0.434106141329,0.771714031696 -9.60052776337,-0.43410000205,0.801279306412 -9.60653495789,-0.43409627676,0.831854820251 -9.59454250336,-0.434090197086,0.860433101654 -9.59655094147,-0.434085816145,0.89100331068 -9.60255813599,-0.43408203125,0.921580016613 -9.60856151581,-0.434080660343,0.936380147934 -9.678565979,-0.436085730791,0.971988916397 -9.73957157135,-0.437089532614,1.00758957863 -9.76057815552,-0.438087821007,1.04017102718 -9.7345867157,-0.43707960844,1.06774401665 -9.74959373474,-0.438076943159,1.10031712055 -9.73460197449,-0.437070190907,1.12889385223 -9.75360488892,-0.438070416451,1.14668095112 -9.73261356354,-0.437062829733,1.17425990105 -9.74062156677,-0.438059151173,1.2058365345 -9.72562980652,-0.437052100897,1.2353978157 -9.73863697052,-0.438049197197,1.2669852972 -9.7216463089,-0.437041848898,1.29555535316 -9.74365234375,-0.438040077686,1.32913541794 -9.71765804291,-0.43703392148,1.34091842175 -9.71866607666,-0.437029123306,1.37149703503 -9.7266740799,-0.438025325537,1.40307724476 -9.71668338776,-0.43801882863,1.43264651299 -9.71069145203,-0.438012957573,1.46222424507 -9.7206993103,-0.438009262085,1.49479734898 -9.7027053833,-0.438004076481,1.50757920742 -9.70671272278,-0.437999665737,1.53816628456 -9.70572090149,-0.43799418211,1.5697286129 -9.70172977448,-0.437988519669,1.59931111336 -9.69573974609,-0.437982469797,1.62888884544 -9.70074748993,-0.437977969646,1.66046667099 -9.68775749207,-0.437970608473,1.6900267601 -9.69176101685,-0.437968611717,1.70581996441 -9.68877029419,-0.437962979078,1.7354054451 -9.68377971649,-0.437956809998,1.76597237587 -9.67678928375,-0.437950402498,1.79554736614 -9.68579673767,-0.437946349382,1.82812547684 -9.67480659485,-0.437939316034,1.8567032814 -9.67881584167,-0.437934488058,1.88828241825 -9.67482089996,-0.437931150198,1.9030687809 -9.67482948303,-0.437925547361,1.93463718891 -9.67383861542,-0.438919901848,1.96521651745 -9.66584777832,-0.437913149595,1.99478948116 -9.66585731506,-0.438907444477,2.02635884285 -9.64486885071,-0.437898665667,2.05293273926 -9.66787624359,-0.438896626234,2.08851909637 -9.65088272095,-0.438891232014,2.10030579567 -9.65889072418,-0.438886672258,2.13387489319 -9.65090179443,-0.438879698515,2.1634478569 -9.64791107178,-0.438873499632,2.19402360916 -9.64992046356,-0.438868105412,2.22560238838 -9.64893054962,-0.438862264156,2.2561852932 -9.64393520355,-0.438858538866,2.27096891403 -9.63794517517,-0.438851833344,2.3005490303 -9.65595340729,-0.439848840237,2.33613061905 -9.63596534729,-0.439839661121,2.36369013786 -9.64197444916,-0.43983477354,2.39627289772 -9.63198566437,-0.439827352762,2.42485332489 -9.64199447632,-0.439822912216,2.45942544937 -9.62300109863,-0.439816921949,2.47021222115 -9.64100933075,-0.439813762903,2.50678753853 -9.61802196503,-0.439804077148,2.53236103058 -9.63602924347,-0.44080093503,2.56893897057 -9.61704158783,-0.439791828394,2.59551334381 -9.61705207825,-0.44078579545,2.62709212303 -9.61905670166,-0.440782994032,2.64387631416 -9.63206577301,-0.440778940916,2.67945361137 -9.61607837677,-0.440770208836,2.70702552795 -9.6200876236,-0.440764784813,2.7396094799 -9.6160993576,-0.440757781267,2.77117609978 -9.61110973358,-0.440750747919,2.80175185204 -9.59712219238,-0.440742105246,2.83031797409 -9.6141242981,-0.441741794348,2.85111308098 -9.59413814545,-0.441732168198,2.87768101692 -9.60514640808,-0.441727846861,2.91227149963 -9.59815788269,-0.441720277071,2.94284129143 -9.60116863251,-0.441714346409,2.97641372681 -9.58618068695,-0.441705524921,3.00398921967 -9.6021900177,-0.442701756954,3.04156661034 -9.58819675446,-0.442696213722,3.05335259438 -9.60220623016,-0.442692190409,3.08993697166 -9.5832195282,-0.442682534456,3.11650824547 -9.59122848511,-0.44267731905,3.15208172798 -9.52124881744,-0.441658854485,3.16263222694 -9.49426269531,-0.440647751093,3.18620300293 -9.43028259277,-0.439630240202,3.19775938988 -9.44628620148,-0.440629601479,3.21954774857 -9.44229698181,-0.440622389317,3.25012993813 -9.44730854034,-0.440616488457,3.28470253944 -9.42632198334,-0.440606176853,3.31027078629 -9.44533157349,-0.440602838993,3.34885978699 -9.41734695435,-0.440591186285,3.37242031097 -9.43734931946,-0.441591322422,3.39522099495 -9.42336273193,-0.441581994295,3.42378401756 -9.43737220764,-0.441577672958,3.46136760712 -9.41738700867,-0.441567450762,3.48694014549 -9.42839622498,-0.441562592983,3.52352428436 -9.41341018677,-0.441553115845,3.55109596252 -9.42341995239,-0.442547857761,3.58866500854 -9.41842746735,-0.442543715239,3.60246372223 -9.41843891144,-0.442536741495,3.63603544235 -9.41145133972,-0.442528605461,3.66661047935 -9.42646121979,-0.44352415204,3.70618486404 -9.40947532654,-0.443514257669,3.73276042938 -9.40648841858,-0.44350668788,3.76533293724 -9.40549945831,-0.443499624729,3.79791641235 -9.41550445557,-0.44449788332,3.81870722771 -9.39851856232,-0.443487882614,3.8452835083 -9.40852928162,-0.444482445717,3.88385272026 -9.39554309845,-0.444473057985,3.91242551804 -9.41155147552,-0.445468962193,3.95201706886 -9.39556694031,-0.444458752871,3.9805753231 -9.40057182312,-0.445456117392,3.99936842918 -9.38258743286,-0.445445746183,4.02594041824 -9.40359687805,-0.445442199707,4.06951618195 -9.37861156464,-0.445430546999,4.09308671951 -9.39062213898,-0.446425676346,4.13167762756 -9.37763690948,-0.446415930986,4.16124153137 -9.3866481781,-0.446410268545,4.19981908798 -9.37665557861,-0.446404844522,4.21260595322 -9.39166545868,-0.447400391102,4.25319480896 -9.37368106842,-0.447389662266,4.28075647354 -9.37869167328,-0.447383344173,4.31734085083 -9.36970615387,-0.447374403477,4.3479180336 -9.36872005463,-0.448366641998,4.38348197937 -9.35872745514,-0.447361171246,4.39626932144 -9.38473510742,-0.448358595371,4.4428601265 -9.35875225067,-0.448346346617,4.46642494202 -9.35476589203,-0.448338150978,4.49999856949 -9.35477924347,-0.449330657721,4.53557300568 -9.36878871918,-0.449325889349,4.5771613121 -9.3997964859,-0.45132407546,4.62774658203 -9.48978710175,-0.453336805105,4.68955659866 -9.47880172729,-0.453327357769,4.72013425827 -9.49181270599,-0.4543222785,4.76271629333 -9.47682762146,-0.454311877489,4.792283535 -9.48184013367,-0.454305142164,4.83185577393 -9.45985603333,-0.454293519258,4.85742712021 -9.48086547852,-0.455289751291,4.90500736237 -9.46887397766,-0.455283850431,4.91679906845 -9.46788692474,-0.455276012421,4.95337343216 -9.46689987183,-0.456268191338,4.98994970322 -9.46791362762,-0.456260740757,5.02752828598 -9.44892978668,-0.456249475479,5.05509710312 -9.46094036102,-0.457244038582,5.09867858887 -9.44795513153,-0.45723387599,5.12925195694 -9.4569606781,-0.457231670618,5.15304088593 -9.44897556305,-0.457222372293,5.18661308289 -9.45598697662,-0.45821595192,5.22819232941 -9.44000339508,-0.458205282688,5.25677156448 -9.46001243591,-0.459201127291,5.30634784698 -9.43403053284,-0.459188461304,5.32991981506 -9.45003414154,-0.459187418222,5.35870456696 -9.43904972076,-0.459177613258,5.39028549194 -9.43606376648,-0.460169047117,5.42785215378 -9.43007850647,-0.460160136223,5.46243476868 -9.44108963013,-0.461154192686,5.50800848007 -9.42210674286,-0.461142748594,5.53558397293 -9.42811965942,-0.461135923862,5.57816076279 -9.42512702942,-0.461131364107,5.59594869614 -9.43113899231,-0.462124377489,5.63951778412 -9.41815471649,-0.46211412549,5.67010307312 -9.37117862701,-0.461096942425,5.68265533447 -9.33619880676,-0.461082190275,5.70122051239 -9.29322052002,-0.460065901279,5.71478462219 -9.26723957062,-0.460052847862,5.73835420609 -9.27724456787,-0.46105068922,5.7641453743 -9.26426124573,-0.461040079594,5.79571819305 -9.27527332306,-0.461034029722,5.84229707718 -9.25629043579,-0.461022347212,5.86987304688 -9.26030349731,-0.462014883757,5.91244935989 -9.25731754303,-0.462006241083,5.95003223419 -9.25933170319,-0.462998449802,5.99160861969 -9.25134086609,-0.46299263835,6.00738763809 -9.26135253906,-0.46398639679,6.05397033691 -9.24337005615,-0.463974565268,6.08353662491 -9.24938392639,-0.463967502117,6.12811613083 -9.2393989563,-0.46495744586,6.16169834137 -9.2434129715,-0.464949756861,6.20626735687 -9.23042297363,-0.464943140745,6.21805477142 -9.25843143463,-0.466940313578,6.2776427269 -9.2284526825,-0.465925902128,6.30020046234 -9.24246311188,-0.466920405626,6.35078620911 -9.22748088837,-0.466909140348,6.38235998154 -9.22449493408,-0.467900007963,6.42292928696 -9.22150325775,-0.467895269394,6.44171905518 -9.23451519012,-0.468889325857,6.49329614639 -9.21553325653,-0.468877106905,6.52286481857 -9.22554588318,-0.469870835543,6.57145404816 -9.21156406403,-0.46985951066,6.60502099991 -9.20557880402,-0.46984988451,6.64359712601 -9.19059753418,-0.469838410616,6.67616844177 -9.21559906006,-0.470838993788,6.71596097946 -9.19861698151,-0.4718272686,6.74653911591 -9.20363044739,-0.471819639206,6.79411363602 -9.19364738464,-0.472809076309,6.83068656921 -9.19966125488,-0.472801655531,6.87926292419 -9.18667793274,-0.47379052639,6.91383647919 -9.19569206238,-0.473783761263,6.9644203186 -9.18470096588,-0.473777145147,6.97919845581 -9.18871498108,-0.474769324064,7.02677726746 -9.18772983551,-0.475760579109,7.0703587532 -9.31571674347,-0.479777246714,7.21297073364 -9.06478691101,-0.472718864679,7.06647825241 -9.04480743408,-0.473706185818,7.09604883194 -9.05582714081,-0.474695235491,7.17241573334 -8.99785423279,-0.473675042391,7.17198038101 -8.95388031006,-0.472657501698,7.18254566193 -8.90190696716,-0.471638470888,7.18611288071 -8.91391944885,-0.472631931305,7.24168682098 -8.89693832397,-0.472619593143,7.27425336838 -8.91094303131,-0.473618030548,7.30804920197 -8.90196037292,-0.474607408047,7.34662437439 -8.9009771347,-0.474598288536,7.39219856262 -8.91198921204,-0.475591570139,7.44777727127 -9.15194892883,-0.483630597591,7.69341564178 -9.14196681976,-0.483619600534,7.73398399353 -9.13498306274,-0.48460945487,7.77556705475 -9.14598846436,-0.485607177019,7.80935573578 -9.14300441742,-0.485597610474,7.85592937469 -9.13102245331,-0.486586302519,7.89450502396 -9.13703727722,-0.48757854104,7.94908189774 -9.12405490875,-0.487566918135,7.9876537323 -9.113073349,-0.487555682659,8.02822399139 -9.26705169678,-0.493577599525,8.21284008026 -9.23906612396,-0.492567509413,8.21362304688 -9.25407886505,-0.493561476469,8.27820110321 -9.24809551239,-0.494551181793,8.32477378845 -9.24311256409,-0.495541274548,8.37135410309 -9.22313213348,-0.495528101921,8.40592098236 -9.23114585876,-0.496520787477,8.46450614929 -9.23115444183,-0.496516168118,8.49129009247 -9.22117233276,-0.497505038977,8.53486442566 -9.22818565369,-0.498497307301,8.59444046021 -9.22220230103,-0.499487012625,8.64201641083 -9.19822502136,-0.499472975731,8.67358398438 -9.21223735809,-0.500466704369,8.74016666412 -9.21425151825,-0.50145804882,8.79574680328 -9.22525691986,-0.50245565176,8.83353614807 -9.20727729797,-0.502442657948,8.87210083008 -9.30328559875,-0.507443606853,9.07527446747 -9.1753320694,-0.50340873003,9.00583076477 -9.14337253571,-0.5043836236,9.08697032928 -9.10938835144,-0.504372179508,9.08075618744 -9.05941772461,-0.503352642059,9.08831501007 -9.04543685913,-0.503340601921,9.12989330292 -9.049451828,-0.504332065582,9.1904706955 -9.03946971893,-0.50532078743,9.23704624176 -9.04548549652,-0.506312549114,9.30062294006 -9.04549312592,-0.507307946682,9.32941055298 -9.0365114212,-0.507296562195,9.37897777557 -9.0315284729,-0.508286237717,9.43155574799 -9.02554607391,-0.509275734425,9.48313617706 -9.01856422424,-0.510264873505,9.53471088409 -9.01158332825,-0.51025390625,9.58728027344 -9.01259899139,-0.511244893074,9.64686393738 -9.02560329437,-0.512242615223,9.69164848328 -8.98862934113,-0.512225627899,9.71221733093 -8.9306602478,-0.511204600334,9.70878982544 -8.87868976593,-0.510184407234,9.71335124969 -8.80872440338,-0.509160578251,9.69790935516 -8.76775169373,-0.509142637253,9.7134771347 -8.7297706604,-0.508130252361,9.70126152039 -8.72378826141,-0.509119391441,9.75583076477 -8.72280502319,-0.510109603405,9.81540966034 -8.7128238678,-0.510098218918,9.86399364471 -8.69784450531,-0.511085510254,9.9095621109 -8.83182621002,-0.517103135586,10.124165535 -8.94881343842,-0.522117376328,10.3217639923 -8.96281814575,-0.523115336895,10.370552063 -8.95383644104,-0.524103879929,10.4251279831 -8.95285320282,-0.525094032288,10.4897022247 -8.93787384033,-0.525081336498,10.538274765 -8.94588851929,-0.527073442936,10.612859726 -8.93190860748,-0.528060853481,10.6634321213 -8.9239282608,-0.528049409389,10.7220020294 -8.94093132019,-0.530048131943,10.7757959366 -8.93095111847,-0.531036257744,10.832367897 -8.92097091675,-0.531024634838,10.8879470825 -8.92998504639,-0.533016622066,10.9685220718 -8.90700817108,-0.533002138138,11.010093689 -8.90602588654,-0.534992218018,11.0786705017 -8.89404582977,-0.534979999065,11.1342449188 -9.02701854706,-0.541002213955,11.3360557556 -8.88607311249,-0.536963701248,11.2306098938 -3.4345407486,-0.336846202612,4.40143013 -3.40156888962,-0.335829615593,4.3870100975 -3.39558982849,-0.335818558931,4.4065952301 -3.38461256027,-0.336806356907,4.42017507553 -9.01313304901,-0.548935413361,11.7992963791 -9.01015090942,-0.549924850464,11.8718709946 -8.99817085266,-0.550912678242,11.9314517975 -8.9861907959,-0.551900267601,11.993024826 -8.9792098999,-0.552888989449,12.0615997314 -8.98122692108,-0.554879367352,12.1431741714 -8.98523330688,-0.555875360966,12.1869678497 -8.98425197601,-0.556864976883,12.2665367126 -8.96527385712,-0.55785125494,12.3201122284 -8.96928977966,-0.558842182159,12.4056930542 -8.95531082153,-0.559829413891,12.4672698975 -8.95133018494,-0.561818599701,12.543844223 -8.91634845734,-0.560806334019,12.5366239548 -8.8863735199,-0.56179022789,12.5771951675 -8.8114118576,-0.559764862061,12.5537595749 -8.79843330383,-0.560752034187,12.6193294525 -8.78745269775,-0.561739802361,12.6869058609 -8.78447246552,-0.563729047775,12.7674808502 -8.77349185944,-0.564716696739,12.837053299 -8.7934961319,-0.566715836525,12.9088468552 -8.7775182724,-0.567702353001,12.9724178314 -8.77853488922,-0.568692564964,13.0599994659 -8.75855827332,-0.56967818737,13.1195669174 -8.75957489014,-0.571668386459,13.2091464996 -8.744597435,-0.572655260563,13.274725914 -8.74561405182,-0.574645221233,13.3672981262 -8.74762248993,-0.575640559196,13.4160861969 -8.74464130402,-0.576629817486,13.502664566 -8.7326631546,-0.578617036343,13.5772352219 -8.73468017578,-0.579607307911,13.6728153229 -8.7147026062,-0.580593109131,13.7353897095 -8.71472072601,-0.582582890987,13.8299674988 -8.69774436951,-0.583569049835,13.8995380402 -8.80372333527,-0.589585542679,14.1183376312 -9.21062469482,-0.608658492565,14.8709793091 -9.17665195465,-0.609641253948,14.9195518494 -9.15767478943,-0.610626995564,14.9941205978 -10.579287529,-0.674907028675,17.4379138947 -10.5083255768,-0.674882173538,17.443479538 -10.41036129,-0.671856880188,17.34324646 -9.08975601196,-0.614577054977,15.2536287308 -8.82586765289,-0.60750246048,15.0237417221 -8.78189849854,-0.607483148575,15.0563116074 -8.76392269135,-0.608469247818,15.1328887939 -8.70295715332,-0.608446478844,15.1354589462 -9.07885837555,-0.626517832279,15.8462963104 -9.09087276459,-0.629509866238,15.9818754196 -9.08889198303,-0.631498992443,16.0954494476 -9.09990596771,-0.634490668774,16.2340240479 -9.06493473053,-0.635473251343,16.289598465 -9.5888004303,-0.662569403648,17.3572444916 -9.53583335876,-0.662548243999,17.3878173828 -8.75908660889,-0.629374265671,16.1530723572 -8.70412063599,-0.628352642059,16.1716423035 -8.65615272522,-0.628332436085,16.203212738 -8.59018993378,-0.628308475018,16.2017784119 -8.54922103882,-0.62828963995,16.2463512421 -8.5572271347,-0.630285978317,16.323141098 -8.54724884033,-0.632273554802,16.4277191162 -8.53727054596,-0.634260833263,16.5352916718 -8.52729129791,-0.636248409748,16.6418685913 -8.51631355286,-0.638235509396,16.7504405975 -8.50333595276,-0.64022231102,16.855014801 -8.49535655975,-0.642210245132,16.9685974121 -8.51036071777,-0.644207835197,17.0663833618 -8.49638366699,-0.646194398403,17.1729564667 -8.48840522766,-0.649182200432,17.2925319672 -8.48142623901,-0.651170253754,17.4141120911 -8.47944450378,-0.654159188271,17.5496845245 -8.44147396088,-0.655140936375,17.6102600098 -10.6018619537,-0.774562299252,22.3848819733 -10.5768880844,-0.777546346188,22.5144519806 -11.1487360001,-0.811651229858,23.9260940552 -11.0567808151,-0.810621738434,23.9226608276 -10.698923111,-0.799527645111,23.5337657928 -10.6449489594,-0.798511326313,23.511548996 -10.5539941788,-0.797482073307,23.5061130524 -10.4670381546,-0.796453535557,23.5096759796 -10.3780832291,-0.795424699783,23.5072422028 -10.2871284485,-0.794395387173,23.5008029938 -10.1981744766,-0.794366419315,23.4983673096 -10.1102190018,-0.793337762356,23.496931076 -10.0592422485,-0.792322039604,23.4787139893 -9.97128772736,-0.791293442249,23.4752807617 -9.88333320618,-0.790264725685,23.4728450775 -9.79837703705,-0.790236771107,23.4754142761 -9.70842266083,-0.789207696915,23.4669761658 -9.62446689606,-0.78817987442,23.4715442657 -9.53251266479,-0.7871504426,23.4541130066 -9.48053836823,-0.786134541035,23.4318943024 -9.40058040619,-0.786107540131,23.4444618225 -9.31262588501,-0.785078883171,23.4380264282 -9.22667121887,-0.784050762653,23.4335975647 -9.14071559906,-0.783022403717,23.4321613312 -9.05376148224,-0.781994104385,23.4227333069 -8.96580696106,-0.780965447426,23.4152946472 -8.92082977295,-0.780950963497,23.4070796967 -8.83487510681,-0.779922783375,23.4006481171 -8.74592208862,-0.778894007206,23.387216568 -8.6649646759,-0.777866840363,23.3917884827 -8.57901000977,-0.77783870697,23.384355545 -8.49405479431,-0.776810765266,23.3789253235 -8.45007801056,-0.775796532631,23.3707103729 -8.3651227951,-0.775768518448,23.3652763367 -8.28416633606,-0.774741470814,23.36784935 -8.20021247864,-0.773713767529,23.3634185791 -8.11325836182,-0.772685348988,23.350982666 -8.03130245209,-0.77265805006,23.3495559692 -7.95034694672,-0.771631002426,23.3511257172 -7.90337085724,-0.770616233349,23.3319129944 -7.81941604614,-0.770588576794,23.3234844208 -7.73846054077,-0.769561350346,23.3270492554 -7.65550518036,-0.768533945084,23.3186225891 -7.57754898071,-0.768507480621,23.3281917572 -7.49459409714,-0.767480015755,23.321762085 -7.4476184845,-0.766465306282,23.2985515594 -4.11266040802,-0.519795358181,12.9909257889 -4.07169294357,-0.519776761532,13.0015077591 -7.2037525177,-0.765384078026,23.2882633209 -7.12279701233,-0.764357149601,23.2838363647 -7.04284143448,-0.763330280781,23.284406662 -6.96188640594,-0.763303399086,23.2769832611 -6.91890954971,-0.762289345264,23.2687625885 -6.83895397186,-0.762262701988,23.2633399963 -6.75799942017,-0.761235713959,23.2589092255 -6.67704439163,-0.760208904743,23.2504825592 -6.60008811951,-0.760182738304,23.2580547333 -6.51913261414,-0.759155929089,23.247631073 -6.43717813492,-0.759128808975,23.23620224 -6.39620113373,-0.758115291595,23.2289905548 -6.31524610519,-0.758088409901,23.2195606232 -6.23629045486,-0.757062017918,23.2151374817 -6.16133403778,-0.75703638792,23.2267093658 -6.08037948608,-0.756009578705,23.2152824402 -6.00042486191,-0.754983007908,23.2058582306 -5.92646741867,-0.754957675934,23.2184333801 -5.88049173355,-0.753943145275,23.1912193298 -5.80153656006,-0.753916859627,23.1817970276 -5.72658014297,-0.753891348839,23.189371109 -5.64762544632,-0.752864956856,23.1839447021 -5.57066917419,-0.752839148045,23.181520462 -5.49371385574,-0.751813292503,23.1810951233 -5.45173692703,-0.75179964304,23.1658840179 -5.37278223038,-0.750773429871,23.1554584503 -5.29482650757,-0.749747395515,23.1480350494 -5.21887111664,-0.749721825123,23.1486110687 -5.14291524887,-0.749696135521,23.151184082 -5.0649600029,-0.74867016077,23.1417636871 -5.01799488068,-0.751650214195,23.2763385773 -5.01900482178,-0.755645036697,23.4581317902 -3.29456233978,-0.572301924229,15.6066799164 -3.2406001091,-0.571280896664,15.5932569504 -3.19463539124,-0.572261452675,15.6178359985 -3.15466880798,-0.573243200779,15.6724157333 -3.05971908569,-0.567214369774,15.4489974976 -3.02174139023,-0.566201746464,15.3847846985 -2.97477674484,-0.566182255745,15.3973693848 -2.93680930138,-0.567164480686,15.4599514008 -2.90384078026,-0.569147527218,15.5545282364 -2.85787606239,-0.569128155708,15.5791082382 -2.81091165543,-0.57010859251,15.5976896286 -2.7729446888,-0.571090757847,15.6692686081 -2.77395486832,-0.575085639954,15.8210573196 -4.76535320282,-0.851454496384,27.7766513824 -4.72638607025,-0.857436060905,28.0812263489 -4.88137865067,-0.905443668365,30.1663894653 -4.7964258194,-0.906416654587,30.2379684448 -4.70147657394,-0.906387627125,30.2525463104 -4.65050315857,-0.906372368336,30.2423305511 -4.56854963303,-0.908345997334,30.3389110565 -4.53957939148,-0.918329536915,30.8064899445 -4.5246052742,-0.931315720081,31.3920650482 -4.66858053207,-0.971332192421,33.1276550293 -4.55365896225,-0.987288475037,33.8558082581 -4.50268554688,-0.987273335457,33.8825950623 -4.42772960663,-0.993248224258,34.1381721497 -4.3837647438,-1.00422906876,34.6507492065 -4.32184648514,-1.05718457699,36.9634895325 -2.72036170959,-0.74787902832,23.5142822266 -2.63640928268,-0.745852708817,23.4328594208 -2.60544037819,-0.754836320877,23.8334407806 -2.54448056221,-0.757814347744,23.9710235596 -2.46852564812,-0.757789611816,23.9706058502 -2.37857532501,-0.753762245178,23.8321857452 -4.05106878281,-1.17206287384,42.1087532043 -3.9751033783,-1.17004334927,42.0075416565 -3.87615585327,-1.17801403999,42.3801193237 -3.80020093918,-1.19298899174,43.0466995239 -3.87219929695,-1.24899148941,45.5062789917 -3.74725985527,-1.25395739079,45.7358589172 -3.60732507706,-1.25492048264,45.7884407043 -3.60833525658,-1.27691531181,46.7492256165 -3.63734722137,-1.33190977573,49.1588058472 -3.48341703415,-1.33187043667,49.1693878174 -3.3654756546,-1.34383797646,49.7179679871 -3.24055767059,-1.41379320621,52.8151283264 -3.09362530708,-1.42175543308,53.1477088928 -3.03865337372,-1.43373990059,53.6734962463 -3.221616745,-1.58476269245,60.3050765991 -3.03169798851,-1.58371710777,60.300655365 -2.84177947044,-1.58367156982,60.2952384949 -1.62118661404,-1.04443800449,36.6428451538 -1.50824368,-1.0454069376,36.6964302063 -1.417293787,-1.06037986279,37.3540077209 -1.21838867664,-1.04332816601,36.6523857117 -1.11944115162,-1.05529987812,37.182975769 -1.85723006725,-1.79742288589,69.7305145264 -1.730291605,-1.88838922977,73.7450942993 -1.55236935616,-1.94934654236,76.4046783447 -1.00156497955,-1.52923667431,57.9702758789 -0.659705162048,-1.39815962315,52.2536621094 -0.504775643349,-1.4221214056,53.3032455444 -0.168924704194,-1.41104066372,52.7904205322 -0.00199911231175,-1.42600047588,53.4840049744 --0.549775719643,-1.33987784386,74.4440307617 --12.4139661789,-1.33741664886,73.3806152344 --12.6598701477,-1.33937001228,73.4292221069 --13.3635997772,-1.3502395153,74.0332641602 --12.0909395218,-1.18942964077,63.5289764404 --12.2848596573,-1.1883919239,63.4635848999 --11.5909881592,-1.07047641277,55.6277198792 --11.7619152069,-1.06944274902,55.5733299255 --11.9488372803,-1.07040655613,55.5939407349 --16.4624080658,-1.38067686558,75.4928741455 --16.4743862152,-1.36467051506,74.4194793701 --16.2094573975,-1.33771049976,72.6792602539 --16.4103775024,-1.33567380905,72.5078811646 --16.04347229,-1.2957277298,69.8594512939 --15.9534816742,-1.27473723888,68.4760437012 --15.9734563828,-1.26172947884,67.599647522 --15.975438118,-1.24772453308,66.670249939 --15.5515604019,-1.21378910542,64.4500198364 --15.6105232239,-1.20477509499,63.8136253357 --15.5525226593,-1.18777942657,62.7172164917 --15.7214508057,-1.18574821949,62.5568351746 --11.0838537216,-0.880463600159,42.9176292419 --11.2947692871,-0.884424567223,43.174243927 --11.3027572632,-0.881420254707,42.9280433655 --11.4266996384,-0.880394876003,42.851650238 --15.0845470428,-1.08582174778,55.9015846252 --15.0615358353,-1.07482051849,55.1241798401 --15.2264661789,-1.07379031181,55.0477981567 --15.3853988647,-1.07276117802,54.9484138489 --15.5913162231,-1.07472491264,55.0170288086 --15.6902761459,-1.07570743561,55.0368385315 --8.95233917236,-0.696734428406,30.9777812958 --9.05628681183,-0.696711659431,30.9703845978 --9.17922973633,-0.697686135769,31.0279903412 --9.32116699219,-0.700657904148,31.14960289 --9.46010494232,-0.702630102634,31.2542095184 --9.46209430695,-0.700626552105,31.0840072632 --9.54005146027,-0.699608206749,30.9906101227 --9.7269744873,-0.703573405743,31.2482261658 --10.0288629532,-0.714521586895,31.8678531647 --10.1218147278,-0.71350133419,31.8134613037 --10.2297620773,-0.71447879076,31.804063797 --14.2285165787,-0.905875563622,43.8080978394 --14.285490036,-0.904864728451,43.7489051819 --14.4834117889,-0.907830536366,43.8895263672 --14.6143541336,-0.907806456089,43.8231391907 --14.8462638855,-0.912767529488,44.0547637939 --18.7310581207,-1.089189291,55.0417938232 --11.4902267456,-0.735244214535,32.8669776917 --13.9064712524,-0.84088498354,39.4018554688 --13.9094524384,-0.835879802704,39.0184555054 --13.8764438629,-0.828879892826,38.541053772 --13.871427536,-0.822875857353,38.1496505737 --13.8484163284,-0.816874444485,37.7122459412 --13.7704315186,-0.809883415699,37.317035675 --13.7494192123,-0.803881704807,36.9026374817 --13.7314071655,-0.798879563808,36.5012321472 --13.7153940201,-0.792877137661,36.1108283997 --13.6933832169,-0.786875605583,35.7144241333 --13.6723718643,-0.781873941422,35.3260231018 --13.7803211212,-0.781853914261,35.2746315002 --13.8432941437,-0.781842648983,35.2714424133 --13.9122543335,-0.779828250408,35.1210479736 --13.7312736511,-0.763844668865,34.0322227478 --13.855219841,-0.763822674751,34.0308380127 --13.4683179855,-0.744872391224,32.7803878784 --13.4782972336,-0.740866303444,32.5119857788 --13.4183073044,-0.735872387886,32.2247810364 --13.4042930603,-0.731869697571,31.905374527 --13.3832826614,-0.726867973804,31.5769729614 --13.3642702103,-0.722865998745,31.2565689087 --13.3492574692,-0.717863380909,30.9491615295 --13.3252468109,-0.713862121105,30.6277599335 --13.3222398758,-0.711860179901,30.4895591736 --13.4341878891,-0.71184027195,30.4841747284 --13.4831562042,-0.709829092026,30.3347797394 --13.6590862274,-0.712800681591,30.4724025726 --13.1942071915,-0.69285929203,29.1839351654 --13.2131843567,-0.689852178097,28.9815349579 --13.2021694183,-0.685849130154,28.7161312103 --13.1391801834,-0.68185532093,28.4609241486 --13.1331653595,-0.678851544857,28.2115192413 --13.1171522141,-0.674849152565,27.9471168518 --13.1111364365,-0.671845436096,27.7047119141 --13.0961236954,-0.66784286499,27.4483070374 --13.0851097107,-0.664839863777,27.2049064636 --13.0730962753,-0.660836935043,26.9615039825 --13.0281009674,-0.65784060955,26.7582931519 --13.1080598831,-0.657825648785,26.7099056244 --13.2140111923,-0.658807277679,26.7125205994 --9.20117473602,-0.519326865673,18.4194736481 --9.23814678192,-0.518315911293,18.3470726013 --9.3081073761,-0.518300831318,18.3426799774 --12.9160404205,-0.638830661774,25.396068573 --9.16612148285,-0.511310100555,17.8500480652 --9.21408939362,-0.511297821999,17.8036460876 --9.28305053711,-0.511282980442,17.7992534637 --9.53196048737,-0.517245233059,18.1398944855 --9.6029214859,-0.518230378628,18.1354999542 --12.8739500046,-0.621809542179,24.1666526794 --12.8379526138,-0.619811952114,24.0064430237 --12.8499326706,-0.617806017399,23.8480453491 --9.56486988068,-0.510214865208,17.5880756378 --9.60084152222,-0.510204553604,17.5216770172 --9.65980625153,-0.510191440582,17.4982814789 --9.73976516724,-0.510175764561,17.510887146 --13.2087440491,-0.616739869118,23.6130962372 --13.2697191238,-0.617730259895,23.6359100342 --13.3586759567,-0.61771517992,23.6175193787 --13.4496326447,-0.618699967861,23.605134964 --13.5415906906,-0.618684768677,23.59375 --13.6335477829,-0.619669675827,23.5813655853 --13.7275037766,-0.620654463768,23.5729827881 --13.7884778976,-0.620645105839,23.5907917023 --13.8804359436,-0.621630251408,23.5784091949 --13.959397316,-0.621617078781,23.5430240631 --14.002368927,-0.620608270168,23.4446277618 --14.1023244858,-0.621592760086,23.4452476501 --14.2562646866,-0.623570859432,23.5318717957 --14.3082342148,-0.623561263084,23.4504833221 --14.3852043152,-0.624550461769,23.4942970276 --14.4901590347,-0.625534713268,23.498916626 --14.6031112671,-0.626518189907,23.515537262 --14.6720762253,-0.626506924629,23.4621524811 --14.7600345612,-0.626493513584,23.4377689362 --14.8649902344,-0.627478182316,23.4393863678 --14.9859409332,-0.628461241722,23.467010498 --15.0659103394,-0.629450500011,23.5108261108 --15.1668672562,-0.630436003208,23.5044441223 --15.2428302765,-0.630424499512,23.460062027 --15.3677806854,-0.632407426834,23.4896850586 --15.4517412186,-0.632395207882,23.4563026428 --15.497713089,-0.631387412548,23.3659152985 --12.8954343796,-0.559679687023,19.3562030792 --12.9723968506,-0.559667229652,19.3388137817 --12.9783802032,-0.557662725449,19.2154140472 --13.0893335342,-0.55964666605,19.2490367889 --14.1510219574,-0.586525261402,20.6788482666 --13.2002706528,-0.559627115726,19.1502532959 --14.4779005051,-0.59148311615,20.8731117249 --16.2763938904,-0.6382843256,23.4022769928 --13.4671583176,-0.562588989735,19.2123069763 --13.5201272964,-0.561579883099,19.1589164734 --14.3678789139,-0.582484841347,20.2316913605 --14.2468967438,-0.577494859695,19.9252643585 --14.1818990707,-0.57449889183,19.7018527985 --11.9604949951,-0.515732824802,16.4859790802 --12.0394649506,-0.516722381115,16.5407962799 --12.0724401474,-0.515714883804,16.4764022827 --12.0724239349,-0.514710962772,16.3669986725 --12.0924034119,-0.513704836369,16.2845973969 --12.1003847122,-0.512700080872,16.1881980896 --12.1483564377,-0.512691140175,16.1448020935 --12.2793045044,-0.514673769474,16.213432312 --12.3232851028,-0.515667319298,16.2182407379 --11.852396965,-0.501711845398,15.490732193 --11.9103660583,-0.502701938152,15.4653434753 --8.89616298676,-0.426003783941,11.4442462921 --8.90714263916,-0.425997257233,11.3838453293 --8.95811271667,-0.425986677408,11.3744506836 --8.98009872437,-0.425981789827,11.3652524948 --12.236207962,-0.504651904106,15.4306077957 --12.4071464539,-0.507631182671,15.5452404022 --12.5700874329,-0.510611534119,15.6498813629 --12.5460786819,-0.50861042738,15.5174694061 --12.5770559311,-0.508603930473,15.4560775757 --12.7299995422,-0.510585546494,15.5437078476 --12.7589845657,-0.511581063271,15.5295162201 --12.8169536591,-0.511572122574,15.4991254807 --12.8339347839,-0.510567247868,15.4207315445 --12.8869056702,-0.510558962822,15.3843383789 --13.0018606186,-0.512544810772,15.4229650497 --12.5879545212,-0.501580774784,14.8324670792 --13.0558166504,-0.511533558369,15.2901792526 --13.1647815704,-0.513521850109,15.3679990768 --13.1657657623,-0.512518763542,15.2716026306 --13.223736763,-0.512510418892,15.2402114868 --13.144742012,-0.509514808655,15.0517921448 --13.3796663284,-0.513490378857,15.2254495621 --13.6885719299,-0.519459486008,15.4801216125 --13.7645378113,-0.520449995995,15.4667367935 --13.4906015396,-0.513473451138,15.1084718704 --13.5225791931,-0.513467848301,15.0470752716 --13.8094911575,-0.51843971014,15.2727518082 --13.9514408112,-0.520424664021,15.3323831558 --14.0323925018,-0.520412802696,15.2255992889 --15.804930687,-0.559257268906,17.1118412018 --12.0228862762,-0.473583251238,12.9024925232 --12.0258712769,-0.472579628229,12.8230886459 --12.0248565674,-0.471576422453,12.741692543 --12.0198431015,-0.4705735147,12.6552886963 --12.0428218842,-0.470568239689,12.5978860855 --12.1217880249,-0.471558362246,12.6015081406 --12.1507730484,-0.47155430913,12.5913124084 --12.1497592926,-0.470551252365,12.5109138489 --12.141746521,-0.469548732042,12.4235115051 --12.1437320709,-0.468545377254,12.3461065292 --12.1357192993,-0.467542856932,12.2586975098 --12.1487007141,-0.467538684607,12.1943006516 --12.1326904297,-0.466536849737,12.0998907089 --12.1216869354,-0.465536206961,12.0506877899 --12.1046762466,-0.464534461498,11.9572820663 --12.1116600037,-0.46353083849,11.8878803253 --12.1076469421,-0.462528079748,11.8084774017 --12.1136312485,-0.461524575949,11.7390756607 --12.1316137314,-0.461520195007,11.6826820374 --12.151594162,-0.461515665054,11.6272830963 --12.1265935898,-0.460516065359,11.566075325 --12.1245794296,-0.459513276815,11.4906730652 --12.1235656738,-0.458510398865,11.416270256 --12.1245517731,-0.457507401705,11.3448696136 --12.1195383072,-0.457504838705,11.2674636841 --12.1115264893,-0.456502556801,11.1880598068 --12.1105127335,-0.455499738455,11.115655899 --12.1015071869,-0.454498946667,11.0714511871 --12.0924959183,-0.453496754169,10.9930496216 --12.0944814682,-0.453493773937,10.9246482849 --12.0984678268,-0.452490657568,10.8582458496 --12.0924549103,-0.451488286257,10.7828397751 --12.0894412994,-0.451485723257,10.7114391327 --12.0764379501,-0.45048519969,10.6652326584 --12.007440567,-0.448487132788,10.5348062515 --12.0164241791,-0.447483748198,10.4754076004 --12.0044136047,-0.446481794119,10.3980054855 --12.024394989,-0.446477681398,10.3476028442 --12.0523748398,-0.446473151445,10.3062152863 --12.0653591156,-0.446469604969,10.2508153915 --12.054353714,-0.445468991995,10.2076072693 --12.0443439484,-0.444466978312,10.1332025528 --12.0443305969,-0.444464355707,10.0678005219 --12.0423164368,-0.443461865187,10.0014009476 --12.0323057175,-0.442459881306,9.92799377441 --12.030292511,-0.442457407713,9.86158943176 --12.0322790146,-0.441454708576,9.79918766022 --12.0132770538,-0.440454632044,9.7519826889 --12.012263298,-0.440452128649,9.68758010864 --12.0102510452,-0.439449727535,9.6231803894 --12.0032396317,-0.438447624445,9.55477523804 --12.009223938,-0.438444763422,9.49637031555 --12.0012130737,-0.437442779541,9.42796707153 --11.9972000122,-0.436440497637,9.36256122589 --11.9711999893,-0.436440765858,9.3113527298 --11.9721870422,-0.435438275337,9.25095081329 --11.9271841049,-0.434438318014,9.15453243256 --11.9261713028,-0.433436006308,9.0941362381 --11.9141607285,-0.432434171438,9.02372169495 --11.9201459885,-0.432431489229,8.96932697296 --11.9701223373,-0.432426422834,8.94693470001 --12.0700941086,-0.434419959784,8.99276447296 --11.942109108,-0.431424438953,8.83732700348 --5.50850391388,-0.308750212193,3.96774291992 --5.50848674774,-0.308743983507,3.94134640694 --11.9320602417,-0.429415792227,8.59571266174 --11.9310464859,-0.428413569927,8.53630447388 --11.9200429916,-0.428413003683,8.50010490417 --11.9130325317,-0.427411109209,8.43769931793 --11.9100198746,-0.426409095526,8.37930202484 --11.9060087204,-0.426407068968,8.31889343262 --11.9049959183,-0.425404936075,8.26148891449 --11.9029836655,-0.425402909517,8.20408821106 --11.8849811554,-0.424402624369,8.1628780365 --11.8849687576,-0.424400508404,8.10747814178 --11.8829574585,-0.423398464918,8.05007171631 --11.8839435577,-0.423396348953,7.99567174911 --11.8809328079,-0.422394424677,7.93826627731 --11.8709220886,-0.422392785549,7.87686252594 --11.8779087067,-0.421390503645,7.82746601105 --11.8159151077,-0.420392006636,7.75824069977 --11.8309001923,-0.420389354229,7.71384048462 --11.8148908615,-0.419387966394,7.64943265915 --11.825876236,-0.419385552406,7.60303354263 --11.8078680038,-0.418384283781,7.5386300087 --11.821852684,-0.418381780386,7.49422979355 --11.8028450012,-0.417380571365,7.42881917953 --11.810836792,-0.417379319668,7.40762042999 --11.7958278656,-0.416377902031,7.34521055222 --11.8088130951,-0.416375607252,7.30181837082 --11.7918043137,-0.415374308825,7.23840522766 --11.7997903824,-0.41537219286,7.19200944901 --11.7817831039,-0.414370954037,7.12859582901 --11.6997861862,-0.412371784449,7.02716779709 --11.6517906189,-0.411372363567,6.97194719315 --11.661775589,-0.411370187998,6.92754888535 --11.6537656784,-0.411368578672,6.87214231491 --11.65275383,-0.410366803408,6.82174253464 --11.6607408524,-0.410364747047,6.77634143829 --11.7207164764,-0.411361277103,6.76196050644 --11.7407016754,-0.411358982325,6.72356367111 --11.7506942749,-0.411357909441,6.7053732872 --11.7516822815,-0.410356223583,6.65596914291 --11.7386732101,-0.410354912281,6.59855985641 --11.754658699,-0.410352885723,6.55816173553 --11.7406492233,-0.409351617098,6.50075292587 --11.7506361008,-0.409349799156,6.45735406876 --11.7246351242,-0.408349633217,6.41814184189 --11.7346220016,-0.408347845078,6.37474155426 --11.7796020508,-0.408345341682,6.35135746002 --11.8525781631,-0.409342318773,6.34298276901 --11.9115543365,-0.410339713097,6.32660388947 --11.9985284805,-0.411336660385,6.32422780991 --12.0575065613,-0.412334293127,6.30684709549 --12.2094621658,-0.414329826832,6.31430196762 --12.2154502869,-0.414328694344,6.26790142059 --12.2174396515,-0.413327634335,6.21949911118 --12.3014135361,-0.414325356483,6.21412944794 --12.3104009628,-0.414324343204,6.16973352432 --12.2943935394,-0.414323687553,6.1123251915 --12.3023872375,-0.414323151112,6.09212970734 --12.2923784256,-0.413322418928,6.03772068024 --12.3003673553,-0.413321524858,5.99332475662 --12.2913579941,-0.41232085228,5.93991661072 --12.2923469543,-0.412320077419,5.89151144028 --12.2843379974,-0.412319391966,5.83910512924 --12.2723302841,-0.411318778992,5.78570318222 --12.2713251114,-0.411318421364,5.76049566269 --12.2713155746,-0.41131773591,5.71309804916 --12.2713050842,-0.410317093134,5.66569852829 --12.2802934647,-0.410316377878,5.62230014801 --12.2912807465,-0.410315692425,5.57990121841 --12.2732744217,-0.409315168858,5.52348709106 --12.2602672577,-0.409314662218,5.47108650208 --12.2652606964,-0.409314364195,5.44988775253 --12.2552528381,-0.40831387043,5.39848279953 --12.2622423172,-0.408313333988,5.3540763855 --12.2712306976,-0.408312827349,5.31168031693 --12.2542228699,-0.408312380314,5.25726985931 --12.2602128983,-0.407311946154,5.21387290955 --12.2622032166,-0.407311558723,5.1684718132 --12.2392015457,-0.407311320305,5.13526058197 --12.2431917191,-0.406310915947,5.09085893631 --12.2461805344,-0.406310558319,5.04646062851 --12.2441720963,-0.406310230494,5.00006008148 --12.236164093,-0.406309872866,4.95065116882 --12.2301549911,-0.405309587717,4.90325260162 --11.6132364273,-0.395305365324,4.58240556717 --11.6192245483,-0.394304692745,4.54099655151 --11.6022186279,-0.39430385828,4.49159002304 --11.594209671,-0.394303113222,4.4461889267 --11.6141958237,-0.394302636385,4.4107875824 --11.6031885147,-0.393301934004,4.36438465118 --11.5961790085,-0.39330124855,4.31897592545 --11.5941753387,-0.393300920725,4.29677152634 --11.5821666718,-0.392300188541,4.25036764145 --11.5881557465,-0.392299711704,4.21097135544 --11.5881462097,-0.392299175262,4.16856431961 --11.5811376572,-0.392298579216,4.12415981293 --11.5831289291,-0.391298145056,4.08275413513 --11.5771245956,-0.39129781723,4.05954885483 --11.5791149139,-0.391297399998,4.01915216446 --11.5751056671,-0.391296923161,3.97574329376 --11.575097084,-0.391296505928,3.93434095383 --11.5610895157,-0.390295863152,3.88894057274 --11.5620794296,-0.390295535326,3.84753298759 --11.5750694275,-0.390295475721,3.81113791466 --11.5550670624,-0.390294909477,3.78393030167 --11.5500593185,-0.389294505119,3.74051785469 --11.5600481033,-0.389294475317,3.70311999321 --11.5520401001,-0.389294058084,3.65971469879 --11.5290336609,-0.388293266296,3.61231064796 --11.4210386276,-0.386290282011,3.53585505486 --11.4160308838,-0.386289864779,3.49445295334 --11.4020280838,-0.386289387941,3.47024846077 --11.4100179672,-0.386289358139,3.43284869194 --11.3980112076,-0.38528880477,3.38944244385 --11.408000946,-0.385288894176,3.35203576088 --11.3919935226,-0.385288238525,3.30762791634 --11.3949842453,-0.385288178921,3.26922893524 --11.397974968,-0.385288178921,3.23082900047 --11.385972023,-0.384287744761,3.20762324333 --11.3789644241,-0.384287416935,3.16621732712 --11.3899536133,-0.384287744761,3.12981557846 --11.376947403,-0.384287267923,3.08741283417 --11.3779382706,-0.384287267923,3.04800415039 --11.3759298325,-0.384287208319,3.00860238075 --11.371922493,-0.383287101984,2.96819400787 --11.3619184494,-0.383286744356,2.94598841667 --11.3679103851,-0.383287042379,2.90858578682 --11.365901947,-0.383287072182,2.8701915741 --11.367893219,-0.383287280798,2.83178687096 --11.3668851852,-0.383287400007,2.7923784256 --11.356877327,-0.382287174463,2.75197887421 --11.3688726425,-0.382287800312,2.73578214645 --11.362865448,-0.38228777051,2.69537258148 --11.319861412,-0.381286084652,2.64594817162 --11.3258533478,-0.381286621094,2.60955119133 --11.3508424759,-0.382288068533,2.57715606689 --11.3898296356,-0.382290273905,2.54877495766 --11.4158191681,-0.382291913033,2.51638031006 --11.4658069611,-0.383294820786,2.49000191689 --11.481801033,-0.383295863867,2.47481107712 --11.3298091888,-0.381288737059,2.40133786201 --11.4917850494,-0.383297532797,2.40000724792 --11.4447822571,-0.382295697927,2.35158753395 --11.6347503662,-0.385307282209,2.3158621788 --11.6817388535,-0.385310739279,2.28748369217 --11.7007331848,-0.38631221652,2.27229332924 --11.7357225418,-0.38631516695,2.24090790749 --11.7687129974,-0.387318104506,2.20851802826 --11.7927045822,-0.387320578098,2.17513394356 --11.8206949234,-0.387323379517,2.14174461365 --11.8696842194,-0.388327509165,2.11236548424 --11.8986787796,-0.388329923153,2.09817528725 --11.919670105,-0.388332545757,2.06278038025 --11.9596605301,-0.389336436987,2.03140044212 --12.0026502609,-0.389340609312,2.00001811981 --12.0206422806,-0.390343278646,1.96362185478 --12.0706329346,-0.390348136425,1.93324458599 --12.1066236496,-0.391352206469,1.8998581171 --12.1336193085,-0.391354858875,1.88466918468 --12.1756095886,-0.392359465361,1.8522888422 --12.2016019821,-0.392363071442,1.81689941883 --12.2475938797,-0.393368214369,1.78451859951 --12.2735862732,-0.393371999264,1.74913263321 --12.3205776215,-0.393377453089,1.71574497223 --12.34856987,-0.394381582737,1.68036055565 --12.3865652084,-0.394385427237,1.66617882252 --12.4225568771,-0.395390361547,1.63078916073 --12.5525436401,-0.397402465343,1.60945034027 --12.5795373917,-0.397406965494,1.57306611538 --12.6425285339,-0.3984144032,1.5406908989 --12.6915206909,-0.39942085743,1.50631177425 --12.7265148163,-0.399426281452,1.47093689442 --12.7575101852,-0.400430202484,1.45374453068 --12.8055038452,-0.400436878204,1.4193726778 --12.8384971619,-0.401442497969,1.38198566437 --12.8874902725,-0.401449531317,1.34660828114 --12.9174852371,-0.402455151081,1.30821764469 --12.9584789276,-0.402461737394,1.27184081078 --12.9984731674,-0.403468459845,1.23445749283 --13.0304708481,-0.403472840786,1.217274189 --13.0784645081,-0.404480457306,1.17989015579 --13.1104602814,-0.404486715794,1.14150738716 --13.1604537964,-0.405494749546,1.10412752628 --13.1964492798,-0.406501591206,1.06574714184 --13.2384443283,-0.406509131193,1.02736616135 --13.2674407959,-0.406515568495,0.987982988358 --13.3094377518,-0.407521367073,0.970806002617 --13.3564329147,-0.408529698849,0.932429790497 --13.3924293518,-0.408537179232,0.892040371895 --13.4314260483,-0.409544974566,0.852661848068 --13.48042202,-0.409553945065,0.813282966614 --13.5234184265,-0.410562396049,0.773908376694 --13.5704145432,-0.411571443081,0.733526229858 --13.6114120483,-0.411577701569,0.715352118015 --13.6564092636,-0.4125867486,0.674974739552 --13.7044067383,-0.413596332073,0.633590400219 --13.7574033737,-0.413606494665,0.593217611313 --13.7894010544,-0.41461455822,0.55183917284 --13.8393993378,-0.415624707937,0.51046282053 --12.3754339218,-0.39247405529,0.393324941397 --12.3124341965,-0.391469091177,0.370087236166 --12.3884296417,-0.392480641603,0.334728300571 --12.5374240875,-0.395500421524,0.301401019096 --12.3614244461,-0.392484724522,0.254912436008 --12.2974224091,-0.391481161118,0.213480040431 --12.4444179535,-0.393501222134,0.179153427482 --12.1784210205,-0.389473080635,0.15081346035 --12.0494203568,-0.387461870909,0.108343958855 --12.3204135895,-0.391496390104,0.0770851373672 --12.191411972,-0.389485180378,0.0346116647124 --12.2004098892,-0.38948982954,-0.00378344999626 --12.0524082184,-0.387475967407,-0.0452663041651 --12.1494045258,-0.389491051435,-0.0816094726324 --12.3294029236,-0.391514599323,-0.0997245684266 --12.1174020767,-0.388492763042,-0.140233770013 --12.2173986435,-0.39050874114,-0.178586155176 --12.4753961563,-0.394544482231,-0.216850608587 --14.6893949509,-0.427824378014,-0.26009657979 --12.2933931351,-0.391530007124,-0.294744223356 --12.1493902206,-0.38951587677,-0.33322763443 --12.1603889465,-0.389519244432,-0.352420479059 --12.152387619,-0.389522224665,-0.390824884176 --12.1633853912,-0.389527648687,-0.429216563702 --12.1483840942,-0.389529764652,-0.467626482248 --12.2143831253,-0.390542626381,-0.507996022701 --12.123380661,-0.388534754515,-0.544445514679 --12.0813779831,-0.388533294201,-0.581870138645 --12.4953832626,-0.394591331482,-0.613853573799 --12.355381012,-0.392576873302,-0.648323297501 --12.3343791962,-0.392578661442,-0.687744915485 --12.3483791351,-0.392585158348,-0.727134823799 --12.3653783798,-0.392592251301,-0.767530977726 --12.1633729935,-0.389568448067,-0.797034919262 --12.5793819427,-0.395632088184,-0.856213271618 --12.3083753586,-0.391595959663,-0.862560033798 --12.7053852081,-0.397657811642,-0.922743797302 --12.731385231,-0.39866694808,-0.965135037899 --15.774477005,-0.445117086172,-1.18789875507 --15.8634853363,-0.447139382362,-1.24425327778 --12.8293905258,-0.399697810411,-1.09328389168 --12.6683855057,-0.397679269314,-1.1227697134 --12.6573858261,-0.397680461407,-1.14298391342 --16.0865154266,-0.450205951929,-1.43752563 --16.1485233307,-0.451225042343,-1.49288451672 --16.1925315857,-0.452241837978,-1.5482609272 --16.2515411377,-0.453260958195,-1.60462474823 --16.2985515594,-0.454278558493,-1.66100001335 --16.3735618591,-0.455300629139,-1.71935343742 --16.4535694122,-0.456318646669,-1.75351405144 --16.5025806427,-0.457337081432,-1.81088578701 --16.5725917816,-0.458359003067,-1.8702429533 --16.6246032715,-0.459378361702,-1.92861235142 --16.7036151886,-0.46040225029,-1.98996555805 --16.751625061,-0.461421251297,-2.04833388329 --16.8146400452,-0.462442964315,-2.10869431496 --16.9036483765,-0.464463561773,-2.14584517479 --16.9546604156,-0.465483784676,-2.20621585846 --17.0156726837,-0.466505795717,-2.26757669449 --17.1126899719,-0.467534184456,-2.33391904831 --17.1537036896,-0.468553394079,-2.39429473877 --17.229719162,-0.46957886219,-2.45965194702 --17.3037281036,-0.470597863197,-2.49680829048 --17.3817462921,-0.472624093294,-2.56316280365 --17.4377613068,-0.473646640778,-2.62652587891 --15.2196073532,-0.439265877008,-2.37416315079 --15.2046146393,-0.43927308917,-2.42056465149 --15.1686191559,-0.438276797533,-2.46498703957 --15.0306158066,-0.436261832714,-2.49346256256 --14.9496126175,-0.435252070427,-2.5057079792 --15.0016241074,-0.436271548271,-2.56207633018 --15.0376348495,-0.437288254499,-2.61645460129 --15.0576438904,-0.437302201986,-2.66884422302 --15.0006465912,-0.436301767826,-2.7082734108 --15.0386581421,-0.437319248915,-2.76365184784 --14.2675952911,-0.425182908773,-2.68148875237 --14.1745901108,-0.424169838428,-2.68874073029 --14.2236013412,-0.425188690424,-2.7441163063 --14.04459095,-0.422163456678,-2.7586171627 --13.8595781326,-0.41913664341,-2.77112364769 --13.7685756683,-0.418127834797,-2.79957389832 --13.8515911102,-0.419153213501,-2.85992193222 --13.9136037827,-0.42017480731,-2.91728591919 --13.7915973663,-0.419159770012,-2.93975925446 --13.8716087341,-0.420180469751,-2.97791099548 --14.2396564484,-0.426264494658,-3.09709858894 --13.7066049576,-0.41816586256,-3.03681325912 --13.6196012497,-0.416157335043,-3.0642645359 --13.1915578842,-0.410078018904,-3.01991486549 --13.4665975571,-0.414143890142,-3.12114644051 --13.3445854187,-0.413123011589,-3.11741805077 --13.2435798645,-0.411110818386,-3.13987827301 --13.3065948486,-0.412133216858,-3.19824528694 --13.3436050415,-0.413150221109,-3.25062179565 --13.3556137085,-0.413162112236,-3.29801630974 --13.4826374054,-0.415199041367,-3.37234544754 --13.4946460724,-0.416211128235,-3.41973376274 --13.862698555,-0.422296285629,-3.52871370316 --13.0455961227,-0.409127026796,-3.38060259819 --13.1346158981,-0.411155879498,-3.44594979286 --12.9125919342,-0.407115727663,-3.43548130989 --12.9275999069,-0.408128231764,-3.48287415504 --12.9236068726,-0.408136487007,-3.52527546883 --12.9746208191,-0.409157454967,-3.58265161514 --13.0396347046,-0.410176873207,-3.62080836296 --12.8446121216,-0.407141685486,-3.61432743073 --12.8556222916,-0.407153517008,-3.66072058678 --13.066660881,-0.411212056875,-3.76099562645 --12.8626375198,-0.408173948526,-3.74951243401 --12.8976507187,-0.408191949129,-3.80390048027 --12.718629837,-0.406159222126,-3.79841017723 --12.614616394,-0.404139131308,-3.79066967964 --12.6686325073,-0.405161380768,-3.84903645515 --12.7926616669,-0.4072009027,-3.9283657074 --12.663646698,-0.406179368496,-3.93484306335 --13.0007123947,-0.41127127409,-4.07703781128 --13.1907539368,-0.414328217506,-4.17832422256 --13.2597761154,-0.416355967522,-4.24468326569 --13.1927680969,-0.415344655514,-4.24691963196 --13.1817760468,-0.415352672338,-4.28932714462 --13.056763649,-0.41333219409,-4.29680633545 --13.0187654495,-0.412333250046,-4.33022880554 --12.904753685,-0.411314994097,-4.33969926834 --12.914765358,-0.411328226328,-4.38809490204 --12.956782341,-0.412349671125,-4.44646644592 --12.9957942963,-0.413365155458,-4.48164129257 --12.7747621536,-0.409318774939,-4.45518064499 --13.2498655319,-0.417453676462,-4.65728759766 --13.2738809586,-0.418471485376,-4.71166992188 --13.2278823853,-0.417471021414,-4.74309968948 --13.1778831482,-0.4174695611,-4.77353715897 --13.0688724518,-0.415451914072,-4.78199911118 --13.0328702927,-0.415448158979,-4.79322576523 --13.0828924179,-0.416473120451,-4.856590271 --13.2169313431,-0.418521434069,-4.95090961456 --13.6130285263,-0.425642073154,-5.14006614685 --17.3478507996,-0.487682431936,-6.53312444687 --17.2858600616,-0.48668473959,-6.57356452942 --17.4219112396,-0.488741606474,-6.68487167358 --17.2788925171,-0.486711323261,-6.66315793991 --17.2269039154,-0.486716270447,-6.70658969879 --17.1559104919,-0.485715568066,-6.74203062057 --17.2289505005,-0.486755609512,-6.83137798309 --25.8999919891,-0.631255626678,-10.2183523178 --25.6859893799,-0.628228902817,-10.2298746109 --26.1051330566,-0.63538479805,-10.4870004654 --25.5680294037,-0.627246439457,-10.3235292435 --24.4478034973,-0.608954012394,-9.97362232208 --26.6333808899,-0.645628988743,-10.9366388321 --26.949508667,-0.651759266853,-11.1618270874 --26.6484851837,-0.647707462311,-11.1384038925 --25.7723121643,-0.633482456207,-10.8763408661 --27.9798965454,-0.671162486076,-11.8341407776 --27.9399414062,-0.670190513134,-11.9215536118 --25.8374500275,-0.635592341423,-11.1422691345 --22.1375312805,-0.574498951435,-9.67100524902 --22.0765533447,-0.573510229588,-9.72743415833 --21.8665370941,-0.570475518703,-9.71996116638 --21.8845806122,-0.571510851383,-9.80933952332 --25.160490036,-0.627547323704,-11.2814464569 --26.1968231201,-0.645908296108,-11.8321704865 --26.0418338776,-0.643897473812,-11.8616552353 --23.526227951,-0.602171480656,-10.9230461121 --26.9842605591,-0.661315500736,-12.5882148743 --16.6743412018,-0.486027210951,-7.95625925064 --16.6223392487,-0.486021131277,-7.96449232101 --16.5833530426,-0.485029727221,-8.00991249084 --16.5353679657,-0.485035479069,-8.05134010315 --16.4983825684,-0.485044807196,-8.09776115417 --16.4814033508,-0.485060930252,-8.15417289734 --16.4544219971,-0.485073387623,-8.20458221436 --16.4524497986,-0.485094577074,-8.26798152924 --21.3539791107,-0.569753706455,-10.6829719543 --21.2789974213,-0.569760084152,-10.7304153442 --25.1622619629,-0.637111961842,-12.7312650681 --24.9992637634,-0.635095834732,-12.7497634888 --22.9166526794,-0.599418699741,-11.8035173416 --23.0147323608,-0.601487994194,-11.9438428879 --26.7620048523,-0.667827486992,-13.9447698593 --23.6300067902,-0.613756477833,-12.3960237503 --24.2352581024,-0.625006079674,-12.8020133972 --23.2079696655,-0.607682108879,-12.3650789261 --22.43475914,-0.59444475174,-12.0539836884 --22.4928283691,-0.596500754356,-12.1743326187 --22.5448970795,-0.59855556488,-12.2936906815 --22.4409103394,-0.596554100513,-12.3291501999 --22.1358280182,-0.591461598873,-12.2105474472 --22.1578845978,-0.593505382538,-12.3129243851 --22.1939487457,-0.594554543495,-12.4232912064 --22.3770618439,-0.59865796566,-12.6145582199 --22.201051712,-0.595629930496,-12.6100702286 --25.9394664764,-0.66305911541,-14.7879581451 --21.8840370178,-0.591584861279,-12.616065979 --21.8770599365,-0.591600298882,-12.6572656631 --21.8170890808,-0.591614305973,-12.7146978378 --22.0302200317,-0.595731914043,-12.927945137 --21.8031864166,-0.592682540417,-12.8894891739 --22.4614887238,-0.604972779751,-13.3644380569 --22.4585437775,-0.606009960175,-13.45682621 --22.4776058197,-0.607056736946,-13.5642080307 --22.7007198334,-0.611163318157,-13.7442531586 --22.7818107605,-0.614234983921,-13.889588356 --23.1660194397,-0.621426701546,-14.2177171707 --23.4031734467,-0.626561760902,-14.4599428177 --24.104516983,-0.63988339901,-14.9878559113 --23.9715270996,-0.638874292374,-15.0113372803 --23.3653411865,-0.62867385149,-14.7411394119 --23.2183094025,-0.62663602829,-14.7014360428 --17.6190319061,-0.52440315485,-11.3106746674 --17.7371234894,-0.527481496334,-11.4619865417 --17.7911911011,-0.528534293175,-11.5743436813 --17.7101974487,-0.528531908989,-11.6017951965 --35.8850860596,-0.865114867687,-23.3366756439 --17.7653312683,-0.530633151531,-11.8357477188 --35.6102409363,-0.863183796406,-23.5588092804 --35.4402732849,-0.861185610294,-23.6073036194 --17.6064395905,-0.530693054199,-12.051440239 --17.3443641663,-0.526612281799,-11.9560165405 --17.1532974243,-0.523545622826,-11.8673496246 --15.606628418,-0.49490493536,-10.8988332748 --15.6026649475,-0.495931088924,-10.9682331085 --16.9623432159,-0.521556913853,-11.9746742249 --15.4486703873,-0.493919461966,-11.0071372986 --15.7908725739,-0.501099526882,-11.3172912598 --44.0004692078,-1.03872954845,-31.1539058685 --41.5023422241,-0.991660654545,-29.5018386841 --41.4184417725,-0.991716504097,-29.6382694244 --41.3945770264,-0.992799818516,-29.8176593781 --43.6438331604,-1.03791856766,-31.6274490356 --43.0747032166,-1.02875876427,-31.4252204895 --42.728679657,-1.02469944954,-31.3808326721 --42.7898635864,-1.02782726288,-31.6311588287 --42.3887367249,-1.0206912756,-31.4406280518 --17.6321983337,-0.543230593204,-13.3595552444 --41.6126403809,-1.00952672958,-31.2759170532 --41.5437583923,-1.01059317589,-31.4283370972 --41.5789299011,-1.01270925999,-31.6596832275 --41.1008300781,-1.00558078289,-31.5023956299 --41.0469551086,-1.00665438175,-31.6658058167 --41.3341827393,-1.0128428936,-31.9887886047 --41.0822067261,-1.00982165337,-32.0013389587 --40.7191619873,-1.00474572182,-31.9259681702 --40.5842437744,-1.00478065014,-32.0274391174 --16.3630046844,-0.5259578228,-13.1992311478 --40.4925041199,-1.00693750381,-32.3682518005 --16.3601055145,-0.527026712894,-13.365026474 --40.4817352295,-1.00908517838,-32.6718139648 --40.3638267517,-1.00912880898,-32.7862739563 --40.4190177917,-1.01225984097,-33.0406036377 --40.1370162964,-1.00922071934,-33.0221824646 --39.99609375,-1.00825226307,-33.1166534424 --40.0002593994,-1.01035892963,-33.3320236206 --40.0074272156,-1.01246762276,-33.5503921509 --39.9814910889,-1.01350653172,-33.6345977783 --39.9686470032,-1.0156058073,-33.837978363 --31.5847625732,-0.846324920654,-26.9824581146 --30.8104190826,-0.831999719143,-26.4954051971 --32.0733184814,-0.859749138355,-27.7418632507 --30.4154281616,-0.827952265739,-26.4924602509 --30.9969139099,-0.841344714165,-27.1634178162 --30.1834697723,-0.824949264526,-26.5422039032 --29.9874706268,-0.822924792767,-26.5387306213 --29.9265594482,-0.822972178459,-26.6511554718 --29.9006671906,-0.825039744377,-26.7965602875 --29.9007949829,-0.82612156868,-26.9649410248 --30.1030540466,-0.832315564156,-27.3151741028 --29.951084137,-0.831314861774,-27.3496704102 --29.5018539429,-0.822107195854,-27.0301952362 --29.3598918915,-0.82111042738,-27.070684433 --29.2449398041,-0.821128129959,-27.1341514587 --29.341135025,-0.824266016483,-27.3934669495 --29.2051734924,-0.823272109032,-27.4379463196 --28.9421272278,-0.820206344128,-27.365530014 --28.8741455078,-0.819208443165,-27.3857688904 --29.0534000397,-0.825396418571,-27.727022171 --28.9814815521,-0.825439989567,-27.8324604034 --29.1737518311,-0.831637859344,-28.189699173 --29.1408634186,-0.832705318928,-28.3341083527 --29.2730941772,-0.837870538235,-28.6383895874 --40.7477607727,-1.09396636486,-40.3487091064 --28.7559928894,-0.844370007515,-29.7602329254 --29.0643768311,-0.853656232357,-30.2643852234 --28.9674510956,-0.853689849377,-30.3528423309 --28.9677524567,-0.857880949974,-30.7336063385 --28.1196117401,-0.845672190189,-30.5036029816 --28.6011543274,-0.859082579613,-31.2136173248 --28.435174942,-0.858072400093,-31.2291278839 --36.1702346802,-1.04660582542,-40.5024909973 --36.0923843384,-1.04768526554,-40.6699256897 --35.1627998352,-1.02918756008,-39.881023407 --35.9536933899,-1.05085718632,-41.0267868042 --35.8037834167,-1.05088949203,-41.1162796021 --35.7689666748,-1.05300033092,-41.3356819153 --35.80210495,-1.05509090424,-41.5038452148 --35.731262207,-1.05617821217,-41.6842727661 --35.6714286804,-1.05827391148,-41.8786964417 --35.6266136169,-1.06038093567,-42.0921096802 --35.5007247925,-1.06043052673,-42.2095870972 --35.2407150269,-1.05738568306,-42.1701660156 --24.736371994,-0.806040942669,-29.9969902039 --24.4292430878,-0.799915492535,-29.8176212311 --24.338312149,-0.800945580006,-29.8970813751 --24.1592979431,-0.797910988331,-29.8686103821 --24.1174144745,-0.799977123737,-30.0080318451 --23.9674263,-0.797963559628,-30.0145397186 --23.9164543152,-0.797973692417,-30.0457725525 --23.5652713776,-0.791808843613,-29.7994403839 --23.3532218933,-0.788746416569,-29.7239971161 --23.3513755798,-0.790842175484,-29.9123878479 --23.2013835907,-0.789825439453,-29.9128952026 --24.4237651825,-0.82286041975,-31.6713104248 --24.155664444,-0.818758606911,-31.5299129486 --23.8785514832,-0.814647912979,-31.3735218048 --23.0517940521,-0.794057011604,-30.3993797302 --22.9308300018,-0.794062614441,-30.4368648529 --21.9489784241,-0.770390629768,-29.3400440216 --21.8510322571,-0.770409703255,-29.3995113373 --21.7791156769,-0.771449744701,-29.4939594269 --21.6281147003,-0.769427478313,-29.4844760895 --21.6992702484,-0.772533416748,-29.675611496 --21.6473751068,-0.773590683937,-29.7990436554 --21.5484294891,-0.77361035347,-29.8595161438 --21.3503761292,-0.770547926426,-29.7820663452 --21.2093830109,-0.76953202486,-29.7825717926 --21.7611579895,-0.787091135979,-30.7485141754 --19.2945785522,-0.723133742809,-27.4879112244 --19.1394786835,-0.720049977303,-27.3602352142 --19.0244979858,-0.719044923782,-27.3777198792 --18.3198471069,-0.701539218426,-26.553691864 --22.3756427765,-0.816094815731,-32.5587692261 --18.3351573944,-0.706732690334,-26.9304676056 --13.0781803131,-0.56327354908,-19.4531879425 --13.0102014542,-0.563277304173,-19.4826431274 --12.936164856,-0.562244415283,-19.4389038086 --13.8314428329,-0.591165006161,-21.0359630585 --21.4817962646,-0.809052348137,-32.6650390625 --12.7333335876,-0.563320994377,-19.6606731415 --12.6413259506,-0.562303423882,-19.6541519165 --18.047121048,-0.719280660152,-28.0710525513 --19.4030609131,-0.7626734972,-30.45952034 --18.1426467896,-0.728617370129,-28.702960968 --13.0144004822,-0.583021044731,-20.9920349121 --12.9704580307,-0.584050893784,-21.0654678345 --17.9610042572,-0.73280698061,-29.1124916077 --18.069316864,-0.739014685154,-29.4887943268 --18.0785064697,-0.741129934788,-29.7091808319 --15.5803546906,-0.668827652931,-25.8416728973 --15.4603443146,-0.667802989483,-25.8241691589 --15.3273172379,-0.666765928268,-25.7856750488 --15.2533693314,-0.666786134243,-25.8441352844 --15.1553125381,-0.664736509323,-25.7724189758 --15.1905136108,-0.668864309788,-26.0127811432 --15.2016859055,-0.670971155167,-26.2181720734 --25.9339351654,-1.00789391994,-44.7455062866 --15.2270393372,-0.67718988657,-26.6369438171 --26.1217823029,-1.0224339962,-45.7191200256 --26.0109176636,-1.02349746227,-45.8555984497 --17.3094673157,-0.749592483044,-30.7711677551 --17.190486908,-0.749585092068,-30.7836608887 --14.7801303864,-0.675175309181,-26.7211093903 --14.9425382614,-0.682447731495,-27.2073688507 --13.6998472214,-0.645229935646,-25.1648330688 --13.61287117,-0.645231127739,-25.1903018951 --16.6176128387,-0.746569216251,-30.8821239471 --16.5676345825,-0.746575474739,-30.9053649902 --16.5347862244,-0.748660564423,-31.0747871399 --16.5470085144,-0.751796126366,-31.3301734924 --13.1568851471,-0.641167640686,-25.1884899139 --12.6322145462,-0.626680731773,-24.3843421936 --12.5472345352,-0.626679241657,-24.4048118591 --12.8619012833,-0.639131307602,-25.1969413757 --12.2830438614,-0.621522843838,-24.1736412048 --12.2411327362,-0.6225695014,-24.2760753632 --12.5167474747,-0.633983790874,-25.0042381287 --12.4377813339,-0.633991599083,-25.0407047272 --12.773686409,-0.651589393616,-26.1052093506 --5.60559272766,-0.400174409151,-11.7989597321 --5.59160137177,-0.400178134441,-11.8151712418 --5.56462287903,-0.400188207626,-11.8526067734 --5.55266952515,-0.401215583086,-11.9190168381 --5.52368879318,-0.401223838329,-11.9534540176 --5.47667551041,-0.40120986104,-11.9499073029 --5.43066358566,-0.401196569204,-11.9473552704 --5.47277355194,-0.403270184994,-12.0825119019 --5.43577861786,-0.403268605471,-12.0999526978 --5.42583322525,-0.404301047325,-12.1753664017 --11.951048851,-0.651674151421,-26.4839267731 --11.1657657623,-0.624777913094,-24.9770202637 --12.2590179443,-0.669303059578,-27.6044521332 --11.0789632797,-0.62788194418,-25.2009010315 --12.0198640823,-0.665171563625,-27.4152641296 --11.8958263397,-0.664128780365,-27.3657741547 --14.7656564713,-0.780079841614,-34.141620636 --11.842130661,-0.668300807476,-27.7066192627 --14.7932395935,-0.789430141449,-34.7903900146 --11.7052783966,-0.670365571976,-27.8645401001 --11.5261268616,-0.666245162487,-27.6820983887 --12.5954236984,-0.710790514946,-30.3373413086 --12.4784202576,-0.710768461227,-30.323846817 --12.3363628387,-0.708709716797,-30.2473716736 --9.90947914124,-0.611400544643,-24.6069583893 --9.8084564209,-0.610369980335,-24.5774497986 --9.73749542236,-0.610381543636,-24.6199131012 --9.65852069855,-0.610383033752,-24.6453895569 --9.62955474854,-0.611398160458,-24.6826133728 --9.54155921936,-0.610386252403,-24.6850986481 --9.45055580139,-0.610369086266,-24.6785831451 --9.3525352478,-0.609339773655,-24.6510715485 --9.26854610443,-0.608332574368,-24.6615505219 --9.17152690887,-0.608304977417,-24.6370410919 --9.08452987671,-0.607291460037,-24.6365203857 --8.97437667847,-0.604181706905,-24.4598236084 --8.85329627991,-0.602113962173,-24.3663387299 --8.7472486496,-0.601067841053,-24.309835434 --8.67027282715,-0.601068794727,-24.3343105316 --8.59429550171,-0.600069344044,-24.3577785492 --7.72536039352,-0.563776731491,-22.1609859467 --7.5922203064,-0.560671448708,-22.0025119781 --7.5351729393,-0.559633731842,-21.9487667084 --7.43210554123,-0.557576239109,-21.8722686768 --7.33705377579,-0.556529819965,-21.8147563934 --7.2811050415,-0.556550323963,-21.8722133636 --6.47217416763,-0.520272314548,-19.6973743439 --6.44327640533,-0.521327853203,-19.8148078918 --6.94671344757,-0.548262298107,-21.4325351715 --6.8827381134,-0.54826593399,-21.4609985352 --6.812748909,-0.548260211945,-21.4734725952 --6.75478982925,-0.548274338245,-21.5199279785 --6.20645570755,-0.523393988609,-20.0268497467 --6.12240934372,-0.522352337837,-19.9773368835 --6.05841827393,-0.52234685421,-19.9898033142 --5.98840904236,-0.522329747677,-19.9822750092 --5.96844625473,-0.522348046303,-20.0244903564 --6.16322231293,-0.536838591099,-20.8917102814 --6.07517004013,-0.534792304039,-20.8342018127 --5.90808343887,-0.532712638378,-20.7411689758 --7.85637378693,-0.647747576237,-27.7217159271 --7.74818515778,-0.643617331982,-27.509021759 --5.79025602341,-0.535793662071,-20.936290741 --5.68514060974,-0.532707452774,-20.809797287 --5.63118982315,-0.5337266922,-20.8652534485 --5.59128856659,-0.534777641296,-20.9757003784 --5.57145214081,-0.537869930267,-21.1571216583 --5.54158830643,-0.539944589138,-21.3085536957 --5.53167581558,-0.540993750095,-21.4047679901 --6.13601779938,-0.583472371101,-23.9815864563 --6.03694915771,-0.581414222717,-23.9040851593 --6.12956190109,-0.591788709164,-24.5743961334 --6.06964254379,-0.59282463789,-24.659860611 --5.97860956192,-0.592788815498,-24.6213550568 --7.35303401947,-0.688204348087,-30.5524234772 --10.0041837692,-0.868608772755,-41.6450767517 --9.70759487152,-0.857209205627,-40.980758667 --7.08900690079,-0.686138033867,-30.4996852875 --5.63871097565,-0.592784821987,-24.7195014954 --5.76554059982,-0.607291221619,-25.6197795868 --4.90539646149,-0.551301240921,-22.1970272064 --4.84745359421,-0.552324175835,-22.2594890594 --4.84459400177,-0.554405272007,-22.4116973877 --4.7916765213,-0.555443644524,-22.5011539459 --5.32929086685,-0.601063668728,-25.3320217133 --4.59545612335,-0.551279187202,-22.2621555328 --4.69923591614,-0.564751565456,-23.1044597626 --4.69756174088,-0.569940268993,-23.4548606873 --4.35433959961,-0.548166275024,-22.1356143951 --5.0346455574,-0.605213403702,-25.699131012 --4.95365858078,-0.605205595493,-25.7096176147 --4.17231845856,-0.547119855881,-22.1128063202 --4.40781068802,-0.573029756546,-23.715970993 --4.28960227966,-0.568886399269,-23.4904937744 --4.23972940445,-0.570950806141,-23.6259479523 --3.75864434242,-0.534650862217,-21.3908443451 --3.73972249031,-0.536692678928,-21.4750652313 --3.65161561966,-0.534614145756,-21.3615589142 --3.59467363358,-0.534636795521,-21.4240188599 --3.99425530434,-0.579207837582,-24.180015564 --4.1445350647,-0.600977122784,-25.5422649384 --4.0464425087,-0.598904192448,-25.4397697449 --3.99662661552,-0.601000785828,-25.6322231293 --3.62109231949,-0.575040817261,-23.9972133636 --3.55113339424,-0.575050771236,-24.038690567 --3.47513842583,-0.575038790703,-24.042175293 --3.33572721481,-0.567773997784,-23.6047229767 --3.22146320343,-0.563599288464,-23.3242435455 --3.18647432327,-0.563598871231,-23.335483551 --3.0832734108,-0.560462534428,-23.1219959259 --3.18148040771,-0.580178022385,-24.3942947388 --3.0923948288,-0.578110933304,-24.3017940521 --3.01740336418,-0.57810074091,-24.3082714081 --2.95350074768,-0.580144166946,-24.4087429047 --1.83133101463,-0.443214386702,-15.8253774643 --1.80934631824,-0.443219125271,-15.8446016312 --1.76336228848,-0.444219917059,-15.8680524826 --2.63105487823,-0.571822702885,-23.9335002899 --2.56613826752,-0.572857558727,-24.0189685822 --2.49013280869,-0.572839081287,-24.0114536285 --2.42724514008,-0.574890911579,-24.1269226074 --2.35830712318,-0.574912428856,-24.1893997192 --2.31525635719,-0.574874579906,-24.1356468201 --2.26551795006,-0.579014718533,-24.4061050415 --2.19255542755,-0.579021155834,-24.4425868988 --2.3404083252,-0.625690162182,-27.4040203094 --2.26350927353,-0.626732051373,-27.5035057068 --2.20685529709,-0.632918655872,-27.8569660187 --2.17702150345,-0.635007679462,-28.0261993408 --2.10117912292,-0.638082265854,-28.1836853027 --2.00709867477,-0.636016130447,-28.0941867828 --1.90692985058,-0.63289809227,-27.9136981964 --2.61020708084,-0.817512094975,-39.5512924194 --2.49535870552,-0.819573581219,-39.6898155212 --2.37340569496,-0.819573581219,-39.7203483582 --2.36528468132,-0.83307492733,-40.6165504456 --2.23423242569,-0.832016050816,-40.544090271 --2.10520529747,-0.830971896648,-40.4976272583 --1.993496418,-0.836113750935,-40.7781448364 --1.88183999062,-0.841285407543,-41.1116638184 --1.90213322639,-0.894173979759,-44.4670219421 --1.76418030262,-0.894169807434,-44.4925689697 --1.6911008358,-0.892107725143,-44.399848938 --1.55516910553,-0.893116116524,-44.44739151 --1.41927492619,-0.894145846367,-44.5329360962 --1.28132081032,-0.895140886307,-44.5574798584 --1.14443683624,-0.896176040173,-44.6530303955 --1.00648915768,-0.896174371243,-44.6835784912 --0.933350026608,-0.8940782547,-44.5308570862 --0.794324398041,-0.893031775951,-44.4824066162 --0.656376302242,-0.894029915333,-44.5129585266 --0.520667135715,-0.898164927959,-44.7855033875 --0.383880227804,-0.901255190372,-44.9790496826 --0.243935987353,-0.901254713535,-45.0125999451 --0.129582330585,-1.02259624004,-52.7230529785 --0.0328212231398,-0.899140417576,-44.8624343872 -0.174390509725,-0.966162085533,-50.6927528381 -0.334374010563,-0.9662129879,-50.7060050964 -0.430727154016,-0.86803650856,-44.0002746582 -0.57400983572,-0.872912168503,-44.310546875 -0.714994490147,-0.872957468033,-44.3188247681 -0.854957580566,-0.873014807701,-44.3050994873 -1.0204975605,-0.941462159157,-48.9341773987 -1.03773212433,-0.855762541294,-43.093536377 -1.17991220951,-0.858696162701,-43.2998085022 -1.31689500809,-0.858741283417,-43.3050880432 -1.4425290823,-0.853982686996,-42.9543800354 -1.60316181183,-0.86366212368,-43.6236381531 -1.7462477684,-0.865649521351,-43.734916687 -1.74248313904,-0.838657855988,-41.9401130676 -1.87340939045,-0.838733375072,-41.8864021301 -2.18303656578,-0.893737673759,-45.6285362244 -2.06595778465,-0.817612707615,-40.4390335083 -2.19392561913,-0.817663609982,-40.426322937 -2.32189559937,-0.817713260651,-40.4156150818 -2.51897454262,-0.834146201611,-41.5468482971 -2.80442929268,-0.887241780758,-45.1178016663 -2.66719269753,-0.822630941868,-40.7723236084 -2.77282810211,-0.81786608696,-40.416633606 -2.89775562286,-0.81693905592,-40.3619270325 -3.0338280201,-0.818931758404,-40.4572105408 -3.15470504761,-0.818032264709,-40.3505134583 -3.20553469658,-0.815142691135,-40.1836700439 -3.33655023575,-0.816166520119,-40.219959259 -3.4503633976,-0.813301742077,-40.0462646484 -3.57733201981,-0.813351392746,-40.0335578918 -3.70025992393,-0.813423037529,-39.9788551331 -3.85147070885,-0.816340148449,-40.2181358337 -3.99257516861,-0.819315195084,-40.3474121094 -4.05757045746,-0.819334030151,-40.3525619507 -4.18958091736,-0.819360613823,-40.383846283 -4.32763004303,-0.821366369724,-40.4561386108 -4.45761394501,-0.821407735348,-40.4594306946 -4.5865855217,-0.821455359459,-40.4507255554 -4.84765720367,-0.838906049728,-41.5949020386 -4.80723381042,-0.81671077013,-40.1223487854 -4.85811662674,-0.815790176392,-40.0095062256 -4.96391916275,-0.812929153442,-39.8218231201 -5.10701322556,-0.814909934998,-39.9411048889 -5.22188901901,-0.814008951187,-39.8304138184 -5.51303243637,-0.832425057888,-41.0565681458 -5.62788963318,-0.830534636974,-40.9268760681 -5.71355676651,-0.825745761395,-40.5962104797 -5.74028015137,-0.821910381317,-40.3143959045 -5.72430086136,-0.807466626167,-39.2988243103 -5.84524106979,-0.806529819965,-39.2551269531 -5.92996025085,-0.802711009979,-38.9764633179 -5.99959468842,-0.797936677933,-38.6078147888 -6.1235666275,-0.797982275486,-38.597114563 -6.23848628998,-0.797055721283,-38.5304298401 -6.30147695541,-0.798075795174,-38.5305786133 -6.50088214874,-0.804891645908,-38.9808158875 -6.59568214417,-0.802028357983,-38.7871437073 -6.70456933975,-0.801118850708,-38.685459137 -6.85668992996,-0.804085731506,-38.8337364197 -7.03494119644,-0.807984054089,-39.1219940186 -7.21719884872,-0.812879264355,-39.4182472229 -7.28923082352,-0.813877880573,-39.4623908997 -7.43328428268,-0.81588113308,-39.5396766663 -7.56025218964,-0.815929353237,-39.5249786377 -7.68319988251,-0.815987706184,-39.4892845154 -7.80815696716,-0.816041111946,-39.4635925293 -7.91402673721,-0.814140379429,-39.3429107666 -7.93782567978,-0.811260819435,-39.1360969543 -8.0497303009,-0.810341000557,-39.0534172058 -8.16264152527,-0.809418082237,-38.9767303467 -8.3086977005,-0.811419785023,-39.05701828 -8.44069099426,-0.812453627586,-39.0703201294 -8.63896179199,-0.817344546318,-39.3835601807 -8.7448387146,-0.816438674927,-39.2708854675 -8.80480957031,-0.815469682217,-39.2480354309 -6.15744638443,-0.630355596542,-26.9158401489 -6.11454916,-0.615859687328,-25.9517173767 -6.19552087784,-0.615894675255,-25.9270610809 -6.27348041534,-0.615936219692,-25.8884086609 -6.34943246841,-0.614981412888,-25.841758728 -6.3793797493,-0.615018606186,-25.786939621 -6.46035003662,-0.614054381847,-25.7602882385 -6.56139755249,-0.616050899029,-25.8176136017 -6.79792690277,-0.624802708626,-26.4038219452 -6.87086296082,-0.623856008053,-26.3401737213 -6.94982194901,-0.62389755249,-26.3015213013 -7.01473140717,-0.622964441776,-26.2078819275 -7.05571699142,-0.622982144356,-26.1950531006 -7.12263536453,-0.622044086456,-26.1114139557 -7.20962190628,-0.622071683407,-26.1027565002 -7.34075164795,-0.625027477741,-26.2520618439 -7.47288513184,-0.62798088789,-26.4063606262 -7.60601520538,-0.630936801434,-26.5566616058 -7.7391409874,-0.632895410061,-26.7019634247 -7.83228635788,-0.635833084583,-26.8670883179 -7.96941947937,-0.638788104057,-27.0213871002 -8.10855007172,-0.64174425602,-27.1746864319 -8.25169181824,-0.64469575882,-27.3389816284 -8.39382648468,-0.647650182247,-27.4972743988 -8.53696155548,-0.65060544014,-27.6545677185 -8.64112091064,-0.653537452221,-27.836687088 -8.78825855255,-0.656491279602,-27.9989795685 -8.93639564514,-0.659445941448,-28.1602687836 -9.08954429626,-0.662395179272,-28.3345527649 -9.24569511414,-0.665343761444,-28.5118370056 -9.39983558655,-0.668296992779,-28.6791229248 -9.56299781799,-0.672240197659,-28.8704013824 -9.67716503143,-0.675170063972,-29.0625133514 -13.4896945953,-0.84456628561,-39.8180236816 -13.5945835114,-0.843652069569,-39.7133560181 -13.729549408,-0.843700349331,-39.6956634521 -13.8685264587,-0.844742298126,-39.6919670105 -15.1503915787,-0.896385490894,-42.9562797546 -15.3476867676,-0.902259647846,-43.302318573 -15.0064315796,-0.880900204182,-41.905040741 -21.8649120331,-1.17698645592,-60.629535675 -20.413816452,-1.10500574112,-56.0212211609 -22.0622634888,-1.1683934927,-59.9822273254 -19.205915451,-1.03796446323,-51.660118103 -19.4129333496,-1.03999638557,-51.7163696289 -19.5319786072,-1.0419946909,-51.7864837646 -19.7359867096,-1.0440325737,-51.8297424316 -20.316860199,-1.06165707111,-52.8636703491 -20.3093757629,-1.0539290905,-52.3461074829 -21.5827732086,-1.09983217716,-55.1304473877 -20.7925376892,-1.0599347353,-52.6055526733 -21.0827236176,-1.06588983536,-52.8527374268 -21.7870349884,-1.09029018879,-54.3803520203 -22.1182899475,-1.09721410275,-54.7094993591 -24.6021499634,-1.18797075748,-60.3448104858 -21.4509506226,-1.05739879608,-52.0929298401 -21.1809482574,-1.04091024399,-50.9715957642 -21.3388519287,-1.03999578953,-50.8958930969 -21.0446243286,-1.01962983608,-49.5257873535 -21.6233940125,-1.03631079197,-50.4517326355 -22.3815097809,-1.05883264542,-51.7805175781 -22.4502296448,-1.05500400066,-51.4908905029 -22.5800743103,-1.05411744118,-51.3452148438 -22.5926895142,-1.04833602905,-50.9336395264 -22.5774593353,-1.04546260834,-50.6828689575 -22.6892757416,-1.04358744621,-50.5042037964 -23.1307201385,-1.05442392826,-51.0582695007 -23.3928203583,-1.05741989613,-51.2084770203 -23.4805870056,-1.05556726456,-50.9728393555 -23.6254653931,-1.05466389656,-50.8651504517 -23.9556808472,-1.06060707569,-51.1533088684 -23.8132286072,-1.05283355713,-50.6396446228 -23.9430770874,-1.05194270611,-50.4989738464 -18.2361946106,-0.84394800663,-37.7496261597 -18.3541259766,-0.844009578228,-37.6889572144 -18.4830780029,-0.845061719418,-37.6522789001 -18.5929965973,-0.844129562378,-37.5746192932 -18.6359329224,-0.844172537327,-37.5117988586 -18.7749023438,-0.845216751099,-37.4951095581 -19.044090271,-0.850164055824,-37.7363166809 -26.1366882324,-1.08002150059,-51.5218467712 -26.3626937866,-1.08306121826,-51.5650939941 -26.6057243347,-1.08508944511,-51.6393280029 -26.854763031,-1.08811569214,-51.7205657959 -27.0198478699,-1.09109914303,-51.8406448364 -27.2558612823,-1.09313595295,-51.8938865662 -27.496881485,-1.09616994858,-51.9551239014 -27.7459125519,-1.09919881821,-52.0303573608 -27.9999504089,-1.1012263298,-52.1105880737 -28.2629966736,-1.10524857044,-52.2058067322 -28.447101593,-1.10822463036,-52.3498764038 -28.7131500244,-1.11124753952,-52.445098877 -28.9882087708,-1.115265131,-52.5553092957 -29.279291153,-1.11827349663,-52.6915130615 -29.5433273315,-1.12230169773,-52.7747383118 -30.5855140686,-1.14883327484,-54.2453231812 -30.7994632721,-1.14990079403,-54.2245903015 -30.9585151672,-1.15190136433,-54.3066825867 -38.118522644,-1.36264896393,-66.4612731934 -38.3504104614,-1.36375379562,-66.3795394897 -38.7585487366,-1.36975049973,-66.6036605835 -42.5970840454,-1.4026927948,-66.7634124756 -42.8069267273,-1.40281569958,-66.6277008057 -33.6952781677,-1.10728728771,-48.8934555054 -33.9582901001,-1.11032557487,-48.945690155 -34.0450973511,-1.10844540596,-48.7420654297 -23.56965065,-0.744754612446,-25.897808075 -40.9762229919,-1.13470768929,-45.12890625 -41.2321968079,-1.13676333427,-45.1251678467 -38.1381034851,-1.02253615856,-37.4551506042 -50.2708702087,-1.2787553072,-49.3204536438 -50.4127120972,-1.27785980701,-49.1488113403 -50.6586341858,-1.2799397707,-49.0800933838 -51.0106315613,-1.28399646282,-49.1122970581 -51.1354637146,-1.28410470486,-48.9226722717 -23.1324195862,-0.695426344872,-21.6740455627 -23.0573158264,-0.693470060825,-21.5333213806 -23.1883068085,-0.694496095181,-21.520658493 -23.4283695221,-0.69849973917,-21.6089191437 -23.0159893036,-0.688639104366,-21.0876579285 -22.9608535767,-0.685702681541,-20.9031333923 -22.8917102814,-0.683768451214,-20.7066192627 -22.9096240997,-0.682816565037,-20.590045929 -23.0576763153,-0.6848128438,-20.6591567993 -23.7240180969,-0.696734309196,-21.130109787 -23.9990978241,-0.701733529568,-21.2433452606 -16.0288524628,-0.539292991161,-13.9905633926 -16.0388011932,-0.538322389126,-13.9099826813 -16.0747642517,-0.538347184658,-13.8513908386 -15.6374588013,-0.52844274044,-13.4219255447 -15.4262723923,-0.523510217667,-13.151506424 -15.1760625839,-0.517583310604,-12.8501138687 -15.2390499115,-0.518600165844,-12.8214979172 -14.3184328079,-0.499786823988,-11.9495944977 -14.4314546585,-0.500792682171,-11.9689378738 -15.048781395,-0.512714803219,-12.4129238129 -14.9226799011,-0.509749054909,-12.2662305832 -8.17960643768,-0.375878959894,-6.53558444977 -8.19059753418,-0.375886887312,-6.50100374222 -8.21759605408,-0.3758918643,-6.4813952446 -8.26660919189,-0.375893622637,-6.47878074646 -8.28960609436,-0.376899540424,-6.45419025421 -8.3095998764,-0.375906020403,-6.42660713196 -8.33360671997,-0.376906782389,-6.42578935623 -8.35760402679,-0.37691244483,-6.40219497681 -8.38060092926,-0.376918256283,-6.37760305405 -8.40760040283,-0.376923531294,-6.35601043701 -8.4305973053,-0.376929283142,-6.33141803741 -8.46560096741,-0.376933217049,-6.31681108475 -8.48859786987,-0.376938700676,-6.29320812225 -8.49359226227,-0.376942723989,-6.27443027496 -8.52659511566,-0.376946955919,-6.25782728195 -8.55159378052,-0.377952247858,-6.23522758484 -8.57358932495,-0.377957999706,-6.20963668823 -8.60559177399,-0.377962350845,-6.1920337677 -8.64159679413,-0.377966225147,-6.17742729187 -8.64358997345,-0.377970218658,-6.15764045715 -8.67659187317,-0.377974569798,-6.14004182816 -8.69658756256,-0.377980351448,-6.11344575882 -8.72058486938,-0.377985775471,-6.08885669708 -8.7375793457,-0.377991974354,-6.05927085876 -8.77358436584,-0.377995729446,-6.04465913773 -8.79958248138,-0.379000753164,-6.02206134796 -8.82558822632,-0.37900197506,-6.01926136017 -8.84558391571,-0.379007577896,-5.99266386032 -8.86357879639,-0.379013448954,-5.96407318115 -8.89357948303,-0.379018098116,-5.94347858429 -8.92858314514,-0.379022151232,-5.9268746376 -8.93657207489,-0.379028946161,-5.89129114151 -8.96757411957,-0.379033356905,-5.87169122696 -8.99057865143,-0.380034893751,-5.86688709259 -9.01357555389,-0.380040168762,-5.84129619598 -9.03257083893,-0.380045831203,-5.81271076202 -9.07357597351,-0.380049437284,-5.79910802841 -9.09557342529,-0.380054593086,-5.77350950241 -9.11657047272,-0.380059868097,-5.74691486359 -9.12156009674,-0.380066543818,-5.70933532715 -9.13255786896,-0.380069077015,-5.69653606415 -9.21858406067,-0.381068915129,-5.71190071106 -9.25058460236,-0.381073445082,-5.69130706787 -13.7144727707,-0.460740029812,-8.46405792236 -13.5763864517,-0.457765519619,-8.31558513641 -13.4733285904,-0.455780446529,-8.22086811066 -13.452293396,-0.454796075821,-8.14930725098 -13.4872808456,-0.45580753684,-8.11271095276 -13.5072622299,-0.454820156097,-8.06612873077 -13.4111967087,-0.45284050703,-7.94862413406 -13.4021673203,-0.452854424715,-7.88605308533 -13.3361158371,-0.450872004032,-7.78852701187 -13.2850828171,-0.449881672859,-7.72977161407 -13.4831361771,-0.452882260084,-7.79206562042 -13.3420562744,-0.449903875589,-7.65058994293 -13.3530368805,-0.449915856123,-7.60100889206 -13.3790216446,-0.44992685318,-7.56041669846 -13.3880023956,-0.448938727379,-7.5098361969 -13.2779359818,-0.446957141161,-7.38934421539 -13.3319444656,-0.44796037674,-7.39252471924 -13.3299207687,-0.446972310543,-7.33694601059 -13.3048887253,-0.446985453367,-7.26739263535 -13.2738552094,-0.445998430252,-7.19583463669 -13.2798347473,-0.445009768009,-7.14426088333 -13.3388338089,-0.446018517017,-7.12265014648 -14.0020494461,-0.457001298666,-7.43463373184 -13.3508052826,-0.446035057306,-7.0472869873 -13.5418510437,-0.448038429022,-7.0975856781 -13.4688034058,-0.447052657604,-7.00306367874 -13.4837875366,-0.447063058615,-6.95747661591 -13.3307132721,-0.444079637527,-6.8210105896 -13.401717186,-0.444087594748,-6.80638217926 -13.3266811371,-0.443095505238,-6.73964881897 -13.2596378326,-0.441108137369,-6.65112304688 -13.2976303101,-0.442117094994,-6.61852359772 -13.3406248093,-0.442126005888,-6.58792448044 -13.4256334305,-0.443133682013,-6.57929229736 -13.5796632767,-0.445139765739,-6.60461997986 -13.6506662369,-0.446148216724,-6.58700227737 -13.4866037369,-0.443157166243,-6.47832155228 -13.5646095276,-0.4441652596,-6.46469736099 -13.743645668,-0.447171479464,-6.50001144409 -13.6245880127,-0.445183753967,-6.38851642609 -13.7085952759,-0.446191906929,-6.37688827515 -13.7906017303,-0.447200149298,-6.3642578125 -13.9796485901,-0.450202077627,-6.42835140228 -13.9736270905,-0.44921207428,-6.37178373337 -13.947599411,-0.448222160339,-6.30622720718 -13.855553627,-0.44723290205,-6.20971679688 -13.9525632858,-0.44824129343,-6.20208311081 -14.0635757446,-0.449249714613,-6.20043945312 -14.1875925064,-0.451258301735,-6.20379018784 -14.441655159,-0.455261349678,-6.29284095764 -14.4796466827,-0.455270826817,-6.25624036789 -14.4746255875,-0.455280572176,-6.19967269897 -14.4736051559,-0.455290168524,-6.14510154724 -14.7606658936,-0.459299325943,-6.21734905243 -15.1597528458,-0.465309113264,-6.33652591705 -15.3367795944,-0.468319565058,-6.35684347153 -15.2917566299,-0.467324584723,-6.30908632278 -15.3287467957,-0.467334866524,-6.268491745 -15.6538105011,-0.472346454859,-6.34971570969 -17.1841850281,-0.497365921736,-6.93518161774 -17.2251701355,-0.498378425837,-6.88958454132 -17.2861614227,-0.498391062021,-6.85197544098 -17.3201446533,-0.498403608799,-6.80238866806 -17.3581409454,-0.499409973621,-6.78657865524 -17.4081287384,-0.499422729015,-6.74298334122 -17.4651184082,-0.500435292721,-6.70337438583 -17.5001010895,-0.500447750092,-6.65378570557 -17.5670928955,-0.501460552216,-6.61717414856 -17.6070766449,-0.501473009586,-6.56958007812 -17.6440734863,-0.502479612827,-6.55177640915 -17.69506073,-0.502492189407,-6.50817584991 -17.7460479736,-0.503504753113,-6.46457386017 -17.7820320129,-0.50351703167,-6.41498184204 -17.8420219421,-0.503529965878,-6.37338113785 -17.8800048828,-0.504542350769,-6.32379102707 -17.9419956207,-0.504555165768,-6.28318405151 -17.972990036,-0.50556153059,-6.2633767128 -17.924955368,-0.50457149744,-6.18283653259 -18.6050777435,-0.514601409435,-6.36185646057 -18.650062561,-0.515614449978,-6.31226205826 -18.597026825,-0.513624548912,-6.22872400284 -18.6980228424,-0.51563924551,-6.19809865952 -18.7850151062,-0.51665353775,-6.1624789238 -18.8250102997,-0.516660571098,-6.14366912842 -18.6769580841,-0.514667034149,-6.02819108963 -18.7149410248,-0.514679431915,-5.97659635544 -19.0229759216,-0.519701778889,-6.01284790039 -18.9839439392,-0.518711686134,-5.93430376053 -18.8909015656,-0.516719222069,-5.83879137039 -18.9898986816,-0.517734110355,-5.80516624451 -19.0488967896,-0.518741965294,-5.79134702682 -19.0448722839,-0.51875269413,-5.72478103638 -19.1328639984,-0.519767224789,-5.68716001511 -18.9797897339,-0.516781926155,-5.50912046432 -18.9707660675,-0.515791833401,-5.44255256653 -18.9747543335,-0.515797257423,-5.41077136993 -19.0397434235,-0.516810417175,-5.36616182327 -19.0807285309,-0.516822576523,-5.31356954575 -19.138715744,-0.517835617065,-5.26497364044 -19.1847019196,-0.517848014832,-5.21337938309 -19.2516899109,-0.518861413002,-5.16777181625 -19.2916755676,-0.51887345314,-5.11418056488 -19.3556728363,-0.519881784916,-5.099360466 -19.3896560669,-0.520893454552,-5.04377269745 -19.4566440582,-0.520906925201,-4.99716472626 -19.5056304932,-0.521919488907,-4.94457292557 -19.564617157,-0.522932529449,-4.89497184753 -19.6176052094,-0.522945284843,-4.84337472916 -19.6695899963,-0.523957908154,-4.79177570343 -19.7165851593,-0.523965477943,-4.77096509933 -19.7785739899,-0.524978756905,-4.72136116028 -19.8335590363,-0.525991678238,-4.66876745224 -19.8795433044,-0.526003837585,-4.61516809464 -19.9335308075,-0.527016639709,-4.5625705719 -20.0015182495,-0.528030335903,-4.51296520233 -20.0535030365,-0.528043150902,-4.45837450027 -20.0994987488,-0.529050707817,-4.43656206131 -20.1604862213,-0.530063867569,-4.38495779037 -20.2164707184,-0.530076980591,-4.33036661148 -20.2754573822,-0.531090021133,-4.2777633667 -20.3384437561,-0.532103478909,-4.22516202927 -20.3854293823,-0.53211581707,-4.16857051849 -20.4414253235,-0.533124268055,-4.14775323868 -20.5074119568,-0.534137964249,-4.09514951706 -20.5543956757,-0.534150362015,-4.03755998611 -20.6123828888,-0.535163402557,-3.98295927048 -20.6783695221,-0.536177098751,-3.92935538292 -20.7333545685,-0.536190032959,-3.87276124954 -20.7913398743,-0.537203073502,-3.81716108322 -20.8503360748,-0.538212060928,-3.79434919357 -20.9103221893,-0.53922533989,-3.7387471199 -20.963306427,-0.539238095284,-3.68115115166 -21.031293869,-0.5402520895,-3.62555074692 -21.0922775269,-0.541265428066,-3.56895017624 -21.1572647095,-0.542279243469,-3.51234984398 -21.232252121,-0.543293714523,-3.45774030685 -21.2712459564,-0.543301224709,-3.42993855476 -21.3412303925,-0.544315397739,-3.3733355999 -21.4122180939,-0.54532968998,-3.31673073769 -21.4582023621,-0.546341776848,-3.25613689423 -21.5211868286,-0.546355366707,-3.19753670692 -21.5951728821,-0.54737007618,-3.13993310928 -21.6471557617,-0.548382818699,-3.078343153 -21.7051525116,-0.54939186573,-3.05352330208 -21.7771377563,-0.550406396389,-2.99392557144 -21.8401222229,-0.551420092583,-2.93432211876 -21.9071083069,-0.551434159279,-2.87372422218 -21.9770927429,-0.552448451519,-2.81411910057 -22.0300788879,-0.553461194038,-2.75152492523 -22.1020717621,-0.554471850395,-2.72570681572 -22.1720561981,-0.55548620224,-2.665102005 -22.2250423431,-0.556499063969,-2.60150885582 -22.2930259705,-0.557513296604,-2.53891158104 -22.3690109253,-0.558528184891,-2.47830176353 -22.4269962311,-0.558541536331,-2.41370987892 -22.506980896,-0.55955696106,-2.35210204124 -22.5609741211,-0.560566067696,-2.32229328156 -22.6359596252,-0.561581015587,-2.25968670845 -22.7039451599,-0.562595367432,-2.19508886337 -22.7729282379,-0.563609778881,-2.13048887253 -22.8399124146,-0.564623951912,-2.06588673592 -22.91289711,-0.565638899803,-2.0002887249 -22.9898910522,-0.56665045023,-1.97146677971 -23.0558738708,-0.567664563656,-1.90586423874 -23.1288585663,-0.568679451942,-1.83926546574 -23.198841095,-0.569694042206,-1.77266454697 -21.4747524261,-0.543520212173,-1.55500924587 -21.2687263489,-0.539504230022,-1.47154808044 -21.2107105255,-0.538503706455,-1.4000146389 -21.1997013092,-0.538505315781,-1.36623549461 -21.27368927,-0.539518773556,-1.30463421345 -9.6162853241,-0.360257923603,-0.427261590958 -9.59828948975,-0.360252916813,-0.396686851978 -9.60629367828,-0.360250681639,-0.367108643055 -9.61229991913,-0.360248178244,-0.337529271841 -9.61130428314,-0.36024492979,-0.307947844267 -9.59830665588,-0.360241830349,-0.292168259621 -9.59631252289,-0.360238313675,-0.261601477861 -9.6013174057,-0.360235571861,-0.232022032142 -9.59632301331,-0.360231727362,-0.202441245317 -9.60032844543,-0.360228836536,-0.172861546278 -9.59533309937,-0.360224813223,-0.142295479774 -9.59733581543,-0.360223323107,-0.127505615354 -9.59134197235,-0.360219210386,-0.0979261770844 -9.57934761047,-0.360214263201,-0.0673618987203 -9.58835315704,-0.360211789608,-0.0377818867564 -9.58535861969,-0.360207885504,-0.00820332206786 -9.58836460114,-0.360204666853,0.0213762633502 -9.5843706131,-0.360200583935,0.050954207778 -9.57937335968,-0.360198169947,0.0657421797514 -9.58537864685,-0.360195189714,0.0953226983547 -9.56738567352,-0.35918918252,0.125881016254 -9.57539176941,-0.360186398029,0.155462026596 -9.57639694214,-0.360182732344,0.185040786862 -9.57240390778,-0.359178423882,0.214617401361 -9.5764093399,-0.360175073147,0.24419747293 -9.5764131546,-0.360173135996,0.258986651897 -9.57941913605,-0.360169619322,0.288566827774 -9.5654258728,-0.359163880348,0.318136483431 -9.56943225861,-0.359160274267,0.348703145981 -9.56243896484,-0.359155356884,0.378276109695 -9.56644535065,-0.35915184021,0.407857120037 -9.56345272064,-0.359147369862,0.437432765961 -9.56145572662,-0.35914504528,0.452220082283 -9.55646324158,-0.359140247107,0.481793642044 -9.5534696579,-0.359135687351,0.511368691921 -9.55247592926,-0.359131336212,0.540945529938 -9.55548286438,-0.359127521515,0.570526480675 -9.55249023438,-0.35912284255,0.600101351738 -9.55349349976,-0.359120815992,0.614891469479 -9.55050086975,-0.359116107225,0.644466280937 -9.54650878906,-0.359111189842,0.674039781094 -9.55551528931,-0.359108090401,0.703628838062 -9.53952312469,-0.35910141468,0.733187317848 -9.53953075409,-0.359096974134,0.762765467167 -9.54053688049,-0.359092652798,0.792345046997 -9.54554080963,-0.359091103077,0.807141065598 -9.53754901886,-0.359085440636,0.836708605289 -9.53555583954,-0.359080582857,0.866284310818 -9.53656387329,-0.359076172113,0.895864486694 -9.52857112885,-0.359070360661,0.925431132317 -9.53057956696,-0.359066009521,0.955013096333 -9.63158321381,-0.361075431108,0.992643356323 -9.67058467865,-0.361078470945,1.01144325733 -9.65959358215,-0.361072361469,1.04002404213 -9.67259979248,-0.362069487572,1.07160353661 -9.66660785675,-0.36206394434,1.10117900372 -9.65961647034,-0.361058175564,1.13075256348 -9.67262363434,-0.362055242062,1.16233444214 -9.6566286087,-0.362050533295,1.17611169815 -9.65163612366,-0.361045002937,1.20568859577 -9.66864395142,-0.36204251647,1.23826622963 -9.645652771,-0.361034333706,1.26583552361 -9.64566135406,-0.362029373646,1.29640805721 -9.65666866302,-0.362026184797,1.32700383663 -9.65267753601,-0.362020522356,1.35756909847 -9.63868236542,-0.362015932798,1.37134683132 -9.64468955994,-0.36201184988,1.40193343163 -9.63569831848,-0.362005412579,1.43150126934 -9.63970661163,-0.362000972033,1.46208441257 -9.64171504974,-0.361996173859,1.4926636219 -9.62772369385,-0.361988961697,1.52123320103 -9.63273239136,-0.361984431744,1.55280637741 -9.64673614502,-0.361984014511,1.56960701942 -9.62274646759,-0.361975133419,1.59716558456 -9.62575435638,-0.36197039485,1.62774860859 -9.62776279449,-0.361965447664,1.65832972527 -9.62077236176,-0.361959069967,1.68790197372 -9.61578178406,-0.361953020096,1.71747922897 -9.61679077148,-0.36194768548,1.74904513359 -9.61279582977,-0.361944526434,1.76284348965 -9.61180400848,-0.3619389534,1.79341816902 -9.61481285095,-0.361933916807,1.82499063015 -9.60882282257,-0.36192753911,1.85456585884 -9.59583282471,-0.361920028925,1.88313472271 -9.60684108734,-0.36191624403,1.91571772099 -9.58784675598,-0.361910551786,1.92749977112 -9.59585571289,-0.361906170845,1.96007502079 -9.60286426544,-0.361901760101,1.99166202545 -9.59287452698,-0.361894488335,2.02122592926 -9.5868844986,-0.361887931824,2.05080151558 -9.602891922,-0.36288484931,2.08439135551 -9.59490203857,-0.362877875566,2.11396169662 -9.5859079361,-0.362873584032,2.12774443626 -9.5839176178,-0.362867534161,2.15832018852 -9.58092784882,-0.362861245871,2.18889307976 -9.57293796539,-0.362854331732,2.21747636795 -9.57994747162,-0.362849652767,2.25005602837 -9.5719575882,-0.36284250021,2.27962660789 -9.57796192169,-0.362840533257,2.29641890526 -9.57597255707,-0.362834364176,2.32699680328 -9.568983078,-0.36282736063,2.35657119751 -9.57199192047,-0.362821787596,2.38914060593 -9.57400131226,-0.362816214561,2.42072081566 -9.56101322174,-0.362808078527,2.44928789139 -9.5600233078,-0.362801998854,2.47987127304 -9.56802749634,-0.363800287247,2.49766087532 -9.55903911591,-0.363792717457,2.52722930908 -9.5650472641,-0.363787710667,2.55981373787 -9.55705928802,-0.363780289888,2.58938622475 -9.55406951904,-0.363773733377,2.61996459961 -9.54008197784,-0.363765150309,2.64852786064 -9.55209064484,-0.363761007786,2.68311190605 -9.54609584808,-0.363757014275,2.69690394402 -9.54210662842,-0.36375015974,2.72748017311 -9.55311584473,-0.363745778799,2.76206326485 -9.53912830353,-0.363737106323,2.7906267643 -9.53114032745,-0.363729506731,2.8202009201 -9.54414844513,-0.364725351334,2.85578203201 -9.53116130829,-0.364716798067,2.884349823 -9.53116607666,-0.364713668823,2.90014076233 -9.53217601776,-0.364707618952,2.93172740936 -9.52718734741,-0.36470040679,2.9623029232 -9.52219867706,-0.364693164825,2.99287843704 -9.52920913696,-0.364687860012,3.0274541378 -9.52921962738,-0.364681333303,3.06002664566 -9.52522563934,-0.364677459002,3.0748155117 -9.52323722839,-0.36467063427,3.10639309883 -9.49325180054,-0.364659100771,3.12896418571 -9.44926834106,-0.364644825459,3.14850926399 -9.36329078674,-0.362623542547,3.15305662155 -9.37130069733,-0.363618314266,3.18763685226 -9.36731243134,-0.363611012697,3.21821546555 -9.381316185,-0.363610059023,3.23900771141 -9.37432861328,-0.363602250814,3.26858663559 -9.37334060669,-0.363595247269,3.30115532875 -9.3813495636,-0.36359000206,3.33574199677 -9.36936283112,-0.363581120968,3.3643116951 -9.36637592316,-0.364573806524,3.39588570595 -9.3693857193,-0.364567548037,3.42946410179 -9.36239242554,-0.364562928677,3.44325065613 -9.36540412903,-0.364556640387,3.4768307209 -9.35641670227,-0.364548206329,3.5064034462 -9.36542701721,-0.364543020725,3.5419895649 -9.35844039917,-0.364534825087,3.5725607872 -9.3574514389,-0.364527732134,3.60513710976 -9.36445617676,-0.365525394678,3.6249191761 -9.35346984863,-0.365516573191,3.65349698067 -9.35548114777,-0.36551001668,3.68707823753 -9.35649299622,-0.36550322175,3.7206556797 -9.33950710297,-0.36549320817,3.74722838402 -9.3445186615,-0.365487009287,3.78280305862 -9.34453105927,-0.365479916334,3.81637787819 -9.34253692627,-0.36647605896,3.83216738701 -9.3475484848,-0.366469830275,3.86774539948 -9.34356021881,-0.366462111473,3.89932632446 -9.33757400513,-0.36645385623,3.93089723587 -9.33258724213,-0.366445839405,3.96247410774 -9.33159923553,-0.366438448429,3.99604868889 -9.3276052475,-0.366434246302,4.0108423233 -9.33261680603,-0.367427825928,4.04741382599 -9.32962989807,-0.367420107126,4.07999229431 -9.32064342499,-0.367411196232,4.11056280136 -9.32665538788,-0.367405056953,4.14714431763 -9.31566905975,-0.367395758629,4.17671728134 -9.31268119812,-0.367388010025,4.20929861069 -9.31868743896,-0.368385493755,4.22908973694 -9.32069969177,-0.36837849021,4.26466560364 -9.31271266937,-0.368369549513,4.29623317719 -9.31672477722,-0.368363112211,4.33182239532 -9.29974079132,-0.368352502584,4.3593878746 -9.30075359344,-0.368345230818,4.39496183395 -9.30176544189,-0.369337916374,4.43053674698 -9.30077266693,-0.369334071875,4.44732809067 -9.2108001709,-0.367309957743,4.44086933136 -9.29379844666,-0.369318038225,4.51348972321 -9.27681446075,-0.369307309389,4.541056633 -9.27682685852,-0.369299739599,4.57663106918 -9.29783630371,-0.370296299458,4.62122583389 -9.29084968567,-0.370287358761,4.65379619598 -9.26885986328,-0.370279371738,4.66156959534 -9.2928686142,-0.370276421309,4.70816469193 -9.29288196564,-0.371268868446,4.74374485016 -9.28389644623,-0.371259540319,4.77531814575 -9.28290939331,-0.371251493692,4.81188297272 -9.27792263031,-0.37124311924,4.84447050095 -9.2859287262,-0.371240675449,4.86725473404 -9.2839422226,-0.371232539415,4.90282869339 -9.24896240234,-0.371218264103,4.92139148712 -9.26297187805,-0.37221339345,4.96398639679 -9.27098369598,-0.372207015753,5.00555753708 -9.26099967957,-0.372197538614,5.03614139557 -9.26301193237,-0.372189998627,5.07471179962 -9.26601791382,-0.373186737299,5.09450435638 -9.26103305817,-0.373177945614,5.12907791138 -9.25604724884,-0.373169124126,5.16365194321 -9.25605964661,-0.373161435127,5.20023727417 -9.24807453156,-0.373151928186,5.2338051796 -9.23209095001,-0.373141020536,5.26237726212 -9.24910163879,-0.37413623929,5.30995416641 -9.25410652161,-0.37413340807,5.33075475693 -9.251121521,-0.374124825001,5.36732578278 -9.24013614655,-0.37511485815,5.39890098572 -9.23715114594,-0.375106275082,5.43547487259 -9.23316478729,-0.375097572803,5.47105407715 -9.23017978668,-0.375089019537,5.50763034821 -9.22519493103,-0.375080019236,5.54320526123 -9.22520160675,-0.376076102257,5.56199884415 -9.232213974,-0.376069247723,5.60556983948 -9.21523094177,-0.376057952642,5.63414287567 -9.2112455368,-0.37604907155,5.67071819305 -9.20825958252,-0.377040535212,5.70730066299 -9.16328239441,-0.376023799181,5.71886587143 -9.21227931976,-0.377029120922,5.76866674423 -9.21829319,-0.377022027969,5.81224107742 -9.20730876923,-0.378011792898,5.84481668472 -9.20632266998,-0.378003507853,5.88339853287 -9.21233558655,-0.377996504307,5.92697811127 -9.19735336304,-0.377985388041,5.95755004883 -9.20135879517,-0.378982007504,5.98033761978 -9.21037101746,-0.378975629807,6.02592182159 -9.19338798523,-0.378964036703,6.05549287796 -9.19840145111,-0.379956781864,6.09907388687 -9.19841575623,-0.379948526621,6.1396522522 -9.1844329834,-0.379937529564,6.17122602463 -9.18344783783,-0.379928946495,6.21180057526 -9.18745326996,-0.380925625563,6.23459482193 -9.18346881866,-0.380916506052,6.27317047119 -9.17848491669,-0.380907088518,6.31174087524 -9.17449855804,-0.380897969007,6.35031986237 -9.17751312256,-0.381890237331,6.3938999176 -9.1685295105,-0.381880104542,6.4294757843 -9.16654396057,-0.381871283054,6.47005367279 -9.17155075073,-0.382867991924,6.49484109879 -9.17056465149,-0.382859379053,6.53641939163 -9.16358089447,-0.382849544287,6.57399511337 -9.15359783173,-0.382839083672,6.60956954956 -9.15561103821,-0.383830934763,6.65414428711 -9.14862728119,-0.383821129799,6.69172382355 -9.14864253998,-0.38381254673,6.73529720306 -9.15264987946,-0.384808987379,6.7600851059 -9.15366268158,-0.384800761938,6.80366945267 -9.14468002319,-0.384790331125,6.8412399292 -9.13669681549,-0.385780274868,6.87881803513 -9.1447095871,-0.385773330927,6.92840194702 -9.13572692871,-0.3857627213,6.96696710587 -9.14473152161,-0.386760413647,6.99476909637 -9.13574886322,-0.386749833822,7.0333366394 -9.32772064209,-0.390779495239,7.22298049927 -9.03280162811,-0.385712057352,7.04445981979 -9.01582050323,-0.385699987411,7.07603263855 -9.04182910919,-0.386696487665,7.14062166214 -9.00085353851,-0.386679530144,7.15418386459 -8.95087242126,-0.385665357113,7.1369638443 -8.87990283966,-0.384642332792,7.12651729584 -8.87192058563,-0.384631961584,7.1650929451 -8.86493778229,-0.384621739388,7.20466804504 -8.85395622253,-0.385610729456,7.24124097824 -8.84997177124,-0.385601013899,7.28381490707 -8.85598564148,-0.386593550444,7.33340358734 -8.86699104309,-0.386591166258,7.36618757248 -9.0549621582,-0.390620082617,7.56582641602 -9.12896060944,-0.392626017332,7.67442417145 -9.12697601318,-0.392616868019,7.72000741959 -9.11499404907,-0.39360550046,7.75857782364 -9.11301040649,-0.393596231937,7.80515670776 -9.12601470947,-0.394594281912,7.84094429016 -9.11903095245,-0.394584029913,7.88352298737 -9.1200466156,-0.395575195551,7.93409538269 -9.10906410217,-0.395564109087,7.97367238998 -9.09808254242,-0.395553022623,8.01325130463 -8.95913124084,-0.39351606369,7.94179058075 -9.21708583832,-0.398559004068,8.21743965149 -9.21909236908,-0.399554997683,8.24423217773 -9.22710514069,-0.399547547102,8.30280971527 -9.24011802673,-0.400541245937,8.36539459229 -9.21214103699,-0.400526404381,8.39295768738 -9.20615673065,-0.401516348124,8.43854141235 -9.20317363739,-0.401506662369,8.48811817169 -9.2061882019,-0.402498155832,8.54369354248 -9.21419429779,-0.402495205402,8.57748317719 -9.19721412659,-0.402482628822,8.61505508423 -9.20122814178,-0.403474390507,8.67163658142 -9.20424365997,-0.404465854168,8.72821426392 -9.19026279449,-0.404453933239,8.76878929138 -9.18128013611,-0.404442965984,8.81436538696 -9.19728374481,-0.405441701412,8.85616207123 -9.37627124786,-0.410459727049,9.13736915588 -9.15934085846,-0.406406372786,8.98488235474 -9.11138534546,-0.406378030777,9.05001831055 -9.06341266632,-0.406359046698,9.05858325958 -9.0314283371,-0.405347973108,9.0543680191 -9.02444553375,-0.406337350607,9.10294628143 -9.02546215057,-0.406328201294,9.16052246094 -9.02147865295,-0.407318234444,9.21210670471 -9.01949596405,-0.407308399677,9.2676782608 -9.01151371002,-0.408297359943,9.31725120544 -9.01252174377,-0.408293068409,9.34604644775 -9.00453948975,-0.409282058477,9.39562225342 -9.00855445862,-0.409273445606,9.45819854736 -8.99257564545,-0.410260677338,9.50076675415 -8.99459075928,-0.410251736641,9.56134700775 -8.97861099243,-0.411239027977,9.60391902924 -8.9706287384,-0.41122803092,9.65449810028 -8.95364189148,-0.411220014095,9.66528987885 -8.89567279816,-0.410198569298,9.6638469696 -8.83470535278,-0.410176575184,9.65840625763 -8.77973556519,-0.409155845642,9.65896892548 -8.72576618195,-0.409135371447,9.65953636169 -8.67679595947,-0.408115774393,9.66609954834 -8.67181301117,-0.409105211496,9.72067546844 -8.68781757355,-0.410103738308,9.76846981049 -8.6838350296,-0.410093337297,9.82504558563 -8.67085552216,-0.411081284285,9.87062740326 -8.75285053253,-0.413088470697,10.025223732 -8.91882324219,-0.418112963438,10.275847435 -8.91384124756,-0.4181022048,10.3354177475 -8.91085910797,-0.419092088938,10.3959980011 -8.9208650589,-0.420089364052,10.4397907257 -8.91488265991,-0.420078665018,10.4973735809 -8.91589927673,-0.421069145203,10.564948082 -8.89692115784,-0.421055495739,10.6095180511 -8.89593791962,-0.422045648098,10.6750955582 -8.89995288849,-0.423036843538,10.746676445 -8.90096187592,-0.423032253981,10.7814664841 -8.89697933197,-0.424021661282,10.845041275 -8.89099788666,-0.425010710955,10.9066162109 -8.89201450348,-0.426001399755,10.9752044678 -8.91602420807,-0.426996678114,11.0737895966 -8.7540845871,-0.42395362258,10.9443264008 -3.40755224228,-0.293839663267,4.37038707733 -3.3925652504,-0.293831974268,4.36418962479 -3.37858939171,-0.293818801641,4.37475299835 -8.97811698914,-0.433945834637,11.6200590134 -8.97513580322,-0.434935390949,11.6906356812 -8.99113941193,-0.435933828354,11.7484302521 -8.97815990448,-0.435921192169,11.8079996109 -8.96917915344,-0.43690943718,11.8725738525 -8.96419715881,-0.437898725271,11.9411582947 -8.95721626282,-0.438887447119,12.0087366104 -8.95023536682,-0.438875973225,12.0783061981 -8.9402551651,-0.439864069223,12.1428842545 -8.95326042175,-0.440861791372,12.1996765137 -8.94528007507,-0.441850215197,12.2682523727 -8.93629932404,-0.441838443279,12.3358297348 -8.92831993103,-0.442826896906,12.4054059982 -8.92033863068,-0.443815350533,12.474984169 -8.88736438751,-0.44379863143,12.5105571747 -8.8423948288,-0.443779379129,12.5301237106 -8.80041503906,-0.442765682936,12.5129003525 -8.77843856812,-0.443751126528,12.5644731522 -8.76845836639,-0.444739103317,12.6330499649 -8.76247787476,-0.445727914572,12.7076301575 -8.75349807739,-0.445716023445,12.7792062759 -8.74751663208,-0.44670471549,12.8557815552 -8.74053573608,-0.447693228722,12.9313592911 -8.74554347992,-0.448689192533,12.9821481705 -8.74556064606,-0.449679166079,13.0687294006 -8.73458194733,-0.450666815042,13.1403045654 -8.73559856415,-0.451656877995,13.2308807373 -8.71862125397,-0.452643305063,13.2944555283 -8.71263980865,-0.453632086515,13.37403965 -8.72464561462,-0.453629463911,13.437830925 -8.72066497803,-0.45561850071,13.5234079361 -8.71068572998,-0.455606222153,13.6009807587 -8.69670677185,-0.45659327507,13.6715602875 -8.69372558594,-0.457582443953,13.761136055 -8.68374538422,-0.45857027173,13.8397140503 -8.67576599121,-0.459558457136,13.9222927094 -8.8237323761,-0.464583665133,14.2071084976 -8.81575202942,-0.465571731329,14.2936811447 -8.80377483368,-0.466558992863,14.374256134 -8.79679393768,-0.467547357082,14.4628343582 -8.78781414032,-0.468535274267,14.5494117737 -8.77583503723,-0.46952265501,14.6309909821 -8.76685523987,-0.47051051259,14.7195672989 -8.77886104584,-0.471507847309,14.7913599014 -8.77388000488,-0.47349652648,14.8879375458 -8.76390171051,-0.474484235048,14.97651577 -8.7489233017,-0.475470751524,15.0590867996 -8.73894405365,-0.476458370686,15.1496648788 -8.7339630127,-0.477447122335,15.2492446899 -8.74596881866,-0.478444308043,15.3260326385 -8.73799037933,-0.479432463646,15.4216156006 -8.7290096283,-0.481420189142,15.5181903839 -8.71803188324,-0.482407420874,15.6137599945 -8.71005153656,-0.483395516872,15.7123422623 -8.69707393646,-0.484382450581,15.8049173355 -8.68709468842,-0.486369997263,15.9034938812 -8.70609855652,-0.487368702888,15.9962882996 -8.70211791992,-0.488357484341,16.1078662872 -8.66214752197,-0.489338904619,16.1534385681 -8.60818195343,-0.489317327738,16.1750030518 -8.53921985626,-0.488292843103,16.1665725708 -8.52324295044,-0.489279121161,16.2581501007 -8.51226425171,-0.490266382694,16.3607254028 -8.53026866913,-0.492264896631,16.4565219879 -8.52028942108,-0.493252396584,16.5630989075 -8.51231002808,-0.495240271091,16.6746749878 -8.49833297729,-0.496226787567,16.7772483826 -8.48635387421,-0.497213870287,16.8828258514 -8.47937488556,-0.499201983213,16.9994068146 -8.49038124084,-0.500198841095,17.0891933441 -8.4804019928,-0.502186357975,17.2017726898 -8.47342300415,-0.503174364567,17.323348999 -8.46144485474,-0.5051612854,17.4369239807 -8.44846820831,-0.506148219109,17.547504425 -11.4286022186,-0.613743543625,23.8845405579 -11.3366470337,-0.6127140522,23.8841018677 -10.6108703613,-0.588561117649,22.4527816772 -11.1837177277,-0.611666738987,23.8494472504 -11.0977621078,-0.610638439655,23.8610076904 -10.9988098145,-0.609607517719,23.8425712585 -10.9038553238,-0.609577417374,23.8331298828 -10.6569471359,-0.60251647234,23.4886722565 -10.5659914017,-0.602487206459,23.4832363129 -10.5140171051,-0.601471185684,23.4670143127 -10.4260616302,-0.601442575455,23.4665794373 -10.334107399,-0.600413143635,23.4561462402 -10.2501497269,-0.599385261536,23.4647121429 -10.1601963043,-0.599356174469,23.4592723846 -10.066242218,-0.598326325417,23.4428386688 -9.98128700256,-0.598298192024,23.4484004974 -9.93131065369,-0.597282588482,23.4331817627 -9.84335517883,-0.597253978252,23.4287490845 -9.75240135193,-0.596224665642,23.4183120728 -9.67144393921,-0.596197545528,23.4278831482 -9.57749176025,-0.595167636871,23.409444809 -9.49653434753,-0.594140410423,23.4210109711 -9.44555950165,-0.594124734402,23.3987960815 -9.35560512543,-0.593095600605,23.3883590698 -9.27264881134,-0.593068063259,23.3909301758 -9.18569374084,-0.592039585114,23.3864936829 -9.09673976898,-0.592010676861,23.3760585785 -9.01078414917,-0.590982556343,23.3706264496 -8.93082714081,-0.590955674648,23.3791980743 -8.8798532486,-0.589939832687,23.3579769135 -8.79189872742,-0.589911401272,23.3435497284 -8.71294212341,-0.588884592056,23.3561172485 -8.62298870087,-0.58885550499,23.339679718 -8.54203128815,-0.587828338146,23.3442516327 -8.45607757568,-0.587800204754,23.335817337 -8.41209983826,-0.586786031723,23.3266067505 -8.32814502716,-0.586758255959,23.3221740723 -8.24619007111,-0.585730850697,23.3257389069 -8.15823554993,-0.585702359676,23.3073101044 -8.08027839661,-0.584675908089,23.3178825378 -7.99632406235,-0.584648132324,23.3124485016 -7.91036891937,-0.583620011806,23.2990169525 -7.86639213562,-0.583605825901,23.2888050079 -7.78343725204,-0.583578288555,23.2843704224 -7.69848299026,-0.582550466061,23.2719421387 -7.62352514267,-0.582524597645,23.2895126343 -7.53757095337,-0.581496536732,23.2730846405 -7.45761537552,-0.581469774246,23.2736568451 -4.08667707443,-0.41578707099,12.9508047104 -4.06869268417,-0.415778070688,12.9665870667 -7.24073123932,-0.579399287701,23.2235794067 -7.16977262497,-0.579374313354,23.2501525879 -7.08681821823,-0.579346895218,23.2407226562 -7.00786209106,-0.578320384026,23.2402973175 -6.92690706253,-0.578293323517,23.2368659973 -6.8479514122,-0.57826679945,23.2364406586 -6.79997587204,-0.577251851559,23.2092227936 -6.72401952744,-0.577225923538,23.217798233 -6.64306402206,-0.576199054718,23.2103710175 -6.56510829926,-0.576172709465,23.2129421234 -6.48515272141,-0.576146066189,23.2065162659 -6.40519762039,-0.575119435787,23.201089859 -6.362221241,-0.575105547905,23.1858768463 -6.28426504135,-0.575079321861,23.1854496002 -6.20231056213,-0.574052155018,23.1740188599 -6.12635469437,-0.574026465416,23.1775970459 -6.04739952087,-0.573999941349,23.1751670837 -5.97044277191,-0.572974026203,23.1737442017 -5.89148759842,-0.572947621346,23.1693172455 -5.84551239014,-0.571933209896,23.1391067505 -5.77155542374,-0.571907877922,23.1516799927 -5.69459962845,-0.571881890297,23.1532516479 -5.61464500427,-0.570855438709,23.1398277283 -5.53668928146,-0.57082927227,23.1354007721 -5.45873403549,-0.57080322504,23.1289768219 -5.4157576561,-0.569789409637,23.1097640991 -5.3418006897,-0.569764137268,23.1203384399 -5.2628455162,-0.569737970829,23.1059169769 -5.18888950348,-0.569712758064,23.1154937744 -5.1089348793,-0.568686246872,23.1000652313 -5.03197908401,-0.568660497665,23.0946426392 -5.01600456238,-0.572646677494,23.370223999 -5.03400945663,-0.576644718647,23.6340179443 -3.24559307098,-0.450285643339,15.5304107666 -3.16663861275,-0.447259813547,15.3939876556 -3.10667824745,-0.446237623692,15.3465652466 -3.06171298027,-0.447218447924,15.3711471558 -3.00775074959,-0.446197509766,15.3507270813 -2.96378540993,-0.447178512812,15.3813076019 -2.94280219078,-0.447169184685,15.403096199 -2.90083646774,-0.447150558233,15.4456758499 -2.85387182236,-0.448131024837,15.4622564316 -2.81090593338,-0.448112368584,15.4978427887 -2.77893662453,-0.449095755816,15.5994243622 -2.741969347,-0.450078070164,15.6780023575 -4.74535560608,-0.633454024792,27.5017852783 -4.75836181641,-0.638451099396,27.8345775604 -4.72939157486,-0.64343470335,28.1961574554 -4.96233844757,-0.673468589783,30.1497612 -4.8663892746,-0.673439323902,30.156337738 -4.77743816376,-0.674411416054,30.2069149017 -4.68048906326,-0.673382103443,30.207490921 -4.63151502609,-0.673367261887,30.207277298 -4.57955169678,-0.678346514702,30.5038585663 -4.54358386993,-0.684328913689,30.9214401245 -4.65658950806,-0.71732878685,33.1186141968 -4.64461374283,-0.727315604687,33.8001976013 -4.53766822815,-0.727284491062,33.8057746887 -4.49269247055,-0.728270590305,33.8705673218 -4.4367313385,-0.73424911499,34.2701454163 -4.37877035141,-0.740227341652,34.6767272949 -4.35080003738,-0.750211238861,35.3423080444 -4.3058347702,-0.759191930294,35.8998908997 -4.25787067413,-0.767172038555,36.4624710083 -2.70137572289,-0.568872332573,23.5451583862 -2.63041877747,-0.56884855032,23.5727443695 -2.57345795631,-0.571827232838,23.738325119 -2.49850273132,-0.571802616119,23.7459030151 -2.41554999352,-0.569776594639,23.6674861908 -4.01506185532,-0.82606703043,40.3991775513 -3.9461042881,-0.835043311119,41.011756897 -3.95511198044,-0.84703963995,41.7865486145 -3.89215278625,-0.858017027378,42.5411300659 -3.87619948387,-0.902992606163,45.4843025208 -3.72626757622,-0.901953935623,45.406879425 -3.6293194294,-0.909925103188,45.9914627075 -3.5583627224,-0.92490118742,46.9660453796 -3.64534568787,-0.957912027836,49.1228408813 -3.49441432953,-0.958873271942,49.1774215698 -3.39046812057,-0.969843268394,49.922000885 -3.25455331802,-1.01279675961,52.8051681519 -3.12061667442,-1.02176141739,53.3617477417 -3.3395678997,-1.12679123878,60.2833442688 -3.24360871315,-1.12676823139,60.2741317749 -3.05269050598,-1.12572228909,60.2517127991 -2.8647711277,-1.12667715549,60.2752952576 -2.68884801865,-1.13063418865,60.5848770142 -1.52324080467,-0.774409234524,37.187412262 -1.3893045187,-0.767374396324,36.7579917908 -1.32633507252,-0.765357673168,36.6077880859 -1.22338867188,-0.770328640938,36.9553718567 -2.06813979149,-1.24747335911,68.3110046387 -1.91221022606,-1.28043448925,70.4375839233 -1.77527475357,-1.33239924908,73.903175354 -1.5983518362,-1.37235677242,76.5087585449 -1.02255654335,-1.09024167061,57.9603271484 -0.674699068069,-1.00516307354,52.3886985779 -0.517769932747,-1.01612460613,53.1082839966 -0.348844707012,-1.01008403301,52.7438697815 --0.802672445774,-0.954821705818,74.0525741577 --1.03657710552,-0.955770015717,74.1251602173 --12.9347667694,-0.959318101406,73.5037841797 --13.2796392441,-0.965255498886,74.0964050293 --12.3118553162,-0.858387053013,63.527545929 --11.7749147415,-0.779440522194,55.6093101501 --16.369430542,-0.973689079285,74.3816070557 --16.215461731,-0.955709040165,72.5942077637 --16.0384788513,-0.927727997303,69.7444000244 --15.9314937592,-0.91274034977,68.2969894409 --15.983458519,-0.905727446079,67.5615997314 --15.5675601959,-0.873786211014,64.4459686279 --15.5695409775,-0.865781247616,63.5805740356 --15.5435304642,-0.855780601501,62.6211738586 --15.7314529419,-0.855746388435,62.5407905579 --15.3985376358,-0.83379393816,60.4153671265 --11.11784935,-0.654458642006,43.0776443481 --11.2457904816,-0.654432475567,43.0112457275 --11.3177576065,-0.654418170452,43.0100517273 --15.1035642624,-0.796823322773,56.6489486694 --15.0595598221,-0.787825405598,55.779548645 --15.0565423965,-0.781821131706,55.0801467896 --15.231470108,-0.781789422035,55.0417671204 --15.3934011459,-0.780759751797,54.952381134 --15.506357193,-0.781740128994,55.0241928101 --15.692281723,-0.782707035542,55.0208129883 --15.8862028122,-0.782672822475,55.0424308777 --14.7035503387,-0.734849214554,50.3539276123 --9.20023059845,-0.533684253693,31.1660575867 --9.30617904663,-0.533661425114,31.1656665802 --9.4141254425,-0.534638345242,31.1662693024 --9.46110153198,-0.534627914429,31.1470737457 --9.55605316162,-0.533607006073,31.1076793671 --9.71198654175,-0.535576879978,31.264289856 --9.87391662598,-0.538546025753,31.4328975677 --10.094830513,-0.54250639677,31.7845115662 --10.1947803497,-0.542485117912,31.7541217804 --10.3017292023,-0.54246288538,31.7427272797 --14.4944152832,-0.671829044819,43.9375267029 --14.1744222641,-0.640853106976,40.8015022278 --11.4702396393,-0.55624806881,32.8590278625 --13.8944816589,-0.626887142658,39.3968696594 --13.8994617462,-0.62288159132,39.0184707642 --13.8774499893,-0.618880093098,38.5720710754 --13.7994565964,-0.612886726856,37.9806632996 --13.7814445496,-0.608884632587,37.5632629395 --13.685464859,-0.603896141052,37.1210517883 --13.7274341583,-0.601885378361,36.8766555786 --13.7274160385,-0.598880589008,36.5242538452 --13.7034053802,-0.594879329205,36.115852356 --13.6843938828,-0.59087741375,35.7274513245 --13.6723794937,-0.587874472141,35.3630523682 --13.7733306885,-0.586855351925,35.2916641235 --13.8333044052,-0.58784455061,35.2824745178 --13.9432525635,-0.58782440424,35.2360839844 --14.0791950226,-0.587800621986,35.2536964417 --13.7322816849,-0.575845062733,34.073261261 --13.8302345276,-0.575826764107,34.0088729858 --13.4683265686,-0.562873005867,32.8234329224 --13.4733066559,-0.560867726803,32.5430297852 --13.4123163223,-0.557873904705,32.2518234253 --13.3953046799,-0.554871618748,31.9264202118 --13.375292778,-0.550869822502,31.601020813 --13.3682775497,-0.548866152763,31.3096199036 --13.3462657928,-0.545864582062,30.9862155914 --13.3322525024,-0.542861938477,30.6888141632 --13.3162488937,-0.540861845016,30.5186100006 --13.4241991043,-0.541842460632,30.5042247772 --13.4541740417,-0.539833784103,30.3138313293 --13.6450996399,-0.541803300381,30.4844551086 --13.2132110596,-0.528857588768,29.2719993591 --13.2131938934,-0.52685302496,29.0286006927 --13.2001791,-0.52485024929,28.7591972351 --13.132191658,-0.521857142448,28.4929904938 --13.1291742325,-0.519853055477,28.2515888214 --13.1191616058,-0.516849815845,28.0001888275 --13.1071472168,-0.514846920967,27.7447853088 --13.1001319885,-0.512843310833,27.5063858032 --13.1031131744,-0.510838449001,27.2909851074 --13.0841016769,-0.507836461067,27.0315818787 --13.0331087112,-0.505841016769,26.8183727264 --13.0930747986,-0.505828619003,26.7289867401 --13.1840305328,-0.505812227726,26.6995944977 --13.2150039673,-0.504803836346,26.5522003174 --9.24815559387,-0.413317531347,18.4372596741 --9.27213001251,-0.412308335304,18.3398590088 --9.29711437225,-0.412302047014,18.31665802 --9.17613124847,-0.408311754465,17.9372367859 --9.20610427856,-0.408301949501,17.8588447571 --9.28506374359,-0.408285707235,17.8714466095 --9.3830165863,-0.409267187119,17.9220561981 --9.5799407959,-0.412236094475,18.1586818695 --9.67989349365,-0.413217514753,18.2072887421 --12.843960762,-0.480812370777,24.0695457458 --12.8539409637,-0.478806704283,23.9051456451 --9.54088878632,-0.407220751047,17.6092624664 --9.60685253143,-0.407206654549,17.5978679657 --9.65682029724,-0.407194644213,17.5574703217 --9.71978378296,-0.408181071281,17.5400753021 --13.1967582703,-0.477742552757,23.6421985626 --13.2457361221,-0.478734433651,23.6430072784 --13.3406915665,-0.478718578815,23.6366195679 --13.4356470108,-0.479702860117,23.6292324066 --13.5176076889,-0.479688853025,23.6008472443 --13.6105642319,-0.479673594236,23.590461731 --13.7125196457,-0.480657279491,23.5940761566 --13.768494606,-0.480648577213,23.6048870087 --13.8584527969,-0.480633944273,23.5885028839 --13.9594078064,-0.481618076563,23.5891189575 --14.0203742981,-0.481607139111,23.5227298737 --14.1013355255,-0.481593877077,23.4903450012 --14.2042894363,-0.481578052044,23.4929618835 --14.2222681046,-0.48057243228,23.3555641174 --14.2182617188,-0.479571223259,23.2663650513 --14.3722028732,-0.481549590826,23.3529930115 --14.5801277161,-0.484521776438,23.5246295929 --14.6560897827,-0.484509646893,23.4802417755 --14.6720714569,-0.482504606247,23.3418464661 --14.8570022583,-0.485479950905,23.4714775085 --14.9699554443,-0.485463857651,23.4861011505 --15.0329303741,-0.486455112696,23.5029125214 --15.1328868866,-0.486440688372,23.4955329895 --15.1408691406,-0.485436886549,23.3451328278 --15.2608203888,-0.48642039299,23.3687572479 --15.4047651291,-0.487401276827,23.4273834229 --15.267788887,-0.483414143324,23.0599632263 --12.8074703217,-0.438691049814,19.2733230591 --12.8624401093,-0.438681006432,19.2239322662 --15.5646686554,-0.485374182463,23.1110229492 --14.2160148621,-0.459519118071,20.820980072 --13.1542949677,-0.43963354826,19.1333866119 --13.1832714081,-0.438626736403,19.0459899902 --13.2372484207,-0.438618987799,19.0587978363 --13.4421758652,-0.441593050957,19.2254390717 --13.4241657257,-0.440591603518,19.0710372925 --13.4001569748,-0.438590794802,18.9096336365 --14.3778715134,-0.454481750727,20.155412674 --12.5243673325,-0.421678215265,17.436668396 --14.2458782196,-0.450490087271,19.7055912018 --12.0074872971,-0.41172772646,16.5489692688 --12.0494594574,-0.410719275475,16.4975776672 --12.0734367371,-0.410712718964,16.4201793671 --12.1264066696,-0.41070318222,16.3837890625 --12.1813755035,-0.410693496466,16.3493976593 --12.2483415604,-0.410682678223,16.3320121765 --12.2493333817,-0.410680621862,16.2788085938 --11.5934972763,-0.398744821548,15.3052864075 --11.982375145,-0.404700517654,15.7149553299 --11.9613647461,-0.403698772192,15.5845499039 --12.1083097458,-0.404679834843,15.6731758118 --8.92315673828,-0.352000027895,11.4651670456 --8.95513153076,-0.351991415024,11.4317722321 --8.94412612915,-0.350989788771,11.3795633316 --8.99609470367,-0.351979136467,11.3711681366 --12.5811128616,-0.408615618944,15.8154659271 --12.5281124115,-0.407617419958,15.6470556259 --12.5750846863,-0.407609283924,15.6046657562 --12.6780414581,-0.407595723867,15.6312875748 --12.8109912872,-0.409579277039,15.6929101944 --12.8599700928,-0.409572869539,15.7027225494 --12.6960000992,-0.406585514545,15.4022884369 --12.9149265289,-0.408561080694,15.5679340363 --12.7389574051,-0.405574768782,15.2564973831 --12.7189483643,-0.404573380947,15.135093689 --13.0698404312,-0.409536808729,15.4537658691 --13.1438140869,-0.409528255463,15.4905767441 --13.0758171082,-0.407531678677,15.3121643066 --13.054807663,-0.406530588865,15.1897592545 --13.1927576065,-0.408514767885,15.2533922195 --13.3147106171,-0.409500539303,15.2960157394 --13.3007001877,-0.408499002457,15.1826143265 --13.3226804733,-0.408494114876,15.1102151871 --13.5446157455,-0.411472529173,15.3140659332 --13.4466266632,-0.408478736877,15.1066465378 --13.6375627518,-0.411458790302,15.2232837677 --13.881485939,-0.414434462786,15.3989419937 --20.9016590118,-0.518808782101,23.0651321411 --13.9034519196,-0.412427634001,15.2271442413 --14.0254068375,-0.413414567709,15.2647762299 --14.0114040375,-0.413414627314,15.2005720139 --15.309056282,-0.432299524546,16.5074634552 --12.0588769913,-0.383578836918,12.9093332291 --12.0558624268,-0.382575780153,12.8239297867 --12.0538492203,-0.381572633982,12.7405281067 --12.0518350601,-0.381569474936,12.6571245193 --12.0798206329,-0.381565511227,12.6469335556 --12.1457891464,-0.381556689739,12.6355457306 --12.1917619705,-0.381549656391,12.6031551361 --12.1867494583,-0.38154694438,12.5187559128 --12.1847352982,-0.38054394722,12.4363489151 --12.1837215424,-0.379540920258,12.3569507599 --12.1827068329,-0.379537880421,12.27754879 --12.1517076492,-0.378538876772,12.2073411942 --12.1496944427,-0.378535926342,12.1279392242 --12.1616773605,-0.377531945705,12.0635433197 --12.1536645889,-0.376529455185,11.9781360626 --12.1446523666,-0.376527130604,11.8937339783 --12.1646337509,-0.376522570848,11.8383398056 --12.1666193008,-0.375519424677,11.7649374008 --12.1516151428,-0.375519096851,11.7127323151 --12.1685972214,-0.374514818192,11.6553382874 --12.1635847092,-0.374512225389,11.5759325027 --12.1625699997,-0.373509407043,11.5015306473 --12.1585578918,-0.373506814241,11.4251317978 --12.155544281,-0.372504085302,11.3487243652 --12.1525316238,-0.3725014925,11.2753314972 --12.1385278702,-0.37150105834,11.2251205444 --12.1285161972,-0.37049895525,11.1447181702 --12.1295022964,-0.370496064425,11.0753211975 --12.1364870071,-0.370492726564,11.0109205246 --12.1334733963,-0.369490087032,10.9375152588 --12.1304607391,-0.369487524033,10.8651151657 --12.1284542084,-0.368486315012,10.828915596 --12.1154432297,-0.368484437466,10.7475070953 --12.1254272461,-0.367480993271,10.6881113052 --12.0604295731,-0.366482704878,10.5616893768 --12.0524177551,-0.366480559111,10.4882936478 --12.0484056473,-0.365478038788,10.4168872833 --12.0833826065,-0.365472972393,10.3794908524 --12.0813770294,-0.365471810102,10.3452949524 --12.0793638229,-0.364469259977,10.2768917084 --12.0903482437,-0.364465922117,10.2204961777 --12.0833358765,-0.364463746548,10.1480884552 --12.083322525,-0.363461136818,10.0826883316 --12.0793104172,-0.363458812237,10.0142869949 --12.0772972107,-0.362456351519,9.94788455963 --12.0482978821,-0.36245688796,9.8916759491 --12.0602817535,-0.361453592777,9.83727741241 --12.054268837,-0.361451417208,9.76786994934 --12.0532569885,-0.360448986292,9.70447349548 --12.0502433777,-0.360446661711,9.63907337189 --12.0492305756,-0.360444277525,9.57567310333 --12.0362205505,-0.359442561865,9.50226402283 --12.026216507,-0.359441906214,9.46306037903 --12.0172052383,-0.358439952135,9.39365386963 --12.0291900635,-0.358436882496,9.34226131439 --12.0321760178,-0.358434289694,9.2828578949 --11.979174614,-0.357434898615,9.18144607544 --11.9671640396,-0.356433153152,9.11103630066 --11.9591598511,-0.356432437897,9.07583999634 --11.9631462097,-0.355429828167,9.01843643188 --11.9951257706,-0.355425715446,8.98203849792 --11.988114357,-0.355423808098,8.91763782501 --11.9921016693,-0.355421334505,8.86224365234 --12.1810455322,-0.35740929842,8.94289207458 --5.56448698044,-0.273744642735,3.997579813 --11.9600820541,-0.354418426752,8.7204284668 --5.57146787643,-0.273737847805,3.97517156601 --5.58444833755,-0.273730933666,3.95777368546 --11.956038475,-0.352410793304,8.51401805878 --11.9740219116,-0.35240778327,8.4706287384 --11.9590129852,-0.352406322956,8.40221977234 --11.951002121,-0.351404547691,8.33981609344 --11.9479961395,-0.351403623819,8.30961704254 --11.9419851303,-0.351401746273,8.24820804596 --11.9389734268,-0.350399792194,8.18980407715 --11.9329624176,-0.350398004055,8.13040542603 --11.9259519577,-0.350396245718,8.07000255585 --11.9239387512,-0.349394232035,8.01259613037 --11.9229269028,-0.349392265081,7.95719671249 --11.9189224243,-0.349391430616,7.92699480057 --11.9069128036,-0.348389953375,7.86459255219 --11.8889036179,-0.348388701677,7.79818582535 --11.8808937073,-0.34738701582,7.73777484894 --11.872882843,-0.347385406494,7.67937707901 --11.877869606,-0.347383260727,7.6289768219 --11.8738584518,-0.34638145566,7.57257127762 --11.8588552475,-0.34638106823,7.53636693954 --11.8588428497,-0.346379190683,7.48397016525 --11.858830452,-0.345377296209,7.43056440353 --11.8528203964,-0.345375657082,7.37416124344 --11.851808548,-0.345373868942,7.32176446915 --11.8547964096,-0.345371931791,7.27136325836 --11.8357934952,-0.344371646643,7.2331533432 --11.833782196,-0.344369888306,7.17974853516 --11.7937784195,-0.343369424343,7.10333204269 --11.6947860718,-0.342370808125,6.99290704727 --11.6977729797,-0.342368841171,6.94350147247 --11.6897630692,-0.341367274523,6.88809585571 --11.6907510757,-0.341365456581,6.8386964798 --11.6847467422,-0.341364771128,6.8104968071 --11.7237272263,-0.3413618505,6.78310441971 --11.7947015762,-0.341358155012,6.774725914 --11.8116865158,-0.341356039047,6.73432779312 --11.8126745224,-0.34135439992,6.68492603302 --11.8056640625,-0.34135299921,6.63152503967 --11.8056526184,-0.34135144949,6.58212471008 --11.7926502228,-0.340350985527,6.54991817474 --11.7926387787,-0.340349435806,6.50051546097 --11.7916269302,-0.34034794569,6.45111513138 --11.7916154861,-0.340346425772,6.40170907974 --11.8036022186,-0.340344697237,6.36031770706 --11.8305864334,-0.340342640877,6.32592058182 --11.9165582657,-0.340339481831,6.32354450226 --11.9935388565,-0.341337233782,6.3403673172 --12.0615158081,-0.342334657907,6.32799005508 --12.1324920654,-0.342332154512,6.31661224365 --12.2624578476,-0.343328744173,6.33625745773 --12.2724437714,-0.34332755208,6.29085063934 --12.2354402542,-0.343327224255,6.22243881226 --12.2964191437,-0.343325316906,6.20506095886 --12.3474054337,-0.344324052334,6.20688056946 --12.3183994293,-0.343323647976,6.1424665451 --12.4833593369,-0.345320522785,6.17611694336 --12.3433742523,-0.343321681023,6.05767822266 --19.2161560059,-0.420237183571,9.41661167145 --12.3073348999,-0.342318713665,5.82085466385 --12.297326088,-0.341318130493,5.76845312119 --12.303314209,-0.341317415237,5.72305107117 --12.3013048172,-0.341316789389,5.67465114594 --12.4992609024,-0.343314826488,5.71931600571 --12.3112878799,-0.34131577611,5.60704517365 --14.8348474503,-0.368302851915,6.66712188721 --14.7668514252,-0.367304503918,6.57970046997 --14.6998538971,-0.366306126118,6.49327802658 --14.6208591461,-0.365307658911,6.40184926987 --14.5548620224,-0.364309102297,6.3174290657 --14.4698724747,-0.363309890032,6.25219726562 --14.4018754959,-0.362311184406,6.1677737236 --14.3158826828,-0.361312389374,6.07634401321 --14.2738819122,-0.360313534737,6.0049328804 --14.2108831406,-0.36031460762,5.92451000214 --14.137887001,-0.359315633774,5.84008073807 --14.0788888931,-0.358316540718,5.76366758347 --14.0008974075,-0.357316821814,5.70443534851 --13.9199028015,-0.356317549944,5.61900615692 --11.6792316437,-0.331305772066,4.60840845108 --11.666223526,-0.331305027008,4.56000089645 --11.6742124557,-0.330304414034,4.51959609985 --11.6732025146,-0.330303788185,4.47720241547 --11.6621999741,-0.330303370953,4.45099258423 --11.6631908417,-0.330302804708,4.40858983994 --11.6611804962,-0.330302208662,4.36518716812 --11.6561717987,-0.330301612616,4.32078313828 --11.6591615677,-0.329301118851,4.27938079834 --11.6601524353,-0.329300671816,4.23798370361 --11.6571426392,-0.329300135374,4.19457960129 --11.65213871,-0.329299837351,4.17137432098 --11.6451301575,-0.329299300909,4.12697124481 --11.6491212845,-0.329298973083,4.08657073975 --11.6381130219,-0.328298389912,4.04116773605 --11.6381034851,-0.328298002481,3.99976873398 --11.6320953369,-0.328297555447,3.95535755157 --11.6270914078,-0.328297287226,3.93315768242 --11.6360807419,-0.328297168016,3.89475774765 --11.6320724487,-0.328296810389,3.85235762596 --11.6270637512,-0.328296452761,3.80894899368 --11.6210546494,-0.327296078205,3.76554226875 --11.6200466156,-0.327295839787,3.72413945198 --11.6210374832,-0.327295690775,3.68374013901 --11.6190328598,-0.327295571566,3.66253709793 --11.5260372162,-0.326293110847,3.59210467339 --11.4830331802,-0.325291782618,3.53768372536 --11.4850234985,-0.325291603804,3.49828386307 --11.4870147705,-0.325291484594,3.45888328552 --11.4850063324,-0.325291275978,3.41848301888 --11.4819974899,-0.325291067362,3.37707424164 --11.4799938202,-0.325290948153,3.35687613487 --11.473985672,-0.325290679932,3.31547403336 --11.4729766846,-0.324290603399,3.27506732941 --11.4779672623,-0.324290722609,3.23666501045 --11.4679603577,-0.324290394783,3.19425988197 --11.4749507904,-0.324290633202,3.15686130524 --11.4789419174,-0.324290812016,3.11845946312 --11.4549407959,-0.324290007353,3.09225201607 --11.4539318085,-0.324290037155,3.0528512001 --11.4559230804,-0.324290215969,3.01445221901 --11.4509162903,-0.323290139437,2.97303843498 --11.4529075623,-0.323290348053,2.9346382618 --11.4588985443,-0.323290765285,2.89723849297 --11.4358930588,-0.32329005003,2.85283303261 --11.4438886642,-0.323290467262,2.83563661575 --11.4458799362,-0.323290795088,2.79723405838 --11.4318733215,-0.323290467262,2.7548251152 --11.4598617554,-0.323291987181,2.72343635559 --11.4378557205,-0.322291374207,2.67902231216 --11.3948526382,-0.322289764881,2.62959885597 --11.4128427505,-0.322290927172,2.59621024132 --11.4538345337,-0.322293043137,2.58702754974 --11.4768247604,-0.323294579983,2.55363106728 --11.5048141479,-0.323296427727,2.52123594284 --11.5438022614,-0.323298931122,2.4918513298 --11.5637931824,-0.323300540447,2.45745396614 --11.5687856674,-0.323301464319,2.42005467415 --11.4967842102,-0.322298377752,2.36562204361 --11.4767827988,-0.322297662497,2.34241580963 --11.6787557602,-0.324309200048,2.34709215164 --11.7307443619,-0.325312912464,2.31971645355 --11.7467355728,-0.325314730406,2.28432321548 --11.7837247849,-0.325317829847,2.25293588638 --11.8067169189,-0.325320243835,2.21854329109 --11.8417062759,-0.325323402882,2.18615269661 --11.8597011566,-0.326325088739,2.16995763779 --11.8976917267,-0.326328545809,2.13857579231 --11.9266834259,-0.326331585646,2.10518908501 --11.9636735916,-0.326335221529,2.0728020668 --12.0216617584,-0.327340304852,2.0434179306 --12.0346546173,-0.32734259963,2.00702905655 --12.0676488876,-0.327345490456,1.99283850193 --12.1276378632,-0.328351020813,1.96345889568 --12.1656284332,-0.32835522294,1.93007111549 --12.1976213455,-0.328359097242,1.89669311047 --12.2316122055,-0.329363256693,1.86230456829 --12.2696037292,-0.329367786646,1.82791244984 --12.3075962067,-0.329372376204,1.7945330143 --12.3345918655,-0.330375313759,1.77833998203 --12.3725833893,-0.330380111933,1.74395370483 --12.3995761871,-0.330384165049,1.70857155323 --12.4535675049,-0.331390380859,1.67619287968 --12.4725608826,-0.331394135952,1.63779246807 --12.5695495605,-0.33240377903,1.61143708229 --12.6445398331,-0.332412004471,1.58106827736 --12.6885356903,-0.333416670561,1.56688976288 --12.7375278473,-0.333423167467,1.53251123428 --12.7695207596,-0.334428429604,1.49512052536 --12.8075141907,-0.334434300661,1.45873630047 --12.8465089798,-0.33444032073,1.42235338688 --12.9035005569,-0.335447967052,1.38797938824 --12.9264965057,-0.335452973843,1.34858345985 --12.9744911194,-0.335458517075,1.33340501785 --12.9944868088,-0.336463421583,1.29401409626 --13.0554800034,-0.336471915245,1.25863778591 --13.0934743881,-0.336478531361,1.22125887871 --13.1414690018,-0.337486177683,1.18387699127 --13.16746521,-0.337491989136,1.14448952675 --13.2014598846,-0.337498664856,1.10509967804 --13.2394561768,-0.33850389719,1.0879201889 --13.3074502945,-0.338513851166,1.05154812336 --13.3364467621,-0.339520305395,1.01216685772 --13.3544435501,-0.339525908232,0.970771849155 --13.4044389725,-0.339534580708,0.932395875454 --13.4614343643,-0.340544104576,0.894021093845 --13.5024309158,-0.340550214052,0.874831497669 --13.5164299011,-0.340555727482,0.833443760872 --13.575425148,-0.341565847397,0.794066429138 --13.6104221344,-0.341573655605,0.753687143326 --13.6684188843,-0.342584013939,0.71330678463 --13.6794166565,-0.342589646578,0.670916080475 --13.6404161453,-0.341590255499,0.6255017519 --12.3604516983,-0.328462451696,0.510502696037 --12.3104515076,-0.328458875418,0.488280624151 --13.8684062958,-0.344625979662,0.527599394321 --13.912405014,-0.34463557601,0.48622572422 --12.3494405746,-0.328473001719,0.372090905905 --12.1514425278,-0.326454937458,0.325607568026 --12.099439621,-0.326452553272,0.284173637629 --12.0044393539,-0.325445264578,0.242731541395 --12.025437355,-0.32544913888,0.224542528391 --12.4004278183,-0.329494446516,0.197313085198 --12.1114292145,-0.326465427876,0.149772942066 --12.152425766,-0.326473504305,0.112391896546 --12.2114229202,-0.327483773232,0.0750184431672 --12.1944198608,-0.327485412359,0.0356057025492 --12.1464185715,-0.32648152113,0.0163917727768 --12.1454162598,-0.326485067606,-0.0230186935514 --12.1164140701,-0.326485186815,-0.0614291988313 --12.3684101105,-0.328519195318,-0.0987159535289 --12.2704086304,-0.32751122117,-0.138162270188 --12.6784057617,-0.332565248013,-0.177372127771 --12.2844047546,-0.328520745039,-0.215956360102 --12.284403801,-0.328522711992,-0.235153913498 --12.4044017792,-0.329541862011,-0.275502234697 --12.2804002762,-0.327530384064,-0.313967496157 --14.87541008,-0.354866594076,-0.388101667166 --12.2213964462,-0.32753098011,-0.390796840191 --12.3203954697,-0.328547924757,-0.431145638227 --12.0643911362,-0.325518637896,-0.464674681425 --12.0293903351,-0.325516015291,-0.482891470194 --12.0103874207,-0.325517445803,-0.520299196243 --12.0393867493,-0.325525403023,-0.559690117836 --12.1463861465,-0.326544076204,-0.602043926716 --11.9233818054,-0.324517905712,-0.632556796074 --12.2593860626,-0.327568233013,-0.683790802956 --12.1343832016,-0.326555371284,-0.717252790928 --12.293384552,-0.328579694033,-0.743371367455 --12.0953798294,-0.326556444168,-0.772869884968 --12.4273862839,-0.329608082771,-0.829114079475 --12.4913873672,-0.330622136593,-0.872486710548 --12.199379921,-0.327584952116,-0.895029306412 --12.2073793411,-0.327590793371,-0.934427261353 --12.1833782196,-0.327592045069,-0.971841096878 --12.4113845825,-0.329627990723,-1.00592494011 --12.5643892288,-0.331655830145,-1.05625164509 --12.7433958054,-0.332688003778,-1.10956668854 --16.0325183868,-0.367190927267,-1.39729678631 --13.1104125977,-0.33675506711,-1.2191785574 --13.0664110184,-0.336754441261,-1.25760281086 --13.06341362,-0.336760103703,-1.29900419712 --16.3155536652,-0.370269030333,-1.60054302216 --16.3195610046,-0.37027990818,-1.65293824673 --16.4025726318,-0.371303468943,-1.71329712868 --16.4705848694,-0.372324675322,-1.7716550827 --16.5215930939,-0.372343629599,-1.83003115654 --16.586605072,-0.373364895582,-1.88939380646 --16.6686191559,-0.374389141798,-1.95074546337 --16.733625412,-0.374405443668,-1.98491442204 --16.7896385193,-0.375425815582,-2.04427909851 --16.8566513062,-0.376448303461,-2.1056406498 --16.9166641235,-0.376469939947,-2.16700863838 --16.9896774292,-0.377493798733,-2.22936224937 --17.0666923523,-0.378518819809,-2.2937207222 --17.1377086639,-0.379543095827,-2.35808420181 --17.1937179565,-0.379558682442,-2.39224910736 --17.2537307739,-0.380581408739,-2.45561528206 --17.3317470551,-0.381607562304,-2.52197265625 --17.4057636261,-0.382633060217,-2.58732509613 --17.489780426,-0.383660852909,-2.65567994118 --17.5467967987,-0.383683949709,-2.72004389763 --15.0856132507,-0.358249366283,-2.39155721664 --15.1156234741,-0.359264701605,-2.44494056702 --15.150633812,-0.359281122684,-2.49932146072 --15.1786432266,-0.360296398401,-2.55270457268 --15.1696510315,-0.360304892063,-2.60010433197 --15.2246627808,-0.360325485468,-2.65847539902 --15.3256807327,-0.361354887486,-2.72482180595 --14.9076471329,-0.357281655073,-2.68024492264 --14.489616394,-0.353212654591,-2.65786719322 --14.182595253,-0.350163817406,-2.65243411064 --14.178601265,-0.350172281265,-2.69783401489 --14.192609787,-0.350184231997,-2.7462220192 --14.1866149902,-0.350192517042,-2.79162526131 --14.2356281281,-0.35121178627,-2.84800505638 --14.1246194839,-0.350194692612,-2.85026264191 --13.9496088028,-0.348169445992,-2.86275243759 --13.8976097107,-0.347168534994,-2.89918637276 --13.9016160965,-0.348178654909,-2.94558286667 --13.8886222839,-0.347185462713,-2.98899197578 --14.1056537628,-0.350238978863,-3.07826685905 --14.1196622849,-0.350251883268,-3.12866711617 --14.0956640244,-0.350251883268,-3.14687895775 --13.5796108246,-0.345154941082,-3.08456420898 --13.4356002808,-0.343134045601,-3.09803843498 --13.3305940628,-0.342121094465,-3.11949443817 --13.4216127396,-0.343149363995,-3.18384385109 --13.48462677,-0.344172149897,-3.24321436882 --13.2956094742,-0.342140972614,-3.24471616745 --13.0425815582,-0.340091228485,-3.20905852318 --13.3336248398,-0.343163073063,-3.32029700279 --13.1796112061,-0.341138958931,-3.32878541946 --13.1526145935,-0.341142207384,-3.36619853973 --13.4126577377,-0.344208866358,-3.47345399857 --13.3246526718,-0.343198984861,-3.49690413475 --13.6137008667,-0.346273392439,-3.61414504051 --13.5496959686,-0.346264183521,-3.62138438225 --13.3776788712,-0.344235301018,-3.62287783623 --12.9586257935,-0.340149968863,-3.56051850319 --13.052646637,-0.341180860996,-3.62886571884 --13.1326665878,-0.342208862305,-3.69422078133 --13.0676651001,-0.341203600168,-3.72166085243 --13.0066633224,-0.341199010611,-3.74909186363 --12.910651207,-0.340181410313,-3.7453494072 --12.9336633682,-0.340196460485,-3.79573774338 --12.9416713715,-0.340208083391,-3.84213399887 --12.8076581955,-0.339185923338,-3.84861207008 --12.6866455078,-0.338166356087,-3.85707521439 --12.855682373,-0.340216964483,-3.95038628578 --12.7016639709,-0.33818924427,-3.94887042046 --12.6886663437,-0.338190972805,-3.96708011627 --12.9397172928,-0.341262340546,-4.08533287048 --12.8547105789,-0.340251624584,-4.10478639603 --12.9357337952,-0.341282010078,-4.17414188385 --12.9657487869,-0.341299951077,-4.22852754593 --12.967757225,-0.342310875654,-4.27392435074 --13.0587797165,-0.343339174986,-4.32507228851 --13.1908140182,-0.344383776188,-4.41340446472 --13.0467967987,-0.343357861042,-4.41288518906 --13.012799263,-0.343359977007,-4.44730377197 --13.1268320084,-0.344400584698,-4.53064155579 --13.3308820724,-0.346464931965,-4.64391899109 --13.2278728485,-0.345449507236,-4.65638017654 --13.3749074936,-0.347494065762,-4.72949695587 --13.4689378738,-0.348530858755,-4.80884361267 --13.2048959732,-0.345472425222,-4.76539564133 --13.1769018173,-0.345476716757,-4.80281543732 --13.3679533005,-0.347540169954,-4.91710758209 --13.0879039764,-0.345476061106,-4.86466598511 --17.4568538666,-0.393682539463,-6.47547340393 --17.4248580933,-0.392683207989,-6.49468803406 --17.3578662872,-0.392684072256,-6.53312778473 --17.410900116,-0.39371791482,-6.61449098587 --17.3409080505,-0.392717719078,-6.65092849731 --17.2939186096,-0.392724096775,-6.69635677338 --17.1859169006,-0.391712993383,-6.71781778336 --17.1299266815,-0.391716331244,-6.75824546814 --17.1839637756,-0.391751378775,-6.84161329269 --26.0270557404,-0.490300238132,-10.2894144058 --26.1931419373,-0.492383211851,-10.4486999512 --17.2720680237,-0.393846422434,-7.0959482193 --17.2650909424,-0.393864542246,-7.15634870529 --26.8214874268,-0.50171226263,-11.0858640671 --27.6767272949,-0.510984659195,-11.4825277328 --26.5955047607,-0.499700635672,-11.1405820847 --26.2364635468,-0.495630055666,-11.0901918411 --25.5393333435,-0.488456517458,-10.8970165253 --25.6974239349,-0.490540295839,-11.0583057404 --25.9325332642,-0.493648350239,-11.2535467148 --25.3184223175,-0.487496435642,-11.0873193741 --22.1636009216,-0.451541244984,-9.7764787674 --22.0516109467,-0.450536817312,-9.81094074249 --21.9186153412,-0.449525535107,-9.83541488647 --25.0775241852,-0.485547244549,-11.312828064 --24.9925518036,-0.485556840897,-11.3702716827 --21.2905597687,-0.443417280912,-9.80198669434 --16.8063259125,-0.39301481843,-7.85218954086 --16.7583255768,-0.392010122538,-7.86241865158 --16.7233409882,-0.392020016909,-7.90983390808 --16.6813564301,-0.39202773571,-7.95425605774 --16.6493740082,-0.392038851976,-8.00367450714 --16.6273937225,-0.39205339551,-8.05808925629 --16.5994110107,-0.392065614462,-8.10850048065 --16.5954380035,-0.392086356878,-8.17190647125 --21.6229801178,-0.45076918602,-10.6149148941 --21.350938797,-0.447709798813,-10.5674800873 --21.2089366913,-0.446693480015,-10.5819654465 --21.544084549,-0.450837910175,-10.8291416168 --21.4250888824,-0.449829399586,-10.8546094894 --21.4221324921,-0.449860572815,-10.9380064011 --24.4381465912,-0.485931187868,-12.5394592285 --24.3561458588,-0.484922170639,-12.546708107 --24.2661705017,-0.483929038048,-12.5971546173 --24.1721916199,-0.48393458128,-12.645606041 --23.4049892426,-0.474703401327,-12.3454914093 --26.4580669403,-0.511819422245,-14.0299053192 --22.5247955322,-0.465464770794,-12.0708408356 --22.4538192749,-0.465475171804,-12.1242790222 --22.5568790436,-0.466529995203,-12.2244081497 --26.0991592407,-0.50884282589,-14.2104921341 --22.3188972473,-0.464516162872,-12.2793464661 --22.4569950104,-0.466602653265,-12.445649147 --22.2499732971,-0.465563237667,-12.4241752625 --22.2960395813,-0.466616779566,-12.5415391922 --22.1120243073,-0.464585125446,-12.5310506821 --21.9529914856,-0.462544292212,-12.4883518219 --25.8054580688,-0.509021162987,-14.7422094345 --21.9250812531,-0.46360629797,-12.6541519165 --21.8931217194,-0.463630914688,-12.7275648117 --21.8151435852,-0.462638229132,-12.7750110626 --21.7861843109,-0.463663816452,-12.8494195938 --22.1373691559,-0.467835813761,-13.1455783844 --22.5645618439,-0.473019748926,-13.4424934387 --22.3935508728,-0.47199228406,-13.43699646 --22.7217330933,-0.476159363985,-13.7271709442 --22.8338356018,-0.478243380785,-13.8914880753 --23.4921550751,-0.486543536186,-14.3854408264 --23.2010974884,-0.483470082283,-14.3100252151 --24.1385383606,-0.495885670185,-14.9817867279 --23.9895095825,-0.493848145008,-14.9430837631 --23.6554355621,-0.490757763386,-14.8416986465 --23.2293186188,-0.486628353596,-14.6793708801 --17.5930213928,-0.417378246784,-11.2575445175 --17.9202003479,-0.421542495489,-11.5417251587 --23.6496829987,-0.492930233479,-15.2522602081 --35.40574646,-0.638803243637,-22.7834949493 --35.4428710938,-0.640890300274,-22.963848114 --35.499004364,-0.641986191273,-23.1581897736 --35.4540901184,-0.642040133476,-23.2875976562 --35.6412849426,-0.646192133427,-23.5688476562 --35.5773658752,-0.646239519119,-23.6882724762 --35.1923065186,-0.642149031162,-23.5929107666 --35.1503410339,-0.642168045044,-23.6451301575 --35.1734619141,-0.643251895905,-23.8204917908 --15.6436796188,-0.398933827877,-10.9570274353 --15.5726852417,-0.397930622101,-10.980471611 --15.7378025055,-0.401031911373,-11.1677589417 --15.6007566452,-0.398985415697,-11.1090507507 --15.882932663,-0.403139591217,-11.3792533875 --41.6154403687,-0.733711004257,-29.5808620453 --41.4444999695,-0.73272806406,-29.6563510895 --41.3686065674,-0.732787847519,-29.7987766266 --41.3567466736,-0.733876883984,-29.9871578217 --41.249835968,-0.733923375607,-30.1086063385 --41.2789230347,-0.734984338284,-30.2287731171 --42.5207023621,-0.751654207706,-31.334274292 --42.2066917419,-0.749607563019,-31.3088665009 --42.2428627014,-0.750723481178,-31.5402107239 --41.8608169556,-0.747643887997,-31.46185112 --42.026058197,-0.750822126865,-31.7921085358 --41.0827178955,-0.739474236965,-31.2871437073 --41.0837898254,-0.740523934364,-31.3893280029 --41.1179618835,-0.742639183998,-31.6186752319 --41.1031074524,-0.743732154369,-31.8130607605 --41.3073730469,-0.74793189764,-32.1772880554 --40.6521720886,-0.739713609219,-31.875125885 --40.5192527771,-0.739748775959,-31.9765911102 --40.5354194641,-0.7418577075,-32.1959533691 --40.5314941406,-0.741906344891,-32.2961425781 --40.3165283203,-0.740901112556,-32.3326683044 --40.17760849,-0.739933490753,-32.4291381836 --40.1907730103,-0.742042064667,-32.6475067139 --40.1799278259,-0.743139982224,-32.8488883972 --40.08203125,-0.743193268776,-32.9783287048 --40.0611839294,-0.744286835194,-33.1727180481 --32.8940582275,-0.647664368153,-27.3730487823 --32.8791770935,-0.64874112606,-27.5354404449 --40.047580719,-0.74754178524,-33.6916618347 --31.5586490631,-0.633223176003,-26.7781562805 --30.6812438965,-0.621845126152,-26.2061691284 --30.6393413544,-0.622903108597,-26.3365821838 --30.4433479309,-0.620879948139,-26.3361091614 --30.760602951,-0.626088440418,-26.6910686493 --30.4475364685,-0.623003005981,-26.589679718 --30.4146404266,-0.623066723347,-26.7290878296 --30.4127655029,-0.625147104263,-26.8954696655 --30.6790618896,-0.629374265671,-27.299659729 --29.9667358398,-0.621068716049,-26.8405609131 --29.9758701324,-0.622155547142,-27.0169372559 --30.1170253754,-0.62527513504,-27.2290287018 --29.9890708923,-0.624287426472,-27.2845039368 --29.7950744629,-0.622262835503,-27.2800292969 --29.5880661011,-0.621230959892,-27.2635688782 --29.4961357117,-0.621262609959,-27.3500175476 --29.5312900543,-0.622366607189,-27.5543785095 --28.8759117126,-0.61403554678,-27.0320472717 --28.712928772,-0.613025128841,-27.0495529175 --29.0673027039,-0.619311988354,-27.5516777039 --29.1935214996,-0.622469902039,-27.8439693451 --29.2997303009,-0.625617444515,-28.1192760468 --29.1447563171,-0.624613344669,-28.146774292 --29.2329559326,-0.626752197742,-28.4080944061 --28.5795612335,-0.618410885334,-27.866771698 --28.6027107239,-0.61950981617,-28.0621376038 --28.4407310486,-0.618499994278,-28.0796432495 --28.8120632172,-0.63439822197,-29.8042526245 --28.9524669647,-0.639673709869,-30.3239173889 --29.066783905,-0.642889142036,-30.7284069061 --38.4573707581,-0.788986682892,-40.8166809082 --38.3254776001,-0.789034187794,-40.9331512451 --38.2696418762,-0.790130317211,-41.1295700073 --28.3208007812,-0.637795865536,-30.7055130005 --28.1698322296,-0.636793673038,-30.7340106964 --28.5032615662,-0.644110560417,-31.2901439667 --37.7251663208,-0.790378510952,-41.7086753845 --28.3285121918,-0.645243823528,-31.5912399292 --27.9805393219,-0.642210781574,-31.600276947 --26.1891651154,-0.616094827652,-29.7820339203 --35.192199707,-0.76140576601,-40.2966918945 --26.3586921692,-0.622449874878,-30.4478740692 --26.305803299,-0.622510552406,-30.5793037415 --26.1898574829,-0.622527360916,-30.6377773285 --35.7077484131,-0.78044128418,-42.1931800842 --35.5278129578,-0.780453979969,-42.2496986389 --35.5229187012,-0.781520009041,-42.3768882751 --35.6232376099,-0.784732818604,-42.7661895752 --24.5001754761,-0.603860855103,-29.6942214966 --24.5723972321,-0.60600912571,-29.9705543518 --24.6065864563,-0.608130931854,-30.202917099 --24.4095554352,-0.607084274292,-30.154460907 --24.3276348114,-0.607121646404,-30.2459125519 --24.3106975555,-0.607158005238,-30.3211212158 --24.3218669891,-0.609264850616,-30.5284996033 --24.1908988953,-0.609266340733,-30.5599899292 --23.6645469666,-0.601970374584,-30.0947952271 --23.3423862457,-0.597824335098,-29.8794384003 --23.2014026642,-0.596814274788,-29.8909378052 --23.0794410706,-0.596819579601,-29.9284267426 --23.116558075,-0.597896814346,-30.0715904236 --24.3900108337,-0.621982872486,-31.9169769287 --23.0518131256,-0.600045740604,-30.3774242401 --23.315246582,-0.606352806091,-30.9196052551 --22.0721225739,-0.586475133896,-29.47797966 --22.023229599,-0.587534070015,-29.6044082642 --21.9952793121,-0.587560653687,-29.6626262665 --21.9203605652,-0.587599873543,-29.7560787201 --21.8614578247,-0.588651657104,-29.8705177307 --22.374174118,-0.599168121815,-30.7645015717 --22.1691207886,-0.597104370594,-30.6850547791 --22.2073307037,-0.59923940897,-30.9394168854 --22.0212955475,-0.598190546036,-30.8849563599 --21.6110095978,-0.591953873634,-30.5146770477 --21.0274429321,-0.582518219948,-29.796339035 --21.2718830109,-0.588825285435,-30.3395366669 --21.219991684,-0.589884996414,-30.4669685364 --21.0419597626,-0.58783775568,-30.4145050049 --20.8168716431,-0.585750043392,-30.2940788269 --20.8901252747,-0.588916838169,-30.6014118195 --20.8281383514,-0.588915586472,-30.6126556396 --22.1588764191,-0.615179717541,-32.7679748535 --21.946811676,-0.613108634949,-32.6755409241 --14.1306753159,-0.46733585,-21.2922458649 --14.1057596207,-0.467384397984,-21.3976631165 --13.9156455994,-0.465286403894,-21.2562160492 --21.4079170227,-0.61108982563,-32.7525405884 --21.6703338623,-0.617384195328,-33.2625274658 --17.9158840179,-0.546095728874,-27.741973877 --21.357334137,-0.615336120129,-33.2355651855 --21.1172294617,-0.612234652042,-33.0911521912 --20.8641033173,-0.609119534492,-32.9237518311 --20.8943386078,-0.612265646458,-33.1971168518 --20.6331996918,-0.609140694141,-33.0127220154 --18.1520881653,-0.560865700245,-29.1819534302 --18.0301017761,-0.559855520725,-29.1904506683 --15.9615545273,-0.519987523556,-26.0575428009 --15.8816003799,-0.520003497601,-26.1090049744 --15.6965055466,-0.517917871475,-25.9885540009 --15.6215591431,-0.517939090729,-26.0490169525 --15.4925374985,-0.516906142235,-26.0175189972 --15.459569931,-0.516920924187,-26.0547466278 --15.305513382,-0.515863180161,-25.9812717438 --15.2185497284,-0.515871524811,-26.0197429657 --15.6322832108,-0.526380956173,-26.9067955017 --15.598400116,-0.52744692564,-27.0432262421 --15.4042882919,-0.525349199772,-26.9017829895 --15.3814210892,-0.526425898075,-27.0562019348 --25.9677658081,-0.7533659935,-45.6185684204 --25.5474529266,-0.747109234333,-45.212310791 --17.2646045685,-0.571645498276,-30.8826274872 --17.1165790558,-0.570607483387,-30.8431434631 --14.9996204376,-0.526486575603,-27.2683124542 --14.8936328888,-0.525477409363,-27.2767982483 --13.6838912964,-0.500236034393,-25.1810112 --16.7016487122,-0.568582653999,-30.8888816833 --16.6047000885,-0.56859767437,-30.9393596649 --16.5367946625,-0.569644510746,-31.0438117981 --16.524980545,-0.570753633976,-31.2542190552 --13.2019433975,-0.498191863298,-25.2234134674 --13.088927269,-0.497164189816,-25.1999111176 --12.6844396591,-0.489807009697,-24.615650177 --13.2324037552,-0.503474235535,-25.7623901367 --13.1073684692,-0.502433657646,-25.7168960571 --13.1616277695,-0.505598068237,-26.0202503204 --12.7911863327,-0.498273432255,-25.4909629822 --14.2367734909,-0.535059034824,-28.5551395416 --13.8242721558,-0.526691317558,-27.9528884888 --13.8313789368,-0.52775657177,-28.076084137 --16.0393466949,-0.583491444588,-32.7595977783 --12.3632307053,-0.497232407331,-25.5261306763 --5.6126537323,-0.335204750299,-11.8611984253 --5.57966518402,-0.335207790136,-11.8866386414 --5.55769586563,-0.335223823786,-11.9340639114 --5.53071784973,-0.33523401618,-11.9714956284 --5.46570682526,-0.335219115019,-11.9761610031 --5.47379302979,-0.336273699999,-12.0895643234 --5.41976737976,-0.336250960827,-12.0710220337 --5.43286418915,-0.337312221527,-12.1954126358 --12.1756467819,-0.512048721313,-27.1411056519 --12.2990808487,-0.517327785492,-27.6414012909 --12.2671222687,-0.517346739769,-27.685628891 --15.3262338638,-0.599494040012,-34.7963829041 --11.9108400345,-0.51211977005,-27.3447399139 --11.746720314,-0.510021626949,-27.2002811432 --11.8381080627,-0.515267074108,-27.6436061859 --11.6779966354,-0.513174116611,-27.508146286 --11.6170845032,-0.514215648174,-27.602602005 --11.5723114014,-0.51634323597,-27.8562412262 --11.3861408234,-0.513210713863,-27.6528053284 --12.4425764084,-0.544833242893,-30.4542865753 --12.3626499176,-0.545863747597,-30.5307598114 --12.2676916122,-0.54587161541,-30.5682411194 --12.2056827545,-0.544855356216,-30.5524978638 --10.8439693451,-0.509017169476,-27.4270915985 --9.6846446991,-0.477443546057,-24.7535095215 --9.5926399231,-0.477425277233,-24.7449932098 --9.48460006714,-0.476383060217,-24.6954936981 --9.38557815552,-0.476353675127,-24.6679859161 --9.28254413605,-0.475316286087,-24.6264762878 --9.22651767731,-0.474291115999,-24.5947303772 --9.12749290466,-0.474260002375,-24.5642223358 --9.01142692566,-0.472200989723,-24.4857311249 --8.90738773346,-0.472160041332,-24.4382266998 --8.8203868866,-0.471144765615,-24.4347076416 --8.73940086365,-0.471138834953,-24.4471817017 --8.66543197632,-0.471145004034,-24.4806537628 --8.6314535141,-0.471151977777,-24.5038833618 --7.60510730743,-0.441591501236,-21.8451957703 --7.47096204758,-0.439482778311,-21.6807250977 --7.46012496948,-0.440577238798,-21.8651390076 --10.6285057068,-0.547062933445,-31.3197250366 --7.1276512146,-0.434241503477,-21.3322467804 --7.05565500259,-0.434231221676,-21.3367176056 --7.03369283676,-0.434249967337,-21.3799381256 --6.96771192551,-0.434250146151,-21.4024047852 --6.88869571686,-0.434227108955,-21.3848800659 --6.85781097412,-0.435290008783,-21.5153160095 --6.76375484467,-0.434240698814,-21.4528102875 --6.70479488373,-0.434254139662,-21.4982719421 --6.64984416962,-0.435273587704,-21.5537223816 --9.90228748322,-0.552389204502,-32.1010017395 --6.50674819946,-0.433192431927,-21.4474658966 --6.20327377319,-0.426861047745,-20.9205493927 --6.12926292419,-0.426842033863,-20.9100265503 --6.42136907578,-0.440542340279,-22.1401729584 --6.36743307114,-0.440570145845,-22.2106285095 --5.8862657547,-0.425801515579,-20.9176692963 --5.82328653336,-0.425802797079,-20.9421348572 --5.74526023865,-0.425773888826,-20.9146156311 --5.69431877136,-0.425799012184,-20.9800682068 --5.64739465714,-0.426835477352,-21.0655212402 --5.62042188644,-0.426846474409,-21.0957508087 --5.5765080452,-0.427888870239,-21.1911964417 --5.57975959778,-0.43103697896,-21.4696025848 --5.46861743927,-0.42893409729,-21.3141098022 --5.42972946167,-0.42999240756,-21.4375572205 --5.37076950073,-0.430005162954,-21.4820175171 --7.88116931915,-0.542942583561,-31.7751274109 --5.99173402786,-0.465846896172,-24.7254734039 --7.54892587662,-0.539738059044,-31.4834461212 --7.27528333664,-0.531312704086,-30.7721061707 --7.16324615479,-0.530269920826,-30.7226142883 --5.59947776794,-0.461624741554,-24.4344673157 --5.07168197632,-0.439482778311,-22.4793605804 --7.81291389465,-0.573521077633,-34.6850242615 --7.87464523315,-0.581956446171,-35.4653739929 --6.67413043976,-0.528109014034,-30.555896759 --5.96053552628,-0.496468126774,-27.7359714508 --4.94053268433,-0.448952972889,-23.3983230591 --4.86352682114,-0.448935240507,-23.3908023834 --4.78752756119,-0.448921442032,-23.3902816772 --4.75053024292,-0.448916077614,-23.3925189972 --4.68859148026,-0.448939800262,-23.4569835663 --5.11794281006,-0.476384013891,-25.9879970551 --5.05705118179,-0.477435052395,-26.1004581451 --4.93185853958,-0.475299358368,-25.8889865875 --4.38860797882,-0.448892503977,-23.4689044952 --4.31059122086,-0.447867870331,-23.449382782 --4.27560520172,-0.44786927104,-23.4636211395 --4.21869850159,-0.448912352324,-23.562084198 --4.14169454575,-0.448895454407,-23.5565681458 --4.43264579773,-0.471079558134,-25.6397018433 --4.03091144562,-0.450999766588,-23.7854919434 --4.27468729019,-0.471072763205,-25.6766719818 --3.969424963,-0.456284224987,-24.328371048 --4.44235563278,-0.49006870389,-27.4471282959 --3.8524222374,-0.45625987649,-24.322095871 --4.2965388298,-0.492145121098,-27.6300830841 --3.88053750992,-0.468908786774,-25.5008869171 --3.58721327782,-0.453087300062,-24.0935726166 --3.51926732063,-0.454105257988,-24.1490459442 --3.39974236488,-0.44777905941,-23.5923652649 --3.54318737984,-0.464640289545,-25.1186408997 --3.20443272591,-0.444562226534,-23.2623729706 --3.13344740868,-0.444556772709,-23.2768478394 --3.06649756432,-0.444572329521,-23.3283252716 --3.19093990326,-0.460427492857,-24.8456172943 --3.08573865891,-0.458290576935,-24.6311264038 --3.00874352455,-0.458277910948,-24.6336116791 --2.97780370712,-0.459306508303,-24.6958465576 --1.85443627834,-0.364268481731,-15.9142951965 --1.79031300545,-0.36318552494,-15.7917709351 --1.75543034077,-0.364246696234,-15.9212207794 --2.91194152832,-0.482521593571,-26.9205513 --2.57971429825,-0.457174599171,-24.5892791748 --2.56291794777,-0.459288090467,-24.8005046844 --2.42939090729,-0.452958166599,-24.2480430603 --2.34531450272,-0.452897310257,-24.1665363312 --2.29557657242,-0.455037474632,-24.4369983673 --2.2114880085,-0.453969329596,-24.3424854279 --2.14964842796,-0.456048727036,-24.5069599152 --2.2819890976,-0.481418460608,-26.9332427979 --2.25010800362,-0.483480155468,-27.0544776917 --2.16814732552,-0.483485400677,-27.089969635 --2.08820962906,-0.483504354954,-27.1494598389 --2.00421714783,-0.483490884304,-27.1519527435 --1.92529785633,-0.484520614147,-27.2304401398 --1.87275588512,-0.489771813154,-27.6979026794 --1.80301332474,-0.49190428853,-27.9573860168 --2.44546031952,-0.607020914555,-38.7159385681 --2.31940340996,-0.605960607529,-38.6404762268 --2.21569633484,-0.609105288982,-38.924987793 --2.09473228455,-0.60909897089,-38.944519043 --1.99413120747,-0.613304793835,-39.3370246887 --1.90075278282,-0.619639217854,-39.9565238953 --1.77985680103,-0.620671749115,-40.0450592041 --1.88667798042,-0.662878990173,-43.946144104 --1.75687336922,-0.663961291313,-44.1236801147 --1.61581134796,-0.662894070148,-44.0382347107 --1.48501980305,-0.664983510971,-44.2287712097 --1.3490998745,-0.665998518467,-44.288318634 --1.20903778076,-0.664931178093,-44.2028656006 --1.0689766407,-0.663864374161,-44.1184196472 --1.00102126598,-0.663874328136,-44.1526947021 --0.871440351009,-0.668083965778,-44.5562324524 --0.729208409786,-0.665919184685,-44.2987861633 --0.591294288635,-0.665936470032,-44.3633384705 --0.536305963993,-0.752495706081,-52.4527702332 --0.315354049206,-0.665907025337,-44.3794364929 --0.209357023239,-0.752448678017,-52.4439201355 --0.127061277628,-0.7492608428,-52.1302108765 -0.096052788198,-0.710800528526,-51.2814788818 -0.212349459529,-0.63622713089,-43.525718689 -0.350323051214,-0.636278152466,-43.5219993591 -0.48722961545,-0.63536709547,-43.4502716064 -0.625204205513,-0.635417401791,-43.4475517273 -0.764273524284,-0.636413931847,-43.5408287048 -0.834265112877,-0.63643682003,-43.5439720154 -0.974343836308,-0.638427972794,-43.6472434998 -1.085293293,-0.628056526184,-42.6015434265 -1.21922242641,-0.628131389618,-42.5518264771 -1.53978550434,-0.682037055492,-48.2449645996 -1.49535608292,-0.629126131535,-42.732383728 -1.5643774271,-0.630131483078,-42.7655220032 -1.70239984989,-0.630154132843,-42.8108062744 -1.8424808979,-0.631143629551,-42.9160842896 -1.97435736656,-0.63024777174,-42.8123703003 -2.03078365326,-0.615161061287,-41.2217178345 -2.08636784554,-0.601984024048,-39.7900695801 -2.20827627182,-0.601067364216,-39.7153625488 -2.27226781845,-0.60108846426,-39.7165107727 -2.40637540817,-0.60306096077,-39.8467979431 -2.53031516075,-0.602126955986,-39.8040924072 -2.6633784771,-0.603124260902,-39.8893814087 -2.78021812439,-0.602245330811,-39.7436828613 -2.90518307686,-0.602296829224,-39.7269744873 -3.0362136364,-0.602312326431,-39.7782669067 -3.08704471588,-0.601421535015,-39.6134262085 -3.20999622345,-0.601479947567,-39.5827178955 -3.32888507843,-0.600573301315,-39.4870223999 -3.56132555008,-0.605379521847,-39.9734268188 -3.6882891655,-0.60543191433,-39.9557228088 -3.82234144211,-0.606435239315,-40.0300102234 -3.88026952744,-0.605490744114,-39.9651603699 -4.04863166809,-0.609325528145,-40.3624191284 -4.184674263,-0.610334515572,-40.4277114868 -4.30557584763,-0.609420776367,-40.3450126648 -4.4254732132,-0.609508872032,-40.2583122253 -4.53831720352,-0.607625603676,-40.1156234741 -4.66124773026,-0.607695579529,-40.0629234314 -4.72927331924,-0.607697367668,-40.100063324 -4.85623216629,-0.607751846313,-40.0773620605 -4.98722648621,-0.607787072659,-40.0916557312 -5.11923217773,-0.608815848827,-40.1179504395 -5.29353904724,-0.612682819366,-40.4612045288 -5.48293638229,-0.616501629353,-40.9004478455 -5.61290597916,-0.616550266743,-40.8897438049 -5.47147750854,-0.602332413197,-39.3930740356 -5.5883846283,-0.601413905621,-39.3143844604 -5.70832157135,-0.60147857666,-39.2676887512 -5.79806518555,-0.599646627903,-39.0160217285 -5.86568117142,-0.595882296562,-38.6283721924 -5.9896531105,-0.595928013325,-38.6176719666 -6.04258584976,-0.595979034901,-38.5558357239 -6.17158555984,-0.596010267735,-38.5741348267 -6.30159568787,-0.596035122871,-38.6044311523 -7.37393379211,-0.652240335941,-44.3058891296 -6.55155181885,-0.59711933136,-38.5960350037 -6.68356752396,-0.59714192152,-38.6313323975 -6.799492836,-0.597212016582,-38.5706443787 -6.87253808975,-0.59820318222,-38.6287879944 -7.06285047531,-0.601069629192,-38.9820327759 -7.19586038589,-0.602095127106,-39.0123291016 -7.45951890945,-0.609780967236,-39.7375068665 -7.55935192108,-0.607899487019,-39.578830719 -7.68229627609,-0.607960045338,-39.5391426086 -7.80323457718,-0.608023166656,-39.4934501648 -7.8702340126,-0.608039259911,-39.5025978088 -8.11914157867,-0.608149826527,-39.4432106018 -8.1878490448,-0.605332195759,-39.148563385 -8.35700702667,-0.607281684875,-39.3378295898 -8.46890735626,-0.607363760471,-39.2511482239 -8.62198543549,-0.608354508877,-39.355430603 -8.70906925201,-0.609327077866,-39.4555587769 -8.75067996979,-0.605558514595,-39.0539398193 -6.19975137711,-0.489209711552,-27.2096157074 -8.87710475922,-0.600915491581,-38.4686698914 -6.18962955475,-0.477849394083,-26.0088729858 -6.26056003571,-0.477905631065,-25.9392261505 -6.29853582382,-0.477928549051,-25.9154033661 -6.37147474289,-0.476980388165,-25.854757309 -6.44341421127,-0.477031856775,-25.7941093445 -6.52137565613,-0.477072119713,-25.7574577332 -9.76669406891,-0.60035097599,-38.1640205383 -6.91313409805,-0.485728889704,-26.6009483337 -9.87436485291,-0.597562670708,-37.8315544128 -16.4120292664,-0.827246248722,-60.6440353394 -16.6039447784,-0.827335953712,-60.594291687 -8.4832649231,-0.522298276424,-30.1022949219 -17.2950210571,-0.822008550167,-59.7695999146 -16.316324234,-0.780896782875,-55.7118873596 -8.9000711441,-0.522501885891,-29.9348182678 -18.5979671478,-0.836750030518,-61.017375946 -17.0477809906,-0.779360711575,-55.2821655273 -18.0139846802,-0.80531680584,-57.7787399292 -9.345662117,-0.519833862782,-29.534740448 -18.5837841034,-0.806550383568,-57.678527832 -18.6493740082,-0.802796602249,-57.2598953247 -18.4609985352,-0.788536071777,-55.7767066956 -18.5637187958,-0.786716580391,-55.5000419617 -13.5007972717,-0.627538263798,-39.8768730164 -13.6137056351,-0.627614200115,-39.7952041626 -13.7416534424,-0.627671062946,-39.7575149536 -13.8816328049,-0.627711713314,-39.756816864 -15.1045484543,-0.662317037582,-43.0599708557 -15.3627901077,-0.666234433651,-43.3581733704 -15.0155210495,-0.651880145073,-41.9479026794 -19.3728275299,-0.772953093052,-53.6535606384 -19.5437450409,-0.773035109043,-53.5968360901 -19.4179477692,-0.765459239483,-52.7293777466 -19.5016670227,-0.762636423111,-52.44373703 -19.5996608734,-0.763659834862,-52.4548683167 -19.7836170197,-0.763721585274,-52.4421386719 -19.9590854645,-0.760057330132,-51.9078483582 -19.9445972443,-0.755329847336,-51.3852920532 -20.3680953979,-0.762134253979,-51.991355896 -20.4721012115,-0.763152241707,-52.0154800415 -20.6650791168,-0.763204813004,-52.0237464905 -20.7127342224,-0.760408222675,-51.6651420593 -20.835559845,-0.759531080723,-51.5004653931 -21.1207351685,-0.762489974499,-51.7366523743 -21.407907486,-0.766449928284,-51.9718399048 -21.0316505432,-0.742645978928,-49.4876708984 -22.9270858765,-0.786089122295,-53.4984931946 -22.1420764923,-0.762063324451,-51.2085952759 -22.2829456329,-0.76216584444,-51.0899085999 -22.4158000946,-0.761273741722,-50.9562263489 -23.4716625214,-0.785435497761,-53.137550354 -23.0454158783,-0.771051168442,-51.7263412476 -22.6833133698,-0.758600413799,-50.4760856628 -22.8151702881,-0.757706284523,-50.3444061279 -22.9490299225,-0.756810545921,-50.2167282104 -23.205121994,-0.759809195995,-50.3579483032 -23.6796131134,-0.766626238823,-50.9669837952 -23.6523685455,-0.764758110046,-50.698223114 -23.9585418701,-0.767720878124,-50.9353981018 -24.1885719299,-0.769748330116,-51.0066413879 -24.5668640137,-0.774657607079,-51.385761261 -24.7327766418,-0.774738907814,-51.3180541992 -25.322429657,-0.784485757351,-52.1249961853 -25.4492645264,-0.783603012562,-51.9663276672 -25.576292038,-0.784611821175,-52.0174407959 -25.6840991974,-0.783741056919,-51.8247871399 -18.8881587982,-0.631121575832,-37.7408866882 -26.1891975403,-0.787781238556,-52.0172386169 -29.7849674225,-0.84535574913,-56.7146644592 -30.3797149658,-0.84660756588,-56.5414962769 -30.5888442993,-0.848574995995,-56.716545105 -29.9424552917,-0.832227826118,-55.0955200195 -29.9961585999,-0.829403340816,-54.7799186707 -30.1149635315,-0.828533470631,-54.5872612 -30.2537994385,-0.828649938107,-54.4315910339 -30.4397087097,-0.828735649586,-54.3608779907 -30.6176052094,-0.828825056553,-54.278175354 -30.7536220551,-0.829840540886,-54.3192825317 -31.0176429749,-0.831877112389,-54.385509491 -38.1345787048,-0.968666672707,-66.4351272583 -23.5497512817,-0.564715445042,-25.98046875 -40.9672622681,-0.820717513561,-45.1028022766 -49.8725357056,-0.918376147747,-49.9920196533 -49.8942871094,-0.91651070118,-49.6994667053 -49.8600006104,-0.913657784462,-49.3519554138 -38.130241394,-0.748488366604,-37.5618247986 -50.3189468384,-0.917756736279,-49.3393096924 -50.4968185425,-0.917852640152,-49.2036399841 -50.7497406006,-0.918931722641,-49.1399154663 -50.8335456848,-0.918049097061,-48.9113197327 -51.1405067444,-0.920116245747,-48.8985557556 -23.1085033417,-0.532393574715,-21.7466926575 -23.1394233704,-0.532441675663,-21.6381072998 -23.1253128052,-0.530499100685,-21.4875545502 -22.9190711975,-0.527595639229,-21.1591377258 -23.1211090088,-0.529606878757,-21.2124271393 -23.2300834656,-0.529637753963,-21.1777858734 -22.9688091278,-0.525742828846,-20.8034114838 -23.0558185577,-0.525750994682,-20.8175640106 -23.1667957306,-0.526780664921,-20.7859210968 -23.0446205139,-0.523855626583,-20.5434436798 -16.006942749,-0.429251462221,-14.1009149551 -16.0038833618,-0.428283631802,-14.0083436966 -16.0328426361,-0.428309828043,-13.9437551498 -16.0157737732,-0.427344232798,-13.8391962051 -15.9126796722,-0.426378399134,-13.7044830322 -15.6374492645,-0.42145845294,-13.3761091232 -15.3902406693,-0.417531460524,-13.0767087936 -15.4762411118,-0.418545126915,-13.0660791397 -15.7413511276,-0.421527713537,-13.2093172073 -14.5885944366,-0.405752241611,-12.1445560455 -14.4805040359,-0.403783649206,-12.0128498077 -14.3233623505,-0.401834964752,-11.8033847809 -8.20963859558,-0.321872115135,-6.56945466995 -8.2166261673,-0.320880442858,-6.53286170959 -8.31665039062,-0.321883887053,-6.5286359787 -8.33565330505,-0.321885883808,-6.52184009552 -8.36765575409,-0.321890354156,-6.50523328781 -8.39965724945,-0.322895020247,-6.48763561249 -8.42165374756,-0.322901159525,-6.46204280853 -8.4476518631,-0.322906732559,-6.43944978714 -8.47665214539,-0.322911679745,-6.41984796524 -8.48964309692,-0.322918981314,-6.38726043701 -8.52365398407,-0.322918772697,-6.39244794846 -8.54264831543,-0.322925120592,-6.36485338211 -8.56064224243,-0.322931796312,-6.33527135849 -8.5836391449,-0.322937518358,-6.3106751442 -8.60863685608,-0.32294306159,-6.28708171844 -8.63763618469,-0.32294806838,-6.26648616791 -8.66564369202,-0.322948783636,-6.2666759491 -8.68764019012,-0.322954595089,-6.24108076096 -8.70163249969,-0.322961360216,-6.2094912529 -8.7236289978,-0.322967261076,-6.18290615082 -8.75362968445,-0.322971999645,-6.16330432892 -8.77562618256,-0.322977662086,-6.13770914078 -8.79061889648,-0.322984069586,-6.10711717606 -8.83263301849,-0.32398340106,-6.11630296707 -8.84362316132,-0.323990434408,-6.08172416687 -8.88262844086,-0.323994159698,-6.06811714172 -8.88861751556,-0.324001520872,-6.03053712845 -8.92562103271,-0.324005335569,-6.01592540741 -8.95762252808,-0.324009954929,-5.99633073807 -8.99662685394,-0.324013799429,-5.98172903061 -8.99061775208,-0.324018269777,-5.95694303513 -9.0216178894,-0.324022978544,-5.93635034561 -9.04861736298,-0.32402792573,-5.91375112534 -9.07461547852,-0.324033021927,-5.89015626907 -9.10961818695,-0.325037270784,-5.87255525589 -9.13161468506,-0.325042694807,-5.84596443176 -9.12459850311,-0.324050635099,-5.80038928986 -9.11458778381,-0.324055284262,-5.77261447906 -9.14158725739,-0.324060022831,-5.75001430511 -9.17558860779,-0.324064254761,-5.73141479492 -9.24960899353,-0.32506519556,-5.7387881279 -9.27160549164,-0.325070470572,-5.71219491959 -9.28760051727,-0.32507622242,-5.6816072464 -13.8625421524,-0.378733366728,-8.53906154633 -13.6954565048,-0.37675344944,-8.40338420868 -13.7144355774,-0.376766860485,-8.354804039 -13.4663047791,-0.373799055815,-8.14138793945 -13.5102958679,-0.373810023069,-8.10978984833 -13.4512453079,-0.372827917337,-8.01525497437 -13.3831920624,-0.371846079826,-7.91572856903 -13.3941831589,-0.371851980686,-7.89393281937 -13.3411369324,-0.370868504047,-7.8053894043 -13.322104454,-0.369882792234,-7.73683071136 -13.3901062012,-0.370891451836,-7.72121095657 -13.4150915146,-0.370902985334,-7.67862701416 -13.4900960922,-0.371911227703,-7.66699934006 -13.3870325089,-0.369929641485,-7.55049180984 -13.3610095978,-0.369937419891,-7.50672721863 -13.3749914169,-0.36994895339,-7.45914506912 -13.3939752579,-0.368960112333,-7.41455793381 -13.3169240952,-0.367975831032,-7.31602954865 -13.3289051056,-0.367987126112,-7.26745223999 -13.3388853073,-0.367998421192,-7.21787548065 -13.3848800659,-0.368007808924,-7.18926906586 -13.350856781,-0.368014991283,-7.14350128174 -13.426861763,-0.368023127317,-7.13087940216 -13.6489191055,-0.371025472879,-7.19716691971 -13.5718688965,-0.369040191174,-7.09964752197 -13.4858169556,-0.368054687977,-6.99912643433 -13.5238084793,-0.368064284325,-6.96552610397 -13.5047807693,-0.368075996637,-6.90096855164 -13.3727245331,-0.366085976362,-6.80426645279 -13.3607006073,-0.366096735001,-6.74569320679 -13.3866882324,-0.366106539965,-6.70511198044 -13.349656105,-0.365117847919,-6.63355779648 -13.4126567841,-0.366126298904,-6.61294603348 -13.4806585312,-0.366134703159,-6.59433317184 -13.5066576004,-0.366138994694,-6.58152627945 -13.4746274948,-0.366149783134,-6.51297044754 -13.7967100143,-0.369152456522,-6.62019824982 -13.5246047974,-0.366168409586,-6.43279218674 -13.6446218491,-0.367175936699,-6.4381518364 -13.6866159439,-0.367184817791,-6.40654706955 -13.866651535,-0.369191646576,-6.43986749649 -13.840634346,-0.369196951389,-6.40109443665 -13.8126049042,-0.368207156658,-6.33454036713 -13.9236192703,-0.369215190411,-6.33489227295 -13.9486083984,-0.369224578142,-6.29330587387 -13.9125776291,-0.369234502316,-6.22375440598 -14.1546287537,-0.371241807938,-6.2820353508 -14.398680687,-0.37324950099,-6.34031009674 -14.4096727371,-0.373254477978,-6.31752252579 -14.4846754074,-0.374263882637,-6.29690551758 -14.5676774979,-0.375273376703,-6.27928590775 -14.8107261658,-0.377282261848,-6.33355712891 -14.8847255707,-0.378292322159,-6.30994653702 -15.0037374496,-0.379302114248,-6.30729579926 -15.3588132858,-0.383312612772,-6.40451145172 -15.3878107071,-0.383317857981,-6.38870668411 -17.110244751,-0.401333659887,-7.0660867691 -17.1772384644,-0.402346402407,-7.03147554398 -17.2152233124,-0.402359127998,-6.98388528824 -17.2622089386,-0.402371793985,-6.94028663635 -17.2991924286,-0.403384536505,-6.89169931412 -17.3561935425,-0.403391093016,-6.88387727737 -17.3811740875,-0.403403639793,-6.83029603958 -17.4571685791,-0.404416620731,-6.79768133163 -17.4941539764,-0.404429197311,-6.7490901947 -17.5421409607,-0.404441714287,-6.70548725128 -17.5781230927,-0.404454290867,-6.65589857101 -17.6541175842,-0.405467331409,-6.62228298187 -17.6691074371,-0.40547350049,-6.5964884758 -17.7330989838,-0.405486404896,-6.55787944794 -17.7840843201,-0.406499236822,-6.51328325272 -17.8260688782,-0.406511723995,-6.46568870544 -17.8700561523,-0.406524389982,-6.4180970192 -17.9190425873,-0.406537055969,-6.37249994278 -17.9730300903,-0.407549768686,-6.32889795303 -17.9970245361,-0.407556027174,-6.30609750748 -18.057012558,-0.407568901777,-6.26449012756 -18.501083374,-0.412592411041,-6.3586602211 -18.5520706177,-0.412605673075,-6.31106519699 -18.4800300598,-0.411615043879,-6.22153520584 -18.4630012512,-0.411626130342,-6.1499838829 -18.5389938354,-0.411639690399,-6.11236476898 -18.7880325317,-0.414653509855,-6.16443586349 -18.7379970551,-0.413663357496,-6.08189916611 -18.700963974,-0.413673371077,-6.00435400009 -18.7959594727,-0.413687795401,-5.97172403336 -18.7849330902,-0.413698643446,-5.90216970444 -18.8239173889,-0.41371101141,-5.85057401657 -18.8539123535,-0.414717644453,-5.82777261734 -18.9909133911,-0.415734052658,-5.80612659454 -18.9908885956,-0.415745049715,-5.74056148529 -19.003868103,-0.415756314993,-5.67998313904 -19.0648555756,-0.415769696236,-5.63338136673 -19.0218238831,-0.414778470993,-5.55484104156 -19.0117988586,-0.414788454771,-5.48727798462 -18.999786377,-0.414793074131,-5.4515004158 -19.0537719727,-0.414805918932,-5.4029006958 -19.1197605133,-0.415819346905,-5.35729694366 -19.1507434845,-0.415831029415,-5.30171012878 -19.2217350006,-0.415844738483,-5.25710248947 -19.2677192688,-0.416857242584,-5.2045135498 -19.3107147217,-0.416864395142,-5.18470096588 -19.3667011261,-0.416877359152,-5.13510227203 -19.4256877899,-0.417890578508,-5.08550596237 -19.4746723175,-0.417903095484,-5.03390836716 -19.5356616974,-0.418916255236,-4.98530435562 -19.5816459656,-0.418928712606,-4.93171358109 -19.6456336975,-0.419942110777,-4.88311004639 -19.6866283417,-0.419949293137,-4.86130046844 -19.737613678,-0.419961988926,-4.80870485306 -19.7966003418,-0.420975267887,-4.7571105957 -19.8585891724,-0.420988500118,-4.70750427246 -19.9145736694,-0.422001540661,-4.65490961075 -19.9575576782,-0.422013729811,-4.59931898117 -20.0145454407,-0.422026664019,-4.54771518707 -20.0615386963,-0.423034518957,-4.52491188049 -20.1265277863,-0.423048049212,-4.47430610657 -20.1865119934,-0.424061328173,-4.42170763016 -20.2384986877,-0.424074083567,-4.36711215973 -20.3054866791,-0.425087869167,-4.31550979614 -20.3584709167,-0.425100624561,-4.26091194153 -20.4214572906,-0.426114082336,-4.20830821991 -20.4634513855,-0.426121622324,-4.18350458145 -20.5324401855,-0.426135629416,-4.13090276718 -20.5794258118,-0.4271479249,-4.07430744171 -20.6314105988,-0.427160710096,-4.01771402359 -20.7113990784,-0.428175479174,-3.96710181236 -20.7563819885,-0.428187727928,-3.90851259232 -20.8173770905,-0.429196745157,-3.88669729233 -20.877363205,-0.429210066795,-3.83109664917 -20.9273490906,-0.43022274971,-3.77250671387 -20.9913330078,-0.430236399174,-3.71690559387 -21.0663204193,-0.431251019239,-3.66230273247 -21.1223068237,-0.431264042854,-3.60470485687 -21.1772918701,-0.432277083397,-3.54611158371 -21.2382850647,-0.43228623271,-3.52329182625 -21.2992725372,-0.433299809694,-3.46469855309 -21.3682575226,-0.433313965797,-3.40809440613 -21.4242420197,-0.434326946735,-3.34949445724 -21.4852275848,-0.434340536594,-3.28990125656 -21.5532131195,-0.435354620218,-3.23229718208 -21.6231975555,-0.436368972063,-3.17369842529 -21.6861934662,-0.436378568411,-3.14888167381 -21.7361793518,-0.437391161919,-3.08728909492 -21.8181629181,-0.437406629324,-3.02968239784 -21.8791484833,-0.438420176506,-2.96908426285 -21.9431343079,-0.438434004784,-2.90848469734 -22.0101203918,-0.439448148012,-2.847884655 -22.0731048584,-0.439461916685,-2.78628706932 -22.1290969849,-0.440471082926,-2.75847649574 -22.2060832977,-0.441486090422,-2.69886732101 -22.2650680542,-0.441499590874,-2.63527536392 -22.3330535889,-0.442513823509,-2.57367157936 -22.4010372162,-0.442528128624,-2.51107144356 -22.4710216522,-0.443542689085,-2.44747591019 -22.5250148773,-0.444551765919,-2.4186630249 -22.611000061,-0.444567859173,-2.35705375671 -22.6789836884,-0.445582270622,-2.29245781898 -22.7419700623,-0.446596115828,-2.22785902023 -22.812953949,-0.446610808372,-2.16325855255 -22.8959388733,-0.447626680136,-2.09965157509 -22.9529209137,-0.447639942169,-2.03305768967 -23.0089130402,-0.448649406433,-2.00224661827 -23.0968990326,-0.449665904045,-1.93763899803 -23.1638832092,-0.44968020916,-1.87103974819 -23.237865448,-0.45069527626,-1.80443871021 -21.4347705841,-0.432513356209,-1.58180260658 -21.1767444611,-0.429491907358,-1.49436640739 -21.193731308,-0.429499357939,-1.42879450321 -21.1987228394,-0.429502665997,-1.39600849152 -20.9506988525,-0.427481502295,-1.31157040596 -9.71629333496,-0.312269985676,-0.44602638483 -9.70029735565,-0.312265217304,-0.414461731911 -9.69830131531,-0.312261939049,-0.383889585733 -9.70430660248,-0.312259554863,-0.354306399822 -9.71030902863,-0.312258690596,-0.339515537024 -9.69231414795,-0.311253517866,-0.307953327894 -9.7023191452,-0.312251478434,-0.278371185064 -9.69132328033,-0.311247050762,-0.247798353434 -9.6933298111,-0.31124407053,-0.218214482069 -9.68833446503,-0.311240196228,-0.187643945217 -9.67733573914,-0.311237245798,-0.171865403652 -9.68834209442,-0.311235159636,-0.142282247543 -9.69134712219,-0.311232179403,-0.112698540092 -9.68435192108,-0.311227917671,-0.0821293592453 -9.6753578186,-0.311223506927,-0.0525471903384 -9.68836402893,-0.311221450567,-0.021976146847 -9.6723690033,-0.311216115952,0.00760383950546 -9.66737270355,-0.311213672161,0.0233800727874 -9.67537784576,-0.311211079359,0.0529645606875 -9.68238353729,-0.311208337545,0.0825493708253 -9.66638946533,-0.311202704906,0.113112643361 -9.6723947525,-0.311199784279,0.14269721508 -9.6544008255,-0.311193794012,0.173257753253 -9.6674079895,-0.311191678047,0.202845677733 -9.66341018677,-0.311189293861,0.217634752393 -9.64841651917,-0.311183542013,0.248194605112 -9.65242290497,-0.311180233955,0.277778357267 -9.65842819214,-0.311177134514,0.30736374855 -9.64843559265,-0.311171859503,0.337924897671 -9.6514415741,-0.311168342829,0.367508530617 -9.65144729614,-0.31116437912,0.397090166807 -9.65045166016,-0.311162143946,0.412866294384 -9.64045810699,-0.311156839132,0.442439705133 -9.63746452332,-0.311152398586,0.472018420696 -9.64247131348,-0.311149001122,0.501604259014 -9.63347816467,-0.311143547297,0.532163262367 -9.63248443604,-0.311139255762,0.561743497849 -9.63548851013,-0.311137586832,0.576537251472 -9.63049507141,-0.311132729053,0.606113433838 -9.63550186157,-0.311129063368,0.636686384678 -9.63050937653,-0.311124116182,0.666262388229 -9.62251663208,-0.311118721962,0.695834457874 -9.6285238266,-0.311115115881,0.726409375668 -9.62153053284,-0.311109751463,0.755982279778 -9.62053394318,-0.311107426882,0.770771801472 -9.61054229736,-0.311101734638,0.799354076385 -9.61454868317,-0.311097741127,0.82992708683 -9.59655761719,-0.311090797186,0.858497202396 -9.57856464386,-0.310083776712,0.88706612587 -9.59857177734,-0.311081916094,0.918648838997 -9.60357570648,-0.311080366373,0.933447301388 -9.68457984924,-0.312086760998,0.971045434475 -9.87757968903,-0.314108937979,1.01770675182 -9.87258815765,-0.31410369277,1.04827880859 -9.88359451294,-0.314100712538,1.07986390591 -9.80560493469,-0.3130851686,1.10340607166 -9.9316072464,-0.31409829855,1.14604258537 -9.91061115265,-0.314092963934,1.15981733799 -9.90361881256,-0.314087301493,1.19038724899 -9.87262916565,-0.314078211784,1.21795272827 -9.92063426971,-0.314080268145,1.25454461575 -9.95763969421,-0.315080940723,1.2891459465 -9.96964645386,-0.315077930689,1.32172846794 -9.93065643311,-0.314067542553,1.34829032421 -9.75566959381,-0.313039839268,1.34300196171 -9.95466709137,-0.315063685179,1.39865744114 -9.8956785202,-0.314050287008,1.42221319675 -9.89168643951,-0.314044803381,1.45278918743 -9.76470184326,-0.313021212816,1.46730899811 -9.89970207214,-0.314035952091,1.5169365406 -10.0256986618,-0.316052079201,1.54977965355 -10.0557041168,-0.316051602364,1.58537304401 -9.99371623993,-0.315037310123,1.60891449451 -9.67674541473,-0.311985164881,1.59336459637 -9.93273639679,-0.315018117428,1.66304135323 -9.92074584961,-0.315011203289,1.69261395931 -9.94375324249,-0.315009593964,1.72720694542 -9.76876926422,-0.312980592251,1.71591353416 -14.4484395981,-0.361683368683,2.50546145439 -14.4354438782,-0.361678302288,2.5500228405 -14.4344463348,-0.361675083637,2.59559845924 -14.4344491959,-0.361671924591,2.64216709137 -9.45283699036,-0.309905737638,1.81567549706 -14.4424543381,-0.362666755915,2.73631310463 -14.4424562454,-0.362665146589,2.75910258293 -14.9764165878,-0.367744356394,2.90389513969 -9.45986938477,-0.310887247324,1.92319178581 -9.67286968231,-0.312909156084,2.02443814278 -9.67287921906,-0.312903493643,2.05600833893 -9.66088867188,-0.31289601326,2.08458256721 -9.59489917755,-0.311882764101,2.08733844757 -14.9734344482,-0.368723154068,3.21810436249 -14.959438324,-0.368717610836,3.26367092133 -14.96144104,-0.368714600801,3.31224727631 -9.43295288086,-0.310834228992,2.17658305168 -9.93291664124,-0.315907657146,2.3163497448 -9.94591999054,-0.315906941891,2.33514547348 -9.88793468475,-0.315891981125,2.3546974659 -9.69396305084,-0.313855201006,2.3431968689 -9.78296375275,-0.314863681793,2.39481282234 -9.96295547485,-0.316886812449,2.46846055984 -9.96696472168,-0.316881686449,2.5020377636 -9.85698509216,-0.315858095884,2.50856900215 -9.66001033783,-0.313823282719,2.47728180885 -9.92099285126,-0.316859573126,2.57295465469 -9.8850069046,-0.315847873688,2.5965192318 -9.87501716614,-0.315840423107,2.62609767914 -9.60405540466,-0.312790244818,2.58957433701 -9.90603351593,-0.316833555698,2.69926166534 -9.96203708649,-0.316836714745,2.74685668945 -9.98104000092,-0.317836791277,2.76864790916 -9.77207279205,-0.314796358347,2.74614596367 -9.69609165192,-0.314777761698,2.75769972801 -9.87508201599,-0.316801130772,2.83933544159 -9.83009719849,-0.315787553787,2.85989427567 -9.7271194458,-0.314764350653,2.86343860626 -9.59213924408,-0.313738703728,2.84217143059 -9.81812381744,-0.315770089626,2.9388282299 -9.93312072754,-0.317783176899,3.00445199013 -9.92413139343,-0.317775517702,3.03502750397 -9.54418754578,-0.313705414534,2.95646429062 -9.83116340637,-0.316747367382,3.07414627075 -9.83117389679,-0.316740989685,3.10771799088 -9.87817287445,-0.317745774984,3.1385242939 -9.72920227051,-0.315714269876,3.126049757 -9.57724285126,-0.314675450325,3.14513921738 -9.52026081085,-0.313659220934,3.15969562531 -9.457280159,-0.313641875982,3.17224645615 -9.45129203796,-0.313634216785,3.20281863213 -9.46629524231,-0.313633531332,3.22361588478 -9.47330570221,-0.313628137112,3.25819778442 -9.46331787109,-0.313619703054,3.28776669502 -9.45533084869,-0.313611745834,3.31734490395 -9.46833992004,-0.313607186079,3.35491943359 -9.46635150909,-0.313600212336,3.38650202751 -9.44836521149,-0.313590377569,3.41307234764 -9.46236896515,-0.314589500427,3.43387150764 -9.4423828125,-0.313579142094,3.46043252945 -9.4523935318,-0.314574033022,3.49701142311 -9.45540428162,-0.314567863941,3.53059577942 -9.43541812897,-0.314557373524,3.55715656281 -9.4374294281,-0.314550936222,3.59073758125 -9.44943332672,-0.31454962492,3.61153268814 -9.42744922638,-0.314538776875,3.63709616661 -9.43545913696,-0.314533412457,3.67268443108 -9.43547058105,-0.314526438713,3.7062587738 -9.4294834137,-0.314518332481,3.73782849312 -9.42549705505,-0.314510524273,3.77039647102 -9.4315071106,-0.315504670143,3.80597949028 -9.432513237,-0.315501451492,3.82277369499 -9.42352581024,-0.315492719412,3.85334253311 -9.41753864288,-0.315484583378,3.88491535187 -9.42455005646,-0.315478771925,3.92149543762 -9.41356372833,-0.315469682217,3.95106768608 -9.41457557678,-0.315462708473,3.98564314842 -9.42058086395,-0.315460383892,4.00444221497 -9.41159343719,-0.315451592207,4.03501462936 -9.41460514069,-0.315444946289,4.0705909729 -9.40761852264,-0.315436452627,4.10216331482 -9.39863204956,-0.315427601337,4.13273668289 -9.40464305878,-0.316421329975,4.17030906677 -9.39365768433,-0.31641215086,4.19988536835 -9.39266490936,-0.316408336163,4.21667385101 -9.4016752243,-0.316402703524,4.25525426865 -9.3966884613,-0.316394507885,4.28782939911 -9.39270210266,-0.316386342049,4.32139921188 -9.38271522522,-0.316377162933,4.35197162628 -9.38072872162,-0.316369533539,4.38555431366 -9.37874031067,-0.31636172533,4.42012548447 -9.37874698639,-0.317357987165,4.43791151047 -9.3687620163,-0.317348748446,4.46848583221 -9.37777233124,-0.317342966795,4.50806522369 -9.36378765106,-0.317332983017,4.53664112091 -9.35180187225,-0.317323356867,4.56621694565 -9.35081481934,-0.317315578461,4.60178756714 -9.34882831573,-0.317307710648,4.6363658905 -9.33283805847,-0.317300856113,4.6471414566 -9.35684585571,-0.317297935486,4.69373703003 -9.34086227417,-0.317287325859,4.72230291367 -9.33487606049,-0.318278491497,4.75587177277 -9.32089138031,-0.318268418312,4.78445100784 -9.33790111542,-0.318263977766,4.82903432846 -9.33090877533,-0.318258821964,4.84381914139 -9.33592128754,-0.318252176046,4.88240194321 -9.32793521881,-0.318242967129,4.91497468948 -9.32694911957,-0.318235009909,4.95154523849 -9.31396389008,-0.318224936724,4.98112249374 -9.32497501373,-0.319219082594,5.02469110489 -9.32398891449,-0.31921133399,5.06027793884 -9.30699825287,-0.319204181433,5.07005739212 -9.32900810242,-0.319200605154,5.11864471436 -9.32202243805,-0.319191485643,5.15221881866 -9.3110370636,-0.319181352854,5.18477916718 -9.31505012512,-0.320174515247,5.22336959839 -9.30406570435,-0.320164352655,5.25593185425 -9.31007766724,-0.32015773654,5.29651546478 -9.3150844574,-0.320154726505,5.31830501556 -9.30209922791,-0.320144385099,5.34887838364 -9.3031129837,-0.320136666298,5.38745594025 -9.30512619019,-0.321129083633,5.42703056335 -9.29714107513,-0.321119427681,5.46159601212 -9.3031539917,-0.321112692356,5.50317811966 -9.30915927887,-0.321109831333,5.52596855164 -9.30017471313,-0.321100085974,5.55954122543 -9.29518890381,-0.321091175079,5.59511947632 -9.29920196533,-0.322083860636,5.63669490814 -9.28521823883,-0.322073161602,5.66726875305 -9.2792339325,-0.322063952684,5.70284414291 -9.28224754333,-0.322056353092,5.74441671371 -9.28525257111,-0.322052836418,5.76620340347 -9.28526687622,-0.322044909,5.80479097366 -9.28927993774,-0.323037475348,5.8473649025 -9.28029537201,-0.323027521372,5.8819360733 -9.27231121063,-0.323017925024,5.91651535034 -9.27232551575,-0.323009639978,5.95708751678 -9.27133274078,-0.323005288839,5.97687244415 -9.27834510803,-0.32299849391,6.02145385742 -9.26536178589,-0.322987705469,6.05402326584 -9.26137733459,-0.323978811502,6.09160375595 -9.26938915253,-0.323971986771,6.1381778717 -9.26040554047,-0.323961883783,6.17374753952 -9.24842166901,-0.323951393366,6.20632743835 -9.25542736053,-0.323948472738,6.23211240768 -9.25444126129,-0.324939996004,6.27269029617 -9.24545764923,-0.324929893017,6.30826425552 -9.25547027588,-0.324923455715,6.35684251785 -9.24448680878,-0.324912935495,6.39141559601 -9.23950195312,-0.324903577566,6.42999124527 -9.23251819611,-0.32589378953,6.46756410599 -9.25252056122,-0.325893521309,6.50236034393 -9.23453903198,-0.325881689787,6.53193616867 -9.23055458069,-0.325872302055,6.57250499725 -9.23456859589,-0.325864642859,6.61808347702 -9.22058582306,-0.325853347778,6.65165185928 -9.21460151672,-0.326843708754,6.69022989273 -9.22361469269,-0.326837003231,6.73981142044 -9.22462081909,-0.326832890511,6.76259756088 -9.21663761139,-0.326822847128,6.80017471313 -9.22165107727,-0.327815264463,6.84775209427 -9.21166801453,-0.327804774046,6.88432741165 -9.20268535614,-0.327794224024,6.92289209366 -9.20869827271,-0.32778686285,6.97147369385 -9.20470619202,-0.32778185606,6.99026536942 -9.20372104645,-0.328772902489,7.03483629227 -9.18074131012,-0.328759908676,7.0614156723 -9.14476394653,-0.32774412632,7.07898283005 -9.0468006134,-0.326716095209,7.0485367775 -9.04781532288,-0.327707409859,7.09510469437 -9.10681724548,-0.328710436821,7.18569993973 -9.05983543396,-0.327696830034,7.17147827148 -8.99786376953,-0.327675610781,7.16903162003 -8.93789291382,-0.326655000448,7.16659641266 -8.92391109467,-0.326643317938,7.20116519928 -8.92492580414,-0.327634871006,7.24674844742 -8.91494369507,-0.327624052763,7.28432321548 -8.91595840454,-0.327615410089,7.3309006691 -8.92796325684,-0.328613370657,7.36369180679 -8.88798809052,-0.327596545219,7.37725830078 -9.12594890594,-0.331635057926,7.61989355087 -9.1549577713,-0.331631839275,7.69247102737 -9.14897346497,-0.332621693611,7.73604297638 -9.14698982239,-0.332612633705,7.78162908554 -9.14200592041,-0.332602500916,7.82719516754 -9.13901519775,-0.332597464323,7.84898328781 -9.14102935791,-0.333588957787,7.89956188202 -9.12804794312,-0.333577305079,7.9381313324 -9.13406276703,-0.333569586277,7.99271011353 -9.11808204651,-0.333557456732,8.02828598022 -9.09610271454,-0.333543896675,8.05984973907 -9.25207328796,-0.336570709944,8.22167873383 -9.26408576965,-0.336564153433,8.28325939178 -9.25010490417,-0.336552232504,8.32282829285 -9.26811504364,-0.337547063828,8.38941955566 -9.25113487244,-0.337534457445,8.42698574066 -9.23915290833,-0.337522953749,8.46855831146 -9.2481584549,-0.338520169258,8.5033454895 -9.23517799377,-0.33850851655,8.54392147064 -9.22819519043,-0.33849799633,8.59049606323 -9.22321224213,-0.338487893343,8.63907146454 -9.22722625732,-0.339479535818,8.69664669037 -9.21224594116,-0.339467406273,8.73622226715 -9.18326854706,-0.339452415705,8.76279258728 -9.2132692337,-0.339453816414,8.81858539581 -9.23729515076,-0.341440200806,8.95174026489 -9.37527751923,-0.343458861113,9.14034843445 -9.18433952332,-0.341411143541,9.01088428497 -9.11538791656,-0.340378671885,9.05502128601 -9.07640552521,-0.340366244316,9.04380607605 -9.05342769623,-0.340352088213,9.0783662796 -9.05844211578,-0.341343909502,9.13894844055 -9.04646110535,-0.341332137585,9.18352222443 -9.03747940063,-0.341321021318,9.23109817505 -9.0284986496,-0.341309756041,9.27966880798 -9.02951335907,-0.342300742865,9.33725166321 -9.03552055359,-0.342297166586,9.37303638458 -9.03453636169,-0.34328764677,9.4296169281 -9.02555561066,-0.34327635169,9.47918796539 -9.01557350159,-0.343264877796,9.52776050568 -9.01059150696,-0.343254476786,9.58133792877 -9.01760578156,-0.344246387482,9.64891147614 -9.03660964966,-0.345245569944,9.69870662689 -8.97964096069,-0.344224631786,9.69727516174 -8.92767047882,-0.344204545021,9.70183849335 -8.86370277405,-0.343182086945,9.69240379333 -8.80873298645,-0.343161195517,9.69396018982 -8.75476360321,-0.343140751123,9.69452953339 -8.72278785706,-0.343124628067,9.72009563446 -8.73979187012,-0.343123346567,9.76888942719 -8.7338104248,-0.343112677336,9.8224697113 -8.72282981873,-0.344100803137,9.8720407486 -8.71984767914,-0.344090551138,9.93061447144 -8.94980430603,-0.348127990961,10.2532463074 -8.95681858063,-0.349119752645,10.3258218765 -8.95383739471,-0.349109470844,10.3873958588 -8.96984100342,-0.35010778904,10.4391822815 -8.95985984802,-0.350096195936,10.4927597046 -8.95287895203,-0.350085139275,10.5503349304 -8.94589710236,-0.351074010134,10.6089076996 -8.93991470337,-0.351063132286,10.6684846878 -8.93793201447,-0.352053076029,10.7330627441 -8.9519367218,-0.352051049471,10.7838516235 -8.9409570694,-0.353039175272,10.8384284973 -8.93297576904,-0.353027850389,10.8970060349 -8.9319934845,-0.354017794132,10.9655780792 -8.92101383209,-0.354005753994,11.022149086 -8.91803073883,-0.353995352983,11.0887231827 -8.89405441284,-0.354980707169,11.1292963028 -9.01702976227,-0.357001066208,11.31711483 -3.41952610016,-0.265854358673,4.35190868378 -3.41354799271,-0.265842884779,4.37247514725 -3.39957141876,-0.265830099583,4.38205575943 -3.37659668922,-0.265815705061,4.37964296341 -3.3706176281,-0.265804618597,4.39922714233 -8.81218624115,-0.356900185347,11.4935331345 -8.81619358063,-0.356895983219,11.536318779 -8.81321144104,-0.357885628939,11.6058998108 -8.80922985077,-0.357874810696,11.6764707565 -8.80124950409,-0.358863174915,11.7420425415 -8.78926944733,-0.358850896358,11.8016204834 -8.77229213715,-0.359837412834,11.8561906815 -8.79729366302,-0.35983774066,11.926990509 -8.78831386566,-0.360825806856,11.9935598373 -8.78133296967,-0.360814452171,12.0621366501 -8.77635097504,-0.361803412437,12.1347093582 -8.76637077332,-0.361791402102,12.2002859116 -8.75539207458,-0.362779170275,12.2648611069 -8.752409935,-0.363768577576,12.3414382935 -8.76441478729,-0.363766103983,12.3982315063 -8.75743484497,-0.364754468203,12.4717998505 -8.75545310974,-0.36474403739,12.5513772964 -8.80045795441,-0.366743117571,12.6999588013 -8.79047775269,-0.366731077433,12.7695360184 -8.78249740601,-0.367719382048,12.8431119919 -8.80849933624,-0.368719667196,12.9239053726 -8.78852272034,-0.368705451488,12.9814758301 -8.78654098511,-0.369694888592,13.0660514832 -8.77356147766,-0.369682103395,13.1346263885 -8.76958084106,-0.370671212673,13.2172021866 -8.75160312653,-0.370657473803,13.2787790298 -8.75461959839,-0.371647834778,13.3743524551 -8.75962734222,-0.372643887997,13.4261474609 -8.75964450836,-0.372633606195,13.5187196732 -8.74966526031,-0.373621344566,13.5962924957 -8.73968601227,-0.37460911274,13.6738681793 -8.72570800781,-0.374595999718,13.7464408875 -8.7197265625,-0.375584661961,13.8310203552 -8.72974205017,-0.376576453447,13.9425983429 -8.71675491333,-0.376568555832,13.9713792801 -9.23162746429,-0.387663513422,14.8970365524 -8.68280029297,-0.377541154623,14.1115274429 -9.02472114563,-0.385600715876,14.768157959 -9.35664463043,-0.392658174038,15.4177846909 -8.64586448669,-0.379502773285,14.3492546082 -9.00578022003,-0.387565851212,15.0518817902 -9.10176086426,-0.389580368996,15.2646884918 -8.69089603424,-0.382486253977,14.6802053452 -8.89787387848,-0.388507694006,15.2453861237 -8.77492713928,-0.387472122908,15.1449384689 -8.62498760223,-0.38443121314,14.9934959412 -8.93790721893,-0.391489833593,15.5923299789 -9.08388328552,-0.395509213209,15.9609279633 -8.65402412415,-0.387411236763,15.3174448013 -8.60605716705,-0.387391060591,15.3440141678 -8.98396587372,-0.396457493305,16.1356391907 -9.58980846405,-0.410570412874,17.3493003845 -9.52684497833,-0.410547047853,17.3638629913 -8.69309520721,-0.393372237682,15.902545929 -8.78608608246,-0.396380633116,16.1931304932 -8.69913005829,-0.395352363586,16.1536922455 -8.63616657257,-0.395329087973,16.1572608948 -8.56920337677,-0.394305080175,16.1518325806 -8.53023338318,-0.39528670907,16.1994075775 -8.56123447418,-0.39628764987,16.3211956024 -8.55825328827,-0.397276520729,16.4397716522 -8.55027389526,-0.398264467716,16.5493507385 -8.53829574585,-0.399251401424,16.6539230347 -8.52531814575,-0.400238215923,16.7574977875 -8.5183391571,-0.401226192713,16.8740730286 -8.50636100769,-0.402213186026,16.9816474915 -8.52236461639,-0.403211116791,17.0804367065 -8.50638866425,-0.403197318316,17.182012558 -8.4964094162,-0.404184669256,17.297586441 -8.48543167114,-0.405171841383,17.4121627808 -8.47445297241,-0.40615901351,17.5277385712 -11.4545936584,-0.477752000093,23.8816814423 -11.3706359863,-0.477724194527,23.8972473145 -10.6438589096,-0.461571574211,22.4599437714 -11.2187080383,-0.476677060127,23.8665866852 -10.4969396591,-0.461520135403,22.5130729675 -10.4099826813,-0.460491776466,22.5086421967 -10.9418430328,-0.475588440895,23.8552780151 -10.7069311142,-0.471530109644,23.5358276367 -10.5979814529,-0.470497131348,23.4923839569 -10.5490055084,-0.470481812954,23.4811668396 -10.4600496292,-0.469452887774,23.4797306061 -10.3680944443,-0.469423502684,23.4692974091 -10.2871379852,-0.469396233559,23.4848632812 -10.1931848526,-0.468366384506,23.4694271088 -10.1012306213,-0.468336880207,23.4589881897 -10.0512542725,-0.468321382999,23.442773819 -9.96729755402,-0.467293471098,23.4503364563 -9.87534332275,-0.467264026403,23.4369029999 -9.79038715363,-0.466236025095,23.4394702911 -9.70343208313,-0.466207534075,23.4380340576 -9.61447811127,-0.466178745031,23.4296016693 -9.52652263641,-0.465150088072,23.4241657257 -9.47854709625,-0.465134978294,23.4109477997 -9.39159202576,-0.465106546879,23.4065151215 -9.30763530731,-0.464078634977,23.4100799561 -9.21868133545,-0.464049905539,23.397649765 -9.12872695923,-0.463020831347,23.3852119446 -9.04477214813,-0.462993085384,23.3847808838 -8.96781349182,-0.462966680527,23.4033508301 -8.91184043884,-0.462949961424,23.3671321869 -8.82788467407,-0.461922138929,23.3666992188 -8.74492931366,-0.461894601583,23.367269516 -8.66097354889,-0.461866915226,23.3638401031 -8.57301902771,-0.460838317871,23.3514080048 -8.49506187439,-0.460811764002,23.3649749756 -8.44308757782,-0.460795849562,23.3367576599 -8.36113166809,-0.459768593311,23.3363304138 -8.27717590332,-0.459740847349,23.3318958282 -8.19322109222,-0.459713071585,23.3274650574 -8.11326503754,-0.458686172962,23.3330345154 -8.03130912781,-0.458658903837,23.3316059113 -7.94735431671,-0.458631247282,23.3241767883 -7.90137815475,-0.458616554737,23.3099594116 -7.82142210007,-0.457589775324,23.3115329742 -7.74146604538,-0.457562804222,23.3171005249 -7.65651130676,-0.457534968853,23.3046684265 -7.57455587387,-0.456507772207,23.299243927 -7.49260091782,-0.456480503082,23.2958126068 -4.13964414597,-0.346807003021,12.9921875 -4.10966348648,-0.345795661211,12.9699697495 -4.07369470596,-0.346778094769,12.9955530167 -7.20275831223,-0.455384761095,23.2643146515 -7.1258020401,-0.455358505249,23.2748832703 -7.04484653473,-0.45533156395,23.2704563141 -6.96089220047,-0.454304039478,23.2540283203 -6.91991472244,-0.454290419817,23.2508125305 -6.83995914459,-0.454263627529,23.2493839264 -6.75700473785,-0.453236401081,23.2339572906 -6.67904853821,-0.453210115433,23.236530304 -6.60009288788,-0.453183591366,23.2361030579 -6.51713848114,-0.453156262636,23.2216739655 -6.44018220901,-0.452130258083,23.2242507935 -6.40220403671,-0.452117264271,23.2300357819 -6.31825017929,-0.452089875937,23.207611084 -6.23929452896,-0.452063411474,23.2051811218 -6.16333818436,-0.452037572861,23.2127552032 -6.08038425446,-0.45101043582,23.1913299561 -6.00142860413,-0.450984090567,23.1849040985 -5.92647171021,-0.450958490372,23.1954803467 -5.88249588013,-0.450944393873,23.1752643585 -5.80554008484,-0.449918478727,23.1758384705 -5.73058366776,-0.449892878532,23.1854133606 -5.64762926102,-0.449865847826,23.1599884033 -5.56967353821,-0.449839830399,23.1525669098 -5.49371814728,-0.448814064264,23.1571388245 -5.41476297379,-0.448787897825,23.1447181702 -5.3757853508,-0.448774784803,23.1435031891 -5.2998290062,-0.448749184608,23.1440792084 -5.21887493134,-0.448722571135,23.1236534119 -5.14191913605,-0.447696745396,23.1212272644 -5.0669631958,-0.447671353817,23.1258049011 -5.03399372101,-0.449654102325,23.324382782 -5.04999876022,-0.452651798725,23.5771751404 -5.02802658081,-0.454636693001,23.8387546539 -3.23060488701,-0.368279874325,15.5252981186 -3.16564583778,-0.367256730795,15.4558763504 -3.11068367958,-0.367235600948,15.4324579239 -3.05772089958,-0.367214858532,15.4180383682 -3.00275921822,-0.367193728685,15.39361763 -2.98277568817,-0.367184519768,15.4214048386 -2.93681097031,-0.367165148258,15.4429855347 -2.89384508133,-0.367146372795,15.4805660248 -2.84888005257,-0.367127269506,15.5071487427 -2.8039150238,-0.368108183146,15.5347309113 -4.79831457138,-0.487477988005,27.1603240967 -4.8073220253,-0.490474194288,27.4651145935 -4.77835226059,-0.493457853794,27.8106956482 -4.72938776016,-0.496437549591,28.054271698 -4.92134857178,-0.513463139534,29.7758522034 -4.88538074493,-0.517445266247,30.1454315186 -4.80142784119,-0.517418324947,30.2280101776 -4.70547914505,-0.517389118671,30.2365837097 -4.65550470352,-0.517374277115,30.2213764191 -4.59754371643,-0.520352303982,30.4849529266 -4.56557416916,-0.524335324764,30.9285335541 -4.59858465195,-0.53333067894,31.8491134644 -4.58865070343,-0.555295944214,34.0518531799 -4.50968599319,-0.55327552557,33.8686408997 -4.45572376251,-0.557254374027,34.2872161865 -4.39876270294,-0.562232673168,34.7067909241 -4.37279176712,-0.568216860294,35.3913726807 -4.32082891464,-0.573196172714,35.9029502869 -4.2758641243,-0.579176783562,36.4955291748 -4.22190189362,-0.585155785084,37.037109375 -2.66240215302,-0.447858452797,23.6099014282 -2.58844637871,-0.447833925486,23.6234798431 -2.5164899826,-0.447809934616,23.6490631104 -2.44253444672,-0.447785586119,23.6566448212 -2.37157797813,-0.448761731386,23.7032241821 -2.29962182045,-0.448737859726,23.7298069 -3.96710848808,-0.633042633533,41.8165817261 -3.90119242668,-0.671997666359,45.7143211365 -3.7392642498,-0.668956696987,45.5009002686 -3.64631485939,-0.675928592682,46.150478363 -3.66534042358,-0.707915842533,49.3668479919 -3.49841427803,-0.706874012947,49.2204246521 -3.41748213768,-0.742837488651,52.7815856934 -3.25155568123,-0.742796063423,52.7871665955 -3.12861585617,-0.749762713909,53.5377464294 -3.42653226852,-0.818812072277,60.3175354004 -3.23561382294,-0.817766129971,60.2931137085 -3.04569506645,-0.817720472813,60.2986946106 -1.76711928844,-0.582476019859,37.0942993164 -1.64317977428,-0.581442832947,36.9378814697 -1.52523827553,-0.580410838127,36.8964614868 -1.40829646587,-0.580379068851,36.8840484619 -1.35232484341,-0.581363677979,36.9338378906 -2.25006341934,-0.893516242504,67.857383728 -1.8732252121,-0.912426531315,69.7205581665 -1.77027916908,-0.96239733696,74.6821365356 -1.01556003094,-0.793239951134,57.9563102722 -0.674699425697,-0.737163066864,52.4566993713 -0.512772023678,-0.741123557091,52.816280365 -0.346845716238,-0.740083575249,52.7268676758 --0.969605028629,-0.440784871578,74.127281189 --12.8777980804,-0.439329177141,73.5718841553 --13.1366968155,-0.440280675888,73.6844940186 --11.5480165482,-0.383484631777,55.5877685547 --11.708946228,-0.383452445269,55.4823760986 --16.6973724365,-0.454644650221,77.9673309326 --16.2774848938,-0.444707483053,74.8538970947 --16.4044246674,-0.443682491779,74.3095092773 --16.1315021515,-0.437723845243,72.5302886963 --16.3614120483,-0.437682509422,72.4889068604 --15.9525194168,-0.428743004799,69.6484832764 --15.8195428848,-0.423759430647,68.0820770264 --15.9034976959,-0.421741425991,67.480682373 --15.4865989685,-0.412800312042,64.3430480957 --15.4635877609,-0.409799128771,63.3686485291 --15.4655675888,-0.406794071198,62.5232505798 --15.6464929581,-0.406760901213,62.4138679504 --10.9729213715,-0.344488382339,43.1540756226 --11.0838680267,-0.3444647789,43.0236816406 --11.2208061218,-0.344437211752,42.9922904968 --15.0036277771,-0.389844805002,57.1634140015 --15.005607605,-0.38783967495,56.4450149536 --14.9656019211,-0.38484108448,55.5896148682 --14.9905748367,-0.383832395077,54.9902114868 --15.170501709,-0.383799821138,54.967830658 --15.339430809,-0.383769094944,54.9074478149 --15.5323524475,-0.383734822273,54.930065155 --15.6313123703,-0.383717358112,54.9518737793 --15.8122396469,-0.383685141802,54.9304924011 --14.6905660629,-0.368852198124,50.4259910583 --14.8045129776,-0.368830054998,50.229598999 --14.9834394455,-0.368798106909,50.2522163391 --9.54507255554,-0.307611912489,31.2458667755 --9.58205127716,-0.307603061199,31.1926708221 --9.68899917603,-0.307580381632,31.1902751923 --9.81094264984,-0.307555556297,31.2358818054 --10.004863739,-0.308520019054,31.5074996948 --10.1218090057,-0.308496147394,31.5311050415 --10.1917676926,-0.308479368687,31.4087085724 --14.2285251617,-0.348874121904,43.662940979 --14.4244470596,-0.348840177059,43.7965621948 --14.5683851242,-0.348814129829,43.7691764832 --14.1174497604,-0.339862048626,40.6895217896 --11.4322576523,-0.313253819942,32.7610206604 --13.8325099945,-0.334896743298,39.2648887634 --13.7795085907,-0.3338996768,38.7234840393 --13.7375030518,-0.331901013851,38.2240829468 --13.8104629517,-0.331885635853,38.0506896973 --13.8984174728,-0.330868124962,37.918296814 --13.6764669418,-0.327895492315,36.9488677979 --13.6604633331,-0.326895445585,36.7286643982 --13.6394519806,-0.325893700123,36.3212661743 --13.6244382858,-0.324891120195,35.9358596802 --13.6074256897,-0.323888778687,35.5504570007 --13.6134061813,-0.322883218527,35.2340545654 --13.7313528061,-0.32286170125,35.2076683044 --13.8812980652,-0.323838025331,35.4284896851 --13.916270256,-0.322828501463,35.1900901794 --13.6523151398,-0.318856626749,33.8932571411 --13.7822570801,-0.318833768368,33.9088745117 --13.4043540955,-0.314882218838,32.6804237366 --13.4003372192,-0.313878059387,32.3770179749 --13.3343477249,-0.312884986401,32.0748100281 --13.3183355331,-0.31188249588,31.752407074 --13.3073215485,-0.311879366636,31.4480075836 --13.2863101959,-0.310877621174,31.1236000061 --13.2662982941,-0.309875696898,30.8061962128 --13.251285553,-0.308873146772,30.5067958832 --13.3272447586,-0.3088580966,30.4184036255 --13.3822202682,-0.308848291636,30.4142112732 --13.4781732559,-0.308830618858,30.3718223572 --13.1342411041,-0.30486831069,29.0959701538 --13.1382236481,-0.303863167763,28.8615703583 --13.1192111969,-0.302861124277,28.5791664124 --13.0652179718,-0.30186611414,28.3419532776 --13.0532045364,-0.301863133907,28.0825519562 --13.0421905518,-0.30086004734,27.8291511536 --13.0371742249,-0.299856156111,27.5907478333 --13.0291604996,-0.298852652311,27.3503456116 --13.0111474991,-0.298850476742,27.0899391174 --13.0061311722,-0.297846615314,26.8615379333 --12.9741325378,-0.297848582268,26.6873321533 --13.0610895157,-0.297832608223,26.6519412994 --13.1440486908,-0.297817289829,26.6105575562 --13.2430028915,-0.297799944878,26.5991706848 --9.09020137787,-0.268336266279,18.0781040192 --9.23814105988,-0.268310964108,18.2297210693 --9.28710842133,-0.268298625946,18.1843261719 --9.15913581848,-0.26731210947,17.8610992432 --9.20510482788,-0.267300128937,17.8116989136 --9.28306293488,-0.26728412509,17.8253078461 --9.46099376678,-0.268255442381,18.0299358368 --9.57294368744,-0.269235312939,18.104549408 --12.8259801865,-0.289816439152,24.1096897125 --9.43895435333,-0.267243504524,17.6449165344 --9.47492599487,-0.267233133316,17.5795192719 --9.53589057922,-0.267219543457,17.5581207275 --12.8869037628,-0.288793504238,23.591293335 --12.9548664093,-0.288780659437,23.5379009247 --13.0288295746,-0.288767188787,23.4965133667 --13.160774231,-0.288746625185,23.5601348877 --13.2157497406,-0.288737714291,23.570941925 --13.3137054443,-0.288721501827,23.5705566406 --13.3996639252,-0.288706898689,23.5491695404 --13.504617691,-0.289690077305,23.5607872009 --13.5835781097,-0.289676517248,23.5264015198 --13.6425447464,-0.289665460587,23.4570083618 --13.7584953308,-0.289647579193,23.4856281281 --13.7984762192,-0.289640873671,23.4694366455 --13.9334220886,-0.289620876312,23.5290584564 --14.012383461,-0.28960776329,23.4936733246 --14.0373601913,-0.289601176977,23.36627388 --13.9713630676,-0.288605451584,23.0898628235 --14.1742897034,-0.289577841759,23.2615013123 --14.2892484665,-0.28956246376,23.3673210144 --14.4471883774,-0.29054042697,23.4599514008 --14.5461444855,-0.290525496006,23.4545669556 --14.6441020966,-0.290510773659,23.4471855164 --14.710067749,-0.290499895811,23.387796402 --14.8080234528,-0.29048538208,23.3794155121 --14.9379720688,-0.291467308998,23.4220409393 --14.9999475479,-0.291458636522,23.4368515015 --15.0949048996,-0.291444808245,23.4234733582 --15.1398763657,-0.291436761618,23.3300800323 --15.0878763199,-0.290439903736,23.0886707306 --15.3297939301,-0.2914095819,23.3003196716 --15.2258081436,-0.290418684483,22.9828987122 --12.9274339676,-0.276674866676,19.3620510101 --12.9654150009,-0.276668697596,19.3528575897 --12.8944196701,-0.276672810316,19.1134376526 --12.8794078827,-0.275670737028,18.9620361328 --14.1440410614,-0.282526642084,20.6938877106 --13.1562986374,-0.276632606983,19.11028862 --12.2445354462,-0.271729230881,17.6577033997 --12.2555246353,-0.27172601223,17.6135025024 --12.2994966507,-0.271717190742,17.5581092834 --13.4161729813,-0.276591777802,19.0339355469 --12.0675287247,-0.269734323025,16.9942588806 --12.1065015793,-0.269726037979,16.9338588715 --12.2144565582,-0.269710451365,16.9724807739 --12.1304626465,-0.268715471029,16.743062973 --12.2214307785,-0.269703775644,16.8128795624 --12.2234144211,-0.268699645996,16.7034778595 --11.1826820374,-0.262805461884,15.1698522568 --11.2486476898,-0.263794153929,15.1594657898 --11.3076152802,-0.263783603907,15.1380720139 --11.430565834,-0.263766497374,15.2026948929 --12.2943162918,-0.267672896385,16.2524776459 --11.9933900833,-0.266702085733,15.8002157211 --12.1303367615,-0.266684085131,15.8768424988 --12.2182979584,-0.26667124033,15.8874568939 --8.85318660736,-0.250009179115,11.4022903442 --8.86816596985,-0.24900226295,11.3478937149 --8.89814090729,-0.248993754387,11.3114919662 --8.94112110138,-0.249986633658,11.3282928467 --12.3721866608,-0.266638964415,15.6216812134 --12.4681453705,-0.266625851393,15.6423044205 --12.6280879974,-0.267606467009,15.7419404984 --12.5720872879,-0.266608476639,15.5685195923 --12.5970649719,-0.266602575779,15.4991264343 --12.5550613403,-0.266603261232,15.3477172852 --12.5780487061,-0.266599267721,15.3255186081 --12.718996048,-0.266582250595,15.3991518021 --12.8909358978,-0.267562389374,15.5077867508 --12.8839225769,-0.266559839249,15.3993835449 --12.8489170074,-0.266559958458,15.2579717636 --12.9098863602,-0.266550987959,15.2325849533 --12.9868507385,-0.266540586948,15.2251996994 --13.2127847672,-0.267517894506,15.4430541992 --13.3157434464,-0.267505347729,15.4646778107 --13.2977333069,-0.267504125834,15.3452749252 --13.3237123489,-0.267498850822,15.2768793106 --13.2867078781,-0.267499387264,15.1364679337 --13.3816690445,-0.26748791337,15.1480894089 --13.4966316223,-0.267476081848,15.2309188843 --13.5456047058,-0.267468929291,15.1875228882 --13.6725568771,-0.268454939127,15.2341566086 --13.6835412979,-0.267451375723,15.1497602463 --13.7635068893,-0.268441736698,15.1413764954 --15.1761302948,-0.274314880371,16.6033248901 --13.9894208908,-0.268417060375,15.1976337433 --14.3023338318,-0.270388573408,15.4905090332 --11.9689159393,-0.258588582277,12.8595266342 --11.9768981934,-0.258584499359,12.7861251831 --11.965886116,-0.258582055569,12.6927185059 --11.9828672409,-0.25857719779,12.6293172836 --11.9988489151,-0.25857257843,12.5669240952 --12.0728158951,-0.258563041687,12.5645389557 --12.0898036957,-0.258560031652,12.5433473587 --12.1077852249,-0.258555263281,12.4809427261 --12.0817775726,-0.258554250002,12.3755378723 --12.1017570496,-0.257549405098,12.3171396255 --12.0857467651,-0.257547557354,12.2227334976 --12.0897312164,-0.25754404068,12.1483287811 --12.0747213364,-0.257542103529,12.0559215546 --12.0797128677,-0.257540136576,12.0227231979 --12.0537052155,-0.256539076567,11.9203128815 --12.0616884232,-0.256535351276,11.8529157639 --12.0586748123,-0.256532490253,11.774512291 --12.0716571808,-0.256528407335,11.7121114731 --12.0746421814,-0.25652512908,11.6407108307 --12.0786342621,-0.256523311138,11.6075115204 --12.0666227341,-0.256521195173,11.5221061707 --12.0746068954,-0.25651755929,11.455701828 --12.0695943832,-0.255514979362,11.3783006668 --12.0595827103,-0.255512744188,11.2958917618 --12.0635671616,-0.255509495735,11.2274904251 --12.0675525665,-0.255506336689,11.1610975266 --12.0505495071,-0.25550609827,11.1088876724 --12.0375385284,-0.255504101515,11.0254793167 --12.0455226898,-0.25450065732,10.9630832672 --12.0375108719,-0.254498362541,10.8856782913 --12.0414962769,-0.25449514389,10.8182687759 --12.0364837646,-0.254492729902,10.7458724976 --12.0264720917,-0.254490584135,10.6674642563 --12.031463623,-0.254488795996,10.6372623444 --11.964466095,-0.253490626812,10.5098438263 --11.9654521942,-0.253487706184,10.4424362183 --11.9474430084,-0.253486126661,10.3600320816 --11.964425087,-0.253482222557,10.308637619 --12.00340271,-0.253476917744,10.2762470245 --12.0133867264,-0.253473520279,10.2178430557 --11.9913845062,-0.253473609686,10.1666402817 --11.9823732376,-0.252471506596,10.0932340622 --11.9793605804,-0.252469003201,10.0248270035 --11.9823465347,-0.252466142178,9.96242523193 --11.9803333282,-0.252463638783,9.89602184296 --11.9763202667,-0.252461254597,9.82861804962 --11.9703159332,-0.252460300922,9.79141426086 --11.9583044052,-0.252458453178,9.71800899506 --11.952293396,-0.251456201077,9.64960289001 --11.9512796402,-0.251453697681,9.58620262146 --11.9522666931,-0.251451104879,9.52480316162 --11.9462547302,-0.25144892931,9.45739650726 --11.9422426224,-0.251446634531,9.3919916153 --11.9182405472,-0.25144675374,9.34178161621 --11.929224968,-0.251443624496,9.28938388824 --11.9202136993,-0.251441687346,9.22198390961 --11.8662128448,-0.250442236662,9.11856079102 --11.8761978149,-0.250439196825,9.06616210938 --11.8671865463,-0.250437200069,8.99875354767 --11.8621749878,-0.250435054302,8.93535041809 --11.8891620636,-0.250432372093,8.92615604401 --11.9491357803,-0.250426828861,8.91277503967 --12.0590991974,-0.250418752432,8.93640804291 --5.48251914978,-0.224752813578,3.95380115509 --5.46550512314,-0.224747031927,3.91337585449 --5.47948503494,-0.224739938974,3.89697527885 --11.8630838394,-0.249418452382,8.52653121948 --11.8590726852,-0.249416410923,8.46713447571 --11.8620595932,-0.249413982034,8.41172981262 --11.859046936,-0.24941188097,8.3523235321 --11.8520355225,-0.249409988523,8.29092025757 --11.8550224304,-0.24940764904,8.23651790619 --11.8440113068,-0.248405963182,8.17210674286 --11.839006424,-0.248405098915,8.14090633392 --11.8349952698,-0.248403117061,8.08250236511 --11.8299837112,-0.248401224613,8.02410125732 --11.8319702148,-0.248398989439,7.96969509125 --11.8359575272,-0.248396739364,7.91830015182 --11.8229475021,-0.248395204544,7.85489416122 --11.8059444427,-0.248394861817,7.81568336487 --11.7639417648,-0.247394487262,7.73326683044 --11.7819261551,-0.247391700745,7.69187307358 --11.7569179535,-0.247390642762,7.62146091461 --11.7659034729,-0.247388258576,7.57406187057 --11.7578935623,-0.247386544943,7.51565647125 --11.7618808746,-0.247384399176,7.46525430679 --11.7448778152,-0.247384041548,7.42804861069 --11.7498645782,-0.247381880879,7.37864685059 --11.7348556519,-0.247380450368,7.3162355423 --11.7448415756,-0.247378185391,7.27083921432 --11.7358312607,-0.246376603842,7.21343421936 --11.7448167801,-0.24637439847,7.16703224182 --11.728808403,-0.246373057365,7.10562419891 --11.7248039246,-0.246372252703,7.07742118835 --11.7217922211,-0.246370524168,7.02502202988 --11.7307777405,-0.246368378401,6.97861480713 --11.7117700577,-0.246367186308,6.91721200943 --11.7097587585,-0.246365427971,6.86480331421 --11.7127466202,-0.246363565326,6.8164024353 --11.7207326889,-0.246361598372,6.77100229263 --11.6917333603,-0.246361583471,6.72979831696 --11.697719574,-0.246359676123,6.68339681625 --11.6937093735,-0.245358064771,6.63098859787 --11.6976966858,-0.24535626173,6.58358478546 --11.6856870651,-0.245354890823,6.52717590332 --11.6926736832,-0.245353102684,6.48278093338 --11.6836643219,-0.245351687074,6.42837190628 --11.6816587448,-0.245350927114,6.40317201614 --11.6706504822,-0.245349600911,6.34876823425 --11.7936162949,-0.245345309377,6.36840820312 --11.7496118546,-0.245344758034,6.29498577118 --11.827586174,-0.245341688395,6.28961467743 --11.9005622864,-0.245338842273,6.28023529053 --11.9695386887,-0.246336206794,6.26885938644 --12.0785131454,-0.246333524585,6.30269622803 --12.1584882736,-0.246330931783,6.29632520676 --12.1704750061,-0.246329635382,6.25292396545 --12.138469696,-0.246329143643,6.18751430511 --12.2174453735,-0.246326833963,6.17913627625 --12.2424297333,-0.24632550776,6.1437497139 --12.2234277725,-0.246325328946,6.10954236984 --12.4263811111,-0.247321560979,6.16421508789 --12.2554016113,-0.246323078871,6.02774620056 --12.1993637085,-0.246320009232,5.78291797638 --12.2013540268,-0.24631921947,5.73652029037 --12.1983442307,-0.245318487287,5.6871137619 --12.2003335953,-0.245317742229,5.64071321487 --12.4212856293,-0.246315523982,5.69739103317 --19.5370807648,-0.271275281906,8.91124248505 --14.7458753586,-0.254302591085,6.65426397324 --14.6798782349,-0.254304200411,6.56784296036 --14.6208810806,-0.253305733204,6.48441886902 --14.5528841019,-0.25330722332,6.39799356461 --14.4638910294,-0.253308683634,6.30255842209 --14.4028940201,-0.252310007811,6.221139431 --14.333896637,-0.252311259508,6.13570928574 --14.251906395,-0.252311855555,6.07247638702 --14.1799097061,-0.252312958241,5.98805332184 --14.1119127274,-0.251313954592,5.90562820435 --14.0499153137,-0.251314908266,5.82620382309 --13.9749183655,-0.251315772533,5.74177360535 --13.9119205475,-0.250316560268,5.66335010529 --13.8359241486,-0.250317245722,5.57991933823 --11.5492620468,-0.242305129766,4.56341600418 --11.5622491837,-0.242304444313,4.52601861954 --11.5472421646,-0.242303565145,4.47660398483 --11.5612297058,-0.242302969098,4.44021129608 --11.5532207489,-0.242302209139,4.39480781555 --11.5492172241,-0.242301821709,4.3716006279 --11.5352096558,-0.242301017046,4.32419538498 --11.5441980362,-0.242300465703,4.28579854965 --11.5371894836,-0.242299750447,4.24038648605 --11.5401792526,-0.242299199104,4.19998836517 --11.5331707001,-0.242298543453,4.15558338165 --11.5441598892,-0.242298156023,4.11818742752 --11.5251569748,-0.24229760468,4.08997488022 --11.5231485367,-0.241297051311,4.04757022858 --11.5171403885,-0.241296455264,4.00416660309 --11.5171308517,-0.241295978427,3.96276330948 --11.5241203308,-0.241295665503,3.92436671257 --11.5281105042,-0.241295322776,3.88395929337 --11.5061035156,-0.241294503212,3.83555102348 --11.5240974426,-0.241294667125,3.82135748863 --11.5100898743,-0.241294026375,3.77595233917 --11.5150794983,-0.241293802857,3.73654866219 --11.5020723343,-0.24129319191,3.69113779068 --11.508061409,-0.241293057799,3.65273952484 --11.5030536652,-0.241292670369,3.61033248901 --11.3800611496,-0.241289317608,3.52987980843 --11.3710565567,-0.240288928151,3.50667142868 --11.3540506363,-0.240288153291,3.46126031876 --11.3780374527,-0.24028852582,3.429874897 --11.3400344849,-0.240287214518,3.37845849991 --11.334025383,-0.240286782384,3.33705306053 --11.3450145721,-0.240286871791,3.30065107346 --11.3460063934,-0.240286707878,3.2612452507 --11.3400030136,-0.240286439657,3.24004435539 --11.3489933014,-0.240286573768,3.20364713669 --11.3419847488,-0.24028621614,3.16223978996 --11.33497715,-0.240285873413,3.12083148956 --11.3409671783,-0.240285992622,3.08343029022 --11.3169612885,-0.240285098553,3.03802132607 --11.3379507065,-0.240285813808,3.00563263893 --11.3279476166,-0.240285456181,2.98241662979 --11.337937355,-0.240285843611,2.94702458382 --11.3189325333,-0.240285143256,2.9026081562 --11.325922966,-0.240285485983,2.86621165276 --11.3089160919,-0.240284889936,2.82279801369 --11.3099069595,-0.240285024047,2.78540372849 --11.3098993301,-0.240285158157,2.74599003792 --11.3238935471,-0.240285843611,2.73079872131 --11.3158864975,-0.240285679698,2.69039177895 --11.2918806076,-0.240284815431,2.64597702026 --11.2558765411,-0.239283397794,2.59956479073 --11.2978639603,-0.239285558462,2.57117247581 --11.3388519287,-0.240287780762,2.54379558563 --11.3708400726,-0.240289658308,2.51340794563 --11.3748369217,-0.240290060639,2.49520754814 --11.4318237305,-0.240293309093,2.46982431412 --11.4348144531,-0.240293964744,2.43242478371 --11.4018106461,-0.240292802453,2.3870100975 --11.3838043213,-0.240292400122,2.3445956707 --11.5617761612,-0.240302801132,2.32707691193 --11.6307630539,-0.240307316184,2.30370783806 --11.6497545242,-0.240309253335,2.26830554008 --11.657746315,-0.24031059444,2.23191261292 --11.6997356415,-0.240313947201,2.20152521133 --11.7347259521,-0.241317003965,2.17014122009 --11.7617168427,-0.241319686174,2.13675117493 --11.796710968,-0.24132232368,2.12456941605 --11.831700325,-0.241325646639,2.09218025208 --11.8606920242,-0.241328671575,2.05879163742 --11.8986825943,-0.241332381964,2.02640175819 --11.9286737442,-0.241335660219,1.99301505089 --11.9496660233,-0.241338446736,1.95762205124 --12.0156545639,-0.241344258189,1.93025112152 --12.0346498489,-0.241346299648,1.91406011581 --12.0846405029,-0.241351246834,1.88368499279 --12.1146316528,-0.242354989052,1.84929740429 --12.1586227417,-0.242359787226,1.81691420078 --12.1746168137,-0.242362767458,1.77951622009 --12.2216081619,-0.242367953062,1.74814414978 --12.2476005554,-0.242371827364,1.71174740791 --12.2935943604,-0.2423761338,1.69957411289 --12.3155879974,-0.242379829288,1.66318488121 --12.3685789108,-0.242385923862,1.63080513477 --12.4815654755,-0.243396684527,1.60645008087 --12.5325584412,-0.243402913213,1.57408058643 --12.5575523376,-0.243407323956,1.53668797016 --12.62454319,-0.243415087461,1.50531959534 --12.6585388184,-0.243419110775,1.48913145065 --12.6855335236,-0.243423953652,1.45174252987 --12.7325258255,-0.243430450559,1.41736888885 --12.7735204697,-0.243436679244,1.38098275661 --12.8015146255,-0.243441879749,1.3435986042 --12.8545074463,-0.244449332356,1.30821859837 --12.9005031586,-0.244454741478,1.29304122925 --12.9284982681,-0.244460269809,1.25465273857 --12.9744920731,-0.244467437267,1.21827459335 --13.0134868622,-0.244474127889,1.18089330196 --13.0514822006,-0.244480833411,1.14351475239 --13.0914764404,-0.244487896562,1.10512757301 --13.1324710846,-0.244495093822,1.06775212288 --13.1784667969,-0.245502978563,1.02936732769 --13.2224626541,-0.245508790016,1.01319611073 --13.2434597015,-0.245514512062,0.972805738449 --13.2934551239,-0.24552308023,0.93442595005 --13.3424501419,-0.245531663299,0.896049320698 --13.3834466934,-0.245539620519,0.856668293476 --13.4094438553,-0.245546221733,0.816283464432 --13.4424409866,-0.245553642511,0.775898754597 --11.9534893036,-0.241408914328,0.645958185196 --11.9624853134,-0.241412505507,0.608562231064 --12.0024795532,-0.241419270635,0.573181688786 --12.0424757004,-0.241426229477,0.536793172359 --12.1184692383,-0.241436928511,0.503434360027 --13.7084236145,-0.246605291963,0.554822802544 --12.1814632416,-0.24144808948,0.448861926794 --12.2054576874,-0.241453781724,0.411473959684 --12.4194507599,-0.24247983098,0.383181005716 --12.2574501038,-0.242465913296,0.335692465305 --12.252448082,-0.24146874249,0.29628610611 --12.0384483337,-0.241448611021,0.248775273561 --12.06944561,-0.241455197334,0.212397485971 --12.1164426804,-0.241462141275,0.194213911891 --12.0714406967,-0.241460368037,0.154794856906 --11.8904399872,-0.240443110466,0.111300975084 --11.9574365616,-0.241454020143,0.0749307572842 --12.0304327011,-0.24146579206,0.0385665036738 --12.3634262085,-0.242508262396,0.00633195275441 --11.7894287109,-0.240444228053,-0.042368106544 --11.8394269943,-0.240451708436,-0.0595342554152 --11.9044237137,-0.240462854505,-0.0969078019261 --12.0284194946,-0.241481259465,-0.133240193129 --12.0044183731,-0.241481944919,-0.171655267477 --12.1764154434,-0.241506829858,-0.209973067045 --12.0564136505,-0.241495743394,-0.248436450958 --11.92441082,-0.240482911468,-0.28590464592 --11.9004096985,-0.240481749177,-0.305122554302 --12.1674089432,-0.241519406438,-0.345384716988 --11.8434047699,-0.240481778979,-0.379955202341 --11.8004016876,-0.240479916334,-0.417384594679 --11.8724002838,-0.240492969751,-0.45574349165 --12.5594053268,-0.242587432265,-0.508787512779 --12.5624055862,-0.242592409253,-0.548181295395 --12.0993976593,-0.241532951593,-0.556633651257 --12.0283946991,-0.241527438164,-0.592063009739 --11.8273906708,-0.240504324436,-0.624580562115 --11.9413900375,-0.241523876786,-0.665917575359 --11.9423894882,-0.241528168321,-0.704322755337 --11.9423875809,-0.241532281041,-0.741718173027 --12.1843919754,-0.241570577025,-0.790993869305 --12.2993946075,-0.242589145899,-0.816136717796 --12.2193918228,-0.241582363844,-0.850573837757 --11.9963846207,-0.241555035114,-0.878099679947 --12.1053876877,-0.241575270891,-0.922442555428 --12.0193834305,-0.241567328572,-0.955890238285 --11.8653783798,-0.24054916203,-0.984373152256 --12.0283823013,-0.241577893496,-1.03369438648 --11.9493789673,-0.241568371654,-1.04693138599 --12.3053922653,-0.242626488209,-1.11013972759 --12.6044034958,-0.24367685616,-1.17137825489 --16.0425434113,-0.255207180977,-1.47593069077 --12.229388237,-0.242630213499,-1.22238945961 --16.2055644989,-0.255252033472,-1.5916377306 --12.1783866882,-0.241632550955,-1.296220541 --12.1373844147,-0.241628602147,-1.31143677235 --16.3635902405,-0.256302446127,-1.73554801941 --16.4186019897,-0.256321668625,-1.79291510582 --16.4916133881,-0.25634393096,-1.85227131844 --16.5516242981,-0.256364554167,-1.91164052486 --16.6146354675,-0.256385713816,-1.97100245953 --16.6926422119,-0.257403850555,-2.00515365601 --16.7586555481,-0.257426083088,-2.06652021408 --16.8226699829,-0.257447957993,-2.12687897682 --16.883682251,-0.257469773293,-2.1882455349 --16.9566955566,-0.25849366188,-2.25059890747 --17.0117092133,-0.258514881134,-2.31196737289 --17.0887260437,-0.258540064096,-2.37632274628 --17.1587352753,-0.258558154106,-2.4124815464 --17.2257499695,-0.259582132101,-2.4768447876 --17.2997646332,-0.259607255459,-2.5411939621 --17.3597831726,-0.259630531073,-2.60556101799 --17.4327983856,-0.259656280279,-2.67191886902 --17.5048141479,-0.260682046413,-2.73827385902 --17.5878334045,-0.260710000992,-2.80662226677 --15.0306358337,-0.252255052328,-2.46024703979 --15.0576448441,-0.25226983428,-2.51262760162 --14.7576265335,-0.251225054264,-2.51620030403 --14.5976200104,-0.250205159187,-2.53868603706 --14.4706163406,-0.250191181898,-2.56615924835 --14.4256191254,-0.250192165375,-2.60558104515 --13.981584549,-0.249117955565,-2.5792350769 --14.1196012497,-0.249148592353,-2.62535858154 --14.3016242981,-0.250192284584,-2.70164680481 --14.2366247177,-0.249189302325,-2.7370839119 --14.2896375656,-0.250209093094,-2.79345655441 --14.2206373215,-0.249205306172,-2.827896595 --13.8246040344,-0.248137146235,-2.80152130127 --13.8026075363,-0.248141944408,-2.8429350853 --14.0206346512,-0.249189794064,-2.90701198578 --14.0066394806,-0.249196484685,-2.9504199028 --13.8156261444,-0.248167529702,-2.95892691612 --13.7656269073,-0.248166710138,-2.99435400963 --13.5216054916,-0.24712638557,-2.99089860916 --13.4306020737,-0.247116655111,-3.01634597778 --13.3996047974,-0.24711933732,-3.0547683239 --13.4016075134,-0.247124165297,-3.07696318626 --13.2515964508,-0.247101917863,-3.08945131302 --13.1035852432,-0.246079817414,-3.10194325447 --13.1195926666,-0.246092036366,-3.1493370533 --13.0165863037,-0.246078908443,-3.16979575157 --13.0916023254,-0.246103778481,-3.23015189171 --13.2066230774,-0.247137621045,-3.30048656464 --13.1946249008,-0.247139587998,-3.31969261169 --13.0926179886,-0.246126592159,-3.34015583992 --13.2196416855,-0.247163459659,-3.41347408295 --13.1766433716,-0.247163444757,-3.44790363312 --13.3116693497,-0.24720287323,-3.52522420883 --13.2976751328,-0.247209429741,-3.56663346291 --13.3526906967,-0.247231498361,-3.62499856949 --13.0796556473,-0.246174648404,-3.57836008072 --12.9586448669,-0.246156662703,-3.59183526039 --12.9196462631,-0.246157050133,-3.62525629997 --12.8346405029,-0.246147066355,-3.64771699905 --12.8246459961,-0.246153995395,-3.68811869621 --12.848657608,-0.246169090271,-3.73850750923 --12.7656478882,-0.246154353023,-3.73775696754 --12.8026609421,-0.246172457933,-3.79113221169 --12.7396583557,-0.246167108417,-3.81757283211 --12.7316646576,-0.246174752712,-3.85897898674 --12.7106685638,-0.246179252863,-3.89639019966 --12.993724823,-0.246257409453,-4.02161931992 --12.8677120209,-0.246236994863,-4.03010082245 --12.8487129211,-0.246237277985,-4.04630899429 --12.8937292099,-0.246258556843,-4.10468864441 --13.09877491,-0.247319310904,-4.20995616913 --12.4906749725,-0.245178461075,-4.07072925568 --12.960767746,-0.247306108475,-4.25884532928 --13.3758535385,-0.248421370983,-4.43299341202 --13.1528224945,-0.247376069427,-4.40953063965 --13.1818332672,-0.247388958931,-4.44171380997 --13.4829006195,-0.248477190733,-4.58392953873 --13.6009349823,-0.249519318342,-4.669257164 --13.5719394684,-0.24952352047,-4.70666837692 --13.769990921,-0.250587254763,-4.81994867325 --14.0200529099,-0.250665426254,-4.9521985054 --13.2089014053,-0.248463839293,-4.72809505463 --13.1909093857,-0.248470664024,-4.76850509644 --13.3939571381,-0.248530730605,-4.86158180237 --13.2339353561,-0.248499929905,-4.85408353806 --13.1379261017,-0.248485893011,-4.86754274368 --13.2059526443,-0.248516350985,-4.93890571594 --17.5078926086,-0.263703525066,-6.51663303375 --17.442899704,-0.263705074787,-6.55607128143 --17.4689178467,-0.263721764088,-6.59625053406 --17.1988811493,-0.263666450977,-6.56081676483 --25.522769928,-0.294007301331,-9.68907833099 --17.171918869,-0.263697206974,-6.67462778091 --17.2159538269,-0.263728886843,-6.75299596786 --17.1579627991,-0.26373192668,-6.79342937469 --25.8060131073,-0.295222520828,-10.1654567719 --25.9900779724,-0.296292334795,-10.2825345993 --17.2720489502,-0.263813763857,-6.99334859848 --26.4032707214,-0.297482103109,-10.6330528259 --26.4673366547,-0.29853707552,-10.7554044724 --26.9015426636,-0.299738079309,-11.1239080429 --27.58776474,-0.302979439497,-11.5018672943 --26.4625053406,-0.298663437366,-11.0927610397 --25.6423473358,-0.295454710722,-10.8526620865 --27.8789730072,-0.304164558649,-11.8766479492 --26.3026161194,-0.298726439476,-11.3190231323 --28.1551532745,-0.305329203606,-12.2012491226 --22.2626419067,-0.283561646938,-9.79134654999 --22.1446495056,-0.283555626869,-9.82381248474 --16.891248703,-0.263944298029,-7.59534835815 --16.8312587738,-0.263946503401,-7.63278341293 --16.7882728577,-0.263953864574,-7.6772069931 --16.7442855835,-0.263961076736,-7.72163438797 --16.7193050385,-0.263974189758,-7.77404785156 --16.6923236847,-0.263986647129,-7.82546186447 --16.6593379974,-0.263997167349,-7.87387800217 --16.6763572693,-0.264013111591,-7.91306304932 --20.9906425476,-0.28043025732,-9.96368694305 --20.8706474304,-0.27942109108,-9.98915958405 --20.8616828918,-0.279447466135,-10.0645551682 --21.5619335175,-0.282707631588,-10.4754962921 --21.5389671326,-0.282731235027,-10.5479021072 --21.5800228119,-0.282776296139,-10.651268959 --21.4299983978,-0.282742202282,-10.6215648651 --21.5310726166,-0.28280749917,-10.7538909912 --21.5281124115,-0.28283816576,-10.8362827301 --25.1883144379,-0.2971136868,-12.7263031006 --24.8232536316,-0.296028375626,-12.6439285278 --26.9189815521,-0.304787367582,-13.7919569016 --25.137462616,-0.298214823008,-12.998500824 --24.2402515411,-0.294962018728,-12.6896677017 --26.496055603,-0.303791582584,-13.9485874176 --23.0659637451,-0.290625214577,-12.2742166519 --22.3437690735,-0.287406057119,-11.9900856018 --26.449224472,-0.303905308247,-14.2427797318 --26.3512516022,-0.303913891315,-14.2972297668 --26.0641822815,-0.302832603455,-14.1976118088 --22.470035553,-0.288612157106,-12.4647579193 --22.3510456085,-0.288605362177,-12.4922294617 --22.2680664062,-0.288611441851,-12.5386772156 --21.8329582214,-0.28748691082,-12.3893556595 --21.8450126648,-0.287527441978,-12.4867420197 --22.8644142151,-0.290925890207,-13.1022596359 --21.8270816803,-0.287574857473,-12.6123399734 --21.7611083984,-0.287586331367,-12.6657752991 --21.7371501923,-0.287613779306,-12.7431840897 --21.6981868744,-0.287635415792,-12.8115997314 --22.4545288086,-0.290962785482,-13.3424873352 --22.4285469055,-0.290972054005,-13.3746995926 --22.3455677032,-0.290978729725,-13.4211473465 --22.7207717896,-0.29216375947,-13.7382879257 --23.4681224823,-0.295495897532,-14.2791728973 --23.2300891876,-0.294443815947,-14.2367219925 --23.9234256744,-0.297760009766,-14.7556467056 --36.4585876465,-0.348792642355,-22.4775848389 --23.7064323425,-0.296738475561,-14.7783794403 --23.1022453308,-0.294539153576,-14.510178566 --23.3534088135,-0.29568234086,-14.7653961182 --35.7506637573,-0.347757786512,-22.5913848877 --23.8107910156,-0.298999845982,-15.3622560501 --35.4388542175,-0.346844404936,-22.864730835 --35.4979324341,-0.347904771566,-22.98087883 --35.4450149536,-0.34795486927,-23.1042938232 --35.4491271973,-0.348029404879,-23.2656707764 --35.5422782898,-0.349141538143,-23.4849834442 --17.4283485413,-0.273579567671,-11.8391952515 --17.3143386841,-0.272561877966,-11.8416652679 --17.3153629303,-0.273578375578,-11.8828668594 --17.1533317566,-0.272539645433,-11.8523721695 --16.969291687,-0.27149116993,-11.8068962097 --15.4986476898,-0.265880197287,-10.8833179474 --15.4496641159,-0.265886932611,-10.9227561951 --15.6167812347,-0.266988545656,-11.1100358963 --15.5687990189,-0.266995608807,-11.1494655609 --41.7914161682,-0.379678845406,-29.4724388123 --41.499420166,-0.378642141819,-29.4640140533 --41.5595932007,-0.37876239419,-29.701341629 --41.5837478638,-0.37986779213,-29.9156990051 --41.3497772217,-0.37885594368,-29.9452323914 --42.5705299377,-0.384509205818,-31.0227546692 --42.6807365417,-0.385658502579,-31.3070487976 --42.2646026611,-0.384516566992,-31.1075267792 --42.4118309021,-0.385683119297,-31.418794632 --42.1318397522,-0.384652346373,-31.4183616638 --41.8968696594,-0.383641988039,-31.4498996735 --41.6498985291,-0.383625000715,-31.4704456329 --41.0357246399,-0.381433218718,-31.2132492065 --41.1849555969,-0.382603079081,-31.5295181274 --41.254070282,-0.382685512304,-31.6836547852 --41.117149353,-0.382719576359,-31.784122467 --40.9452095032,-0.382736742496,-31.8576183319 --40.7302474976,-0.381732732058,-31.8971424103 --40.4462471008,-0.381694465876,-31.8817157745 --40.3923721313,-0.381768018007,-32.044128418 --40.3354949951,-0.381840854883,-32.2055397034 --40.3415794373,-0.381894469261,-32.3137245178 --40.1876487732,-0.3819193542,-32.3982086182 --40.1257705688,-0.381989955902,-32.5556221008 --40.2339935303,-0.38314718008,-32.8519210815 --40.0130271912,-0.383138626814,-32.8824539185 --40.0271949768,-0.38324919343,-33.1038169861 --31.7264709473,-0.346097558737,-26.4771518707 --31.6514911652,-0.345099508762,-26.4993991852 --39.0750350952,-0.380018442869,-32.8414344788 --31.5786991119,-0.34622451663,-26.7762145996 --30.4381351471,-0.340710282326,-25.9854221344 --30.3482017517,-0.340741813183,-26.0728683472 --30.3523292542,-0.341823518276,-26.2412471771 --30.8206768036,-0.344111889601,-26.7251014709 --30.4525756836,-0.342997282743,-26.576751709 --30.1985416412,-0.341942340136,-26.5243206024 --30.1386318207,-0.341991275549,-26.6397476196 --30.1057357788,-0.342054575682,-26.7781543732 --29.985786438,-0.342071443796,-26.8416290283 --29.960899353,-0.342139750719,-26.98802948 --30.0310077667,-0.343218952417,-27.1341667175 --29.8960475922,-0.343227475882,-27.1836509705 --29.8251304626,-0.343271195889,-27.2900848389 --29.8542804718,-0.343370944262,-27.4874477386 --29.0128498077,-0.339982241392,-26.8904514313 --28.9909629822,-0.340052127838,-27.0388507843 --29.1872253418,-0.341246545315,-27.3900928497 --29.1072387695,-0.341243326664,-27.4023456573 --29.075345993,-0.341308474541,-27.5427494049 --29.692905426,-0.344749450684,-28.2966785431 --28.7854099274,-0.341310471296,-27.614736557 --28.644443512,-0.341313183308,-27.6532268524 --28.9537963867,-0.342579543591,-28.1223812103 --28.7718029022,-0.342558532953,-28.1218986511 --29.5485668182,-0.347151249647,-29.1429004669 --37.4336280823,-0.388076990843,-37.2847747803 --36.6684379578,-0.384849965572,-36.9891052246 --36.6255912781,-0.385942131281,-37.1785125732 --36.4775772095,-0.384910196066,-37.1448097229 --27.8283500671,-0.341777414083,-28.7800769806 --28.5790672302,-0.346335113049,-29.7298908234 --28.8994636536,-0.348629295826,-30.2470359802 --28.7745170593,-0.348645299673,-30.30651474 --28.9007663727,-0.34982085228,-30.6288051605 --28.8978424072,-0.349866867065,-30.7210006714 --28.2344665527,-0.346538245678,-30.211889267 --28.1255283356,-0.346562594175,-30.2843532562 --28.0816459656,-0.347629845142,-30.4277763367 --28.3239955902,-0.348883569241,-30.8789749146 --27.1002960205,-0.343272268772,-29.93268013 --28.3774318695,-0.351164460182,-31.4238967896 --26.9255275726,-0.344392865896,-30.2107791901 --26.8285980225,-0.3444237113,-30.2932434082 --26.6265792847,-0.343382954597,-30.2567844391 --26.171339035,-0.341168195009,-29.9315185547 --26.0844154358,-0.34120413661,-30.0219745636 --26.3206977844,-0.343414336443,-30.3859863281 --26.2107582092,-0.343435287476,-30.4514598846 --26.204908371,-0.343528538942,-30.6368522644 --26.3932323456,-0.345757842064,-31.0480899811 --26.2192363739,-0.344735443592,-31.0416145325 --26.1613445282,-0.344794392586,-31.17004776 --34.7353401184,-0.39399972558,-41.5217781067 --26.8662319183,-0.350448220968,-32.3030776978 --26.8023433685,-0.350507497787,-32.4325180054 --24.5283946991,-0.337969720364,-29.902677536 --24.4384651184,-0.337999939919,-29.982131958 --24.3355255127,-0.338022172451,-30.0486049652 --24.2766246796,-0.338075757027,-30.1670379639 --24.4128341675,-0.33922535181,-30.4311256409 --24.0696620941,-0.33806926012,-30.1997833252 --24.1559047699,-0.339231878519,-30.5001049042 --23.2391681671,-0.334643036127,-29.5462188721 --23.5966758728,-0.337009310722,-30.1863250732 --24.7519855499,-0.343987256289,-31.8488044739 --24.7311344147,-0.345076531172,-32.0272102356 --24.6292896271,-0.345157265663,-32.2058753967 --23.7515659332,-0.340581774712,-31.2719554901 --24.3303318024,-0.344138264656,-32.2318878174 --23.6157646179,-0.340683788061,-31.4998455048 --22.5007686615,-0.334906756878,-30.2271232605 --22.4969291687,-0.335003852844,-30.4175167084 --22.6221427917,-0.3361543715,-30.6836090088 --22.2919578552,-0.334991902113,-30.4392662048 --22.2270545959,-0.335041284561,-30.5497074127 --23.7768993378,-0.345405578613,-32.8658599854 --22.8570785522,-0.339763641357,-31.816986084 --21.4368572235,-0.332803070545,-30.2599086761 --21.3908901215,-0.332815945148,-30.2951412201 --21.7995166779,-0.336261123419,-31.0702037811 --20.9797611237,-0.331676065922,-30.1142559052 --21.1190891266,-0.332897514105,-30.5135383606 --20.9310436249,-0.331840842962,-30.4450798035 --20.978269577,-0.332986176014,-30.7164344788 --21.235742569,-0.335314422846,-31.2956161499 --21.9086208344,-0.339952588081,-32.3832702637 --21.6394882202,-0.338830441236,-32.204875946 --21.4774780273,-0.338800400496,-32.1814002991 --21.4336109161,-0.338874220848,-32.3328285217 --21.3006362915,-0.338869184256,-32.3513298035 --21.1856842041,-0.338880181313,-32.396812439 --17.9528961182,-0.318080693483,-27.7038497925 --21.0608119965,-0.338939666748,-32.5375022888 --20.7798442841,-0.338914990425,-32.5495185852 --18.39702034,-0.3228328228,-29.0618667603 --20.5138912201,-0.337902843952,-32.5825233459 --20.653263092,-0.340150237083,-33.0267982483 --15.9964227676,-0.308886498213,-25.8510303497 --15.8543128967,-0.307798296213,-25.7143478394 --15.7613391876,-0.307800173759,-25.7418193817 --15.6693687439,-0.307804256678,-25.7732963562 --15.6064348221,-0.307835131884,-25.8497428894 --15.4704036713,-0.307795614004,-25.8072547913 --15.3634109497,-0.307783901691,-25.8117408752 --15.3084135056,-0.307776808739,-25.8119869232 --15.3025588989,-0.307864367962,-25.9843883514 --15.3017129898,-0.307957798243,-26.1667881012 --15.5141677856,-0.310266047716,-26.7130088806 --15.4111833572,-0.310260236263,-26.7274913788 --15.5094861984,-0.311458051205,-27.0868034363 --20.9224071503,-0.352089047432,-36.6546783447 --20.8204956055,-0.352124303579,-36.741153717 --25.6045532227,-0.388134360313,-45.2493553162 --25.4926872253,-0.38819539547,-45.3818397522 --15.0135192871,-0.311401277781,-27.1000156403 --14.9275617599,-0.311413198709,-27.1444835663 --13.6748504639,-0.302184939384,-25.0839366913 --13.5958881378,-0.302195429802,-25.1254043579 --16.6546192169,-0.325527876616,-30.7950229645 --16.5536632538,-0.32553768158,-30.8365020752 --16.4557132721,-0.325552076101,-30.8859844208 --16.3677787781,-0.325576037169,-30.9514503479 --16.268825531,-0.325588732958,-30.9979324341 --16.2329750061,-0.32667195797,-31.1643600464 --13.1873006821,-0.303380131721,-25.5923500061 --13.2524881363,-0.303503334522,-25.813495636 --13.0663547516,-0.303393959999,-25.6510543823 --13.1797094345,-0.304624885321,-26.0673542023 --13.1007518768,-0.304637759924,-26.112821579 --12.5429954529,-0.301095098257,-25.2127017975 --12.4179534912,-0.300049990416,-25.1592082977 --12.3119430542,-0.300026625395,-25.1427001953 --12.2258806229,-0.29997587204,-25.0679779053 --12.0948238373,-0.298920959234,-24.9974880219 --12.0729570389,-0.29999729991,-25.1509094238 --5.52564287186,-0.245175361633,-11.8470449448 --5.49766302109,-0.245184272528,-11.8824796677 --5.40964412689,-0.245161429048,-11.8833656311 --5.41969871521,-0.245196506381,-11.9535675049 --11.926856041,-0.302510291338,-26.1766414642 --11.9651145935,-0.303670853376,-26.4740104675 --16.8194332123,-0.34801787138,-37.3331947327 --22.2530288696,-0.397218495607,-49.6558837891 --15.4993400574,-0.337553441525,-34.8709373474 --15.3613376617,-0.337527930737,-34.8524513245 --15.0099191666,-0.335220426321,-34.3521537781 --14.9210071564,-0.335257530212,-34.4406318665 --14.6898145676,-0.33410397172,-34.2032279968 --11.3353643417,-0.30371516943,-26.724565506 --21.5832862854,-0.400838345289,-50.9010047913 --12.5112915039,-0.317648172379,-30.0895366669 --12.4073123932,-0.316642582417,-30.1040287018 --12.2862987518,-0.316613584757,-30.0785369873 --12.3336381912,-0.317822307348,-30.4598960876 --12.2216434479,-0.317806184292,-30.4563961029 --12.2460670471,-0.320060431957,-30.9279766083 --12.2082357407,-0.320153474808,-31.1114063263 --12.0331048965,-0.319045722485,-30.9509620667 --9.43154335022,-0.294317424297,-24.5856781006 --9.31849098206,-0.29326748848,-24.5231876373 --9.22247314453,-0.29324054718,-24.4996757507 --9.12244415283,-0.293206632137,-24.4641666412 --9.06541347504,-0.293179124594,-24.4284191132 --8.97641086578,-0.293162584305,-24.4229030609 --8.88640213013,-0.293142139912,-24.4103851318 --8.81042957306,-0.293145388365,-24.4388599396 --8.84873104095,-0.294329941273,-24.7782249451 --19.1632041931,-0.407105356455,-53.6054039001 --7.6732583046,-0.282671362162,-21.976102829 --10.9144239426,-0.319036394358,-31.2013759613 --7.26151132584,-0.279161065817,-21.1330852509 --7.17246866226,-0.279121220112,-21.086566925 --7.08944272995,-0.279091745615,-21.0580501556 --7.02446174622,-0.279091984034,-21.0805130005 --6.95546865463,-0.279084742069,-21.0899791718 --6.92357683182,-0.279143035412,-21.2124156952 --6.89259195328,-0.279146581888,-21.2296485901 --6.8005399704,-0.279100209475,-21.1721401215 --10.2161064148,-0.320310473442,-31.8794250488 --10.1121311188,-0.320305854082,-31.8959197998 --10.0171823502,-0.32031801343,-31.9414081573 --6.41826915741,-0.277875721455,-20.8741111755 --6.3732419014,-0.276851952076,-20.8443565369 --6.264128685,-0.276766866446,-20.7198638916 --6.21819877625,-0.276800125837,-20.7993125916 --6.16725492477,-0.276824116707,-20.8627662659 --6.10828733444,-0.276833027601,-20.900226593 --6.04731369019,-0.27683788538,-20.9306869507 --5.92114305496,-0.276716083288,-20.7432155609 --5.87911844254,-0.276694238186,-20.7164535522 --5.82716989517,-0.276715368032,-20.7749061584 --5.77322053909,-0.276735663414,-20.8323669434 --5.7222776413,-0.276760220528,-20.8968200684 --5.67735767365,-0.276799112558,-20.9862689972 --5.62039756775,-0.276812583208,-21.0317287445 --5.61160087585,-0.27792969346,-21.2561397552 --5.62075376511,-0.278020441532,-21.4243392944 --5.52065134048,-0.277942985296,-21.3128376007 --5.41854000092,-0.277859717607,-21.1913394928 --5.41176128387,-0.277987599373,-21.4347515106 --5.34578037262,-0.277986854315,-21.4562244415 --6.73004865646,-0.300305217505,-27.2153224945 --6.6530995369,-0.300320625305,-27.2657985687 --5.73717260361,-0.288450241089,-24.0662708282 --7.28738307953,-0.313344359398,-30.8272132874 --5.60728502274,-0.288491487503,-24.1842079163 --6.86694192886,-0.312008231878,-30.3198242188 --6.80208873749,-0.312080800533,-30.4702892303 --9.34267139435,-0.35569152236,-41.9341011047 --6.69427156448,-0.313165903091,-30.6549987793 --5.39759159088,-0.293209671974,-25.5810489655 --5.27944087982,-0.292099952698,-25.4145679474 --4.74142360687,-0.283830821514,-23.2374897003 --5.22092056274,-0.294366538525,-25.9244327545 --4.6284236908,-0.283809304237,-23.2352085114 --4.56145954132,-0.283817499876,-23.2726783752 --4.47540903091,-0.28377199173,-23.2171707153 --4.41146183014,-0.283790409565,-23.2726402283 --4.88613843918,-0.294427990913,-26.1395835876 --4.76797294617,-0.294309556484,-25.9581069946 --4.20536565781,-0.283695727587,-23.1668567657 --4.13940668106,-0.283706694841,-23.2093257904 --4.0704369545,-0.283711135387,-23.2408046722 --4.03765296936,-0.284829676151,-23.4702377319 --3.98276495934,-0.284883499146,-23.5877017975 --3.90575289726,-0.284861564636,-23.5731811523 --4.0701007843,-0.289670586586,-25.0044269562 --3.89958429337,-0.288339704275,-24.4530029297 --3.80727672577,-0.287144422531,-24.1252994537 --3.72122168541,-0.28609585762,-24.0647907257 --3.62711143494,-0.28601410985,-23.9462871552 --3.56318759918,-0.286045312881,-24.0247592926 --3.49121546745,-0.28604722023,-24.052236557 --3.48063898087,-0.28828895092,-24.4976539612 --3.49499034882,-0.289493709803,-24.8668441772 --3.42001533508,-0.289493173361,-24.8903236389 --3.4155254364,-0.290785580873,-25.4247360229 --3.25395512581,-0.288425505161,-24.8213024139 --3.16186213493,-0.288353651762,-24.7208061218 --3.09595179558,-0.288391977549,-24.8122787476 --2.98167681694,-0.287210911512,-24.5207996368 --1.8633595705,-0.255211174488,-15.8041601181 --1.81032514572,-0.25518143177,-15.7746257782 --1.76535367966,-0.2551895082,-15.8110818863 --2.88311219215,-0.29301482439,-26.0123214722 --2.80615592003,-0.293024092913,-26.0538063049 --2.76249194145,-0.294207841158,-26.4002552032 --2.68656110764,-0.294231772423,-26.4677391052 --2.64960551262,-0.295249730349,-26.5119819641 --2.33538866043,-0.285914868116,-24.2017116547 --2.48764777184,-0.295240491629,-26.5469589233 --2.22481060028,-0.288134068251,-24.6356391907 --2.3388428688,-0.295321166515,-26.7399253845 --2.25382947922,-0.295295804739,-26.7214183807 --2.17386817932,-0.295301288366,-26.7569065094 --2.13288354874,-0.295301377773,-26.7701530457 --2.03673362732,-0.295195519924,-26.6106586456 --1.9486746788,-0.294143259525,-26.5451583862 --1.87580156326,-0.295200526714,-26.6716365814 --1.79179573059,-0.295179545879,-26.6611328125 --1.71792531013,-0.295237839222,-26.7896137238 --1.64306735992,-0.296303272247,-26.9311008453 --1.60512447357,-0.296327829361,-26.9873428345 --1.53026914597,-0.296394467354,-27.1308231354 --1.47071921825,-0.298638850451,-27.5872936249 --1.99704825878,-0.341220468283,-39.1861343384 --2.20865559578,-0.366037160158,-45.9303207397 --1.79600453377,-0.344721257687,-40.1291542053 --1.66487777233,-0.344619750977,-39.9816970825 --1.76264965534,-0.358792811632,-43.8227920532 --1.63182377815,-0.358862519264,-43.9783325195 --1.74478459358,-0.385856747627,-51.0476112366 --1.58685016632,-0.385857969522,-51.0851783752 --1.4527233839,-0.388324797153,-51.9437217712 --1.29074263573,-0.388298511505,-51.9332923889 --1.12984859943,-0.389321893454,-52.0108680725 --1.05407464504,-0.389433145523,-52.2251434326 --0.888997375965,-0.389351010323,-52.1167221069 --0.727088987827,-0.389365673065,-52.1792984009 --0.567372441292,-0.390490084887,-52.4358634949 --0.404456496239,-0.390500038862,-52.4904403687 --0.241579309106,-0.39053195715,-52.5840148926 --0.158338949084,-0.389375627041,-52.3263053894 -0.0551149249077,-0.329362571239,-43.1872329712 -0.192055001855,-0.329432487488,-43.1495094299 -0.329004049301,-0.32949718833,-43.1207885742 -0.463864207268,-0.329611927271,-43.0020713806 -0.599773108959,-0.328699231148,-42.9323501587 -0.738952577114,-0.329632997513,-43.1366271973 -0.81005102396,-0.32959535718,-43.2477645874 -0.95437669754,-0.331446886063,-43.6010360718 -1.08503580093,-0.330674856901,-43.2783203125 -1.35573375225,-0.34306666255,-48.0754737854 -1.34140849113,-0.329098463058,-42.6859016418 -1.47534358501,-0.329169839621,-42.6421852112 -1.60824656487,-0.328259319067,-42.5654716492 -1.67216026783,-0.328324794769,-42.488609314 -1.75594580173,-0.325038671494,-41.2709465027 -1.87670326233,-0.325207710266,-41.0442428589 -2.10327887535,-0.326937168837,-41.6646461487 -2.18429970741,-0.324516177177,-40.6829833984 -2.30410766602,-0.323656260967,-40.5062828064 -2.35894846916,-0.323760688305,-40.3534355164 -2.48387002945,-0.322837263346,-40.2927284241 -2.60372638702,-0.322949558496,-40.1650314331 -2.73169922829,-0.322997272015,-40.1573219299 -2.86778593063,-0.322982162237,-40.2666091919 -2.988676548,-0.323074907064,-40.1739082336 -3.11563372612,-0.323130995035,-40.1501998901 -3.16545820236,-0.322243839502,-39.9783554077 -3.29445624352,-0.323277026415,-39.9966506958 -3.40726327896,-0.322415232658,-39.8169593811 -3.52715873718,-0.322504878044,-39.7282600403 -3.66323232651,-0.322496652603,-39.824546814 -3.79324936867,-0.322519242764,-39.8618354797 -3.91314959526,-0.322605848312,-39.7781410217 -3.97916316986,-0.322614371777,-39.8022880554 -4.10714387894,-0.322657316923,-39.8015861511 -4.23512935638,-0.322696834803,-39.8068771362 -4.35302734375,-0.322784096003,-39.7201805115 -4.46688842773,-0.322891056538,-39.5954933167 -4.58277845383,-0.321982443333,-39.499797821 -4.6376991272,-0.322040975094,-39.4269561768 -4.80298519135,-0.322918087244,-39.7462158203 -4.94407176971,-0.323903262615,-39.8564987183 -5.06701040268,-0.32396787405,-39.8128013611 -5.31084012985,-0.325553864241,-40.7039871216 -5.40052556992,-0.32575494051,-40.3943214417 -5.51438570023,-0.324862360954,-40.2676315308 -5.55520820618,-0.324973583221,-40.0908050537 -5.46469926834,-0.320812225342,-38.5213127136 -5.58867645264,-0.320855379105,-38.5156135559 -5.69755887985,-0.319948792458,-38.4099273682 -5.81046915054,-0.320026814938,-38.3342399597 -5.93142700195,-0.320079743862,-38.3085441589 -6.06245136261,-0.320097237825,-38.3528404236 -6.10029649734,-0.320194602013,-38.1980133057 -6.21321249008,-0.320269495249,-38.12733078 -6.34323120117,-0.32028979063,-38.1656227112 -6.49637079239,-0.321246445179,-38.332901001 -6.64045953751,-0.32122990489,-38.4461898804 -6.74533033371,-0.321328312159,-38.327507019 -6.87031126022,-0.321368724108,-38.3258132935 -6.94636964798,-0.321353167295,-38.3979492188 -7.2351899147,-0.323953509331,-39.2931022644 -7.41442584991,-0.32486101985,-39.5653572083 -7.55245018005,-0.324879318476,-39.6116447449 -7.69047021866,-0.324900329113,-39.6529388428 -7.81542348862,-0.324955970049,-39.6232452393 -12.6022500992,-0.389629095793,-63.0902252197 -8.00737667084,-0.325027048588,-39.6036987305 -8.12027645111,-0.325110375881,-39.5160140991 -8.20203971863,-0.325264066458,-39.2813606262 -8.27477073669,-0.324434369802,-39.0107116699 -8.42182922363,-0.324434697628,-39.0939979553 -8.54879570007,-0.324482679367,-39.0783081055 -8.60274410248,-0.324524879456,-39.031463623 -6.093708992,-0.292234778404,-27.1082248688 -6.16964626312,-0.291288763285,-27.0465698242 -6.25963449478,-0.291316598654,-27.0409107208 -9.10258674622,-0.324728399515,-38.9406967163 -9.23357486725,-0.324764609337,-38.9479980469 -6.23246145248,-0.288980156183,-25.7851963043 -6.33066654205,-0.288886010647,-26.0113182068 -10.3645677567,-0.334317296743,-42.2590179443 -10.51704216,-0.333650499582,-41.7317276001 -10.5195245743,-0.331945061684,-41.1891479492 -10.6564950943,-0.331992328167,-41.1794471741 -16.5289726257,-0.387360066175,-60.505027771 -8.6001739502,-0.301404625177,-29.9627132416 -8.68711566925,-0.301456987858,-29.9090557098 -8.76803779602,-0.301519811153,-29.8324050903 -8.85297298431,-0.301575660706,-29.7707538605 -8.93891239166,-0.301629066467,-29.7140960693 -9.02084064484,-0.30168813467,-29.6444454193 -9.10176849365,-0.300747364759,-29.5737953186 -9.14072608948,-0.30078047514,-29.5309734344 -9.21864509583,-0.300843447447,-29.4513244629 -9.30057525635,-0.300901085138,-29.3836784363 -9.39053344727,-0.300945043564,-29.3460178375 -9.42934322357,-0.301061183214,-29.1444072723 -9.53635025024,-0.30108115077,-29.1607322693 -9.68947982788,-0.301040679216,-29.3160190582 -18.6356983185,-0.379228621721,-56.4492416382 -13.445763588,-0.331582278013,-39.7637214661 -13.5636873245,-0.331650644541,-39.6990432739 -13.6916360855,-0.331707000732,-39.6623535156 -13.8486585617,-0.331727176905,-39.7096443176 -15.0956583023,-0.34229272604,-43.1007537842 -15.3278360367,-0.343240648508,-43.3269729614 -14.9805593491,-0.338890165091,-41.9097099304 -19.1254177094,-0.372183322906,-53.0814781189 -19.6241378784,-0.374878793955,-53.9354705811 -19.8151016235,-0.374938517809,-53.9317359924 -19.900812149,-0.374120235443,-53.6390914917 -19.4154109955,-0.36981087923,-52.0667381287 -19.5733108521,-0.369899362326,-51.9890327454 -20.2373886108,-0.373427093029,-53.2518806458 -19.7938899994,-0.369181632996,-51.5807037354 -20.9841499329,-0.377151101828,-54.1920928955 -21.1570625305,-0.377235382795,-54.1303787231 -21.3941173553,-0.378252238035,-54.2316093445 -20.3585796356,-0.36947119236,-51.3487243652 -20.5004482269,-0.369573950768,-51.233039856 -20.7515563965,-0.37056401372,-51.3912506104 -20.9695892334,-0.370589673519,-51.4634971619 -21.1335048676,-0.370669990778,-51.4017868042 -21.3815937042,-0.371668428183,-51.5420074463 -21.5535259247,-0.371741890907,-51.4972915649 -20.7576560974,-0.365633517504,-49.36120224 -21.9426898956,-0.372726798058,-51.7406082153 -22.1526927948,-0.372766882181,-51.7798614502 -22.2143974304,-0.372945398092,-51.4732437134 -22.3592720032,-0.372044444084,-51.3635520935 -22.6344032288,-0.373024821281,-51.5517539978 -22.935585022,-0.373983383179,-51.7959289551 -22.9934883118,-0.374047368765,-51.7050971985 -23.4780158997,-0.376847267151,-52.3531188965 -23.0928668976,-0.372415870428,-51.0528869629 -22.9762477875,-0.370740264654,-50.3664245605 -23.2153091431,-0.371753394604,-50.4706535339 -23.3521709442,-0.371856123209,-50.3469734192 -23.7186584473,-0.373655349016,-50.9318771362 -25.1358699799,-0.381692945957,-53.5531044006 -24.3981208801,-0.376528292894,-51.5441741943 -24.6281452179,-0.376558840275,-51.609413147 -24.794052124,-0.376642763615,-51.5367126465 -24.935918808,-0.376744657755,-51.4160308838 -25.7619857788,-0.381307810545,-52.7057685852 -25.7207183838,-0.38044911623,-52.4100189209 -25.8826141357,-0.380539298058,-52.3223228455 -18.8281478882,-0.335149109364,-37.6557426453 -26.178352356,-0.380741238594,-52.0889511108 -26.3202133179,-0.379845410585,-51.962272644 -29.4821090698,-0.398716151714,-57.7940444946 -29.718082428,-0.399775475264,-57.8062858582 -30.076461792,-0.401631295681,-58.279209137 -30.3885536194,-0.401638507843,-58.433391571 -31.0383548737,-0.402871072292,-58.3301773071 -33.4847946167,-0.416414856911,-62.4795684814 -31.6895580292,-0.404879897833,-58.6615180969 -29.8334712982,-0.393249422312,-54.9952926636 -29.8931846619,-0.392419964075,-54.6926879883 -30.0039749146,-0.392556130886,-54.4840354919 -30.1518287659,-0.392665892839,-54.3463592529 -30.3197097778,-0.392762541771,-54.2446632385 -30.524646759,-0.39283439517,-54.2109336853 -30.7325878143,-0.392905861139,-54.1792030334 -30.9166755676,-0.393890887499,-54.3052749634 -33.0093612671,-0.404787480831,-57.5819892883 -33.4215698242,-0.405746430159,-57.8800888062 -33.8133201599,-0.387363493443,-48.7953948975 -23.4717388153,-0.318735003471,-25.9013996124 -40.9063491821,-0.395704269409,-45.103553772 -55.7234115601,-0.450748234987,-56.3478507996 -38.4700965881,-0.377123981714,-38.553188324 -38.4338722229,-0.377238601446,-38.2736663818 -38.3894424438,-0.375457763672,-37.7486076355 -38.6125106812,-0.376456797123,-37.8506622314 -50.4669570923,-0.425821572542,-49.2603225708 -50.6068000793,-0.425926327705,-49.0866851807 -50.9167671204,-0.42599260807,-49.0779190063 -51.1726913452,-0.427071511745,-49.0151977539 -49.7904586792,-0.420509845018,-47.3826789856 -23.1415157318,-0.310414373875,-21.7077960968 -23.029384613,-0.309466004372,-21.5321006775 -23.3825302124,-0.310444772243,-21.7292728424 -23.5535449982,-0.311463475227,-21.7515850067 -23.8146209717,-0.311463922262,-21.8568286896 -22.7818183899,-0.307729572058,-20.7620258331 -22.8347568512,-0.307770490646,-20.6784248352 -22.7676639557,-0.306809663773,-20.550693512 -23.1778411865,-0.308779686689,-20.7928314209 -23.1707401276,-0.307831943035,-20.6552696228 -16.0820045471,-0.279244959354,-14.1459035873 -16.0519237518,-0.279282927513,-14.0273599625 -16.0348567963,-0.278317391872,-13.9228000641 -15.549487114,-0.276438504457,-13.4035921097 -15.6064968109,-0.276442497969,-13.4117593765 -15.4703540802,-0.276496738195,-13.2062892914 -15.567360878,-0.276508778334,-13.2046527863 -15.7093963623,-0.276512503624,-13.2429742813 -15.104968071,-0.27464607358,-12.6388454437 -15.1659545898,-0.274663209915,-12.6082344055 -15.3800344467,-0.274654179811,-12.7085046768 -8.12059783936,-0.245886713266,-6.49449253082 -8.13358974457,-0.245894223452,-6.4619102478 -8.17159557343,-0.245897620916,-6.45030784607 -8.22761249542,-0.245897963643,-6.45467805862 -8.24960803986,-0.245904058218,-6.42909193039 -8.26460838318,-0.245906531811,-6.41929864883 -8.29761123657,-0.245910465717,-6.4046831131 -8.30960178375,-0.245917961001,-6.37110280991 -8.33960437775,-0.245922625065,-6.35250425339 -8.36560249329,-0.245927810669,-6.33090639114 -8.38759899139,-0.245933502913,-6.30630874634 -8.41459846497,-0.246938660741,-6.28471755981 -8.43660163879,-0.246940180659,-6.27992105484 -8.44859409332,-0.246947005391,-6.24832248688 -8.48059654236,-0.246951386333,-6.23072481155 -8.50459384918,-0.246956989169,-6.20614004135 -8.5305929184,-0.246961802244,-6.18552875519 -8.56059360504,-0.246966481209,-6.16593456268 -8.58459186554,-0.246971979737,-6.14134836197 -8.58958721161,-0.246975436807,-6.12455272675 -8.61558628082,-0.24698035419,-6.10295009613 -8.64858913422,-0.246984630823,-6.08535385132 -8.66758441925,-0.246990486979,-6.05776309967 -8.69658374786,-0.246995002031,-6.03815889359 -8.72458362579,-0.24699985981,-6.01656627655 -8.74758148193,-0.247005149722,-5.9919719696 -8.76958465576,-0.247006803751,-5.98617696762 -8.79358291626,-0.247011885047,-5.96257734299 -8.82158279419,-0.24701666832,-5.94098329544 -8.84458065033,-0.247021853924,-5.91638612747 -8.87057971954,-0.247026711702,-5.89378786087 -8.89958000183,-0.247031256557,-5.87318754196 -8.92057609558,-0.247036665678,-5.84659719467 -8.94358158112,-0.247038155794,-5.84179401398 -8.96957969666,-0.24704310298,-5.81820392609 -8.99457836151,-0.247048020363,-5.7946062088 -9.03058242798,-0.247051954269,-5.7780046463 -8.96854019165,-0.247064754367,-5.69547605515 -9.04156112671,-0.247065097094,-5.70483541489 -9.05456066132,-0.247067496181,-5.69303941727 -9.08055973053,-0.247072264552,-5.66944742203 -9.15257930756,-0.247073203325,-5.67582273483 -9.17957782745,-0.247077837586,-5.65322256088 -13.5714492798,-0.263748586178,-8.38300609589 -13.5914306641,-0.263761609793,-8.33641815186 -12.1007804871,-0.257881373167,-7.36266088486 -13.4883451462,-0.262790977955,-8.18213367462 -13.4453001022,-0.262808144093,-8.09659099579 -13.5463161469,-0.26281490922,-8.10095024109 -13.5382862091,-0.262829124928,-8.03837776184 -13.7433433533,-0.263829141855,-8.10566520691 -13.4341917038,-0.261863082647,-7.85930299759 -13.4011650085,-0.26187184453,-7.81053972244 -13.4561624527,-0.261881649494,-7.78593492508 -13.4291257858,-0.261896163225,-7.7133769989 -13.2760410309,-0.260918229818,-7.56491661072 -13.3230352402,-0.261927872896,-7.53730821609 -13.3070058823,-0.26094096899,-7.47274160385 -13.2159471512,-0.260958105326,-7.36423254013 -13.1639156342,-0.260966867208,-7.3064827919 -13.2259159088,-0.260975539684,-7.28687238693 -13.2148895264,-0.260987728834,-7.22630405426 -13.2098646164,-0.260999590158,-7.16873693466 -13.2248487473,-0.26101025939,-7.12315225601 -13.233830452,-0.261021047831,-7.07456922531 -13.196805954,-0.260028332472,-7.02680921555 -13.315826416,-0.261034429073,-7.03816080093 -13.2557840347,-0.260047972202,-6.95162582397 -13.2947759628,-0.260057359934,-6.91902828217 -13.4528102875,-0.261062264442,-6.95035219193 -13.2867307663,-0.260079175234,-6.80788803101 -13.2767076492,-0.260090082884,-6.74932289124 -13.2636919022,-0.260095834732,-6.71554851532 -13.2766771317,-0.260105669498,-6.66996383667 -13.3196716309,-0.260114639997,-6.63936567307 -14.720117569,-0.265083789825,-7.30986642838 -13.4106616974,-0.26013225317,-6.58115720749 -13.3696279526,-0.260143399239,-6.50761175156 -13.4746427536,-0.26015073061,-6.50797176361 -13.4056100845,-0.260157287121,-6.44722890854 -13.4766139984,-0.260165423155,-6.43060779572 -13.6456480026,-0.261171549559,-6.46192407608 -13.7766695023,-0.26117888093,-6.47326660156 -13.7076282501,-0.261189997196,-6.38673734665 -13.6896028519,-0.261200219393,-6.3241853714 -13.7425994873,-0.261208862066,-6.29757404327 -13.6985769272,-0.261214375496,-6.24982070923 -13.8596067429,-0.261221587658,-6.2741394043 -13.9726219177,-0.261229753494,-6.27449321747 -14.2236757278,-0.262236833572,-6.33776283264 -14.1586370468,-0.262247115374,-6.25423049927 -14.1796236038,-0.262256503105,-6.2106423378 -14.2696399689,-0.26226067543,-6.22480010986 -14.6087169647,-0.263268440962,-6.32401418686 -14.6707143784,-0.264277994633,-6.29739999771 -14.7777233124,-0.264287650585,-6.28976249695 -15.0137681961,-0.265297144651,-6.33903837204 -15.0897693634,-0.265307247639,-6.31641864777 -15.0757446289,-0.265317201614,-6.2548532486 -15.0707330704,-0.265322327614,-6.22407627106 -15.1927452087,-0.265332609415,-6.2204284668 -17.1072292328,-0.271350830793,-6.97763729095 -17.1412124634,-0.271363347769,-6.92904663086 -17.1952018738,-0.272376000881,-6.88844537735 -17.2501907349,-0.272388696671,-6.84784507751 -17.2851753235,-0.272400945425,-6.80024671555 -17.3241729736,-0.272407412529,-6.78443956375 -17.3741588593,-0.272420138121,-6.74084472656 -17.4171447754,-0.272432565689,-6.69524812698 -17.4531288147,-0.272444933653,-6.64665603638 -17.5211219788,-0.272457629442,-6.61104059219 -17.5651054382,-0.272470206022,-6.5644493103 -17.6030902863,-0.272482603788,-6.51585865021 -17.6510906219,-0.272489219904,-6.50304222107 -17.6930751801,-0.272501707077,-6.45545101166 -17.7380619049,-0.273514032364,-6.40985107422 -17.808052063,-0.273527115583,-6.37224292755 -17.8330345154,-0.273539036512,-6.31865644455 -17.8930244446,-0.273551881313,-6.27705335617 -17.916015625,-0.273558020592,-6.25425243378 -18.0470218658,-0.273572593927,-6.2386007309 -18.1390190125,-0.274586379528,-6.20797634125 -18.1730003357,-0.274598747492,-6.15539312363 -18.2419910431,-0.274611949921,-6.11578273773 -18.274974823,-0.274624109268,-6.06319570541 -18.3459644318,-0.274637281895,-6.02457904816 -18.3589553833,-0.274643272161,-5.99678897858 -18.4299468994,-0.274656563997,-5.95717573166 -18.4739322662,-0.27466905117,-5.90758371353 -18.5279197693,-0.274681925774,-5.86098527908 -18.5729064941,-0.274694263935,-5.81238555908 -18.647895813,-0.275707960129,-5.77177858353 -18.6648864746,-0.27571401,-5.74498558044 -18.7428798676,-0.275727808475,-5.70537233353 -18.7838630676,-0.275739967823,-5.65477466583 -18.8448524475,-0.275753110647,-5.60917186737 -18.8858356476,-0.275765329599,-5.55757856369 -18.9118175507,-0.275776922703,-5.50099563599 -18.9027938843,-0.275786906481,-5.43343639374 -18.9387874603,-0.275793731213,-5.41163396835 -18.9847736359,-0.275806069374,-5.36103868484 -19.042760849,-0.275819003582,-5.31343746185 -19.0847454071,-0.27583104372,-5.26184129715 -19.1517333984,-0.276844471693,-5.21623659134 -19.1847190857,-0.276856154203,-5.16065168381 -19.2557067871,-0.276869744062,-5.11604118347 -19.2967033386,-0.276876807213,-5.09523248672 -19.3556900024,-0.276889801025,-5.04663085938 -19.4016742706,-0.276902139187,-4.99403810501 -19.4636631012,-0.276915371418,-4.94543600082 -19.5036487579,-0.276927322149,-4.89084672928 -19.57563591,-0.277940988541,-4.8452334404 -19.6226215363,-0.277953386307,-4.79164266586 -19.6766204834,-0.277961343527,-4.77282762527 -19.7216053009,-0.277973502874,-4.71923160553 -19.7975921631,-0.277987629175,-4.67262172699 -19.8335781097,-0.277999252081,-4.61603403091 -19.899564743,-0.278012752533,-4.56642913818 -19.9495487213,-0.278025388718,-4.5118393898 -20.0115470886,-0.279033988714,-4.49401807785 -20.0515327454,-0.279045850039,-4.43742895126 -20.1155185699,-0.279059350491,-4.38582849503 -20.168504715,-0.279071986675,-4.33222913742 -20.2434940338,-0.279086232185,-4.2826218605 -20.2884788513,-0.279098302126,-4.22702455521 -20.3554649353,-0.279112100601,-4.17442560196 -20.3974590302,-0.280119478703,-4.15061616898 -20.4714488983,-0.280133664608,-4.10000705719 -20.5144309998,-0.280145794153,-4.04142189026 -20.5844192505,-0.280159652233,-3.98981142044 -20.6294021606,-0.280171900988,-3.93122506142 -20.7153930664,-0.28018707037,-3.88160920143 -20.7593746185,-0.281199097633,-3.82301902771 -20.8163719177,-0.281207859516,-3.80020618439 -20.8723564148,-0.281220823526,-3.74360823631 -20.934343338,-0.281234234571,-3.68800640106 -21.001329422,-0.281248122454,-3.6324057579 -21.0543136597,-0.281260788441,-3.57480716705 -21.1153011322,-0.281274139881,-3.5182056427 -21.1842861176,-0.28228828311,-3.46160674095 -21.2332801819,-0.282296538353,-3.4357984066 -21.3022670746,-0.282310515642,-3.38018918037 -21.3682537079,-0.282324373722,-3.32258892059 -21.4192390442,-0.282337009907,-3.26199817657 -21.4932231903,-0.28235155344,-3.20539140701 -21.561208725,-0.283365637064,-3.1467924118 -21.6142044067,-0.283374279737,-3.12097811699 -21.6741886139,-0.283387631178,-3.06137824059 -21.7511749268,-0.283402532339,-3.00377082825 -21.8031597137,-0.283415287733,-2.94118237495 -21.8781452179,-0.283430039883,-2.88257575035 -21.953130722,-0.284444779158,-2.82396697998 -21.9981136322,-0.284456908703,-2.75938344002 -22.0641098022,-0.284466922283,-2.73356366158 -22.1330947876,-0.284481137991,-2.67295908928 -22.2190818787,-0.284497082233,-2.61335062981 -22.2560653687,-0.285508304834,-2.54776501656 -22.342048645,-0.285524308681,-2.48715782166 -22.4020347595,-0.285537749529,-2.42356109619 -22.4740180969,-0.285552382469,-2.3609585762 -22.5440139771,-0.285562962294,-2.3341345787 -22.6009979248,-0.286576241255,-2.26854419708 -22.6749820709,-0.286591142416,-2.20494151115 -22.7479667664,-0.286605894566,-2.14133667946 -22.8069496155,-0.286619275808,-2.07574033737 -22.8799343109,-0.286634087563,-2.01113677025 -22.9739189148,-0.287651091814,-1.94752597809 -23.0229129791,-0.287659823895,-1.91571962833 -21.2988128662,-0.281488776207,-1.68707120419 -21.3207969666,-0.281496971846,-1.62249100208 -21.3207817078,-0.281502902508,-1.55492937565 -21.3317661285,-0.281509876251,-1.48836135864 -21.358751297,-0.281518429518,-1.42377984524 -21.3377418518,-0.281518995762,-1.38900601864 -9.56029224396,-0.243255451322,-0.458754837513 -9.56629753113,-0.243253022432,-0.42917779088 -9.5663022995,-0.243249952793,-0.399598151445 -9.56830787659,-0.243247047067,-0.370019286871 -9.5703125,-0.243244096637,-0.340440481901 -9.55231666565,-0.243238896132,-0.309870392084 -9.55531978607,-0.24323759973,-0.295081883669 -9.5623254776,-0.243235096335,-0.265504777431 -9.56233024597,-0.243231803179,-0.235926091671 -9.53733539581,-0.243225634098,-0.205358803272 -9.56434059143,-0.243225336075,-0.176769226789 -9.54534626007,-0.243219703436,-0.146204397082 -9.555352211,-0.243217378855,-0.116626732051 -9.55135440826,-0.243215188384,-0.101837947965 -9.53036022186,-0.243209183216,-0.0712761506438 -9.54136562347,-0.243206992745,-0.0426840335131 -9.55037117004,-0.243204444647,-0.0131055004895 -9.53637695312,-0.243199080229,0.0174548011273 -9.52338314056,-0.243193879724,0.0470281876624 -9.54138946533,-0.243192315102,0.0766096487641 -9.53839206696,-0.243190094829,0.0913970991969 -9.51439762115,-0.243183463812,0.120965063572 -9.53040504456,-0.243181586266,0.150547191501 -9.5244102478,-0.24317702651,0.180120781064 -9.52241706848,-0.24317291379,0.20969581604 -9.52242279053,-0.243169009686,0.239271759987 -9.5164270401,-0.243166297674,0.254056364298 -9.51243209839,-0.243161961436,0.282643795013 -9.52443885803,-0.243159487844,0.312227070332 -9.51144599915,-0.243153810501,0.341794222593 -9.51345252991,-0.243149995804,0.371371239424 -9.50645923615,-0.243144989014,0.400941520929 -9.50646591187,-0.243140861392,0.430516958237 -9.49946975708,-0.243137851357,0.445298790932 -9.49547576904,-0.243133127689,0.474870473146 -9.50448322296,-0.243130117655,0.504453957081 -9.48949050903,-0.243123978376,0.533029198647 -9.49249744415,-0.243120089173,0.562607288361 -9.49450397491,-0.243116036057,0.592184662819 -9.49850749969,-0.243114426732,0.606976687908 -9.49351406097,-0.243109360337,0.6365467906 -9.48152160645,-0.243103429675,0.665122568607 -9.48652935028,-0.243099704385,0.694703817368 -9.47853755951,-0.243094101548,0.724269330502 -9.48054409027,-0.24308988452,0.753847301006 -9.48555183411,-0.243086069822,0.783429563046 -9.47655582428,-0.243082493544,0.798205316067 -9.47656345367,-0.243077918887,0.82778096199 -9.47457027435,-0.243073165417,0.85636806488 -9.46257781982,-0.243066906929,0.884940266609 -9.48158550262,-0.243064746261,0.916516780853 -9.61758899689,-0.24307897687,0.956166982651 -9.55559825897,-0.24306564033,0.981705784798 -9.84659099579,-0.244103983045,1.01964890957 -9.78260040283,-0.244090437889,1.04519081116 -9.89160346985,-0.244101211429,1.08482837677 -9.88861083984,-0.244096204638,1.11540448666 -9.86361885071,-0.244087889791,1.14495527744 -9.84862804413,-0.24408121407,1.17353594303 -9.86163043976,-0.244080707431,1.19032931328 -9.85763835907,-0.244075402617,1.22090280056 -9.69965457916,-0.244047954679,1.23539865017 -9.78066635132,-0.244049862027,1.30558788776 -9.91966629028,-0.24406516552,1.35223293304 -9.94767284393,-0.244064390659,1.38682174683 -9.58870506287,-0.243004500866,1.39000797272 -9.77970218658,-0.244027584791,1.4436852932 -9.81370830536,-0.244027525187,1.47927331924 -9.58173084259,-0.242988318205,1.47874891758 -9.93771648407,-0.244035944343,1.55749356747 -9.66974258423,-0.243990987539,1.55193829536 -9.93972873688,-0.244028717279,1.60485982895 -9.81774520874,-0.244005322456,1.6193703413 -9.83875179291,-0.244003430009,1.65296494961 -9.65277290344,-0.243970200419,1.65645027161 -9.76877403259,-0.243982419372,1.70507919788 -9.84877681732,-0.243989288807,1.74869287014 -9.68180179596,-0.243955925107,1.7689756155 -9.42383003235,-0.242911115289,1.75742948055 -14.3524656296,-0.259660631418,2.61032319069 -14.3484687805,-0.259656786919,2.65589094162 -14.3484725952,-0.259653508663,2.70245814323 -14.3604745865,-0.259652107954,2.750041008 -14.9074344635,-0.261731922626,2.91864800453 -9.53989028931,-0.242887288332,2.00531220436 -9.51790142059,-0.24287815392,2.03187727928 -9.5259103775,-0.242873832583,2.0634663105 -9.58291530609,-0.243877008557,2.10606122017 -9.63891410828,-0.243883162737,2.13188719749 -9.60292720795,-0.243871614337,2.15643715858 -9.60893630981,-0.243866965175,2.1880261898 -14.7994699478,-0.26168692112,3.30595803261 -9.68994808197,-0.243868231773,2.2682082653 -9.82794475555,-0.24488465488,2.32885694504 -9.77395915985,-0.243870168924,2.34940314293 -9.78096389771,-0.243868336082,2.36719036102 -9.69898033142,-0.243849307299,2.38072824478 -9.86597442627,-0.244870439172,2.45038175583 -9.66800403595,-0.243832528591,2.43686819077 -9.84599494934,-0.244855642319,2.50953483582 -9.81500720978,-0.244844600558,2.53508901596 -9.80401325226,-0.244839981198,2.5478811264 -9.77702617645,-0.244829639792,2.57344675064 -9.80403327942,-0.244827955961,2.61302566528 -9.80004405975,-0.244821459055,2.64360976219 -9.44509124756,-0.24375680089,2.58701682091 -9.88005542755,-0.244822636247,2.72879958153 -9.86606693268,-0.244814202189,2.75836372375 -9.85607242584,-0.244809523225,2.77214717865 -9.8190870285,-0.244797363877,2.79471206665 -9.75210380554,-0.24477994442,2.81024837494 -9.46814632416,-0.243726357818,2.76569890976 -9.72612762451,-0.24476338923,2.86739969254 -9.71613883972,-0.244755521417,2.89697384834 -9.71814918518,-0.244749516249,2.93054556847 -9.79114532471,-0.244758695364,2.96736764908 -9.81715297699,-0.244756788015,3.00795245171 -9.78716659546,-0.244745582342,3.03152561188 -9.51321029663,-0.243692696095,2.98497223854 -9.75719165802,-0.244727864861,3.0886657238 -9.78819847107,-0.244726732373,3.13125252724 -9.77321052551,-0.244717806578,3.15982317924 -9.434258461,-0.243656620383,3.07345795631 -9.41927146912,-0.243647485971,3.10102677345 -9.35429096222,-0.243629813194,3.11257863045 -9.33930397034,-0.243620544672,3.14014410973 -9.32431602478,-0.243611440063,3.16672229767 -9.32832813263,-0.243605405092,3.20029640198 -9.34033203125,-0.243604153395,3.22009158134 -9.32534503937,-0.243594989181,3.24667000771 -9.33035564423,-0.243588969111,3.28123855591 -9.33436584473,-0.243583127856,3.31382966042 -9.33137798309,-0.243575781584,3.3454015255 -9.31239128113,-0.243565738201,3.37097430229 -9.32840156555,-0.243561580777,3.40954875946 -9.32740688324,-0.2435580194,3.42533802986 -9.3174200058,-0.243549510837,3.45391654968 -9.32942962646,-0.243544816971,3.49050116539 -9.32444190979,-0.243536904454,3.52206730843 -9.30645656586,-0.24352696538,3.54764485359 -9.30146884918,-0.243519023061,3.57921123505 -9.31247329712,-0.243517622352,3.59901237488 -9.29848670959,-0.243508204818,3.62658500671 -9.30849742889,-0.243503019214,3.6631667614 -9.30451011658,-0.243495285511,3.69474124908 -9.29852294922,-0.243487030268,3.72630572319 -9.30253505707,-0.243480727077,3.76088571548 -9.29554748535,-0.243472605944,3.7904715538 -9.28955364227,-0.243467897177,3.80525159836 -9.30056476593,-0.243462786078,3.8428337574 -9.282579422,-0.243452370167,3.86940002441 -9.28459072113,-0.24344573915,3.90298628807 -9.28760242462,-0.243439152837,3.9375667572 -9.27961540222,-0.243430495262,3.96813797951 -9.2816286087,-0.243423655629,4.00271511078 -9.28363418579,-0.2444203794,4.02050352097 -9.27464771271,-0.244411408901,4.05107069016 -9.27965831757,-0.244405165315,4.08665513992 -9.28367137909,-0.244398653507,4.12223529816 -9.27068519592,-0.244388997555,4.15080690384 -9.26569843292,-0.244380652905,4.18337535858 -9.26171207428,-0.244372576475,4.21594953537 -9.26871681213,-0.244370266795,4.23574638367 -9.27272796631,-0.244363769889,4.27133226395 -9.26274299622,-0.244354456663,4.3018989563 -9.25575637817,-0.2443459481,4.33248329163 -9.24977016449,-0.244337290525,4.36505031586 -9.26178073883,-0.244331970811,4.40562725067 -9.25478839874,-0.244327053428,4.41941833496 -9.2508020401,-0.244318947196,4.45199918747 -9.24981403351,-0.244311258197,4.48657560349 -9.2438287735,-0.24430257082,4.51914644241 -9.23484325409,-0.244293451309,4.54972362518 -9.24485397339,-0.244287639856,4.59029817581 -9.22686958313,-0.244276762009,4.61686992645 -9.24887275696,-0.244277179241,4.64467334747 -9.24188709259,-0.244268193841,4.67724275589 -9.2259016037,-0.244257643819,4.70481586456 -9.23691368103,-0.244252175093,4.74540424347 -9.2289276123,-0.244242876768,4.77796983719 -9.21494293213,-0.244232654572,4.80654525757 -9.21595668793,-0.244225129485,4.84312200546 -9.22696113586,-0.244223311543,4.86691236496 -9.22597408295,-0.245215445757,4.90249061584 -9.21498966217,-0.245205655694,4.93306398392 -9.2230014801,-0.245199412107,4.97364473343 -9.21501541138,-0.245190292597,5.00522756577 -9.21502876282,-0.245182305574,5.04279375076 -9.2200345993,-0.245179399848,5.06358718872 -9.20805072784,-0.24516928196,5.09415817261 -9.21206283569,-0.245162308216,5.13274240494 -9.21907424927,-0.245155856013,5.17332553864 -9.20109176636,-0.24514451623,5.20089435577 -9.19910621643,-0.245136171579,5.23746585846 -9.20111846924,-0.245128631592,5.27604293823 -9.20712375641,-0.245125874877,5.29783773422 -9.20113945007,-0.245116740465,5.33240938187 -9.20015239716,-0.24510872364,5.36899280548 -9.19116783142,-0.245099067688,5.40156888962 -9.18818187714,-0.245090454817,5.43814086914 -9.18919563293,-0.24508266151,5.47671985626 -9.19220256805,-0.245079234242,5.49750995636 -9.1962146759,-0.245071992278,5.5380897522 -9.19122982025,-0.245062977076,5.57366514206 -9.18424415588,-0.246053546667,5.60823822021 -9.17825984955,-0.246044427156,5.64281988144 -9.18127250671,-0.246036931872,5.6833987236 -9.17028903961,-0.246026650071,5.71597003937 -9.18029403687,-0.246024474502,5.74176025391 -9.18130779266,-0.24601636827,5.78233003616 -9.1773223877,-0.24600751698,5.81890964508 -9.16333961487,-0.245996683836,5.84948444366 -9.16335296631,-0.245988503098,5.88906240463 -9.15436935425,-0.245978653431,5.92264270782 -9.1643819809,-0.245972290635,5.9692196846 -9.16738700867,-0.245968788862,5.99101066589 -9.16240215302,-0.245959445834,6.02858066559 -9.16041660309,-0.245950892568,6.0671620369 -9.15743255615,-0.245942011476,6.10573816299 -9.13945007324,-0.245930060744,6.1353020668 -9.14646244049,-0.245923265815,6.17988967896 -9.15547466278,-0.245916754007,6.22647333145 -9.14948368073,-0.246911361814,6.24325799942 -9.13850021362,-0.246900901198,6.27683401108 -9.15251159668,-0.246895313263,6.32741832733 -9.13053035736,-0.246882423759,6.35497903824 -9.13454341888,-0.246874958277,6.39856624603 -9.13255882263,-0.246866121888,6.43914175034 -9.13656616211,-0.24686267972,6.462931633 -9.13558006287,-0.246854007244,6.50450706482 -9.13359546661,-0.246845215559,6.54508733749 -9.11361312866,-0.246832773089,6.57365703583 -9.12162685394,-0.24682597816,6.62124347687 -9.12164115906,-0.246817320585,6.66481399536 -9.10965824127,-0.246806383133,6.69938564301 -9.10866546631,-0.246801927686,6.72017431259 -9.12567710876,-0.246796742082,6.77575778961 -9.11069583893,-0.246785193682,6.80833053589 -9.10970973969,-0.24777649343,6.8509106636 -9.10772514343,-0.247767448425,6.89348554611 -9.09374332428,-0.247756063938,6.92705917358 -9.09475708008,-0.247747510672,6.97263097763 -9.13275623322,-0.247750923038,7.02244091034 -8.99880123138,-0.246715575457,6.96597337723 -8.95882511139,-0.246698975563,6.97954034805 -8.99484729767,-0.247688800097,7.09571075439 -8.93187618256,-0.247667387128,7.0922627449 -8.87990283966,-0.24664837122,7.09582948685 -8.82792282104,-0.246633559465,7.07760000229 -8.83893585205,-0.246626913548,7.1311788559 -8.8249540329,-0.246615350246,7.16475391388 -8.81997013092,-0.246605619788,7.20533466339 -8.81098747253,-0.247594878078,7.24390411377 -8.82599925995,-0.247589021921,7.30148649216 -8.80201339722,-0.247579693794,7.30526351929 -9.07296562195,-0.248625293374,7.57193183899 -9.0829782486,-0.248618453741,7.62751245499 -9.07199573517,-0.248607382178,7.66608667374 -9.06001377106,-0.248595967889,7.7046546936 -9.06402778625,-0.24858802557,7.75524091721 -9.06403541565,-0.248583450913,7.7800245285 -9.06605148315,-0.248575046659,7.82960748672 -9.05706787109,-0.248564392328,7.87018728256 -9.05108547211,-0.248554095626,7.91475629807 -9.00411128998,-0.248535856605,7.92232942581 -9.07610988617,-0.24954123795,8.03492069244 -9.1671037674,-0.249550744891,8.16353225708 -9.18010807037,-0.249548852444,8.20032501221 -9.18712234497,-0.250541180372,8.25789928436 -9.16814136505,-0.250528454781,8.29147815704 -9.14616298676,-0.250514835119,8.32404232025 -9.17917060852,-0.250512570143,8.40463447571 -9.13819599152,-0.250495284796,8.41920280457 -9.15720748901,-0.250489830971,8.48977661133 -9.1622133255,-0.250486463308,8.51957511902 -9.15223121643,-0.250475347042,8.56314849854 -9.14424991608,-0.250464618206,8.60872364044 -9.14826393127,-0.250456184149,8.66629695892 -9.15227890015,-0.250447958708,8.72288131714 -9.13829803467,-0.250435978174,8.7634563446 -9.13231563568,-0.251425385475,8.8130235672 -9.14831924438,-0.251424312592,8.85382843018 -9.09334754944,-0.251403868198,8.85638713837 -9.12335586548,-0.251400768757,8.9399728775 -9.04840660095,-0.251366943121,8.97810268402 -8.992436409,-0.251346439123,8.97767162323 -8.98444652557,-0.251340180635,8.99745750427 -8.98146438599,-0.251330137253,9.05102729797 -8.97648048401,-0.251320034266,9.10061359406 -8.97049808502,-0.251309424639,9.15118598938 -8.96351623535,-0.251298666,9.20076084137 -8.95953369141,-0.251288384199,9.25433158875 -8.95755004883,-0.251278728247,9.3089132309 -8.96455574036,-0.251275658607,9.3437128067 -8.95357513428,-0.251264005899,9.39028549194 -8.95459079742,-0.252254754305,9.44986057281 -8.94760894775,-0.252244025469,9.50044059753 -8.95762252808,-0.252236604691,9.57001972198 -8.93364524841,-0.252222329378,9.60359287262 -8.89367198944,-0.252204596996,9.62115573883 -8.84069252014,-0.252189099789,9.59393310547 -8.79372119904,-0.252170085907,9.60250091553 -8.7277545929,-0.251147031784,9.59105873108 -8.67778491974,-0.251127243042,9.59661960602 -8.64780902863,-0.251111596823,9.62319087982 -8.65182495117,-0.252103000879,9.68677425385 -8.65283203125,-0.252098500729,9.71756649017 -8.65584850311,-0.252089440823,9.78213977814 -8.64586734772,-0.252078026533,9.83072376251 -8.90581607819,-0.253121703863,10.1853685379 -8.8908367157,-0.253108918667,10.2329349518 -8.89185333252,-0.25309959054,10.2975168228 -8.87987327576,-0.254087537527,10.3480911255 -8.89787578583,-0.254086494446,10.4008874893 -8.88089752197,-0.254073351622,10.4464597702 -8.89391136169,-0.254066407681,10.5270423889 -8.87293338776,-0.254052430391,10.5686130524 -8.87694835663,-0.254043549299,10.6401891708 -8.8629693985,-0.254030972719,10.6907625198 -8.85998630524,-0.255020827055,10.7533473969 -8.87199211121,-0.255018383265,10.8021354675 -8.86900997162,-0.255008041859,10.8667135239 -8.91101551056,-0.255006998777,10.9863033295 -8.95701980591,-0.256006777287,11.1118946075 -8.82907104492,-0.254970759153,11.0244407654 -3.33157253265,-0.226825803518,4.27045106888 -3.33458209038,-0.226821199059,4.28823184967 -3.33560037613,-0.226812005043,4.31483697891 -8.8171672821,-0.255914509296,11.4011173248 -8.81918430328,-0.255905121565,11.4766950607 -8.8042049408,-0.255892276764,11.5302743912 -8.82220840454,-0.256890982389,11.5910654068 -8.80822849274,-0.256878226995,11.6476383209 -8.80724716187,-0.256868183613,11.7212171555 -8.79626750946,-0.256856113672,11.7817955017 -8.78928565979,-0.256844848394,11.8483743668 -8.77930641174,-0.256832718849,11.9129428864 -8.7963104248,-0.256831228733,11.9747343063 -8.782330513,-0.257818609476,12.0323162079 -8.7803478241,-0.257808297873,12.1078948975 -8.77236843109,-0.257796645164,12.1764688492 -8.7653875351,-0.257785320282,12.24604702 -8.75640678406,-0.257773518562,12.313624382 -8.75742340088,-0.257763713598,12.3962020874 -8.75443267822,-0.258758187294,12.4319944382 -8.75944900513,-0.25874915719,12.5215711594 -8.74647045135,-0.258736431599,12.5861444473 -8.74548816681,-0.258726269007,12.667725563 -8.73550796509,-0.258714199066,12.7373018265 -8.73252677917,-0.258703410625,12.8188743591 -8.71554851532,-0.259690016508,12.8784542084 -8.74155044556,-0.259690374136,12.9592504501 -8.72857093811,-0.259677529335,13.0278215408 -8.71859169006,-0.259665489197,13.0994033813 -8.70761203766,-0.259653061628,13.1719760895 -8.70962905884,-0.260643392801,13.2635564804 -8.68765354156,-0.260628759861,13.3201293945 -8.69066905975,-0.260619193316,13.4157066345 -8.69367790222,-0.260614663363,13.4664936066 -8.6956949234,-0.260605096817,13.5600786209 -8.68371582031,-0.261592507362,13.6336574554 -8.68173408508,-0.261581808329,13.725230217 -8.65975856781,-0.261567026377,13.7858009338 -8.58279800415,-0.261541068554,13.7583646774 -8.6847782135,-0.261556923389,13.9681758881 -9.16765785217,-0.265645861626,14.8398513794 -8.60383605957,-0.26151996851,14.0313205719 -8.688829422,-0.262527167797,14.267914772 -9.25268650055,-0.266632646322,15.2916040421 -8.57789707184,-0.26248395443,14.2850522995 -8.65489292145,-0.263489484787,14.5136461258 -9.06278610229,-0.266567915678,15.2465085983 -8.57694244385,-0.263457894325,14.5389919281 -8.59895324707,-0.263452231884,14.6785793304 -8.83490371704,-0.265490323305,15.1852035522 -8.62798118591,-0.264437615871,14.9387426376 -8.5390253067,-0.264408946037,14.8933010101 -8.68199253082,-0.265433162451,15.1941204071 -9.06090259552,-0.267500400543,15.9667682648 -8.54806804657,-0.2653850317,15.1792526245 -8.52709197998,-0.265370339155,15.2528266907 -8.6590719223,-0.266386985779,15.6004285812 -9.02398395538,-0.269451260567,16.3720741272 -8.6261177063,-0.266359508038,15.7705831528 -8.52215671539,-0.266332954168,15.6403503418 -8.59615421295,-0.26733776927,15.8909463882 -8.63216114044,-0.267334640026,16.0765285492 -8.55220222473,-0.267307847738,16.0480937958 -8.49223899841,-0.267285197973,16.0556621552 -8.48225975037,-0.267272591591,16.1592350006 -8.50527095795,-0.268266886473,16.3248214722 -8.51927566528,-0.268264561892,16.4126148224 -8.51929473877,-0.268254071474,16.5381946564 -8.49931907654,-0.268239438534,16.6267662048 -8.49133968353,-0.269227415323,16.7383460999 -8.47936153412,-0.269214391708,16.8449211121 -8.46838283539,-0.269201666117,16.9535007477 -8.46640205383,-0.270190626383,17.0830764771 -8.47540855408,-0.270187199116,17.1678676605 -8.47242832184,-0.27017608285,17.2964477539 -8.45045375824,-0.271161019802,17.3890190125 -8.43747520447,-0.271147847176,17.4995975494 -11.4076147079,-0.293741285801,23.804643631 -11.3106622696,-0.293710768223,23.7932052612 -10.6038799286,-0.288561761379,22.4038848877 -11.1757287979,-0.293667137623,23.7965488434 -11.0697774887,-0.292634814978,23.7641086578 -10.3540077209,-0.287478655577,22.4185771942 -10.8518781662,-0.292568832636,23.6842250824 -10.1770963669,-0.287421226501,22.4017066956 -10.5480051041,-0.291485518217,23.4083347321 -10.4940299988,-0.290469169617,23.3861160278 -10.4050750732,-0.290440291166,23.3836784363 -10.313120842,-0.290410786867,23.3742408752 -10.2301626205,-0.290383249521,23.381811142 -10.1362094879,-0.290353238583,23.3683681488 -10.0502529144,-0.290325015783,23.3699359894 -9.96229839325,-0.290296405554,23.3655033112 -9.90932369232,-0.290280282497,23.3422832489 -9.82436752319,-0.289252191782,23.3458480835 -9.74241065979,-0.289224743843,23.3554134369 -9.65145587921,-0.289195477962,23.3429794312 -9.56750011444,-0.289167702198,23.3455448151 -9.47254657745,-0.289137691259,23.3211116791 -9.42957019806,-0.289123505354,23.320892334 -9.33961582184,-0.289094418287,23.3094558716 -9.25765800476,-0.289067000151,23.3160228729 -9.16970443726,-0.289038360119,23.3075885773 -9.08674812317,-0.289010822773,23.3091583252 -9.00179290771,-0.287982732058,23.3077220917 -8.91383743286,-0.28795427084,23.2942962646 -8.86686134338,-0.287939310074,23.282075882 -8.78290653229,-0.287911564112,23.2796459198 -8.6999502182,-0.287883877754,23.282207489 -8.61199569702,-0.287855356932,23.2677764893 -8.53104019165,-0.287828266621,23.2713489532 -8.44708442688,-0.287800490856,23.2679176331 -8.36412906647,-0.287772893906,23.2674827576 -8.31815242767,-0.287758290768,23.2522678375 -8.23519706726,-0.286730676889,23.251832962 -8.15224075317,-0.286703258753,23.2464065552 -8.06728649139,-0.286675274372,23.2379741669 -7.98533058167,-0.286648035049,23.2355442047 -7.90237569809,-0.286620467901,23.2321109772 -7.85739898682,-0.28660607338,23.2178974152 -7.77644348145,-0.286578923464,23.2194652557 -7.69248867035,-0.286551296711,23.2090377808 -7.61353206635,-0.286524653435,23.2136077881 -7.54957103729,-0.286500930786,23.2651767731 -4.11464834213,-0.250804901123,12.8763036728 -4.06768274307,-0.250785201788,12.8658866882 -4.05669641495,-0.25077778101,12.900677681 -7.24073457718,-0.285401374102,23.1736755371 -7.1557803154,-0.28537350893,23.1582450867 -7.08482217789,-0.285348504782,23.1858158112 -6.99786806107,-0.285320401192,23.1593894958 -6.92191171646,-0.285294353962,23.171957016 -6.8379573822,-0.285266846418,23.1545295715 -6.79997873306,-0.285253942013,23.1573181152 -6.71302556992,-0.28522580862,23.1298885345 -6.6400680542,-0.285200506449,23.1484642029 -6.55411434174,-0.284172594547,23.1230335236 -6.48415565491,-0.284147948027,23.1506099701 -6.39920186996,-0.284120202065,23.1281776428 -6.32224607468,-0.284094154835,23.1317520142 -6.27627038956,-0.284079730511,23.1035423279 -6.20431280136,-0.284054636955,23.1261119843 -6.11635971069,-0.284026503563,23.0856876373 -6.04340219498,-0.284001201391,23.1042575836 -5.9634475708,-0.28397461772,23.093832016 -5.88849067688,-0.283949106932,23.1004085541 -5.84151506424,-0.283934354782,23.070192337 -5.77155733109,-0.283909916878,23.0937728882 -5.68660402298,-0.283882409334,23.0613441467 -5.61564588547,-0.283857673407,23.0839195251 -5.53269195557,-0.282830476761,23.0604896545 -5.45773601532,-0.282804995775,23.0660648346 -5.37878084183,-0.282778769732,23.0536422729 -5.34180212021,-0.282766103745,23.0594272614 -5.25784921646,-0.282738924026,23.0250034332 -5.18589162827,-0.282714128494,23.0405807495 -5.10493707657,-0.282687455416,23.0201511383 -5.04297685623,-0.282664626837,23.0817298889 -5.02700281143,-0.283650755882,23.3573131561 -5.04400682449,-0.284648746252,23.6111087799 -5.01703596115,-0.285632669926,23.8516864777 -3.1686372757,-0.257262080908,15.3600692749 -3.10967636108,-0.257240146399,15.3166484833 -3.05771350861,-0.257219582796,15.306227684 -3.00974917412,-0.257199883461,15.3128118515 -2.96278452873,-0.257180273533,15.3283910751 -2.9388024807,-0.25717034936,15.3341789246 -2.89383745193,-0.257151126862,15.3607578278 -2.85387063026,-0.257133036852,15.4103431702 -2.80390715599,-0.257112920284,15.4099235535 -2.76394033432,-0.25709477067,15.4645051956 -4.79132127762,-0.295475691557,27.1642951965 -4.76135110855,-0.296459048986,27.4978752136 -4.7773566246,-0.297456741333,27.8486671448 -4.74838590622,-0.298440426588,28.2042503357 -4.71841621399,-0.299423754215,28.5758285522 -4.68744659424,-0.300407111645,28.9444141388 -4.65447759628,-0.301389992237,29.3219947815 -4.62150859833,-0.303372770548,29.7175731659 -4.58753967285,-0.304355472326,30.1191539764 -4.60454463959,-0.305353313684,30.5489463806 -4.57057571411,-0.306336045265,30.9785289764 -4.61158323288,-0.309333086014,31.9401187897 -4.57561540604,-0.311315357685,32.4116973877 -4.5346493721,-0.312296748161,32.8612785339 -4.4976811409,-0.314278930426,33.3608589172 -4.50868844986,-0.315275609493,33.8416557312 -4.46772146225,-0.3172570467,34.3502388 -4.37977027893,-0.317229509354,34.5228157043 -4.38678836823,-0.320220082998,35.4584007263 -4.33682537079,-0.322199761868,35.9839782715 -4.29286003113,-0.32418063283,36.5815620422 -4.2368979454,-0.325159281492,37.105140686 -2.64141392708,-0.281852543354,23.5458278656 -2.56146025658,-0.281826913357,23.502407074 -2.49050378799,-0.281803131104,23.5339889526 -2.41054964066,-0.281777620316,23.4815692902 -2.34959030151,-0.282755643129,23.6231479645 -3.99009037018,-0.338053643703,41.2068481445 -3.99409937859,-0.341048955917,41.9316368103 -3.9321398735,-0.343026608229,42.6942214966 -3.80320167542,-0.342991679907,42.7697982788 -3.81121969223,-0.347982436419,44.4273834229 -3.74626111984,-0.350959569216,45.3349647522 -3.67930316925,-0.353936374187,46.2815475464 -3.60334801674,-0.356911569834,47.1901321411 -3.60135889053,-0.359905838966,48.1529273987 -3.52340483665,-0.36288061738,49.1825065613 -3.43945217133,-0.36585432291,50.220085144 -3.35549974442,-0.369828075171,51.3476715088 -3.2705476284,-0.373801678419,52.5772514343 -3.16160297394,-0.376770913601,53.5198364258 -3.09864354134,-0.382748693228,55.3894195557 -3.27359867096,-0.397775650024,60.1812171936 -3.08367967606,-0.397729992867,60.1687965393 -1.76611924171,-0.323476463556,36.9273262024 -1.64417886734,-0.323443710804,36.7919082642 -1.52723705769,-0.323411911726,36.7684936523 -1.41329431534,-0.323380708694,36.8150749207 -1.30135071278,-0.3233499825,36.9046630859 -1.22640573978,-0.333321034908,40.0740432739 -1.10046672821,-0.333287775517,40.0876274109 -0.973528087139,-0.333254426718,40.0462112427 -0.847589194775,-0.333221286535,40.0647926331 -0.721650183201,-0.333188265562,40.0433807373 -0.658680617809,-0.333171784878,40.0261688232 -0.53274166584,-0.333138823509,40.0297546387 -0.407802343369,-0.333106130362,40.074344635 -0.282862991095,-0.333073496819,40.1469306946 --0.285881757736,-0.0989354625344,69.0774612427 --0.51578783989,-0.096884265542,70.7820358276 --0.728699326515,-0.0978362411261,69.873626709 --1.38542830944,-0.0976896435022,69.7943878174 --12.9507770538,-0.0873162001371,73.7638092041 --13.1716871262,-0.0872739851475,73.6624145508 --13.41959095,-0.087227486074,73.7090377808 --12.2728805542,-0.103394158185,63.4575653076 --12.7137041092,-0.10331055522,63.5917930603 --11.6339921951,-0.115470156074,55.9167289734 --11.7179460526,-0.116450428963,55.4463310242 --12.1297798157,-0.115372031927,55.6605529785 --16.2774600983,-0.0876997336745,73.0072250366 --16.4333934784,-0.0876702517271,72.6338424683 --16.1124725342,-0.0917168036103,70.1894226074 --16.2224197388,-0.0926947146654,69.6650314331 --15.9914731979,-0.0957267731428,67.7116088867 --16.1174163818,-0.0957022160292,67.2992324829 --15.6555404663,-0.100770585239,64.4777984619 --15.6725254059,-0.100765556097,64.1095962524 --15.6055288315,-0.102771416306,62.9781951904 --15.7194738388,-0.102748841047,62.5968055725 --11.0099143982,-0.134482473135,43.2900619507 --11.114862442,-0.134459838271,43.1346664429 --11.24680233,-0.134433045983,43.084274292 --11.4057340622,-0.134402185678,43.136882782 --15.1755590439,-0.111812740564,57.0099754333 --15.1485490799,-0.112812198699,56.1985740662 --15.106543541,-0.11481398344,55.3511734009 --15.2234888077,-0.114791184664,55.0957832336 --15.388420105,-0.11476110667,55.0184020996 --15.5873394012,-0.114725925028,55.0610198975 --15.6863002777,-0.114708475769,55.0808296204 --15.86622715,-0.114676445723,55.0534439087 --14.7735443115,-0.121839158237,50.6679534912 --14.8724956512,-0.121819347143,50.4195671082 --15.0304288864,-0.121790617704,50.3701820374 --15.1603708267,-0.121766276658,50.2287940979 --14.5945262909,-0.125847429037,47.810344696 --14.6594982147,-0.125835239887,47.7551498413 --9.80896854401,-0.152563020587,31.6173248291 --9.86593151093,-0.152548000216,31.450925827 --9.96188259125,-0.152527213097,31.4115333557 --10.0718297958,-0.152504354715,31.4141387939 --10.1657819748,-0.152483984828,31.3667430878 --10.3187170029,-0.152454942465,31.5013561249 --10.3876857758,-0.152441546321,31.5431594849 --10.4416503906,-0.152427405119,31.3757648468 --10.6135797501,-0.152395784855,31.560377121 --14.236410141,-0.135842218995,40.8233261108 --11.5702037811,-0.149228394032,32.8536567688 --13.9564599991,-0.138873919845,39.2285003662 --13.9404459,-0.139871507883,38.7940979004 --13.877448082,-0.139875993133,38.24269104 --13.9883966446,-0.139855220914,38.1743049622 --14.0273675919,-0.140844896436,37.9099121094 --13.7594394684,-0.1418813169,37.008682251 --13.7814149857,-0.142873421311,36.7122802734 --13.7634029388,-0.142871335149,36.3168792725 --13.7423906326,-0.143869668245,35.9194793701 --13.7273778915,-0.14386716485,35.5460777283 --13.7773456573,-0.144855394959,35.3436851501 --13.8872938156,-0.14483512938,35.2962989807 --13.8442983627,-0.144838988781,35.0270957947 --13.8232870102,-0.145837381482,34.6536903381 --13.8062744141,-0.145835220814,34.2962913513 --13.791261673,-0.146832823753,33.9518890381 --13.7622528076,-0.146832361817,33.5774879456 --13.5273065567,-0.14886072278,32.711063385 --13.4693145752,-0.148866504431,32.4248504639 --13.449303627,-0.148864686489,32.0914497375 --13.4342899323,-0.149862155318,31.7740478516 --13.4232759476,-0.149859085679,31.4716472626 --13.4012651443,-0.150857552886,31.1482448578 --13.3782539368,-0.150856122375,30.8258399963 --13.3792362213,-0.151851445436,30.5654411316 --13.4292125702,-0.151842311025,30.5482463837 --13.5171699524,-0.151825785637,30.488861084 --13.5071554184,-0.151822671294,30.2084579468 --13.4851436615,-0.152821213007,29.9070587158 --13.2601938248,-0.153847262263,29.1626281738 --13.2521791458,-0.153843805194,28.9022274017 --13.2351665497,-0.15484161675,28.6278266907 --13.1861724854,-0.154845938087,28.4036178589 --13.1671609879,-0.154843971133,28.1302165985 --13.1591463089,-0.155840530992,27.883813858 --13.1511316299,-0.155837118626,27.6414146423 --13.1401176453,-0.155834108591,27.3960132599 --13.1251049042,-0.156831637025,27.1446094513 --13.0731115341,-0.156836271286,26.928401947 --13.108083725,-0.15682721138,26.7860088348 --13.202038765,-0.156810417771,26.7636203766 --13.2760009766,-0.156796336174,26.7002296448 --13.2629880905,-0.157793715596,26.4648284912 --13.2519741058,-0.157790824771,26.2354259491 --9.31211090088,-0.172297865152,18.2924900055 --9.25311946869,-0.172302544117,18.1062793732 --9.26209831238,-0.172295406461,17.9838790894 --9.31806468964,-0.172282233834,17.9534835815 --9.38902664185,-0.172267124057,17.9500846863 --9.57295417786,-0.172237679362,18.1617088318 --9.62792015076,-0.172224923968,18.1283149719 --9.5269317627,-0.172231927514,17.8008937836 --9.54691696167,-0.172226533294,17.7716960907 --9.5968837738,-0.172214388847,17.7292976379 --9.67284488678,-0.172199115157,17.7369098663 --13.0208568573,-0.160773396492,23.6989936829 --13.0668268204,-0.161763429642,23.6055984497 --13.1807765961,-0.160745069385,23.6352157593 --13.2577476501,-0.16073346138,23.6860275269 --13.3527021408,-0.160717591643,23.6786384583 --13.4446592331,-0.160702258348,23.6672554016 --13.534617424,-0.16068726778,23.6528720856 --13.6245756149,-0.160672336817,23.6354827881 --13.7235307693,-0.160656437278,23.635099411 --13.818488121,-0.160641118884,23.6267166138 --13.8734636307,-0.160632610321,23.6355247498 --13.964422226,-0.160617932677,23.619140625 --14.0543804169,-0.160603478551,23.6007537842 --14.1583347321,-0.160587444901,23.6053714752 --14.233297348,-0.160575002432,23.5619850159 --14.2012901306,-0.160575389862,23.3425827026 --14.4202127457,-0.16054597497,23.5342159271 --14.4651918411,-0.160539016128,23.5250263214 --14.5901403427,-0.159520983696,23.5606479645 --14.6980953217,-0.15950512886,23.5692672729 --14.7880535126,-0.159491464496,23.5478839874 --14.8730144501,-0.159478485584,23.5174999237 --14.9179859161,-0.159470245242,23.4241065979 --15.0259485245,-0.159456267953,23.511926651 --15.0969133377,-0.159445181489,23.4595394135 --15.0179204941,-0.1604513973,23.1761302948 --15.3428134918,-0.159411355853,23.5137844086 --15.4337739944,-0.159398317337,23.4924068451 --15.520734787,-0.159385830164,23.4630241394 --15.1408262253,-0.160426139832,22.7315578461 --13.122382164,-0.166652187705,19.6300010681 --13.1483592987,-0.166645571589,19.5346050262 --13.0953578949,-0.166647851467,19.3241958618 --16.0195293427,-0.158318936825,23.4853229523 --13.2062959671,-0.166628271341,19.2264194489 --13.1422977448,-0.167631715536,19.0030040741 --13.1762723923,-0.167624384165,18.9236087799 --12.2754983902,-0.16971732676,17.4508457184 --12.2085008621,-0.170720651746,17.2394351959 --13.1522245407,-0.167614609003,18.4502048492 --13.1732034683,-0.167608827353,18.3558063507 --14.2288990021,-0.165492281318,19.6976032257 --12.732301712,-0.169650733471,17.564125061 --12.1394491196,-0.170710191131,16.6346187592 --12.1964178085,-0.170700207353,16.6022281647 --12.2203941345,-0.171693772078,16.5248317719 --12.2233781815,-0.171689614654,16.4204330444 --12.1943702698,-0.171688735485,16.27202034 --12.3053245544,-0.171673387289,16.3136444092 --12.2753248215,-0.171674609184,16.2204380035 --12.2673110962,-0.171671643853,16.1030349731 --12.2572994232,-0.17166890204,15.9846315384 --8.95117759705,-0.181003302336,11.5866069794 --8.95615959167,-0.180997371674,11.5172042847 --8.97213745117,-0.180990368128,11.4628047943 --9.02610588074,-0.180979505181,11.4564085007 --9.05508995056,-0.180973947048,11.4562139511 --12.6201171875,-0.171612218022,15.8784980774 --12.4931364059,-0.171621337533,15.6160707474 --12.4761247635,-0.172619476914,15.4936666489 --12.4951047897,-0.172614067793,15.4162664413 --12.6100587845,-0.171599373221,15.4588918686 --12.7900037766,-0.171580120921,15.6297292709 --12.8669681549,-0.171569377184,15.6233472824 --12.909942627,-0.171561941504,15.5739517212 --12.9839076996,-0.171551644802,15.5625658035 --12.9479026794,-0.171551942825,15.4201593399 --13.016869545,-0.171542257071,15.4037761688 --13.0248527527,-0.171538382769,15.313372612 --13.1278181076,-0.171527147293,15.3851947784 --13.1927871704,-0.171518087387,15.3638124466 --13.1277894974,-0.171521157026,15.1893949509 --13.2807340622,-0.171504050493,15.26902771 --13.4256830215,-0.171487852931,15.3376588821 --13.542637825,-0.171474397182,15.3732852936 --13.6615934372,-0.170460894704,15.409910202 --13.7275686264,-0.170453593135,15.4347229004 --13.7515487671,-0.170448899269,15.3643321991 --13.8195171356,-0.170440256596,15.3409414291 --13.8664913177,-0.170433610678,15.2955522537 --15.4130792618,-0.167294546962,16.9004993439 --15.2171163559,-0.16731017828,16.5780563354 --14.207362175,-0.170396640897,15.3764295578 --14.9161748886,-0.168333917856,16.0963954926 --12.0708875656,-0.17557823658,12.9323568344 --12.0988664627,-0.175572484732,12.8799610138 --12.0978517532,-0.175569295883,12.7975616455 --12.0838403702,-0.175567194819,12.7011547089 --12.1098194122,-0.175561740994,12.6477584839 --12.168797493,-0.175555184484,12.6695728302 --12.2167711258,-0.175547987223,12.6391830444 --12.2277536392,-0.175543904305,12.5697813034 --12.2117433548,-0.175542145967,12.4743795395 --12.2117290497,-0.175539016724,12.3949775696 --12.2137136459,-0.175535812974,12.3195819855 --12.2107000351,-0.176532968879,12.2381792068 --12.1807003021,-0.176533848047,12.168970108 --12.1906843185,-0.176529973745,12.1015691757 --12.1826715469,-0.176527544856,12.0161619186 --12.1816568375,-0.17652463913,11.9397659302 --12.1806440353,-0.176521718502,11.8633651733 --12.1816291809,-0.176518648863,11.7889633179 --12.1956129074,-0.176514595747,11.7275648117 --12.2156000137,-0.176511585712,11.7093687057 --12.1985902786,-0.176509976387,11.6189641953 --12.2005758286,-0.176506921649,11.5475664139 --12.196562767,-0.176504328847,11.4701633453 --12.1965484619,-0.176501438022,11.3967590332 --12.188536644,-0.177499175072,11.3173589706 --12.1995210648,-0.17749555409,11.2559623718 --12.1665210724,-0.177496507764,11.1887493134 --12.1675071716,-0.177493616939,11.1183481216 --12.1714925766,-0.177490547299,11.0519523621 --12.1684799194,-0.177487969398,10.9785490036 --12.1614675522,-0.177485704422,10.9021453857 --12.1784496307,-0.177481725812,10.8467435837 --12.1404523849,-0.177483022213,10.7785348892 --12.1564340591,-0.177479192615,10.7241401672 --12.0914363861,-0.177480921149,10.5977201462 --12.0874233246,-0.178478464484,10.5263175964 --12.0844116211,-0.178475990891,10.4569196701 --12.0903959274,-0.178472876549,10.3945169449 --12.1293725967,-0.178467616439,10.3611249924 --12.1213684082,-0.178466841578,10.3209218979 --12.1203546524,-0.178464308381,10.2545261383 --12.1093444824,-0.178462386131,10.1781158447 --12.1153287888,-0.1784594208,10.1177177429 --12.1083173752,-0.178457319736,10.0473194122 --12.1173028946,-0.178454205394,9.98992061615 --12.110291481,-0.178452119231,9.91951751709 --12.0782909393,-0.178452804685,9.86030387878 --12.099272728,-0.178448989987,9.81290435791 --12.0932617188,-0.178446874022,9.74450302124 --12.0812511444,-0.178445145488,9.67210388184 --12.0842380524,-0.17844247818,9.61069774628 --12.0852241516,-0.178440004587,9.54929924011 --12.0772132874,-0.179438054562,9.48089885712 --12.0592098236,-0.17943790555,9.43569374084 --12.0581979752,-0.179435521364,9.37228679657 --12.0481872559,-0.179433733225,9.3038892746 --12.0021839142,-0.179433912039,9.2064704895 --11.9991722107,-0.179431721568,9.14407157898 --11.9971590042,-0.17942944169,9.08166694641 --12.0001459122,-0.179426953197,9.024269104 --12.0161352158,-0.179424911737,9.00606918335 --12.0191221237,-0.179422453046,8.94866943359 --12.0141105652,-0.179420426488,8.88526439667 --12.1780614853,-0.179409697652,8.94791030884 --5.60049581528,-0.192746847868,4.04183721542 --5.57848310471,-0.192741468549,3.99741435051 --5.59947013855,-0.192737236619,3.99921774864 --12.000043869,-0.180408969522,8.55405902863 --11.9980316162,-0.180406883359,8.49465465546 --11.994020462,-0.180404931307,8.43424987793 --11.9950065613,-0.180402755737,8.37784862518 --11.9899950027,-0.180400893092,8.31744480133 --11.9769926071,-0.180400446057,8.28024291992 --11.9769802094,-0.180398374796,8.2238407135 --11.9769678116,-0.180396303535,8.16743755341 --11.9719562531,-0.180394470692,8.10803413391 --11.9699440002,-0.180392533541,8.05062866211 --11.9689321518,-0.18039059639,7.99523162842 --11.9639205933,-0.180388823152,7.93682956696 --11.9389200211,-0.180388882756,7.89262104034 --11.9199113846,-0.180387675762,7.82521343231 --11.9039030075,-0.180386334658,7.75980329514 --11.9048900604,-0.180384382606,7.70740938187 --11.9028787613,-0.18038251996,7.65200519562 --11.8998680115,-0.180380731821,7.59660387039 --11.8938560486,-0.181379064918,7.53919935226 --11.883852005,-0.181378483772,7.50599384308 --11.8808412552,-0.181376740336,7.4515953064 --11.8808288574,-0.181374877691,7.398188591 --11.8738183975,-0.181373313069,7.34178972244 --11.8758058548,-0.181371420622,7.29038572311 --11.872795105,-0.181369751692,7.23698806763 --11.8707838058,-0.181368038058,7.18358373642 --11.8577795029,-0.181367576122,7.14937591553 --11.8557682037,-0.181365862489,7.0959687233 --11.8557567596,-0.181364178658,7.04557466507 --11.8607444763,-0.181362301111,6.99717283249 --11.8557329178,-0.181360766292,6.94276571274 --11.8437242508,-0.181359469891,6.88536405563 --11.8517112732,-0.181357577443,6.83896064758 --11.8317089081,-0.181357339025,6.8027586937 --11.8356971741,-0.181355595589,6.75435447693 --11.8276863098,-0.181354209781,6.69995260239 --11.8306751251,-0.181352540851,6.65154933929 --11.8266639709,-0.181351110339,6.60015106201 --11.8286523819,-0.181349515915,6.55174922943 --11.8186483383,-0.181348994374,6.52154636383 --11.8136377335,-0.181347593665,6.46913957596 --11.812625885,-0.182346135378,6.41973876953 --11.8576068878,-0.181343659759,6.39534902573 --11.8695936203,-0.181341990829,6.35295057297 --11.9465684891,-0.181339010596,6.34557151794 --12.0315418243,-0.181336045265,6.34320497513 --12.0945243835,-0.181334197521,6.35202169418 --12.1844978333,-0.181331351399,6.35065078735 --12.2784690857,-0.181328579783,6.35027647018 --12.2954559326,-0.181327313185,6.30988359451 --12.2834472656,-0.181326568127,6.25448179245 --12.3254289627,-0.181324958801,6.2260890007 --12.3894071579,-0.181323125958,6.20971107483 --12.3694057465,-0.18132302165,6.17450141907 --12.5673599243,-0.181319460273,6.22516679764 --12.3623857498,-0.181321516633,6.0726981163 --19.5081272125,-0.169233113527,9.57071018219 --19.5611152649,-0.169237107038,9.52033519745 --19.6370983124,-0.16924098134,9.48096942902 --19.6000995636,-0.169246122241,9.38656330109 --12.3553409576,-0.181318342686,5.84988689423 --12.3373346329,-0.181317865849,5.79348325729 --12.349322319,-0.18131712079,5.75108575821 --12.3313150406,-0.181316643953,5.69467926025 --12.4982776642,-0.181314900517,5.72432851791 --12.3642892838,-0.181315273046,5.61488962173 --19.0941619873,-0.170280575752,8.66081905365 --14.8858566284,-0.177302405238,6.69815444946 --14.8198604584,-0.177304133773,6.61072921753 --14.7388658524,-0.177305802703,6.51830625534 --14.6648702621,-0.178307399154,6.42887926102 --14.6088724136,-0.178308859468,6.34846067429 --14.529876709,-0.178310289979,6.25803089142 --14.4598846436,-0.178310990334,6.1998052597 --14.3788900375,-0.178312256932,6.11037826538 --14.3148927689,-0.178313434124,6.02895736694 --14.2338981628,-0.17831453681,5.94052743912 --14.1828975677,-0.179315596819,5.86611223221 --14.1039028168,-0.179316520691,5.77968072891 --14.0409040451,-0.179317414761,5.70126008987 --13.9739112854,-0.17931766808,5.64804029465 --13.9279108047,-0.179318517447,5.5776257515 --11.6932449341,-0.183305948973,4.61943149567 --11.6992340088,-0.183305338025,4.57903528214 --11.6972236633,-0.183304682374,4.53462743759 --11.6972141266,-0.183304071426,4.49122190475 --11.6932058334,-0.183303460479,4.44681882858 --11.6852016449,-0.183303102851,4.42261838913 --11.6861925125,-0.183302551508,4.38021564484 --11.6801834106,-0.183301970363,4.33581542969 --11.6791744232,-0.183301448822,4.2924079895 --11.6821641922,-0.183301001787,4.25100564957 --11.6811552048,-0.183300539851,4.20860528946 --11.6721467972,-0.183299988508,4.16320085526 --11.665143013,-0.183299675584,4.140001297 --11.6811313629,-0.183299526572,4.10360336304 --11.6711235046,-0.18329899013,4.058198452 --11.6601161957,-0.18329846859,4.0127954483 --11.6671056747,-0.183298259974,3.97339391708 --11.6600971222,-0.18329782784,3.92898583412 --11.6570882797,-0.183297500014,3.8865840435 --11.6600837708,-0.183297425508,3.8663790226 --11.6480760574,-0.18329693377,3.82097268105 --11.645067215,-0.183296650648,3.77957749367 --11.6520576477,-0.183296620846,3.74017238617 --11.6410503387,-0.183296203613,3.69576883316 --11.6440410614,-0.183296129107,3.65536355972 --11.5530433655,-0.184293687344,3.58593511581 --11.5110445023,-0.184292525053,3.55171322823 --11.5150346756,-0.184292450547,3.51331877708 --11.5280246735,-0.184292644262,3.47691893578 --11.5110177994,-0.184292048216,3.43151092529 --11.5050106049,-0.184291765094,3.38910126686 --11.5120010376,-0.184291884303,3.3517062664 --11.5039930344,-0.18429158628,3.30929994583 --11.4999895096,-0.184291452169,3.2880961895 --11.4989805222,-0.184291392565,3.24768996239 --11.4829740524,-0.184290871024,3.20429110527 --11.4919643402,-0.18429119885,3.16688799858 --11.4999551773,-0.184291526675,3.12948727608 --11.4869480133,-0.184291154146,3.08607697487 --11.4839401245,-0.184291154146,3.04668164253 --11.4849357605,-0.184291258454,3.02647233009 --11.4799280167,-0.184291213751,2.98607039452 --11.4739208221,-0.184291154146,2.94566941261 --11.4799108505,-0.18429158628,2.90827035904 --11.4679040909,-0.184291318059,2.86586093903 --11.4638967514,-0.184291407466,2.82545256615 --11.4688920975,-0.184291750193,2.80725312233 --11.4568853378,-0.184291526675,2.76585102081 --11.4778747559,-0.18429274857,2.73245763779 --11.455868721,-0.184292122722,2.68804454803 --11.409866333,-0.184290394187,2.63862848282 --11.4288568497,-0.184291630983,2.60422754288 --11.4678449631,-0.184293866158,2.57584881783 --11.4938383102,-0.184295326471,2.56265711784 --11.5158281326,-0.184296905994,2.52926397324 --11.5598163605,-0.184299647808,2.49986982346 --11.5698080063,-0.184300765395,2.46448206902 --11.6117963791,-0.184303581715,2.43509578705 --11.5157985687,-0.18429929018,2.37464761734 --11.5047922134,-0.184299379587,2.33424377441 --11.6957702637,-0.184309989214,2.35612106323 --11.746758461,-0.184313669801,2.32773685455 --11.7787485123,-0.184316411614,2.29534721375 --11.8137388229,-0.184319406748,2.26396417618 --11.8487291336,-0.184322521091,2.23157334328 --11.8817195892,-0.18432559073,2.19918727875 --11.9087095261,-0.18432842195,2.16479206085 --11.9377040863,-0.184330806136,2.15060138702 --11.9706954956,-0.184334099293,2.11822032928 --12.0146846771,-0.184338212013,2.08683443069 --12.0396776199,-0.183341234922,2.05244803429 --12.079668045,-0.183345288038,2.02006220818 --12.1106595993,-0.183348894119,1.98567080498 --12.1486501694,-0.183353036642,1.9522818327 --12.1896438599,-0.183356583118,1.94010460377 --12.2156362534,-0.183360084891,1.90471482277 --12.2536277771,-0.183364540339,1.87032115459 --12.2856197357,-0.183368638158,1.83593726158 --12.3276119232,-0.183373555541,1.80255329609 --12.3476047516,-0.183377027512,1.76515638828 --12.3885993958,-0.183380976319,1.75197899342 --12.4235916138,-0.183385685086,1.71658849716 --12.4615840912,-0.183390691876,1.68220674992 --12.4975767136,-0.183395683765,1.64681923389 --12.5995645523,-0.18340575695,1.62045907974 --12.6665563583,-0.183413386345,1.58908855915 --12.7175483704,-0.183419957757,1.5547066927 --12.766541481,-0.182426482439,1.52032923698 --12.8015375137,-0.182430639863,1.50414264202 --12.8445301056,-0.18243688345,1.46876502037 --12.881524086,-0.182442843914,1.4313750267 --12.9195184708,-0.182448908687,1.39499604702 --12.9625110626,-0.182455614209,1.35760593414 --13.0015058517,-0.182461977005,1.32123053074 --13.0375013351,-0.1824683249,1.2828400135 --13.0794973373,-0.182473555207,1.26665973663 --13.1194915771,-0.182480350137,1.22928035259 --13.1584863663,-0.182487249374,1.19089412689 --13.1984806061,-0.182494342327,1.15250957012 --13.2424764633,-0.182501927018,1.11412525177 --13.2804718018,-0.182509034872,1.07574629784 --13.3194684982,-0.182514429092,1.05856800079 --13.3554649353,-0.182521685958,1.01817452908 --13.3774604797,-0.18252761662,0.977788090706 --13.4424562454,-0.182537719607,0.940417170525 --13.4704532623,-0.182544454932,0.900032579899 --13.5234489441,-0.181553781033,0.860652089119 --13.5324468613,-0.181558907032,0.818256735802 --12.1634931564,-0.184426873922,0.698432207108 --12.0464935303,-0.184418141842,0.651981472969 --12.258482933,-0.183442145586,0.627678930759 --12.2094812393,-0.183440282941,0.58525210619 --13.7614326477,-0.181602120399,0.637559771538 --12.21347332,-0.183446854353,0.507448732853 --12.2684688568,-0.183455750346,0.471068650484 --12.0814714432,-0.184437677264,0.442790716887 --12.1354665756,-0.18444648385,0.406408637762 --11.9954662323,-0.184434607625,0.361947089434 --12.2364578247,-0.183463737369,0.33365470171 --12.2664546967,-0.183470413089,0.295260637999 --12.2174520493,-0.184468388557,0.254839986563 --12.1494503021,-0.184464246035,0.213402628899 --12.3334465027,-0.183486491442,0.200293123722 --12.2924451828,-0.183485463262,0.159871548414 --12.2254428864,-0.183481365442,0.119441479445 --12.0284414291,-0.184462234378,0.0759430378675 --12.0014400482,-0.184462442994,0.0375318005681 --12.1044359207,-0.184477925301,0.00118098116945 --11.9704341888,-0.18446560204,-0.0392883569002 --12.2234315872,-0.184497460723,-0.0553663037717 --12.0314292908,-0.184478119016,-0.095861852169 --12.0514278412,-0.184484139085,-0.134256824851 --11.9594249725,-0.18447650969,-0.172703191638 --12.0424232483,-0.18449036777,-0.211067438126 --12.1754198074,-0.184510633349,-0.249398991466 --12.0214176178,-0.184495136142,-0.286875545979 --12.0794172287,-0.184504419565,-0.307053864002 --12.0614147186,-0.184505909681,-0.344456583261 --11.9804124832,-0.184499397874,-0.381902009249 --11.9764108658,-0.184502750635,-0.420310169458 --11.9694080353,-0.184505656362,-0.457710087299 --12.1184072495,-0.184529334307,-0.500044465065 --12.237408638,-0.183549299836,-0.541382193565 --12.5904121399,-0.183598905802,-0.572419464588 --11.9734020233,-0.184520095587,-0.591115534306 --12.0564022064,-0.184535518289,-0.632479310036 --12.0033988953,-0.184532448649,-0.668909072876 --12.0973997116,-0.184549719095,-0.711265981197 --12.1593999863,-0.184562757611,-0.752637326717 --12.008395195,-0.184545814991,-0.783105075359 --12.1293983459,-0.184565111995,-0.808245003223 --11.9793920517,-0.184548288584,-0.839730858803 --12.2664003372,-0.183594033122,-0.893987476826 --12.1663961411,-0.184584289789,-0.927442550659 --12.37840271,-0.183620095253,-0.979739546776 --12.6214103699,-0.183660969138,-1.03501570225 --12.3064002991,-0.183616831899,-1.03337085247 --12.4434051514,-0.183642357588,-1.08270680904 --12.442404747,-0.183647379279,-1.1221061945 --12.3554019928,-0.183639466763,-1.15555620193 --12.426404953,-0.183655560017,-1.20092344284 --12.3674030304,-0.183651730418,-1.23535132408 --12.4164047241,-0.183664605021,-1.27872347832 --12.3304014206,-0.183653861284,-1.29096770287 --12.3134012222,-0.183656588197,-1.32938301563 --16.4966087341,-0.17832750082,-1.76765048504 --16.5596199036,-0.178348362446,-1.82701861858 --16.6256313324,-0.178369775414,-1.88637948036 --16.6886444092,-0.177391141653,-1.94674873352 --16.7606563568,-0.177413895726,-2.00710225105 --16.8246650696,-0.177430152893,-2.04126977921 --16.8886795044,-0.177452221513,-2.10263514519 --16.9486904144,-0.1774738729,-2.16400265694 --17.0237064362,-0.177498221397,-2.2273607254 --17.0867195129,-0.177520796657,-2.28972434998 --17.163734436,-0.177545964718,-2.35407924652 --17.2137489319,-0.177566722035,-2.41544771194 --17.2977600098,-0.176587551832,-2.45460581779 --17.365776062,-0.176611810923,-2.51896357536 --17.4237918854,-0.176634758711,-2.58333301544 --17.4978084564,-0.176660627127,-2.6496887207 --17.5778255463,-0.176687985659,-2.71804571152 --14.9436302185,-0.180227503181,-2.38883399963 --14.96463871,-0.180241033435,-2.44022059441 --14.9406404495,-0.180241718888,-2.4614379406 --14.8886432648,-0.180242046714,-2.50186467171 --15.0946674347,-0.180289790034,-2.58214998245 --14.9626636505,-0.180275395513,-2.60961651802 --14.301612854,-0.1811619699,-2.55037164688 --14.1896085739,-0.181150063872,-2.57782793045 --14.5586490631,-0.181229263544,-2.68703079224 --14.1766176224,-0.181161478162,-2.64543819427 --14.4996547699,-0.181232750416,-2.74866724014 --14.4836606979,-0.181239411235,-2.79307436943 --14.5036697388,-0.181253001094,-2.84345769882 --14.4336700439,-0.181249395013,-2.87890219688 --14.132645607,-0.181199908257,-2.86946368217 --13.9006290436,-0.182163283229,-2.87098479271 --13.8396263123,-0.182155802846,-2.88221907616 --13.8346319199,-0.182164013386,-2.9266204834 --13.8186368942,-0.18217009306,-2.96902966499 --13.8926515579,-0.181194454432,-3.02938771248 --13.681634903,-0.182160794735,-3.03190374374 --13.6116333008,-0.182155624032,-3.06234073639 --13.5576334,-0.182153850794,-3.09677815437 --13.4416227341,-0.182134225965,-3.0940387249 --13.2516069412,-0.182103559375,-3.09754538536 --13.0505876541,-0.183070003986,-3.09705495834 --13.1156024933,-0.183092400432,-3.15441441536 --13.0556001663,-0.183088511229,-3.18485164642 --13.1866235733,-0.1821257025,-3.25918507576 --13.1316204071,-0.183118358254,-3.26841545105 --13.2076377869,-0.182143881917,-3.3297700882 --13.2756538391,-0.182168006897,-3.39013195038 --13.3236665726,-0.18218806386,-3.44650793076 --13.3366765976,-0.182200610638,-3.49490499496 --13.3716888428,-0.182218044996,-3.54828429222 --13.3896989822,-0.18223182857,-3.5976729393 --13.2066764832,-0.182195484638,-3.5739774704 --13.1586771011,-0.182194262743,-3.60640668869 --12.9626550674,-0.183159083128,-3.59991812706 --13.0196704865,-0.183181509376,-3.65828108788 --13.128695488,-0.182216346264,-3.73162102699 --13.0926980972,-0.182217895985,-3.76704692841 --13.0156936646,-0.183209642768,-3.79049062729 --12.8946781158,-0.183185920119,-3.77875447273 --13.1007194519,-0.182244569063,-3.88104581833 --12.8856925964,-0.183203205466,-3.86456346512 --12.8066883087,-0.183193996549,-3.88600850105 --12.858704567,-0.183216378093,-3.94538331032 --12.8677139282,-0.183228597045,-3.99278402328 --12.7447013855,-0.183208376169,-4.00025129318 --12.8017196655,-0.183232367039,-4.06162261963 --12.837729454,-0.183246314526,-4.09480476379 --12.7707271576,-0.183239668608,-4.11823892593 --12.8457489014,-0.183268532157,-4.18559646606 --12.8797645569,-0.18328744173,-4.24097919464 --13.0398035049,-0.182338446379,-4.33628892899 --13.4958982468,-0.182465627789,-4.52742910385 --13.2058486938,-0.182397127151,-4.45779466629 --13.4299020767,-0.182466104627,-4.57706975937 --13.7619791031,-0.181563615799,-4.73227310181 --13.8510084152,-0.181599199772,-4.81062650681 --13.8820266724,-0.181619867682,-4.87001085281 --13.8540334702,-0.181625068188,-4.90942716599 --13.8450431824,-0.181635200977,-4.95482826233 --13.7670345306,-0.181620895863,-4.95307826996 --13.7530431747,-0.181629642844,-4.99648237228 --17.6558818817,-0.175695672631,-6.41258335114 --17.6519012451,-0.17571388185,-6.47398233414 --17.6399230957,-0.175729945302,-6.53238487244 --17.6629524231,-0.175755783916,-6.60376834869 --17.5549488068,-0.176745757461,-6.62823295593 --17.4409370422,-0.176723763347,-6.61749649048 --17.3989505768,-0.176731601357,-6.66492033005 --17.4239788055,-0.17675794661,-6.7362985611 --23.6854438782,-0.167547360063,-9.15992641449 --25.5879268646,-0.165118828416,-9.9691619873 --17.2680130005,-0.176772773266,-6.86558389664 --21.3350048065,-0.170962870121,-8.50552272797 --26.1331691742,-0.164361596107,-10.4138040543 --22.0542678833,-0.170240536332,-8.98506641388 --26.4994029999,-0.163575574756,-10.845741272 --17.531211853,-0.175961047411,-7.31961154938 --17.4312133789,-0.175952121615,-7.34306764603 --17.4352378845,-0.17597399652,-7.40845727921 --28.0389728546,-0.161166489124,-11.8231515884 --25.6083965302,-0.164472535253,-10.9130353928 --27.9730644226,-0.161226630211,-12.0029640198 --17.1192455292,-0.176951989532,-7.50204610825 --17.0632572174,-0.176955506206,-7.54147386551 --17.0152702332,-0.176961705089,-7.58490228653 --16.9732837677,-0.176969572902,-7.63032436371 --16.9622955322,-0.176976665854,-7.65752983093 --16.9243106842,-0.176985919476,-7.70495176315 --16.9153327942,-0.177004024386,-7.76435089111 --16.8893527985,-0.177017360926,-7.81777000427 --16.8673725128,-0.177031412721,-7.87117528915 --16.8673992157,-0.177052900195,-7.93557310104 --21.0236377716,-0.171416535974,-9.91237926483 --21.2937355042,-0.170518770814,-10.0774078369 --21.1067218781,-0.170487985015,-10.0719175339 --21.1357688904,-0.170527294278,-10.1662902832 --20.7297267914,-0.171453490853,-10.1363344193 --20.7547721863,-0.171491578221,-10.2287111282 --20.8008289337,-0.17153711617,-10.3320770264 --22.0202293396,-0.169962316751,-10.9665021896 --24.8731708527,-0.165960118175,-12.453083992 --27.1299419403,-0.162766396999,-13.6670360565 --24.9362983704,-0.165058925748,-12.6798229218 --25.0864009857,-0.165149450302,-12.8531141281 --26.9450645447,-0.162832573056,-13.8943157196 --26.6400260925,-0.162770047784,-13.8458995819 --26.6670646667,-0.162800759077,-13.9120740891 --26.5921001434,-0.162817686796,-13.9795093536 --26.6041641235,-0.162865251303,-14.0918874741 --23.2940979004,-0.167733669281,-12.4634084702 --26.5822811127,-0.162945255637,-14.2946796417 --26.5483322144,-0.162977263331,-14.3840885162 --26.4903450012,-0.162978693843,-14.4073219299 --26.3093414307,-0.16295722127,-14.4168243408 --22.815164566,-0.167728543282,-12.6284790039 --22.6501579285,-0.167705476284,-12.631978035 --22.7602500916,-0.167783051729,-12.7852983475 --22.8303279877,-0.167846500874,-12.9176425934 --21.9130439758,-0.169542759657,-12.4996318817 --22.7253684998,-0.167864248157,-13.0002975464 --25.9836387634,-0.16312712431,-14.9365615845 --25.1814002991,-0.164868861437,-14.5874729156 --21.8832111359,-0.168659254909,-12.802025795 --21.7322063446,-0.169638440013,-12.8065156937 --21.7642688751,-0.168687686324,-12.9168872833 --22.5366210938,-0.168023481965,-13.4617729187 --22.7958087921,-0.167183354497,-13.7591905594 --22.9679336548,-0.167290970683,-13.9594688416 --23.705286026,-0.166622072458,-14.5003700256 --23.3271961212,-0.166514500976,-14.3730096817 --24.3056545258,-0.164946839213,-15.0707530975 --23.9155883789,-0.165856733918,-14.9885988235 --23.8826370239,-0.165887191892,-15.0720090866 --23.3504772186,-0.166715249419,-14.8447570801 --23.7047538757,-0.165947407484,-15.2743005753 --23.5617580414,-0.16593272984,-15.2877864838 --35.0428199768,-0.149751141667,-22.7664489746 --35.4110336304,-0.14894066751,-23.0823917389 --35.4901771545,-0.149046331644,-23.2917194366 --35.5753250122,-0.149155199528,-23.5060367584 --17.5313930511,-0.174610599875,-11.8750009537 --35.2905311584,-0.14925570786,-23.7983665466 --35.0165138245,-0.14921233058,-23.7759342194 --15.6186618805,-0.176891118288,-10.857676506 --15.5886869431,-0.17690615356,-10.9100990295 --17.2865276337,-0.174680456519,-12.1503534317 --15.7528429031,-0.177034884691,-11.1687850952 --15.8009061813,-0.177085086703,-11.2761526108 --15.7059011459,-0.177071705461,-11.2836141586 --15.6098737717,-0.177043125033,-11.2528772354 --41.5726509094,-0.139774397016,-29.7234535217 --41.6118125916,-0.138886272907,-29.9477977753 --41.398853302,-0.139884442091,-29.9933166504 --41.3539733887,-0.138958930969,-30.1587219238 --41.374130249,-0.139063820243,-30.3720817566 --33.6753463745,-0.15059171617,-24.9327964783 --42.2397994995,-0.13761022687,-31.3070373535 --42.0178375244,-0.137606069446,-31.3485660553 --33.0813293457,-0.151505753398,-24.9001598358 --33.1504821777,-0.150615110993,-25.1144943237 --32.9595031738,-0.151601701975,-25.1340084076 --32.9676246643,-0.150682330132,-25.3023834229 --32.9477310181,-0.150750786066,-25.4517784119 --32.8537406921,-0.150744557381,-25.4620361328 --40.8812294006,-0.13871230185,-31.8217830658 --32.5328025818,-0.151745185256,-25.5430240631 --40.6243972778,-0.139787957072,-32.0337104797 --40.5034866333,-0.139829397202,-32.1451721191 --40.2044754028,-0.13978227973,-32.1147537231 --40.2015533447,-0.139831498265,-32.2159461975 --40.2177200317,-0.139941245317,-32.4363098145 --40.2478942871,-0.139058053493,-32.6676635742 --42.1641578674,-0.136129245162,-34.4296760559 --40.4973602295,-0.139391481876,-33.2912330627 --39.5099449158,-0.139991760254,-32.6933097839 --39.2429466248,-0.140957117081,-32.6808738708 --31.4353942871,-0.151986867189,-26.3176250458 --31.5996170044,-0.152152463794,-26.6218910217 --30.8372840881,-0.152837157249,-26.1518192291 --31.1916217804,-0.152102679014,-26.6169490814 --31.3828659058,-0.152284920216,-26.9481945038 --30.4994487762,-0.15289953351,-26.3632106781 --30.4575481415,-0.152957648039,-26.4936256409 --30.3875675201,-0.152960732579,-26.5168685913 --30.167552948,-0.153923243284,-26.4924068451 --30.2937602997,-0.153072744608,-26.7707023621 --30.0387229919,-0.153015747666,-26.7142696381 --30.0478572845,-0.153102919459,-26.8916492462 --30.1430473328,-0.153237625957,-27.1459655762 --30.0921421051,-0.153292357922,-27.2703857422 --29.930103302,-0.153244569898,-27.2106971741 --29.7971420288,-0.153253361583,-27.260175705 --30.0264263153,-0.153465941548,-27.6413936615 --29.7683868408,-0.153405308723,-27.5779666901 --30.1837997437,-0.152725279331,-28.1340465546 --30.0758609772,-0.152750551701,-28.2105102539 --30.1920776367,-0.151904016733,-28.4958095551 --29.6277561188,-0.153623342514,-28.0554141998 --29.1845855713,-0.153454169631,-27.814125061 --29.17070961,-0.153531432152,-27.9745178223 --29.2228813171,-0.153648331761,-28.1998672485 --29.1089363098,-0.153668135405,-28.2663345337 --28.9379520416,-0.153654366732,-28.2778453827 --28.8580322266,-0.153694391251,-28.3772926331 --28.8440914154,-0.153729990125,-28.452495575 --28.7431564331,-0.153756856918,-28.5299530029 --30.622674942,-0.150978565216,-30.5669498444 --30.3908081055,-0.151029095054,-30.7188892365 --30.2848796844,-0.151060268283,-30.804353714 --36.6118278503,-0.141059815884,-37.4120254517 --30.1980438232,-0.151151791215,-31.0059928894 --30.1231384277,-0.15120203793,-31.1224327087 --27.9766368866,-0.153956606984,-29.1064186096 --28.0058021545,-0.154065802693,-29.3187828064 --27.736738205,-0.15398748219,-29.2223720551 --27.7028560638,-0.154056817293,-29.3687820435 --28.9199714661,-0.151928707957,-30.8392601013 --27.3758144379,-0.154985547066,-29.2996101379 --27.2818832397,-0.155016764998,-29.3830680847 --28.2858448029,-0.152760893106,-30.643699646 --28.1779117584,-0.152787044644,-30.7191638947 --28.0859909058,-0.152824059129,-30.8126220703 --26.7700538635,-0.155051618814,-29.5670013428 --27.173538208,-0.154412910342,-30.1960830688 --28.5147418976,-0.15235504508,-31.7712612152 --28.7571105957,-0.15161895752,-32.2404632568 --28.6872158051,-0.151674672961,-32.3649024963 --26.3683872223,-0.155205026269,-29.9610519409 --26.2784614563,-0.155238613486,-30.0475082397 --26.0854473114,-0.155201748013,-30.0170440674 --26.2746887207,-0.155379936099,-30.3280925751 --26.333896637,-0.154517695308,-30.587436676 --26.4921951294,-0.154725819826,-30.9637031555 --27.9796886444,-0.15186829865,-32.89295578 --27.834728241,-0.151872068644,-32.9304504395 --26.5116939545,-0.154040083289,-31.5778522491 --35.4420509338,-0.138515233994,-42.3823776245 --27.3057594299,-0.152815178037,-32.9290161133 --27.3128528595,-0.151873886585,-33.0422058105 --27.1829051971,-0.151888012886,-33.0966949463 --27.1600570679,-0.151979133487,-33.2790985107 --25.9771118164,-0.154221281409,-32.0464019775 --23.9483375549,-0.157829612494,-29.755355835 --23.8734226227,-0.157870665193,-29.8528060913 --23.7303638458,-0.157812491059,-29.770111084 --23.8906764984,-0.157029598951,-30.1613769531 --23.3462982178,-0.157717704773,-29.6691875458 --23.5016117096,-0.157932937145,-30.0574607849 --24.0943622589,-0.156483575702,-31.0063915253 --24.0144462585,-0.156524091959,-31.1028423309 --24.0886878967,-0.156684085727,-31.3991756439 --24.0717544556,-0.15572284162,-31.4783840179 --22.3571662903,-0.159491971135,-29.4471130371 --24.0550785065,-0.155919656157,-31.8651771545 --24.1283283234,-0.156084194779,-32.1695137024 --23.56291008,-0.156743481755,-31.6273460388 --22.9944801331,-0.157395377755,-31.0721817017 --22.5922203064,-0.158176288009,-30.7328891754 --22.343038559,-0.158027410507,-30.4972820282 --22.3902549744,-0.158167928457,-30.7606372833 --23.5416793823,-0.156211227179,-32.5391235352 --22.8611125946,-0.156763061881,-31.8150520325 --22.2726364136,-0.157384380698,-31.206905365 --22.0795974731,-0.15833067894,-31.1444530487 --21.9155864716,-0.15829923749,-31.1189746857 --21.6924209595,-0.158165127039,-30.9073467255 --21.5594425201,-0.158158704638,-30.9238471985 --21.3333587646,-0.159072697163,-30.8064193726 --21.1162796021,-0.158992245793,-30.6979846954 --20.8321228027,-0.159853562713,-30.4916038513 --20.6420726776,-0.159794539213,-30.4191493988 --22.1650447845,-0.156227856874,-32.8593292236 --21.6285037994,-0.157816246152,-32.1799545288 --21.6507148743,-0.156947672367,-32.4283294678 --21.8871860504,-0.157271131873,-33.0005302429 --21.2736320496,-0.157840237021,-32.3014144897 --22.0748023987,-0.155673921108,-33.7341690063 --21.3961601257,-0.157180443406,-32.9291038513 --21.1990146637,-0.157060563564,-32.7404594421 --20.8217334747,-0.157832369208,-32.3821563721 --20.6036491394,-0.158748105168,-32.2667274475 --20.8221168518,-0.158065378666,-32.8289451599 --20.6751251221,-0.158047407866,-32.8254585266 --20.3769359589,-0.157885909081,-32.5790939331 --16.1376113892,-0.166004270315,-26.0459156036 --15.9935731888,-0.166960388422,-25.9964332581 --15.8003950119,-0.166822597384,-25.7757892609 --15.7514801025,-0.166867032647,-25.8752269745 --15.7035675049,-0.166913166642,-25.9776630402 --15.5705432892,-0.166877701879,-25.9421730042 --15.5126171112,-0.16691441834,-26.0286178589 --15.7360801697,-0.166229143739,-26.5858364105 --15.7762145996,-0.166316613555,-26.7460002899 --15.215596199,-0.166856274009,-25.990858078 --21.3193149567,-0.154072850943,-36.5462646484 --21.5128211975,-0.153407588601,-37.140499115 --21.6833000183,-0.153722777963,-37.701751709 --21.3560714722,-0.153531998396,-37.4054107666 --21.1590251923,-0.153473302722,-37.3329696655 --21.1010608673,-0.153485000134,-37.3662109375 --20.9711112976,-0.153493672609,-37.4077110291 --20.8501739502,-0.15351177752,-37.4652061462 --15.008685112,-0.166482582688,-27.2584228516 --14.9217281342,-0.166494458914,-27.3028964996 --13.6790103912,-0.168265804648,-25.2403202057 --16.6927947998,-0.161617904902,-30.9582328796 --16.6408119202,-0.161620825529,-30.9754714966 --16.5558853149,-0.161650434136,-31.0509414673 --16.4469165802,-0.161652013659,-31.0784282684 --16.3870277405,-0.161708772182,-31.1998767853 --16.3381576538,-0.161778464913,-31.3433151245 --13.4727554321,-0.167681872845,-26.1010990143 --13.3978052139,-0.167699471116,-26.1545639038 --13.3007326126,-0.168640956283,-26.0668430328 --14.1483001709,-0.165715619922,-27.9195404053 --14.1214437485,-0.165796935558,-28.0819644928 --14.1727180481,-0.165969312191,-28.3993186951 --12.6182851791,-0.169264033437,-25.5190219879 --12.4291334152,-0.16914331913,-25.3365802765 --13.3027181625,-0.167230680585,-27.201051712 --12.2400665283,-0.169072255492,-25.2503414154 --12.1590976715,-0.169078245759,-25.2838134766 --12.0360546112,-0.170033246279,-25.2303180695 --5.54977464676,-0.184251889586,-11.9995012283 --5.50777006149,-0.184243872762,-12.005944252 --5.51882553101,-0.184279233217,-12.0761365891 --5.56999349594,-0.184389218688,-12.2845115662 --17.5021839142,-0.15555369854,-38.1959037781 --12.4930953979,-0.167323797941,-27.5845527649 --12.3582420349,-0.167389258742,-27.7434711456 --16.3180713654,-0.157694354653,-36.8315010071 --16.2921619415,-0.156743705273,-36.9287261963 --15.2684469223,-0.159554585814,-34.9219970703 --15.1544904709,-0.159560665488,-34.9574928284 --14.7850265503,-0.160222932696,-34.4052085876 --14.6039304733,-0.160134971142,-34.2797660828 --14.5190267563,-0.160177320242,-34.3772392273 --17.4162406921,-0.152342021465,-41.5281486511 --11.0895709991,-0.168779686093,-26.9121780396 --17.0443077087,-0.152315139771,-41.5484657288 --12.4671726227,-0.164141178131,-31.0272102356 --10.9661712646,-0.168113127351,-27.5769023895 --12.3143453598,-0.164216279984,-31.2041454315 --10.1737623215,-0.170146971941,-25.9561901093 --12.1984767914,-0.164273604751,-31.3388519287 --10.0318698883,-0.170186460018,-26.0701236725 --9.42069721222,-0.171390980482,-24.7290534973 --9.30663967133,-0.171337768435,-24.6605567932 --9.21363067627,-0.171316549182,-24.6470451355 --9.11861610413,-0.171291843057,-24.6275348663 --9.07160758972,-0.171278491616,-24.6157741547 --8.98962402344,-0.171274095774,-24.6312541962 --8.91164588928,-0.171273976564,-24.6537265778 --8.85171318054,-0.171303480864,-24.7271842957 --7.37648010254,-0.175148487091,-21.0702762604 --7.33246135712,-0.17512999475,-21.0495185852 --7.26547527313,-0.175127357244,-21.0669841766 --7.19648599625,-0.175121739507,-21.0794525146 --7.12949848175,-0.175118014216,-21.09491539 --7.09660387039,-0.175174504519,-21.2143554688 --7.03563451767,-0.175182312727,-21.2498149872 --6.9716591835,-0.175185933709,-21.2782802582 --6.96373510361,-0.175229072571,-21.363489151 --7.48234653473,-0.173264861107,-23.1684455872 --7.40736103058,-0.173260107636,-23.1829204559 --7.35042285919,-0.173286810517,-23.2513771057 --7.26841688156,-0.17326875031,-23.2428569794 --9.96735954285,-0.16439217329,-32.0908927917 --6.36135482788,-0.17590290308,-20.9456691742 --6.22415876389,-0.175764426589,-20.7292003632 --6.18123912811,-0.175804018974,-20.8196487427 --6.10321474075,-0.175776347518,-20.7941265106 --6.04424619675,-0.175784677267,-20.8305873871 --6.02138900757,-0.175864338875,-20.9900131226 --5.95941638947,-0.175869569182,-21.0214805603 --5.93946218491,-0.175892904401,-21.0727005005 --5.84237575531,-0.175825282931,-20.9781970978 --5.75030422211,-0.175767421722,-20.9006881714 --5.73147058487,-0.175861284137,-21.0851154327 --5.66347360611,-0.175851121545,-21.0895805359 --5.60150146484,-0.17585632205,-21.1210479736 --6.22687864304,-0.173353686929,-23.7309055328 --5.61290216446,-0.17609231174,-21.5626564026 --5.56096887589,-0.175121843815,-21.6361122131 --5.5541973114,-0.175253644586,-21.8865280151 --8.09257602692,-0.165168508887,-32.1376724243 --7.89625930786,-0.164947941899,-31.7812576294 --6.43123960495,-0.17076292634,-26.2959804535 --7.75754547119,-0.165087208152,-32.0722007751 --5.77726221085,-0.173494532704,-24.136177063 --5.6922416687,-0.173466950655,-24.111661911 --5.6272983551,-0.173487856984,-24.171131134 --5.5483007431,-0.173474654555,-24.1716117859 --5.50745201111,-0.172554552555,-24.3330554962 --5.52987194061,-0.172802016139,-24.7854499817 --6.94887065887,-0.165541559458,-31.2773780823 --5.44502353668,-0.171873897314,-24.9451389313 --6.60630226135,-0.166146919131,-30.6435070038 --6.52538967133,-0.166181847453,-30.7289886475 --6.45051002502,-0.166236773133,-30.8494682312 --6.36357402802,-0.166256681085,-30.908952713 --4.70250463486,-0.173855304718,-23.2958621979 --4.63855648041,-0.173873245716,-23.3503303528 --4.55232810974,-0.174725085497,-23.1046104431 --4.46627759933,-0.174679517746,-23.0491046906 --4.41136980057,-0.174722760916,-23.1475658417 --5.8146238327,-0.166177600622,-30.9107093811 --5.08548116684,-0.170224383473,-27.5417785645 --5.00151157379,-0.170225396752,-27.5682697296 --4.18353176117,-0.173772647977,-23.3162078857 --4.11355876923,-0.173774808645,-23.3436870575 --4.03754997253,-0.173755228519,-23.3331642151 --3.99472641945,-0.173848673701,-23.5196208954 --3.93380522728,-0.17388240993,-23.6020889282 --3.86383366585,-0.173885151744,-23.6305618286 --3.80090641975,-0.173914760351,-23.7060317993 --3.76592040062,-0.173916131258,-23.7202682495 --3.70702052116,-0.173962324858,-23.8247356415 --3.63303041458,-0.173953458667,-23.8332157135 --3.60130882263,-0.173107340932,-24.12566185 --3.52832746506,-0.173103630543,-24.1431369781 --3.5016541481,-0.173286110163,-24.4855747223 --3.54144001007,-0.171745344996,-25.3109531403 --3.47828483582,-0.172643840313,-25.1462173462 --3.43856406212,-0.171796157956,-25.4366703033 --3.37165927887,-0.171837329865,-25.5331401825 --3.2997276783,-0.171862259507,-25.6016235352 --3.11495471001,-0.172381609678,-24.7872066498 --3.03594827652,-0.172362044454,-24.7776927948 --3.10510921478,-0.172041729093,-25.9900436401 --3.06411027908,-0.172034099698,-25.9892883301 --1.81450712681,-0.181276842952,-15.9487991333 --1.76549959183,-0.181263372302,-15.9472522736 --2.68191695213,-0.173272624612,-24.7328777313 --2.75022578239,-0.171035945415,-26.0932292938 --2.67428779602,-0.17105589807,-26.153717041 --2.61954879761,-0.171194165945,-26.4211826324 --2.58461284637,-0.171223551035,-26.4854202271 --2.51171970367,-0.171269640326,-26.5919055939 --2.42569565773,-0.171238064766,-26.5624008179 --2.3366253376,-0.171179249883,-26.4848918915 --2.24351334572,-0.171095758677,-26.3643951416 --2.19389510155,-0.170303717256,-26.7548561096 --2.12203979492,-0.170371234417,-26.8993377686 --2.08814001083,-0.170421510935,-27.0005779266 --2.00415420532,-0.170411884785,-27.0100727081 --1.92826724052,-0.170460447669,-27.1215591431 --1.86760902405,-0.169642716646,-27.4680328369 --1.78972673416,-0.169693350792,-27.5835208893 --1.70778214931,-0.169707596302,-27.635011673 --1.61670815945,-0.169645950198,-27.5535125732 --1.57167994976,-0.169620200992,-27.5217647552 --1.47853624821,-0.170518353581,-27.3692626953 --2.01025319099,-0.158314958215,-39.3512077332 --1.89645767212,-0.158406227827,-39.5427360535 --1.84195160866,-0.156245172024,-41.0502052307 --2.07642436028,-0.148124456406,-49.6724090576 --2.00252366066,-0.148164212704,-49.7596893311 --1.8978959322,-0.146921917796,-51.1292076111 --1.74410235882,-0.147004276514,-51.3097724915 --1.5882588625,-0.146057635546,-51.4393386841 --1.42621159554,-0.14599353075,-51.361907959 --1.26520729065,-0.146954253316,-51.3284797668 --1.04419779778,-0.145466923714,-52.2873191833 --0.883364617825,-0.145524710417,-52.4258918762 --0.557525873184,-0.145540848374,-52.5280418396 --0.395807564259,-0.144663363695,-52.7816162109 --0.23187315464,-0.144662439823,-52.8171920776 -0.0561503618956,-0.124371439219,-43.1721153259 -0.193126142025,-0.12442099303,-43.1703948975 -0.328936398029,-0.124564416707,-43.0016784668 -0.540479540825,-0.123310282826,-43.5840873718 -0.678442120552,-0.123367376626,-43.5693626404 -0.819525003433,-0.12335665524,-43.6766433716 -0.890633106232,-0.12331341207,-43.7977790833 -1.03689730167,-0.123200751841,-44.089050293 -1.17168986797,-0.123353525996,-43.9023323059 -1.46357119083,-0.1126492396,-48.8844680786 -1.61854815483,-0.112701810896,-48.8897247314 -1.5762566328,-0.123704023659,-43.5321807861 -1.65785002708,-0.127525746822,-42.1225166321 -1.71664524078,-0.127657428384,-41.9246635437 -1.84143817425,-0.127807289362,-41.7349586487 -1.96933138371,-0.127900734544,-41.6472473145 -2.10334587097,-0.127926558256,-41.6835289001 -2.2322537899,-0.128011748195,-41.6108207703 -2.36421656609,-0.128066450357,-41.5941085815 -2.48400163651,-0.129218995571,-41.3954086304 -2.49208927155,-0.130740866065,-40.4696044922 -2.61599183083,-0.13082768023,-40.3899040222 -2.7490298748,-0.130839645863,-40.4491882324 -2.94796729088,-0.128355562687,-41.4344139099 -3.08601570129,-0.12836265564,-41.5056991577 -3.12179589272,-0.131066560745,-40.269077301 -3.27486348152,-0.129496470094,-41.3811416626 -3.30565834045,-0.131190851331,-40.1575279236 -3.43060159683,-0.131254464388,-40.1188240051 -3.55959105492,-0.131292551756,-40.1281166077 -3.68352460861,-0.131361231208,-40.0794143677 -3.80241370201,-0.132453769445,-39.9847183228 -3.92534852028,-0.132521361113,-39.9370155334 -3.99337244034,-0.132524430752,-39.9721603394 -4.11428833008,-0.132602363825,-39.904460907 -4.23924350739,-0.132658720016,-39.8777618408 -4.36419296265,-0.13271830976,-39.8450584412 -4.45687675476,-0.132921129465,-39.5353851318 -4.57780838013,-0.13298971951,-39.4836883545 -4.69974708557,-0.133054643869,-39.4389915466 -4.84035348892,-0.131743356586,-40.083065033 -4.98948526382,-0.131704643369,-40.2413444519 -5.0831990242,-0.131890594959,-39.9616699219 -5.30485391617,-0.130570754409,-40.6698799133 -5.39957857132,-0.131750762463,-40.4012107849 -5.51444673538,-0.131853565574,-40.2835235596 -5.63134098053,-0.131941944361,-40.1928291321 -5.69129514694,-0.131982445717,-40.1549835205 -8.69310569763,-0.0909871086478,-60.0035743713 -5.68555307388,-0.135973632336,-38.3578224182 -5.81356048584,-0.136000230908,-38.3841209412 -5.93854761124,-0.136037379503,-38.3894233704 -6.06856155396,-0.136060640216,-38.4227180481 -6.66229295731,-0.129646271467,-41.3355865479 -6.74436903,-0.129622116685,-41.4277191162 -6.83711147308,-0.129790872335,-41.1760520935 -7.49601507187,-0.123292982578,-44.2828559875 -7.62993431091,-0.123370319605,-44.2221488953 -6.84625148773,-0.136421501637,-38.2157211304 -6.9132642746,-0.136429950595,-38.2388725281 -7.04427814484,-0.136452972889,-38.2721633911 -7.16925621033,-0.136494845152,-38.2674713135 -7.30227708817,-0.135513991117,-38.3087692261 -7.63124132156,-0.134042024612,-39.3598823547 -7.77328252792,-0.134051576257,-39.4241714478 -7.93240022659,-0.133021637797,-39.5704460144 -7.99437618256,-0.13304977119,-39.554599762 -8.12636089325,-0.133088827133,-39.5588989258 -8.21917438507,-0.134215965867,-39.3792304993 -8.33207893372,-0.134296312928,-39.2965545654 -8.43494129181,-0.134399026632,-39.1668815613 -8.58902549744,-0.134385734797,-39.2791595459 -8.66076278687,-0.134552046657,-39.0145149231 -8.73980903625,-0.134543776512,-39.0746536255 -6.19786596298,-0.15918725729,-27.2503929138 -6.2778134346,-0.159235954285,-27.2007389069 -9.09762477875,-0.134730681777,-38.9335899353 -9.27378559113,-0.134678825736,-39.1288528442 -6.33662557602,-0.161927014589,-25.9373607635 -6.43181562424,-0.160841196775,-26.146484375 -10.8507604599,-0.127343416214,-42.4887428284 -7.46621322632,-0.155713632703,-28.7922286987 -10.9430370331,-0.128774628043,-41.7445030212 -7.78763103485,-0.154549226165,-29.267780304 -11.3421363831,-0.128806784749,-41.9112052917 -11.499162674,-0.127825975418,-41.9644889832 -8.27103996277,-0.153425619006,-29.7518215179 -8.71929740906,-0.152380630374,-30.069890976 -8.81125259399,-0.152426421642,-30.0312309265 -8.89317417145,-0.152488946915,-29.955581665 -8.97710704803,-0.153545558453,-29.8919258118 -9.05903339386,-0.153605759144,-29.8202762604 -9.14898300171,-0.153654322028,-29.7746200562 -9.17690849304,-0.153702899814,-29.696805954 -9.24179077148,-0.153784513474,-29.5751667023 -9.34377765656,-0.153814509511,-29.5704994202 -9.42971801758,-0.153866887093,-29.5148468018 -9.51365756989,-0.153919696808,-29.4571933746 -9.55246829987,-0.154035761952,-29.2555828094 -9.66348266602,-0.154052108526,-29.2809085846 -9.76160430908,-0.154004395008,-29.4220333099 -20.8480682373,-0.0856966227293,-62.4386024475 -13.5159950256,-0.13249130547,-39.9735565186 -13.6168708801,-0.132583409548,-39.8548927307 -13.7357969284,-0.132649883628,-39.7942123413 -13.8737697601,-0.132694751024,-39.7845191956 -18.6023769379,-0.105130717158,-52.8827667236 -15.288772583,-0.125295519829,-43.2019119263 -15.0046596527,-0.127864912152,-41.9705924988 -18.9449825287,-0.105424135923,-52.5275421143 -19.1650295258,-0.10544295609,-52.6167831421 -19.4392032623,-0.105400800705,-52.8509750366 -20.8751468658,-0.0980380326509,-56.2231445312 -21.0490436554,-0.0981315970421,-56.1464271545 -19.8539829254,-0.105610482395,-52.6906929016 -20.0629940033,-0.105646766722,-52.739944458 -20.1968326569,-0.105765543878,-52.5912590027 -20.4188728333,-0.104787960649,-52.6734962463 -21.5479507446,-0.0998478755355,-55.0809440613 -21.6877841949,-0.0999710261822,-54.9272575378 -21.7795085907,-0.101143740118,-54.6526107788 -21.8905162811,-0.101161785424,-54.6807327271 -21.1855182648,-0.105143271387,-52.4297828674 -23.5902404785,-0.0939737409353,-57.8801231384 -22.1456756592,-0.102686025202,-53.8308181763 -22.7565078735,-0.100339710712,-54.8277206421 -22.8632736206,-0.100492589176,-54.5970649719 -21.7828063965,-0.106662802398,-51.7742195129 -20.9977664948,-0.11165048182,-49.4603347778 -22.0444908142,-0.10689086467,-51.4838638306 -22.2324523926,-0.106950081885,-51.4741363525 -22.3222160339,-0.107099756598,-51.2374954224 -22.4149875641,-0.108246400952,-51.0078544617 -22.663066864,-0.107250750065,-51.1350746155 -22.8141593933,-0.107229031622,-51.2591629028 -22.9169521332,-0.107365570962,-51.0535087585 -23.1790542603,-0.107360094786,-51.2067184448 -23.7226810455,-0.105115190148,-51.972694397 -24.3895282745,-0.103771619499,-52.9955596924 -25.0142803192,-0.10147254914,-53.9104614258 -24.5800685883,-0.104065999389,-52.5332717896 -24.8032741547,-0.103993318975,-52.7943000793 -25.1104316711,-0.102965511382,-53.0144729614 -25.4867076874,-0.101884461939,-53.3745918274 -25.5884895325,-0.103026352823,-53.1559486389 -25.6291618347,-0.103216134012,-52.8113517761 -25.8671855927,-0.103248752654,-52.8765869141 -26.0911827087,-0.103292837739,-52.9118385315 -26.1731300354,-0.103338733315,-52.8669891357 -29.1848888397,-0.0912607908249,-58.5138778687 -19.0132389069,-0.135158717632,-37.7309150696 -30.1326293945,-0.0890280753374,-59.4779624939 -30.5559024811,-0.0879569351673,-59.8450508118 -31.1259765625,-0.0870225280523,-60.0264549255 -30.7301177979,-0.0894254595041,-59.0310134888 -30.831861496,-0.0895862877369,-58.7733726501 -31.066822052,-0.0896526351571,-58.7706184387 -31.2707309723,-0.0897420868278,-58.7058944702 -33.5979728699,-0.0813752934337,-62.6173858643 -33.8008499146,-0.081481128931,-62.5206642151 -30.052444458,-0.0973390936852,-54.9354629517 -30.1391983032,-0.0974912047386,-54.6828346252 -30.27302742,-0.0976119786501,-54.5161705017 -30.4228801727,-0.0977205634117,-54.3814926147 -30.5947685242,-0.0978140234947,-54.2877883911 -30.8007068634,-0.0978864654899,-54.2530632019 -30.9477386475,-0.0978955999017,-54.3121604919 -31.2367954254,-0.0979174971581,-54.4203681946 -33.2863883972,-0.0908593088388,-57.5861167908 -30.1293125153,-0.117944888771,-43.7138252258 -32.4862442017,-0.112298808992,-46.2092666626 -23.6248435974,-0.152719795704,-26.0023937225 -23.6487998962,-0.152748137712,-25.9465942383 -38.6530647278,-0.120194114745,-38.4744300842 -38.596824646,-0.12031327188,-38.1749267578 -38.5165710449,-0.120436131954,-37.8554382324 -38.3223304749,-0.121533282101,-37.5438079834 -50.5690536499,-0.0928188711405,-49.3131790161 -50.8850212097,-0.0918839275837,-49.3104095459 -50.9618225098,-0.0930034220219,-49.0738143921 -51.4869384766,-0.0920223519206,-49.2708930969 -50.9072723389,-0.0932852104306,-48.4057846069 -49.5200462341,-0.0977174565196,-46.7832717896 -48.1529693604,-0.101074419916,-45.341506958 -47.0489730835,-0.103431746364,-44.016784668 -23.6396446228,-0.158438667655,-21.8494033813 -23.6325378418,-0.158494651318,-21.7048435211 -22.9529743195,-0.160687446594,-20.9387779236 -22.939868927,-0.160742223263,-20.7932262421 -22.9467773438,-0.160792186856,-20.6676578522 -23.220911026,-0.160763561726,-20.8516750336 -23.2648429871,-0.160806372762,-20.7590770721 -23.4008350372,-0.160831704736,-20.748418808 -16.1580352783,-0.177250877023,-14.1560792923 -16.1759872437,-0.177278980613,-14.082490921 -16.2299633026,-0.177300632,-14.0398807526 -16.190908432,-0.177323639393,-13.9601259232 -15.7325601578,-0.1784376055,-13.4698867798 -15.7425107956,-0.178465425968,-13.3923063278 -15.7334508896,-0.178496330976,-13.298740387 -15.9515304565,-0.178488105536,-13.3990192413 -15.6192722321,-0.179573789239,-13.0306806564 -15.4601211548,-0.179629057646,-12.8112268448 -15.515130043,-0.179633319378,-12.8173961639 -12.3161535263,-0.187186032534,-10.0560827255 -8.29171276093,-0.195857286453,-6.64428281784 -8.23666191101,-0.195876047015,-6.5547451973 -8.28267288208,-0.195878461003,-6.54913711548 -8.33268547058,-0.195880323648,-6.54652643204 -8.36968898773,-0.195884302258,-6.53292608261 -8.38168811798,-0.195887207985,-6.52112722397 -8.41068744659,-0.19589227438,-6.50152683258 -8.43668556213,-0.1958976686,-6.47992324829 -8.45468044281,-0.19590434432,-6.45133113861 -8.4836807251,-0.195909544826,-6.4307384491 -8.48966693878,-0.195917934179,-6.39216041565 -8.53867816925,-0.195920199156,-6.38754987717 -8.54767513275,-0.195923358202,-6.3737487793 -8.57467365265,-0.195928618312,-6.35214996338 -8.59867095947,-0.195934399962,-6.32755947113 -8.62467002869,-0.195939794183,-6.30496311188 -8.64966678619,-0.195945322514,-6.28136920929 -8.67566585541,-0.195950657129,-6.25877189636 -8.70266437531,-0.195955976844,-6.23618030548 -8.7206659317,-0.195958048105,-6.22837972641 -8.74766540527,-0.195963144302,-6.20677757263 -8.76666069031,-0.195969387889,-6.178191185 -8.79465961456,-0.195974439383,-6.15659475327 -8.82165813446,-0.195979639888,-6.1340007782 -8.85466003418,-0.195984005928,-6.11639595032 -8.8696603775,-0.195986539125,-6.10560321808 -8.88265228271,-0.195993036032,-6.0740070343 -8.91465377808,-0.194997698069,-6.0544128418 -8.94365406036,-0.19500246644,-6.03380918503 -8.96364879608,-0.195008456707,-6.00522756577 -8.99565029144,-0.195013061166,-5.98563146591 -9.02264976501,-0.195017889142,-5.96402359009 -9.03965091705,-0.195020198822,-5.95423126221 -9.06264781952,-0.195025607944,-5.92863702774 -9.08664512634,-0.195030838251,-5.9040389061 -9.11664485931,-0.195035651326,-5.88244628906 -9.14764595032,-0.19504031539,-5.86184930801 -9.1696434021,-0.195045754313,-5.83525753021 -9.24866485596,-0.195046126842,-5.84662437439 -9.17662620544,-0.195055991411,-5.77888011932 -9.19762229919,-0.195061460137,-5.75129318237 -9.2636384964,-0.195063203573,-5.75267839432 -9.2946395874,-0.195067733526,-5.73207712173 -9.31763648987,-0.195072874427,-5.7064781189 -13.7425260544,-0.186740770936,-8.47001647949 -13.630449295,-0.186763927341,-8.33951759338 -13.6954641342,-0.18676635623,-8.35068702698 -13.5663805008,-0.187790289521,-8.21020317078 -13.5603523254,-0.187804609537,-8.14862728119 -13.5953388214,-0.187816306949,-8.11103534698 -12.5018634796,-0.18990328908,-7.38518047333 -12.5038423538,-0.189914807677,-7.33359956741 -13.5942726135,-0.187850654125,-7.9651017189 -13.501209259,-0.187869921327,-7.85158824921 -13.3521242142,-0.187892273068,-7.70511627197 -13.3891143799,-0.187902867794,-7.67051887512 -13.3170623779,-0.187919676304,-7.57199192047 -13.5841417313,-0.187917336822,-7.67124938965 -13.3250160217,-0.188944026828,-7.46484327316 -13.2999954224,-0.188951358199,-7.42306995392 -13.3820028305,-0.188959240913,-7.41444587708 -13.4219942093,-0.188969269395,-7.38184595108 -13.3709526062,-0.188983589411,-7.29830121994 -13.3059053421,-0.188998416066,-7.20677137375 -13.3008823395,-0.189010217786,-7.14920377731 -13.3888912201,-0.189017727971,-7.14357328415 -13.3848791122,-0.189023673534,-7.1137919426 -13.4128665924,-0.189033731818,-7.07519721985 -13.3958387375,-0.189045637846,-7.01163578033 -13.5318651199,-0.189051479101,-7.03097343445 -13.5028333664,-0.189063623548,-6.96141672134 -13.7198867798,-0.188067123294,-7.02170944214 -13.7838869095,-0.188076242805,-7.00009965897 -13.5668020248,-0.189088836312,-6.85944843292 -13.524766922,-0.189100846648,-6.7839012146 -13.4587240219,-0.189113348722,-6.69636964798 -13.4767093658,-0.189123108983,-6.65278291702 -13.5217037201,-0.189132228494,-6.62218475342 -13.5606956482,-0.189141482115,-6.58858919144 -13.5356779099,-0.189147099853,-6.54981613159 -13.5646677017,-0.189156487584,-6.51122665405 -13.6426725388,-0.189164638519,-6.49759960175 -13.7866973877,-0.189171761274,-6.51493883133 -13.7946796417,-0.189181655645,-6.46536254883 -13.8196687698,-0.189191043377,-6.42476987839 -13.791639328,-0.189201325178,-6.35821533203 -13.8456459045,-0.189205378294,-6.35739612579 -14.0746955872,-0.188212156296,-6.41168785095 -14.3277521133,-0.188218921423,-6.47695493698 -14.3607416153,-0.188228592277,-6.43835783005 -14.4147367477,-0.188238143921,-6.40875291824 -14.3506975174,-0.188248798251,-6.32422685623 -14.6477632523,-0.188256531954,-6.40546512604 -14.6587562561,-0.188261568546,-6.38267421722 -14.7157526016,-0.187271371484,-6.35306739807 -14.8547706604,-0.187280997634,-6.3594121933 -15.0237970352,-0.18729069829,-6.37873363495 -15.3698701859,-0.18630091846,-6.4729552269 -15.1817979813,-0.187311246991,-6.33450031281 -15.2017831802,-0.18732124567,-6.28790903091 -15.166762352,-0.187326312065,-6.24415016174 -15.2827730179,-0.187336727977,-6.23750686646 -17.2452659607,-0.183357864618,-7.00373888016 -17.2862529755,-0.183370426297,-6.95814037323 -17.3232364655,-0.183383181691,-6.90955209732 -17.3772239685,-0.183395832777,-6.86894655228 -17.4092178345,-0.18340228498,-6.85014343262 -17.4592075348,-0.183415099978,-6.80654668808 -17.5151958466,-0.183427840471,-6.76594114304 -17.5571804047,-0.183440431952,-6.71934604645 -17.609167099,-0.183453306556,-6.67574977875 -17.6641559601,-0.183466017246,-6.63414478302 -17.6951389313,-0.183478429914,-6.58255767822 -17.7371368408,-0.183485120535,-6.56674957275 -17.7941246033,-0.183497920632,-6.52514457703 -17.8441123962,-0.183510616422,-6.48054504395 -17.8910961151,-0.183523371816,-6.43395185471 -17.9440841675,-0.183536067605,-6.39034891129 -17.9850692749,-0.183548554778,-6.34175539017 -18.0220661163,-0.183555275202,-6.32295179367 -18.0200405121,-0.183566659689,-6.25838565826 -18.0670280457,-0.183579176664,-6.21178817749 -18.0930080414,-0.183591172099,-6.1572060585 -18.1539974213,-0.183603987098,-6.11559724808 -18.1949825287,-0.183616355062,-6.06600618362 -18.2679748535,-0.1836296767,-6.02739477158 -18.2829647064,-0.183635666966,-6.00060224533 -18.3599567413,-0.182649150491,-5.96298742294 -18.3869400024,-0.18266095221,-5.90840196609 -18.4589309692,-0.18267442286,-5.86779546738 -18.4819107056,-0.182685911655,-5.81220912933 -18.5489025116,-0.182699203491,-5.76960420609 -18.589887619,-0.182711392641,-5.71901130676 -18.6488857269,-0.182719126344,-5.70519685745 -18.690870285,-0.182731360197,-5.65460252762 -18.7418556213,-0.182744055986,-5.60600709915 -18.7998447418,-0.182756870985,-5.56040048599 -18.846830368,-0.182769432664,-5.50981044769 -18.9108181,-0.182782575488,-5.46520280838 -18.9538021088,-0.182794839144,-5.41361045837 -19.0258045197,-0.182803303003,-5.40278434753 -19.1257991791,-0.182818353176,-5.36716127396 -19.1787853241,-0.182831183076,-5.31756353378 -19.2357730865,-0.181844189763,-5.26896381378 -19.2937583923,-0.181857258081,-5.22036314011 -19.3477458954,-0.181870058179,-5.17076253891 -19.392742157,-0.181877538562,-5.14995765686 -19.4387264252,-0.181889995933,-5.09736442566 -19.4957122803,-0.181902989745,-5.04776334763 -19.5567016602,-0.181916192174,-4.99915885925 -19.6096858978,-0.181929036975,-4.94756269455 -19.6586723328,-0.181941598654,-4.894967556 -19.7156600952,-0.181954756379,-4.84337282181 -19.768655777,-0.181962653995,-4.82455682755 -19.8246421814,-0.181975662708,-4.77295827866 -19.8756275177,-0.181988433003,-4.71936511993 -19.9276123047,-0.182001113892,-4.66676568985 -19.9855995178,-0.182014346123,-4.61417102814 -20.0495853424,-0.182027846575,-4.5635676384 -20.099571228,-0.181040495634,-4.50897407532 -20.146566391,-0.181048199534,-4.48716259003 -20.2035522461,-0.18106135726,-4.43356704712 -20.2635402679,-0.181074634194,-4.38096570969 -20.3205242157,-0.181087702513,-4.32736635208 -20.3855133057,-0.181101411581,-4.27476596832 -20.4404983521,-0.181114345789,-4.22016811371 -20.4934825897,-0.18112719059,-4.1645731926 -20.5454788208,-0.181135341525,-4.14275741577 -20.6124649048,-0.181149274111,-4.08915805817 -20.674451828,-0.181162804365,-4.03455972672 -20.7254371643,-0.181175455451,-3.97796320915 -20.7894210815,-0.181189119816,-3.9233622551 -20.8474082947,-0.18120239675,-3.86676740646 -20.9014034271,-0.180210858583,-3.84395122528 -20.9613895416,-0.180224299431,-3.78735518456 -21.0223731995,-0.180237799883,-3.7307574749 -21.0863609314,-0.180251449347,-3.67515349388 -21.1433448792,-0.180264607072,-3.6175558567 -21.2083320618,-0.180278420448,-3.56095504761 -21.2623157501,-0.180291429162,-3.50136518478 -21.338312149,-0.180301904678,-3.4805393219 -21.3932971954,-0.180314972997,-3.42094635963 -21.4542827606,-0.180328518152,-3.36234855652 -21.5292682648,-0.180343255401,-3.30574297905 -21.5812530518,-0.180356025696,-3.24514937401 -21.6352386475,-0.180368959904,-3.18455529213 -21.7152252197,-0.179384157062,-3.12794518471 -21.7522163391,-0.179391592741,-3.09814715385 -21.8382034302,-0.179407373071,-3.04153585434 -21.9011878967,-0.179421156645,-2.98093795776 -21.9571723938,-0.179434269667,-2.9193418026 -22.0141563416,-0.179447561502,-2.85675048828 -22.1111450195,-0.179464444518,-2.80013251305 -22.1461277008,-0.17947563529,-2.73454904556 -22.2241210938,-0.179486855865,-2.70972466469 -22.2791061401,-0.179499924183,-2.64613127708 -22.3510913849,-0.179514586926,-2.58452820778 -22.4180755615,-0.178528785706,-2.52192759514 -22.5020599365,-0.178544715047,-2.46032238007 -22.5500431061,-0.178557097912,-2.39473223686 -22.626039505,-0.178568348289,-2.36790895462 -22.6890220642,-0.17858222127,-2.3033118248 -22.765007019,-0.178597405553,-2.23970842361 -22.8099899292,-0.178609535098,-2.17212343216 -22.9069766998,-0.17862688005,-2.10951137543 -22.9579601288,-0.178639501333,-2.04291725159 -23.0329437256,-0.178654655814,-1.97731649876 -23.1179389954,-0.177667140961,-1.94849276543 -23.1609210968,-0.177678987384,-1.87990486622 -21.3898200989,-0.180501878262,-1.65425765514 -21.3958034515,-0.180508539081,-1.58669471741 -21.4227905273,-0.180517211556,-1.52211260796 -21.4517745972,-0.180526152253,-1.45653581619 -21.4397583008,-0.180530548096,-1.38897264004 -21.3257465363,-0.180521130562,-1.34724771976 -21.318731308,-0.180525913835,-1.27968716621 -9.7403087616,-0.197272911668,-0.450933873653 -9.72831249237,-0.197268694639,-0.420355886221 -9.7203168869,-0.19726473093,-0.388794362545 -9.7323217392,-0.197263002396,-0.359212100506 -9.72632694244,-0.197259262204,-0.328638076782 -9.72132873535,-0.197257205844,-0.313843935728 -9.72533321381,-0.19725446403,-0.283272981644 -9.7183380127,-0.19725048542,-0.252700120211 -9.71834373474,-0.197247326374,-0.223114967346 -9.72134876251,-0.197244361043,-0.192543953657 -9.7083530426,-0.19723957777,-0.161972329021 -9.71135616302,-0.197238281369,-0.147180110216 -9.71636199951,-0.197235554457,-0.11759544909 -9.69936656952,-0.197230085731,-0.0860397964716 -9.70437240601,-0.197227269411,-0.0564554110169 -9.70537662506,-0.197223976254,-0.0268712658435 -9.70338249207,-0.19722019136,0.00369840976782 -9.69838809967,-0.197216004133,0.0342671051621 -9.69439125061,-0.19721378386,0.0490578189492 -9.69539737701,-0.197210356593,0.0786414891481 -9.6974029541,-0.197206899524,0.109211668372 -9.68940830231,-0.197202324867,0.138791948557 -9.68341445923,-0.197197824717,0.169358491898 -9.686419487,-0.197194501758,0.19894272089 -9.69642353058,-0.1971937567,0.21472530067 -9.67942905426,-0.197187900543,0.244299411774 -9.67943477631,-0.197184130549,0.273882061243 -9.67944145203,-0.197180181742,0.304450780153 -9.67944812775,-0.197176337242,0.334033459425 -9.67845439911,-0.197172194719,0.364601582289 -9.67646121979,-0.197168022394,0.394182771444 -9.67146396637,-0.19716539979,0.408970206976 -9.67147064209,-0.19716130197,0.439538806677 -9.67647743225,-0.19715796411,0.469125688076 -9.66548347473,-0.197152465582,0.498698562384 -9.66049003601,-0.197147592902,0.529262363911 -9.66549682617,-0.197144150734,0.55884963274 -9.66050338745,-0.197139203548,0.589413166046 -9.65950775146,-0.197136983275,0.604203402996 -9.66051387787,-0.19713293016,0.633787035942 -9.65952110291,-0.19712844491,0.664354681969 -9.65152835846,-0.197123065591,0.693928003311 -9.65253543854,-0.197118923068,0.723511815071 -9.64854335785,-0.197114050388,0.753089547157 -9.64754676819,-0.197111591697,0.768865644932 -9.64755344391,-0.197107225657,0.798448443413 -9.63556098938,-0.197101086378,0.828014850616 -9.63956737518,-0.197097241879,0.857603132725 -9.64357566833,-0.197093233466,0.888178050518 -9.63358306885,-0.197087258101,0.917746305466 -9.63359069824,-0.197082743049,0.94732940197 -9.68559265137,-0.197087541223,0.967133104801 -9.71759796143,-0.197087422013,0.999728679657 -10.0055942535,-0.197122886777,1.05543160439 -10.0106019974,-0.197119116783,1.08701205254 -10.0776062012,-0.197123855352,1.12560462952 -10.0466146469,-0.19711497426,1.15416657925 -9.98462486267,-0.197101727128,1.17872464657 -9.94263076782,-0.19709341228,1.1904886961 -10.041633606,-0.197102814913,1.23210787773 -10.0356407166,-0.197097361088,1.2626850605 -10.0386476517,-0.19709315896,1.29426586628 -9.94566059113,-0.197074964643,1.31579244137 -10.0176639557,-0.197080597281,1.3554019928 -10.0986680984,-0.19708751142,1.39700937271 -10.1106710434,-0.197086960077,1.41381025314 -9.87069129944,-0.197047263384,1.41528475285 -9.84570121765,-0.19703873992,1.44285452366 -9.96070194244,-0.197050571442,1.48947525024 -9.97770881653,-0.197048157454,1.52306091785 -10.0827112198,-0.197058618069,1.56967496872 -9.85072898865,-0.197021961212,1.55237329006 -10.0827226639,-0.197051271796,1.61704540253 -10.087729454,-0.197047054768,1.64962470531 -10.0197429657,-0.197031766176,1.67216181755 -9.79376602173,-0.196992948651,1.66865170002 -9.72977924347,-0.196978032589,1.6901948452 -10.0147676468,-0.197015702724,1.76688718796 -10.00877285,-0.197012260556,1.78167498112 -14.498456955,-0.190688312054,2.55415177345 -9.51382541656,-0.197926789522,1.76163184643 -9.82381057739,-0.196968510747,1.84533190727 -14.4874668121,-0.190677285194,2.69185900688 -14.5074672699,-0.190677136183,2.74243450165 -9.52686023712,-0.196906685829,1.88593769073 -9.49386787415,-0.197898730636,1.89570486546 -15.0674304962,-0.189755812287,2.96260714531 -15.0524339676,-0.189750432968,3.00817346573 -9.70388793945,-0.196909025311,2.05810403824 -9.71689605713,-0.196905508637,2.0916891098 -9.68290328979,-0.196897387505,2.10046458244 -9.74190807343,-0.196900933981,2.14406013489 -9.65692424774,-0.196881964803,2.15760707855 -9.72692871094,-0.196887180209,2.20420265198 -9.7619342804,-0.196887090802,2.24279808998 -14.9994630814,-0.189714163542,3.41249775887 -9.87194252014,-0.196893021464,2.33098649979 -9.66096687317,-0.196856632829,2.29969835281 -9.94194984436,-0.196895718575,2.39438581467 -9.91696166992,-0.196886003017,2.42095398903 -9.99796390533,-0.196893170476,2.47255587578 -9.95297813416,-0.196880087256,2.49510860443 -10.0139808655,-0.196884229779,2.54171586037 -10.0159902573,-0.195878699422,2.57528972626 -9.98899745941,-0.196871429682,2.58506798744 -9.63604259491,-0.196808248758,2.53051137924 -9.87102794647,-0.19684047997,2.62117600441 -9.94703006744,-0.196846976876,2.67278409004 -9.95304012299,-0.196841984987,2.70736026764 -9.99304580688,-0.195842534304,2.75094866753 -9.69508743286,-0.196787536144,2.70541214943 -10.0370550156,-0.195840805769,2.8123292923 -10.007068634,-0.195829793811,2.837890625 -9.9640827179,-0.195816650987,2.85945081711 -9.73211860657,-0.196772038937,2.82893681526 -9.87411308289,-0.196789562702,2.90057206154 -9.88412189484,-0.196785107255,2.93615555763 -9.87212848663,-0.19677990675,2.94993114471 -9.54417610168,-0.196718916297,2.88839030266 -9.96213912964,-0.195782616735,3.0421204567 -9.96514892578,-0.195776879787,3.07669591904 -9.91916370392,-0.195762962103,3.09625935555 -9.87018013,-0.195748463273,3.11481976509 -9.57922554016,-0.196692794561,3.06028056145 -9.92318916321,-0.195747941732,3.18120336533 -9.93419837952,-0.195743381977,3.21877741814 -9.61324882507,-0.196682408452,3.15223383904 -9.53526973724,-0.196662530303,3.16077589989 -9.52428150177,-0.196654200554,3.18935418129 -9.47629928589,-0.196639314294,3.2069067955 -9.59128952026,-0.196655869484,3.25974678993 -9.44331932068,-0.196623846889,3.24426674843 -9.48532485962,-0.196624368429,3.29085612297 -9.49233531952,-0.196619004011,3.32544088364 -9.48734760284,-0.196611359715,3.35700917244 -9.474360466,-0.19660256803,3.38459134102 -9.47537136078,-0.196595937014,3.41816329956 -9.48537540436,-0.196594327688,3.43795681 -9.47338867188,-0.196585521102,3.46653175354 -9.47340011597,-0.196578621864,3.5001013279 -9.47041225433,-0.196571186185,3.53267002106 -9.46042537689,-0.196562796831,3.56125497818 -9.45943641663,-0.196555614471,3.59482216835 -9.45544910431,-0.196548089385,3.6263999939 -9.46545410156,-0.196546316147,3.64718651772 -9.46546554565,-0.196539372206,3.68076109886 -9.45447731018,-0.196530669928,3.70934319496 -9.45049095154,-0.196522891521,3.74191141129 -9.45250225067,-0.196516230702,3.77648615837 -9.44651508331,-0.196508333087,3.80707025528 -9.4465265274,-0.196501150727,3.84163665771 -9.44953155518,-0.1964982301,3.85942959785 -9.44554424286,-0.19649040699,3.89200139046 -9.43955802917,-0.196482270956,3.92357563972 -9.44056892395,-0.196475327015,3.95815086365 -9.43758106232,-0.196467742324,3.99073028564 -9.43159389496,-0.196459576488,4.02230644226 -9.44359874725,-0.196458205581,4.04410266876 -9.43161201477,-0.196448847651,4.07367229462 -9.43762302399,-0.196442812681,4.11025476456 -9.43063640594,-0.19643433392,4.14182853699 -9.42165088654,-0.196425318718,4.17339134216 -9.42066287994,-0.196418017149,4.20697593689 -9.42067527771,-0.196410775185,4.24155426025 -9.4226808548,-0.196407392621,4.26033687592 -9.40969562531,-0.196397647262,4.28990364075 -9.41170692444,-0.196390748024,4.32548379898 -9.4117193222,-0.195383504033,4.36006593704 -9.40673351288,-0.195375084877,4.39363241196 -9.40074634552,-0.195366591215,4.42620611191 -9.39675998688,-0.195358633995,4.45879173279 -9.41176319122,-0.195357635617,4.48358297348 -9.39477920532,-0.195347100496,4.51115369797 -9.39479160309,-0.195339635015,4.5467300415 -9.39380455017,-0.195331901312,4.58230113983 -9.38881778717,-0.195323437452,4.61587381363 -9.38383102417,-0.195314973593,4.64944696426 -9.39183616638,-0.195312902331,4.67024993896 -9.38585090637,-0.19530415535,4.70381879807 -9.38486385345,-0.195296421647,4.73939561844 -9.37687778473,-0.195287302136,4.77196550369 -9.3838891983,-0.195281043649,4.81154680252 -9.37290382385,-0.195271447301,4.84212303162 -9.37291717529,-0.195263803005,4.87869930267 -9.3809223175,-0.195261374116,4.90148496628 -9.37493610382,-0.195252612233,4.9350605011 -9.37395000458,-0.195244684815,4.9716334343 -9.36996269226,-0.19523628056,5.0062122345 -9.36497688293,-0.195227593184,5.04078483582 -9.36399078369,-0.195219680667,5.07736158371 -9.35799789429,-0.195214807987,5.09215497971 -9.36500930786,-0.195208236575,5.13372755051 -9.36202430725,-0.19519995153,5.16930627823 -9.35603809357,-0.195190951228,5.20387792587 -9.35305213928,-0.195182666183,5.23945856094 -9.35206604004,-0.195174351335,5.27801990509 -9.34508037567,-0.195165261626,5.31159973145 -9.3520860672,-0.195162668824,5.3343911171 -9.35209846497,-0.195154905319,5.37197351456 -9.33711528778,-0.195143982768,5.40253686905 -9.34012794495,-0.195136725903,5.44211959839 -9.3321428299,-0.19512732327,5.47569704056 -9.33215618134,-0.195119157434,5.51526260376 -9.33417034149,-0.195111632347,5.55484342575 -9.32917785645,-0.195106625557,5.57162714005 -9.33318996429,-0.195099517703,5.61221218109 -9.33820343018,-0.195092350245,5.65478467941 -9.32221984863,-0.195081278682,5.68435811996 -9.32023429871,-0.195072740316,5.72292947769 -9.32024765015,-0.195064842701,5.76151561737 -9.3042640686,-0.195053547621,5.79207992554 -9.31027126312,-0.19505058229,5.81586694717 -9.31828212738,-0.19504404068,5.86044788361 -9.30529880524,-0.195033475757,5.89202451706 -9.30031394958,-0.19402423501,5.92959403992 -9.30632686615,-0.19401730597,5.97317647934 -9.29134368896,-0.194006279111,6.00375270844 -9.29734992981,-0.194003194571,6.02853536606 -9.30536174774,-0.193996563554,6.07411623001 -9.29037857056,-0.193985342979,6.1056842804 -9.2883939743,-0.193976715207,6.14526128769 -9.29040718079,-0.193968802691,6.1878361702 -9.28542232513,-0.193959623575,6.22541570663 -9.27143955231,-0.19394852221,6.25798416138 -9.28944301605,-0.193947851658,6.29077672958 -9.27746009827,-0.193937212229,6.32435131073 -9.26947498322,-0.193927273154,6.36092424393 -9.2744884491,-0.193919852376,6.40650033951 -9.26250553131,-0.193909198046,6.44007730484 -9.26251983643,-0.193900749087,6.48265171051 -9.26453399658,-0.193892791867,6.52623176575 -9.25854301453,-0.193887278438,6.5440120697 -9.25855731964,-0.193878874183,6.58659029007 -9.25657176971,-0.193870022893,6.62816619873 -9.24358844757,-0.193859070539,6.66174268723 -9.24560260773,-0.193850800395,6.70731115341 -9.24861621857,-0.193843081594,6.75189876556 -9.23263454437,-0.193831324577,6.78446626663 -9.23764133453,-0.193827986717,6.81025362015 -9.24565410614,-0.193821057677,6.85983371735 -9.23467063904,-0.193810418248,6.89541244507 -9.22768688202,-0.193800374866,6.93498325348 -9.23170089722,-0.193792551756,6.98255968094 -9.22271823883,-0.193782046437,7.02112865448 -9.22472476959,-0.193778157234,7.04491901398 -9.21874141693,-0.193768322468,7.08549261093 -9.2247543335,-0.193760886788,7.13507318497 -9.0977973938,-0.193727180362,7.08262014389 -9.06781864166,-0.193712413311,7.10518217087 -9.10583305359,-0.193706855178,7.20255756378 -9.0458612442,-0.19368621707,7.20111846924 -8.977891922,-0.193664014339,7.19268035889 -8.95391178131,-0.193650409579,7.21924877167 -8.95192718506,-0.193641275167,7.2628288269 -8.93694591522,-0.193629309535,7.29739332199 -8.93996047974,-0.193621218204,7.34497785568 -8.94696712494,-0.193618178368,7.37376832962 -8.93298530579,-0.19360640645,7.40933513641 -8.96099472046,-0.192603111267,7.47891902924 -9.19195652008,-0.192640244961,7.71755218506 -9.18797302246,-0.192630663514,7.76213169098 -9.17998981476,-0.192620232701,7.80370855331 -9.17500591278,-0.192610159516,7.84927558899 -9.18401241302,-0.192607551813,7.88106918335 -9.17702960968,-0.192597359419,7.9236497879 -9.16304683685,-0.192585587502,7.96122169495 -9.17106151581,-0.192578047514,8.0187921524 -9.15108108521,-0.192565247416,8.05037212372 -9.28906440735,-0.191583812237,8.22197723389 -9.2790813446,-0.191572785378,8.2645483017 -9.29708576202,-0.191572040319,8.3053483963 -9.28710365295,-0.19156087935,8.3489151001 -9.27512168884,-0.191549539566,8.38949394226 -9.29613208771,-0.191544622183,8.4610710144 -9.27315330505,-0.191530972719,8.49264335632 -9.25817203522,-0.191518783569,8.53221130371 -9.27917480469,-0.191518440843,8.57800292969 -9.16721725464,-0.191486895084,8.52755832672 -9.27920532227,-0.191500335932,8.68416118622 -9.2522277832,-0.191485792398,8.71273231506 -9.24524593353,-0.191475212574,8.76030445099 -9.23826313019,-0.191464662552,8.80788040161 -9.23427867889,-0.191454723477,8.85845756531 -9.253282547,-0.191453740001,8.9052400589 -9.32529640198,-0.190450042486,9.08441734314 -9.21633911133,-0.191418781877,9.03496742249 -9.1653842926,-0.191389799118,9.09810066223 -9.11441135406,-0.191370263696,9.10366725922 -9.09542369843,-0.191362023354,9.11146259308 -9.08244419098,-0.19134990871,9.15602779388 -9.07246208191,-0.191338583827,9.20260238647 -9.07347774506,-0.190329521894,9.260181427 -9.0624961853,-0.190317884088,9.30675315857 -9.0605134964,-0.190308123827,9.36233043671 -9.07151889801,-0.19030559063,9.4031162262 -9.06053733826,-0.19029404223,9.44969272614 -9.05655479431,-0.190283820033,9.50426769257 -9.04157447815,-0.190271317959,9.54783821106 -9.05058860779,-0.190263748169,9.61641788483 -9.04160690308,-0.190252587199,9.66599750519 -9.04562282562,-0.190243914723,9.7305727005 -9.05362892151,-0.190240800381,9.76936244965 -8.92367744446,-0.190204784274,9.69090557098 -8.89070224762,-0.190188571811,9.71547412872 -8.84973049164,-0.190170764923,9.73104286194 -8.792760849,-0.190149724483,9.72861099243 -8.74778842926,-0.190131083131,9.73918151855 -8.744805336,-0.190121054649,9.79576206207 -8.75481128693,-0.190118283033,9.83755302429 -8.74882984161,-0.190107360482,9.89312171936 -8.74584770203,-0.190097138286,9.95169734955 -8.80584812164,-0.190099745989,10.0822849274 -8.98781776428,-0.189127177,10.3538970947 -8.97883701324,-0.189115718007,10.4084720612 -8.99084186554,-0.189113453031,10.4542665482 -8.98386096954,-0.189102247357,10.512834549 -8.9798784256,-0.189091905951,10.5734157562 -8.97189712524,-0.189080551267,10.630988121 -8.96691513062,-0.189069926739,10.6915664673 -8.96293354034,-0.189059302211,10.7551364899 -8.95995044708,-0.189048945904,10.8197107315 -8.96395778656,-0.189045086503,10.8575077057 -8.96297550201,-0.189035013318,10.926076889 -8.96099281311,-0.189025044441,10.9916610718 -8.94801235199,-0.189012527466,11.0462303162 -8.94103145599,-0.188001349568,11.1078042984 -8.93704986572,-0.187990769744,11.1733808517 -8.92206192017,-0.187982827425,11.1901674271 -9.0770368576,-0.188004598022,11.4567699432 -3.45553779602,-0.200852736831,4.42154550552 -3.44056129456,-0.200839802623,4.43012714386 -3.42058634758,-0.200825706124,4.43270206451 -3.41660737991,-0.200814634562,4.4562702179 -8.90617656708,-0.187915593386,11.6444072723 -8.90519332886,-0.187905550003,11.7179851532 -8.89321327209,-0.187893241644,11.7775602341 -8.88923168182,-0.187882572412,11.8481378555 -8.88825035095,-0.187872454524,11.9237146378 -8.86827278137,-0.186858311296,11.9752817154 -8.86329078674,-0.186847433448,12.0458612442 -8.88229465485,-0.186846241355,12.1116485596 -8.86831569672,-0.18683347106,12.1712245941 -8.86033439636,-0.186821758747,12.2407951355 -8.85735321045,-0.186811223626,12.3163738251 -8.84637355804,-0.186798989773,12.3819484711 -8.84039211273,-0.186787828803,12.4545269012 -8.829413414,-0.186775460839,12.5220975876 -8.83541965485,-0.186771675944,12.5718870163 -8.83043861389,-0.186760574579,12.6484603882 -8.82545757294,-0.186749532819,12.7250366211 -8.81347751617,-0.185737103224,12.7916154861 -8.80949687958,-0.185726091266,12.8721876144 -8.80551528931,-0.185715273023,12.9517660141 -8.81252193451,-0.185711637139,13.0055551529 -8.80554199219,-0.185700163245,13.0821323395 -8.80455875397,-0.18568983674,13.1687088013 -8.7865819931,-0.185675963759,13.2312793732 -8.77760219574,-0.185664027929,13.3068561554 -8.77362060547,-0.185652911663,13.3924264908 -8.7636423111,-0.185640737414,13.468003273 -8.77464675903,-0.185638010502,13.5297966003 -8.76766681671,-0.184626311064,13.6123685837 -8.76168632507,-0.184614822268,13.6969413757 -8.75670528412,-0.184603586793,13.7835168839 -8.7447271347,-0.184590980411,13.8590936661 -8.7217502594,-0.184576019645,13.9186668396 -8.73275661469,-0.184573143721,13.9844560623 -9.20963954926,-0.182660266757,14.849105835 -8.74378967285,-0.184554800391,14.1986064911 -8.68582344055,-0.18453271687,14.2031755447 -9.09572601318,-0.182606071234,14.9768133163 -9.26669406891,-0.182630747557,15.3644189835 -8.64388847351,-0.183493256569,14.4358978271 -9.00079631805,-0.182561025023,15.0827445984 -8.98481941223,-0.182547405362,15.1633167267 -8.63693523407,-0.183466151357,14.6808443069 -8.78193092346,-0.182474970818,15.1420173645 -8.60000038147,-0.183427527547,14.9355678558 -8.61701393127,-0.18342064321,15.0731477737 -8.95592594147,-0.182484477758,15.7219839096 -8.69301986694,-0.182420477271,15.3725223541 -8.58506774902,-0.182388052344,15.2930822372 -8.74104118347,-0.182409405708,15.6846809387 -8.86502456665,-0.181424170732,16.024274826 -8.59611988068,-0.182358980179,15.6538133621 -8.64812374115,-0.182359099388,15.8653964996 -8.63113689423,-0.182350501418,15.8921852112 -8.63915348053,-0.181341558695,16.0267601013 -8.67316150665,-0.181338012218,16.2103404999 -8.60020065308,-0.18131262064,16.1959056854 -8.53823757172,-0.181289479136,16.2014713287 -8.53425693512,-0.18127822876,16.3160514832 -8.57925319672,-0.181282162666,16.463848114 -8.5672750473,-0.181269139051,16.5674209595 -8.55829620361,-0.181256785989,16.6769981384 -8.54731845856,-0.180243894458,16.7855682373 -8.53533935547,-0.180231049657,16.8901481628 -8.52735996246,-0.180218875408,17.0057258606 -8.51238250732,-0.180205062032,17.1112918854 -8.53538608551,-0.180204555392,17.2230873108 -8.51740932465,-0.180190294981,17.3226623535 -8.50643157959,-0.179177314043,17.4392337799 -8.48745536804,-0.179163023829,17.536813736 -8.47647762299,-0.179150089622,17.6553859711 -11.4156312943,-0.16873472929,23.9663333893 -11.3146791458,-0.169703349471,23.9478931427 -11.252705574,-0.169685408473,23.9126739502 -11.170747757,-0.169657886028,23.9332351685 -11.0847902298,-0.169629633427,23.9437999725 -10.9848384857,-0.169598534703,23.9233608246 -10.8069086075,-0.169551625848,23.7319126129 -10.6049871445,-0.170499950647,23.4824638367 -10.53901577,-0.170481204987,23.4332447052 -10.0521783829,-0.171371951699,22.5397586823 -10.4100904465,-0.170433297753,23.5403747559 -10.3271341324,-0.170405566692,23.5529384613 -10.2341785431,-0.17037601769,23.5385074615 -10.149222374,-0.1703479141,23.5450706482 -10.0582685471,-0.170318678021,23.5356369019 -10.0102920532,-0.170303419232,23.5274124146 -9.91633796692,-0.170273691416,23.5079841614 -9.8353805542,-0.170246377587,23.5225467682 -9.74342727661,-0.170216977596,23.5081138611 -9.65947151184,-0.170189067721,23.5146770477 -9.56551837921,-0.170159250498,23.4942417145 -9.4885597229,-0.170132860541,23.5148105621 -9.43358612061,-0.170116335154,23.4845943451 -9.35062885284,-0.170088663697,23.4911594391 -9.25867557526,-0.170059338212,23.4717273712 -9.17971897125,-0.170032501221,23.4872951508 -9.08976459503,-0.171003416181,23.4748573303 -9.00680828094,-0.170975923538,23.4764289856 -8.9548330307,-0.170959994197,23.4512119293 -8.87387657166,-0.170932784677,23.459777832 -8.7799243927,-0.170902967453,23.4333438873 -8.70296669006,-0.170876696706,23.4489154816 -8.61501216888,-0.17084813118,23.4364833832 -8.53105735779,-0.170820340514,23.4350509644 -8.44910144806,-0.17079295218,23.4386177063 -8.39412689209,-0.170776501298,23.4004020691 -8.32116889954,-0.170751035213,23.4259738922 -8.23521327972,-0.170722842216,23.4175395966 -8.15325832367,-0.170695483685,23.4191093445 -8.06530380249,-0.170667052269,23.400680542 -7.98834705353,-0.170640781522,23.4142513275 -7.89939308167,-0.170612096786,23.3928203583 -7.85541677475,-0.170597806573,23.384601593 -7.77646017075,-0.170571163297,23.3911724091 -7.6865067482,-0.170542344451,23.3637428284 -7.60855007172,-0.170515924692,23.3723163605 -7.52459526062,-0.170488268137,23.3628845215 -7.44264030457,-0.17146101594,23.359457016 -4.11667251587,-0.186793163419,13.0438251495 -4.09768867493,-0.186783984303,13.0566082001 -7.1557970047,-0.171365782619,23.3409538269 -7.07984018326,-0.1713398844,23.3515281677 -6.99388647079,-0.171311929822,23.3310985565 -6.91293048859,-0.171284928918,23.3276691437 -6.86895465851,-0.171270757914,23.3134536743 -6.79199790955,-0.171244710684,23.3190307617 -6.70904302597,-0.171217411757,23.30560112 -6.63208675385,-0.171191230416,23.3141727448 -6.5471329689,-0.171163588762,23.2917442322 -6.47217559814,-0.171137928963,23.3043193817 -6.39122104645,-0.171111091971,23.2948932648 -6.35024356842,-0.171097531915,23.2896766663 -6.26528978348,-0.171069934964,23.264251709 -6.1923327446,-0.171044677496,23.2838249207 -6.10837841034,-0.171017244458,23.2623977661 -6.03142213821,-0.170991271734,23.2649726868 -5.95346641541,-0.170965149999,23.2625465393 -5.91248941422,-0.170951664448,23.2543334961 -5.83153438568,-0.170924976468,23.2389087677 -5.7585773468,-0.170899808407,23.2564849854 -5.67462396622,-0.170872420073,23.2320537567 -5.59866762161,-0.170846804976,23.2336330414 -5.51971197128,-0.171820536256,23.2252082825 -5.44275665283,-0.171794652939,23.2247829437 -5.3997797966,-0.171780899167,23.2035713196 -5.32682275772,-0.171755805612,23.2201461792 -5.24386930466,-0.171728804708,23.1917209625 -5.17091178894,-0.17170381546,23.2052974701 -5.08995771408,-0.171677261591,23.1838741302 -5.03299570084,-0.171655267477,23.2754459381 -5.01602172852,-0.170641094446,23.5550251007 -5.03102731705,-0.170638591051,23.8078174591 -4.99905776978,-0.169621437788,24.0323905945 -3.19163823128,-0.18326304853,15.5519361496 -3.13167762756,-0.183240905404,15.5065145493 -3.07971453667,-0.183220416307,15.4970979691 -3.02775168419,-0.183199748397,15.4916734695 -2.9807870388,-0.183180242777,15.5072574615 -2.95780444145,-0.183170542121,15.5190467834 -2.91483879089,-0.183151707053,15.5596246719 -2.86987376213,-0.183132499456,15.5902032852 -2.82390880585,-0.183113187551,15.6137857437 -2.78094315529,-0.183094501495,15.6543684006 -4.76334810257,-0.164461746812,27.401966095 -4.77835416794,-0.164459139109,27.747756958 -4.74738407135,-0.16344229877,28.0963344574 -4.71541500092,-0.163425296545,28.4499130249 -4.68544530869,-0.162408605218,28.8334903717 -4.65147638321,-0.162391200662,29.2050685883 -4.61550855637,-0.161373451352,29.5766468048 -4.58353948593,-0.160356432199,29.9922237396 -4.59654569626,-0.160353511572,30.3940181732 -4.56457662582,-0.159336477518,30.841594696 -4.5366063118,-0.158320218325,31.3341712952 -4.56161928177,-0.157314047217,32.2217521667 -4.5226521492,-0.156295761466,32.685333252 -4.48268556595,-0.156277313828,33.1619110107 -4.49469232559,-0.155274048448,33.6547012329 -4.45172643661,-0.154255017638,34.1502761841 -4.40676164627,-0.153235554695,34.6598548889 -4.29981613159,-0.153204515576,34.6854324341 -4.31883096695,-0.15219719708,35.7600135803 -4.27286624908,-0.151177614927,36.3435897827 -4.22290277481,-0.150157287717,36.9221725464 -2.68739414215,-0.169864326715,23.7559547424 -2.60544109344,-0.170838445425,23.6935386658 -2.52748656273,-0.170813262463,23.6681175232 -2.45652961731,-0.170789510012,23.7027015686 -2.38657283783,-0.169765904546,23.7542819977 -2.31661581993,-0.169742316008,23.8088645935 -3.90014076233,-0.14302611351,41.6224365234 -3.90315055847,-0.142021164298,42.3832206726 -3.83319354057,-0.139997303486,43.1018028259 -3.68326163292,-0.14095851779,42.9483795166 -3.70927453041,-0.137952491641,44.9179611206 -3.63931775093,-0.135928690434,45.8245391846 -3.56536221504,-0.134904071689,46.7711181641 -3.48740768433,-0.132878869772,47.7187004089 -3.48042058945,-0.131872147322,48.6834869385 -3.39746785164,-0.129845932126,49.7350654602 -3.30951690674,-0.128818914294,50.7976455688 -3.221565485,-0.126791909337,51.9672241211 -3.12861609459,-0.124764017761,53.1778030396 -2.99168038368,-0.123728103936,53.7263870239 -3.08166265488,-0.118739195168,56.9921760559 -2.90473937988,-0.11869597435,57.042755127 -2.8817679882,-0.113681040704,60.3383369446 -1.66317236423,-0.14944781363,37.0629348755 -1.54423081875,-0.149415686727,36.9955215454 -1.42828881741,-0.149384066463,37.0181007385 -1.31434595585,-0.149352908134,37.0916862488 -0.159922614694,-0.144041493535,40.1845245361 --0.289863497019,0.136073276401,43.4151191711 --1.30745923519,0.336293876171,68.7634963989 --1.52337002754,0.336342036724,68.734085083 --2.04517388344,0.395449131727,76.2164764404 --2.22470164299,-0.00733364373446,24.9953632355 --2.26866650581,-0.0103165647015,24.6009483337 --2.34362196922,-0.0102943461388,24.5715389252 --2.42657494545,-0.0102708041668,24.6251316071 --9.8330450058,0.399070769548,75.8524017334 --12.2019138336,0.305592775345,63.3576507568 --12.6507349014,0.307677745819,63.5368766785 --7.94316959381,0.108925752342,38.877948761 --15.5635719299,0.316216051579,63.8866729736 --15.5245656967,0.308214664459,62.8622741699 --15.4515695572,0.299207925797,61.7298660278 --10.995926857,0.149514496326,43.3111000061 --11.1068735123,0.148538053036,43.1807098389 --11.2508087158,0.148566737771,43.1743164062 --11.4137401581,0.149598225951,43.2429275513 --15.1015930176,0.261174678802,56.8930397034 --15.0735836029,0.255175113678,56.0736351013 --15.0205821991,0.248171687126,55.1822357178 --15.1655187607,0.247198835015,55.0328483582 --15.3284502029,0.247228637338,54.9494667053 --15.5363674164,0.248265251517,55.0260848999 --15.7092952728,0.248296320438,54.974697113 --15.8142547607,0.249314635992,55.0145072937 --14.7185735703,0.213151499629,50.5950088501 --14.820523262,0.211171835661,50.3536186218 --14.9384679794,0.210194528103,50.1692314148 --15.0744094849,0.210219800472,50.0518455505 --14.5405540466,0.191143527627,47.7293891907 --9.73801422119,0.058419726789,31.7447147369 --9.80497455597,0.0574363209307,31.6073169708 --9.87893199921,0.0574539043009,31.4949188232 --9.93989467621,0.0564694665372,31.3435211182 --10.023850441,0.0554884597659,31.2641239166 --10.1257991791,0.0555100217462,31.2437286377 --10.2357473373,0.0565326958895,31.247335434 --10.3247108459,0.057549059391,31.352142334 --10.4266605377,0.0575703680515,31.3307514191 --10.5865926743,0.0586002282798,31.4793624878 --14.1324605942,0.138139590621,40.7815475464 --11.4992408752,0.0717581883073,32.8268508911 --13.8755111694,0.127108976245,39.4359169006 --13.914481163,0.125119462609,39.1505203247 --13.884472847,0.121119827032,38.6791152954 --13.8314714432,0.117116846144,38.1537132263 --13.9474182129,0.117138400674,38.098323822 --13.7114629745,0.108111344278,36.9096946716 --13.7104444504,0.105115935206,36.5532913208 --13.6954307556,0.102118544281,36.1628875732 --13.6814174652,0.0991212427616,35.7854881287 --13.6674041748,0.0971239432693,35.4130821228 --13.6513910294,0.0941263213754,35.0436820984 --13.6313791275,0.091128192842,34.6662788391 --13.5603923798,0.0881204456091,34.3270683289 --13.5383806229,0.0861220285296,33.9566650391 --13.5243673325,0.0831247344613,33.6122589111 --13.5053548813,0.0801267251372,33.2618598938 --13.4843444824,0.0781284421682,32.9114532471 --13.4653320312,0.0751304328442,32.5710487366 --13.4533176422,0.0731334090233,32.2526473999 --13.3883285522,0.0711266770959,31.9544391632 --13.3713159561,0.0681289732456,31.6320343018 --13.35430336,0.0661312714219,31.3146286011 --13.3432893753,0.0641343519092,31.0182285309 --13.3242778778,0.0611363388598,30.7068252563 --13.2842721939,0.0591354742646,30.3504161835 --13.2132844925,0.056128051132,30.0582065582 --13.1982707977,0.0541306138039,29.7688045502 --13.1762599945,0.052132230252,29.4673995972 --13.1562490463,0.0501341298223,29.1739940643 --13.2042179108,0.0491452254355,29.0355987549 --13.1912031174,0.0471480488777,28.7641944885 --13.1781902313,0.0451508276165,28.4987945557 --13.1211986542,0.0431454256177,28.2585849762 --13.1131830215,0.0411489233375,28.0081806183 --13.1011695862,0.0391518361866,27.754781723 --13.0931549072,0.0381553322077,27.5103740692 --13.0821399689,0.0361583791673,27.2649726868 --13.0721273422,0.0341615378857,27.0255699158 --13.0081281662,0.0311576146632,26.6761569977 --12.9581346512,0.0301533062011,26.4659481049 --12.9511194229,0.0281568672508,26.2425479889 --12.9471035004,0.0271608289331,26.0271453857 --9.12520122528,-0.0423324108124,18.1641349792 --9.15717411041,-0.0433221943676,18.0857372284 --9.17915058136,-0.043313305825,17.9883365631 --9.18113994598,-0.0443100221455,17.9221343994 --9.23910522461,-0.0442965105176,17.8957386017 --9.30606746674,-0.0442818924785,17.8863430023 --9.38802528381,-0.0432654507458,17.9059524536 --9.4179983139,-0.0442557446659,17.8265533447 --9.45996761322,-0.0442444495857,17.7681503296 --9.51593399048,-0.044231493026,17.7377548218 --9.53591918945,-0.0442260876298,17.7085571289 --12.8179531097,0.0101930033416,23.6617012024 --12.9129095078,0.0102092660964,23.6593170166 --12.9988679886,0.0102243022993,23.6399307251 --13.0488367081,0.0102347685024,23.5545368195 --13.1827812195,0.0112556489184,23.6191558838 --13.285736084,0.0112724862993,23.6297740936 --13.3347129822,0.0112805739045,23.6295814514 --13.4296703339,0.012296281755,23.6241989136 --13.5156288147,0.012310821563,23.6008090973 --13.6175832748,0.0123271895573,23.606426239 --13.702542305,0.0133413756266,23.5820407867 --13.8054971695,0.013357643038,23.5886592865 --13.855474472,0.0133655890822,23.5874652863 --13.9554309845,0.0143813248724,23.5880851746 --14.0433883667,0.01439555455,23.5656967163 --14.119351387,0.014408217743,23.5243110657 --14.211309433,0.0144227128476,23.5089244843 --14.3032674789,0.014437074773,23.4945430756 --14.3242454529,0.0144429579377,23.3621463776 --14.2692537308,0.012438159436,23.1889362335 --14.49817276,0.015468458645,23.3975791931 --14.6381177902,0.016488160938,23.456199646 --14.6970863342,0.0154982004315,23.3868122101 --12.9485626221,-0.0117019573227,20.4470882416 --14.682059288,0.0135026816279,23.0380115509 --14.912979126,0.0155324246734,23.238653183 --15.1279115677,0.0185586288571,23.4944953918 --12.7125720978,-0.0177153199911,19.5876369476 --12.7595424652,-0.0187059752643,19.5242424011 --15.4287824631,0.0196013450623,23.4703521729 --15.3827791214,0.0175987891853,23.2389431 --15.5997047424,0.0196258835495,23.4075870514 --15.682674408,0.020636478439,23.4524040222 --15.775633812,0.0206493660808,23.431022644 --13.1023597717,-0.0176463313401,19.3081016541 --13.2772951126,-0.0166232194752,19.4337329865 --13.182305336,-0.0186301786453,19.16431427 --13.2292776108,-0.0186213813722,19.1019210815 --13.3202371597,-0.018607866019,19.1045379639 --13.2602453232,-0.0196126587689,18.9533233643 --12.5324296951,-0.0306883715093,17.7877807617 --12.5794010162,-0.0306794084609,17.7343864441 --12.6183748245,-0.0306713748723,17.6699905396 --12.7153320312,-0.0306572224945,17.6886100769 --12.8072910309,-0.0296436753124,17.6982269287 --12.7892808914,-0.0306419506669,17.5558223724 --12.6902999878,-0.0326506085694,17.3605995178 --12.8642368317,-0.0306285656989,17.4832324982 --12.6222877502,-0.0346503816545,17.037776947 --12.1124105453,-0.0427000336349,16.2372703552 --12.1233911514,-0.0426949374378,16.1438655853 --12.2773342133,-0.0416751392186,16.2434997559 --12.2473344803,-0.0426763407886,16.1502933502 --12.2503185272,-0.0426722206175,16.0478916168 --8.89820194244,-0.0870107486844,11.5457353592 --8.91018199921,-0.0880040451884,11.4853315353 --8.93915748596,-0.0879956930876,11.447936058 --8.9691324234,-0.0879872590303,11.4115371704 --9.03109931946,-0.0879756733775,11.4161462784 --12.3532056808,-0.0446413010359,15.6096992493 --12.523144722,-0.0436207987368,15.7243404388 --12.6311006546,-0.0426065847278,15.7579612732 --12.6090908051,-0.0436052344739,15.6265487671 --12.5910816193,-0.0446035861969,15.5041465759 --12.6030626297,-0.0445989482105,15.4177446365 --13.1079149246,-0.0395466126502,15.9364566803 --12.8089866638,-0.0435739345849,15.5201892853 --12.8679561615,-0.0435649864376,15.4918012619 --12.881937027,-0.0435604341328,15.4094057083 --12.990893364,-0.0425468496978,15.4400262833 --13.1218442917,-0.0415313392878,15.4966554642 --13.284787178,-0.0405129604042,15.5892887115 --13.2377853394,-0.041514441371,15.434879303 --13.3787412643,-0.0404998362064,15.5507125854 --13.3697290421,-0.0404977723956,15.4393043518 --13.4286994934,-0.0404895022511,15.4089183807 --13.169752121,-0.0445104502141,15.013458252 --13.1727361679,-0.0445072390139,14.9200544357 --13.6545982361,-0.0394607596099,15.3727731705 --13.6335964203,-0.0404613353312,15.2995662689 --13.6695737839,-0.0404555127025,15.2431774139 --13.8145217896,-0.0394399873912,15.3068056107 --14.0814399719,-0.0364138670266,15.5064735413 --13.9934482574,-0.0384193211794,15.3110532761 --14.7122507095,-0.030354026705,16.0008220673 --15.1021385193,-0.0263181645423,16.3235168457 --15.1361236572,-0.0263143684715,16.3083248138 --12.0378961563,-0.0625796243548,12.8611602783 --12.0338821411,-0.0635766163468,12.7747554779 --12.033867836,-0.0635733306408,12.694357872 --12.0398521423,-0.0645695179701,12.6199560165 --12.1068201065,-0.0645606294274,12.6105728149 --12.1707897186,-0.0635520219803,12.5961818695 --12.1667833328,-0.0645508021116,12.5529842377 --12.1457748413,-0.0645493268967,12.4505720139 --12.1457605362,-0.0655461922288,12.3721733093 --12.1497449875,-0.0655427277088,12.2977733612 --12.146730423,-0.0665398389101,12.2163686752 --12.138718605,-0.0665373429656,12.1299610138 --12.1447029114,-0.0665338039398,12.0595636368 --12.1147031784,-0.0675346106291,11.9903497696 --12.1206874847,-0.067531093955,11.9209547043 --12.1176738739,-0.0685282424092,11.841547966 --12.1106615067,-0.0685257315636,11.7591428757 --12.1446390152,-0.0685200989246,11.7177505493 --12.1546220779,-0.0695163682103,11.6533527374 --12.1276216507,-0.0695169046521,11.5891399384 --12.1326065063,-0.0695135369897,11.51973629 --12.1295928955,-0.0705108493567,11.4443378448 --12.1295785904,-0.0705079063773,11.3709335327 --12.1295642853,-0.0715049952269,11.2985305786 --12.1265525818,-0.0715023428202,11.2241306305 --12.1285381317,-0.0714993402362,11.1547307968 --12.1095352173,-0.0724992826581,11.101524353 --12.0995235443,-0.0724970921874,11.0201129913 --12.1075077057,-0.0734937116504,10.9577169418 --12.1084938049,-0.0734908133745,10.8883132935 --12.1114797592,-0.0734878256917,10.8219146729 --12.1014671326,-0.0744856968522,10.7425041199 --12.0964546204,-0.0744833126664,10.6701049805 --12.031463623,-0.0754863470793,10.5768795013 --12.0224523544,-0.0764842331409,10.5024833679 --12.0214385986,-0.0764814987779,10.4330739975 --12.0154266357,-0.0764791443944,10.3606700897 --12.068400383,-0.0764728859067,10.3392791748 --12.0683870316,-0.0764702558517,10.2738838196 --12.0663738251,-0.0774677172303,10.2054786682 --12.0533704758,-0.077467225492,10.1612730026 --12.0413599014,-0.078465372324,10.0858697891 --12.0543432236,-0.0784618780017,10.0304641724 --12.0423326492,-0.07846006006,9.95606231689 --12.0463190079,-0.0784572213888,9.89465999603 --12.0453052521,-0.0794547349215,9.83026218414 --12.0362939835,-0.0794527381659,9.75885677338 --12.0102930069,-0.0804530456662,9.70564746857 --12.0102796555,-0.0804504975677,9.64224338531 --12.0162649155,-0.080447614193,9.58384132385 --12.0122528076,-0.0814453363419,9.51743507385 --12.0042409897,-0.0814433321357,9.44903182983 --12.0052280426,-0.0814408063889,9.3876285553 --11.9762277603,-0.0824412256479,9.33341598511 --11.9882125854,-0.0824381187558,9.28202056885 --11.9512081146,-0.0824377909303,9.19261074066 --11.9331989288,-0.0834363177419,9.11719799042 --11.9371843338,-0.0834336727858,9.05979537964 --11.9341716766,-0.0844314396381,8.99739074707 --11.9611539841,-0.0844276100397,8.95799541473 --11.9971389771,-0.0834245830774,8.95681381226 --12.0831069946,-0.0834177434444,8.96143436432 --5.54951238632,-0.147750139236,4.00685739517 --5.55849313736,-0.147743374109,3.98645734787 --11.9330768585,-0.0864141881466,8.55637741089 --11.9340696335,-0.086413025856,8.52817630768 --11.9270582199,-0.0864111557603,8.46577262878 --11.9280462265,-0.0864088758826,8.40836334229 --11.9190349579,-0.0874071121216,8.34495925903 --11.9260215759,-0.0874046385288,8.29356098175 --11.918009758,-0.0874028578401,8.23115348816 --11.9179973602,-0.087400726974,8.17475032806 --11.8959960938,-0.0884006991982,8.13254928589 --11.9009828568,-0.0883983671665,8.08014774323 --11.8919715881,-0.088396653533,8.01773738861 --11.9039573669,-0.0883940979838,7.97134256363 --11.8849487305,-0.0893928408623,7.90293073654 --11.8919343948,-0.0893905088305,7.85252809525 --11.8669281006,-0.0893895551562,7.78212356567 --11.8399267197,-0.0903895944357,7.73590517044 --11.8369150162,-0.09038772434,7.68050575256 --11.8279047012,-0.0903861001134,7.62110185623 --11.8428897858,-0.0913835242391,7.57669878006 --11.8268814087,-0.0913821980357,7.51329278946 --11.8238697052,-0.0913803651929,7.45788621902 --11.8318557739,-0.0913782119751,7.41149616241 --11.8138532639,-0.0923778936267,7.37328577042 --11.8078432083,-0.0923762172461,7.31688022614 --11.8048315048,-0.0923744365573,7.2624745369 --11.8058185577,-0.092372559011,7.21107149124 --11.8078069687,-0.0933706685901,7.16067123413 --11.8057947159,-0.093368947506,7.10827112198 --11.7877922058,-0.0933686122298,7.0710606575 --11.7867803574,-0.0933668762445,7.01966094971 --11.7887687683,-0.0933650285006,6.96925401688 --11.7647619247,-0.0943639948964,6.90384197235 --11.7627506256,-0.0943623334169,6.85244178772 --11.7787361145,-0.0943601801991,6.81204891205 --11.7837228775,-0.094358317554,6.76363897324 --11.7667207718,-0.0953579843044,6.7294383049 --11.7627096176,-0.0953564271331,6.67703294754 --11.7606992722,-0.0953548550606,6.6266336441 --11.7546882629,-0.0953533798456,6.5732254982 --11.7686738968,-0.0953514277935,6.5318274498 --11.7596645355,-0.0963500738144,6.47742080688 --11.7556533813,-0.0963486135006,6.42601537704 --11.7476491928,-0.0963480174541,6.3968091011 --11.7696342468,-0.0963460057974,6.36041545868 --11.800617218,-0.0963438674808,6.32902526855 --11.8805913925,-0.0953407511115,6.32364702225 --11.9565649033,-0.095337882638,6.31627321243 --12.0455389023,-0.0943349003792,6.31590795517 --12.1295127869,-0.0943321511149,6.31153488159 --12.1954956055,-0.0933304056525,6.32236051559 --12.2464752197,-0.0933284536004,6.29897022247 --12.2964553833,-0.0933266505599,6.27659320831 --12.2794475555,-0.0933259725571,6.21717643738 --12.3134317398,-0.0933245420456,6.18579006195 --12.3114213943,-0.09332370013,6.13538646698 --12.1954317093,-0.0943244472146,6.02794694901 --19.2461891174,-0.0322330594063,9.49688529968 --19.2461833954,-0.0322374776006,9.42048835754 --19.244178772,-0.0332419164479,9.34409427643 --12.2733612061,-0.0943190082908,5.80076217651 --12.2753553391,-0.0943186283112,5.77756071091 --12.2723455429,-0.0953179523349,5.72815799713 --12.2803344727,-0.0953172072768,5.68375492096 --12.1533460617,-0.096317447722,5.57630777359 --18.4502830505,-0.042280908674,8.41384124756 --14.8398742676,-0.0733026564121,6.67611074448 --14.7838783264,-0.074303612113,6.62189006805 --14.7118835449,-0.0753052681684,6.53246307373 --14.637887001,-0.075306840241,6.44303703308 --14.5668916702,-0.0763083249331,6.35561132431 --14.4848966599,-0.0773097425699,6.2641825676 --14.4298973083,-0.0783110633492,6.18475914001 --14.3459033966,-0.0793123096228,6.09332609177 --14.2769107819,-0.0793128833175,6.03609800339 --14.2099142075,-0.0803139805794,5.95367383957 --14.1389169693,-0.0813149958849,5.87024831772 --14.0639219284,-0.0823159143329,5.785820961 --14.0009231567,-0.082316800952,5.70639228821 --13.9349250793,-0.0833175852895,5.62696790695 --11.6252641678,-0.103305667639,4.59946203232 --11.6402521133,-0.103305056691,4.56307029724 --11.6252450943,-0.103304259479,4.51365756989 --11.6212348938,-0.103303551674,4.46925401688 --11.6392230988,-0.103303074837,4.43385982513 --11.6202163696,-0.104302272201,4.38344717026 --11.6212053299,-0.104301698506,4.34205102921 --11.6281995773,-0.104301474988,4.32284593582 --11.614192009,-0.104300759733,4.27544021606 --11.6041851044,-0.10430008918,4.22902965546 --11.6121740341,-0.104299686849,4.19063711166 --11.6071643829,-0.104299113154,4.14622688293 --11.6071557999,-0.104298658669,4.10482931137 --11.6091461182,-0.105298236012,4.06342363358 --11.5931434631,-0.105297766626,4.03722047806 --11.5891342163,-0.105297282338,3.99381279945 --11.5991239548,-0.105297066271,3.95540952682 --11.5871162415,-0.105296485126,3.91000437737 --11.5831079483,-0.105296067894,3.867603302 --11.5950965881,-0.105295993388,3.83020210266 --11.5790901184,-0.10529537499,3.78379511833 --11.5760860443,-0.10629517585,3.76259589195 --11.5750770569,-0.106294892728,3.72119164467 --11.5720682144,-0.106294594705,3.67878246307 --11.5610609055,-0.106294117868,3.63437509537 --11.4460668564,-0.107291020453,3.55592250824 --11.4380578995,-0.107290558517,3.51351976395 --11.4270515442,-0.107290022075,3.47011423111 --11.4380455017,-0.10729020834,3.45392012596 --11.4270381927,-0.108289703727,3.41051292419 --11.4150304794,-0.108289167285,3.3671066761 --11.4170207977,-0.108289062977,3.3277015686 --11.418012619,-0.108288958669,3.28829836845 --11.4100046158,-0.10828859359,3.24588799477 --11.4249982834,-0.108289033175,3.2306933403 --11.4119911194,-0.108288541436,3.18728423119 --11.4129829407,-0.108288526535,3.14888858795 --11.4059753418,-0.108288273215,3.10748195648 --11.4069652557,-0.108288310468,3.0680744648 --11.4009580612,-0.10928811878,3.02767372131 --11.3879508972,-0.109287686646,2.985268116 --11.3759479523,-0.109287269413,2.96205711365 --11.3779392242,-0.109287425876,2.92365455627 --11.400929451,-0.109288439155,2.89126348495 --11.3759231567,-0.109287582338,2.8458507061 --11.376914978,-0.109287783504,2.80744838715 --11.3869056702,-0.109288401902,2.77104568481 --11.3688993454,-0.109287850559,2.727632761 --11.3948926926,-0.109289094806,2.71544718742 --11.3768863678,-0.109288580716,2.67203259468 --11.3208847046,-0.110286325216,2.61960411072 --11.3548727036,-0.11028816551,2.59022068977 --11.3928604126,-0.110290296376,2.56083083153 --11.4248504639,-0.10929222405,2.53044438362 --11.4468393326,-0.109293751419,2.49704885483 --11.483833313,-0.10929582268,2.48686742783 --11.5078220367,-0.109297573566,2.45448112488 --11.7227945328,-0.107309222221,2.46416687965 --11.4498128891,-0.109295777977,2.36465001106 --11.4498052597,-0.110296390951,2.32624483109 --11.629781723,-0.108306765556,2.32691931725 --11.6807699203,-0.10831040144,2.29954338074 --11.7057638168,-0.108312241733,2.28535246849 --11.7357549667,-0.107314877212,2.25296497345 --11.7567462921,-0.107317090034,2.21857380867 --11.8087348938,-0.107321180403,2.19019460678 --11.8327264786,-0.107323743403,2.15580153465 --11.8647165298,-0.107326887548,2.12240743637 --11.8977108002,-0.106329478323,2.1102309227 --11.9347009659,-0.106333069503,2.07784295082 --11.9576931,-0.106335893273,2.04244637489 --11.993683815,-0.106339596212,2.01006340981 --12.0336742401,-0.10634367913,1.97767663002 --12.0766649246,-0.105348035693,1.94629824162 --12.1086568832,-0.105351820588,1.91190648079 --12.148648262,-0.10535620153,1.87952649593 --12.1756429672,-0.105358913541,1.8643386364 --12.215634346,-0.104363501072,1.83095192909 --12.2456264496,-0.10436745733,1.7965695858 --12.2866182327,-0.104372315109,1.76318621635 --12.3106117249,-0.104376077652,1.72679388523 --12.3486042023,-0.103380933404,1.69240748882 --12.3855962753,-0.103385813534,1.65802466869 --12.4295902252,-0.103390164673,1.64484798908 --12.5385789871,-0.102400638163,1.62049782276 --12.583571434,-0.102406509221,1.58611571789 --12.6345643997,-0.101412937045,1.55274033546 --12.697555542,-0.101420469582,1.52036774158 --12.7305498123,-0.101425834,1.48297464848 --12.7575454712,-0.100429311395,1.46679449081 --12.7975387573,-0.100435376167,1.43040883541 --12.8385324478,-0.100441642106,1.39402461052 --12.8755264282,-0.100447639823,1.35764563084 --12.913520813,-0.0994539037347,1.32025802135 --12.9625148773,-0.0994611382484,1.28488504887 --12.996509552,-0.0994673147798,1.24649512768 --13.0365056992,-0.099472373724,1.23031640053 --13.0705013275,-0.0984787046909,1.19192957878 --13.1164951324,-0.0984862074256,1.1545484066 --13.158490181,-0.0984934344888,1.11717176437 --13.1964855194,-0.0975004658103,1.07878959179 --13.2464809418,-0.0975086912513,1.04141426086 --13.288476944,-0.0975163206458,1.00303542614 --13.3034753799,-0.0975196659565,0.982839584351 --13.3574705124,-0.0965286716819,0.944459676743 --13.3984670639,-0.0965364724398,0.90608716011 --13.4454622269,-0.0965450927615,0.86670601368 --13.4954586029,-0.0955541357398,0.827326476574 --12.2694969177,-0.105438224971,0.693329036236 --12.2424945831,-0.10543859005,0.651910662651 --13.6004505157,-0.0945752933621,0.727379798889 --13.6574478149,-0.094585493207,0.688009083271 --11.9694929123,-0.107418455184,0.536768972874 --12.0714864731,-0.107431799173,0.504414439201 --12.1394815445,-0.106441825628,0.470048576593 --12.2774753571,-0.105459414423,0.438714534044 --12.0714759827,-0.107440844178,0.389210611582 --12.1444730759,-0.106450125575,0.374050945044 --12.3614654541,-0.10447666049,0.345761448145 --12.2774648666,-0.105471037328,0.302312642336 --12.3064613342,-0.105477683246,0.263920605183 --12.18846035,-0.106468088925,0.220459550619 --12.2214565277,-0.106475166976,0.18307736516 --12.206454277,-0.106476962566,0.143667012453 --12.2134523392,-0.106479510665,0.124469742179 --12.0604515076,-0.107465460896,0.0819931104779 --12.0184497833,-0.107464015484,0.0425682589412 --11.8474473953,-0.108447410166,0.00107922183815 --11.8724451065,-0.108453631401,-0.0363114997745 --12.0664405823,-0.107480101287,-0.0716151818633 --11.961438179,-0.108471058309,-0.111071653664 --11.8554372787,-0.108459927142,-0.130320504308 --11.9414339066,-0.108473844826,-0.167679578066 --12.3174324036,-0.105523720384,-0.204888522625 --11.9554290771,-0.108482718468,-0.243475154042 --12.4874296188,-0.10355310142,-0.283601731062 --12.3944272995,-0.104545682669,-0.32305598259 --12.3084259033,-0.105538927019,-0.361501723528 --11.9184217453,-0.108490921557,-0.375900328159 --11.8014183044,-0.109479561448,-0.412367165089 --11.860417366,-0.108490921557,-0.450736165047 --11.8554143906,-0.108494125307,-0.489149540663 --11.7494115829,-0.109483771026,-0.52360033989 --11.7814092636,-0.109491817653,-0.561986982822 --11.8034086227,-0.109496667981,-0.581174314022 --11.7124042511,-0.110488153994,-0.615622758865 --11.834405899,-0.109508752823,-0.657968342304 --11.9254055023,-0.108525246382,-0.698313415051 --11.8634023666,-0.108520753682,-0.733749091625 --11.8814020157,-0.108527489007,-0.773150205612 --12.4474163055,-0.104611925781,-0.838251292706 --12.3484134674,-0.104600198567,-0.852498233318 --12.0444040298,-0.107561402023,-0.876064658165 --12.1884069443,-0.10658672452,-0.922388255596 --15.7855224609,-0.0781160369515,-1.17388343811 --12.2794094086,-0.105609633029,-1.0061467886 --12.6804237366,-0.102674022317,-1.07133114338 --12.6134204865,-0.102669402957,-1.10676419735 --12.4464149475,-0.104647018015,-1.11505305767 --12.1644039154,-0.106609627604,-1.1346116066 --12.1814050674,-0.106617197394,-1.17500638962 --12.423415184,-0.104659467936,-1.23327767849 --12.8564348221,-0.100731931627,-1.3084410429 --12.7574319839,-0.101722382009,-1.34089398384 --16.3436088562,-0.074292846024,-1.70136642456 --12.2804107666,-0.105655767024,-1.35875380039 --16.483625412,-0.0723307803273,-1.79288840294 --16.54063797,-0.0723506361246,-1.85125613213 --16.6046485901,-0.0713718086481,-1.91061961651 --16.672662735,-0.0713936910033,-1.96997404099 --16.7366733551,-0.0704153552651,-2.03033804893 --16.8066864014,-0.0704382285476,-2.09169769287 --16.877696991,-0.0694558024406,-2.12686038017 --16.9467105865,-0.0684789940715,-2.18922233582 --17.0017223358,-0.0684998854995,-2.24958586693 --17.0727386475,-0.0675238519907,-2.31294536591 --17.1417541504,-0.067547686398,-2.37630391121 --17.2107696533,-0.0665718913078,-2.44066643715 --17.2827835083,-0.0655966699123,-2.50502085686 --17.3447933197,-0.065613783896,-2.54118609428 --17.4238109589,-0.0646402612329,-2.60753774643 --17.5078277588,-0.0646680891514,-2.67589187622 --17.5498428345,-0.063688583672,-2.73826479912 --17.6368618011,-0.0627173781395,-2.80761361122 --14.7336368561,-0.0852049961686,-2.43461418152 --17.7698993683,-0.0617682933807,-2.94132900238 --14.5746335983,-0.0871903449297,-2.4823038578 --14.8286619186,-0.0852467268705,-2.56956362724 --14.7796649933,-0.0852475166321,-2.60999083519 --14.3576345444,-0.0881782472134,-2.58861923218 --14.0916166306,-0.0901376605034,-2.59217572212 --14.0346164703,-0.0911357477307,-2.62759947777 --13.7986001968,-0.0920997709036,-2.63313603401 --13.7766008377,-0.0931000560522,-2.65235280991 --13.8836174011,-0.0921294316649,-2.71568632126 --13.9166278839,-0.0911448970437,-2.7670674324 --13.9146337509,-0.0911536887288,-2.81246972084 --13.6236095428,-0.0941055268049,-2.80403757095 --13.5326061249,-0.0940963178873,-2.83148980141 --13.5936155319,-0.0941129401326,-2.86565685272 --13.56361866,-0.0941157564521,-2.90406990051 --13.7196416855,-0.093156427145,-2.98038673401 --13.4446172714,-0.0951096042991,-2.9699420929 --13.406619072,-0.095110706985,-3.00636219978 --13.2666101456,-0.0960908010602,-3.02184581757 --13.3356237411,-0.095113940537,-3.08020472527 --13.3076229095,-0.0961125940084,-3.09642148018 --13.2186193466,-0.0961029976606,-3.12187862396 --13.2566299438,-0.0961197689176,-3.17324852943 --13.1276197433,-0.0971015840769,-3.18973398209 --13.1206254959,-0.0971088558435,-3.23113155365 --13.1886415482,-0.0961325094104,-3.29049229622 --13.3386678696,-0.0951743200421,-3.36980772018 --13.2306575775,-0.0961555540562,-3.36707353592 --13.1956596375,-0.0961570739746,-3.40248894691 --13.1956672668,-0.0961664542556,-3.44689083099 --13.2206773758,-0.0961814150214,-3.49727582932 --13.2196846008,-0.0951907485723,-3.54167842865 --13.1546831131,-0.0961857438087,-3.57011890411 --13.0956821442,-0.0961819514632,-3.59955477715 --13.1146917343,-0.0961958914995,-3.64894556999 --13.1627035141,-0.096211604774,-3.68311309814 --13.1467084885,-0.0962176844478,-3.72352313995 --13.2627344131,-0.0952546000481,-3.79986214638 --13.2207365036,-0.095254778862,-3.83328437805 --13.0707216263,-0.0962296947837,-3.83777761459 --14.2279176712,-0.0865132063627,-4.20148420334 --13.1167411804,-0.0952555015683,-3.91734981537 --13.1097478867,-0.0952638238668,-3.95974993706 --13.4538145065,-0.0933567807078,-4.10294675827 --13.1507730484,-0.0952941849828,-4.06152629852 --12.9697494507,-0.0962605252862,-4.05403614044 --12.9057483673,-0.0972551777959,-4.0804810524 --13.692896843,-0.0904593244195,-4.35940313339 --12.9457683563,-0.0962802916765,-4.159055233 --13.7389202118,-0.0904879197478,-4.44397115707 --13.0218000412,-0.095320045948,-4.27180767059 --13.0678186417,-0.0953424721956,-4.33218765259 --12.9308023453,-0.0963184982538,-4.33467102051 --14.1770496368,-0.0866470038891,-4.77430725098 --13.9550189972,-0.0876027643681,-4.75284385681 --14.0370407104,-0.0876301825047,-4.80399608612 --13.7509975433,-0.0895685628057,-4.75956678391 --13.8220233917,-0.0885995179415,-4.83192920685 --13.8380384445,-0.0886160284281,-4.88531446457 --13.7800397873,-0.0886133238673,-4.91475057602 --13.7100381851,-0.0896074324846,-4.94019794464 --17.4788379669,-0.0586267858744,-6.28128480911 --17.6028728485,-0.0576695464551,-6.35540962219 --17.6098976135,-0.0576907023787,-6.42080497742 --17.6339244843,-0.0567162409425,-6.49118280411 --17.6749572754,-0.0567468181252,-6.56855392456 --17.4159221649,-0.0586954131722,-6.53911161423 --17.9320602417,-0.0538571402431,-6.78818893433 --17.2989425659,-0.059701513499,-6.62097597122 --17.3469657898,-0.0587246716022,-6.67014789581 --17.2589683533,-0.0597193427384,-6.69959640503 --17.2929992676,-0.0587484687567,-6.774974823 --17.3700408936,-0.057789824903,-6.86632156372 --17.3360557556,-0.0577997937799,-6.91573572159 --17.3860931396,-0.0578341074288,-6.99810123444 --17.3771133423,-0.0578518211842,-7.05850744247 --17.3031082153,-0.0578403063118,-7.06074857712 --17.3231391907,-0.0578663870692,-7.13213443756 --17.2421417236,-0.0578630305827,-7.16358280182 --17.3291873932,-0.0579090341926,-7.26192474365 --17.1921806335,-0.0578890331089,-7.27040910721 --17.1391906738,-0.0588935725391,-7.31183719635 --17.0922031403,-0.0589000955224,-7.35626554489 --17.076210022,-0.0589052625,-7.38046884537 --17.0292243958,-0.0589118264616,-7.42489957809 --17.0032424927,-0.0589245222509,-7.47731256485 --16.9782619476,-0.0589374341071,-7.52972221375 --16.9522819519,-0.0589502230287,-7.5821352005 --16.9453048706,-0.0589688718319,-7.64253520966 --17.0593624115,-0.0580257102847,-7.75686359406 --22.2298107147,-0.014654988423,-10.0597887039 --21.6266841888,-0.0194960255176,-9.87656211853 --21.1545906067,-0.0233763959259,-9.74725246429 --21.1776332855,-0.0234129093587,-9.83762836456 --21.0946483612,-0.0234160125256,-9.88107585907 --21.2117233276,-0.0224833209068,-10.0153961182 --21.7219142914,-0.0176787022501,-10.3324642181 --21.010723114,-0.023462921381,-10.0441131592 --20.7846946716,-0.0254185963422,-10.0186481476 --20.8007411957,-0.0244536586106,-10.1070337296 --20.8097820282,-0.0244862623513,-10.1914196014 --20.7277984619,-0.0254889260978,-10.2328643799 --20.7738513947,-0.0245344750583,-10.3362312317 --20.7088508606,-0.0245278477669,-10.3454704285 --20.6808834076,-0.0245486553758,-10.4128828049 --20.7009315491,-0.0245855655521,-10.5032587051 --20.7870006561,-0.023645568639,-10.6275978088 --21.6283149719,-0.0159656647593,-11.1314496994 --26.6830120087,0.0272561255842,-13.7665719986 --21.5903911591,-0.0160180535167,-11.2832574844 --26.5750675201,0.0272292234004,-13.8702220917 --26.5491809845,0.027151832357,-14.0690145493 --26.5042266846,0.0271244402975,-14.1514282227 --26.5453014374,0.0280660521239,-14.2797899246 --26.5273590088,0.0280281230807,-14.3781919479 --26.5974445343,0.0289588309824,-14.5225315094 --26.4964408875,0.0279728546739,-14.5227928162 --22.7281665802,-0.00370176043361,-12.5936489105 --24.768951416,0.0145151559263,-13.7976999283 --22.1351089478,-0.00759417098016,-12.545211792 --21.993106842,-0.00857829954475,-12.5587015152 --25.061296463,0.0182382762432,-14.3700647354 --22.6824398041,-0.00189117807895,-13.0828304291 --25.0763950348,0.0191675499082,-14.5356407166 --25.1424808502,0.0200990326703,-14.6779842377 --24.4142665863,0.013333035633,-14.3638544083 --24.5213680267,0.0152491293848,-14.5291748047 --22.5016422272,-0.00201469729654,-13.4529066086 --24.3544254303,0.0142275905237,-14.6380624771 --22.7888393402,0.000814767263364,-13.7663040161 --23.0119857788,0.0026873301249,-13.996547699 --23.8733901978,0.0113079324365,-14.6103601456 --23.9324741364,0.0122416149825,-14.748711586 --24.0635910034,0.0131464079022,-14.9310121536 --23.4034442902,0.00832358188927,-14.7342405319 --36.0517501831,0.12020021677,-22.6029396057 --35.758731842,0.11824760586,-22.5775127411 --23.6307582855,0.0120792156085,-15.2364521027 --23.5918064117,0.0120506510139,-15.3168706894 --36.0012702942,0.12285912782,-23.3628635406 --35.1300010681,0.116148814559,-22.9618301392 --35.0220031738,0.115157723427,-22.9710960388 --34.805015564,0.114177487791,-22.9856204987 --34.9862060547,0.116028994322,-23.2608757019 --34.8572540283,0.116010814905,-23.3343448639 --34.8223495483,0.11595261842,-23.4697494507 --35.1806259155,0.119725860655,-23.8668823242 --35.059677124,0.119703605771,-23.9463443756 --35.3388671875,0.122544847429,-24.2163448334 --34.7477035522,0.117727294564,-23.9761276245 --34.7108001709,0.117668837309,-24.1115341187 --34.6638870239,0.117614723742,-24.2399425507 --15.6758813858,-0.0550398379564,-11.2154273987 --15.6439065933,-0.055054448545,-11.2668485641 --35.7707748413,0.129890948534,-25.5063209534 --35.7188072205,0.12987485528,-25.5535469055 --35.5868644714,0.129854857922,-25.6290149689 --35.4349098206,0.128844201565,-25.6894989014 --35.3910102844,0.128784537315,-25.8269081116 --33.4471473694,0.111597701907,-24.5876369476 --35.2932052612,0.129668906331,-26.0957355499 --33.2632293701,0.110569536686,-24.6943359375 --33.2983627319,0.112476706505,-24.8826942444 --33.0223350525,0.110530011356,-24.839263916 --33.0264511108,0.110451519489,-25.0046443939 --32.8524742126,0.109457291663,-25.0361480713 --32.9296340942,0.111343458295,-25.2574768066 --32.3974685669,0.106521226466,-25.0152301788 --32.4635620117,0.108451291919,-25.1463737488 --32.6297683716,0.110293962061,-25.4366397858 --32.4447898865,0.109306059778,-25.457151413 --34.2058830261,0.126367077231,-26.9942951202 --34.1159591675,0.126327842474,-27.097738266 --34.0130310059,0.126295298338,-27.1901912689 --33.8510665894,0.125292047858,-27.2356853485 --33.8481330872,0.126251414418,-27.3208770752 --33.7211875916,0.125231087208,-27.3933467865 --33.6292648315,0.125192716718,-27.4947948456 --33.5283355713,0.125159174204,-27.5882472992 --33.205280304,0.123238809407,-27.4998588562 --31.8696212769,0.11083868891,-26.5751895905 --31.3354320526,0.106032386422,-26.3019542694 --31.369512558,0.106974422932,-26.4141235352 --31.5067214966,0.108822420239,-26.6964073181 --31.4217948914,0.108785226941,-26.7938518524 --31.025680542,0.105911545455,-26.6275177002 --30.7146167755,0.103994295001,-26.5311260223 --30.695728302,0.103923298419,-26.6825218201 --30.4386940002,0.101979039609,-26.6290912628 --30.4277515411,0.102944388986,-26.7032909393 --30.3488273621,0.102905355394,-26.8027324677 --30.4510211945,0.104768127203,-27.0610427856 --30.1809768677,0.102832615376,-26.9926204681 --30.2711639404,0.104700408876,-27.2429409027 --30.3253269196,0.105587273836,-27.4622840881 --30.1243286133,0.104614496231,-27.4538154602 --30.155412674,0.105555176735,-27.5679836273 --30.8470058441,0.113083794713,-28.3698654175 --29.9465389252,0.104502372444,-27.7249069214 --29.7835617065,0.103509522974,-27.7484092712 --29.5145130157,0.101577304304,-27.672990799 --29.4385948181,0.102535769343,-27.7754306793 --29.5387973785,0.104393042624,-28.0427417755 --30.0762367249,0.110039785504,-28.6365413666 --29.4609470367,0.104308113456,-28.2333774567 --28.9997596741,0.100490286946,-27.9701004028 --28.7657279968,0.0995413810015,-27.9206600189 --28.9610004425,0.10234054178,-28.2828998566 --28.901096344,0.102288372815,-28.4023303986 --28.8131713867,0.102253139019,-28.4937801361 --28.804233551,0.102214470506,-28.5739803314 --30.3645191193,0.120187826455,-30.2902107239 --29.5991020203,0.112556412816,-29.720161438 --30.1776790619,0.120112091303,-30.4831161499 --30.1067790985,0.120060175657,-30.6025543213 --30.0078544617,0.120025247335,-30.6940135956 --28.2516670227,0.102016337216,-29.0987052917 --28.1266422272,0.101048670709,-29.0619926453 --27.946647644,0.100070662796,-29.058511734 --27.8266963959,0.100055009127,-29.1169910431 --27.9869689941,0.102863192558,-29.4652576447 --27.9821090698,0.103774040937,-29.6446456909 --27.7390632629,0.101836919785,-29.5732154846 --27.5920219421,0.100884228945,-29.5115222931 --27.3609809875,0.0989408418536,-29.4500808716 --27.4341869354,0.100801214576,-29.7124118805 --27.4873809814,0.10267315805,-29.9557590485 --26.8940429688,0.0969678536057,-29.5005931854 --26.8851833344,0.097880795598,-29.6759872437 --26.9774093628,0.0997260585427,-29.963306427 --26.6943206787,0.0978206992149,-29.8379077911 --26.5392665863,0.0968770980835,-29.760219574 --26.2751922607,0.0949601903558,-29.6538124084 --26.2273006439,0.0948993712664,-29.7852325439 --26.3705768585,0.0977072566748,-30.1345119476 --26.4998435974,0.100522510707,-30.4718036652 --26.3418579102,0.0995346605778,-30.4823112488 --26.5761432648,0.102324508131,-30.8463249207 --26.5372695923,0.103252507746,-30.9967441559 --26.5244178772,0.104161836207,-31.1781425476 --26.413476944,0.10414018482,-31.2446136475 --27.6807937622,0.119142472744,-32.9340286255 --26.2456493378,0.104057811201,-31.4425182343 --26.1387138367,0.104032538831,-31.5149898529 --26.1768321991,0.104954384267,-31.6601543427 --25.1360244751,0.0936036631465,-30.6093444824 --25.9729728699,0.1048964113,-31.8170890808 --26.0011672974,0.106772556901,-32.0534553528 --24.9343166351,0.0954521521926,-30.9506702423 --24.6862411499,0.0935348421335,-30.8422546387 --23.5282802582,0.0802960768342,-29.6015434265 --23.6104373932,0.0821865648031,-29.7986755371 --23.3072986603,0.0793172046542,-29.6093025208 --23.0331821442,0.0774284154177,-29.4519023895 --23.1034069061,0.0792787969112,-29.7302417755 --22.8142757416,0.0764019936323,-29.55286026 --23.9435768127,0.0914358645678,-31.1963691711 --23.8606586456,0.0913976207376,-31.2888221741 --24.0559425354,0.0941939875484,-31.643863678 --23.8128623962,0.0932788923383,-31.5304470062 --22.0391902924,0.0725684165955,-29.4002304077 --21.9712753296,0.0725244283676,-29.5016784668 --23.8223896027,0.0969531610608,-32.1616096497 --22.4751319885,0.080924525857,-30.5620632172 --21.821598053,0.0743486136198,-29.8789730072 --21.7025508881,0.0733948275447,-29.8152637482 --21.6957054138,0.0743011310697,-29.9996604919 --21.6788539886,0.0752135813236,-30.1740684509 --21.5438709259,0.0742230191827,-30.1855659485 --21.5100002289,0.0751485601068,-30.3379898071 --21.6383113861,0.0779394209385,-30.7162742615 --21.3070220947,0.0741640180349,-30.3527374268 --21.5724945068,0.0788367390633,-30.9299201965 --21.4605388641,0.078825853765,-30.975402832 --21.1283321381,0.0760027840734,-30.7050609589 --20.7140235901,0.0712531656027,-30.3107852936 --20.5830402374,0.0712621957064,-30.3222827911 --20.4830932617,0.0712444931269,-30.3787555695 --20.4021720886,0.0712101384997,-30.4632129669 --20.3471927643,0.0712049230933,-30.485458374 --20.8479709625,0.0786561593413,-31.4364509583 --21.5429954529,0.0899279341102,-32.690284729 --20.9544639587,0.0833397507668,-32.0231513977 --20.542142868,0.0785978510976,-31.6148777008 --20.9548397064,0.0861119404435,-32.4609375 --21.0760860443,0.0879443064332,-32.7570343018 --20.6827850342,0.0841874033213,-32.3737449646 --20.4596920013,0.0822774991393,-32.2483215332 --20.5520019531,0.0850762352347,-32.6146392822 --20.3679580688,0.0841302126646,-32.5501861572 --16.0405292511,0.0250827614218,-25.9001026154 --15.9335403442,0.025092298165,-25.9085884094 --15.854511261,0.0241218321025,-25.8708515167 --15.7174797058,0.0231613740325,-25.8283596039 --15.7656974792,0.0250224675983,-26.087720871 --15.4746112823,0.0231186617166,-25.9737548828 --15.3826398849,0.0231150500476,-26.0042304993 --21.3530502319,0.110113292933,-36.1877250671 --21.8168087006,0.117585033178,-37.0955429077 --21.72290802,0.117538794875,-37.2010116577 --21.9524688721,0.123166285455,-37.8592185974 --21.9066448212,0.124068759382,-38.0516471863 --21.3420791626,0.117499142885,-37.3495063782 --21.2511863708,0.117449298501,-37.4609718323 --21.1993522644,0.118358239532,-37.6424102783 --21.0632724762,0.117427289486,-37.5387191772 --21.4761276245,0.1258495152,-38.5457725525 --14.9856977463,0.0295379161835,-27.2245483398 --14.8927288055,0.029533566907,-27.2560253143 --13.6500167847,0.0117581421509,-25.2014598846 --16.659784317,0.0584216117859,-30.8903503418 --16.6138134003,0.0584111772478,-30.920589447 --16.5318870544,0.0593796595931,-30.9990539551 --16.4579753876,0.059339299798,-31.0925121307 --20.7729892731,0.128451496363,-39.4243087769 --20.6350383759,0.128445833921,-39.4608154297 --13.3976840973,0.0153959589079,-25.9702777863 --13.3197278976,0.0153819257393,-26.017742157 --13.2346744537,0.0144274597988,-25.9520130157 --13.3149776459,0.0172330252826,-26.3063468933 --13.2790937424,0.0181696433574,-26.4377784729 --12.6662464142,0.00977404974401,-25.4326972961 --12.5442113876,0.00881450437009,-25.3872032166 --12.5173358917,0.00974395684898,-25.530626297 --14.1192617416,0.0377403534949,-28.96667099 --12.5426397324,0.0115580949932,-25.8822059631 --13.901386261,0.0377021804452,-29.0918560028 --5.50877380371,-0.102235324681,-11.9868917465 --5.4767870903,-0.102239616215,-12.0143280029 --5.41674995422,-0.103209234774,-11.982790947 --12.0559520721,0.0124512640759,-26.2162361145 --17.0643997192,0.101017490029,-37.2183609009 --12.5372266769,0.0236147008836,-27.6906261444 --12.3410587311,0.0217470787466,-27.4881954193 --12.2390670776,0.0217589158565,-27.4916858673 --18.2127380371,0.129849821329,-41.0239715576 --18.1078510284,0.130801856518,-41.1324577332 --18.0488948822,0.130786627531,-41.1717033386 --17.8889007568,0.129810661077,-41.1572380066 --15.0916700363,0.0813749954104,-35.0910377502 --14.5869312286,0.0738969370723,-34.2238731384 --17.4550056458,0.12882527709,-41.211807251 --17.3671550751,0.129752799869,-41.3622779846 --17.2141723633,0.129769742489,-41.3598060608 --17.1381816864,0.128777369857,-41.3600730896 --12.6543655396,0.0477402806282,-31.2057476044 --11.0932769775,0.0188268721104,-27.6575050354 --10.2176055908,0.00396001385525,-25.7406730652 --10.1125822067,0.00299181556329,-25.7091674805 --10.0916395187,0.00396162457764,-25.7723865509 --10.0307159424,0.00392709672451,-25.8548488617 --9.89462089539,0.00300558796152,-25.7433700562 --9.37365341187,-0.00633566547185,-24.6372318268 --9.27262496948,-0.00630170619115,-24.6017227173 --9.17761039734,-0.00727700581774,-24.5822124481 --9.10364246368,-0.00728383427486,-24.6166801453 --9.07067012787,-0.00729469535872,-24.6469154358 --8.97966194153,-0.00727420812473,-24.6343975067 --8.90970611572,-0.00728847831488,-24.6818675995 --8.01374340057,-0.0249814447016,-22.461063385 --7.37938117981,-0.0370724834502,-20.923034668 --7.31740903854,-0.0370789915323,-20.9565010071 --7.25042200089,-0.0370752550662,-20.9719619751 --7.20941019058,-0.0370614007115,-20.9592037201 --7.13239812851,-0.0370412990451,-20.9466781616 --7.07142686844,-0.037047944963,-20.9801387787 --6.99942588806,-0.037035446614,-20.9806079865 --6.9705414772,-0.0360983647406,-21.1110458374 --6.93563985825,-0.0361503958702,-21.2224807739 --6.88570165634,-0.0351779013872,-21.2919330597 --7.44532060623,-0.0212235245854,-23.1016349792 --7.44453716278,-0.0203501470387,-23.3420410156 --10.1964101791,0.0475640706718,-32.116985321 --6.43715238571,-0.0407794937491,-20.6837596893 --6.36213874817,-0.0407587513328,-20.6702365875 --6.28712272644,-0.0417363904417,-20.6537094116 --6.22113418579,-0.0417318828404,-20.6681804657 --6.1951584816,-0.0407413877547,-20.6954040527 --6.13317966461,-0.0407433696091,-20.720867157 --6.08725166321,-0.0407777018845,-20.802318573 --6.03129291534,-0.0407918468118,-20.8487758636 --6.40767002106,-0.0286618247628,-22.3708400726 --6.33266973495,-0.0286484938115,-22.3703155518 --5.94668579102,-0.0380067303777,-21.286075592 --5.9076757431,-0.0379939563572,-21.2753181458 --5.74136638641,-0.0407843180001,-20.9358768463 --5.69343662262,-0.0398168750107,-21.0143299103 --5.64651155472,-0.0398523062468,-21.0977802277 --6.07518482208,-0.0259028803557,-22.9337902069 --6.02527618408,-0.0249466728419,-23.032245636 --5.4968380928,-0.0370157323778,-21.4583435059 --8.36419677734,0.0484482645988,-32.7751312256 --8.2833070755,0.0493994913995,-32.8846130371 --6.70599031448,0.00477344356477,-27.0764541626 --5.81203556061,-0.019348949194,-23.8536834717 --6.7709107399,0.0122283259407,-28.0672130585 --6.67590236664,0.0112510826439,-28.051700592 --5.78668737411,-0.0147219682112,-24.5567245483 --5.43363523483,-0.0230471845716,-23.4124603271 --5.35964679718,-0.023040426895,-23.4239387512 --5.29268741608,-0.0230515245348,-23.4664115906 --5.21769380569,-0.0230413358659,-23.4718875885 --5.15675592422,-0.0230658501387,-23.5373477936 --5.42101383209,-0.0128424055874,-24.8943080902 --6.56116771698,0.0289653427899,-30.4496631622 --6.46619510651,0.0289679672569,-30.4701595306 --6.37222576141,0.0289682876319,-30.4946556091 --4.69323015213,-0.0276755709201,-22.9656238556 --4.61019086838,-0.0286370888352,-22.9221096039 --4.51308679581,-0.029558762908,-22.8096122742 --4.48412179947,-0.0285735595971,-22.8468418121 --4.41916322708,-0.0285851638764,-22.8903141022 --4.457695961,-0.0248998794705,-23.4596805573 --6.46887254715,0.0568514280021,-34.3342208862 --4.27855825424,-0.0257863420993,-23.3096694946 --4.2095913887,-0.0257919579744,-23.3431472778 --4.13056659698,-0.0257626585662,-23.3156280518 --4.32778596878,-0.0165027752519,-24.6136455536 --4.10804176331,-0.0220319647342,-23.8192634583 --3.97774672508,-0.0248369500041,-23.5037937164 --3.90777659416,-0.0248407553881,-23.5342712402 --3.81970500946,-0.0257824826986,-23.4567661285 --3.77487587929,-0.0238719582558,-23.6362171173 --3.6998796463,-0.023859584704,-23.6387004852 --3.61157608032,-0.026667997241,-23.316986084 --3.56474161148,-0.0257538873702,-23.490442276 --3.4786734581,-0.0256978403777,-23.416934967 --3.43889045715,-0.0248146615922,-23.6443824768 --3.39307951927,-0.022914133966,-23.8418388367 --3.51236891747,-0.0126772308722,-25.1961326599 --3.42431139946,-0.013626771979,-25.1326236725 --3.48097467422,-0.00901831872761,-25.8277740479 --3.40702867508,-0.00803423393518,-25.8802547455 --3.33308887482,-0.0080540087074,-25.9397373199 --3.26015734673,-0.00707837287337,-26.0072174072 --3.17312407494,-0.00804191268981,-25.968711853 --3.08205008507,-0.00898098107427,-25.8872089386 --1.80345582962,-0.0822317525744,-15.8708791733 --1.77946531773,-0.0822327211499,-15.8841161728 --2.85688138008,-0.00983858667314,-25.7014560699 --2.78797960281,-0.00888063479215,-25.7999286652 --2.70899987221,-0.00887617655098,-25.8174171448 --2.63506770134,-0.0088996887207,-25.8838996887 --2.57830405235,-0.00702310819179,-26.1253662109 --2.49932765961,-0.00702035007998,-26.1458511353 --2.45833015442,-0.00701315607876,-26.1460971832 --2.37834715843,-0.00700630340725,-26.1595840454 --2.31049752235,-0.0060781352222,-26.3110599518 --2.25378680229,-0.00423141382635,-26.6055297852 --2.19506716728,-0.00137896987144,-26.8899974823 --2.11207914352,-0.00136840657797,-26.8974895477 --2.08627581596,-0.000475175416796,-27.0977191925 --2.00128412247,-0.000462060270365,-27.1012172699 --1.90309798717,-0.0013351830421,-26.9047241211 --1.82214903831,-0.00134715286549,-26.9522151947 --1.7381426096,-0.00132567423861,-26.9407081604 --1.70593202114,0.00423130160198,-27.7451496124 --1.60267543793,0.00239949417301,-27.4766674042 --1.58102238178,0.00520660262555,-27.8288936615 --3.96702694893,0.327202528715,-71.8061065674 --2.70415353775,0.207518175244,-55.5030975342 --2.26154851913,0.165806338191,-49.7539215088 --2.38178944588,0.211229994893,-56.0832366943 --1.98797345161,0.337553977966,-73.3287506104 --1.7600902319,0.338540971279,-73.3953933716 --1.53534436226,0.339449197054,-73.6010284424 --0.284889161587,0.127906695008,-44.7170143127 --0.143611162901,0.126097336411,-44.4145698547 -0.0394212529063,0.153748109937,-43.3729248047 -0.108455896378,0.154749676585,-43.4190635681 -0.2453687042,0.153664514422,-43.3543434143 -0.38335108757,0.153618603945,-43.3596191406 -0.521415054798,0.154619053006,-43.4468994141 -0.661521196365,0.155643075705,-43.5771751404 -0.795278787613,0.153470739722,-43.3554573059 -0.944791078568,0.157723352313,-43.8967208862 -1.01587164402,0.158750787377,-43.98985672 -1.16415071487,0.161871150136,-44.2961273193 -1.30412435532,0.161820277572,-44.2934036255 -1.46470093727,0.16710691154,-44.9026565552 -1.54392278194,0.151075869799,-43.121006012 -1.67884647846,0.15099799633,-43.0662918091 -1.70070433617,0.141342997551,-41.9154815674 -1.82752430439,0.140208169818,-41.7537765503 -1.95847606659,0.140147358179,-41.7260627747 -2.0904314518,0.139088526368,-41.7023506165 -2.3803384304,0.164668053389,-44.6934661865 -2.34216809273,0.137874856591,-41.475933075 -3.82044935226,0.330173462629,-64.3057937622 -2.66703271866,0.136715814471,-41.390663147 -2.80306863785,0.137702018023,-41.4489440918 -2.94418072701,0.138730227947,-41.5852241516 -3.33964729309,0.168603181839,-45.1722412109 -3.18988466263,0.136500358582,-41.3238220215 -3.57597303391,0.16316087544,-44.52784729 -3.66922998428,0.166283801198,-44.8049659729 -3.81422352791,0.166244149208,-44.8232421875 -5.70455598831,0.334772229195,-64.8207244873 -3.77330946922,0.124458886683,-39.8105621338 -3.90331339836,0.124429099262,-39.8348579407 -4.03230524063,0.124392464757,-39.8461494446 -4.10336923599,0.125411242247,-39.9222869873 -4.20813035965,0.123249731958,-39.6946105957 -4.3340959549,0.123199284077,-39.6789093018 -4.4630947113,0.123166814446,-39.6972045898 -4.60217189789,0.124176628888,-39.7974853516 -4.74729681015,0.125212237239,-39.9477653503 -4.87426519394,0.125163376331,-39.9350624084 -4.89088153839,0.121941059828,-39.5442581177 -5.0198764801,0.122906707227,-39.5585517883 -5.1589422226,0.122910685837,-39.6478385925 -5.35743665695,0.128143370152,-40.1850662231 -5.47532701492,0.127052903175,-40.0913772583 -5.59625005722,0.126979827881,-40.0306816101 -5.66325473785,0.126966372132,-40.0458259583 -5.80834293365,0.127981767058,-40.1591072083 -5.90510940552,0.125825598836,-39.9334335327 -6.02603244781,0.125752881169,-39.8727416992 -6.14998054504,0.125693634152,-39.8380432129 -6.28499746323,0.125671163201,-39.8763389587 -6.4230298996,0.126656576991,-39.9306297302 -6.49405479431,0.126654163003,-39.9677696228 -7.33210992813,0.163761183619,-44.2833747864 -7.46502113342,0.163679644465,-44.2146720886 -7.03181171417,0.134957209229,-40.8325195312 -7.75498390198,0.163590550423,-44.2252426147 -10.4273958206,0.285586744547,-58.5160827637 -10.6072998047,0.285491019487,-58.4543380737 -7.23035001755,0.123079754412,-39.350818634 -7.43806648254,0.120869740844,-39.0874671936 -7.5660443306,0.120827399194,-39.0837669373 -7.75732421875,0.123941905797,-39.403011322 -7.91745138168,0.124977022409,-39.5592842102 -8.06149578094,0.125969082117,-39.6275672913 -8.14054584503,0.1269787848,-39.6907043457 -11.9340696335,0.278490424156,-57.4565048218 -8.28097057343,0.121619783342,-39.1134223938 -8.40793704987,0.121571719646,-39.0977287292 -8.50578212738,0.120460912585,-38.9500617981 -8.62472057343,0.120398670435,-38.9033737183 -8.73663043976,0.120321854949,-38.8256950378 -6.17880010605,0.0197563432157,-27.135345459 -6.27682065964,0.0207450333983,-27.1646785736 -9.03247451782,0.119166091084,-38.7064743042 -6.59835720062,0.0259752012789,-27.7602176666 -6.27539682388,0.00793446134776,-25.6463699341 -6.39752340317,0.00897810421884,-25.789680481 -6.54892635345,0.01317222137,-26.2307453156 -9.70321655273,0.118867732584,-38.5331878662 -7.33713006973,0.0342440493405,-28.6458492279 -7.45319366455,0.0352537073195,-28.7241592407 -11.081653595,0.152508735657,-42.3471755981 -7.76959848404,0.0394115559757,-29.1847133636 -8.13898563385,0.0435480475426,-29.6334247589 -8.26305198669,0.0445574633777,-29.7157325745 -8.70027542114,0.0475859306753,-29.9968147278 -8.76313972473,0.0464947037399,-29.8571815491 -8.86913967133,0.047471113503,-29.8675079346 -8.95006370544,0.046410061419,-29.7938556671 -9.0370054245,0.0463575087488,-29.739200592 -9.11492061615,0.046292219311,-29.6555557251 -9.20487117767,0.0452448427677,-29.6119003296 -9.23179626465,0.045196082443,-29.5330867767 -9.3107213974,0.0441355369985,-29.4584369659 -9.40869617462,0.0450999066234,-29.4407749176 -9.48862266541,0.0440408661962,-29.3691253662 -9.56554317474,0.0439790710807,-29.29047966 -9.64446926117,0.0429194718599,-29.2168312073 -20.9619503021,0.341725021601,-63.2869606018 -18.7827377319,0.280681073666,-56.366153717 -13.4609556198,0.137464165688,-39.8594169617 -13.5678453445,0.136379346251,-39.7577514648 -13.6947937012,0.13632273674,-39.7200660706 -13.8357744217,0.136282294989,-39.7203712463 -18.7960586548,0.258168280125,-53.552318573 -15.2616233826,0.165590062737,-42.9709396362 -14.9065275192,0.155046582222,-41.7494773865 -22.5060081482,0.338874667883,-62.6060714722 -22.1214733124,0.325090676546,-60.9208564758 -19.5276050568,0.257761508226,-53.205619812 -19.6764717102,0.256656169891,-53.09192276 -19.6158409119,0.251314550638,-52.4154129028 -19.6386547089,0.250204771757,-52.2216110229 -19.7975540161,0.250115573406,-52.142906189 -19.9544525146,0.249026045203,-52.0621986389 -20.0943069458,0.248916864395,-51.934513092 -20.3714771271,0.250955611467,-52.1627044678 -21.6418704987,0.276042044163,-54.9260101318 -21.9079818726,0.278049856424,-55.0902137756 -21.9959354401,0.278006851673,-55.0583534241 -20.9982814789,0.251718014479,-52.0626754761 -22.3728122711,0.278861105442,-54.9938926697 -21.3962516785,0.253621786833,-52.1012001038 -22.6805343628,0.277644068003,-54.7545051575 -22.8394107819,0.277542769909,-54.6508026123 -21.6344490051,0.248124465346,-51.2873001099 -20.9227676392,0.231323838234,-49.3701438904 -21.949464798,0.249069899321,-51.356678009 -22.1885299683,0.25105831027,-51.4659080505 -30.2933826447,0.416327089071,-69.795249939 -28.811870575,0.380654543638,-65.7929916382 -22.7333698273,0.25186124444,-51.3877410889 -24.3068122864,0.27891716361,-54.2700309753 -22.946767807,0.247483298182,-50.7796554565 -23.4242801666,0.253675162792,-51.4076805115 -23.6452960968,0.254641920328,-51.463924408 -23.9815254211,0.258703619242,-51.7650756836 -23.9109973907,0.253422439098,-51.1855735779 -24.0077857971,0.25228497386,-50.9729270935 -24.7930240631,0.265823870897,-52.4364700317 -24.9749526978,0.26574909687,-52.3907585144 -25.8631496429,0.28024572134,-53.8294258118 -28.582572937,0.328186988831,-59.0485267639 -28.8105316162,0.329119265079,-59.0427742004 -25.9791564941,0.271669566631,-52.7786521912 -33.7031059265,0.412400871515,-68.0364608765 -18.8583316803,0.134892135859,-37.7524375916 -18.9692516327,0.134825751185,-37.677772522 -29.9585380554,0.333903849125,-59.2517929077 -30.1053504944,0.33277246356,-59.0771141052 -30.3232860565,0.333695203066,-59.0453720093 -30.5782794952,0.334643900394,-59.0835990906 -30.7693786621,0.336662977934,-59.2236633301 -31.3348731995,0.342830896378,-59.8546257019 -36.3394966125,0.428120166063,-68.942817688 -36.5843925476,0.429019212723,-68.8810653687 -33.513053894,0.370632767677,-62.5871200562 -33.7139320374,0.370526909828,-62.4893989563 -29.9704914093,0.301656454802,-54.8832359314 -30.0552425385,0.299502789974,-54.6266136169 -30.1820602417,0.298378795385,-54.4499511719 -30.3429336548,0.298277914524,-54.3362579346 -30.5188236237,0.298185884953,-54.2475585938 -30.7237606049,0.299112647772,-54.2108345032 -30.9567394257,0.300057470798,-54.2240829468 -31.1518440247,0.302079170942,-54.369140625 -28.7810440063,0.259414702654,-49.8365745544 -28.9068927765,0.259308695793,-49.6909141541 -29.0697975159,0.259225934744,-49.6102218628 -29.8324718475,0.220158353448,-43.7811508179 -29.7802791595,0.218061923981,-43.5564155579 -29.9211864471,0.217985570431,-43.4677467346 -30.1912441254,0.219969540834,-43.5669708252 -32.2003211975,0.246753171086,-46.1757926941 -32.2641181946,0.245631784201,-45.9561920166 -32.447052002,0.246565818787,-45.909488678 -32.6600265503,0.246512636542,-45.9037628174 -23.5658416748,0.071265719831,-25.9433231354 -23.6497802734,0.071219176054,-25.8706989288 -41.0673980713,0.281228721142,-45.0305404663 -54.3679237366,0.421650081873,-56.5953330994 -52.9519233704,0.398812562227,-54.0778083801 -50.8601722717,0.373211234808,-51.7646217346 -51.0420341492,0.373110502958,-51.6239471436 -51.0877952576,0.371976613998,-51.3453788757 -38.5911216736,0.226811870933,-38.4602394104 -38.5408859253,0.225694984198,-38.1687278748 -38.4586296082,0.22257116437,-37.846244812 -38.3223342896,0.219436079264,-37.4728012085 -50.6692810059,0.358241468668,-49.4957847595 -50.6550102234,0.356100827456,-49.1702613831 -50.7848472595,0.355993896723,-48.9866333008 -50.9677200317,0.356899380684,-48.8549613953 -50.7723236084,0.35272154212,-48.3595733643 -49.3760871887,0.335285276175,-46.7240753174 -48.0320205688,0.318931102753,-45.2993049622 -46.8779830933,0.304561793804,-43.924621582 -23.6395797729,0.0465061739087,-21.7097587585 -23.7795715332,0.0474803112447,-21.7010936737 -23.8455123901,0.0474392548203,-21.6234817505 -23.7713623047,0.0453705191612,-21.4179763794 -23.8933944702,0.0463684163988,-21.46210289 -23.9933605194,0.0463343821466,-21.4154682159 -23.8711795807,0.0442577414215,-21.1689968109 -23.9641418457,0.045223146677,-21.1173667908 -23.8709831238,0.0431536361575,-20.8998737335 -23.9779548645,0.0431221351027,-20.8612327576 -24.0428981781,0.0430826507509,-20.7846240997 -16.2268829346,-0.0403564423323,-13.8785848618 -15.7965526581,-0.0454643443227,-13.4143362045 -15.7914943695,-0.0454950332642,-13.3227739334 -15.8614826202,-0.0455120690167,-13.2971515656 -15.8964509964,-0.0455350801349,-13.2415542603 -16.0214729309,-0.0445429757237,-13.2618923187 -16.0284233093,-0.0455706454813,-13.1823158264 -8.24869823456,-0.126864552498,-6.60729551315 -8.18964576721,-0.127884045243,-6.51376914978 -8.2186460495,-0.127889081836,-6.49417543411 -8.26165485382,-0.127891793847,-6.48656606674 -8.29865932465,-0.126895457506,-6.47395944595 -8.32866001129,-0.12690025568,-6.45535993576 -8.34665489197,-0.126906678081,-6.42776155472 -8.35865402222,-0.126909524202,-6.41596412659 -8.38165092468,-0.126915365458,-6.39137220383 -8.41165161133,-0.126920074224,-6.37277078629 -8.43564891815,-0.12692566216,-6.34917545319 -8.47465419769,-0.126929298043,-6.33657646179 -8.47964096069,-0.126937493682,-6.29799556732 -8.49264144897,-0.126940056682,-6.28719472885 -8.52164077759,-0.126945033669,-6.26660346985 -8.53863430023,-0.126951336861,-6.23800849915 -8.58464431763,-0.126953840256,-6.23139333725 -8.60063743591,-0.126960456371,-6.20081043243 -8.62863731384,-0.12696531415,-6.18020963669 -8.65263462067,-0.126970857382,-6.15562105179 -8.66663455963,-0.126973167062,-6.14581489563 -8.69363498688,-0.12697814405,-6.12421607971 -8.71262836456,-0.126984253526,-6.09563398361 -8.74363040924,-0.126988679171,-6.07703018188 -8.77363109589,-0.126993462443,-6.05643939972 -8.79362678528,-0.126999109983,-6.02984189987 -8.81762504578,-0.126004248857,-6.00624084473 -8.8326253891,-0.126006692648,-5.99544906616 -8.87062931061,-0.126010477543,-5.98084688187 -8.88462352753,-0.12601660192,-5.95025062561 -8.92062568665,-0.126020669937,-5.93365383148 -8.95062732697,-0.126025319099,-5.91305732727 -8.97762584686,-0.126030221581,-5.89046192169 -8.99061870575,-0.126036345959,-5.85886955261 -9.01662445068,-0.126037567854,-5.8560628891 -9.04762458801,-0.126042172313,-5.83547019958 -9.0606174469,-0.126048371196,-5.80288743973 -9.09762096405,-0.126052200794,-5.78727960587 -9.15463447571,-0.125054329634,-5.78465795517 -9.13861465454,-0.126062899828,-5.73309326172 -9.14561080933,-0.126066029072,-5.71631097794 -9.21562862396,-0.125067159534,-5.72168159485 -9.23762607574,-0.125072225928,-5.69607973099 -9.26862716675,-0.125076860189,-5.67448949814 -13.4083843231,-0.08677405864,-8.22642993927 -13.4703836441,-0.0857836231589,-8.20681476593 -13.4463596344,-0.0867923051119,-8.16304111481 -13.4743452072,-0.0868042036891,-8.12244701385 -13.2512254715,-0.0888339355588,-7.9250330925 -13.1901741028,-0.0898514166474,-7.8305015564 -13.234167099,-0.0898615419865,-7.80089712143 -13.1861219406,-0.089877858758,-7.71436309814 -13.1290740967,-0.0908942446113,-7.62382936478 -13.1820831299,-0.09089718014,-7.62800550461 -13.1710548401,-0.0909104421735,-7.56544160843 -13.1890382767,-0.0909217000008,-7.52085399628 -13.1770095825,-0.0909346863627,-7.45828914642 -13.2500143051,-0.0909427702427,-7.44566774368 -13.1769628525,-0.0919587910175,-7.34814357758 -13.1799411774,-0.0919705927372,-7.2945728302 -13.2609605789,-0.0909722968936,-7.31373119354 -13.2609376907,-0.0919840186834,-7.25915718079 -13.2579135895,-0.091995857656,-7.20258808136 -13.1978683472,-0.0930102318525,-7.11405897141 -13.2178544998,-0.0930205509067,-7.07147073746 -13.4249076843,-0.09102281183,-7.13176107407 -13.3558712006,-0.0920313373208,-7.06701660156 -13.3788576126,-0.0920415818691,-7.02542877197 -13.4018440247,-0.0920519828796,-6.98284816742 -13.4328336716,-0.0920616686344,-6.94624996185 -13.3957986832,-0.0920739024878,-6.87270021439 -13.3717689514,-0.0930855125189,-6.80614566803 -13.3867540359,-0.0930956229568,-6.76056432724 -13.4597682953,-0.0920984148979,-6.77272558212 -13.4667491913,-0.0921088755131,-6.72215461731 -13.4247150421,-0.0931204259396,-6.64760732651 -13.5067224503,-0.0921283140779,-6.63697767258 -13.5437145233,-0.092137619853,-6.60238409042 -13.6247196198,-0.0921458378434,-6.58976173401 -13.4996595383,-0.0931588411331,-6.47426939011 -13.6206893921,-0.0921610295773,-6.5084028244 -13.6996936798,-0.0911692753434,-6.49477624893 -13.7066764832,-0.0921790748835,-6.44519996643 -13.8717079163,-0.0901859179139,-6.47251987457 -13.8076686859,-0.0911969915032,-6.38799142838 -13.790643692,-0.0912070721388,-6.32643318176 -13.8116312027,-0.0912163481116,-6.28384590149 -13.9426603317,-0.090219296515,-6.31997013092 -13.8996286392,-0.0912294909358,-6.24642848969 -14.0276470184,-0.0902377068996,-6.25277709961 -14.4667568207,-0.0862431675196,-6.40291690826 -13.9825954437,-0.0912568792701,-6.12665748596 -14.8678321838,-0.0832604542375,-6.47651100159 -14.735783577,-0.0842663869262,-6.38881015778 -14.8517961502,-0.0842760577798,-6.38516807556 -14.8007612228,-0.0842862129211,-6.30762386322 -14.8617582321,-0.0842961147428,-6.27901649475 -15.1368131638,-0.0823059007525,-6.34426689148 -14.7466850281,-0.0853158161044,-6.11795330048 -14.7156581879,-0.0863251984119,-6.05039978027 -14.6926412582,-0.086329780519,-6.01362657547 -14.9166822433,-0.0843401625752,-6.05391740799 -17.1832580566,-0.0653621852398,-6.9538974762 -17.2312469482,-0.0653747245669,-6.91129589081 -17.2812347412,-0.0643873885274,-6.86869621277 -17.3282203674,-0.0644001364708,-6.82410335541 -17.3592166901,-0.0644062981009,-6.80629205704 -17.4092025757,-0.0644190609455,-6.76269674301 -17.4591903687,-0.0644315928221,-6.72009325027 -17.5101776123,-0.0634441673756,-6.67749071121 -17.5531635284,-0.0634567514062,-6.63089704514 -17.6061515808,-0.0634694248438,-6.58829641342 -17.6501369476,-0.0634819939733,-6.54170322418 -17.6941337585,-0.0624886639416,-6.52689218521 -17.7381210327,-0.0625011771917,-6.48029661179 -17.7891082764,-0.0625137239695,-6.43669366837 -17.8470973969,-0.0625264942646,-6.39508867264 -17.8870811462,-0.0625388845801,-6.34649610519 -17.9410705566,-0.0615515783429,-6.30289411545 -17.9940567017,-0.0615643262863,-6.25829601288 -18.0300521851,-0.0615709237754,-6.2394900322 -18.0810394287,-0.0615836121142,-6.19389247894 -18.1310253143,-0.0605961754918,-6.14829158783 -18.1780128479,-0.0606087706983,-6.10069847107 -18.2370014191,-0.060621548444,-6.0580906868 -18.2809867859,-0.0606339611113,-6.00949621201 -18.3309726715,-0.0596465282142,-5.96289682388 -18.3749713898,-0.0596534237266,-5.94608449936 -18.4289569855,-0.0596663057804,-5.89948987961 -18.4779434204,-0.0586788654327,-5.85189151764 -18.5259304047,-0.0586912855506,-5.80429124832 -18.5809173584,-0.0587041415274,-5.75769376755 -18.6229019165,-0.0587164200842,-5.70710086823 -18.6718997955,-0.0577235631645,-5.69128322601 -18.7268867493,-0.0577364936471,-5.6436882019 -18.7758731842,-0.0577489957213,-5.59508943558 -18.8358612061,-0.0577619932592,-5.5494852066 -18.8888492584,-0.0567747876048,-5.50088882446 -18.9258308411,-0.056786686182,-5.44829511642 -18.9838199615,-0.0567997023463,-5.40069723129 -19.0328159332,-0.0558071248233,-5.38288450241 -19.088804245,-0.0558199137449,-5.33528089523 -19.1327896118,-0.0558321587741,-5.2836856842 -19.1867752075,-0.0558449923992,-5.23408889771 -19.2347602844,-0.0548575296998,-5.18249607086 -19.2927474976,-0.0548705086112,-5.13389539719 -19.34973526,-0.0548833571374,-5.08529186249 -19.3887310028,-0.053890388459,-5.06348514557 -19.4437160492,-0.0539033040404,-5.01288890839 -19.5087051392,-0.0539166890085,-4.9652838707 -19.5576896667,-0.0529291033745,-4.9136838913 -19.6106777191,-0.0529418624938,-4.86208724976 -19.6696643829,-0.0529550127685,-4.81148958206 -19.7316513062,-0.0519682727754,-4.76188611984 -19.7646446228,-0.051974941045,-4.73807954788 -19.8266334534,-0.0519882999361,-4.68748092651 -19.879617691,-0.0520010367036,-4.63488340378 -19.9386043549,-0.0510141775012,-4.58328342438 -19.9895915985,-0.0510267838836,-4.52968740463 -20.0525779724,-0.0500401072204,-4.47908163071 -20.0955715179,-0.0500476770103,-4.45527935028 -20.1565589905,-0.0500609017909,-4.40367555618 -20.2115459442,-0.0490737743676,-4.35007667542 -20.2675304413,-0.0490867085755,-4.29647779465 -20.3285160065,-0.0491001047194,-4.24288129807 -20.3915023804,-0.0481135323644,-4.19027805328 -20.4384880066,-0.0481258630753,-4.13368606567 -20.5154876709,-0.0481358319521,-4.11685800552 -20.5604705811,-0.0471480488777,-4.05926704407 -20.6204566956,-0.0471613332629,-4.00466775894 -20.6814441681,-0.0471746847034,-3.95006728172 -20.7434310913,-0.046188108623,-3.89546489716 -20.7914142609,-0.0462004579604,-3.83787059784 -20.8684024811,-0.0452150776982,-3.78526234627 -20.9043960571,-0.0452221930027,-3.75845885277 -20.9783840179,-0.0452366061509,-3.70485162735 -21.0373687744,-0.04424995929,-3.64725804329 -21.0983543396,-0.0442633591592,-3.59065723419 -21.1543388367,-0.0432763248682,-3.5330581665 -21.2303256989,-0.0432909615338,-3.47844958305 -21.2753105164,-0.043303091079,-3.41785979271 -21.3403053284,-0.0423127710819,-3.39404559135 -21.4072914124,-0.0423266552389,-3.33743906021 -21.4652767181,-0.0413399301469,-3.27784442902 -21.5202617645,-0.041352853179,-3.21824717522 -21.6042480469,-0.0403683148324,-3.1626355648 -21.646232605,-0.0403801500797,-3.10004782677 -21.7182292938,-0.0403905659914,-3.07622742653 -21.778213501,-0.039404027164,-3.01563072205 -21.8451976776,-0.0394180752337,-2.95602917671 -21.9091835022,-0.0384318865836,-2.89543008804 -21.9901695251,-0.0384472645819,-2.83682274818 -22.037153244,-0.0384595282376,-2.77323317528 -22.1121387482,-0.0374743193388,-2.71362519264 -22.1701335907,-0.0374836958945,-2.68581366539 -22.2311172485,-0.0364972762764,-2.62321639061 -22.305103302,-0.0365120135248,-2.56260848045 -22.3650875092,-0.0355255268514,-2.4990131855 -22.4350719452,-0.0355399847031,-2.43641209602 -22.4970550537,-0.0345536470413,-2.37281322479 -22.5750408173,-0.0345689281821,-2.31020879745 -22.6280345917,-0.0335779450834,-2.28039836884 -22.7080192566,-0.0335934199393,-2.21779036522 -22.7710037231,-0.0326073020697,-2.15219593048 -22.8399887085,-0.0326217114925,-2.08759403229 -22.9089717865,-0.0316361933947,-2.02199578285 -22.9999580383,-0.0316529050469,-1.95838463306 -23.0419406891,-0.0306646041572,-1.88979876041 -23.1289348602,-0.0306772086769,-1.86196756363 -23.2089195251,-0.0296928472817,-1.79636061192 -23.2769031525,-0.0297073014081,-1.72876358032 -23.3268852234,-0.0287198759615,-1.65917670727 -22.7068405151,-0.0336610786617,-1.5379383564 -22.4968147278,-0.0356452651322,-1.45048820972 -22.2797985077,-0.0376251935959,-1.39882349968 -9.6403131485,-0.136261463165,-0.438052624464 -9.64231777191,-0.136258676648,-0.408470630646 -9.63632297516,-0.136254921556,-0.377899706364 -9.6443271637,-0.13625267148,-0.348319888115 -9.6303319931,-0.136247992516,-0.317747652531 -9.63833713531,-0.136245682836,-0.28816768527 -9.62833976746,-0.13624291122,-0.272388607264 -9.63034439087,-0.136239916086,-0.242807477713 -9.62734985352,-0.136236339808,-0.213225722313 -9.6233549118,-0.136232495308,-0.182658240199 -9.61836051941,-0.136228486896,-0.152091160417 -9.6273651123,-0.13622623682,-0.123496487737 -9.62236881256,-0.136223867536,-0.107720203698 -9.61437416077,-0.136219531298,-0.0781402215362 -9.61137962341,-0.136215597391,-0.0475744046271 -9.61438560486,-0.136212438345,-0.0179939009249 -9.62339115143,-0.13620993495,0.0115880286321 -9.60739612579,-0.136204361916,0.0421503782272 -9.60640239716,-0.136200621724,0.07172973454 -9.61040592194,-0.13619928062,0.0865207910538 -9.60841178894,-0.136195376515,0.11609980464 -9.60541725159,-0.136191293597,0.145678207278 -9.59142303467,-0.136185720563,0.176237434149 -9.60142993927,-0.136183157563,0.205821171403 -9.60143566132,-0.136179342866,0.23540045321 -9.59144210815,-0.136174231768,0.26497399807 -9.59944438934,-0.136173307896,0.279768198729 -9.59645175934,-0.136169016361,0.309345513582 -9.59245681763,-0.136164441705,0.339907884598 -9.59046363831,-0.136160194874,0.36948543787 -9.58947086334,-0.136156067252,0.399063616991 -9.59047698975,-0.136152148247,0.428643405437 -9.58847999573,-0.136149853468,0.443431258202 -9.58948707581,-0.136145889759,0.473011136055 -9.58449363708,-0.136141091585,0.50258564949 -9.57550144196,-0.136135727167,0.532155990601 -9.56650733948,-0.136130303144,0.56172567606 -9.56151390076,-0.13612537086,0.591298818588 -9.57252216339,-0.136122465134,0.621875107288 -9.58152484894,-0.136121571064,0.636674582958 -9.57253265381,-0.136116012931,0.666243493557 -9.56653881073,-0.136110827327,0.695815384388 -9.56554698944,-0.136106312275,0.725393116474 -9.56555366516,-0.136101901531,0.754972159863 -9.5675611496,-0.136097744107,0.784554004669 -9.56556797028,-0.136092990637,0.814130723476 -9.55957221985,-0.136089876294,0.828912079334 -9.56657886505,-0.136086240411,0.859487533569 -9.54658794403,-0.136078894138,0.88805180788 -9.54259586334,-0.136073708534,0.917624890804 -9.56060218811,-0.136071637273,0.948218226433 -9.49461269379,-0.137057796121,0.972762048244 -9.91060352325,-0.133111208677,1.0365511179 -9.93260669708,-0.133111953735,1.05434381962 -9.99161052704,-0.133115798235,1.08995747566 -10.0066175461,-0.133113369346,1.12254142761 -9.99662494659,-0.133107379079,1.15311014652 -9.78964233398,-0.134073331952,1.16458070278 -9.83464813232,-0.134074956179,1.2001734972 -9.97664546967,-0.133093029261,1.22904527187 -9.99265193939,-0.133090540767,1.26262116432 -9.95366096497,-0.13308031857,1.28918612003 -9.96066761017,-0.133076488972,1.32175862789 -10.0046739578,-0.133078053594,1.35835278034 -10.0646772385,-0.132082134485,1.39597070217 -10.0646848679,-0.132077217102,1.4285351038 -9.63771343231,-0.135012313724,1.3921148777 -9.79671287537,-0.134030744433,1.44177806377 -9.9137134552,-0.133042871952,1.48840224743 -9.93972015381,-0.133041769266,1.52299284935 -9.78473758698,-0.134013786912,1.53349351883 -9.99573230743,-0.132040172815,1.5931776762 -10.0807352066,-0.132047861814,1.63679528236 -10.0117435455,-0.132035106421,1.64255475998 -9.81676387787,-0.134000748396,1.64603340626 -9.65578460693,-0.134971231222,1.65352666378 -9.83478069305,-0.132993072271,1.71119344234 -9.9687795639,-0.132008075714,1.76382732391 -9.93778991699,-0.132998228073,1.79039156437 -9.86979961395,-0.132985278964,1.79514920712 -14.4204750061,-0.0976744815707,2.57086730003 -9.80082130432,-0.133964180946,1.84627246857 -9.91083049774,-0.132970318198,1.92847084999 -9.46987342834,-0.135896772146,1.88184320927 -14.4324884415,-0.0966603457928,2.80373740196 -14.5154838562,-0.0966715142131,2.84255599976 -14.4414930344,-0.0966567471623,2.87509918213 -9.61789512634,-0.134900137782,2.01642537117 -9.60390472412,-0.134892448783,2.04400467873 -9.63891124725,-0.133892163634,2.08258605003 -9.63092136383,-0.133885398507,2.11117124557 -9.69792461395,-0.133890300989,2.15577840805 -9.68692970276,-0.133885651827,2.16955709457 -14.8814792633,-0.0927003324032,3.31808114052 -9.75995254517,-0.132880106568,2.27931880951 -9.51598453522,-0.13483518362,2.2587761879 -9.68197822571,-0.133856102824,2.32543849945 -9.86597061157,-0.131879851222,2.39809751511 -9.86897468567,-0.131877437234,2.41488647461 -9.94997692108,-0.130884736776,2.46550011635 -9.93998622894,-0.130877450109,2.49508023262 -9.94699573517,-0.130872711539,2.52965474129 -9.89301013947,-0.131858125329,2.54920935631 -9.65704441071,-0.133813560009,2.52566838264 -9.57805728912,-0.133797824383,2.52143383026 -9.66205883026,-0.132805466652,2.57404232025 -9.89704322815,-0.130838155746,2.66373372078 -9.89705371857,-0.130832031369,2.69729852676 -9.60409545898,-0.133777722716,2.65474772453 -9.63310146332,-0.132776334882,2.69433403015 -9.94407844543,-0.130821764469,2.80804777145 -9.87808990479,-0.130807831883,2.80681085587 -9.85110378265,-0.13079726696,2.83237600327 -9.80911827087,-0.131784126163,2.85393214226 -9.81112766266,-0.131778419018,2.88651847839 -9.80413913727,-0.131770938635,2.91808271408 -9.81614780426,-0.13076685369,2.95367264748 -9.866147995,-0.1307721138,2.98447990417 -9.8821554184,-0.130768612027,3.02206516266 -9.90416240692,-0.130766093731,3.06165146828 -9.84518051147,-0.130749762058,3.07819652557 -9.58122253418,-0.132698744535,3.03266477585 -9.50424289703,-0.133679166436,3.04220509529 -9.85921001434,-0.130733251572,3.18193721771 -9.8662147522,-0.130731284618,3.20072960854 -9.46827411652,-0.133656695485,3.1121263504 -9.46828556061,-0.133650094271,3.14469885826 -9.42730236053,-0.133636638522,3.16326856613 -9.4003162384,-0.133625403047,3.18683457375 -9.40232658386,-0.133618965745,3.22040295601 -9.35634422302,-0.133604496717,3.2369697094 -9.39534473419,-0.133607909083,3.2657752037 -9.40035533905,-0.133601978421,3.30034685135 -9.39636707306,-0.133594676852,3.33092880249 -9.39237976074,-0.133587151766,3.36249828339 -9.38839054108,-0.133579820395,3.39308142662 -9.38540363312,-0.133572518826,3.42465686798 -9.38041591644,-0.133564695716,3.45622348785 -9.39041900635,-0.132563054562,3.47601699829 -9.38543224335,-0.132555440068,3.50659775734 -9.38444328308,-0.132548391819,3.53917312622 -9.37745571136,-0.132540240884,3.56974458694 -9.37646770477,-0.132533162832,3.60232162476 -9.37847900391,-0.132526636124,3.63590192795 -9.37948513031,-0.132523372769,3.65269255638 -9.37549686432,-0.132515743375,3.68426895142 -9.371509552,-0.132507875562,3.71683359146 -9.35852336884,-0.132498726249,3.7444152832 -9.36653423309,-0.132493108511,3.78099322319 -9.36054706573,-0.132484897971,3.81256222725 -9.36955738068,-0.132479548454,3.84914827347 -9.36156463623,-0.132474541664,3.86293196678 -9.36357593536,-0.131467789412,3.89750814438 -9.35858917236,-0.131459802389,3.92908501625 -9.35960102081,-0.131452769041,3.96365761757 -9.35361385345,-0.131444722414,3.99424290657 -9.35062599182,-0.131437033415,4.02682065964 -9.34363937378,-0.131428480148,4.05838918686 -9.35264492035,-0.131426513195,4.07918119431 -9.34165763855,-0.131417289376,4.10875368118 -9.34766960144,-0.131411164999,4.14533519745 -9.33368492126,-0.131401315331,4.17390441895 -9.34169483185,-0.131395533681,4.21148729324 -9.3337097168,-0.131386652589,4.24305438995 -9.33471488953,-0.131383165717,4.2608423233 -9.33672618866,-0.130376383662,4.29543161392 -9.32774066925,-0.130367413163,4.32600688934 -9.33075332642,-0.130360499024,4.36258029938 -9.32776546478,-0.130352541804,4.3961558342 -9.32577896118,-0.130344867706,4.42973804474 -9.32479095459,-0.130337044597,4.46530294418 -9.32879734039,-0.130334198475,4.48410081863 -9.31781101227,-0.130324825644,4.51368045807 -9.32182407379,-0.130318000913,4.5512547493 -9.3058385849,-0.130307376385,4.57981681824 -9.30885124207,-0.130300492048,4.61639928818 -9.31186389923,-0.129293382168,4.65397119522 -9.32186889648,-0.129291653633,4.67577409744 -9.30388450623,-0.129280626774,4.70333814621 -9.30189704895,-0.129272729158,4.73791790009 -9.29991054535,-0.129264831543,4.77249908447 -9.30892181396,-0.12925888598,4.81307935715 -9.28993797302,-0.129247486591,4.84063863754 -9.29894924164,-0.129241555929,4.88122177124 -9.29895591736,-0.129237800837,4.89901542664 -9.29596996307,-0.128229632974,4.93359518051 -9.28998374939,-0.128220766783,4.96716976166 -9.28899765015,-0.128212764859,5.00374126434 -9.29001045227,-0.128205358982,5.04032754898 -9.27902603149,-0.128195419908,5.07189512253 -9.28203868866,-0.128188192844,5.11047363281 -9.2900428772,-0.12818582356,5.1332654953 -9.27705955505,-0.128175482154,5.163834095 -9.2810716629,-0.128168389201,5.20341157913 -9.27008724213,-0.128158420324,5.23498344421 -9.2681016922,-0.127150341868,5.27056932449 -9.27111339569,-0.127142980695,5.31014490128 -9.26412773132,-0.127133801579,5.34372329712 -9.27313327789,-0.127131596208,5.36751699448 -9.28314495087,-0.127125605941,5.41109895706 -9.26816177368,-0.127114593983,5.44166088104 -9.25517749786,-0.127104192972,5.47223567963 -9.25719070435,-0.127096578479,5.51181268692 -9.25920391083,-0.12608897686,5.55139160156 -9.25421142578,-0.126084133983,5.56718540192 -9.2612247467,-0.12607729435,5.61075735092 -9.23924255371,-0.126065075397,5.63632965088 -9.25125408173,-0.126059427857,5.68191671371 -9.24726772308,-0.12605060637,5.71849393845 -9.23428440094,-0.126039758325,5.75105381012 -9.23629760742,-0.126032233238,5.79064273834 -9.24930286407,-0.12503066659,5.81843519211 -9.23431873322,-0.125019595027,5.84900522232 -9.23533344269,-0.125011578202,5.88958072662 -9.22234916687,-0.125000923872,5.92115545273 -9.23935985565,-0.124996058643,5.97174024582 -9.2193775177,-0.124983966351,5.99931049347 -9.23038959503,-0.124978028238,6.04589939117 -9.2243976593,-0.123972669244,6.06268215179 -9.22741127014,-0.123964987695,6.10526037216 -9.21842765808,-0.123954840004,6.14082765579 -9.21344280243,-0.123945787549,6.17741394043 -9.20545864105,-0.123935759068,6.21398019791 -9.21447086334,-0.12392911315,6.26155662537 -9.19548988342,-0.123917087913,6.29012870789 -9.20949363708,-0.122915707529,6.31992578506 -9.20350837708,-0.122906371951,6.35651063919 -9.19952392578,-0.122896917164,6.39707183838 -9.19353866577,-0.122887596488,6.43366003036 -9.20055198669,-0.122880622745,6.48024272919 -9.1815700531,-0.122868381441,6.50980997086 -9.19657421112,-0.122867070138,6.54160165787 -9.19458961487,-0.121858343482,6.58218431473 -9.18860530853,-0.121848486364,6.62174940109 -9.17462253571,-0.121837325394,6.6543264389 -9.18663406372,-0.121831201017,6.70590829849 -9.18065071106,-0.121821388602,6.74547815323 -9.18365764618,-0.121817924082,6.76827764511 -9.17367458344,-0.120807357132,6.80485010147 -9.18068695068,-0.120800234377,6.85343265533 -9.16370582581,-0.120788089931,6.88599395752 -9.16971969604,-0.120780676603,6.93457269669 -9.15373706818,-0.120769061148,6.96615314484 -9.15775108337,-0.120761215687,7.01373052597 -9.16875648499,-0.119759045541,7.04452133179 -9.14277648926,-0.119745358825,7.06909608841 -9.05081176758,-0.12071826309,7.04463815689 -9.02083396912,-0.120703630149,7.06620740891 -9.0338602066,-0.120688728988,7.16636419296 -8.96289157867,-0.120665870607,7.1559214592 -8.91590976715,-0.120652101934,7.14169502258 -8.88593196869,-0.121637485921,7.16227006912 -8.88394737244,-0.120628081262,7.20683765411 -8.88196372986,-0.120618894696,7.25041627884 -8.87697982788,-0.120609253645,7.29100084305 -8.87899398804,-0.120600767434,7.33857679367 -8.92799758911,-0.119601801038,7.42417287827 -9.04297924042,-0.118620298803,7.54199171066 -9.13498783112,-0.116621151567,7.71218061447 -9.12800502777,-0.116610832512,7.75475406647 -9.1180229187,-0.11660002172,7.79433250427 -9.11203956604,-0.116589725018,7.83889961243 -9.11706161499,-0.115577563643,7.91527748108 -9.12107563019,-0.115569271147,7.96884918213 -9.11309337616,-0.115558713675,8.01142501831 -9.26607227325,-0.113580577075,8.19404888153 -9.19310474396,-0.114556990564,8.18060874939 -9.20711708069,-0.113550908864,8.2431936264 -9.22112178802,-0.113549247384,8.28098773956 -9.22913551331,-0.112541660666,8.34055900574 -9.21715354919,-0.11253028363,8.38113498688 -9.23916339874,-0.112525708973,8.45272064209 -9.21420097351,-0.112502552569,8.53486919403 -9.21121692657,-0.11149276793,8.58544158936 -9.21422386169,-0.111488908529,8.61423492432 -9.20924091339,-0.111478805542,8.6628112793 -9.21825408936,-0.110471561551,8.72439479828 -9.20827198029,-0.110460400581,8.76896858215 -9.19129276276,-0.110447734594,8.80753803253 -9.18031024933,-0.110436409712,8.85111522675 -9.3103017807,-0.108449056745,9.05751991272 -9.1713514328,-0.109411552548,8.98005390167 -9.1783657074,-0.109403863549,9.04163837433 -9.07942199707,-0.109365209937,9.05676364899 -9.03345012665,-0.110346578062,9.06732845306 -9.03245735168,-0.109341755509,9.09411811829 -9.03647232056,-0.109333209693,9.15469360352 -9.17645359039,-0.107352495193,9.35131263733 -9.03150558472,-0.109313614666,9.26284885406 -9.00556850433,-0.108275532722,9.43836116791 -8.99660301208,-0.107255019248,9.54551792145 -8.99761962891,-0.107245899737,9.60510063171 -8.99963474274,-0.106236897409,9.66667842865 -8.97965717316,-0.106223225594,9.70624351501 -8.9046831131,-0.107203200459,9.65601444244 -8.80374240875,-0.107163734734,9.66614818573 -8.75777053833,-0.108144894242,9.67571735382 -8.698802948,-0.108123138547,9.67227172852 -8.69881916046,-0.108113706112,9.73185348511 -8.69083690643,-0.107102543116,9.78343009949 -8.70684146881,-0.107101112604,9.8312253952 -8.6978597641,-0.107089802623,9.8818063736 -8.70487499237,-0.106081500649,9.95237731934 -8.93983078003,-0.103120073676,10.2810173035 -8.93884754181,-0.103110514581,10.3426046371 -8.93386554718,-0.10209980607,10.402176857 -8.94087219238,-0.102096401155,10.4429664612 -8.93588924408,-0.102085769176,10.5025424957 -8.93890571594,-0.101076878607,10.5711269379 -8.91592884064,-0.101062491536,10.6106967926 -8.91894340515,-0.101053409278,10.6812734604 -8.91196250916,-0.10004235059,10.7398519516 -8.91297912598,-0.100032918155,10.8084316254 -8.91598701477,-0.100028529763,10.8472137451 -8.91400337219,-0.099018484354,10.9127950668 -8.90302371979,-0.0990065261722,10.9683704376 -8.93203258514,-0.0980027988553,11.0729570389 -8.97603797913,-0.097002081573,11.1975450516 -3.42754721642,-0.165846988559,4.38654327393 -3.39757561684,-0.16583058238,4.37710475922 -3.41458034515,-0.165829226375,4.41190481186 -3.39960384369,-0.165816217661,4.42048311234 -8.86915969849,-0.0959264561534,11.4582033157 -8.85518074036,-0.0959136039019,11.5147705078 -8.85419750214,-0.0959037020802,11.5863542557 -8.84721660614,-0.0948923900723,11.6519289017 -8.86022090912,-0.0948900878429,11.7067193985 -8.85024166107,-0.0938781425357,11.7692937851 -8.84525966644,-0.0938673466444,11.8378753662 -8.83128070831,-0.0938546285033,11.8954515457 -8.83329772949,-0.0928450375795,11.9760255814 -8.81631851196,-0.0928316712379,12.0306005478 -8.8303232193,-0.0918296128511,12.0883951187 -8.82534217834,-0.0918187052011,12.1599731445 -8.82635974884,-0.0918089896441,12.2405529022 -8.80738162994,-0.0907950475812,12.2951231003 -8.80439949036,-0.0907845720649,12.3707046509 -8.79441928864,-0.089772388339,12.4392747879 -8.78943824768,-0.0897615328431,12.5128583908 -8.79844474792,-0.08975828439,12.5676441193 -8.7914648056,-0.0887468978763,12.6402235031 -8.77848529816,-0.0887341573834,12.7057971954 -8.77650260925,-0.0877238214016,12.7863798141 -8.76352500916,-0.0877109542489,12.8539485931 -8.7645406723,-0.0867013037205,12.939535141 -8.7745475769,-0.0866982191801,12.9983224869 -8.76656627655,-0.0856865942478,13.0729017258 -8.75358772278,-0.0856738314033,13.1414775848 -8.74860668182,-0.0846627578139,13.2220563889 -8.7416267395,-0.0846512392163,13.3006343842 -8.73264694214,-0.084639146924,13.3782052994 -8.72166633606,-0.083626806736,13.4517831802 -8.73767185211,-0.0836250707507,13.5215778351 -8.7316904068,-0.0826137438416,13.6041574478 -8.72471046448,-0.0816021040082,13.6867313385 -8.70973205566,-0.0815888419747,13.7573060989 -8.70775032043,-0.0805782452226,13.8488845825 -8.6847743988,-0.0805633962154,13.9074602127 -8.74177646637,-0.0795648619533,14.0950498581 -8.8327589035,-0.0775783210993,14.290851593 -8.79378795624,-0.0775601938367,14.326426506 -8.7788105011,-0.0765467882156,14.4029989243 -8.8048210144,-0.0755418613553,14.5465803146 -8.78384399414,-0.0755274966359,14.6121635437 -8.73787593842,-0.0755077078938,14.6397294998 -8.77288341522,-0.0745045617223,14.8023118973 -8.78088951111,-0.073501162231,14.8671073914 -8.68793487549,-0.0744717046618,14.8166637421 -8.77792644501,-0.0724798813462,15.075261116 -8.75694942474,-0.071465305984,15.1468372345 -8.67099285126,-0.0724372416735,15.1083946228 -8.71199989319,-0.0714353770018,15.287984848 -8.76099491119,-0.0704401433468,15.4297780991 -8.73901844025,-0.0694254413247,15.5013599396 -8.65905952454,-0.0703986659646,15.4729223251 -8.70606422424,-0.0683978572488,15.670507431 -8.72107791901,-0.0673904940486,15.8130865097 -8.7011013031,-0.0673760697246,15.8926639557 -8.60914611816,-0.0673468634486,15.8422269821 -8.67813587189,-0.0663557946682,16.0270290375 -8.68215274811,-0.0653461068869,16.1546058655 -8.62918663025,-0.0653248205781,16.1771736145 -8.55722522736,-0.065299667418,16.1637401581 -8.51725482941,-0.0652811154723,16.2093143463 -8.53226947784,-0.0642736181617,16.3618927002 -8.51929092407,-0.0632605776191,16.4604721069 -8.54329299927,-0.0622602440417,16.5692653656 -8.52531719208,-0.0622460395098,16.6618404388 -8.52133655548,-0.0612347126007,16.7824172974 -8.50436019897,-0.0602207966149,16.8779964447 -8.49937915802,-0.0602093078196,16.9985771179 -8.48440170288,-0.0591956526041,17.1021499634 -8.50440597534,-0.0581943951547,17.209941864 -8.4894285202,-0.0571807511151,17.3155136108 -8.48644733429,-0.0561696663499,17.4450969696 -8.46747207642,-0.0561551488936,17.5456695557 -11.459608078,-0.000753215630539,23.8887271881 -11.3786497116,-0.00172590045258,23.9122886658 -10.6118936539,-0.0135593544692,22.4887504578 -11.2247219086,-0.00167837319896,23.8776302338 -11.1257686615,-0.0026474876795,23.8601913452 -11.0468111038,-0.00262050307356,23.8877506256 -10.9558553696,-0.00259129540063,23.8853168488 -10.6809549332,-0.00652462989092,23.4828491211 -10.525018692,-0.00848222058266,23.333404541 -10.5120401382,-0.00646867137402,23.5009765625 -10.4640645981,-0.00745355477557,23.4917583466 -9.9332408905,-0.0153351398185,22.495256424 -9.87627506256,-0.0153128821403,22.5548305511 -9.83030796051,-0.0152927180752,22.6423988342 -10.1142406464,-0.00833928864449,23.4930171967 -10.0162887573,-0.00830860249698,23.4675807953 -9.97031116486,-0.0082939285785,23.4603652954 -9.87835788727,-0.0092643937096,23.4489269257 -9.79839992523,-0.00923738256097,23.4634933472 -9.70244789124,-0.00920710805804,23.4400558472 -9.62148952484,-0.00917988549918,23.4516239166 -9.53153514862,-0.010150782764,23.4421863556 -9.44757938385,-0.0101229511201,23.4457511902 -9.39160633087,-0.0101062739268,23.4115371704 -9.31364822388,-0.0110796066001,23.4301013947 -9.22369384766,-0.0110506564379,23.4156703949 -9.14573574066,-0.011024014093,23.4332351685 -9.05178356171,-0.0109941931441,23.4088020325 -8.97082614899,-0.0119669288397,23.4183654785 -8.88087272644,-0.0119380168617,23.4009361267 -8.83489608765,-0.0119231920689,23.3927154541 -8.74694156647,-0.0128947440535,23.3782863617 -8.66498565674,-0.0128673287109,23.3828525543 -8.58003044128,-0.0128393881023,23.3774223328 -8.49807453156,-0.0128119895235,23.3809890747 -8.40812110901,-0.013782969676,23.3625545502 -8.33016300201,-0.013756532222,23.3731269836 -8.28218746185,-0.01374147553,23.3539123535 -8.20023155212,-0.0137141095474,23.3554782867 -8.11027812958,-0.0146851828322,23.3330459595 -8.03731918335,-0.0146597158164,23.3576183319 -7.94536733627,-0.0146303046495,23.3301811218 -7.86341190338,-0.0146030560136,23.327753067 -7.81943464279,-0.0145888328552,23.3175373077 -7.73847913742,-0.0155617576092,23.318107605 -7.65452384949,-0.0155340693891,23.309677124 -7.576567173,-0.015507617034,23.3182468414 -7.48861408234,-0.0154791744426,23.2958164215 -4.10767173767,-0.100794397295,12.9749498367 -4.06870365143,-0.100776217878,12.9915313721 -4.05471849442,-0.1007681638,13.0183191299 -7.20276975632,-0.016384087503,23.2803115845 -7.12481355667,-0.0163578409702,23.2828884125 -7.03985977173,-0.0173299498856,23.2684555054 -6.95890378952,-0.0173030905426,23.2610301971 -6.88394641876,-0.017277373001,23.27460289 -6.83597135544,-0.0172623749822,23.2473869324 -6.75901508331,-0.0172362215817,23.2549571991 -6.67406082153,-0.0182084999979,23.2345294952 -6.59910392761,-0.0181827694178,23.2481021881 -6.51814842224,-0.0181558504701,23.2406730652 -6.44119262695,-0.0181298013777,23.2452468872 -6.35723829269,-0.0181024316698,23.2228221893 -6.31826019287,-0.0180893298239,23.2226085663 -6.23830509186,-0.0190626364201,23.2171783447 -6.1563501358,-0.0190355591476,23.2037506104 -6.07939434052,-0.0190095622092,23.206325531 -6.00343799591,-0.0189837943763,23.2118988037 -5.92048311234,-0.0199566781521,23.1894741058 -5.84352779388,-0.0199306029826,23.1940422058 -5.80255079269,-0.0199171677232,23.1838302612 -5.72359514236,-0.0198908727616,23.1754055023 -5.64363956451,-0.0198644082993,23.1619815826 -5.56968307495,-0.0198390316218,23.1755542755 -5.48872852325,-0.0208123903722,23.1571292877 -5.41377162933,-0.02078695409,23.1627063751 -5.3358168602,-0.020760813728,23.1592769623 -5.29383993149,-0.0207472369075,23.1420650482 -5.214884758,-0.0207210071385,23.1306400299 -5.14192771912,-0.0206960961223,23.1412200928 -5.06097364426,-0.0216694399714,23.1217918396 -5.03300189972,-0.0196532774717,23.3403759003 -5.01003026962,-0.0176379308105,23.593952179 -5.02503538132,-0.0156355164945,23.8447475433 -3.21362352371,-0.0822721719742,15.5451335907 -3.15066385269,-0.0832493826747,15.4867095947 -3.09370207787,-0.0832279250026,15.4522924423 -3.04273891449,-0.0832075104117,15.4498701096 -3.00077271461,-0.0831889659166,15.4904537201 -2.95280861855,-0.0831690207124,15.507027626 -2.9218287468,-0.0831578522921,15.4748182297 -2.8768632412,-0.0831387788057,15.5004024506 -2.84289479256,-0.0821217000484,15.5899829865 -2.79193162918,-0.0821013376117,15.5885601044 -4.79132318497,0.00952306576073,27.1073513031 -4.76235246658,0.0115394880995,27.4449329376 -4.77935743332,0.0145415477455,27.7957286835 -4.75038719177,0.0175580084324,28.1573066711 -4.72141695023,0.0205742754042,28.5228900909 -4.68844795227,0.023591471836,28.8864707947 -4.656478405,0.0266083516181,29.2640533447 -4.62350940704,0.0296255294234,29.6566333771 -4.59153985977,0.0326424539089,30.0682144165 -4.60154724121,0.0356459766626,30.4530067444 -4.56957769394,0.0386628955603,30.8945865631 -4.60258817673,0.0456673763692,31.7981739044 -4.57461738586,0.0496835485101,32.3177566528 -4.53465080261,0.0537019707263,32.7723388672 -4.49468374252,0.056720353663,33.2459220886 -4.45471668243,0.0607387796044,33.7455024719 -4.46372461319,0.0647425055504,34.2262916565 -4.41476011276,0.0687625259161,34.6898765564 -4.31681203842,0.0687919333577,34.7944526672 -4.33482694626,0.0777993649244,35.8560371399 -4.28986167908,0.0818186029792,36.4346199036 -4.24289751053,0.0868382304907,37.0282020569 -2.63042783737,-0.0188464261591,23.7066707611 -2.58645224571,-0.0198329016566,23.6484622955 -2.50949716568,-0.0198079645634,23.6280441284 -2.43554162979,-0.019783494994,23.6436214447 -2.36158561707,-0.0197592563927,23.6452064514 -3.98409342766,0.11794629693,40.9948997498 -3.92313337326,0.122968487442,41.7234802246 -3.92514324188,0.128973484039,42.4542770386 -3.84318971634,0.133999526501,43.0288581848 -3.81921815872,0.144014745951,44.3214416504 -3.73926401138,0.149040445685,45.0450210571 -3.6683075428,0.156064406037,45.9326057434 -3.59735059738,0.164088279009,46.881187439 -3.51839637756,0.171113729477,47.822769165 -3.51440811157,0.179119795561,48.8035621643 -3.43345451355,0.187145486474,49.85414505 -3.34650301933,0.195172324777,50.9237251282 -3.2615506649,0.205198690295,52.1133079529 -3.17060017586,0.214226171374,53.3398895264 -3.02066874504,0.217264488339,53.6594696045 -3.10265302658,0.240254610777,56.6632652283 -3.10867190361,0.268264085054,60.2008552551 -2.92275166512,0.26930898428,60.2764358521 -1.66717064381,0.0855508819222,37.0059623718 -1.54922890663,0.0855828672647,36.9685440063 -1.42828822136,0.0846153274179,36.8421287537 -1.32234275341,0.0866449996829,37.1167106628 -0.17091730237,0.109955593944,40.0575637817 -0.0459777787328,0.110988080502,40.2011528015 --0.422817647457,0.608099043369,58.0340385437 --0.5137783885,0.608120262623,58.0228309631 --0.696699678898,0.609162926674,58.0904197693 --0.887618243694,0.616206884384,58.6140060425 --1.69729912281,0.761380553246,68.8977661133 --2.21669745445,0.141668438911,24.5822086334 --2.28865408897,0.140690103173,24.526802063 --2.35861086845,0.139711484313,24.4453926086 --2.44656229019,0.140735909343,24.5489845276 --9.76607513428,0.867058098316,75.6924667358 --9.99798107147,0.86610430479,75.6150741577 --10.2328882217,0.866150915623,75.5636749268 --10.4697933197,0.866197645664,75.5302734375 --10.7136974335,0.866245448589,75.541885376 --9.96091270447,0.77012604475,68.6944503784 --10.0358791351,0.767142057419,68.4582519531 --10.2447929382,0.766183912754,68.3828659058 --10.260638237,0.636237800121,58.9878425598 --9.76230049133,0.349325329065,38.1317405701 --11.3627681732,0.424588173628,43.2410469055 --15.2385540009,0.628197133541,57.2309379578 --15.1265802383,0.617182135582,56.4537277222 --15.0595817566,0.604176461697,55.5073280334 --15.1155462265,0.598189890385,55.0279312134 --15.2934732437,0.598222076893,54.9965438843 --8.19663715363,0.221133470535,29.1516017914 --8.29158782959,0.222155168653,29.1372051239 --15.846247673,0.600320577621,54.9703979492 --14.6725988388,0.537143111229,50.6051025391 --14.7815475464,0.53416454792,50.3877105713 --14.9224863052,0.533190727234,50.2823257446 --15.076420784,0.533218741417,50.2239456177 --14.6295213699,0.497160315514,47.6461029053 --14.7904539108,0.497189313173,47.6357192993 --9.87194824219,0.262449800968,31.6380996704 --9.92791175842,0.260464608669,31.4687004089 --9.99687194824,0.258481383324,31.3423023224 --10.0918245316,0.258501946926,31.2989063263 --10.1967725754,0.258523881435,31.289516449 --10.3247156143,0.260549157858,31.3461227417 --10.416677475,0.262565970421,31.4569282532 --10.5516176224,0.263592153788,31.5315380096 --14.1824407578,0.402149915695,40.661277771 --11.5452222824,0.284768044949,32.7756233215 --13.8984994888,0.382115364075,39.2506484985 --13.8704900742,0.375116020441,38.7832489014 --13.7954950333,0.367109805346,38.1958427429 --13.8904485703,0.366128355265,38.0824508667 --13.9834022522,0.365146517754,37.9650611877 --13.7424573898,0.351116359234,36.9526367188 --13.7754297256,0.347125828266,36.688243866 --13.6984443665,0.342117041349,36.3110351562 --13.684431076,0.337119758129,35.9306335449 --13.6694173813,0.332122296095,35.5552330017 --13.6524047852,0.32712456584,35.1798324585 --13.6343927383,0.322126686573,34.808429718 --13.6173791885,0.317128926516,34.4460258484 --13.5493917465,0.313121587038,34.1168212891 --13.5313796997,0.308123737574,33.7604141235 --13.5063686371,0.30312487483,33.3930168152 --13.491355896,0.299127399921,33.0576133728 --13.4723443985,0.294129401445,32.7152099609 --13.4553318024,0.290131658316,32.383808136 --13.4423179626,0.286134421825,32.0684089661 --13.376329422,0.28112757206,31.770198822 --13.3593168259,0.277129799128,31.4538002014 --13.3413038254,0.273131966591,31.1373958588 --13.327290535,0.269134610891,30.8379974365 --13.3182764053,0.265137970448,30.5515956879 --13.3052635193,0.262140750885,30.2621955872 --13.2892494202,0.258143156767,29.9677906036 --13.2312583923,0.254137516022,29.7105827332 --13.219244957,0.250140458345,29.4351844788 --13.2022323608,0.247142717242,29.1507797241 --13.1942176819,0.243146181107,28.890378952 --13.1782054901,0.240148544312,28.6179790497 --13.1681909561,0.236151739955,28.359577179 --13.1131982803,0.233146622777,28.1253700256 --13.1031837463,0.230149820447,27.8739681244 --13.091170311,0.227152734995,27.6225681305 --13.0781574249,0.223155513406,27.3711624146 --13.0711421967,0.220159068704,27.136762619 --13.0601291656,0.21716208756,26.8973617554 --13.0501146317,0.214165255427,26.6619586945 --12.9971208572,0.211160540581,26.4467487335 --12.9951047897,0.209164708853,26.2353534698 --12.9950876236,0.206169173121,26.0279521942 --9.07921600342,0.0806628540158,18.0430355072 --9.09319400787,0.0796707570553,17.9296321869 --9.12716579437,0.0786812603474,17.8562316895 --9.17513275146,0.0786935165524,17.8108329773 --9.19411849976,0.0786988958716,17.7806396484 --9.24708557129,0.0787117630243,17.7442398071 --9.30904865265,0.0787256509066,17.7268447876 --9.40600299835,0.079743988812,17.7744541168 --9.46296882629,0.0797571316361,17.7460575104 --9.56692028046,0.0817761421204,17.8056678772 --12.8279676437,0.17719168961,23.7859249115 --12.8519439697,0.176199033856,23.6525287628 --12.9389019012,0.176214277744,23.634141922 --13.0098648071,0.176227450371,23.5857486725 --13.0878257751,0.176241382957,23.5513591766 --13.2187709808,0.178261816502,23.6109790802 --13.3107280731,0.178277283907,23.6005935669 --13.3647041321,0.179285988212,23.6084003448 --13.4586610794,0.179301545024,23.6010150909 --13.5506181717,0.180316746235,23.5896320343 --13.6475744247,0.18033246696,23.5862464905 --13.7305345535,0.181346386671,23.5578613281 --13.8394880295,0.181363359094,23.5734786987 --13.9224481583,0.182377070189,23.5450935364 --13.822467804,0.178366839886,23.2908744812 --13.830450058,0.176371455193,23.1384792328 --13.9324045181,0.177387326956,23.1420936584 --12.6547517776,0.140238523483,20.8694896698 --14.0193490982,0.175404801965,22.9583110809 --12.4997625351,0.133228510618,20.3216609955 --12.6547107697,0.136248886585,20.50248909 --12.8096513748,0.138271257281,20.6071109772 --14.4101829529,0.179462820292,23.0209712982 --12.9355831146,0.138293966651,20.5203342438 --13.0355386734,0.139309510589,20.5349502563 --13.2564601898,0.143338963389,20.7375850677 --12.8255653381,0.130293041468,19.9231109619 --13.3504104614,0.14335539937,20.6679992676 --13.3413972855,0.141358032823,20.511598587 --13.3593759537,0.140363737941,20.3982028961 --13.4973220825,0.142383053899,20.4678268433 --15.5427360535,0.192618012428,23.411781311 --15.6536903381,0.193633064628,23.4184036255 --13.0294046402,0.125341102481,19.3565483093 --13.161359787,0.128357797861,19.4843654633 --13.1653442383,0.127361878753,19.3579673767 --13.1883220673,0.126368045807,19.2615718842 --12.8444013596,0.11633361131,18.6321125031 --13.2772655487,0.125385016203,19.1307888031 --13.1982727051,0.121379867196,18.8893737793 --13.2762432098,0.123390160501,18.9371891022 --13.4401826859,0.125411495566,19.0428180695 --13.1682415009,0.117385454476,18.5313663483 --13.11024189,0.114382699132,18.3269577026 --13.0402460098,0.111378677189,18.1085472107 --13.0072402954,0.109378695488,17.9421386719 --12.800280571,0.10336022079,17.5386981964 --12.7602834702,0.101357765496,17.4264945984 --12.4403553009,0.0923275724053,16.8770370483 --12.3753576279,0.0903245508671,16.676618576 --12.5033063889,0.0913417339325,16.7382411957 --12.1523866653,0.0823088809848,16.1607761383 --12.1853618622,0.0813161581755,16.0983810425 --12.2733230591,0.0823290497065,16.108997345 --12.326300621,0.0833363756537,16.1258087158 --8.89321041107,0.00298812706023,11.5477695465 --8.90419101715,0.00199470669031,11.4863672256 --8.94116306305,0.00200396729633,11.4579658508 --8.9611415863,0.00201140576974,11.4085645676 --9.00911140442,0.00202154088765,11.3961753845 --12.4641714096,0.0793722867966,15.6794290543 --12.4771604538,0.0793753862381,15.6442279816 --12.5861158371,0.0803896933794,15.679851532 --12.639087677,0.0803983733058,15.6444625854 --12.7080535889,0.0814086049795,15.6270704269 --12.7480278015,0.081415861845,15.5756797791 --12.7880020142,0.0804230570793,15.5242881775 --12.9009656906,0.0824356377125,15.6111097336 --12.9369411469,0.0824423059821,15.5547189713 --12.8479499817,0.0794370025396,15.3472967148 --13.1048669815,0.0844646468759,15.5549497604 --13.2048273087,0.0854771584272,15.5735702515 --13.2468013763,0.0854840949178,15.5231790543 --13.3257656097,0.0854944363236,15.5157938004 --13.2127876282,0.0824853181839,15.3355741501 --13.3917264938,0.0855048596859,15.4442100525 --13.4067087173,0.0845090597868,15.3628139496 --13.4186916351,0.0845129564404,15.2784147263 --13.6586151123,0.0885375887156,15.4530649185 --13.7775707245,0.089550986886,15.4886903763 --13.2366952896,0.0775048211217,14.7841749191 --13.572602272,0.0835363566875,15.1130504608 --13.7025547028,0.085550583899,15.1606760025 --15.1781625748,0.115683883429,16.6926002502 --15.0431842804,0.11167370528,16.4381694794 --14.1513986588,0.0915973931551,15.3625745773 --15.758975029,0.123739413917,17.0055351257 --12.0229129791,0.0454176738858,12.8793106079 --12.0189065933,0.0454190038145,12.8341093063 --12.0058946609,0.0444212369621,12.7387037277 --12.0228757858,0.0434260368347,12.6753034592 --12.0248603821,0.0434295162559,12.5969018936 --12.0988273621,0.0434390120208,12.5945186615 --12.1607971191,0.0444474108517,12.5791311264 --12.1407957077,0.0434473566711,12.5179233551 --12.1377811432,0.0424502417445,12.4365262985 --12.1367683411,0.0414533391595,12.3561220169 --12.1357536316,0.0404564030468,12.2767210007 --12.1307401657,0.040459100157,12.194319725 --12.1297254562,0.0394621305168,12.1159172058 --12.1297111511,0.0384652428329,12.0385131836 --12.1047105789,0.0374647602439,11.9763116837 --12.1056966782,0.0364679321647,11.9009084702 --12.101682663,0.0364706739783,11.8215065002 --12.0976705551,0.0354733839631,11.743106842 --12.1106529236,0.0344774313271,11.6807060242 --12.1116380692,0.0344805158675,11.6073036194 --12.0986280441,0.0334824770689,11.521903038 --12.0856237411,0.0324829816818,11.4726982117 --12.0896081924,0.0314862653613,11.4032964706 --12.0965929031,0.0314897112548,11.3378992081 --12.0975790024,0.0304927174002,11.266497612 --12.0905666351,0.0294951144606,11.1880931854 --12.0925521851,0.0294981505722,11.1186914444 --12.0965366364,0.028501316905,11.0512895584 --12.083533287,0.0285018086433,11.0040855408 --12.0745220184,0.0275039710104,10.9266881943 --12.072508812,0.026506697759,10.8542814255 --12.0804929733,0.0265100840479,10.7918796539 --12.0534858704,0.0245109666139,10.6994762421 --12.0874633789,0.0245161056519,10.6610822678 --12.0304632187,0.0235149487853,10.5426673889 --12.0094614029,0.02251489833,10.4904613495 --12.0104484558,0.0215177312493,10.4240598679 --12.0114345551,0.0215205606073,10.3576564789 --12.0534114838,0.0215260758996,10.3272657394 --12.0573968887,0.0205290000886,10.2648687363 --12.0283899307,0.0195297561586,10.1744613647 --12.0283823013,0.019531102851,10.1412582397 --12.0203714371,0.0185332465917,10.068854332 --12.0153598785,0.0185355320573,10.0004558563 --12.0153455734,0.0175381805748,9.93505001068 --12.0123329163,0.0165405757725,9.86864948273 --12.0133199692,0.0165432300419,9.80524730682 --12.0023088455,0.0155451092869,9.73284339905 --11.9903039932,0.0155456867069,9.69063472748 --11.9922914505,0.01454831101,9.63024139404 --11.9892787933,0.0145506681874,9.56483650208 --11.977268219,0.0135524841025,9.49242973328 --11.9772548676,0.0125549538061,9.43103122711 --11.9822406769,0.0125577421859,9.3726272583 --11.9742298126,0.0115597266704,9.30522537231 --11.9672241211,0.0115605564788,9.26902198792 --11.9302196503,0.0105609018356,9.17961120605 --11.922208786,0.00956288445741,9.11320972443 --11.9201955795,0.00856522656977,9.05080318451 --11.913184166,0.00856721866876,8.98640441895 --11.9451646805,0.00857132486999,8.95101070404 --11.9541501999,0.00757413962856,8.89861297607 --12.0691184998,0.00958134327084,8.95544528961 --12.1070976257,0.00958555936813,8.92405319214 --5.52652692795,-0.105753734708,3.99999594688 --5.51851129532,-0.105747684836,3.96658349037 --5.52749204636,-0.105740852654,3.94618058205 --11.9700641632,0.0055896230042,8.53100967407 --11.9630584717,0.00459039118141,8.49680328369 --11.9600467682,0.00459241773933,8.43740177155 --11.9510364532,0.00359414657578,8.37399768829 --11.9520235062,0.00359634519555,8.31759357452 --11.9440126419,0.00259810779244,8.25518798828 --11.9499988556,0.00260045565665,8.20379161835 --11.941988945,0.00160217273515,8.14238929749 --11.926984787,0.00160254398361,8.1041841507 --11.9199743271,0.000604304077569,8.04378032684 --11.9249610901,0.000606545538176,7.99238300323 --11.9109516144,-0.000391989917262,7.92697095871 --11.8849449158,-0.00139104947448,7.85455989838 --11.8459405899,-0.00239067012444,7.77515363693 --11.8249387741,-0.00239050202072,7.73394489288 --11.8199281693,-0.00338867516257,7.67653942108 --11.8109169006,-0.00338703184389,7.61713504791 --11.814904213,-0.00438490789384,7.56673669815 --11.8158912659,-0.0043829139322,7.51433610916 --11.8188791275,-0.00538088660687,7.46393966675 --11.8058691025,-0.00537943048403,7.40253067017 --11.7968654633,-0.00637879269198,7.3703250885 --11.7938547134,-0.00637699430808,7.31592082977 --11.7968406677,-0.00637500593439,7.26551818848 --11.78383255,-0.00737361377105,7.20611667633 --11.7918186188,-0.00737151689827,7.159719944 --11.7908067703,-0.00836972333491,7.10731554031 --11.7927942276,-0.00836785323918,7.05691146851 --11.7767925262,-0.00836747232825,7.02170562744 --11.768781662,-0.0093659600243,6.96630430222 --11.7647705078,-0.00936431437731,6.9128985405 --11.7657585144,-0.0103625655174,6.86350107193 --11.7657470703,-0.0103608490899,6.81309890747 --11.7617359161,-0.0103592704982,6.7606959343 --11.7607250214,-0.011357627809,6.71029472351 --11.7467212677,-0.0113571695983,6.67708730698 --11.7437105179,-0.0123555958271,6.62568426132 --11.7406997681,-0.0123540656641,6.57528734207 --11.742688179,-0.0123523948714,6.52688360214 --11.7426757812,-0.0133507959545,6.47747850418 --11.7406654358,-0.0133492965251,6.42808103561 --11.7346553802,-0.0133478762582,6.3756737709 --11.7626447678,-0.0133464727551,6.36647891998 --11.8026256561,-0.0133441211656,6.340092659 --11.8386068344,-0.0123419128358,6.31069850922 --11.8625917435,-0.0123400390148,6.27530670166 --11.926568985,-0.0123374359682,6.26092433929 --11.8135786057,-0.0143382670358,6.15248632431 --11.8675632477,-0.0133366091177,6.15730524063 --12.1794967651,-0.00932981818914,6.27300596237 --12.2284765244,-0.00832793489099,6.24861431122 --12.2514619827,-0.00832660030574,6.21222829819 --12.3024435043,-0.0083248661831,6.18884038925 --12.2954339981,-0.00832407735288,6.13543128967 --12.2754268646,-0.00932350754738,6.07702875137 --12.197435379,-0.0103241428733,6.01380586624 --12.3264026642,-0.00832158792764,6.02944421768 --12.3163938522,-0.00932093709707,5.97604227066 --12.3123836517,-0.00932020880282,5.92463159561 --12.2743701935,-0.0103191323578,5.80981779099 --12.2733602524,-0.0113184237853,5.76141643524 --12.2593574524,-0.0113182011992,5.73121404648 --12.2673463821,-0.011317438446,5.68681097031 --12.3103284836,-0.0113164708018,5.65942382812 --12.2653255463,-0.01231615711,5.59100866318 --18.4562911987,0.0837182477117,8.40173435211 --14.8068885803,0.0266971662641,6.66007184982 --14.7498903275,0.0256955511868,6.57765436172 --14.6758975983,0.0236946120858,6.51643228531 --14.6009025574,0.0226930454373,6.42600059509 --14.5219078064,0.0206916071475,6.33658218384 --14.454911232,0.0196902249008,6.25115346909 --14.3849153519,0.0186889544129,6.16673564911 --14.3169174194,0.0166877284646,6.08230733871 --14.24792099,0.0156865958124,5.99888324738 --14.1689291,0.0146861299872,5.93865823746 --14.0849351883,0.0126851880923,5.85023117065 --14.0299358368,0.0116842612624,5.77481412888 --13.9729366302,0.0106833837926,5.69839143753 --13.8879413605,0.00868269614875,5.61095809937 --13.8539400101,0.00868184585124,5.54554605484 --11.6282682419,-0.0253055281937,4.59135961533 --11.6052675247,-0.026305032894,4.56115579605 --11.6052570343,-0.0263043213636,4.51875734329 --11.6122465134,-0.026303678751,4.47835350037 --11.6032381058,-0.0273029338568,4.43194580078 --11.6022291183,-0.0273022893816,4.3895483017 --11.6182165146,-0.0273018348962,4.3531498909 --11.6062088013,-0.0273011252284,4.3067483902 --11.5852069855,-0.0283005964011,4.27753925323 --11.6081943512,-0.0273003112525,4.24414491653 --11.5831890106,-0.0282994545996,4.19273376465 --11.5871782303,-0.028298990801,4.15233278275 --11.5971679688,-0.0282986462116,4.11393165588 --11.5761613846,-0.029297856614,4.06452131271 --11.5841503143,-0.0292975436896,4.02612495422 --11.5811452866,-0.0292972773314,4.00391864777 --11.571138382,-0.0292966999114,3.95951867104 --11.5731287003,-0.0292963422835,3.91810965538 --11.5871181488,-0.0292962640524,3.88272190094 --11.5661115646,-0.0302955079824,3.83330225945 --11.5631027222,-0.030295137316,3.79190516472 --11.556098938,-0.0302948355675,3.76869773865 --11.5480899811,-0.0312943719327,3.72529411316 --11.5450820923,-0.0312940441072,3.68389415741 --11.5550718307,-0.0312940478325,3.64649534225 --11.4730730057,-0.0322917960584,3.57906007767 --11.4200716019,-0.033290181309,3.52163600922 --11.4340610504,-0.0332902930677,3.48624038696 --11.4110584259,-0.0342895537615,3.45903086662 --11.4070501328,-0.0342892073095,3.4176235199 --11.4200401306,-0.0342893749475,3.38222956657 --11.4040327072,-0.0342887304723,3.3378226757 --11.4060239792,-0.0342886336148,3.29841661453 --11.4070148468,-0.0342885367572,3.25901269913 --11.3750104904,-0.0352874100208,3.21060299873 --11.3960037231,-0.0352880395949,3.19741272926 --11.3829956055,-0.0352875366807,3.1540017128 --11.3919868469,-0.0352877937257,3.11760473251 --11.3929777145,-0.0352878123522,3.07819700241 --11.3909692764,-0.0362877473235,3.03879642487 --11.3949604034,-0.036287933588,3.00140070915 --11.3919534683,-0.0362878888845,2.96099042892 --11.3909492493,-0.0362878926098,2.94179415703 --11.3749427795,-0.0362873747945,2.89838218689 --11.3639345169,-0.0372870527208,2.85697793961 --11.3709259033,-0.0372874774039,2.82058238983 --11.3769168854,-0.0372879058123,2.78317809105 --11.3719100952,-0.0372878983617,2.74377799034 --11.3908996582,-0.0372889637947,2.70937561989 --11.3548994064,-0.0372875072062,2.68115997314 --11.3248939514,-0.0382864102721,2.6357486248 --11.341884613,-0.0382874570787,2.60134887695 --11.3678741455,-0.0382889769971,2.56996250153 --11.395863533,-0.037290673703,2.53857302666 --11.4388513565,-0.0372931808233,2.51018571854 --11.4648456573,-0.0362946949899,2.49699425697 --11.4868354797,-0.0362963192165,2.46360039711 --11.5478219986,-0.0352999977767,2.43922591209 --11.4168272018,-0.0372938476503,2.3717713356 --11.4288187027,-0.0372950434685,2.336373806 --11.6577825546,-0.0343088172376,2.30866122246 --11.680773735,-0.0343109890819,2.27426290512 --11.7197656631,-0.0343136377633,2.26307940483 --11.7587566376,-0.0333168357611,2.23269820213 --11.7877473831,-0.0333195775747,2.19930505753 --11.8207378387,-0.0333226323128,2.16691708565 --11.8477277756,-0.0323254391551,2.13251972198 --11.8947181702,-0.0323295108974,2.10314464569 --11.9257087708,-0.0313327349722,2.06975483894 --11.9507045746,-0.0313349813223,2.05456233025 --11.9866943359,-0.0313386581838,2.0221786499 --12.0176858902,-0.0303421486169,1.98778307438 --12.0576763153,-0.0303462967277,1.95539808273 --12.0916690826,-0.0293501466513,1.92201256752 --12.1276597977,-0.02935423702,1.88862669468 --12.158654213,-0.0293572265655,1.8734331131 --12.1966457367,-0.0283616259694,1.84004795551 --12.228638649,-0.0283657051623,1.80566227436 --12.2686300278,-0.0273704472929,1.77227890491 --12.3006219864,-0.0273747593164,1.73688685894 --12.331615448,-0.0273790825158,1.70149767399 --12.3716077805,-0.0263841152191,1.66812062263 --12.4016027451,-0.0263874642551,1.65192759037 --12.5025911331,-0.0243972726166,1.6265733242 --12.5695829391,-0.0234047695994,1.59519827366 --12.614575386,-0.0234107207507,1.56081783772 --12.6775665283,-0.0224182102829,1.52844393253 --12.7165603638,-0.0224240012467,1.49205458164 --12.7575531006,-0.0214300025254,1.45667564869 --12.7915496826,-0.021434141323,1.44049108028 --12.828543663,-0.0204400904477,1.40309941769 --12.8715372086,-0.0204466115683,1.36671555042 --12.9115314484,-0.019452964887,1.33033585548 --12.9545259476,-0.0194597002119,1.29395675659 --12.9885196686,-0.0184658486396,1.25556600094 --13.0295143127,-0.018472680822,1.21818304062 --13.0635118484,-0.0174773037434,1.20099902153 --13.1035070419,-0.0174842048436,1.16362047195 --13.1435022354,-0.0164912920445,1.12523424625 --13.1894960403,-0.016499074176,1.08684790134 --13.2384910583,-0.0155071811751,1.04947221279 --13.2704877853,-0.015513879247,1.01008713245 --13.2644844055,-0.0155171900988,0.966679513454 --13.349480629,-0.014527015388,0.953525781631 --13.3914775848,-0.0135349901393,0.914142727852 --13.2924785614,-0.0155295459554,0.863698005676 --12.149515152,-0.0314227081835,0.735782146454 --12.0685148239,-0.0324175879359,0.691345691681 --13.5174646378,-0.0115640005097,0.751595616341 --13.5424623489,-0.0115708634257,0.710207223892 --12.0945034027,-0.0324272699654,0.596349179745 --13.6684560776,-0.00959041062742,0.652659952641 --12.2294921875,-0.0304470378906,0.526603102684 --12.1554918289,-0.0314424410462,0.484173387289 --12.3994817734,-0.0274711437523,0.457882463932 --11.9934883118,-0.0334314703941,0.399299263954 --12.1434822083,-0.0314506031573,0.366956859827 --12.0604820251,-0.0324432067573,0.344725042582 --12.2504749298,-0.0304670464247,0.313404887915 --11.9214782715,-0.0344342440367,0.262857675552 --11.9274740219,-0.034438021481,0.224451228976 --12.3084659576,-0.0294838082045,0.198225930333 --12.4734611511,-0.0275060199201,0.163903698325 --12.1044626236,-0.032467648387,0.115331269801 --12.0174617767,-0.0334593728185,0.0940896719694 --11.9434604645,-0.034454125911,0.0546556264162 --11.9824571609,-0.0334620028734,0.0172709804028 --12.1654520035,-0.031486980617,-0.0180419813842 --12.8134479523,-0.0225680209696,-0.0511502400041 --12.0344486237,-0.0334785915911,-0.0969137102365 --13.3404445648,-0.0146383391693,-0.108495309949 --12.254445076,-0.030510796234,-0.153409436345 --12.0344419479,-0.0334875546396,-0.191912323236 --11.9524402618,-0.0344810932875,-0.23035864532 --12.83644104,-0.0215956456959,-0.274338692427 --11.9064340591,-0.0354826115072,-0.30618801713 --11.8434324265,-0.0354781709611,-0.342614173889 --11.9334316254,-0.0344915315509,-0.362772315741 --11.821428299,-0.0364808440208,-0.399233520031 --11.8684263229,-0.0354906432331,-0.437611222267 --11.8274240494,-0.0364889800549,-0.474029451609 --11.8384218216,-0.0354942604899,-0.512431800365 --11.8174200058,-0.0364952087402,-0.548837423325 --11.8684186935,-0.0355059616268,-0.588215827942 --11.703414917,-0.0374855324626,-0.601498961449 --12.0024185181,-0.0335302427411,-0.649751603603 --12.1944217682,-0.030560977757,-0.696061968803 --12.0994176865,-0.0325522758067,-0.73151910305 --12.8324365616,-0.0216597076505,-0.804557323456 --11.9154109955,-0.0345349013805,-0.798404753208 --12.0974149704,-0.0325652435422,-0.846722900867 --12.156416893,-0.0315759256482,-0.868890941143 --12.0004110336,-0.0335579365492,-0.898368537426 --12.6274299622,-0.0246539767832,-0.975461304188 --12.5254278183,-0.0256443414837,-1.00992178917 --12.1414136887,-0.0315925106406,-1.02351200581 --12.019408226,-0.0335789658129,-1.05296814442 --12.1044111252,-0.0315965563059,-1.09833478928 --12.0204076767,-0.0325861535966,-1.11057019234 --11.9524049759,-0.0335805788636,-1.14401042461 --12.0964107513,-0.0316075049341,-1.19434309006 --12.2434167862,-0.0296352803707,-1.24567186832 --16.2636108398,0.0257298368961,-1.64304673672 --12.9734544754,-0.0197608340532,-1.39110672474 --16.3996315002,0.0276876669377,-1.75977194309 --12.2174167633,-0.0296494495124,-1.38008832932 --16.5426502228,0.0306486729532,-1.85329973698 --16.6076641083,0.0316273458302,-1.91266179085 --16.669675827,0.0326063074172,-1.97202444077 --16.725687027,0.0325859822333,-2.03139138222 --16.8037014008,0.0345617644489,-2.09374833107 --16.8547134399,0.0345416665077,-2.15412306786 --16.9197235107,0.035525072366,-2.18828415871 --17.0027389526,0.0374990962446,-2.25364589691 --17.0577526093,0.0374778471887,-2.31501364708 --17.1317672729,0.0394530743361,-2.37937283516 --17.2067813873,0.0404280051589,-2.44372677803 --17.2647972107,0.0414054691792,-2.50709486008 --17.3348140717,0.042380604893,-2.57245588303 --17.4208259583,0.0433592498302,-2.6116039753 --17.4738407135,0.0443368330598,-2.67597746849 --17.5478610992,0.0453105382621,-2.74333643913 --17.5948753357,0.046288959682,-2.80670619011 --17.5848865509,0.046277474612,-2.86210799217 --17.7389125824,0.0482359938323,-2.94241976738 --14.7606611252,0.00677631003782,-2.50719928741 --14.7826700211,0.00676253018901,-2.55858635902 --14.7356739044,0.00676147220656,-2.59901070595 --14.459654808,0.00280360132456,-2.60055065155 --13.8766069412,-0.00509571377188,-2.54925942421 --13.8376083374,-0.00609705690295,-2.58767867088 --13.8536167145,-0.00510901212692,-2.63607430458 --13.9646310806,-0.00413478398696,-2.67821383476 --13.9976406097,-0.00315021234564,-2.72959423065 --13.8836355209,-0.00513726519421,-2.7550599575 --13.7596292496,-0.00612201774493,-2.77752733231 --13.8376426697,-0.00514653511345,-2.83788919449 --13.8296489716,-0.00515401177108,-2.88128900528 --13.8996629715,-0.0041773179546,-2.94065260887 --14.1726970673,-0.000237015614402,-3.01770615578 --13.8906726837,-0.00418956112117,-3.00725507736 --13.6396503448,-0.0071478090249,-3.00179123878 --13.5936527252,-0.00814754143357,-3.03721570969 --13.4606428146,-0.0101293390617,-3.05469322205 --13.3246335983,-0.0111100925133,-3.07016777992 --13.1026115417,-0.0140724033117,-3.06568598747 --13.158624649,-0.014093044214,-3.12206029892 --13.2416391373,-0.0121150193736,-3.16221356392 --13.1696367264,-0.0131085962057,-3.18965005875 --13.1176357269,-0.0141064990312,-3.22208333015 --13.0416326523,-0.0150991026312,-3.24852848053 --13.20566082,-0.0121437581256,-3.33083987236 --13.1396589279,-0.0131385391578,-3.35927677155 --13.2066717148,-0.0121578769758,-3.3974404335 --13.1306676865,-0.0131503371522,-3.42287993431 --13.1356754303,-0.0131607716903,-3.46827816963 --13.1136798859,-0.0131651666015,-3.50668859482 --12.9836683273,-0.0151453036815,-3.51816391945 --13.1126947403,-0.0131839988753,-3.59549570084 --12.9276742935,-0.015151114203,-3.59099411964 --13.3097362518,-0.0102436672896,-3.71398925781 --13.4957733154,-0.00729657150805,-3.80828356743 --13.2857484818,-0.0102581167594,-3.79780340195 --13.4127779007,-0.00829783640802,-3.87712860107 --13.4207878113,-0.00731020048261,-3.92552947998 --13.5518188477,-0.00535170920193,-4.00785541534 --13.4478111267,-0.00733751058578,-4.02431058884 --13.3798046112,-0.00732667557895,-4.02855396271 --13.3848152161,-0.00733849033713,-4.07595252991 --13.612862587,-0.00440444471315,-4.18822288513 --13.3968353271,-0.00736290682107,-4.17174911499 --13.4868602753,-0.00539571465924,-4.24409294128 --13.6729040146,-0.00245292950422,-4.34739351273 --13.6659135818,-0.00246269581839,-4.39279985428 --13.6989250183,-0.00247677927837,-4.42698431015 --13.7339429855,-0.0014969407348,-4.48435592651 --13.7449560165,-0.00151152780745,-4.53575181961 --13.7029590607,-0.00151267007459,-4.5701751709 --13.6889686584,-0.00152123312,-4.61459255219 --14.220082283,0.0063302507624,-4.83368015289 --14.5531616211,0.0112309539691,-4.99289035797 --17.3127174377,0.051506370306,-5.9274930954 --17.1927127838,0.0495198592544,-5.94795751572 --17.39777565,0.0534476451576,-6.07824087143 --17.4708099365,0.0544101260602,-6.16358947754 --17.4388256073,0.0543998144567,-6.21500968933 --17.417842865,0.0543867647648,-6.26941871643 --17.5388908386,0.0563355796039,-6.37273931503 --17.6369228363,0.0582993589342,-6.43888282776 --17.674955368,0.0582696609199,-6.51525783539 --17.7549953461,0.0602283626795,-6.60660409927 --17.5399703979,0.0572679080069,-6.59212875366 --17.3719577789,0.0552949644625,-6.59362649918 --17.2859592438,0.0542996674776,-6.6240735054 --17.2539768219,0.0542892925441,-6.67449092865 --17.210975647,0.0532916560769,-6.68971633911 --17.2220039368,0.0542691461742,-6.75610733032 --17.5381011963,0.0591595098376,-6.93931627274 --17.3520812988,0.0561928078532,-6.93082141876 --17.3441028595,0.0561750084162,-6.99122571945 --17.3341255188,0.0571577958763,-7.05062961578 --17.2591304779,0.056159555912,-7.08407068253 --17.2131309509,0.0551629662514,-7.09729671478 --17.2171573639,0.0561417266726,-7.16168928146 --17.1751708984,0.0551338270307,-7.20811223984 --17.1531906128,0.0551199987531,-7.26252317429 --17.1182079315,0.0551098957658,-7.31194496155 --17.0902252197,0.0550979450345,-7.36335659027 --17.0712432861,0.055083155632,-7.41876459122 --17.062253952,0.0550754927099,-7.44696998596 --17.0562782288,0.0550564862788,-7.50837278366 --21.3124580383,0.119724147022,-9.40216827393 --21.072429657,0.115769892931,-9.37770748138 --21.2375125885,0.118689991534,-9.52899932861 --21.2615566254,0.119653597474,-9.61937713623 --21.127538681,0.117681011558,-9.60065841675 --21.2536125183,0.120612114668,-9.73697471619 --21.819814682,0.129402399063,-10.0730190277 --21.0276260376,0.117625460029,-9.79590129852 --21.0856819153,0.119577623904,-9.90225696564 --22.3690986633,0.139132335782,-10.5758523941 --21.467874527,0.125393778086,-10.2418060303 --21.994052887,0.134206369519,-10.5296773911 --21.3108901978,0.124399401248,-10.2914915085 --21.0208415985,0.120464593172,-10.2360668182 --20.8178215027,0.117501698434,-10.2205896378 --20.77384758,0.117486447096,-10.2800092697 --20.9059276581,0.119411893189,-10.4253196716 --20.9209747314,0.120376132429,-10.5147047043 --20.8379688263,0.119388855994,-10.514954567 --20.7929954529,0.119373522699,-10.5743761063 --20.8090438843,0.120337046683,-10.6647615433 --21.0741710663,0.124214440584,-10.8809890747 --20.966178894,0.12322025001,-10.9094495773 --20.9502182007,0.123194023967,-10.9848537445 --24.7565422058,0.182825922966,-13.033823967 --26.5281715393,0.210182204843,-14.0018892288 --26.4682102203,0.2101598382,-14.0773181915 --26.4262580872,0.210131198168,-14.1617336273 --26.6353931427,0.214012667537,-14.3789863586 --26.5684337616,0.213992223144,-14.4514188766 --39.7251548767,0.419180214405,-21.6453323364 --39.7602729797,0.42109566927,-21.8256835938 --24.7539424896,0.187543481588,-13.7335586548 --24.6839733124,0.186528041959,-13.7959909439 --24.6640262604,0.187493935227,-13.8863935471 --22.0701274872,0.147416263819,-12.5434598923 --22.6974658966,0.15810701251,-13.0818405151 --22.6334953308,0.158093258739,-13.1392707825 --25.1374759674,0.197124779224,-14.6178426743 --25.2205696106,0.199049189687,-14.7711782455 --24.3512973785,0.186338201165,-14.373134613 --24.446395874,0.188258886337,-14.5314626694 --24.343416214,0.187255486846,-14.574921608 --22.5967845917,0.160893380642,-13.6434545517 --22.9799957275,0.167703554034,-13.9685964584 --38.155128479,0.409716188908,-23.1048069 --23.0591125488,0.169611170888,-14.1641311646 --24.1166057587,0.187149450183,-14.9058265686 --37.8633422852,0.408608317375,-23.41913414 --23.3504753113,0.177326917648,-14.7445039749 --35.467666626,0.373356372118,-22.4168567657 --35.4407081604,0.373331815004,-22.4780654907 --35.0296401978,0.367429703474,-22.3737163544 --23.5847969055,0.18307889998,-15.2527189255 --35.05286026,0.37027874589,-22.6984634399 --35.2030334473,0.374145030975,-22.9507408142 --34.8930015564,0.370202690363,-22.9073295593 --34.8340873718,0.370156019926,-23.0247478485 --34.8861618042,0.371097713709,-23.1379051208 --35.1433868408,0.376915931702,-23.4651107788 --34.835357666,0.372974157333,-23.4197006226 --34.4733009338,0.368056476116,-23.3363246918 --34.5124320984,0.369967073202,-23.5196762085 --34.5625648499,0.371872037649,-23.7120246887 --34.3175048828,0.367941766977,-23.6253833771 --34.7788352966,0.376666307449,-24.0994491577 --34.1726608276,0.367858678102,-23.8422393799 --34.1937789917,0.369775563478,-24.0156059265 --33.997795105,0.367788165808,-24.0391197205 --33.7938117981,0.365805029869,-24.0556430817 --35.5978164673,0.396917194128,-25.4937915802 --35.5828666687,0.396884530783,-25.5669898987 --34.0272140503,0.372512221336,-24.6224346161 --33.5660934448,0.36564707756,-24.4521312714 --33.4041290283,0.364646047354,-24.4956226349 --33.3502159119,0.364595025778,-24.6180438995 --33.5024108887,0.368448406458,-24.8913211823 --33.4024772644,0.368418633938,-24.9797706604 --33.2544555664,0.366449743509,-24.9510631561 --32.8273506165,0.360573768616,-24.7957420349 --32.9265174866,0.363450944424,-25.0310535431 --32.8816108704,0.364395081997,-25.1604690552 --32.598575592,0.360453903675,-25.10704422 --32.3285484314,0.357507020235,-25.0626144409 --32.123550415,0.354529231787,-25.0671405792 --32.2716941833,0.358419150114,-25.2622280121 --34.1008262634,0.390447705984,-26.8513393402 --34.133972168,0.393348813057,-27.0496959686 --33.968006134,0.391347050667,-27.0931949615 --33.6269416809,0.38743314147,-26.9958152771 --33.7541427612,0.390286177397,-27.27110672 --33.6312026978,0.390263974667,-27.346572876 --33.5862426758,0.390244454145,-27.3977966309 --33.4632987976,0.389222115278,-27.4732666016 --30.9819755554,0.346401840448,-25.618391037 --33.3695106506,0.390100568533,-27.7470932007 --31.1903419495,0.353137791157,-26.1180114746 --31.1644477844,0.35407140851,-26.2624149323 --31.2416229248,0.356950521469,-26.4947471619 --31.2386817932,0.357911705971,-26.5759391785 --31.2648239136,0.359816759825,-26.7663040161 --31.1368713379,0.358802348375,-26.8267784119 --31.0069198608,0.357789129019,-26.8852558136 --30.9169902802,0.357754737139,-26.9777030945 --30.8750934601,0.358694851398,-27.1111183167 --30.5560188293,0.353783845901,-27.0037307739 --30.4600219727,0.352794826031,-27.0039920807 --30.2510166168,0.350825577974,-26.9905261993 --30.1120548248,0.349819034338,-27.0370121002 --30.4524078369,0.357548892498,-27.5111522675 --31.4091701508,0.376934468746,-28.5448493958 --30.4446678162,0.360383778811,-27.8509273529 --30.4938335419,0.363270789385,-28.0702762604 --30.3928337097,0.362284600735,-28.0655403137 --29.9516716003,0.355446815491,-27.8372459412 --29.6916294098,0.352509081364,-27.7708187103 --29.660741806,0.353441298008,-27.9162273407 --29.7709522247,0.356292009354,-28.1945323944 --30.2724380493,0.367915630341,-28.8435535431 --30.1745109558,0.367883443832,-28.9310092926 --30.4317626953,0.372688531876,-29.2670154572 --30.3958797455,0.374619096518,-29.4154262543 --29.6054573059,0.360993236303,-28.838388443 --29.3554172516,0.358052790165,-28.7749557495 --29.5907287598,0.36382317543,-29.1851711273 --29.6138896942,0.365718662739,-29.3905391693 --30.3374938965,0.38123819232,-30.1952018738 --29.4139595032,0.364702373743,-29.4682636261 --30.0826034546,0.379204422235,-30.3191585541 --30.1317901611,0.382079511881,-30.5585079193 --30.0338687897,0.382043987513,-30.6509647369 --29.0953044891,0.365528136492,-29.8890457153 --28.6380996704,0.358719855547,-29.6067657471 --28.8924446106,0.365467697382,-30.0549659729 --28.8154582977,0.364469587803,-30.0682144165 --27.947927475,0.349922567606,-29.3552455902 --27.8349838257,0.348902970552,-29.419713974 --27.8751621246,0.35178476572,-29.6470737457 --27.8022518158,0.351738601923,-29.7555160522 --27.2389450073,0.343008995056,-29.3413238525 --27.7534370422,0.353629887104,-29.9831314087 --27.5864505768,0.352644175291,-29.991645813 --27.133228302,0.344846874475,-29.688369751 --27.0062713623,0.343837231398,-29.7358531952 --27.6839904785,0.359293669462,-30.6667366028 --27.1536979675,0.350550323725,-30.273519516 --26.6143932343,0.341816335917,-29.8643112183 --26.4343147278,0.338890165091,-29.7576408386 --26.362405777,0.339844584465,-29.8640842438 --26.3095092773,0.340785741806,-29.9925136566 --26.21758461,0.340753346682,-30.0769729614 --26.398897171,0.345532476902,-30.4742240906 --26.4220752716,0.348418861628,-30.6935977936 --26.355173111,0.349367231131,-30.8100376129 --27.924659729,0.382221281528,-32.7290458679 --27.7917098999,0.382209151983,-32.7805290222 --27.2904243469,0.373457252979,-32.3992996216 --26.8021469116,0.365699648857,-32.0270614624 --26.2558078766,0.355986773968,-31.579864502 --26.1568813324,0.355956017971,-31.6613273621 --26.062959671,0.355921059847,-31.7497901917 --27.2761859894,0.38298869133,-33.3180580139 --25.9130706787,0.35587516427,-31.8714904785 --24.8271980286,0.334570020437,-30.7427082062 --23.8243942261,0.315211594105,-29.7018661499 --24.5812835693,0.333551883698,-30.8316764832 --23.588476181,0.314194589853,-29.7878303528 --24.5055370331,0.335406601429,-31.132516861 --23.3084335327,0.310260474682,-29.7206306458 --24.5988807678,0.341182202101,-31.5510311127 --24.3007488251,0.336305737495,-31.3736534119 --24.1197338104,0.334341257811,-31.3431835175 --22.6544075012,0.304371923208,-29.6477050781 --22.7256393433,0.308218747377,-29.9320430756 --22.4944801331,0.303349971771,-29.7264194489 --24.6819210052,0.354531675577,-32.7991218567 --23.9753551483,0.340981125832,-32.0750579834 --22.3478088379,0.307168662548,-30.1137123108 --22.2248420715,0.306167006493,-30.1442012787 --21.7504959106,0.297448396683,-29.6999607086 --21.9458694458,0.304190427065,-30.1602039337 --21.6497135162,0.2993298769,-29.953830719 --21.6167602539,0.299307376146,-30.0050506592 --22.0684242249,0.311834067106,-30.8270931244 --22.0405654907,0.313752025366,-30.9925098419 --22.0026950836,0.314678221941,-31.1439342499 --21.3321113586,0.301134884357,-30.4038505554 --21.9499835968,0.318509250879,-31.4827613831 --21.3583946228,0.304957032204,-30.7434215546 --21.2224121094,0.304966956377,-30.7539253235 --21.4418411255,0.311672657728,-31.2761459351 --20.782245636,0.298134416342,-30.5260601044 --20.6612758636,0.298133969307,-30.5535507202 --20.5923671722,0.298088401556,-30.6569976807 --20.5735206604,0.299998313189,-30.8354091644 --20.5886287689,0.301930814981,-30.9625968933 --20.3044624329,0.297075033188,-30.7462177277 --20.8322849274,0.312495201826,-31.7501926422 --20.6152019501,0.309578835964,-31.6357593536 --21.0058727264,0.321112632751,-32.448841095 --20.8638877869,0.320125937462,-32.4533538818 --20.8030014038,0.321066230536,-32.5807952881 --20.9582939148,0.326864987612,-32.9338684082 --20.5960273743,0.320082426071,-32.5935554504 --20.6352710724,0.323928594589,-32.8799171448 --20.6014232635,0.32484164834,-33.0533409119 --15.9795589447,0.210096642375,-25.8884296417 --15.8825826645,0.210097238421,-25.9119052887 --19.9381465912,0.316113620996,-32.6730575562 --19.8130779266,0.314173877239,-32.5843582153 --22.0813407898,0.375855386257,-36.5329322815 --21.8562602997,0.37293857336,-36.4195098877 --21.70728302,0.371949493885,-36.4280204773 --21.4361343384,0.368080943823,-36.232635498 --21.2681293488,0.366111904383,-36.2071647644 --21.2762527466,0.368035882711,-36.3493537903 --21.4216880798,0.374751776457,-36.8576316833 --21.319776535,0.374714374542,-36.9481086731 --21.0426158905,0.370856136084,-36.7347335815 --21.3512973785,0.382398247719,-37.5378723145 --21.1682739258,0.380442738533,-37.4894180298 --20.9932575226,0.37848007679,-37.4529571533 --20.9413032532,0.378461390734,-37.4981956482 --14.9986686707,0.217577204108,-27.1454219818 --14.9197225571,0.217557102442,-27.2038898468 --13.6800088882,0.185779333115,-25.1522941589 --13.6010465622,0.185768812895,-25.1937599182 --16.5998439789,0.27242064476,-30.9057197571 --16.4998931885,0.272408604622,-30.9512023926 --16.4398994446,0.272413432598,-30.9554519653 --20.778963089,0.399499595165,-39.3332977295 --20.7141284943,0.401412278414,-39.5087471008 --20.0052566528,0.384046643972,-38.4567260742 --20.4372234344,0.400402098894,-39.5797653198 --13.2737693787,0.193387493491,-26.0190505981 --13.1527423859,0.191422253847,-25.9835529327 --13.0696897507,0.190466552973,-25.9198226929 --12.9967422485,0.190447211266,-25.9762859344 --14.0066232681,0.223163589835,-28.1858558655 --14.1089887619,0.228928521276,-28.6101741791 --12.5424919128,0.184668332338,-25.6698684692 --12.4194545746,0.182711005211,-25.6203708649 --12.382566452,0.184649974108,-25.7478065491 --12.3075218201,0.182688266039,-25.6940689087 --12.226556778,0.182680547237,-25.7305393219 --12.1736412048,0.18363879621,-25.8249855042 --12.0706377029,0.183658048511,-25.8154754639 --5.45073795319,-0.0241957642138,-11.9342813492 --5.36164665222,-0.0261285416782,-11.8397665024 --12.7143907547,0.211511746049,-27.8421535492 --12.6714134216,0.211505755782,-27.8643932343 --12.5113134384,0.20959071815,-27.742931366 --12.4473962784,0.209552749991,-27.8313865662 --12.375462532,0.210525274277,-27.9018516541 --13.3846311569,0.247074782848,-30.4044132233 --17.9678459167,0.402864456177,-41.0429725647 --17.9780254364,0.405756860971,-41.2401618958 --17.817029953,0.403782069683,-41.2237014771 --17.7161521912,0.404728204012,-41.3421821594 --17.5551567078,0.403754025698,-41.3247184753 --17.340045929,0.400856822729,-41.1752967834 --17.306306839,0.404708981514,-41.4547271729 --12.539683342,0.242187067866,-30.3931484222 --12.5297842026,0.243129760027,-30.5033588409 --12.429816246,0.243127822876,-30.5308494568 --12.3979930878,0.245029464364,-30.7232780457 --12.387219429,0.247897997499,-30.9726924896 --10.1475763321,0.171011015773,-25.6629867554 --11.9647979736,0.240218475461,-30.4718589783 --11.8999071121,0.241165786982,-30.5863208771 --9.95968055725,0.170981496572,-25.7711601257 --9.43570423126,0.154644072056,-24.6580085754 --9.32365322113,0.15269331634,-24.5965118408 --9.23164367676,0.152714386582,-24.5829944611 --9.14464759827,0.151726856828,-24.5844764709 --9.07869911194,0.152707770467,-24.6399402618 --8.99771690369,0.152710959315,-24.6574192047 --8.9567232132,0.151714459062,-24.6626529694 --8.90380954742,0.152672842145,-24.7571086884 --7.92562294006,0.117122858763,-22.2893447876 --7.3704366684,0.0979134365916,-20.9532184601 --7.30445480347,0.0979138612747,-20.9746875763 --7.69863796234,0.116152174771,-22.3057613373 --7.1103272438,0.0950214266777,-20.8336677551 --7.08736228943,0.0960045680404,-20.8738975525 --7.00433206558,0.0950362384319,-20.841375351 --6.95639467239,0.096007540822,-20.9128265381 --6.89542245865,0.0960014685988,-20.9452877045 --6.84648370743,0.0959739238024,-21.0147380829 --6.82862997055,0.097891189158,-21.1791610718 --6.77066898346,0.098878197372,-21.2236213684 --6.73065900803,0.0988909304142,-21.2128620148 --6.63659572601,0.0969440788031,-21.1433486938 --6.29081392288,0.0844604074955,-20.2760543823 --6.23284626007,0.0844515711069,-20.3135185242 --6.16986036301,0.0844541192055,-20.3309803009 --6.10486984253,0.0844596624374,-20.3434467316 --6.10497140884,0.0864003747702,-20.4566516876 --6.1944475174,0.0931067839265,-20.9849872589 --6.1184296608,0.0931303650141,-20.966463089 --6.027364254,0.0911840870976,-20.8959503174 --5.95736598969,0.091195628047,-20.8984260559 --5.88134288788,0.0902220085263,-20.8748970032 --6.22968435287,0.111379735172,-22.3510112762 --5.84668397903,0.0950296223164,-21.2517547607 --6.244099617,0.117135547101,-22.8066177368 --6.12696266174,0.114235788584,-22.656129837 --6.06099414825,0.11522949487,-22.6895961761 --6.00205278397,0.11520601809,-22.7530612946 --5.95314359665,0.116162128747,-22.8515110016 --5.9694685936,0.120970405638,-23.2059135437 --5.9495344162,0.121935836971,-23.2771377563 --5.79324913025,0.117129668593,-22.9646816254 --5.73932933807,0.118092924356,-23.0511398315 --7.71589326859,0.232350662351,-31.277841568 --5.78406572342,0.128658398986,-23.8489265442 --5.71510076523,0.129650622606,-23.8853969574 --5.65015363693,0.129631951451,-23.940864563 --5.60613775253,0.129649549723,-23.9221115112 --5.70985746384,0.140214174986,-24.6994361877 --5.51439809799,0.132515892386,-24.2000141144 --5.31089448929,0.1248447299,-23.6536045074 --5.15657806396,0.120056353509,-23.3101520538 --5.11070489883,0.121991612017,-23.4456062317 --5.05278110504,0.122958511114,-23.5260658264 --4.9002904892,0.115270078182,-22.9974021912 --4.82930755615,0.115273416042,-23.0148792267 --4.7382349968,0.113332077861,-22.9363746643 --4.66624498367,0.113339982927,-22.945848465 --4.59927797318,0.1143335253,-22.9803218842 --4.50719356537,0.112399607897,-22.8888130188 --4.4241476059,0.111441493034,-22.8392982483 --4.42934942245,0.114324323833,-23.0545024872 --5.23163175583,0.176706850529,-27.6252250671 --5.14866399765,0.176704525948,-27.653711319 --4.26665401459,0.11817996949,-23.3758907318 --4.26603651047,0.123960293829,-23.7813053131 --4.12871313095,0.119172506034,-23.435836792 --4.12811136246,0.123943813145,-23.8572502136 --4.09312963486,0.124940179288,-23.8754920959 --4.05534648895,0.127822726965,-24.1039428711 --3.92403674126,0.123026199639,-23.7734680176 --3.86714553833,0.123974740505,-23.886932373 --3.77505707741,0.123043477535,-23.7914333344 --3.65780830383,0.119209073484,-23.5269489288 --3.54557299614,0.115365825593,-23.2774562836 --3.51461100578,0.116350188851,-23.3166942596 --3.43859744072,0.115372814238,-23.3011760712 --3.37466192245,0.116348445415,-23.367647171 --3.32180523872,0.118276625872,-23.5171146393 --3.2739815712,0.120185174048,-23.7005691528 --3.2040169239,0.121178738773,-23.7360477448 --3.17534828186,0.124994754791,-24.081489563 --3.65307188034,0.177768841386,-27.9792919159 --3.31825137138,0.151877507567,-26.0689964294 --3.23625779152,0.151890456676,-26.0714874268 --2.87508106232,0.121207669377,-23.795211792 --2.8877851963,0.130802631378,-24.5276222229 --1.80447781086,0.0137685183436,-15.8699207306 --1.78249704838,0.013761610724,-15.8931493759 --1.72945475578,0.0127957053483,-15.8556070328 --2.74490976334,0.146189332008,-25.6872119904 --2.67399668694,0.147154271603,-25.77368927 --2.60007214546,0.148126363754,-25.8481788635 --2.55340862274,0.152944132686,-26.1926383972 --2.47544789314,0.152937829494,-26.2291221619 --2.43444633484,0.152947232127,-26.2253665924 --2.3605389595,0.153909727931,-26.3168525696 --2.28259134293,0.154896214604,-26.3663406372 --2.20868802071,0.155856445432,-26.4618244171 --2.13479781151,0.156809419394,-26.5703105927 --2.07204937935,0.160679161549,-26.8247871399 --2.03971219063,0.169308528304,-27.5012359619 --2.8206307888,0.320927321911,-38.7138137817 --1.87015116215,0.161663889885,-26.917011261 --2.60708451271,0.326716125011,-39.1448516846 --1.7576777935,0.182819232345,-28.4671707153 --2.35907411575,0.339208424091,-40.1131286621 --1.58475768566,0.182810723782,-28.5361652374 --2.87286949158,0.555119872093,-56.1758079529 --2.69996881485,0.556102752686,-56.2423934937 --2.55056548119,0.563798189163,-56.8149528503 --2.36542844772,0.560918271542,-56.6405487061 --2.84203362465,0.787383019924,-73.4706420898 --2.60488057137,0.784525036812,-73.2632904053 --2.48270320892,0.781654059887,-73.0576095581 --2.24960851669,0.779762029648,-72.9102478027 --2.02266764641,0.779781579971,-72.9188842773 --1.79472470284,0.779802381992,-72.9255218506 --1.56992161274,0.781743466854,-73.0731582642 --1.34519207478,0.784642755985,-73.2947998047 --1.12046861649,0.787538766861,-73.5224304199 --0.330665081739,0.397061347961,-44.4319801331 --0.191631168127,0.396112710238,-44.3755302429 --0.0536399744451,0.396139711142,-44.3620834351 -0.128430217505,0.422692269087,-43.32995224 -0.197396829724,0.421655446291,-43.3080940247 -0.344489127398,0.438236832619,-44.4293556213 -0.48440092802,0.437150508165,-44.3646316528 -0.61791908741,0.430842459202,-43.9029197693 -0.755824565887,0.429753154516,-43.8311958313 -1.03585970402,0.43070089817,-43.9137496948 -1.09963154793,0.427555024624,-43.6948928833 -2.17593693733,0.698670625687,-62.3319664001 -2.38518619537,0.703759372234,-62.6271781921 -2.57699465752,0.701602697372,-62.4754066467 -3.04455041885,0.755503892899,-66.1585464478 -3.2320702076,0.748184800148,-65.7157821655 -2.29932713509,0.396940559149,-41.5666847229 -2.42825245857,0.39586558938,-41.5119743347 -2.55820465088,0.395805537701,-41.4842643738 -2.67392897606,0.391619861126,-41.2235717773 -2.74601769447,0.39365196228,-41.3247070312 -2.87901544571,0.393617421389,-41.3439941406 -3.18835663795,0.428869575262,-43.7690963745 -4.93480443954,0.736046135426,-64.8076934814 -5.14378929138,0.736986577511,-64.8379058838 -3.79682374001,0.437983453274,-44.3461761475 -5.6455206871,0.734711766243,-64.6744766235 -6.11833143234,0.778192400932,-67.6224136353 -6.02004718781,0.729352235794,-64.2759552002 -6.37651491165,0.752099215984,-65.8400192261 -6.40370845795,0.72606742382,-64.0154266357 -6.58847570419,0.722891151905,-63.8196678162 -6.94580459595,0.759126603603,-66.257522583 -7.23545646667,0.769427001476,-66.9816589355 -7.35559463501,0.757909238338,-66.133972168 -7.53326797485,0.753681480885,-65.8412246704 -7.74624061584,0.754615068436,-65.8594436646 -4.8253288269,0.375177711248,-39.9318122864 -4.98757219315,0.379276514053,-40.2060775757 -5.02434635162,0.376139163971,-39.9802513123 -5.15030622482,0.376085788012,-39.9585533142 -5.23899888992,0.371889561415,-39.6568832397 -5.34381055832,0.368757545948,-39.4802093506 -5.53725099564,0.376960813999,-39.96144104 -5.70964717865,0.368576675653,-39.3681182861 -5.77967691422,0.368576735258,-39.4092636108 -5.8925614357,0.36748406291,-39.3075790405 -6.01551866531,0.367430210114,-39.281879425 -6.166639328,0.369462758303,-39.4291572571 -6.31977272034,0.372501820326,-39.5894317627 -6.4779253006,0.375550836325,-39.7706985474 -6.68836641312,0.382751524448,-40.2579231262 -6.66987848282,0.375479012728,-39.752155304 -6.81796503067,0.377492785454,-39.8634338379 -6.96402931213,0.378495126963,-39.9527206421 -6.92611598969,0.364985495806,-39.0031814575 -7.02796268463,0.362874358892,-38.8595046997 -7.15192556381,0.362824350595,-38.8398132324 -7.27991247177,0.363786876202,-38.8451118469 -7.3328499794,0.362739056349,-38.7882728577 -7.46083688736,0.363701701164,-38.7935714722 -7.58379268646,0.363647937775,-38.7658805847 -7.74995803833,0.366703152657,-38.9621505737 -8.13249397278,0.375918477774,-39.5756340027 -8.27753734589,0.376909285784,-39.6419181824 -13.3337173462,0.730324089527,-63.4572944641 -13.6893119812,0.740580797195,-64.1423873901 -13.7255134583,0.729120731354,-63.329788208 -13.8752164841,0.725919246674,-63.0560836792 -14.1092815399,0.727904140949,-63.172290802 -14.3081932068,0.727809667587,-63.1225357056 -6.2108039856,0.192728281021,-27.0994129181 -6.53334712982,0.202961489558,-27.7009525299 -6.64039087296,0.203961506486,-27.7562789917 -6.30139446259,0.171905770898,-25.6054344177 -6.44459962845,0.175988972187,-25.8337249756 -6.4916100502,0.175983965397,-25.8478908539 -7.38216543198,0.218230053782,-28.642911911 -10.00207901,0.364690959454,-38.3728981018 -7.66044187546,0.224323451519,-28.9624996185 -8.18801879883,0.234530836344,-29.626493454 -8.70132064819,0.241586685181,-29.9987163544 -8.78926277161,0.241534084082,-29.9450588226 -8.82119750977,0.240490496159,-29.879240036 -8.90613269806,0.240434631705,-29.8175868988 -8.98906326294,0.239376798272,-29.7509346008 -9.07099151611,0.23931774497,-29.6812839508 -9.15291881561,0.238258272409,-29.6106357574 -9.23484992981,0.237201020122,-29.5439834595 -9.31678104401,0.237143859267,-29.4773330688 -9.35573768616,0.236111402512,-29.4355144501 -9.4336605072,0.236050233245,-29.3588638306 -9.49453544617,0.233965978026,-29.2292327881 -9.60153675079,0.23494336009,-29.240562439 -9.71054649353,0.235924959183,-29.260887146 -18.7997207642,0.646622061729,-56.2660598755 -13.5209207535,0.396399706602,-39.7705078125 -13.6348333359,0.396325677633,-39.6928329468 -13.7718067169,0.396281599998,-39.6841392517 -13.9228124619,0.397253125906,-39.7124328613 -14.8567991257,0.432175129652,-41.9650192261 -19.0719413757,0.608002305031,-53.398651123 -15.0376586914,0.432058423758,-41.8435058594 -19.257648468,0.604798555374,-53.1221351624 -23.4383239746,0.774371623993,-64.072807312 -23.2673149109,0.75884115696,-62.9834060669 -24.2901706696,0.792672812939,-65.1279220581 -25.2568531036,0.8234192729,-67.0815048218 -24.7450523376,0.794513940811,-65.0934066772 -25.0143814087,0.800643622875,-65.4913787842 -26.2867126465,0.843691766262,-68.1866836548 -21.4310817719,0.641158223152,-55.0264663696 -21.5949668884,0.641060173512,-54.9337615967 -21.827003479,0.643033623695,-55.0139884949 -26.0187492371,0.799087882042,-65.0257034302 -22.36652565,0.639658212662,-54.6060447693 -22.5444393158,0.640574336052,-54.546333313 -28.6868991852,0.864316284657,-68.8603363037 -20.9457950592,0.56129527092,-49.3280563354 -29.5128746033,0.870139658451,-68.9979476929 -29.6458568573,0.871104478836,-69.0070495605 -30.2835731506,0.886378645897,-69.8869400024 -28.7639789581,0.823670864105,-65.7967224121 -28.9788703918,0.823568105698,-65.722984314 -23.6334552765,0.605690419674,-51.5506515503 -27.4481925964,0.731702387333,-59.4137649536 -23.8250179291,0.601409137249,-51.1133613586 -24.0340099335,0.602364122868,-51.1396179199 -24.4824352264,0.61251437664,-51.671672821 -24.6585578918,0.615548491478,-51.8327407837 -24.8475074768,0.616483449936,-51.8090171814 -32.815284729,0.874613523483,-67.9525680542 -18.8636341095,0.400027900934,-38.02293396 -18.92045784,0.397918611765,-37.8363189697 -18.9133090973,0.395837545395,-37.6725387573 -18.9711380005,0.39373037219,-37.4899253845 -19.1661987305,0.395726919174,-37.5821914673 -19.4604206085,0.401793986559,-37.8643760681 -30.3030052185,0.737496256828,-58.6485404968 -30.530960083,0.739426910877,-58.6367912292 -35.6017417908,0.890785396099,-67.8929138184 -30.7466812134,0.737232148647,-58.3742790222 -30.9676208496,0.73815703392,-58.3465385437 -31.1925640106,0.739084541798,-58.32579422 -31.4685916901,0.742047309875,-58.4010047913 -31.6604804993,0.741950452328,-58.314289093 -30.0746326447,0.688670635223,-54.9660835266 -30.1323413849,0.685498893261,-54.6594810486 -30.1561908722,0.683411121368,-54.4996833801 -30.3020381927,0.682299971581,-54.3580055237 -30.4679164886,0.68220192194,-54.2523117065 -30.6598339081,0.683120965958,-54.1935997009 -30.8757858276,0.684054553509,-54.1758613586 -31.1327972412,0.686013936996,-54.2300949097 -28.7812023163,0.616461873055,-49.9302902222 -28.8569812775,0.613325595856,-49.6986732483 -28.9988536835,0.61322915554,-49.5800018311 -33.778591156,0.638679802418,-48.8667869568 -33.8794136047,0.637566149235,-48.6831512451 -34.1474342346,0.640529930592,-48.7413864136 -41.9367103577,0.825688540936,-59.1219863892 -42.1135559082,0.824573397636,-58.9753036499 -42.3156089783,0.827566206455,-59.0623703003 -42.3643112183,0.824396073818,-58.7377891541 -42.6582870483,0.826333105564,-58.7560081482 -42.7540435791,0.824184596539,-58.4983901978 -23.5908298492,0.288232922554,-25.8774585724 -23.6537513733,0.287180870771,-25.7828483582 -23.6707019806,0.28715094924,-25.7200527191 -23.7736587524,0.287110596895,-25.6694107056 -23.844587326,0.287060856819,-25.5827960968 -54.8417549133,0.918968439102,-57.5192070007 -51.5318222046,0.846937417984,-53.691192627 -46.8045654297,0.743426203728,-48.1307106018 -44.1992912292,0.686633050442,-45.1501426697 -42.5187606812,0.650087833405,-43.1498718262 -39.4553070068,0.586269378662,-39.8974113464 -38.7935943604,0.570997178555,-38.9763679504 -38.6662979126,0.56585931778,-38.6029167175 -38.545009613,0.560724496841,-38.2384605408 -38.4937705994,0.556608021259,-37.9469528198 -38.3794898987,0.552477657795,-37.5944900513 -38.5734405518,0.553420484066,-37.5487976074 -38.5673408508,0.552367866039,-37.424030304 -38.5891609192,0.550271451473,-37.2094688416 -38.6780357361,0.55019068718,-37.0608520508 -38.7208747864,0.548099577427,-36.867275238 -38.7937431335,0.547016322613,-36.7046737671 -38.9646720886,0.547954320908,-36.6350021362 -38.9915046692,0.546861886978,-36.4294319153 -25.4390163422,0.281965494156,-23.6026954651 -39.2510414124,0.543576359749,-35.8688316345 -25.4876022339,0.276739120483,-23.0554161072 -25.5315227509,0.276689350605,-22.9478263855 -25.6474895477,0.276654452085,-22.9071807861 -25.675453186,0.276631087065,-22.859380722 -24.0953102112,0.245273381472,-21.2999782562 -24.1982784271,0.24624030292,-21.2563381195 -24.4343299866,0.249231263995,-21.3286075592 -24.3361682892,0.24616111815,-21.1071147919 -24.208990097,0.242086529732,-20.8616447449 -17.0673923492,0.107768841088,-14.5382556915 -17.0813694,0.106754854321,-14.5034618378 -17.1273365021,0.106730610132,-14.4508543015 -15.8765029907,0.0834837928414,-13.2901859283 -15.940486908,0.0834654867649,-13.2585706711 -15.7713308334,0.0794086307287,-13.0311183929 -15.8823432922,0.0803984850645,-13.0394706726 -12.2421255112,0.0127916475758,-9.960272789 -8.17465782166,-0.0618815198541,-6.52353525162 -8.19465255737,-0.0618878938258,-6.49694395065 -8.29267692566,-0.0608914159238,-6.49171495438 -8.32968139648,-0.0608951002359,-6.47910737991 -8.34367275238,-0.0609025470912,-6.44652843475 -8.35066890717,-0.0609061382711,-6.43073368073 -8.38467216492,-0.0609103478491,-6.41513252258 -8.40666770935,-0.0609161667526,-6.39053249359 -8.43266677856,-0.0609216243029,-6.36794137955 -8.45666408539,-0.0609272122383,-6.34434556961 -8.47565841675,-0.0609334781766,-6.31675386429 -8.49365234375,-0.0609398819506,-6.28816509247 -8.64973068237,-0.0579233020544,-6.38726615906 -8.56565380096,-0.0599519833922,-6.23816728592 -8.60265827179,-0.0599559023976,-6.22356843948 -8.61965179443,-0.0599623247981,-6.19398260117 -8.64765167236,-0.0599671825767,-6.17338132858 -8.67965221405,-0.0599717199802,-6.15478610992 -8.68664836884,-0.0599750392139,-6.13899278641 -8.71464920044,-0.0599798373878,-6.11838960648 -8.74565029144,-0.0599843002856,-6.09978580475 -8.76564598083,-0.0599902048707,-6.0721988678 -8.78764247894,-0.0599957332015,-6.04660511017 -8.81064033508,-0.0590012520552,-6.02101707458 -8.83164310455,-0.0590029172599,-6.01521444321 -8.84863758087,-0.0590089894831,-5.98562812805 -8.88964271545,-0.0590124726295,-5.97302389145 -8.91063976288,-0.0590178407729,-5.94742155075 -8.94064044952,-0.059022679925,-5.92583560944 -8.97264099121,-0.0590270012617,-5.90723133087 -8.99063682556,-0.0590327456594,-5.87863969803 -9.00363540649,-0.059035256505,-5.86684322357 -9.04764270782,-0.0580386035144,-5.85523986816 -9.06363773346,-0.0580443926156,-5.82564496994 -9.09463787079,-0.0580489598215,-5.80505084991 -9.12363815308,-0.0580536313355,-5.78345346451 -9.21766757965,-0.0570526346564,-5.80480957031 -9.12161159515,-0.0580681152642,-5.7003030777 -9.14961719513,-0.058069229126,-5.69849395752 -9.21163272858,-0.0570711418986,-5.69787740707 -9.23863124847,-0.0570758208632,-5.67527532578 -9.26763153076,-0.0570805370808,-5.65268373489 -13.4724292755,0.0122311376035,-8.26833820343 -13.3593530655,0.0102083543316,-8.13784694672 -12.2348508835,-0.00888638570905,-7.38001203537 -13.2882833481,0.00818246696144,-8.00653457642 -13.186214447,0.00616203714162,-7.88702344894 -12.9580945969,0.00213338714093,-7.69060134888 -13.2531909943,0.00614002719522,-7.81383800507 -13.1871395111,0.00512296846136,-7.71830034256 -13.1130838394,0.00310533493757,-7.61678409576 -13.1440849304,0.0031010855455,-7.60797357559 -13.2240924835,0.00409328937531,-7.59935188293 -13.1830530167,0.00307850097306,-7.51980304718 -13.3250837326,0.00507418857887,-7.54713916779 -13.3950881958,0.00606577517465,-7.53251600266 -13.1449680328,0.00204024487175,-7.33310222626 -13.1669521332,0.00102946767583,-7.29051923752 -13.2799835205,0.00302933831699,-7.3276591301 -13.3279790878,0.00301991170272,-7.30005455017 -13.1708974838,0.00100062729325,-7.1565861702 -13.1678743362,-1.08405474748e-05,-7.10101413727 -13.1808567047,-2.14749379666e-05,-7.05443191528 -13.3378925323,0.00197426998056,-7.08775186539 -13.2598419189,0.000959665921982,-6.99023532867 -13.4519014359,0.00296202325262,-7.06832075119 -13.3468408585,0.000946636137087,-6.9568195343 -13.3528223038,0.000935930234846,-6.90624332428 -13.4078197479,0.00192704075016,-6.88163757324 -13.4888267517,0.00291910138912,-6.8710103035 -13.602845192,0.00391215132549,-6.87736082077 -13.4527721405,0.000896787561942,-6.74588108063 -13.502779007,0.00189305725507,-6.74506282806 -13.5197639465,0.00188290642109,-6.69948673248 -13.5287456512,0.00187281402759,-6.65090703964 -13.5117197037,0.00086215918418,-6.5893445015 -13.5457115173,0.000852932396811,-6.5537481308 -13.5997085571,0.00184402056038,-6.52714586258 -14.113863945,0.00985047314316,-6.75602865219 -13.8557596207,0.00483434461057,-6.57362604141 -14.0858125687,0.00782871432602,-6.63290214539 -13.6766633987,0.00181107840035,-6.38058853149 -13.6976499557,0.00180173583794,-6.33800315857 -13.7326412201,0.00179271888919,-6.30240631104 -13.8236503601,0.00278440420516,-6.2927775383 -13.8556499481,0.00277994433418,-6.28097486496 -13.8006153107,0.00176978227682,-6.20243787766 -13.9056272507,0.00376152899116,-6.19879865646 -13.8355875015,0.00175161648076,-6.11426830292 -13.9405994415,0.00274318782613,-6.10963201523 -13.8855657578,0.00173382461071,-6.03308773041 -14.8628358841,0.0167342219502,-6.44569683075 -14.9548406601,0.0177243240178,-6.43106746674 -14.8237829208,0.0157136265188,-6.31658267975 -14.8827791214,0.0167038664222,-6.28796863556 -14.7207136154,0.0136938523501,-6.16150426865 -14.5566492081,0.0106846541166,-6.03702831268 -14.58963871,0.0106751443818,-5.9964427948 -14.6396436691,0.0116704953834,-5.99162006378 -14.8106689453,0.0136603107676,-6.00894927979 -15.3337879181,0.0216477457434,-6.1730556488 -15.5328187943,0.0236363876611,-6.19936227798 -17.2832489014,0.0506108850241,-6.86071443558 -17.3322353363,0.0505981631577,-6.81711912155 -17.372220993,0.0505857057869,-6.77052354813 -17.4092159271,0.0515792258084,-6.75371694565 -17.4592037201,0.0515665151179,-6.71012067795 -17.5051898956,0.0515540167689,-6.66552114487 -17.5471763611,0.0525415427983,-6.61892604828 -17.5991630554,0.0525287874043,-6.57532978058 -17.6571521759,0.0535160861909,-6.5347237587 -17.6971359253,0.0535037405789,-6.48712778091 -17.7421360016,0.0544970035553,-6.47231769562 -17.798122406,0.0544841997325,-6.42971754074 -17.8421096802,0.0544717796147,-6.38311958313 -17.8960990906,0.0554590523243,-6.33951950073 -17.9450855255,0.0554464533925,-6.29392194748 -17.9920692444,0.0564339011908,-6.24732589722 -18.0340671539,0.0564271211624,-6.23051738739 -18.0830535889,0.0574144460261,-6.18392276764 -18.1390419006,0.057401701808,-6.14031934738 -18.1800251007,0.0583893060684,-6.09072875977 -18.2360153198,0.0583766400814,-6.04712247849 -18.2800006866,0.05836423859,-5.99852800369 -18.3279857635,0.0593516975641,-5.95093154907 -18.3759841919,0.0593446083367,-5.93511962891 -18.4249706268,0.0603320263326,-5.88752269745 -18.4819583893,0.0603190883994,-5.8419251442 -18.5339450836,0.0613064803183,-5.79532337189 -18.5789299011,0.0612940564752,-5.74572992325 -18.6329174042,0.0622813366354,-5.69912910461 -18.6869049072,0.0622684955597,-5.65153312683 -18.7329025269,0.0632613152266,-5.63372373581 -18.7818889618,0.0632488206029,-5.58512401581 -18.8378753662,0.0642360448837,-5.53852033615 -18.8928623199,0.0642230734229,-5.48992776871 -18.9428482056,0.0652106031775,-5.44132518768 -18.9958343506,0.0651977434754,-5.39173269272 -19.0418205261,0.0661854222417,-5.3411359787 -19.0858154297,0.0661781653762,-5.32132911682 -19.1408042908,0.0671653673053,-5.27272796631 -19.1967906952,0.0671525150537,-5.22412776947 -19.2367744446,0.0681404396892,-5.17053794861 -19.3027629852,0.0681270137429,-5.12393331528 -19.3537502289,0.0691144391894,-5.07333517075 -19.4027462006,0.0701067596674,-5.05352735519 -19.4517326355,0.0700942724943,-5.00193071365 -19.5067195892,0.0710814148188,-4.95133256912 -19.5637054443,0.0710683912039,-4.90073537827 -19.6146907806,0.0720558390021,-4.84913635254 -19.6716766357,0.0720428973436,-4.79853630066 -19.735666275,0.0730294510722,-4.74893522263 -19.782661438,0.0740218609571,-4.72812366486 -19.8246440887,0.0740097314119,-4.67253541946 -19.8846321106,0.0749966204166,-4.62193202972 -19.9506187439,0.0749829486012,-4.57133293152 -19.9916038513,0.0759710446,-4.51573944092 -20.0465888977,0.0759581029415,-4.46214580536 -20.125579834,0.0769436657429,-4.41453361511 -20.160572052,0.0779367610812,-4.38972902298 -20.2105579376,0.0779241248965,-4.33413887024 -20.2905464172,0.078909508884,-4.28552818298 -20.3345317841,0.0788974016905,-4.22893619537 -20.3895168304,0.079884506762,-4.1743388176 -20.4575023651,0.0808706283569,-4.12173748016 -20.5164890289,0.0808575451374,-4.06813383102 -20.5604839325,0.0818498283625,-4.04332923889 -20.636472702,0.0828353390098,-3.99172210693 -20.6824569702,0.0828231200576,-3.93412923813 -20.7334423065,0.083810441196,-3.87653827667 -20.8064289093,0.0847962126136,-3.82392907143 -20.8534145355,0.0847838893533,-3.76533889771 -20.9044075012,0.0857756435871,-3.74152612686 -20.9873962402,0.0867604389787,-3.68891763687 -21.0373821259,0.0867478996515,-3.63032460213 -21.0943660736,0.0877348035574,-3.57272791862 -21.1693534851,0.0887202620506,-3.51812028885 -21.2223377228,0.0897074043751,-3.45852994919 -21.2853240967,0.0896937996149,-3.4009308815 -21.3463191986,0.0906845331192,-3.37711429596 -21.3993034363,0.0916717648506,-3.31751918793 -21.4632892609,0.0916580036283,-3.25892162323 -21.5372772217,0.0926434546709,-3.20231366158 -21.5892601013,0.0936306715012,-3.14072537422 -21.6612453461,0.0946162715554,-3.08311843872 -21.7352333069,0.0956015735865,-3.02451634407 -21.7832241058,0.0955932363868,-2.99670934677 -21.8512115479,0.0965790972114,-2.9371073246 -21.9101963043,0.0975658297539,-2.876506567 -21.9791812897,0.0985515341163,-2.8159070015 -22.0321655273,0.0985387563705,-2.75331330299 -22.1151504517,0.099523127079,-2.69370746613 -22.166135788,0.100510530174,-2.6301150322 -22.2401313782,0.101499646902,-2.60429310799 -22.3081169128,0.102485358715,-2.54169535637 -22.3540992737,0.102473281324,-2.47710323334 -22.4020824432,0.103460930288,-2.41151618958 -22.4800662994,0.104445658624,-2.34891438484 -16.3576755524,0.0180405769497,-1.60457324982 -16.4536781311,0.0200297590345,-1.5897333622 -22.7090320587,0.107404157519,-2.19588088989 -22.7780170441,0.108389727771,-2.13128089905 -22.8449993134,0.108375452459,-2.06568479538 -22.9299869537,0.110359407961,-2.00207448006 -22.9859695435,0.110346220434,-1.93448519707 -23.0729541779,0.111329890788,-1.86987662315 -23.1259460449,0.112320706248,-1.83806800842 -23.2059307098,0.113305091858,-1.77246081829 -23.2619132996,0.114291921258,-1.70386958122 -23.0288848877,0.110309414566,-1.61242818832 -22.2208347321,0.0993887409568,-1.47928380966 -22.2338161469,0.0993811041117,-1.41071152687 -22.2278079987,0.0993786081672,-1.37493550777 -9.64332294464,-0.0762608796358,-0.429161310196 -9.64832782745,-0.0762583911419,-0.399580389261 -9.64233207703,-0.0762546285987,-0.369009405375 -9.64033699036,-0.0762512385845,-0.338440299034 -9.64434146881,-0.0762485340238,-0.308859020472 -9.64134502411,-0.0762466415763,-0.294067203999 -9.63034915924,-0.0762421786785,-0.263497024775 -9.63635444641,-0.0762396007776,-0.233916416764 -9.63935947418,-0.0762366726995,-0.204335123301 -9.63236427307,-0.0762325003743,-0.173767074943 -9.63437080383,-0.0762293860316,-0.144185885787 -9.62937545776,-0.0762253403664,-0.113618813455 -9.63137817383,-0.0762238651514,-0.0988282412291 -9.62838363647,-0.0762200951576,-0.0692475810647 -9.61938858032,-0.0772154778242,-0.0386823527515 -9.62439441681,-0.0762125402689,-0.00910089351237 -9.61839962006,-0.0772082954645,0.0204779244959 -9.61740589142,-0.0772044733167,0.0510437861085 -9.62140846252,-0.0772031396627,0.065834954381 -9.62641429901,-0.0762001052499,0.0954170748591 -9.61641979218,-0.0771952345967,0.124993436038 -9.61442661285,-0.0771911591291,0.155558511615 -9.61843204498,-0.0771879032254,0.185140162706 -9.61443805695,-0.0771836340427,0.214718133211 -9.6004447937,-0.0771780759096,0.244290336967 -9.60244750977,-0.077176399529,0.259081065655 -9.60645389557,-0.0771728977561,0.289648801088 -9.59846019745,-0.0771679729223,0.319223076105 -9.60546684265,-0.0771649256349,0.348807156086 -9.60347366333,-0.0771606937051,0.378385215998 -9.59847927094,-0.0771560296416,0.407960802317 -9.59648609161,-0.077151723206,0.437538474798 -9.59348964691,-0.0771492943168,0.452325582504 -9.59449577332,-0.0771451964974,0.48289167881 -9.59850311279,-0.077141597867,0.51247471571 -9.59350967407,-0.0771367698908,0.542049467564 -9.58751583099,-0.0771317631006,0.571622788906 -9.58052349091,-0.0771265700459,0.601194679737 -9.58353042603,-0.0771227180958,0.63077712059 -9.58053398132,-0.0771201550961,0.645563423634 -9.58354091644,-0.0771161168814,0.676132202148 -9.57754802704,-0.0771110802889,0.704718530178 -9.59255504608,-0.0771085470915,0.73628872633 -9.57856273651,-0.0771022960544,0.764864802361 -9.57456970215,-0.0770972818136,0.794439256191 -9.58157348633,-0.0770959183574,0.81022465229 -9.56758117676,-0.077089548111,0.838799118996 -9.57758808136,-0.0770863518119,0.869379341602 -9.54559612274,-0.0770773738623,0.8969399333 -9.56160354614,-0.0770750194788,0.92752969265 -9.56161117554,-0.07707041502,0.957109689713 -9.73361301422,-0.0750895440578,1.0017594099 -9.82061386108,-0.0730993151665,1.02458500862 -9.96561431885,-0.0711149647832,1.0682259798 -9.86462593079,-0.0730961859226,1.09074723721 -9.94962978363,-0.0711035728455,1.12936675549 -9.93663787842,-0.0710971802473,1.15894114971 -9.93964481354,-0.0710929483175,1.19051659107 -9.93265247345,-0.071087256074,1.22108769417 -9.95665550232,-0.0710883811116,1.2388907671 -9.90166568756,-0.0720757618546,1.26443779469 -9.83267688751,-0.0730610489845,1.28797996044 -9.93667888641,-0.0710712596774,1.33060693741 -9.76769542694,-0.0740419477224,1.34210288525 -9.75870418549,-0.0740357339382,1.37167596817 -9.65771389008,-0.0750187411904,1.37343478203 -9.72071838379,-0.0740228891373,1.41203629971 -9.66172981262,-0.0750091299415,1.43557870388 -9.70373535156,-0.0740103051066,1.47118008137 -9.69174480438,-0.0740033611655,1.50074350834 -9.64575576782,-0.0749915391207,1.52430832386 -9.70476055145,-0.0739950239658,1.56390154362 -9.58577156067,-0.0759748071432,1.56164348125 -9.71777248383,-0.0739893019199,1.61128044128 -9.67778396606,-0.0739779770374,1.63682878017 -9.85678005219,-0.0719995573163,1.69547796249 -9.78579330444,-0.072983764112,1.71503138542 -9.84379863739,-0.0719872489572,1.75563049316 -9.71681594849,-0.072962731123,1.76615214348 -9.57783031464,-0.0749390795827,1.7578908205 -9.68883132935,-0.0739505067468,1.80750954151 -9.64885234833,-0.0739335119724,1.86264157295 -9.47287368774,-0.07690115273,1.861156106 -9.62087154388,-0.0739183202386,1.91878938675 -9.54888629913,-0.0749016404152,1.93633508682 -9.61288642883,-0.0739086642861,1.96414268017 -9.63890266418,-0.0739016383886,2.03031468391 -9.63091182709,-0.0738947466016,2.0598859787 -9.61892223358,-0.0738872289658,2.08845853806 -9.62893104553,-0.0738830268383,2.12203216553 -9.55694198608,-0.0748688578606,2.12279105186 -9.60794734955,-0.0738711431623,2.16438746452 -9.48196697235,-0.0758454501629,2.16891121864 -9.59696769714,-0.0738578289747,2.22453188896 -9.54798030853,-0.0748443901539,2.2441008091 -9.61498451233,-0.0728490874171,2.29069447517 -9.58899688721,-0.0738390609622,2.31625890732 -9.61299991608,-0.07284001261,2.33706021309 -9.59101104736,-0.0738305449486,2.3636238575 -9.59702110291,-0.0728256180882,2.39620494843 -9.56703281403,-0.0738149732351,2.41977906227 -9.56204319,-0.0738081037998,2.45034766197 -9.5660533905,-0.0738027021289,2.48292255402 -9.50806427002,-0.0737902224064,2.48468470573 -9.58406639099,-0.0727966278791,2.53429794312 -9.5380821228,-0.0737829580903,2.55484867096 -9.56808853149,-0.0727818608284,2.59344387054 -9.56409931183,-0.0727750882506,2.62401914597 -9.57910728455,-0.0727714151144,2.65960121155 -9.58111763,-0.0727655291557,2.69217443466 -9.58512306213,-0.0717631354928,2.70896673203 -9.58113288879,-0.0717563256621,2.73954415321 -9.57814407349,-0.0717495158315,2.77111291885 -9.56115627289,-0.0717405751348,2.79769134521 -9.53716945648,-0.072730243206,2.82325387001 -9.55917739868,-0.0717275291681,2.86183333397 -9.56218719482,-0.0717217698693,2.89441514015 -9.5541934967,-0.0717172548175,2.90819978714 -9.50720977783,-0.0727029815316,2.92675614357 -9.55821418762,-0.0717052593827,2.9733581543 -9.46723651886,-0.072683416307,2.97889399529 -9.55723667145,-0.0716920942068,3.0384991169 -9.56424617767,-0.0706870108843,3.07209038734 -9.56225681305,-0.0706800594926,3.1046564579 -9.54626369476,-0.0706741958857,3.11544513702 -9.51027965546,-0.0716614872217,3.13700294495 -9.48929214478,-0.0716513991356,3.16257405281 -9.4153137207,-0.0726321935654,3.17112421989 -9.40632629395,-0.072623975575,3.20069408417 -9.3983373642,-0.0726159662008,3.23026871681 -9.40834236145,-0.0726142823696,3.25005626678 -9.40835380554,-0.0726077705622,3.28164291382 -9.40636539459,-0.0716005563736,3.31420850754 -9.40537643433,-0.0715937837958,3.34579229355 -9.40538787842,-0.0715870335698,3.37836885452 -9.39739990234,-0.0715789422393,3.40794610977 -9.39841175079,-0.071572214365,3.44151616096 -9.40241622925,-0.0715695023537,3.45930576324 -9.39742851257,-0.0715617015958,3.49087357521 -9.39444065094,-0.0715543776751,3.52245187759 -9.39745140076,-0.0705481246114,3.55603528023 -9.39046382904,-0.0705399885774,3.58660769463 -9.37947750092,-0.0705310255289,3.61617302895 -9.38348865509,-0.0705248042941,3.65075159073 -9.38549518585,-0.0705217942595,3.66754746437 -9.37850666046,-0.0705135986209,3.69812202454 -9.38751792908,-0.0705082416534,3.73470377922 -9.37453079224,-0.0704988986254,3.76327347755 -9.37054347992,-0.0704910159111,3.79584002495 -9.38555335999,-0.0694868117571,3.83443260193 -9.37756061554,-0.0694818347692,3.84821653366 -9.37157249451,-0.0694736242294,3.87978744507 -9.36758518219,-0.0694659203291,3.91136908531 -9.37059783936,-0.0694592222571,3.94693994522 -9.35861110687,-0.0694500133395,3.97551751137 -9.3666229248,-0.0684442147613,4.01309299469 -9.35663604736,-0.0684353038669,4.04267024994 -9.36364173889,-0.0684327930212,4.06345081329 -9.36365318298,-0.0684257075191,4.09703493118 -9.3546667099,-0.0684168189764,4.12760686874 -9.3496799469,-0.0684085786343,4.160176754 -9.35769081116,-0.0684028118849,4.19776010513 -9.34070682526,-0.0683923363686,4.22532510757 -9.34771156311,-0.0673900693655,4.24512290955 -9.34872341156,-0.0673828199506,4.28069400787 -9.33773803711,-0.067373521626,4.31027030945 -9.33375167847,-0.0673653036356,4.34383821487 -9.33876228333,-0.0673589482903,4.38042354584 -9.3307762146,-0.0673500299454,4.41199445724 -9.328789711,-0.0673421472311,4.44656610489 -9.33479404449,-0.06633964926,4.46636295319 -9.32980823517,-0.0663311332464,4.49993038177 -9.32382202148,-0.0663227513433,4.53151607513 -9.3298330307,-0.0663162916899,4.57009077072 -9.31984806061,-0.0663069710135,4.60066604614 -9.31486129761,-0.0662984326482,4.63423633575 -9.32587242126,-0.0652930140495,4.67482280731 -9.31688022614,-0.0652875080705,4.68860530853 -9.31289386749,-0.0652790442109,4.72317266464 -9.31990623474,-0.065272718668,4.76275014877 -9.30692100525,-0.0652626827359,4.79232311249 -9.30493450165,-0.0642545893788,4.82789421082 -9.31694507599,-0.0642493367195,4.86948442459 -9.29896068573,-0.0642382279038,4.89705133438 -9.30396652222,-0.0642353147268,4.91784143448 -9.30497932434,-0.0642279088497,4.95442438126 -9.29699420929,-0.0642186701298,4.98699808121 -9.29200839996,-0.0632098987699,5.02156829834 -9.3000202179,-0.0632035508752,5.06314229965 -9.28403663635,-0.0631927475333,5.0917134285 -9.28204345703,-0.0631886124611,5.10850858688 -9.29805374146,-0.06218386814,5.15409326553 -9.28407001495,-0.0621732287109,5.18465614319 -9.28008365631,-0.0621645562351,5.22022819519 -9.28309631348,-0.0621573887765,5.25881242752 -9.26711273193,-0.0621463097632,5.28837537766 -9.26812648773,-0.0621387511492,5.32596063614 -9.28113079071,-0.0611371509731,5.35274744034 -9.26514720917,-0.0611262619495,5.38132286072 -9.26216125488,-0.0611177012324,5.41789674759 -9.27317237854,-0.0611118227243,5.46247625351 -9.25518894196,-0.0611004903913,5.49005174637 -9.25320339203,-0.0600920468569,5.52762508392 -9.26121616364,-0.0600855015218,5.57120132446 -9.25422286987,-0.0600802376866,5.58599233627 -9.25023841858,-0.0600711964071,5.62355566025 -9.25525093079,-0.059064168483,5.66513776779 -9.23626899719,-0.0590524636209,5.69270992279 -9.23928165436,-0.0590450242162,5.73329210281 -9.24029541016,-0.0590369738638,5.77386283875 -9.22831249237,-0.0590266436338,5.80544185638 -9.23631668091,-0.0580240935087,5.83023166656 -9.23833084106,-0.0580161958933,5.87180280685 -9.22934627533,-0.0580064207315,5.90538406372 -9.22436141968,-0.0579971149564,5.94295167923 -9.22437572479,-0.0569888167083,5.98352384567 -9.21938991547,-0.056979727,6.0201048851 -9.22439575195,-0.0569767020643,6.04290103912 -9.22541046143,-0.0569685660303,6.08447408676 -9.21542644501,-0.0559582784772,6.11904478073 -9.21344089508,-0.0559495948255,6.15862035751 -9.21545505524,-0.0559416301548,6.20119524002 -9.20047187805,-0.0559305176139,6.23177433014 -9.21047687531,-0.0549281984568,6.25956058502 -9.20749187469,-0.0549192354083,6.29913473129 -9.19850826263,-0.0549091026187,6.33470869064 -9.19652271271,-0.0549002923071,6.37528276443 -9.19853687286,-0.0538922213018,6.41885709763 -9.19055366516,-0.0538824386895,6.45444154739 -9.18856716156,-0.0538734719157,6.49601078033 -9.19857311249,-0.0528712831438,6.52380561829 -9.19158840179,-0.0528614707291,6.56138134003 -9.18860435486,-0.052852217108,6.60294723511 -9.18661880493,-0.0528435111046,6.64353227615 -9.17763519287,-0.0518332496285,6.6801071167 -9.17765045166,-0.0518246591091,6.72368097305 -9.17466545105,-0.0518154688179,6.76525354385 -9.17567253113,-0.051811337471,6.78803920746 -9.16968917847,-0.0508017390966,6.82662200928 -9.17070293427,-0.0507931746542,6.87218999863 -9.16271877289,-0.0507831200957,6.9097700119 -9.15973567963,-0.049773812294,6.95234107971 -9.16274833679,-0.0497658066452,6.99892044067 -9.14876651764,-0.049754306674,7.03348875046 -9.20076274872,-0.0487604662776,7.09430122375 -9.09780025482,-0.0497314110398,7.06084918976 -9.0188331604,-0.0507069975138,7.04540109634 -9.06185245514,-0.0496980845928,7.1685667038 -8.99688243866,-0.0496764145792,7.16312503815 -8.94790172577,-0.0506621673703,7.14789390564 -8.89592838287,-0.0516431368887,7.15146064758 -8.88494491577,-0.0506321042776,7.18803262711 -8.88296127319,-0.0506229102612,7.23161029816 -8.88097667694,-0.0506137423217,7.27518987656 -8.87099456787,-0.0496029108763,7.31276416779 -8.94399356842,-0.0486084111035,7.4193520546 -8.97499370575,-0.0476103276014,7.46715641022 -8.96501159668,-0.0475992709398,7.50672197342 -9.11999225616,-0.0436213687062,7.68234157562 -9.12700557709,-0.0436137653887,7.7369146347 -9.11402320862,-0.0436024293303,7.77349567413 -9.11603832245,-0.0425938554108,7.82406997681 -9.12006092072,-0.0415811538696,7.90143156052 -9.11907577515,-0.0415721535683,7.94901514053 -9.12009143829,-0.0415633544326,7.99959039688 -9.09911251068,-0.0405499711633,8.03215312958 -9.2880821228,-0.0365789271891,8.24777984619 -9.21911430359,-0.0375562272966,8.2373456955 -9.2181224823,-0.0375513248146,8.26312446594 -9.23813343048,-0.0365462526679,8.33270263672 -9.21715354919,-0.0365330576897,8.36527633667 -9.21217060089,-0.0365231446922,8.41185855865 -9.21218585968,-0.0355138368905,8.46542453766 -9.22019958496,-0.0355064049363,8.52500534058 -9.19822025299,-0.0344928838313,8.55757713318 -9.19922828674,-0.034488465637,8.58536243439 -9.23423480988,-0.0334864221513,8.67094898224 -9.19725990295,-0.0334699228406,8.68952083588 -9.20927238464,-0.0324631147087,8.75509643555 -9.19229221344,-0.0324504449964,8.79366493225 -9.25831508636,-0.0304408427328,8.99362468719 -9.15735626221,-0.0314112827182,8.95117950439 -9.15637111664,-0.0314018204808,9.00575447083 -9.09641838074,-0.0313712544739,9.05789756775 -9.03345012665,-0.0313490517437,9.0524520874 -9.03645706177,-0.0313450396061,9.08324241638 -9.03647327423,-0.0303356740624,9.13981628418 -9.05448532104,-0.0293300226331,9.21439838409 -9.02050971985,-0.0303137972951,9.23696708679 -8.99453163147,-0.0302991904318,9.26753807068 -9.00254631042,-0.0292916167527,9.33212375641 -8.99356460571,-0.0282802451402,9.381690979 -8.97957611084,-0.0282728243619,9.39548206329 -9.01060009003,-0.027260189876,9.54563713074 -8.98362350464,-0.0262453015894,9.5762090683 -8.99063873291,-0.0262371748686,9.64378166199 -9.05163955688,-0.0242400579154,9.76937007904 -8.91568183899,-0.0262077655643,9.65313148499 -8.87170886993,-0.0271893236786,9.66569709778 -8.82073879242,-0.0271696299314,9.66927146912 -8.76476955414,-0.028148625046,9.66883182526 -8.71579837799,-0.0281290784478,9.67539596558 -8.7008190155,-0.0281166546047,9.7179775238 -8.68983745575,-0.0271046664566,9.76754283905 -8.6938457489,-0.0271008703858,9.80134010315 -8.69986057281,-0.0260922629386,9.87090682983 -8.68688011169,-0.0260802395642,9.91649055481 -8.93483448029,-0.0201208889484,10.2631072998 -8.93984889984,-0.0191123690456,10.3326883316 -8.92486953735,-0.0190996788442,10.3802614212 -8.91288948059,-0.0180875491351,10.4318332672 -8.93489170074,-0.0170872975141,10.4896297455 -8.92391109467,-0.0170753262937,10.5432004929 -8.92092895508,-0.0160650853068,10.6057777405 -8.91594696045,-0.0160542912781,10.6673488617 -8.90196800232,-0.0150417424738,10.7179231644 -8.90698242188,-0.0140330800787,10.7915019989 -8.89600276947,-0.0140211693943,10.8460788727 -8.90200996399,-0.013017501682,10.8878669739 -8.89802646637,-0.0130070252344,10.9514465332 -8.89504528046,-0.0119966985658,11.0170240402 -8.88306522369,-0.0119844293222,11.0725955963 -8.91107463837,-0.00998034793884,11.1781768799 -8.95607948303,-0.00797977484763,11.3057632446 -8.85611438751,-0.00995436124504,11.2165288925 -3.40256643295,-0.131836369634,4.37031078339 -3.39958620071,-0.131826162338,4.39290618896 -3.37561249733,-0.131811097264,4.39047431946 -8.85120105743,-0.00590415718034,11.5744104385 -8.84022140503,-0.00589198991656,11.6349821091 -8.85522556305,-0.00489016762003,11.6917762756 -8.84924411774,-0.00387905933894,11.7593517303 -8.83826446533,-0.00386677193455,11.8219203949 -8.83128356934,-0.00285552279092,11.8885002136 -8.82830142975,-0.00184506701771,11.9610795975 -8.81632232666,-0.000832554884255,12.0236492157 -8.82832717896,-0.000829996773973,12.0794391632 -8.82134723663,0.000181422175956,12.1490125656 -8.816365242,0.00119240442291,12.2215890884 -8.80638504028,0.00120434025303,12.2871675491 -8.79940414429,0.00221583386883,12.3587398529 -8.79042434692,0.00322777591646,12.4283123016 -8.78244304657,0.00423928536475,12.4978933334 -8.79145050049,0.0042425445281,12.5526800156 -8.78946781158,0.00525301555172,12.6332550049 -8.7814874649,0.00626459810883,12.704834938 -8.77250766754,0.00727649778128,12.7764101028 -8.76252841949,0.00828871503472,12.8479814529 -8.75754642487,0.00829980988055,12.9265575409 -8.74956607819,0.00931161642075,13.0021295547 -8.76257228851,0.0103139923885,13.0649213791 -8.74859333038,0.01132690534,13.1314983368 -8.7486114502,0.0123371277004,13.2210712433 -8.73663234711,0.013349737972,13.2926454544 -8.72465324402,0.0133624030277,13.3652172089 -8.72067165375,0.0143732307479,13.448800087 -8.71469116211,0.0153847346082,13.532371521 -8.7266960144,0.0163873620331,13.5971632004 -8.7187166214,0.0173991601914,13.6777391434 -8.70873737335,0.0184115283191,13.7573099136 -8.6947593689,0.0194245781749,13.8298854828 -8.65578746796,0.0194427706301,13.8634557724 -8.61781597137,0.0194606948644,13.8980302811 -8.62882232666,0.0204635411501,13.9638214111 -8.62284088135,0.0214751064777,14.0523939133 -8.61286258698,0.0224874634296,14.1349668503 -8.60088348389,0.0225001871586,14.2145423889 -8.59790229797,0.0245111193508,14.3101186752 -8.58692359924,0.0255236290395,14.3926944733 -8.57994365692,0.0265353806317,14.4832696915 -8.59494781494,0.0275374799967,14.5600605011 -8.58396911621,0.028550086543,14.6456346512 -8.57898902893,0.0295614618808,14.7422094345 -8.56601047516,0.0305744651705,14.8257856369 -8.55403232574,0.0315872132778,14.911362648 -8.54205417633,0.0326000824571,14.9989356995 -8.53807258606,0.0336113348603,15.1015100479 -8.5520772934,0.0346136800945,15.1813011169 -8.54109954834,0.0356264263391,15.2738714218 -8.53012084961,0.0366389080882,15.3644533157 -8.52613925934,0.037650283426,15.4720249176 -8.50516414642,0.0386650189757,15.5485982895 -8.50218391418,0.0396759398282,15.6571798325 -8.51818847656,0.0416780002415,15.7459669113 -8.51420783997,0.0426893793046,15.8575401306 -8.50322914124,0.0437020882964,15.956114769 -8.50424766541,0.0457123070955,16.0776939392 -8.51426315308,0.0467207469046,16.2182731628 -8.52427768707,0.048729300499,16.3618507385 -8.51729869843,0.0507412366569,16.4734249115 -8.53630161285,0.0517427138984,16.574213028 -8.52432346344,0.0527557171881,16.6787872314 -8.51634502411,0.0547679103911,16.7923622131 -8.50636672974,0.0557804070413,16.9019432068 -8.49238872528,0.0567937791348,17.0055198669 -8.48440933228,0.05880600214,17.1230945587 -8.4744310379,0.0598186850548,17.2386665344 -8.49143505096,0.0608205422759,17.3414573669 -8.47345924377,0.0628348514438,17.4430294037 -8.4634809494,0.0638474971056,17.5616054535 -11.4256315231,0.161258131266,23.8965625763 -11.3276777267,0.160288840532,23.8831233978 -10.5809144974,0.138450935483,22.4905986786 -11.1867456436,0.1593336761,23.8744659424 -11.0927915573,0.159363642335,23.8690261841 -10.9908390045,0.15839509666,23.8435897827 -10.9098815918,0.158422276378,23.8621578217 -10.6569738388,0.152484387159,23.5046958923 -10.5350284576,0.150519922376,23.4302558899 -10.4540700912,0.150547161698,23.4458217621 -10.4290866852,0.150557607412,23.4876060486 -10.3331327438,0.149588003755,23.4711666107 -10.2191858292,0.148621812463,23.4087314606 -9.7403459549,0.13372926414,22.5032501221 -10.0632686615,0.147675052285,23.4498634338 -9.55743694305,0.132787942886,22.4653778076 -9.89935398102,0.147729992867,23.4729938507 -9.84537887573,0.146746367216,23.4477729797 -9.76642227173,0.146773219109,23.4653396606 -9.67146873474,0.145803287625,23.4439048767 -9.58551216125,0.145831480622,23.4424705505 -9.49755764008,0.144860133529,23.4370346069 -9.41160202026,0.144888326526,23.4346027374 -9.32064819336,0.143917620182,23.4211673737 -9.27966976166,0.143931180239,23.4219551086 -9.1877155304,0.142960652709,23.4045181274 -9.1037607193,0.142988488078,23.406085968 -9.01580524445,0.142017140985,23.3976478577 -8.93284893036,0.14204467833,23.3992195129 -8.84289550781,0.141073703766,23.3837833405 -8.80491638184,0.141086682677,23.3915729523 -8.70896434784,0.140116870403,23.3581371307 -8.62900733948,0.140143930912,23.3687019348 -8.54505252838,0.140171647072,23.3652744293 -8.45909690857,0.139199763536,23.3558425903 -8.37614059448,0.139227241278,23.3534126282 -8.29418468475,0.138254582882,23.3549804688 -8.24321079254,0.138270273805,23.3277626038 -8.16325378418,0.137297213078,23.3343315125 -8.07929801941,0.137324869633,23.3269023895 -7.99734258652,0.137352138758,23.3254737854 -7.91138839722,0.136380299926,23.3140392303 -7.83743000031,0.136405929923,23.3346118927 -7.78645515442,0.135421544313,23.303396225 -7.70549964905,0.135448634624,23.3039646149 -7.62454366684,0.135475680232,23.3035354614 -7.54058885574,0.134503260255,23.2921085358 -7.45363521576,0.133531570435,23.2736759186 -4.11866664886,-0.0167987179011,12.9810400009 -4.06470346451,-0.0177773050964,12.9536094666 -4.05171728134,-0.016769586131,12.9814043045 -7.17178964615,0.132625743747,23.2671737671 -7.09083414078,0.132652759552,23.2637462616 -7.00687980652,0.131680235267,23.2473182678 -6.93092250824,0.131706297398,23.260887146 -6.84496879578,0.130734160542,23.2364597321 -6.77001190186,0.130759894848,23.2500324249 -6.7260351181,0.130773961544,23.2328205109 -6.64508008957,0.130800962448,23.2273902893 -6.56512403488,0.129827618599,23.2219638824 -6.49016714096,0.129853323102,23.2345371246 -6.40521335602,0.128880932927,23.2101097107 -6.32925701141,0.128906816244,23.2186832428 -6.24830150604,0.128933668137,23.2082538605 -6.20932340622,0.128946736455,23.2070426941 -6.12636947632,0.12797395885,23.1886138916 -6.05041265488,0.127999737859,23.1941890717 -5.97245693207,0.128025859594,23.1907634735 -5.89250183105,0.127052485943,23.1823368073 -5.81654548645,0.127078220248,23.1869106293 -5.77156972885,0.127092435956,23.160697937 -5.69361400604,0.126118600368,23.1572723389 -5.61965703964,0.126143917441,23.1688461304 -5.54070138931,0.126170158386,23.1584243774 -5.4587469101,0.125197008252,23.1359977722 -5.38578987122,0.125222072005,23.1505737305 -5.30383586884,0.125248938799,23.1281452179 -5.26485824585,0.124261975288,23.1249313354 -5.18690252304,0.124287933111,23.1155090332 -5.11094617844,0.124313518405,23.1150856018 -5.03998947144,0.12433821708,23.1406574249 -5.02301502228,0.128352314234,23.4142379761 -4.9980430603,0.131367996335,23.6588172913 -5.01204872131,0.135370776057,23.912607193 -3.20962572098,0.0147284446284,15.522143364 -3.15166449547,0.0147501341999,15.4847249985 -3.09370303154,0.0137717863545,15.4453077316 -3.04373931885,0.0137919671834,15.4468870163 -2.99377584457,0.013812225312,15.450463295 -2.9448120594,0.013832195662,15.4570426941 -2.93182635307,0.0138399144635,15.5198345184 -2.89685797691,0.0158572066575,15.6034145355 -2.84689450264,0.0148773100227,15.6059942245 -2.79393196106,0.0148980468512,15.5935726166 -4.77533912659,0.180530741811,27.2281799316 -4.74536943436,0.184547379613,27.5657577515 -4.71839857101,0.189563423395,27.9333362579 -4.73140478134,0.194566488266,28.2861232758 -4.70143461227,0.199583128095,28.659702301 -4.67146444321,0.205599725246,29.0472812653 -4.63749599457,0.210617095232,29.4248600006 -4.60252809525,0.215634733438,29.8164348602 -4.56955909729,0.221651822329,30.2270202637 -4.53259134293,0.226669862866,30.6405925751 -4.54259872437,0.232673406601,31.045381546 -4.58860492706,0.246675550938,32.0609664917 -4.54963827133,0.252693921328,32.5205421448 -4.51167058945,0.259712040424,33.0061187744 -4.4717040062,0.266730487347,33.4967002869 -4.42473983765,0.272750347853,33.9642753601 -4.41875219345,0.278756916523,34.3380661011 -4.34779500961,0.282781243324,34.647644043 -4.35281467438,0.295791149139,35.5912284851 -4.30585050583,0.303811013699,36.1568031311 -4.25988578796,0.311830550432,36.7553825378 -4.20392370224,0.318851947784,37.296962738 -2.59944605827,0.127162918448,23.6535339355 -2.55846905708,0.126175791025,23.6163272858 -2.48251414299,0.126200675964,23.613904953 -2.41055727005,0.126224532723,23.6324901581 -2.33760166168,0.127248823643,23.6620674133 -3.94112181664,0.375961065292,41.3916473389 -3.87816262245,0.385983675718,42.1362228394 -3.88517093658,0.397987812757,42.9550132751 -3.74223685265,0.397025346756,42.8805885315 -3.75625348091,0.42203360796,44.671169281 -3.68829584122,0.434057056904,45.5777511597 -3.61633944511,0.447081267834,46.5093269348 -3.5393846035,0.460106343031,47.4499053955 -3.45243310928,0.473133265972,48.3354873657 -3.4344496727,0.484142065048,49.1872749329 -3.34149980545,0.498170018196,50.1228523254 -3.25254893303,0.513197243214,51.2204360962 -3.15959906578,0.529225051403,52.3540153503 -3.06065154076,0.54525411129,53.5155944824 -3.07266879082,0.592262685299,56.8931732178 -2.91174077988,0.597302913666,57.2477531433 -1.82809066772,0.311506509781,36.9015579224 -1.71614718437,0.313537538052,37.0031394958 -1.59820532799,0.312569469213,36.9537239075 -1.48026359081,0.311601430178,36.9143066406 -1.36931979656,0.313632130623,37.07188797 -1.3513468504,0.355645865202,40.0384674072 -1.22440803051,0.354679316282,40.0020484924 -1.16143834591,0.354695916176,39.9938430786 -1.03549921513,0.354729086161,39.9764251709 -0.909560024738,0.354762226343,39.9630088806 -0.78362095356,0.354795336723,39.9715919495 -0.657681822777,0.354828357697,39.9531745911 -0.532742202282,0.353861093521,39.946762085 -0.4697727561,0.354877591133,39.9695510864 -0.344833165407,0.354910224676,39.9641418457 -0.218894049525,0.353943049908,39.9187240601 -0.0939545556903,0.354975581169,39.9983100891 --0.36784029007,0.97608679533,56.3431396484 --0.543763875961,0.975128233433,56.2837257385 --0.619729280472,0.951146781445,55.1285209656 --1.49739050865,1.32333242893,72.8612976074 --2.09315037727,1.34146237373,73.680267334 --2.35004854202,1.35851740837,74.4838562012 --2.67692446709,1.4145847559,77.1774520874 --1.99383962154,0.323598146439,25.0825901031 --2.0478014946,0.316617012024,24.7691783905 --2.11176013947,0.313637495041,24.5987663269 --2.14773845673,0.312648415565,24.5655612946 --2.22469329834,0.312671124935,24.552148819 --2.30064845085,0.312693595886,24.5287380219 --2.51054096222,0.324748158455,25.0819244385 --9.43319034576,1.35499966145,73.6775665283 --9.63010787964,1.34904003143,73.3811721802 --9.85901641846,1.34908568859,73.3417739868 --10.0899238586,1.34913158417,73.3103790283 --10.3268299103,1.35017848015,73.3259811401 --9.26913928986,1.16000819206,64.3245315552 --9.44506454468,1.15604484081,64.1201324463 --9.1510848999,1.02202093601,57.6956939697 --9.32901000977,1.02205765247,57.650302887 --9.49493694305,1.02009224892,57.5269050598 --9.59489631653,1.02111244202,57.5697059631 --9.78881645203,1.02315139771,57.6153106689 --9.97473812103,1.02318894863,57.6129150391 --10.1596603394,1.02422618866,57.6045227051 --10.3445825577,1.02426338196,57.5901260376 --10.5025138855,1.02229607105,57.4307289124 --10.7134284973,1.02533721924,57.5623397827 --7.24749469757,0.61977481842,38.5539207458 --7.35244178772,0.617799699306,38.4415168762 --7.4713845253,0.617826700211,38.408115387 --8.29780864716,0.522077560425,33.5396652222 --8.31479358673,0.519083857536,33.3804588318 --8.46572685242,0.523114740849,33.538066864 --7.74486875534,0.429031193256,29.1153755188 --7.83382129669,0.429052293301,29.0809764862 --7.88479614258,0.430063813925,29.0897808075 --7.97974729538,0.430085808039,29.0753803253 --8.0387096405,0.427102088928,28.9339790344 --8.17464828491,0.431130170822,29.0685844421 --7.7627248764,0.382085084915,26.7835254669 --7.83768177032,0.382103800774,26.7261257172 --7.92763471603,0.382124692202,26.7217273712 --8.00959014893,0.382144272327,26.6903305054 --7.69864559174,0.348111659288,25.0704784393 --7.7756023407,0.347130507231,25.0400810242 --7.80958271027,0.347139149904,25.01288414 --7.88653898239,0.34715795517,24.9794807434 --7.96249675751,0.347176462412,24.9470825195 --8.04045295715,0.347195208073,24.9196834564 --8.12240886688,0.347214490175,24.9052848816 --8.20336532593,0.347233504057,24.8888912201 --8.27832317352,0.347251623869,24.8524913788 --8.34129333496,0.349264413118,24.9112949371 --9.08403015137,0.387387692928,26.5805664062 --9.17598342896,0.387407898903,26.5741710663 --9.26893615723,0.388428151608,26.5707740784 --9.36988639832,0.389449387789,26.5923805237 --9.41986274719,0.389459937811,26.6001834869 --13.8345108032,0.66111010313,38.7332801819 --13.797504425,0.651109516621,38.2488746643 --13.9014549255,0.650129377842,38.1594848633 --13.7284708023,0.625113785267,36.954662323 --13.7474479675,0.620121240616,36.6522674561 --13.671462059,0.612112760544,36.2730522156 --13.6584482193,0.604115605354,35.895652771 --13.650431633,0.597119152546,35.5362510681 --13.6324195862,0.590121328831,35.1568450928 --13.6084089279,0.582122564316,34.7684440613 --13.5903968811,0.575124740601,34.4040412903 --13.573384285,0.567126989365,34.0446357727 --13.5023965836,0.560119271278,33.7124290466 --13.4893836975,0.554122149944,33.3730239868 --13.4753694534,0.547124862671,33.0376243591 --13.4553575516,0.540126681328,32.6932182312 --13.4413442612,0.534129440784,32.3678131104 --13.4233322144,0.52713149786,32.0384101868 --13.3553438187,0.52112442255,31.735200882 --13.3443288803,0.515127539635,31.4307994843 --13.3323154449,0.509130477905,31.1293964386 --13.3163022995,0.503132939339,30.8209915161 --13.3062877655,0.497136175632,30.5325889587 --13.2922744751,0.49213886261,30.2391853333 --13.2762622833,0.486141264439,29.9457836151 --13.2172708511,0.480135500431,29.6855754852 --13.2112550735,0.475139290094,29.4211730957 --13.190243721,0.46914100647,29.1277675629 --13.1782302856,0.46414399147,28.8573646545 --13.1702156067,0.459147453308,28.6009616852 --13.1621999741,0.454150915146,28.3475589752 --13.1441879272,0.449153065681,28.0751552582 --13.0911951065,0.444148242474,27.8479480743 --13.087179184,0.440152257681,27.6105422974 --13.0691671371,0.435154408216,27.3491401672 --13.0641517639,0.430158227682,27.1177368164 --13.0511379242,0.425161004066,26.8733348846 --13.0441226959,0.421164572239,26.6449317932 --13.0001268387,0.417161047459,26.447725296 --13.0021095276,0.413165807724,26.2413215637 --9.08823204041,0.224659606814,18.1643180847 --9.09621143341,0.22266677022,18.0369110107 --9.13018226624,0.221677333117,17.9615077972 --9.17115306854,0.220688700676,17.9021091461 --9.22811794281,0.220702052116,17.8747158051 --9.24810314178,0.220707654953,17.8435134888 --9.30706787109,0.220721170306,17.8201198578 --9.38402748108,0.221737027168,17.8287239075 --9.44399166107,0.221750512719,17.8073310852 --9.55294322968,0.223770201206,17.8769454956 --12.8499755859,0.368192672729,23.9020786285 --12.8529567719,0.365197360516,23.727678299 --12.8849401474,0.365203529596,23.6984844208 --12.973897934,0.365218997002,23.68409729 --13.017868042,0.364228785038,23.5867023468 --13.1538133621,0.367249935865,23.6563224792 --13.2557668686,0.368266731501,23.6639385223 --13.3397264481,0.368281185627,23.6395530701 --13.3957023621,0.369290083647,23.6513595581 --13.4926576614,0.370306015015,23.6479740143 --13.5786170959,0.371320486069,23.6245861053 --13.6715745926,0.371335685253,23.6142024994 --13.7605323792,0.372350305319,23.5968170166 --13.8664865494,0.37336692214,23.6064338684 --13.9354505539,0.373378902674,23.5540466309 --13.8854570389,0.369374722242,23.3838348389 --13.829457283,0.364371627569,23.1234283447 --12.6597709656,0.313235551119,21.0058193207 --13.9743843079,0.364396244287,23.0326461792 --12.781703949,0.313258349895,20.9080371857 --12.9086523056,0.31627741456,20.9676589966 --12.798666954,0.308268547058,20.6402339935 --12.7076845169,0.304259866476,20.4210186005 --12.7136659622,0.301264643669,20.2876186371 --12.8536109924,0.304285019636,20.3672389984 --12.9035806656,0.304294764996,20.3048496246 --12.9805431366,0.304307609797,20.2834606171 --12.6975975037,0.290280967951,19.6328048706 --13.0854740143,0.302329272032,20.0964775085 --13.1424417496,0.302339583635,20.0440826416 --13.0294570923,0.295330494642,19.7346630096 --13.6172790527,0.315400660038,20.4893741608 --13.3343410492,0.302372336388,19.9229164124 --13.3213300705,0.299374490976,19.7675132751 --13.5232658386,0.306398838758,20.0003509521 --13.5542421341,0.304405778646,19.9099559784 --13.3412847519,0.294385612011,19.4635181427 --13.3622636795,0.293391436338,19.3621177673 --13.4172325134,0.292400985956,19.3107280731 --13.3542346954,0.288397580385,19.0893115997 --13.3842105865,0.287404328585,19.0039176941 --13.2752332687,0.282394230366,18.7846946716 --13.0552768707,0.272373914719,18.3472480774 --13.2412109375,0.27639746666,18.4868869781 --12.9422769547,0.263368934393,17.9454212189 --12.7963008881,0.256356954575,17.6239929199 --12.3843975067,0.239316940308,16.9395065308 --12.1664409637,0.230297744274,16.5290584564 --12.19942379,0.230303198099,16.518863678 --12.2553920746,0.230312988162,16.4844684601 --12.283370018,0.229319736362,16.4140758514 --12.3353404999,0.229328975081,16.3746833801 --12.2943353653,0.226328536868,16.2122707367 --12.3373088837,0.226336747408,16.1618766785 --8.8912229538,0.104985781014,11.5749158859 --8.90620231628,0.104992777109,11.5185136795 --8.94617366791,0.105002336204,11.4941139221 --8.97614860535,0.105010762811,11.4577169418 --9.04411411285,0.106022939086,11.4703292847 --12.4471940994,0.220368042588,15.7306938171 --12.5941400528,0.223386287689,15.8133201599 --12.6441192627,0.224393025041,15.8241271973 --12.6860933304,0.224400594831,15.7747373581 --12.7220678329,0.223407551646,15.7173442841 --12.8210277557,0.225420609117,15.7379636765 --12.9349822998,0.227435007691,15.7755851746 --12.9409656525,0.22643879056,15.6821899414 --12.9699430466,0.225444763899,15.6167964935 --12.9659366608,0.22444601357,15.5605916977 --12.9789190292,0.223450407386,15.4761924744 --12.9689064026,0.221452608705,15.3647899628 --12.8469228745,0.215444236994,15.1213607788 --13.0138654709,0.219463080168,15.2209968567 --13.3757572174,0.229499861598,15.5476799011 --13.5946855545,0.235523030162,15.7023277283 --13.6476650238,0.236529275775,15.7141418457 --13.6396522522,0.234531253576,15.6037359238 --13.5826530457,0.231528714299,15.4383201599 --13.7495965958,0.234546542168,15.5309638977 --13.784573555,0.234552294016,15.4705677032 --15.155207634,0.276677817106,16.9134922028 --15.1482028961,0.275678098202,16.8522930145 --15.1741828918,0.274682164192,16.772895813 --20.9786911011,0.455197453499,23.0918655396 --15.8399877548,0.291744053364,17.2932567596 --15.9349508286,0.292753696442,17.2868824005 --15.9669294357,0.292757719755,17.2114887238 --12.0499067307,0.169421359897,12.8751363754 --12.0339031219,0.168421700597,12.8159265518 --12.0318889618,0.167424857616,12.7325258255 --12.0298757553,0.166428014636,12.6491212845 --12.0918455124,0.166436508298,12.6347379684 --12.1688117981,0.167446181178,12.6353549957 --12.1697969437,0.166449457407,12.5559530258 --12.173781395,0.165452972054,12.4795475006 --12.1427822113,0.164451986551,12.4083414078 --12.148765564,0.163455620408,12.3359422684 --12.1347541809,0.161457657814,12.2425327301 --12.1367406845,0.160460919142,12.1671323776 --12.1317272186,0.159463629127,12.0847291946 --12.1327123642,0.157466769218,12.0093288422 --12.1267004013,0.156469374895,11.9269237518 --12.1226930618,0.155470594764,11.8847208023 --12.102684021,0.154472082853,11.7893123627 --12.1156663895,0.153476148844,11.7269134521 --12.1076545715,0.152478545904,11.6445074081 --12.1056413651,0.151481375098,11.569108963 --12.093629837,0.14948348701,11.4826965332 --12.1026134491,0.148487120867,11.4182977676 --12.0746135712,0.147486507893,11.3550872803 --12.0775995255,0.146489650011,11.2866926193 --12.0645875931,0.145491674542,11.2012796402 --12.0775709152,0.144495502114,11.1428861618 --12.0685586929,0.143497750163,11.0634813309 --12.0745439529,0.142501071095,10.9980792999 --12.04454422,0.141500324011,10.9358730316 --12.0485296249,0.140503525734,10.8684654236 --12.0425167084,0.139505937696,10.7940645218 --12.0485019684,0.138509169221,10.7306661606 --12.035490036,0.13651111722,10.6492538452 --12.0424747467,0.136514395475,10.58685112 --12.0384626389,0.135516896844,10.5154485703 --12.0214595795,0.134517088532,10.4672470093 --12.0174474716,0.133519604802,10.3958396912 --12.0144338608,0.132522135973,10.3264360428 --12.0094213486,0.131524518132,10.2560358047 --12.0154075623,0.130527600646,10.1956377029 --12.0043954849,0.129529610276,10.119225502 --12.0103807449,0.128532662988,10.0588245392 --11.9863796234,0.127532437444,10.0066204071 --11.9903650284,0.126535341144,9.94521999359 --11.9853534698,0.125537693501,9.87581062317 --11.9783420563,0.124539844692,9.80640888214 --11.9803276062,0.123542577028,9.74400615692 --11.977314949,0.12254499644,9.67759990692 --11.9703035355,0.121547117829,9.6091966629 --11.9562997818,0.121547572315,9.56598949432 --11.9502878189,0.120549723506,9.49959087372 --11.9492750168,0.119552202523,9.43618488312 --11.9562597275,0.118555128574,9.37978363037 --11.9572467804,0.117557644844,9.31938457489 --11.9442367554,0.116559371352,9.24797916412 --11.9522218704,0.11656229943,9.19257354736 --11.9322195053,0.115562416613,9.14636421204 --11.9312067032,0.114564754069,9.0859670639 --11.9231958389,0.113566733897,9.0195608139 --11.933180809,0.113569676876,8.96716022491 --11.9321680069,0.112571947277,8.90776348114 --12.077123642,0.115581914783,8.95740318298 --5.55251789093,-0.0567499436438,4.00883960724 --5.54151153564,-0.0567472241819,3.9866271019 --11.883108139,0.106582224369,8.54852867126 --11.889093399,0.106584794819,8.49512672424 --11.8870811462,0.105586923659,8.43672561646 --11.8710784912,0.10458727926,8.39651870728 --11.8640670776,0.10458920151,8.33411026001 --11.8510570526,0.103590786457,8.26870632172 --11.8560438156,0.102593198419,8.21630764008 --11.8500328064,0.101595103741,8.15590190887 --11.8380222321,0.100596740842,8.09149360657 --11.8340110779,0.0995987132192,8.03308773041 --11.8140087128,0.0995988994837,7.99188184738 --11.81599617,0.098601102829,7.93848133087 --11.8119850159,0.0976030305028,7.88107776642 --11.8069725037,0.0966049358249,7.82266998291 --11.8369541168,0.0976082012057,7.78928279877 --11.8489398956,0.096610724926,7.74288225174 --11.8479280472,0.0966126769781,7.68848133087 --11.8239269257,0.0956127420068,7.64526891708 --11.8259143829,0.0946148112416,7.59286546707 --11.8299007416,0.0946169123054,7.54246711731 --11.823890686,0.0936186462641,7.48505973816 --11.8328762054,0.09362090379,7.4376578331 --11.8208665848,0.0926223322749,7.37825918198 --11.8298521042,0.0916245505214,7.33085489273 --11.8118505478,0.091624841094,7.29364967346 --11.8138380051,0.090626783669,7.24224424362 --11.8028287888,0.0896282419562,7.18384075165 --11.804816246,0.0896301195025,7.13343906403 --11.805803299,0.08863196522,7.08203268051 --11.795794487,0.0876334235072,7.02462673187 --11.7957830429,0.0876351520419,6.97422933578 --11.7887783051,0.0866358280182,6.94402170181 --11.789765358,0.0866376012564,6.89361715317 --11.7827548981,0.0856390967965,6.83921480179 --11.7787446976,0.085640668869,6.78681325912 --11.7797317505,0.0846423879266,6.73640394211 --11.7767219543,0.0836439430714,6.6850028038 --11.763718605,0.0836444124579,6.65279960632 --11.7567081451,0.082645855844,6.59939670563 --11.7626962662,0.0826476290822,6.55299282074 --11.7556858063,0.081649042666,6.49958658218 --11.7696714401,0.081650942564,6.45818662643 --11.7546625137,0.080652102828,6.4017868042 --11.7926445007,0.0816544890404,6.37339162827 --11.8326311111,0.0816560983658,6.37120485306 --11.8336200714,0.081657551229,6.32280158997 --11.836607933,0.0806590020657,6.27640533447 --11.8515949249,0.0806606784463,6.23600816727 --11.9205713272,0.081663325429,6.22463035583 --11.9905471802,0.0836658701301,6.21325206757 --12.0785207748,0.0846686139703,6.21087932587 --12.1425046921,0.0856702700257,6.21969795227 --12.2824687958,0.0886735916138,6.24435043335 --12.3294496536,0.0896752625704,6.21896266937 --12.3294391632,0.0886761248112,6.16956090927 --12.3404273987,0.088677123189,6.12616491318 --12.2404336929,0.0856766179204,6.02572059631 --12.3843984604,0.0886792764068,6.05037879944 --12.3693962097,0.0886794626713,6.01817083359 --12.4013805389,0.0886805653572,5.98477745056 --12.2883796692,0.0856807753444,5.8319311142 --12.2983675003,0.0846815854311,5.78853225708 --12.2933588028,0.084682226181,5.73812818527 --12.2883491516,0.0836828500032,5.68772268295 --12.210357666,0.0816825926304,5.62749862671 --12.3283281326,0.0846840590239,5.6351351738 --18.4313106537,0.224721074104,8.44098091125 --14.8408966064,0.141698047519,6.70526838303 --14.8128938675,0.140696525574,6.63586139679 --14.739897728,0.138694837689,6.54543161392 --14.6798992157,0.136693283916,6.46200895309 --14.5999088287,0.134692385793,6.39777755737 --14.517914772,0.131690949202,6.30635213852 --14.4389200211,0.12968955934,6.21591901779 --14.3729228973,0.127688288689,6.13249540329 --14.3159236908,0.125687077641,6.0530705452 --14.2449274063,0.123685978353,5.96965122223 --14.1669311523,0.121684938669,5.88221645355 --14.0699424744,0.11968459934,5.813975811 --11.7272844315,0.0646923556924,4.72927904129 --11.7292737961,0.0646930485964,4.6858716011 --11.6412773132,0.0626942291856,4.60643672943 --11.6392679214,0.0616949349642,4.56303834915 --11.6342582703,0.0616956651211,4.51762962341 --11.6352539062,0.0616959929466,4.49642705917 --11.6222457886,0.0606967508793,4.44902515411 --11.633234024,0.0606972798705,4.41062545776 --11.6362247467,0.0606978498399,4.36922359467 --11.6202173233,0.0596986114979,4.31980800629 --11.6192073822,0.059699177742,4.27740812302 --11.6092042923,0.0586995743215,4.25220012665 --11.597196579,0.0587002597749,4.20579528809 --11.6071853638,0.0587006360292,4.16739463806 --11.6111755371,0.058701056987,4.126994133 --11.5911684036,0.0577018223703,4.07758188248 --11.5961589813,0.0577021762729,4.03818559647 --11.6061477661,0.0577024184167,3.99978280067 --11.5841464996,0.0567029938102,3.97157716751 --11.5691394806,0.0557036623359,3.92416167259 --11.5981254578,0.0567034631968,3.89377784729 --11.5981168747,0.0557037815452,3.85237431526 --11.5801105499,0.0557044520974,3.80496382713 --11.587100029,0.0557045824826,3.76555681229 --11.57609272,0.0547050759196,3.72115254402 --11.5810871124,0.0547050759196,3.70295882225 --11.5600805283,0.0537057965994,3.65454173088 --11.4600849152,0.0517084822059,3.58109903336 --11.4490766525,0.0507090240717,3.5376958847 --11.4420690536,0.0507094524801,3.49529004097 --11.432062149,0.0497099533677,3.45188117027 --11.4360523224,0.0497100427747,3.4134824276 --11.4240493774,0.0497104786336,3.38927078247 --11.4240407944,0.049710649997,3.34987163544 --11.4180326462,0.0487109795213,3.30745744705 --11.4190235138,0.0487110689282,3.26906442642 --11.4240140915,0.048711001873,3.23065972328 --11.4170064926,0.0487112924457,3.189255476 --11.4139976501,0.0477114357054,3.14884972572 --11.4119939804,0.0477115139365,3.12864780426 --11.4049863815,0.047711763531,3.08724069595 --11.4109764099,0.0477115288377,3.04984092712 --11.4149684906,0.0477113313973,3.01244592667 --11.4019613266,0.0467117391527,2.96902990341 --11.3999528885,0.0467117205262,2.92962694168 --11.3899497986,0.0457120500505,2.90742111206 --11.3959407806,0.0457116775215,2.87001895905 --11.3929328918,0.0457116365433,2.83061623573 --11.3889255524,0.0457116141915,2.79121518135 --11.4019155502,0.0457108430564,2.75581622124 --11.409907341,0.0457102395594,2.7194185257 --11.3779020309,0.0447113774717,2.67300415039 --11.3438978195,0.0437126234174,2.62558054924 --11.3758907318,0.0447110161185,2.61439323425 --11.3958806992,0.0447097495198,2.58099961281 --11.437869072,0.0457073636353,2.55261325836 --11.4658584595,0.0457055605948,2.52122688293 --11.5008468628,0.0467033274472,2.49083805084 --11.5268373489,0.0467014536262,2.4584479332 --11.7628078461,0.0516887456179,2.47415590286 --11.4808301926,0.0457028895617,2.38981819153 --11.4848222733,0.0457020588219,2.35241723061 --11.6238021851,0.0476939603686,2.34508156776 --11.687789917,0.049689669162,2.32071208954 --11.722779274,0.0496868230402,2.28932547569 --11.7507696152,0.0506842695177,2.25593161583 --11.7777643204,0.0506822168827,2.24173927307 --11.8147544861,0.0516790151596,2.2103536129 --11.8417463303,0.0516763068736,2.17696595192 --11.8727369308,0.0526732541621,2.14357304573 --11.914727211,0.0536694787443,2.11319589615 --11.9437179565,0.053666383028,2.0798099041 --11.982708931,0.0546625480056,2.04742074013 --12.0077028275,0.0546602457762,2.03222966194 --12.0476942062,0.0556561872363,1.99984264374 --12.0856847763,0.0556521713734,1.96746087074 --12.1146774292,0.0566486306489,1.9330728054 --12.154668808,0.0576442815363,1.9006922245 --12.1846599579,0.0576404929161,1.86630654335 --12.2346515656,0.0586351826787,1.83391785622 --12.25664711,0.0596327148378,1.81772828102 --12.2966394424,0.0596279613674,1.78434586525 --12.3206319809,0.0606242194772,1.74795329571 --12.3566236496,0.0606195442379,1.71356904507 --12.391617775,0.0616148561239,1.67918777466 --12.4356088638,0.0626093894243,1.64580929279 --12.5415973663,0.0645991042256,1.62045192719 --12.5945911407,0.0655939131975,1.60828077793 --12.6455841064,0.0665874481201,1.57389509678 --12.7375745773,0.068577773869,1.5465451479 --12.7785673141,0.0685717761517,1.510155797 --12.8175611496,0.0695659220219,1.47478020191 --12.856554985,0.0705599039793,1.43839681149 --12.8955497742,0.0715537071228,1.40100586414 --12.9235458374,0.0715498998761,1.3838198185 --12.9705400467,0.0725429579616,1.34844648838 --13.0125341415,0.0735362097621,1.31105947495 --12.4195594788,0.0605833828449,1.20137524605 --13.0475244522,0.0735266506672,1.23127400875 --12.1595630646,0.0546006150544,1.09344673157 --13.1395139694,0.0755118057132,1.15751934052 --12.2115545273,0.0555922873318,1.04087519646 --12.8915214539,0.0705287232995,1.06980144978 --12.1285495758,0.05459452793,0.954026162624 --12.1785430908,0.0555873326957,0.919646382332 --12.1835393906,0.055584192276,0.881248474121 --12.0495405197,0.0525940544903,0.830783784389 --12.1545314789,0.054581489414,0.801436781883 --11.9845352173,0.0505962707102,0.767144322395 --12.0255308151,0.0515897460282,0.732769489288 --12.2035198212,0.0555696599185,0.707449793816 --13.6554708481,0.0854192450643,0.731359899044 --13.7054672241,0.086409650743,0.690982043743 --12.247505188,0.0555532872677,0.554868459702 --13.7994632721,0.0883930847049,0.631428360939 --12.1395025253,0.0535597652197,0.490214943886 --12.0555009842,0.0515654608607,0.446770519018 --12.0434980392,0.0515636764467,0.407358586788 --12.0954933167,0.0525551177561,0.371986806393 --11.7894954681,0.0465848594904,0.3184222579 --11.8144931793,0.0465807691216,0.301238834858 --11.9674873352,0.0495611391962,0.269912600517 --11.9754838943,0.0495571829379,0.232518583536 --12.052479744,0.051545444876,0.197155326605 --11.9874773026,0.0505494810641,0.156720325351 --11.898475647,0.0485562942922,0.11526530236 --12.0494718552,0.0515358187258,0.0819461643696 --12.0754699707,0.0515310652554,0.0627514347434 --12.202466011,0.0545128621161,0.027417615056 --12.7974596024,0.0664393007755,-0.000682673591655 --14.457452774,0.101238198578,-0.0162424407899 --11.9584589005,0.0495310612023,-0.0919141620398 --12.5664558411,0.0624541342258,-0.123998522758 --11.9904546738,0.050520144403,-0.16770157218 --11.7804527283,0.0455441512167,-0.187004357576 --11.9464502335,0.0495202206075,-0.224321320653 --11.9664487839,0.0495140664279,-0.262717068195 --11.9624452591,0.0495108477771,-0.301125526428 --11.9234428406,0.0485121123493,-0.338545024395 --11.8774404526,0.047514282167,-0.375971794128 --12.0224399567,0.0504918545485,-0.415292233229 --12.2924432755,0.0564547404647,-0.439358323812 --12.271440506,0.0554532669485,-0.477768331766 --11.8824329376,0.047500424087,-0.508378088474 --11.8874311447,0.0474959388375,-0.545772016048 --12.0384321213,0.0514716655016,-0.588096618652 --11.8974285126,0.0484867095947,-0.621569693089 --11.9044265747,0.0484816990793,-0.659971237183 --12.2154331207,0.0544369108975,-0.69000440836 --11.8994245529,0.048476267606,-0.716576814651 --11.8844232559,0.0484742112458,-0.753988802433 --12.0824270248,0.0524420589209,-0.801288843155 --11.9964237213,0.0504499450326,-0.834728062153 --11.920419693,0.0484564453363,-0.869172751904 --11.9584197998,0.0494465641677,-0.909557402134 --11.8714170456,0.0474569797516,-0.923806667328 --11.8374137878,0.0474576503038,-0.959223031998 --12.0824232101,0.0524170957506,-1.01249301434 --12.1014232635,0.0524094887078,-1.05289053917 --11.8914146423,0.0484363101423,-1.07640087605 --11.9904174805,0.0504167340696,-1.1217508316 --12.1084222794,0.0533939823508,-1.16908955574 --12.8324546814,0.0682805851102,-1.24490189552 --12.309431076,0.057355504483,-1.24358510971 --12.2804307938,0.0573548339307,-1.27999734879 --12.1714258194,0.0543665811419,-1.31046497822 --12.181427002,0.0553598850965,-1.34985637665 --12.0984220505,0.0533678457141,-1.38130521774 --16.5506668091,0.14664773643,-1.85231685638 --16.6296749115,0.148629635572,-1.88647270203 --16.6876869202,0.149609401822,-1.94483363628 --16.7446975708,0.150588989258,-2.00420022011 --16.8177127838,0.152565523982,-2.06656455994 --16.8657245636,0.153546318412,-2.1249294281 --16.9467411041,0.155521214008,-2.18828320503 --17.0157489777,0.156503781676,-2.22344398499 --17.072763443,0.158482074738,-2.28581738472 --17.1437778473,0.159458011389,-2.34917449951 --17.0197811127,0.15746717155,-2.38863825798 --17.2168045044,0.161420941353,-2.46892929077 --17.3428249359,0.164386719465,-2.54025244713 --17.2358283997,0.162392646074,-2.58271479607 --17.020816803,0.157424539328,-2.58002257347 --17.1928405762,0.161381557584,-2.65932798386 --16.7618160248,0.152446135879,-2.65295910835 --14.9066734314,0.113768488169,-2.43638157845 --15.082695961,0.117726787925,-2.51068091393 --14.9966964722,0.115732513368,-2.54612445831 --14.6496725082,0.108786471188,-2.54071640968 --14.5946712494,0.107791818678,-2.55594730377 --14.2656478882,0.100843563676,-2.55053019524 --14.5086774826,0.10678870976,-2.63679409027 --14.3906736374,0.103801421821,-2.66425895691 --14.4966907501,0.106771633029,-2.72960186005 --14.3236808777,0.102795042098,-2.74710035324 --13.9476499557,0.094858057797,-2.72771430016 --13.9646587372,0.0958456844091,-2.77610182762 --13.8996543884,0.0938537418842,-2.78733968735 --13.8286533356,0.0928585454822,-2.81978011131 --13.8306598663,0.0928490906954,-2.86517572403 --13.8436689377,0.0938371941447,-2.9135723114 --14.019695282,0.0977926701307,-2.99286746979 --13.8076782227,0.0928258672357,-2.99739098549 --13.6436634064,0.0898544117808,-2.9876871109 --13.7406806946,0.0918254852295,-3.05202817917 --13.3736438751,0.0848916321993,-3.02163791656 --13.1926279068,0.0809201598167,-3.02814364433 --13.1776323318,0.0809145644307,-3.06855177879 --13.182639122,0.0809045955539,-3.11395454407 --13.1796445847,0.0808965116739,-3.15634989738 --13.1556463242,0.080897025764,-3.17356967926 --13.15965271,0.0808872953057,-3.21796512604 --13.0136394501,0.0779097154737,-3.22844862938 --13.1636667252,0.0818683356047,-3.30676412582 --13.0746612549,0.0798785090446,-3.33021903038 --13.0256614685,0.0788801088929,-3.36265063286 --13.2486991882,0.0838217884302,-3.4599199295 --13.1276855469,0.0818437859416,-3.45319414139 --12.8896589279,0.0768875405192,-3.43873357773 --13.1667060852,0.0828163102269,-3.5509698391 --12.9766864777,0.0788496807218,-3.54748296738 --13.2657365799,0.0847744941711,-3.66571736336 --13.1857328415,0.0837831124663,-3.68915891647 --13.3637676239,0.0877323150635,-3.78045296669 --13.338768959,0.0877330005169,-3.79666948318 --13.3487787247,0.0877204313874,-3.84506750107 --13.4538040161,0.0906857252121,-3.91840100288 --13.5188245773,0.0916597768664,-3.98276853561 --13.6848611832,0.0956097319722,-4.07507038116 --14.0399312973,0.103514075279,-4.2212562561 --13.7058839798,0.0965825989842,-4.17485952377 --13.5958709717,0.0946034938097,-4.16712713242 --13.6718940735,0.0965740904212,-4.23547887802 --13.7229137421,0.0975503027439,-4.2978515625 --13.6509113312,0.0965567156672,-4.32329034805 --13.6689252853,0.0975409299135,-4.37567853928 --13.6379299164,0.0965370312333,-4.41410160065 --13.7319583893,0.0995019152761,-4.49044704437 --13.7829742432,0.100483335555,-4.52961301804 --13.7019691467,0.0984919890761,-4.55206012726 --13.7919979095,0.101457200944,-4.62840795517 --13.6559839249,0.0984800383449,-4.63288784027 --13.6229887009,0.0974765345454,-4.67030954361 --13.6049966812,0.097469098866,-4.71272563934 --17.5458011627,0.184429749846,-6.0577454567 --17.5968208313,0.185407340527,-6.10491037369 --17.5448322296,0.184402391315,-6.14933729172 --17.5638580322,0.185378670692,-6.2177233696 --17.3948440552,0.18240480125,-6.22222328186 --17.5559005737,0.186342954636,-6.33952379227 --17.6579437256,0.188296571374,-6.43685531616 --17.5909538269,0.187295362353,-6.47629451752 --17.7239933014,0.191249594092,-6.55441045761 --17.7160148621,0.191232159734,-6.61481189728 --19.6274642944,0.233685985208,-7.3680472374 --17.5890331268,0.189227700233,-6.69568490982 --17.3279972076,0.184280604124,-6.6632437706 --17.6420917511,0.191173359752,-6.84144306183 --17.3510494232,0.185235396028,-6.79601860046 --17.3260536194,0.185232549906,-6.81823396683 --17.2660636902,0.184230059385,-6.85766458511 --17.3261013031,0.186192929745,-6.94402885437 --17.3471336365,0.187166854739,-7.01541423798 --17.3261508942,0.18715301156,-7.06981992722 --17.2361545563,0.185159161687,-7.0972700119 --17.2991828918,0.187130466104,-7.15443325043 --17.3072090149,0.187107846141,-7.22082328796 --17.2872276306,0.18709333241,-7.27623128891 --20.5700950623,0.261095166206,-8.67859268188 --20.3010597229,0.256149113178,-8.64415550232 --21.2003307343,0.276852190495,-9.09198856354 --27.9191417694,0.427788287401,-11.9842195511 --21.3314208984,0.280770212412,-9.26549816132 --22.2527046204,0.301459908485,-9.73631954193 --22.2687473297,0.302424937487,-9.82569980621 --21.3835468292,0.283668428659,-9.52664375305 --21.3205661774,0.282658755779,-9.580078125 --21.0825405121,0.277704268694,-9.55561923981 --20.9185314178,0.274726897478,-9.56311798096 --20.9745674133,0.276695013046,-9.62727832794 --20.992609024,0.27766045928,-9.71465873718 --18.975063324,0.232275828719,-8.88232707977 --21.032699585,0.279589056969,-9.89342308044 --21.6929340363,0.295346200466,-10.2773990631 --22.1221027374,0.306175798178,-10.5595197678 --21.8020496368,0.299248486757,-10.4951152802 --21.6410236359,0.29628559947,-10.4614133835 --20.9288482666,0.280489087105,-10.2082605362 --21.5670833588,0.296247512102,-10.5932435989 --20.8989181519,0.281438827515,-10.3560647964 --20.7719192505,0.279451191425,-10.3755369186 --20.6879329681,0.27744910121,-10.4159851074 --20.8240184784,0.281372517347,-10.5642929077 --20.80103302,0.281365126371,-10.5935020447 --20.5770015717,0.27741086483,-10.5640411377 --20.6280593872,0.279362946749,-10.6703996658 --20.7271327972,0.282297611237,-10.8027305603 --20.8972320557,0.286207079887,-10.9720144272 --21.1093482971,0.292101085186,-11.164270401 --26.5402412415,0.419155091047,-14.064163208 --26.5122623444,0.419143408537,-14.1023740768 --26.464307785,0.419116407633,-14.1847963333 --38.2304611206,0.69486862421,-20.5075969696 --38.1705436707,0.694822192192,-20.6300125122 --38.1256256104,0.695770263672,-20.7604198456 --38.4838562012,0.705571293831,-21.1095638275 --38.7270469666,0.712412893772,-21.3987827301 --39.4993743896,0.731094896793,-21.8994693756 --39.5344963074,0.734009563923,-22.0808238983 --22.7654190063,0.339153677225,-12.9411220551 --22.7284584045,0.340129613876,-13.0145368576 --22.6784954071,0.339110195637,-13.0809621811 --22.6635437012,0.340077489614,-13.1673650742 --25.125535965,0.399105578661,-14.6681375504 --25.1325702667,0.400081157684,-14.7243261337 --37.8205451965,0.703184902668,-22.1583881378 --24.3964710236,0.385232925415,-14.6109800339 --24.3905334473,0.386191874743,-14.7113742828 --37.5228538513,0.703012049198,-22.6220932007 --38.1632194519,0.719687342644,-23.1660499573 --38.1922912598,0.721638798714,-23.2652187347 --35.630355835,0.66158002615,-21.8792934418 --23.4094753265,0.36934247613,-14.6871786118 --35.3985671997,0.660463988781,-22.1985836029 --35.13256073,0.655501902103,-22.1871395111 --35.2576675415,0.659416079521,-22.3422451019 --23.6798095703,0.379081189632,-15.2153644562 --23.6128444672,0.379064708948,-15.2767972946 --35.146938324,0.662249028683,-22.7384605408 --35.4001541138,0.670072495937,-23.0566711426 --35.3552436829,0.670019090176,-23.1850795746 --34.5439910889,0.652287185192,-22.8160057068 --34.4049797058,0.649310469627,-22.8022880554 --34.4100914001,0.651236653328,-22.9616680145 --34.3541755676,0.652189075947,-23.0800857544 --34.4483222961,0.656077027321,-23.2984027863 --34.4794502258,0.657990932465,-23.4767627716 --34.5135765076,0.66090297699,-23.658121109 --34.4206428528,0.660870015621,-23.7535629272 --34.0925445557,0.652976632118,-23.6089782715 --34.109664917,0.65589594841,-23.778345108 --34.1788063049,0.658791780472,-23.9846801758 --34.1909255981,0.660712003708,-24.1530532837 --34.1059989929,0.660674870014,-24.2544937134 --33.9170188904,0.657685101032,-24.2810020447 --33.8511009216,0.658640027046,-24.3944263458 --33.8831748962,0.659587860107,-24.4975967407 --33.891292572,0.662508487701,-24.6649723053 --33.6522903442,0.657541453838,-24.6555194855 --33.6954269409,0.660445988178,-24.8478679657 --33.9226570129,0.668263494968,-25.1780967712 --33.9397888184,0.671178281307,-25.3544635773 --32.8443336487,0.644613325596,-24.7076034546 --32.916431427,0.64754152298,-24.8417453766 --32.5543518066,0.64063668251,-24.7313766479 --32.5414657593,0.641566753387,-24.8827705383 --32.4195137024,0.640548944473,-24.9512367249 --32.2515411377,0.63855355978,-24.9837341309 --32.2686653137,0.640468418598,-25.1591072083 --32.4969100952,0.648280382156,-25.4983310699 --32.7841300964,0.657101511955,-25.8033218384 --32.8392829895,0.66099524498,-26.0126667023 --32.8604164124,0.662905216217,-26.1960334778 --32.8545417786,0.664827764034,-26.359418869 --32.7425994873,0.664802730083,-26.4388809204 --33.7643127441,0.6932092309,-27.4285469055 --33.5843429565,0.691215634346,-27.4580535889 --33.558391571,0.691186666489,-27.524263382 --33.4574623108,0.691153049469,-27.6177158356 --32.169834137,0.658725500107,-26.7380065918 --31.8207511902,0.65182352066,-26.6186351776 --31.1604824066,0.63608288765,-26.2394866943 --31.0535411835,0.636058628559,-26.3159446716 --31.1347179413,0.639935255051,-26.552274704 --31.1457862854,0.641889512539,-26.6444568634 --31.1719284058,0.64479392767,-26.8358249664 --31.1480407715,0.645724356174,-26.9852256775 --31.1111488342,0.646661579609,-27.1236343384 --30.5699367523,0.634868264198,-26.8264064789 --30.5440483093,0.635800242424,-26.9728107452 --30.6152210236,0.640679657459,-27.2041416168 --30.4781990051,0.637712359428,-27.1694316864 --30.7675170898,0.648470580578,-27.597612381 --30.5344963074,0.643514573574,-27.5621604919 --30.5956687927,0.648396134377,-27.7905044556 --30.7729206085,0.655211925507,-28.1257610321 --30.6589794159,0.654189348221,-28.1982269287 --30.7511100769,0.658094465733,-28.3703517914 --30.4430389404,0.652180612087,-28.2659606934 --29.9978713989,0.64234572649,-28.0326690674 --29.8058757782,0.639369308949,-28.0291919708 --29.7079429626,0.638338983059,-28.1136493683 --29.4739170074,0.634387493134,-28.0692043304 --29.3789863586,0.6343562603,-28.1546573639 --29.2800521851,0.634327411652,-28.2361164093 --30.1147136688,0.65879547596,-29.1227035522 --29.9597454071,0.656796693802,-29.1551990509 --29.9218616486,0.658728957176,-29.3006134033 --29.9690380096,0.662609875202,-29.529964447 --29.7900543213,0.65962511301,-29.5394821167 --29.6771144867,0.659601688385,-29.6119480133 --29.5490913391,0.656633138657,-29.5772342682 --30.2137355804,0.679137647152,-30.4241352081 --30.1438331604,0.679085195065,-30.5445728302 --30.0559177399,0.680044054985,-30.6460208893 --29.857919693,0.676069974899,-30.6375522614 --28.5630760193,0.641777634621,-29.507894516 --28.413105011,0.639779627323,-29.5373916626 --28.0438919067,0.629964411259,-29.2498588562 --27.8919181824,0.627969264984,-29.2743587494 --27.9441051483,0.63284432888,-29.5127086639 --27.7861270905,0.63085269928,-29.5312137604 --27.657169342,0.628842890263,-29.5796966553 --27.5292167664,0.62783241272,-29.6291790009 --27.3772411346,0.626838088036,-29.6516819 --27.346288681,0.626811861992,-29.710899353 --27.2113285065,0.625806570053,-29.7513866425 --27.2284927368,0.628701508045,-29.9567623138 --27.2366485596,0.631601810455,-30.1531448364 --27.006608963,0.627659797668,-30.0887050629 --26.8786525726,0.626650094986,-30.1361904144 --27.1720581055,0.63835722208,-30.6523571014 --26.8478565216,0.629527032375,-30.3867988586 --26.6098060608,0.625592470169,-30.3093643188 --26.3527374268,0.62067168951,-30.208946228 --26.2387905121,0.619653820992,-30.2694225311 --26.0557842255,0.616683959961,-30.2499504089 --25.9928836823,0.617631018162,-30.3683872223 --25.9149703979,0.618588268757,-30.4698371887 --25.8730106354,0.618569016457,-30.5170631409 --25.8991928101,0.622452795506,-30.7404308319 --25.8513069153,0.623388290405,-30.8778572083 --25.7603855133,0.624353826046,-30.9653167725 --25.5883865356,0.621377050877,-30.9568367004 --25.5054702759,0.622336566448,-31.0542926788 --25.4484977722,0.621327936649,-31.083530426 --25.4176330566,0.623249530792,-31.2439441681 --25.1735649109,0.619327008724,-31.1445217133 --23.5401554108,0.568430542946,-29.3341617584 --23.5142841339,0.571354568005,-29.4895744324 --24.7046031952,0.613370656967,-31.1600513458 --23.2583446503,0.568354725838,-29.5465545654 --24.4837169647,0.612332105637,-31.2830047607 --24.3997173309,0.61034476757,-31.2762641907 --22.8413181305,0.56242954731,-29.4928607941 --22.7463779449,0.562406539917,-29.5593223572 --24.1239433289,0.611245691776,-31.5286521912 --24.2362308502,0.618053615093,-31.8789577484 --24.1943588257,0.619980812073,-32.0293807983 --22.6478366852,0.570139825344,-30.1037750244 --22.4467887878,0.566198587418,-30.0333251953 --23.3328876495,0.599395751953,-31.4060287476 --23.3460731506,0.603279411793,-31.6294136047 --23.5664844513,0.613996565342,-32.1316337585 --22.310300827,0.57390409708,-30.638004303 --22.4195899963,0.580712378025,-30.9873104095 --22.2705135345,0.577781319618,-30.8856258392 --22.0504398346,0.572858214378,-30.7841892242 --21.9775295258,0.573813617229,-30.8866443634 --21.5352058411,0.562077224255,-30.4713821411 --21.398223877,0.560087800026,-30.4808864594 --20.9548873901,0.548357605934,-30.0546283722 --21.0301437378,0.554190814495,-30.3619651794 --22.1344985962,0.595200538635,-32.0402908325 --20.8752193451,0.553167402744,-30.4416770935 --20.815322876,0.555114150047,-30.5581188202 --21.0157318115,0.565835177898,-31.0543556213 --21.1350536346,0.573622941971,-31.4386577606 --20.8028335571,0.564805328846,-31.1583156586 --21.1063804626,0.579428195953,-31.8204689026 --20.9853229523,0.576480448246,-31.7457618713 --21.5291748047,0.600883483887,-32.7787246704 --21.3581562042,0.597921192646,-32.7422561646 --21.2822532654,0.598873496056,-32.8497085571 --21.2373905182,0.600797832012,-33.0041389465 --21.1404628754,0.600768506527,-33.0806121826 --20.9533233643,0.595882236958,-32.9019584656 --20.6981925964,0.589999198914,-32.7315597534 --20.5522003174,0.588017582893,-32.7270698547 --20.6575336456,0.596800506115,-33.1203842163 --21.7641811371,0.64263677597,-35.1128883362 --20.2123451233,0.586982131004,-32.8665275574 --20.0953903198,0.585973858833,-32.9070205688 --21.7897548676,0.654288828373,-35.7688522339 --21.6798267365,0.654262125492,-35.8413352966 --21.9724464417,0.670844733715,-36.5744972229 --22.4443206787,0.69324618578,-37.6145095825 --21.9028072357,0.676639378071,-36.9763412476 --21.3402576447,0.659057855606,-36.2951927185 --21.2814025879,0.660980224609,-36.4536323547 --21.2985420227,0.663894176483,-36.6128158569 --21.2046413422,0.664850175381,-36.7142906189 --21.2078800201,0.669707119465,-36.9836769104 --21.1410217285,0.671634197235,-37.1341285706 --21.6399898529,0.696976006031,-38.2771224976 --21.4649791718,0.69401049614,-38.2456550598 --20.8453102112,0.673510432243,-37.4245567322 --15.0217485428,0.432551980019,-27.1885089874 --14.9307842255,0.432544797659,-27.2249851227 --13.6870708466,0.383765995502,-25.1764068604 --16.7158622742,0.515421867371,-30.8773193359 --16.6119041443,0.515413939953,-30.9158039093 --16.5269737244,0.515384912491,-30.9902763367 --16.4660816193,0.517330944538,-31.1067237854 --20.4454593658,0.69189119339,-38.6636543274 --20.7582206726,0.710388600826,-39.54479599 --20.0363311768,0.684034407139,-38.4737854004 --20.5644512177,0.712284386158,-39.7757453918 --20.2442035675,0.704484403133,-39.4624061584 --13.0676498413,0.388516098261,-25.8247318268 --12.7412805557,0.377788186073,-25.3854103088 --12.6411972046,0.374853104353,-25.2866954803 --12.5722503662,0.375832945108,-25.3441543579 --12.4952898026,0.375821143389,-25.3876209259 --12.4493846893,0.376772373915,-25.4940624237 --13.1097002029,0.41088321805,-27.0319137573 --12.322511673,0.378716886044,-25.6349716187 --12.2935504913,0.378698468208,-25.6781997681 --12.214589119,0.378688395023,-25.7186717987 --12.1536569595,0.379657149315,-25.7951221466 --5.46176052094,0.0658004507422,-11.9362239838 --5.4437994957,0.0657791048288,-11.9926452637 --12.7252607346,0.418613821268,-27.6448516846 --12.7404880524,0.423476278782,-27.9032421112 --12.6694564819,0.422506511211,-27.8635044098 --12.5834989548,0.422496110201,-27.9049816132 --17.9579124451,0.692452669144,-39.9548721313 --17.9181404114,0.696326076984,-40.1972999573 --18.1799583435,0.715800583363,-41.1214828491 --13.3167695999,0.477033704519,-30.4979724884 --17.9200878143,0.715769052505,-41.2285003662 --17.8641376495,0.715749740601,-41.2747459412 --17.7582511902,0.716701805592,-41.3832321167 --17.594247818,0.715732216835,-41.3577728271 --12.7106056213,0.46723228693,-30.2672996521 --12.5254592896,0.462349414825,-30.0908584595 --12.408454895,0.461372584105,-30.0753650665 --12.4127016068,0.467226833105,-30.3487625122 --12.3557024002,0.466235548258,-30.3460140228 --12.2427053452,0.465253412724,-30.339515686 --12.1948471069,0.468178927898,-30.4909591675 --12.0978841782,0.467173486948,-30.5244445801 --12.0470237732,0.47010037303,-30.6738948822 --15.8988466263,0.689266562462,-40.6940155029 --9.48377418518,0.337618529797,-24.692899704 --9.41071033478,0.335668236017,-24.6191654205 --9.31970500946,0.334687024355,-24.6096496582 --9.22769737244,0.333707034588,-24.5981330872 --9.14270591736,0.332716077566,-24.6056156158 --8.18365192413,0.282083511353,-22.2828521729 --8.09262275696,0.280116021633,-22.2493362427 --7.53647232056,0.251884937286,-20.9522266388 --7.50849199295,0.251877754927,-20.9754543304 --7.32121133804,0.244073718786,-20.6610221863 --7.21212053299,0.242145195603,-20.5605297089 --7.12909126282,0.240176349878,-20.5290126801 --7.05708837509,0.240190029144,-20.5274829865 --7.02919816971,0.24213039875,-20.6519145966 --7.00522518158,0.243118450046,-20.6831359863 --6.93823766708,0.242122381926,-20.6986045837 --6.98755216599,0.249929487705,-21.0519676208 --7.02885437012,0.256745517254,-21.3903388977 --6.63298797607,0.235319897532,-20.4251003265 --6.55496454239,0.234346911311,-20.4005775452 --6.48295593262,0.233364000916,-20.3930473328 --6.43100357056,0.234345108271,-20.4475021362 --6.38597393036,0.233369961381,-20.4157447815 --6.31496906281,0.233384862542,-20.4122200012 --6.37734460831,0.241154581308,-20.8305702209 --6.86095714569,0.279130905867,-22.6155509949 --6.12902545929,0.233383923769,-20.4796047211 --6.06303215027,0.233391180634,-20.4890708923 --6.14939594269,0.241164281964,-20.8912010193 --6.08340787888,0.241168737411,-20.9056682587 --6.00137138367,0.240204021335,-20.8671531677 --5.95845460892,0.241163253784,-20.9595985413 --5.92055463791,0.243111491203,-21.0710411072 --6.28795337677,0.275233864784,-22.6071224213 --6.22399330139,0.276221901178,-22.650592804 --6.16592550278,0.274271667004,-22.575843811 --6.09694766998,0.274271219969,-22.5993156433 --6.05706453323,0.276210457087,-22.7267589569 --6.00313949585,0.278176516294,-22.8082199097 --5.92914772034,0.278185427189,-22.8156967163 --5.92338895798,0.2830465734,-23.0781059265 --8.2097492218,0.474792420864,-32.1804924011 --5.79132795334,0.281105935574,-23.0098419189 --5.71834039688,0.281111985445,-23.0223178864 --5.65639066696,0.281094253063,-23.0757808685 --5.59946393967,0.283062249422,-23.1542453766 --5.55558490753,0.285000085831,-23.2846927643 --5.45951128006,0.283060520887,-23.2031917572 --5.40157938004,0.284031808376,-23.2756481171 --5.33145427704,0.281116932631,-23.1399173737 --5.26047325134,0.281118988991,-23.1593933105 --5.21058082581,0.283066362143,-23.2738494873 --5.1446223259,0.284054636955,-23.3173217773 --5.08870363235,0.285018026829,-23.4037799835 --5.16836214066,0.299623727798,-24.1101169586 --4.8171916008,0.273363888264,-22.8508472443 --4.78722143173,0.273351967335,-22.8830776215 --4.72829055786,0.274323582649,-22.9555454254 --4.65529584885,0.274333804846,-22.9610214233 --4.58732366562,0.275330781937,-22.9894962311 --5.30901622772,0.357070714235,-26.9342575073 --5.21699762344,0.356099426746,-26.9087505341 --5.13401985168,0.356102794409,-26.927236557 --5.09504127502,0.356098085642,-26.9474773407 --4.9437289238,0.348306536674,-26.6100273132 --4.41449928284,0.298688322306,-24.2339134216 --4.33549451828,0.298706352711,-24.226398468 --4.22834014893,0.29481524229,-24.0609054565 --4.18351364136,0.298724621534,-24.2423591614 --4.10752105713,0.298735141754,-24.2478408813 --4.05444669724,0.296788007021,-24.1680984497 --3.91610693932,0.28900963068,-23.8066368103 --3.84110713005,0.288024038076,-23.8051128387 --3.76913404465,0.2890227139,-23.8315944672 --3.70923018456,0.290979355574,-23.9310646057 --3.59096932411,0.284151792526,-23.6545791626 --3.52479457855,0.280264794827,-23.4698467255 --3.4387242794,0.279321968555,-23.3943424225 --3.38082885742,0.28127348423,-23.5028076172 --3.3330051899,0.284182071686,-23.6862659454 --3.26404166222,0.285174906254,-23.722738266 --3.19709825516,0.286155849695,-23.7802143097 --3.12813854218,0.286146491766,-23.8206882477 --3.09618473053,0.287126541138,-23.8679294586 --3.01211619377,0.286182492971,-23.7944164276 --2.93409514427,0.285209983587,-23.7709026337 --2.85909676552,0.285224348307,-23.7703876495 --1.78858149052,0.123726956546,-15.9542121887 --1.73050653934,0.122780762613,-15.8826818466 --2.57388734818,0.279401093721,-23.5470943451 --2.50090289116,0.279407024384,-23.561580658 --2.43598389626,0.281373977661,-23.6440563202 --2.64804315567,0.345587611198,-26.8064899445 --2.57919359207,0.348516315222,-26.9569683075 --2.48105573654,0.345615267754,-26.8094711304 --2.43804693222,0.345629364252,-26.7977199554 --2.36314415932,0.347589582205,-26.8932037354 --2.2973446846,0.351489335299,-27.0946788788 --2.2305521965,0.355385243893,-27.303155899 --2.22349405289,0.374851286411,-28.2655849457 --2.12638449669,0.37193390727,-28.1470890045 --3.77076435089,0.965462863445,-57.1592178345 --2.50013113022,0.616182863712,-40.1236839294 --3.4057097435,0.961576163769,-57.0323905945 --4.12091732025,1.27779138088,-72.5082855225 --2.75024151802,0.948990523815,-56.4314651489 --2.5865240097,0.953867673874,-56.6840400696 --2.91216015816,1.29636538029,-73.4887313843 --2.67399597168,1.29251372814,-73.2703781128 --2.3207719326,1.28572285175,-72.9663391113 --2.0928144455,1.28575205803,-72.9579772949 --1.86487555504,1.28577065468,-72.9686126709 --1.64008355141,1.28870546818,-73.1272506714 --1.41634333134,1.2926107645,-73.3378829956 --1.19062173367,1.2975063324,-73.5665206909 -0.436139553785,1.47522711754,-78.0873947144 -0.316977977753,0.737910926342,-43.8351478577 -0.456995606422,0.738884568214,-43.8764266968 -0.597045958042,0.739876925945,-43.9506988525 -0.743451952934,0.749069035053,-44.3829650879 -1.28287506104,0.847436189651,-48.9206161499 -1.35877156258,0.84535831213,-48.8307533264 -2.12304067612,1.13568222523,-62.3176651001 -2.32819342613,1.13971734047,-62.5148773193 -2.52512001991,1.13962638378,-62.4831047058 -2.87044715881,1.21342504025,-65.9031448364 -3.10086464882,1.22360408306,-66.3733291626 -3.19155478477,1.21740591526,-66.0814437866 -3.40355062485,1.2183508873,-66.123664856 -3.63185667992,1.22646772861,-66.481842041 -3.83568239212,1.22331857681,-66.3510742188 -3.91044282913,1.17503118515,-64.1114425659 -4.12964105606,1.18108952045,-64.3586425781 -4.26612997055,1.1923327446,-64.8807144165 -4.40513515472,1.17173492908,-63.9080123901 -4.61113119125,1.17268204689,-63.9482307434 -4.8161149025,1.17362236977,-63.9754524231 -5.10210084915,1.19611120224,-65.0325775146 -5.32221889496,1.20012450218,-65.1997833252 -3.79615807533,0.756130635738,-44.6089324951 -5.63315391541,1.20101177692,-65.2011108398 -5.88762140274,1.21221518517,-65.7292785645 -5.97832584381,1.18445920944,-64.4396286011 -6.17418193817,1.18333005905,-64.3358612061 -6.52456712723,1.21503043175,-65.8129272461 -6.63052654266,1.19341540337,-64.7832641602 -6.83546257019,1.1933298111,-64.7624816895 -6.95963335037,1.19739687443,-64.9625778198 -7.46016740799,1.25571215153,-67.6364822388 -7.49456548691,1.2217965126,-66.0218887329 -7.69139766693,1.21865475178,-65.8951263428 -4.8456864357,0.664337515831,-40.2315864563 -4.93535280228,0.657126665115,-39.9049224854 -5.05022954941,0.655028641224,-39.7962379456 -5.10717153549,0.653981804848,-39.745388031 -5.36010551453,0.654883384705,-39.7169876099 -5.50117826462,0.656890690327,-39.8132705688 -5.6301612854,0.65684992075,-39.8155670166 -5.7520980835,0.65678447485,-39.7688713074 -5.90221357346,0.659814298153,-39.911151886 -5.99840831757,0.664901375771,-40.1252670288 -6.14750814438,0.667922198772,-40.2505455017 -9.45706367493,1.11521816254,-60.8525810242 -9.60572910309,1.10899448395,-60.5428657532 -6.46500778198,0.658563196659,-39.7855148315 -6.59297943115,0.659516751766,-39.7758102417 -6.71793460846,0.658461987972,-39.7491149902 -6.72761726379,0.652279675007,-39.4233207703 -6.73593950272,0.636893570423,-38.7257423401 -6.87197256088,0.638880252838,-38.7800369263 -6.99795103073,0.638838291168,-38.7763366699 -7.13598585129,0.640825510025,-38.8326301575 -7.27603530884,0.642820954323,-38.904914856 -8.94913387299,0.831017911434,-47.5284500122 -9.09405422211,0.830939114094,-47.4717407227 -7.52665662766,0.636547625065,-38.5497398376 -7.65463972092,0.636508285999,-38.5510444641 -7.80272293091,0.639521181583,-38.659324646 -12.927737236,1.17836844921,-63.2866744995 -13.1156024933,1.1772493124,-63.1869316101 -9.83035182953,0.820373058319,-46.8783950806 -9.96925735474,0.819287717342,-46.8046875 -13.614397049,1.17702114582,-63.0805358887 -13.8534841537,1.18101680279,-63.2197418213 -14.0584230423,1.18093657494,-63.1999816895 -6.18691778183,0.390772819519,-27.1701469421 -6.26586055756,0.389721781015,-27.1154956818 -6.54743146896,0.404980063438,-27.7428531647 -6.23348093033,0.358946621418,-25.6480197906 -6.33152198792,0.360946685076,-25.697347641 -6.4717168808,0.366024821997,-25.9146347046 -6.58380174637,0.368047118187,-26.0129508972 -7.39525318146,0.42824986577,-28.6867980957 -8.19810009003,0.452547162771,-29.6623706818 -8.69936466217,0.46158400178,-29.9926013947 -8.78831195831,0.461534291506,-29.9449424744 -8.8282699585,0.460501760244,-29.9041194916 -8.91621494293,0.46045088768,-29.8534622192 -8.9931268692,0.45938411355,-29.7668132782 -9.07605552673,0.45832529664,-29.6981658936 -9.15898609161,0.457267671824,-29.6315155029 -9.24191951752,0.456211179495,-29.566865921 -9.32384967804,0.455154031515,-29.500213623 -9.35779476166,0.45411503315,-29.443397522 -9.44072914124,0.45406037569,-29.3817462921 -9.50461006165,0.451979011297,-29.2591152191 -9.61361980438,0.452960014343,-29.2784404755 -9.73165225983,0.453952789307,-29.3247566223 -21.9234313965,1.27780783176,-65.8578414917 -13.5140218735,0.692421257496,-39.8073043823 -13.6219177246,0.691339433193,-39.7116355896 -13.7649049759,0.692302048206,-39.7189369202 -13.9169149399,0.693275392056,-39.7512283325 -18.7017269135,0.994909524918,-53.0142478943 -18.9598712921,1.00093650818,-53.2114448547 -15.1077661514,0.745065689087,-41.8954315186 -22.0337314606,1.17914915085,-60.9792861938 -24.680644989,1.33291924,-67.6793060303 -24.8985424042,1.33281695843,-67.6155471802 -25.1555290222,1.33575677872,-67.6527633667 -25.3032550812,1.33157444,-67.3980789185 -25.4319438934,1.32637310028,-67.0964050293 -24.8760433197,1.28042340279,-64.9993515015 -26.2328834534,1.3547372818,-68.2403411865 -21.39320755,1.0551854372,-55.056186676 -21.5460681915,1.05407679081,-54.9374847412 -21.733001709,1.05400216579,-54.9017601013 -27.2938499451,1.3665034771,-68.4141769409 -22.308839798,1.0567959547,-54.834564209 -27.9016914368,1.37029409409,-68.3697509766 -28.1877155304,1.37325084209,-68.4519348145 -28.3284320831,1.3690649271,-68.182258606 -28.7327022552,1.38013517857,-68.5453491211 -20.9239215851,0.937325000763,-49.3727912903 -29.5762958527,1.40229904652,-69.3344955444 -29.7754135132,1.40632641315,-69.4995422363 -31.1406059265,1.468277812,-72.0717697144 -28.702123642,1.32570385933,-65.8243942261 -28.9230270386,1.32560622692,-65.7636489868 -27.309627533,1.19391751289,-59.7480964661 -27.4925041199,1.19381296635,-59.6493797302 -31.9768733978,1.40103960037,-68.2993240356 -24.5276985168,1.01660478115,-51.8703346252 -24.6986160278,1.01652443409,-51.8076286316 -24.6713695526,1.01139330864,-51.5398712158 -24.9464740753,1.01639795303,-51.6970748901 -25.2596416473,1.02443134785,-51.9302368164 -18.8557224274,0.698044061661,-38.0507316589 -18.91655159,0.694936811924,-37.8701171875 -18.9683685303,0.691824913025,-37.6755027771 -18.973241806,0.68975353241,-37.5367164612 -19.2404251099,0.696803748608,-37.7719192505 -19.4725437164,0.701825082302,-37.9321556091 -31.0750045776,1.20729672909,-58.6760978699 -33.4323425293,1.30570077896,-62.6755180359 -33.6081809998,1.3045771122,-62.5298156738 -37.4777984619,1.46995639801,-69.2449417114 -30.0427742004,1.12770521641,-55.0167808533 -30.1044902802,1.12253582478,-54.7171783447 -30.124332428,1.11944508553,-54.5493850708 -30.2721805573,1.1183347702,-54.4107055664 -30.4400634766,1.11823821068,-54.309009552 -30.6470012665,1.11916649342,-54.2762832642 -30.8529396057,1.12109351158,-54.2405548096 -31.1039428711,1.12404930592,-54.2847938538 -28.7090930939,1.0143699646,-49.7102813721 -28.833108902,1.01635479927,-49.744392395 -29.0330657959,1.01829397678,-49.7266731262 -39.4605941772,1.45137822628,-67.2292861938 -39.5562782288,1.44618833065,-66.9066619873 -39.8001785278,1.44708871841,-66.8399200439 -40.0590934753,1.44899642467,-66.7951507568 -40.3260192871,1.45190834999,-66.7623901367 -40.5250740051,1.45590162277,-66.8544540405 -40.7008743286,1.45376086235,-66.668762207 -40.9537811279,1.45566439629,-66.6110076904 -41.1976776123,1.45656251907,-66.5372695923 -41.5166702271,1.46150195599,-66.5844573975 -42.1380577087,1.47760367393,-67.1123962402 -42.3711471558,1.48261117935,-67.2494354248 -33.7727432251,1.05571758747,-48.9414863586 -33.8845787048,1.05360949039,-48.7748451233 -32.0251274109,0.978597700596,-45.7678184509 -32.1880378723,0.979522943497,-45.6931381226 -32.5641975403,0.987543880939,-45.9212760925 -42.0276679993,1.32959342003,-58.9730033875 -42.1864929199,1.32847201824,-58.8043327332 -42.3004455566,1.3294261694,-58.7674674988 -23.3259220123,0.530301094055,-25.9226531982 -23.4278774261,0.531260550022,-25.8720111847 -23.5178222656,0.531216323376,-25.8073787689 -23.5567245483,0.530157148838,-25.6857891083 -23.7017803192,0.533163607121,-25.7628974915 -23.8017368317,0.534122943878,-25.7102546692 -23.8836746216,0.534076333046,-25.6356315613 -48.8458709717,1.28527760506,-50.9748840332 -47.8968467712,1.25188553333,-49.6620788574 -45.8419685364,1.18421721458,-47.2181167603 -44.1734161377,1.12866044044,-45.1998519897 -42.4718666077,1.073107481,-43.1726074219 -39.2551689148,0.971190392971,-39.6265182495 -38.6776275635,0.951993346214,-38.9151878357 -38.551322937,0.944855690002,-38.5427360535 -38.5661392212,0.941753327847,-38.3141784668 -38.5078964233,0.935634672642,-38.0146789551 -38.3745994568,0.928499698639,-37.6432342529 -38.5815582275,0.930445194244,-37.6095352173 -38.6664276123,0.929362118244,-37.4549217224 -38.7273750305,0.929325163364,-37.39610672 -38.7161750793,0.926221430302,-37.1495666504 -38.7129821777,0.922120273113,-36.9120254517 -38.8208694458,0.9220443964,-36.7823944092 -26.8352241516,0.569360971451,-25.1638565063 -26.476852417,0.556220173836,-24.6665687561 -24.6914920807,0.50278198719,-22.8353500366 -24.40924263,0.493694156408,-22.4987812042 -23.7476787567,0.472501069307,-21.7407188416 -22.8909931183,0.445272773504,-20.8118000031 -22.7197780609,0.438186883926,-20.5223655701 -22.4465007782,0.429082334042,-20.1430053711 -22.4454040527,0.42703256011,-20.0134449005 -22.3392887115,0.422987431288,-19.8537425995 -22.2991695404,0.419930875301,-19.6902122498 -22.373128891,0.419897258282,-19.6315917969 -22.1588993073,0.412809640169,-19.3161888123 -22.2448654175,0.412778317928,-19.2675647736 -21.5853557587,0.392612576485,-18.567489624 -18.8224849701,0.313056647778,-15.9941902161 -17.0633125305,0.262712538242,-14.3759279251 -16.9361724854,0.257658392191,-14.174454689 -16.6179161072,0.247572734952,-13.812122345 -16.0495109558,0.230447337031,-13.2429714203 -16.1655273438,0.232437461615,-13.2543182373 -8.22769355774,0.0141221405938,-6.54568004608 -8.22168159485,0.0131163252518,-6.51889753342 -8.3056974411,0.0141104515642,-6.50168085098 -8.33369636536,0.0141052296385,-6.48108577728 -8.35169124603,0.0140985483304,-6.45249652863 -8.3776884079,0.0140932211652,-6.43089580536 -8.40769004822,0.0150884641334,-6.41229438782 -8.40568161011,0.0140836378559,-6.38950490952 -8.43968391418,0.0150792542845,-6.37291097641 -8.46468257904,0.0150738433003,-6.35031175613 -8.49668312073,0.0150693310425,-6.33271217346 -8.50967502594,0.0150621999055,-6.30012750626 -8.54667949677,0.015058436431,-6.28652143478 -8.56167888641,0.0150560280308,-6.27672386169 -8.57667255402,0.0150493625551,-6.24613332748 -8.6056728363,0.0160444192588,-6.22553920746 -8.63367271423,0.0160395242274,-6.20493745804 -8.64966583252,0.0160331595689,-6.17534446716 -8.68967151642,0.0160296019167,-6.16274309158 -8.70266437531,0.0160229932517,-6.13114976883 -8.72266578674,0.0160211268812,-6.12435293198 -8.75266647339,0.0160164851695,-6.10475206375 -8.78066730499,0.0170115269721,-6.08315706253 -8.80566501617,0.0170062854886,-6.05956220627 -8.83066272736,0.0170010738075,-6.03596639633 -8.8566608429,0.0169958658516,-6.01237726212 -8.87965869904,0.0169905778021,-5.9877781868 -8.89265823364,0.0169879999012,-5.97598266602 -8.91365432739,0.0169824417681,-5.94939041138 -8.9516582489,0.0179786756635,-5.93478441238 -8.98466014862,0.0179743133485,-5.91618585587 -9.0026550293,0.0179683733732,-5.88660335541 -9.02365207672,0.0179629400373,-5.86000967026 -9.06065559387,0.0189590677619,-5.84440279007 -9.07065391541,0.0189562980086,-5.83060741425 -9.09965324402,0.0189516004175,-5.80901050568 -9.14566135406,0.0189483761787,-5.7984046936 -9.16265583038,0.0189426466823,-5.76881456375 -9.14963722229,0.0189343616366,-5.71924781799 -9.20865058899,0.0199323520064,-5.71762418747 -9.24165821075,0.0199315715581,-5.71881151199 -9.26765727997,0.0199265480042,-5.69422245026 -9.30466079712,0.0209225770086,-5.67761564255 -13.4234399796,0.123234413564,-8.2661190033 -13.4604282379,0.123222887516,-8.23052310944 -12.4129524231,0.096131362021,-7.51268291473 -13.1732521057,0.115173920989,-7.93358039856 -13.1672363281,0.114166907966,-7.90179538727 -13.0551643372,0.111145786941,-7.77530384064 -13.2132053375,0.114143647254,-7.81661748886 -13.2591981888,0.115133620799,-7.78801393509 -13.207151413,0.113117203116,-7.69948101044 -13.2051258087,0.112104281783,-7.64191150665 -13.2201080322,0.112092457712,-7.59433317184 -13.1720762253,0.11008348316,-7.53857469559 -13.4081459045,0.115084968507,-7.62283706665 -13.4071216583,0.11507216841,-7.56527042389 -13.1349906921,0.108044818044,-7.3508849144 -13.0629396439,0.10502910614,-7.25436353683 -13.0799236298,0.105018369853,-7.20978021622 -13.1329221725,0.106009587646,-7.18616867065 -13.2349491119,0.108008921146,-7.21731042862 -13.1608991623,0.105993807316,-7.1207909584 -13.10085392,0.103979766369,-7.03325986862 -13.1458482742,0.103970691562,-7.00465774536 -13.3368968964,0.107967734337,-7.05595874786 -13.2408399582,0.104952663183,-6.9494509697 -13.2888469696,0.105949096382,-6.94863367081 -13.3848600388,0.107942119241,-6.94798803329 -13.3758354187,0.106930688024,-6.88842868805 -13.3688116074,0.106919623911,-6.83086299896 -13.6138753891,0.111917339265,-6.90712451935 -13.5138187408,0.108903251588,-6.80061817169 -13.498793602,0.107892163098,-6.73905754089 -13.5828113556,0.109889507294,-6.7562122345 -13.5037631989,0.106876686215,-6.66169500351 -13.6547927856,0.109870575368,-6.68601942062 -13.7498035431,0.11186259985,-6.6803855896 -13.5877304077,0.107848249376,-6.54492282867 -13.6537313461,0.108839802444,-6.5253033638 -16.1085147858,0.165888875723,-7.7188873291 -13.5926818848,0.106823451817,-6.41499137878 -13.6256732941,0.10681450367,-6.37939119339 -13.6866722107,0.107805788517,-6.35578393936 -13.8517045975,0.110798723996,-6.38210678101 -13.6956367493,0.106786705554,-6.25463676453 -13.6936168671,0.106777392328,-6.20206022263 -13.8036403656,0.108774006367,-6.22720718384 -13.7626094818,0.107764184475,-6.15566062927 -13.860619545,0.108755946159,-6.1490240097 -13.8716039658,0.108746759593,-6.10144662857 -13.9426059723,0.10973816365,-6.08182621002 -13.9335851669,0.109728984535,-6.02526044846 -13.9525718689,0.109720088542,-5.98167514801 -14.0415878296,0.110715851188,-5.99483585358 -14.1596031189,0.113707222044,-5.99518299103 -14.2176008224,0.114698193967,-5.96757698059 -14.6677064896,0.123689159751,-6.11170768738 -14.5996685028,0.121679678559,-6.02718687057 -14.6226558685,0.122670412064,-5.98359632492 -14.8046855927,0.125660419464,-6.00690937042 -15.0007276535,0.129654675722,-6.06200218201 -15.0147123337,0.129645183682,-6.01341772079 -15.1287212372,0.131634891033,-6.00577449799 -15.3957710266,0.137622997165,-6.0600361824 -15.4707698822,0.138612702489,-6.03541135788 -15.499756813,0.139602705836,-5.99082279205 -17.4352340698,0.182574659586,-6.74180746078 -17.4942245483,0.183561906219,-6.70220136642 -17.5592155457,0.184549048543,-6.66459274292 -17.5901985168,0.184536606073,-6.61300802231 -17.6561889648,0.185523718596,-6.57539796829 -17.6961727142,0.186511322856,-6.52780246735 -17.7411594391,0.186498910189,-6.48220252991 -17.7781562805,0.187492325902,-6.46439599991 -17.8291416168,0.187479615211,-6.41979885101 -17.8801307678,0.188466921449,-6.37519979477 -17.9421195984,0.18945401907,-6.33459329605 -17.9671001434,0.189441978931,-6.28001117706 -18.0280914307,0.190429240465,-6.23939943314 -18.0840797424,0.191416442394,-6.19579792023 -18.1270751953,0.19140958786,-6.1789894104 -18.1670608521,0.192397251725,-6.12939691544 -18.2370510101,0.193383961916,-6.08978843689 -18.2680339813,0.193372011185,-6.03719806671 -18.3400249481,0.194358617067,-5.99758958817 -18.373008728,0.195346578956,-5.94500112534 -18.4359970093,0.196333542466,-5.90239429474 -18.4649925232,0.196327000856,-5.87959575653 -18.5239810944,0.197314053774,-5.83499288559 -18.5679645538,0.198301687837,-5.78539800644 -18.6209506989,0.19828902185,-5.73879623413 -18.6739387512,0.19927623868,-5.69119930267 -18.7229251862,0.200263693929,-5.64260196686 -18.7629203796,0.200256898999,-5.62378883362 -18.8289089203,0.201243489981,-5.57918739319 -18.8778953552,0.202231034636,-5.53058576584 -18.9168815613,0.203218907118,-5.47799539566 -18.9848690033,0.204205408692,-5.43339109421 -19.0158519745,0.204193651676,-5.37780714035 -19.0988445282,0.205179601908,-5.33818674088 -19.1338386536,0.206172868609,-5.31638050079 -19.1778240204,0.207160487771,-5.26379060745 -19.2318096161,0.207147657871,-5.21419286728 -19.2937965393,0.208134427667,-5.16659069061 -19.3257808685,0.209122851491,-5.11100149155 -19.3947696686,0.210109308362,-5.06539154053 -19.4397544861,0.210096895695,-5.01180362701 -19.4967536926,0.211088910699,-4.99498414993 -19.5377368927,0.212076798081,-4.94039487839 -19.6067256927,0.21306322515,-4.89378452301 -19.6517105103,0.21405094862,-4.84019088745 -19.7136974335,0.215037673712,-4.79058837891 -19.758682251,0.21502533555,-4.73599910736 -19.8226699829,0.216011926532,-4.6863951683 -19.8616657257,0.217004850507,-4.66358661652 -19.9386539459,0.217990621924,-4.61697387695 -19.9736366272,0.218978986144,-4.55938768387 -20.0376243591,0.219965413213,-4.50779008865 -20.0946102142,0.220952406526,-4.45519065857 -20.1485977173,0.221939593554,-4.40159320831 -20.1945915222,0.22293202579,-4.37977838516 -20.2595787048,0.223918452859,-4.3281750679 -20.3075637817,0.223905906081,-4.27158737183 -20.3775501251,0.225892022252,-4.22097730637 -20.4295349121,0.22587929666,-4.16538381577 -20.4915218353,0.226865887642,-4.11178255081 -20.5485095978,0.227852866054,-4.05718278885 -20.6095046997,0.228843972087,-4.03636550903 -20.6504898071,0.229832082987,-3.97777581215 -20.7244758606,0.230817705393,-3.92517089844 -20.7804641724,0.23180475831,-3.86956954002 -20.8404483795,0.232791334391,-3.81297636032 -20.8944320679,0.233778551221,-3.75637674332 -20.9774208069,0.235763475299,-3.70476222038 -21.0114154816,0.235756456852,-3.67696237564 -21.066400528,0.236743539572,-3.6193652153 -21.1353874207,0.237729460001,-3.56376194954 -21.1953716278,0.238716095686,-3.50616407394 -21.255355835,0.239702746272,-3.448564291 -21.3343429565,0.241687715054,-3.39295983315 -21.379327774,0.24267564714,-3.33236718178 -21.4573249817,0.243664965034,-3.31153798103 -21.5123081207,0.244651898742,-3.25094723701 -21.5742950439,0.245638370514,-3.19234538078 -21.6242790222,0.24662579596,-3.13075518608 -21.7162666321,0.248609647155,-3.07613706589 -21.7542495728,0.248598173261,-3.01255106926 -21.8182449341,0.250588327646,-2.98673677444 -21.8932304382,0.251573592424,-2.92813038826 -21.9492149353,0.25256049633,-2.86653399467 -22.0282020569,0.253545254469,-2.80693054199 -22.0811843872,0.254532456398,-2.74433541298 -22.1441688538,0.255518764257,-2.6827352047 -22.2081546783,0.257504850626,-2.62013912201 -16.3887310028,0.135050863028,-1.8425732851 -16.4117259979,0.13504563272,-1.79398727417 -16.3027076721,0.13205306232,-1.72848141193 -16.2766990662,0.132052719593,-1.67392539978 -16.3006916046,0.132047608495,-1.62534189224 -16.2566795349,0.131049215794,-1.56879794598 -16.261674881,0.131047427654,-1.54400777817 -16.2706680298,0.131043925881,-1.49343526363 -16.3176612854,0.132036671042,-1.44684135914 -16.3276557922,0.132033154368,-1.39626789093 -16.4296531677,0.134020373225,-1.3556355238 -23.0259876251,0.272340714931,-1.924497962 -22.9249629974,0.27034381032,-1.84298801422 -22.2669219971,0.256408542395,-1.74855732918 -23.0559425354,0.272319465876,-1.74657011032 -22.2768878937,0.256394326687,-1.60942363739 -22.2628688812,0.255389302969,-1.53787004948 -22.2048492432,0.254389107227,-1.46333801746 -22.1858291626,0.254384875298,-1.39178681374 -22.1308116913,0.25238469243,-1.31825256348 -9.67533302307,-0.00826385989785,-0.426196187735 -9.66533756256,-0.00825964938849,-0.394636124372 -9.65734195709,-0.00825568567961,-0.364063888788 -9.66934776306,-0.00825397763401,-0.335470348597 -9.65935230255,-0.00824960879982,-0.303912341595 -9.67035675049,-0.00824774522334,-0.275317758322 -9.66736030579,-0.0082457344979,-0.259539544582 -9.66436481476,-0.00824221223593,-0.229956194758 -9.65436935425,-0.00823777168989,-0.199386462569 -9.65137386322,-0.00823404733092,-0.168818071485 -9.64637947083,-0.00823016557842,-0.139236092567 -9.64738464355,-0.00822680070996,-0.108668327332 -9.65439033508,-0.00822419393808,-0.0790861621499 -9.64539337158,-0.00922145694494,-0.0642964616418 -9.65439891815,-0.00821891985834,-0.033727414906 -9.6544046402,-0.00821543578058,-0.00414570281282 -9.64940929413,-0.00921133067459,0.0254345163703 -9.64141559601,-0.00920670758933,0.0559997558594 -9.64442062378,-0.00920346193016,0.0855817124248 -9.65042686462,-0.0092005468905,0.115164972842 -9.63643074036,-0.00919690914452,0.130936354399 -9.633436203,-0.0091928485781,0.16051581502 -9.63744163513,-0.00918960664421,0.190098255873 -9.64544773102,-0.00918670743704,0.220669105649 -9.63345432281,-0.00918142218143,0.250243574381 -9.63346004486,-0.00917758792639,0.27982416749 -9.63646697998,-0.00917397160083,0.310392707586 -9.63246917725,-0.00917151756585,0.325180441141 -9.61647605896,-0.00916554406285,0.354749828577 -9.62148189545,-0.00916222389787,0.384333521128 -9.62348842621,-0.00915835704654,0.414901345968 -9.61849498749,-0.00915367342532,0.444477558136 -9.62750148773,-0.00915080495179,0.474065631628 -9.61950492859,-0.00914770085365,0.488848805428 -9.6125125885,-0.00914265308529,0.518422603607 -9.61151885986,-0.00913836993277,0.548001766205 -9.62052536011,-0.00913527887315,0.578577280045 -9.61053276062,-0.00912970304489,0.608147263527 -9.60753917694,-0.0091250455007,0.637724339962 -9.60854625702,-0.00912091042846,0.667305886745 -9.61754989624,-0.0091198803857,0.683092713356 -9.61155605316,-0.00911472178996,0.712666392326 -9.61256408691,-0.00911051873118,0.742248535156 -9.60657024384,-0.00910528283566,0.771821796894 -9.60457801819,-0.00910043716431,0.802386105061 -9.59858608246,-0.00909512117505,0.831958830357 -9.60859298706,-0.00909211300313,0.861554086208 -9.59559726715,-0.00908795371652,0.876325964928 -9.57360458374,-0.010080316104,0.904887855053 -9.59961128235,-0.00907932873815,0.93648058176 -9.59261894226,-0.00907369982451,0.966051161289 -9.69662284851,-0.00708364695311,1.0036906004 -9.74562835693,-0.00608583912253,1.03828918934 -9.73463344574,-0.00608190521598,1.05306506157 -9.72164154053,-0.00607552053407,1.08164465427 -9.70065021515,-0.00706784008071,1.11020898819 -9.71565628052,-0.0060652596876,1.14179587364 -9.71666431427,-0.00606063241139,1.17237198353 -9.72567176819,-0.00605709385127,1.20394992828 -9.70868015289,-0.00604986213148,1.23251986504 -9.71068382263,-0.00604767166078,1.24830424786 -9.71569156647,-0.00604359619319,1.27888929844 -9.71169948578,-0.00603804225102,1.30945670605 -9.70470809937,-0.00603212183341,1.33903157711 -9.69471645355,-0.00602566683665,1.36859989166 -9.69472503662,-0.00602066516876,1.39917552471 -9.70273303986,-0.00601681368425,1.43075537682 -9.71673583984,-0.0050163990818,1.44755446911 -9.69774532318,-0.006008640863,1.47512972355 -9.68875408173,-0.00600219145417,1.50469958782 -9.70076179504,-0.00599879771471,1.53727722168 -9.68677043915,-0.00599158881232,1.56584906578 -9.68677902222,-0.00598642230034,1.59642660618 -9.67578887939,-0.00597948022187,1.62599098682 -9.67579269409,-0.00597695540637,1.64078676701 -9.68280029297,-0.00497278617695,1.67236912251 -9.68580913544,-0.00496789906174,1.70394206047 -9.67381858826,-0.00496082752943,1.73251724243 -9.67482852936,-0.00495553296059,1.76408553123 -9.68583583832,-0.00495185516775,1.79666769505 -9.66684150696,-0.0049463454634,1.80845379829 -9.66384983063,-0.00494043389335,1.83902561665 -9.66085910797,-0.00493449438363,1.86959755421 -9.66086769104,-0.00492908246815,1.90017831326 -9.65587806702,-0.00492272013798,1.93074512482 -9.65988731384,-0.00491783581674,1.96232461929 -9.64289665222,-0.00490968907252,1.9898968935 -9.66589927673,-0.00491048814729,2.00969552994 -9.66590881348,-0.00490499241278,2.04027867317 -9.64991950989,-0.00489677255973,2.06884026527 -9.65192890167,-0.00489142816514,2.10041618347 -9.65193748474,-0.00388586171903,2.1310005188 -9.6509475708,-0.00387990172021,2.16256856918 -9.65595245361,-0.00387798901647,2.17837023735 -9.64796161652,-0.00387099012733,2.20794320107 -9.59297561646,-0.00485648121685,2.2274954319 -9.63298225403,-0.00385690527037,2.26807880402 -9.6419916153,-0.00385265704244,2.30066847801 -9.63100147247,-0.00384493591264,2.33023166656 -9.62701129913,-0.00383859244175,2.35981845856 -9.62701702118,-0.00383563269861,2.37560558319 -9.62002754211,-0.00382845662534,2.40616893768 -9.62503623962,-0.00382334226742,2.43874835968 -9.6200466156,-0.00381671590731,2.46833300591 -9.60605812073,-0.00380838173442,2.49689817429 -9.61306762695,-0.00280345161445,2.53047394753 -9.62507629395,-0.00279938313179,2.56505560875 -9.61508178711,-0.00279482966289,2.57784724236 -9.55509853363,-0.00377871817909,2.59538507462 -9.6131029129,-0.00278229918331,2.6409971714 -9.60811328888,-0.00277534243651,2.67157053947 -9.60412406921,-0.00276857661083,2.7021484375 -9.60313415527,-0.00276224757545,2.73372507095 -9.59914493561,-0.00175524957012,2.76529073715 -9.60114955902,-0.00175261567347,2.7810895443 -9.60015964508,-0.00174605543725,2.81365466118 -9.59817028046,-0.00173964467831,2.84424233437 -9.59718227386,-0.00173305347562,2.87680888176 -9.58919239044,-0.00172546727117,2.90638637543 -9.58220386505,-0.00171788281295,2.93695473671 -9.59720802307,-0.000717363902368,2.95675802231 -9.5442237854,-0.00170209573116,2.97331547737 -9.57923030853,-0.000701610872056,3.01590633392 -9.59723949432,-0.000698286399711,3.0534927845 -9.59225082397,-0.000690889719408,3.08505964279 -9.56526470184,-0.000679774151649,3.10962128639 -9.57927322388,-0.000675730407238,3.14620685577 -9.5402841568,-0.000665887491778,3.14998435974 -9.50629901886,-0.00165358057711,3.17154979706 -9.42632007599,-0.00263316836208,3.17908644676 -9.43333053589,-0.00262774317525,3.21366500854 -9.43334197998,-0.0026210618671,3.2462387085 -9.42535400391,-0.00261306529865,3.27581524849 -9.42736530304,-0.00260663684458,3.30938696861 -9.42836952209,-0.00160362420138,3.32518625259 -9.42538261414,-0.00159638654441,3.35676121712 -9.42539310455,-0.00158966134768,3.38933873177 -9.43140411377,-0.0015837844694,3.42490768433 -9.41741752625,-0.00157463294454,3.45248317719 -9.42642688751,-0.00056948751444,3.48806905746 -9.41943359375,-0.000564892659895,3.50185704231 -9.41244602203,-0.000556801562198,3.53242921829 -9.41845798492,-0.000550910655875,3.56800293922 -9.4194688797,-0.000544182956219,3.60157847404 -9.41048145294,-0.000535754370503,3.63115501404 -9.41049289703,0.000471243110951,3.66472744942 -9.39550685883,0.000480823800899,3.69229960442 -9.40951061249,0.000481796916574,3.71409511566 -9.40152359009,0.000490235572215,3.74466586113 -9.39953613281,0.000497565546539,3.77724337578 -9.39754772186,0.000504903611727,3.80982160568 -9.40155887604,0.0015111065004,3.84440755844 -9.39357185364,0.0015196017921,3.8749806881 -9.39157772064,0.00152343825903,3.89077210426 -9.40158939362,0.00152889953461,3.92934298515 -9.39360237122,0.00253742304631,3.95991826057 -9.38861465454,0.00254537956789,3.99149751663 -9.38062858582,0.0025539372582,4.02207326889 -9.38163948059,0.00256094476208,4.05665016174 -9.37665271759,0.00256914249621,4.08921909332 -9.3816576004,0.00357175222598,4.10801506042 -9.38366985321,0.00357869709842,4.14358758926 -9.37668323517,0.00358724058606,4.17516040802 -9.37169551849,0.0035952560138,4.20674467087 -9.3617105484,0.00360443699174,4.23731327057 -9.36172294617,0.00461173430085,4.2718911171 -9.37273311615,0.00461704935879,4.31147241592 -9.3577413559,0.00462346849963,4.32225465775 -9.34275722504,0.00463366508484,4.35082101822 -9.36376571655,0.0056370254606,4.39441537857 -9.3527803421,0.00564654683694,4.42498207092 -9.35479259491,0.00565370358527,4.46155405045 -9.35280609131,0.00566135160625,4.49513912201 -9.33482074738,0.00567226111889,4.52270174026 -9.34782600403,0.00667360052466,4.54649496078 -9.3488368988,0.00668082106858,4.58207654953 -9.34185123444,0.00668968679383,4.61464738846 -9.33686447144,0.00669799279422,4.64723062515 -9.34287643433,0.00770440325141,4.68581104279 -9.33589076996,0.00771328574046,4.7183842659 -9.33189678192,0.00771777098998,4.73417425156 -9.33890914917,0.00872407853603,4.7737531662 -9.33392333984,0.00873259920627,4.80732917786 -9.33293628693,0.00874058529735,4.84389638901 -9.32894992828,0.00874882005155,4.87748098373 -9.3229637146,0.00975764449686,4.91105413437 -9.31197929382,0.00976732280105,4.94163131714 -9.31898403168,0.00976983364671,4.96342325211 -9.31399822235,0.00977858062834,4.99799346924 -9.31501197815,0.0107861729339,5.03556871414 -9.31202507019,0.010794323869,5.07015323639 -9.30104064941,0.0108042433858,5.10172271729 -9.30305290222,0.010811730288,5.1402964592 -9.30406570435,0.0118192983791,5.17787694931 -9.29207420349,0.011825603433,5.19065475464 -9.30108642578,0.0118315760046,5.23224306107 -9.30809879303,0.0128381252289,5.27382183075 -9.29111480713,0.0128492731601,5.30239009857 -9.2861289978,0.0128580201417,5.33697032928 -9.29614067078,0.0138640291989,5.38055086136 -9.27615737915,0.0138757238165,5.40712356567 -9.29316234589,0.0138766691089,5.43690633774 -9.29117584229,0.0148848826066,5.47348880768 -9.28219127655,0.0148946400732,5.50706005096 -9.26920700073,0.0149050327018,5.5376367569 -9.27321910858,0.0149121936411,5.57821989059 -9.27323246002,0.0159201752394,5.61679935455 -9.27523994446,0.0159238427877,5.63758659363 -9.26925468445,0.0159330721945,5.67316007614 -9.26726913452,0.0169416554272,5.71173000336 -9.26028347015,0.0169509928674,5.74630975723 -9.26529693604,0.0179581623524,5.78888750076 -9.24731349945,0.0179697629064,5.81745815277 -9.2603187561,0.0179713182151,5.84525156021 -9.26433181763,0.0189787540585,5.88782644272 -9.24634933472,0.018990367651,5.91639947891 -9.25236129761,0.0189973432571,5.95998096466 -9.25037574768,0.020005851984,5.99856138229 -9.24539089203,0.0200151149184,6.0361328125 -9.23740673065,0.0200247373432,6.07071590424 -9.24441242218,0.0210276972502,6.09649658203 -9.24942588806,0.0210348982364,6.14007997513 -9.23344230652,0.0210462994874,6.17065143585 -9.23645591736,0.0220539178699,6.21323394775 -9.22447299957,0.0220646224916,6.2468047142 -9.22848701477,0.0230720806867,6.29038763046 -9.22250175476,0.023081606254,6.32796239853 -9.22750759125,0.0230849254876,6.3527469635 -9.21752357483,0.0240951571614,6.38732528687 -9.22753620148,0.0241017434746,6.43689775467 -9.21155452728,0.0241131596267,6.46747589111 -9.20756912231,0.0251223742962,6.50705099106 -9.2045841217,0.0251312442124,6.54663515091 -9.20059967041,0.0261406302452,6.58720397949 -9.20860481262,0.0261432491243,6.61399698257 -9.21261787415,0.0271509028971,6.65957736969 -9.20863342285,0.0271600428969,6.69916057587 -9.20065021515,0.0281703174114,6.73772573471 -9.18766784668,0.0281813051552,6.77130365372 -9.19268131256,0.0281889233738,6.8188791275 -9.19668769836,0.0291924085468,6.84366941452 -9.19870090485,0.029200412333,6.88825511932 -9.17672157288,0.0292134676129,6.91681957245 -9.18273448944,0.0302208457142,6.96540021896 -9.18274879456,0.0312294699252,7.0099773407 -9.1687669754,0.0312409494072,7.04454612732 -9.19277667999,0.0322447419167,7.10713529587 -9.15979194641,0.0322556756437,7.10491132736 -9.06282806396,0.0302837435156,7.07645273209 -9.07785415649,0.0312980823219,7.17761611938 -9.02088165283,0.0303180906922,7.17818021774 -8.94691371918,0.029341654852,7.16573190689 -8.89993858337,0.0283597074449,7.17329931259 -8.91694355011,0.0293608605862,7.21008682251 -8.90696048737,0.0293716900051,7.24765920639 -8.90997505188,0.0303796399385,7.29425048828 -8.89799308777,0.030390959233,7.33082008362 -8.89500904083,0.0314006023109,7.37538766861 -8.93501472473,0.0324012041092,7.45298957825 -8.8840341568,0.0314159169793,7.43475961685 -9.13599205017,0.0393742844462,7.68941354752 -9.13200759888,0.0393839217722,7.73399162292 -9.13402271271,0.040392331779,7.7835726738 -9.11604118347,0.0404048711061,7.81714344025 -9.13306808472,0.0424192808568,7.92930412292 -9.15007209778,0.0434202626348,7.96810150146 -9.13609027863,0.0434320345521,8.00567436218 -9.1401052475,0.0444402471185,8.05924987793 -9.05713939667,0.0424659177661,8.03680419922 -9.25210952759,0.0484355576336,8.25744152069 -9.2311296463,0.049448762089,8.29001331329 -9.23414421082,0.0494570806623,8.34359550476 -9.25214862823,0.0504581145942,8.38638210297 -9.23916625977,0.0514698177576,8.42695426941 -9.23218345642,0.0514802224934,8.47253131866 -9.2281999588,0.0524900481105,8.52111053467 -9.20923519135,0.0535120293498,8.60926151276 -9.15428733826,0.0535458996892,8.69119167328 -9.23528385162,0.0565385892987,8.82079410553 -9.23631572723,0.0585568509996,8.93194293976 -9.20133876801,0.0585731230676,8.9535112381 -9.14735984802,0.0565886944532,8.92928409576 -9.19736385345,0.0595877692103,9.03287506104 -9.12641239166,0.0586206093431,9.07501220703 -9.07044219971,0.0576412007213,9.07557582855 -9.05146312714,0.0586544014513,9.11314582825 -9.05047130585,0.0586591959,9.13993644714 -9.06148529053,0.0596662722528,9.20751667023 -9.03550720215,0.0596808567643,9.23808765411 -9.05956554413,0.0647133290768,9.4934053421 -9.03659534454,0.0647319480777,9.55677127838 -9.01561737061,0.0657458603382,9.59533309937 -9.00963497162,0.0657564178109,9.64791202545 -9.01265048981,0.0667651742697,9.71049404144 -8.95068264008,0.0657872185111,9.70405769348 -8.88971424103,0.0648091360927,9.69861888885 -8.79276371002,0.0638432279229,9.68395900726 -8.74079322815,0.062863394618,9.68752193451 -8.71881484985,0.0628773421049,9.72309589386 -8.71583175659,0.0638873949647,9.77967739105 -8.7038526535,0.0648993998766,9.827252388 -8.70386886597,0.0659090057015,9.88882827759 -8.70187664032,0.0659142434597,9.91761398315 -8.96582508087,0.0748697817326,10.2782592773 -8.95484542847,0.0758815854788,10.329834938 -8.94686412811,0.0768926888704,10.3844165802 -8.94188213348,0.077903367579,10.4439897537 -8.94889640808,0.0789114013314,10.5165758133 -8.94790458679,0.0799165666103,10.5493593216 -8.94592189789,0.0809265747666,10.6129369736 -8.93794059753,0.0809377580881,10.6695175171 -8.93495845795,0.0819481834769,10.734087944 -8.9189786911,0.0829610005021,10.7816677094 -8.92199516296,0.0839702114463,10.8542394638 -8.91201400757,0.0849819779396,10.9108142853 -8.92701911926,0.0859836414456,10.9626121521 -8.92103767395,0.0869945213199,11.0241918564 -9.02002811432,0.0909840837121,11.2167863846 -8.84709072113,0.0870292410254,11.0733270645 -3.43455934525,-0.0918433517218,4.40934038162 -3.40658569336,-0.0928279086947,4.40092515945 -3.40459656715,-0.0928223282099,4.4127073288 -8.88717269897,0.0950748994946,11.5190124512 -8.87019443512,0.0950880423188,11.5695934296 -8.86821174622,0.0960982739925,11.6411724091 -8.86323070526,0.097109310329,11.7107419968 -8.87623596191,0.099111571908,11.7655344009 -8.8582572937,0.0991250649095,11.8171100616 -8.8682718277,0.101132877171,11.9066905975 -8.84429550171,0.101147636771,11.9512662888 -8.84131240845,0.102158173919,12.0248432159 -8.82933425903,0.103170506656,12.0864210129 -8.83335018158,0.105179786682,12.1719923019 -8.83635807037,0.106183893979,12.2137918472 -8.83537483215,0.107194185257,12.2933635712 -8.82439517975,0.108206316829,12.3579435349 -8.82541179657,0.109216086566,12.4405212402 -8.80643463135,0.110229901969,12.495098114 -8.80745220184,0.112239778042,12.5796728134 -8.79347324371,0.112252704799,12.643245697 -8.80547904968,0.114255234599,12.7020378113 -8.79349899292,0.115267671645,12.7686166763 -8.79051685333,0.116278201342,12.8481988907 -8.77853775024,0.117290765047,12.9167728424 -8.77355670929,0.118302039802,12.997341156 -8.76057815552,0.119314625859,13.0639228821 -8.78258037567,0.121315196157,13.1407146454 -8.76860141754,0.122328050435,13.2072954178 -8.76462078094,0.123339034617,13.2908697128 -8.75064182281,0.124352008104,13.3594455719 -8.75165939331,0.126361966133,13.4520215988 -8.73768138885,0.127375036478,13.5225944519 -8.73169994354,0.129386365414,13.6051740646 -8.74170684814,0.130389377475,13.6669664383 -8.73572540283,0.131400808692,13.7515420914 -8.7247467041,0.13241328299,13.8291168213 -8.71476650238,0.134425401688,13.9076967239 -8.70278739929,0.135438024998,13.9842748642 -8.69580745697,0.136449754238,14.070848465 -8.69182682037,0.138460695744,14.1614294052 -8.69883346558,0.139464497566,14.2232151031 -8.68685436249,0.141477152705,14.3027925491 -8.68287372589,0.142488211393,14.3963708878 -8.67889308929,0.144499272108,14.4909496307 -8.66791343689,0.145511761308,14.5745267868 -8.6559343338,0.147524535656,14.6581020355 -8.6709394455,0.14852656424,14.7348957062 -8.65996074677,0.150539234281,14.822467804 -8.65298080444,0.151550933719,14.9160461426 -8.64000225067,0.153563812375,14.9996261597 -8.63302230835,0.154575645924,15.096200943 -8.6230430603,0.156588107347,15.1887750626 -8.61406326294,0.158600226045,15.2823543549 -8.63006782532,0.15960213542,15.3661460876 -8.62008953094,0.161614581943,15.4607229233 -8.61310958862,0.163626268506,15.560303688 -8.59713172913,0.164639934897,15.6458797455 -8.58515357971,0.166652947664,15.7414493561 -8.57517528534,0.167665421963,15.8400259018 -8.5661945343,0.169677510858,15.9396095276 -8.58220005035,0.17167943716,16.0284023285 -8.57721996307,0.173690959811,16.1399784088 -8.56923961639,0.1757029742,16.2455596924 -8.55926036835,0.177715525031,16.3501319885 -8.54728317261,0.17872838676,16.450712204 -8.5393037796,0.180740624666,16.5622825623 -8.5543088913,0.182742774487,16.6540775299 -8.54233074188,0.184755712748,16.7586536407 -8.52935218811,0.186768934131,16.8632278442 -8.52137374878,0.188780978322,16.9768104553 -8.50939559937,0.190793976188,17.0853862762 -8.500415802,0.192806333303,17.200963974 -8.48643779755,0.194819703698,17.3075408936 -8.50744152069,0.196820795536,17.4193305969 -8.49646282196,0.198833525181,17.5339107513 -10.8637866974,0.31536257267,22.563873291 -10.7738304138,0.314391613007,22.557434082 -10.6678800583,0.312423974276,22.5169944763 -10.6039161682,0.313447773457,22.5645580292 -10.5259571075,0.3124743402,22.5811233521 -10.947842598,0.335394084454,23.5769767761 -10.8109006882,0.332432687283,23.4745330811 -10.3320598602,0.31154063344,22.6250362396 -10.5070257187,0.324516028166,23.197637558 -10.5790233612,0.331512212753,23.5492305756 -10.4580764771,0.329547643661,23.4777851105 -10.3281335831,0.326584756374,23.3823451996 -10.338139534,0.328588157892,23.5041332245 -10.240187645,0.327618867159,23.4806957245 -10.1272392273,0.325652688742,23.4232540131 -10.0642757416,0.326676249504,23.4778232574 -9.97832012177,0.325704455376,23.4793891907 -9.49248313904,0.303813546896,22.536895752 -9.45250415802,0.30282703042,22.5406780243 -9.33255958557,0.300862193108,22.4532356262 -9.24960231781,0.299889743328,22.4508056641 -9.16764545441,0.298917144537,22.4513702393 -9.07969093323,0.297945797443,22.4369354248 -8.99873352051,0.297972917557,22.4375038147 -8.91977596283,0.296999722719,22.444070816 -8.86880016327,0.296015411615,22.4178543091 -8.78784370422,0.296042591333,22.4184188843 -8.70588779449,0.295069992542,22.4159851074 -8.61893177032,0.294098287821,22.3985557556 -8.540974617,0.294124811888,22.4041233063 -8.46701622009,0.294150650501,22.4226894379 -8.45402908325,0.295158624649,22.4924812317 -8.56301593781,0.306147664785,22.9990730286 -8.55903625488,0.310159415007,23.2096500397 -8.50907039642,0.311180353165,23.2982215881 -8.44810771942,0.312203496695,23.3577919006 -8.37214946747,0.312229543924,23.3743629456 -8.28719425201,0.31125754118,23.367931366 -8.23921966553,0.310272574425,23.3487148285 -8.16126251221,0.310299128294,23.3612823486 -8.07430744171,0.309327453375,23.3468513489 -7.99235153198,0.30835467577,23.3444232941 -7.90939617157,0.308382183313,23.3409919739 -7.82744026184,0.307409435511,23.3385620117 -7.74148607254,0.306437641382,23.3271274567 -7.69950866699,0.306451439857,23.3219127655 -7.6195526123,0.306478261948,23.3244819641 -7.53559732437,0.305505990982,23.3160514832 -4.1326584816,0.0781953632832,12.983171463 -4.08669281006,0.0772151574492,12.9807424545 -4.05572223663,0.0782316252589,13.0213298798 -7.20977544785,0.303614407778,23.3003349304 -7.16579866409,0.30262863636,23.2881164551 -7.0838432312,0.301655828953,23.2816886902 -7.00688695908,0.30168196559,23.2892608643 -6.92293214798,0.300709486008,23.2728328705 -6.84497594833,0.300735861063,23.2784042358 -6.76402044296,0.299762815237,23.2729740143 -6.71804475784,0.29977735877,23.2507591248 -6.6400885582,0.298803716898,23.2543296814 -6.56113243103,0.298830091953,23.2509078979 -6.47717761993,0.297857552767,23.2304801941 -6.40122175217,0.297883480787,23.2410507202 -6.32126569748,0.296910077333,23.2336235046 -6.24131059647,0.296936810017,23.2291927338 -6.20033311844,0.295950263739,23.2199821472 -6.11937856674,0.295977115631,23.2095527649 -6.0414223671,0.295003324747,23.2091255188 -5.96346664429,0.295029461384,23.2067012787 -5.88551044464,0.294055610895,23.2032756805 -5.80755472183,0.29408171773,23.1998500824 -5.76457834244,0.293095588684,23.1836357117 -5.68762207031,0.293121576309,23.1852073669 -5.60866689682,0.29214784503,23.1757831573 -5.52971124649,0.292174071074,23.1653614044 -5.45475482941,0.291199654341,23.1749305725 -5.37579965591,0.291225850582,23.1625099182 -5.29684448242,0.290252119303,23.1530799866 -5.25586700439,0.290265530348,23.141866684 -5.17991113663,0.29029121995,23.1444416046 -5.09995651245,0.28931760788,23.1270160675 -5.05998897552,0.292336016893,23.2866001129 -5.041015625,0.297350585461,23.5561790466 -5.02104187012,0.303365260363,23.8257598877 -3.22162413597,0.126726254821,15.5831432343 -3.18864488602,0.125738024712,15.5489282608 -3.12868404388,0.124760001898,15.4995126724 -3.07772064209,0.124780386686,15.497092247 -3.02675747871,0.123800843954,15.4966678619 -2.97979259491,0.124820314348,15.5112524033 -2.93382763863,0.124839663506,15.5338335037 -2.89685988426,0.125857293606,15.6054153442 -2.88287472725,0.126865342259,15.6692018509 -2.83191156387,0.126885563135,15.6657848358 -4.82730674744,0.369510710239,27.0635757446 -4.79933547974,0.376526832581,27.3971595764 -4.77236461639,0.383542835712,27.75274086 -4.74239444733,0.390559464693,28.1063194275 -4.75640058517,0.397562205791,28.460111618 -4.72543096542,0.405578911304,28.8256950378 -4.69546079636,0.413595497608,29.2152748108 -4.66349124908,0.421612501144,29.6088542938 -4.62952232361,0.429629743099,29.9994373322 -4.59155464172,0.437647849321,30.3840179443 -4.54059171677,0.443668305874,30.6926002502 -4.59558439255,0.458663225174,31.399394989 -4.61859750748,0.476669669151,32.2579803467 -4.57963037491,0.485687941313,32.7155609131 -4.53966379166,0.495706409216,33.1871414185 -4.49869728088,0.505724966526,33.6647262573 -4.45773077011,0.515743553638,34.1733055115 -4.46773767471,0.525747060776,34.6681022644 -4.35679388046,0.525778889656,34.6656761169 -4.38480567932,0.549784421921,35.792263031 -4.33484172821,0.560804665089,36.325843811 -4.28287887573,0.571825325489,36.8704223633 -2.66740846634,0.294141322374,23.6998882294 -2.58845424652,0.293166726828,23.6674671173 -2.54647779465,0.292179852724,23.6242599487 -2.47552084923,0.292203605175,23.6568431854 -2.3905684948,0.290230065584,23.561422348 -2.34060525894,0.29524987936,23.8090057373 -3.95611643791,0.66495680809,41.3667068481 -3.89515662193,0.680979013443,42.1212882996 -3.8281981945,0.696002364159,42.8618659973 -3.7652285099,0.697019457817,42.9146575928 -3.77124738693,0.732029080391,44.580242157 -3.69929075241,0.749053180218,45.4138259888 -3.63933062553,0.771075129509,46.4814071655 -3.55837678909,0.789100885391,47.3399887085 -3.49741721153,0.815122902393,48.566570282 -3.39547014236,0.830152511597,49.3051528931 -3.38748288155,0.851159334183,50.3259468079 -3.30752897263,0.877184808254,51.5445251465 -3.20558190346,0.897214353085,52.5331077576 -3.10363483429,0.920243799686,53.6116905212 -2.01399993896,0.570455849171,36.948223114 -2.95972204208,0.998291611671,57.3438606262 -1.84808373451,0.573502063751,37.1245918274 -1.72914218903,0.572534263134,37.0711746216 -1.60920107365,0.570566654205,37.0027580261 -1.49525809288,0.571597874165,37.0573387146 -1.49227976799,0.634608566761,40.0579338074 -1.36634039879,0.634641885757,40.0445175171 -1.24140071869,0.634674966335,40.0641021729 -1.1774315834,0.63469183445,40.0438919067 -1.05049264431,0.633725225925,40.0084724426 -0.925553023815,0.633758127689,40.0170593262 -0.79861420393,0.633791446686,39.9896392822 -0.673674702644,0.633824288845,40.0312232971 -0.548735141754,0.634857058525,40.072807312 -0.421796232462,0.633890151978,39.994392395 -0.359826177359,0.632906377316,39.9901885986 -0.233887046576,0.6339392066,40.0347709656 -0.10894741863,0.635971724987,40.1193580627 --0.477790892124,1.21911346912,54.5888442993 --0.649715662003,1.22015428543,54.6124305725 --1.49837446213,1.49734008312,65.2159805298 --1.83794486523,0.471546083689,25.8266716003 --1.92289698124,0.472570419312,25.8662586212 --1.95686531067,0.456585735083,25.2558498383 --1.96684157848,0.434596776962,24.4004421234 --2.03579902649,0.43261808157,24.3120365143 --2.11675238609,0.433641552925,24.3506221771 --2.1927075386,0.433664053679,24.3382129669 --2.22868585587,0.432674914598,24.3140106201 --2.29864287376,0.430696368217,24.2345981598 --2.37459802628,0.430718690157,24.2291908264 --2.45155310631,0.431741207838,24.2287807465 --2.53750514984,0.433765262365,24.3123703003 --8.50144958496,1.47085535526,63.587802887 --8.68537139893,1.46789371967,63.4434051514 --8.8642950058,1.46393120289,63.2710113525 --9.0502166748,1.46196973324,63.1526107788 --9.25313282013,1.46201097965,63.1552124023 --8.3783864975,1.27387189865,55.9797821045 --8.48634243011,1.27689361572,56.0975837708 --8.64027404785,1.27392673492,55.9251823425 --8.80920124054,1.27296221256,55.8587875366 --8.92914295197,1.26298940182,55.482383728 --9.06508159637,1.25701916218,55.2209892273 --9.28299236298,1.26406228542,55.4575920105 --9.41093349457,1.25709056854,55.1561965942 --9.52088832855,1.26111221313,55.2769966125 --9.72380542755,1.26515269279,55.4136047363 --9.89773178101,1.26518821716,55.3812065125 --10.1056470871,1.27022910118,55.537815094 --7.26948881149,0.821779131889,38.6108779907 --7.97200059891,0.715993583202,34.2804489136 --7.98297739029,0.70500266552,33.8460426331 --7.3990483284,0.581951022148,29.1167812347 --7.48900079727,0.580972492695,29.0893821716 --7.58095264435,0.580994367599,29.0649814606 --7.67290449142,0.58101606369,29.0425815582 --7.8298368454,0.588047802448,29.2651882172 --7.72773981094,0.523079097271,26.6905498505 --7.72259521484,0.468132346869,24.494512558 --8.52715587616,0.471321851015,24.3445301056 --8.61211109161,0.472341090441,24.340133667 --8.86198806763,0.476394236088,24.4341468811 --13.690495491,0.828106343746,36.9988098145 --13.7404632568,0.823118269444,36.7794189453 --13.7254505157,0.81412088871,36.3880119324 --13.7214326859,0.805124938488,36.0356178284 --13.6624412537,0.797118902206,35.7094078064 --13.6454296112,0.787121117115,35.3320083618 --13.6314153671,0.778123736382,34.9706077576 --13.6124038696,0.769125759602,34.597202301 --13.5953912735,0.760128080845,34.2378005981 --13.576379776,0.75113004446,33.8794021606 --13.5573673248,0.743131935596,33.5270004272 --13.4933776855,0.734125256538,33.2167892456 --13.4793643951,0.72612798214,32.88438797 --13.4633522034,0.718130350113,32.5539894104 --13.449338913,0.710133016109,32.234588623 --13.4303264618,0.70213496685,31.9041843414 --13.4103145599,0.694136798382,31.5777816772 --13.4062986374,0.687140882015,31.2943820953 --13.3363113403,0.680133461952,30.9971752167 --13.3342933655,0.673137784004,30.725774765 --13.315281868,0.66613972187,30.4193725586 --13.2982702255,0.658141970634,30.1209697723 --13.2832565308,0.651144504547,29.8345718384 --13.2762413025,0.645148158073,29.5671691895 --13.2142505646,0.638141930103,29.3059635162 --13.2022371292,0.631144881248,29.0345611572 --13.1982212067,0.625148892403,28.7831554413 --13.1792097092,0.619150876999,28.5057582855 --13.1711950302,0.613154351711,28.2533531189 --13.1601810455,0.606157362461,27.9999542236 --13.1491670609,0.600160419941,27.7485523224 --13.09217453,0.594155073166,27.5163440704 --13.0861597061,0.589158773422,27.2819442749 --13.0731458664,0.583161473274,27.0365428925 --13.0651311874,0.577164888382,26.8041400909 --13.0581159592,0.572168469429,26.5767402649 --13.0521011353,0.567172110081,26.3543395996 --13.0630807877,0.562177956104,26.1689414978 --9.11022567749,0.32966375351,18.1782264709 --9.1222038269,0.326671391726,18.0598258972 --9.16017436981,0.325682431459,17.9934253693 --9.21414089203,0.325695455074,17.959028244 --9.26710700989,0.325708210468,17.9246368408 --9.3090763092,0.32471960783,17.866235733 --9.33606052399,0.324726015329,17.8500404358 --9.40802097321,0.325741171837,17.8496456146 --9.51397323608,0.328760564327,17.9132537842 --9.61892414093,0.330779761076,17.9728622437 --12.8649692535,0.507196247578,23.8589115143 --12.8879470825,0.504203498363,23.7215118408 --12.9729042053,0.504218459129,23.6991233826 --13.0158843994,0.50522595644,23.6889305115 --13.0608549118,0.50323587656,23.593536377 --13.2147941589,0.507259190083,23.6951580048 --13.3017530441,0.508274078369,23.6757698059 --13.3917102814,0.509289205074,23.6613845825 --13.4846668243,0.510304689407,23.6499958038 --13.5576305389,0.510317564011,23.6056118011 --13.6096076965,0.511325836182,23.6104202271 --13.7245588303,0.513343691826,23.6360340118 --13.822514534,0.514359354973,23.6336517334 --13.9184713364,0.515374720097,23.6262683868 --13.9754390717,0.514385163784,23.5528774261 --14.0573997498,0.514398634434,23.521490097 --13.8894395828,0.50438028574,23.1562614441 --13.9024200439,0.501385450363,23.0128650665 --12.6967449188,0.437245517969,20.8672771454 --12.854683876,0.442268401384,20.9769001007 --12.6907138824,0.43025302887,20.5634746552 --12.7496805191,0.430264085531,20.5130805969 --12.6986789703,0.424262195826,20.2876701355 --12.6426858902,0.420257627964,20.1284656525 --12.6846590042,0.419266581535,20.0550746918 --12.8236036301,0.422286778688,20.132692337 --13.0045366287,0.428311675787,20.2753219604 --12.8655595779,0.418299496174,19.9198989868 --12.875541687,0.416304528713,19.7985019684 --12.6105909348,0.399280190468,19.1898536682 --12.7775278091,0.404303073883,19.3114833832 --13.2773733139,0.425363451242,19.9301643372 --13.0404233932,0.410340428352,19.4407272339 --13.0474061966,0.408344954252,19.3183250427 --13.2723274231,0.416373729706,19.5179615021 --13.2263326645,0.412370413542,19.3847560883 --13.3952703476,0.417392671108,19.5013885498 --13.5862026215,0.423417210579,19.6460208893 --13.4712190628,0.415407985449,19.3486022949 --13.437212944,0.411407679319,19.1701946259 --13.4871835709,0.410416543484,19.1128063202 --12.9333200455,0.382359921932,18.2033042908 --12.8883237839,0.379356831312,18.0790958405 --12.900305748,0.377361774445,17.9756984711 --12.9912652969,0.379375129938,17.9823150635 --12.4853715897,0.351328521967,17.0514183044 --13.4011087418,0.389429032803,18.1841869354 --12.3493776321,0.341321706772,16.6445960999 --12.3213777542,0.338320732117,16.5503845215 --12.3513536453,0.337327599525,16.4829959869 --12.3553371429,0.3353317976,16.3795928955 --12.4073076248,0.335340946913,16.3402004242 --12.4602775574,0.335350096226,16.3028087616 --8.94420623779,0.181993246078,11.6157665253 --8.93520069122,0.180995076895,11.5655603409 --8.9691734314,0.18100400269,11.533159256 --9.00114917755,0.181012585759,11.4997663498 --9.03412342072,0.18102131784,11.4663658142 --12.5761623383,0.3283816576,15.873626709 --12.6091384888,0.32838845253,15.8122320175 --12.57513237,0.324388593435,15.6668233871 --12.6061172485,0.324393391609,15.6546287537 --12.7610607147,0.329412072897,15.7452583313 --12.8440237045,0.330423474312,15.7468795776 --12.8849973679,0.330430746078,15.6954870224 --13.0889291763,0.336453765631,15.8411245346 --13.0839157104,0.334456413984,15.7327213287 --13.1008968353,0.332461088896,15.6533288956 --13.1318817139,0.333465605974,15.6401357651 --13.2178440094,0.334476828575,15.640748024 --13.2688169479,0.334484636784,15.6003570557 --13.5877189636,0.345517486334,15.8750267029 --13.4387426376,0.337506353855,15.5995931625 --13.6596717834,0.344529628754,15.7562427521 --13.6046791077,0.341525882483,15.6430339813 --13.6556510925,0.341533303261,15.6006402969 --13.7356176376,0.342543244362,15.5922574997 --15.1032514572,0.394670039415,17.0401477814 --15.3291797638,0.40169224143,17.1868000031 --15.6930732727,0.413726568222,17.4834785461 --20.8467445374,0.613187193871,23.0952148438 --20.9237194061,0.614193320274,23.1070346832 --21.0486774445,0.616202890873,23.0986709595 --21.1706352234,0.618212103844,23.0853042603 --15.9979381561,0.415759563446,17.3217582703 --16.0639076233,0.41676646471,17.282371521 --12.0809030533,0.261424273252,12.902100563 --12.0888872147,0.260428279638,12.8287010193 --12.0598869324,0.258427470922,12.7564907074 --12.062871933,0.257431030273,12.6790924072 --12.1318397522,0.258440107107,12.6707038879 --12.1928100586,0.258448421955,12.6543178558 --12.2147893906,0.258453398943,12.5969219208 --12.2027788162,0.256455570459,12.5045166016 --12.1977729797,0.255456745625,12.4593133926 --12.1907606125,0.253459244967,12.373913765 --12.1907463074,0.252462357283,12.2955131531 --12.1887311935,0.250465273857,12.2151088715 --12.184718132,0.249468043447,12.1337070465 --12.174706459,0.247470274568,12.0473060608 --12.1796913147,0.246473699808,11.9759054184 --12.1566896439,0.244473412633,11.9146976471 --12.152677536,0.243476107717,11.8352956772 --12.1556615829,0.241479322314,11.7638998032 --12.1626462936,0.240482866764,11.6954965591 --12.15163517,0.239484965801,11.6110944748 --12.1526212692,0.237488016486,11.5376901627 --12.1546058655,0.236491084099,11.4662895203 --12.1416025162,0.235491544008,11.4180898666 --12.1275911331,0.233493447304,11.3316802979 --12.1215801239,0.232495844364,11.2552843094 --12.1355619431,0.231499776244,11.1958827972 --12.1235513687,0.229501754045,11.1134786606 --12.1225366592,0.228504553437,11.0410728455 --12.1235237122,0.227507457137,10.9716720581 --12.0965223312,0.225506916642,10.9124670029 --12.0965089798,0.224509716034,10.8430671692 --12.0994949341,0.223512709141,10.7766675949 --12.098482132,0.222515434027,10.7062625885 --12.0874700546,0.220517426729,10.6278572083 --12.0984544754,0.219520941377,10.5694589615 --12.0684537888,0.218520253897,10.5092506409 --12.0654420853,0.216522753239,10.4398517609 --12.074426651,0.216526061296,10.3804512024 --12.0674142838,0.214528262615,10.3080511093 --12.0634012222,0.213530644774,10.238650322 --12.0673875809,0.212533593178,10.1752443314 --12.0533771515,0.210535272956,10.0988454819 --12.0393743515,0.209535717964,10.0536365509 --12.0403594971,0.208538413048,9.98923301697 --12.0423460007,0.207541108131,9.92683506012 --12.0313358307,0.206542998552,9.85343074799 --12.0393209457,0.205546066165,9.7960319519 --12.0223112106,0.203547552228,9.71862602234 --12.0312957764,0.203550636768,9.66222381592 --12.0172920227,0.202551037073,9.62002372742 --12.0052814484,0.200552821159,9.54761791229 --11.9932718277,0.19955457747,9.47621631622 --12.0112543106,0.19855812192,9.42781543732 --11.9972438812,0.197559759021,9.35541152954 --12.0032300949,0.196562558413,9.29800701141 --12.0052165985,0.19556504488,9.23961353302 --11.9802160263,0.194564849138,9.18940353394 --11.9782037735,0.193567141891,9.12699985504 --11.9801902771,0.192569613457,9.0686006546 --11.9751777649,0.191571682692,9.00520038605 --11.9781646729,0.190574198961,8.94779968262 --11.9781522751,0.189576506615,8.88839817047 --12.0131378174,0.190579518676,8.88420200348 --12.0491161346,0.190583646297,8.85180950165 --5.55551815033,-0.0207490269095,4.00778627396 --5.55750083923,-0.0207426566631,3.98238658905 --5.59447574615,-0.0207343697548,3.98198652267 --11.9550733566,0.183589980006,8.49177646637 --11.9340724945,0.182590037584,8.44857311249 --11.9330606461,0.181592151523,8.39117336273 --11.9320478439,0.180594310164,8.33276557922 --11.9270362854,0.179596185684,8.2733669281 --11.929022789,0.178598418832,8.21796131134 --11.9270114899,0.17760039866,8.16156673431 --11.9239988327,0.176602363586,8.10316085815 --11.9129953384,0.175602927804,8.06795787811 --11.9109840393,0.17560492456,8.01055049896 --11.9119701385,0.174607008696,7.95614957809 --11.9089593887,0.173608869314,7.89974975586 --11.9059476852,0.172610774636,7.84234189987 --11.8989372253,0.171612456441,7.78394317627 --11.8969259262,0.170614331961,7.72854137421 --11.8939199448,0.170615196228,7.69933795929 --11.8889083862,0.169616952538,7.64193201065 --11.8828983307,0.168618649244,7.5845284462 --11.8898849487,0.167620807886,7.53613233566 --11.8768749237,0.166622191668,7.47472715378 --11.8818616867,0.166624233127,7.42532873154 --11.8768510818,0.165625870228,7.36992883682 --11.8668479919,0.164626464248,7.33671951294 --11.8628358841,0.16362811625,7.28232002258 --11.8708229065,0.163630202413,7.23491811752 --11.8458156586,0.161631166935,7.16750764847 --11.8568019867,0.161633267999,7.1231136322 --11.8457918167,0.160634666681,7.06470632553 --11.846786499,0.160635560751,7.03950405121 --11.8297777176,0.158636763692,6.97809648514 --11.8417634964,0.158638805151,6.93470096588 --11.8307542801,0.15764015913,6.87729454041 --11.8377418518,0.157642021775,6.83089447021 --11.8347301483,0.156643539667,6.77949714661 --11.8337192535,0.155645146966,6.72808980942 --11.8157167435,0.154645457864,6.69288492203 --11.8317022324,0.154647454619,6.65249013901 --11.816693306,0.153648659587,6.59408140182 --11.8166818619,0.15265019238,6.54468011856 --11.8146715164,0.152651667595,6.49427747726 --11.8196592331,0.151653289795,6.44787693024 --11.8136482239,0.151654645801,6.39547157288 --11.8576345444,0.151656344533,6.39528512955 --11.8866186142,0.152658358216,6.36289787292 --11.8876075745,0.151659741998,6.31449556351 --11.8885955811,0.151661127806,6.26609134674 --11.9175796509,0.151663020253,6.23269557953 --11.9995536804,0.153665810823,6.2273182869 --12.0915269852,0.155668601394,6.22795438766 --12.1375131607,0.156669974327,6.22676181793 --12.2284860611,0.158672526479,6.22539234161 --12.3334579468,0.160675168037,6.23002290726 --12.3854379654,0.161676809192,6.20764255524 --12.3444347382,0.160677030683,6.1372256279 --12.5603866577,0.165680766106,6.19689702988 --17.7214851379,0.31574678421,8.71920394897 --17.742477417,0.315745383501,8.69400882721 --17.8044624329,0.316742777824,8.65463352203 --17.8464508057,0.317739874125,8.60525131226 --12.3363695145,0.156681790948,5.81661272049 --12.3233613968,0.155682340264,5.76220607758 --12.3503465652,0.155683189631,5.72782039642 --12.3113489151,0.154683202505,5.68459892273 --12.4923086166,0.158685043454,5.72226428986 --18.3023414612,0.325719475746,8.36683559418 --14.8608932495,0.225696742535,6.65786170959 --14.7838973999,0.222694993019,6.56543016434 --14.7119064331,0.220694065094,6.50520849228 --14.6399097443,0.217692539096,6.41778993607 --14.5649147034,0.2146910429,6.32836008072 --14.4889183044,0.211689651012,6.23993492126 --14.4129238129,0.209688350558,6.15251159668 --14.3489265442,0.206687122583,6.07008600235 --14.2849283218,0.204685986042,5.98967027664 --14.193939209,0.201685532928,5.92343330383 --14.1299419403,0.199684530497,5.84401655197 --14.0669431686,0.196683600545,5.76459217072 --11.786283493,0.132691904902,4.76640176773 --11.7832746506,0.131692588329,4.72099590302 --11.7952632904,0.131693139672,4.68260192871 --11.7022666931,0.128694325686,4.60116481781 --11.6842651367,0.127694770694,4.57195425034 --11.6952533722,0.127695322037,4.53355836868 --11.6842460632,0.126696035266,4.48615217209 --11.6852350235,0.126696616411,4.44375085831 --11.6722278595,0.125697299838,4.39634752274 --11.6932153702,0.125697627664,4.36195373535 --11.6832075119,0.125698253512,4.31554794312 --11.675204277,0.124698594213,4.29134464264 --11.6721954346,0.124699115753,4.24794197083 --11.6581878662,0.123699761927,4.20053529739 --11.670176506,0.123700045049,4.16213035583 --11.6611671448,0.122700601816,4.11672401428 --11.6741571426,0.12270077318,4.08033514023 --11.6631498337,0.122701317072,4.03392267227 --11.6541452408,0.121701650321,4.00971698761 --11.6451377869,0.12170214206,3.96531581879 --11.654127121,0.121702283621,3.92691683769 --11.6531190872,0.120702579618,3.88551855087 --11.6511106491,0.120702877641,3.84311199188 --11.652100563,0.11970308423,3.80170583725 --11.635099411,0.119703561068,3.77549958229 --11.636089325,0.118703745306,3.73510146141 --11.6390800476,0.118703849614,3.69469666481 --11.6380710602,0.118704020977,3.65329265594 --11.5200777054,0.114707127213,3.57485127449 --11.5240688324,0.11470721662,3.53544735909 --11.4960622787,0.113708131015,3.48704171181 --11.5030574799,0.113708026707,3.46884012222 --11.4770526886,0.112708903849,3.42042541504 --11.4970407486,0.112708449364,3.38703489304 --11.4950323105,0.112708605826,3.34663319588 --11.4930238724,0.112708732486,3.30522036552 --11.4900159836,0.11170887202,3.26481938362 --11.4760093689,0.111709341407,3.22141551971 --11.4930028915,0.111708782613,3.20621728897 --11.4609975815,0.110709838569,3.1578066349 --11.4869861603,0.110708907247,3.12541031837 --11.4659795761,0.109709575772,3.07999920845 --11.4759712219,0.109709121287,3.04360175133 --11.464963913,0.109709404409,3.00119352341 --11.4609556198,0.108709417284,2.96179842949 --11.45495224,0.108709566295,2.94059443474 --11.4819412231,0.108708314598,2.9081966877 --11.4469366074,0.107709512115,2.85977888107 --11.4409294128,0.107709534466,2.81937384605 --11.4349212646,0.10670953244,2.7789683342 --11.4559116364,0.107708349824,2.7455739975 --11.4799013138,0.107706971467,2.71318435669 --11.441901207,0.106708489358,2.68497443199 --11.4098968506,0.105709597468,2.63855910301 --11.4268875122,0.105708450079,2.60416245461 --11.4738750458,0.106705829501,2.57677674294 --11.4968643188,0.107704252005,2.54338026047 --11.5278539658,0.107702210546,2.51199007034 --11.5618429184,0.108699932694,2.4816057682 --11.5878362656,0.108698286116,2.46740722656 --11.6138267517,0.109696283937,2.43502044678 --11.5198287964,0.106700479984,2.37557959557 --11.5068225861,0.106700494885,2.3341691494 --11.7237958908,0.111688017845,2.34185171127 --11.7647848129,0.112684853375,2.3124756813 --11.7797765732,0.112683005631,2.2760746479 --11.8077707291,0.113680891693,2.26188063622 --11.8467617035,0.114677593112,2.2315030098 --11.8757514954,0.11467474699,2.19811296463 --11.8987436295,0.115672148764,2.16271305084 --11.9567317963,0.116667404771,2.13534235954 --11.9657249451,0.11666547507,2.09693646431 --12.0167150497,0.117660932243,2.06756091118 --12.0357093811,0.11865901202,2.05136823654 --12.0737009048,0.11965508759,2.01898479462 --12.1086931229,0.119651205838,1.98458743095 --12.150683403,0.120646804571,1.95220267773 --12.1846752167,0.121642850339,1.91882073879 --12.2246665955,0.122638352215,1.8854329586 --12.2656612396,0.123634628952,1.87224900723 --12.2796545029,0.123631767929,1.83485674858 --12.3276462555,0.12462644279,1.8024750948 --12.3676376343,0.125621542335,1.76808524132 --12.3966302872,0.126617357135,1.73269987106 --12.4246234894,0.126613110304,1.69630718231 --12.470615387,0.127607479692,1.66292738914 --12.4946117401,0.128604501486,1.64573216438 --12.6135988235,0.131593182683,1.62238442898 --12.6345939636,0.131589084864,1.58499765396 --12.6795864105,0.132582977414,1.54960978031 --12.7545776367,0.1345744133,1.51823782921 --12.8095703125,0.135567322373,1.48486745358 --12.8425645828,0.136561796069,1.44747853279 --12.884560585,0.137556955218,1.43229913712 --12.9335536957,0.138549879193,1.39591181278 --12.9665489197,0.139544084668,1.35852873325 --13.0025424957,0.140537917614,1.3211452961 --12.8165483475,0.135550498962,1.25866341591 --13.0775327682,0.142524927855,1.24537336826 --12.8675394058,0.136539801955,1.18087565899 --12.3365621567,0.122584715486,1.10544288158 --12.2025632858,0.118593938649,1.05298829079 --12.3665523529,0.123576648533,1.02965736389 --12.3955469131,0.123571261764,0.993274092674 --12.1145544052,0.116594143212,0.927744865417 --12.1975469589,0.118583858013,0.896381378174 --12.1735439301,0.117583356798,0.854965388775 --12.1585416794,0.117583438754,0.834762990475 --12.1875371933,0.11757786572,0.79736572504 --12.2365312576,0.11957038939,0.762994170189 --12.177529335,0.117573231459,0.719566047192 --12.3265218735,0.121555604041,0.690221607685 --12.2855186462,0.120556659997,0.648808300495 --12.2285194397,0.11856084317,0.625583052635 --12.2435150146,0.118556268513,0.587184667587 --12.2115125656,0.118556410074,0.545763194561 --12.2175092697,0.118552714586,0.507366001606 --12.090508461,0.11456283927,0.461908727884 --12.1145048141,0.115557268262,0.42451685667 --12.203499794,0.117544673383,0.390156298876 --12.2474966049,0.118536658585,0.352769941092 --12.0104980469,0.112560637295,0.323461681604 --12.1304931641,0.115544453263,0.29011708498 --11.9274930954,0.110563606024,0.244625389576 --12.0804843903,0.114540152252,0.172888085246 --12.2494802475,0.118517585099,0.13856087625 --12.072479248,0.113534376025,0.0960827022791 --12.1244773865,0.115526676178,0.077904522419 --12.2474746704,0.118508860469,0.0415591858327 --12.4984703064,0.12447566539,0.0062728151679 --12.6484680176,0.128453940153,-0.0310528464615 --12.4554662704,0.12347278744,-0.0735509321094 --12.66746521,0.129443123937,-0.111852616072 --12.0934638977,0.114510715008,-0.134322673082 --11.9134607315,0.109529107809,-0.172807812691 --11.8044576645,0.106539085507,-0.210259273648 --11.7894554138,0.106537520885,-0.247668415308 --11.7714529037,0.106536313891,-0.285080313683 --12.157453537,0.116483710706,-0.327303618193 --11.9744501114,0.111503265798,-0.362787514925 --11.9084482193,0.109509840608,-0.381022781134 --11.9164466858,0.109505109489,-0.418414562941 --11.9634447098,0.111495092511,-0.457799255848 --11.9524431229,0.110492683947,-0.495202720165 --11.9154405594,0.109493635595,-0.532627701759 --12.1864433289,0.11645322293,-0.578896760941 --12.3504457474,0.121426664293,-0.623217940331 --12.4874486923,0.124405644834,-0.648357391357 --12.5144481659,0.125397250056,-0.688741922379 --12.5564489365,0.126386523247,-0.731130897999 --12.4954462051,0.125390261412,-0.767555058002 --12.7444534302,0.131350189447,-0.8198376894 --12.0424337387,0.113444939256,-0.823580920696 --12.0024299622,0.112446218729,-0.860005438328 --12.210436821,0.117414012551,-0.891105771065 --12.1044330597,0.115424737334,-0.92355889082 --12.4914455414,0.125363364816,-0.986771583557 --12.0224285126,0.113427549601,-0.995404183865 --11.9304246902,0.110436707735,-1.0268458128 --12.0114269257,0.113419942558,-1.07121229172 --12.1854343414,0.117388918996,-1.12252521515 --12.0524282455,0.114406660199,-1.13179337978 --11.9964256287,0.112410366535,-1.16622757912 --11.9694232941,0.112409822643,-1.20163595676 --12.0214252472,0.113396838307,-1.24501788616 --11.9784240723,0.112398684025,-1.27943956852 --11.9154205322,0.111403740942,-1.31187260151 --12.0214252472,0.113381944597,-1.3602206707 --11.9674224854,0.112388022244,-1.37445163727 --12.0454273224,0.114370390773,-1.42081522942 --12.2084379196,0.119338735938,-1.47613143921 --12.2244386673,0.119330607355,-1.51752996445 --16.8487262726,0.24056006968,-2.07158637047 --16.8897380829,0.241541817784,-2.12996029854 --16.9777545929,0.243515491486,-2.19431066513 --17.0237617493,0.245501756668,-2.22748923302 --17.1187782288,0.247473731637,-2.2938375473 --17.1477909088,0.248456761241,-2.35221767426 --16.9877891541,0.24447222054,-2.38669705391 --16.7987861633,0.239493101835,-2.41619038582 --17.1568222046,0.249418348074,-2.51940703392 --16.8248081207,0.240464508533,-2.52897834778 --17.0608310699,0.247416689992,-2.58905339241 --15.2576971054,0.199726179242,-2.38538503647 --15.2407045364,0.199719011784,-2.43279743195 --15.3897237778,0.203681960702,-2.50411629677 --15.3177261353,0.202684551477,-2.54355764389 --15.2257261276,0.199691236019,-2.57799720764 --14.7776908875,0.188768610358,-2.53243422508 --14.9317121506,0.192730128765,-2.60575723648 --15.0187273026,0.194703906775,-2.66810655594 --14.762711525,0.188741803169,-2.67464470863 --14.2686710358,0.175825610757,-2.63830256462 --14.3036813736,0.176809608936,-2.69068169594 --14.1636743546,0.173826977611,-2.71316003799 --14.0346641541,0.169847384095,-2.71242070198 --14.000667572,0.169844657183,-2.75284481049 --13.9726715088,0.168840959668,-2.79325723648 --13.8486652374,0.165856167674,-2.81572318077 --13.7646617889,0.163863673806,-2.84516882896 --13.5946493149,0.159888505936,-2.85766267776 --13.5966567993,0.159879311919,-2.90205550194 --13.6256628036,0.160868957639,-2.93024015427 --13.5896654129,0.159867048264,-2.96866679192 --13.6556797028,0.161844432354,-3.02703094482 --13.542673111,0.15885849297,-3.04849171638 --13.4326658249,0.156872153282,-3.06995177269 --13.4666776657,0.157856076956,-3.12132978439 --13.3766727448,0.155865713954,-3.14678311348 --13.3296699524,0.153870999813,-3.15901231766 --13.3706817627,0.155853196979,-3.21238946915 --13.3006792068,0.153858989477,-3.24082660675 --13.2386779785,0.152863070369,-3.27126455307 --13.1316709518,0.149877250195,-3.28971672058 --13.2976999283,0.154831886292,-3.37302684784 --13.429725647,0.158793240786,-3.45036458969 --13.3387174606,0.155808538198,-3.45061254501 --13.365729332,0.156792968512,-3.50199818611 --13.3147287369,0.155794635415,-3.5344285965 --13.3157367706,0.15678486228,-3.57882261276 --13.2877407074,0.155781298876,-3.61724448204 --13.2947502136,0.15676997602,-3.66363883018 --13.2467508316,0.155771106482,-3.69606637955 --13.4847917557,0.161711171269,-3.78214168549 --13.3137741089,0.157740652561,-3.78163266182 --13.3467874527,0.158722817898,-3.83601665497 --13.2767839432,0.156728982925,-3.86245822906 --13.8208827972,0.17159023881,-4.05855369568 --13.7118749619,0.169605091214,-4.07501411438 --13.5928640366,0.16662247479,-4.0884847641 --13.7098894119,0.169589057565,-4.14461374283 --13.7008981705,0.169579863548,-4.19002771378 --13.6248950958,0.168587252498,-4.21446800232 --13.4708776474,0.164613753557,-4.21595716476 --13.450884819,0.164607688785,-4.25636863708 --13.4859008789,0.165587872267,-4.31375217438 --13.5609254837,0.167558059096,-4.38310670853 --13.6419458389,0.170532152057,-4.43125867844 --13.6839647293,0.17150978744,-4.49264335632 --13.6669721603,0.171502590179,-4.5340461731 --13.7750043869,0.174463197589,-4.61638736725 --13.9440498352,0.179407581687,-4.71969747543 --17.6958045959,0.2824254632,-5.99094438553 --17.6588058472,0.281426012516,-6.00916004181 --17.5087985992,0.27744653821,-6.02164554596 --17.4648113251,0.277439802885,-6.06806564331 --17.5048408508,0.278410673141,-6.14344167709 --17.5348682404,0.280383974314,-6.21582365036 --17.5148868561,0.280370742083,-6.27022838593 --17.5689182281,0.282337158918,-6.35159683228 --17.6029376984,0.283318430185,-6.39477586746 --17.6699771881,0.285281002522,-6.48113393784 --17.5769786835,0.283287078142,-6.51058387756 --17.6890258789,0.287236869335,-6.61391639709 --17.7350597382,0.289204627275,-6.69328212738 --17.5420398712,0.284238487482,-6.6857919693 --17.5360622406,0.284220278263,-6.74719619751 --17.4570560455,0.282232522964,-6.74944210052 --17.4350738525,0.282219111919,-6.80385065079 --17.3820858002,0.281214207411,-6.84728288651 --17.3631038666,0.281199872494,-6.9026889801 --17.3551273346,0.282182425261,-6.96208763123 --17.395160675,0.28315064311,-7.04146385193 --17.3531761169,0.283142477274,-7.08888959885 --17.2951869965,0.282139480114,-7.12831544876 --20.7290611267,0.378120243549,-8.53546142578 --21.4272727966,0.397887170315,-8.89443874359 --21.019203186,0.386980980635,-8.80607414246 --20.8181877136,0.382014006376,-8.80058765411 --20.4291210175,0.372104018927,-8.71621704102 --21.3694038391,0.399792760611,-9.18604373932 --21.2613925934,0.396811395884,-9.18030643463 --21.1463985443,0.393818229437,-9.21076965332 --40.2536315918,0.930918037891,-17.4684906006 --24.2323207855,0.482808113098,-10.7006750107 --21.0514850616,0.393762618303,-9.4070110321 --21.1855621338,0.39869210124,-9.54532337189 --20.9955444336,0.393723040819,-9.54083156586 --21.0045661926,0.394706040621,-9.58402061462 --20.9976005554,0.394679427147,-9.66041851044 --18.9930591583,0.339290231466,-8.83304023743 --20.9996795654,0.396620571613,-9.82120609283 --21.3568248749,0.407476007938,-10.0653772354 --21.5109119415,0.413395792246,-10.2186765671 --25.271112442,0.521117448807,-12.1089391708 --21.706073761,0.421254336834,-10.5185413361 --22.394329071,0.440994918346,-10.9305047989 --22.2953453064,0.439994484186,-10.9709644318 --21.9952945709,0.432062357664,-10.9115409851 --20.8359718323,0.39942073822,-10.4306554794 --20.9780578613,0.404342114925,-10.5819597244 --20.704990387,0.397419422865,-10.4883289337 --20.7190361023,0.398383706808,-10.5777177811 --20.5990409851,0.396394282579,-10.5991868973 --20.7741394043,0.402303308249,-10.7684669495 --20.7401695251,0.40228381753,-10.8338832855 --20.7302093506,0.402255952358,-10.9112825394 --21.0993804932,0.414094120264,-11.1864490509 --21.1714248657,0.417052716017,-11.2655973434 --21.5315952301,0.427891969681,-11.5397644043 --26.4753627777,0.573092639446,-14.2390222549 --38.5626792908,0.927706480026,-20.781703949 --38.4897537231,0.926664173603,-20.8981266022 --38.891998291,0.940448701382,-21.2722473145 --38.1588363647,0.920646369457,-21.0310935974 --37.9888267517,0.916674077511,-21.0163917542 --38.0359458923,0.920587718487,-21.1977386475 --22.8284301758,0.474154144526,-12.9168844223 --22.8054771423,0.475124388933,-12.999294281 --22.7505092621,0.474107354879,-13.0617170334 --22.7345581055,0.475074797869,-13.1481227875 --25.2015552521,0.549101114273,-14.652926445 --25.2155914307,0.550074100494,-14.7131109238 --25.192647934,0.551038444042,-14.806517601 --37.668586731,0.924197912216,-22.1708106995 --24.3665122986,0.530226230621,-14.6372203827 --38.2271385193,0.946762979031,-22.9825820923 --37.2488517761,0.919073760509,-22.5595970154 --37.2889175415,0.922022104263,-22.6627597809 --37.5651397705,0.9318395257,-22.9909591675 --36.3857650757,0.899236142635,-22.4341125488 --37.9245147705,0.947547852993,-23.5354785919 --35.7447090149,0.883351743221,-22.3522891998 --35.5987548828,0.881339907646,-22.4177646637 --35.5828552246,0.882275283337,-22.564157486 --35.6549377441,0.88621032238,-22.6872997284 --23.6948661804,0.524056494236,-15.268573761 --35.1259231567,0.874285459518,-22.6644096375 --35.2800979614,0.881149888039,-22.9196872711 --34.6429214478,0.863344490528,-22.6644916534 --34.5589904785,0.863308787346,-22.7649269104 --34.6230735779,0.866246342659,-22.8840751648 --34.6401901245,0.869167387486,-23.0514469147 --34.3231506348,0.861230611801,-22.9980373383 --34.5683746338,0.871053814888,-23.3172550201 --34.3843994141,0.867060184479,-23.3517608643 --34.4445381165,0.871961772442,-23.5491008759 --34.5216827393,0.875854611397,-23.7604293823 --34.3816757202,0.872878789902,-23.7447166443 --34.3167533875,0.872833549976,-23.8591423035 --34.2638435364,0.873783051968,-23.9815578461 --34.4050216675,0.880645394325,-24.2408447266 --34.5572128296,0.887502074242,-24.5091266632 --34.0750923157,0.874642968178,-24.3308315277 --34.2402839661,0.882493078709,-24.6091003418 --34.008228302,0.876559913158,-24.5254497528 --33.7432136536,0.870604932308,-24.497013092 --34.0394744873,0.882393598557,-24.8721923828 --33.4723052979,0.866578221321,-24.622959137 --33.59948349,0.872443556786,-24.8772544861 --33.3324661255,0.866491019726,-24.8438186646 --33.4906616211,0.874340176582,-25.1240959167 --32.9974632263,0.859533309937,-24.8386230469 --32.8324928284,0.856535315514,-24.8761177063 --32.4393997192,0.846645534039,-24.7417697906 --32.4605293274,0.849559247494,-24.9191417694 --32.3005561829,0.846560120583,-24.9576320648 --32.1265792847,0.843567728996,-24.9851360321 --32.089679718,0.845508873463,-25.1185455322 --32.1167488098,0.847457230091,-25.2207183838 --32.5411071777,0.8631721735,-25.7148113251 --32.8574066162,0.876937568188,-26.1289749146 --32.7634773254,0.875903904438,-26.2224235535 --32.6195220947,0.873895168304,-26.2759056091 --32.8787918091,0.884684681892,-26.6521072388 --32.4256591797,0.872831046581,-26.4568061829 --32.7308998108,0.884636163712,-26.7887859344 --33.444442749,0.910191357136,-27.5416717529 --32.8031959534,0.89243388176,-27.1915035248 --33.1885566711,0.908152461052,-27.6826171875 --33.1276550293,0.909098744392,-27.8080425262 --32.9746932983,0.906092166901,-27.8575344086 --32.4525108337,0.891279399395,-27.5942821503 --31.0467128754,0.845973432064,-26.4944591522 --30.9417743683,0.844947755337,-26.5729179382 --30.8878669739,0.845894873142,-26.6953411102 --30.9740486145,0.851767122746,-26.9386672974 --30.8921260834,0.851728379726,-27.038110733 --30.8772449493,0.853653669357,-27.1955051422 --30.4500999451,0.842801749706,-26.992193222 --30.71833992,0.852614760399,-27.3131961823 --29.811882019,0.825026273727,-26.6822223663 --31.1839084625,0.875190734863,-28.0736351013 --31.1250038147,0.876137018204,-28.197063446 --30.8149337769,0.868222415447,-28.094669342 --28.1552886963,0.778621971607,-25.8549461365 --28.0523414612,0.777600944042,-25.9234085083 --28.0133781433,0.777583122253,-25.9696311951 --27.9194393158,0.777557551861,-26.045085907 --27.8194942474,0.776535093784,-26.1155452728 --27.7255535126,0.776509463787,-26.1910018921 --27.6476249695,0.776474058628,-26.2824478149 --27.5476818085,0.775451898575,-26.3519058228 --27.4967079163,0.775441169739,-26.386138916 --27.398765564,0.774417757988,-26.4575958252 --27.3128318787,0.774387061596,-26.5410480499 --27.2218952179,0.774359762669,-26.6185016632 --27.1239509583,0.77333676815,-26.6889591217 --27.0300121307,0.773310244083,-26.7654209137 --26.9330711365,0.772287011147,-26.8358764648 --26.8941059113,0.772269308567,-26.8810997009 --26.8081741333,0.772238790989,-26.963552475 --26.7292461395,0.77320343256,-27.0540008545 --26.6313037872,0.77218067646,-27.1234588623 --26.5523757935,0.772145688534,-27.2129058838 --26.4354190826,0.771133840084,-27.264383316 --26.338476181,0.771110296249,-27.3348426819 --26.3115215302,0.771085143089,-27.3920574188 --26.2205867767,0.77105730772,-27.4695148468 --26.1266460419,0.771031796932,-27.5429725647 --26.0226993561,0.770012378693,-27.6064395905 --25.9327659607,0.769983887672,-27.6848964691 --27.6572971344,0.837787628174,-29.6900177002 --27.4963169098,0.834798336029,-29.7045249939 --27.409318924,0.833808362484,-29.7037830353 --27.1642684937,0.827875137329,-29.6253528595 --27.1423988342,0.829796016216,-29.7877597809 --27.1445522308,0.833700597286,-29.9771461487 --26.9695529938,0.830722868443,-29.9716625214 --26.8956451416,0.831676959991,-30.0791091919 --27.0118961334,0.839503645897,-30.3974132538 --26.9228992462,0.837515294552,-30.3936748505 --27.0331478119,0.845343887806,-30.7089805603 --26.6769962311,0.83548951149,-30.4986362457 --26.4819812775,0.831525921822,-30.469171524 --25.9756889343,0.815778315067,-30.0809402466 --26.1910362244,0.82753276825,-30.5191688538 --26.3062973022,0.835354685783,-30.8454723358 --26.0901813507,0.82945638895,-30.6918315887 --25.9642276764,0.827446222305,-30.7393169403 --25.8983268738,0.829394340515,-30.8557567596 --25.7333335876,0.826412796974,-30.8552703857 --25.6193885803,0.825395107269,-30.9147453308 --18.628988266,0.549342930317,-22.7043895721 --18.4148979187,0.543428003788,-22.5889472961 --18.1597137451,0.534578561783,-22.3513374329 --17.8665428162,0.525723934174,-22.1349563599 --17.6914863586,0.520783662796,-22.0614891052 --17.628534317,0.521762192249,-22.1229324341 --17.5715885162,0.521735489368,-22.1933727264 --17.5176486969,0.522706329823,-22.2678127289 --17.4556999207,0.522683143616,-22.3322601318 --17.4307308197,0.522666811943,-22.3724784851 --17.3727855682,0.52364051342,-22.4419212341 --17.3158416748,0.523613631725,-22.5123596191 --17.2578983307,0.524586796761,-22.5828037262 --17.1989517212,0.524561047554,-22.6512470245 --17.1370048523,0.525537192822,-22.7166957855 --17.0780601501,0.52551138401,-22.7851352692 --17.0530948639,0.52649384737,-22.8273582458 --17.0001564026,0.527462720871,-22.9047985077 --16.9442157745,0.527433931828,-22.9782390594 --16.8842716217,0.5284075737,-23.0476875305 --16.8213233948,0.52838408947,-23.1121330261 --16.7653846741,0.529354691505,-23.1865749359 --16.7384166718,0.52933883667,-23.2257976532 --16.6864814758,0.530305802822,-23.3062362671 --16.627538681,0.531278669834,-23.3766784668 --16.5726032257,0.531247437,-23.454120636 --16.5016498566,0.531229317188,-23.5095767975 --16.44871521,0.532196760178,-23.5890140533 --16.3857707977,0.533171534538,-23.6564674377 --16.3238258362,0.533146083355,-23.7239112854 --16.3078708649,0.534120619297,-23.7791233063 --16.2479305267,0.535092830658,-23.8505687714 --16.1809844971,0.535070002079,-23.9140262604 --16.1310539246,0.53603374958,-23.9994621277 --16.0721168518,0.537004232407,-24.0739097595 --16.0131797791,0.537974715233,-24.1483573914 --15.9962263107,0.53894919157,-24.2035675049 --20.8402919769,0.765546262264,-31.650188446 --21.4342079163,0.797900974751,-32.76512146 --21.1109981537,0.78807669878,-32.4957695007 --21.3284645081,0.802763521671,-33.050994873 --21.1544399261,0.798805177212,-33.0075302124 --20.8923015594,0.791927993298,-32.8271331787 --20.9845180511,0.798783659935,-33.0842590332 --20.6082305908,0.785015165806,-32.7199478149 --20.5763835907,0.788927078247,-32.8953704834 --21.6960525513,0.847750782967,-34.9098892212 --20.277387619,0.783971428871,-32.8733978271 --20.1724491119,0.783951342106,-32.933883667 --21.5254669189,0.855528175831,-35.3672065735 --21.6647644043,0.864328026772,-35.7192955017 --21.5668544769,0.865290641785,-35.8097686768 --21.5500545502,0.870173454285,-36.0351791382 --22.5837078094,0.927019953728,-38.0147514343 --21.6145973206,0.884838163853,-36.6569213867 --21.4946594238,0.88382011652,-36.7144126892 --21.993598938,0.915179133415,-37.8274078369 --21.5120353699,0.893593430519,-37.1389923096 --21.741601944,0.911218106747,-37.8022041321 --21.9311199188,0.926879405975,-38.4034500122 --21.0961475372,0.889592468739,-37.2215156555 --20.9832248688,0.890565097332,-37.2950019836 --20.8172206879,0.887594163418,-37.2725334167 --15.0058383942,0.591520249844,-27.253786087 --14.918879509,0.591508924961,-27.2972583771 --13.6841640472,0.529728293419,-25.2506504059 --16.6879634857,0.694387793541,-30.9486427307 --16.5810012817,0.694382846355,-30.9821300507 --16.5161018372,0.696332454681,-31.0925827026 --16.5021839142,0.697286248207,-31.1837940216 --20.1001224518,0.899175524712,-38.1972885132 --20.1093959808,0.906011521816,-38.5026779175 --20.0175113678,0.907958626747,-38.6191520691 --20.0748729706,0.91773545742,-39.0255088806 --14.0552129745,0.588446497917,-27.631778717 --13.9822778702,0.588419735432,-27.7012405396 --12.7123327255,0.521779119968,-25.4106731415 --12.6793632507,0.522766470909,-25.4439029694 --12.5082435608,0.51686501503,-25.299446106 --12.5554962158,0.524707078934,-25.5918121338 --12.3192625046,0.514883637428,-25.314409256 --12.2443037033,0.515871047974,-25.35887146 --12.2214384079,0.518794596195,-25.5122947693 --12.1944799423,0.519774436951,-25.5585212708 --13.7133750916,0.613811790943,-28.9286880493 --12.1377363205,0.525631129742,-25.8493766785 --12.0778102875,0.52659702301,-25.9308300018 --5.54497861862,0.137665182352,-12.1814813614 --5.43384599686,0.13276027143,-12.038974762 --12.8598394394,0.589268863201,-28.268409729 --18.0397014618,0.909590542316,-39.6833610535 --18.03399086,0.916421234608,-39.9987678528 --17.9581508636,0.919340372086,-40.163230896 --17.7310199738,0.913456082344,-39.9918174744 --13.2978878021,0.647988200188,-30.5882797241 --17.757019043,0.938866436481,-41.0790061951 --17.8022708893,0.94571095705,-41.3581695557 --17.6392688751,0.943740665913,-41.3337020874 --17.4632396698,0.940788030624,-41.2792510986 --17.3152675629,0.938798546791,-41.287776947 --12.4354276657,0.625404834747,-30.0082187653 --11.3493776321,0.558792471886,-27.6565208435 --16.9364852905,0.939738929272,-41.4692955017 --16.5097427368,0.91524630785,-40.6138534546 --12.2538881302,0.635165691376,-30.5017910004 --12.1328735352,0.633194684982,-30.4762973785 --12.0008325577,0.630241632462,-30.4198131561 --16.0370731354,0.917137801647,-40.9048614502 --9.48878955841,0.470625668764,-24.6779098511 --9.40079212189,0.469638705254,-24.6783924103 --8.27038764954,0.394240319729,-21.9537334442 --7.60501432419,0.351157128811,-20.4026870728 --7.55606746674,0.352134048939,-20.464138031 --7.48206138611,0.352149486542,-20.4596118927 --7.43011045456,0.352129489183,-20.5160694122 --7.41916847229,0.354097187519,-20.5822792053 --7.33614015579,0.352127164602,-20.5527572632 --7.27917528152,0.353116363287,-20.593214035 --7.22822666168,0.354094564915,-20.6526699066 --7.12614965439,0.351156592369,-20.5681648254 --7.0561504364,0.350167810917,-20.5706310272 --7.03227376938,0.35409963131,-20.710067749 --7.02033376694,0.355066269636,-20.7782783508 --7.07265901566,0.364867210388,-21.1426467896 --6.68782806396,0.339418500662,-20.2163772583 --6.65091323853,0.341374576092,-20.3138179779 --6.58191299438,0.340386420488,-20.315284729 --6.50689792633,0.339407742023,-20.3007640839 --6.42786693573,0.338439226151,-20.2682342529 --6.39386796951,0.337444335222,-20.2704696655 --6.3559551239,0.340399950743,-20.3689155579 --6.2909655571,0.339404881001,-20.3823814392 --6.22597742081,0.339409321547,-20.3968486786 --6.17402505875,0.340390414,-20.4513034821 --6.70882463455,0.393250018358,-22.4392700195 --6.1182718277,0.347256094217,-20.7271766663 --6.16852903366,0.354097694159,-21.011341095 --6.12160205841,0.356063395739,-21.092792511 --6.05060148239,0.3550760746,-21.0932674408 --6.00668287277,0.357036411762,-21.1837120056 --5.99186038971,0.361936032772,-21.3791351318 --5.9359126091,0.362915277481,-21.4376010895 --6.13580226898,0.388363957405,-22.4118461609 --6.15197992325,0.393258094788,-22.6060390472 --6.09002399445,0.394243657589,-22.653503418 --6.03810548782,0.395205676556,-22.7419624329 --5.9741435051,0.396195292473,-22.7824268341 --5.94028949738,0.400116831064,-22.9408683777 --5.88436126709,0.401085227728,-23.0183296204 --5.84736680984,0.401088863611,-23.0235710144 --5.78441143036,0.402074486017,-23.0710315704 --5.70941972733,0.402083545923,-23.0785140991 --5.57749271393,0.403065472841,-23.1554470062 --5.48944854736,0.401106834412,-23.1069393158 --5.45059251785,0.405030936003,-23.261384964 --5.42966175079,0.405994772911,-23.3356132507 --5.36370372772,0.406983017921,-23.3790817261 --5.27063798904,0.405038237572,-23.3065757751 --5.2197394371,0.406988948584,-23.4150314331 --5.16884756088,0.409936338663,-23.5294914246 --5.16515493393,0.417760193348,-23.8579063416 --5.12732553482,0.422668993473,-24.0393543243 --5.10841464996,0.42462143302,-24.1335792542 --5.0454826355,0.425594329834,-24.2040462494 --4.98255300522,0.427565515041,-24.2775154114 --4.92364549637,0.429523557425,-24.3739814758 --5.56599760056,0.522476732731,-27.9508666992 --5.47198534012,0.521502077579,-27.9313621521 --5.2011179924,0.49605178833,-27.001001358 --5.19429826736,0.500949919224,-27.1902160645 --5.17263031006,0.509763479233,-27.5386543274 --4.99920368195,0.497041881084,-27.0792121887 --4.38350152969,0.422709405422,-24.2051448822 --4.302485466,0.421734362841,-24.185628891 --4.22548818588,0.421747744083,-24.1861114502 --4.15753984451,0.422731280327,-24.2385845184 --4.11954164505,0.421737372875,-24.2398223877 --4.63385629654,0.512740135193,-27.7398223877 --4.57301712036,0.516660451889,-27.9032897949 --4.44579696655,0.509811639786,-27.664812088 --3.78137683868,0.415897727013,-24.0567817688 --3.70638394356,0.415908306837,-24.0622615814 --3.59215331078,0.409062534571,-23.8177776337 --3.57327079773,0.411999285221,-23.9400005341 --3.53350043297,0.417875647545,-24.1794528961 --3.4715988636,0.420831978321,-24.2799243927 --3.39459657669,0.419848412275,-24.2754058838 --3.32162618637,0.420846134424,-24.3038883209 --3.22851014137,0.416930824518,-24.1803836823 --3.18849730492,0.416946262121,-24.1656265259 --3.11653232574,0.416940569878,-24.2001094818 --3.02541971207,0.414022982121,-24.0806045532 --2.96654987335,0.416960567236,-24.2140731812 --2.90365457535,0.419913649559,-24.3205432892 --1.79059624672,0.204729139805,-15.9492321014 --1.74058842659,0.203742876649,-15.9476947784 --2.56200695038,0.401351511478,-23.6412982941 --2.50718212128,0.406263023615,-23.820766449 --2.45438432693,0.411158591509,-24.0282306671 --2.38948464394,0.41311481595,-24.1297092438 --2.31550550461,0.414118051529,-24.1491947174 --2.23646450043,0.41215762496,-24.1046791077 --2.21766066551,0.417049884796,-24.3059062958 --2.46316003799,0.509009897709,-27.9061546326 --2.35997986794,0.504134058952,-27.7146606445 --2.29727196693,0.511981248856,-28.009141922 --2.18800544739,0.504155576229,-27.7296524048 --3.6912343502,1.23982071877,-56.5385360718 --3.32408952713,1.23398578167,-56.3207092285 --2.67964911461,1.21838128567,-55.7517738342 --2.52202796936,1.22720265388,-56.1023406982 --2.34093022346,1.22329938412,-55.9689292908 --2.82571601868,1.65668833256,-72.9321365356 --2.59159708023,1.6518099308,-72.7607727051 --2.35642886162,1.64595997334,-72.5394134521 --2.23828411102,1.64206933975,-72.367729187 --2.01132297516,1.64110028744,-72.3563690186 --1.7853679657,1.64112782478,-72.3510055542 --1.56049537659,1.64310836792,-72.4286422729 --1.33774507046,1.64801943302,-72.6292800903 --1.11501908302,1.65391695499,-72.8539123535 --0.889252543449,1.65783810616,-73.0375518799 -0.750550687313,1.86075842381,-77.47240448 -1.28848159313,1.46109819412,-62.5035324097 -1.48436033726,1.45897996426,-62.4237594604 -1.29434871674,1.08410060406,-48.3325462341 -1.44525563717,1.08200955391,-48.2668151855 -2.14741253853,1.4382764101,-61.6135749817 -2.34546542168,1.44025671482,-61.7087936401 -2.55678153038,1.45038247108,-62.0710029602 -2.74863362312,1.44725084305,-61.9632301331 -3.11611437798,1.54312860966,-65.5392379761 -3.39953279495,1.52972912788,-65.0165939331 -3.6411113739,1.54699671268,-65.6507644653 -3.86126852036,1.5520311594,-65.8569717407 -3.9838616848,1.51520490646,-64.4682846069 -4.2537984848,1.54266822338,-65.4694290161 -4.37145853043,1.50788104534,-64.1457519531 -4.46532583237,1.50478315353,-64.032875061 -4.60037231445,1.48021030426,-63.1011772156 -4.84084320068,1.49441802502,-63.6273536682 -5.08531856537,1.50862681866,-64.158531189 -5.27611112595,1.50446307659,-63.9907684326 -5.43557071686,1.4911185503,-63.4800376892 -5.60921287537,1.48287391663,-63.1562957764 -5.85777521133,1.52669739723,-64.7862472534 -6.05868244171,1.52559649944,-64.7364654541 -6.56648492813,1.52436184883,-64.6460342407 -6.76941299438,1.52427244186,-64.6172637939 -6.96224451065,1.52113080025,-64.4885025024 -7.05614519119,1.51905226707,-64.4086227417 -7.44869804382,1.56383657455,-66.0636444092 -4.79676485062,0.874365746975,-40.2533531189 -4.88340377808,0.865140318871,-39.8986930847 -8.06777191162,1.51759970188,-64.2477645874 -8.25055503845,1.51343429089,-64.0680160522 -8.37065887451,1.51746404171,-64.1981048584 -5.30815601349,0.860896945,-39.7107582092 -5.44419002533,0.862883150578,-39.7660484314 -5.5530371666,0.859770357609,-39.6263656616 -5.86938858032,0.871893405914,-40.03490448 -5.99434375763,0.871838092804,-40.0082015991 -6.05430078506,0.870799422264,-39.9733581543 -6.16214704514,0.867686331272,-39.8316764832 -6.2720079422,0.864581525326,-39.7059936523 -6.40401029587,0.865551352501,-39.7282867432 -6.52896690369,0.86549705267,-39.7025947571 -6.71727895737,0.875629365444,-40.0528335571 -6.86272001266,0.88784468174,-40.5289039612 -6.9967083931,0.888806223869,-40.537197113 -7.78321695328,0.990606606007,-44.2708320618 -8.92574977875,1.0953387022,-48.0969848633 -7.74202013016,0.903807878494,-40.9746017456 -11.4701414108,1.42519032955,-60.2520866394 -11.6620721817,1.42510724068,-60.2203330994 -12.6226787567,1.5309253931,-64.1058197021 -12.7984733582,1.52776920795,-63.9320831299 -12.9411211014,1.51953828335,-63.6023788452 -13.0797586441,1.51130235195,-63.2606811523 -9.8955783844,1.07245326042,-47.0632705688 -9.95950508118,1.07139754295,-46.9994239807 -13.5906019211,1.51209914684,-63.2072753906 -13.8447532654,1.51912713051,-63.4144668579 -14.0165500641,1.5149743557,-63.2427368164 -6.23398160934,0.536779165268,-27.206205368 -6.3229675293,0.536750555038,-27.1985416412 -6.61055040359,0.555013537407,-27.8379020691 -6.28256940842,0.497967600822,-25.712064743 -13.3568181992,1.27519702911,-54.1336708069 -6.61113548279,0.516211926937,-26.3365955353 -7.35634279251,0.583289861679,-28.7415218353 -7.46939182281,0.585291802883,-28.8038387299 -11.9508285522,1.04600358009,-45.6049842834 -8.1642074585,0.613594710827,-29.7340965271 -8.28225231171,0.615593552589,-29.7934112549 -8.77146720886,0.626605510712,-30.0706539154 -8.85740184784,0.625549256802,-30.0090007782 -8.88733005524,0.623502016068,-29.9351863861 -8.97226428986,0.62244617939,-29.8735332489 -9.05920600891,0.621393561363,-29.8188781738 -9.1401309967,0.620333254337,-29.7462272644 -9.22305965424,0.619274616241,-29.6775817871 -9.30799770355,0.618220806122,-29.6189289093 -9.38691902161,0.617159128189,-29.5422801971 -9.42086410522,0.616120159626,-29.4854640961 -9.50781059265,0.615071296692,-29.4368076324 -9.54461574554,0.61095315218,-29.2302017212 -9.66766452789,0.612953543663,-29.2935123444 -21.9677848816,1.64195179939,-66.1505126953 -13.5571393967,0.911451160908,-39.8872032166 -13.5970497131,0.909392058849,-39.7973823547 -13.7330179214,0.910345554352,-39.7836875916 -13.8760032654,0.911306619644,-39.7879943848 -23.4610748291,1.66980433464,-66.753578186 -23.6970272064,1.67172920704,-66.7518081665 -15.0608415604,0.975089728832,-41.9152030945 -22.1038322449,1.51414954662,-61.0201683044 -23.4267902374,1.60953319073,-64.3671798706 -23.7269172668,1.61654353142,-64.5603408813 -25.0274410248,1.70068836212,-67.4505996704 -25.3145008087,1.70566356182,-67.5707778931 -25.394071579,1.69540667534,-67.1371536255 -25.4646244049,1.68514323235,-66.6855316162 -26.2217655182,1.72562730312,-68.0282974243 -26.4389572144,1.73369073868,-68.2723236084 -21.5422534943,1.36014461517,-55.0632247925 -21.7161617279,1.36005687714,-54.9955062866 -21.9572162628,1.3650393486,-55.0977287292 -27.2563781738,1.73020279408,-67.82837677 -27.4532222748,1.72807586193,-67.7026443481 -27.5280895233,1.72598779202,-67.5798034668 -27.7960834503,1.72993087769,-67.6260070801 -28.2735214233,1.74807977676,-68.1790313721 -28.5375003815,1.75101542473,-68.2082366943 -28.7894477844,1.75393736362,-68.2044677734 -21.0589733124,1.21529316902,-49.3858451843 -29.4737129211,1.77094972134,-68.6167449951 -28.5565719604,1.70193779469,-66.1847991943 -28.6742649078,1.69574379921,-65.8841400146 -28.8631038666,1.6946182251,-65.7524185181 -30.3675346375,1.7796741724,-68.6015319824 -30.5753898621,1.77855229378,-68.4877929688 -27.3138217926,1.53498375416,-59.8768196106 -27.4916877747,1.53487479687,-59.7671051025 -29.8606472015,1.67161405087,-64.4014663696 -30.0670318604,1.65923190117,-63.7861785889 -30.3881282806,1.66622316837,-63.9473457336 -30.4487495422,1.65800106525,-63.5557441711 -30.3583450317,1.64579463005,-63.1100463867 -24.9041805267,1.30220878124,-51.3082885742 -30.6408920288,1.63848996162,-62.6807022095 -18.8378410339,0.919088184834,-38.1284790039 -18.9046802521,0.915986418724,-37.9618530273 -18.9805374146,0.912891507149,-37.8132209778 -19.0093154907,0.907761931419,-37.5716362 -19.1974983215,0.914827287197,-37.7966918945 -19.4506549835,0.922865450382,-38.0009040833 -31.2830200195,1.60133159161,-60.7970695496 -26.265329361,1.30147659779,-50.610874176 -26.6826496124,1.31557428837,-51.0229568481 -31.7494754791,1.59494328499,-60.2960166931 -26.8854370117,1.3134175539,-50.8234481812 -26.9601955414,1.30827105045,-50.5758323669 -27.4406032562,1.32640457153,-51.0908622742 -27.5914840698,1.32531094551,-50.9861793518 -27.8325042725,1.3302770853,-51.0464172363 -28.0975608826,1.33525836468,-51.1486358643 -28.453754425,1.3462985754,-51.4147758484 -28.5136699677,1.34524071217,-51.3319473267 -29.0691547394,1.36640548706,-51.9479179382 -29.5344982147,1.38250803947,-52.3939666748 -30.7749824524,1.44009542465,-54.2033576965 -31.032995224,1.44405531883,-54.2595863342 -32.1182136536,1.49252486229,-55.7561149597 -28.8511219025,1.31132566929,-49.6953392029 -29.0672664642,1.31836545467,-49.8863792419 -32.6380348206,1.4973294735,-55.6417961121 -33.180431366,1.51544940472,-56.1627883911 -33.8069419861,1.5386146307,-56.8177070618 -34.1410331726,1.54660403728,-56.9708786011 -34.5702514648,1.5596460104,-57.277973175 -35.0275039673,1.57370185852,-57.6270370483 -34.621761322,1.54836893082,-56.7536048889 -35.320602417,1.55615437031,-56.6873779297 -35.5325164795,1.55707037449,-56.6286582947 -32.2580757141,1.36668097973,-50.1449737549 -32.5591430664,1.37366449833,-50.264175415 -32.1593284607,1.34628975391,-49.3019561768 -32.4203453064,1.35125422478,-49.3611907959 -32.7554588318,1.35925531387,-49.5323600769 -33.0735473633,1.36724674702,-49.6745491028 -32.9802818298,1.35911726952,-49.3638496399 -31.8696250916,1.29941177368,-47.3662223816 -32.0835952759,1.30235791206,-47.3624916077 -29.8986949921,1.19216191769,-43.8207397461 -29.9384784698,1.1880364418,-43.5811576843 -32.3996963501,1.28481197357,-46.3952560425 -32.7067756653,1.29280078411,-46.5234489441 -36.0159873962,1.42996907234,-50.5736503601 -40.3756828308,1.40691506863,-46.2115020752 -23.419965744,0.71229070425,-25.9387378693 -23.5219192505,0.713249742985,-25.8870983124 -23.6188716888,0.713207662106,-25.8304595947 -23.7208271027,0.714166939259,-25.7788200378 -23.8397960663,0.716130495071,-25.7441692352 -23.800699234,0.713084459305,-25.6194190979 -39.0677375793,1.29002356529,-41.425994873 -39.0975418091,1.28591525555,-41.1964263916 -39.0102539062,1.27677643299,-40.8439483643 -38.9771232605,1.27371048927,-40.6802024841 -38.9398765564,1.26658713818,-40.3846893311 -38.9867019653,1.26348698139,-40.1791038513 -39.0215187073,1.26038444042,-39.9625320435 -39.0193099976,1.2552729845,-39.707988739 -39.048122406,1.25217056274,-39.4874229431 -38.9088096619,1.24202764034,-39.097984314 -38.6655235291,1.22991430759,-38.7283973694 -38.5952720642,1.22279143333,-38.4149055481 -38.5270195007,1.21566987038,-38.1044120789 -38.4968032837,1.2105588913,-37.8348884583 -38.4585762024,1.2044467926,-37.5583724976 -38.5214271545,1.20235943794,-37.3837814331 -38.5792808533,1.20027112961,-37.2041893005 -38.5631713867,1.19721710682,-37.0714302063 -38.6380348206,1.19613325596,-36.9088287354 -38.6978912354,1.19404709339,-36.7342376709 -27.1425304413,0.771455585957,-25.5253562927 -26.3998832703,0.74123185873,-24.663351059 -26.339723587,0.736156105995,-24.450838089 -24.8875999451,0.681792497635,-22.9423618317 -23.857837677,0.643551528454,-21.9133453369 -22.9611206055,0.608313977718,-20.9454517365 -22.6938400269,0.597208321095,-20.5670890808 -22.2494449615,0.579069852829,-20.0318546295 -21.582906723,0.552890181541,-19.299785614 -21.2756156921,0.53978407383,-18.9004459381 -20.8742637634,0.523662209511,-18.4211769104 -20.5530128479,0.511579275131,-18.0756320953 -20.5279140472,0.508531451225,-17.9380874634 -20.581867218,0.50849878788,-17.8714790344 -18.6505489349,0.439106017351,-16.0663318634 -18.371301651,0.427019029856,-15.7209663391 -18.2901821136,0.422968357801,-15.5494613647 -18.639333725,0.43299382925,-15.7506351471 -16.4029064178,0.354589819908,-13.7854766846 -16.4188575745,0.353561937809,-13.709897995 -16.4718322754,0.354540586472,-13.6662893295 -16.7309341431,0.361553609371,-13.7965288162 -12.3082008362,0.208802938461,-10.0171346664 -8.25873088837,0.0701322853565,-6.59441280365 -8.25271892548,0.0701264217496,-6.56762838364 -8.35074234009,0.0711225122213,-6.5614027977 -8.37774085999,0.0721170082688,-6.53980731964 -8.39273262024,0.0711096599698,-6.50822305679 -8.42473506927,0.0721051841974,-6.49161434174 -8.46073818207,0.0721008405089,-6.47602272034 -8.46573352814,0.0720970705152,-6.45922279358 -8.47372150421,0.0720889866352,-6.42263841629 -8.51772975922,0.0720859840512,-6.41403341293 -8.53872489929,0.0720799788833,-6.38843250275 -8.57472896576,0.0730757191777,-6.37283658981 -8.58271789551,0.0720678344369,-6.33625459671 -8.61271762848,0.0730629488826,-6.31665611267 -8.61971378326,0.0730594918132,-6.30086040497 -8.6547164917,0.0730553343892,-6.2852563858 -8.6727104187,0.0730487927794,-6.25567340851 -8.71571826935,0.0740456581116,-6.24606132507 -8.72770881653,0.0730385482311,-6.21247816086 -8.75670909882,0.0740336179733,-6.19187879562 -8.77170848846,0.074031047523,-6.1810874939 -8.80471038818,0.0740266367793,-6.16348409653 -8.81670188904,0.0740198791027,-6.13089132309 -8.85470676422,0.0750159621239,-6.11628866196 -8.87470245361,0.0750100314617,-6.08869791031 -8.89369678497,0.0750039815903,-6.06011104584 -8.91469287872,0.0749982967973,-6.03351736069 -8.95070362091,0.0749980732799,-6.0377073288 -8.96869754791,0.0749921277165,-6.00911331177 -9.0067024231,0.075988098979,-5.99351501465 -9.00168609619,0.0749799013138,-5.94893693924 -9.0396900177,0.0759759172797,-5.93333673477 -9.08569717407,0.076972797513,-5.9237241745 -9.08868503571,0.0759654641151,-5.88414764404 -9.11669158936,0.0769643113017,-5.88234043121 -9.16369915009,0.0769611671567,-5.87273025513 -9.17469120026,0.0769547820091,-5.8391418457 -9.18568229675,0.0769482776523,-5.80456399918 -9.1836681366,0.0759408324957,-5.76199102402 -9.22267246246,0.076936930418,-5.7463889122 -9.28468704224,0.077934935689,-5.74576950073 -9.30769062042,0.0789332166314,-5.73996639252 -9.32468509674,0.0789275690913,-5.71037340164 -13.5234975815,0.208242431283,-8.33100891113 -13.4894552231,0.206225469708,-8.25045967102 -12.3209285736,0.169125899673,-7.46067142487 -13.1822710037,0.195175364614,-7.94251966476 -13.2402687073,0.196166157722,-7.92190361023 -13.0371713638,0.189145475626,-7.76825475693 -13.1121778488,0.191137522459,-7.7576341629 -13.2191963196,0.193131536245,-7.76599311829 -13.2511844635,0.193120777607,-7.72939538956 -13.1531190872,0.190101757646,-7.6138920784 -13.2151203156,0.191093027592,-7.59527635574 -13.1420793533,0.188082545996,-7.52453565598 -13.1590623856,0.188071191311,-7.47895336151 -13.7592735291,0.205092355609,-7.77298784256 -13.2040328979,0.188049420714,-7.39477872849 -13.1559906006,0.186034947634,-7.31223773956 -13.1849794388,0.186024770141,-7.2746424675 -13.1889572144,0.185013234615,-7.2220697403 -13.2759790421,0.18701171875,-7.2442240715 -13.1959257126,0.183996334672,-7.14470529556 -13.192902565,0.183984905481,-7.08913326263 -13.2899160385,0.185977861285,-7.08849906921 -13.2108659744,0.182963490486,-6.9919719696 -13.2178468704,0.181952834129,-6.94239330292 -13.3538742065,0.185947135091,-6.96173715591 -13.4408941269,0.187945023179,-6.98189163208 -13.6289386749,0.192940875888,-7.02819681168 -13.5068731308,0.18792539835,-6.90870666504 -13.4748411179,0.186913520098,-6.83815288544 -13.5078315735,0.186903864145,-6.80156040192 -13.4998073578,0.185893058777,-6.74399185181 -13.5998210907,0.188885554671,-6.74235200882 -14.8822402954,0.225915908813,-7.36975097656 -13.5457715988,0.18586833775,-6.63403367996 -13.6027698517,0.18685951829,-6.60942602158 -13.7207870483,0.1898522228,-6.61577367783 -13.7877883911,0.190843403339,-6.59516143799 -16.2725658417,0.262884318829,-7.76299905777 -13.8087654114,0.190828680992,-6.52578449249 -13.799741745,0.189818322659,-6.46722459793 -13.7447042465,0.187807500362,-6.38768625259 -13.8637218475,0.190799683332,-6.39203596115 -13.7236585617,0.185787945986,-6.27255249023 -13.8266716003,0.187779858708,-6.26891326904 -13.8436565399,0.187770605087,-6.22432899475 -13.8646535873,0.18876606226,-6.20753145218 -13.9176502228,0.189757108688,-6.17892980576 -13.9036273956,0.188747748733,-6.12036275864 -13.9286155701,0.188738644123,-6.07877922058 -13.9796123505,0.189729943871,-6.05016851425 -14.0596160889,0.190721035004,-6.03255367279 -14.1916351318,0.19371239841,-6.03889513016 -14.3086585999,0.197708040476,-6.06403493881 -14.5136966705,0.202698931098,-6.10033416748 -14.5206785202,0.201689422131,-6.04876470566 -14.6987094879,0.206679865718,-6.07207679749 -14.696688652,0.205670401454,-6.01651000977 -14.9227304459,0.211660042405,-6.05779743195 -15.0037307739,0.213649973273,-6.03618097305 -14.9116973877,0.210645854473,-5.97045230865 -15.0407114029,0.213635489345,-5.9688038826 -15.4758043289,0.225622102618,-6.09196186066 -15.571808815,0.227611452341,-6.07532596588 -17.4752693176,0.280578702688,-6.78158664703 -17.557264328,0.282565563917,-6.75096654892 -17.5902614594,0.282559067011,-6.73216295242 -17.6332454681,0.283546209335,-6.68457460403 -17.6882343292,0.284533500671,-6.64296865463 -17.7242164612,0.284521013498,-6.59337806702 -17.7792053223,0.285508155823,-6.55077648163 -17.834192276,0.286495357752,-6.50817394257 -17.8861808777,0.287482500076,-6.46357679367 -17.9211750031,0.287475913763,-6.44477176666 -17.9721641541,0.288463175297,-6.40017032623 -18.0131473541,0.289450705051,-6.35157680511 -18.0601329803,0.290438055992,-6.3049788475 -18.1221237183,0.291425019503,-6.26337432861 -18.1821117401,0.292411983013,-6.22077083588 -18.2120933533,0.292399793863,-6.16718626022 -18.2670917511,0.293392539024,-6.15436983109 -18.3060779572,0.294380128384,-6.10377931595 -18.3540630341,0.295367449522,-6.05618286133 -18.4120502472,0.296354621649,-6.01257610321 -18.4620380402,0.297341823578,-5.96498012543 -18.5060214996,0.297329306602,-5.91538715363 -18.5670108795,0.298316329718,-5.87177991867 -18.6030063629,0.299309462309,-5.85097789764 -18.6619930267,0.300296366215,-5.80537796021 -18.709980011,0.30128377676,-5.75677919388 -18.762966156,0.302270948887,-5.70918083191 -18.8119525909,0.303258240223,-5.65958786011 -18.8689403534,0.304245263338,-5.61298513412 -18.8899326324,0.304239094257,-5.58718919754 -18.9649238586,0.306225329638,-5.54557704926 -19.0119075775,0.306212753057,-5.49498271942 -19.0648937225,0.307199984789,-5.44638252258 -19.0998764038,0.308187991381,-5.39179515839 -19.1708679199,0.309174239635,-5.3471903801 -19.2148532867,0.310161948204,-5.29559326172 -19.2678508759,0.311154156923,-5.27778196335 -19.3048324585,0.312142133713,-5.22319316864 -19.3738212585,0.313128501177,-5.17758512497 -19.4158058167,0.31411626935,-5.12399339676 -19.4907951355,0.315102130175,-5.07838869095 -19.520778656,0.316090673208,-5.02180051804 -19.5767765045,0.317082613707,-5.00398492813 -19.6437644958,0.318068981171,-4.95637893677 -19.7027511597,0.320055752993,-4.9057803154 -19.7247314453,0.320044785738,-4.84619855881 -19.8027210236,0.321030378342,-4.79959249496 -19.8547077179,0.322017610073,-4.74699544907 -19.911693573,0.324004560709,-4.69539499283 -19.9486885071,0.323997527361,-4.67158985138 -20.0256767273,0.325983136892,-4.62398147583 -20.0586605072,0.325971513987,-4.56539869308 -20.1246471405,0.327957868576,-4.51479434967 -20.1666316986,0.328945726156,-4.45820426941 -20.2436199188,0.329931348562,-4.40959405899 -20.2946052551,0.330918669701,-4.35499715805 -20.3546028137,0.332910001278,-4.33517932892 -20.3885860443,0.332898408175,-4.27559661865 -20.4695739746,0.334883540869,-4.22598838806 -20.5165576935,0.335871130228,-4.1693944931 -20.5825443268,0.336857438087,-4.1167883873 -20.6295280457,0.337844997644,-4.05919790268 -20.6995162964,0.339830815792,-4.00559806824 -20.7435112,0.340823084116,-3.98079061508 -20.8134975433,0.34180906415,-3.92818069458 -20.8644828796,0.342796236277,-3.8695936203 -20.9414691925,0.344781547785,-3.81698393822 -20.9834537506,0.345769584179,-3.75739383698 -21.0744419098,0.347753793001,-3.70677614212 -21.0964355469,0.347747594118,-3.6759865284 -21.1754207611,0.34973269701,-3.62237668037 -21.2274055481,0.350719958544,-3.56378030777 -21.3083934784,0.352704763412,-3.50917291641 -21.3513755798,0.353692650795,-3.44758677483 -21.4373645782,0.355677098036,-3.39397144318 -21.4723472595,0.355665683746,-3.33039116859 -21.5593452454,0.357654184103,-3.31055855751 -21.5923271179,0.35864302516,-3.24697422981 -21.6773147583,0.360627293587,-3.19036817551 -21.730298996,0.361614465714,-3.12977099419 -21.8252849579,0.363597840071,-3.07415771484 -21.8412666321,0.363588213921,-3.00658631325 -21.9382553101,0.366571426392,-2.95096850395 -21.9772472382,0.367563903332,-2.92216157913 -22.0662345886,0.369547754526,-2.86454892159 -22.1022167206,0.369536399841,-2.79896736145 -16.4247684479,0.221055537462,-1.97745001316 -16.3447532654,0.218059718609,-1.91492414474 -16.3057422638,0.217060223222,-1.85738193989 -16.2507286072,0.216062456369,-1.7998342514 -16.2017211914,0.214065656066,-1.76807641983 -16.1957111359,0.214063361287,-1.71551477909 -16.2137050629,0.214058861136,-1.66693103313 -16.1976947784,0.214057669044,-1.61337423325 -16.2216892242,0.214052662253,-1.56479239464 -16.1976795197,0.213052466512,-1.51123440266 -16.227678299,0.214048236609,-1.48942840099 -16.2496700287,0.21404351294,-1.43985283375 -16.3356685638,0.21703235805,-1.39723646641 -16.3546600342,0.21702799201,-1.34765660763 -16.4476566315,0.219016045332,-1.30503571033 -16.5856571198,0.222999349236,-1.26539492607 -22.2239208221,0.369407892227,-1.69088196754 -22.2669143677,0.370400071144,-1.65908026695 -22.3148994446,0.371388554573,-1.59348773956 -22.2428779602,0.369389653206,-1.51696717739 -22.237859726,0.36938393116,-1.4474016428 -22.2248439789,0.369379132986,-1.37684345245 -22.2378253937,0.369371503592,-1.30727732182 -9.74634170532,0.0437278971076,-0.436071753502 -9.74934387207,0.0437290333211,-0.421279370785 -9.7413482666,0.0437328778207,-0.390703201294 -9.74735355377,0.0437353104353,-0.360132157803 -9.73535728455,0.0437396727502,-0.329556137323 -9.73436164856,0.0437429249287,-0.298983603716 -9.74036693573,0.0437453612685,-0.269398778677 -9.73637199402,0.0437490157783,-0.23882599175 -9.72637462616,0.0427517816424,-0.223046094179 -9.74437999725,0.0437529906631,-0.193461865187 -9.72538375854,0.0427584089339,-0.16288946569 -9.72238922119,0.0427621118724,-0.132318347692 -9.72939395905,0.0427646227181,-0.102733187377 -9.72439956665,0.0427686311305,-0.0721624940634 -9.71440219879,0.0427715666592,-0.0563851855695 -9.72140789032,0.0427741594613,-0.0267997961491 -9.71641349792,0.0427782833576,0.00376982125454 -9.72141933441,0.042781163007,0.0333552621305 -9.72542476654,0.0427843034267,0.0639269202948 -9.71142959595,0.0427896231413,0.0944929420948 -9.70443534851,0.0427940413356,0.124074220657 -9.71043777466,0.0427951216698,0.138868376613 -9.70444393158,0.0427996069193,0.169435694814 -9.70044994354,0.0418037697673,0.199017047882 -9.70845603943,0.042806610465,0.229590982199 -9.70046234131,0.0418113432825,0.259169906378 -9.69246768951,0.0418162569404,0.289734572172 -9.70447444916,0.042818672955,0.320311844349 -9.68947696686,0.0418225042522,0.335093289614 -9.69548416138,0.0418256036937,0.364680558443 -9.69648933411,0.0418295003474,0.395250737667 -9.68649578094,0.0418347381055,0.424826145172 -9.67150306702,0.0418406836689,0.454396545887 -9.69050884247,0.0418423116207,0.484981894493 -9.66951656342,0.041849154979,0.514545798302 -9.67551898956,0.0418503843248,0.529342710972 -9.67652606964,0.0418544784188,0.559912621975 -9.68353271484,0.041857779026,0.59048897028 -9.66153907776,0.0418648160994,0.619062542915 -9.670545578,0.0418679080904,0.649641275406 -9.66755390167,0.0418725460768,0.679220855236 -9.65455722809,0.0418764948845,0.693996965885 -9.6685628891,0.0418789386749,0.724582791328 -9.66557025909,0.041883662343,0.754162311554 -9.65957832336,0.0418889969587,0.784723818302 -9.66158485413,0.0418930724263,0.814309775829 -9.64759254456,0.0418995060027,0.843873679638 -9.64160060883,0.0419048257172,0.873448133469 -9.65260314941,0.0419055819511,0.889241814613 -9.65861034393,0.0419093109667,0.919820487499 -9.62161922455,0.0409188903868,0.946388661861 -9.72962284088,0.0439086705446,0.986005008221 -9.78462791443,0.0459055490792,1.02061331272 -9.78763580322,0.0459098406136,1.05218076706 -9.77663898468,0.0449136085808,1.06597077847 -9.7856464386,0.045917019248,1.09754908085 -9.77865409851,0.0459226258099,1.12712717056 -9.77966213226,0.045927323401,1.15869212151 -9.77666950226,0.0459323711693,1.18827736378 -9.76767730713,0.0459384024143,1.21785116196 -9.76068592072,0.0459443181753,1.24841487408 -9.7746887207,0.0459447130561,1.26521015167 -9.76369762421,0.0459511615336,1.29477977753 -9.75770568848,0.0459568426013,1.32435894012 -9.75871372223,0.04596157372,1.3549387455 -9.76072120667,0.0459663234651,1.38650739193 -9.75072956085,0.045972764492,1.41607785225 -9.754737854,0.0459770746529,1.4466650486 -9.74874210358,0.0459804944694,1.46144795418 -9.75675010681,0.0459843203425,1.49303138256 -9.74875831604,0.0459907129407,1.52359247208 -9.74476718903,0.0459963008761,1.55317616463 -9.74377536774,0.0460015647113,1.58375358582 -9.74178409576,0.0460070259869,1.61432886124 -9.73578929901,0.0460105538368,1.62911105156 -9.73679733276,0.0460157059133,1.66068029404 -9.73780536652,0.0460207089782,1.69126355648 -9.71781539917,0.0460289567709,1.71883392334 -9.7288236618,0.0460325703025,1.75141644478 -9.72583198547,0.0470383651555,1.7819904089 -9.71484184265,0.0460454635322,1.81155598164 -9.70784664154,0.0460491329432,1.82534813881 -9.7248544693,0.0470520406961,1.85992312431 -9.70386505127,0.046060718596,1.88748764992 -9.71987247467,0.047063652426,1.9210755825 -9.70688247681,0.0470711030066,1.94964873791 -9.70489215851,0.0470768883824,1.98022663593 -9.68590259552,0.047085378319,2.00779485703 -9.7139043808,0.0470837838948,2.0285961628 -9.68891620636,0.0470932871103,2.05515956879 -9.69592475891,0.0470977984369,2.08773875237 -9.68993377686,0.0471044667065,2.11830568314 -9.70194244385,0.0481082126498,2.15188932419 -9.68395328522,0.0471167229116,2.17945861816 -9.69496154785,0.0481206811965,2.2130408287 -9.67796707153,0.047126185149,2.22482562065 -9.68197727203,0.048131365329,2.25739955902 -9.67498779297,0.0481381975114,2.28697776794 -9.67799568176,0.0481436103582,2.31954932213 -9.67500686646,0.0481498725712,2.35012769699 -9.66901683807,0.0481567680836,2.38069629669 -9.6670217514,0.048159930855,2.39549088478 -9.67403030396,0.0481647662818,2.42906522751 -9.66704082489,0.0481717400253,2.45864462852 -9.65505218506,0.0481797754765,2.48820590973 -9.6580619812,0.0491852946579,2.52078175545 -9.6560716629,0.049191493541,2.55136632919 -9.6470823288,0.0491989962757,2.58093857765 -9.65308666229,0.0492011085153,2.59872436523 -9.65109729767,0.0492075458169,2.63029694557 -9.63310909271,0.0492166541517,2.65786194801 -9.64111804962,0.0492213778198,2.69144701958 -9.62513065338,0.0492301359773,2.71901917458 -9.6251411438,0.049236420542,2.75158786774 -9.63814926147,0.0502404645085,2.78716945648 -9.62115573883,0.0502462759614,2.79795885086 -9.62216663361,0.0502523779869,2.83053326607 -9.61917686462,0.0502591840923,2.86210513115 -9.61918735504,0.0502653457224,2.89368987083 -9.6062002182,0.0502738393843,2.92226052284 -9.59921169281,0.0502814091742,2.95283007622 -9.60521507263,0.0502835549414,2.97062206268 -9.58822822571,0.0502928346395,2.99818897247 -9.59423828125,0.0512982979417,3.03276252747 -9.57025146484,0.050308663398,3.05733752251 -9.5782623291,0.0513138882816,3.092908144 -9.5792722702,0.0513201393187,3.12548828125 -9.53328895569,0.0503343529999,3.14305496216 -9.50029850006,0.0493432320654,3.14883112907 -9.48331069946,0.0493528097868,3.17639398575 -9.44732666016,0.0483655072749,3.1969602108 -9.50734138489,0.0503685697913,3.28212809563 -9.50535297394,0.0513754598796,3.31370997429 -9.49336528778,0.0513841658831,3.34228420258 -9.50136947632,0.0513862632215,3.36206650734 -9.49138259888,0.0513947196305,3.39163780212 -9.48939323425,0.0514016635716,3.42322158813 -9.49540424347,0.0524074696004,3.45879387856 -9.4874162674,0.0524154938757,3.48837590218 -9.48242855072,0.052423208952,3.51994752884 -9.4864397049,0.052429318428,3.55452561378 -9.47944641113,0.0524340979755,3.5693025589 -9.48545646667,0.0534397177398,3.60389232635 -9.48646831512,0.0534463748336,3.63747119904 -9.47748184204,0.0534549430013,3.66803836823 -9.46749401093,0.0534635819495,3.69761323929 -9.48250389099,0.0544679388404,3.73719072342 -9.46051311493,0.0534753724933,3.74596691132 -9.47352218628,0.0544800274074,3.78454875946 -9.47353458405,0.0544869750738,3.81812763214 -9.46754741669,0.0544950626791,3.84970092773 -9.46455955505,0.0555025972426,3.88227844238 -9.46457099915,0.0555095672607,3.91585993767 -9.45258426666,0.0555188506842,3.94542813301 -9.45759010315,0.0555216483772,3.96520924568 -9.46260166168,0.0565277263522,4.00079536438 -9.44661617279,0.0565376952291,4.02836751938 -9.43862819672,0.0565461963415,4.0589466095 -9.44464015961,0.0565524287522,4.09651660919 -9.43965339661,0.0575605630875,4.12908887863 -9.44065856934,0.0575640052557,4.14687633514 -9.4406709671,0.0575712174177,4.181453228 -9.43568325043,0.0575793683529,4.21402788162 -9.43169689178,0.0585872642696,4.24660873413 -9.42970943451,0.0585950314999,4.28117704391 -9.42272281647,0.0586035512388,4.31275463104 -9.41473579407,0.0586123615503,4.34432697296 -9.41774177551,0.0586154647171,4.36311721802 -9.42075443268,0.0596222802997,4.39969396591 -9.41076850891,0.0596314556897,4.4302687645 -9.40778064728,0.059639532119,4.46483659744 -9.40379428864,0.0606474801898,4.49742364883 -9.40780544281,0.0606542229652,4.53499937057 -9.40481853485,0.0606623031199,4.56957054138 -9.40382575989,0.0616663098335,4.58735370636 -9.39684009552,0.0616751126945,4.61992645264 -9.40285110474,0.0616814754903,4.65850687027 -9.39686489105,0.0626902133226,4.69207572937 -9.39887714386,0.0626972839236,4.72865867615 -9.39189147949,0.0627061128616,4.76123476028 -9.39490413666,0.0637130886316,4.79881477356 -9.39491081238,0.063717007637,4.81759643555 -9.3929233551,0.0637250170112,4.8531703949 -9.38893699646,0.0647334009409,4.8877453804 -9.38095188141,0.0647425353527,4.92031955719 -9.37796497345,0.0647508352995,4.95589160919 -9.38097763062,0.0657577887177,4.99347877502 -9.37898349762,0.0657620877028,5.01126241684 -9.38299655914,0.0667689293623,5.04984664917 -9.36901187897,0.0667794495821,5.0804104805 -9.37102508545,0.066786877811,5.11898469925 -9.3720369339,0.0677943900228,5.1565656662 -9.37005138397,0.0678025782108,5.19314002991 -9.3590669632,0.0678124427795,5.22471427917 -9.36307239532,0.0688155516982,5.24550676346 -9.358086586,0.0688244402409,5.28107595444 -9.35710048676,0.0688325241208,5.31865024567 -9.35511398315,0.0698407068849,5.35523033142 -9.35312747955,0.0698488801718,5.39181137085 -9.35014152527,0.0708575472236,5.42937707901 -9.34915542603,0.0708656087518,5.46695613861 -9.3471622467,0.0708700940013,5.48573637009 -9.33817768097,0.0708795934916,5.51831960678 -9.34319019318,0.0718865990639,5.5598988533 -9.34320449829,0.0728947296739,5.5994682312 -9.32822036743,0.0729054808617,5.62904691696 -9.32623386383,0.072914019227,5.6676158905 -9.33323955536,0.0739167034626,5.69140672684 -9.33425331116,0.0739244893193,5.73098802567 -9.32726860046,0.0749339535832,5.76655912399 -9.32428264618,0.0749425664544,5.80413770676 -9.31229877472,0.0749530121684,5.83670902252 -9.3143119812,0.0759608522058,5.87828207016 -9.31132602692,0.0759696513414,5.91685390472 -9.3193321228,0.0769721269608,5.9416475296 -9.31434726715,0.076981343329,5.97921848297 -9.32535839081,0.0779872313142,6.02580690384 -9.29937744141,0.0780005529523,6.05037117004 -9.31338882446,0.0790060460567,6.09995365143 -9.29940509796,0.079016931355,6.13152933121 -9.3014125824,0.0790208652616,6.15430784225 -9.30142688751,0.0800290182233,6.19489049911 -9.30543994904,0.0810364484787,6.2384724617 -9.29645633698,0.0810464993119,6.27404546738 -9.29147148132,0.0810560435057,6.31360864639 -9.28548622131,0.082065500319,6.35118532181 -9.2874994278,0.0830733180046,6.39376974106 -9.28450775146,0.0830780416727,6.41255950928 -9.28952121735,0.0840856283903,6.45912837982 -9.27753829956,0.0840962454677,6.4927072525 -9.27755260468,0.0841046646237,6.53528404236 -9.27356719971,0.0851139947772,6.57585334778 -9.26358413696,0.0851243287325,6.61142969131 -9.26859760284,0.0861318036914,6.6580080986 -9.27360343933,0.0871349945664,6.68280172348 -9.2596206665,0.0871462598443,6.71637248993 -9.26563453674,0.0881537273526,6.76494407654 -9.25365161896,0.0881645008922,6.79952192307 -9.24866676331,0.0881740823388,6.84009408951 -9.24868106842,0.0891825333238,6.88367557526 -9.2416973114,0.0901925712824,6.92324590683 -9.24370479584,0.0901964902878,6.94703388214 -9.25071811676,0.091203853488,6.99760532379 -9.23473548889,0.0912153795362,7.02918863297 -9.21775436401,0.0912274494767,7.06175613403 -9.22876739502,0.0922339484096,7.11533498764 -9.12780284882,0.0902624726295,7.08288955688 -9.08382034302,0.0892755240202,7.07166576385 -9.14083766937,0.0922817960382,7.20682764053 -9.06587028503,0.0903054848313,7.19437932968 -9.02089500427,0.0893230587244,7.20394897461 -8.96492195129,0.0883430317044,7.20550727844 -8.95593833923,0.0893534719944,7.24308872223 -8.97394275665,0.0903544127941,7.28087615967 -8.95596218109,0.0903668478131,7.31244659424 -8.9549779892,0.0913759469986,7.3580198288 -8.955991745,0.0913845077157,7.40460109711 -8.92701435089,0.0913991257548,7.42717170715 -9.19896793365,0.101353824139,7.69881629944 -9.17898750305,0.101366661489,7.73038864136 -9.34495735168,0.107338003814,7.8932185173 -9.17601108551,0.10338062048,7.80075120926 -9.25001049042,0.106374785304,7.91234445572 -9.17205810547,0.105408169329,7.94448041916 -9.17807197571,0.106415890157,7.99905920029 -9.17408847809,0.107425689697,8.04563331604 -9.22208404541,0.1094205603,8.11243438721 -9.20310497284,0.109433293343,8.14600849152 -9.29109954834,0.113424882293,8.27559566498 -9.284116745,0.114435173571,8.32017612457 -9.25813770294,0.114449411631,8.34874534607 -9.26515102386,0.115456938744,8.40632820129 -9.29615211487,0.116455376148,8.46111679077 -9.28517055511,0.117466643453,8.5036907196 -9.27018928528,0.117478810251,8.54325962067 -9.26120758057,0.118489682674,8.58783531189 -9.27721881866,0.119495481253,8.65541934967 -9.26724433899,0.120511360466,8.72777271271 -9.25026512146,0.121523834765,8.76534938812 -9.24828052521,0.122533418238,8.81792545319 -9.26329231262,0.12353951484,8.8865070343 -9.21531963348,0.122558452189,8.896068573 -9.16734695435,0.122577294707,8.90463638306 -9.16136455536,0.122587770224,8.9542093277 -9.16437149048,0.123591810465,8.98499679565 -9.14740753174,0.125613614917,9.07915115356 -9.10643386841,0.124631173909,9.09471893311 -9.07445716858,0.124647125602,9.12027931213 -9.09846782684,0.126651585102,9.20086097717 -9.0674905777,0.126667156816,9.22643184662 -9.07649612427,0.127670034766,9.26422119141 -9.05651760101,0.127683356404,9.30079555511 -9.0595331192,0.12869207561,9.36137390137 -8.95457458496,0.125722706318,9.31092834473 -9.04556941986,0.130713716149,9.46352100372 -9.05159950256,0.132731303573,9.5876750946 -9.04960823059,0.133736297488,9.6144695282 -9.05362319946,0.134745016694,9.67904186249 -9.0506401062,0.135755181313,9.73661327362 -8.99567127228,0.134775832295,9.7381772995 -8.94369983673,0.133795753121,9.74174690247 -8.87973308563,0.132818341255,9.73330688477 -8.83375167847,0.131832420826,9.71308708191 -8.77878284454,0.130853191018,9.71364879608 -8.76280403137,0.130865782499,9.75523090363 -8.75782108307,0.131876394153,9.81080436707 -8.75183963776,0.132887333632,9.86637210846 -8.75485515594,0.134896233678,9.93095302582 -8.74587440491,0.135907769203,9.98352241516 -9.01181411743,0.146858274937,10.3163719177 -9.00483322144,0.147869288921,10.3729476929 -9.00384902954,0.148879215121,10.4375181198 -8.99386882782,0.149890825152,10.4910964966 -8.98988628387,0.150901183486,10.5516757965 -8.9789056778,0.15191309154,10.6052494049 -8.97892284393,0.152922868729,10.6728200912 -8.98293018341,0.153926968575,10.7116060257 -8.9769487381,0.154937744141,10.7711868286 -8.97796440125,0.156947284937,10.8407611847 -8.96798419952,0.157959058881,10.8973350525 -8.95400524139,0.157971709967,10.9499063492 -8.95302200317,0.159981578588,11.0174856186 -8.96402645111,0.160984262824,11.0662736893 -8.95404720306,0.161996126175,11.1248445511 -8.98505496979,0.164999470115,11.2334318161 -9.04505634308,0.168996974826,11.3800201416 -3.45053744316,-0.0638562589884,4.40275287628 -3.41456604004,-0.0648392140865,4.38433742523 -3.42258358002,-0.0638309046626,4.42192077637 -3.41959381104,-0.0638254061341,4.43171405792 -8.93717861176,0.172073185444,11.6476659775 -8.91120243073,0.173088282347,11.6882410049 -8.90022182465,0.174100369215,11.7488174438 -8.89823913574,0.175110697746,11.82239151 -8.89325809479,0.177121698856,11.8929634094 -8.90426445007,0.17812435329,11.9457559586 -8.90028190613,0.180135145783,12.018330574 -8.88830280304,0.181147605181,12.0809011459 -8.88132190704,0.182159021497,12.1504745483 -8.86734199524,0.183171764016,12.2100524902 -8.86436080933,0.18518230319,12.2856302261 -8.87336730957,0.186185479164,12.3384189606 -8.86838531494,0.187196552753,12.4129934311 -8.85440731049,0.189209356904,12.4745693207 -8.85342407227,0.190219655633,12.5561418533 -8.84544467926,0.192231282592,12.6277189255 -8.83746337891,0.193242996931,12.7002925873 -8.83248233795,0.195253998041,12.7768707275 -8.84248828888,0.196256965399,12.8336620331 -8.81851196289,0.1972720474,12.8852300644 -8.83152675629,0.199279502034,12.9908075333 -8.81354904175,0.200293272734,13.0513811111 -8.80256938934,0.202305659652,13.1229553223 -8.80558586121,0.204315006733,13.2145395279 -8.81959152222,0.205317348242,13.2813234329 -8.80361366272,0.207330733538,13.3468980789 -8.80163097382,0.208341285586,13.4344749451 -8.77965545654,0.209355920553,13.4920482635 -8.78067207336,0.211365997791,13.5866212845 -8.76869297028,0.213378533721,13.660200119 -8.76271247864,0.215389981866,13.7447748184 -8.77371788025,0.216392755508,13.8085680008 -8.76873683929,0.218404129148,13.8971385956 -8.74776077271,0.219418630004,13.9597120285 -8.74977779388,0.222428396344,14.0592918396 -8.73380088806,0.223441958427,14.1318645477 -8.73281955719,0.225452467799,14.2294378281 -8.71284198761,0.22646689415,14.2970094681 -8.73884391785,0.229466602206,14.3888063431 -8.71886825562,0.230481013656,14.4573783875 -8.71388721466,0.232492506504,14.5529470444 -8.70590686798,0.234504342079,14.6415281296 -8.69692802429,0.236516445875,14.7301054001 -8.67295265198,0.23753169179,14.7946767807 -8.68296813965,0.24054004252,14.9182548523 -8.68097686768,0.241545602679,14.968044281 -8.68399429321,0.244555398822,15.081618309 -8.66401863098,0.245569974184,15.1571874619 -8.66603565216,0.248579964042,15.2707643509 -8.6390619278,0.249595761299,15.3333406448 -8.64307880402,0.2516053617,15.452917099 -8.64508724213,0.253610223532,15.5137033463 -8.64910411835,0.256619751453,15.6342840195 -8.62912845612,0.257634311914,15.7138566971 -8.6261472702,0.26064530015,15.8244352341 -8.60317230225,0.261660456657,15.9000091553 -8.60918807983,0.264669746161,16.0305843353 -8.57721614838,0.26568672061,16.0911560059 -8.61021614075,0.269685357809,16.2149467468 -8.59223842621,0.270699501038,16.3035202026 -8.59125804901,0.273710310459,16.4260940552 -8.56928157806,0.275725156069,16.5076751709 -8.57030105591,0.27873557806,16.6372470856 -8.55332374573,0.280749619007,16.7328205109 -8.56632900238,0.282752245665,16.8226108551 -8.55934906006,0.28576412797,16.9381904602 -8.55137062073,0.287776440382,17.0557613373 -8.53439426422,0.290790468454,17.1553344727 -8.52541542053,0.292802870274,17.2719097137 -8.51243686676,0.295816123486,17.382484436 -8.5014591217,0.297828823328,17.4960651398 -8.53345870972,0.301827818155,17.633852005 -10.8587989807,0.44436737895,22.616733551 -10.7798404694,0.44439420104,22.6332969666 -10.6718902588,0.441426843405,22.5878582001 -10.6359176636,0.444444924593,22.6944293976 -10.5869503021,0.445465654135,22.7749977112 -10.4999933243,0.44449415803,22.774559021 -10.3930339813,0.439521104097,22.6343364716 -10.4720287323,0.449516147375,22.9979171753 -10.2601099014,0.440569847822,22.7204647064 -10.142162323,0.43760445714,22.646030426 -10.4410924911,0.461554974318,23.510641098 -10.3441400528,0.45958545804,23.4902038574 -10.2321910858,0.457619041204,23.435760498 -10.2182044983,0.458627313375,23.5035476685 -10.1342477798,0.458655148745,23.5111122131 -10.0133018494,0.455690443516,23.4316749573 -9.94534111023,0.455715090036,23.4762401581 -9.87238121033,0.455740749836,23.5088062286 -9.76143264771,0.452773958445,23.4483718872 -9.3035774231,0.424871534109,22.4471054077 -9.64149570465,0.45281457901,23.4717178345 -9.54254436493,0.450845390558,23.4382820129 -9.44259262085,0.448876470327,23.4028453827 -9.38562774658,0.449898838997,23.4724159241 -9.28967571259,0.448929011822,23.443983078 -9.17172908783,0.445963650942,23.359544754 -9.16174125671,0.446971148252,23.4423313141 -9.05579280853,0.445003390312,23.3868961334 -8.89086055756,0.438047379255,23.1754550934 -8.85389137268,0.441065698862,23.2960281372 -8.74694156647,0.439098089933,23.2335929871 -8.39206790924,0.417180031538,22.5041313171 -8.29711532593,0.416209965944,22.4636993408 -8.24813938141,0.415225148201,22.4374847412 -8.15518665314,0.413254678249,22.401052475 -8.08522701263,0.413279622793,22.4276218414 -8.01026916504,0.413305521011,22.4391918182 -7.91931533813,0.411334604025,22.4057598114 -7.84535694122,0.411360234022,22.4183311462 -7.80337953568,0.410374104977,22.412115097 -7.73242044449,0.41039916873,22.4336853027 -7.64846515656,0.409426867962,22.4182529449 -7.59250211716,0.41044896841,22.4848251343 -7.67449617386,0.423443585634,22.9634113312 -7.64852380753,0.426459699869,23.1259880066 -7.60655593872,0.429479002953,23.2425613403 -7.58757162094,0.430488318205,23.3093452454 -7.50361680984,0.430515885353,23.2979183197 -4.16364622116,0.150187119842,13.0522613525 -4.10468482971,0.148209363222,13.0078372955 -4.07471418381,0.149225667119,13.0524225235 -7.19079065323,0.428621798754,23.3241996765 -7.11883211136,0.428646981716,23.3497714996 -7.06985664368,0.427662104368,23.3185577393 -6.99390029907,0.427688151598,23.3331279755 -6.90594625473,0.425716400146,23.3027019501 -6.8339881897,0.425741553307,23.3272743225 -6.74703454971,0.424769639969,23.3008460999 -6.67207765579,0.42479544878,23.3174152374 -6.62510204315,0.423810124397,23.2892036438 -6.54914474487,0.422835975885,23.2977771759 -6.46219158173,0.421864062548,23.2693462372 -6.39123344421,0.421888887882,23.294921875 -6.30328083038,0.420917242765,23.2624893188 -6.22632408142,0.419943213463,23.2660655975 -6.13837146759,0.418971389532,23.2276382446 -6.0833978653,0.416987657547,23.1674213409 -5.99344587326,0.415016144514,23.1179962158 -5.89449596405,0.412046462297,23.0335674286 -5.77055454254,0.407081484795,22.8441429138 -5.6006269455,0.396125584841,22.4677085876 -5.50667619705,0.394154757261,22.3882846832 -5.56367921829,0.408154636621,22.9328613281 -5.59667873383,0.415153592825,23.2256565094 -5.51772356033,0.415179938078,23.2192287445 -5.43876838684,0.414206176996,23.2088031769 -5.36281251907,0.4142318964,23.2133769989 -5.28485679626,0.413257837296,23.2049541473 -5.20590162277,0.412284046412,23.193529129 -5.12794589996,0.412310093641,23.1881027222 -5.09296703339,0.412322223186,23.1998920441 -5.0709939003,0.418337374926,23.4514713287 -5.04702234268,0.424352884293,23.700050354 -5.02604913712,0.431367844343,23.9716262817 -3.23162150383,0.20972391963,15.6221628189 -3.16766238213,0.207746982574,15.5617351532 -3.13768196106,0.206757903099,15.5355300903 -3.08571887016,0.205778494477,15.5291090012 -3.03475522995,0.205798909068,15.5276870728 -2.99078965187,0.206817790866,15.5582723618 -2.95482158661,0.208835303783,15.6368503571 -2.90385818481,0.207855656743,15.6354293823 -2.85489439964,0.207875564694,15.6440095901 -2.83691048622,0.208884388208,15.6877946854 -4.82431793213,0.514515697956,27.2464103699 -4.79834651947,0.523531556129,27.6049900055 -4.7683763504,0.532548248768,27.9545650482 -4.74040603638,0.542564511299,28.3241462708 -4.71043586731,0.551581084728,28.6997241974 -4.72044324875,0.560584723949,29.0505104065 -4.68847417831,0.570601761341,29.4360923767 -4.65450572968,0.580619156361,29.829668045 -4.62153625488,0.590636312962,30.2382488251 -4.58356904984,0.601654469967,30.6378250122 -4.55459928513,0.613670945168,31.1154022217 -4.55861854553,0.632681071758,31.8409824371 -4.57462406158,0.644683539867,32.3157730103 -4.5386557579,0.656701266766,32.8043518066 -4.49968862534,0.669719576836,33.2959289551 -4.45772314072,0.681738436222,33.7835044861 -4.41975545883,0.695756494999,34.326084137 -4.34879827499,0.703780829906,34.6386642456 -4.26884412766,0.709806799889,34.8862419128 -4.33783340454,0.736799180508,35.9190330505 -4.28986930847,0.751819252968,36.4916114807 -4.2399058342,0.766839563847,37.0711898804 -2.650421381,0.417147785425,23.7557601929 -2.56746840477,0.415173977613,23.6913394928 -2.49151325226,0.415198743343,23.6829204559 -2.42055630684,0.416222572327,23.7245006561 -2.38957667351,0.417233586311,23.7872924805 -4.03008699417,0.883938789368,41.607875824 -3.92114210129,0.889970004559,41.8574523926 -3.86118149757,0.910992085934,42.6570320129 -3.75323653221,0.919023036957,42.9716072083 -3.77125191689,0.967030584812,44.8141860962 -3.73127508163,0.977043449879,45.1919746399 -3.66131806374,1.00006735325,46.1125564575 -3.58636236191,1.024091959,47.0401344299 -3.53240036964,1.05811285973,48.3467140198 -3.42745447159,1.07614314556,49.0392875671 -3.34250235558,1.10316956043,50.0908699036 -3.25255155563,1.13119697571,51.1664505005 -3.23956608772,1.16020476818,52.2642402649 -3.13761925697,1.18723428249,53.3358192444 -2.9786901474,1.19127440453,53.5003967285 -1.72614514828,0.764535427094,37.1601524353 -1.66017651558,0.760552763939,37.0009422302 -1.5472329855,0.762583851814,37.0775260925 -1.43129062653,0.762615442276,37.1031074524 -1.41831612587,0.840628266335,40.070690155 -1.29137718678,0.839661717415,40.0502700806 -1.16543781757,0.839694976807,40.0518493652 -1.03849899769,0.838728368282,40.0184326172 -0.975529193878,0.838744938374,39.9962272644 -0.849589943886,0.837778091431,39.9928131104 -0.598710954189,0.837843894958,39.9799804688 -0.472771793604,0.837876856327,39.9975585938 -0.347832083702,0.837909460068,40.0001487732 -0.221892923117,0.838942289352,40.0207328796 -0.158923313022,0.83895868063,40.0355224609 --0.257884800434,1.41906249523,50.7173271179 --0.4188131392,1.42510128021,50.8959121704 --0.58374029398,1.44014072418,51.359500885 --0.756664931774,1.46618139744,52.1880874634 --0.860621869564,1.51220488548,53.6178817749 --1.20747065544,1.52628624439,54.0520591736 --1.37139821053,1.52032506466,53.8506469727 --1.53432583809,1.51236367226,53.5952339172 --1.69925308228,1.5094025135,53.4898223877 --1.78221654892,1.5084220171,53.4746170044 --1.95014262199,1.50846135616,53.4532051086 --2.11706924438,1.50750029087,53.435798645 --2.27999687195,1.50353860855,53.2983856201 --3.32553243637,1.48278236389,52.5777206421 --1.8059630394,0.623537242413,25.7748126984 --1.87192118168,0.616558253765,25.555398941 --1.89488220215,0.576576590538,24.285774231 --1.96783816814,0.57459872961,24.2373638153 --2.04079437256,0.573620796204,24.190952301 --2.11375021935,0.572642922401,24.1425380707 --2.19470381737,0.573666274548,24.1911277771 --2.26865959167,0.573688387871,24.1637210846 --2.30863666534,0.574699878693,24.1835155487 --2.38259291649,0.573721885681,24.1601104736 --2.46054697037,0.573744654655,24.1636943817 --2.57149171829,0.585772812366,24.4992923737 --6.1083483696,1.57439291477,55.1686477661 --6.22230243683,1.58241653442,55.4084472656 --7.98257875443,1.64878153801,57.2570533752 --8.10352039337,1.63480949402,56.8136482239 --8.26744842529,1.63184440136,56.6882514954 --8.24743556976,1.58884859085,55.3308410645 --8.38137340546,1.57987844944,55.0434417725 --8.45633888245,1.57789468765,54.9532432556 --8.62826538086,1.57793068886,54.9238471985 --8.803191185,1.57796704769,54.9064445496 --8.97811603546,1.57900333405,54.8930511475 --9.15504169464,1.58003973961,54.8946533203 --9.32796669006,1.5800755024,54.8662567139 --9.50389289856,1.58011162281,54.8568611145 --9.59485435486,1.58113014698,54.8686599731 --7.87936592102,1.23585546017,44.2101593018 --7.91933298111,1.2178696394,43.6337547302 --7.21952962875,1.06976270676,39.0643043518 --7.3814291954,1.04480838776,38.2522926331 --7.49937152863,1.04483520985,38.2148933411 --7.80823612213,1.05590033531,38.5110969543 --7.89718866348,1.05092227459,38.3266983032 --8.04612255096,1.05495369434,38.4383010864 --8.17806148529,1.05698227882,38.4669036865 --6.59349966049,0.775747358799,29.8247623444 --6.60747480392,0.763757526875,29.4463558197 --6.65643930435,0.75777310133,29.2319488525 --6.80435371399,0.752812087536,29.0391483307 --6.853328228,0.753823757172,29.0399436951 --6.94428062439,0.75384581089,29.0175457001 --7.03323316574,0.752867519855,28.9871444702 --7.12818384171,0.753890156746,28.9777431488 --7.22013568878,0.753912091255,28.9613456726 --7.31208753586,0.753934085369,28.9419460297 --7.36006259918,0.753945350647,28.9397449493 --7.45501375198,0.754967749119,28.931344986 --7.54796504974,0.754989743233,28.9129428864 --7.64391565323,0.756012022495,28.9085445404 --7.80284738541,0.764044106007,29.1391506195 --7.37695789337,0.700985491276,27.1977043152 --7.40193033218,0.692996740341,26.9533004761 --7.39992046356,0.688000202179,26.778093338 --7.4558839798,0.685016274452,26.6536903381 --7.53484010696,0.684035718441,26.6132926941 --7.1759095192,0.622995615005,24.7414398193 --7.46273326874,0.616072595119,24.4296340942 --8.14935874939,0.620236158371,24.3272438049 --8.32327747345,0.626272380352,24.4626522064 --9.21188545227,0.663446009159,25.3661174774 --8.92793178558,0.622417986393,24.1042728424 --9.05187606812,0.626442492008,24.202878952 --13.6054935455,1.03510332108,36.0900115967 --13.6014766693,1.02410757542,35.738609314 --13.5864639282,1.01311004162,35.3632049561 --13.5084781647,1.00110137463,34.9919967651 --13.4974632263,0.990104496479,34.6385955811 --13.4784507751,0.979106605053,34.2691917419 --13.4664363861,0.968109548092,33.9237861633 --13.4404268265,0.957110643387,33.5483818054 --13.4234142303,0.946112990379,33.2009773254 --13.3554258347,0.936105787754,32.883769989 --13.347410202,0.927109360695,32.5693664551 --13.3363962173,0.917112469673,32.2509651184 --13.3213825226,0.90811508894,31.9285621643 --13.295372963,0.897116184235,31.5851573944 --13.2893562317,0.888120055199,31.2927532196 --13.2703456879,0.879122018814,30.9763507843 --13.2163524628,0.871116876602,30.7161426544 --13.2143354416,0.863121330738,30.4447402954 --13.1963233948,0.853123545647,30.1423358917 --13.1963062286,0.846128165722,29.884935379 --13.1992874146,0.83913320303,29.6385345459 --13.2072677612,0.832138836384,29.4061336517 --13.2072496414,0.825143456459,29.1587314606 --13.1592559814,0.818139255047,28.9295215607 --13.143242836,0.809141635895,28.6551208496 --13.1332292557,0.802144885063,28.3957195282 --13.1232147217,0.794148087502,28.1393146515 --13.1092014313,0.786150753498,27.8789100647 --13.0971870422,0.779153764248,27.6255054474 --13.0521917343,0.772149980068,27.4193019867 --13.0391778946,0.765152812004,27.1698970795 --13.0281648636,0.758155822754,26.9284954071 --13.0191497803,0.751159191132,26.6950931549 --13.0061359406,0.744161963463,26.4536857605 --13.001121521,0.738165795803,26.2352867126 --9.10623455048,0.451662123203,18.1962890625 --9.08023262024,0.447661846876,18.0710792542 --9.11820316315,0.445672899485,18.0046787262 --9.16816997528,0.44568541646,17.9632835388 --9.22413539886,0.445698708296,17.9318847656 --9.27010440826,0.444710642099,17.8824882507 --9.34106636047,0.445725679398,17.8820972443 --9.41802597046,0.447741478682,17.8906993866 --9.46300411224,0.448750197887,17.9075031281 --9.56395626068,0.45176884532,17.9621162415 --12.8330001831,0.670188426971,23.9572410583 --12.8369817734,0.666193306446,23.7828388214 --12.87895298,0.663202941418,23.6824455261 --12.9629125595,0.6642177701,23.6590576172 --12.9848966599,0.663222670555,23.6098594666 --13.1008472443,0.66624134779,23.6434745789 --13.1998023987,0.667257845402,23.6460895538 --13.2977590561,0.669274032116,23.6477069855 --13.388715744,0.670289337635,23.6333179474 --13.4666776657,0.670302927494,23.5979309082 --13.5686321259,0.672319352627,23.6035480499 --13.6276073456,0.673328518867,23.6193561554 --13.7265634537,0.675344347954,23.6199741364 --13.8115224838,0.67635846138,23.5935840607 --13.9234743118,0.678375720978,23.6152076721 --14.0084342957,0.679389595985,23.5878181458 --14.1123895645,0.68140566349,23.5934352875 --14.1993484497,0.681419610977,23.5690479279 --14.236330986,0.681425750256,23.5458526611 --14.3342866898,0.683440864086,23.5404720306 --14.4482393265,0.685457706451,23.5610942841 --12.6467294693,0.571248710155,20.4633731842 --12.5777320862,0.563244700432,20.2069568634 --12.6277017593,0.562254726887,20.145565033 --12.5577125549,0.556248545647,19.9623508453 --12.6606683731,0.558264672756,19.9869689941 --12.7446279526,0.559278488159,19.9785804749 --12.7866001129,0.558287322521,19.9061870575 --12.8525657654,0.558298826218,19.870798111 --13.0884838104,0.568329751492,20.0964374542 --12.9275140762,0.555315196514,19.7110061646 --12.886516571,0.551312446594,19.5807991028 --12.9274892807,0.550320982933,19.50740242 --12.9354715347,0.547325670719,19.3870048523 --13.2763614655,0.563367724419,19.764667511 --13.1803722382,0.554360628128,19.486246109 --12.8934354782,0.5343323946,18.9297885895 --13.2153310776,0.549371778965,19.2734489441 --13.3232936859,0.55338549614,19.3662700653 --13.3832616806,0.553395628929,19.3228816986 --13.9990777969,0.584466516972,20.0816020966 --14.2030076981,0.592491924763,20.2392425537 --13.5711641312,0.55342644453,19.20271492 --14.4309148788,0.598522663116,20.2904853821 --14.2509565353,0.5865046978,19.9692516327 --13.2592105865,0.528401196003,18.4466495514 --13.3201789856,0.528411149979,18.4082603455 --14.7197847366,0.60156339407,20.2201423645 --14.8777265549,0.606582820415,20.3027744293 --13.3851146698,0.522428154945,18.1320667267 --12.6053094864,0.477349758148,16.9555053711 --12.5213251114,0.471342802048,16.7862873077 --12.4683237076,0.466340959072,16.60587883 --12.3443412781,0.456331878901,16.3304481506 --12.3623209,0.454337477684,16.247051239 --12.3832998276,0.453343361616,16.1676521301 --8.92920398712,0.267995238304,11.5464887619 --8.95817947388,0.268003642559,11.5080890656 --8.97416591644,0.268007993698,11.4908895493 --8.99614334106,0.267015576363,11.4444913864 --9.08310413361,0.26902961731,11.4811086655 --12.6911334991,0.45439428091,15.9855041504 --12.5911445618,0.446387827396,15.7550792694 --12.542142868,0.441386461258,15.591668129 --12.7330846786,0.450407028198,15.7795095444 --12.9020252228,0.456426948309,15.8871450424 --12.796037674,0.448419928551,15.6527166367 --13.0539560318,0.459448218346,15.8683757782 --12.9959554672,0.453445792198,15.6949596405 --13.1079120636,0.456459701061,15.7295837402 --13.1368894577,0.455465555191,15.663189888 --13.2178611755,0.458474785089,15.7100076675 --13.317820549,0.461487263441,15.7276287079 --14.0256223679,0.4935567379,16.4633846283 --13.5137414932,0.465511411428,15.7568712234 --13.2947835922,0.452493876219,15.3994169235 --13.4497289658,0.45751106739,15.4810523987 --20.1669864655,0.784131526947,23.1291847229 --13.6756486893,0.465535968542,15.5925035477 --13.7446174622,0.466544896364,15.5711174011 --13.8135852814,0.467553704977,15.5497312546 --15.8460521698,0.562739193439,17.7438087463 --15.8770313263,0.561743378639,17.6654167175 --15.8000383377,0.55573785305,17.4680023193 --15.6420717239,0.546724557877,17.2357616425 --15.7560310364,0.549736022949,17.2533950806 --15.9829597473,0.55775731802,17.3920478821 --16.0269355774,0.557762384415,17.3296604156 --12.0349292755,0.366418510675,12.8972949982 --12.0579090118,0.365423828363,12.8398971558 --12.0398988724,0.362425625324,12.7384881973 --12.0348930359,0.361426860094,12.6932897568 --12.065870285,0.360432773829,12.6448917389 --12.1368379593,0.362441986799,12.6395101547 --12.1738147736,0.362448275089,12.5981178284 --12.1837978363,0.36045229435,12.5277147293 --12.1677865982,0.358454138041,12.4313058853 --12.1757707596,0.356457859278,12.361913681 --12.1567678452,0.355457961559,12.3016996384 --12.1407575607,0.35245975852,12.2082986832 --12.1387443542,0.350462734699,12.1278915405 --12.1447277069,0.34946629405,12.0564889908 --12.138715744,0.347468912601,11.9740867615 --12.1297025681,0.34547123313,11.8896856308 --12.1346874237,0.343474686146,11.81828022 --12.1116867065,0.341474384069,11.7590789795 --12.1116724014,0.340477436781,11.683672905 --12.114657402,0.338480651379,11.6122713089 --12.1046457291,0.3364828825,11.5288677216 --12.1056318283,0.335485965014,11.4554595947 --12.111615181,0.333489388227,11.3880577087 --12.0756168365,0.331488162279,11.3178491592 --12.0766029358,0.329491138458,11.2474517822 --12.0785884857,0.328494220972,11.1770458221 --12.0785751343,0.326497137547,11.1056442261 --12.0725631714,0.325499564409,11.0292406082 --12.0725488663,0.323502421379,10.9588375092 --12.065536499,0.321504771709,10.882434845 --12.047533989,0.320504933596,10.8312282562 --12.0575180054,0.319508492947,10.7708282471 --12.0505056381,0.317510813475,10.6954231262 --12.0454931259,0.315513253212,10.6230230331 --12.0474786758,0.31451612711,10.5566205978 --12.0424661636,0.312518596649,10.4832105637 --12.0394535065,0.311521142721,10.41381073 --12.0214509964,0.30952128768,10.36460495 --12.0174379349,0.308523774147,10.2941999435 --12.0144252777,0.306526303291,10.2247943878 --12.0234098434,0.305529534817,10.1673994064 --12.0083999634,0.303531259298,10.0889930725 --12.0073862076,0.302533835173,10.0225877762 --12.0113725662,0.301536738873,9.96118736267 --11.9873714447,0.299536556005,9.90797519684 --11.9853582382,0.298539012671,9.84257507324 --11.9933423996,0.297542124987,9.78517436981 --11.984331131,0.295544177294,9.7137670517 --11.9853181839,0.294546812773,9.65136623383 --11.9833049774,0.292549222708,9.58696365356 --11.9553050995,0.29154881835,9.53275299072 --11.9572906494,0.289551466703,9.47235298157 --11.9622764587,0.288554280996,9.41394996643 --11.948266983,0.287555962801,9.34154605865 --11.9562520981,0.286558896303,9.28614425659 --11.9542398453,0.284561216831,9.22374248505 --11.9552259445,0.283563733101,9.16333770752 --11.9282255173,0.282563447952,9.11212921143 --11.9352111816,0.281566232443,9.05773162842 --11.9291992188,0.279568314552,8.9923210144 --11.9341850281,0.278571009636,8.93591690063 --11.9831619263,0.279575884342,8.91453552246 --12.0301380157,0.280580669641,8.89014530182 --5.56451225281,0.0212539546192,4.00362062454 --5.54250860214,0.019256092608,3.97340655327 --5.56848573685,0.020263845101,3.96500277519 --11.8991098404,0.27058416605,8.53029727936 --11.9020967484,0.269586592913,8.47489547729 --11.9020843506,0.268588781357,8.41749095917 --11.8980712891,0.266590863466,8.35708427429 --11.8860683441,0.266591370106,8.32088375092 --11.887055397,0.264593601227,8.2644777298 --11.8790435791,0.263595402241,8.20206928253 --11.8800315857,0.262597590685,8.14767360687 --11.8830194473,0.261599808931,8.09427452087 --11.8780078888,0.260601729155,8.03486728668 --11.8699960709,0.259603470564,7.97446393967 --11.8569936752,0.258603960276,7.93725299835 --11.8549814224,0.257605940104,7.88185501099 --11.8609676361,0.256608247757,7.83044815063 --11.858956337,0.25561016798,7.77504730225 --11.8549451828,0.254611998796,7.7186460495 --11.8479337692,0.253613710403,7.66024255753 --11.8399295807,0.252614378929,7.62803792953 --11.8379173279,0.251616299152,7.57262992859 --11.832906723,0.250618040562,7.51622724533 --11.8308944702,0.249619916081,7.46182346344 --11.8288831711,0.248621761799,7.40741729736 --11.8338699341,0.247623816133,7.35801696777 --11.8238601685,0.246625319123,7.2996134758 --11.81985569,0.245626077056,7.27141427994 --11.8178434372,0.244627863169,7.21801042557 --11.8218307495,0.24462980032,7.16860866547 --11.8128204346,0.242631316185,7.11120176315 --11.8118085861,0.241633087397,7.05879592896 --11.8067979813,0.240634694695,7.00439071655 --11.8097858429,0.240636497736,6.95599508286 --11.7867841721,0.238636657596,6.91678619385 --11.788772583,0.238638475537,6.86637687683 --11.7927598953,0.237640246749,6.81898117065 --11.7937488556,0.236641943455,6.7695813179 --11.7897367477,0.23564350605,6.71616983414 --11.788725853,0.23464512825,6.66576766968 --11.7877140045,0.234646707773,6.61536359787 --11.7777099609,0.233647242188,6.58516120911 --11.7667016983,0.232648536563,6.52975749969 --11.7656898499,0.231650099158,6.47934913635 --11.7736768723,0.230651825666,6.43495082855 --11.7696666718,0.230653241277,6.38455247879 --11.8236455917,0.231655925512,6.36516427994 --11.856628418,0.23165807128,6.33376789093 --11.843624115,0.230658501387,6.30256414413 --11.8426141739,0.230659842491,6.25416755676 --11.8855953217,0.230662032962,6.22877931595 --11.9535722733,0.232664614916,6.21639871597 --12.0365457535,0.23466733098,6.21202754974 --12.1095228195,0.236669719219,6.20165109634 --12.1894979477,0.239672109485,6.19427490234 --12.3044719696,0.242674440145,6.22911119461 --12.3224582672,0.242675587535,6.18972158432 --12.3224487305,0.242676451802,6.14031887054 --12.5314025879,0.248680174351,6.19698905945 --17.6615104675,0.432748019695,8.73341083527 --17.6904983521,0.432745218277,8.67902946472 --17.7314891815,0.433744072914,8.66384124756 --17.7824726105,0.433741360903,8.61946487427 --17.8204612732,0.434738367796,8.56807899475 --12.293387413,0.236681178212,5.80969715118 --12.2903776169,0.235681846738,5.76029491425 --12.2913665771,0.235682547092,5.71188497543 --12.2963562012,0.234683230519,5.66749286652 --12.3203468323,0.235683709383,5.65429496765 --18.1183853149,0.439720928669,8.32700634003 --18.1653747559,0.440717369318,8.27962970734 --14.8259115219,0.321697235107,6.66902065277 --14.7549152374,0.318695545197,6.57858657837 --14.6829185486,0.315693944693,6.49016523361 --14.6149225235,0.312692403793,6.40374088287 --14.5299320221,0.308691561222,6.33750724792 --14.4589357376,0.305690169334,6.25108242035 --14.3969373703,0.302688866854,6.16865682602 --14.3199424744,0.29968765378,6.08022451401 --14.255944252,0.296686530113,5.99980926514 --14.1779489517,0.292685478926,5.91237688065 --14.1149511337,0.290684461594,5.83194875717 --14.0649547577,0.288684040308,5.78473234177 --11.7323007584,0.206691995263,4.75143623352 --11.7422895432,0.206692650914,4.712038517 --11.7422800064,0.20569331944,4.66863822937 --11.6522827148,0.202694535255,4.58819913864 --11.6592721939,0.201695159078,4.5477976799 --11.6462650299,0.20069591701,4.49938821793 --11.6442604065,0.200696259737,4.477186203 --11.6142539978,0.198697164655,4.42277431488 --11.6392421722,0.19969753921,4.39038467407 --11.6412315369,0.198698103428,4.34797668457 --11.6322231293,0.198698744178,4.30257511139 --11.6392126083,0.197699204087,4.2631778717 --11.6332082748,0.197699546814,4.238966465 --11.6351995468,0.197700023651,4.1975646019 --11.6211910248,0.196700692177,4.15015506744 --11.6271810532,0.195701047778,4.1107583046 --11.6311712265,0.195701405406,4.07035684586 --11.6211633682,0.194701969624,4.02495002747 --11.6171550751,0.194702416658,3.98255181313 --11.616150856,0.193702608347,3.96134972572 --11.6081428528,0.193703100085,3.91694259644 --11.6121320724,0.192703351378,3.87653756142 --11.6041250229,0.192703813314,3.83212828636 --11.6031150818,0.19170409441,3.79072642326 --11.600107193,0.191704407334,3.74932932854 --11.605096817,0.190704524517,3.70992779732 --11.5920944214,0.19070494175,3.68471717834 --11.5680885315,0.189705714583,3.63630819321 --11.4690923691,0.185708388686,3.56286072731 --11.4730825424,0.185708522797,3.52446508408 --11.4640750885,0.184708967805,3.48105478287 --11.4660654068,0.184709101915,3.44165325165 --11.4470586777,0.183709830046,3.39523792267 --11.4600534439,0.183709532022,3.38004875183 --11.4590444565,0.182709679008,3.33964323997 --11.4470376968,0.182710155845,3.29623556137 --11.4470281601,0.181710228324,3.25582528114 --11.4630184174,0.182709768414,3.22143316269 --11.4370126724,0.18071064353,3.17401766777 --11.4360046387,0.180710688233,3.13461732864 --11.4399995804,0.180710539222,3.11642098427 --11.424993515,0.179711043835,3.07200336456 --11.4249849319,0.17971098423,3.033608675 --11.4389753342,0.179710388184,2.99820995331 --11.4319677353,0.178710535169,2.95680046082 --11.4239597321,0.178710713983,2.91539168358 --11.4119529724,0.17771102488,2.87399148941 --11.4059495926,0.177711188793,2.85278534889 --11.414940834,0.177710622549,2.81638622284 --11.4029331207,0.176710903645,2.77397274971 --11.4079256058,0.176710441709,2.73758196831 --11.4349136353,0.176708981395,2.70518374443 --11.4049091339,0.175710007548,2.65876483917 --11.3599052429,0.17371173203,2.60934400558 --11.3888988495,0.17471024394,2.5971531868 --11.4328861237,0.175707802176,2.56977248192 --11.4568767548,0.176706209779,2.53738331795 --11.4868659973,0.176704257727,2.50599336624 --11.5238552094,0.177701875567,2.47560143471 --11.5458450317,0.178700149059,2.44220948219 --11.5908336639,0.179697170854,2.41382670403 --11.4778404236,0.175702735782,2.36957979202 --11.6638097763,0.181691378355,2.33385968208 --11.7127981186,0.182687819004,2.30547785759 --11.7437887192,0.183685138822,2.2730884552 --11.7727794647,0.184682458639,2.23969364166 --11.8117723465,0.185679718852,2.2285130024 --11.8337640762,0.185677319765,2.19412255287 --11.8647546768,0.186674311757,2.16072893143 --11.906744957,0.187670573592,2.13035106659 --11.9277362823,0.188667982817,2.09495592117 --11.9707269669,0.18966396153,2.06357002258 --12.0067186356,0.190660282969,2.03118681908 --12.0357122421,0.191657692194,2.01700043678 --12.0657043457,0.191654205322,1.98260867596 --12.1066951752,0.192649930716,1.9502235651 --12.1406869888,0.193646013737,1.91683995724 --12.1806783676,0.19464160502,1.88446056843 --12.2146711349,0.195637464523,1.85007083416 --12.2366638184,0.196634054184,1.81367695332 --12.2756586075,0.197630405426,1.80049777031 --12.3146495819,0.198625609279,1.76610720158 --12.3446426392,0.199621409178,1.73071873188 --12.3846359253,0.200616404414,1.6973413229 --12.4256277084,0.201611176133,1.6629550457 --12.4586210251,0.20260643959,1.6275690794 --12.5896081924,0.206594198942,1.60622942448 --12.6196041107,0.207590669394,1.59004163742 --12.6565971375,0.2085852772,1.55466032028 --12.6905908585,0.209579989314,1.5182737112 --12.7345838547,0.210573807359,1.48289048672 --12.767578125,0.211568415165,1.44650864601 --12.8045721054,0.212562575936,1.41012561321 --12.8475656509,0.213556066155,1.37374031544 --12.8795633316,0.214551910758,1.35655081272 --12.9295558929,0.216544687748,1.32117414474 --12.966550827,0.217538401484,1.28378975391 --13.0105457306,0.218531429768,1.24741280079 --13.0465402603,0.21952496469,1.20902347565 --13.0795354843,0.220518678427,1.1706379652 --13.130531311,0.221512496471,1.15546631813 --13.1665277481,0.222505763173,1.11708295345 --13.1685247421,0.222501933575,1.07467901707 --12.2235593796,0.192584499717,0.942826986313 --12.1735572815,0.190586432815,0.899404466152 --12.2945489883,0.194572433829,0.871059656143 --13.3435077667,0.22847057879,0.921159207821 --12.1715450287,0.190578401089,0.782195627689 --12.2185411453,0.191572442651,0.766012132168 --12.1395397186,0.189577281475,0.721579372883 --13.5094957352,0.233440175653,0.784840643406 --12.1395320892,0.188571557403,0.6437728405 --12.2255268097,0.191559970379,0.610407710075 --12.2455224991,0.192554935813,0.573018670082 --12.2445192337,0.192551910877,0.533613204956 --12.1935195923,0.190555617213,0.511391103268 --12.1315174103,0.18855895102,0.468958377838 --13.7344799042,0.239387705922,0.517347335815 --12.1035108566,0.187555700541,0.390139430761 --12.0135097504,0.184562236071,0.347696959972 --12.2685022354,0.192531526089,0.320417225361 --12.6514940262,0.204488202929,0.31740668416 --12.6484928131,0.204484701157,0.27700316906 --12.0424976349,0.185548037291,0.21429720521 --11.968495369,0.182553112507,0.173861965537 --12.3704881668,0.195504382253,0.147657215595 --12.5774850845,0.20247708261,0.114362835884 --12.63048172,0.203467041254,0.0759911462665 --12.491481781,0.199481099844,0.0527198575437 --12.2644805908,0.19250369072,0.00819959584624 --12.2404794693,0.191502794623,-0.0312148816884 --12.3534765244,0.194485589862,-0.068558819592 --14.476474762,0.26222640276,-0.0858862996101 --14.5344762802,0.264212906361,-0.132264509797 --12.4714708328,0.198459282517,-0.185702815652 --12.277469635,0.192481085658,-0.206003174186 --12.1094665527,0.187498047948,-0.244487196207 --11.889462471,0.180521830916,-0.28200122714 --11.9814605713,0.182506486773,-0.321365624666 --11.8724584579,0.179516687989,-0.357818812132 --12.3304615021,0.194453924894,-0.401987761259 --12.4134607315,0.196438893676,-0.442344516516 --12.2094583511,0.190463319421,-0.458653897047 --12.2444572449,0.191454529762,-0.498035877943 --12.359457016,0.195435032248,-0.539374172688 --12.3264560699,0.19443500042,-0.577793478966 --12.3804559708,0.195423170924,-0.619172394276 --12.4594573975,0.198407903314,-0.660526037216 --12.344452858,0.194419011474,-0.695988535881 --12.3614530563,0.195414379239,-0.716179609299 --12.3954534531,0.196404904127,-0.757570028305 --12.5334568024,0.20138078928,-0.802896380424 --15.5345458984,0.296950787306,-0.986734330654 --12.623459816,0.204357922077,-0.887655675411 --11.9624376297,0.182448118925,-0.891400039196 --12.6144599915,0.203348860145,-0.967462182045 --11.9274349213,0.181446522474,-0.947026848793 --12.0784397125,0.186419844627,-0.994347631931 --15.8655872345,0.307853639126,-1.28075969219 --11.9134321213,0.181435123086,-1.06024074554 --11.9644346237,0.183422908187,-1.10161209106 --11.9934339523,0.184413805604,-1.14199864864 --11.9584321976,0.183414429426,-1.17741751671 --11.945432663,0.183414041996,-1.19562697411 --11.9664325714,0.183405950665,-1.23602223396 --11.8674278259,0.180416613817,-1.26547396183 --12.377453804,0.197331354022,-1.34960865974 --12.2444477081,0.193347141147,-1.3760727644 --12.2424478531,0.193342059851,-1.41547930241 --12.175444603,0.191347494721,-1.44791507721 --16.6067028046,0.332627683878,-1.9117462635 --16.6787147522,0.335605025291,-1.97210383415 --16.7487297058,0.337582290173,-2.0334675312 --16.8187427521,0.340559393167,-2.0948278904 --16.8767547607,0.342538297176,-2.15519356728 --16.9477710724,0.344514787197,-2.21755242348 --17.0137805939,0.346497744322,-2.25271701813 --17.0667934418,0.348476976156,-2.31308078766 --17.0918045044,0.349460572004,-2.37146759033 --17.0058097839,0.347463190556,-2.41591405869 --16.8738117218,0.343474060297,-2.45338201523 --17.0888385773,0.350424349308,-2.53666448593 --17.0398426056,0.349420636892,-2.58508825302 --16.754825592,0.340465098619,-2.5724363327 --15.3427209854,0.294705033302,-2.42660307884 --14.7756824493,0.27679669857,-2.39431381226 --14.8636960983,0.27977129817,-2.45466017723 --15.1097249985,0.287716478109,-2.54093146324 --14.9377174377,0.28273794055,-2.56342577934 --14.3496713638,0.263836830854,-2.5191488266 --14.3636760712,0.264829665422,-2.54433774948 --14.2676734924,0.261838257313,-2.57579350471 --14.2666807175,0.261829137802,-2.622194767 --14.2786874771,0.262817561626,-2.670586586 --14.2746944427,0.26280900836,-2.71598410606 --14.2466993332,0.261804789305,-2.75840544701 --14.1056919098,0.25782263279,-2.7798845768 --13.7486572266,0.245887503028,-2.73828196526 --13.7316608429,0.245882019401,-2.7796869278 --13.795674324,0.247860357165,-2.83705401421 --13.7386751175,0.246862560511,-2.87148618698 --13.6026668549,0.242880553007,-2.89096832275 --13.7216873169,0.246847555041,-2.9593026638 --13.587677002,0.242865517735,-2.97777915001 --13.5366744995,0.240871548653,-2.9889998436 --13.5686855316,0.241855889559,-3.04038286209 --13.4896821976,0.239863023162,-3.06882834435 --13.4956893921,0.240852549672,-3.11522960663 --13.7237262726,0.247795686126,-3.20849585533 --13.7117319107,0.247788503766,-3.2519068718 --13.6477308273,0.246792420745,-3.2833442688 --13.4617109299,0.240827202797,-3.26465129852 --13.4247131348,0.239825740457,-3.30107235909 --13.2807006836,0.234847426414,-3.31255292892 --13.2937097549,0.235835105181,-3.36095499992 --13.3497238159,0.237813547254,-3.41831994057 --13.2817220688,0.235818997025,-3.44675970078 --13.319735527,0.237800940871,-3.50114345551 --13.3477430344,0.238789916039,-3.53032708168 --13.3277482986,0.238784790039,-3.56973457336 --13.5207853317,0.244731560349,-3.6630218029 --13.1667394638,0.233801737428,-3.61862874031 --13.2827653885,0.237765595317,-3.69296097755 --13.4337978363,0.243721008301,-3.77727270126 --13.4648113251,0.244703486562,-3.83166050911 --13.6758489609,0.251649349928,-3.9107375145 --13.8398857117,0.257600426674,-4.00103807449 --13.7608823776,0.255608022213,-4.0264840126 --14.7250518799,0.287368863821,-4.34032297134 --13.8119106293,0.257573693991,-4.13525867462 --13.6738977432,0.253595471382,-4.14374256134 --13.6028900146,0.251607269049,-4.14597654343 --13.6849136353,0.254576414824,-4.21632862091 --13.6659212112,0.254569590092,-4.25874757767 --13.6169233322,0.253570348024,-4.29117536545 --13.3608875275,0.245622217655,-4.26172780991 --13.7539691925,0.258513659239,-4.42689704895 --13.8129920959,0.261487305164,-4.49225997925 --13.534945488,0.251551121473,-4.4306230545 --13.517952919,0.251543790102,-4.47303962708 --13.9150400162,0.265431702137,-4.64419841766 --13.9850654602,0.268401712179,-4.71455287933 --13.9190645218,0.266406059265,-4.74299860001 --13.8690671921,0.265406608582,-4.77542829514 --13.8240699768,0.26440602541,-4.80885124207 --13.8130750656,0.264402538538,-4.83006286621 --13.7650766373,0.263402760029,-4.86249017715 --13.7750911713,0.263387799263,-4.91387987137 --17.4998874664,0.389385670424,-6.2290430069 --17.3848838806,0.386397570372,-6.25151014328 --17.4889278412,0.39035102725,-6.34884166718 --17.5689678192,0.393310338259,-6.43919181824 --17.7480297089,0.400242567062,-6.56447696686 --17.5549983978,0.39428538084,-6.52779388428 --17.5650234222,0.395263195038,-6.59418582916 --17.5470428467,0.395248621702,-6.65059375763 --17.5700740814,0.396222621202,-6.72197628021 --17.5420913696,0.396210819483,-6.77438783646 --17.5251102448,0.396195590496,-6.83179807663 --17.2940673828,0.389251023531,-6.77613401413 --17.2170734406,0.387253254652,-6.80957841873 --17.2040920258,0.387237399817,-6.8669834137 --17.1651077271,0.386228919029,-6.91440391541 --17.168132782,0.387208074331,-6.97880315781 --17.3922119141,0.396123230457,-7.12905979156 --21.3482284546,0.531945466995,-8.76303482056 --21.0441684723,0.522021114826,-8.68041419983 --20.8411540985,0.515054047108,-8.67593193054 --21.1182575226,0.525945007801,-8.86515617371 --20.9022369385,0.518981993198,-8.85468387604 --20.9172763824,0.520950376987,-8.93806838989 --20.7112579346,0.514985203743,-8.9295873642 --20.006105423,0.491172254086,-8.71042060852 --21.4825191498,0.542709350586,-9.37069988251 --21.0934524536,0.529799759388,-9.28533554077 --21.0554790497,0.529783248901,-9.34775257111 --21.0435142517,0.530758440495,-9.42215633392 --20.9025115967,0.526773929596,-9.43963813782 --20.8375301361,0.524766147137,-9.48906803131 --18.9780368805,0.461325019598,-8.74062347412 --21.083656311,0.53564542532,-9.71750640869 --20.8076171875,0.526704251766,-9.67307186127 --20.8126564026,0.527673482895,-9.75546646118 --20.9827442169,0.534589707851,-9.91275310516 --21.0558052063,0.538536787033,-10.026096344 --21.3279285431,0.549418032169,-10.2343225479 --21.4209976196,0.553357243538,-10.3596544266 --21.6871013641,0.56325417757,-10.5266838074 --20.6928367615,0.529551744461,-10.1377038956 --20.7008781433,0.53051930666,-10.2220935822 --20.730928421,0.532479166985,-10.3174695969 --20.7869873047,0.536430120468,-10.4258289337 --21.3702163696,0.557202100754,-10.7938537598 --21.5403137207,0.565112650394,-10.9611349106 --21.7073917389,0.571039259434,-11.087228775 --20.7541217804,0.538334071636,-10.6952266693 --20.8431949615,0.543272197247,-10.8225660324 --20.7311992645,0.540279865265,-10.8480291367 --20.8512821198,0.545206427574,-10.9923467636 --21.2614650726,0.561030507088,-11.2874774933 --21.288520813,0.563988149166,-11.3868541718 --21.349565506,0.566950201988,-11.4610099792 --38.4075546265,1.17883729935,-20.5284843445 --40.1102523804,1.24215936661,-21.5857696533 --37.9976119995,1.16884839535,-20.6195011139 --38.1697692871,1.17671823502,-20.8657665253 --38.035823822,1.17469799519,-20.9492321014 --23.8667640686,0.66482424736,-13.3577413559 --22.7674427032,0.627170741558,-12.8980436325 --22.733537674,0.629107773304,-13.0668468475 --22.6855735779,0.629087626934,-13.1342697144 --25.1855831146,0.721103787422,-14.6520318985 --25.1326255798,0.72107988596,-14.7274580002 --35.222568512,1.09020936489,-20.5880794525 --35.098613739,1.0881909132,-20.6645412445 --24.3815517426,0.699215769768,-14.6573152542 --34.7217597961,1.08113896847,-20.8869304657 --34.5918045044,1.07912361622,-20.9573955536 --34.5168228149,1.07711982727,-20.9866371155 --34.416885376,1.07609260082,-21.0750846863 --34.507019043,1.08199048042,-21.2774047852 --34.6461791992,1.08986771107,-21.5116939545 --37.8386230469,1.21051597595,-23.6279678345 --37.6996765137,1.20849633217,-23.70744133 --35.7219467163,1.13722503185,-22.6371269226 --35.6079483032,1.13423609734,-22.6433906555 --35.3849601746,1.12825584412,-22.6599216461 --35.2710189819,1.12623167038,-22.7433757782 --34.9369773865,1.11629867554,-22.6859779358 --34.9390869141,1.11922693253,-22.8423557281 --35.3964004517,1.13896346092,-23.2954311371 --33.9318466187,1.08650839329,-22.4967899323 --33.942905426,1.08846843243,-22.5809745789 --34.1080856323,1.09732794762,-22.84324646 --34.006149292,1.09630072117,-22.929693222 --33.9212150574,1.09526574612,-23.0281352997 --34.031375885,1.10214614868,-23.2584438324 --34.1115226746,1.10803925991,-23.4687709808 --33.9375534058,1.10404253006,-23.5072689056 --34.077671051,1.11094486713,-23.6813640594 --34.2298583984,1.11980438232,-23.944644928 --34.09790802,1.11778891087,-24.0121135712 --33.9359397888,1.11378610134,-24.0596084595 --34.0951309204,1.12264060974,-24.3308811188 --33.6920433044,1.10974740982,-24.2055358887 --33.4050178528,1.10180258751,-24.161113739 --33.3430404663,1.10079360008,-24.196346283 --33.4422035217,1.10767352581,-24.4276618958 --33.2132034302,1.10170388222,-24.4211997986 --33.2063140869,1.10463178158,-24.576587677 --33.3204917908,1.11150324345,-24.8208904266 --33.2345619202,1.11146664619,-24.9203357697 --32.7454223633,1.09562015533,-24.7180519104 --32.54637146,1.08867585659,-24.6503829956 --32.5735054016,1.09258759022,-24.830745697 --32.5335960388,1.09453082085,-24.9611549377 --32.5337142944,1.09745430946,-25.1225376129 --32.4137687683,1.09543466568,-25.1940059662 --32.2457962036,1.09243917465,-25.2265052795 --32.3519744873,1.09931015968,-25.4718170166 --32.813293457,1.11904597282,-25.9126873016 --32.7473754883,1.11999857426,-26.0281181335 --32.77551651,1.12390494347,-26.2174797058 --32.6675796509,1.12287807465,-26.2999401093 --32.8938331604,1.13568484783,-26.6481628418 --32.5347518921,1.12478280067,-26.5307979584 --32.4658432007,1.12473630905,-26.6442298889 --32.3998641968,1.12372899055,-26.6754665375 --33.3395462036,1.1661683321,-27.61419487 --33.2786407471,1.16711473465,-27.7396202087 --33.1506996155,1.16509509087,-27.810092926 --32.4363975525,1.1393802166,-27.3899745941 --31.2528095245,1.09391248226,-26.5711917877 --31.2709465027,1.0978218317,-26.7545623779 --31.2630062103,1.09878492355,-26.8327617645 --31.1080379486,1.09578478336,-26.8702545166 --30.9270534515,1.09179866314,-26.8847694397 --30.9852180481,1.09768509865,-27.1051139832 --32.3782348633,1.15985369682,-28.4865131378 --30.2760219574,1.07490193844,-26.8273868561 --30.07695961,1.06896901131,-26.7367191315 --30.0610752106,1.07189595699,-26.8911170959 --29.9541358948,1.06987261772,-26.9645786285 --30.0133037567,1.07675755024,-27.1869220734 --30.222574234,1.08855831623,-27.5461597443 --28.1293067932,1.00364005566,-25.8240432739 --28.0353660583,1.00261414051,-25.9004955292 --27.9803905487,1.00160586834,-25.9307289124 --27.8954563141,1.00157499313,-26.0151786804 --27.7995147705,1.00155007839,-26.0896377563 --27.7125797272,1.00052011013,-26.1720867157 --27.6186389923,1.00049495697,-26.2465400696 --27.5247001648,0.999468743801,-26.3229980469 --27.432762146,0.999441742897,-26.4004554749 --27.3957996368,0.999423027039,-26.447675705 --27.2948551178,0.998401343822,-26.5161380768 --27.2039165497,0.9983741045,-26.5935916901 --27.0979690552,0.997355520725,-26.6570568085 --27.0070304871,0.996328115463,-26.7345123291 --26.9240989685,0.996296346188,-26.8189582825 --26.829158783,0.9962708354,-26.8934211731 --26.7961978912,0.996249973774,-26.9436359406 --26.699256897,0.996226131916,-27.0150985718 --26.5903072357,0.994209587574,-27.0745677948 --26.5253887177,0.995166063309,-27.1780033112 --26.4084320068,0.994154810905,-27.2284793854 --26.3305053711,0.994119167328,-27.3189239502 --26.2345657349,0.994094967842,-27.3903865814 --26.0906543732,0.993058800697,-27.4970741272 --26.0107269287,0.993024170399,-27.5855236053 --26.3331203461,1.01173257828,-28.0976772308 --27.8294715881,1.08468389511,-29.85896492 --27.5964317322,1.07874059677,-29.7975254059 --27.3393707275,1.07081401348,-29.7081050873 --27.4225139618,1.0767134428,-29.8902359009 --27.3285884857,1.07668042183,-29.9766979218 --27.0965442657,1.06973910332,-29.9112567902 --27.4830207825,1.09238874912,-30.522359848 --27.3700828552,1.0913670063,-30.5898323059 --27.079990387,1.08246481419,-30.459438324 --26.9089984894,1.07848346233,-30.4599552155 --26.9931488037,1.0853780508,-30.6500873566 --26.4938697815,1.06562077999,-30.2788486481 --26.2247886658,1.05770897865,-30.1634407043 --25.9787254333,1.04978251457,-30.0720119476 --25.9948959351,1.05567538738,-30.2803916931 --25.9099750519,1.05563795567,-30.3728466034 --25.7619972229,1.0526444912,-30.3923473358 --25.6639862061,1.05066490173,-30.3736171722 --25.561050415,1.04964053631,-30.4440841675 --18.7449150085,0.721393406391,-22.5696182251 --18.3576660156,0.705601274967,-22.2503051758 --17.6923656464,0.682878017426,-21.8680057526 --17.6573867798,0.682870030403,-21.8942279816 --17.5984401703,0.683845162392,-21.9616737366 --17.5464992523,0.683815419674,-22.0371112823 --17.4815483093,0.684794664383,-22.0975608826 --17.4256019592,0.684767842293,-22.1680011749 --17.3686561584,0.68574154377,-22.2374401093 --17.3416843414,0.685727417469,-22.2736587524 --17.2847423553,0.686700105667,-22.3451042175 --17.2318019867,0.687670767307,-22.4195423126 --17.1728572845,0.687645077705,-22.487985611 --17.0629730225,0.689587593079,-22.6348667145 --17.1201496124,0.696470558643,-22.8562221527 --16.9460849762,0.690534412861,-22.7747573853 --16.9391365051,0.692504107952,-22.8379573822 --16.8641757965,0.691490292549,-22.8864154816 --16.8082332611,0.692461967468,-22.9588565826 --17.6422576904,0.740714848042,-24.2366123199 --17.5653018951,0.740698695183,-24.289068222 --17.5203819275,0.741655826569,-24.3865032196 --17.4834079742,0.742646038532,-24.4157314301 --17.2452716827,0.733762085438,-24.2463150024 --16.5346069336,0.699271440506,-23.416267395 --16.470659256,0.699247419834,-23.4817180634 --16.3997058868,0.699230313301,-23.5351696014 --16.2557926178,0.699196219444,-23.642080307 --16.1767654419,0.697224795818,-23.6063423157 --21.5401687622,0.998541533947,-31.5085506439 --16.98097229,0.750372052193,-25.0905094147 --16.9220428467,0.751338541508,-25.171957016 --16.9081668854,0.755265235901,-25.3203659058 --16.8422279358,0.755236625671,-25.393819809 --16.7752876282,0.756210029125,-25.4632701874 --15.8652477264,0.706975460052,-24.1861877441 --15.8033056259,0.706949293613,-24.2546348572 --21.4774913788,1.03675270081,-33.0405693054 --21.0771846771,1.01999843121,-32.6532783508 --21.1404571533,1.02882432938,-32.9736251831 --21.1376495361,1.034709692,-33.1940231323 --20.8654994965,1.0248414278,-32.9986305237 --20.9517059326,1.03270292282,-33.2457618713 --20.6475124359,1.02186703682,-32.9953994751 --20.4514541626,1.01593208313,-32.9119529724 --21.5352973938,1.09265840054,-35.1178817749 --21.5975971222,1.10346913338,-35.4652328491 --21.9322681427,1.13001537323,-36.2593612671 --21.8232345581,1.12705338001,-36.2086448669 --22.6575984955,1.18410491943,-37.8403739929 --22.4585647583,1.17915761471,-37.7789306641 --22.1764087677,1.1692956686,-37.5725517273 --21.6499061584,1.14367866516,-36.9513664246 --21.6020755768,1.14758646488,-37.1347999573 --21.5641384125,1.14955472946,-37.2020301819 --21.4532165527,1.14952552319,-37.2785148621 --21.7979545593,1.17803049088,-38.1446380615 --21.5207977295,1.1681689024,-37.9372558594 --21.5030174255,1.17504131794,-38.1806640625 --21.1076793671,1.15730559826,-37.7593803406 --15.0047969818,0.771567583084,-27.1626911163 --14.928855896,0.772544443607,-27.2261581421 --13.6920681,0.694805443287,-25.0983600616 --13.6511640549,0.697754323483,-25.2087955475 --16.6599636078,0.900418877602,-30.8957614899 --16.5650157928,0.90040153265,-30.9502372742 --16.5041255951,0.902346491814,-31.068687439 --16.4452381134,0.905289113522,-31.1911354065 --20.1432189941,1.15614283085,-38.2503395081 --20.0252895355,1.1561204195,-38.31483078 --19.968460083,1.16002893448,-38.4972724915 --19.87657547,1.16197550297,-38.6147499084 --19.7426242828,1.16096961498,-38.651260376 --12.8063735962,0.690761208534,-25.4203147888 --12.7494478226,0.69172590971,-25.5037651062 --12.6643915176,0.688773155212,-25.4350376129 --12.7326774597,0.6995921731,-25.7663822174 --12.6026287079,0.695641458035,-25.7058944702 --12.460559845,0.691705405712,-25.6204147339 --12.3745851517,0.690704107285,-25.6458892822 --13.6760559082,0.790030479431,-28.5212230682 --12.1395244598,0.685777187347,-25.5678920746 --12.1095590591,0.685761511326,-25.6061172485 --5.53997039795,0.214680895209,-12.1504364014 --5.41080713272,0.207796916366,-11.9729604721 --18.1775379181,1.16169559956,-39.461730957 --17.273141861,1.10266840458,-37.8278770447 --17.1752433777,1.10462486744,-37.9283599854 --17.1633644104,1.10855662823,-38.0575714111 --17.0484333038,1.10853528976,-38.1200675964 --17.5256500244,1.15474140644,-39.50207901 --17.4367790222,1.15667974949,-39.6335525513 --17.2857913971,1.15470004082,-39.6250762939 --13.2119951248,0.844964683056,-30.6528549194 --17.7762393951,1.20776820183,-41.257270813 --17.5581264496,1.20087218285,-41.1058540344 --17.376083374,1.19692838192,-41.0364074707 --17.1760005951,1.19101190567,-40.9199790955 --16.771490097,1.16837990284,-40.3167152405 --16.4852161407,1.15459012985,-39.9833526611 --16.4374446869,1.16146552563,-40.2228012085 --16.3063316345,1.15555536747,-40.0821113586 --16.3086662292,1.16635894775,-40.4445114136 --16.7118816376,1.21058011055,-41.8045768738 --11.9958686829,0.822245419025,-30.4139213562 --16.509141922,1.21546411514,-42.0565567017 --9.50579166412,0.624641537666,-24.6428318024 --9.41077709198,0.623665571213,-24.6243190765 --9.36577510834,0.622674405575,-24.6205596924 --7.62497234344,0.477194964886,-20.3224487305 --7.55597734451,0.476203352213,-20.329914093 --7.48999023438,0.476206570864,-20.3463821411 --7.42801094055,0.476204454899,-20.3718414307 --7.37705659866,0.477185875177,-20.4252872467 --7.29904174805,0.476207822561,-20.4097671509 --7.29612112045,0.478161662817,-20.4999752045 --7.22010850906,0.47718167305,-20.4874477386 --7.7265496254,0.53025329113,-22.1034221649 --7.23750972748,0.490943580866,-20.9402503967 --7.42016172409,0.514531910419,-21.6695041656 --7.00227546692,0.480119973421,-20.6812705994 --6.97238254547,0.484062641859,-20.8017044067 --6.61972999573,0.458503097296,-20.0776233673 --6.55273294449,0.458512604237,-20.0830879211 --6.48172569275,0.457528591156,-20.0775623322 --6.42876672745,0.45851367712,-20.1250152588 --6.36177158356,0.457522213459,-20.1324863434 --6.32285118103,0.460482269526,-20.2229270935 --6.33197546005,0.464408457279,-20.361125946 --6.29105329514,0.466369777918,-20.4495697021 --6.28724384308,0.473259866238,-20.6609859467 --6.15606117249,0.465388417244,-20.4615058899 --6.10812473297,0.467359870672,-20.5329627991 --6.2206697464,0.486023634672,-21.1342735291 --6.14254045486,0.48111230135,-20.9925460815 --6.08156776428,0.482106894255,-21.0240077972 --6.05570697784,0.486030817032,-21.1774425507 --5.99473714828,0.487023741007,-21.2119064331 --5.94580745697,0.48899179697,-21.2893600464 --5.85273361206,0.485050708055,-21.2098484039 --5.79678344727,0.487031638622,-21.2653121948 --6.14805364609,0.531233787537,-22.6532077789 --6.01887559891,0.524360120296,-22.4577312469 --6.10341596603,0.54303252697,-23.0460720062 --5.96118927002,0.53418892622,-22.7986030579 --5.89723110199,0.53517639637,-22.8430709839 --5.83226919174,0.536166250706,-22.8835391998 --5.77232456207,0.537144958973,-22.9430007935 --5.75740861893,0.540099442005,-23.0332202911 --5.58104133606,0.526343047619,-22.6347846985 --5.47793769836,0.522422015667,-22.5212879181 --5.41598463058,0.523406088352,-22.5717582703 --5.37209796906,0.526348412037,-22.6942062378 --5.27601337433,0.523415088654,-22.6016998291 --5.33152246475,0.540111541748,-23.1500663757 --5.29954576492,0.541104197502,-23.1742992401 --5.25266265869,0.544045627117,-23.2987537384 --5.21983909607,0.549950182438,-23.4871940613 --5.16693973541,0.552902162075,-23.5936546326 --5.13111352921,0.557809114456,-23.7780990601 --5.09127235413,0.562725305557,-23.9465465546 --5.81174659729,0.681595265865,-27.6623325348 --4.98833274841,0.563709974289,-24.0082530975 --4.92138338089,0.565693795681,-24.0597267151 --4.85544013977,0.566673696041,-24.1182003021 --4.80255794525,0.570616185665,-24.2416610718 --5.44091844559,0.684568464756,-27.8185157776 --5.35293531418,0.684576094151,-27.8300094604 --5.18355083466,0.67082887888,-27.4155693054 --5.15663766861,0.672784566879,-27.5048007965 --5.04251718521,0.667875647545,-27.3713169098 --4.9183344841,0.6610044837,-27.171836853 --5.16607618332,0.719960272312,-29.0110397339 --4.80466556549,0.670837283134,-27.5117683411 --4.70359706879,0.667896568775,-27.4332695007 --4.78126096725,0.690502166748,-28.1314105988 --4.67718839645,0.686563968658,-28.048915863 --3.89929676056,0.555939555168,-23.9410095215 --4.52032613754,0.690516829491,-28.1808853149 --4.45547676086,0.694443583488,-28.3333568573 --3.66526484489,0.553003549576,-23.9014587402 --3.54446220398,0.558914721012,-24.1043968201 --3.50746917725,0.558918058872,-24.1106376648 --3.43046689034,0.558934569359,-24.1061229706 --3.36352872849,0.559912621975,-24.1685943604 --3.29860782623,0.561880350113,-24.2490692139 --3.17729520798,0.551082670689,-23.9205913544 --3.09122180939,0.549141645432,-23.8420848846 --3.06631112099,0.551095724106,-23.9343128204 --2.96109580994,0.544239580631,-23.707824707 --2.86593317986,0.538351118565,-23.5373210907 --2.82822108269,0.547194778919,-23.8347740173 --1.80658102036,0.295747339725,-15.9080934525 --1.76363050938,0.297727257013,-15.9655485153 --2.63246560097,0.554095387459,-24.0821971893 --2.59043216705,0.553122937679,-24.0464439392 --2.5295650959,0.557059645653,-24.1819190979 --2.45658731461,0.558062076569,-24.2023983002 --2.37352013588,0.555117249489,-24.1308898926 --2.2944817543,0.553155064583,-24.0893745422 --2.24171185493,0.561035454273,-24.323841095 --2.14246749878,0.552194535732,-24.0703449249 --6.12245988846,1.94796919823,-68.2694168091 --5.53200483322,2.05409550667,-71.7106781006 --5.30705976486,2.05311536789,-71.7163085938 --3.88098549843,1.56496441364,-56.2440414429 --3.69892430305,1.56204009056,-56.1466255188 --3.51991486549,1.56008577347,-56.1022109985 --3.35206913948,1.5630364418,-56.2247848511 --2.70456504822,1.54246842861,-55.5918502808 --2.5479631424,1.55427896976,-55.9614219666 --2.38526630402,1.56214487553,-56.233997345 --2.88072562218,2.08472943306,-72.8492126465 --2.64660787582,2.07885026932,-72.678855896 --2.41245293617,2.07199215889,-72.471496582 --2.18032884598,2.06711673737,-72.2951278687 --2.06633353233,2.06614041328,-72.2744445801 --1.84140789509,2.0661509037,-72.299079895 --1.61652255058,2.06813907623,-72.3637237549 --1.39478051662,2.07504534721,-72.5723571777 --1.17097890377,2.07898592949,-72.720993042 --0.947264671326,2.08687758446,-72.9566345215 --0.749159693718,2.17628955841,-75.8062896729 --0.629030227661,2.17139101028,-75.6496200562 -0.441043376923,2.33205127716,-77.7789154053 -0.673535168171,2.28514027596,-76.3261260986 -0.794558346272,2.28712248802,-76.3772125244 -1.03547155857,2.28601264954,-76.3463973999 -1.2721657753,2.277780056,-76.0955810547 -1.24351072311,1.83207428455,-62.4312782288 -1.43625223637,1.8258793354,-62.2135047913 -1.27036488056,1.37107586861,-48.273349762 -1.42126381397,1.36898028851,-48.1996154785 -1.49619436264,1.36692202091,-48.1437530518 -1.65124714375,1.36991238594,-48.2250137329 -2.3713953495,1.87028968334,-63.5584373474 -2.57540869713,1.87224602699,-63.6156539917 -2.85310864449,1.92913734913,-65.3807678223 -3.02429842949,1.90463662148,-64.6050262451 -3.2160050869,1.89642333984,-64.3522644043 -3.30981278419,1.89129137993,-64.1793899536 -3.51276636124,1.89121472836,-64.1766052246 -3.71875905991,1.89215958118,-64.2138214111 -4.05316400528,1.90830588341,-64.6931152344 -4.26420354843,1.91127610207,-64.7783355713 -4.474214077,1.91423046589,-64.8345489502 -4.54880619049,1.90098178387,-64.4406814575 -4.77403354645,1.91105484962,-64.717880249 -4.96378517151,1.90386807919,-64.5091247559 -5.17886638641,1.9088613987,-64.6373291016 -5.37570905685,1.90572464466,-64.5215606689 -5.60898399353,1.91682302952,-64.8487548828 -5.80988359451,1.91571760178,-64.790977478 -5.90476799011,1.91262936592,-64.695098877 -6.09961032867,1.90949308872,-64.5783309937 -6.31970787048,1.91449522972,-64.7245407104 -6.51354122162,1.91135406494,-64.5977706909 -6.72049999237,1.91128098965,-64.6010055542 -6.91736602783,1.90915811062,-64.5082321167 -7.10112810135,1.90297961235,-64.3074798584 -7.20713424683,1.9049577713,-64.3365936279 -7.42519664764,1.9089410305,-64.4468002319 -7.72391033173,1.93527257442,-65.2319259644 -7.81693649292,1.90470039845,-64.2672805786 -8.01180839539,1.90258216858,-64.1805114746 -8.23891830444,1.90859007835,-64.3397216797 -8.29152297974,1.89535439014,-63.9508857727 -8.51560974121,1.90135061741,-64.0870895386 -8.71653175354,1.90025877953,-64.0503234863 -8.94464015961,1.9062666893,-64.209526062 -9.27946662903,1.93765389919,-65.1176223755 -9.5085439682,1.94264471531,-65.2468261719 -5.96225500107,1.10876345634,-39.8540763855 -6.02523899078,1.10873925686,-39.8472251892 -9.77178955078,1.88759243488,-63.5226631165 -6.22484111786,1.09746658802,-39.4698791504 -6.34979963303,1.09741342068,-39.4461860657 -6.47878694534,1.09837555885,-39.4524841309 -6.63291692734,1.10441255569,-39.609752655 -6.75787448883,1.1033591032,-39.5850601196 -7.59918069839,1.25459384918,-44.1383934021 -7.74617528915,1.2555564642,-44.1576766968 -8.70463562012,1.37928712368,-47.8705558777 -8.84854602814,1.37820279598,-47.8038406372 -11.895108223,1.89071857929,-63.2791366577 -11.5161647797,1.79014480114,-60.197971344 -11.6201705933,1.79112422466,-60.2250862122 -12.3888864517,1.88948071003,-63.1557426453 -12.5787630081,1.88736832142,-63.0699958801 -12.7806987762,1.88828611374,-63.0462341309 -12.9776058197,1.88718926907,-62.9924812317 -13.188577652,1.88912582397,-63.0077133179 -13.3915138245,1.89004361629,-62.9839515686 -13.4864549637,1.88898956776,-62.9440803528 -13.7165079117,1.8939678669,-63.0462875366 -13.9244642258,1.89489650726,-63.0445251465 -14.1123332977,1.89378094673,-62.9497795105 -6.22595119476,0.702742278576,-27.1331653595 -14.5543460846,1.89968895912,-63.0532264709 -6.50451374054,0.723995089531,-27.7485256195 -6.60654163361,0.725987315178,-27.7868518829 -6.38094043732,0.670134007931,-26.0739364624 -6.40669775009,0.661990463734,-25.8173408508 -7.3523440361,0.760268568993,-28.6994628906 -11.7769203186,1.32705831528,-45.6055145264 -8.20318603516,0.797550499439,-29.6711997986 -16.6963768005,1.83254885674,-60.4371185303 -8.76046180725,0.812581062317,-30.0185852051 -8.8383731842,0.810513734818,-29.9319381714 -8.91929626465,0.809451580048,-29.8562889099 -8.95825004578,0.808417260647,-29.8114681244 -9.03817176819,0.806355535984,-29.7358188629 -9.10304927826,0.803271710873,-29.6101856232 -9.20804405212,0.804245531559,-29.6145172119 -9.29097747803,0.803189635277,-29.5508651733 -9.37090206146,0.801129877567,-29.4782180786 -9.45383453369,0.800073087215,-29.4125709534 -9.4907913208,0.799040734768,-29.3697471619 -9.53561878204,0.793933570385,-29.1881351471 -9.66067123413,0.796935975552,-29.2564468384 -13.4342985153,1.16553533077,-39.978717804 -13.5151195526,1.16041719913,-39.800075531 -13.6190042496,1.15833067894,-39.6934127808 -13.7040328979,1.16032838821,-39.7355499268 -13.8079195023,1.15824258327,-39.6298866272 -18.3862953186,1.59665691853,-52.3620185852 -18.531162262,1.59455180168,-52.2473220825 -15.0358839035,1.24108529091,-41.8930397034 -18.7677612305,1.58527863026,-51.8689880371 -18.8206481934,1.58320426941,-51.7591552734 -18.948474884,1.57908129692,-51.600479126 -19.1354503632,1.5820287466,-51.6067466736 -19.3184127808,1.58297002316,-51.5990219116 -19.4723072052,1.58287906647,-51.5143165588 -19.5580425262,1.57571315765,-51.2496795654 -19.7540359497,1.57867002487,-51.2779388428 -19.7758579254,1.57256519794,-51.0921440125 -19.9057006836,1.57045197487,-50.9504623413 -20.0836524963,1.5713891983,-50.9307403564 -20.2295322418,1.570291996,-50.8280487061 -20.3263072968,1.56414628029,-50.6054000854 -20.3950214386,1.55597352982,-50.3157844543 -20.6270942688,1.56296670437,-50.4310112 -20.6389064789,1.55685853958,-50.232219696 -20.8318920135,1.55981230736,-50.2504882812 -20.9467105865,1.5556883812,-50.0778274536 -21.0054168701,1.54751265049,-49.7752113342 -21.0310573578,1.53630745411,-49.3976325989 -21.2140254974,1.53825306892,-49.3939094543 -21.3739471436,1.53817665577,-49.3352088928 -21.4298591614,1.53711652756,-49.2503814697 -21.5757522583,1.53602814674,-49.1606903076 -21.7206439972,1.53493976593,-49.0700035095 -21.8705482483,1.53485584259,-48.9903068542 -22.0034141541,1.53275597095,-48.8706321716 -22.1342830658,1.53065705299,-48.750957489 -22.2841873169,1.53057408333,-48.6722640991 -22.3641490936,1.53053677082,-48.6434135437 -22.5190620422,1.53045785427,-48.5747184753 -22.6779823303,1.53038370609,-48.5170211792 -22.8549365997,1.53232383728,-48.496307373 -22.9958248138,1.53123378754,-48.3976211548 -23.1517429352,1.53115737438,-48.3329277039 -23.2286968231,1.53111708164,-48.296081543 -23.3695888519,1.53102898598,-48.2003974915 -23.5395259857,1.53196191788,-48.1606941223 -18.7968502045,1.17107188702,-38.0753440857 -18.8536739349,1.16696202755,-37.8877334595 -18.9165058136,1.16185688972,-37.7121200562 -18.9352664948,1.15472090244,-37.4525375366 -19.1895637512,1.16883635521,-37.8105316162 -24.5012397766,1.54061806202,-48.0002861023 -24.6791915894,1.54255735874,-47.9755706787 -24.8861923218,1.54651761055,-48.0068359375 -25.0451068878,1.54644143581,-47.9411430359 -25.2200546265,1.54837810993,-47.9084320068 -25.4210395813,1.5513317585,-47.9227027893 -25.5280399323,1.55331289768,-47.9418296814 -25.7430477142,1.55827617645,-47.9820899963 -25.9089756012,1.55920433998,-47.9273910522 -26.0789070129,1.56013524532,-47.8796882629 -26.2388248444,1.56005978584,-47.8139953613 -26.3887271881,1.55997753143,-47.729309082 -26.5396308899,1.5598962307,-47.6466255188 -26.6105747223,1.55985248089,-47.596786499 -26.7464580536,1.55876171589,-47.4871139526 -26.9213981628,1.56069684029,-47.4484100342 -27.0913314819,1.56162762642,-47.3987121582 -27.2602615356,1.56255793571,-47.3470115662 -27.4241847992,1.56348562241,-47.2873153687 -27.5780906677,1.56340610981,-47.2076339722 -27.6380195618,1.56235635281,-47.1388053894 -27.7468681335,1.56025159359,-46.9851570129 -27.8627204895,1.55815029144,-46.841506958 -27.9715690613,1.55504655838,-46.6888618469 -28.0984401703,1.55395317078,-46.5661964417 -28.2323246002,1.55286478996,-46.4565353394 -28.3702144623,1.5527780056,-46.3518638611 -28.379076004,1.54870152473,-46.2020797729 -28.5259780884,1.54862129688,-46.114402771 -28.6518535614,1.54752957821,-45.9927444458 -28.7446842194,1.54342019558,-45.8181114197 -28.8745651245,1.54233181477,-45.7044487 -29.0815486908,1.54628515244,-45.713722229 -29.2426128387,1.5522916317,-45.8078117371 -29.4616088867,1.55625009537,-45.8330726624 -29.6695899963,1.56020152569,-45.838344574 -29.8955898285,1.56416201591,-45.8706054688 -30.1376113892,1.57012975216,-45.9258537292 -30.3696174622,1.575091362,-45.9631080627 -29.908082962,1.51933693886,-44.1860618591 -31.4895343781,1.35752224922,-36.831703186 -31.6565876007,1.36252331734,-36.9107933044 -31.9931030273,1.35620701313,-36.3643188477 -23.2990341187,0.919326603413,-25.9702968597 -23.3929824829,0.920283615589,-25.9106616974 -23.493938446,0.921242833138,-25.8590202332 -23.5968952179,0.922201812267,-25.8073825836 -23.6908435822,0.922158718109,-25.7467498779 -23.8098125458,0.924123167992,-25.714094162 -23.7687110901,0.920076191425,-25.58634758 -35.5833969116,1.47730910778,-38.2295646667 -35.6852798462,1.47622966766,-38.0969352722 -35.8111801147,1.47615742683,-37.9912910461 -33.6812477112,1.37047708035,-35.4863967896 -33.7541236877,1.36839807034,-35.3387947083 -36.0407676697,1.46990263462,-37.5174713135 -35.9796218872,1.46483445168,-37.3347434998 -36.028465271,1.46174371243,-37.1501617432 -36.0673027039,1.45765089989,-36.9555854797 -36.1061401367,1.4535586834,-36.762008667 -36.1469802856,1.45046770573,-36.5714302063 -36.2048377991,1.44738185406,-36.3998374939 -36.271697998,1.44529879093,-36.2382392883 -36.2786064148,1.44325089455,-36.1304626465 -36.3915100098,1.44317913055,-36.0148277283 -36.3362808228,1.43506836891,-35.7333221436 -36.5652694702,1.44002461433,-35.7336006165 -36.6511459351,1.43894743919,-35.5919914246 -36.7390289307,1.43787145615,-35.45337677 -36.8379173279,1.4367980957,-35.3257522583 -36.8608436584,1.43575549126,-35.2359619141 -26.2040290833,0.95531886816,-24.7955112457 -26.2849655151,0.956272304058,-24.7148952484 -26.0496807098,0.942158460617,-24.335515976 -24.4543361664,0.864702224731,-22.5376033783 -23.0312480927,0.799352049828,-21.0711231232 -22.9821643829,0.795316040516,-20.9593772888 -22.7148838043,0.781210064888,-20.5800189972 -22.2774906158,0.759072065353,-20.0487880707 -21.6369686127,0.727897286415,-19.3397045135 -21.2165985107,0.707768619061,-18.8364601135 -20.6401309967,0.679612696171,-18.1983318329 -20.4869880676,0.671561896801,-18.0036640167 -20.5509490967,0.672530710697,-17.9450531006 -18.5095443726,0.582111001015,-16.0270195007 -18.4174137115,0.57605701685,-15.8435220718 -18.2682476044,0.566993355751,-15.6110696793 -17.8869400024,0.548890113831,-15.1807861328 -17.4325885773,0.527776181698,-14.6915597916 -16.9542560577,0.506676852703,-14.2341308594 -16.5709590912,0.488579422235,-13.8148517609 -16.5668983459,0.486548185349,-13.7222862244 -16.4327583313,0.478495776653,-13.5208158493 -8.23572731018,0.13312792778,-6.57243013382 -8.22770595551,0.132117047906,-6.52285432816 -8.31973552704,0.135117322206,-6.53441381454 -8.33973026276,0.135110720992,-6.50682830811 -8.36272621155,0.135104745626,-6.482234478 -8.39672851562,0.135100483894,-6.46663236618 -8.41272258759,0.135093659163,-6.43703699112 -8.44072151184,0.135088294744,-6.41544914246 -8.43370914459,0.134082749486,-6.38866424561 -8.47171497345,0.135079115629,-6.37605762482 -8.49771308899,0.135073661804,-6.35346460342 -8.53371620178,0.136069878936,-6.33985137939 -8.54370594025,0.136062189937,-6.30427503586 -8.57270717621,0.136057391763,-6.28467178345 -8.6047077179,0.136052727699,-6.26607847214 -8.62771224976,0.137051343918,-6.26227378845 -8.64770793915,0.137045383453,-6.23567676544 -8.67470741272,0.137040302157,-6.21407699585 -8.6997051239,0.137034893036,-6.19048309326 -8.72370243073,0.137029334903,-6.16589212418 -8.74669933319,0.1380238235,-6.14129447937 -8.77569961548,0.138018786907,-6.11970567703 -8.78969955444,0.138016492128,-6.10989809036 -8.81969928741,0.138011664152,-6.08930540085 -8.83469295502,0.138005331159,-6.05871391296 -8.8666934967,0.139000698924,-6.03912210464 -8.89769554138,0.13899628818,-6.02051353455 -9.0297460556,0.144002303481,-6.07184314728 -8.93068313599,0.138984009624,-5.96034002304 -8.95368671417,0.138982474804,-5.95553731918 -8.98969078064,0.139978379011,-5.93893671036 -8.99467945099,0.138971298933,-5.90135335922 -9.0486907959,0.1409689188,-5.89674186707 -9.06568527222,0.140963032842,-5.86715221405 -9.10168838501,0.140958994627,-5.85054779053 -9.13268852234,0.141954377294,-5.82995128632 -9.14068603516,0.141951501369,-5.81515312195 -9.20970439911,0.143950223923,-5.81953144073 -9.15166473389,0.140938088298,-5.74098730087 -9.17766284943,0.140933051705,-5.71640110016 -9.25668621063,0.142932668328,-5.72776174545 -9.28268432617,0.143927633762,-5.70317173004 -13.48350811,0.302245765924,-8.33181095123 -13.3824367523,0.297223567963,-8.20831012726 -13.3313875198,0.294205695391,-8.11777305603 -13.3283596039,0.293191671371,-8.05820083618 -13.1492567062,0.285165220499,-7.88875627518 -13.0371837616,0.280144095421,-7.76226472855 -13.2182483673,0.287150174379,-7.84634780884 -12.986125946,0.277121603489,-7.64793539047 -13.1431665421,0.282119125128,-7.68725728989 -13.0841178894,0.279102683067,-7.59572553635 -13.1341123581,0.280093312263,-7.57011890411 -13.0580587387,0.276076197624,-7.46860551834 -13.2090950012,0.281073093414,-7.50391960144 -13.2420959473,0.281068712473,-7.49511480331 -13.2220640182,0.280055314302,-7.42755889893 -13.2270421982,0.27904343605,-7.37498569489 -13.2850408554,0.280034780502,-7.35436582565 -13.2049875259,0.277018636465,-7.25285434723 -13.2289733887,0.277008265257,-7.2122631073 -13.1759319305,0.273994207382,-7.12772941589 -13.2149343491,0.274990409613,-7.12291431427 -13.4009809494,0.280987411737,-7.17221641541 -13.1968841553,0.271967113018,-7.00478410721 -13.261885643,0.273958683014,-6.98617267609 -13.2788705826,0.273948580027,-6.94258213043 -13.3108596802,0.27393886447,-6.90599060059 -13.5719432831,0.282943367958,-7.0200252533 -13.4818887711,0.27892896533,-6.91751384735 -13.4408521652,0.276916503906,-6.84097576141 -13.4398317337,0.275905936956,-6.78740024567 -13.4678192139,0.27589610219,-6.74781560898 -13.5108137131,0.276886999607,-6.71721076965 -14.7852230072,0.321913123131,-7.31977939606 -14.6891784668,0.317904263735,-7.24106121063 -14.6751499176,0.31689196825,-7.17649745941 -13.6597900391,0.278854876757,-6.60660791397 -13.6347618103,0.277844160795,-6.54105043411 -13.7747879028,0.281837135553,-6.55738639832 -13.7527599335,0.280826538801,-6.49283123016 -13.6377029419,0.275814384222,-6.38333654404 -13.6807060242,0.276810228825,-6.37752532959 -13.6386737823,0.274799913168,-6.30497789383 -13.7346849442,0.276791810989,-6.29834508896 -13.9047174454,0.282784700394,-6.32665967941 -14.0177326202,0.285776466131,-6.32701253891 -13.9837026596,0.283766537905,-6.25845813751 -13.853644371,0.27875572443,-6.14497327805 -13.6195640564,0.269748747349,-6.00935268402 -13.9136343002,0.279742330313,-6.0935792923 -14.0836648941,0.284734338522,-6.11889219284 -14.0016212463,0.280724555254,-6.02838039398 -14.1006307602,0.283715814352,-6.01974725723 -14.1366224289,0.284706860781,-5.98315143585 -14.4006881714,0.293702751398,-6.07319355011 -14.5827198029,0.298693716526,-6.10049438477 -14.6067066193,0.298684120178,-6.05591535568 -14.589682579,0.297674775124,-5.99435663223 -14.7176990509,0.301665216684,-5.99569797516 -14.7136774063,0.30065587163,-5.93913602829 -14.7126588821,0.299646854401,-5.88555860519 -15.3058052063,0.320638090372,-6.10539484024 -15.4198150635,0.323627471924,-6.09674930573 -15.5018157959,0.325616896152,-6.07412672043 -15.756860733,0.333604425192,-6.12139225006 -15.7828464508,0.333594173193,-6.0748052597 -17.5182628632,0.392561256886,-6.71012401581 -17.5682487488,0.393548607826,-6.66652441025 -17.6102466583,0.394542068243,-6.65171146393 -17.6522312164,0.395529448986,-6.60412073135 -17.7022190094,0.396516859531,-6.56051778793 -17.7642097473,0.398503988981,-6.52091026306 -17.802192688,0.398491442204,-6.47132205963 -17.8531799316,0.399478882551,-6.42771720886 -17.9101696014,0.400466024876,-6.38511562347 -17.9451637268,0.401459485292,-6.36630964279 -17.9841480255,0.402447044849,-6.31671905518 -18.0441360474,0.403434157372,-6.27511262894 -18.0871238708,0.404421627522,-6.22652053833 -18.145111084,0.405408829451,-6.18391418457 -18.199098587,0.406396061182,-6.1393122673 -18.2320919037,0.407389432192,-6.11851119995 -18.2780799866,0.408376932144,-6.07091379166 -18.3410682678,0.410363823175,-6.02830934525 -18.3900547028,0.410351127386,-5.98071432114 -18.4340400696,0.411338806152,-5.93211603165 -18.4950294495,0.413325756788,-5.88851070404 -18.5370121002,0.41331332922,-5.8379201889 -18.5800113678,0.415306389332,-5.82010889053 -18.6359977722,0.416293442249,-5.77351140976 -18.6869831085,0.417280763388,-5.72591161728 -18.7319698334,0.418268412352,-5.67631435394 -18.7929573059,0.419255256653,-5.63071346283 -18.8359413147,0.420242965221,-5.58011722565 -18.8809394836,0.421235889196,-5.56230354309 -18.9439277649,0.423222631216,-5.51670026779 -18.9849128723,0.424210309982,-5.46411132812 -19.0389003754,0.425197511911,-5.4155125618 -19.0948867798,0.426184654236,-5.36790847778 -19.1508731842,0.427171707153,-5.31930923462 -19.1928577423,0.428159505129,-5.26671648026 -19.2478561401,0.430151700974,-5.24990129471 -19.295841217,0.431139111519,-5.19830751419 -19.3478279114,0.432126402855,-5.14771080017 -19.4048137665,0.433113515377,-5.09910583496 -19.4507980347,0.434100985527,-5.04551839828 -19.5097846985,0.436087965965,-4.9969124794 -19.5627727509,0.437075138092,-4.94531726837 -19.6187705994,0.43806707859,-4.92750072479 -19.6657543182,0.439054727554,-4.87490272522 -19.7337436676,0.441040992737,-4.8263001442 -19.7787284851,0.44202876091,-4.77270364761 -19.8337154388,0.443015724421,-4.72011041641 -19.8896999359,0.445002824068,-4.6685090065 -19.9376869202,0.44599044323,-4.61491107941 -19.9866809845,0.44698253274,-4.59310436249 -20.0486698151,0.448969244957,-4.54249811172 -20.1036548615,0.44995623827,-4.48890352249 -20.163640976,0.450942963362,-4.43630504608 -20.2266273499,0.45292955637,-4.38470077515 -20.2826137543,0.453916549683,-4.33110189438 -20.3266086578,0.455908924341,-4.30729579926 -20.3935966492,0.456895142794,-4.25569057465 -20.4585838318,0.458881497383,-4.20308732986 -20.5055675507,0.459869146347,-4.14649391174 -20.5635528564,0.461856007576,-4.09189414978 -20.6265392303,0.462842494249,-4.03829097748 -20.680524826,0.464829564095,-3.98169803619 -20.7365207672,0.465821027756,-3.95988035202 -20.7925071716,0.467807918787,-3.90328526497 -20.8584918976,0.468794137239,-3.84868359566 -20.9264793396,0.470780104399,-3.79408073425 -20.982465744,0.471767127514,-3.73748064041 -21.0374507904,0.473754167557,-3.67988467216 -21.1044368744,0.475740253925,-3.6242814064 -21.1584300995,0.476731538773,-3.5994720459 -21.2074146271,0.477719157934,-3.54087424278 -21.2804031372,0.479704678059,-3.48526883125 -21.3453865051,0.481690824032,-3.42766952515 -21.4193744659,0.483676284552,-3.37206029892 -21.4783592224,0.48566287756,-3.31246638298 -21.5363445282,0.486649602652,-3.25287055969 -21.5873394012,0.488641142845,-3.2270565033 -21.659324646,0.490626692772,-3.16945075989 -21.7173080444,0.491613388062,-3.10885620117 -21.7872962952,0.493599057198,-3.05025148392 -21.8282775879,0.494587242603,-2.98666524887 -21.9242668152,0.497570604086,-2.93104696274 -21.9542598724,0.498563826084,-2.90024924278 -16.3187885284,0.316070228815,-2.03984165192 -16.2537727356,0.314072906971,-1.97930693626 -16.2157611847,0.313073188066,-1.92176568508 -16.1327457428,0.31007796526,-1.86023640633 -16.1297359467,0.309075325727,-1.80866909027 -16.1057262421,0.308074712753,-1.75411713123 -16.1227226257,0.309071719646,-1.73131775856 -16.061712265,0.307074844837,-1.67278409004 -16.0757045746,0.307070821524,-1.62321031094 -16.0616950989,0.306069642305,-1.571641922 -16.0666866302,0.306066632271,-1.52107310295 -16.086681366,0.307062208652,-1.47249257565 -16.152677536,0.309053212404,-1.42888426781 -16.1216716766,0.308055132627,-1.40011787415 -16.2286701202,0.311041921377,-1.35949325562 -16.2376613617,0.311038702726,-1.30991339684 -16.3336601257,0.314026534557,-1.26729488373 -16.3596553802,0.315021574497,-1.21870744228 -16.4326515198,0.317011713982,-1.17310237885 -22.1779136658,0.500404477119,-1.59842026234 -22.2009067535,0.501398861408,-1.56562483311 -22.2178897858,0.501390695572,-1.49705290794 -22.1898708344,0.500387430191,-1.42550230026 -9.70934867859,0.100732557476,-0.427164018154 -9.70335292816,0.100736215711,-0.396590173244 -9.69635486603,0.100738532841,-0.380809098482 -9.70036029816,0.100741133094,-0.351225554943 -9.68836402893,0.100745551288,-0.320651680231 -9.69936943054,0.100747480989,-0.291069954634 -9.69337463379,0.10075135529,-0.260498404503 -9.68237876892,0.0997558236122,-0.229927137494 -9.68838405609,0.0997584909201,-0.199358105659 -9.6923866272,0.0997596755624,-0.184566602111 -9.66839122772,0.0997657179832,-0.153996229172 -9.67739677429,0.0997680351138,-0.124413505197 -9.68440151215,0.0997707024217,-0.0938441380858 -9.67340755463,0.0997753441334,-0.0642622187734 -9.66541194916,0.0987798050046,-0.0336950682104 -9.6744184494,0.0997822359204,-0.00411096541211 -9.66842079163,0.0997847989202,0.0116650760174 -9.66342639923,0.0987889096141,0.0412456803024 -9.67043209076,0.0997916460037,0.0708299204707 -9.65643787384,0.0987970307469,0.101393125951 -9.66444396973,0.0987997055054,0.130977705121 -9.65744972229,0.0988043472171,0.161542654037 -9.64745521545,0.0988092795014,0.191119521856 -9.64945793152,0.0988109111786,0.205911055207 -9.65946483612,0.0988135635853,0.236483603716 -9.64047050476,0.098819732666,0.266054332256 -9.64447593689,0.0988230705261,0.295637637377 -9.65248298645,0.0988260582089,0.326209962368 -9.64448928833,0.0988309830427,0.355785757303 -9.63949203491,0.0988335907459,0.370572686195 -9.64349937439,0.0988371670246,0.401142686605 -9.6325044632,0.0978426039219,0.430714637041 -9.63751125336,0.0988459736109,0.460299909115 -9.63351821899,0.0978505685925,0.489877045155 -9.63052463531,0.0978552028537,0.520441174507 -9.63553142548,0.0988586470485,0.550027251244 -9.6385345459,0.0988603159785,0.564820826054 -9.62554168701,0.0978662669659,0.594388306141 -9.62054824829,0.0978711694479,0.623963773251 -9.61855506897,0.0978756994009,0.653542339802 -9.62556171417,0.0978791415691,0.684117436409 -9.61356925964,0.0978851392865,0.713684082031 -9.61657333374,0.0978868827224,0.728478252888 -9.61558055878,0.0978913828731,0.758058071136 -9.62358665466,0.098894752562,0.788636207581 -9.60559558868,0.0979017838836,0.818193018436 -9.59960174561,0.0979071110487,0.847765684128 -9.65560817719,0.0999039486051,0.881372928619 -9.51361942291,0.0949279889464,0.900882065296 -9.52062320709,0.0959294065833,0.916667759418 -9.5066318512,0.0949360057712,0.945237755775 -9.5136384964,0.0949396342039,0.974826753139 -9.51164722443,0.0949446409941,1.00440168381 -9.51665496826,0.0959487557411,1.03497481346 -9.51066207886,0.0959542840719,1.06355726719 -9.50967025757,0.0959593877196,1.09412026405 -9.51367378235,0.0959611684084,1.10891699791 -9.50668239594,0.0959670990705,1.1384832859 -9.50768947601,0.0959717929363,1.16806447506 -9.51069736481,0.0959761962295,1.19764983654 -9.50970649719,0.0959812626243,1.22722792625 -9.49871444702,0.095987983048,1.2567858696 -9.5027179718,0.0959898084402,1.27158415318 -9.49572658539,0.0959959328175,1.30114984512 -9.48973560333,0.0960017666221,1.32973146439 -9.49074459076,0.0960066393018,1.35931408405 -9.48875236511,0.0960122048855,1.38987660408 -9.4907617569,0.0960169509053,1.41946208477 -9.49076938629,0.0960220620036,1.44904351234 -9.48077487946,0.0960261598229,1.4628251791 -9.48878192902,0.096030279994,1.49439775944 -9.47479152679,0.0960375219584,1.52197420597 -9.4828004837,0.0970416888595,1.55354821682 -9.47580909729,0.0960479527712,1.58212721348 -9.48181724548,0.0970524996519,1.61369776726 -9.46882724762,0.0970597192645,1.6412756443 -9.47483062744,0.0970614701509,1.65706884861 -9.47184085846,0.0970673114061,1.68664479256 -9.47384929657,0.0970724523067,1.7172203064 -9.48085784912,0.0970768854022,1.7487963438 -9.47386741638,0.0970833450556,1.77737617493 -9.46287727356,0.0970905721188,1.80594456196 -9.46088600159,0.0970963612199,1.83552420139 -9.46489143372,0.0980985239148,1.85131502151 -9.45890045166,0.0981050878763,1.8808836937 -9.46190929413,0.0981101766229,1.91146528721 -9.45891857147,0.0981162339449,1.94104325771 -9.4629278183,0.0981213450432,1.972615242 -9.45693778992,0.0981280207634,2.00218486786 -9.45194339752,0.0981315672398,2.01597714424 -9.45195293427,0.0981373116374,2.04655170441 -9.44496250153,0.098144069314,2.07513213158 -9.45197200775,0.0991488546133,2.10770273209 -9.44998168945,0.0991548672318,2.1372859478 -9.44399261475,0.0991616845131,2.16685652733 -9.44200134277,0.0991679280996,2.19742679596 -9.44400691986,0.0991705581546,2.2132153511 -9.44601631165,0.0991760268807,2.24380016327 -9.43902683258,0.0991831347346,2.27336812019 -9.42503833771,0.0991913229227,2.30093860626 -9.43204689026,0.100196018815,2.33252882957 -9.43305683136,0.100201956928,2.36409854889 -9.44106578827,0.100206643343,2.39668035507 -9.41807365417,0.100213341415,2.40646219254 -9.42708301544,0.100218042731,2.44003510475 -9.43309211731,0.101223178208,2.47261190414 -9.414103508,0.100232236087,2.4981906414 -9.42311286926,0.101236954331,2.53176665306 -9.43312263489,0.101241461933,2.56534790993 -9.42912864685,0.101245246828,2.58013129234 -9.41714000702,0.101253308356,2.60770988464 -9.41715049744,0.101259596646,2.63928103447 -9.41416072845,0.102266162634,2.6688683033 -9.41317176819,0.102272704244,2.70043683052 -9.4211807251,0.10227766633,2.73401594162 -9.4071931839,0.102286309004,2.76158642769 -9.41319847107,0.103288352489,2.77838492393 -9.42620658875,0.103292614222,2.81396055222 -9.40421962738,0.103302709758,2.83952498436 -9.41522979736,0.103307232261,2.87410783768 -9.42523956299,0.104311965406,2.90868806839 -9.4152507782,0.104320034385,2.93726372719 -9.4192609787,0.104325741529,2.96984672546 -9.42826557159,0.105327494442,2.98863649368 -9.42527675629,0.105334401131,3.01921725273 -9.4282875061,0.105340540409,3.05278587341 -9.4322977066,0.106346257031,3.0853729248 -9.43030834198,0.10635317117,3.11694741249 -9.42132091522,0.106361337006,3.14651703835 -9.43133068085,0.107366248965,3.18209528923 -9.4053401947,0.106374025345,3.18987298012 -9.43434715271,0.107375659049,3.2314620018 -9.46235466003,0.109377481043,3.27305006981 -9.45436668396,0.109385453165,3.3026278019 -9.4483795166,0.109393179417,3.33320212364 -9.45139026642,0.109399348497,3.36678099632 -9.44639587402,0.109403602779,3.38156557083 -9.44440746307,0.11041059345,3.41314792633 -9.44541835785,0.11041726172,3.44671940804 -9.43343162537,0.11042612046,3.47529268265 -9.44544124603,0.111430712044,3.51188158989 -9.43445491791,0.111439570785,3.54144787788 -9.4314661026,0.111446864903,3.57302856445 -9.42647266388,0.11145118624,3.58781456947 -9.4394826889,0.112455919385,3.62638807297 -9.42349624634,0.11246548593,3.65296840668 -9.41950893402,0.112473279238,3.68553376198 -9.42951869965,0.112478345633,3.72212123871 -9.41653156281,0.112487629056,3.75069236755 -9.41753864288,0.113491088152,3.76847314835 -9.42354869843,0.113496959209,3.80405569077 -9.41156196594,0.113506034017,3.83263301849 -9.41557407379,0.114512421191,3.8682076931 -9.41258621216,0.114520020783,3.90078353882 -9.39960002899,0.114529415965,3.92935657501 -9.40760993958,0.115534976125,3.96594333649 -9.41261577606,0.115537792444,3.98572421074 -9.39863014221,0.115547500551,4.01429319382 -9.3946428299,0.115555197001,4.04587936401 -9.39465522766,0.116562455893,4.08045148849 -9.39166736603,0.116570107639,4.11303281784 -9.38468074799,0.116578631103,4.14460468292 -9.37969398499,0.117586843669,4.17717647552 -9.38969802856,0.117588713765,4.19896554947 -9.37571239471,0.117598332465,4.22654914856 -9.38072490692,0.11860486865,4.26411819458 -9.37873649597,0.118612483144,4.29769849777 -9.37174987793,0.118621066213,4.32927417755 -9.37076282501,0.119628630579,4.36384963989 -9.36877632141,0.119636468589,4.39841985703 -9.36978149414,0.119639933109,4.41621160507 -9.36879444122,0.120647497475,4.4507894516 -9.3608083725,0.120656400919,4.48236322403 -9.36182117462,0.120663613081,4.51794290543 -9.36183357239,0.121671110392,4.55351829529 -9.35384750366,0.121680028737,4.5850944519 -9.36085224152,0.122682623565,4.6068778038 -9.36186504364,0.122689828277,4.64246225357 -9.35487937927,0.122698679566,4.67503499985 -9.34989261627,0.123706966639,4.70762062073 -9.34790611267,0.123715020716,4.74318981171 -9.34191894531,0.124723829329,4.77675962448 -9.3329334259,0.124733090401,4.80833482742 -9.34893703461,0.125733852386,4.83413267136 -9.3429517746,0.125742644072,4.86770486832 -9.340965271,0.1257507056,4.90327978134 -9.33797836304,0.12675884366,4.93786144257 -9.33199214935,0.126767665148,4.97143602371 -9.33300495148,0.127775236964,5.00901079178 -9.32501888275,0.127784445882,5.04158639908 -9.3310251236,0.127787217498,5.06337499619 -9.32803916931,0.128795564175,5.09895038605 -9.32805156708,0.12880320847,5.1355342865 -9.32506561279,0.129811540246,5.17111206055 -9.31408119202,0.129821464419,5.20268440247 -9.32309246063,0.130827620625,5.24526262283 -9.31809997559,0.130832627416,5.26204204559 -9.31311416626,0.131841346622,5.29662179947 -9.31212806702,0.131849467754,5.33419513702 -9.30614185333,0.131858497858,5.36877059937 -9.30615520477,0.132866308093,5.40635347366 -9.31016921997,0.133873492479,5.44693088531 -9.29718399048,0.133883848786,5.47750759125 -9.30219078064,0.133887022734,5.50029039383 -9.30620288849,0.134894177318,5.54087209702 -9.29621887207,0.135904014111,5.57344913483 -9.29623222351,0.135911986232,5.61202859879 -9.29124736786,0.136921092868,5.64859771729 -9.28726100922,0.136929869652,5.68517494202 -9.28726768494,0.13693395257,5.7049612999 -9.28728103638,0.137941882014,5.7435464859 -9.28129673004,0.138951271772,5.78011369705 -9.27731132507,0.138960033655,5.81669473648 -9.27132606506,0.138969436288,5.85326385498 -9.26834106445,0.139978080988,5.89084482193 -9.26435565948,0.140987038612,5.92841911316 -9.27536010742,0.140988960862,5.95521259308 -9.265376091,0.141999021173,5.98879098892 -9.26239013672,0.142007827759,6.02736568451 -9.26540374756,0.143015503883,6.06994247437 -9.25541973114,0.143025740981,6.1045126915 -9.25543403625,0.144033953547,6.14509248734 -9.25844764709,0.145041570067,6.1876745224 -9.26045417786,0.145045310259,6.20946455002 -9.2514705658,0.146055400372,6.24503612518 -9.25548362732,0.147062838078,6.28861951828 -9.24450016022,0.1470733881,6.32318973541 -9.24451446533,0.148081704974,6.36476802826 -9.23952960968,0.148091062903,6.40334272385 -9.22654628754,0.149102076888,6.43691253662 -9.24354934692,0.150102764368,6.46871519089 -9.23856544495,0.15011228621,6.50828409195 -9.22458267212,0.150123402476,6.54085874557 -9.22759628296,0.151131227612,6.58543872833 -9.22661113739,0.152139976621,6.62801122665 -9.21662807465,0.152150347829,6.66358852386 -9.22263336182,0.153153404593,6.68937969208 -9.22264766693,0.154161944985,6.73295402527 -9.2086648941,0.154173061252,6.76553487778 -9.21067905426,0.155181288719,6.81110811234 -9.21169471741,0.156189650297,6.85568523407 -9.20071029663,0.156200304627,6.89126253128 -9.19672679901,0.157209739089,6.93283557892 -9.21073055267,0.158211126924,6.964635849 -9.19075012207,0.158223673701,6.99420690536 -9.19176387787,0.159232139587,7.03978300095 -9.18078136444,0.15924295783,7.07635688782 -9.10581302643,0.15726660192,7.06490564346 -9.03884220123,0.15528857708,7.05846261978 -9.09785175323,0.159289821982,7.17085123062 -9.02788257599,0.157312586904,7.16240167618 -8.97890853882,0.156331017613,7.16896724701 -8.91893672943,0.155351862311,7.16752099991 -8.91995239258,0.156360566616,7.21409273148 -8.9149684906,0.156370207667,7.25467634201 -8.90898418427,0.157380178571,7.2952542305 -8.91399097443,0.158383771777,7.32303667068 -8.96899414062,0.161381423473,7.41263961792 -9.02099704742,0.164379805326,7.50123548508 -9.12298870087,0.169368192554,7.63184499741 -9.14099979401,0.171373441815,7.69442844391 -9.12801742554,0.171384960413,7.73199939728 -9.1600189209,0.173382982612,7.78279781342 -9.1440372467,0.173394978046,7.81737518311 -9.14705181122,0.175403341651,7.86895132065 -9.13806915283,0.175414100289,7.91052436829 -9.14808177948,0.177420958877,7.96810722351 -9.134100914,0.177432730794,8.00567913055 -9.17309951782,0.179429411888,8.06447792053 -9.12112617493,0.178448796272,8.06904315948 -9.25311088562,0.185431182384,8.23465919495 -9.27112293243,0.18743647635,8.30124473572 -9.27513694763,0.188444584608,8.35582637787 -9.24915790558,0.188459008932,8.385389328 -9.25617218018,0.189466521144,8.44297409058 -9.24418258667,0.189473539591,8.45875549316 -9.25719547272,0.191479861736,8.52234077454 -9.24621295929,0.192491292953,8.56590938568 -9.23123264313,0.192503288388,8.60448741913 -9.23124790192,0.193512454629,8.65806102753 -9.20027065277,0.193527802825,8.68263053894 -9.21828174591,0.195533305407,8.75321292877 -9.24328422546,0.197532713413,8.80301380157 -9.22030448914,0.197546496987,8.83558559418 -9.13035774231,0.196583196521,8.85971164703 -9.12437534332,0.197593554854,8.90828990936 -9.1323890686,0.198601096869,8.97087001801 -9.13541221619,0.200614377856,9.05723571777 -9.07844257355,0.199635148048,9.05679988861 -9.05846309662,0.199648544192,9.09336948395 -9.05947875977,0.201657533646,9.14995098114 -9.0444984436,0.201669886708,9.19152450562 -9.04251480103,0.202679738402,9.24709510803 -9.04852104187,0.203683063388,9.28089141846 -9.05153656006,0.205691799521,9.34146881104 -9.03355789185,0.205704838037,9.38103961945 -9.03157329559,0.206714555621,9.43661975861 -9.02958965302,0.208724379539,9.49319458008 -9.02260780334,0.209735065699,9.54377651215 -9.00462913513,0.209748193622,9.58434677124 -9.03562927246,0.211746498942,9.64614582062 -9.02364826202,0.212758436799,9.69371700287 -8.9776763916,0.212777346373,9.70527935028 -8.91370773315,0.210799723864,9.69584655762 -8.85673999786,0.209820836782,9.69440937042 -8.79877090454,0.207842379808,9.69296264648 -8.74480056763,0.206862822175,9.6935300827 -8.73481082916,0.207869574428,9.71231842041 -8.73182868958,0.208879634738,9.7688999176 -8.73084545135,0.209889367223,9.82847690582 -8.72286319733,0.210900604725,9.88105106354 -8.71288394928,0.211912244558,9.93162441254 -8.96683502197,0.225869849324,10.2812671661 -8.97984027863,0.226871967316,10.3280591965 -8.96885871887,0.228883728385,10.3796367645 -8.96787548065,0.229893505573,10.4432153702 -8.96089458466,0.230904445052,10.4997968674 -8.95091342926,0.231916323304,10.5553627014 -8.94693088531,0.233926638961,10.615945816 -8.93695068359,0.234938412905,10.6715164185 -8.95195388794,0.236939966679,10.7213182449 -8.9519701004,0.237949639559,10.788895607 -8.93699169159,0.238962471485,10.839466095 -8.93500995636,0.240972667933,10.906039238 -8.93102645874,0.241982981563,10.9686260223 -8.91804695129,0.242995366454,11.0222005844 -8.9860458374,0.247991174459,11.1757926941 -9.07303142548,0.253978192806,11.318602562 -3.4295539856,-0.0308472272009,4.38955307007 -3.40558099747,-0.0318318866193,4.38810825348 -3.39160346985,-0.0318194888532,4.39670467377 -3.40161991119,-0.0308118648827,4.43630027771 -8.90716743469,0.25506606698,11.5092391968 -8.8951883316,0.257078260183,11.5668182373 -8.89220523834,0.258088588715,11.6364002228 -8.88622379303,0.260099738836,11.7039728165 -8.87324523926,0.261112421751,11.7635402679 -8.86926364899,0.263122975826,11.8331241608 -8.86528110504,0.265133619308,11.9037046432 -8.87128829956,0.266137510538,11.9514865875 -8.86430740356,0.268148779869,12.0190658569 -8.86132526398,0.269159257412,12.0926456451 -8.84934520721,0.271171659231,12.1552200317 -8.84336471558,0.27318289876,12.2267942429 -8.83638381958,0.274194061756,12.2953805923 -8.84139060974,0.276198089123,12.3431663513 -8.8354101181,0.277209401131,12.4167385101 -8.83242797852,0.279220014811,12.4943151474 -8.82044792175,0.281232386827,12.5588941574 -8.81246852875,0.283244013786,12.6304702759 -8.8084859848,0.284254819155,12.7080497742 -8.79550743103,0.286267369986,12.7726297379 -8.80851173401,0.288269817829,12.8344182968 -8.80652999878,0.290280282497,12.9169960022 -8.79355144501,0.292293041945,12.9845695496 -8.78857040405,0.294304132462,13.0641460419 -8.7805891037,0.2953158319,13.1397237778 -8.77160930634,0.297327727079,13.214302063 -8.7656288147,0.29933911562,13.2948760986 -8.78163337708,0.301340848207,13.3636703491 -8.76565551758,0.303354293108,13.4302434921 -8.76467323303,0.305364608765,13.5198221207 -8.75469303131,0.307376891375,13.5973949432 -8.74371433258,0.309389263391,13.6729717255 -8.7357339859,0.31140100956,13.7535514832 -8.73375225067,0.314411610365,13.8451280594 -8.73776054382,0.315415889025,13.8989181519 -8.72978019714,0.317427664995,13.9814987183 -8.72379875183,0.320439100266,14.0690746307 -8.71082115173,0.321451961994,14.1456508636 -8.70384025574,0.324463665485,14.2332267761 -8.70285797119,0.326474070549,14.3308057785 -8.70986557007,0.328477859497,14.3935909271 -8.70188522339,0.330489635468,14.4801740646 -8.69490528107,0.333501368761,14.5707511902 -8.67992687225,0.335514634848,14.6483287811 -8.67294692993,0.337526410818,14.7409038544 -8.6619682312,0.339538961649,14.8274784088 -8.65198898315,0.342551380396,14.9170532227 -8.66899394989,0.344552993774,14.9988489151 -8.66101360321,0.347565025091,15.0934238434 -8.64803600311,0.34957793355,15.1790027618 -8.64505386353,0.352588891983,15.28358078 -8.63307571411,0.354601860046,15.3751506805 -8.61609840393,0.35661560297,15.4557323456 -8.63410282135,0.359617203474,15.5455207825 -8.62612247467,0.362629115582,15.6441020966 -8.61414432526,0.364642053843,15.7386741638 -8.60916423798,0.367653489113,15.8462524414 -8.59418678284,0.369666904211,15.9358301163 -8.58720684052,0.372678726912,16.0414085388 -8.57422828674,0.375691890717,16.1379833221 -8.59123325348,0.37869349122,16.2287807465 -8.57725524902,0.380706936121,16.3263511658 -8.57227516174,0.383718371391,16.4399318695 -8.56429481506,0.386730521917,16.5505065918 -8.55131816864,0.389743715525,16.6520824432 -8.53833961487,0.392756849527,16.7546596527 -8.52936077118,0.395769178867,16.866235733 -8.54136657715,0.398772001266,16.9550285339 -8.53238773346,0.401784330606,17.0686073303 -8.51940917969,0.404797434807,17.1751861572 -8.51642894745,0.407808750868,17.3057575226 -8.50245189667,0.410822063684,17.4123382568 -8.52446269989,0.416828095913,17.5949230194 -10.8727941513,0.592361032963,22.5868854523 -10.8238172531,0.591376364231,22.5756645203 -10.7088689804,0.588410556316,22.5172233582 -10.627910614,0.587437748909,22.5277881622 -10.5569486618,0.587462902069,22.5593547821 -10.5139808655,0.589482426643,22.651922226 -10.5020017624,0.594495594501,22.811498642 -10.5200052261,0.598497450352,22.9452857971 -10.5010290146,0.602512061596,23.0928630829 -10.1411533356,0.580595850945,22.4913825989 -10.105181694,0.582613945007,22.5989551544 -7.66292285919,0.397119820118,17.3121490479 -10.352145195,0.613585650921,23.5411472321 -10.1362276077,0.602640211582,23.2486915588 -7.55700111389,0.39916780591,17.4380836487 -7.46604776382,0.396196871996,17.3776493073 -7.41208219528,0.39621847868,17.402217865 -7.30313444138,0.392251223326,17.2977790833 -7.28915739059,0.395264595747,17.4143600464 -9.3005771637,0.566868841648,22.3802433014 -7.1042509079,0.389323294163,17.2764930725 -7.04227876663,0.386341124773,17.2022724152 -6.98931407928,0.386362433434,17.2258453369 -6.9293513298,0.386385321617,17.234413147 -6.90637683868,0.388400495052,17.3309955597 -9.29568099976,0.599929630756,23.4949226379 -6.74946308136,0.384453475475,17.2511310577 -6.70148706436,0.382468372583,17.2069168091 -6.64852237701,0.382489800453,17.2314853668 -6.58855962753,0.382512450218,17.2350616455 -6.52659845352,0.381535768509,17.2366275787 -6.46663570404,0.381558448076,17.2402000427 -6.41067171097,0.380580276251,17.2537765503 -6.3387131691,0.379605412483,17.2253475189 -6.30573272705,0.378617346287,17.2181339264 -6.20378351212,0.374648600817,17.1076984406 -6.10883188248,0.370678275824,17.0122642517 -6.10185337067,0.374690264463,17.1588497162 -6.01390028,0.3717187047,17.0834121704 -5.86696386337,0.362758696079,16.8339767456 -5.87398147583,0.368767917156,17.0235614777 -5.82400655746,0.365783214569,16.9643478394 -5.79603528976,0.368799448013,17.0559234619 -5.72107744217,0.366825193167,17.0114936829 -5.66311454773,0.365847319365,17.0130710602 -5.63014507294,0.367864698172,17.0936450958 -5.58817768097,0.369883716106,17.1462211609 -7.56558609009,0.575494766235,23.289270401 -4.15864467621,0.229185163975,12.9973831177 -4.1076798439,0.228205755353,12.9769611359 -4.06871271133,0.228224232793,12.9975309372 -6.94985151291,0.54066079855,22.3465175629 -7.16580533981,0.57162886858,23.2941226959 -7.08285045624,0.570656299591,23.2836933136 -7.03987360001,0.570670247078,23.2734775543 -6.95791816711,0.569697499275,23.266046524 -6.88196134567,0.568723320961,23.2756214142 -6.79600715637,0.567751288414,23.2531909943 -6.72005033493,0.566777169704,23.2627658844 -6.64009475708,0.56680393219,23.2593364716 -6.56113862991,0.565830349922,23.2569103241 -6.51416301727,0.564845085144,23.2306938171 -6.4402050972,0.564870536327,23.2462673187 -6.35625123978,0.562898039818,23.2258396149 -6.28129386902,0.562923669815,23.2374134064 -6.1993393898,0.561950802803,23.2259807587 -6.12238311768,0.560976803303,23.227558136 -6.03942871094,0.560003876686,23.2071304321 -6.00045108795,0.560016989708,23.2069168091 -5.91849565506,0.559043943882,23.1884899139 -5.84253978729,0.558069765568,23.1950626373 -5.76358413696,0.5570961833,23.1896324158 -5.46769571304,0.528164923191,22.3011856079 -5.60867214203,0.55614823103,23.1857814789 -5.56669521332,0.555161714554,23.1685714722 -5.48973941803,0.555187702179,23.1701431274 -5.4087843895,0.55421423912,23.1477222443 -5.3348274231,0.553239643574,23.1622924805 -5.25287342072,0.552266478539,23.1378669739 -5.17891645432,0.552291631699,23.1464443207 -5.10096120834,0.551317572594,23.1370201111 -5.08597564697,0.554325819016,23.239812851 -5.07399988174,0.56333899498,23.5383911133 -5.04602861404,0.57035523653,23.7669734955 -5.01105976105,0.577372789383,23.9705524445 -3.18764829636,0.301738321781,15.5469303131 -3.12968707085,0.299760192633,15.513504982 -3.09670805931,0.298771947622,15.4772901535 -3.05074238777,0.298791110516,15.4938793182 -3.00477790833,0.299810647964,15.5204524994 -2.96681022644,0.301828384399,15.5830364227 -2.92184519768,0.301847666502,15.61561203 -2.87687945366,0.302866637707,15.6411991119 -2.83591341972,0.303885161877,15.6977748871 -4.91027545929,0.6804895401,27.2907905579 -4.88330411911,0.691505610943,27.6363716125 -4.85633325577,0.702521622181,27.9919528961 -4.82236385345,0.712538957596,28.3215332031 -4.79339361191,0.724555313587,28.6891174316 -4.76142406464,0.73657232523,29.0606937408 -4.73045396805,0.747589051723,29.444278717 -4.74346065521,0.7605920434,29.8250694275 -4.70549297333,0.771610081196,30.1926517487 -4.67652225494,0.785626411438,30.6312351227 -4.6405544281,0.798644185066,31.0508117676 -4.60658597946,0.812661409378,31.492395401 -4.57061719894,0.826679110527,31.9449748993 -4.5346493721,0.841696739197,32.4125595093 -4.60263824463,0.868689239025,33.2723579407 -4.51068782806,0.871717512608,33.3779335022 -4.4717206955,0.887735724449,33.8885116577 -4.4297542572,0.903754472733,34.3970947266 -4.34480190277,0.909781455994,34.5956726074 -4.33882427216,0.936793446541,35.4452552795 -4.40881252289,0.969785630703,36.4840507507 -4.30786514282,0.973815500736,36.6086273193 -2.62443518639,0.55615490675,23.667673111 -2.54748010635,0.555179834366,23.6472549438 -2.47352433205,0.556204319,23.6608333588 -2.39456987381,0.554229617119,23.6204166412 -2.37458658218,0.560238599777,23.7952060699 -4.04808139801,1.13393449783,41.6719169617 -3.9431347847,1.14296495914,41.9624938965 -3.88817310333,1.1699860096,42.8120727539 -3.7652323246,1.17401969433,42.9516525269 -3.74625897408,1.21803402901,44.3252372742 -3.70428276062,1.22904729843,44.6670265198 -3.57834291458,1.23408138752,44.8456077576 -3.44940423965,1.23911607265,45.0131835938 -3.32246494293,1.24515044689,45.2167663574 -3.19452643394,1.25218486786,45.4303474426 -3.0635881424,1.2572196722,45.6069259644 -2.93165063858,1.26325488091,45.7995033264 -2.87267971039,1.27027094364,46.0012931824 -2.19491386414,0.984407067299,37.1008415222 -2.08197021484,0.986438333988,37.1764221191 -1.96302878857,0.985470712185,37.1390075684 -1.84008824825,0.980503737926,37.0085868835 -1.71414911747,0.974537312984,36.8221702576 -1.59420776367,0.971569657326,36.7267494202 -1.52523982525,0.962587475777,36.4495429993 -1.4232929945,0.973616480827,36.7871246338 -1.32334554195,0.987645089626,37.2287063599 -1.20540356636,0.986676871777,37.1942901611 -1.16943562031,1.07269358635,39.8988800049 -1.04449594021,1.07272648811,39.8914642334 -0.918556690216,1.07175970078,39.8850479126 -0.855587005615,1.07177627087,39.8778381348 -0.73064738512,1.07280910015,39.8914222717 -0.605707705021,1.07284188271,39.8980064392 -0.480768054724,1.07387471199,39.9365921021 -0.358827292919,1.08290672302,40.2231788635 -0.229889065027,1.07294011116,39.9217605591 -0.167918995023,1.07495641708,39.9605560303 -0.0439789779484,1.10898864269,41.0261421204 --0.0509761534631,1.4770128727,43.5988464355 --0.341842621565,1.56108510494,45.7850151062 --0.48977509141,1.57612144947,46.1595993042 --0.633708834648,1.57215714455,46.073184967 --0.772644221783,1.56019175053,45.7527732849 --0.841612040997,1.55420899391,45.5955657959 --0.982546746731,1.55024385452,45.4941558838 --1.12248182297,1.54627859592,45.3727416992 --1.2634165287,1.54331326485,45.300327301 --1.40235185623,1.53934764862,45.1999168396 --1.53928780556,1.53338158131,45.0395011902 --1.6822218895,1.53541648388,45.0660896301 --1.74719119072,1.53043270111,44.9388885498 --1.88512682915,1.52746653557,44.853477478 --2.02606153488,1.52650105953,44.833065033 --2.1599984169,1.52153408527,44.6856536865 --2.29993391037,1.52156805992,44.6802444458 --2.43587017059,1.51860129833,44.5968360901 --2.57280611992,1.51663458347,44.5284233093 --2.64677238464,1.5186522007,44.5922164917 --2.78470826149,1.51768553257,44.5498085022 --2.92364382744,1.51771903038,44.5324020386 --1.87191259861,0.765562534332,25.0672092438 --1.8729019165,0.746567368507,24.5720081329 --1.92886328697,0.73658657074,24.2965946198 --2.00281906128,0.735608875751,24.2601852417 --2.0757753849,0.73463088274,24.2197780609 --2.14873147011,0.732652902603,24.1703624725 --2.22568655014,0.733675479889,24.1809558868 --2.30764007568,0.735698997974,24.2375469208 --2.34561729431,0.735710263252,24.2253379822 --2.42557168007,0.736733257771,24.2599315643 --2.52951788902,0.747760415077,24.5155181885 --4.94174051285,1.59118354321,46.2521057129 --5.09067392349,1.59221744537,46.2737007141 --5.2466044426,1.59625256062,46.3502998352 --5.40753316879,1.60128843784,46.461894989 --5.50749206543,1.61030960083,46.6816902161 --5.68941402435,1.62134897709,46.9512863159 --5.86533880234,1.63038694859,47.1628875732 --6.02726793289,1.63442265987,47.254486084 --6.19019603729,1.63845837116,47.3480834961 --6.36212205887,1.64549565315,47.4946784973 --6.53604745865,1.65253293514,47.660282135 --6.63500642776,1.65955352783,47.8190803528 --6.80393362045,1.6645898819,47.9286766052 --6.96786165237,1.66762530804,47.9952735901 --7.14078760147,1.67366218567,48.1268768311 --7.31871175766,1.68069958687,48.2794761658 --7.50163459778,1.68873786926,48.4560775757 --7.49762535095,1.66874110699,47.9328727722 --7.64056062698,1.66677236557,47.8604736328 --7.78549528122,1.66580414772,47.8050727844 --7.94542551041,1.66783821583,47.8366775513 --7.37858104706,1.50275206566,43.5862503052 --7.44953918457,1.48777127266,43.1868476868 --7.57148075104,1.48479914665,43.0804443359 --7.6284532547,1.48281216621,43.0132446289 --7.7553935051,1.48084068298,42.9428482056 --7.8773355484,1.47786819935,42.8474464417 --7.41541862488,1.30281543732,38.3082084656 --7.76326036453,1.31189072132,38.481212616 --7.84321594238,1.30491113663,38.2588119507 --7.97115564346,1.30593931675,38.2704162598 --8.1440820694,1.31597447395,38.493019104 --8.20504379272,1.3049916029,38.189617157 --6.63749790192,0.991751074791,30.2179336548 --6.6694278717,0.947779417038,29.058719635 --6.75738096237,0.947801172733,29.0213184357 --6.84733295441,0.947823226452,28.9939155579 --6.89530849457,0.947834670544,28.9927158356 --6.9922580719,0.948857665062,28.9973163605 --7.0852098465,0.948879957199,28.9809131622 --7.17816114426,0.949902236462,28.9635124207 --7.26611423492,0.948923587799,28.9291133881 --7.36306428909,0.949946343899,28.9287128448 --7.45601606369,0.949968338013,28.9133110046 --7.49999284744,0.94997882843,28.8991146088 --7.59194469452,0.95000064373,28.8767127991 --7.35199832916,0.900970578194,27.6132926941 --7.41395998001,0.896987557411,27.5008964539 --7.39094686508,0.880991518497,27.0734844208 --7.36493492126,0.864994764328,26.6510810852 --7.02601909637,0.804949879646,25.1186523438 --7.00001716614,0.795949697495,24.8754482269 --7.03098773956,0.788961946964,24.6870441437 --7.07395505905,0.783976018429,24.5456428528 --7.41976070404,0.784062027931,24.4398441315 --7.49171924591,0.783080279827,24.4004421234 --7.57567405701,0.784100234509,24.3990440369 --7.65762996674,0.785119831562,24.3896427155 --7.73558616638,0.785138726234,24.3712444305 --8.26339626312,0.837228536606,25.6116790771 --8.34535312653,0.837247729301,25.5892791748 --8.17534637451,0.788243293762,24.2880516052 --8.26230144501,0.789263010025,24.2946567535 --8.38624382019,0.794288277626,24.404258728 --9.15382289886,0.795466601849,24.1372871399 --9.23677825928,0.796485006809,24.1268920898 --9.38571548462,0.803512692451,24.2855033875 --10.2564458847,0.89264023304,26.4123840332 --10.3713922501,0.895662605762,26.4599914551 --10.4873390198,0.899685025215,26.508600235 --13.4754123688,1.19111859798,33.4381103516 --13.4593992233,1.17812097073,33.0987091064 --13.45038414,1.16712450981,32.7783050537 --13.3833961487,1.15511727333,32.4710998535 --13.3683824539,1.14311993122,32.1456985474 --13.3393735886,1.13012051582,31.7942943573 --13.3313589096,1.11912417412,31.4978961945 --13.3153448105,1.10812652111,31.1844921112 --13.3053312302,1.0981297493,30.8930931091 --13.2413415909,1.0871232748,30.6108837128 --13.2263278961,1.076125741,30.3144836426 --13.2153139114,1.06612884998,30.0310821533 --13.2072992325,1.05613231659,29.758682251 --13.1852884293,1.04513406754,29.457277298 --13.1742734909,1.0351370573,29.185874939 --13.170258522,1.02714109421,28.9354782104 --13.1132659912,1.01713573933,28.6892681122 --13.1032514572,1.00813889503,28.4308700562 --13.0872392654,0.998141288757,28.1624679565 --13.0722265244,0.989143848419,27.8990631104 --13.0592126846,0.9801466465,27.6456642151 --13.0581960678,0.972151041031,27.4182624817 --13.040184021,0.963153123856,27.160861969 --12.9881906509,0.954148471355,26.9436531067 --12.9801769257,0.946151971817,26.7102508545 --12.9661626816,0.937154650688,26.4688491821 --12.9681453705,0.930159389973,26.2634506226 --12.9571313858,0.922162473202,26.0340480804 --9.13022613525,0.585667014122,18.2031650543 --9.12321949005,0.582669138908,18.1169605255 --9.15919113159,0.580679893494,18.0465621948 --9.2091588974,0.580692470074,18.0031604767 --9.27012252808,0.580706357956,17.9827690125 --9.31908988953,0.579718649387,17.9373683929 --9.39505004883,0.58173429966,17.9459762573 --9.46401309967,0.582749009132,17.9395828247 --9.52398586273,0.58575963974,17.9843883514 --12.841012001,0.853187263012,24.0634269714 --12.8509931564,0.847192823887,23.9010314941 --12.7580032349,0.834185481071,23.5486125946 --12.7259950638,0.825185835361,23.3152122498 --12.7619686127,0.822194635868,23.206817627 --12.8559246063,0.824210762978,23.2024269104 --12.9039030075,0.825218915939,23.2032337189 --12.9948596954,0.826234400272,23.1948490143 --13.294757843,0.844275712967,23.5554924011 --13.4077091217,0.847293674946,23.5811061859 --13.410692215,0.842297971249,23.4137058258 --13.5316410065,0.845316708088,23.454328537 --13.5796203613,0.846324503422,23.4521350861 --13.7135658264,0.851344704628,23.5107517242 --13.8675060272,0.857367098331,23.6033763885 --13.9954538345,0.861386239529,23.6499958038 --14.076415062,0.861399590969,23.6176128387 --14.1833686829,0.864416003227,23.6262264252 --14.2623310089,0.864428877831,23.5898418427 --14.3343029022,0.867439210415,23.6236515045 --14.468249321,0.871458411217,23.6762752533 --14.5092220306,0.869466602802,23.575881958 --12.6877174377,0.730255246162,20.4681930542 --12.7086954117,0.727261781693,20.3587989807 --12.8526382446,0.73228263855,20.4454193115 --12.7616481781,0.721276044846,20.1590061188 --12.7356472015,0.71727502346,20.0478019714 --12.7516269684,0.714280903339,19.9334030151 --12.9655504227,0.725309550762,20.1280384064 --12.8435688019,0.711299419403,19.7996139526 --12.9325284958,0.713313400745,19.8012332916 --12.9785003662,0.712322533131,19.7348384857 --12.8755207062,0.703312754631,19.5106201172 --12.698554039,0.686296582222,19.1101894379 --12.8105068207,0.69031304121,19.1478099823 --13.0454263687,0.702343285084,19.3654460907 --12.8684597015,0.685327231884,18.9730167389 --12.9454221725,0.687339603901,18.9566287994 --13.2673177719,0.704378902912,19.2982845306 --12.7964391708,0.670328676701,18.5490016937 --13.7241697311,0.729434549809,19.761762619 --12.4894914627,0.642302572727,17.8611488342 --12.5534582138,0.642313480377,17.8317584991 --12.5374469757,0.638315498829,17.6903553009 --12.489443779,0.631314218044,17.503944397 --12.6323900223,0.636333405972,17.5875720978 --12.7513494492,0.642348051071,17.694393158 --12.7963218689,0.642356514931,17.638999939 --12.8442935944,0.641365289688,17.5876064301 --13.615070343,0.688450396061,18.5213451385 --12.8622426987,0.63237786293,17.2654075623 --14.5617771149,0.740557312965,19.4875240326 --13.3740825653,0.659436404705,17.7779045105 --12.8642034531,0.623386859894,16.9854068756 --12.8821840286,0.621392130852,16.8990135193 --12.8771705627,0.617395162582,16.7816104889 --8.97019863129,0.366999238729,11.6024999619 --8.98617744446,0.366006314754,11.5470981598 --9.00116443634,0.366010576487,11.5278949738 --9.03213882446,0.365019053221,11.4924983978 --12.539191246,0.581376612186,15.8657407761 --12.6571445465,0.586391925812,15.9123659134 --12.7800970078,0.59040760994,15.9629878998 --12.8400659561,0.591416835785,15.9345998764 --12.7610721588,0.583412408829,15.7331800461 --12.8370456696,0.58642154932,15.7769994736 --13.1109580994,0.600451529026,16.0096492767 --13.2099180222,0.602464258671,16.0272693634 --13.2488927841,0.602471113205,15.9708747864 --13.1129131317,0.591461122036,15.7044458389 --13.1628856659,0.591468930244,15.6650619507 --13.2338600159,0.593477189541,15.6988754272 --13.4407920837,0.603499770164,15.8425149918 --13.3128099442,0.592490613461,15.590086937 --13.4447622299,0.597505807877,15.6447143555 --13.4627428055,0.595510303974,15.5663204193 --13.528711319,0.596519172192,15.5429344177 --20.2579669952,0.989139437675,23.1499557495 --20.3299446106,0.991145551205,23.1587753296 --20.4519023895,0.994155704975,23.1494064331 --13.9425563812,0.610566139221,15.6656227112 --20.6988162994,1.00017571449,23.1326732635 --20.8077812195,1.00218427181,23.107301712 --15.8420314789,0.711742162704,17.4698314667 --15.9040031433,0.711748957634,17.4264450073 --16.0029697418,0.715758323669,17.479265213 --16.0129547119,0.713760375977,17.3798732758 --16.0929222107,0.714768588543,17.3554897308 --12.0899190903,0.485423833132,12.9422216415 --12.0719099045,0.48142555356,12.8418207169 --12.0778942108,0.479429394007,12.7664194107 --12.0788784027,0.477432787418,12.6860160828 --12.1068639755,0.478436738253,12.6758241653 --12.1748323441,0.479445695877,12.6664381027 --12.2018117905,0.479451149702,12.6140422821 --12.1937990189,0.476453602314,12.5256376266 --12.1997833252,0.474457234144,12.4522371292 --12.1997699738,0.472460359335,12.3738384247 --12.1747674942,0.469459861517,12.3086299896 --12.167755127,0.467462360859,12.2242307663 --12.174738884,0.465466082096,12.1528263092 --12.1647281647,0.462468296289,12.0664253235 --12.1577157974,0.460470795631,11.9830226898 --12.1637001038,0.458474338055,11.9126214981 --12.1576881409,0.456476867199,11.8312177658 --12.1386852264,0.454476892948,11.77501297 --12.1386709213,0.452479869127,11.7006139755 --12.129658699,0.44948220253,11.6172075272 --12.1376428604,0.448485732079,11.5518112183 --12.1406288147,0.446488887072,11.4814119339 --12.1376152039,0.44449159503,11.4060125351 --12.1306028366,0.442494034767,11.3256015778 --12.1106014252,0.440493971109,11.271399498 --12.1005897522,0.437496125698,11.1899938583 --12.1035747528,0.436499238014,11.1215934753 --12.1065597534,0.434502273798,11.0541963577 --12.0885505676,0.431503862143,10.9667882919 --12.0975351334,0.430507302284,10.9053907394 --12.0995206833,0.428510248661,10.8379917145 --12.0815181732,0.426510423422,10.7857789993 --12.0735054016,0.424512624741,10.7103796005 --12.0854892731,0.423516243696,10.6519784927 --12.072479248,0.421518117189,10.5725746155 --12.0664663315,0.419520407915,10.5001754761 --12.06645298,0.417523145676,10.4327735901 --12.0444517136,0.415523022413,10.3795642853 --12.040438652,0.413525432348,10.3101663589 --12.0474233627,0.412528604269,10.2497653961 --12.0404119492,0.41053083539,10.177359581 --12.0403985977,0.408533453941,10.1119594574 --12.0403852463,0.407536119223,10.0465574265 --12.032374382,0.405538201332,9.97515487671 --12.0233688354,0.403538912535,9.93595600128 --12.0193567276,0.402541220188,9.8685541153 --12.0153446198,0.400543600321,9.80115032196 --12.0123319626,0.398545980453,9.73474597931 --12.0123186111,0.397548496723,9.67134380341 --12.0073060989,0.395550727844,9.6039390564 --12.0132923126,0.394553601742,9.54654121399 --11.9952888489,0.3925537467,9.50133800507 --11.9862785339,0.3905557096,9.43193340302 --11.9882650375,0.389558315277,9.37153053284 --11.981253624,0.387560337782,9.30513000488 --11.9762411118,0.385562509298,9.23972511292 --11.978228569,0.38456505537,9.18032264709 --11.984213829,0.383567780256,9.123919487 --11.9602127075,0.381567627192,9.07571411133 --11.9621992111,0.380570113659,9.01731300354 --11.9571866989,0.378572195768,8.95391082764 --11.9521760941,0.376574248075,8.89151287079 --12.0171489716,0.378580003977,8.88012313843 --12.0921201706,0.380586117506,8.87674331665 --5.57851743698,0.0672528743744,4.02173185349 --5.5945057869,0.0682569369674,4.01952838898 --5.58948993683,0.0672628730536,3.98913121223 --11.93409729,0.367588102818,8.49889469147 --11.935084343,0.366590350866,8.4424943924 --11.926074028,0.36459210515,8.37909030914 --11.913069725,0.36359256506,8.34188842773 --11.9090585709,0.361594587564,8.28147888184 --11.9070463181,0.360596597195,8.22407817841 --11.907034874,0.359598696232,8.16868019104 --11.9020233154,0.357600599527,8.10927677155 --11.8980102539,0.356602489948,8.05087280273 --11.8999986649,0.35560464859,7.99747467041 --11.8849954605,0.353605031967,7.95926618576 --11.8839826584,0.352607041597,7.90386581421 --11.8759727478,0.351608753204,7.84345769882 --11.8839588165,0.350611060858,7.79506349564 --11.8849468231,0.349613070488,7.74166250229 --11.8719358444,0.347614586353,7.67824983597 --11.873925209,0.346616566181,7.62685632706 --11.8559217453,0.345616877079,7.58764457703 --11.8569097519,0.344618827105,7.53524446487 --11.8618965149,0.343620896339,7.48584747314 --11.8518867493,0.341622412205,7.42644166946 --11.8508749008,0.340624272823,7.37303829193 --11.8568620682,0.339626312256,7.32464027405 --11.8478517532,0.338627815247,7.26723909378 --11.8518447876,0.337628871202,7.24303483963 --11.8408355713,0.336630314589,7.18362379074 --11.8408241272,0.335632055998,7.13323163986 --11.8328132629,0.333633571863,7.07682704926 --11.8298015594,0.332635223866,7.02342176437 --11.8317899704,0.331636995077,6.97402381897 --11.8337783813,0.330638766289,6.92361688614 --11.816775322,0.329639106989,6.88841199875 --11.8167638779,0.328640758991,6.8380112648 --11.8197517395,0.327642500401,6.78961133957 --11.8117418289,0.326643943787,6.73420238495 --11.8107299805,0.325645536184,6.68380069733 --11.8047199249,0.32464697957,6.63039541245 --11.8007097244,0.323648422956,6.57899570465 --11.7957048416,0.322649091482,6.55179548264 --11.7926940918,0.321650564671,6.50038957596 --11.7886829376,0.320652008057,6.44898509979 --11.7796726227,0.319653302431,6.39558410645 --11.8406515121,0.320656120777,6.38020038605 --11.8786325455,0.321658343077,6.3518075943 --11.8636302948,0.320658743382,6.31960439682 --11.8626194,0.319660067558,6.27120876312 --11.9056005478,0.320662289858,6.24481248856 --11.9855747223,0.323665052652,6.23944187164 --12.0715494156,0.326667845249,6.23505926132 --12.1425256729,0.328670173883,6.22368335724 --12.2265005112,0.331672608852,6.21830844879 --12.3364753723,0.335674852133,6.25014066696 --12.3664608002,0.335676193237,6.21675443649 --12.3524522781,0.334676831961,6.16034984589 --12.3884353638,0.335678130388,6.12895727158 --17.415561676,0.550743997097,8.59220027924 --17.4625473022,0.551741540432,8.54681968689 --17.5025348663,0.552738964558,8.49743366241 --17.5425243378,0.553737819195,8.48325157166 --12.3163919449,0.327681332827,5.82572793961 --12.3313789368,0.327682167292,5.78432703018 --12.3183708191,0.32568269968,5.72991991043 --12.3303594589,0.325683414936,5.68852901459 --12.3813409805,0.327684372663,5.66413974762 --17.8874340057,0.560718476772,8.2007932663 --17.9134254456,0.560714900494,8.14340209961 --14.8369188309,0.429697155952,6.66795969009 --14.7689218521,0.425695478916,6.58053827286 --14.6969251633,0.421693891287,6.4921169281 --14.620929718,0.417692303658,6.40168714523 --14.5559329987,0.41369086504,6.31827163696 --14.4839410782,0.410690128803,6.25804042816 --14.4079456329,0.406688809395,6.17061805725 --14.3379478455,0.402687579393,6.08619594574 --14.2699508667,0.398686438799,6.00277042389 --14.2079534531,0.395685344934,5.92335271835 --14.1289577484,0.391684412956,5.83692550659 --14.0799617767,0.388683974743,5.789706707 --11.7703046799,0.291691720486,4.77550792694 --11.7632961273,0.290692418814,4.7291059494 --11.7612867355,0.290693074465,4.68470335007 --11.6712903976,0.285694271326,4.60527610779 --11.6542825699,0.284695059061,4.55486345291 --11.6472740173,0.283695757389,4.50946187973 --11.6452693939,0.283696115017,4.48725986481 --11.6432600021,0.282696783543,4.4438586235 --11.6442508698,0.281697362661,4.40145492554 --11.6262435913,0.280698150396,4.35204696655 --11.6262340546,0.279698699713,4.3096446991 --11.6262245178,0.279699236155,4.26724100113 --11.6252155304,0.278699785471,4.22483968735 --11.6172113419,0.278700143099,4.20063400269 --11.6162023544,0.277700632811,4.15823078156 --11.6181926727,0.277701050043,4.11783647537 --11.6091852188,0.276701658964,4.07242774963 --11.6281719208,0.276701778173,4.03702688217 --11.6261634827,0.275702178478,3.99462342262 --11.6091575623,0.274702847004,3.94721627235 --11.6071519852,0.27470305562,3.92601656914 --11.6241407394,0.274703025818,3.89062070847 --11.6141328812,0.273703545332,3.84621834755 --11.6281223297,0.27370351553,3.80982160568 --11.6291131973,0.273703724146,3.7684135437 --11.6151065826,0.27270424366,3.72300934792 --11.6140966415,0.271704465151,3.68160533905 --11.603094101,0.270704805851,3.65739870071 --11.4841012955,0.265707939863,3.57795095444 --11.4880914688,0.265708059072,3.53955578804 --11.4970808029,0.26570802927,3.50215625763 --11.488073349,0.264708459377,3.45874619484 --11.4840660095,0.26370871067,3.41835141182 --11.4950551987,0.263708502054,3.38094472885 --11.4700536728,0.262709319592,3.35373806953 --11.4620456696,0.261709630489,3.31133055687 --11.4770355225,0.261709243059,3.27593207359 --11.4660282135,0.260709643364,3.23353075981 --11.4690198898,0.260709583759,3.19513201714 --11.4700107574,0.260709524155,3.15572810173 --11.4550046921,0.259710013866,3.11232304573 --11.4679985046,0.259709537029,3.09612464905 --11.4629898071,0.258709609509,3.05471324921 --11.4479846954,0.25771009922,3.01231503487 --11.4459762573,0.257710039616,2.97190380096 --11.4559659958,0.257709503174,2.93550467491 --11.4369602203,0.256710082293,2.89210176468 --11.4499511719,0.256709337234,2.85670518875 --11.4379482269,0.255709737539,2.83349275589 --11.4239416122,0.254710078239,2.79108476639 --11.4309329987,0.254709541798,2.75469017029 --11.4539222717,0.255708247423,2.72129106522 --11.4109182358,0.253709822893,2.67187047005 --11.376914978,0.251711040735,2.62545824051 --11.4039077759,0.252709656954,2.61327195168 --11.4268980026,0.25270819664,2.5798728466 --11.465886116,0.254705905914,2.55048298836 --11.5038747787,0.255703598261,2.5210981369 --11.5238656998,0.25570204854,2.48770928383 --11.551856041,0.25670003891,2.45531582832 --11.6418399811,0.259694755077,2.43695092201 --11.4918498993,0.253702163696,2.3836824894 --11.4938421249,0.253701448441,2.34628558159 --11.6988162994,0.261689692736,2.35196495056 --11.7288074493,0.262687206268,2.31957602501 --11.7577972412,0.263684600592,2.28618001938 --11.8027868271,0.264681071043,2.25679993629 --11.8317775726,0.265678286552,2.22340750694 --11.8547725677,0.266676396132,2.20821356773 --11.8857631683,0.267673403025,2.17583084106 --11.9247541428,0.268669784069,2.14343714714 --11.9657440186,0.269666016102,2.1120531559 --11.988735199,0.270663172007,2.07665705681 --12.0247268677,0.271659523249,2.04427409172 --12.0617179871,0.272655665874,2.01189184189 --12.0887126923,0.273653149605,1.9966994524 --12.1167049408,0.274649709463,1.96231234074 --12.1466970444,0.275646030903,1.92691361904 --12.1926879883,0.276641219854,1.89553678036 --12.2226800919,0.277637302876,1.86014187336 --12.2606725693,0.278632849455,1.82675921917 --12.2926654816,0.279628664255,1.79237580299 --12.3116607666,0.280626326799,1.77518093586 --12.3596525192,0.282620817423,1.74179196358 --12.3926448822,0.283616304398,1.7074123621 --12.4306373596,0.28461125493,1.67201900482 --12.4716300964,0.285605937243,1.63763511181 --12.5906181335,0.290594607592,1.61428642273 --12.630613327,0.29159027338,1.59909892082 --12.6816062927,0.293583840132,1.56572449207 --12.714600563,0.294578641653,1.52933943272 --12.7475938797,0.29557326436,1.4919462204 --12.7905874252,0.297567039728,1.45656621456 --12.8275814056,0.298561185598,1.4201836586 --12.862575531,0.299555361271,1.38279485703 --12.9165697098,0.301547855139,1.34741413593 --12.9455661774,0.302543878555,1.33022844791 --12.9495620728,0.302540361881,1.28882694244 --12.0726003647,0.268612295389,1.15205311775 --12.0545959473,0.267611503601,1.11063611507 --12.1895856857,0.272597312927,1.08629775047 --12.1775817871,0.271595865488,1.04588973522 --13.156537056,0.30950537324,1.10091114044 --13.1905345917,0.310500472784,1.08272242546 --13.1725311279,0.309498488903,1.03931820393 --13.2475271225,0.312487870455,1.00395154953 --12.9425354004,0.300512552261,0.93541508913 --12.2745552063,0.274572074413,0.838715910912 --13.2705183029,0.31347411871,0.878759205341 --13.4615106583,0.320453733206,0.871636867523 --12.0855522156,0.267583191395,0.726628124714 --12.1045475006,0.267578542233,0.689233183861 --13.1635131836,0.308470726013,0.723309099674 --13.639497757,0.326418966055,0.71212041378 --13.6494970322,0.327413320541,0.668719053268 --12.1485328674,0.269562512636,0.537648081779 --12.0935316086,0.266566693783,0.515425622463 --12.1155281067,0.267561405897,0.478033065796 --12.1055250168,0.267559379339,0.438623309135 --12.1255207062,0.267554163933,0.401232719421 --12.5665092468,0.284503698349,0.382027864456 --12.246512413,0.272534787655,0.329488009214 --12.1585102081,0.269541025162,0.287044972181 --12.1795082092,0.269537031651,0.267847210169 --12.1705064774,0.269534736872,0.229447767138 --12.1695041656,0.269531428814,0.190038323402 --12.1735010147,0.269527554512,0.151640176773 --12.1624984741,0.268525391817,0.113239176571 --12.1594953537,0.268522173166,0.0738286525011 --12.1694936752,0.269517511129,0.0354318134487 --12.1564912796,0.268517255783,0.0162285640836 --12.2024898529,0.27050819993,-0.0221559759229 --12.1874866486,0.269506365061,-0.0605593919754 --12.1514844894,0.26850694418,-0.0999829024076 --12.1234817505,0.267506659031,-0.138394832611 --12.1264801025,0.267502576113,-0.176794230938 --12.1224784851,0.26749932766,-0.215196982026 --12.1244773865,0.267497092485,-0.235406905413 --12.1114740372,0.266494899988,-0.273814707994 --12.0074720383,0.262504309416,-0.310255467892 --12.1134700775,0.266486883163,-0.350615829229 --12.1184692383,0.267482310534,-0.389013886452 --12.1224679947,0.267477810383,-0.427412003279 --12.1254653931,0.267473369837,-0.465810477734 --12.1204652786,0.26747199893,-0.485014498234 --12.1654644012,0.269461810589,-0.525401651859 --12.2024641037,0.270452678204,-0.564781308174 --12.1654615402,0.269453406334,-0.602199733257 --12.1504602432,0.268451094627,-0.64061164856 --12.1584587097,0.26944565773,-0.680014431477 --12.1834592819,0.270437806845,-0.719400405884 --12.1884593964,0.270434945822,-0.738594591618 --12.1964578629,0.270429283381,-0.77799487114 --12.1624565125,0.269429534674,-0.815416693687 --12.2124567032,0.271417856216,-0.856793701649 --12.005449295,0.263443112373,-0.883290588856 --12.4154624939,0.279378831387,-0.94750469923 --11.9864473343,0.262436896563,-0.959109008312 --12.1954555511,0.27140378952,-0.9922118783 --12.5214672089,0.283350527287,-1.05345416069 --12.0864496231,0.267410457134,-1.0620675087 --12.0494480133,0.265411347151,-1.09748327732 --11.9864444733,0.263416171074,-1.13091480732 --12.1414518356,0.269387602806,-1.18224525452 --11.9644432068,0.262412428856,-1.18652832508 --12.2604570389,0.27436158061,-1.2507904768 --12.035446167,0.265391558409,-1.27030682564 --12.0824489594,0.267379254103,-1.31268048286 --12.2414579391,0.273348808289,-1.36700820923 --12.220457077,0.273346811533,-1.40442323685 --12.1464529037,0.270353406668,-1.43585968018 --12.1944570541,0.27234300971,-1.46003401279 --12.1724557877,0.271341145039,-1.49745321274 --12.2874641418,0.276316821575,-1.54879379272 --16.8307590485,0.451555997133,-2.10290455818 --16.8967723846,0.454533487558,-2.16426634789 --16.9357852936,0.456515163183,-2.22364735603 --16.8877925873,0.454511582851,-2.27206873894 --16.9538021088,0.457494497299,-2.30723237991 --16.9298114777,0.456486731768,-2.35864186287 --16.4177818298,0.437563568354,-2.34630346298 --16.7058124542,0.448501944542,-2.43755125999 --16.9288406372,0.457450956106,-2.52183270454 --17.0118579865,0.461424022913,-2.58818817139 --16.4908256531,0.441504657269,-2.56885933876 --16.6428432465,0.447471648455,-2.61697506905 --16.2908248901,0.433523029089,-2.6195628643 --16.3208370209,0.43550619483,-2.67593860626 --16.4558582306,0.440469622612,-2.75027036667 --16.5128746033,0.443447172642,-2.81263875961 --14.4126901627,0.361825555563,-2.52712678909 --14.4356994629,0.362811744213,-2.57852101326 --14.6587238312,0.371765196323,-2.63860082626 --14.5207176208,0.366781502962,-2.66307330132 --14.5467281342,0.367766976357,-2.71445560455 --14.4967298508,0.366766631603,-2.75388789177 --14.3457221985,0.360786020756,-2.77436804771 --13.8376750946,0.341875404119,-2.72802877426 --13.9106893539,0.344852000475,-2.78739476204 --13.8496866226,0.341859430075,-2.79862546921 --13.7316799164,0.337873578072,-2.82209229469 --13.650677681,0.334880679846,-2.8515355587 --13.6056785583,0.333880871534,-2.88695430756 --13.6966953278,0.337853431702,-2.950309515 --13.6666994095,0.336850255728,-2.98972916603 --13.6367025375,0.335847318172,-3.02814102173 --13.5336933136,0.331863850355,-3.02939748764 --13.517698288,0.331858038902,-3.07080698013 --13.6037158966,0.335830897093,-3.13416266441 --13.5477151871,0.333833187819,-3.16759777069 --13.6347351074,0.33780542016,-3.23195242882 --13.5157260895,0.33282122016,-3.25041532516 --13.4767284393,0.331820040941,-3.28683972359 --13.4467277527,0.330821871758,-3.30205273628 --13.3687238693,0.32782933116,-3.32849311829 --13.4917488098,0.333792984486,-3.40283298492 --13.2677249908,0.324832469225,-3.39435482025 --13.2987365723,0.326816350222,-3.44573307037 --13.4087600708,0.331782221794,-3.51807975769 --13.2227363586,0.323818862438,-3.49437975883 --13.2747526169,0.326797693968,-3.55175065994 --14.1008853912,0.359601318836,-3.80669975281 --13.6498260498,0.342692881823,-3.73835039139 --13.1057500839,0.320807158947,-3.64204549789 --13.2397785187,0.326766520739,-3.72237753868 --13.3448038101,0.331732183695,-3.79572319984 --13.2037849426,0.325760036707,-3.77999782562 --13.5418491364,0.339670866728,-3.91721272469 --13.7608947754,0.34960848093,-4.024497509 --13.6198816299,0.343630969524,-4.03197574615 --13.5368766785,0.341640084982,-4.05441761017 --13.4958791733,0.339638978243,-4.0898475647 --13.4898881912,0.340629637241,-4.13425064087 --13.7019300461,0.348572731018,-4.21933317184 --13.7069416046,0.349560320377,-4.26772928238 --13.6869487762,0.349553853273,-4.30914211273 --13.7749757767,0.353520572186,-4.383497715 --13.7659854889,0.353511303663,-4.42789936066 --13.7489929199,0.353503912687,-4.47030878067 --13.7340021133,0.35349586606,-4.51372098923 --13.6970052719,0.352493345737,-4.55014514923 --13.656003952,0.351498037577,-4.56036329269 --13.6060056686,0.349498838186,-4.59279918671 --13.5490055084,0.34750187397,-4.62122631073 --13.5070085526,0.346501022577,-4.65464878082 --13.4770145416,0.34649682045,-4.69307470322 --13.4790258408,0.346484601498,-4.74046850204 --17.316827774,0.50246733427,-6.05647611618 --17.4458751678,0.508414804935,-6.16180181503 --17.6099319458,0.51535230875,-6.28010606766 --17.5569438934,0.514347672462,-6.32353115082 --17.6119785309,0.517313838005,-6.4048948288 --17.6430091858,0.519285976887,-6.47927856445 --17.8570785522,0.528208136559,-6.6185503006 --17.6850528717,0.522245645523,-6.58784484863 --17.6010570526,0.519248902798,-6.62129545212 --17.6020793915,0.520229041576,-6.68469142914 --17.5660953522,0.519219517708,-6.73410701752 --17.5031032562,0.518217504025,-6.77353954315 --17.4061069489,0.514225125313,-6.79999303818 --17.2430915833,0.508251547813,-6.80149030685 --17.2591056824,0.510237216949,-6.83867835999 --17.2031173706,0.508233487606,-6.88011169434 --17.5072154999,0.522125899792,-7.06133031845 --17.5012397766,0.522107303143,-7.12273025513 --17.4552536011,0.521100282669,-7.16815280914 --17.4722824097,0.523074567318,-7.23954391479 --21.0002117157,0.669010341167,-8.73084068298 --21.0032291412,0.669996142387,-8.77003192902 --20.8362216949,0.664018571377,-8.77952957153 --20.8752670288,0.666979789734,-8.8729019165 --21.069355011,0.675893962383,-9.0311794281 --21.0783939362,0.677863657475,-9.11256504059 --18.9688568115,0.591480433941,-8.29522800446 --18.9078731537,0.589474976063,-8.33965873718 --19.115945816,0.598398625851,-8.4647321701 --21.0865249634,0.681762635708,-9.39194011688 --19.0349845886,0.59737432003,-8.57257175446 --18.985004425,0.596364855766,-8.62300300598 --18.9670314789,0.597345709801,-8.68640708923 --20.8676147461,0.677717208862,-9.61164855957 --20.9836864471,0.683651208878,-9.74397468567 --21.3188056946,0.698529422283,-9.93596458435 --21.1567955017,0.692551612854,-9.9434595108 --21.1118221283,0.692536354065,-10.0038833618 --21.0468444824,0.690527796745,-10.054315567 --20.9978675842,0.690514147282,-10.1117362976 --20.583782196,0.673620462418,-9.99738883972 --20.5928249359,0.67558836937,-10.0807752609 --20.7558956146,0.683519423008,-10.1988716125 --20.7459316254,0.683492600918,-10.2752742767 --20.7199630737,0.684471130371,-10.3436861038 --20.549949646,0.678498506546,-10.3411846161 --20.5439910889,0.679470539093,-10.4185810089 --21.0081825256,0.700281143188,-10.7316913605 --20.9492053986,0.699270427227,-10.7841176987 --21.0712680817,0.705212175846,-10.8882436752 --20.9102573395,0.700236737728,-10.8887329102 --20.8802909851,0.700215339661,-10.9571485519 --21.1354217529,0.712094008923,-11.1723833084 --21.1844825745,0.716044127941,-11.2827472687 --21.1024990082,0.714040696621,-11.3241901398 --21.0635318756,0.714021503925,-11.3896121979 --38.6447563171,1.47570300102,-20.7667140961 --38.3127403259,1.46375405788,-20.7442970276 --25.1381092072,0.894461929798,-13.7990255356 --39.8605041504,1.5370516777,-21.8970718384 --23.8757686615,0.842840850353,-13.3136053085 --38.2831382751,1.47348773479,-21.3538303375 --38.2401771545,1.47346889973,-21.4080467224 --38.1802558899,1.47342097759,-21.5324630737 --22.7345905304,0.801089346409,-13.1120958328 --22.9907436371,0.8139539361,-13.3533267975 --35.2145309448,1.3542650938,-20.4648799896 --35.3516807556,1.36314690113,-20.6921730042 --35.3167152405,1.36312758923,-20.7453861237 --35.2017707825,1.36110532284,-20.8278408051 --24.4815921783,0.88819783926,-14.6661319733 --34.968875885,1.35606253147,-20.9887542725 --34.8519287109,1.35404145718,-21.0682125092 --34.7329788208,1.35102164745,-21.1456699371 --34.248878479,1.33314681053,-21.001367569 --34.4179954529,1.34204661846,-21.177444458 --34.5531539917,1.35092532635,-21.4097423553 --34.6923141479,1.35980188847,-21.6450328827 --34.8084640503,1.36768651009,-21.8683376312 --35.4808578491,1.40134382248,-22.441280365 --35.4049301147,1.40130412579,-22.5487098694 --35.3229980469,1.40026700497,-22.652141571 --35.2640304565,1.39925539494,-22.6933746338 --34.7198982239,1.37840974331,-22.5011138916 --34.5329208374,1.37241733074,-22.5346164703 --34.6840934753,1.38228297234,-22.7879009247 --34.5531387329,1.38026714325,-22.8573684692 --34.8203735352,1.39508211613,-23.1895751953 --35.1336250305,1.41287636757,-23.5537452698 --33.6890144348,1.34845745564,-22.6728935242 --35.3308830261,1.42668044567,-23.9261894226 --34.7737350464,1.40484666824,-23.7119407654 --34.4837112427,1.39489901066,-23.6745147705 --34.5448532104,1.40079843998,-23.8758583069 --36.1497383118,1.47901809216,-25.1401691437 --34.8232154846,1.42052614689,-24.3894348145 --34.8072662354,1.42149579525,-24.4586353302 --34.1460571289,1.39471447468,-24.1594619751 --33.7649841309,1.37981021404,-24.0521011353 --33.7460861206,1.38274466991,-24.1974925995 --33.6581535339,1.3817101717,-24.2939338684 --33.3921356201,1.37275636196,-24.2634963989 --33.2031555176,1.36776804924,-24.2870082855 --33.2192192078,1.36972332001,-24.3781890869 --33.3884239197,1.38156974316,-24.6624584198 --33.2794799805,1.37954437733,-24.7439155579 --32.9974479675,1.37060034275,-24.6964874268 --33.0946159363,1.37847840786,-24.930809021 --32.8175849915,1.36853325367,-24.8843765259 --32.5195426941,1.35859811306,-24.8219661713 --32.6086502075,1.36451768875,-24.9700984955 --32.6357841492,1.36942815781,-25.1524620056 --32.7119445801,1.37631416321,-25.3737945557 --33.1813278198,1.403008461,-25.9008579254 --32.828250885,1.39010155201,-25.7924804688 --32.8323745728,1.39401984215,-25.9628639221 --32.5763549805,1.38506686687,-25.9274215698 --32.5243873596,1.38505232334,-25.9706516266 --32.5625305176,1.39095389843,-26.1670074463 --32.448589325,1.38893067837,-26.2434711456 --32.4307022095,1.39185929298,-26.3968658447 --32.3297729492,1.39082896709,-26.4843215942 --32.2758636475,1.39277541637,-26.6087417603 --32.2669258118,1.39373898506,-26.6869430542 --32.5121955872,1.41053128242,-27.0591583252 --33.2667808533,1.45205974579,-27.8560161591 --31.4137916565,1.36393404007,-26.4876880646 --31.483959198,1.3718162775,-26.7150249481 --31.0408153534,1.35396683216,-26.5097179413 --32.2006607056,1.41527426243,-27.6642951965 --31.2151145935,1.36875259876,-26.9111747742 --30.649887085,1.34397065639,-26.595954895 --31.1843528748,1.37560355663,-27.2259693146 --31.2505264282,1.38248455524,-27.4553089142 --31.0885543823,1.37848782539,-27.4868068695 --30.9746112823,1.37746560574,-27.5592708588 --30.9046993256,1.37841892242,-27.6717090607 --30.7546672821,1.37245881557,-27.625005722 --30.6507320404,1.37143146992,-27.7054653168 --30.746931076,1.38129281998,-27.9667835236 --28.1793460846,1.2536380291,-25.8159809113 --28.0683937073,1.25162184238,-25.8764457703 --27.9974689484,1.25258255005,-25.9748897552 --27.8805141449,1.2505698204,-26.0293598175 --27.8375453949,1.25055480003,-26.0705833435 --27.7646198273,1.25051701069,-26.1660232544 --27.6466636658,1.24850487709,-26.2194976807 --27.5577278137,1.24847614765,-26.2999515533 --27.4777984619,1.24844229221,-26.3883972168 --27.3768520355,1.24742078781,-26.4568595886 --27.2879161835,1.24639236927,-26.5363082886 --27.2349433899,1.24638283253,-26.5685443878 --27.1580142975,1.24634695053,-26.6599884033 --27.0580711365,1.2453250885,-26.7284488678 --26.9661312103,1.24529826641,-26.8049030304 --26.8541793823,1.24328315258,-26.8623771667 --26.7692470551,1.24325203896,-26.9458293915 --26.7013263702,1.24421107769,-27.0452651978 --26.6253356934,1.24221587181,-27.0535144806 --26.5424041748,1.24218344688,-27.1389656067 --26.4534683228,1.24215459824,-27.218421936 --26.3595294952,1.24112915993,-27.2918796539 --26.275598526,1.24209725857,-27.3763332367 --26.1836624146,1.24107050896,-27.451789856 --26.0917243958,1.24104380608,-27.5272445679 --26.0417537689,1.24003255367,-27.5614795685 --26.0929279327,1.24791479111,-27.7868309021 --27.5022106171,1.33092260361,-29.4551963806 --27.492351532,1.33583629131,-29.6295948029 --27.3944206238,1.33480703831,-29.7100582123 --27.1733856201,1.32785797119,-29.6576080322 --27.0724525452,1.32783091068,-29.7340736389 --27.0675239563,1.32978761196,-29.821269989 --27.0756816864,1.33568787575,-30.0176563263 --26.9967670441,1.33664560318,-30.1191043854 --26.9348678589,1.33759188652,-30.2395381927 --26.9460315704,1.34348845482,-30.4419212341 --26.756023407,1.3385207653,-30.4194526672 --26.419883728,1.32465314865,-30.2310905457 --26.184753418,1.31376647949,-30.0584602356 --25.9977416992,1.30779957771,-30.0339870453 --25.8477630615,1.30480754375,-30.0514907837 --25.6827716827,1.30082666874,-30.0500049591 --26.2224159241,1.33735203743,-30.8689975739 --26.0173912048,1.33139717579,-30.8245429993 --26.188627243,1.34422695637,-31.1226081848 --18.7889404297,0.913394510746,-22.5554828644 --18.4927787781,0.899536311626,-22.3461036682 --18.3507556915,0.895569860935,-22.3166046143 --17.7043609619,0.864902317524,-21.8148803711 --17.6734409332,0.866857051849,-21.916305542 --17.5804595947,0.865857839584,-21.9407711029 --17.5885219574,0.8678175807,-22.0209655762 --17.5145587921,0.867803990841,-22.0694198608 --17.4736289978,0.868765771389,-22.1588497162 --17.4337024689,0.870726406574,-22.2502784729 --17.3827648163,0.871694803238,-22.3287200928 --17.319814682,0.872672736645,-22.3911628723 --17.2868366241,0.872662901878,-22.4203872681 --17.2248897552,0.872639596462,-22.4848327637 --17.1679458618,0.873612165451,-22.5562782288 --17.0889778137,0.873602449894,-22.5977363586 --16.9929981232,0.871604859829,-22.6192111969 --16.9370555878,0.872576773167,-22.691652298 --16.9091434479,0.875526428223,-22.8010730743 --24.2920818329,1.34561049938,-32.7276878357 --22.3041248322,1.2260928154,-30.2715930939 --17.6972961426,0.936706244946,-24.2394771576 --17.6203422546,0.93668961525,-24.2929344177 --17.566411972,0.937653899193,-24.3783779144 --17.5284996033,0.940605044365,-24.4858036041 --17.2282962799,0.925772726536,-24.2294311523 --17.4095649719,0.940582633018,-24.5614948273 --16.5096797943,0.88625228405,-23.4615783691 --16.4367237091,0.886235952377,-23.5140361786 --16.3517532349,0.885230600834,-23.547498703 --16.1868171692,0.884214401245,-23.6244277954 --16.2780532837,0.895056664944,-23.9147624969 --21.9638385773,1.27910256386,-32.2656059265 --16.9351730347,0.952279508114,-25.2852592468 --16.8381977081,0.951278686523,-25.3117370605 --16.7992935181,0.95322728157,-25.4231643677 --16.7453727722,0.955187916756,-25.5146083832 --15.7034292221,0.896912336349,-24.3544120789 --15.7646455765,0.905771970749,-24.61577034 --21.0727519989,1.29168832302,-33.2484588623 --22.4237041473,1.39430963993,-35.6038093567 --22.385761261,1.39628088474,-35.6660385132 --23.2250823975,1.46335983276,-37.2497825623 --23.0951385498,1.46234691143,-37.2992782593 --22.397436142,1.42087507248,-36.4342155457 --21.8869762421,1.39222967625,-35.8620147705 --21.8271179199,1.39515554905,-36.0144538879 --21.9314842224,1.41192018986,-36.4397735596 --21.7885131836,1.40892481804,-36.4592781067 --21.9979190826,1.42865037918,-36.9373168945 --21.8559551239,1.42665147781,-36.9628295898 --21.7810821533,1.4295873642,-37.0982818604 --21.5089321136,1.41771948338,-36.9018974304 --21.1166057587,1.39697623253,-36.493598938 --21.0327205658,1.39892220497,-36.6120643616 --21.1029376984,1.40878093243,-36.8652076721 --20.9709835052,1.40777516365,-36.901714325 --20.9872493744,1.41761565208,-37.1990966797 --20.8613033295,1.41660284996,-37.2475967407 --20.7193336487,1.41460776329,-37.2661056519 --14.9648771286,0.974551320076,-27.2040481567 --14.8729114532,0.97354477644,-27.2395267487 --13.685177803,0.882764160633,-25.1806602478 --14.8150854111,0.979450285435,-27.4361782074 --14.733133316,0.979434132576,-27.4876441956 --16.5141143799,1.12938058376,-31.0016403198 --16.469247818,1.13330793381,-31.1500778198 --20.2785491943,1.44995963573,-38.5674514771 --20.1906738281,1.45290160179,-38.6929244995 --13.9386711121,0.945834457874,-26.9150943756 --13.8256654739,0.942855775356,-26.9025878906 --13.7366981506,0.942850649357,-26.9350624084 --13.6317033768,0.940863728523,-26.9365501404 --13.50867939,0.937897384167,-26.903055191 --12.6604242325,0.872776806355,-25.4291343689 --12.569439888,0.871781945229,-25.4436092377 --12.5054178238,0.869805157185,-25.4158668518 --12.4835538864,0.87472820282,-25.5702896118 --12.4306373596,0.876687049866,-25.6637382507 --13.6810235977,0.992074489594,-28.4361476898 --13.3856964111,0.974315583706,-28.0487861633 --18.5712184906,1.4388500452,-39.0990333557 --5.46383571625,0.292783677578,-11.9714651108 --5.40780544281,0.290809303522,-11.9479227066 --18.2218933105,1.45651376247,-39.7911262512 --18.0939540863,1.45649969578,-39.841632843 --17.8317584991,1.44366002083,-39.5942459106 --17.8228912354,1.44858384132,-39.7374534607 --17.6508636475,1.44362926483,-39.6859931946 --17.5509777069,1.44558012486,-39.7964820862 --17.2907733917,1.43274378777,-39.5430984497 --13.1410427094,1.05997610092,-30.6482658386 --17.5111675262,1.48989152908,-41.0791320801 --17.0002880096,1.44649350643,-40.0627479553 --16.9374809265,1.4523922205,-40.2622032166 --16.7834873199,1.44941604137,-40.2477340698 --16.8850288391,1.47208237648,-40.8450584412 --16.5456428528,1.45136666298,-40.3847351074 --16.3445453644,1.44345867634,-40.2533073425 --16.2396526337,1.44541478157,-40.3547973633 --16.3781242371,1.46611642838,-40.8788871765 --16.4476222992,1.4858148098,-41.4222335815 --15.9368371964,1.44636130333,-40.5120582581 --9.46984100342,0.79563999176,-24.6561374664 --7.7420797348,0.622130811214,-20.4069423676 --7.67007875443,0.62114328146,-20.4074115753 --7.62205076218,0.619167566299,-20.3766555786 --7.53401088715,0.616205096245,-20.3341388702 --7.44897699356,0.614239037037,-20.2976169586 --7.39201021194,0.614228844643,-20.3370742798 --7.35509252548,0.61718660593,-20.43151474 --7.29211235046,0.617185652256,-20.4549789429 --7.22512340546,0.617190122604,-20.4694480896 --7.26430749893,0.625075817108,-20.6766166687 --7.21035385132,0.626057624817,-20.7300777435 --7.12932729721,0.624086797237,-20.70154953 --7.03126001358,0.620142519474,-20.6280460358 --6.98332023621,0.622115492821,-20.6964988708 --6.77996778488,0.605355083942,-20.3060703278 --6.74296236038,0.604364335537,-20.3013095856 --6.59575366974,0.594511032104,-20.0708408356 --6.52474451065,0.593528091908,-20.0633106232 --6.51089572906,0.599442481995,-20.2327365875 --6.43086290359,0.597475230694,-20.1982135773 --6.33678770065,0.593534588814,-20.1176986694 --6.40417575836,0.609297573566,-20.5480613708 --6.65098524094,0.644784510136,-21.4430732727 --6.29616308212,0.607323288918,-20.5367660522 --6.34551239014,0.622111916542,-20.9231433868 --6.30159044266,0.625074028969,-21.0105934143 --6.34092092514,0.638875424862,-21.3749713898 --6.23180961609,0.632958948612,-21.2534790039 --6.15378904343,0.63098436594,-21.2319583893 --6.10273981094,0.629021942616,-21.1782035828 --6.12302732468,0.640852034092,-21.4936027527 --6.27774953842,0.671406447887,-22.2848911285 --6.18368625641,0.667459726334,-22.2153816223 --5.84381771088,0.629022181034,-21.2670726776 --5.80492162704,0.632968723774,-21.3815193176 --6.00382995605,0.671408474445,-22.3717727661 --5.97385549545,0.672399282455,-22.3990077972 --5.89283084869,0.670428216457,-22.3714847565 --5.86298799515,0.676342785358,-22.541929245 --5.84317922592,0.683235824108,-22.7493572235 --5.78524208069,0.685210049152,-22.8168201447 --5.70723342896,0.684229373932,-22.8063011169 --5.66736221313,0.689162433147,-22.9447479248 --6.8569188118,0.881322085857,-27.8699893951 --6.77696895599,0.882308542728,-27.917470932 --5.39705324173,0.674389541149,-22.6090106964 --5.32807016373,0.674392521381,-22.6264762878 --5.2580871582,0.674395680428,-22.643951416 --5.22424793243,0.680309414864,-22.8163967133 --5.21953201294,0.691146969795,-23.1208171844 --5.28696393967,0.708886444569,-23.5839767456 --5.1627664566,0.700022935867,-23.3704910278 --5.1128783226,0.703967988491,-23.488948822 --5.08106851578,0.711865186691,-23.6903915405 --5.0241560936,0.71482527256,-23.7828540802 --5.02048254013,0.727639019489,-24.1292762756 --4.95135068893,0.721727609634,-23.9875431061 --4.87234640121,0.720744907856,-23.9810256958 --4.81142616272,0.723711013794,-24.0634975433 --4.74346923828,0.724699378014,-24.1069660187 --4.58910274506,0.708938360214,-23.7155075073 --4.46085453033,0.698104918003,-23.4500350952 --4.36977720261,0.694166481495,-23.3665275574 --4.32090997696,0.699099779129,-23.5059871674 --5.30612945557,0.911927580833,-29.0314121246 --5.03521347046,0.873503565788,-28.0550518036 --4.93516397476,0.870551407337,-27.9965515137 --4.79992246628,0.859715998173,-27.7350788116 --4.80946731567,0.881403505802,-28.3034934998 --4.69936466217,0.876483738422,-28.1890068054 --4.78008317947,0.905058264732,-28.942155838 --4.55330514908,0.872546732426,-28.1167545319 --3.79435110092,0.711950004101,-23.9567718506 --4.39041900635,0.875514268875,-28.2237319946 --4.30847120285,0.877501368523,-28.2712211609 --4.15708398819,0.860751867294,-27.8597602844 --4.03185558319,0.850907206535,-27.6142845154 --4.01502847672,0.857812106609,-27.7925071716 --3.97032594681,0.868651986122,-28.0969696045 --3.87428355217,0.865695476532,-28.0464687347 --3.20622420311,0.703138291836,-23.8094043732 --3.13122057915,0.702155172825,-23.8038825989 --3.02801346779,0.694293737411,-23.5863857269 --2.94394207001,0.690350949764,-23.5108757019 --2.90996837616,0.691342890263,-23.5371170044 --2.84402704239,0.693322718143,-23.5965900421 --2.83253765106,0.71303498745,-24.1240291595 --1.8056166172,0.398741066456,-15.920170784 --1.76467978954,0.401712864637,-15.9916210175 --1.7066026926,0.398767769337,-15.9180898666 --2.65467977524,0.756422877312,-25.2938766479 --5.68507814407,1.87469220161,-54.5808753967 --5.52825021744,1.87962949276,-54.7244377136 --1.55276656151,0.405703812838,-16.1086864471 --6.25549507141,2.39297986031,-68.226272583 --6.03852415085,2.39101195335,-68.2088851929 --5.83468770981,2.3949649334,-68.3294906616 --6.04944896698,2.54079174995,-72.1585769653 --5.82046842575,2.53883218765,-72.127204895 --5.57123613358,2.52701973915,-71.8388519287 --5.33210849762,2.51914572716,-71.6574935913 --5.06559658051,2.49749565125,-71.0841445923 --4.84467124939,2.49750328064,-71.1107711792 --3.64908719063,1.93000924587,-56.2120018005 --3.55299282074,1.92508423328,-56.0983047485 --3.38616013527,1.93002736568,-56.2338829041 --3.22038125992,1.93694007397,-56.4234580994 --2.98636341095,1.89556777477,-55.3560714722 --2.66187667847,1.91235184669,-55.8082237244 --2.06741642952,1.92718327045,-56.2332611084 --1.88732433319,1.92227673531,-56.105846405 --1.70925366879,1.9183576107,-56.0004348755 --1.53117787838,1.91344130039,-55.8900184631 --1.44108486176,1.90951478481,-55.7793121338 --1.26399385929,1.90460717678,-55.6539001465 --1.08892440796,1.90068697929,-55.5504837036 --0.913839817047,1.89577543736,-55.4320678711 --0.738744139671,1.8908700943,-55.3026504517 --0.565702140331,1.88793432713,-55.2272338867 --0.392575889826,1.88204598427,-55.067817688 --0.411559462547,2.60134005547,-74.0124359131 --0.155050009489,2.20132493973,-63.473865509 -0.126899152994,2.24652075768,-62.4797973633 -0.323773860931,2.24239993095,-62.3970184326 -0.519562959671,2.23623085022,-62.2282447815 -0.715450227261,2.233117342,-62.1574668884 -0.91029381752,2.22897958755,-62.0426940918 -1.0071721077,2.22488641739,-61.9418067932 -1.20001041889,2.22074627876,-61.8210334778 -1.39182150364,2.21459126472,-61.6732673645 -1.32596051693,1.71135365963,-48.8012161255 -1.47991037369,1.71028614044,-48.7794799805 -1.63694667816,1.7132666111,-48.8447418213 -2.17162299156,2.21328234673,-61.6401672363 -2.3624560833,2.20914030075,-61.5133972168 -2.55129766464,2.2050037384,-61.3946304321 -2.7401342392,2.19986438751,-61.270866394 -2.92896986008,2.19572424889,-61.1461029053 -3.11680960655,2.19058728218,-61.0253410339 -3.30365872383,2.18645596504,-60.9135780334 -3.39555096626,2.18337225914,-60.8246994019 -3.58139872551,2.17923998833,-60.7109413147 -3.99177694321,2.3160443306,-64.1878890991 -4.18863296509,2.31191468239,-64.0861206055 -4.38549757004,2.30878973007,-63.9923477173 -4.57729434967,2.30362820625,-63.8295822144 -4.76910638809,2.29747486115,-63.6818237305 -4.85995435715,2.29336714745,-63.5489463806 -5.05380916595,2.28923773766,-63.4441795349 -4.96029472351,2.15027809143,-59.8907585144 -5.15125370026,2.15120816231,-59.8889961243 -5.30683422089,2.13593387604,-59.4992752075 -5.48365926743,2.13179183006,-59.3595275879 -5.56550741196,2.12668657303,-59.2236595154 -5.74639129639,2.1235768795,-59.1439056396 -5.9080915451,2.11436867714,-58.8751792908 -6.07181930542,2.10517573357,-58.6344451904 -6.24768161774,2.10205578804,-58.5317001343 -6.42353820801,2.0979321003,-58.422958374 -6.59336042404,2.09279131889,-58.2782173157 -6.6802854538,2.09072804451,-58.2203445435 -6.85010576248,2.08658599854,-58.0736083984 -7.01288127899,2.07942056656,-57.8798751831 -7.18776512146,2.07731318474,-57.7981300354 -7.35458230972,2.07217073441,-57.6473999023 -7.53248882294,2.07007551193,-57.5886535645 -7.6942896843,2.06492495537,-57.419921875 -7.78022241592,2.06286644936,-57.369052887 -7.94404172897,2.05772590637,-57.2193222046 -8.20552539825,2.0799369812,-57.7624855042 -8.31900787354,2.06161785126,-57.2598152161 -8.44860839844,2.04736304283,-56.8821220398 -8.62955474854,2.04728984833,-56.8633728027 -8.8487405777,2.05734300613,-57.0955848694 -8.88840007782,2.04514169693,-56.7577629089 -7.61364889145,1.6845074892,-47.6125679016 -7.34327363968,1.54766750336,-44.1197357178 -7.47015523911,1.54457080364,-44.0200386047 -7.61313009262,1.54552316666,-44.0183258057 -7.7681684494,1.54950845242,-44.0836029053 -7.84317493439,1.55049455166,-44.1027374268 -7.98916196823,1.55145323277,-44.114025116 -8.82971763611,1.70326185226,-47.8995895386 -8.93141365051,1.6920671463,-47.6069221497 -10.5436038971,1.99674677849,-55.2576942444 -10.6984395981,1.99261868,-55.1199760437 -10.7763633728,1.99155771732,-55.0571174622 -10.9312038422,1.98743271828,-54.9244041443 -11.0971031189,1.98533809185,-54.8536720276 -11.2559671402,1.98222565651,-54.7459526062 -11.4098148346,1.9791046381,-54.6192398071 -11.5656728745,1.97598910332,-54.5035209656 -11.7195253372,1.97187173367,-54.3828048706 -11.7904253006,1.96979939938,-54.2939567566 -5.49887228012,0.794714808464,-24.8457336426 -5.57182741165,0.793672025204,-24.8020877838 -5.64076280594,0.791619062424,-24.7374458313 -5.70870018005,0.789567649364,-24.6748008728 -5.78366565704,0.788530409336,-24.6421508789 -12.7145996094,1.95112729073,-53.6226768494 -6.2958240509,0.841065108776,-25.9017162323 -6.42899513245,0.849130749702,-26.0920085907 -12.7061815262,1.62139809132,-44.9186096191 -8.72754383087,1.02160799503,-30.0523319244 -8.81047058105,1.01954829693,-29.9826812744 -8.98033809662,1.01643550396,-29.8573760986 -9.05925559998,1.01437199116,-29.7777290344 -9.09720802307,1.0133368969,-29.7309074402 -9.18415260315,1.01228606701,-29.6792526245 -9.26106548309,1.00922012329,-29.5936088562 -9.34600448608,1.00816690922,-29.5359573364 -9.43094539642,1.00711488724,-29.4803028107 -9.53077697754,1.00199818611,-29.3088512421 -9.6277513504,1.00196254253,-29.2901916504 -13.3582687378,1.43950009346,-39.8705253601 -13.4370861053,1.43338084221,-39.6888847351 -13.5479879379,1.43130230904,-39.6012153625 -13.6268100739,1.42618608475,-39.424571991 -13.6697311401,1.423132658,-39.3467521667 -13.7896623611,1.42306876183,-39.2910728455 -13.9597196579,1.42806458473,-39.3753509521 -14.0896759033,1.42901241779,-39.346660614 -15.0326509476,1.52291989326,-41.578212738 -14.3903236389,1.4207521677,-39.0146865845 -17.633556366,1.762119174,-47.1683197021 -17.8722629547,1.75490617752,-46.8979797363 -15.5410814285,1.47093605995,-39.9830169678 -15.895359993,1.48901832104,-40.3303413391 -15.4269647598,1.4253360033,-38.7742118835 -16.1889724731,1.47874164581,-39.9573822021 -16.3810520172,1.4857468605,-40.069644928 -16.4638938904,1.48164129257,-39.9110069275 -16.5557537079,1.47754538059,-39.7753562927 -18.9847240448,1.71782183647,-45.4443588257 -16.5843238831,1.46129894257,-39.3159866333 -19.1573314667,1.70556867123,-45.0530776978 -19.2892341614,1.70448756218,-44.9683990479 -19.3890705109,1.7003762722,-44.8087501526 -19.504940033,1.69828116894,-44.6880874634 -19.5498504639,1.69522190094,-44.5982666016 -19.6647205353,1.69312679768,-44.476600647 -19.7795944214,1.69003272057,-44.3569374084 -19.8884544373,1.68693435192,-44.2252807617 -19.9993228912,1.68483877182,-44.0996208191 -20.1182041168,1.6827493906,-43.9899559021 -20.2300739288,1.67965590954,-43.8682937622 -20.2719860077,1.6775970459,-43.7764778137 -20.3838577271,1.67450428009,-43.6558151245 -20.4977359772,1.67241430283,-43.5411529541 -20.5995883942,1.66931331158,-43.3985061646 -20.7184791565,1.66722893715,-43.2968406677 -20.8283519745,1.66513681412,-43.1751823425 -20.9252033234,1.66103518009,-43.0275382996 -20.9711227417,1.6589820385,-42.9477157593 -18.7949867249,1.45411396027,-38.1570892334 -21.1638298035,1.6517816782,-42.6564292908 -21.267698288,1.64968836308,-42.5277786255 -19.0055236816,1.44081676006,-37.6782150269 -21.5054855347,1.64652562141,-42.3314476013 -19.4497318268,1.45884549618,-37.9607048035 -21.5691394806,1.63432109356,-41.9620552063 -21.7130794525,1.63526070118,-41.9173660278 -21.7728805542,1.62913942337,-41.7087554932 -21.844701767,1.62402737141,-41.5241394043 -21.8964958191,1.61690354347,-41.3055305481 -21.9412784576,1.60977518559,-41.0739364624 -21.9770507812,1.60264277458,-40.8293457031 -22.0109653473,1.59958851337,-40.73853302 -22.0797920227,1.59447956085,-40.5569152832 -22.1596393585,1.59038054943,-40.4002876282 -22.25050354,1.58728849888,-40.2626533508 -22.3463783264,1.58520138264,-40.137008667 -22.4402503967,1.58211290836,-40.0073661804 -22.5391311646,1.58002793789,-39.8867225647 -22.5810604095,1.57798159122,-39.814907074 -22.6749343872,1.57589411736,-39.6862678528 -22.7547893524,1.57179927826,-39.5356407166 -22.8566741943,1.57071816921,-39.4229927063 -22.9545593262,1.56863594055,-39.3063545227 -23.115404129,1.56652033329,-39.1528778076 -23.2012729645,1.56343233585,-39.0172462463 -23.2811336517,1.55934047699,-38.8706207275 -23.360994339,1.55624973774,-38.7259941101 -23.4488658905,1.55416369438,-38.5943603516 -23.5567684174,1.55208969116,-38.496711731 -23.6706790924,1.55202019215,-38.4110527039 -23.6875801086,1.5489628315,-38.3022613525 -23.7874736786,1.546885252,-38.1926193237 -23.8332939148,1.5417791605,-37.9980239868 -23.9902648926,1.54373419285,-37.9823303223 -24.0911598206,1.54265868664,-37.8766860962 -24.1249694824,1.53654789925,-37.6651039124 -24.1748008728,1.53144705296,-37.481502533 -24.1937122345,1.52839434147,-37.3817062378 -24.3046226501,1.52732586861,-37.2940559387 -24.2993888855,1.51919877529,-37.028503418 -24.3332061768,1.51309275627,-36.8249168396 -24.38904953,1.50799822807,-36.6553153992 -24.4278812408,1.5028976202,-36.4647216797 -24.4767208099,1.49880182743,-36.2881240845 -24.4565868378,1.49273228645,-36.1333656311 -24.5314598083,1.48965072632,-35.9987411499 -24.5993289948,1.48656690121,-35.8551254272 -24.6812152863,1.48448932171,-35.731502533 -24.7610969543,1.48241102695,-35.6048774719 -24.7909221649,1.47631156445,-35.4092941284 -24.797826767,1.47325789928,-35.2995109558 -24.8727054596,1.47017884254,-35.1678924561 -24.9225578308,1.46608996391,-35.0032920837 -24.9834270477,1.46300685406,-34.8556861877 -25.0683193207,1.46093392372,-34.7410621643 -25.2219944,1.45272994041,-34.3780403137 -25.3339214325,1.45367097855,-34.3043861389 -25.379776001,1.44958424568,-34.139793396 -25.4796886444,1.44851982594,-34.0481567383 -25.5325527191,1.44443738461,-33.8955535889 -25.6084442139,1.44236469269,-33.7739372253 -25.7323856354,1.44431090355,-33.7152786255 -25.7513084412,1.44126713276,-33.629486084 -25.8372116089,1.44019901752,-33.5218582153 -25.937128067,1.44013643265,-33.432220459 -26.0300369263,1.43907141685,-33.3335914612 -26.1109352112,1.43700242043,-33.2209663391 -26.1948375702,1.43593502045,-33.1123428345 -26.2637233734,1.43386220932,-32.9847297668 -26.3347053528,1.43483924866,-32.9668960571 -26.4276161194,1.43377578259,-32.870262146 -26.5455513,1.43472135067,-32.8046112061 -26.6474742889,1.43466126919,-32.7189712524 -26.7293739319,1.43359470367,-32.6093521118 -26.8823451996,1.43655240536,-32.5856742859 -26.9743461609,1.4385368824,-32.5928192139 -27.0382289886,1.43646383286,-32.4602165222 -27.146156311,1.43640637398,-32.3815765381 -27.2640914917,1.4373524189,-32.3149223328 -27.3730220795,1.43729543686,-32.2372817993 -27.5079727173,1.43924689293,-32.1896209717 -27.7039813995,1.44521868229,-32.2149047852 -27.8490276337,1.45021915436,-32.2810134888 -27.8698749542,1.44613397121,-32.0994415283 -27.9547805786,1.44506943226,-31.992816925 -28.0777206421,1.44601678848,-31.9291687012 -28.1716365814,1.4449557066,-31.8335380554 -28.3035850525,1.44690585136,-31.7798786163 -23.3610477448,1.15030014515,-25.9354248047 -23.4589996338,1.151258111,-25.8797874451 -23.5659599304,1.15221858025,-25.833147049 -23.6639118195,1.15317690372,-25.7775096893 -23.7728710175,1.15513789654,-25.7328643799 -23.8237838745,1.15308237076,-25.6242656708 -23.9587669373,1.15605115891,-25.6085987091 -29.4622478485,1.46753537655,-31.4505386353 -29.6010379791,1.46340107918,-31.2023220062 -29.7019577026,1.46334207058,-31.1106929779 -29.7948722839,1.46328186989,-31.0120658875 -29.8877849579,1.46322131157,-30.912443161 -29.9646892548,1.46215748787,-30.797826767 -30.3004016876,1.46095132828,-30.4631328583 -30.7610588074,1.46269619465,-30.0617923737 -30.853975296,1.46263730526,-29.9621696472 -30.9508972168,1.46258020401,-29.8685417175 -31.0498180389,1.46252346039,-29.7759132385 -27.0557899475,1.24256181717,-25.7483901978 -26.7194862366,1.22245466709,-25.344865799 -26.253030777,1.19328832626,-24.7406616211 -26.0707817078,1.17918550968,-24.4112434387 -25.2220649719,1.12994360924,-23.4583244324 -25.3780612946,1.13491666317,-23.4556484222 -24.7044830322,1.09471869469,-22.6815948486 -23.8878135681,1.04849600792,-21.7846469879 -22.9881496429,0.999287068844,-20.8875408173 -22.8139324188,0.986200869083,-20.5961074829 -22.2684688568,0.954043030739,-19.969953537 -21.5999298096,0.915864408016,-19.2388916016 -21.3256587982,0.898765683174,-18.8715286255 -20.8702716827,0.871633827686,-18.3443069458 -20.5689926147,0.853534042835,-17.9609642029 -18.4395675659,0.742118895054,-16.0227622986 -18.478521347,0.741089105606,-15.955163002 -18.2853279114,0.729017555714,-15.6847381592 -18.0411052704,0.713938117027,-15.3723526001 -17.7898807526,0.697859287262,-15.057967186 -17.4175834656,0.676760911942,-14.6426734924 -17.4805908203,0.678755104542,-14.6488447189 -17.2163639069,0.662677526474,-14.3304710388 -17.0622062683,0.652619838715,-14.1080179214 -16.8590259552,0.64055544138,-13.8475952148 -8.24373531342,0.204123735428,-6.55463314056 -8.26473045349,0.204117506742,-6.52903652191 -8.34076690674,0.207124501467,-6.56919908524 -8.36176204681,0.207118272781,-6.54359960556 -8.38375854492,0.207112044096,-6.51800727844 -8.40175151825,0.207105308771,-6.4894156456 -8.43675518036,0.208101212978,-6.47480821609 -8.44474315643,0.207092866302,-6.43723392487 -8.47474384308,0.20708809793,-6.4186296463 -8.49374580383,0.208085939288,-6.41084003448 -8.51574230194,0.208080127835,-6.38623714447 -8.53873825073,0.208074107766,-6.36065101624 -8.56273555756,0.208068519831,-6.33705234528 -8.5927362442,0.208063647151,-6.31745529175 -8.61173057556,0.208057433367,-6.2898607254 -8.6437330246,0.209052756429,-6.27126550674 -8.66373538971,0.209051027894,-6.26546001434 -8.67672729492,0.209044039249,-6.23287391663 -8.70472621918,0.209038928151,-6.21127939224 -8.74273109436,0.210035160184,-6.19767189026 -8.76672840118,0.210029602051,-6.17307949066 -8.7867231369,0.210023581982,-6.14549016953 -8.81372261047,0.211018383503,-6.12289714813 -8.82371997833,0.211015403271,-6.10910272598 -8.86272525787,0.212011680007,-6.09549617767 -8.88972377777,0.212006539106,-6.07290124893 -8.90771865845,0.21200054884,-6.04430818558 -8.93471717834,0.211995482445,-6.02171182632 -8.96571826935,0.212990701199,-6.00112056732 -8.96771144867,0.211987093091,-5.98232507706 -9.00971889496,0.21298353374,-5.96972131729 -21.4786834717,0.796195268631,-14.472533226 -9.05571174622,0.213972717524,-5.91853427887 -9.08971500397,0.213968500495,-5.90092754364 -9.11571311951,0.214963257313,-5.87634134293 -9.13670921326,0.214957818389,-5.84974431992 -9.14870834351,0.214955165982,-5.83694982529 -9.20271873474,0.215952545404,-5.83133935928 -9.16468811035,0.213942050934,-5.76578187943 -9.19268703461,0.213937088847,-5.74219655991 -9.24769973755,0.21593464911,-5.73757743835 -9.29270648956,0.216931089759,-5.72497749329 -9.327709198,0.217926964164,-5.70736789703 -12.1119241714,0.345139056444,-7.45671987534 -12.3389987946,0.354144245386,-7.54699325562 -12.3129644394,0.351129978895,-7.47644090652 -13.1172857285,0.387175709009,-7.9233288765 -12.6200485229,0.363127499819,-7.55909109116 -12.5900125504,0.361113280058,-7.48653554916 -13.1172094345,0.383136451244,-7.75460386276 -12.8060665131,0.369109451771,-7.53702878952 -13.0851573944,0.380114972591,-7.65027284622 -13.1891756058,0.384108781815,-7.6566324234 -13.1401319504,0.381093293428,-7.57208871841 -13.2041330338,0.382084697485,-7.55447292328 -13.3751764297,0.389082044363,-7.59878969193 -13.3321466446,0.386073410511,-7.54602861404 -13.369137764,0.387063026428,-7.51143360138 -13.4301376343,0.389053970575,-7.4908208847 -13.5271511078,0.392046630383,-7.49018669128 -13.9252786636,0.408054232597,-7.66034936905 -13.5821228027,0.392025023699,-7.41000127792 -13.4510507584,0.385006994009,-7.28151130676 -13.3289928436,0.378995269537,-7.18481445312 -13.3519792557,0.378984838724,-7.14322566986 -13.2689256668,0.374970078468,-7.04370450974 -13.3619384766,0.377962648869,-7.04007434845 -13.3709192276,0.376951992512,-6.99149131775 -13.4289178848,0.378943026066,-6.96788787842 -13.5889530182,0.384938061237,-7.00020313263 -13.5489273071,0.381931036711,-6.95144557953 -13.5198965073,0.379919052124,-6.88189315796 -14.6252574921,0.426943987608,-7.40560150146 -13.6679039001,0.38490229845,-6.85164833069 -13.6318693161,0.381890296936,-6.77810716629 -13.6678609848,0.382880866528,-6.74350500107 -13.7378635406,0.3848721385,-6.72489023209 -13.8899040222,0.390870839357,-6.77500391006 -13.7958517075,0.385857909918,-6.67349338531 -13.9378757477,0.390850663185,-6.68983316422 -13.6777715683,0.378834694624,-6.50742816925 -13.8157949448,0.383827418089,-6.52176856995 -13.7827644348,0.381816953421,-6.45321130753 -13.7017297745,0.377810567617,-6.38747692108 -13.6867046356,0.375800490379,-6.3269200325 -13.8387317657,0.381793260574,-6.34724664688 -13.9337415695,0.384784758091,-6.3386182785 -14.0347528458,0.387776315212,-6.33298063278 -13.7616500854,0.375763714314,-6.1525850296 -13.9446868896,0.382756203413,-6.18489551544 -13.9026641846,0.380751132965,-6.13913726807 -13.8896417618,0.378741949797,-6.08156728745 -13.9386367798,0.379733085632,-6.05096769333 -14.0136404037,0.382724374533,-6.0323472023 -14.2596921921,0.391716003418,-6.08862400055 -14.275677681,0.391706883907,-6.04303741455 -14.6457614899,0.40669760108,-6.15024089813 -14.6577558517,0.406692862511,-6.12844610214 -14.6867437363,0.40668335557,-6.08685493469 -14.7307357788,0.407673805952,-6.05125713348 -14.6286888123,0.402664870024,-5.95375061035 -14.7417011261,0.406655222178,-5.94810247421 -14.7746906281,0.407645791769,-5.90751314163 -14.7736711502,0.406636685133,-5.85294342041 -15.3438100815,0.429626941681,-6.05881023407 -15.570848465,0.438615143299,-6.09609079361 -15.565826416,0.437605410814,-6.03752374649 -15.6098184586,0.438595175743,-5.99892425537 -15.6408042908,0.438585042953,-5.95433855057 -17.6092720032,0.519545197487,-6.66755771637 -17.6362667084,0.52053886652,-6.64675426483 -17.6972541809,0.521525979042,-6.60714673996 -17.7432422638,0.522513329983,-6.56154870987 -17.7792243958,0.523500740528,-6.51096343994 -17.8362121582,0.524488031864,-6.46935749054 -17.8912010193,0.526475131512,-6.42575931549 -17.9381885529,0.527462601662,-6.38015842438 -17.976184845,0.528455972672,-6.36235046387 -18.0271701813,0.529443144798,-6.31675481796 -18.0721569061,0.530430555344,-6.26916027069 -18.1361465454,0.532417535782,-6.22855186462 -18.1771316528,0.533405065536,-6.17896080017 -18.2291183472,0.534392297268,-6.13336133957 -18.2751159668,0.53638535738,-6.11754894257 -18.3180999756,0.5363727808,-6.06795835495 -18.3640861511,0.538360357285,-6.02035856247 -18.4330768585,0.5403470397,-5.97974872589 -18.4770622253,0.54133450985,-5.93015623093 -18.5210475922,0.542322039604,-5.88056230545 -18.5780353546,0.543309092522,-5.83496189117 -18.6200313568,0.544302046299,-5.81615591049 -18.6600170135,0.545289874077,-5.76555919647 -18.7110004425,0.547277092934,-5.71696472168 -18.7739906311,0.548263847828,-5.6723613739 -18.822977066,0.550251305103,-5.62376070023 -18.8849639893,0.551238119602,-5.57815885544 -18.9339523315,0.553225457668,-5.52856206894 -18.9679450989,0.554218769073,-5.50675725937 -19.0189323425,0.555206000805,-5.45716190338 -19.0809192657,0.557192742825,-5.41055965424 -19.1269035339,0.558180212975,-5.35896778107 -19.1828899384,0.559167265892,-5.31036806107 -19.2388782501,0.561154425144,-5.26176643372 -19.2748622894,0.562142491341,-5.20717716217 -19.3358592987,0.56413424015,-5.19136095047 -19.3888473511,0.565121412277,-5.14076471329 -19.4368305206,0.566108942032,-5.08916711807 -19.4828166962,0.568096399307,-5.03557920456 -19.5508060455,0.570082843304,-4.98896980286 -19.6027908325,0.57107013464,-4.93737268448 -19.6567897797,0.573062062263,-4.91855955124 -19.7097740173,0.574049293995,-4.86696052551 -19.7627601624,0.576036393642,-4.81436681747 -19.8207473755,0.578023374081,-4.76376342773 -19.8777332306,0.579010307789,-4.71216440201 -19.9157161713,0.57999843359,-4.65557718277 -19.9737033844,0.581985354424,-4.60397577286 -20.0357017517,0.583976626396,-4.58516120911 -20.0976886749,0.585963129997,-4.53356075287 -20.1496734619,0.586950421333,-4.4799618721 -20.2036590576,0.588937520981,-4.4253692627 -20.2336406708,0.588926255703,-4.36578655243 -20.3086299896,0.591911911964,-4.316177845 -20.379617691,0.593897938728,-4.26556968689 -20.427614212,0.595889985561,-4.24275875092 -20.4925994873,0.597876250744,-4.18916130066 -20.5505847931,0.598863065243,-4.13456344604 -20.6015701294,0.600850403309,-4.07896327972 -20.6625576019,0.60283690691,-4.02337026596 -20.7205410004,0.603823840618,-3.96876692772 -20.7805290222,0.605810403824,-3.91316890717 -20.8405246735,0.607801496983,-3.89135217667 -20.9025115967,0.609787940979,-3.83575224876 -20.9504928589,0.611775517464,-3.77716040611 -21.0254821777,0.613760828972,-3.72255921364 -21.0814666748,0.615747749805,-3.66496253014 -21.1304512024,0.616735339165,-3.60636687279 -21.1744441986,0.618727385998,-3.57956361771 -21.2624320984,0.621711730957,-3.52694892883 -21.2984161377,0.622700214386,-3.46436667442 -21.364402771,0.624686419964,-3.40776109695 -21.4553909302,0.627670347691,-3.3541469574 -21.5113754272,0.629657268524,-3.29455065727 -21.5403556824,0.629646480083,-3.22997236252 -21.6103534698,0.632636189461,-3.20615386963 -17.6019706726,0.475977569818,-2.51878285408 -17.5689563751,0.474975645542,-2.45723509789 -17.5419406891,0.472973316908,-2.39668560028 -17.664937973,0.47795778513,-2.35904669762 -21.9612827301,0.644564330578,-2.91113853455 -16.3698101044,0.427066862583,-2.06760859489 -16.2647972107,0.422074794769,-2.02688360214 -16.2107849121,0.420076549053,-1.96834015846 -16.1537704468,0.418078750372,-1.90979814529 -16.1627616882,0.41807487607,-1.85922801495 -16.107749939,0.415077149868,-1.80168390274 -16.1037406921,0.415074676275,-1.75011706352 -16.0787315369,0.41407430172,-1.69556641579 -16.0897274017,0.414071887732,-1.67177283764 -16.0777168274,0.413070380688,-1.61921274662 -16.0567073822,0.412069916725,-1.56664991379 -16.0627002716,0.412066817284,-1.51608169079 -16.1076965332,0.414059907198,-1.47048461437 -16.1056861877,0.414057731628,-1.41991269588 -16.1456871033,0.415052503347,-1.39811015129 -16.1646785736,0.416048288345,-1.34952676296 -16.1936740875,0.416043013334,-1.30094563961 -16.2376670837,0.418036282063,-1.25434947014 -16.3456668854,0.422022819519,-1.2127225399 -16.3506584167,0.422020077705,-1.16115581989 -16.4446563721,0.425008028746,-1.11753571033 -19.193780899,0.531715512276,-1.30631434917 -19.1427650452,0.529716849327,-1.24177753925 -19.1557540894,0.529711484909,-1.18320012093 -19.1957435608,0.530703186989,-1.1256146431 -9.7293548584,0.165728569031,-0.446877151728 -9.73536014557,0.166730940342,-0.416306614876 -9.73536396027,0.165733888745,-0.38672041893 -9.72836685181,0.165736198425,-0.370938807726 -9.71936988831,0.165740251541,-0.340364158154 -9.72937488556,0.165742233396,-0.310781091452 -9.72537994385,0.165745839477,-0.28020849824 -9.72038459778,0.165749594569,-0.249636158347 -9.72439002991,0.16575242579,-0.219065397978 -9.71939468384,0.164756268263,-0.188494086266 -9.70839691162,0.164759099483,-0.173701167107 -9.71140289307,0.16476213932,-0.143130794168 -9.71040725708,0.164765551686,-0.113546535373 -9.70541191101,0.164769560099,-0.0829766094685 -9.71441841125,0.164771899581,-0.0533916428685 -9.70742416382,0.164776235819,-0.0228224918246 -9.69542598724,0.163779452443,-0.00704696821049 -9.70043182373,0.163782343268,0.0225374624133 -9.69243717194,0.163786903024,0.0531048551202 -9.68944263458,0.163790822029,0.0826869830489 -9.69544887543,0.163793802261,0.113258123398 -9.69545459747,0.163797423244,0.142841264606 -9.68745994568,0.163802161813,0.173406943679 -9.68146324158,0.163804739714,0.188195541501 -9.67946815491,0.163808703423,0.217777043581 -9.68747425079,0.163811579347,0.248349949718 -9.68148136139,0.1638161093,0.277929186821 -9.67948627472,0.163820311427,0.308496534824 -9.67949295044,0.163824170828,0.338079035282 -9.68049621582,0.163825973868,0.352870970964 -9.67050266266,0.162831291556,0.383431941271 -9.67950820923,0.163834065199,0.413021475077 -9.67151546478,0.162839084864,0.44259724021 -9.67252159119,0.162843093276,0.473166555166 -9.66952800751,0.162847518921,0.502746284008 -9.66053390503,0.162852808833,0.532320141792 -9.65953826904,0.162855133414,0.548096299171 -9.65854454041,0.162859395146,0.577677428722 -9.6555519104,0.162863969803,0.607256472111 -9.66055774689,0.162867605686,0.637830257416 -9.65456485748,0.16287265718,0.667405903339 -9.65757274628,0.16287663579,0.69797796011 -9.64557933807,0.162882477045,0.726559758186 -9.64558315277,0.162884771824,0.742336928844 -9.64958953857,0.162888541818,0.771924495697 -9.64759731293,0.162893339992,0.802490532398 -9.64360427856,0.162898316979,0.832067787647 -9.64361190796,0.162902742624,0.861650526524 -9.63761901855,0.162908092141,0.891224741936 -9.6466217041,0.162909150124,0.907015621662 -9.63663005829,0.162915125489,0.936583697796 -9.64163780212,0.162919059396,0.967160761356 -9.64164543152,0.162923619151,0.996744334698 -9.63265228271,0.162929579616,1.02631318569 -9.63166046143,0.1629345119,1.05688118935 -9.63766765594,0.163938373327,1.08746182919 -9.62967205048,0.162941798568,1.10125350952 -9.63067913055,0.162946492434,1.13182544708 -9.61968803406,0.162952780724,1.16040337086 -9.62069511414,0.162957534194,1.19097554684 -9.61770343781,0.162962779403,1.2205542326 -9.62271213531,0.163967102766,1.25212132931 -9.61971950531,0.163972422481,1.28170049191 -9.62772274017,0.16397370398,1.29749548435 -9.62173175812,0.163979545236,1.32706880569 -9.61873912811,0.163984924555,1.35664832592 -9.61074829102,0.163991168141,1.3862169981 -9.60875701904,0.163996621966,1.41678476334 -9.61476421356,0.164000749588,1.44737076759 -9.61277294159,0.164006248116,1.47793924809 -9.60877799988,0.164009258151,1.49173724651 -9.61078548431,0.16401411593,1.52231538296 -9.60479450226,0.164020195603,1.55188846588 -9.60580348969,0.165025278926,1.58246517181 -9.59981155396,0.165031433105,1.61203825474 -9.59882068634,0.165036901832,1.64261031151 -9.59682559967,0.16503983736,1.65739941597 -9.59283351898,0.165045708418,1.68697786331 -9.58984375,0.165051609278,1.71754515171 -9.59485149384,0.165056273341,1.74912035465 -9.5878610611,0.165062770247,1.7786911726 -9.59086990356,0.165067657828,1.80927574635 -9.59087848663,0.16607311368,1.83985292912 -9.59288311005,0.166075572371,1.85564041138 -9.57989311218,0.165083095431,1.88420784473 -9.57790279388,0.166088983417,1.9147799015 -9.58091068268,0.166093960404,1.94536674023 -9.5749206543,0.166100472212,1.97494101524 -9.572930336,0.166106432676,2.00551366806 -9.57893848419,0.167111232877,2.03808450699 -9.56694412231,0.166115894914,2.0508711338 -9.56695365906,0.166121527553,2.08145093918 -9.57996273041,0.167125195265,2.11503171921 -9.56397342682,0.167133420706,2.1426024437 -9.56398296356,0.167139112949,2.17318367958 -9.57099151611,0.168143808842,2.20576167107 -9.55199813843,0.167149797082,2.21753716469 -9.57300567627,0.168152272701,2.25312232971 -9.56501579285,0.16815944016,2.28269219398 -9.57002544403,0.168164387345,2.31427955627 -9.55103683472,0.168173462152,2.34183883667 -9.56004524231,0.169177815318,2.37442803383 -9.5440568924,0.168186351657,2.40199661255 -9.55806064606,0.169187054038,2.42079234123 -9.55407142639,0.169193729758,2.45136404037 -9.55108070374,0.169200226665,2.48194003105 -9.54609107971,0.169207155704,2.51250863075 -9.54610157013,0.170213252306,2.54408311844 -9.52911281586,0.169221997261,2.57066035271 -9.53312397003,0.170227482915,2.6032371521 -9.53912734985,0.170229658484,2.62102150917 -9.53713798523,0.170236051083,2.65160322189 -9.51915073395,0.170245334506,2.67916297913 -9.53115940094,0.171249508858,2.71374750137 -9.51717185974,0.170258000493,2.7413225174 -9.5131816864,0.171264901757,2.77189803123 -9.52619171143,0.171269059181,2.80747652054 -9.51419830322,0.171274259686,2.82025718689 -9.51920795441,0.172279804945,2.8538312912 -9.52421760559,0.172285139561,2.8864197731 -9.51222991943,0.172293528914,2.91499066353 -9.51823997498,0.173299059272,2.94955897331 -9.51725101471,0.173305600882,2.98113775253 -9.52025508881,0.173308268189,2.99792933464 -9.49826908112,0.173318430781,3.02349686623 -9.51427745819,0.174322098494,3.06008577347 -9.48829174042,0.173333063722,3.08464789391 -9.50130081177,0.174337416887,3.12122607231 -9.49431228638,0.174345031381,3.15080738068 -9.49232387543,0.174352094531,3.18337249756 -9.48532962799,0.174356549978,3.19716048241 -9.49733924866,0.17536111176,3.23373889923 -9.48335266113,0.175370052457,3.26131558418 -9.4743642807,0.175378233194,3.29088926315 -9.4813747406,0.176383823156,3.32646083832 -9.48038578033,0.176390707493,3.35903453827 -9.47539234161,0.176394745708,3.37283229828 -9.48040294647,0.177400618792,3.40741038322 -9.45941638947,0.176410987973,3.43297958374 -9.46342754364,0.177417129278,3.46755433083 -9.46643829346,0.177423492074,3.5021250248 -9.46545124054,0.178430452943,3.53470301628 -9.45846366882,0.17843849957,3.56527757645 -9.46046829224,0.178441673517,3.58306050301 -9.45348072052,0.178449749947,3.61363577843 -9.46549129486,0.179454490542,3.65121889114 -9.45650291443,0.179462894797,3.68079805374 -9.45251560211,0.180470660329,3.71336531639 -9.44852828979,0.180478230119,3.74494576454 -9.44853973389,0.180485203862,3.77852249146 -9.43954753876,0.180490374565,3.79230237007 -9.45055675507,0.18149535358,3.82988762856 -9.44456958771,0.181503474712,3.86146044731 -9.43458271027,0.181512236595,3.89103746414 -9.4395942688,0.182518541813,3.92760777473 -9.43660640717,0.183526113629,3.96018624306 -9.42661952972,0.183535128832,3.99075245857 -9.42862510681,0.183538109064,4.00755500793 -9.43863582611,0.184543505311,4.04613208771 -9.43164920807,0.184551969171,4.07770395279 -9.41966247559,0.184561356902,4.10727357864 -9.42167472839,0.185568273067,4.14284753799 -9.41268825531,0.185577094555,4.17342233658 -9.41369438171,0.185580551624,4.19121026993 -9.41770648956,0.186587125063,4.22778606415 -9.40971946716,0.186595931649,4.25935602188 -9.41573047638,0.187601953745,4.29594564438 -9.40774440765,0.187610760331,4.32751703262 -9.39875793457,0.187619864941,4.3590836525 -9.41076850891,0.188625052571,4.39966344833 -9.40777492523,0.188629195094,4.41545629501 -9.39978981018,0.189638018608,4.44703054428 -9.39880180359,0.189645767212,4.48259830475 -9.40181446075,0.190652579069,4.51917934418 -9.38982868195,0.190662160516,4.54875564575 -9.39184093475,0.191669270396,4.58533334732 -9.38885402679,0.191677376628,4.6199054718 -9.3868598938,0.191681459546,4.63669490814 -9.3878736496,0.192688837647,4.67326927185 -9.37988758087,0.192697957158,4.70583772659 -9.36790180206,0.192707613111,4.73541736603 -9.36591529846,0.193715661764,4.77098846436 -9.37592697144,0.194721475244,4.81256437302 -9.37593269348,0.194725185633,4.83035755157 -9.37394618988,0.195733219385,4.86593198776 -9.36995887756,0.19574162364,4.90050649643 -9.36397361755,0.196750402451,4.93408155441 -9.35598754883,0.196759566665,4.9666557312 -9.36399936676,0.197765663266,5.00724077225 -9.35701370239,0.197774752975,5.04081201553 -9.3580198288,0.198778584599,5.06059265137 -9.35903358459,0.198786124587,5.09817075729 -9.35004806519,0.199795603752,5.13074398041 -9.3590593338,0.200801551342,5.17233037949 -9.34807491302,0.200811639428,5.20489263535 -9.33908939362,0.200821131468,5.23746776581 -9.35109329224,0.201822653413,5.26226711273 -9.35010814667,0.20283074677,5.29984045029 -9.33212375641,0.202842161059,5.32840442657 -9.34013652802,0.203848540783,5.37098312378 -9.33815002441,0.204856708646,5.40756464005 -9.33316421509,0.204865604639,5.4431385994 -9.33117866516,0.205873981118,5.48071193695 -9.33418464661,0.205877348781,5.50150346756 -9.32120037079,0.205887883902,5.53307104111 -9.3182144165,0.206896364689,5.56965112686 -9.32122707367,0.207903787494,5.61022949219 -9.31924152374,0.208912342787,5.64879798889 -9.31425571442,0.208921208978,5.68438005447 -9.32226848602,0.209927842021,5.72895431519 -9.30227851868,0.20993553102,5.73574590683 -9.30129337311,0.210943952203,5.77531480789 -9.31130409241,0.211950093508,5.82089614868 -9.2933216095,0.211961641908,5.84946870804 -9.29533576965,0.212969481945,5.89104175568 -9.29534912109,0.213977754116,5.93161344528 -9.28936481476,0.213987112045,5.96818637848 -9.3003692627,0.21498902142,5.99498224258 -9.29938316345,0.215997353196,6.03456115723 -9.28539943695,0.216008260846,6.06613492966 -9.28141498566,0.217017352581,6.10470581055 -9.28642845154,0.218024715781,6.14928007126 -9.27244472504,0.218035623431,6.18085622787 -9.28444957733,0.219037517905,6.2096452713 -9.27946472168,0.220046669245,6.24722480774 -9.27347946167,0.220056161284,6.28479909897 -9.27049541473,0.221065074205,6.32437515259 -9.26950931549,0.222073704004,6.36594772339 -9.25652599335,0.222084477544,6.39852619171 -9.25154209137,0.223094016314,6.43809270859 -9.26454544067,0.224095627666,6.46788692474 -9.25556182861,0.22510586679,6.50445747375 -9.25757598877,0.226113826036,6.5480389595 -9.25159168243,0.226123452187,6.58661317825 -9.23660945892,0.226134881377,6.61918306351 -9.23262405396,0.227144002914,6.65876531601 -9.24063682556,0.229151055217,6.70833778381 -9.24164485931,0.229155182838,6.73112297058 -9.23766040802,0.230164468288,6.77169942856 -9.24067306519,0.231172338128,6.81728029251 -9.22269248962,0.231184586883,6.8488445282 -9.23370361328,0.233190864325,6.90043020248 -9.22671985626,0.233200907707,6.94000053406 -9.21673774719,0.234211564064,6.97756958008 -9.22574234009,0.235213860869,7.00537204742 -9.22475719452,0.23622277379,7.04994392395 -9.19777870178,0.23623675108,7.07451295853 -9.23278617859,0.238238632679,7.14709186554 -9.08783149719,0.232275873423,7.08063459396 -9.05885410309,0.232290506363,7.10419464111 -9.14184188843,0.237278223038,7.19001531601 -9.09086894989,0.235297188163,7.1965713501 -9.01989936829,0.233319967985,7.18613147736 -8.95692825317,0.231341227889,7.18169212341 -8.94294643402,0.231352671981,7.21527099609 -8.89697170258,0.230370789766,7.22482776642 -8.94796848297,0.233365088701,7.28862857819 -8.94098472595,0.234375178814,7.32820987701 -8.91400623322,0.234389483929,7.35277462006 -8.9190196991,0.235397219658,7.40235948563 -9.07000160217,0.244376122952,7.57396936417 -9.18199157715,0.251362711191,7.71457386017 -9.18900489807,0.25237005949,7.76815748215 -9.19701099396,0.253373026848,7.79994106293 -9.1860294342,0.254384160042,7.83951425552 -9.18504428864,0.255393147469,7.88709545135 -9.18305969238,0.256402671337,7.93566274643 -9.16707897186,0.257414758205,7.97123718262 -9.17009449005,0.258423179388,8.02381229401 -9.15311336517,0.258435457945,8.0583896637 -9.32708072662,0.268405050039,8.23522281647 -9.28810405731,0.267421960831,8.252784729 -9.28112125397,0.268432408571,8.29835605621 -9.26514053345,0.26944449544,8.33493518829 -9.26715564728,0.270453304052,8.38950443268 -9.26217269897,0.27146333456,8.43707942963 -9.24519252777,0.272475749254,8.47365474701 -9.24819850922,0.273479640484,8.50244617462 -9.26121139526,0.275486290455,8.56801795959 -9.24523067474,0.275498449802,8.60559749603 -9.24324703217,0.277507990599,8.65717124939 -9.25226020813,0.2785153687,8.71974658966 -9.23628044128,0.279527693987,8.75832176208 -9.23728752136,0.280532002449,8.78611278534 -9.24130153656,0.281540453434,8.84468650818 -9.23231983185,0.282551497221,8.89125823975 -9.23133563995,0.284560799599,8.94483947754 -9.20635700226,0.284575104713,8.97640705109 -9.20537376404,0.285584539175,9.03098297119 -9.18940067291,0.287601649761,9.09934329987 -9.12843132019,0.285623162985,9.09490966797 -9.09845542908,0.285638689995,9.12247085571 -9.08847332001,0.286650031805,9.16904449463 -9.08149051666,0.287660568953,9.217628479 -9.07050991058,0.288672238588,9.26419734955 -9.0715265274,0.290681391954,9.32277297974 -9.07053375244,0.291686266661,9.35056114197 -9.0705499649,0.292695730925,9.40913295746 -9.05856895447,0.293707489967,9.45470905304 -9.05958557129,0.295716673136,9.51428604126 -9.04360485077,0.29672935605,9.55685710907 -9.04662036896,0.297738194466,9.61943340302 -9.04862785339,0.298742473125,9.651222229 -9.05364322662,0.30075097084,9.71679782867 -9.01267051697,0.300768762827,9.7333650589 -8.94870281219,0.298791080713,9.72393417358 -8.88873386383,0.296812802553,9.71949672699 -8.83976268768,0.29583221674,9.72606563568 -8.78179359436,0.293853789568,9.72461700439 -8.76180648804,0.293862402439,9.73141098022 -8.75582408905,0.295873254538,9.78598308563 -8.74784374237,0.296884357929,9.83756160736 -8.74586105347,0.298894554377,9.89812850952 -8.73787975311,0.299905717373,9.95070457458 -8.95084190369,0.313871920109,10.2553262711 -8.98385047913,0.317874759436,10.3569126129 -8.99985408783,0.31987631321,10.4077043533 -8.98687458038,0.320888608694,10.4582767487 -8.98889064789,0.32289776206,10.5258560181 -8.97890949249,0.323909640312,10.5814228058 -8.96692943573,0.325921624899,10.6330032349 -8.95994758606,0.326932698488,10.6915788651 -8.97895145416,0.328933745623,10.7483673096 -8.96497154236,0.329946190119,10.7989435196 -8.95798969269,0.331957310438,10.8585214615 -8.95600700378,0.333967477083,10.9250946045 -8.94802570343,0.335978984833,10.985663414 -8.94404411316,0.336989492178,11.0502405167 -8.94206142426,0.338999658823,11.1178178787 -8.9390707016,0.34000518918,11.1496038437 -8.97807693481,0.345006972551,11.2691888809 -9.08606624603,0.353994727135,11.4767866135 -3.44155502319,0.00615137815475,4.40751504898 -3.43957471848,0.00716155627742,4.43210315704 -3.4315969944,0.00717347068712,4.45066928864 -8.91020488739,0.355084747076,11.6584224701 -8.90122509003,0.357096463442,11.7219963074 -8.89724349976,0.359107196331,11.7925710678 -8.89026260376,0.361118584871,11.8601436615 -8.87528324127,0.362131536007,11.9167194366 -8.89828586578,0.365131825209,11.9865093231 -8.88130664825,0.366145193577,12.0410861969 -8.87432575226,0.368156522512,12.1096630096 -8.86934566498,0.370167523623,12.1822376251 -8.86236476898,0.372178852558,12.2518148422 -8.84838485718,0.374191761017,12.3133859634 -8.83940505981,0.376203626394,12.3819599152 -8.86040782928,0.379204273224,12.4517536163 -8.84842777252,0.380216807127,12.517326355 -8.83744907379,0.382229149342,12.584897995 -8.83246707916,0.385240226984,12.6614732742 -8.82048797607,0.387252688408,12.7280483246 -8.81150817871,0.389264583588,12.7996244431 -8.81252574921,0.391274422407,12.8862028122 -8.81553268433,0.393279016018,12.9349851608 -8.81555080414,0.396289080381,13.0215616226 -8.80457115173,0.398301362991,13.0921392441 -8.7905921936,0.40031427145,13.1587171555 -8.79360961914,0.403323799372,13.2522935867 -8.78362941742,0.405336081982,13.3278636932 -8.79563522339,0.407338768244,13.3916521072 -8.78265571594,0.409351468086,13.462228775 -8.78067493439,0.412362158298,13.5518016815 -8.76569652557,0.414375305176,13.6203804016 -8.7617149353,0.417386353016,13.7079544067 -8.7537355423,0.419398188591,13.7895307541 -8.73675823212,0.421411901712,13.8581027985 -8.75276184082,0.42441368103,13.9308958054 -8.74978065491,0.427424520254,14.0224723816 -8.73280334473,0.429438382387,14.0940408707 -8.72682285309,0.432449728251,14.1816215515 -8.72184181213,0.435461103916,14.2731952667 -8.71386241913,0.437472939491,14.3597726822 -8.72886657715,0.440475076437,14.4355611801 -8.72088718414,0.443487018347,14.5241365433 -8.7019109726,0.445501238108,14.5957078934 -8.6949300766,0.448512941599,14.6872854233 -8.68894958496,0.451524615288,14.7828578949 -8.67897129059,0.453536868095,14.8704366684 -8.66899204254,0.456549376249,14.9610090256 -8.68499565125,0.459551215172,15.0418014526 -8.66901874542,0.462565004826,15.1243696213 -8.66703796387,0.465575665236,15.2289524078 -8.6540594101,0.468588858843,15.318520546 -8.64407920837,0.471601128578,15.4111013412 -8.63710021973,0.474613070488,15.512673378 -8.62412166595,0.477626055479,15.6022529602 -8.63412857056,0.480629324913,15.6790390015 -8.63014698029,0.483640551567,15.7876157761 -8.6211681366,0.487652808428,15.8881931305 -8.60519123077,0.489666670561,15.978761673 -8.59421348572,0.493679314852,16.0773391724 -8.58623313904,0.496691375971,16.1829185486 -8.56725692749,0.499705940485,16.271484375 -8.58326148987,0.502707779408,16.362279892 -8.58028125763,0.506718873978,16.4808578491 -8.57430076599,0.510730743408,16.5964298248 -8.56132316589,0.513743937016,16.6990032196 -8.54734611511,0.517757356167,16.8005771637 -8.53736686707,0.520769894123,16.9111537933 -8.55137252808,0.524772286415,17.0039463043 -8.53939437866,0.527785301208,17.1125221252 -8.53041553497,0.53179782629,17.2300930023 -8.5174369812,0.535811007023,17.3396682739 -8.51245689392,0.539822697639,17.4682407379 -8.48148536682,0.541839599609,17.5428161621 -8.30155563354,0.530886530876,17.3073730469 -8.22358798981,0.525907695293,17.2141494751 -8.14363002777,0.523934602737,17.1857128143 -8.08966445923,0.523956000805,17.2082901001 -8.03569889069,0.523977637291,17.2338562012 -7.98173379898,0.523999333382,17.2604217529 -7.8907790184,0.521028220654,17.2029933929 -7.84481143951,0.521048247814,17.2455615997 -7.79083633423,0.519064426422,17.1973457336 -7.77186107635,0.522078990936,17.2999172211 -7.68690490723,0.519106805325,17.254486084 -7.59695053101,0.516135513783,17.1960544586 -6.16938829422,0.384433746338,14.0834751129 -7.4610285759,0.513184309006,17.1781921387 -7.51502227783,0.521178841591,17.3769874573 -7.35408878326,0.511221885681,17.1515464783 -7.27513122559,0.508248448372,17.1141166687 -7.18217754364,0.50427788496,17.0436820984 -6.11851119995,0.403502225876,14.6461515427 -7.06625080109,0.503322601318,17.0658245087 -5.87562179565,0.388572096825,14.3142871857 -6.03058576584,0.406546384096,14.7580900192 -5.96962308884,0.404569119215,14.7386665344 -5.90266275406,0.402593165636,14.7052383423 -5.95566701889,0.413593322039,14.9738178253 -5.87171125412,0.409620702267,14.8973903656 -5.88572692871,0.415628492832,15.0699729919 -5.8907456398,0.421638220549,15.2245473862 -5.9057507515,0.425640553236,15.3343372345 -5.84278964996,0.423663765192,15.3129119873 -5.7888250351,0.422685116529,15.3134899139 -5.7718501091,0.426699310541,15.4160604477 -5.72088479996,0.426719933748,15.4236431122 -5.66792058945,0.425741314888,15.4302129745 -5.70791864395,0.432738691568,15.6150035858 -5.67994689941,0.43575489521,15.689581871 -5.67996692657,0.440765708685,15.8461561203 -5.65399456024,0.443781495094,15.9287366867 -5.62902212143,0.446797221899,16.0183086395 -5.61604547501,0.450810402632,16.1408920288 -5.60606861115,0.455823034048,16.275472641 -5.64906549454,0.463819861412,16.4842643738 -5.60609912872,0.464839160442,16.5278377533 -5.58712434769,0.468853533268,16.641418457 -5.57814693451,0.47486615181,16.7899932861 -5.56117248535,0.478880256414,16.9155693054 -5.55219554901,0.483892828226,17.06914711 -5.52722263336,0.487908452749,17.1737270355 -4.17363977432,0.320180922747,13.0274391174 -4.12767410278,0.319200694561,13.02501297 -4.07870912552,0.318221002817,13.0125865936 -6.90887546539,0.692673265934,22.3123550415 -7.15782022476,0.734635055065,23.376953125 -7.07486486435,0.733662486076,23.368522644 -6.99690818787,0.732688784599,23.3730964661 -6.95193195343,0.731703221798,23.356880188 -6.86897706985,0.730730414391,23.343454361 -6.78702163696,0.729757666588,23.3360233307 -6.70906496048,0.728783965111,23.3395957947 -6.62711048126,0.727811098099,23.3311653137 -6.5481543541,0.726837575436,23.3307380676 -6.50717687607,0.72585105896,23.3235263824 -6.4262213707,0.724877893925,23.3140983582 -6.34726572037,0.723904430866,23.314666748 -6.26731014252,0.722931087017,23.3092403412 -6.18635463715,0.721957743168,23.2948188782 -6.10939836502,0.720983803272,23.3003902435 -6.03144216537,0.721009969711,23.2999629974 -5.98846578598,0.720023870468,23.2837505341 -5.90951013565,0.719050228596,23.2793216705 -5.83055496216,0.718076705933,23.2758922577 -5.75659751892,0.718101978302,23.2874698639 -5.43071746826,0.676176309586,22.2660274506 -5.59768676758,0.716154754162,23.269618988 -5.55470991135,0.714168548584,23.2494068146 -5.47675466537,0.714194655418,23.2469787598 -5.39979839325,0.713220477104,23.2465515137 -5.31984329224,0.712246894836,23.2311286926 -5.24588680267,0.71127218008,23.2437019348 -5.16992998123,0.711297750473,23.2442798615 -5.11196804047,0.714319884777,23.3278560638 -5.12897348404,0.723322093487,23.585641861 -5.10700082779,0.73333722353,23.8442230225 -5.05303812027,0.737358570099,23.9587993622 -3.24961161613,0.408716499805,15.6173267365 -3.18865132332,0.406738936901,15.5709009171 -3.13568806648,0.405759602785,15.5564861298 -3.07872653008,0.403781145811,15.5250644684 -3.05774331093,0.404790461063,15.5468540192 -3.00478053093,0.403811216354,15.5344333649 -2.96881246567,0.406828731298,15.6120109558 -2.92584657669,0.407847434282,15.650595665 -2.87688231468,0.407867342234,15.6591768265 -2.84391355515,0.411884278059,15.7597532272 -4.84931755066,0.868512272835,27.4503707886 -4.86332368851,0.880515038967,27.7831611633 -4.83735227585,0.894530951977,28.1557388306 -4.80238342285,0.907548606396,28.492313385 -4.81242179871,0.953568458557,29.6864776611 -4.72147083282,0.953596770763,29.7170505524 -4.72348070145,0.965601861477,30.0338420868 -4.6875128746,0.980619668961,30.4314174652 -4.65554332733,0.99763661623,30.8649978638 -4.61657619476,1.01265513897,31.2785739899 -4.58460664749,1.03067195415,31.7511539459 -4.54863882065,1.04868960381,32.2157325745 -4.54567098618,1.09070670605,33.3320999146 -4.48271179199,1.10272943974,33.6606788635 -4.43874597549,1.12174880505,34.1532592773 -4.3877825737,1.13876926899,34.6148338318 -4.28383588791,1.14079976082,34.6644096375 -4.30884885788,1.18380594254,35.7919921875 -4.34184932709,1.21380531788,36.5567817688 -4.27189254761,1.22882938385,36.9613571167 -2.67840743065,0.716138601303,23.7539253235 -2.595454216,0.713164746761,23.686504364 -2.52049851418,0.71318924427,23.6820869446 -2.44854187965,0.713213264942,23.7136688232 -2.40557646751,0.726231813431,24.0362491608 -3.76916384697,1.28298342228,38.4190368652 -3.66021895409,1.28801453114,38.5556144714 -3.55027413368,1.29204571247,38.6821937561 -3.4403295517,1.29707705975,38.8337669373 -3.32938528061,1.30210852623,38.9733505249 -3.21844100952,1.30813992023,39.1229286194 -3.10949587822,1.3141708374,39.2975082397 -3.06052184105,1.32118523121,39.4742965698 -2.94757795334,1.32721674442,39.6288757324 -2.83263516426,1.33224868774,39.7704582214 -2.71669220924,1.33728098869,39.9220314026 -2.60074973106,1.34331285954,40.067615509 -2.21289134026,1.17739474773,35.7872009277 -2.08695197105,1.16842854023,35.567779541 -2.03697824478,1.17244303226,35.6725730896 -1.92303490639,1.17047441006,35.6361541748 -1.81908845901,1.17650401592,35.7937355042 -1.70714449883,1.17753481865,35.8103179932 -1.59620046616,1.17956566811,35.8588981628 -1.48125755787,1.17659711838,35.7974815369 -1.42828476429,1.17961192131,35.8902702332 -1.31734061241,1.18264257908,35.9518508911 -1.20339739323,1.18067359924,35.9054374695 -1.09345293045,1.18470394611,36.0100212097 -0.982508957386,1.18773448467,36.1086006165 -0.872564554214,1.19276463985,36.2431869507 -0.76361978054,1.20279467106,36.4837684631 -0.709647238255,1.20880961418,36.6505584717 -0.60270190239,1.22883915901,37.163143158 -0.492757618427,1.24986922741,37.7177276611 -0.440795779228,1.52688896656,44.8992958069 -0.300860762596,1.53292441368,45.0678825378 -0.145930022001,1.35896217823,40.5374755859 -0.0819607377052,1.3619787693,40.6352653503 --0.124940216541,1.60503220558,40.6555938721 --0.250879645348,1.59306490421,40.3861808777 --0.376819074154,1.58709740639,40.2617645264 --0.500759243965,1.58112931252,40.1093521118 --0.624699234962,1.5731613636,39.9399375916 --0.745640218258,1.56219291687,39.6915245056 --0.806610584259,1.55920863152,39.6183128357 --0.928551256657,1.55424022675,39.4949035645 --1.05049204826,1.55127167702,39.4314918518 --1.17443215847,1.55130338669,39.4340782166 --1.29637289047,1.54833471775,39.3516616821 --1.41731381416,1.54536569118,39.2772521973 --1.47728466988,1.54338121414,39.2360458374 --1.59922528267,1.54141235352,39.1916313171 --1.72316539288,1.5424438715,39.2072219849 --1.84610593319,1.54247510433,39.1998138428 --1.9670470953,1.54050576687,39.1534004211 --2.0879881382,1.53953647614,39.1129875183 --2.21092867851,1.53956747055,39.1055793762 --2.27189898491,1.53858292103,39.0893745422 --2.39084076881,1.53661310673,39.0199623108 --2.51378154755,1.53664398193,39.0155487061 --1.86091959476,0.914559423923,25.0542583466 --1.95586907864,0.924585342407,25.2668533325 --2.08577537537,0.887631654739,24.427816391 --2.16073107719,0.887653887272,24.4104118347 --2.23668622971,0.886676371098,24.3889961243 --2.31963968277,0.889699995518,24.4515895844 --2.45257711411,0.915732145309,25.0201835632 --2.42457532883,0.88573205471,24.3359737396 --2.5645108223,0.913765192032,24.9545707703 --4.65677833557,1.61015713215,40.4680366516 --4.7337436676,1.61517465115,40.5708312988 --4.88467597961,1.62420880795,40.7564277649 --5.03560829163,1.63224303722,40.9230232239 --5.18154239655,1.63827610016,41.0486183167 --5.32147789001,1.64230835438,41.1152153015 --5.46841192245,1.64834141731,41.2308120728 --5.61134624481,1.65337383747,41.315410614 --5.70130825043,1.66139316559,41.4872093201 --5.85024166107,1.66742646694,41.6068077087 --6.0021739006,1.67446017265,41.7364044189 --6.15110635757,1.67949330807,41.8330001831 --6.30203914642,1.68552660942,41.9435997009 --6.45097255707,1.69055950642,42.0361976624 --6.59890651703,1.69559204578,42.1217956543 --6.68286991119,1.69960999489,42.2195968628 --6.83980083466,1.70664405823,42.3521995544 --7.01472616196,1.71868085861,42.5837974548 --7.06569004059,1.69669723511,42.0683937073 --7.1176533699,1.67471349239,41.5729866028 --7.2355966568,1.67174065113,41.4775848389 --7.32055997849,1.67675852776,41.5803871155 --7.45649766922,1.67778861523,41.583984375 --7.60143280029,1.68181991577,41.640586853 --7.74136924744,1.68385052681,41.6671905518 --7.87930631638,1.6858805418,41.6777877808 --8.02024269104,1.68791091442,41.7073898315 --8.15218162537,1.68893992901,41.6849899292 --7.66930007935,1.53387272358,38.2443504333 --7.79124259949,1.53490006924,38.2289505005 --7.91718387604,1.53592789173,38.2335510254 --8.03812599182,1.53595471382,38.2121505737 --6.8674659729,1.26077413559,32.1196594238 --7.00240468979,1.26780354977,32.2562637329 --6.49055147171,1.14972555637,29.662021637 --6.49752902985,1.13173449039,29.2506103516 --6.5584897995,1.12575209141,29.0912075043 --6.63844537735,1.12377262115,29.0218067169 --6.73339605331,1.12379562855,29.0144042969 --6.82434797287,1.124817729,28.9940032959 --6.91430044174,1.12383973598,28.9646015167 --6.95827674866,1.12385046482,28.9474010468 --7.05022859573,1.12387263775,28.9310016632 --7.14317989349,1.12489497662,28.915599823 --7.23513174057,1.12491703033,28.8951969147 --7.37806797028,1.1339468956,29.0788021088 --7.45402526855,1.13096618652,28.9974040985 --7.48000717163,1.12797403336,28.9081993103 --7.57295894623,1.12799596786,28.8938026428 --7.39099407196,1.08097505569,27.8353748322 --7.29300403595,1.04896736145,27.1189594269 --7.30198192596,1.0359762907,26.8135509491 --7.02104711533,0.974940359592,25.4611186981 --6.99203586578,0.956943452358,25.0457077026 --6.98600769043,0.935953915119,24.5730934143 --7.085958004,0.939976751804,24.6296958923 --7.33980131149,0.931045234203,24.3530902863 --9.0408821106,0.945442974567,24.1017303467 --9.12084007263,0.946460962296,24.0823307037 --9.20079708099,0.946478903294,24.0639343262 --9.28275299072,0.947497010231,24.0515403748 --9.70054531097,0.957584619522,24.1127700806 --9.83748531342,0.964610099792,24.2313785553 --9.9974193573,0.974638640881,24.4049930573 --13.288435936,1.35610258579,32.3312034607 --13.3054132462,1.34610974789,32.0848007202 --13.286400795,1.333111763,31.755399704 --13.2783851624,1.32011532784,31.454996109 --13.2623729706,1.30711770058,31.1445941925 --13.2453603745,1.29412007332,30.8321895599 --13.2353458405,1.28212344646,30.5417861938 --13.1743545532,1.27011728287,30.2695770264 --13.1723384857,1.25912177563,30.0061759949 --13.1483278275,1.24612307549,29.695772171 --13.1413116455,1.23512673378,29.4273681641 --13.1242990494,1.22312903404,29.1429672241 --13.1162853241,1.21313261986,28.881565094 --13.0612916946,1.20212745667,28.6383552551 --13.0512771606,1.19113063812,28.3789520264 --13.0352649689,1.18013322353,28.1085453033 --13.030248642,1.17013704777,27.8681468964 --13.019235611,1.16014015675,27.6147403717 --13.0072212219,1.14914309978,27.3663406372 --12.9962081909,1.13914620876,27.1209354401 --12.9452133179,1.13014173508,26.9037265778 --12.9312000275,1.12014448643,26.6593227386 --12.9281845093,1.11114859581,26.4399204254 --12.9201698303,1.10215210915,26.2125167847 --9.05327129364,0.70465105772,18.1875343323 --9.09524059296,0.703662633896,18.1281356812 --9.122215271,0.700672268867,18.0397357941 --9.14619922638,0.700678408146,18.0165367126 --9.20116424561,0.699691593647,17.9841403961 --9.25213241577,0.699704229832,17.9437427521 --9.32309341431,0.700719356537,17.9413471222 --9.39305496216,0.702734231949,17.937953949 --9.46201705933,0.703748941422,17.9305553436 --9.52698993683,0.706760168076,17.986366272 --9.59995079041,0.708775222301,17.9859695435 --12.7420330048,1.00017821789,23.7300701141 --12.728020668,0.992180943489,23.5236644745 --12.7080097198,0.983182787895,23.3112621307 --12.7549791336,0.980193078518,23.2218666077 --12.8489360809,0.982209146023,23.2194805145 --12.8889160156,0.98321634531,23.2042827606 --12.9378852844,0.980226635933,23.1198883057 --12.9108772278,0.971227526665,22.9014835358 --12.8668718338,0.961226344109,22.6550750732 --12.8168706894,0.950224399567,22.4016666412 --12.8228521347,0.944229364395,22.2482662201 --12.7998418808,0.936230778694,22.0468616486 --12.761844635,0.930228233337,21.9006519318 --12.7548294067,0.92323166132,21.7302494049 --12.7488145828,0.916235089302,21.5618419647 --14.024438858,1.02239274979,23.5606594086 --12.5938253403,0.89122492075,20.9930114746 --12.5758142471,0.884226918221,20.8146114349 --12.5138235092,0.876221716404,20.6373996735 --12.5308017731,0.872227966785,20.5190010071 --12.5717744827,0.870236992836,20.4396038055 --12.6677312851,0.872252464294,20.4512176514 --12.7206993103,0.871262788773,20.3918228149 --12.6257104874,0.858255803585,20.0974082947 --12.6846780777,0.85826677084,20.0500144958 --12.8346281052,0.867286145687,20.2178440094 --12.6186714172,0.844265222549,19.7363986969 --12.7286243439,0.848281919956,19.7700157166 --12.7875919342,0.848292708397,19.7246246338 --12.8385620117,0.847302377224,19.6672325134 --12.6555967331,0.827285528183,19.2517967224 --12.6415843964,0.821287930012,19.0983943939 --12.6745672226,0.821293592453,19.0832004547 --12.7365350723,0.821304559708,19.0448074341 --12.8074979782,0.822316348553,19.0204181671 --12.7644948959,0.814315378666,18.8270072937 --12.9454298019,0.824339270592,18.9666423798 --12.3755693436,0.774280071259,18.0031299591 --12.4115514755,0.775286018848,17.9949378967 --12.4835166931,0.776297867298,17.9775485992 --12.4615058899,0.770299434662,17.8241405487 --12.4864835739,0.767306029797,17.7407474518 --12.5284566879,0.766314446926,17.6813526154 --12.5554332733,0.764321208,17.5999526978 --12.5804109573,0.762327671051,17.5185604095 --12.5734052658,0.759328842163,17.4493541718 --12.5863857269,0.756334006786,17.3509540558 --12.6303577423,0.755342364311,17.2965641022 --12.7153196335,0.757355093956,17.2981777191 --12.6763143539,0.750354647636,17.1307697296 --12.7362833023,0.751364588737,17.0983791351 --12.7562618256,0.748370289803,17.0109767914 --12.3913526535,0.719334185123,16.4677047729 --12.4493207932,0.720343887806,16.4363136292 --12.5412807465,0.723357141018,16.448928833 --12.5342674255,0.718360006809,16.3315258026 --8.95520114899,0.45299962163,11.556344986 --8.98517608643,0.452008038759,11.5199489594 --9.04715061188,0.456017106771,11.5607528687 --9.06512832642,0.454024255276,11.5083522797 --12.3102579117,0.685353755951,15.5716676712 --12.4402084351,0.691370427608,15.6352949142 --12.5171718597,0.693381607533,15.629907608 --12.591137886,0.695392370224,15.6215238571 --12.6551065445,0.696402132511,15.6001377106 --12.7200813293,0.699410200119,15.6289453506 --12.7970466614,0.70142108202,15.6225614548 --12.868013382,0.702431261539,15.608174324 --12.9399795532,0.70444136858,15.5957918167 --13.0259428024,0.707452774048,15.5994100571 --13.0929098129,0.708462297916,15.5790233612 --13.1758737564,0.710473239422,15.5776395798 --13.2298526764,0.712479829788,15.5914497375 --13.3118171692,0.71449059248,15.5870637894 --13.3787851334,0.716499686241,15.5666809082 --13.4217605591,0.71550655365,15.51628685 --13.5287179947,0.719519257545,15.5419149399 --13.6176815033,0.722530126572,15.5435285568 --13.6726531982,0.722537815571,15.5081443787 --13.7516260147,0.726546287537,15.5479602814 --13.7856025696,0.725551962852,15.4875679016 --13.9135560989,0.73056602478,15.5321950912 --20.7338104248,1.183177948,23.0623626709 --15.9050245285,0.856747627258,17.5488605499 --15.9689950943,0.857754528522,17.5084762573 --21.0647029877,1.19320380688,23.063457489 --21.1846618652,1.19621276855,23.0480899811 --12.0109586716,0.58841407299,12.9285383224 --12.0369377136,0.587419688702,12.8741416931 --12.0219259262,0.583421766758,12.7757329941 --12.0369081497,0.581426382065,12.7103347778 --12.0408916473,0.579429984093,12.633934021 --12.0968704224,0.581436395645,12.6527462006 --12.1558418274,0.583444535732,12.6343593597 --12.1498289108,0.58044731617,12.547955513 --12.1538133621,0.577450811863,12.4715499878 --12.1498003006,0.57545363903,12.3891515732 --12.1477861404,0.572456657887,12.3067407608 --12.148771286,0.570459783077,12.230342865 --12.1267700195,0.567459642887,12.1691360474 --12.1177577972,0.564462006092,12.0827312469 --12.1207418442,0.562465369701,12.0083265305 --12.1147298813,0.55946791172,11.9269275665 --12.1067171097,0.556470394135,11.8425197601 --12.1087026596,0.554473638535,11.7691173553 --12.1086883545,0.552476644516,11.6947174072 --12.0946846008,0.550477087498,11.6435108185 --12.0866737366,0.547479450703,11.5621089935 --12.0846595764,0.544482350349,11.4857006073 --12.0886449814,0.542485535145,11.4173049927 --12.0806322098,0.540488004684,11.335893631 --12.0836172104,0.538491129875,11.2674980164 --12.0626153946,0.53549104929,11.2112884521 --12.0576028824,0.533493578434,11.1348838806 --12.0585889816,0.531496524811,11.0654850006 --12.0545749664,0.528499186039,10.9900760651 --12.0555620193,0.526502132416,10.920674324 --12.0455503464,0.524504303932,10.8422718048 --12.0475358963,0.522507250309,10.7738647461 --12.0305328369,0.520507514477,10.7246627808 --12.0295200348,0.518510222435,10.6552610397 --12.0235071182,0.515512645245,10.5808534622 --12.0234928131,0.513515412807,10.5134534836 --12.0214805603,0.511518061161,10.4440507889 --12.0224666595,0.509520828724,10.3776483536 --12.0144548416,0.507523059845,10.3042449951 --12.0054502487,0.50552380085,10.2630405426 --11.9984378815,0.503526091576,10.1906347275 --12.0004243851,0.501528918743,10.1262311935 --11.9944124222,0.499531209469,10.0558271408 --11.9923992157,0.497533708811,9.98942661285 --11.9873876572,0.495536029339,9.92102527618 --11.9943723679,0.494539111853,9.86161994934 --11.9643716812,0.491538584232,9.80440807343 --11.9763555527,0.490541905165,9.75101280212 --11.9703445435,0.488544136286,9.68260765076 --11.9673309326,0.486546516418,9.61720561981 --11.9633188248,0.484548836946,9.55079936981 --11.964304924,0.482551425695,9.48939800262 --11.9632930756,0.480553865433,9.4259929657 --11.9452905655,0.478554069996,9.38078689575 --11.9402780533,0.476556271315,9.31538295746 --11.9342660904,0.474558413029,9.24897575378 --11.9402523041,0.473561227322,9.19257450104 --11.9342403412,0.471563309431,9.12817573547 --11.9332275391,0.469565689564,9.06677055359 --11.9142255783,0.46856585145,9.02256679535 --11.9162120819,0.466568350792,8.96416378021 --11.9381933212,0.466571927071,8.92076396942 --12.0241622925,0.469578772783,8.92638778687 --5.53553724289,0.107248082757,4.00087738037 --5.53651952744,0.10625449568,3.97447299957 --5.58649158478,0.108263373375,3.98408102989 --11.8831357956,0.454581856728,8.55753421783 --11.8861227036,0.453584253788,8.50213241577 --11.8841094971,0.451586455107,8.44272422791 --11.88509655,0.450588732958,8.38632202148 --11.8820848465,0.448590755463,8.32792186737 --11.877073288,0.447592705488,8.26852226257 --11.8610706329,0.445593088865,8.2283115387 --11.8660573959,0.444595485926,8.17591094971 --11.8590459824,0.442597299814,8.1155090332 --11.861032486,0.441599577665,8.06009864807 --11.8620204926,0.439601689577,8.00569820404 --11.8620080948,0.438603788614,7.95130109787 --11.8549976349,0.436605572701,7.89089012146 --11.8459920883,0.435606241226,7.8576874733 --11.8439807892,0.434608161449,7.80228757858 --11.8389692307,0.432609975338,7.74488449097 --11.8389568329,0.431612014771,7.69047880173 --11.8349456787,0.429613858461,7.63407516479 --11.8359336853,0.428615897894,7.58066892624 --11.8329229355,0.427617669106,7.52627134323 --11.8219184875,0.425618261099,7.49206256866 --11.8139076233,0.424619913101,7.43365478516 --11.8098974228,0.422621637583,7.37925720215 --11.809885025,0.421623528004,7.32685518265 --11.7928762436,0.419624835253,7.26344347 --11.8058614731,0.418627113104,7.22004842758 --11.8098497391,0.417629092932,7.17064714432 --11.7978458405,0.416629612446,7.13643455505 --11.794834137,0.41563129425,7.0840382576 --11.7888240814,0.413632899523,7.02862977982 --11.7918109894,0.412634789944,6.97922706604 --11.7917995453,0.411636501551,6.9288277626 --11.7957868576,0.410638332367,6.88042593002 --11.7807836533,0.409638732672,6.84621953964 --11.7747735977,0.407640308142,6.79181146622 --11.7747621536,0.406641989946,6.74140644073 --11.7677516937,0.405643433332,6.68800640106 --11.7657403946,0.40464502573,6.63659906387 --11.7627296448,0.402646571398,6.58519458771 --11.7647180557,0.4016482234,6.53679132462 --11.7537136078,0.400648742914,6.50659227371 --11.7487039566,0.3996501863,6.45418357849 --11.7446928024,0.398651629686,6.40378522873 --11.7986717224,0.399654388428,6.3843960762 --11.8376531601,0.400656700134,6.35700654984 --11.8386421204,0.399658113718,6.30961084366 --11.8366308212,0.398659497499,6.25920152664 --11.8486232758,0.398660421371,6.24100112915 --11.9205999374,0.401663124561,6.23162651062 --12.0025749207,0.404665887356,6.22725725174 --12.0725507736,0.407668352127,6.21487379074 --12.1415281296,0.409670591354,6.2024974823 --12.2814941406,0.415673881769,6.22715091705 --12.3284749985,0.416675508022,6.20176267624 --12.2954750061,0.414675503969,6.15954589844 --12.4864320755,0.423679053783,6.20821380615 --17.3965740204,0.665743649006,8.57915019989 --17.4475593567,0.666741251945,8.53577041626 --17.4975452423,0.668738722801,8.49138832092 --17.5415325165,0.668736040592,8.44400501251 --12.2834100723,0.407680600882,5.83692741394 --12.2784013748,0.406681269407,5.78652429581 --12.292388916,0.406682103872,5.74512577057 --12.2833805084,0.405682682991,5.69372701645 --12.4843378067,0.414684772491,5.74039173126 --17.8314552307,0.676719725132,8.20492458344 --17.8734474182,0.677718281746,8.19074440002 --14.8129367828,0.526698112488,6.70124292374 --14.7709360123,0.523696541786,6.62482595444 --14.6919403076,0.518694877625,6.53239870071 --14.6169452667,0.513693273067,6.44196844101 --14.5449495316,0.50869178772,6.3545460701 --14.4769525528,0.504690408707,6.26912164688 --14.4029598236,0.500689744949,6.20889425278 --14.3259649277,0.49568849802,6.12046480179 --14.2579669952,0.491687327623,6.03704118729 --14.199968338,0.487686216831,5.95862102509 --14.1219730377,0.483685195446,5.87118577957 --14.0529756546,0.478684276342,5.78875780106 --11.7363176346,0.366691857576,4.7614812851 --11.7323122025,0.365692198277,4.73828172684 --11.731303215,0.364692926407,4.69387531281 --11.6523046494,0.360694050789,4.61743879318 --11.6322984695,0.358694881201,4.56602716446 --11.6212892532,0.357695668936,4.51862049103 --11.6222801208,0.356696307659,4.47621822357 --11.6052722931,0.355697125196,4.42680883408 --11.5992689133,0.354697495699,4.40360975266 --11.6022586823,0.354698121548,4.36220693588 --11.5942497253,0.353698790073,4.31680202484 --11.5912408829,0.352699428797,4.27339792252 --11.5832328796,0.35170006752,4.22798967361 --11.5842227936,0.350700616837,4.18658971786 --11.5882120132,0.350701063871,4.14618873596 --11.5702104568,0.348701566458,4.11797475815 --11.5692014694,0.348702073097,4.07657766342 --11.5651922226,0.347702622414,4.03317022324 --11.5721817017,0.347702950239,3.99477577209 --11.5591745377,0.345703572035,3.94836473465 --11.5591659546,0.345703959465,3.9069609642 --11.5901527405,0.346703708172,3.87656998634 --11.5831489563,0.345704048872,3.85336470604 --11.5861387253,0.345704287291,3.81296014786 --11.591129303,0.344704449177,3.77355957031 --11.5791215897,0.343704968691,3.72915840149 --11.5781135559,0.342705190182,3.68775367737 --11.5801038742,0.342705368996,3.64734911919 --11.4561100006,0.336708664894,3.56589436531 --11.4481067657,0.335708975792,3.54369497299 --11.4500980377,0.335709184408,3.50429368019 --11.4410905838,0.33470967412,3.46088242531 --11.437081337,0.333709985018,3.41947627068 --11.4460725784,0.333709895611,3.38308358192 --11.4440631866,0.332710087299,3.34167027473 --11.4380550385,0.331710398197,3.30026650429 --11.4320516586,0.331710636616,3.27906727791 --11.4250440598,0.330710947514,3.23766422272 --11.4340343475,0.330710709095,3.20025897026 --11.4330253601,0.329710781574,3.16085934639 --11.4260177612,0.329711019993,3.11945343018 --11.4150114059,0.328711390495,3.07704591751 --11.420006752,0.328711181879,3.05884623528 --11.4129991531,0.32771140337,3.01743745804 --11.4069910049,0.326711565256,2.97703552246 --11.4109811783,0.326711326838,2.93862867355 --11.4079742432,0.325711280107,2.89922809601 --11.3979673386,0.324711561203,2.85782217979 --11.4069576263,0.324710994959,2.82142281532 --11.407954216,0.324710845947,2.80222058296 --11.3899469376,0.323711365461,2.75880932808 --11.4229354858,0.324709713459,2.72841787338 --11.3809318542,0.322711288929,2.68000531197 --11.3439283371,0.320712655783,2.63157820702 --11.3839159012,0.321710526943,2.60319256783 --11.4099054337,0.322708964348,2.57079672813 --11.4319000244,0.323707699776,2.55761218071 --11.4628887177,0.324705779552,2.52621865273 --11.5008773804,0.325703412294,2.49683380127 --11.502869606,0.325702756643,2.45943856239 --11.5188617706,0.325701326132,2.42403650284 --11.4648590088,0.322703510523,2.3736114502 --11.4808502197,0.323702037334,2.33921861649 --11.6978206635,0.332689255476,2.32870864868 --11.728811264,0.333686649799,2.29631829262 --11.763800621,0.334683686495,2.26493310928 --11.7887916565,0.335681200027,2.2305355072 --11.8197822571,0.336678355932,2.19815015793 --11.8567724228,0.337675005198,2.16676688194 --11.885766983,0.339672654867,2.15257453918 --11.9187583923,0.340669453144,2.12019085884 --11.9517498016,0.341666072607,2.08679842949 --11.9877405167,0.342662423849,2.05441403389 --12.020731926,0.3436588943,2.02102518082 --12.0547227859,0.345655202866,1.98763668537 --12.0817184448,0.346652686596,1.97345507145 --12.1197099686,0.347648561001,1.94006454945 --12.1597013474,0.349644184113,1.90768361092 --12.1896934509,0.350640416145,1.87329757214 --12.2236852646,0.351636230946,1.8389081955 --12.263677597,0.352631568909,1.80552351475 --12.3016700745,0.354626953602,1.77214324474 --12.3396625519,0.355622172356,1.73775541782 --12.3696575165,0.35761898756,1.72256994247 --12.3996505737,0.358614563942,1.68617391586 --12.4426431656,0.359609216452,1.65279638767 --12.5556306839,0.364598453045,1.62945091724 --12.5986242294,0.36659270525,1.59406030178 --12.641617775,0.367586880922,1.55968248844 --12.6766109467,0.369581520557,1.52329397202 --12.7146062851,0.370577245951,1.50811254978 --12.7615995407,0.3725707829,1.47373735905 --12.8025932312,0.374564647675,1.43735003471 --12.8235883713,0.375560075045,1.39896082878 --12.8735818863,0.377552986145,1.36358082294 --12.9105758667,0.37854680419,1.32619333267 --12.9425735474,0.37954261899,1.31001579762 --12.9655685425,0.380537480116,1.27062118053 --12.7295761108,0.369554549456,1.20311379433 --12.2765922546,0.349590808153,1.11249196529 --12.6685714722,0.366553753614,1.11427545547 --12.1235895157,0.342599213123,1.01862108707 --12.2485809326,0.34758540988,0.991270124912 --12.0795850754,0.340599417686,0.955996632576 --12.142578125,0.342591047287,0.922618687153 --12.1065750122,0.34059175849,0.880196809769 --13.1665353775,0.38848990202,0.935309588909 --13.1855316162,0.388484328985,0.894918620586 --12.2035598755,0.344574391842,0.772038638592 --13.4675178528,0.401449263096,0.832246422768 --13.4785175323,0.401446133852,0.812055706978 --13.5095148087,0.402438730001,0.770663619041 --12.0185527802,0.336582630873,0.622541069984 --12.2075443268,0.344560861588,0.597234487534 --13.6185064316,0.407414585352,0.648514330387 --12.2625360489,0.346549063921,0.522454559803 --12.2045345306,0.344551891088,0.48002409935 --12.3895282745,0.352531045675,0.470912992954 --12.6985197067,0.365495115519,0.44766074419 --12.4635219574,0.355516433716,0.396150290966 --12.1355237961,0.34054812789,0.340581446886 --12.1615209579,0.341542065144,0.303193300962 --12.1365184784,0.340541541576,0.263781964779 --12.1425151825,0.340537577868,0.225382760167 --12.150513649,0.341535001993,0.206183716655 --12.1485109329,0.340531885624,0.167784109712 --12.1455078125,0.34052875638,0.128373265266 --12.1365060806,0.340526372194,0.0899712368846 --12.1385030746,0.340522646904,0.0515715666115 --12.1374998093,0.340519249439,0.0131710451096 --12.1304979324,0.339516431093,-0.026241896674 --12.1284971237,0.339514881372,-0.0454428866506 --12.1354942322,0.340510427952,-0.0838410630822 --12.1714925766,0.34150236845,-0.122226394713 --12.1194896698,0.339505016804,-0.160649031401 --12.1614875793,0.341496109962,-0.199029818177 --12.0834856033,0.337501943111,-0.237469509244 --12.1314840317,0.339492082596,-0.276855826378 --12.0794820786,0.337496757507,-0.295075148344 --12.0684804916,0.337494283915,-0.333484262228 --12.0724782944,0.337489902973,-0.371884346008 --12.0774774551,0.337485313416,-0.41028341651 --12.1454763412,0.340472519398,-0.449648410082 --12.0824737549,0.337476670742,-0.487084209919 --12.1294736862,0.340466290712,-0.52747130394 --12.1264724731,0.339464604855,-0.546673595905 --12.1374702454,0.340458989143,-0.585065066814 --12.1264696121,0.340456217527,-0.623474597931 --12.1304683685,0.340451419353,-0.661871194839 --12.1234664917,0.340448051691,-0.700277805328 --12.1394662857,0.340441435575,-0.739672899246 --12.1334657669,0.340440034866,-0.758878588676 --12.215467453,0.344424009323,-0.80123758316 --12.6684808731,0.364355027676,-0.86240363121 --12.0414600372,0.336439698935,-0.870134353638 --12.2684679031,0.346402466297,-0.920410454273 --12.0984611511,0.339422404766,-0.949905276299 --11.9544553757,0.333438962698,-0.979380905628 --12.5934801102,0.36134237051,-1.03924953938 --12.0204563141,0.336422353983,-1.04094898701 --12.2994680405,0.348375767469,-1.09920835495 --12.0594568253,0.338407039642,-1.1207344532 --12.494477272,0.357335835695,-1.19291234016 --14.196559906,0.433069169521,-1.36640679836 --11.956451416,0.334408402443,-1.22799646854 --11.939450264,0.333408564329,-1.24621200562 --12.0554571152,0.338385552168,-1.2945523262 --11.9724521637,0.335393697023,-1.32499182224 --12.0244550705,0.337380409241,-1.36836755276 --12.2954711914,0.349331885576,-1.4326196909 --16.5897274017,0.541632294655,-1.90074813366 --12.3284749985,0.351315438747,-1.51541078091 --16.7067470551,0.546596884727,-1.99228024483 --16.790763855,0.550571858883,-2.05463194847 --16.8557758331,0.553549647331,-2.11599779129 --16.9157905579,0.55652821064,-2.17635941505 --16.9788036346,0.55950576067,-2.23872852325 --16.9288101196,0.557502448559,-2.28715181351 --16.5787963867,0.542550623417,-2.29773163795 --16.500793457,0.539558231831,-2.31497478485 --16.6498146057,0.546521067619,-2.38729357719 --17.3068752289,0.575394868851,-2.52733922005 --17.2498817444,0.573392152786,-2.57576918602 --16.482831955,0.539515316486,-2.52557873726 --16.5838489532,0.544485628605,-2.5929210186 --16.5928611755,0.54547226429,-2.64731025696 --16.2508354187,0.530527830124,-2.62469768524 --16.5788764954,0.545456826687,-2.72591567039 --16.5218791962,0.542455136776,-2.7713470459 --16.5038890839,0.542446494102,-2.82175207138 --14.6737289429,0.460773795843,-2.58515238762 --14.6857376099,0.46176186204,-2.63454294205 --14.6917448044,0.461750805378,-2.68394398689 --14.8107614517,0.467723548412,-2.72707295418 --14.0876960754,0.435850948095,-2.65287518501 --13.9776916504,0.4308629632,-2.67933177948 --13.9796981812,0.43185338378,-2.72573423386 --13.8986968994,0.427859932184,-2.75718140602 --13.6946802139,0.418890893459,-2.76468896866 --13.6466808319,0.417891353369,-2.80112028122 --13.8847122192,0.428839832544,-2.86818742752 --13.6076869965,0.415885776281,-2.86074090004 --13.7397089005,0.422850161791,-2.93207573891 --13.554693222,0.41487839818,-2.94057822227 --13.7877283096,0.425822019577,-3.03184556961 --13.5197019577,0.413867563009,-3.02239441872 --13.4997034073,0.412867128849,-3.04060554504 --13.5327148438,0.414851248264,-3.09198594093 --13.5077180862,0.413847059011,-3.13240838051 --13.4807214737,0.41384357214,-3.17081952095 --13.4987306595,0.414830327034,-3.22021579742 --13.5267419815,0.416815161705,-3.27059364319 --13.4527397156,0.413821518421,-3.29903674126 --13.4907484055,0.415808558464,-3.33021664619 --13.4257469177,0.412813007832,-3.36065745354 --13.7137947083,0.426740765572,-3.47289347649 --13.6357917786,0.423747867346,-3.5003387928 --13.5227842331,0.41876283288,-3.51880335808 --13.826836586,0.432685494423,-3.63802647591 --13.7398328781,0.429694414139,-3.66348075867 --13.6108179092,0.42371815443,-3.65475726128 --13.2817764282,0.408782303333,-3.61734461784 --13.3037881851,0.410767525434,-3.66773200035 --13.2717905045,0.409764826298,-3.70515751839 --13.2147903442,0.407768160105,-3.73458623886 --13.2248001099,0.408755928278,-3.78198027611 --13.1868019104,0.407754659653,-3.81740927696 --13.2218170166,0.409736424685,-3.87178945541 --13.4218549728,0.418684303761,-3.94887042046 --13.3838577271,0.417682796717,-3.98429465294 --13.5869016647,0.427623987198,-4.08657217026 --13.6459217072,0.430598884821,-4.14993858337 --13.606924057,0.429597258568,-4.18536043167 --13.544924736,0.427601099014,-4.21480369568 --13.5339269638,0.427598237991,-4.23501157761 --13.5949478149,0.430572241545,-4.29937267303 --13.7229824066,0.436529308558,-4.38469791412 --13.6929883957,0.436525195837,-4.42311668396 --13.6759958267,0.436517834663,-4.465528965 --13.6129951477,0.433522194624,-4.49296188354 --13.6400108337,0.435503572226,-4.54935073853 --13.5810050964,0.433512687683,-4.55458688736 --13.6380281448,0.436486423016,-4.61995172501 --13.6680459976,0.438466817141,-4.67733430862 --13.6790599823,0.439451962709,-4.7287273407 --13.5470457077,0.434474289417,-4.73320627213 --13.5350551605,0.434465259314,-4.77761983871 --17.317855835,0.611455738544,-6.09475946426 --17.3758792877,0.614431202412,-6.14492416382 --17.2088661194,0.60745716095,-6.14942121506 --16.7827949524,0.588553071022,-6.06306934357 --17.3339366913,0.615386664867,-6.31514310837 --17.660030365,0.631279826164,-6.49033880234 --17.6910610199,0.633251786232,-6.56472015381 --17.6620769501,0.633240282536,-6.61713266373 --17.6350822449,0.63223773241,-6.6393494606 --17.631105423,0.633219301701,-6.70074701309 --17.639131546,0.634197235107,-6.76714038849 --17.7221755981,0.639154016972,-6.86148738861 --20.005739212,0.748490214348,-7.78050708771 --17.3171272278,0.622228324413,-6.83652830124 --17.3541622162,0.625198185444,-6.91289997101 --17.3681774139,0.626184105873,-6.95009183884 --17.5552463531,0.636110305786,-7.08537387848 --17.5322666168,0.636096358299,-7.14078760147 --20.8561248779,0.795107662678,-8.51516151428 --20.6591091156,0.78613871336,-8.51367855072 --20.3700695038,0.774197638035,-8.47324848175 --20.5461483002,0.784119486809,-8.61953544617 --20.7812252045,0.795036613941,-8.75258636475 --20.9853153229,0.806948721409,-8.91285514832 --18.8237781525,0.704571604729,-8.09557723999 --18.8338088989,0.706545114517,-8.16896343231 --18.7518177032,0.703546285629,-8.20440864563 --20.7333908081,0.799915313721,-9.11758613586 --20.6333999634,0.795918226242,-9.1530456543 --20.5794029236,0.793921232224,-9.16827583313 --19.1660423279,0.727333247662,-8.6305398941 --18.8409843445,0.713409781456,-8.56013774872 --18.9740543365,0.72034317255,-8.69045162201 --20.9236488342,0.816701292992,-9.63163757324 --18.889093399,0.719319820404,-8.79629707336 --21.1057815552,0.827585160732,-9.87331199646 --21.1288070679,0.829562842846,-9.9244966507 --21.3109016418,0.840474486351,-10.0887765884 --22.5603179932,0.902038395405,-10.7493925095 --21.0969181061,0.832483768463,-10.1526985168 --22.5574073792,0.90597397089,-10.9211778641 --22.5104389191,0.904956221581,-10.9866018295 --20.8569660187,0.825472891331,-10.2820281982 --20.6739273071,0.817518949509,-10.2343378067 --20.6999778748,0.820480167866,-10.3277177811 --20.8470649719,0.828400194645,-10.4810218811 --21.9694709778,0.885989069939,-11.1147069931 --21.8034610748,0.879012465477,-11.1192064285 --21.3743648529,0.859127163887,-10.9898672104 --20.9772548676,0.841247498989,-10.8333177567 --21.0113105774,0.844204187393,-10.9336910248 --20.9773426056,0.844184160233,-11.0001068115 --20.9103622437,0.842175960541,-11.0485391617 --20.9594249725,0.846126556396,-11.1579036713 --21.1815452576,0.859015583992,-11.3581571579 --38.487651825,1.72482168674,-20.5415630341 --38.8798408508,1.74564743042,-20.8265037537 --38.6738700867,1.7386521101,-20.8740139008 --25.167137146,1.06545984745,-13.7939910889 --23.9257469177,1.00486886501,-13.2261743546 --25.2032680511,1.07136285305,-14.0187473297 --39.6646461487,1.80100941658,-22.0458889008 --37.9191055298,1.71658110619,-21.245382309 --37.9781799316,1.7215243578,-21.3565349579 --37.974281311,1.72445607185,-21.5109157562 --37.8623428345,1.72242772579,-21.6053657532 --35.2344436646,1.59234762192,-20.2734336853 --35.2335395813,1.59528279305,-20.4198131561 --35.2676506042,1.60020422935,-20.5871734619 --35.158706665,1.59818029404,-20.67162323 --35.0727233887,1.59518027306,-20.6958694458 --34.9427680969,1.59216427803,-20.7683372498 --34.8288192749,1.58914256096,-20.8487892151 --34.7138748169,1.58612108231,-20.9292469025 --34.5789146423,1.58310770988,-20.9967155457 --34.2718887329,1.5701624155,-20.9602985382 --34.4100456238,1.58104133606,-21.1915893555 --34.5821685791,1.59193921089,-21.3706703186 --34.7273292542,1.60281383991,-21.6089553833 --34.8464813232,1.61169719696,-21.8342609406 --36.1311340332,1.68210792542,-22.7848014832 --36.0472068787,1.68107008934,-22.8902339935 --35.123916626,1.63737618923,-22.4662227631 --35.2381248474,1.64822280407,-22.7717189789 --35.2592430115,1.65314233303,-22.9420871735 --35.0762710571,1.64714694023,-22.980588913 --35.0243530273,1.64809668064,-23.1040039062 --35.4906730652,1.6768270731,-23.5670757294 --32.7765464783,1.53690671921,-21.9372558594 --32.6635932922,1.53488719463,-22.0107135773 --32.5666007996,1.53089487553,-22.0199699402 --32.416633606,1.52689135075,-22.0684547424 --32.3166923523,1.52486634254,-22.1499061584 --32.2597618103,1.52582323551,-22.2593288422 --32.334903717,1.53372192383,-22.4596614838 --32.3990402222,1.54062449932,-22.6540031433 --33.9368972778,1.62687325478,-23.8723583221 --33.8869247437,1.62585866451,-23.9165821075 --33.6589279175,1.6178869009,-23.9151153564 --33.7260742188,1.62578260899,-24.1214561462 --33.5881156921,1.62177050114,-24.1829299927 --33.5422096252,1.62371683121,-24.309343338 --33.1771392822,1.6078081131,-24.2079753876 --33.1672477722,1.61173844337,-24.3593635559 --33.0002212524,1.60377800465,-24.3176689148 --33.3965415955,1.63051986694,-24.766784668 --33.5317268372,1.64138066769,-25.0280761719 --32.991558075,1.6165561676,-24.7918281555 --32.863609314,1.6135405302,-24.85729599 --32.6916351318,1.60854566097,-24.889799118 --32.8017539978,1.61645555496,-25.0529136658 --32.7248306274,1.61641478539,-25.1583538055 --32.6869277954,1.61835610867,-25.2917613983 --32.6190109253,1.6193113327,-25.4031925201 --32.6021194458,1.62224185467,-25.5535869598 --32.7002944946,1.63211548328,-25.7949047089 --32.5103111267,1.62612986565,-25.811416626 --32.4163169861,1.62313652039,-25.8206748962 --32.3954277039,1.6260676384,-25.9700737 --32.2974967957,1.62503683567,-26.0585250854 --32.5067405701,1.64185237885,-26.3927650452 --32.4028053284,1.6408239603,-26.4772205353 --32.2748603821,1.63780736923,-26.5426940918 --32.1759300232,1.6367764473,-26.631149292 --32.0138931274,1.6298186779,-26.5824508667 --32.0030174255,1.63374221325,-26.7438468933 --31.9080848694,1.6337095499,-26.8342971802 --31.7981472015,1.63168442249,-26.9127578735 --31.3840198517,1.6128180027,-26.7354316711 --31.1870269775,1.60584008694,-26.736951828 --31.0790882111,1.60481512547,-26.8144130707 --31.0421276093,1.60479366779,-26.8676338196 --31.0662727356,1.61069869995,-27.0580005646 --30.8972930908,1.60570633411,-27.0825061798 --30.7213115692,1.6007181406,-27.1000156403 --30.7194404602,1.60563611984,-27.269405365 --30.8546600342,1.61847877502,-27.5606975555 --30.9388484955,1.6283479929,-27.8090229034 --30.4105682373,1.59959554672,-27.4255867004 --30.1975593567,1.59262907505,-27.407125473 --28.2103633881,1.47964859009,-25.7869148254 --28.1014118195,1.47763061523,-25.8503818512 --28.0064716339,1.47660529613,-25.9258403778 --27.9315452576,1.47656881809,-26.01927948 --27.8275966644,1.47554862499,-26.0857410431 --27.7706203461,1.47454178333,-26.1139755249 --27.6986961365,1.47550320625,-26.2104167938 --27.5907459259,1.47348546982,-26.2728843689 --27.4968070984,1.47245919704,-26.3493423462 --27.4098720551,1.47243010998,-26.4297904968 --27.3139305115,1.4714050293,-26.5042514801 --27.2179908752,1.47038078308,-26.57670784 --27.1890335083,1.47135722637,-26.6319255829 --27.0830860138,1.47033846378,-26.6953907013 --26.9861431122,1.46931481361,-26.7668495178 --26.8962059021,1.46828722954,-26.8443031311 --26.8012676239,1.46826219559,-26.917760849 --26.7253417969,1.4682251215,-27.0112075806 --26.6374053955,1.4681956768,-27.0916614532 --26.5754241943,1.46719241142,-27.1128997803 --26.4804840088,1.46616780758,-27.1853580475 --26.3885478973,1.46514070034,-27.2618160248 --23.8276824951,1.30965304375,-24.8060665131 --23.6866912842,1.30566561222,-24.8155632019 --23.5517044067,1.3016756773,-24.8290519714 --23.4287281036,1.29867732525,-24.8565368652 --23.3707427979,1.29767644405,-24.8727760315 --23.2837924957,1.29665601254,-24.9362316132 --23.1818332672,1.29564523697,-24.9837017059 --23.1179008484,1.29561018944,-25.0711402893 --23.0519695282,1.29657578468,-25.1575832367 --22.9890403748,1.29753994942,-25.2460212708 --22.9961090088,1.30049610138,-25.3332157135 --22.9622058868,1.30344092846,-25.4536304474 --26.9787387848,1.57169353962,-30.0280742645 --26.7506961823,1.56275081635,-29.9646320343 --26.4716110229,1.55084300041,-29.8432312012 --20.7347831726,1.17762839794,-23.6028518677 --20.5777626038,1.17166244984,-23.5743656158 --20.4647789001,1.16866695881,-23.5948467255 --20.4278049469,1.16865682602,-23.6250667572 --20.3438453674,1.16864192486,-23.677526474 --20.2779045105,1.1686142683,-23.7509727478 --20.2069587708,1.16859030724,-23.8184242249 --20.1280040741,1.16857206821,-23.8758773804 --18.8819789886,1.08837878704,-22.5622005463 --18.7459106445,1.08244037628,-22.4735050201 --18.3396453857,1.05866038799,-22.1342086792 --17.7473049164,1.02795064449,-21.7034473419 --17.6633319855,1.02694487572,-21.7389087677 --17.5353183746,1.02197098732,-21.7214031219 --17.6014900208,1.03185498714,-21.9407539368 --17.5625076294,1.03084993362,-21.9619808197 --17.496553421,1.03083086014,-22.0194301605 --17.4726409912,1.03477954865,-22.1308498383 --17.4016799927,1.03376412392,-22.1823005676 --17.3627548218,1.03672361374,-22.2757301331 --17.2897930145,1.03570926189,-22.3251819611 --17.2158336639,1.03569555283,-22.3736381531 --17.2088832855,1.03766584396,-22.4358406067 --17.1559429169,1.03863549232,-22.5122833252 --17.0689697266,1.03763127327,-22.5447483063 --16.9819965363,1.03662765026,-22.5762138367 --16.933057785,1.03759455681,-22.6566486359 --16.8240623474,1.03460812569,-22.6591320038 --24.2621173859,1.58562099934,-32.7138710022 --24.2612075806,1.58856678009,-32.819065094 --17.7293357849,1.11469864845,-24.2464408875 --17.6613922119,1.11467480659,-24.3118915558 --17.6144695282,1.11763358116,-24.4063262939 --17.560541153,1.11859738827,-24.492767334 --17.2843647003,1.10374438763,-24.2713775635 --17.0832691193,1.09483110905,-24.150932312 --16.5136909485,1.05426466465,-23.4355697632 --16.4207134247,1.05226552486,-23.4590415955 --16.3427505493,1.05225336552,-23.5045032501 --16.1868247986,1.05123054981,-23.5924224854 --16.2620410919,1.06308794022,-23.8567638397 --17.0291481018,1.13130354881,-25.2137718201 --16.9431858063,1.13029313087,-25.2562389374 --11.7961215973,0.732721507549,-17.8256454468 --11.6680593491,0.726776838303,-17.7551517487 --11.6080789566,0.726773321629,-17.7835998535 --11.5020418167,0.722810268402,-17.7440910339 --11.4200344086,0.720826327801,-17.7395591736 --11.3630094528,0.717849433422,-17.7118034363 --11.2810001373,0.715865969658,-17.7062759399 --11.2090034485,0.714873731136,-17.7157382965 --11.1430130005,0.713877081871,-17.7321891785 --11.0760231018,0.712880074978,-17.7496528625 --11.0030231476,0.710889518261,-17.7561130524 --10.9710292816,0.71089053154,-17.7653388977 --10.9080438614,0.70989048481,-17.7877941132 --10.8580732346,0.709879040718,-17.8292350769 --10.8010950089,0.709873557091,-17.8606872559 --10.7511262894,0.710861563683,-17.903131485 --10.6961517334,0.710853815079,-17.938583374 --10.6471834183,0.710840582848,-17.9830265045 --10.6262044907,0.711830973625,-18.0102443695 --10.5772390366,0.711816728115,-18.0566940308 --10.5292730331,0.712802827358,-18.1021327972 --10.479306221,0.713790297508,-18.1455783844 --10.4293384552,0.713777661324,-18.1890239716 --10.3803730011,0.714763820171,-18.2344703674 --10.3344106674,0.715746998787,-18.284910202 --10.3134336472,0.715735793114,-18.3151340485 --10.2454395294,0.714741945267,-18.3265895844 --10.2345314026,0.718688547611,-18.4390029907 --10.2296333313,0.723627686501,-18.564414978 --14.9939155579,1.1575460434,-27.2070121765 --13.7522029877,1.05275928974,-25.1724052429 --13.6652297974,1.0517565012,-25.2008800507 --14.8361110687,1.16245436668,-27.4231472015 --14.7681818008,1.16442251205,-27.5016040802 --16.5371265411,1.33539414406,-30.9705924988 --16.4992713928,1.34031391144,-31.132024765 --19.7346305847,1.65162265301,-37.4298439026 --14.0808067322,1.1317538023,-27.0347671509 --13.9677124023,1.12482750416,-26.9210586548 --13.8496999741,1.12185370922,-26.900560379 --13.632522583,1.10899329185,-26.6871376038 --13.5014820099,1.10403728485,-26.6356449127 --13.4475727081,1.10699236393,-26.7360973358 --13.7152032852,1.14057648182,-27.4672794342 --12.636557579,1.04372298717,-25.5395584106 --12.4893913269,1.03284418583,-25.3448791504 --17.9119148254,1.57534480095,-36.4369125366 --13.5618009567,1.16424810886,-28.13422966 --13.4698343277,1.16324293613,-28.1667060852 --17.6875762939,1.59899318218,-37.139705658 --5.48685836792,0.369776785374,-11.9732809067 --5.3877491951,0.363855779171,-11.8587751389 --18.3487682343,1.70959854126,-39.6095848083 --18.1947784424,1.70661890507,-39.601108551 --18.1349639893,1.71251988411,-39.7965583801 --18.0591220856,1.71844017506,-39.9590263367 --17.7368125916,1.69667720795,-39.5806884766 --17.8020877838,1.71050441265,-39.888835907 --17.713224411,1.71444046497,-40.0243148804 --17.6704502106,1.72331523895,-40.2647476196 --17.444316864,1.71243214607,-40.0913352966 --17.2873191833,1.70845830441,-40.0728721619 --13.1362438202,1.26288354397,-30.8236560822 --17.0033798218,1.70447146893,-40.1029090881 --16.8582420349,1.69557726383,-39.9352302551 --16.9748077393,1.72222816944,-40.5585403442 --16.8548851013,1.72320353985,-40.627040863 --16.5375461578,1.70145630836,-40.2207069397 --16.5789680481,1.72020447254,-40.6780776978 --16.6354255676,1.74192810059,-41.1774368286 --16.427318573,1.73302745819,-41.0340118408 --16.6439666748,1.76561295986,-41.7570419312 --16.5410919189,1.76855921745,-41.8755302429 --9.56686115265,0.951631903648,-24.6436634064 --7.79906988144,0.748143672943,-20.3625392914 --7.71905088425,0.746167838573,-20.3430137634 --7.66308689117,0.747155785561,-20.385471344 --7.61706399918,0.74517673254,-20.3607158661 --7.56109905243,0.746165215969,-20.4021701813 --8.2158203125,0.836050510406,-22.3360366821 --8.17490959167,0.839004933834,-22.4364776611 --8.11996936798,0.840979874134,-22.5019340515 --7.38837194443,0.756034016609,-20.7149543762 --7.34945440292,0.759992420673,-20.8083972931 --7.27836799622,0.755054652691,-20.7126655579 --7.19133043289,0.752091050148,-20.6721496582 --7.07822465897,0.74517172575,-20.5556545258 --7.00822401047,0.74418348074,-20.5571193695 --7.27610397339,0.788625776768,-21.5373058319 --6.78500795364,0.731346905231,-20.3201274872 --6.70798873901,0.729371070862,-20.3006038666 --6.63388442993,0.723444283009,-20.185874939 --6.55585956573,0.721471846104,-20.1603546143 --6.49086809158,0.720477879047,-20.1718177795 --6.42587566376,0.720484435558,-20.1822795868 --6.36790513992,0.721477150917,-20.2167415619 --6.3500494957,0.727396249771,-20.3781700134 --6.30812644958,0.73035877943,-20.4646167755 --6.60708761215,0.778749465942,-21.5245685577 --6.52104759216,0.775787591934,-21.481048584 --6.48916864395,0.780723035336,-21.614490509 --6.42218780518,0.780723631382,-21.6359596252 --6.38128423691,0.78467476368,-21.7424049377 --6.30226755142,0.783698558807,-21.7238864899 --6.37271356583,0.8044282794,-22.2122383118 --6.37985277176,0.811346530914,-22.3644390106 --6.2255988121,0.797520339489,-22.086977005 --6.16464042664,0.798506975174,-22.132440567 --6.07659721375,0.79554772377,-22.0849323273 --6.02065563202,0.797523975372,-22.1483917236 --5.96170282364,0.799507141113,-22.1998519897 --5.8987402916,0.800496816635,-22.2403182983 --5.89786291122,0.805426239967,-22.3735256195 --5.85497188568,0.810371339321,-22.4909744263 --5.81709957123,0.815304338932,-22.6294193268 --5.72503900528,0.812355935574,-22.5629119873 --5.69219064713,0.8182746768,-22.726354599 --5.61518335342,0.817292749882,-22.7178325653 --5.60729074478,0.822232604027,-22.8330440521 --5.54634571075,0.824212133884,-22.8915119171 --5.46933746338,0.822230815887,-22.8819885254 --5.36723613739,0.817308008671,-22.7714920044 --5.29926204681,0.817305386066,-22.7989654541 --5.2473487854,0.821265101433,-22.891418457 --5.21451997757,0.828173100948,-23.0738639832 --5.14454221725,0.828173458576,-23.0963363647 --5.25916719437,0.857793688774,-23.7654457092 --5.1580696106,0.852868616581,-23.658946991 --5.08810186386,0.853863358498,-23.6914234161 --5.07437419891,0.865709781647,-23.9808502197 --10.2494220734,1.96854674816,-48.5599861145 --4.92457962036,0.87362074852,-24.1940174103 --4.79233503342,0.860785722733,-23.9315452576 --4.60381889343,0.836116492748,-23.3811206818 --4.54288339615,0.838090956211,-23.4485836029 --4.45181179047,0.834149241447,-23.3710803986 --4.37882328033,0.834156751633,-23.3815593719 --4.32593250275,0.838104307652,-23.4960193634 --4.34622383118,0.851934194565,-23.8032073975 --4.31646585464,0.862801969051,-24.0566520691 --4.24348926544,0.862802743912,-24.0791320801 --4.87124967575,1.03853726387,-28.0410289764 --4.77521848679,1.0365742445,-28.0015258789 --4.68723773956,1.03658092022,-28.0150241852 --3.90833568573,0.852955341339,-23.9090824127 --4.56430721283,1.03856575489,-28.0787525177 --4.50749921799,1.04646778107,-28.2742176056 --4.43763113022,1.05140674114,-28.4057006836 --4.35367155075,1.05240082741,-28.4411869049 --4.12179708481,1.01094424725,-27.5197963715 --4.23809671402,1.07018244267,-28.8721256256 --3.98505401611,1.02082562447,-27.7767524719 --3.92595744133,1.01589238644,-27.6730117798 --2.197909832,0.504513502121,-16.156873703 --2.13682961464,0.50157058239,-16.0793418884 --2.03042292595,0.481822043657,-15.6628446579 --1.98746132851,0.483808130026,-15.7093009949 --1.92434847355,0.478884071112,-15.5987710953 --1.88944971561,0.483833014965,-15.7102212906 --1.86645364761,0.483835071325,-15.7174444199 --1.82047104836,0.484833776951,-15.7419013977 --1.7755010128,0.485825181007,-15.7793607712 --1.73254835606,0.487806260586,-15.8348178864 --1.68858635426,0.489793002605,-15.8802719116 --1.64563035965,0.491776168346,-15.9317207336 --1.60268604755,0.494752764702,-15.995177269 --1.58171617985,0.495739579201,-16.0294017792 --1.53575253487,0.497727781534,-16.0728645325 --6.55115652084,2.7821598053,-67.8525619507 --6.31901311874,2.77229261398,-67.6581954956 --6.10202407837,2.76933455467,-67.6228103638 --5.87288093567,2.76046657562,-67.42943573 --5.64069747925,2.74962234497,-67.19506073 --5.49323177338,2.72691774368,-66.696395874 --5.30453014374,2.73779201508,-66.9549942017 --4.38255500793,2.33106184006,-57.7500801086 --4.18233823776,2.31922888756,-57.4926795959 --4.00541067123,2.3202278614,-57.5302581787 --3.73615908623,2.26199412346,-56.2209014893 --3.64107036591,2.25706577301,-56.1131973267 --3.47018909454,2.2610373497,-56.1987762451 --3.3074426651,2.26993131638,-56.4213523865 --3.06839179993,2.22157788277,-55.3209762573 --2.59134817123,2.25814723969,-56.1866950989 --2.51564097404,2.26999950409,-56.4649810791 --2.33455395699,2.26409006119,-56.3425712585 --2.15448594093,2.25916957855,-56.2391586304 --1.97439801693,2.25426077843,-56.1157455444 --1.79531931877,2.24834609032,-56.00233078 --1.61724257469,2.24343061447,-55.890914917 --1.86805975437,2.93946456909,-71.7384719849 --1.76442086697,2.95428538322,-72.0757904053 --1.54051446915,2.95528531075,-72.1194229126 --0.993694961071,2.21388339996,-55.2229652405 --0.64330893755,1.93056035042,-48.7867774963 --0.492420583963,1.93453276157,-48.87134552 --0.339270710945,1.92665266991,-48.6949043274 --0.262034773827,1.91580355167,-48.446182251 --0.109922610223,1.909902215,-48.3077507019 -0.0938908606768,1.94202756882,-47.4379997253 -0.242534831166,1.92678868771,-47.1102752686 -0.390316903591,1.91862773895,-46.9195480347 -0.538247466087,1.91655039787,-46.8768196106 -0.685052752495,1.90840303898,-46.7090950012 -0.759048819542,1.90938174725,-46.7182273865 -0.894363760948,1.879961133,-46.0585289001 -1.04454863071,1.88902688026,-46.2697868347 -1.19151484966,1.88897013664,-46.2620620728 -1.33952891827,1.89094018936,-46.3023300171 -1.48754096031,1.8929091692,-46.3405990601 -1.63246250153,1.89082813263,-46.2878761292 -1.70029270649,1.88371527195,-46.1300201416 -1.83703422546,1.87353479862,-45.8953094482 -1.9881156683,1.87854242325,-46.003578186 -2.14227128029,1.88659119606,-46.1868362427 -2.2861893177,1.88450860977,-46.130115509 -2.4341943264,1.88647425175,-46.1613845825 -2.49698996544,1.8773431778,-45.9675369263 -2.65719914436,1.88842093945,-46.2057952881 -2.79808592796,1.88432168961,-46.1170768738 -2.94404172897,1.88426017761,-46.0983543396 -3.06970953941,1.87104153633,-45.786655426 -3.20959877968,1.86694431305,-45.6999435425 -3.35962963104,1.86992430687,-45.7572135925 -3.43059825897,1.8688890934,-45.7383499146 -3.56846618652,1.86478042603,-45.6296386719 -3.7255821228,1.87180685997,-45.7739028931 -3.87156295776,1.87275993824,-45.7801780701 -3.98112773895,1.85448753834,-45.3605041504 -4.13823461533,1.86050903797,-45.495765686 -4.28624105453,1.86247634888,-45.5280418396 -4.35114908218,1.85940825939,-45.4461898804 -4.50015687943,1.86137640476,-45.4804649353 -4.66935539246,1.87244701385,-45.7107162476 -4.73558616638,1.83799731731,-44.9450950623 -4.91588830948,1.85412347317,-45.2813301086 -5.01748180389,1.83686947823,-44.8876609802 -5.20684814453,1.85602986813,-45.2908859253 -5.23243665695,1.83779203892,-44.8790855408 -5.35523939133,1.83065104485,-44.7003898621 -5.39942741394,1.7941827774,-43.8847923279 -5.5202422142,1.78704917431,-43.7170982361 -5.66525173187,1.78901958466,-43.7513809204 -5.82537317276,1.7970495224,-43.9016456604 -5.96029615402,1.79497349262,-43.8459396362 -5.96885108948,1.774720788,-43.3951530457 -6.10781764984,1.77566874027,-43.3844413757 -6.23672056198,1.7725828886,-43.3067398071 -6.3384437561,1.76140284538,-43.0420722961 -6.4945306778,1.76741456985,-43.1563415527 -6.59324884415,1.75623238087,-42.8856735229 -6.63305425644,1.74811327457,-42.6938552856 -6.75392150879,1.74300980568,-42.5781669617 -3.83872556686,0.876449465752,-23.5248527527 -3.93583536148,0.882487356663,-23.6431789398 -4.02590560913,0.886504948139,-23.7205085754 -4.11999130249,0.891530036926,-23.8138370514 -4.21608924866,0.896562159061,-23.9211578369 -4.27418851852,0.901603877544,-24.0273113251 -4.36926984787,0.906626462936,-24.1166381836 -4.46233844757,0.910642564297,-24.1929664612 -7.64022779465,1.67884731293,-40.9869537354 -7.77822542191,1.68081378937,-41.0062446594 -7.91018867493,1.68076264858,-40.9895477295 -8.03110122681,1.67868494987,-40.9178581238 -8.08804035187,1.67663741112,-40.8640213013 -8.22302627563,1.6785980463,-40.8703117371 -8.2434720993,1.65328168869,-40.3037338257 -8.45983314514,1.67343497276,-40.7089424133 -8.53856086731,1.66226351261,-40.4402999878 -8.64743328094,1.65816676617,-40.3256225586 -8.74123954773,1.65103626251,-40.1399650574 -5.48289442062,0.94671100378,-24.8306045532 -5.53274583817,0.940615594387,-24.6769886017 -5.61173009872,0.940587818623,-24.6643314362 -5.74794578552,0.952677190304,-24.8996181488 -5.77170038223,0.941533029079,-24.6410236359 -9.30143356323,1.62245464325,-39.3897972107 -6.27383852005,1.0000576973,-25.8765773773 -6.41604137421,1.01213896275,-26.1008625031 -9.72923851013,1.62124824524,-39.2508888245 -9.80501079559,1.61210310459,-39.0252494812 -9.89885425568,1.60599422455,-38.8765907288 -10.0308389664,1.60795605183,-38.8798942566 -10.1377334595,1.60487258434,-38.7852210999 -10.324669838,1.60479557514,-38.7466888428 -10.4315662384,1.60271298885,-38.6530189514 -10.528429985,1.59761536121,-38.5253601074 -10.5871706009,1.58745610714,-38.2617378235 -10.6990919113,1.58538746834,-38.1960601807 -10.7530450821,1.58434903622,-38.1542243958 -10.8489160538,1.58025538921,-38.0325660706 -8.69758224487,1.20861244202,-30.0451488495 -8.75944042206,1.20351886749,-29.9005203247 -8.87045669556,1.20550334454,-29.9288406372 -8.95238208771,1.20344305038,-29.8571910858 -9.03932285309,1.20239043236,-29.8025360107 -9.07727336884,1.20035433769,-29.7537193298 -9.15117835999,1.19728434086,-29.6590766907 -9.23109912872,1.19522237778,-29.5824317932 -9.31904888153,1.19417476654,-29.5367736816 -9.39696502686,1.19211018085,-29.4541320801 -9.48290920258,1.19105958939,-29.4014797211 -9.56484031677,1.18900310993,-29.3358306885 -9.60881614685,1.18798005581,-29.3140010834 -9.72584629059,1.1919709444,-29.3563213348 -12.2785339355,1.54416882992,-36.7722663879 -12.3523674011,1.53805935383,-36.6046333313 -12.4612951279,1.53699588776,-36.5429649353 -12.4388809204,1.51776826382,-36.0994186401 -12.4816436768,1.5076264143,-35.8528175354 -12.4894886017,1.50053834915,-35.6900253296 -12.7297677994,1.51764333248,-36.0172271729 -12.8757963181,1.52162790298,-36.0655250549 -13.0298433304,1.52762186527,-36.1358146667 -13.1568231583,1.52858400345,-36.1311302185 -13.1865625381,1.51743137836,-35.8555374146 -13.2824668884,1.51535785198,-35.7658843994 -13.3314218521,1.5143225193,-35.7240562439 -13.5015048981,1.52133333683,-35.8343315125 -13.4701089859,1.50311875343,-35.4067955017 -13.7193803787,1.52021753788,-35.7269935608 -13.8533735275,1.52318561077,-35.7363052368 -13.8590726852,1.50901675224,-35.4147338867 -13.944111824,1.5130212307,-35.4678726196 -14.0279951096,1.50893843174,-35.352230072 -14.1499633789,1.51089525223,-35.3325500488 -14.2007741928,1.502779603,-35.1359405518 -14.3317642212,1.50574612617,-35.139251709 -14.4447135925,1.50569486618,-35.0985832214 -14.6668968201,1.51875126362,-35.3228149414 -14.7358970642,1.51973748207,-35.3319664001 -14.9079685211,1.52674174309,-35.4292449951 -15.0920639038,1.53475725651,-35.5545082092 -15.3022079468,1.54679512978,-35.7367477417 -15.5133514404,1.55783176422,-35.9169921875 -15.7365169525,1.56987857819,-36.1232223511 -15.9386329651,1.57990205288,-36.2734718323 -15.9946022034,1.57987344265,-36.2466392517 -16.1055316925,1.57881295681,-36.1859779358 -16.1854057312,1.57472598553,-36.0573425293 -16.3284034729,1.57769560814,-36.071647644 -16.4403381348,1.5776373148,-36.0149803162 -16.5612926483,1.57858681679,-35.9783096313 -16.6762332916,1.57853150368,-35.9286384583 -16.7281932831,1.57749927044,-35.8918113708 -16.8471412659,1.5784471035,-35.8501434326 -16.9610824585,1.57839071751,-35.7974777222 -17.0730171204,1.57833302021,-35.740814209 -17.1819496155,1.57727324963,-35.6781539917 -17.3018989563,1.57822215557,-35.6384811401 -17.4118347168,1.57816386223,-35.5788230896 -17.4848327637,1.57914876938,-35.585975647 -17.6077880859,1.5800999403,-35.5513038635 -17.7157173157,1.58003985882,-35.4866409302 -17.9047889709,1.58804178238,-35.5859107971 -18.0237350464,1.58798968792,-35.5422401428 -18.3390140533,1.60808217525,-35.8843994141 -18.6572933197,1.62817525864,-36.2295532227 -18.8514900208,1.6422457695,-36.4675979614 -19.0625839233,1.65125644207,-36.5948486328 -19.3287639618,1.66530418396,-36.8240509033 -19.5648918152,1.67732906342,-36.9922790527 -19.6347465515,1.67223548889,-36.8406562805 -19.7667007446,1.67418551445,-36.8069801331 -19.8376865387,1.67516374588,-36.7991409302 -19.9466075897,1.6740988493,-36.7234840393 -20.0395011902,1.67202353477,-36.6188392639 -20.1754646301,1.67397654057,-36.5921592712 -20.5007152557,1.69305360317,-36.9093170166 -20.5906028748,1.69097495079,-36.7956771851 -20.6624660492,1.68688547611,-36.6510543823 -20.6823749542,1.68283104897,-36.5512580872 -20.7392158508,1.67773318291,-36.3816452026 -20.8200950623,1.67465126514,-36.2560157776 -20.880947113,1.66955816746,-36.09740448 -20.9397945404,1.66446375847,-35.9347953796 -21.0206775665,1.66138386726,-35.8121643066 -21.0935497284,1.65730023384,-35.6775436401 -21.108455658,1.65424573421,-35.5737495422 -21.1723175049,1.65015769005,-35.4251327515 -21.2291698456,1.64506649971,-35.2665252686 -21.3040485382,1.64198589325,-35.1379051208 -21.35389328,1.63589179516,-34.9693031311 -21.3907222748,1.62979137897,-34.780708313 -21.4185409546,1.62268686295,-34.5791282654 -21.3964042664,1.6156154871,-34.4213638306 -21.4292316437,1.60951542854,-34.2307777405 -21.4690723419,1.60342037678,-34.0531845093 -21.4989032745,1.59732139111,-33.8626022339 -21.5107078552,1.58921289444,-33.643032074 -21.545545578,1.5831182003,-33.4624443054 -21.5194129944,1.57604920864,-33.3066864014 -21.5742778778,1.57196652889,-33.1600761414 -21.6241397858,1.56688165665,-33.006477356 -21.6940288544,1.56480824947,-32.8858604431 -21.7088489532,1.55670785904,-32.6822853088 -21.7557125092,1.55262374878,-32.5276870728 -21.7945652008,1.54753684998,-32.3630943298 -21.7864608765,1.54248094559,-32.2413215637 -21.8092956543,1.53638708591,-32.0537452698 -21.8611679077,1.53230857849,-31.9121398926 -21.886013031,1.52621805668,-31.7315597534 -21.9038467407,1.51912522316,-31.5429859161 -21.9547214508,1.51504862309,-31.4033851624 -22.0035972595,1.51097106934,-31.2607860565 -22.0235290527,1.50893080235,-31.1839885712 -22.0884246826,1.50586223602,-31.0673732758 -22.1593265533,1.50379681587,-30.9597549438 -22.2482509613,1.50373923779,-30.8771209717 -22.3451824188,1.50268530846,-30.805480957 -22.4501247406,1.50363528728,-30.7458343506 -22.5420532227,1.50357937813,-30.6672000885 -22.6040363312,1.50455892086,-30.6513652802 -22.7039699554,1.50450658798,-30.5837249756 -22.8109130859,1.50545692444,-30.5250797272 -22.9128551483,1.50540673733,-30.4624328613 -23.0197963715,1.50635707378,-30.4027881622 -23.1337490082,1.50731146336,-30.3551330566 -23.1867218018,1.50728678703,-30.3253097534 -23.3116855621,1.50924503803,-30.2906494141 -23.4166259766,1.51019513607,-30.2290039062 -23.5085544586,1.5101402998,-30.1503696442 -23.6154994965,1.51109170914,-30.0917224884 -23.7444648743,1.51305091381,-30.0600605011 -23.8494052887,1.51400160789,-29.9984149933 -23.9003753662,1.51397633553,-29.9655952454 -24.0163288116,1.51593077183,-29.9169406891 -24.1492977142,1.51789140701,-29.8892745972 -24.3022880554,1.52185928822,-29.886592865 -24.3952159882,1.52180480957,-29.8069610596 -24.5452003479,1.52577126026,-29.7992801666 -24.6911811829,1.52973604202,-29.7856044769 -24.7831878662,1.53272426128,-29.8007507324 -24.9141540527,1.53468370438,-29.7680873871 -25.0541286469,1.53864479065,-29.7434196472 -25.1290378571,1.53658485413,-29.6418018341 -25.5010681152,1.54953837395,-29.7023868561 -25.6060085297,1.55048775673,-29.6347465515 -25.68800354,1.55247223377,-29.6359004974 -25.8069553375,1.55442619324,-29.5842494965 -25.9189014435,1.55537807941,-29.52460289 -26.0258407593,1.55632793903,-29.4579639435 -26.1427898407,1.55728137493,-29.4033145905 -26.265745163,1.55923640728,-29.3546600342 -23.3570613861,1.35828626156,-25.9014167786 -23.5571651459,1.36830961704,-26.0414810181 -23.6320972443,1.3682602644,-25.958864212 -26.6115093231,1.56105422974,-29.0889396667 -26.6954307556,1.55999803543,-28.9963169098 -26.8023719788,1.56094896793,-28.9296760559 -23.9208164215,1.36506283283,-25.6193962097 -27.0102481842,1.56284844875,-28.7874031067 -27.0582141876,1.56282269955,-28.74858284 -27.0210361481,1.55473399162,-28.5260601044 -27.0038757324,1.54765176773,-28.3265209198 -26.9767112732,1.5395680666,-28.1189842224 -26.9525489807,1.53248631954,-27.9164447784 -26.860332489,1.52038705349,-27.6429634094 -26.6571025848,1.50429749489,-27.3443450928 -26.5148525238,1.49018800259,-27.0239028931 -26.4406604767,1.4800978899,-26.7784004211 -26.383480072,1.4710123539,-26.5498905182 -26.3623313904,1.46393680573,-26.3603496552 -26.3431854248,1.45686268806,-26.1748085022 -26.3570671082,1.45279729366,-26.0232410431 -26.3039608002,1.44675028324,-25.8875045776 -26.2938251495,1.44068026543,-25.7139549255 -26.273683548,1.43460834026,-25.531414032 -26.2525424957,1.42853689194,-25.3488731384 -26.2093830109,1.42046129704,-25.1463508606 -26.0321311951,1.40435659885,-24.8159294128 -25.7788276672,1.38423717022,-24.4165649414 -25.8928508759,1.388230443,-24.4477005005 -25.1842269897,1.34001493454,-23.6196842194 -25.2541618347,1.33996915817,-23.5350761414 -24.9178123474,1.31483840942,-23.069776535 -24.5414390564,1.28670203686,-22.5725040436 -24.2491283417,1.2645856142,-22.1591644287 -23.7757492065,1.23346078396,-21.6497497559 -22.8850402832,1.1752281189,-20.6948661804 -22.2615184784,1.13405323029,-19.9937801361 -21.9422111511,1.11094164848,-19.576461792 -21.5878829956,1.08582544327,-19.1321697235 -20.877325058,1.03964400291,-18.3741455078 -20.5120010376,1.01453149319,-17.9318580627 -20.5389766693,1.0145149231,-17.8980560303 -18.441532135,0.886086523533,-15.9340810776 -18.2413330078,0.871013343334,-15.6566667557 -18.24426651,0.867977917194,-15.5590963364 -17.9960422516,0.850898623466,-15.2447166443 -17.6677684784,0.828806400299,-14.8634023666 -17.4925937653,0.814742743969,-14.6179676056 -17.3434696198,0.804701089859,-14.4442939758 -17.167301178,0.791639149189,-14.2018604279 -8.19772338867,0.265118807554,-6.52753210068 -8.23172569275,0.26611456275,-6.51193571091 -8.31474113464,0.268108457327,-6.49372053146 -8.31873607635,0.268104463816,-6.47592353821 -8.35073757172,0.26910007,-6.45931816101 -8.38373947144,0.269095420837,-6.44172859192 -8.40573692322,0.26908954978,-6.41712808609 -8.4177274704,0.269082069397,-6.38354587555 -8.44972801208,0.269077539444,-6.36594724655 -8.47672843933,0.270072489977,-6.34534215927 -8.4937286377,0.270070195198,-6.33654928207 -8.51872730255,0.27006483078,-6.31394958496 -8.54272460938,0.271059334278,-6.29035186768 -8.56672096252,0.271053642035,-6.26576423645 -8.57771205902,0.270046472549,-6.2321767807 -8.62172031403,0.272043585777,-6.22356510162 -8.63371944427,0.272040903568,-6.21176624298 -8.6577167511,0.272035330534,-6.18717718124 -8.68871879578,0.273030787706,-6.16857433319 -8.71071434021,0.273025125265,-6.1429810524 -8.73571300507,0.273019820452,-6.11938714981 -8.76071071625,0.273014545441,-6.09579372406 -8.78370761871,0.273009121418,-6.07119607925 -8.8037109375,0.274007260799,-6.06439733505 -8.82870769501,0.274002045393,-6.04080152512 -8.84970378876,0.273996412754,-6.01421022415 -8.88170623779,0.274991989136,-5.99560832977 -8.90970516205,0.274986952543,-5.97302103043 -8.92770004272,0.274981111288,-5.94442939758 -8.96170330048,0.275976926088,-5.92682743073 -8.9767036438,0.275974690914,-5.91702413559 -8.98569393158,0.275968074799,-5.88243675232 -9.02970123291,0.276964724064,-5.87083435059 -9.04469394684,0.276958584785,-5.83925390244 -9.08870124817,0.277955442667,-5.82863807678 -9.11069869995,0.277950048447,-5.80204916 -9.16170787811,0.279947370291,-5.79543161392 -9.16270256042,0.279943853617,-5.77564191818 -9.16869163513,0.278937071562,-5.73806762695 -9.18368530273,0.278931319714,-5.70747661591 -9.25170230865,0.280929893255,-5.71085262299 -9.28470420837,0.281925499439,-5.69125318527 -9.31070327759,0.281920671463,-5.66765260696 -12.2439880371,0.437144935131,-7.52174711227 -12.2179527283,0.434130698442,-7.45119667053 -12.1819143295,0.431115955114,-7.37465381622 -12.3379583359,0.438115626574,-7.41996526718 -12.9612016678,0.469147711992,-7.75394916534 -13.2242870331,0.482152938843,-7.86019229889 -12.3158807755,0.433078944683,-7.24725914001 -13.0121603012,0.46911907196,-7.64498853683 -13.1081752777,0.472112834454,-7.64834308624 -13.0751361847,0.469097971916,-7.57180166245 -13.1591472626,0.472090810537,-7.56716585159 -13.5122652054,0.489099413157,-7.72134542465 -13.7283267975,0.499098986387,-7.79162359238 -13.2170982361,0.472057372332,-7.43540620804 -13.2741088867,0.47405436635,-7.4405837059 -14.016374588,0.511081933975,-7.81449699402 -13.2520523071,0.470029175282,-7.31745576859 -13.4160928726,0.477025508881,-7.35577249527 -13.3670511246,0.474011301994,-7.27323055267 -13.1639509201,0.46199002862,-7.10380268097 -13.2119455338,0.462980866432,-7.0762014389 -13.5390577316,0.47899004817,-7.23218011856 -13.3499641418,0.468970060349,-7.07174634933 -13.5089998245,0.475965499878,-7.10506153107 -13.4199447632,0.469950556755,-7.00155496597 -13.570977211,0.475945234299,-7.02888011932 -13.5989656448,0.476935327053,-6.99028158188 -13.4959173203,0.470925956964,-6.90757083893 -13.5659208298,0.472917556763,-6.89094877243 -13.4968748093,0.468904435635,-6.80042600632 -13.5138587952,0.46789419651,-6.7548494339 -13.5748586655,0.469885587692,-6.73323392868 -13.5808401108,0.469875276089,-6.68265867233 -13.596824646,0.468865454197,-6.63807106018 -13.600815773,0.468860387802,-6.61328363419 -13.6278038025,0.468850851059,-6.57369327545 -13.584769249,0.465839803219,-6.49915027618 -13.6007537842,0.465830087662,-6.45357322693 -13.6017351151,0.464820384979,-6.40199565887 -13.7267551422,0.469812989235,-6.41034030914 -13.7717494965,0.470803886652,-6.37874269485 -13.7277259827,0.467798292637,-6.33098745346 -13.8147344589,0.4717900455,-6.320353508 -13.8267183304,0.470780551434,-6.27277803421 -14.1618003845,0.486775159836,-6.37798070908 -13.8746938705,0.471762299538,-6.19059753418 -14.0277194977,0.477754235268,-6.20793151855 -13.8586502075,0.468743503094,-6.07747173309 -13.8906497955,0.46973913908,-6.0656671524 -13.9246416092,0.470730304718,-6.02907133102 -13.951631546,0.470721513033,-5.98947811127 -13.9476118088,0.469712466002,-5.93491363525 -14.3217000961,0.486704319715,-6.04809617996 -14.4297113419,0.490695208311,-6.04245233536 -14.6237564087,0.499690562487,-6.10053730011 -14.5857257843,0.496681243181,-6.0299911499 -14.5166873932,0.492672145367,-5.94646549225 -14.5346736908,0.492663055658,-5.9008808136 -14.4856414795,0.489654272795,-5.82634544373 -14.7596960068,0.50164359808,-5.88759708405 -15.0957651138,0.51663184166,-5.97280788422 -14.6956510544,0.497630625963,-5.78028297424 -14.6536216736,0.494622260332,-5.70973873138 -14.6876115799,0.494613230228,-5.6701464653 -15.6138296127,0.538593173027,-5.98897409439 -17.5222911835,0.628557324409,-6.69117832184 -17.5712776184,0.630544781685,-6.64757633209 -17.6102733612,0.631538152695,-6.63077020645 -17.6582603455,0.63252556324,-6.58617162704 -17.7092494965,0.634512841702,-6.54257059097 -17.7532329559,0.635500371456,-6.49597501755 -17.8022212982,0.636487782001,-6.45137453079 -17.8512077332,0.637475073338,-6.40577936172 -17.9021930695,0.639462471008,-6.36117982864 -17.9461917877,0.640455782413,-6.34636354446 -17.9891777039,0.641443371773,-6.29876756668 -18.0381660461,0.64343059063,-6.2521739006 -18.098154068,0.645417809486,-6.21056556702 -18.1351356506,0.64540553093,-6.15997552872 -18.1871242523,0.647392749786,-6.11437654495 -18.2451133728,0.649379968643,-6.07077407837 -18.287109375,0.650372982025,-6.05296707153 -18.3210926056,0.651360988617,-6.00137472153 -18.3860836029,0.653347909451,-5.9597659111 -18.4400691986,0.655335009098,-5.91317033768 -18.4880561829,0.656322538853,-5.8655705452 -18.5390434265,0.658309817314,-5.81797456741 -18.5890293121,0.659297227859,-5.77037572861 -18.6300258636,0.660290300846,-5.7515668869 -18.6850128174,0.662277519703,-5.7049665451 -18.7399997711,0.664264678955,-5.65836381912 -18.784986496,0.66525220871,-5.60777235031 -18.8459720612,0.667239129543,-5.56216907501 -18.8959598541,0.669226586819,-5.51356840134 -18.9439563751,0.670219242573,-5.49575710297 -18.9709377289,0.671207606792,-5.43917512894 -19.0269260406,0.673194825649,-5.39157247543 -19.0929145813,0.675181388855,-5.34596920013 -19.1448993683,0.676168739796,-5.29637098312 -19.1928863525,0.678156256676,-5.24577283859 -19.2408714294,0.679143667221,-5.19418048859 -19.3028717041,0.682135522366,-5.1793589592 -19.3548583984,0.683122813702,-5.12876176834 -19.3828392029,0.684111475945,-5.07217407227 -13.0797834396,0.393445283175,-3.29244828224 -13.1037788391,0.393440634012,-3.25486469269 -13.1247739792,0.394436210394,-3.217274189 -13.0967617035,0.392434567213,-3.16572403908 -19.6497821808,0.693052589893,-4.84996604919 -15.8761777878,0.519265592098,-3.81467485428 -15.9351730347,0.521256268024,-3.77706837654 -15.9731645584,0.522248208523,-3.73347830772 -16.0381622314,0.524238526821,-3.69686794281 -16.037147522,0.524232923985,-3.64330172539 -16.0081291199,0.522229194641,-3.5837469101 -16.0141239166,0.5222260952,-3.55895709991 -16.0751190186,0.524216651917,-3.52035331726 -16.1701202393,0.528204977512,-3.48972558975 -16.0340881348,0.521208703518,-3.40523982048 -16.2201004028,0.529190838337,-3.39456009865 -16.2470912933,0.53018373251,-3.34797048569 -16.2730884552,0.531179189682,-3.3261783123 -16.344083786,0.534169018269,-3.28856563568 -16.3490715027,0.533163547516,-3.23698830605 -16.3640613556,0.533157289028,-3.18641424179 -16.3900508881,0.534150362015,-3.13882732391 -16.3890380859,0.534145474434,-3.08525967598 -16.4210300446,0.535138189793,-3.03867006302 -16.4730300903,0.537131786346,-3.02185964584 -16.5190219879,0.538123488426,-2.97825789452 -16.5600147247,0.540115475655,-2.93266487122 -16.578004837,0.540109276772,-2.88208937645 -16.638999939,0.542099833488,-2.84048080444 -16.6699905396,0.543092608452,-2.791898489 -16.7439861298,0.546081960201,-2.751288414 -16.7979869843,0.549075305462,-2.73446846008 -16.8589801788,0.551065683365,-2.69086670876 -16.9249744415,0.553055644035,-2.64825844765 -16.9529647827,0.554048717022,-2.59867334366 -17.0059604645,0.556039750576,-2.55307435989 -17.065952301,0.559030115604,-2.50847029686 -17.0919418335,0.55902338028,-2.45788788795 -17.1509418488,0.562016129494,-2.44006824493 -17.2009353638,0.564007282257,-2.39247488976 -17.2819309235,0.566995739937,-2.34985995293 -17.3139209747,0.5679885149,-2.29927515984 -17.2809085846,0.565987288952,-2.23972296715 -16.2768154144,0.521074652672,-2.04372024536 -16.1337966919,0.514086067677,-1.99702429771 -16.0917835236,0.512086808681,-1.94047510624 -16.0327701569,0.509089291096,-1.88193595409 -16.0177612305,0.50808775425,-1.82838141918 -16.0047512054,0.507086217403,-1.77681219578 -15.9947423935,0.507084429264,-1.72425353527 -16.0107364655,0.507080197334,-1.67567420006 -15.9797296524,0.506081938744,-1.64690494537 -15.9877223969,0.506078600883,-1.59733080864 -15.9937143326,0.506075561047,-1.54775595665 -16.0087070465,0.506071567535,-1.49818444252 -16.0317020416,0.507066905499,-1.45059800148 -16.0436954498,0.507063388824,-1.40102434158 -16.0676879883,0.508058726788,-1.35343670845 -16.100687027,0.50905418396,-1.33064007759 -16.1546840668,0.512046515942,-1.28603255749 -16.2236785889,0.514037251472,-1.24142622948 -16.2656726837,0.516030669212,-1.19383633137 -16.3536701202,0.520019292831,-1.150218606 -16.49766922,0.526001930237,-1.11057150364 -18.5807590485,0.618778288364,-1.22286641598 -18.6047534943,0.619773924351,-1.19606590271 -18.7447490692,0.625755310059,-1.14842021465 -9.68336009979,0.222733348608,-0.445854336023 -9.67136383057,0.221737623215,-0.415279299021 -9.67736816406,0.221740007401,-0.385697692633 -9.67437362671,0.221743449569,-0.355126768351 -9.67337608337,0.221745073795,-0.340334683657 -9.6713809967,0.221748486161,-0.30976459384 -9.67138576508,0.221751719713,-0.279195278883 -9.66439056396,0.220755636692,-0.249611333013 -9.66239547729,0.220759168267,-0.219042345881 -9.66339969635,0.220762312412,-0.189459949732 -9.660405159,0.220766052604,-0.158891350031 -9.66140842438,0.220767587423,-0.144100278616 -9.65441322327,0.220771834254,-0.113532274961 -9.65541934967,0.22077511251,-0.0839504152536 -9.65642356873,0.220778539777,-0.0533824786544 -9.64942932129,0.219782799482,-0.0238021668047 -9.6514339447,0.219786062837,0.00577957648784 -9.6544380188,0.219787597656,0.0215569958091 -9.64644241333,0.219792097807,0.0511363483965 -9.64144897461,0.219796285033,0.0807159021497 -9.63945388794,0.219800278544,0.111282080412 -9.63945960999,0.21980394423,0.140862822533 -9.63746547699,0.219807893038,0.170442670584 -9.63847255707,0.219811633229,0.20100979507 -9.64447498322,0.219812765718,0.215803131461 -9.63148117065,0.218818172812,0.245376691222 -9.63148784637,0.218822136521,0.27594307065 -9.6354932785,0.218825489283,0.30552598834 -9.63150024414,0.218829900026,0.33510389924 -9.63250541687,0.218833699822,0.364685058594 -9.62251281738,0.218839094043,0.395244002342 -9.62551498413,0.218840703368,0.410036444664 -9.61352157593,0.218846291304,0.439606875181 -9.62852859497,0.218848362565,0.469199746847 -9.61953544617,0.218853652477,0.498772144318 -9.61654186249,0.218858316541,0.529335558414 -9.62154865265,0.218861788511,0.558920800686 -9.61355113983,0.218864962459,0.573702931404 -9.60955810547,0.218869715929,0.603278934956 -9.6145658493,0.218873396516,0.633850634098 -9.61357212067,0.21887780726,0.663430035114 -9.60557937622,0.218883231282,0.693001151085 -9.60858726501,0.218887135386,0.722585260868 -9.60259342194,0.218892350793,0.752158224583 -9.61159706116,0.218893393874,0.767946243286 -9.60360431671,0.218898952007,0.797516524792 -9.59161186218,0.217904999852,0.826094508171 -9.60561943054,0.21890771389,0.857667267323 -9.59162712097,0.218914121389,0.886241972446 -9.58363437653,0.217919871211,0.915810465813 -9.59164142609,0.21892337501,0.946389973164 -9.58664512634,0.218926265836,0.96018666029 -9.58565235138,0.218931183219,0.990752279758 -9.58966064453,0.218935206532,1.02034020424 -9.58066749573,0.218941256404,1.04990661144 -9.58967590332,0.218944713473,1.0804899931 -9.58268356323,0.218950524926,1.11005973816 -9.58369064331,0.218955114484,1.13964366913 -9.56869602203,0.218959704041,1.15342104435 -9.57970333099,0.218963086605,1.18499600887 -9.57671165466,0.218968376517,1.21457278728 -9.58071899414,0.219972744584,1.24514997005 -9.57572841644,0.2189784199,1.27472293377 -9.56873607635,0.218984290957,1.30330574512 -9.57673931122,0.219985604286,1.31910049915 -9.56674766541,0.218992188573,1.34866285324 -9.56975650787,0.219996824861,1.37923955917 -9.56576538086,0.220002487302,1.40881490707 -9.5677728653,0.220007330179,1.43938994408 -9.56378173828,0.220013052225,1.4689655304 -9.57978916168,0.221015706658,1.50056052208 -9.5517950058,0.220022544265,1.51232862473 -9.55780315399,0.220026776195,1.54291427135 -9.56481075287,0.221031039953,1.57448959351 -9.55482006073,0.22003775835,1.60306465626 -9.55382919312,0.221043273807,1.63363480568 -9.55183887482,0.22104883194,1.66321635246 -9.53684806824,0.220056548715,1.69177758694 -9.54685211182,0.221057742834,1.7085698843 -9.5398607254,0.221064075828,1.73715233803 -9.55286884308,0.222067534924,1.76973414421 -9.53587818146,0.221075579524,1.79730284214 -9.54288768768,0.222079977393,1.8288834095 -9.54489707947,0.222085312009,1.86045062542 -9.536901474,0.222089290619,1.87423598766 -9.54691028595,0.222093164921,1.90582704544 -9.54191970825,0.222099483013,1.93540251255 -9.53792953491,0.222105830908,1.96596741676 -9.51493930817,0.222114920616,1.99154317379 -9.53294849396,0.223117858171,2.02612066269 -9.52495765686,0.223124697804,2.05470108986 -9.52196216583,0.223128020763,2.0694873333 -9.51197338104,0.222135484219,2.09904742241 -9.5319814682,0.22413803637,2.13363599777 -9.52099132538,0.223145544529,2.16220712662 -9.51700210571,0.223151907325,2.19178700447 -9.5190114975,0.224157467484,2.2233607769 -9.50602149963,0.224165305495,2.25093841553 -9.51702594757,0.224166467786,2.26873230934 -9.51003646851,0.224173516035,2.29830336571 -9.50104618073,0.224180996418,2.32786750793 -9.51005649567,0.225185394287,2.36045455933 -9.49406719208,0.224193990231,2.38802099228 -9.50207614899,0.225198626518,2.42060613632 -9.50308513641,0.225204512477,2.45218038559 -9.49909114838,0.225208207965,2.46696448326 -9.4821023941,0.225216954947,2.49354028702 -9.49811172485,0.226220488548,2.52911782265 -9.49112319946,0.226227745414,2.5586912632 -9.48713302612,0.226234391332,2.58827567101 -9.48914241791,0.227240368724,2.62084364891 -9.491147995,0.227243036032,2.63663864136 -9.48715877533,0.227249920368,2.66721081734 -9.48516941071,0.227256387472,2.69779157639 -9.47218132019,0.227264896035,2.72635555267 -9.47519111633,0.2282705158,2.75794386864 -9.47820091248,0.228276327252,2.79051971436 -9.47221279144,0.228283762932,2.82108592987 -9.47021770477,0.228287160397,2.83588004112 -9.46722888947,0.229294151068,2.86744642258 -9.47823810577,0.230298608541,2.90203237534 -9.46425056458,0.229307308793,2.92960596085 -9.46326065063,0.230313912034,2.9611825943 -9.46127223969,0.230320736766,2.99275493622 -9.45727825165,0.23032464087,3.00754189491 -9.45628833771,0.230331271887,3.03911972046 -9.4562997818,0.231337666512,3.07070279121 -9.44131278992,0.230346769094,3.09827184677 -9.45332241058,0.231351405382,3.13484477997 -9.45733261108,0.232357308269,3.16842222214 -9.43434619904,0.231367766857,3.19299435616 -9.44734954834,0.232368737459,3.21279501915 -9.44336223602,0.233376130462,3.24436402321 -9.43337440491,0.233384594321,3.27393126488 -9.43138599396,0.233391568065,3.3055100441 -9.43039608002,0.233398318291,3.33709406853 -9.43740653992,0.234403952956,3.37266612053 -9.42442035675,0.234412819147,3.40024614334 -9.42242622375,0.23441657424,3.41603207588 -9.42543792725,0.235422983766,3.45059990883 -9.43044757843,0.23542869091,3.48419165611 -9.41846084595,0.235437601805,3.51276445389 -9.42047214508,0.236444279552,3.54733085632 -9.42148303986,0.237450793386,3.57991838455 -9.40649795532,0.236460506916,3.60847711563 -9.41250133514,0.237462714314,3.62628030777 -9.41451358795,0.238469406962,3.66085004807 -9.41152477264,0.238476753235,3.6924328804 -9.41153621674,0.238483756781,3.72600674629 -9.41354846954,0.23949046433,3.76057982445 -9.39956283569,0.23949983716,3.78815770149 -9.40756702423,0.240501910448,3.80795025826 -9.41257762909,0.240508049726,3.84352898598 -9.40659141541,0.241516202688,3.87510085106 -9.40060329437,0.241524383426,3.90667319298 -9.4016160965,0.242531374097,3.94124627113 -9.39162921906,0.242540225387,3.97082328796 -9.3926410675,0.242547214031,4.00539827347 -9.40464401245,0.243548601866,4.0271935463 -9.38566017151,0.243559032679,4.05277204514 -9.39367008209,0.244564786553,4.09035110474 -9.39168357849,0.244572594762,4.12491369247 -9.38369655609,0.244581177831,4.15549230576 -9.38170909882,0.245588779449,4.18906927109 -9.38572120667,0.246595188975,4.2246556282 -9.37572860718,0.246600821614,4.23843050003 -9.3737411499,0.246608451009,4.27200937271 -9.37875175476,0.247614756227,4.30859279633 -9.37276554108,0.247623279691,4.34116268158 -9.36877918243,0.248631477356,4.37473297119 -9.37379074097,0.249637782574,4.41132068634 -9.36379814148,0.249643266201,4.42410802841 -9.35381221771,0.249652519822,4.45468139648 -9.36082363129,0.250658690929,4.49325942993 -9.35183811188,0.250667899847,4.52482843399 -9.35684967041,0.251674383879,4.56240940094 -9.35686206818,0.252681851387,4.59798622131 -9.35587501526,0.252689421177,4.63256978989 -9.35088157654,0.252694189548,4.64835262299 -9.35289478302,0.253701329231,4.68493270874 -9.34890842438,0.254709750414,4.71950101852 -9.35292053223,0.254716485739,4.75708389282 -9.34693431854,0.255725294352,4.79065418243 -9.33794879913,0.255734562874,4.82222938538 -9.34695339203,0.25673648715,4.84403181076 -9.34596633911,0.2577444911,4.88060045242 -9.33098220825,0.257754892111,4.9091758728 -9.33399486542,0.258762091398,4.94774866104 -9.33800697327,0.259768992662,4.98632955551 -9.33202075958,0.259777784348,5.01990556717 -9.32403564453,0.259786993265,5.05248165131 -9.33404064178,0.260789006948,5.07627344131 -9.32705497742,0.261798113585,5.10984659195 -9.32406806946,0.261806458235,5.14542245865 -9.32208251953,0.262814700603,5.18199586868 -9.31809520721,0.263823330402,5.21756839752 -9.31610965729,0.263831555843,5.2541437149 -9.31312274933,0.264839917421,5.28972482681 -9.31513023376,0.265843421221,5.3095164299 -9.32014274597,0.266850322485,5.35009622574 -9.31615543365,0.266858935356,5.38567447662 -9.30917072296,0.267868250608,5.42024517059 -9.30318546295,0.267877280712,5.45482349396 -9.30019950867,0.268885999918,5.49238920212 -9.30421161652,0.269893169403,5.5329709053 -9.29921913147,0.269897967577,5.54876422882 -9.30323314667,0.270905286074,5.59033727646 -9.28624916077,0.270916521549,5.61891222 -9.29126262665,0.271923542023,5.66049432755 -9.28427791595,0.272933036089,5.69606304169 -9.27829170227,0.273942261934,5.73163843155 -9.2852973938,0.273944944143,5.75543069839 -9.2833108902,0.274953275919,5.79301452637 -9.2723274231,0.275963634253,5.82658052444 -9.27933979034,0.276970356703,5.87016487122 -9.27335453033,0.277979701757,5.90673589706 -9.26337146759,0.277989774942,5.94031190872 -9.26038551331,0.278998613358,5.9788851738 -9.27039051056,0.280000627041,6.00468397141 -9.26040649414,0.28001087904,6.03925228119 -9.25842094421,0.281019359827,6.07783603668 -9.25343608856,0.282028585672,6.11541080475 -9.25145053864,0.283037245274,6.15498733521 -9.24846458435,0.284046202898,6.19455814362 -9.24448013306,0.284055292606,6.23313331604 -9.24848556519,0.285058557987,6.25592851639 -9.24750041962,0.286067247391,6.29749727249 -9.23951625824,0.287077009678,6.33307886124 -9.23653125763,0.2880859375,6.37265634537 -9.24254417419,0.28909304738,6.41823959351 -9.23056125641,0.289103895426,6.45280599594 -9.22357654572,0.290113687515,6.49037981033 -9.24158000946,0.292114406824,6.52417230606 -9.23359584808,0.292124330997,6.56075143814 -9.23161029816,0.293133020401,6.60133504868 -9.2226266861,0.294143259525,6.63790941238 -9.22164154053,0.295151978731,6.68048429489 -9.21165847778,0.295162558556,6.71705389023 -9.22266292572,0.297164648771,6.74684333801 -9.22267818451,0.298173189163,6.79042053223 -9.21169471741,0.298183858395,6.82599592209 -9.2087097168,0.299192965031,6.8675737381 -9.20972442627,0.301201283932,6.91215324402 -9.20174026489,0.301211506128,6.95072603226 -9.20874595642,0.302214294672,6.97752285004 -9.2017621994,0.30322432518,7.01709604263 -9.17778205872,0.30323767662,7.04366731644 -9.16779899597,0.304248332977,7.08123826981 -9.09582996368,0.301271378994,7.07178974152 -9.04585552216,0.299290001392,7.07835149765 -9.09785938263,0.303288280964,7.16294908524 -9.08286952972,0.303295582533,7.17373561859 -9.01190090179,0.300318539143,7.16428565979 -8.95492839813,0.298338651657,7.16484594345 -8.92794895172,0.298352748156,7.18841743469 -8.91796684265,0.299363583326,7.22598981857 -8.91098308563,0.300373911858,7.26655864716 -8.9030008316,0.301384210587,7.30513954163 -8.8640165329,0.299396306276,7.29592227936 -8.90502262115,0.303397059441,7.37550783157 -8.73307704926,0.294440329075,7.28103303909 -9.16299438477,0.320362955332,7.67974805832 -9.17000865936,0.322370529175,7.73432159424 -9.16202545166,0.323380827904,7.77490568161 -9.15604114532,0.324390918016,7.81848096848 -9.16404724121,0.325393736362,7.84927415848 -9.16206359863,0.326403081417,7.89684867859 -9.15008163452,0.327414512634,7.93641710281 -9.15009689331,0.328423321247,7.98500156403 -9.13411617279,0.329435586929,8.02156829834 -9.28309631348,0.339414477348,8.2001953125 -9.25611019135,0.338424533606,8.20296859741 -9.27512073517,0.34142947197,8.26955986023 -9.27413654327,0.342438697815,8.32013607025 -9.25815582275,0.343450784683,8.35671520233 -9.24217510223,0.344463229179,8.39527893066 -9.26718425751,0.347467064857,8.46887111664 -9.24620437622,0.347480535507,8.50343322754 -9.27320575714,0.349479436874,8.55323791504 -9.26022434235,0.350491225719,8.59480762482 -9.26224040985,0.352499991655,8.65038108826 -9.24725914001,0.353512138128,8.68995475769 -9.25327301025,0.355519920588,8.74853897095 -9.24029159546,0.356531620026,8.79011631012 -9.21831226349,0.356545358896,8.82467937469 -9.23831558228,0.358545839787,8.87047576904 -9.18136119843,0.358575701714,8.92561626434 -9.21336841583,0.361578345299,9.01120567322 -9.21138477325,0.3635879457,9.06478309631 -9.1234292984,0.360619723797,9.06312274933 -9.07945632935,0.359637916088,9.07568836212 -9.06847572327,0.360649317503,9.12026691437 -9.0584936142,0.361660689116,9.16683959961 -9.0575094223,0.363670349121,9.22340965271 -9.04852771759,0.365681439638,9.27098751068 -9.045545578,0.36669126153,9.32456970215 -9.05754947662,0.368693441153,9.36536216736 -9.04956817627,0.369704425335,9.4149389267 -9.0395860672,0.370715916157,9.46350860596 -9.0376033783,0.372725725174,9.52008533478 -9.03162002563,0.374736338854,9.57266235352 -9.02063941956,0.375747948885,9.62023639679 -9.03265285492,0.378754794598,9.69182300568 -9.01166629791,0.377763807774,9.6996049881 -8.95569705963,0.376784741879,9.70016670227 -8.90072727203,0.374805510044,9.70172595978 -8.84075832367,0.372827291489,9.69728565216 -8.78079032898,0.370848983526,9.69184970856 -8.73881721497,0.369866997004,9.70542049408 -8.75082206726,0.37186935544,9.74920940399 -8.73684215546,0.372881650925,9.79378700256 -8.73685932159,0.374891132116,9.85436820984 -8.73087692261,0.376902073622,9.90993881226 -8.76588439941,0.380904346704,10.0105295181 -8.97384738922,0.396871238947,10.3081665039 -8.97586345673,0.399880409241,10.374745369 -8.98187065125,0.400884032249,10.4145317078 -8.97688865662,0.402894675732,10.4741077423 -8.97190570831,0.404905289412,10.5336847305 -8.96092605591,0.405917197466,10.5872573853 -8.95494365692,0.407928109169,10.6468334198 -8.93396568298,0.408941954374,10.6884088516 -8.94697093964,0.410944104195,10.7372016907 -8.95098590851,0.413952857256,10.8087863922 -8.95400238037,0.415962010622,10.8813591003 -8.9470205307,0.417973071337,10.9409389496 -8.9330406189,0.418985724449,10.9935112 -8.17825698853,0.369150489569,10.1398963928 -8.97006511688,0.426997542381,11.1786766052 -3.45653748512,0.0391405560076,4.40484905243 -3.4215669632,0.0381579995155,4.38940858841 -3.40459084511,0.0381712689996,4.39499282837 -3.39761137962,0.0381822660565,4.41258859634 -8.88819694519,0.437077999115,11.5449123383 -8.90919971466,0.440078556538,11.608707428 -8.89522075653,0.442091286182,11.6652803421 -8.87224292755,0.443105787039,11.7098550797 -8.87725830078,0.4461145401,11.7914381027 -8.87827587128,0.449124395847,11.8700094223 -8.8672952652,0.451136320829,11.9305934906 -8.86331367493,0.453147113323,12.0031661987 -8.87132072449,0.455150574446,12.0539522171 -8.8653383255,0.457161515951,12.1225366592 -8.8583574295,0.460172891617,12.1921129227 -8.84937763214,0.462184727192,12.25968647 -8.84139633179,0.464196354151,12.3292608261 -8.83441543579,0.467207700014,12.3998394012 -8.84242248535,0.469210922718,12.4506349564 -8.83844089508,0.471221745014,12.5272111893 -8.8304605484,0.474233418703,12.5987863541 -8.82048034668,0.476245552301,12.6683597565 -8.80850028992,0.478258013725,12.7349348068 -8.80951786041,0.481267929077,12.8215103149 -8.79853820801,0.484280019999,12.8890953064 -8.81154346466,0.486282587051,12.9528770447 -8.80556297302,0.489293754101,13.029460907 -8.79758167267,0.492305338383,13.1040410995 -8.77360630035,0.49332049489,13.1576080322 -8.78562068939,0.497328013182,13.2631931305 -8.77364063263,0.50034058094,13.3347682953 -8.78764629364,0.502342939377,13.4025535583 -8.76766967773,0.504357099533,13.4621305466 -8.7656879425,0.507367491722,13.5497131348 -8.75970649719,0.510379076004,13.6342840195 -8.7567243576,0.514389753342,13.721865654 -8.74574565887,0.516402184963,13.7994384766 -8.73576641083,0.519414424896,13.8780174255 -8.74977111816,0.522416651249,13.947810173 -8.74179172516,0.525428533554,14.0323829651 -8.73181152344,0.528440713882,14.1129617691 -8.72383117676,0.531452536583,14.1975421906 -8.71485233307,0.534464716911,14.2831125259 -8.70787143707,0.537476301193,14.3706941605 -8.69589233398,0.540489077568,14.4522686005 -8.7138967514,0.543490469456,14.5330600739 -8.70491790771,0.5475025177,14.619641304 -8.69393825531,0.550514996052,14.7042198181 -8.68495845795,0.553527235985,14.7947912216 -8.67298030853,0.556540071964,14.8803653717 -8.66699981689,0.559551537037,14.9759454727 -8.65602016449,0.563564181328,15.0655183792 -8.67102527618,0.566566169262,15.1443157196 -8.66104602814,0.569578647614,15.2368898392 -8.65706539154,0.573589801788,15.340467453 -8.64108848572,0.576603412628,15.424041748 -8.63310813904,0.580615460873,15.5226192474 -8.61413192749,0.583629608154,15.6011981964 -8.63413524628,0.587630808353,15.6949901581 -8.62615585327,0.590642809868,15.7965660095 -8.61417675018,0.594655692577,15.8921403885 -8.60119915009,0.597668647766,15.9847240448 -8.59721851349,0.602680027485,16.0982952118 -8.58224105835,0.605693638325,16.1918678284 -8.57726097107,0.609704852104,16.3024539948 -8.59326457977,0.613706946373,16.395242691 -8.57428836823,0.616721332073,16.4838180542 -6.2619767189,0.399204343557,12.1639585495 -8.55233192444,0.624746859074,16.6949672699 -8.5583486557,0.630756080151,16.8345489502 -8.53937244415,0.633770465851,16.9271259308 -8.5203962326,0.637784838676,17.0207004547 -6.26206207275,0.416250824928,12.5900783539 -8.52542209625,0.645799577236,17.2300701141 -6.23110961914,0.421277910471,12.7252349854 -6.17214584351,0.419300287962,12.7048072815 -6.10518455505,0.41732442379,12.6683731079 -6.12019920349,0.422331750393,12.7999582291 -5.98124980927,0.410365343094,12.5627202988 -5.97327136993,0.413377344608,12.6463022232 -6.12124729156,0.433357685804,13.0619077682 -6.03329229355,0.428385943174,12.9794750214 -6.0473074913,0.434393525124,13.1150608063 -6.01133728027,0.434411287308,13.1446352005 -5.94637584686,0.431434869766,13.1102085114 -5.96837902069,0.436435669661,13.2130012512 -5.90441703796,0.434459149837,13.1815700531 -5.85345172882,0.433479964733,13.1781415939 -5.86646699905,0.438487768173,13.3177280426 -5.85249042511,0.442501038313,13.3983078003 -5.8105225563,0.442520022392,13.4158830643 -5.78854894638,0.444534927607,13.4794626236 -5.80355405807,0.448537230492,13.5732507706 -5.79557609558,0.452549368143,13.671831131 -5.77660083771,0.454563558102,13.7444143295 -5.73963165283,0.455581605434,13.7769880295 -5.73365259171,0.459593236446,13.8825731277 -5.72767400742,0.464604973793,13.9911527634 -5.72868347168,0.466610133648,14.0569391251 -5.71570682526,0.470623254776,14.150519371 -5.71072864532,0.475634843111,14.2660989761 -5.7047495842,0.479646384716,14.3776874542 -5.68777418137,0.483660370111,14.4662656784 -5.69079303741,0.489670425653,14.607843399 -5.67681741714,0.493683815002,14.7074222565 -5.69282197952,0.49768576026,14.8152208328 -5.65685224533,0.499703526497,14.859796524 -5.64887428284,0.504715919495,14.9803724289 -5.66688871384,0.512722790241,15.1699571609 -5.62991905212,0.51374065876,15.2135400772 -5.6269402504,0.519751906395,15.3521203995 -5.62695980072,0.525762438774,15.500702858 -5.63496732712,0.529766142368,15.597495079 -5.59000062943,0.530785799026,15.6260690689 -5.577023983,0.534798920155,15.7426519394 -5.56904649734,0.540811061859,15.8762350082 -5.6110534668,0.55281329155,16.1558227539 -5.62706851959,0.561820745468,16.3654060364 -5.60709428787,0.566835343838,16.4729881287 -5.60810422897,0.569840550423,16.5617752075 -5.60812425613,0.577851176262,16.7333564758 -5.59914684296,0.58386361599,16.8799381256 -5.58317136765,0.588877439499,17.008518219 -5.5791926384,0.595888853073,17.1760997772 -5.5342259407,0.596908450127,17.2196769714 -4.14465904236,0.400191307068,12.998257637 -4.12968397141,0.403204858303,13.0928354263 -4.06772327423,0.400227546692,13.0364170074 -6.94186735153,0.835665941238,22.4013957977 -7.15582180023,0.878634393215,23.3450031281 -7.07686519623,0.877660870552,23.34557724 -6.99690914154,0.876687586308,23.3441505432 -6.95093345642,0.874702215195,23.3249320984 -6.87097740173,0.873728990555,23.3245010376 -6.79202127457,0.872755527496,23.3250751495 -6.70906639099,0.871782898903,23.3126430511 -6.63011026382,0.870809316635,23.3102207184 -6.55215406418,0.869835555553,23.313791275 -6.50817775726,0.868849754333,23.2985744476 -6.42722272873,0.867876648903,23.2911434174 -6.34926605225,0.866902887821,23.2917194366 -6.26930999756,0.864929437637,23.2842941284 -6.19235420227,0.864955604076,23.2918624878 -6.1133980751,0.863981902599,23.2854385376 -6.03244304657,0.862008750439,23.2750091553 -5.99146556854,0.862022161484,23.264799118 -5.91350984573,0.861048400402,23.266368866 -5.83155536652,0.859075367451,23.2489414215 -5.7196097374,0.852108120918,23.1085128784 -5.44071531296,0.813173651695,22.2870616913 -5.59768724442,0.856153666973,23.2376651764 -5.52073144913,0.855179548264,23.2372398376 -5.4797539711,0.855193018913,23.2280254364 -5.40379810333,0.854218780994,23.2335968018 -5.32584190369,0.853244721889,23.2261734009 -5.24888563156,0.852270483971,23.2227516174 -5.17193031311,0.851296424866,23.2233219147 -5.13196325302,0.858314990997,23.3878993988 -5.1119890213,0.869329690933,23.6494808197 -5.12499523163,0.88033246994,23.8852787018 -5.05503749847,0.881356954575,23.9278488159 -3.23362326622,0.502722203732,15.601225853 -3.168664217,0.499745458364,15.5357980728 -3.11770009995,0.498765707016,15.53038311 -3.06573748589,0.497786402702,15.5259580612 -3.03875565529,0.496796756983,15.514752388 -2.99479031563,0.498815834522,15.5493297577 -2.95582318306,0.50083386898,15.6109085083 -2.90685868263,0.500853657722,15.6154937744 -2.86089396477,0.501873195171,15.6440696716 -2.79693484306,0.497896045446,15.5716457367 -4.87730741501,1.03650486469,27.5124568939 -4.8923125267,1.05150735378,27.8482513428 -4.86534166336,1.06752336025,28.2098331451 -4.83337163925,1.08254027367,28.5554161072 -4.83641195297,1.13256120682,29.6955814362 -4.74446153641,1.13258981705,29.7221565247 -4.75546789169,1.14859306812,30.0889511108 -4.7224984169,1.16661024094,30.4965324402 -4.68952941895,1.18562734127,30.9211120605 -4.65056228638,1.20264565945,31.3286914825 -4.61859273911,1.22366261482,31.7972717285 -4.58162498474,1.24268043041,32.2488555908 -4.54565668106,1.26369810104,32.729434967 -4.54266834259,1.27970409393,33.0842285156 -4.46371364594,1.28772997856,33.2818069458 -4.38075971603,1.29475641251,33.4583854675 -4.28581047058,1.29878520966,33.5489654541 -4.1928601265,1.30381369591,33.6665382385 -4.09791040421,1.30784249306,33.7661170959 -4.0059595108,1.31287062168,33.8956947327 -3.96598243713,1.31788349152,34.0124855042 -2.6804060936,0.856137216091,23.7099647522 -2.60045194626,0.854162812233,23.6685447693 -2.52449655533,0.853187561035,23.6601257324 -2.45453929901,0.85521119833,23.70570755 -2.37158608437,0.851237237453,23.6272888184 -3.38928747177,1.34705626965,34.7309570312 -3.34131288528,1.35007035732,34.8017501831 -3.24036550522,1.35410010815,34.9073257446 -3.14041757584,1.35912942886,35.0229072571 -3.0604634285,1.37415492535,35.3744850159 -2.96051549911,1.38018417358,35.5130653381 -2.85956811905,1.38621354103,35.6566467285 -2.80559515953,1.38722884655,35.6764411926 -2.69565081596,1.3882600069,35.7210159302 -2.58670592308,1.39029073715,35.7765922546 -2.45776724815,1.38032519817,35.541179657 -2.33282732964,1.37135875225,35.3527565002 -2.21988344193,1.36939013004,35.3253364563 -2.11093878746,1.37142074108,35.3679161072 -2.05596613884,1.37143599987,35.3647079468 -1.94802129269,1.37446653843,35.4422912598 -1.83507752419,1.3724976778,35.4138717651 -1.7261326313,1.37452805042,35.4494552612 -1.61818742752,1.37755823135,35.534034729 -1.50524401665,1.37658929825,35.5186157227 -1.45327067375,1.3806040287,35.5944099426 -1.34532558918,1.38563418388,35.7119903564 -1.23538100719,1.38766443729,35.7755737305 -1.12243759632,1.38769543171,35.7651557922 -1.01149332523,1.38972580433,35.8097381592 -0.901548922062,1.3937561512,35.9043235779 -0.790604710579,1.39678633213,35.9809074402 -0.735632479191,1.40080153942,36.0637016296 -0.62568795681,1.40783154964,36.2292861938 -0.515743494034,1.42086160183,36.5238685608 -0.405799031258,1.43889164925,36.9364547729 -0.30885013938,1.53491902351,39.0950469971 -0.188908725977,1.55595076084,39.5576286316 -0.0649687051773,1.57098305225,39.8952140808 -0.00299856625497,1.60899925232,40.7560119629 --0.050974342972,1.56801378727,35.2808074951 --0.161918461323,1.56604373455,35.2353935242 --0.270863384008,1.55807316303,35.084980011 --0.380807816982,1.55510282516,35.0275650024 --0.490752279758,1.55513238907,35.0121498108 --0.599697232246,1.55316162109,34.9797363281 --0.708642065525,1.55119097233,34.9373245239 --0.763614177704,1.55020570755,34.9141159058 --0.874558329582,1.55223536491,34.95470047 --0.981503844261,1.54826402664,34.861289978 --1.09144842625,1.54929327965,34.8738746643 --1.20039319992,1.54732239246,34.8474655151 --1.3053394556,1.54235053062,34.7440567017 --1.41428422928,1.54137945175,34.7186393738 --1.46725726128,1.54039359093,34.6944351196 --1.57620215416,1.54042232037,34.6890258789 --1.68514692783,1.54045116901,34.6716117859 --1.79309225082,1.53947973251,34.6622009277 --1.90503621101,1.54250895977,34.7057914734 --2.01198172569,1.54053711891,34.6633796692 --2.11992716789,1.54056537151,34.6499710083 --2.17489933968,1.54057967663,34.648765564 --2.28284454346,1.53960800171,34.6253509521 --2.38679099083,1.53663551807,34.5479393005 --2.49373674393,1.53566336632,34.5255317688 --1.83292365074,1.0265570879,24.4051494598 --2.02381181717,1.02661371231,24.3911266327 --2.18371963501,1.02966034412,24.4433021545 --2.2496778965,1.02368104458,24.3178901672 --2.33762979507,1.03070545197,24.4354839325 --2.40258860588,1.024725914,24.3130760193 --2.44156575203,1.02473735809,24.3088665009 --2.52951717377,1.03076171875,24.4114551544 --3.76710939407,1.57398343086,35.173034668 --3.89604830742,1.58301436901,35.3256263733 --4.02698659897,1.59204542637,35.493221283 --4.1509270668,1.59707534313,35.5868186951 --4.27386856079,1.60210502148,35.6664085388 --4.3408370018,1.60612082481,35.7452049255 --4.46177911758,1.61014997959,35.8037986755 --4.5867190361,1.61517977715,35.8843955994 --4.70866060257,1.6182090044,35.940990448 --4.83460044861,1.62323892117,36.0205802917 --4.96154069901,1.62826871872,36.1061782837 --5.03250789642,1.63328504562,36.1949729919 --5.15944814682,1.63831472397,36.2715682983 --5.28738737106,1.64334464073,36.3511619568 --5.42032575607,1.64937520027,36.4627609253 --5.55226373672,1.6554056406,36.5573577881 --5.68620204926,1.66143620014,36.659954071 --5.81814098358,1.66746640205,36.7515525818 --5.89110803604,1.67248260975,36.8373527527 --6.02304649353,1.6765127182,36.9129447937 --6.14998626709,1.68054187298,36.9635467529 --6.28192520142,1.68557178974,37.0351409912 --6.41186475754,1.68960118294,37.0947418213 --6.55180072784,1.69563221931,37.2043418884 --6.70073461533,1.70466458797,37.3619384766 --6.71172094345,1.69167041779,37.0897369385 --6.8146686554,1.6876950264,36.9913330078 --6.9276137352,1.68672132492,36.9519348145 --7.03855895996,1.68574726582,36.9055328369 --7.15250396729,1.68477356434,36.8691291809 --7.25845098495,1.68279838562,36.7997322083 --7.37039613724,1.68182420731,36.7583312988 --7.4453625679,1.68584024906,36.8301277161 --6.62759494781,1.45371544361,32.27368927 --6.69055557251,1.44473338127,32.0702857971 --6.73752117157,1.43174874783,31.7968826294 --6.79048442841,1.4207650423,31.5564785004 --6.85044622421,1.4107824564,31.3570766449 --6.90242004395,1.41179454327,31.357875824 --6.59747362137,1.29776132107,29.1060523987 --6.68042802811,1.29578232765,29.0456485748 --6.76538181305,1.29480350018,28.9992465973 --6.85533428192,1.29482555389,28.9728469849 --6.94428682327,1.29484724998,28.943447113 --6.9922618866,1.29485869408,28.9422454834 --7.08621358871,1.29588115215,28.9308433533 --7.15117359161,1.28989887238,28.8054428101 --7.27511548996,1.29692590237,28.9140434265 --7.35507154465,1.29494595528,28.8486442566 --7.46101903915,1.29797005653,28.8822441101 --7.60895347595,1.30900073051,29.0748443604 --7.59494781494,1.2970020771,28.8366413116 --7.20704698563,1.20494890213,27.0252170563 --7.23801755905,1.19396138191,26.8018131256 --7.28598308563,1.18697619438,26.6454086304 --7.32395172119,1.17898952961,26.4590072632 --6.93504095078,1.08394062519,24.6043739319 --6.98800516129,1.07895636559,24.4979743958 --7.06196260452,1.07897520065,24.4635696411 --7.26286220551,1.08702087402,24.5777721405 --7.270840168,1.07502937317,24.3243694305 --7.35079574585,1.07604897022,24.3119697571 --7.38477563858,1.07505774498,24.2867698669 --7.46473169327,1.07607710361,24.2753696442 --7.5486869812,1.07709717751,24.2759723663 --7.62764310837,1.0771163702,24.2595710754 --7.70360088348,1.07713496685,24.2331695557 --7.7885556221,1.07915484905,24.2367725372 --7.86451292038,1.07917332649,24.2093696594 --7.90149211884,1.0791823864,24.1951732635 --7.98244810104,1.07920157909,24.1827716827 --8.06740283966,1.08122122288,24.186378479 --8.14535999298,1.08123970032,24.1659793854 --8.22631645203,1.08225870132,24.1525764465 --8.30427360535,1.08227717876,24.1321773529 --8.34025382996,1.08228588104,24.1129798889 --8.42220973969,1.08330464363,24.1055850983 --8.49916744232,1.08332276344,24.0821857452 --8.58612155914,1.08534228802,24.0847873688 --8.67307758331,1.08636176586,24.0893917084 --8.74603652954,1.08637905121,24.0539951324 --8.830991745,1.08739805222,24.0525989532 --8.87196922302,1.08840727806,24.0453968048 --13.2503576279,1.48212277889,30.7290039062 --13.2293462753,1.46712446213,30.415599823 --13.1933479309,1.45712184906,30.2023944855 --13.2783060074,1.456138134,30.139005661 --13.1923141479,1.43313097954,29.6895961761 --13.1363124847,1.41512787342,29.316192627 --13.1232995987,1.40213084221,29.0407886505 --13.1202831268,1.39113497734,28.792388916 --13.1112680435,1.37913835049,28.5329837799 --13.0572757721,1.36713325977,28.2997817993 --13.0442619324,1.35513615608,28.0383777618 --13.0312480927,1.34313905239,27.7799758911 --13.0232334137,1.33214247227,27.53657341 --13.0032224655,1.31914424896,27.2731723785 --12.9982070923,1.30914819241,27.0427722931 --12.950211525,1.29814398289,26.8355674744 --12.940196991,1.28714728355,26.6001663208 --12.9281845093,1.27715027332,26.3637638092 --9.00030708313,0.821638643742,18.2088775635 --9.03727817535,0.819649577141,18.1394786835 --9.08824539185,0.818662345409,18.0990829468 --9.13021469116,0.81767398119,18.0396823883 --9.15219974518,0.81667983532,18.0134849548 --9.20416641235,0.815692722797,17.9730834961 --9.26313114166,0.816706299782,17.9486865997 --9.32209587097,0.816719830036,17.9252948761 --9.38905906677,0.817734360695,17.9148960114 --9.48201370239,0.82175219059,17.9535045624 --9.58496570587,0.826771140099,18.0111141205 --12.7330532074,1.15917408466,23.8363304138 --12.7300386429,1.15117812157,23.6519317627 --12.727022171,1.14318215847,23.4675273895 --12.7100095749,1.13318443298,23.2601222992 --12.7809734344,1.13319766521,23.2167358398 --12.8639326096,1.13421237469,23.1933441162 --12.9189081192,1.13622128963,23.2061519623 --13.0738477707,1.1452447176,23.3107719421 --13.2007951736,1.15026462078,23.3653945923 --13.2837553024,1.15127897263,23.3390045166 --13.4536914825,1.16130375862,23.466632843 --13.6056318283,1.16932630539,23.5582523346 --13.6635904312,1.16333913803,23.4016590118 --13.7855405807,1.1683576107,23.4412822723 --13.8734989166,1.16937196255,23.4218959808 --14.0164432526,1.17639291286,23.492515564 --14.1183996201,1.17940866947,23.4961338043 --12.5828142166,1.02322876453,20.7894973755 --12.5797986984,1.01623272896,20.6370983124 --12.5657939911,1.01223301888,20.540895462 --12.6267604828,1.01124453545,20.4955043793 --12.7147197723,1.01425898075,20.4921150208 --12.7876834869,1.01427161694,20.4657287598 --12.9076337814,1.0202896595,20.512342453 --12.8306398392,1.00628459454,20.2489318848 --12.7976408005,1.00028276443,20.1257266998 --12.7686319351,0.992283463478,19.9403209686 --12.7166309357,0.981281399727,19.721912384 --12.7616024017,0.979290544987,19.6545181274 --12.7225961685,0.970290005207,19.4601135254 --13.0244970322,0.992328345776,19.7847576141 --12.6295909882,0.951287329197,19.0542984009 --12.5486049652,0.941280186176,18.8660812378 --12.6065731049,0.940290629864,18.8246917725 --12.5845632553,0.933292150497,18.6632862091 --12.61054039,0.930298924446,18.5748882294 --12.5715351105,0.921298503876,18.3914813995 --12.342581749,0.896277070045,17.9350452423 --12.5315132141,0.908301889896,18.0866737366 --12.5654964447,0.908307552338,18.0744800568 --12.5124959946,0.899305641651,17.8770694733 --12.4964838028,0.892307758331,17.7346668243 --12.5744466782,0.894320070744,17.7262802124 --12.5114488602,0.884317040443,17.5198688507 --12.5524225235,0.883325338364,17.4594726562 --12.4814338684,0.874319553375,17.3032608032 --12.4864168167,0.870323896408,17.1958637238 --12.5703783035,0.873336613178,17.1964759827 --12.4793872833,0.860330760479,16.9580554962 --12.5123624802,0.859337985516,16.8906612396 --12.5543355942,0.858346104622,16.8362693787 --12.5023345947,0.849344372749,16.6558589935 --12.2204017639,0.82331687212,16.2256069183 --12.2253847122,0.819321155548,16.1262073517 --12.2403659821,0.81632655859,16.0398082733 --8.93521404266,0.535996437073,11.5464162827 --8.98218536377,0.537006556988,11.5320234299 --9.00316238403,0.536014199257,11.4826183319 --9.03214550018,0.537019729614,11.4824237823 --12.3092632294,0.799354016781,15.5606155396 --12.3622331619,0.800362944603,15.5262241364 --12.3792133331,0.79736828804,15.4478302002 --12.4791727066,0.801381707191,15.4714450836 --12.6491117477,0.811401963234,15.5810756683 --12.7350749969,0.81441372633,15.5856904984 --12.7110738754,0.810413002968,15.5064868927 --12.4731206894,0.787393271923,15.1180429459 --12.9129905701,0.818439126015,15.5517272949 --13.0189495087,0.823452532291,15.5783443451 --13.0899152756,0.824462413788,15.5629587173 --12.2461194992,0.755385518074,14.4633903503 --12.2301158905,0.752385795116,14.3981866837 --12.2211036682,0.748388409615,14.2957849503 --12.231086731,0.745392858982,14.2153835297 --12.22407341,0.741395652294,14.1159791946 --12.2280569077,0.738399505615,14.030579567 --12.2140455246,0.733401596546,13.9261808395 --12.2180299759,0.730405390263,13.8417806625 --12.1860313416,0.726404130459,13.7615747452 --12.1890144348,0.723407924175,13.6761693954 --12.1919994354,0.720411539078,13.5927705765 --12.1809873581,0.716413855553,13.4943685532 --12.1819725037,0.713417291641,13.4099683762 --12.1819572449,0.71042072773,13.3235626221 --15.786034584,0.975740075111,17.1729335785 --19.0162143707,1.2130228281,20.6314334869 --12.0249605179,0.690415263176,12.9435272217 --12.0289449692,0.688418984413,12.8661289215 --12.0069360733,0.683420479298,12.7607221603 --12.0169181824,0.681424617767,12.6903219223 --12.0269012451,0.679428815842,12.6199207306 --12.1068668365,0.682438850403,12.6235361099 --12.1558475494,0.6844445467,12.6353492737 --12.1388378143,0.680446326733,12.5369415283 --12.1408233643,0.677449703217,12.4595403671 --12.1308107376,0.673452019691,12.3711414337 --12.1257972717,0.670454740524,12.2867336273 --12.1277828217,0.668458044529,12.2113351822 --12.1067810059,0.665457904339,12.1511297226 --12.1097660065,0.662461221218,12.0777320862 --12.1007547379,0.659463644028,11.9923295975 --12.1077384949,0.657467246056,11.9229278564 --12.0987262726,0.653469622135,11.8385238647 --12.0957126617,0.651472449303,11.7601203918 --12.1026973724,0.648476004601,11.6927232742 --12.0886936188,0.646476447582,11.6415166855 --12.0776824951,0.643478572369,11.5571126938 --12.0666704178,0.64048075676,11.4737110138 --12.0756540298,0.638484418392,11.4093112946 --12.0646429062,0.634486496449,11.3269100189 --12.0686283112,0.632489800453,11.2585096359 --12.0766124725,0.630493283272,11.1941080093 --12.050611496,0.627492845058,11.1338996887 --12.0455989838,0.625495314598,11.0595026016 --12.0355873108,0.621497511864,10.979095459 --12.0435724258,0.620500981808,10.9166965485 --12.0445585251,0.617504000664,10.8472929001 --12.0425443649,0.615506589413,10.7768936157 --12.0335330963,0.612508833408,10.6994876862 --12.0105314255,0.609508633614,10.6452846527 --12.0125169754,0.607511520386,10.5788831711 --12.0085048676,0.605514109135,10.5074796677 --12.0134897232,0.603517234325,10.4440774918 --12.010477066,0.600519776344,10.3746757507 --12.0084638596,0.598522365093,10.3062734604 --12.0064506531,0.596524953842,10.237868309 --11.9814491272,0.593524634838,10.1836624146 --11.9834356308,0.591527462006,10.120265007 --11.9884214401,0.589530527592,10.0588617325 --11.9894075394,0.587533175945,9.99546527863 --11.9763965607,0.584534943104,9.92006015778 --11.9743843079,0.582537531853,9.85365390778 --11.9623804092,0.580538094044,9.8114490509 --11.9533691406,0.578540086746,9.74104881287 --11.9573545456,0.576542973518,9.68064498901 --11.9573411942,0.574545502663,9.61824798584 --11.9523296356,0.572547793388,9.55083942413 --11.9543161392,0.570550441742,9.49043941498 --11.9423055649,0.567552268505,9.41903686523 --11.9253025055,0.565552473068,9.37483119965 --11.9332885742,0.564555466175,9.32043647766 --11.9302759171,0.562557816505,9.25602817535 --11.9262638092,0.560559988022,9.19262886047 --11.9172515869,0.557561993599,9.12522411346 --11.9162397385,0.555564343929,9.06381988525 --11.9232254028,0.554567158222,9.0094203949 --11.9072227478,0.552567481995,8.96721458435 --11.9072093964,0.550569832325,8.90781211853 --11.9361896515,0.550573706627,8.87142467499 --12.0341567993,0.555581152439,8.88504600525 --5.51255226135,0.145244002342,3.9960474968 --5.53153181076,0.146251216531,3.98365712166 --5.52651500702,0.145257487893,3.95224070549 --11.8701343536,0.537582993507,8.5021944046 --11.8731212616,0.535585463047,8.44679069519 --11.8691091537,0.53358745575,8.38739109039 --11.869096756,0.532589673996,8.330991745 --11.8780822754,0.531592309475,8.28059005737 --11.8680715561,0.528594017029,8.21718406677 --11.8480701447,0.526594161987,8.17598247528 --11.8480577469,0.525596380234,8.11957645416 --11.8460445404,0.523598372936,8.06317710876 --11.8390340805,0.521600246429,8.00277042389 --11.8460197449,0.52060264349,7.95236873627 --11.8510074615,0.519604861736,7.90197658539 --11.8369979858,0.516606390476,7.83756685257 --11.8229942322,0.515606880188,7.80035686493 --11.818983078,0.513608694077,7.74395608902 --11.8219709396,0.512610852718,7.69255876541 --11.8319559097,0.511613249779,7.64515733719 --11.8219461441,0.509614825249,7.58575677872 --11.8179340363,0.507616639137,7.52934932709 --11.8049316406,0.506617188454,7.49414253235 --11.8029203415,0.504618942738,7.44074487686 --11.797908783,0.502620697021,7.38534450531 --11.802895546,0.501622796059,7.33594274521 --11.8028841019,0.500624716282,7.28353881836 --11.7908744812,0.498626112938,7.22413349152 --11.7928619385,0.497628003359,7.17373275757 --11.7718601227,0.495628237724,7.13552951813 --11.7798461914,0.494630336761,7.08812236786 --11.7768354416,0.492632031441,7.03572463989 --11.7888212204,0.492634177208,6.99132108688 --11.7698135376,0.48963534832,6.9299197197 --11.7768001556,0.488637328148,6.88251209259 --11.7637910843,0.486638635397,6.825111866 --11.7597866058,0.485639363527,6.79791164398 --11.7517757416,0.484640866518,6.74250125885 --11.7647619247,0.483642876148,6.70010280609 --11.747754097,0.481644034386,6.64170455933 --11.7517414093,0.480645775795,6.59430217743 --11.7487306595,0.47964733839,6.54289579391 --11.7487192154,0.477648943663,6.49349164963 --11.7417154312,0.476649522781,6.46529006958 --11.737704277,0.47565099597,6.41489267349 --11.7566890717,0.475652962923,6.37649440765 --11.8226661682,0.477655917406,6.36411333084 --11.8236551285,0.476657360792,6.31570911407 --11.8176441193,0.475658684969,6.26329994202 --11.8196334839,0.47466006875,6.21690559387 --11.9026126862,0.478662371635,6.23672771454 --11.9715890884,0.481664955616,6.22434329987 --12.0475654602,0.484667569399,6.21596765518 --12.1065444946,0.486669689417,6.19858884811 --12.2455091476,0.493673056364,6.22122716904 --12.3154859543,0.496675103903,6.20784664154 --12.2914848328,0.494675159454,6.17164373398 --12.4734430313,0.503678679466,6.21429586411 --17.1126308441,0.76173979044,8.43200302124 --17.1626167297,0.762737572193,8.38861942291 --17.2186012268,0.764735341072,8.34924411774 --17.2575893402,0.765732824802,8.29985523224 --12.2724218369,0.486680299044,5.84501981735 --12.2634134293,0.484680920839,5.79362392426 --12.2644033432,0.483681619167,5.74622249603 --12.2613935471,0.482682317495,5.69681787491 --12.4743490219,0.493684560061,5.74948692322 --17.59349823,0.774714529514,8.02039051056 --14.8099460602,0.619698226452,6.70526027679 --14.7569475174,0.61569660902,6.62384080887 --14.6779518127,0.610694944859,6.53141307831 --14.6029567719,0.604693412781,6.44199037552 --14.5359592438,0.600691914558,6.35656785965 --14.467962265,0.59569054842,6.27114391327 --14.3929672241,0.590689241886,6.18371915817 --14.3189754486,0.585688650608,6.12449598312 --14.2489776611,0.580687463284,6.04007101059 --14.1869792938,0.576686382294,5.9606552124 --14.1139831543,0.571685433388,5.87622880936 --14.0499858856,0.566684484482,5.79680919647 --11.7213201523,0.438692361116,4.72821187973 --11.7183151245,0.437692701817,4.70500802994 --11.6463165283,0.432693779469,4.63157606125 --11.6263093948,0.43069460988,4.58117437363 --11.5763072968,0.427695691586,4.51775121689 --11.6222906113,0.429696053267,4.49336385727 --11.597284317,0.426696926355,4.44095468521 --11.6062736511,0.426697522402,4.40155124664 --11.6152667999,0.426697731018,4.3843588829 --11.6122579575,0.425698339939,4.34095668793 --11.6002502441,0.424699068069,4.29354524612 --11.5972414017,0.423699647188,4.25115060806 --11.5912322998,0.422700285912,4.2057352066 --11.5972223282,0.422700732946,4.16633796692 --11.6082115173,0.421701073647,4.1289434433 --11.5892095566,0.420701563358,4.10073232651 --11.5852003098,0.419702112675,4.0583357811 --11.5931892395,0.419702410698,4.01892948151 --11.5801820755,0.417703032494,3.97251963615 --11.5771741867,0.417703479528,3.93112611771 --11.5881624222,0.41770362854,3.89372801781 --11.5801553726,0.415704101324,3.84931850433 --11.5711517334,0.415704458952,3.82611823082 --11.5761423111,0.41470465064,3.78671741486 --11.5621337891,0.413705229759,3.7403023243 --11.5611257553,0.412705510855,3.69990706444 --11.5751152039,0.412705421448,3.66350722313 --11.473118782,0.4067081213,3.58906173706 --11.4331197739,0.404709249735,3.55685448647 --11.4301109314,0.403709620237,3.51544737816 --11.4241027832,0.40270999074,3.47404742241 --11.3990974426,0.400710940361,3.42562890053 --11.4260845184,0.401710391045,3.39423584938 --11.4020786285,0.399711251259,3.34783148766 --11.4090690613,0.399711221457,3.31043219566 --11.4130649567,0.399711161852,3.29122591019 --11.4100561142,0.398711383343,3.2508225441 --11.3940496445,0.397711992264,3.20641112328 --11.4120388031,0.397711455822,3.17302250862 --11.4060316086,0.396711707115,3.13161349297 --11.4000234604,0.395711928606,3.09121394157 --11.368019104,0.393713057041,3.04279613495 --11.3660144806,0.393713116646,3.02259206772 --11.3740053177,0.393712818623,2.98619580269 --11.3739967346,0.392712771893,2.94678735733 --11.3859872818,0.392712205648,2.91139125824 --11.3739805222,0.391712576151,2.86998987198 --11.3929700851,0.392711639404,2.83558678627 --11.3709640503,0.390712380409,2.79218578339 --11.37196064,0.390712231398,2.77298283577 --11.3969488144,0.391710966825,2.74058747292 --11.366944313,0.389712035656,2.69416928291 --11.3239402771,0.386713683605,2.64575576782 --11.3419313431,0.387712597847,2.61135363579 --11.3699207306,0.388711005449,2.57996201515 --11.4019098282,0.389709144831,2.54957437515 --11.4379024506,0.390707194805,2.53939247131 --11.4708919525,0.392705112696,2.50799512863 --11.49888134,0.393703192472,2.4766099453 --11.50187397,0.392702490091,2.4382019043 --11.4458713531,0.389704793692,2.38778162003 --11.4378643036,0.38870459795,2.34737014771 --11.6668338776,0.399691313505,2.33986377716 --11.6898241043,0.400689214468,2.30546545982 --11.7088155746,0.40168723464,2.27107548714 --11.7578048706,0.403683453798,2.24168634415 --11.7767963409,0.403681337833,2.20729899406 --11.8297863007,0.406677126884,2.17891860008 --11.846777916,0.406674921513,2.14251637459 --11.8817720413,0.408672243357,2.13033556938 --11.9087629318,0.409669280052,2.0959405899 --11.9547538757,0.41166511178,2.06555938721 --11.9777450562,0.412662267685,2.03016328812 --12.0277357101,0.414657592773,1.99978113174 --12.0567274094,0.415654152632,1.96539032459 --12.0927190781,0.417650192976,1.93200147152 --12.1197137833,0.418647557497,1.91681110859 --12.1597061157,0.419643193483,1.88443088531 --12.1916971207,0.421639233828,1.85004234314 --12.2416887283,0.42363384366,1.81765413284 --12.2786808014,0.425629347563,1.78427398205 --12.2986745834,0.425625890493,1.74687516689 --12.3376693726,0.427622109652,1.7336987257 --12.3686618805,0.42861777544,1.69831049442 --12.4006557465,0.430613160133,1.66191244125 --12.4596471786,0.432606518269,1.63053917885 --12.5816345215,0.438594937325,1.60718727112 --12.6176290512,0.440589696169,1.57180476189 --12.6446218491,0.44158500433,1.53441274166 --12.676618576,0.44258120656,1.51822555065 --12.7136125565,0.444575577974,1.48183739185 --12.7646045685,0.446568727493,1.44745981693 --12.8075990677,0.448562353849,1.41107165813 --12.8305940628,0.449557542801,1.37268126011 --12.8685884476,0.451551437378,1.33630096912 --12.9115829468,0.453544735909,1.29991936684 --12.93957901,0.454540759325,1.28172540665 --12.9695739746,0.4555349648,1.24333643913 --13.0335683823,0.458526194096,1.20896804333 --13.0435647964,0.459521889687,1.16756522655 --12.9405660629,0.453527659178,1.11612546444 --13.1495542526,0.464505523443,1.09481573105 --13.1915502548,0.46549808979,1.05643153191 --13.1995487213,0.466495513916,1.03623616695 --12.1505842209,0.413588821888,0.901376605034 --13.3065404892,0.471477985382,0.960477292538 --13.3255367279,0.472472250462,0.919080674648 --12.4485626221,0.427552223206,0.808302164078 --13.3885307312,0.474458158016,0.839312493801 --13.4235277176,0.476450592279,0.798925280571 --12.1295633316,0.411575704813,0.686155736446 --12.2355575562,0.416562348604,0.654802501202 --12.2205533981,0.415560811758,0.614389777184 --13.5825176239,0.484419494867,0.658590495586 --13.6635141373,0.487406671047,0.620228111744 --12.7125329971,0.4395006001,0.524401545525 --12.7985286713,0.444487988949,0.489044964314 --12.6155319214,0.43450525403,0.458755433559 --12.6155290604,0.434501677752,0.41936147213 --12.5735263824,0.432502478361,0.376936674118 --12.0925312042,0.408550977707,0.317319214344 --12.2795257568,0.417527318001,0.28600242734 --12.1175251007,0.409541785717,0.241529375315 --12.1205215454,0.409538149834,0.203129172325 --12.1215209961,0.409536391497,0.183929041028 --12.1105184555,0.408534228802,0.144516065717 --12.117515564,0.409529983997,0.10611627996 --12.1265125275,0.409525513649,0.067717730999 --12.1235103607,0.409522354603,0.0293162111193 --12.1175079346,0.409519553185,-0.00908653531224 --12.1185045242,0.409515857697,-0.0474872067571 --12.1225042343,0.40951359272,-0.0666861981153 --12.1185016632,0.409510433674,-0.105088748038 --12.1194992065,0.409506648779,-0.143489360809 --12.1334972382,0.409501105547,-0.182894229889 --12.109495163,0.408500343561,-0.221306860447 --12.1234931946,0.409494787455,-0.259700834751 --12.1154928207,0.408493876457,-0.278905510902 --12.0804891586,0.407494515181,-0.316316813231 --12.1064882278,0.408487230539,-0.355713486671 --12.1494865417,0.410477727652,-0.395097285509 --12.1014852524,0.408479958773,-0.43251979351 --12.1264839172,0.409472584724,-0.471913695335 --12.1134815216,0.409470289946,-0.509313762188 --12.1104812622,0.40846863389,-0.528516292572 --12.1194801331,0.409463196993,-0.567920744419 --12.1144781113,0.409459650517,-0.606325685978 --12.1114768982,0.409455806017,-0.644729077816 --12.1114759445,0.409451544285,-0.68312984705 --12.1184749603,0.409446269274,-0.721523761749 --12.1144742966,0.409442454576,-0.759927988052 --12.1214733124,0.409439176321,-0.780131697655 --12.1714744568,0.412427604198,-0.821511983871 --12.07447052,0.407436937094,-0.854960560799 --12.0974702835,0.409429132938,-0.89434748888 --12.0714683533,0.407428324223,-0.931766569614 --12.0674686432,0.407424420118,-0.9691619277 --12.53748703,0.431350022554,-1.04034662247 --11.9684638977,0.402432054281,-1.02082073689 --14.2365608215,0.517087161541,-1.22311985493 --14.1995630264,0.515085399151,-1.2655364275 --12.0774669647,0.408401578665,-1.14397382736 --11.9464607239,0.402416884899,-1.17143523693 --11.8964576721,0.400419831276,-1.20586693287 --11.8534555435,0.398421794176,-1.24029183388 --11.9494600296,0.403399527073,-1.30584526062 --11.9304590225,0.402397632599,-1.34225606918 --11.8494539261,0.39840567112,-1.37270069122 --11.9584608078,0.404383093119,-1.42205119133 --11.8974580765,0.401388019323,-1.45347797871 --11.9484605789,0.40437451005,-1.49786174297 --11.9724626541,0.405368059874,-1.51904404163 --14.3796234131,0.526962459087,-1.83124923706 --14.4456329346,0.529942989349,-1.88561999798 --14.5716466904,0.536913216114,-1.94695472717 --16.6938056946,0.644543111324,-2.25527977943 --16.5478057861,0.637556552887,-2.2907538414 --16.737827301,0.646512210369,-2.36905789375 --16.3838062286,0.629567801952,-2.34943699837 --16.2288036346,0.621583759785,-2.38091039658 --16.3918266296,0.630543708801,-2.45622944832 --16.3868350983,0.630533099174,-2.50863170624 --16.1458244324,0.618564784527,-2.52614831924 --16.369852066,0.630513131618,-2.6114320755 --16.3208580017,0.628510415554,-2.65685415268 --16.5458850861,0.639463543892,-2.71794033051 --16.3688793182,0.631483912468,-2.74443268776 --16.6269130707,0.644424557686,-2.83769154549 --14.6687383652,0.545776605606,-2.57510375977 --14.6547441483,0.545769512653,-2.62051105499 --14.7127571106,0.548748850822,-2.67787957191 --14.727763176,0.54974091053,-2.70507740974 --14.7677745819,0.55172342062,-2.75945138931 --14.7397794724,0.550718665123,-2.80286693573 --14.6097745895,0.544733583927,-2.82833957672 --14.4537649155,0.537753939629,-2.84782266617 --14.3477611542,0.532764852047,-2.87527632713 --14.6568031311,0.548694133759,-2.98051190376 --14.3117685318,0.531757354736,-2.93889427185 --14.959851265,0.564617991447,-3.1119556427 --14.9938640594,0.566600501537,-3.16733288765 --13.489695549,0.490893959999,-2.91552996635 --13.5147047043,0.492880016565,-2.96491575241 --13.5007095337,0.491873919964,-3.00632071495 --13.4917144775,0.491866588593,-3.04973196983 --13.4067077637,0.487879693508,-3.05397677422 --13.5117282867,0.493848860264,-3.12031579018 --14.2128257751,0.529692292213,-3.31834363937 --13.4827384949,0.492836356163,-3.20413756371 --13.4837465286,0.493826717138,-3.2495405674 --13.5127563477,0.495811104774,-3.30092453957 --13.5727729797,0.499788552523,-3.36029672623 --13.2097301483,0.480857849121,-3.31988787651 --13.1037187576,0.475876301527,-3.31714749336 --13.1147270203,0.476864814758,-3.36354160309 --13.1417379379,0.478849679232,-3.41392683983 --13.1667490005,0.480834782124,-3.46431517601 --12.9897298813,0.471864938736,-3.46481585503 --13.1827659607,0.482812255621,-3.55710935593 --13.1427640915,0.480816453695,-3.56933307648 --13.2137823105,0.484790831804,-3.63169240952 --13.1937885284,0.484785676003,-3.67110395432 --13.1167831421,0.480793625116,-3.69554805756 --13.2158079147,0.486760824919,-3.76689767838 --13.3418369293,0.493721395731,-3.84623122215 --13.3998556137,0.497697502375,-3.90760064125 --13.3508520126,0.495703905821,-3.91682744026 --13.362862587,0.496690571308,-3.96622562408 --13.3548707962,0.496682018042,-4.00963068008 --13.2798671722,0.493689507246,-4.03407526016 --13.2558717728,0.492684870958,-4.07248783112 --13.2858867645,0.49466702342,-4.12687206268 --13.2968988419,0.495653569698,-4.17627000809 --13.4109239578,0.50262016058,-4.23340892792 --13.4709453583,0.506594359875,-4.29777526855 --13.5099639893,0.5085734725,-4.35615301132 --13.5289773941,0.510557293892,-4.4095492363 --13.5239877701,0.510547399521,-4.45394420624 --13.5890111923,0.51451921463,-4.52231454849 --13.5690193176,0.514512598515,-4.56373023987 --13.7010507584,0.522472858429,-4.62985706329 --13.665055275,0.520470380783,-4.6652712822 --16.4766387939,0.669728219509,-5.63708782196 --16.7097053528,0.682650625706,-5.77235460281 --16.63971138,0.679651856422,-5.80779361725 --16.6277275085,0.679637908936,-5.86219787598 --16.6647548676,0.682610869408,-5.93357467651 --16.9088172913,0.696537137032,-6.04663181305 --16.916841507,0.697516918182,-6.11002969742 --17.4169712067,0.725363910198,-6.34513711929 --17.3259716034,0.721369862556,-6.37458515167 --17.6320648193,0.738266944885,-6.54681110382 --17.6460914612,0.740243792534,-6.61419677734 --17.6561183929,0.742221176624,-6.68159198761 --19.9446563721,0.864575266838,-7.55346155167 --17.6081428528,0.741204798222,-6.75921773911 --20.0287380219,0.871504068375,-7.72820281982 --19.954750061,0.868500769138,-7.77264213562 --17.2161197662,0.723256528378,-6.7996339798 --17.2471523285,0.726228117943,-6.87401437759 --17.2901859283,0.729195952415,-6.95338630676 --17.5382595062,0.743114352226,-7.08143806458 --17.4712677002,0.741113126278,-7.11988019943 --19.9499206543,0.87536752224,-8.16981983185 --20.5501079559,0.909165918827,-8.48386096954 --20.2220554352,0.892236948013,-8.42644882202 --20.1000576019,0.887247622013,-8.45091629028 --20.3361530304,0.901151359081,-8.62216949463 --20.3581752777,0.903131484985,-8.66935634613 --20.5202522278,0.913056433201,-8.81164932251 --18.4277229309,0.801665723324,-8.00629425049 --18.4807662964,0.805626273155,-8.0976600647 --18.9969367981,0.83544421196,-8.38774681091 --21.0455417633,0.947785496712,-9.3459186554 --18.6589069366,0.81950032711,-8.3827419281 --18.7229404449,0.823468267918,-8.44590091705 --18.6989650726,0.823451340199,-8.50631427765 --18.8020267487,0.830394387245,-8.62264633179 --18.6960277557,0.826403319836,-8.64610671997 --18.7530765533,0.831360220909,-8.74347019196 --18.4410152435,0.815435647964,-8.67205429077 --18.48204422,0.818410158157,-8.72622776031 --18.2980213165,0.809445083141,-8.71173477173 --18.9442501068,0.846209764481,-9.08374214172 --18.6561965942,0.832278311253,-9.0213136673 --18.5471973419,0.827288687229,-9.0417766571 --18.6202526093,0.833238780499,-9.14913272858 --18.6452941895,0.836205005646,-9.23250770569 --18.6953277588,0.840175032616,-9.29367828369 --22.0764484406,1.02901041508,-11.0160017014 --20.895111084,0.965377449989,-10.5221242905 --18.7024345398,0.845093667507,-9.51686382294 --18.7234783173,0.84805971384,-9.60124969482 --20.8812332153,0.970289170742,-10.7623186111 --20.7002162933,0.961320698261,-10.752822876 --20.7002372742,0.962305128574,-10.7940206528 --20.7963123322,0.969240486622,-10.9253540039 --20.9514083862,0.980154335499,-11.0886526108 --20.7613868713,0.971189498901,-11.0731630325 --21.0575351715,0.990051805973,-11.3133792877 --36.6230888367,1.87045145035,-19.6390323639 --23.8776321411,1.15297162533,-12.9884080887 --25.1731243134,1.2274851799,-13.7297897339 --38.5090065002,1.98560452461,-21.0277957916 --23.7367210388,1.15092539787,-13.1544761658 --25.0662651062,1.22939860821,-13.9790287018 --38.1281776428,1.9755358696,-21.2891712189 --37.4890403748,1.94270312786,-21.0909538269 --38.4855232239,2.00326228142,-21.8037014008 --37.0200195312,1.92177522182,-21.0598201752 --35.113483429,1.81935954094,-20.2807941437 --35.0085411072,1.81733441353,-20.3672447205 --34.886592865,1.81331586838,-20.4437046051 --34.762638092,1.81029832363,-20.518163681 --34.6456871033,1.80727815628,-20.5966205597 --34.5677070618,1.80427575111,-20.6238613129 --34.4517555237,1.80125522614,-20.7023200989 --34.3458137512,1.79923129082,-20.7857704163 --34.2308616638,1.79621100426,-20.8632240295 --34.2539710999,1.80113577843,-21.0245914459 --34.3871269226,1.81201612949,-21.2538890839 --34.5082778931,1.82290053368,-21.477191925 --34.6073684692,1.83082675934,-21.6133213043 --36.4482574463,1.9430128336,-22.9085121155 --36.1862602234,1.93204689026,-22.9040622711 --35.8832359314,1.91809856892,-22.8716392517 --35.7612876892,1.91507613659,-22.9531021118 --35.5773200989,1.9080799818,-22.9936027527 --35.4473686218,1.90506219864,-23.0670661926 --35.6545181274,1.91893935204,-23.280122757 --35.1654090881,1.89407122135,-23.1218242645 --34.7673339844,1.8751667738,-23.0194683075 --32.785533905,1.76093626022,-21.8701477051 --32.6665840149,1.75791919231,-21.9396114349 --32.5346260071,1.75390803814,-22.000082016 --32.4166717529,1.75089132786,-22.0685424805 --32.3166770935,1.74690032005,-22.0758018494 --32.1947212219,1.74388551712,-22.1412677765 --32.2018280029,1.74781417847,-22.2946472168 --32.2819671631,1.75771033764,-22.4989776611 --34.6862487793,1.90757644176,-24.3167724609 --34.4322395325,1.89661407471,-24.301322937 --34.8475036621,1.92339134216,-24.6722373962 --34.4984436035,1.90747141838,-24.5898513794 --34.413520813,1.90643310547,-24.6932926178 --34.2655639648,1.90242385864,-24.7507743835 --34.2436676025,1.90535736084,-24.8981704712 --33.6354751587,1.87255930901,-24.6219596863 --33.661605835,1.87947106361,-24.8033275604 --33.7166938782,1.88540756702,-24.9244823456 --33.8598823547,1.89826416969,-25.1927680969 --33.6178779602,1.88829958439,-25.178314209 --33.0687065125,1.85948050022,-24.9330673218 --32.6105766296,1.8356205225,-24.7517623901 --32.6166954041,1.84054172039,-24.9171409607 --33.3191986084,1.889128685,-25.6140537262 --32.8319892883,1.86132347584,-25.3245754242 --33.0592384338,1.88013625145,-25.6628036499 --32.6331214905,1.85826385021,-25.4994773865 --32.8613739014,1.87807428837,-25.8417072296 --32.8294754028,1.88101065159,-25.9831142426 --34.0382881165,1.96233463287,-27.1026744843 --32.6326141357,1.87894821167,-26.1620178223 --32.5406188965,1.87495350838,-26.1732730865 --32.6948356628,1.89079654217,-26.463552475 --32.5778961182,1.88777399063,-26.5390167236 --32.4199295044,1.88277232647,-26.5805091858 --32.2939796448,1.88075506687,-26.6469802856 --32.1980514526,1.87972223759,-26.7384319305 --32.0861091614,1.87769782543,-26.8158950806 --32.064163208,1.87866795063,-26.883102417 --32.4385185242,1.90839099884,-27.367231369 --32.0984420776,1.89148449898,-27.2548503876 --31.6823139191,1.87061917782,-27.0755233765 --31.4312877655,1.85966861248,-27.0330810547 --31.4924564362,1.8685529232,-27.2574272156 --31.7717647552,1.89232027531,-27.6706199646 --31.7077903748,1.89131188393,-27.7028579712 --31.6729011536,1.89424562454,-27.8472690582 --31.019613266,1.85751366615,-27.4501056671 --30.603477478,1.83565557003,-27.2567825317 --30.7917308807,1.85346925259,-27.5950374603 --30.4856624603,1.8385528326,-27.495639801 --30.2136135101,1.82661831379,-27.4252185822 --30.1356277466,1.82361984253,-27.4404659271 --28.1133975983,1.69366419315,-25.778263092 --28.0214576721,1.69263708591,-25.8567199707 --27.9165115356,1.69061768055,-25.9221801758 --27.8225708008,1.68959212303,-25.997636795 --27.7586517334,1.69154894352,-26.1020736694 --27.6497001648,1.68953180313,-26.1635417938 --27.5887203217,1.68752717972,-26.1877765656 --27.4977817535,1.68750011921,-26.2652320862 --27.4098472595,1.6864708662,-26.3466835022 --27.3139038086,1.68544661999,-26.4191417694 --27.2489871979,1.68640422821,-26.5215759277 --27.1460399628,1.68538367748,-26.5880413055 --27.0531005859,1.68435716629,-26.6644992828 --26.9931221008,1.68335235119,-26.6887378693 --26.8981800079,1.68232786655,-26.7611942291 --26.8102455139,1.68229854107,-26.8416481018 --26.7243118286,1.68226861954,-26.9230976105 --24.0023727417,1.49584770203,-24.3624286652 --23.7623062134,1.48392140865,-24.2719917297 --23.6312637329,1.47796559334,-24.2142810822 --23.5323047638,1.47595334053,-24.2647438049 --23.4553604126,1.47592759132,-24.3371944427 --23.0486907959,1.47677397728,-24.7546577454 --20.3916759491,1.33776164055,-23.4207324982 --20.2246456146,1.33080399036,-23.3782520294 --20.2837543488,1.3377276659,-23.5184059143 --18.8739318848,1.25242841244,-22.4630298615 --18.5897827148,1.2355607748,-22.2696361542 --18.320640564,1.22068476677,-22.0892295837 --17.6743011475,1.18298196793,-21.659702301 --17.5893287659,1.18197691441,-21.6941661835 --17.4723243713,1.17799520493,-21.6896533966 --17.521478653,1.18689227104,-21.887014389 --17.4505214691,1.186876297,-21.9394683838 --17.4165420532,1.18686771393,-21.9666938782 --17.3646011353,1.18783783913,-22.042131424 --17.2846317291,1.18682956696,-22.0815887451 --17.216676712,1.18681120872,-22.1380443573 --17.1667385101,1.18877995014,-22.2154788971 --17.097782135,1.18876266479,-22.2699298859 --17.0478439331,1.18973100185,-22.348367691 --17.0188713074,1.19071805477,-22.3825893402 --16.96393013,1.19168937206,-22.4560337067 --16.9129924774,1.19265806675,-22.5334701538 --16.856048584,1.19463121891,-22.6039142609 --16.7940998077,1.19460785389,-22.6683597565 --16.7361564636,1.19558131695,-22.7378044128 --16.8863792419,1.21142411232,-23.0138950348 --15.207780838,1.08263766766,-21.0279502869 --15.0298032761,1.07864820957,-21.058889389 --14.9748516083,1.07862651348,-21.1193294525 --14.9128923416,1.0796097517,-21.1717796326 --14.8569412231,1.08058774471,-21.2332267761 --14.9821414948,1.09344792366,-21.4803352356 --14.7720136642,1.08155524731,-21.3238983154 --16.1398468018,1.21224379539,-23.5786705017 --11.8519048691,0.842862308025,-17.5122947693 --11.6938066483,0.833943784237,-17.397819519 --11.4786844254,0.82204836607,-17.2555923462 --11.3966732025,0.819065570831,-17.2490596771 --11.3376913071,0.819062590599,-17.2765083313 --11.2807130814,0.818057358265,-17.3079605103 --11.236746788,0.819041728973,-17.3563938141 --11.1797676086,0.819036483765,-17.3878479004 --11.1597881317,0.819026827812,-17.4150619507 --11.0787782669,0.817043960094,-17.408531189 --11.0558433533,0.820007383823,-17.4929599762 --11.0088748932,0.819994091988,-17.5373973846 --10.9559011459,0.819985151291,-17.5748443604 --10.5471830368,0.825870275497,-17.9576129913 --10.6533823013,0.838734388351,-18.1987361908 --10.0225782394,0.834704756737,-18.4805030823 --9.97060871124,0.835693776608,-18.52094841 --9.9556427002,0.836676001549,-18.562166214 --9.9717798233,0.844590961933,-18.728559494 --16.4891872406,1.53439128399,-30.986907959 --14.2568368912,1.30872952938,-27.0370540619 --14.1438331604,1.30574917793,-27.0275478363 --14.0779047012,1.30771720409,-27.106004715 --13.9638986588,1.30473852158,-27.0935001373 --13.8668308258,1.2987947464,-27.0097789764 --13.8329563141,1.30372571945,-27.1512126923 --13.6297988892,1.29085087776,-26.9617767334 --13.4637022018,1.28193449974,-26.8433151245 --13.3026103973,1.27301442623,-26.7308444977 --13.3608932495,1.28883779049,-27.0552062988 --19.1140518188,1.94091975689,-38.8650856018 --19.161272049,1.95378196239,-39.1132507324 --13.4547262192,1.33333134651,-28.0015602112 --13.3026504517,1.3254005909,-27.907081604 --13.2617759705,1.33033299446,-28.0465240479 --13.2269144058,1.33725762367,-28.1989593506 --5.50695800781,0.44872328639,-12.0775671005 --18.2998905182,1.95956623554,-39.6789627075 --18.1368846893,1.95559680462,-39.6534957886 --17.9227790833,1.94469499588,-39.5120697021 --17.8930244446,1.95555782318,-39.7724990845 --18.3512191772,2.02578163147,-41.1245384216 --17.8004608154,1.97431874275,-40.2333831787 --17.6433086395,1.96343410015,-40.0497131348 --17.3851089478,1.94659411907,-39.8023223877 --17.3914375305,1.96240282059,-40.1557235718 --13.0953035355,1.45287954807,-30.8409557343 --16.4755191803,1.894094944,-39.0506744385 --17.2172145844,1.99598097801,-40.9692840576 --16.9499893188,1.97815811634,-40.692905426 --16.7499008179,1.96924495697,-40.5704727173 --16.6600418091,1.97317886353,-40.7099494934 --16.5511455536,1.97613739967,-40.8074455261 --16.7268714905,2.0156853199,-41.607711792 --16.514755249,2.00479054451,-41.4542922974 --16.5590305328,2.01962375641,-41.7534599304 --9.51583576202,1.09767413139,-24.5778961182 --9.41781520844,1.09470236301,-24.5523853302 --9.32681083679,1.09272062778,-24.5438709259 --9.24282264709,1.09172785282,-24.5543518066 --9.16484355927,1.09172844887,-24.5758209229 --9.13387489319,1.09271526337,-24.6100521088 --8.25999450684,0.978958249092,-22.4991569519 --9.0320558548,1.09962773323,-24.8059577942 --7.35434484482,0.877071559429,-20.6541118622 --7.25226831436,0.872132897377,-20.5706062317 --7.28854084015,0.886968016624,-20.8759937286 --7.46107196808,0.917630016804,-21.4680652618 --7.07226228714,0.86816650629,-20.5677814484 --7.05540180206,0.875088274479,-20.7242069244 --7.06561565399,0.886961817741,-20.9636135101 --7.01266670227,0.888941287994,-21.021068573 --6.71506118774,0.852343261242,-20.3517208099 --6.57185840607,0.839485168457,-20.1292438507 --6.53785991669,0.839490234852,-20.1314792633 --6.48490095139,0.840475320816,-20.1789321899 --6.69468307495,0.884985744953,-21.0441894531 --6.39302778244,0.846417248249,-20.3228359222 --6.33706521988,0.847404897213,-20.3662967682 --6.26304960251,0.845426619053,-20.3507709503 --6.50395822525,0.896858930588,-21.3509960175 --6.46394729614,0.894872248173,-21.3392353058 --6.38793468475,0.893892467022,-21.3267116547 --6.31994628906,0.892897546291,-21.3401794434 --6.32518053055,0.905761063099,-21.5975894928 --6.28427934647,0.909711182117,-21.7060375214 --6.24237680435,0.91466242075,-21.8124866486 --6.21039056778,0.914660096169,-21.8277187347 --6.25777673721,0.935428917408,-22.2490997314 --6.1988286972,0.937409341335,-22.3055648804 --5.98160219193,0.922578573227,-22.0585708618 --5.90759992599,0.92159307003,-22.0560455322 --5.85868120193,0.925554871559,-22.1444988251 --5.76862478256,0.920603573322,-22.082988739 --5.74567222595,0.923580408096,-22.1342144012 --5.73890733719,0.935446381569,-22.3886375427 --5.67193222046,0.935444176197,-22.4151058197 --5.59793329239,0.934457063675,-22.4155826569 --5.55002737045,0.939411520958,-22.517036438 --5.47101163864,0.937434911728,-22.4995212555 --5.4410367012,0.938426196575,-22.5257511139 --5.41923761368,0.948315024376,-22.7411880493 --5.34523916245,0.947327375412,-22.7426643372 --5.28328704834,0.949311375618,-22.7931289673 --5.32375001907,0.973038673401,-23.2885169983 --5.20890474319,0.979971349239,-23.4514446259 --5.17593002319,0.980963051319,-23.4776859283 --5.13608360291,0.987882614136,-23.6401348114 --5.0791721344,0.991842806339,-23.7325992584 --5.01322221756,0.993826627731,-23.784072876 --4.94124698639,0.99482601881,-23.8085517883 --4.76881313324,0.970106422901,-23.3451004028 --4.66267347336,0.962206125259,-23.1956062317 --4.59854698181,0.95429033041,-23.0608615875 --4.52354669571,0.954304754734,-23.059343338 --4.47165489197,0.95925283432,-23.1728076935 --4.41675281525,0.963207423687,-23.2752723694 --4.3638625145,0.968155026436,-23.3897342682 --4.37731027603,0.99189722538,-23.8611450195 --4.31136465073,0.993878960609,-23.9166183472 --4.27537679672,0.993878722191,-23.928855896 --4.18832349777,0.989926040173,-23.8703460693 --4.12338638306,0.992902636528,-23.9348201752 --4.7281627655,1.19163632393,-27.9017906189 --4.64520740509,1.19262754917,-27.9422836304 --4.57129669189,1.19659149647,-28.0297622681 --4.5315952301,1.21142995358,-28.3362197876 --4.59423828125,1.24505221844,-29.0063858032 --4.47005271912,1.23418259621,-28.8049087524 --4.38107442856,1.23418819904,-28.820400238 --4.31524276733,1.24210596085,-28.9888763428 --4.24942398071,1.25001657009,-29.1703567505 --3.97018456459,1.18477582932,-27.8719902039 --2.19889378548,0.594534754753,-16.1168670654 --2.13882470131,0.590585172176,-16.0513381958 --2.0716958046,0.583670914173,-15.9238100052 --1.97030115128,0.563914418221,-15.5202960968 --1.9263279438,0.564907312393,-15.5547513962 --1.87933719158,0.564910709858,-15.5712137222 --1.83839309216,0.567886590958,-15.6356697083 --1.82547748089,0.57284116745,-15.7258863449 --1.78252100945,0.5748244524,-15.7773418427 --1.73654139042,0.575821518898,-15.8047990799 --1.6945950985,0.578799068928,-15.8662519455 --1.64962923527,0.580788195133,-15.9077100754 --1.60265171528,0.581784367561,-15.9371747971 --1.58168101311,0.582771778107,-15.9703998566 --1.5346968174,0.583771705627,-15.9928560257 --4.4309797287,2.13205623627,-47.0444946289 --4.29109334946,2.13602304459,-47.1350440979 --4.12896251678,2.12713217735,-46.975605011 --3.98098039627,2.12615466118,-46.9681587219 --3.84210371971,2.13011574745,-47.0687065125 --3.65675425529,2.06091713905,-45.6790504456 --3.53403782845,2.07378458977,-45.9435882568 --3.36979103088,2.05895996094,-45.6681480408 --3.23188328743,2.06193876266,-45.7376937866 --3.08181333542,2.05701136589,-45.642250061 --2.92665457726,2.04713535309,-45.4568138123 --2.79686975479,2.05604314804,-45.6513557434 --2.71674108505,2.04913377762,-45.5086326599 --2.56866455078,2.04420995712,-45.4071884155 --2.4205698967,2.03729629517,-45.2877426147 --2.15348887444,1.98096501827,-44.1605873108 --2.00425291061,1.96713137627,-43.9001350403 --1.83862280846,1.93452346325,-43.24269104 --1.76755356789,1.93057858944,-43.1619682312 --1.63358223438,1.93059265614,-43.1695137024 --1.50064086914,1.93258976936,-43.2070579529 --1.36565470695,1.93161261082,-43.1996040344 --1.22444736958,1.9197614193,-42.9701499939 --1.09148311615,1.92077159882,-42.9846954346 --0.956443607807,1.91682469845,-42.9242362976 --0.884230792522,1.90596091747,-42.7005119324 --0.752300143242,1.90795218945,-42.7490577698 --0.62036973238,1.91094338894,-42.7975997925 --0.4852026999,1.90106832981,-42.6101417542 --0.347634375095,1.87241971493,-42.0226783752 --0.219210326672,1.89912557602,-42.5762367249 --0.0871975496411,1.89816331863,-42.5427780151 -0.0211444348097,1.92177772522,-41.6448936462 -0.151827812195,1.9065656662,-41.351184845 -0.2828091681,1.90752100945,-41.3534698486 -0.415924340487,1.91355121136,-41.4897499084 -0.545778095722,1.90743541718,-41.3650398254 -0.675681352615,1.90434730053,-41.2893295288 -0.739599883556,1.90028488636,-41.2184753418 -0.859048426151,1.87294399738,-40.687789917 -0.992204964161,1.8819975853,-40.8650665283 -1.12011682987,1.8789151907,-40.7973594666 -1.24081063271,1.86471188068,-40.5106658936 -1.36977875233,1.8646607399,-40.4989547729 -1.47824883461,1.83833479881,-39.9862747192 -1.54121315479,1.83729875088,-39.9604263306 -1.67229497433,1.84231126308,-40.0627098083 -1.79721701145,1.84023535252,-40.0040092468 -1.90889132023,1.82402384281,-39.6953201294 -2.02568817139,1.81487977505,-39.5096282959 -2.12620949745,1.79158484936,-39.0449638367 -2.24814844131,1.78951954842,-39.0022583008 -2.30200600624,1.78342580795,-38.8674201965 -2.43107581139,1.78843224049,-38.9567070007 -2.54389190674,1.7803003788,-38.7890205383 -2.66177892685,1.7752071619,-38.6933288574 -2.78881168365,1.77819371223,-38.7456169128 -2.91685175896,1.78218400478,-38.8049125671 -3.02564382553,1.77203989029,-38.6122283936 -3.06031250954,1.75584459305,-38.2834129333 -3.18228507042,1.75579857826,-38.2737121582 -3.30224204063,1.75474429131,-38.2480125427 -3.39996123314,1.74156200886,-37.9793434143 -3.51789784431,1.73949706554,-37.9326515198 -3.64291882515,1.74247777462,-37.9719429016 -2.11976623535,0.898760557175,-21.4172115326 -2.16284584999,0.903794229031,-21.4993782043 -2.24394798279,0.908830940723,-21.6057186127 -4.02243804932,1.7221133709,-37.541053772 -4.11013269424,1.70791983604,-37.2443962097 -4.24221897125,1.71393585205,-37.3506889343 -4.35312700272,1.7108566761,-37.2729988098 -4.42219018936,1.71487545967,-37.3471450806 -4.49177598953,1.69462513924,-36.936504364 -4.58959341049,1.68649852276,-36.7648353577 -4.70455121994,1.6854467392,-36.7381439209 -4.79935884476,1.67731523514,-36.555480957 -4.91734075546,1.67727649212,-36.5537872314 -5.01719760895,1.6711717844,-36.4221153259 -3.26917695999,0.980263352394,-22.8997135162 -3.33209300041,0.976200222969,-22.8150787354 -5.27816534042,1.6215275526,-35.4043617249 -5.40925168991,1.6285443306,-35.5096511841 -5.60472679138,1.65576469898,-36.0218772888 -5.73982286453,1.66178679466,-36.1391677856 -5.75857257843,1.64964139462,-35.8853645325 -5.8665060997,1.64757800102,-35.8316841125 -5.97343397141,1.64551174641,-35.7720069885 -6.18998098373,1.6767680645,-36.3622093201 -4.21500682831,1.03249704838,-23.8001918793 -4.30204916,1.03549969196,-23.8485298157 -4.35914373398,1.04053902626,-23.9496803284 -4.45623350143,1.04656600952,-24.0480079651 -6.78660106659,1.6664134264,-36.0539703369 -6.87543725967,1.6593003273,-35.8973121643 -6.98336982727,1.65723729134,-35.8426361084 -7.10939073563,1.66021931171,-35.8809394836 -7.17010736465,1.64704561234,-35.5963096619 -7.26526832581,1.65711414814,-35.775428772 -7.38526058197,1.65808188915,-35.7837409973 -7.49118947983,1.65601706505,-35.7240638733 -7.51375198364,1.63476574421,-35.274471283 -7.7693400383,1.66903722286,-35.91664505 -7.89937162399,1.67302501202,-35.9669418335 -5.5107665062,1.08661329746,-24.6618347168 -5.53971242905,1.08457577229,-24.6060199738 -5.61768865585,1.08454406261,-24.5853691101 -5.76595211029,1.09965753555,-24.8716468811 -8.31179523468,1.64960598946,-35.4234771729 -8.43278598785,1.6515737772,-35.4307899475 -6.28681755066,1.15302276611,-25.817615509 -6.36778831482,1.15198755264,-25.7919635773 -6.99379730225,1.26697349548,-27.9607620239 -7.07674837112,1.2649269104,-27.9161071777 -7.1516699791,1.26286542416,-27.8394622803 -7.23060846329,1.26081264019,-27.7808113098 -7.31757259369,1.25977265835,-27.7501564026 -7.40069580078,1.26782298088,-27.8872871399 -7.53582811356,1.276866436,-28.0385818481 -7.69804763794,1.29095292091,-28.2848510742 -9.38740253448,1.59758067131,-34.1066017151 -9.52245140076,1.60257768631,-34.1739006042 -9.60432338715,1.59748744965,-34.0492553711 -9.68619823456,1.59339904785,-33.9276046753 -9.68500137329,1.58228850365,-33.7198219299 -8.7245721817,1.38757812977,-29.9942016602 -8.80649375916,1.38551557064,-29.9185562134 -8.89142799377,1.38345956802,-29.8569030762 -8.97235107422,1.38139855862,-29.7832527161 -9.05628299713,1.37934160233,-29.7186050415 -9.13921451569,1.37728500366,-29.6539516449 -9.17616844177,1.37525093555,-29.6081295013 -9.25508785248,1.37318813801,-29.5294857025 -9.33802127838,1.3711322546,-29.4658355713 -9.42195701599,1.36907792091,-29.4051856995 -9.49185657501,1.36500573158,-29.3035488129 -9.57880115509,1.36395609379,-29.2528972626 -9.6637430191,1.36290478706,-29.1982460022 -9.73379230499,1.36691713333,-29.257390976 -10.5356760025,1.47979807854,-31.3510513306 -10.6837644577,1.48781573772,-31.4613437653 -10.8118000031,1.49180734158,-31.5116500854 -10.8937082291,1.48873889446,-31.4230098724 -11.0458040237,1.49675917625,-31.5402927399 -11.1148309708,1.49975991249,-31.5774440765 -11.2759428024,1.50878763199,-31.7137260437 -11.3829183578,1.50975072384,-31.6980514526 -11.531996727,1.51776254177,-31.7973423004 -11.6529989243,1.51973855495,-31.8136672974 -11.8742513657,1.53783249855,-32.1078834534 -11.9852275848,1.53879523277,-32.0932159424 -12.0803089142,1.54482126236,-32.1923408508 -12.2283744812,1.55182611942,-32.277633667 -12.3744325638,1.55782771111,-32.3559303284 -12.5415363312,1.5668503046,-32.485206604 -12.7136459351,1.57687568665,-32.6224784851 -12.9017906189,1.58891689777,-32.7987365723 -13.070889473,1.59693682194,-32.9240112305 -13.1769857407,1.60496819019,-33.0391311646 -13.3069915771,1.60794472694,-33.0604476929 -13.4299840927,1.6109149456,-33.0657653809 -13.5279188156,1.60985791683,-33.0051078796 -13.6238508224,1.60880029202,-32.9424514771 -13.7358179092,1.60975837708,-32.9177818298 -13.8357572556,1.60870456696,-32.8641242981 -13.8897352219,1.60868132114,-32.8462944031 -14.0057096481,1.61064302921,-32.830619812 -14.1126661301,1.61059653759,-32.7939529419 -14.2106018066,1.60954117775,-32.7353019714 -14.3225679398,1.61049902439,-32.7096328735 -14.4215068817,1.61044466496,-32.6529769897 -14.512430191,1.60838377476,-32.5793266296 -14.5874500275,1.61137986183,-32.6094741821 -14.6974115372,1.61233568192,-32.5778121948 -14.793343544,1.61127877235,-32.5141601562 -14.8902807236,1.61022436619,-32.4555053711 -15.0062541962,1.61218607426,-32.4378318787 -15.1182174683,1.61314308643,-32.4091682434 -15.2702550888,1.61813366413,-32.466468811 -15.3322496414,1.62011826038,-32.4666290283 -15.5524101257,1.63416337967,-32.6658630371 -15.8096351624,1.65123701096,-32.9400672913 -16.0798797607,1.67131853104,-33.2362556458 -16.2589530945,1.67932391167,-33.3365364075 -16.4410324097,1.68833124638,-33.4418106079 -16.5380821228,1.69333922863,-33.5059394836 -16.6780834198,1.69731330872,-33.5242500305 -16.8180828094,1.70128548145,-33.5385627747 -16.9560813904,1.70425677299,-33.5498733521 -17.0820560455,1.70621860027,-33.5361938477 -17.1930046082,1.7071685791,-33.4915351868 -17.3189792633,1.70912921429,-33.474861145 -17.3739528656,1.7091037035,-33.4510307312 -17.4828987122,1.70905256271,-33.4023704529 -17.5908432007,1.71000123024,-33.3527107239 -17.6917743683,1.70894396305,-33.2870597839 -17.7957134247,1.70889043808,-33.2304039001 -17.8976478577,1.70883440971,-33.1677513123 -17.9845600128,1.70676887035,-33.0781135559 -18.0405349731,1.70674395561,-33.0552825928 -18.1464748383,1.70669138432,-33.000629425 -18.2634353638,1.70764660835,-32.966960907 -18.38139534,1.70960211754,-32.9342956543 -18.5063648224,1.71156156063,-32.9126243591 -18.6513671875,1.71553444862,-32.9279327393 -18.7152423859,1.71145451069,-32.7963180542 -18.6941051483,1.70438218117,-32.6385536194 -18.9252319336,1.71640849113,-32.8037910461 -19.0341777802,1.71735787392,-32.7531356812 -18.9228038788,1.6951738596,-32.3226661682 -18.8715229034,1.68002915382,-32.0011520386 -18.9464244843,1.67696022987,-31.895526886 -18.9292984009,1.67089486122,-31.7527561188 -18.9781646729,1.66581237316,-31.6061534882 -19.0040035248,1.65871810913,-31.4235687256 -19.0618839264,1.65364217758,-31.2939567566 -19.1007404327,1.64855670929,-31.1353607178 -19.1395988464,1.64247143269,-30.9767665863 -19.121383667,1.63135612011,-30.728219986 -19.0702190399,1.62127566338,-30.5364818573 -19.1200962067,1.61720001698,-30.4018783569 -19.1419410706,1.61011016369,-30.2242927551 -19.1778011322,1.60402739048,-30.0677051544 -19.2106609344,1.5979449749,-29.9101142883 -19.2685565948,1.59487640858,-29.7925014496 -19.3144340515,1.58980190754,-29.6568984985 -19.299325943,1.58374464512,-29.5291347504 -19.3171730042,1.57665777206,-29.353553772 -19.3700656891,1.57358884811,-29.2319469452 -19.4149475098,1.56851661205,-29.0993442535 -19.4848613739,1.56645655632,-29.0037250519 -19.532749176,1.56238722801,-28.8781204224 -19.6126785278,1.56133270264,-28.7984924316 -19.5785522461,1.55427098274,-28.6507377625 -19.5663700104,1.54517388344,-28.4371871948 -19.6753368378,1.54713559151,-28.4045314789 -19.6831798553,1.53904938698,-28.2229633331 -19.7631130219,1.53899800777,-28.1483325958 -19.8650684357,1.53995597363,-28.1036872864 -19.9060344696,1.5389302969,-28.0668716431 -19.9889717102,1.53888046741,-27.9962406158 -20.0849227905,1.53883624077,-27.9435977936 -20.1828746796,1.5397926569,-27.89295578 -20.261806488,1.53874158859,-27.8173274994 -20.3627624512,1.53969991207,-27.7716808319 -20.474729538,1.54166245461,-27.740026474 -20.5437278748,1.54464936256,-27.7421875 -20.8616104126,1.5485291481,-27.6202411652 -20.9685707092,1.55048942566,-27.5805931091 -21.0595188141,1.55044364929,-27.5199546814 -21.1544647217,1.55139899254,-27.4633178711 -21.2304706573,1.55338788033,-27.4724750519 -21.3214130402,1.55434191227,-27.4108390808 -21.4013462067,1.55329179764,-27.3352127075 -21.5673694611,1.56027472019,-27.370513916 -21.6793327332,1.56223618984,-27.333864212 -21.7712783813,1.56219041348,-27.272228241 -21.8982601166,1.56515836716,-27.2565612793 -21.9822673798,1.56814861298,-27.2717170715 -22.1062450409,1.57111465931,-27.2500553131 -22.2432346344,1.57508444786,-27.2423839569 -22.3592014313,1.57804775238,-27.2107257843 -22.5652542114,1.58704066277,-27.2850055695 -22.7542915344,1.59502804279,-27.3392906189 -22.5959968567,1.57589650154,-26.9728565216 -22.9212341309,1.5979681015,-27.2768154144 -23.1142692566,1.60695517063,-27.3321018219 -23.3043041229,1.61494076252,-27.3823871613 -23.5273647308,1.62493622303,-27.4696502686 -23.8124828339,1.64095103741,-27.6278648376 -23.9644775391,1.64492201805,-27.6281833649 -23.4478683472,1.59868228436,-26.8550357819 -23.5327339172,1.59559643269,-26.6946315765 -23.658706665,1.59856128693,-26.6679725647 -23.532459259,1.5824495554,-26.355512619 -23.5603466034,1.5783854723,-26.2189311981 -23.3770542145,1.55825948715,-25.8475170135 -23.3559684753,1.55321800709,-25.7417526245 -23.4879512787,1.55718660355,-25.7250881195 -23.5118408203,1.55312347412,-25.5875110626 -23.5057067871,1.54605233669,-25.4179573059 -23.5025749207,1.53998291492,-25.2533988953 -23.5214633942,1.53492033482,-25.1138248444 -23.5493602753,1.53086090088,-24.9852409363 -23.5302829742,1.52682220936,-24.885477066 -23.5361614227,1.52175700665,-24.7329158783 -23.5650615692,1.51769912243,-24.6073322296 -23.5759468079,1.51263678074,-24.46276474 -23.5938396454,1.50857686996,-24.3271903992 -23.6547679901,1.50752806664,-24.235584259 -23.6396350861,1.5004607439,-24.0670375824 -23.6135559082,1.4954226017,-23.9642753601 -23.6324520111,1.49136507511,-23.832698822 -23.639339447,1.48630428314,-23.6881370544 -23.6342201233,1.48124158382,-23.53358078 -23.6240978241,1.47517836094,-23.3750267029 -23.590959549,1.46711015701,-23.1944923401 -23.5268535614,1.46006524563,-23.0577602386 -23.5247421265,1.45500528812,-22.909204483 -23.5076179504,1.44794273376,-22.7476577759 -23.5155124664,1.44388616085,-22.6110916138 -23.508398056,1.4378272295,-22.4615364075 -23.5172958374,1.43377161026,-22.3269710541 -23.5281982422,1.42971801758,-22.1973991394 -23.5121307373,1.42568600178,-22.1106357574 -23.5150279999,1.42163109779,-21.9740695953 -23.5049152374,1.41557371616,-21.8255176544 -23.4327602386,1.40550363064,-21.61901474 -23.3506031036,1.39543306828,-21.4065132141 -23.2674446106,1.38536286354,-21.1940155029 -22.7810115814,1.34721291065,-20.613822937 -22.7389335632,1.34217882156,-20.5090751648 -22.398607254,1.31406152248,-20.0697727203 -22.1943759918,1.29597306252,-19.7583618164 -21.8030261993,1.26585030556,-19.2820911407 -21.2415657043,1.22369778156,-18.658952713 -20.9372806549,1.1985963583,-18.2706184387 -20.7060470581,1.17951011658,-17.9502277374 -20.5939350128,1.17046844959,-17.7945289612 -18.3153896332,1.01401782036,-15.6966590881 -18.1422100067,0.998951137066,-15.4462213516 -17.8839797974,0.978870689869,-15.1248464584 -17.5406990051,0.952777445316,-14.7345333099 -17.4675884247,0.944731652737,-14.5770225525 -13.084815979,0.652967333794,-10.7866649628 -12.8686618805,0.637920260429,-10.5690412521 -16.8880805969,0.899555981159,-13.8595266342 -8.19972896576,0.326115459204,-6.51266717911 -8.22872924805,0.327110648155,-6.49406337738 -8.30575847626,0.331113040447,-6.51343631744 -8.29974651337,0.330107301474,-6.48665475845 -8.32874584198,0.3301025033,-6.4680480957 -8.34273719788,0.330095082521,-6.43546962738 -8.39174938202,0.331093072891,-6.43185806274 -8.38572978973,0.330083221197,-6.38527488708 -8.41372871399,0.330077946186,-6.36368894577 -8.44973373413,0.331074178219,-6.35007953644 -8.46373271942,0.331071555614,-6.33928585052 -8.48572921753,0.331065833569,-6.3146853447 -8.50772476196,0.331059962511,-6.28909540176 -8.54172801971,0.332055658102,-6.2724981308 -8.55371952057,0.332048684359,-6.23990774155 -8.59572696686,0.333045423031,-6.22930431366 -8.61071968079,0.333038836718,-6.19871520996 -8.621717453,0.333035975695,-6.18591928482 -8.65572071075,0.334031790495,-6.16931819916 -8.6797170639,0.334026277065,-6.14472913742 -8.70271492004,0.33402082324,-6.12013339996 -8.74071979523,0.33501714468,-6.10652589798 -8.75971508026,0.335011065006,-6.07794284821 -8.78771495819,0.336006134748,-6.05634832382 -8.79871273041,0.336003571749,-6.04454088211 -8.8187084198,0.335997760296,-6.01695394516 -8.84670829773,0.335992902517,-5.99535799026 -8.88271141052,0.336988985538,-5.97975254059 -8.91071033478,0.337983995676,-5.95716428757 -8.93170833588,0.337978631258,-5.93156194687 -8.9497089386,0.337976515293,-5.922768116 -8.97570800781,0.338971436024,-5.89917564392 -8.98569869995,0.337964832783,-5.86459589005 -9.03470802307,0.33996206522,-5.85698366165 -9.05570411682,0.339956671,-5.83038949966 -9.09671020508,0.340953081846,-5.81678533554 -9.11070346832,0.340947061777,-5.78519868851 -9.0146522522,0.334935039282,-5.70147371292 -9.12368869781,0.339937448502,-5.73282146454 -9.16969776154,0.341934263706,-5.72221326828 -9.20569992065,0.342930197716,-5.70461463928 -9.23870182037,0.343925833702,-5.68501758575 -9.27770614624,0.34492200613,-5.66941356659 -12.1209411621,0.513131916523,-7.42792510986 -11.9398508072,0.501112401485,-7.28726148605 -12.031867981,0.505107581615,-7.29262685776 -12.0928726196,0.507100641727,-7.27900695801 -12.1448726654,0.50909268856,-7.25840139389 -11.9577713013,0.49706864357,-7.09194898605 -12.0197763443,0.499061763287,-7.07833433151 -13.3973264694,0.578139603138,-7.85884141922 -13.2472505569,0.569123506546,-7.74015378952 -13.1741962433,0.563106298447,-7.64062738419 -13.2512025833,0.566098213196,-7.630007267 -13.1261281967,0.557078361511,-7.50051784515 -13.4122180939,0.573082387447,-7.61275434494 -13.126080513,0.555054068565,-7.39037227631 -13.223107338,0.559053480625,-7.4195189476 -13.2000732422,0.557040214539,-7.35096359253 -13.2830820084,0.560032486916,-7.34333753586 -13.3911008835,0.565025985241,-7.3496928215 -13.9662971497,0.597041785717,-7.61873292923 -14.5424890518,0.628055632114,-7.88278102875 -13.3970336914,0.560990989208,-7.18797302246 -13.4140281677,0.561986088753,-7.17017412186 -13.4150056839,0.559974730015,-7.11659812927 -13.4469957352,0.560964584351,-7.07900905609 -13.5470085144,0.564957380295,-7.07936573029 -13.4799633026,0.55994361639,-6.9888381958 -13.4679365158,0.557932198048,-6.92827415466 -13.4108943939,0.553919196129,-6.84374332428 -13.3898763657,0.551913201809,-6.80597066879 -13.4248666763,0.55190384388,-6.7713727951 -13.418844223,0.550893068314,-6.71480560303 -13.5308618546,0.555885910988,-6.7191619873 -13.5138349533,0.553875207901,-6.65759658813 -13.4888057709,0.55086427927,-6.59203958511 -13.6058244705,0.55585694313,-6.59739637375 -13.6338224411,0.556852519512,-6.58459377289 -13.6808176041,0.558843493462,-6.55498933792 -13.7248125076,0.559834301472,-6.52339029312 -13.7217912674,0.558824241161,-6.46881914139 -13.7177696228,0.55681437254,-6.41424751282 -13.8227825165,0.561806321144,-6.4116101265 -13.7307434082,0.555799841881,-6.34088468552 -13.7067165375,0.55378985405,-6.27633237839 -13.8027276993,0.557781755924,-6.26969480515 -13.8887338638,0.561773240566,-6.25706958771 -13.9337282181,0.562764286995,-6.22546672821 -13.8436813354,0.556754171848,-6.1319475174 -13.7986488342,0.55274450779,-6.05841016769 -13.8626585007,0.55574041605,-6.06158256531 -13.89564991,0.556731522083,-6.02399253845 -14.086687088,0.565723359585,-6.05729866028 -14.1496868134,0.568714439869,-6.03268527985 -14.2536964417,0.572705566883,-6.02604436874 -14.233672142,0.570696353912,-5.96349287033 -14.6647834778,0.593691647053,-6.1244301796 -14.4937171936,0.583682477474,-5.99696445465 -14.403673172,0.57767355442,-5.9044547081 -14.4516677856,0.578664422035,-5.87185239792 -14.5336713791,0.582655072212,-5.85322856903 -14.506644249,0.579646468163,-5.78867530823 -14.7016782761,0.589636087418,-5.81598091125 -14.5886383057,0.58263272047,-5.74326324463 -14.6376333237,0.584623515606,-5.70966482162 -14.8336658478,0.594612538815,-5.73497390747 -17.4433116913,0.734569966793,-6.72077226639 -17.4952983856,0.735557258129,-6.67817258835 -17.5552883148,0.737544536591,-6.63856697083 -17.6012763977,0.739531874657,-6.59297180176 -17.6442737579,0.740525305271,-6.57815980911 -17.6822566986,0.741512715816,-6.52857446671 -17.7332458496,0.743500113487,-6.48497247696 -17.7622261047,0.743487894535,-6.43238782883 -17.826215744,0.745474934578,-6.39278173447 -17.8842048645,0.747462213039,-6.3511762619 -17.886182785,0.746450841427,-6.28860664368 -17.9621868134,0.750443279743,-6.2847738266 -18.0461578369,0.752418458462,-6.18759012222 -18.0931415558,0.754405975342,-6.14099121094 -18.1561336517,0.756393015385,-6.09938621521 -18.2311248779,0.75937962532,-6.0617723465 -18.2761230469,0.761372625828,-6.04496431351 -18.3001041412,0.761360824108,-5.98938179016 -18.37109375,0.764347612858,-5.94976997375 -18.3960762024,0.764335811138,-5.89418840408 -14.8803319931,0.57745218277,-4.67474079132 -18.5230541229,0.769309639931,-5.80797815323 -18.5710391998,0.770297050476,-5.7593832016 -15.0413255692,0.584429264069,-4.5977191925 -14.9562940598,0.578426003456,-4.5191988945 -14.955280304,0.578419566154,-4.46762800217 -14.9492635727,0.57641351223,-4.41505718231 -15.0312662125,0.580403625965,-4.38844299316 -14.9502363205,0.575400948524,-4.31291818619 -15.0252361298,0.578391373158,-4.28430509567 -14.9882221222,0.576390028,-4.24754285812 -15.0022115707,0.57638335228,-4.20096254349 -15.0071983337,0.575377166271,-4.1513915062 -15.0591945648,0.577368795872,-4.11578845978 -15.1111898422,0.579360425472,-4.08018350601 -15.1531839371,0.581352412701,-4.0405921936 -15.1651725769,0.581346035004,-3.9930138588 -12.9727945328,0.466458797455,-3.36350297928 -12.9897899628,0.46745455265,-3.32491779327 -12.9617767334,0.465452730656,-3.27336668968 -13.0137777328,0.46744659543,-3.24376535416 -13.0647773743,0.469440549612,-3.21415925026 -13.0947742462,0.470435649157,-3.17856812477 -13.0657663345,0.46843573451,-3.14880394936 -15.4581279755,0.591290831566,-3.7128508091 -15.5261259079,0.594281494617,-3.67923593521 -15.5581178665,0.595274150372,-3.63564801216 -15.6151132584,0.598265349865,-3.5980451107 -15.6281023026,0.598259270191,-3.5494685173 -15.7201023102,0.602248191833,-3.51984500885 -15.774105072,0.604242026806,-3.50603461266 -15.8411006927,0.607232511044,-3.47042036057 -15.9221000671,0.611221849918,-3.43680500984 -15.934088707,0.611215889454,-3.38722848892 -15.969080925,0.612208425999,-3.34264039993 -16.00507164,0.613200843334,-3.29805207253 -16.0710678101,0.616191267967,-3.26044154167 -16.0800647736,0.616188108921,-3.23565554619 -16.1200561523,0.618180274963,-3.19205975533 -16.1570491791,0.619172632694,-3.14647579193 -16.1910419464,0.620165288448,-3.10088706017 -16.2320346832,0.622157514095,-3.05728816986 -16.2940292358,0.624148011208,-3.01668572426 -16.3450222015,0.62713944912,-2.97408533096 -16.3950233459,0.629133224487,-2.9572725296 -16.4130134583,0.629127144814,-2.90769314766 -16.5010108948,0.633115589619,-2.87107467651 -16.5170001984,0.634109675884,-2.82049870491 -16.6229991913,0.638096570969,-2.78587436676 -16.6619930267,0.64008885622,-2.73928332329 -16.7059898376,0.642082989216,-2.72047185898 -16.7379817963,0.643075883389,-2.67288041115 -16.8069763184,0.646065592766,-2.63027715683 -16.8709716797,0.64905577898,-2.58667516708 -16.9499664307,0.653044700623,-2.54605770111 -16.9969596863,0.654036164284,-2.49846982956 -17.0659561157,0.658025860786,-2.45585513115 -17.1019515991,0.659020483494,-2.43405175209 -17.1559467316,0.662011444569,-2.38745450974 -17.2149391174,0.664001762867,-2.34085845947 -17.2889328003,0.666990935802,-2.29724526405 -17.2749214172,0.665987849236,-2.23968863487 -16.2078227997,0.612081229687,-2.03769922256 -16.1078052521,0.60608714819,-1.97318029404 -16.0317935944,0.602092683315,-1.9374370575 -16.0227851868,0.602090537548,-1.88487660885 -15.9857730865,0.599091112614,-1.82932770252 -15.9567623138,0.598091065884,-1.77576756477 -15.93775177,0.596090137959,-1.72221493721 -15.9527454376,0.597086012363,-1.67363643646 -15.9397363663,0.59608477354,-1.62207090855 -15.9417324066,0.596083343029,-1.59728348255 -15.9357242584,0.59508150816,-1.54671359062 -15.9707183838,0.597075581551,-1.50012540817 -15.9787120819,0.597072482109,-1.45055186749 -15.9817037582,0.597069859505,-1.399985075 -16.0126991272,0.598064541817,-1.35240137577 -16.0106945038,0.598063647747,-1.32761240005 -16.0596904755,0.60005646944,-1.28201472759 -16.1316871643,0.603046894073,-1.23741161823 -16.1866817474,0.606039047241,-1.19180977345 -16.2766799927,0.610027551651,-1.14819467068 -16.4036769867,0.616012096405,-1.10755550861 -18.5747718811,0.72577881813,-1.22084891796 -18.648771286,0.72876906395,-1.1970281601 -18.7727661133,0.734752118587,-1.14739573002 -18.7847537994,0.735747098923,-1.08882629871 -9.65136623383,0.276737481356,-0.436949461699 -9.65337085724,0.276740252972,-0.407367229462 -9.65137577057,0.276743590832,-0.376797497272 -9.65037918091,0.276745229959,-0.362005800009 -9.66038322449,0.276747256517,-0.332426011562 -9.65038871765,0.275751560926,-0.301855027676 -9.65139293671,0.275754600763,-0.272272914648 -9.64539813995,0.275758564472,-0.241703733802 -9.64440250397,0.275761902332,-0.212121814489 -9.64440822601,0.275765299797,-0.181554079056 -9.64841079712,0.27576649189,-0.166763499379 -9.64541625977,0.275770157576,-0.137181818485 -9.63642120361,0.274774640799,-0.106614992023 -9.62542533875,0.274779289961,-0.0770349130034 -9.63243103027,0.274782091379,-0.0464675761759 -9.63343715668,0.274785459042,-0.0168867576867 -9.63444328308,0.274788856506,0.012694071047 -9.63044548035,0.274791091681,0.0274834595621 -9.63145160675,0.274794697762,0.0580501779914 -9.6194562912,0.273799747229,0.0876265019178 -9.62346172333,0.273802936077,0.117207825184 -9.62246894836,0.273806869984,0.147773444653 -9.63447475433,0.274809122086,0.177359059453 -9.62047672272,0.273812711239,0.192142441869 -9.62648296356,0.274815738201,0.221725657582 -9.61848831177,0.273820579052,0.251301079988 -9.62049484253,0.273824304342,0.281868070364 -9.61150169373,0.273829311132,0.311442196369 -9.61950778961,0.27383223176,0.341027200222 -9.61751461029,0.273836433887,0.370605677366 -9.61651706696,0.273838669062,0.386380851269 -9.60852432251,0.273843735456,0.415954381227 -9.60753059387,0.273847907782,0.445533126593 -9.59653663635,0.272853434086,0.475102782249 -9.61354255676,0.273855417967,0.505683898926 -9.59854984283,0.272861450911,0.534263193607 -9.60155773163,0.27386534214,0.564831972122 -9.59755992889,0.272868007421,0.579617381096 -9.60256671906,0.273871541023,0.609202563763 -9.59657382965,0.273876607418,0.6387758255 -9.5995798111,0.27388048172,0.668359041214 -9.58758735657,0.272886484861,0.697924375534 -9.59259414673,0.273890286684,0.728496491909 -9.59060192108,0.273894935846,0.758073925972 -9.5836057663,0.27289801836,0.771868526936 -9.5876121521,0.273901998997,0.802439987659 -9.57762050629,0.272907942533,0.832005977631 -9.58162689209,0.272911846638,0.861591637135 -9.58563423157,0.273915916681,0.892164111137 -9.56964206696,0.272922724485,0.92073404789 -9.56864643097,0.272925168276,0.93552261591 -9.57765388489,0.273928552866,0.966103374958 -9.57566165924,0.273933470249,0.99568092823 -9.57466888428,0.273938298225,1.02526021004 -9.57667636871,0.273942828178,1.05583071709 -9.57968425751,0.273947060108,1.08541738987 -9.57469177246,0.273952573538,1.11499023438 -9.56169605255,0.27395683527,1.12877142429 -9.57670307159,0.273959577084,1.16035294533 -9.56771183014,0.273965805769,1.18991804123 -9.56072044373,0.27397158742,1.21850061417 -9.56072807312,0.273976624012,1.24906885624 -9.55573654175,0.273982316256,1.27864122391 -9.55774402618,0.273986935616,1.30822789669 -9.57074832916,0.274987578392,1.32501900196 -9.55475616455,0.273995012045,1.35358214378 -9.55876541138,0.274999469519,1.38416051865 -9.56677246094,0.275003314018,1.41474831104 -9.53978252411,0.274012386799,1.44131278992 -9.53979110718,0.274017632008,1.47188258171 -9.5517950058,0.275018453598,1.48867511749 -9.54980373383,0.275023907423,1.51825511456 -9.53681278229,0.275031089783,1.5468224287 -9.54082012177,0.275035709143,1.57740330696 -9.53682994843,0.2750415802,1.60697853565 -9.53183841705,0.275047659874,1.63655149937 -9.53484725952,0.276052564383,1.66713130474 -9.52885150909,0.27505621314,1.68190872669 -9.52386188507,0.275062382221,1.71148169041 -9.52686977386,0.276067316532,1.74206256866 -9.52087974548,0.276073515415,1.77064692974 -9.51788806915,0.276079595089,1.80121195316 -9.53589630127,0.277082324028,1.8347953558 -9.5129070282,0.276091426611,1.86135935783 -9.51791095734,0.277093350887,1.87715423107 -9.51892089844,0.277098745108,1.9077321291 -9.51093006134,0.277105659246,1.93729746342 -9.5039396286,0.277112275362,1.96587944031 -9.51594829559,0.27811601758,1.99846458435 -9.50995826721,0.278122633696,2.02803659439 -9.49696826935,0.277130454779,2.05660009384 -9.51097202301,0.278131067753,2.07439851761 -9.49398231506,0.277139514685,2.10196304321 -9.49699211121,0.278144717216,2.13255047798 -9.50700092316,0.279149055481,2.16612100601 -9.49701118469,0.279156416655,2.19469428062 -9.49002170563,0.2791634202,2.22426390648 -9.50102519989,0.279164433479,2.24107050896 -9.49603557587,0.279171258211,2.27163386345 -9.4890460968,0.279178321362,2.30120396614 -9.49205589294,0.280183792114,2.33278250694 -9.491065979,0.280189871788,2.36336064339 -9.4790763855,0.280197650194,2.39094090462 -9.48708534241,0.281202495098,2.42451190948 -9.47409248352,0.280207484961,2.43630337715 -9.4691028595,0.280214488506,2.46686816216 -9.48311138153,0.281218260527,2.50145030022 -9.46412372589,0.281227499247,2.5280175209 -9.46213340759,0.281233906746,2.55859494209 -9.47214317322,0.28223836422,2.59217834473 -9.46314811707,0.282242834568,2.60497021675 -9.45715999603,0.282250165939,2.63553333282 -9.47216892242,0.283253967762,2.67111229897 -9.46317958832,0.283261567354,2.69969153404 -9.46019077301,0.283268302679,2.73026776314 -9.4542016983,0.283275544643,2.75984597206 -9.44421386719,0.283283650875,2.7894077301 -9.44221878052,0.283287078142,2.80420088768 -9.46022796631,0.285290390253,2.84078621864 -9.44823932648,0.284298807383,2.86935377121 -9.44025039673,0.284306555986,2.89892506599 -9.43526172638,0.285313904285,2.92949604988 -9.43627262115,0.285320073366,2.96107983589 -9.42928409576,0.285327672958,2.99065613747 -9.44428825378,0.286328405142,3.01144623756 -9.44029903412,0.287335574627,3.04202365875 -9.43531036377,0.287342935801,3.07259726524 -9.42832183838,0.2873506248,3.10217499733 -9.43033313751,0.287357002497,3.13574147224 -9.41534614563,0.287366002798,3.16232323647 -9.42635536194,0.288370877504,3.19889330864 -9.43136119843,0.28937330842,3.21668314934 -9.41637325287,0.288382589817,3.2442522049 -9.41038513184,0.289390087128,3.27383708954 -9.42139530182,0.290394991636,3.31041169167 -9.40540885925,0.289404571056,3.33797621727 -9.41441822052,0.290409743786,3.37355685234 -9.42442321777,0.291411370039,3.39334845543 -9.40843677521,0.291420817375,3.41992640495 -9.40944766998,0.292427539825,3.4534971714 -9.40545940399,0.292434871197,3.48408269882 -9.40047168732,0.292442679405,3.51565074921 -9.40648269653,0.29344856739,3.55122351646 -9.4034948349,0.294455915689,3.58280348778 -9.39650154114,0.293460547924,3.59659123421 -9.39851284027,0.294467270374,3.63115954399 -9.3935251236,0.294474929571,3.66174340248 -9.39553642273,0.295481652021,3.69631361961 -9.38754940033,0.295490086079,3.72688341141 -9.39755916595,0.296495169401,3.76347208023 -9.37857341766,0.296505659819,3.79003620148 -9.39157772064,0.297506868839,3.81182956696 -9.37959194183,0.29751598835,3.84040546417 -9.37760353088,0.298523336649,3.87298488617 -9.38461494446,0.299529194832,3.90956354141 -9.37962722778,0.299537360668,3.94212889671 -9.37763977051,0.299544751644,3.97471094131 -9.38064575195,0.300547897816,3.99349331856 -9.37565803528,0.300555884838,4.02507257462 -9.37666988373,0.301562905312,4.05964946747 -9.37168216705,0.30157110095,4.09221839905 -9.37969398499,0.303576827049,4.12979888916 -9.36670875549,0.303586393595,4.1583738327 -9.36571979523,0.303593724966,4.19195556641 -9.36272716522,0.303598105907,4.20873260498 -9.36073970795,0.30460575223,4.24231004715 -9.36975002289,0.305611401796,4.28089046478 -9.3567647934,0.305621027946,4.30946779251 -9.3587770462,0.306627988815,4.34504699707 -9.34479236603,0.306638121605,4.37460708618 -9.35079669952,0.307640612125,4.39440250397 -9.41979789734,0.311635375023,4.46100521088 -9.33582496643,0.307658165693,4.45755243301 -9.34284877777,0.309671878815,4.53170442581 -9.34986019135,0.310678243637,4.57127428055 -9.327876091,0.310689717531,4.59584856033 -9.35287952423,0.312688827515,4.62564611435 -9.33689403534,0.312699228525,4.65322208405 -9.3549041748,0.313703656197,4.69879341125 -9.32592201233,0.313716590405,4.72036266327 -9.33693218231,0.314722150564,4.76194095612 -9.31694889069,0.314733356237,4.78751754761 -9.32795906067,0.315738916397,4.82909965515 -9.33596515656,0.316741377115,4.85188388824 -9.336977005,0.317748785019,4.88846492767 -9.31699466705,0.317760229111,4.91503190994 -9.32500553131,0.318766385317,4.95561313629 -9.31202125549,0.318776458502,4.98518943787 -9.31303310394,0.319784045219,5.02276420593 -9.31304645538,0.320791959763,5.06033372879 -9.31405353546,0.320795595646,5.07912540436 -9.30906772614,0.321804314852,5.11369895935 -9.31307983398,0.322811424732,5.15327453613 -9.29909515381,0.322821825743,5.1828494072 -9.29510974884,0.323830485344,5.21842098236 -9.30012226105,0.324837476015,5.25899648666 -9.30812740326,0.325839757919,5.28179311752 -9.28814411163,0.325851410627,5.30836391449 -9.29815578461,0.326857417822,5.35194301605 -9.29017066956,0.327866882086,5.38551664352 -9.28218650818,0.327876359224,5.41909074783 -9.29219722748,0.329882532358,5.46366453171 -9.29121112823,0.330890625715,5.50124406815 -9.27722072601,0.329897224903,5.51203155518 -9.29323101044,0.331902295351,5.56060647964 -9.26725006104,0.331915289164,5.58417367935 -9.28326034546,0.333920091391,5.63176393509 -9.27727603912,0.333929538727,5.66832637787 -9.27528953552,0.334937900305,5.70590686798 -9.2583065033,0.334949165583,5.73448324203 -9.27830886841,0.336949378252,5.76627779007 -9.25532722473,0.33696192503,5.79184627533 -9.25934028625,0.337969392538,5.83441925049 -9.25535488129,0.338978379965,5.87199163437 -9.25736904144,0.339986234903,5.91356468201 -9.2413854599,0.339997410774,5.94314098358 -9.24939918518,0.342004150152,5.98871707916 -9.24040699005,0.342009872198,6.00250911713 -9.25241851807,0.34301584959,6.05108451843 -9.25043296814,0.344024568796,6.09065818787 -9.24544811249,0.345033764839,6.12823295593 -9.22946548462,0.345045179129,6.15880393982 -9.24047756195,0.347051411867,6.20738077164 -9.23248672485,0.347057014704,6.22217273712 -9.23150062561,0.348065495491,6.26274967194 -9.22951507568,0.349074333906,6.30332136154 -9.23352813721,0.351081758738,6.34690713882 -9.21654701233,0.351093500853,6.37747573853 -9.21856021881,0.352101534605,6.42105054855 -9.20856952667,0.352107822895,6.43582963943 -9.21358299255,0.354115247726,6.48140859604 -9.21459674835,0.355123400688,6.5239906311 -9.22061061859,0.357130795717,6.57156133652 -9.19762992859,0.357143580914,6.59714126587 -9.21264076233,0.359149336815,6.65171194077 -9.19365882874,0.359161555767,6.68128347397 -9.20166492462,0.360164135695,6.70807933807 -9.19968032837,0.361173182726,6.75064992905 -9.20469379425,0.363180786371,6.79822444916 -9.1877117157,0.363192558289,6.82880401611 -9.19172477722,0.365200459957,6.87637519836 -9.18174171448,0.365211009979,6.91295051575 -9.17975711823,0.367219954729,6.95552921295 -9.18476295471,0.36822322011,6.98132038116 -9.19177627563,0.369230598211,7.03189325333 -9.24577999115,0.374228537083,7.11748743057 -9.1218214035,0.368261665106,7.0680308342 -9.04585266113,0.364285379648,7.0545873642 -9.07687568665,0.369296729565,7.16874790192 -9.04489040375,0.368307441473,7.16652679443 -8.95792388916,0.363333553076,7.14407396317 -8.91094970703,0.362351596355,7.15164232254 -8.85797691345,0.360370844603,7.15420818329 -8.46507835388,0.33645761013,6.88368701935 -8.83801174164,0.361392617226,7.22934913635 -8.54208469391,0.343455642462,7.01107263565 -8.60708522797,0.349451750517,7.10866117477 -8.88004016876,0.368406295776,7.37730789185 -9.14299678802,0.386362820864,7.64095020294 -9.14701080322,0.388370960951,7.69252490997 -8.44818401337,0.344519227743,7.15592575073 -9.13604450226,0.391390889883,7.77967786789 -9.14405059814,0.392393708229,7.81047010422 -9.13506698608,0.393404483795,7.85204124451 -9.14108181,0.395412296057,7.90661525726 -9.12709999084,0.396423906088,7.94319486618 -9.10711956024,0.396436959505,7.97576284409 -9.31008815765,0.411405295134,8.20239067078 -9.13914299011,0.401448398829,8.10292816162 -9.25612354279,0.410429596901,8.23173999786 -9.25813865662,0.412438124418,8.2843208313 -9.2341594696,0.412452042103,8.31488800049 -9.26916694641,0.416453957558,8.39747714996 -9.23119163513,0.41547074914,8.41603851318 -9.22520828247,0.417481154203,8.46360683441 -9.22621631622,0.418485283852,8.48940563202 -9.2152338028,0.419496744871,8.53297138214 -9.21524906158,0.421505779028,8.5855512619 -9.23126220703,0.423511773348,8.65412712097 -9.22227859497,0.425522625446,8.69870662689 -9.20529937744,0.425535291433,8.73727321625 -9.21731185913,0.428542047739,8.80285167694 -9.20832061768,0.428548306227,8.82064533234 -9.20833683014,0.430557489395,8.87522125244 -9.19935512543,0.43256855011,8.92179393768 -9.19437217712,0.433578789234,8.97236824036 -9.1783914566,0.434591203928,9.01194381714 -9.11943721771,0.434621691704,9.06607913971 -9.07645606995,0.432635068893,9.05185604095 -9.05647659302,0.432648450136,9.08842468262 -9.04849433899,0.434659272432,9.13600349426 -9.03851222992,0.435670614243,9.18257713318 -9.03353118896,0.437681108713,9.2351474762 -9.03154659271,0.439690768719,9.28972816467 -9.03555393219,0.440694600344,9.32251739502 -9.0385684967,0.442703336477,9.38309669495 -9.02658939362,0.444715291262,9.42966461182 -9.02360534668,0.446725338697,9.48523807526 -9.01662349701,0.447736144066,9.53681278229 -9.00364208221,0.448748081923,9.58139228821 -9.01865577698,0.45275464654,9.65796375275 -9.033659935,0.454756289721,9.70375728607 -8.96969223022,0.451778769493,9.69531917572 -8.90272521973,0.449801772833,9.68288421631 -8.84975528717,0.447822034359,9.68544960022 -8.79378509521,0.445842981339,9.68501091003 -8.72381877899,0.442866623402,9.66757774353 -8.74282264709,0.445867657661,9.71936511993 -8.73484134674,0.446878820658,9.77094078064 -8.71986198425,0.44789147377,9.81551170349 -8.71887874603,0.450901180506,9.87509250641 -8.70389938354,0.451913803816,9.91966629028 -8.96185016632,0.473870813847,10.2753009796 -8.96386623383,0.475880146027,10.342871666 -9.02085971832,0.481873333454,10.4406719208 -8.5669927597,0.449975341558,9.98015785217 -8.23109531403,0.426053613424,9.65265750885 -8.16312980652,0.423077076674,9.63322353363 -8.11015987396,0.421097666025,9.63178634644 -8.07418632507,0.421114504337,9.64836502075 -8.01022052765,0.418137460947,9.63392162323 -7.98523521423,0.418147325516,9.63370895386 -7.92726707458,0.415168851614,9.62427711487 -7.87929725647,0.414188563824,9.62783813477 -7.83432626724,0.413207441568,9.63340950012 -7.80835008621,0.413222432137,9.66198444366 -7.75438165665,0.411243259907,9.65655136108 -7.68441724777,0.408267408609,9.63111305237 -7.8103928566,0.419246584177,9.81892681122 -7.59846591949,0.405299603939,9.61446762085 -3.41156888008,0.0691587999463,4.37346220016 -3.40558981895,0.0691698938608,4.39304542542 -3.39261245728,0.069182343781,4.40363121033 -3.36364030838,0.0681985914707,4.39519166946 -7.34962844849,0.398404747248,9.63409328461 -7.35764408112,0.401413023472,9.70667266846 -7.25868797302,0.395443081856,9.63823413849 -7.22771406174,0.395459264517,9.65880966187 -7.18274450302,0.394478589296,9.66237258911 -7.08778715134,0.388507723808,9.59594154358 -7.05480480194,0.387519478798,9.58272266388 -7.01083517075,0.38653844595,9.58529281616 -6.95286846161,0.383560180664,9.56786346436 -6.95688533783,0.386569440365,9.63643932343 -6.93790864944,0.387583464384,9.67400836945 -6.89393854141,0.386602342129,9.67558193207 -6.82896518707,0.382620662451,9.61635875702 -6.91096115112,0.391613900661,9.79495239258 -6.84099817276,0.388638079166,9.75952339172 -6.92499399185,0.398631006479,9.94411563873 -6.88102436066,0.397650182247,9.94768047333 -6.85904836655,0.398664802313,9.98225212097 -6.77708911896,0.393691539764,9.9288187027 -6.72311306,0.390707671642,9.88359546661 -6.65315008163,0.386731982231,9.84616470337 -6.56119346619,0.381760835648,9.77572917938 -8.75961208344,0.582322120667,13.125667572 -8.74165248871,0.588345944881,13.2758216858 -8.75266647339,0.59235394001,13.383398056 -8.75967407227,0.595357596874,13.4401845932 -8.74569511414,0.598370492458,13.5087652206 -8.74071407318,0.601381838322,13.5943374634 -8.7447309494,0.605391204357,13.6939144135 -8.71875667572,0.607406795025,13.7484817505 -8.70777702332,0.610419332981,13.8260564804 -8.71579265594,0.615427792072,13.9336385727 -8.71880054474,0.617432236671,13.9864292145 -8.71082019806,0.620444178581,14.0710039139 -8.69484329224,0.623457670212,14.143576622 -8.69386100769,0.627468287945,14.2421474457 -8.6818819046,0.631480932236,14.3217258453 -6.34155273438,0.407968342304,10.5429506302 -6.32656574249,0.408976435661,10.5547399521 -6.26260280609,0.405999720097,10.5223083496 -6.29861116409,0.412002533674,10.6568965912 -6.24464559555,0.410023838282,10.6414642334 -6.19467782974,0.409044146538,10.6310415268 -6.2036948204,0.413052588701,10.7226228714 -6.14273071289,0.410075396299,10.6951856613 -6.14174032211,0.412080764771,10.7319746017 -6.07877779007,0.409103929996,10.6995420456 -6.08079576492,0.412113726139,10.780125618 -6.06381940842,0.414127498865,10.8287000656 -6.02484989166,0.413145780563,10.8382730484 -5.98088121414,0.412164956331,10.8378486633 -5.93491363525,0.41118478775,10.8354139328 -5.92892456055,0.412191003561,10.8632087708 -5.91694736481,0.415203779936,10.9217863083 -5.86598062515,0.413224428892,10.9083604813 -5.86300086975,0.41623544693,10.9849357605 -5.84402608871,0.418249726295,11.0325088501 -5.8440451622,0.421260118484,11.1160860062 -5.85205221176,0.424263626337,11.1728792191 -5.85706996918,0.428272873163,11.2664632797 -5.84309339523,0.431286007166,11.3250427246 -5.84611177444,0.435296028852,11.4196128845 -5.83313512802,0.438309073448,11.4821901321 -5.82215738297,0.44032150507,11.5477752686 -5.8281750679,0.445330798626,11.6503515244 -5.82118701935,0.446337461472,11.682138443 -5.81720733643,0.450348585844,11.7647209167 -5.81122875214,0.454360336065,11.8462944031 -5.83224153519,0.460366487503,11.9828767776 -5.82526302338,0.464378327131,12.0634565353 -5.81428575516,0.467390984297,12.1370334625 -5.80830717087,0.470402598381,12.2216129303 -5.82631158829,0.47540435195,12.3103981018 -5.83032989502,0.480414092541,12.4189758301 -5.83334827423,0.485423833132,12.5255594254 -5.81437301636,0.487438052893,12.586139679 -5.80939483643,0.491449713707,12.6807117462 -5.77442359924,0.492467135191,12.7072916031 -5.80442523956,0.498466402292,12.8270816803 -5.78844976425,0.501480281353,12.8996553421 -5.7724738121,0.504494011402,12.9722318649 -5.75549840927,0.507507860661,13.0428113937 -5.76651477814,0.513516247272,13.1793880463 -5.72954511642,0.514534175396,13.2059669495 -5.73756217957,0.520543038845,13.3375482559 -5.75056838989,0.525545716286,13.4253396988 -5.71659803391,0.526562988758,13.4609174728 -5.73761129379,0.534569442272,13.6294946671 -5.73063325882,0.538581550121,13.7340669632 -5.80363130569,0.554577231407,14.0296621323 -5.69468307495,0.545609712601,13.8892278671 -3.44736123085,0.252069175243,8.47965717316 -3.41738009453,0.25008019805,8.44245147705 -3.38141155243,0.248098045588,8.43101787567 -3.34144330025,0.247116208076,8.40560340881 -3.31347203255,0.246132284403,8.41217803955 -3.27650308609,0.245149895549,8.39376163483 -3.2525305748,0.24516505003,8.40934181213 -3.22255945206,0.245181202888,8.40792942047 -3.20457530022,0.244190201163,8.40170955658 -3.17260551453,0.243206962943,8.39628791809 -3.13763594627,0.242224216461,8.38187026978 -3.11666250229,0.243238791823,8.40544986725 -3.0916903019,0.243253976107,8.41703605652 -3.06271910667,0.242270067334,8.41861724854 -3.04973316193,0.242277801037,8.4234085083 -3.02576112747,0.243293076754,8.43998432159 -2.99878978729,0.243308827281,8.44756317139 -2.96981883049,0.242324948311,8.44914245605 -2.9458463192,0.243340060115,8.46472358704 -2.91687583923,0.242356196046,8.4663028717 -2.89390325546,0.243371084332,8.48488521576 -2.88691568375,0.244377672672,8.5076751709 -2.85594582558,0.243394419551,8.50524616241 -2.83197331429,0.244409456849,8.52082920074 -2.81499910355,0.245423167944,8.55841064453 -2.79102635384,0.24543812871,8.57399749756 -2.76805377007,0.246452987194,8.59358119965 -2.75106978416,0.246461734176,8.58836269379 -2.73009681702,0.247476354241,8.61593914032 -2.70812368393,0.247490927577,8.63852596283 -2.69214940071,0.249504566193,8.68310260773 -2.66917705536,0.250519484282,8.70468330383 -2.65020346642,0.251533538103,8.73926639557 -2.62523150444,0.252548843622,8.75484752655 -2.62124371529,0.254555076361,8.79362869263 -2.5992705822,0.254569590092,8.81821727753 -2.58929419518,0.258581876755,8.88580036163 -2.57531952858,0.260595202446,8.94337463379 -2.56134414673,0.263608217239,8.998960495 -2.54137134552,0.264622747898,9.03753376007 -2.53639340401,0.269633948803,9.12712192535 -6.40023803711,1.00388455391,23.2600517273 -6.32128190994,1.00291097164,23.2586212158 -6.24432563782,1.00193691254,23.2601985931 -6.16536998749,1.00096344948,23.257768631 -6.08841323853,0.999989390373,23.261341095 -6.00645875931,0.999016523361,23.2469120026 -5.92750310898,0.997042715549,23.238489151 -5.88852500916,0.997055888176,23.2402744293 -5.81056880951,0.99608194828,23.2348499298 -5.63464260101,0.974127233028,22.8354167938 -5.44971942902,0.950174152851,22.3849868774 -5.57570123672,0.992160499096,23.2205715179 -5.49674606323,0.991186797619,23.2131443024 -5.45476913452,0.990200459957,23.1999282837 -5.3798122406,0.98922586441,23.2045059204 -5.29985713959,0.988252401352,23.1920776367 -5.22390127182,0.987277984619,23.192653656 -5.14794445038,0.986303389072,23.1902332306 -5.11297607422,0.995321214199,23.3838043213 -5.09500169754,1.00833547115,23.6533889771 -5.10700845718,1.02033865452,23.8931770325 -5.02505397797,1.01836538315,23.8757514954 -3.23162293434,0.59272146225,15.5652742386 -3.17066264153,0.589743852615,15.5158519745 -3.11969852448,0.588764071465,15.5104370117 -3.06373691559,0.586785554886,15.4860105515 -3.03875470161,0.586795508862,15.4848031998 -2.99378967285,0.587814748287,15.513381958 -2.95382285118,0.589833080769,15.5689601898 -2.90185952187,0.588853538036,15.560541153 -2.86789083481,0.592870652676,15.6521186829 -2.81692743301,0.592890918255,15.6487007141 -4.85332345963,1.19851303101,27.5443210602 -4.86732912064,1.21451568604,27.876115799 -4.8423576355,1.23353147507,28.2566928864 -4.81038856506,1.25054848194,28.6102714539 -4.7734208107,1.2675665617,28.9508476257 -4.71545934677,1.27758848667,29.1674251556 -4.69748544693,1.30160284042,29.6480045319 -4.60853385925,1.30263066292,29.68957901 -4.59954738617,1.31463778019,29.941368103 -4.51859235764,1.31966412067,30.0399475098 -4.43463945389,1.32269096375,30.1255245209 -4.3486866951,1.32671809196,30.2000980377 -4.26773262024,1.33174431324,30.3136749268 -4.1787815094,1.33377218246,30.3742523193 -4.09482812881,1.33779883385,30.4718284607 -4.05984926224,1.34281075001,30.5706195831 -3.97789549828,1.34783709049,30.6901988983 -3.89494228363,1.35386359692,30.8127727509 -2.91826510429,0.991057872772,23.6413402557 -2.84930729866,0.993081390858,23.6879253387 -2.77435159683,0.99310618639,23.6965007782 -2.72137856483,0.986121416092,23.5632915497 -2.64942169189,0.987145423889,23.5878715515 -2.57446599007,0.986170053482,23.5854511261 -2.50050997734,0.986194431782,23.5930347443 -2.42055559158,0.983219981194,23.5406150818 -2.34759950638,0.9842441082,23.5591945648 -2.30763316154,1.00226223469,23.9247741699 -2.25366044044,0.993277430534,23.7465667725 -2.28767108917,1.05328166485,24.9491462708 -2.21271538734,1.05530619621,24.9997253418 -2.12776279449,1.05133247375,24.9243087769 -2.04580950737,1.0493581295,24.8908863068 -1.96385598183,1.04638385773,24.8404712677 -1.92087996006,1.04439687729,24.791261673 -2.48572683334,1.48530352116,33.562828064 -2.39777517319,1.49733042717,33.8184051514 -2.29582810402,1.50135982037,33.8919868469 -2.19288134575,1.50338923931,33.9515686035 -2.08693552017,1.50441944599,33.9781494141 -1.98198926449,1.50544917583,34.0017318726 -1.9280166626,1.50546443462,33.993522644 -1.82307040691,1.50649404526,34.0341033936 -1.71712481976,1.50852394104,34.069683075 -1.61217856407,1.51055371761,34.1122627258 -1.50823199749,1.51358318329,34.1848487854 -1.40328598022,1.51661264896,34.2444267273 -1.29833984375,1.52064216137,34.3240127563 -1.24736630917,1.52365660667,34.3958015442 -1.14142048359,1.52668619156,34.4613876343 -1.03447508812,1.53071606159,34.5319671631 -0.927529633045,1.53274571896,34.5845527649 -0.820584177971,1.53677535057,34.6551361084 -0.712639093399,1.53880524635,34.7047157288 -0.603694140911,1.53783512115,34.6863021851 -0.550721466541,1.54484975338,34.8250923157 -0.443775862455,1.55187928677,34.9616775513 -0.337830245495,1.57590854168,35.434261322 -0.226886153221,1.58293867111,35.5768432617 -0.114942200482,1.57196891308,35.3604316711 -0.00399798853323,1.56999897957,35.3150138855 --0.000999477459118,1.60200023651,31.9289970398 --0.100947119296,1.59402823448,31.7805805206 --0.150920853019,1.59004223347,31.7103710175 --0.249868959188,1.5890699625,31.6909580231 --0.348816990852,1.5870975256,31.6535453796 --0.447764962912,1.5851252079,31.6121311188 --0.546712875366,1.58315265179,31.5857162476 --0.645660936832,1.58218026161,31.5673027039 --0.743609309196,1.58120751381,31.5328903198 --0.793582975864,1.58022141457,31.5176811218 --0.888532280922,1.57224798203,31.3832683563 --0.986480653286,1.57227516174,31.3678569794 --1.08342921734,1.56830203533,31.304441452 --1.1823772192,1.56932938099,31.3200302124 --1.27932584286,1.56735622883,31.2756156921 --1.32630074024,1.56536924839,31.2314109802 --1.42724812031,1.56839668751,31.2889995575 --1.52119767666,1.56342279911,31.1885852814 --1.61814641953,1.56244945526,31.1751747131 --1.71609473228,1.56247627735,31.1587619781 --1.81504285336,1.56350314617,31.1733512878 --1.91099190712,1.56152939796,31.1389389038 --1.95996618271,1.56254267693,31.143737793 --2.05891418457,1.56356942654,31.1493263245 --2.15886211395,1.56459629536,31.1659107208 --1.79295349121,1.19754266739,24.6874694824 --1.84191703796,1.17556071281,24.2930526733 --1.91687262058,1.17458319664,24.2746448517 --2.01282167435,1.18860924244,24.5052337646 --2.06179594994,1.19562256336,24.6290283203 --2.28666305542,1.19168949127,24.527797699 --2.3496222496,1.18270969391,24.372385025 --2.41458106041,1.17673015594,24.2479743958 --2.4545583725,1.17774164677,24.2657699585 --2.57849884033,1.20377206802,24.722366333 --3.39122676849,1.59691953659,31.6170024872 --3.49717330933,1.59994661808,31.6715965271 --3.60611844063,1.60497426987,31.7391872406 --3.71406412125,1.6090015173,31.80078125 --3.82200956345,1.61302876472,31.8583755493 --3.88098096848,1.61704325676,31.9231700897 --3.98892664909,1.62107026577,31.977766037 --4.09787225723,1.6250975132,32.0303611755 --4.20681762695,1.62812459469,32.0819511414 --4.31376361847,1.63115143776,32.1135482788 --4.4267077446,1.63617920876,32.1861381531 --4.53665304184,1.64020633698,32.2377357483 --4.59762382507,1.64422082901,32.3015327454 --4.70956850052,1.64824819565,32.3551254272 --4.82451248169,1.65327584743,32.4347229004 --4.93745660782,1.65730333328,32.4863166809 --5.05539941788,1.66333138943,32.5789146423 --5.16834402084,1.66735863686,32.6275100708 --5.28128814697,1.67138576508,32.6751022339 --5.34725761414,1.67640089989,32.7559051514 --5.46220159531,1.68042826653,32.8115005493 --5.57914495468,1.68545591831,32.8760948181 --5.68809080124,1.68748211861,32.8916969299 --5.80303525925,1.6905092001,32.9402923584 --5.91398000717,1.69353556633,32.9628868103 --5.97495126724,1.69654965401,33.0056877136 --6.08589696884,1.69857597351,33.0262832642 --6.20683908463,1.70360374451,33.0988845825 --6.33977746964,1.71263337135,33.2294845581 --6.44872379303,1.71465921402,33.2340812683 --6.37572574615,1.66165518761,32.3086662292 --6.4346871376,1.64967274666,32.074256897 --6.41068458557,1.62867283821,31.6960544586 --6.46764659882,1.61669003963,31.4676494598 --6.55060052872,1.61171138287,31.3682460785 --6.62455749512,1.60573101044,31.2318439484 --6.70151376724,1.59975135326,31.1094379425 --6.78746700287,1.59677290916,31.035036087 --6.87941884995,1.59479546547,30.9856319427 --6.92439508438,1.59380638599,30.961435318 --7.02234458923,1.59382975101,30.939031601 --7.12229394913,1.59485328197,30.9316329956 --7.22124385834,1.59587657452,30.9162311554 --7.32719135284,1.59790098667,30.9288311005 --7.42514133453,1.59792399406,30.9064292908 --7.47211694717,1.59793508053,30.8912334442 --7.10520887375,1.48688495159,28.9657936096 --7.21115684509,1.49090909958,29.0053958893 --7.37206745148,1.4859495163,28.8715896606 --7.56496858597,1.48799443245,28.8677883148 --7.6639289856,1.50001358986,29.0605945587 --7.68390321732,1.48502409458,28.7691898346 --7.2650103569,1.37396657467,26.8517436981 --7.31697463989,1.36698210239,26.7103424072 --7.10294961929,1.24598288536,24.5474834442 --7.18690443039,1.24700331688,24.5480823517 --7.21887493134,1.23801553249,24.3736820221 --7.29483222961,1.23803448677,24.3482818604 --7.38178634644,1.24005508423,24.3588809967 --7.4207649231,1.24006474018,24.3496818542 --7.55370473862,1.25109195709,24.5102882385 --7.59967136383,1.24510633945,24.3848838806 --7.64563798904,1.24012041092,24.2634811401 --8.16335582733,1.24424386024,24.167886734 --8.40822410583,1.24730062485,24.1376934052 --8.52715873718,1.24832832813,24.1120967865 --8.61511325836,1.25034797192,24.1187000275 --8.68707370758,1.24936509132,24.0813026428 --8.76403141022,1.24938297272,24.0559024811 --8.84998607635,1.25140213966,24.0555057526 --8.89296340942,1.25241160393,24.0563087463 --8.96692276001,1.25142884254,24.0229110718 --9.05087852478,1.25344753265,24.0165138245 --9.13083553314,1.25446546078,24.000120163 --9.21479225159,1.25548398495,23.993724823 --9.2917509079,1.2555013895,23.9683303833 --9.41168689728,1.2565279007,23.9397335052 --9.5616235733,1.26855552197,24.0993461609 --9.70356273651,1.27858185768,24.2339572906 --9.74553203583,1.27359390259,24.1195602417 --9.83048820496,1.27461194992,24.110162735 --9.94243621826,1.27963376045,24.165769577 --9.98640441895,1.27564609051,24.0563697815 --9.94840717316,1.26364374161,23.8601665497 --10.0443601608,1.26766312122,23.8777751923 --10.1373138428,1.26968193054,23.888381958 --10.2422657013,1.27370238304,23.9259910583 --13.1793670654,1.67011797428,30.2865581512 --13.1543655396,1.66011667252,30.0993537903 --13.1653442383,1.64812290668,29.8669528961 --13.1123428345,1.62812042236,29.4925422668 --13.0983285904,1.61312305927,29.2141437531 --13.0913133621,1.60012674332,28.9527416229 --13.0793008804,1.58512973785,28.6833362579 --13.0732841492,1.57213354111,28.4309329987 --13.0222911835,1.55912899971,28.2037277222 --13.0082778931,1.54613173008,27.941324234 --12.9972629547,1.53213489056,27.6879196167 --12.9902477264,1.52013850212,27.4465179443 --12.9842329025,1.50814223289,27.2101135254 --12.9752187729,1.49514555931,26.9727134705 --12.9602050781,1.48214817047,26.7243080139 --12.8962154388,1.46914196014,26.4840965271 --12.9691762924,1.4671561718,26.4217033386 --13.0571346283,1.46817219257,26.3913173676 --9.05327129364,0.947653949261,18.1193237305 --9.0852432251,0.944664239883,18.0399208069 --9.14021015167,0.944677472115,18.0075244904 --9.16119480133,0.943683207035,17.9793281555 --9.221159935,0.944697082043,17.9549255371 --9.28612232208,0.945711433887,17.9435329437 --9.34708690643,0.945725262165,17.9221363068 --9.42904567719,0.948741614819,17.9407444 --9.5299987793,0.954760432243,17.9953556061 --12.7500610352,1.33717477322,23.9304542542 --12.708065033,1.32717168331,23.7602462769 --12.7080478668,1.31817615032,23.5798435211 --12.6960344315,1.30817890167,23.3804397583 --12.7000160217,1.29918396473,23.2120380402 --12.7899742126,1.3011995554,23.2016487122 --12.8419427872,1.29921030998,23.1242580414 --12.8619203568,1.29321706295,22.9878578186 --12.9248943329,1.2962269783,23.0156669617 --13.0468425751,1.30224633217,23.0622844696 --13.1687917709,1.3072655201,23.1089038849 --13.319732666,1.31628799438,23.2035274506 --13.3976945877,1.31730151176,23.1701393127 --13.4816551208,1.3183157444,23.1467533112 --13.5686225891,1.32432818413,23.2115631104 --13.8105373383,1.34336137772,23.4562034607 --13.8115215302,1.33436512947,23.2888011932 --13.8434963226,1.33037269115,23.1754055023 --12.5568408966,1.18022251129,20.8597869873 --12.5578231812,1.17322671413,20.7143878937 --12.5528087616,1.16623044014,20.5579833984 --12.5717954636,1.16423487663,20.5157852173 --12.6447591782,1.16524755955,20.4893951416 --12.7227201462,1.16626083851,20.4710063934 --12.8176774979,1.17027616501,20.4796218872 --12.7916688919,1.16027700901,20.2932109833 --12.7206716537,1.14627289772,20.0397987366 --12.6706705093,1.13427114487,19.8213882446 --12.6176767349,1.12526702881,19.669178009 --12.6446533203,1.12127423286,19.5737781525 --12.7596054077,1.12729120255,19.617401123 --12.8545637131,1.13030612469,19.6270141602 --12.5436325073,1.09227466583,19.0185585022 --12.5856056213,1.09028351307,18.9501590729 --12.5835971832,1.08728528023,18.8819599152 --12.5375938416,1.07628393173,18.6845493317 --12.6615438461,1.08330190182,18.7421741486 --12.5755519867,1.06829619408,18.4867515564 --12.4155797958,1.04628241062,18.1263198853 --12.4465551376,1.04428982735,18.0489253998 --12.5355148315,1.0473035574,18.0555381775 --12.5185117722,1.04230368137,17.9693336487 --12.6524591446,1.05032217503,18.0409564972 --12.5544710159,1.03531515598,17.780538559 --12.6174373627,1.03532588482,17.7501487732 --12.5934276581,1.02832710743,17.5977420807 --12.5454263687,1.01732575893,17.4133300781 --12.4894247055,1.00732350349,17.2189159393 --12.451426506,1.00032138824,17.1087055206 --12.4564094543,0.996325790882,17.0013027191 --12.3824148178,0.983321785927,16.7878856659 --12.3963947296,0.980327069759,16.6954879761 --12.3423938751,0.970325231552,16.5130748749 --12.2873926163,0.96032333374,16.3296604156 --12.2463874817,0.951322853565,16.1682510376 --12.2173881531,0.94632178545,16.0770454407 --12.2153720856,0.941325426102,15.9676389694 --8.91722869873,0.628992915154,11.5465278625 --8.95020294189,0.629001736641,11.5131263733 --8.97917842865,0.628010034561,11.4757318497 --9.02215099335,0.629019677639,11.4563388824 --12.2672891617,0.925347566605,15.5698394775 --12.2952671051,0.923354029655,15.5044460297 --12.402223587,0.928368330002,15.539068222 --12.5241756439,0.935383975506,15.5896854401 --12.5251607895,0.931387543678,15.4902858734 --12.4341697693,0.918382227421,15.2768630981 --12.5841150284,0.927400290966,15.3624925613 --12.7680597305,0.941419839859,15.5393352509 --12.8880138397,0.948434710503,15.5849590302 --12.9219903946,0.946441233158,15.5255651474 --12.9189767838,0.942444145679,15.4221630096 --13.108912468,0.954465329647,15.5487976074 --12.2301244736,0.873385488987,14.4062070847 --12.2201118469,0.868388056755,14.3018016815 --12.2031087875,0.864388227463,14.2345914841 --12.1910972595,0.859390616417,14.1291866302 --12.2030792236,0.857395172119,14.0527877808 --13.5587177277,0.970523357391,15.5276927948 --13.6426820755,0.97353374958,15.5253124237 --13.8626127243,0.98855638504,15.6769628525 --12.1850233078,0.840407371521,13.6761741638 --12.2569980621,0.844415545464,13.7139911652 --20.5508861542,1.54616224766,22.9344787598 --12.1799869537,0.83041536808,13.453166008 --12.1579790115,0.82541680336,13.342757225 --20.7538032532,1.54517638683,22.7243442535 --12.1679468155,0.819424271584,13.1849584579 --12.0159778595,0.804412782192,12.9767189026 --11.9839706421,0.798413395882,12.8593082428 --11.9779577255,0.794416248798,12.7709035873 --11.9779424667,0.791419625282,12.6895008087 --11.981926918,0.788423359394,12.6131000519 --12.0688905716,0.792433977127,12.6247177124 --12.1188640594,0.793441474438,12.5963249207 --12.1138572693,0.791442632675,12.5511226654 --12.1048460007,0.787445068359,12.4627218246 --12.1078310013,0.784448564053,12.3863182068 --12.0958194733,0.780450761318,12.2949113846 --12.089805603,0.776453435421,12.2105073929 --12.1027889252,0.774457633495,12.1471128464 --12.0947761536,0.770460128784,12.0617074966 --12.08477211,0.768460869789,12.0124998093 --12.0677614212,0.763462603092,11.919093132 --12.0757446289,0.761466383934,11.8506889343 --12.0647335052,0.7574685812,11.765288353 --12.0687189102,0.755471885204,11.6948900223 --12.0587072372,0.751474261284,11.6104831696 --12.0636911392,0.748477637768,11.5410804749 --12.0416898727,0.745477497578,11.482872963 --12.0466747284,0.743480861187,11.4144697189 --12.0346641541,0.739482939243,11.3310689926 --12.0436468124,0.73748666048,11.2666654587 --12.0426330566,0.734489500523,11.1942644119 --12.0356206894,0.731491923332,11.1158571243 --12.0266094208,0.727494180202,11.0364522934 --12.0106058121,0.725494503975,10.986246109 --12.014591217,0.722497701645,10.9198455811 --12.016576767,0.720500707626,10.8524465561 --12.0125637054,0.71750330925,10.7790403366 --12.0115509033,0.714506149292,10.7086353302 --12.0095367432,0.712508797646,10.6382322311 --11.9965333939,0.709509253502,10.5930309296 --11.9865217209,0.706511437893,10.515622139 --11.9855089188,0.704514145851,10.4472198486 --11.9814958572,0.70151668787,10.3768177032 --11.9844818115,0.698519647121,10.3124141693 --11.9754705429,0.695521712303,10.2390146255 --11.9734573364,0.693524360657,10.1706075668 --11.9604530334,0.691524922848,10.1264019012 --11.9594402313,0.688527584076,10.0599975586 --11.9614267349,0.686530411243,9.99659538269 --11.9564142227,0.683532774448,9.92718791962 --11.9504013062,0.680534958839,9.85879039764 --11.949388504,0.678537547588,9.79438972473 --11.9453763962,0.676539897919,9.72698402405 --11.9283733368,0.673540234566,9.68077373505 --11.9283599854,0.671542823315,9.61736965179 --11.9263477325,0.669545292854,9.55296611786 --11.9303331375,0.667548060417,9.49356269836 --11.9213218689,0.664550125599,9.42516422272 --11.9213094711,0.662552595139,9.3637638092 --11.9212961197,0.659555196762,9.30135440826 --11.9012928009,0.657555222511,9.25514888763 --11.8992805481,0.655557632446,9.19274616241 --11.8962678909,0.652559936047,9.12934017181 --11.8932561874,0.650562226772,9.06693744659 --11.8962421417,0.648564815521,9.00953769684 --11.8902311325,0.646566927433,8.94513225555 --11.9472055435,0.648572325706,8.9287443161 --12.0311813354,0.653577923775,8.96357440948 --5.47156572342,0.187241494656,3.9670522213 --5.45955038071,0.185247436166,3.93063497543 --5.4915266037,0.186255514622,3.9272351265 --11.8601541519,0.631580650806,8.54250907898 --11.8601417542,0.629582941532,8.48409938812 --11.8471374512,0.627583444118,8.44690132141 --11.8481245041,0.625585734844,8.39049816132 --11.847111702,0.623587965965,8.33309555054 --11.8480997086,0.622590243816,8.27668952942 --11.8400888443,0.61959207058,8.21528816223 --11.8430757523,0.618594408035,8.16088294983 --11.8250722885,0.616594612598,8.120677948 --11.8250598907,0.614596843719,8.06426811218 --11.8210487366,0.612598836422,8.0068693161 --11.8220367432,0.610600948334,7.95246648788 --11.819024086,0.608603000641,7.89506006241 --11.824010849,0.607605218887,7.84466409683 --11.8159999847,0.605606973171,7.7842540741 --11.8049964905,0.603607594967,7.75005102158 --11.7999849319,0.601609408855,7.69264554977 --11.7979736328,0.599611401558,7.63723993301 --11.7969608307,0.597613275051,7.58384227753 --11.7979488373,0.596615374088,7.53043365479 --11.7949371338,0.594617187977,7.47603464127 --11.793926239,0.59261906147,7.42263221741 --11.7799215317,0.591619551182,7.38742637634 --11.7769107819,0.589621424675,7.33302259445 --11.7728996277,0.587623119354,7.27862119675 --11.7778863907,0.586625218391,7.22921609879 --11.7598781586,0.583626449108,7.16580438614 --11.7558679581,0.581628203392,7.11240530014 --11.742857933,0.579629540443,7.05299711227 --11.7418527603,0.578630447388,7.02679538727 --11.7408399582,0.577632308006,6.97438526154 --11.7418289185,0.575634121895,6.92498922348 --11.7488155365,0.574636042118,6.87858915329 --11.7368068695,0.572637438774,6.82118320465 --11.7277965546,0.570638895035,6.76477003098 --11.7487812042,0.570641219616,6.72737646103 --11.7317781448,0.568641543388,6.69317531586 --11.7307662964,0.567643225193,6.64277076721 --11.7387533188,0.566645145416,6.59736680984 --11.7267446518,0.564646422863,6.54095888138 --11.7247333527,0.562647998333,6.49156284332 --11.7267217636,0.561649680138,6.44315624237 --11.7127180099,0.559650063515,6.41095066071 --11.7487010956,0.560652434826,6.38256216049 --11.7916812897,0.562654972076,6.35717010498 --11.8066673279,0.561656713486,6.31677293777 --11.8026571274,0.560658037663,6.26637125015 --11.7996463776,0.558659434319,6.21596479416 --11.8956184387,0.563662648201,6.21959781647 --11.9576015472,0.567664444447,6.22841739655 --12.0395765305,0.571667134762,6.22304105759 --12.089556694,0.572669148445,6.20065689087 --12.2365217209,0.581672668457,6.22931098938 --12.2765035629,0.582674264908,6.19991588593 --12.2734937668,0.580675125122,6.14951562881 --12.4994440079,0.593679189682,6.21619558334 --12.2704782486,0.578676402569,6.07491493225 --16.7867012024,0.863737046719,8.30709838867 --16.8346862793,0.865735113621,8.26471805573 --16.9026679993,0.867733299732,8.23133945465 --16.9316577911,0.867730975151,8.17995738983 --12.2354326248,0.570680081844,5.814889431 --12.2524204254,0.570680975914,5.77549552917 --12.2424163818,0.569681286812,5.74628686905 --12.2314081192,0.567681908607,5.69287776947 --12.3943719864,0.576683819294,5.72354078293 --17.2645664215,0.878714561462,7.90748929977 --14.7999572754,0.722698032856,6.69620513916 --14.7599563599,0.719696521759,6.62078905106 --14.6739654541,0.713695466518,6.55356121063 --14.6079683304,0.707693934441,6.46713542938 --14.542971611,0.702692508698,6.38271570206 --14.4699745178,0.696691095829,6.29428577423 --14.3919801712,0.690689682961,6.2048573494 --14.3109846115,0.684688508511,6.11543178558 --14.2499856949,0.679687321186,6.03400230408 --14.1769933701,0.674686789513,5.9757771492 --14.0989980698,0.668685853481,5.88935089111 --14.029999733,0.662684857845,5.80692338943 --11.7013320923,0.517692327499,4.7252368927 --11.7013225555,0.51669305563,4.6818356514 --11.6183242798,0.510694265366,4.60440301895 --11.5943231583,0.509694695473,4.57319355011 --11.5723161697,0.506695628166,4.52178573608 --11.5943031311,0.507696211338,4.48738622665 --11.5772953033,0.505697011948,4.437977314 --11.5952835083,0.505697488785,4.40258169174 --11.6002731323,0.504698097706,4.36218118668 --11.588265419,0.503698825836,4.31577968597 --11.5822610855,0.502699196339,4.2915687561 --11.5872507095,0.50269973278,4.25116634369 --11.5712442398,0.500700473785,4.20376443863 --11.5752334595,0.499700963497,4.16336297989 --11.5772237778,0.499701440334,4.12195777893 --11.5662164688,0.497702091932,4.0765542984 --11.5652112961,0.497702360153,4.055352211 --11.5672016144,0.49670279026,4.01394510269 --11.5561943054,0.494703412056,3.96853780746 --11.5581846237,0.494703769684,3.92813801765 --11.5611753464,0.493704110384,3.88773441315 --11.547167778,0.492704719305,3.84132242203 --11.5501585007,0.491705030203,3.80192685127 --11.5551528931,0.491705060005,3.7827231884 --11.5371465683,0.489705771208,3.73530960083 --11.5471363068,0.48970580101,3.69892096519 --11.5231304169,0.487706631422,3.64950156212 --11.41913414,0.480709433556,3.575060606 --11.3971271515,0.47871029377,3.52764725685 --11.3931188583,0.477710694075,3.48624134064 --11.4061136246,0.478710472584,3.47105073929 --11.4041042328,0.477710783482,3.42963814735 --11.4140939713,0.477710723877,3.39324164391 --11.3920888901,0.475711554289,3.34683156013 --11.4030780792,0.475711405277,3.31043124199 --11.3880710602,0.473711997271,3.26601910591 --11.3960618973,0.473711878061,3.22962594032 --11.3880577087,0.472712188959,3.2074201107 --11.3910493851,0.472712159157,3.16901874542 --11.3750429153,0.470712780952,3.12460398674 --11.3810329437,0.470712602139,3.08720374107 --11.3760251999,0.469712764025,3.04679989815 --11.384016037,0.469712466002,3.01040387154 --11.3790082932,0.468712598085,2.96999835968 --11.3680057526,0.467712968588,2.94779491425 --11.3739967346,0.467712670565,2.91039228439 --11.3569898605,0.465713262558,2.86698150635 --11.365981102,0.465712755919,2.83058071136 --11.3369760513,0.463713794947,2.78416323662 --11.3599653244,0.464712649584,2.75177097321 --11.3699607849,0.464712113142,2.73557877541 --11.3399553299,0.462713211775,2.68915939331 --11.3099498749,0.460714310408,2.64374804497 --11.3369398117,0.461712837219,2.61134672165 --11.3669290543,0.462711155415,2.58096170425 --11.3989181519,0.463709294796,2.55057358742 --11.4229078293,0.464707702398,2.51818299294 --11.4598970413,0.466705441475,2.48778772354 --11.4818906784,0.467704057693,2.47359442711 --11.5308799744,0.469701051712,2.44722104073 --11.4258813858,0.463705837727,2.38477063179 --11.4278736115,0.462705165148,2.34737157822 --11.6548395157,0.475691586733,2.31965732574 --11.6898288727,0.47668877244,2.28826880455 --11.7018251419,0.477687686682,2.27207946777 --11.7348155975,0.478684812784,2.23968648911 --11.7708063126,0.480681747198,2.20830059052 --11.7977962494,0.481679052114,2.17491078377 --11.8367872238,0.483675599098,2.14352369308 --11.8637781143,0.484672784805,2.1101372242 --11.8887739182,0.485670596361,2.0949420929 --11.9447631836,0.48866584897,2.06656551361 --11.9637556076,0.489663273096,2.03117513657 --12.0057458878,0.491659164429,1.99979329109 --12.0327386856,0.492655873299,1.96540427208 --12.0867290497,0.494650751352,1.93502104282 --12.1147212982,0.496647238731,1.90063393116 --12.1497154236,0.497644007206,1.88644468784 --12.1837081909,0.499639928341,1.85306334496 --12.2206993103,0.501635551453,1.81968021393 --12.2566919327,0.50363111496,1.78529024124 --12.2886838913,0.504626810551,1.74989700317 --12.3276767731,0.50662201643,1.71651768684 --12.3616695404,0.508617460728,1.68213582039 --12.3976650238,0.50961369276,1.66694581509 --12.4846544266,0.514604926109,1.63958323002 --12.5676450729,0.518596351147,1.61122024059 --12.6006393433,0.520591378212,1.57482981682 --12.639632225,0.522585749626,1.53944587708 --12.6726255417,0.524580597878,1.50305938721 --12.7116203308,0.525574803352,1.467679739 --12.7456159592,0.527570664883,1.45149350166 --12.7906093597,0.530564248562,1.41611254215 --12.8296041489,0.531558156013,1.37972939014 --12.8575992584,0.533552825451,1.34234595299 --12.9125928879,0.536545157433,1.3069653511 --12.9485874176,0.537538945675,1.26958096027 --12.982583046,0.539532899857,1.23219966888 --13.018579483,0.541528105736,1.21501278877 --13.0625743866,0.543520927429,1.17762947083 --13.1045694351,0.545513749123,1.14024949074 --13.1365661621,0.547507405281,1.10186719894 --13.1785612106,0.549499988556,1.06348216534 --13.2245559692,0.552492082119,1.02509760857 --13.2635526657,0.554484724998,0.986718595028 --13.2915506363,0.555480241776,0.968536376953 --12.1155872345,0.488586962223,0.823566257954 --12.2115802765,0.493575155735,0.793214440346 --13.3355417252,0.557464182377,0.84435147047 --12.2735710144,0.497563391924,0.720445156097 --12.256567955,0.495562106371,0.680035591125 --12.2835626602,0.497556358576,0.642644643784 --12.0675668716,0.485576361418,0.607330739498 --13.6095275879,0.572417855263,0.670675635338 --13.6465244293,0.574409484863,0.629289507866 --12.1595544815,0.48955821991,0.498177736998 --12.1955509186,0.491551339626,0.460786193609 --12.564540863,0.512509346008,0.441563904285 --13.6295213699,0.572392463684,0.454678118229 --12.7495346069,0.522484183311,0.391056835651 --12.1025409698,0.486550211906,0.321340322495 --12.126537323,0.487544298172,0.282940655947 --12.1055355072,0.486543357372,0.243527978659 --12.0895328522,0.485541880131,0.205125033855 --12.1105289459,0.486536175013,0.166726589203 --12.1025276184,0.485535383224,0.14752484858 --12.1055250168,0.485531657934,0.109124153852 --12.1045217514,0.485528349876,0.0707225501537 --12.1115198135,0.48652407527,0.032322883606 --12.1085176468,0.485520899296,-0.00607904279605 --12.104514122,0.485517829657,-0.0444818511605 --12.103512764,0.485514372587,-0.0828837901354 --12.1075115204,0.485512077808,-0.102082952857 --12.0955085754,0.485509872437,-0.14048974216 --12.091506958,0.484506577253,-0.179903835058 --12.1115045547,0.486500382423,-0.218296214938 --12.1355028152,0.487493604422,-0.256684750319 --12.1055011749,0.485493481159,-0.295102089643 --12.0654983521,0.483494758606,-0.332517027855 --11.9314956665,0.475509881973,-0.350790292025 --12.0524950027,0.482490599155,-0.390129715204 --12.0914945602,0.485481530428,-0.429517090321 --12.1304931641,0.487472504377,-0.467890948057 --12.1194915771,0.486469864845,-0.506299555302 --12.0904893875,0.48546949029,-0.544723331928 --12.1074886322,0.48646312952,-0.583111107349 --12.1134881973,0.486460149288,-0.603317141533 --12.1114864349,0.486456185579,-0.641719698906 --12.1084861755,0.486452311277,-0.680123269558 --12.1064844131,0.486448258162,-0.718526005745 --12.1034841537,0.486444294453,-0.756929695606 --12.0974826813,0.486440718174,-0.795336604118 --12.4284925461,0.504389226437,-0.849561452866 --12.0884809494,0.485435366631,-0.851936578751 --12.5034952164,0.509371042252,-0.913127064705 --14.2295598984,0.607115745544,-1.05063128471 --14.1965618134,0.605113387108,-1.09404921532 --14.1615638733,0.60311126709,-1.13747131824 --14.4375782013,0.619063079357,-1.20072722435 --14.115568161,0.601103723049,-1.2242937088 --14.1765727997,0.604090869427,-1.25146496296 --14.1095724106,0.60109359026,-1.29190194607 --14.0755748749,0.599091470242,-1.33432006836 --14.0765781403,0.599084019661,-1.37871432304 --14.0445804596,0.598081588745,-1.42113280296 --14.0045814514,0.596080362797,-1.46255421638 --14.2075967789,0.607040822506,-1.52584981918 --13.9375829697,0.592079818249,-1.52318620682 --13.9765892029,0.595066189766,-1.57156682014 --14.0225954056,0.598051190376,-1.62094402313 --14.0335998535,0.598041653633,-1.66734147072 --14.4816331863,0.6239605546,-1.75950860977 --14.5776453018,0.62993645668,-1.81585407257 --14.5376472473,0.627934515476,-1.85827565193 --16.4497795105,0.7366117239,-2.0964653492 --16.7408084869,0.753551840782,-2.18270850182 --16.7208175659,0.752543747425,-2.2341170311 --16.8118343353,0.757516801357,-2.29846310616 --16.4918212891,0.740559875965,-2.31303477287 --16.2848129272,0.728584349155,-2.33954238892 --16.2698173523,0.728581428528,-2.36374926567 --16.268825531,0.728570342064,-2.41614866257 --16.4418487549,0.738528549671,-2.49245619774 --16.2488441467,0.728551387787,-2.51795268059 --16.1018390656,0.720566272736,-2.54942941666 --16.2578639984,0.729526817799,-2.62474751472 --16.1698665619,0.724531233311,-2.66419243813 --16.2128734589,0.727517783642,-2.69636464119 --14.6837434769,0.640786767006,-2.51358938217 --14.7177534103,0.642770767212,-2.5669734478 --14.7577648163,0.64575356245,-2.62135267258 --14.8717832565,0.652722299099,-2.687687397 --16.305934906,0.7354413867,-2.97530674934 --16.7339897156,0.76034784317,-3.10147404671 --14.2357387543,0.61781835556,-2.70003724098 --14.6037845612,0.63873809576,-2.81123805046 --14.5817890167,0.637732446194,-2.8546462059 --14.3757743835,0.626762628555,-2.86516070366 --14.6618146896,0.64369648695,-2.96540570259 --14.6288194656,0.642692863941,-3.00681972504 --15.0818796158,0.668592274189,-3.14197301865 --13.7937383652,0.595839619637,-2.94108605385 --13.7857398987,0.594836592674,-2.96229100227 --13.6707410812,0.589841365814,-3.03015828133 --13.657746315,0.588834822178,-3.07256507874 --13.5257368088,0.581852793694,-3.09003853798 --13.4817371368,0.579852759838,-3.12546372414 --13.5077447891,0.581842660904,-3.15365195274 --13.5707607269,0.585820138454,-3.2120153904 --13.6587791443,0.591792047024,-3.27636504173 --13.4687614441,0.580822885036,-3.27987790108 --14.8239555359,0.660522401333,-3.63251280785 --13.5247840881,0.585791766644,-3.38264775276 --13.2117471695,0.567850351334,-3.35422205925 --13.1717453003,0.565854370594,-3.36744999886 --13.1657514572,0.565846502781,-3.40985131264 --13.2237682343,0.56982421875,-3.46822047234 --13.1897697449,0.568822264671,-3.50464391708 --13.1637735367,0.567818760872,-3.54205489159 --13.0777692795,0.563828468323,-3.56551218033 --13.0287675858,0.560830175877,-3.59693932533 --12.9677619934,0.557839393616,-3.60317397118 --12.9337654114,0.556837677956,-3.63859820366 --13.0757961273,0.5657954216,-3.71991753578 --13.3288450241,0.580727040768,-3.8311650753 --13.2958478928,0.579724550247,-3.86758518219 --13.3228626251,0.581707775593,-3.92097663879 --13.1118345261,0.570747613907,-3.90749597549 --13.1078386307,0.570743560791,-3.92869830132 --13.1038475037,0.570734202862,-3.97310733795 --13.4359140396,0.590644180775,-4.11230945587 --13.4889335632,0.594620585442,-4.17367839813 --13.5199489594,0.597601890564,-4.23006916046 --13.5419635773,0.599585533142,-4.28245067596 --13.5559768677,0.60057079792,-4.33384656906 --13.4559631348,0.59558993578,-4.32710552216 --13.4369697571,0.594583630562,-4.36751365662 --13.5309991837,0.601548552513,-4.44386577606 --13.6650362015,0.609503388405,-4.53218364716 --13.7200584412,0.614477515221,-4.59755563736 --13.6890640259,0.613473713398,-4.6349697113 --13.7390851974,0.616448760033,-4.69934415817 --13.8431129456,0.623416006565,-4.75647783279 --13.9731521606,0.632369816303,-4.84780359268 --13.9431591034,0.631364941597,-4.88722372055 --16.4156894684,0.778702557087,-5.76115512848 --16.3696994781,0.776697814465,-5.80358123779 --16.4467353821,0.782660484314,-5.88793563843 --16.7178134918,0.799570918083,-6.03917074203 --16.7968406677,0.804540812969,-6.09632444382 --17.6570529938,0.857290506363,-6.45721530914 --17.7540969849,0.864244699478,-6.55455636978 --17.7961292267,0.868213534355,-6.63292884827 --20.2337093353,1.01452338696,-7.57387304306 --19.9986858368,1.00256454945,-7.56040525436 --19.9096946716,0.99856543541,-7.59985589981 --19.7686767578,0.990592718124,-7.58414077759 --17.3021221161,0.843262553215,-6.73500537872 --17.2271270752,0.84026414156,-6.76944923401 --17.1841411591,0.839256763458,-6.81587505341 --17.1641597748,0.839242994785,-6.87028312683 --17.135175705,0.838231623173,-6.92169952393 --19.8318748474,1.00243103504,-8.03747081757 --19.7988815308,1.00142836571,-8.0606880188 --19.5628528595,0.988472878933,-8.03922367096 --19.1947898865,0.967556416988,-7.9648475647 --20.2931060791,1.03620815277,-8.47757530212 --20.3831634521,1.04315555096,-8.58891487122 --20.3771953583,1.04413104057,-8.66231632233 --19.022851944,0.962524592876,-8.14033126831 --20.4922771454,1.05405688286,-8.82283592224 --20.5093173981,1.05602490902,-8.9062204361 --20.3723144531,1.0490398407,-8.92469882965 --18.8499298096,0.958480775356,-8.35002326965 --18.8059482574,0.956469833851,-8.40244960785 --18.5769138336,0.944516956806,-8.3729839325 --18.6119403839,0.947494089603,-8.42316055298 --18.8460388184,0.963396430016,-8.59641265869 --18.7210350037,0.95741122961,-8.61188411713 --18.6860561371,0.956397593021,-8.66730213165 --18.5950622559,0.95240175724,-8.69775772095 --18.4340457916,0.944428741932,-8.69525337219 --18.5261077881,0.951374530792,-8.80759048462 --18.5811405182,0.956344127655,-8.86875629425 --18.5231552124,0.954337954521,-8.91318798065 --18.4801750183,0.953326821327,-8.96461296082 --18.5552310944,0.959277033806,-9.07096004486 --19.1274452209,0.997061669827,-9.41600131989 --19.0894699097,0.996047437191,-9.47242355347 --21.5372886658,1.15119981766,-10.7322921753 --20.8760967255,1.11040616035,-10.4529018402 --20.8391284943,1.11038851738,-10.5153131485 --20.8061580658,1.11036872864,-10.5817317963 --22.0486125946,1.18991291523,-11.2823486328 --22.0026435852,1.18989551067,-11.3457679749 --21.6385669708,1.1689876318,-11.2493934631 --21.1114330292,1.1371383667,-11.066116333 --21.1014518738,1.13812577724,-11.1033201218 --20.8844223022,1.12616956234,-11.0758523941 --20.9865016937,1.13510167599,-11.2121801376 --25.2830543518,1.40954375267,-13.5468635559 --36.5931167603,2.13146519661,-19.6161289215 --23.8076438904,1.32099056244,-12.9665784836 --23.8127307892,1.32493054867,-13.1141624451 --23.731754303,1.32292091846,-13.1676063538 --23.8928718567,1.33582293987,-13.3518924713 --37.3219146729,2.19983720779,-20.8357601166 --38.2463607788,2.26342654228,-21.5015525818 --36.7639083862,2.1719083786,-20.8318729401 --36.7410011292,2.17484927177,-20.9712677002 --36.7410507202,2.1768155098,-21.0474567413 --35.0765075684,2.07337617874,-20.2538986206 --34.9565582275,2.0693564415,-20.332359314 --34.8536148071,2.06733107567,-20.418806076 --34.7416687012,2.06430864334,-20.5012607574 --34.6217193604,2.06028985977,-20.5767173767 --34.508769989,2.05726766586,-20.6581764221 --34.4397888184,2.05426263809,-20.6894073486 --34.323841095,2.05124211311,-20.7678661346 --34.2128944397,2.04822015762,-20.8483200073 --34.2950248718,2.05712151527,-21.0446510315 --34.4221801758,2.0700044632,-21.2699508667 --34.5653381348,2.08387994766,-21.5072422028 --34.7245101929,2.09874796867,-21.7555198669 --37.6838264465,2.29651832581,-23.6637916565 --36.375377655,2.2149746418,-23.0120182037 --37.5289916992,2.29643011093,-23.8966503143 --35.5902557373,2.1721508503,-22.8352928162 --35.2712211609,2.15521073341,-22.7898845673 --35.3583679199,2.16610264778,-23.0022087097 --35.3144035339,2.16508507729,-23.0524272919 --35.2494850159,2.1660399437,-23.1678524017 --35.4136695862,2.18189811707,-23.4331264496 --32.772567749,2.00894379616,-21.8572406769 --32.6556167603,2.00592565536,-21.9287052155 --32.5346641541,2.00190997124,-21.9961681366 --32.3947029114,1.9969022274,-22.0506458282 --32.3027076721,1.99290800095,-22.0628986359 --32.1947593689,1.99088728428,-22.1373519897 --32.2428855896,1.99879813194,-22.3187065125 --32.3300323486,2.00869107246,-22.5280342102 --34.3061027527,2.14874863625,-24.0451087952 --34.2461853027,2.14970064163,-24.1635322571 --33.9761657715,2.13674616814,-24.1350955963 --33.9672203064,2.13871383667,-24.2072887421 --34.0543785095,2.1495988369,-24.4306182861 --34.0825119019,2.15651059151,-24.6119823456 --35.4043006897,2.25283265114,-25.7224826813 --35.2923660278,2.25080442429,-25.8099365234 --35.2034416199,2.2507648468,-25.9153804779 --33.7908287048,2.15733885765,-25.0517101288 --34.0250091553,2.17619132996,-25.3057441711 --33.7499885559,2.16324138641,-25.2683143616 --33.0997619629,2.12246918678,-24.9491348267 --32.611618042,2.09362316132,-24.745847702 --32.6667671204,2.10352110863,-24.9481945038 --32.9150161743,2.12632608414,-25.298412323 --33.7315864563,2.18985629082,-26.0852432251 --32.9982414246,2.1401693821,-25.6079311371 --32.9693489075,2.14410471916,-25.7513370514 --32.8434028625,2.14108705521,-25.8198070526 --34.1372528076,2.23837423325,-26.9963130951 --32.6385307312,2.13702893257,-25.9917144775 --32.5876274109,2.13897442818,-26.1181335449 --32.4236526489,2.13397598267,-26.1546325684 --32.5117683411,2.14289164543,-26.3097648621 --32.2417373657,2.12894678116,-26.2603340149 --32.1598129272,2.12890768051,-26.3617763519 --32.07188797,2.12887167931,-26.4582233429 --32.1300506592,2.13876080513,-26.6745681763 --32.0821495056,2.14170360565,-26.8049869537 --31.7460727692,2.1227953434,-26.695602417 --31.7291259766,2.12476348877,-26.7658061981 --31.9884128571,2.14954638481,-27.1530132294 --31.2701015472,2.10283875465,-26.7198963165 --31.8766059875,2.15343785286,-27.4038639069 --31.6035671234,2.13949847221,-27.3434391022 --31.5396575928,2.14144873619,-27.4608669281 --32.5454330444,2.22282576561,-28.5055580139 --30.932466507,2.10564780235,-27.1948719025 --30.8635540009,2.10660147667,-27.3063049316 --30.8296642303,2.11053657532,-27.4477138519 --30.8518104553,2.11844038963,-27.6400852203 --31.2502098083,2.15513658524,-28.1691970825 --30.5899047852,2.11241436005,-27.7550449371 --30.3819007874,2.10244464874,-27.7415771484 --28.1154403687,1.93466341496,-25.7793617249 --28.0174980164,1.93263995647,-25.8518180847 --27.9315624237,1.93261003494,-25.9342670441 --27.8376235962,1.9315841198,-26.0107250214 --27.7446842194,1.93055784702,-26.087179184 --27.6627521515,1.9305254221,-26.173625946 --27.6117782593,1.92951524258,-26.2068557739 --27.5188388824,1.9284889698,-26.2833118439 --27.4188976288,1.92746627331,-26.3537750244 --27.3239555359,1.92644095421,-26.428232193 --24.3989639282,1.70507872105,-23.7836952209 --24.1869239807,1.6941318512,-23.7282409668 --24.065946579,1.69013273716,-23.7577171326 --23.9549789429,1.68812704086,-23.7981948853 --23.9310188293,1.68910574913,-23.848405838 --23.8500709534,1.68808269501,-23.9168567657 --23.7391014099,1.68507790565,-23.955329895 --23.6671638489,1.68504929543,-24.0327739716 --23.5972232819,1.68601942062,-24.1122188568 --23.5192813873,1.68499445915,-24.1836681366 --23.490316391,1.68597590923,-24.2288837433 --23.4033641815,1.68495595455,-24.2923431396 --23.338432312,1.68592321873,-24.3757820129 --23.2694950104,1.68689262867,-24.4562244415 --23.1935539246,1.68686616421,-24.5296726227 --23.0965938568,1.68485295773,-24.5811386108 --23.0236549377,1.68482410908,-24.6585865021 --22.9876861572,1.68480992317,-24.6968097687 --21.027759552,1.56064879894,-23.4846076965 --20.8106307983,1.54475784302,-23.3179607391 --20.3705921173,1.52684020996,-23.2654743195 --20.2846317291,1.52482819557,-23.3129329681 --20.2527179718,1.52877819538,-23.4233531952 --20.1697597504,1.5277633667,-23.4758110046 --20.1367893219,1.52774977684,-23.5120372772 --20.0708465576,1.5287232399,-23.583480835 --20.0049037933,1.52869617939,-23.6559276581 --18.7598781586,1.42750048637,-22.3462409973 --18.475725174,1.40963292122,-22.1528511047 --18.1475276947,1.38679921627,-21.9024906158 --17.8713779449,1.36892950535,-21.7120952606 --17.7162837982,1.35800802708,-21.5944080353 --17.6353149414,1.35699999332,-21.6338691711 --17.5723628998,1.35697925091,-21.6943149567 --17.5134143829,1.35795497894,-21.760761261 --17.4474582672,1.3579365015,-21.8172073364 --17.3915138245,1.35891020298,-21.8866500854 --17.3695449829,1.3598921299,-21.9298667908 --17.3085956573,1.3608700037,-21.9923095703 --17.2516498566,1.36184418201,-22.060749054 --17.1957054138,1.36281740665,-22.131193161 --17.1337547302,1.36279475689,-22.1946411133 --17.0878219604,1.36476051807,-22.2770729065 --17.0338821411,1.36673080921,-22.352519989 --16.9639225006,1.36671507359,-22.403968811 --17.0901126862,1.38158142567,-22.6400737762 --16.8890190125,1.36866676807,-22.5226249695 --15.5216884613,1.24867153168,-20.8660583496 --15.4306974411,1.24667811394,-20.8795280457 --15.159620285,1.23276281357,-20.7865371704 --15.1346464157,1.23375022411,-20.8197536469 --15.0646762848,1.23274052143,-20.8602104187 --15.0117273331,1.23371720314,-20.9236526489 --14.9617815018,1.23569095135,-20.9920940399 --14.8327465057,1.22973001003,-20.950592041 --16.3545780182,1.38239836693,-23.2108402252 --16.2936325073,1.38337349892,-23.2772846222 --16.2816829681,1.38534510136,-23.3374958038 --16.2177333832,1.38632249832,-23.3999443054 --12.0690374374,0.987768411636,-17.6325206757 --11.8759021759,0.974877476692,-17.4720745087 --11.3496761322,0.946086466312,-17.2223052979 --11.3007040024,0.946075558662,-17.2627410889 --11.244726181,0.946069717407,-17.2951908112 --11.2027645111,0.947051823139,-17.3476276398 --11.0566740036,0.938127160072,-17.2431507111 --11.0998191833,0.948032200336,-17.4255218506 --10.9798984528,0.948999404907,-17.5366287231 --10.5142002106,0.954880297184,-17.9488506317 --10.6244039536,0.969741225243,-18.1949634552 --10.4412498474,0.955860376358,-18.0155162811 --9.94764041901,0.966694712639,-18.527173996 --9.81771945953,0.968666255474,-18.6302947998 --9.78077507019,0.970638215542,-18.6997299194 --9.75184345245,0.974601387978,-18.7841587067 --13.9357318878,1.4838654995,-26.8562488556 --13.8998527527,1.48880040646,-26.9906806946 --13.7557964325,1.48185646534,-26.9192028046 --13.7448682785,1.48581516743,-27.0014133453 --13.6248493195,1.48084533215,-26.9739131927 --13.8934850693,1.52442717552,-27.7091083527 --13.4469156265,1.47983503342,-27.0388660431 --13.2978458405,1.47189974785,-26.9523925781 --18.9968891144,2.1980676651,-38.6112823486 --13.5998439789,1.53626263142,-28.0971679688 --13.482834816,1.53328740597,-28.078666687 --13.3888654709,1.53228461742,-28.1071472168 --13.290886879,1.53028774261,-28.125629425 --13.1989221573,1.53028213978,-28.1591110229 --5.51601600647,0.534697711468,-12.1277322769 --18.6522827148,2.26431107521,-40.0863800049 --18.3610420227,2.24250078201,-39.7890167236 --18.1579627991,2.23158216476,-39.6765861511 --18.0360336304,2.23156166077,-39.7380867004 --17.6566104889,2.1968729496,-39.2327957153 --18.3332195282,2.30581974983,-41.0576629639 --17.5930938721,2.22260165215,-39.7486572266 --17.5291233063,2.221596241,-39.7709083557 --17.2859535217,2.20573663712,-39.5575141907 --17.1760444641,2.20670247078,-39.6420059204 --17.0571193695,2.20767998695,-39.7065048218 --13.0695505142,1.67476606369,-31.060508728 --17.0109882355,2.25418281555,-40.635761261 --16.4399604797,2.18087911606,-39.4574203491 --16.3280467987,2.18284797668,-39.5369186401 --8.99692440033,1.13889706135,-22.3866348267 --8.93296051025,1.13888633251,-22.4270935059 --8.84294128418,1.13591206074,-22.4055805206 --8.76594924927,1.13492071629,-22.4130496979 --8.70189476013,1.12996244431,-22.352306366 --9.48383998871,1.26069831848,-24.5410861969 --9.39684200287,1.25871121883,-24.5415630341 --9.30283069611,1.25573420525,-24.5250492096 --9.21984386444,1.25474023819,-24.537530899 --9.15289115906,1.25572347641,-24.5889911652 --9.07792472839,1.25671720505,-24.622467041 --9.063996315,1.26067769527,-24.7016830444 --9.01809883118,1.26562607288,-24.8131313324 --7.43645572662,1.02101063728,-20.7438335419 --7.38751363754,1.02298533916,-20.8092861176 --7.24734306335,1.01110780239,-20.6208095551 --7.38587331772,1.04477632046,-21.2121105194 --7.12339162827,1.01110029221,-20.6777362823 --7.14353513718,1.02001345158,-20.837928772 --7.13770532608,1.029915452,-21.0283412933 --7.16496515274,1.0457597971,-21.3177280426 --6.74705314636,0.98435986042,-20.3084888458 --7.11723089218,1.06061398983,-21.6125926971 --7.05626726151,1.06160354614,-21.6530570984 --6.54397201538,0.976441144943,-20.2236881256 --6.90716266632,1.05268931389,-21.5387992859 --6.8361697197,1.05169725418,-21.5472698212 --6.76818418503,1.05170047283,-21.5637359619 --6.59891033173,1.03288805485,-21.2632904053 --6.52490472794,1.03090417385,-21.2577629089 --6.52611780167,1.04378092289,-21.4921722412 --6.45211410522,1.04279589653,-21.4886474609 --6.41411113739,1.04180407524,-21.4858894348 --6.35715484619,1.0437887907,-21.5343456268 --6.29619216919,1.04477775097,-21.5758132935 --6.24024152756,1.04675900936,-21.6302700043 --6.22140979767,1.05566561222,-21.8136978149 --6.13336372375,1.05170726776,-21.7641887665 --6.11843109131,1.05567133427,-21.8374042511 --6.05445957184,1.05666601658,-21.8688716888 --6.00553941727,1.0606290102,-21.9553279877 --5.93856096268,1.06062853336,-21.9787979126 --5.86556005478,1.05964183807,-21.9782714844 --5.79255962372,1.05865526199,-21.9777469635 --5.73461103439,1.06063616276,-22.033208847 --5.71667814255,1.06460094452,-22.1054325104 --5.66776132584,1.06856167316,-22.1958866119 --5.63490772247,1.0764837265,-22.3533287048 --5.52778577805,1.06757283211,-22.2218322754 --5.4708442688,1.0705498457,-22.2842922211 --5.39684295654,1.06956386566,-22.2827720642 --5.39310646057,1.08441376686,-22.5651912689 --5.39425230026,1.09333002567,-22.7213973999 --5.2961602211,1.0864007473,-22.6218929291 --5.21513319016,1.08343112469,-22.5923748016 --5.20639467239,1.09828293324,-22.8718013763 --5.14946603775,1.10225260258,-22.9472637177 --5.08551216125,1.10423862934,-22.9947338104 --5.05871486664,1.11512756348,-23.2101745605 --5.04280471802,1.12007915974,-23.3053913116 --4.98890209198,1.12503349781,-23.4078578949 --4.97115516663,1.13989269733,-23.6752872467 --4.93031549454,1.14880895615,-23.8437404633 --4.71971559525,1.11119067669,-23.205329895 --4.63366270065,1.1072371006,-23.1478157043 --4.55866193771,1.10625207424,-23.1452941895 --4.54376888275,1.11219358444,-23.258518219 --4.45369911194,1.10625064373,-23.1830120087 --4.51335191727,1.14486753941,-23.8713798523 --4.45845985413,1.15081632137,-23.9838428497 --4.36538076401,1.14487922192,-23.8983383179 --4.31853437424,1.15380108356,-24.0577964783 --7.17190980911,2.07250809669,-40.2329750061 --7.72619438171,2.26753425598,-43.6777572632 --7.60029554367,2.27150297165,-43.7612876892 --7.47439718246,2.27447152138,-43.8448143005 --7.3364315033,2.27348041534,-43.8583526611 --7.20349836349,2.27547025681,-43.9048881531 --7.05447101593,2.27151656151,-43.8534317017 --6.92757081985,2.27448654175,-43.9349632263 --4.45004749298,1.41321361065,-28.754076004 --4.35704374313,1.41223478317,-28.7425727844 --6.23547363281,2.14481639862,-41.691570282 --6.10953521729,2.14580821991,-41.7350997925 --5.92521429062,2.12502789497,-41.3806762695 --2.16187000275,0.692568659782,-16.0712051392 --2.10179710388,0.688621342182,-16.0016765594 --2.00142264366,0.665852546692,-15.6201696396 --1.99372315407,0.683683395386,-15.9376001358 --1.89736545086,0.662904441357,-15.5740995407 --1.81849622726,0.670845091343,-15.7220010757 --1.80155158043,0.673816859722,-15.7822227478 --1.75758755207,0.675804793835,-15.8256778717 --1.71362543106,0.67779147625,-15.871131897 --1.66563546658,0.678794980049,-15.887597084 --1.61360156536,0.676824092865,-15.8590555191 --1.57872664928,0.683759987354,-15.9935016632 --1.53073203564,0.684766173363,-16.0049571991 --1.50876259804,0.686753153801,-16.0391921997 --3.80859589577,2.05782771111,-40.4390258789 --3.67958569527,2.05586147308,-40.4095535278 --3.41781687737,2.00835108757,-39.5964012146 --3.30698919296,2.01727843285,-39.7539253235 --3.13342761993,1.98363244534,-39.1634902954 --3.07446098328,1.98462641239,-39.1887512207 --2.95045924187,1.98265457153,-39.1692810059 --2.8041601181,1.96385490894,-38.8478279114 --2.69028234482,1.9698113203,-38.9543533325 --2.55916690826,1.9619051218,-38.8198890686 --2.43512868881,1.9579539299,-38.7644195557 --2.31720066071,1.96093952656,-38.8199501038 --2.25721931458,1.96094238758,-38.8302116394 --2.12097382545,1.94611060619,-38.5647506714 --1.98062944412,1.92533540726,-38.2002906799 --1.87693285942,1.94118797779,-38.4898147583 --1.74469304085,1.9263522625,-38.2313499451 --1.62879431248,1.93032121658,-38.3168792725 --1.50264334679,1.92143440247,-38.1484146118 --1.385171175,1.83728802204,-36.6606864929 --1.27324819565,1.84026968479,-36.7232131958 --1.16029655933,1.84226799011,-36.7567367554 --1.04427242279,1.84030771255,-36.7172660828 --0.932350516319,1.84328913689,-36.7807922363 --0.812131166458,1.83043956757,-36.5463180542 --0.758283853531,1.83836603165,-36.6915817261 --0.626341879368,1.78492486477,-35.7360992432 --0.514270067215,1.77999067307,-35.6506195068 --0.401094734669,1.76911485195,-35.4621429443 --0.292200267315,1.7740803957,-35.5536651611 --0.182316198945,1.78004038334,-35.6551933289 --0.0671468675137,1.71372306347,-34.4796867371 --0.0142460158095,1.71867954731,-34.5719528198 -0.120381578803,1.74535691738,-33.8862991333 -0.226101994514,1.73117208481,-33.6216163635 -0.321871399879,1.66145598888,-32.4099845886 -0.432490676641,1.69777452946,-33.039264679 -0.532089114189,1.67552292347,-32.6515960693 -0.641376376152,1.69265568256,-32.9508934021 -0.721748292446,1.77140510082,-34.3279762268 -0.752400934696,1.58051693439,-30.9944763184 -0.880498170853,1.64409995079,-32.1037254333 -0.97212344408,1.62386548519,-31.7400665283 -1.06589591503,1.61171317101,-31.5233955383 -1.16278612614,1.60562646389,-31.4247207642 -1.25456130505,1.59347617626,-31.2100563049 -1.29431164265,1.58032536507,-30.9642333984 -1.39023947716,1.57626008987,-30.902557373 -0.977534174919,0.960349500179,-20.1237678528 -1.0435655117,0.962349355221,-20.1551151276 -1.11264228821,0.967374026775,-20.2324619293 -1.18272566795,0.972402274609,-20.3168087006 -1.25178313255,0.975416243076,-20.3751564026 -1.28784549236,0.979441702366,-20.4383220673 -1.35993635654,0.984473764896,-20.5306663513 -1.43101239204,0.989497661591,-20.608007431 -1.50410985947,0.995533287525,-20.7073478699 -1.57719540596,1.0005620718,-20.7946891785 -2.38662600517,1.5506592989,-30.3919754028 -2.42448329926,1.5425696373,-30.2521533966 -2.5123705864,1.53648388386,-30.1474895477 -2.62453651428,1.5475487709,-30.3267917633 -2.7144446373,1.54347419739,-30.2431259155 -2.00381064415,1.03879678249,-21.4265422821 -2.06573390961,1.03473734856,-21.348903656 -2.13978266716,1.0377458334,-21.4002475739 -3.02713942528,1.52922391891,-29.9662971497 -3.14231443405,1.54029345512,-30.1555938721 -3.23929905891,1.54026055336,-30.1499214172 -3.3635327816,1.55536091328,-30.4002113342 -3.44336628914,1.54624736309,-30.2395572662 -3.64422750473,1.59868192673,-31.1367530823 -3.74623060226,1.60065829754,-31.1510734558 -3.77404284477,1.58954596519,-30.9632606506 -3.87302899361,1.590513587,-30.9595832825 -3.86922454834,1.54406201839,-30.1390342712 -3.98434352875,1.55210053921,-30.2723388672 -4.13198518753,1.53286242485,-29.9210453033 -4.2773065567,1.554007411,-30.2643165588 -3.26504993439,1.12017297745,-22.731754303 -3.35213541985,1.12619924545,-22.8230838776 -3.42915344238,1.12719011307,-22.8444252014 -4.62328767776,1.55691277981,-30.281452179 -4.72429084778,1.55888974667,-30.2947769165 -4.78605318069,1.54574120045,-30.0571460724 -4.85688638687,1.53762996197,-29.8925018311 -4.9109082222,1.53962945938,-29.9206619263 -5.07428121567,1.56279969215,-30.3209114075 -5.1732673645,1.56376814842,-30.3172416687 -5.1204161644,1.51330220699,-29.4347381592 -4.2551612854,1.1955537796,-23.9251651764 -4.32209920883,1.19250249863,-23.8635196686 -4.42723560333,1.20255374908,-24.0108337402 -5.30760192871,1.4687987566,-28.6100578308 -5.46893119812,1.49094569683,-28.9663181305 -5.39105701447,1.43847250938,-28.0528392792 -5.4790263176,1.43843412399,-28.0281791687 -5.58106803894,1.44243323803,-28.080499649 -5.6790804863,1.44441711903,-28.1018314362 -5.85970878601,1.48372721672,-28.7708492279 -5.98685026169,1.49377703667,-28.930141449 -6.32795572281,1.56431806087,-30.1122074127 -6.48921823502,1.58142781258,-30.4014701843 -6.59522914886,1.58440923691,-30.4237918854 -6.69421291351,1.58537697792,-30.4171180725 -5.5577545166,1.24757421017,-24.6120033264 -5.63673639297,1.24754548073,-24.5973510742 -5.69262456894,1.24246907234,-24.4817199707 -6.96943330765,1.54487466812,-29.6307868958 -7.24612855911,1.59020113945,-30.3849277496 -6.40207290649,1.3381177187,-26.0536937714 -6.38584041595,1.32499063015,-25.8069248199 -7.04398441315,1.46104347706,-28.1176643372 -7.17611646652,1.47108721733,-28.2679576874 -7.38151025772,1.49826097488,-28.7001781464 -7.55477428436,1.51636993885,-28.9944324493 -7.80229997635,1.55160844326,-29.5706043243 -7.76681089401,1.52234196663,-29.0520801544 -7.83085775375,1.52635359764,-29.1072311401 -7.91881036758,1.52530729771,-29.0655727386 -8.43622112274,1.6179817915,-30.603471756 -8.52917289734,1.61693358421,-30.5618114471 -8.76523971558,1.62591814995,-30.6564388275 -8.86922740936,1.62688779831,-30.6537666321 -8.88610553741,1.62081587315,-30.5269699097 -8.94595432281,1.61271739006,-30.372341156 -8.90047454834,1.58445882797,-29.8598251343 -8.98541259766,1.58240497112,-29.8021697998 -9.06934452057,1.58034801483,-29.7375183105 -9.14926528931,1.57728588581,-29.6608734131 -9.1862154007,1.57524967194,-29.6110572815 -9.26914787292,1.57319378853,-29.5474052429 -9.35207939148,1.57013738155,-29.482755661 -9.42899513245,1.56707334518,-29.4001159668 -9.52496814728,1.56803631783,-29.378452301 -9.69715213776,1.58210194111,-29.5917167664 -9.78911304474,1.58205974102,-29.5580539703 -9.8741979599,1.58908843994,-29.6561889648 -9.99122142792,1.59307670593,-29.6935081482 -10.0831794739,1.59203314781,-29.6568489075 -10.2042131424,1.59702515602,-29.7031650543 -10.3653507233,1.6090669632,-29.8654403687 -10.5284910202,1.62111032009,-30.0317134857 -10.6936302185,1.63215267658,-30.1969871521 -10.7957487106,1.64219689369,-30.334104538 -10.9578771591,1.65323376656,-30.4873771667 -11.0879182816,1.65822911263,-30.5446872711 -11.1969060898,1.66019880772,-30.542016983 -11.2998809814,1.6611623764,-30.5243492126 -11.3958368301,1.66111767292,-30.4866905212 -11.4867801666,1.66006708145,-30.4350376129 -11.538769722,1.66104984283,-30.4282035828 -11.6387348175,1.66100895405,-30.3995437622 -11.7326879501,1.66096293926,-30.3578853607 -11.8266382217,1.65991556644,-30.3132324219 -11.9266042709,1.66087532043,-30.285572052 -12.0245656967,1.66083371639,-30.2539100647 -12.1295423508,1.66279816628,-30.237247467 -12.1805286407,1.66278004646,-30.2274131775 -12.2855033875,1.66374385357,-30.2097492218 -12.3814611435,1.66470062733,-30.1730918884 -12.4774179459,1.66465628147,-30.1344356537 -12.5723705292,1.66361021996,-30.0917816162 -12.6633176804,1.66356229782,-30.0431289673 -12.7592744827,1.66351771355,-30.0034751892 -12.8092565536,1.66349804401,-29.9896450043 -12.9032096863,1.66345214844,-29.9459915161 -13.0011711121,1.66341030598,-29.9123344421 -13.122179985,1.66739034653,-29.9326534271 -13.2762527466,1.67539966106,-30.0269451141 -13.4784193039,1.69045054913,-30.227191925 -13.6606626511,1.70954823494,-30.5102367401 -13.8968868256,1.72862541676,-30.7794513702 -14.0759983063,1.74065005779,-30.916721344 -14.2280521393,1.74764943123,-30.9910163879 -14.3700866699,1.75363993645,-31.0423202515 -14.4950866699,1.75661444664,-31.0536422729 -14.6150779724,1.75958573818,-31.0559654236 -14.6790790558,1.76157343388,-31.0631275177 -14.7850437164,1.76253271103,-31.0344619751 -14.8859977722,1.76348674297,-30.992805481 -14.9769334793,1.76243281364,-30.9301605225 -15.0768861771,1.76238691807,-30.8875045776 -15.1598091125,1.7603276968,-30.8098621368 -15.2527484894,1.75927567482,-30.7512168884 -15.2917060852,1.75824427605,-30.7073993683 -15.3916606903,1.75819921494,-30.6657428741 -15.4765872955,1.75714182854,-30.5921020508 -15.5625152588,1.75508546829,-30.5204620361 -15.6464424133,1.75402867794,-30.4468212128 -15.7283668518,1.75197041035,-30.369184494 -15.8183059692,1.7509188652,-30.3085384369 -15.8662776947,1.75089418888,-30.2817153931 -15.9562158585,1.74984264374,-30.2210712433 -16.0211143494,1.74677312374,-30.111448288 -16.1050434113,1.74471795559,-30.0398082733 -16.2440605164,1.74970054626,-30.0711212158 -16.3760662079,1.75467801094,-30.0884399414 -16.3959960938,1.75063514709,-30.0106430054 -16.540019989,1.75662064552,-30.0499477386 -16.6349658966,1.75657212734,-29.996301651 -16.7329158783,1.75652647018,-29.9496517181 -16.7767848969,1.75144565105,-29.8050479889 -16.6832561493,1.71817207336,-29.1990070343 -16.658121109,1.71010363102,-29.0462474823 -16.6669464111,1.70000576973,-28.8486766815 -16.6998100281,1.69392359257,-28.6940841675 -16.7236595154,1.68583726883,-28.5264987946 -16.7795581818,1.68176996708,-28.4128894806 -16.8034133911,1.67468595505,-28.2493000031 -16.8392848969,1.66860902309,-28.1057071686 -16.8201675415,1.6615486145,-27.9709434509 -16.859046936,1.65547466278,-27.8343467712 -16.8929195404,1.64939856529,-27.6907558441 -16.9167804718,1.6423176527,-27.5321712494 -16.9636745453,1.63825047016,-27.4125652313 -17.0115718842,1.63418519497,-27.2969589233 -17.058467865,1.629119277,-27.179353714 -17.037355423,1.62206196785,-27.0485916138 -17.0902614594,1.61900067329,-26.94298172 -17.1451702118,1.61594057083,-26.8403720856 -17.1970767975,1.61187970638,-26.7347621918 -17.2630023956,1.60982644558,-26.651140213 -17.2538318634,1.59973430634,-26.4505882263 -17.2928028107,1.59971117973,-26.4187717438 -17.2746238708,1.58861625195,-26.2072257996 -17.3425521851,1.58756577969,-26.1296043396 -17.3924636841,1.583507061,-26.0259952545 -17.448381424,1.58145153522,-25.9313831329 -17.4982910156,1.57739377022,-25.8287754059 -17.5341854095,1.57332861423,-25.7041835785 -17.5110816956,1.56627714634,-25.5824222565 -17.6040477753,1.56724095345,-25.5447788239 -17.6689796448,1.56619143486,-25.4661579132 -17.7659473419,1.56715726852,-25.4345111847 -17.8529052734,1.56811785698,-25.3868751526 -17.9388599396,1.56807875633,-25.3392372131 -18.0298213959,1.56904149055,-25.2975978851 -18.0758056641,1.57002329826,-25.2777767181 -18.1747741699,1.57198953629,-25.2471294403 -18.2647361755,1.57295167446,-25.2034931183 -18.36170578,1.57391762733,-25.1708450317 -18.4586734772,1.57588267326,-25.1362018585 -18.5526371002,1.57684671879,-25.0975608826 -18.6486053467,1.57881176472,-25.0619163513 -18.701593399,1.57979607582,-25.0500907898 -18.81457901,1.58276772499,-25.0364341736 -18.9235591888,1.58573806286,-25.0177783966 -19.0435504913,1.58971166611,-25.0111198425 -19.1495265961,1.59168052673,-24.9874649048 -19.2735233307,1.59665572643,-24.9857997894 -19.353471756,1.59661412239,-24.9271678925 -19.4174690247,1.59860229492,-24.9283332825 -19.5604820251,1.60458433628,-24.9496536255 -19.6043949127,1.60152852535,-24.8430557251 -19.7363948822,1.60550606251,-24.8493843079 -19.866394043,1.61048233509,-24.8517169952 -19.9773731232,1.61345160007,-24.8300628662 -20.0933570862,1.61642277241,-24.8144054413 -20.1683654785,1.6194139719,-24.8265628815 -20.2853488922,1.62338531017,-24.8119029999 -20.4213504791,1.62836253643,-24.8182315826 -20.5183124542,1.63032615185,-24.7765903473 -20.66132164,1.63530564308,-24.7909107208 -20.7783031464,1.63927555084,-24.7722530365 -20.8963508606,1.64628100395,-24.8353729248 -20.9913101196,1.64724266529,-24.7877407074 -21.1203022003,1.65221619606,-24.7820739746 -20.9550189972,1.63009309769,-24.4276485443 -20.8047542572,1.60997653008,-24.0942077637 -20.7996273041,1.60290837288,-23.9336528778 -20.9186115265,1.60688054562,-23.9189929962 -20.9165477753,1.60284662247,-23.8392162323 -20.9534606934,1.59979307652,-23.7296237946 -20.9843673706,1.5957378149,-23.6130371094 -21.0042648315,1.59167957306,-23.4844608307 -21.019159317,1.58662068844,-23.3518867493 -21.0700855255,1.5835723877,-23.2592868805 -21.1009941101,1.58051896095,-23.1457004547 -21.0669059753,1.57447779179,-23.033946991 -21.122838974,1.5724323988,-22.9493408203 -21.1307315826,1.56737375259,-22.8127708435 -21.1356220245,1.56131410599,-22.6722068787 -21.149520874,1.55725812912,-22.5436325073 -21.1173801422,1.54818940163,-22.3651008606 -21.1603622437,1.54817175865,-22.3402862549 -21.2082920074,1.54712605476,-22.2496833801 -21.2281970978,1.54207289219,-22.129108429 -21.2591133118,1.53902339935,-22.0215206146 -21.2860279083,1.53597307205,-21.9099388123 -21.3309555054,1.53392755985,-21.8173427582 -21.3778877258,1.53188323975,-21.7277431488 -21.3738288879,1.52885377407,-21.653968811 -21.383731842,1.52380073071,-21.5273990631 -21.3556060791,1.51573824883,-21.3618602753 -21.3274803162,1.50767636299,-21.1973228455 -21.326379776,1.50262236595,-21.0627593994 -21.367307663,1.50057816505,-20.9691677094 -21.4482688904,1.50154399872,-20.9165439606 -21.4342079163,1.4975143671,-20.8367729187 -21.4561233521,1.49446678162,-20.7261943817 -21.472038269,1.49041843414,-20.6106204987 -21.4649333954,1.48436462879,-20.4720668793 -21.4678401947,1.47931420803,-20.345500946 -21.4637393951,1.47426223755,-20.2119426727 -21.4846611023,1.47021687031,-20.1043643951 -21.4575920105,1.46618556976,-20.0136070251 -21.4765110016,1.46213984489,-19.9040317535 -21.4924297333,1.45909440517,-19.7934551239 -21.5033435822,1.45404791832,-19.6778850555 -21.5132579803,1.45000123978,-19.5613174438 -21.5381851196,1.44795870781,-19.4607334137 -21.5430984497,1.44291174412,-19.340171814 -21.4429855347,1.43286848068,-19.1874675751 -21.2487659454,1.41378426552,-18.8900527954 -21.0125198364,1.3906930685,-18.5566730499 -20.907365799,1.37862837315,-18.3441925049 -20.585067749,1.34952425957,-17.9408779144 -20.4979305267,1.33846545219,-17.7493782043 -20.5419178009,1.33945226669,-17.7305679321 -18.2673683167,1.16400051117,-15.6307353973 -18.1742401123,1.15394794941,-15.4492416382 -17.9250164032,1.13086926937,-15.1358623505 -12.8517503738,0.748959839344,-10.6911649704 -12.8527097702,0.745938360691,-10.622592926 -12.8676786423,0.744919419289,-10.5660114288 -12.8566522598,0.742906987667,-10.5222349167 -8.1827287674,0.393111646175,-6.49369955063 -8.20772647858,0.393106102943,-6.47110700607 -8.26874637604,0.396106272936,-6.47848176956 -8.27873516083,0.395098686218,-6.44488573074 -8.30673503876,0.396093338728,-6.42330169678 -8.31673240662,0.396090328693,-6.41050100327 -8.36174201965,0.398087829351,-6.40389060974 -8.37173175812,0.397080153227,-6.36930561066 -8.39873123169,0.397075146437,-6.3487033844 -8.42072677612,0.397069215775,-6.32311487198 -8.44072246552,0.397063165903,-6.29652261734 -8.46872234344,0.398058205843,-6.27592611313 -8.48972606659,0.39905667305,-6.27112150192 -8.50571918488,0.398050218821,-6.2415304184 -8.53972244263,0.399045974016,-6.2249341011 -8.56271934509,0.399040400982,-6.20034074783 -8.58971881866,0.400035351515,-6.17874479294 -8.6087141037,0.400029361248,-6.15115356445 -8.63271808624,0.401028215885,-6.14834594727 -8.65171337128,0.401022255421,-6.12075471878 -8.67171001434,0.401016503572,-6.09416007996 -8.70571231842,0.402012377977,-6.07755804062 -8.7437171936,0.403008788824,-6.06395101547 -8.76571369171,0.403003066778,-6.03736829758 -8.79171276093,0.402998059988,-6.01477098465 -8.80471134186,0.403995633125,-6.00396680832 -8.82570838928,0.403990060091,-5.97737693787 -8.85871124268,0.404985874891,-5.9597735405 -8.87470436096,0.403979718685,-5.92919158936 -8.90770626068,0.40497559309,-5.9115858078 -8.92770195007,0.404969960451,-5.88399839401 -8.95770359039,0.405965387821,-5.86340284348 -8.95769691467,0.40596178174,-5.84360742569 -8.99169826508,0.406957477331,-5.82501506805 -9.02069950104,0.40695297718,-5.80441141129 -9.06470584869,0.408949702978,-5.79280662537 -9.09070491791,0.408944785595,-5.76921272278 -9.16472625732,0.41294413805,-5.77758169174 -9.11168766022,0.407932460308,-5.70204162598 -9.13769340515,0.408931046724,-5.69824075699 -9.18870353699,0.410928279161,-5.69063043594 -9.2307100296,0.41292488575,-5.67801523209 -9.24570274353,0.412919223309,-5.6474237442 -11.707780838,0.577103435993,-7.18005800247 -11.7327690125,0.577094137669,-7.14446878433 -11.7577705383,0.578090429306,-7.13466405869 -11.8217763901,0.580083966255,-7.1230506897 -11.4656019211,0.55504745245,-6.84973287582 -11.6916780472,0.569052815437,-6.93999910355 -11.6736497879,0.56604129076,-6.87943172455 -11.6136045456,0.561026871204,-6.79290056229 -11.528550148,0.5540112257,-6.69139146805 -11.8246622086,0.572025001049,-6.84539651871 -13.458313942,0.679115891457,-7.77565908432 -13.4943027496,0.679105043411,-7.74006414413 -13.6153259277,0.686099112034,-7.7544093132 -13.5422706604,0.679082155228,-7.65488529205 -13.6963071823,0.68807798624,-7.68820381165 -13.2881212234,0.659043133259,-7.39392709732 -13.231086731,0.655034065247,-7.33318281174 -13.6132116318,0.678041815758,-7.49734163284 -13.7522411346,0.686036467552,-7.52066802979 -13.3510627747,0.658004820347,-7.23738050461 -13.3640451431,0.656993806362,-7.18980073929 -13.3890314102,0.656983435154,-7.14921045303 -13.3720026016,0.654971420765,-7.08564758301 -13.5600614548,0.665973603725,-7.16173219681 -13.6320648193,0.668965101242,-7.14611101151 -13.4779863358,0.657947599888,-7.00764608383 -13.4889678955,0.656936883926,-6.95906877518 -13.4819431305,0.654925525188,-6.90050792694 -13.4829216003,0.653914928436,-6.84792900085 -13.4769086838,0.65290915966,-6.81715345383 -13.5319070816,0.654900372028,-6.79254245758 -13.4548578262,0.648887395859,-6.69902276993 -13.5088558197,0.650878608227,-6.67341661453 -13.4528160095,0.645866811275,-6.59188079834 -13.3437585831,0.63685387373,-6.48338699341 -13.5117950439,0.646848142147,-6.51570129395 -13.5598011017,0.648844301701,-6.51387882233 -13.5607805252,0.6478343606,-6.46130847931 -13.7038078308,0.654827594757,-6.479637146 -13.6907835007,0.652817368507,-6.4200758934 -13.6707572937,0.650807261467,-6.35751771927 -13.7007465363,0.650798022747,-6.31893014908 -13.8167743683,0.657795131207,-6.34906005859 -13.8057498932,0.655785262585,-6.29049968719 -13.8227357864,0.65577596426,-6.24591588974 -13.8697309494,0.656767070293,-6.2153134346 -13.8066930771,0.651757121086,-6.13378143311 -13.5045824051,0.631745219231,-5.94142007828 -13.7756462097,0.647738516331,-6.01466417313 -13.8966722488,0.654734909534,-6.04379749298 -14.0547008514,0.662726759911,-6.06311988831 -13.3924894333,0.620715022087,-5.71399021149 -13.3734664917,0.618706882,-5.65543222427 -13.3884534836,0.617698848248,-5.61185359955 -13.4854640961,0.622690856457,-5.60421943665 -13.4434366226,0.619683086872,-5.53667068481 -13.4504299164,0.618679225445,-5.51488018036 -13.5204334259,0.622671127319,-5.49426937103 -13.4944095612,0.619663536549,-5.43371343613 -13.4823904037,0.617656052113,-5.37914991379 -13.5243864059,0.619648337364,-5.34754800797 -13.5373744965,0.618640899658,-5.30396461487 -13.5883712769,0.620633006096,-5.27536058426 -13.6083698273,0.621629178524,-5.25856399536 -13.6403617859,0.62262147665,-5.22197246552 -13.6533508301,0.622614204884,-5.17838764191 -13.6893444061,0.62360650301,-5.14279747009 -13.7283391953,0.624598860741,-5.10919761658 -13.7583312988,0.625591397285,-5.07160615921 -13.8563480377,0.630586147308,-5.08475780487 -13.9363527298,0.63457763195,-5.06613206863 -13.9253349304,0.633570790291,-5.01157331467 -13.9413232803,0.633563518524,-4.96799182892 -13.9633131027,0.633556306362,-4.92740011215 -13.9743022919,0.633549273014,-4.8818230629 -14.0653076172,0.637540280819,-4.86519765854 -14.0693025589,0.637536942959,-4.84240436554 -14.1002941132,0.638529419899,-4.803814888 -14.1122817993,0.638522446156,-4.75823831558 -14.1582784653,0.639514625072,-4.72464132309 -14.2022733688,0.641506910324,-4.69103717804 -14.2552709579,0.643498778343,-4.65943527222 -14.2802619934,0.644491672516,-4.61884307861 -14.3442687988,0.647486269474,-4.61502408981 -14.3882637024,0.649478495121,-4.58042192459 -14.4162549973,0.650471150875,-4.53983354568 -14.454249382,0.651463508606,-4.50224161148 -14.4522352219,0.650457382202,-4.45167207718 -14.5182342529,0.653448760509,-4.42306089401 -14.5612297058,0.655440986156,-4.38745832443 -14.5892276764,0.656436860561,-4.37165260315 -14.6262216568,0.657429277897,-4.33306121826 -14.6542129517,0.658422112465,-4.29147481918 -14.703209877,0.660414099693,-4.25687074661 -14.7512044907,0.662406086922,-4.22127103806 -14.7901992798,0.664398431778,-4.18267726898 -14.8472032547,0.667392969131,-4.17485427856 -14.8471889496,0.666387081146,-4.12428569794 -14.8971843719,0.668378949165,-4.08868408203 -12.911819458,0.550471365452,-3.46435165405 -12.7777881622,0.542474687099,-3.38285970688 -12.8317890167,0.544468581676,-3.35525250435 -12.8077774048,0.542466580868,-3.30569267273 -12.8197755814,0.543464303017,-3.28690505028 -12.8227682114,0.542461037636,-3.24532556534 -12.8027563095,0.540458977222,-3.19676876068 -12.8427553177,0.542453706264,-3.1641767025 -12.8167438507,0.540452241898,-3.11461925507 -12.8717460632,0.542446255684,-3.08700633049 -12.9537506104,0.547438442707,-3.06439256668 -12.9297437668,0.545438468456,-3.03761291504 -15.5071296692,0.695279419422,-3.64347267151 -15.5701265335,0.698270261288,-3.60786366463 -15.611120224,0.6992623806,-3.56627058983 -15.7021207809,0.704251587391,-3.53763866425 -15.7041072845,0.703246176243,-3.4860701561 -15.7711048126,0.706236600876,-3.44946575165 -15.8001031876,0.708232164383,-3.43066048622 -15.8600988388,0.711223125458,-3.39305090904 -15.9260950089,0.714213550091,-3.35544657707 -16.2451248169,0.732186555862,-3.37468600273 -16.0490856171,0.720194935799,-3.27823472023 -16.0390720367,0.718190670013,-3.22367119789 -16.0560684204,0.719186961651,-3.20087885857 -16.1190643311,0.722177565098,-3.16226911545 -16.1380558014,0.72317135334,-3.11368918419 -16.2190532684,0.72716063261,-3.07807040215 -16.235042572,0.727154612541,-3.02849292755 -16.300037384,0.73014497757,-2.98888468742 -16.3630332947,0.733135461807,-2.94827985764 -16.4010314941,0.735130190849,-2.92947053909 -16.4410247803,0.737122476101,-2.88387942314 -16.4990196228,0.740113258362,-2.84227156639 -16.5400104523,0.741105377674,-2.79568648338 -16.6030063629,0.745095729828,-2.75407838821 -16.6520004272,0.747087299824,-2.70948004723 -16.691991806,0.749079465866,-2.66288852692 -16.7769947052,0.753070235252,-2.65105295181 -16.7939853668,0.754064321518,-2.59947919846 -16.9509887695,0.762046635151,-2.57181954384 -16.9299755096,0.760044038296,-2.51426196098 -16.9939689636,0.764034211636,-2.47065377235 -17.090965271,0.769021391869,-2.4310336113 -17.1879634857,0.774008512497,-2.39140939713 -17.1449546814,0.771010100842,-2.35764837265 -17.2219486237,0.774999022484,-2.31503129005 -17.2459392548,0.775992631912,-2.2634510994 -16.201839447,0.716083168983,-2.05948090553 -16.0628185272,0.70809262991,-1.98898792267 -16.0078048706,0.704094707966,-1.93045032024 -15.9757976532,0.702096164227,-1.90068423748 -15.9427871704,0.700096309185,-1.84513807297 -15.8977746964,0.69709777832,-1.78859603405 -15.899766922,0.697094917297,-1.73902082443 -15.8997583389,0.696092247963,-1.68845367432 -15.8727483749,0.694092273712,-1.63490009308 -15.8957424164,0.695087611675,-1.58731818199 -15.8967380524,0.695086300373,-1.56253111362 -15.8987312317,0.695083737373,-1.5129570961 -15.9237241745,0.696078896523,-1.46537470818 -15.948718071,0.697074115276,-1.41779100895 -15.9557113647,0.697071194649,-1.36821806431 -15.9587039948,0.697068750858,-1.31864368916 -16.0027046204,0.700063228607,-1.29783368111 -16.0456981659,0.702056646347,-1.25124263763 -16.0756931305,0.703051447868,-1.20365536213 -16.1676902771,0.708039820194,-1.16103589535 -16.287689209,0.715025246143,-1.12039923668 -16.400686264,0.721011161804,-1.07777285576 -18.5537815094,0.842779457569,-1.19301974773 -18.7127838135,0.851760625839,-1.17614781857 -18.7067718506,0.850757598877,-1.11658751965 -9.65137577057,0.338738292456,-0.429042339325 -9.63337993622,0.337743252516,-0.398466855288 -9.64738559723,0.337744832039,-0.368889480829 -9.62138938904,0.33675083518,-0.337327629328 -9.64739513397,0.337751150131,-0.308738678694 -9.63039684296,0.336754620075,-0.292957991362 -9.64140224457,0.337756633759,-0.263378322124 -9.62140655518,0.335762113333,-0.232808321714 -9.63841247559,0.33676353097,-0.203228995204 -9.62941741943,0.336767822504,-0.173647150397 -9.63242149353,0.336770921946,-0.143080323935 -9.62542438507,0.335773408413,-0.128290191293 -9.6384305954,0.336775332689,-0.0987087115645 -9.61743545532,0.335781276226,-0.0681439489126 -9.63444137573,0.33678278327,-0.0385613180697 -9.61744594574,0.335788249969,-0.00898395758122 -9.62145137787,0.33579146862,0.0215828306973 -9.61645698547,0.335795640945,0.0511615239084 -9.62446022034,0.335796505213,0.0659537017345 -9.61046600342,0.334801793098,0.0955288931727 -9.61747169495,0.335804760456,0.126097232103 -9.60947704315,0.334809422493,0.155673339963 -9.61748313904,0.335812211037,0.185256659985 -9.59948825836,0.33381819725,0.214826777577 -9.62149524689,0.335819423199,0.245404243469 -9.6054983139,0.334823340178,0.260184824467 -9.61550521851,0.33482593298,0.289770126343 -9.60151100159,0.334831625223,0.319340676069 -9.61251735687,0.334834158421,0.348927408457 -9.59052276611,0.333840966225,0.3784904778 -9.59552955627,0.333844482899,0.409059077501 -9.5925359726,0.333848923445,0.43863555789 -9.6025390625,0.334849625826,0.45343375206 -9.5875453949,0.333855718374,0.482999503613 -9.60455226898,0.334857702255,0.51358038187 -9.58355903625,0.333864569664,0.542153298855 -9.60256576538,0.334866315126,0.572737693787 -9.5755739212,0.333874106407,0.601302504539 -9.59257602692,0.334874033928,0.617096543312 -9.57358264923,0.33388081193,0.645668327808 -9.58458995819,0.333883732557,0.676245927811 -9.57659721375,0.333889186382,0.705815553665 -9.59660434723,0.33489087224,0.73640614748 -9.56561183929,0.332899540663,0.764959514141 -9.5856180191,0.334901243448,0.795551896095 -9.57062244415,0.333905518055,0.809335172176 -9.5886297226,0.334907650948,0.840912163258 -9.5626373291,0.333915680647,0.868482649326 -9.57864379883,0.334917992353,0.899072289467 -9.55665302277,0.33392572403,0.927632570267 -9.57965946198,0.334927171469,0.959220767021 -9.55566692352,0.333935290575,0.987776339054 -9.57467079163,0.334934860468,1.00358378887 -9.56767845154,0.334940582514,1.03315293789 -9.56068611145,0.333946377039,1.06272137165 -9.57469367981,0.334949076176,1.09331333637 -9.54970264435,0.333957433701,1.12087726593 -9.56870937347,0.334959536791,1.1524657011 -9.55271339417,0.334964305162,1.16624045372 -9.55372142792,0.334968984127,1.19582378864 -9.54473018646,0.333975285292,1.22538745403 -9.57173633575,0.335976302624,1.2579818964 -9.53974628448,0.334985911846,1.28454101086 -9.55675411224,0.335988402367,1.31613075733 -9.53476333618,0.334996640682,1.34369444847 -9.55476570129,0.335996329784,1.36148715019 -9.52777576447,0.335005313158,1.38805258274 -9.55178356171,0.336007028818,1.42163360119 -9.5217924118,0.335016459227,1.44720435143 -9.54180049896,0.336018651724,1.47979235649 -9.53980922699,0.33602425456,1.51035797596 -9.53781795502,0.336029738188,1.53993749619 -9.52582263947,0.336034029722,1.55272841454 -9.54882907867,0.337035864592,1.58631455898 -9.52083969116,0.336045444012,1.61287117004 -9.52984809875,0.337049424648,1.64445161819 -9.51785755157,0.336056619883,1.67301976681 -9.52486610413,0.337060809135,1.70361042023 -9.51587581635,0.337067693472,1.7331725359 -9.53487873077,0.338067471981,1.75097584724 -9.5088891983,0.337076932192,1.77753317356 -9.5308971405,0.338078975677,1.81112623215 -9.50190830231,0.337088942528,1.83668720722 -9.51091575623,0.338093042374,1.86827301979 -9.50992584229,0.338098824024,1.89884459972 -9.52292919159,0.339099615812,1.91663599014 -9.49394035339,0.338109612465,1.94120752811 -9.50994873047,0.339112758636,1.97478973866 -9.50395774841,0.339119374752,2.00436115265 -9.49596786499,0.3391264081,2.03392648697 -9.4859790802,0.338133692741,2.06249880791 -9.5019865036,0.340136855841,2.09608578682 -9.48499298096,0.339142411947,2.10786771774 -9.49300193787,0.340146958828,2.1404440403 -9.47301292419,0.339155942202,2.16701102257 -9.48602199554,0.340159714222,2.20059132576 -9.47803211212,0.34016674757,2.22917079926 -9.48904037476,0.341170966625,2.26274681091 -9.46004867554,0.33917850256,2.27152562141 -9.48705482483,0.341180056334,2.3081176281 -9.47606658936,0.341187775135,2.33668732643 -9.4790763855,0.342193245888,2.36826586723 -9.45508861542,0.341203182936,2.3938293457 -9.47709655762,0.342205494642,2.42942333221 -9.45410728455,0.341215312481,2.45498943329 -9.47411155701,0.343215167522,2.47578072548 -9.45112419128,0.342224985361,2.5013461113 -9.46113204956,0.343229472637,2.53492736816 -9.44814395905,0.343237668276,2.56250286102 -9.46015357971,0.344241917133,2.59708023071 -9.44816493988,0.344249933958,2.62466001511 -9.45017433167,0.344255983829,2.65722727776 -9.4431810379,0.344260245562,2.67101311684 -9.45618915558,0.345264285803,2.70559859276 -9.43620204926,0.344273775816,2.73117280006 -9.45521068573,0.346276879311,2.76775860786 -9.43722248077,0.345286220312,2.79432725906 -9.44323253632,0.346291601658,2.82790231705 -9.43424510956,0.346299558878,2.85746836662 -9.44324874878,0.347301095724,2.87526845932 -9.4252614975,0.346310555935,2.90183663368 -9.44526958466,0.348313599825,2.93942165375 -9.42328262329,0.347323805094,2.96498584747 -9.43229293823,0.348328769207,2.99956560135 -9.4233045578,0.348336666822,3.02814650536 -9.43630886078,0.349337667227,3.04794216156 -9.42632007599,0.349346011877,3.07750630379 -9.4253320694,0.350352704525,3.10908484459 -9.40434455872,0.349362879992,3.13465189934 -9.42535400391,0.351365834475,3.17324018478 -9.41036701202,0.351375073195,3.20080852509 -9.4083776474,0.351382046938,3.2323846817 -9.41338348389,0.352384507656,3.25017523766 -9.42639255524,0.353388905525,3.28675818443 -9.40140628815,0.35239982605,3.31033182144 -9.41241645813,0.353404700756,3.34690785408 -9.40642929077,0.354412525892,3.37748169899 -9.41643810272,0.355417639017,3.41405582428 -9.39645290375,0.354427874088,3.43962669373 -9.40845680237,0.355429202318,3.46041679382 -9.4044675827,0.356436550617,3.49100279808 -9.41047954559,0.357442468405,3.52657461166 -9.3884935379,0.356453061104,3.55114817619 -9.40050315857,0.357457906008,3.58872652054 -9.39151668549,0.357466340065,3.61830210686 -9.40152072906,0.358467936516,3.63810014725 -9.38653373718,0.358477503061,3.66567158699 -9.3955450058,0.359483093023,3.70323967934 -9.37555980682,0.359493583441,3.72881054878 -9.39256858826,0.360497504473,3.76839756966 -9.37158298492,0.360508292913,3.79396343231 -9.38659286499,0.361512511969,3.83255577087 -9.37859916687,0.361517488956,3.84633946419 -9.39261054993,0.36352211237,3.88591694832 -9.37162494659,0.362533032894,3.91148304939 -9.38263511658,0.364538043737,3.94907236099 -9.37364864349,0.364546835423,3.97964143753 -9.37466049194,0.365553855896,4.01421642303 -9.37066745758,0.365558028221,4.02901029587 -9.37867736816,0.366563826799,4.06658840179 -9.37069129944,0.366572409868,4.09716510773 -9.36870384216,0.367580026388,4.13073968887 -9.35671806335,0.367589503527,4.16030740738 -9.36172962189,0.368595898151,4.19688606262 -9.3527431488,0.368604809046,4.22745990753 -9.3617477417,0.369606733322,4.24825668335 -9.34476280212,0.36961722374,4.27582216263 -9.36077213287,0.371621608734,4.31740808487 -9.34578704834,0.371631771326,4.34597396851 -9.35879802704,0.372636735439,4.38655757904 -9.34181213379,0.372647076845,4.41313695908 -9.38781833649,0.376646131277,4.46972703934 -9.32683467865,0.372661113739,4.45948982239 -9.32985877991,0.374675542116,4.53164100647 -9.34586811066,0.376679986715,4.57422828674 -9.32288455963,0.376691758633,4.59879732132 -9.32489681244,0.377698898315,4.63537454605 -9.32291030884,0.377706766129,4.66995239258 -9.33591461182,0.379708051682,4.69375085831 -9.31993103027,0.379718720913,4.72231578827 -9.33394050598,0.380723655224,4.76490116119 -9.33195304871,0.381731718779,4.80047225952 -9.30997085571,0.381743520498,4.82603693008 -9.32898044586,0.383747547865,4.87162399292 -9.30799007416,0.382755160332,4.87841367722 -9.31800079346,0.38376095891,4.91999387741 -9.31201553345,0.384769797325,4.95356798172 -9.31402778625,0.385777115822,4.99114704132 -9.29504489899,0.385788559914,5.01870965958 -9.31205463409,0.387793064117,5.0642952919 -9.29307079315,0.387804359198,5.09086990356 -9.30107688904,0.388806730509,5.11366081238 -9.30608844757,0.38981372118,5.15423154831 -9.29810333252,0.390822947025,5.18681097031 -9.29111766815,0.390832096338,5.22038602829 -9.29413032532,0.391839265823,5.25897073746 -9.27814674377,0.391850352287,5.28853368759 -9.28915882111,0.393856048584,5.33211803436 -9.29716300964,0.394858568907,5.355905056 -9.28617858887,0.395868510008,5.38748121262 -9.28819179535,0.39687615633,5.42705535889 -9.28620529175,0.397884368896,5.46363782883 -9.27922058105,0.397893697023,5.49820995331 -9.28123378754,0.399901300669,5.53778886795 -9.27724838257,0.39990991354,5.57337236404 -9.27125549316,0.400915265083,5.59014844894 -9.27326869965,0.401922821999,5.62973117828 -9.26328468323,0.40193271637,5.66230916977 -9.26929759979,0.403939813375,5.70587921143 -9.26031303406,0.403949558735,5.73945569992 -9.2633266449,0.40595716238,5.78103017807 -9.26133346558,0.405961453915,5.79882574081 -9.25534820557,0.406970858574,5.83539390564 -9.25436115265,0.40797907114,5.87397623062 -9.25237560272,0.408987641335,5.91255331039 -9.25238990784,0.409995704889,5.95213508606 -9.23240756989,0.41000777483,5.97970533371 -9.25341129303,0.412007898092,6.0134973526 -9.2484254837,0.413017183542,6.05106925964 -9.25343894958,0.415024369955,6.09465074539 -9.2384557724,0.415035426617,6.12522792816 -9.23747062683,0.416043996811,6.16580104828 -9.23748397827,0.418052196503,6.20638275146 -9.2215013504,0.418063610792,6.2369556427 -9.23350524902,0.419065445662,6.2657456398 -9.23951911926,0.421072632074,6.31132364273 -9.22253704071,0.421084374189,6.34189176559 -9.22455024719,0.423092246056,6.38447475433 -9.2205657959,0.424101471901,6.42404747009 -9.2165813446,0.425110727549,6.46362113953 -9.20859718323,0.426120638847,6.50019741058 -9.21660232544,0.427123337984,6.52698755264 -9.20961856842,0.428133100271,6.56456375122 -9.21363162994,0.429140776396,6.61014127731 -9.20764732361,0.430150419474,6.64871788025 -9.19866371155,0.431160658598,6.68529319763 -9.19467926025,0.432170003653,6.72586727142 -9.19669342041,0.434178084135,6.77044773102 -9.19270133972,0.434183120728,6.78923606873 -9.19371509552,0.436191499233,6.83381175995 -9.19073104858,0.437200605869,6.87538957596 -9.19974327087,0.43920737505,6.92597150803 -9.1867609024,0.440218508244,6.96054553986 -9.17977714539,0.441228568554,7.00011730194 -9.16578769684,0.441235661507,7.01190185547 -9.3447637558,0.455208748579,7.19153690338 -9.11482810974,0.440262913704,7.06204748154 -9.02286338806,0.435290068388,7.03758621216 -8.58697414398,0.406385749578,6.74801397324 -8.70396327972,0.416371077299,6.88063526154 -8.39304637909,0.395441889763,6.68211126328 -8.45204162598,0.400434464216,6.74892234802 -8.36507606506,0.395460754633,6.72346878052 -8.40408229828,0.399461716413,6.79606485367 -8.2621307373,0.391499131918,6.72658824921 -8.2511472702,0.39151006937,6.75917053223 -8.32014846802,0.398505300283,6.85776519775 -8.30516719818,0.398517161608,6.88834047318 -8.26018428802,0.396530628204,6.87311649323 -8.21321105957,0.394549012184,6.87767791748 -8.15623950958,0.391569346189,6.8732419014 -8.17025279999,0.394575536251,6.92782354355 -8.16426944733,0.395585864782,6.96639585495 -8.11229705811,0.393605291843,6.96595859528 -8.08631134033,0.39261507988,6.96573877335 -8.05233573914,0.391630977392,6.98030471802 -8.01236057281,0.389647960663,6.98887681961 -7.98938179016,0.389661639929,7.01244783401 -7.93341016769,0.387681931257,7.00701379776 -7.93442630768,0.388690918684,7.05158901215 -7.90344953537,0.388706326485,7.06815719604 -7.88046312332,0.387715548277,7.06993770599 -7.81849384308,0.384737163782,7.05850028992 -7.80851221085,0.385748296976,7.09307718277 -7.0607213974,0.331918329,6.50798845291 -9.26221847534,0.501481473446,8.54226589203 -9.24723720551,0.501493632793,8.58183574677 -9.2502450943,0.503497540951,8.61062812805 -7.41769552231,0.364878356457,6.97763252258 -9.22328186035,0.50552123785,8.6927728653 -9.22329711914,0.507530331612,8.74635124207 -9.22731208801,0.509538590908,8.80393218994 -9.2183303833,0.511549651623,8.85050106049 -9.22633647919,0.512552678585,8.8852930069 -9.23635005951,0.515559792519,8.94987106323 -9.21436977386,0.516573429108,8.98344707489 -9.19839000702,0.517585754395,9.02302360535 -9.11644077301,0.515620946884,9.05515098572 -9.06546974182,0.513640582561,9.06071567535 -9.05547904968,0.513647198677,9.0785036087 -9.04549884796,0.515658557415,9.1250743866 -9.03751564026,0.516669392586,9.17265605927 -9.04253101349,0.519677758217,9.23522853851 -9.03454875946,0.521688699722,9.28380584717 -9.02256774902,0.522700548172,9.32937812805 -9.03657150269,0.524702131748,9.37117958069 -9.02759075165,0.526713490486,9.42074871063 -9.02060890198,0.528724372387,9.47232055664 -9.02062416077,0.530733585358,9.52990436554 -9.00864315033,0.532745420933,9.57647800446 -9.01165962219,0.534754216671,9.63905525208 -9.01767349243,0.537762403488,9.70463752747 -8.97369289398,0.53577619791,9.68841075897 -8.91072559357,0.532798469067,9.6809720993 -8.85875511169,0.53081870079,9.68553161621 -8.79478740692,0.528841197491,9.6760931015 -8.74481582642,0.526860773563,9.6806640625 -8.72983646393,0.527873337269,9.72423839569 -8.71385669708,0.528886258602,9.76780605316 -8.72586154938,0.531888484955,9.81060409546 -8.72987747192,0.534897148609,9.87618350983 -8.72189617157,0.535908401012,9.92875957489 -8.96085166931,0.55886900425,10.2604026794 -8.96286773682,0.561878144741,10.3269786835 -8.93889045715,0.56289255619,10.3635540009 -8.27107810974,0.508039236069,9.65995121002 -8.21210193634,0.504056096077,9.62172603607 -8.17412853241,0.504073619843,9.63829135895 -8.10016536713,0.500098407269,9.6118516922 -8.07118988037,0.50011408329,9.63841915131 -8.00422382355,0.49713742733,9.61898422241 -7.94625616074,0.494158923626,9.6095533371 -7.91827201843,0.493169546127,9.6063337326 -7.87829971313,0.4921875,9.61890125275 -7.78834009171,0.487215727568,9.57045650482 -7.74336957932,0.486234724522,9.57602500916 -7.68440246582,0.483256667852,9.56458473206 -7.78039455414,0.494246631861,9.74319267273 -3.40957283974,0.104160115123,4.37342786789 -3.40458369255,0.104165904224,4.38022613525 -3.40060424805,0.105176746845,4.40280437469 -3.36763262749,0.103193454444,4.38837814331 -7.35060405731,0.47038897872,9.53876781464 -7.32462882996,0.47140416503,9.56634044647 -7.28064966202,0.468418180943,9.54011821747 -7.24867534637,0.468434453011,9.55869579315 -7.16871500015,0.463460952044,9.51624965668 -7.10774898529,0.460483342409,9.49681568146 -7.07177686691,0.46050080657,9.51137924194 -7.0378036499,0.459517508745,9.52595901489 -6.98183631897,0.457538992167,9.51252365112 -6.94685506821,0.455551177263,9.49630355835 -6.90088510513,0.453570485115,9.4948759079 -6.85591554642,0.45258975029,9.49544334412 -6.82594156265,0.452605873346,9.51601600647 -6.77097463608,0.449627101421,9.50158500671 -6.73500299454,0.449644565582,9.51415157318 -6.68503427505,0.447664737701,9.50572490692 -6.66004991531,0.446674823761,9.50150966644 -6.60908269882,0.444695562124,9.49306869507 -6.56711196899,0.442714035511,9.49464607239 -6.53214025497,0.442731261253,9.50721645355 -6.48517179489,0.440751045942,9.50278282166 -6.43820238113,0.438770711422,9.4973526001 -6.40922880173,0.438786715269,9.5179271698 -6.38224506378,0.437797099352,9.5087184906 -6.33627653122,0.436816781759,9.50528049469 -6.31230163574,0.436831891537,9.53385162354 -6.26333379745,0.43485173583,9.52243423462 -6.20936727524,0.432872921228,9.50500202179 -6.16739749908,0.430891811848,9.50656414032 -6.13041734695,0.428904533386,9.48234462738 -6.09544563293,0.427921801805,9.49291801453 -6.0804681778,0.429934889078,9.53349971771 -6.02150297165,0.426957041025,9.5060710907 -5.99652910233,0.426972568035,9.53363418579 -5.97455406189,0.427987039089,9.56321716309 -5.97857189178,0.431996405125,9.63579654694 -5.94858980179,0.430007725954,9.62157726288 -5.96160459518,0.435014903545,9.70717334747 -5.96962118149,0.439023584127,9.78874874115 -5.98563528061,0.444030195475,9.88134288788 -5.95366334915,0.44404694438,9.89791679382 -5.89969778061,0.441068440676,9.87947750092 -5.87872171402,0.442082643509,9.91206550598 -5.9277176857,0.449077814817,10.0298604965 -5.88474845886,0.448096841574,10.0284318924 -5.85877466202,0.449112296104,10.0550107956 -5.84879684448,0.451124548912,10.1095895767 -5.83182048798,0.453138321638,10.1531639099 -5.8218421936,0.455150455236,10.2077484131 -5.85584259033,0.461148709059,10.3045406342 -5.85286188126,0.46415951848,10.3731241226 -5.85987901688,0.469168305397,10.4607067108 -5.83790445328,0.470182985067,10.4972858429 -5.85391902924,0.476190000772,10.6028690338 -5.81794834137,0.475207597017,10.6154441833 -5.81796693802,0.479217678308,10.6920337677 -5.81897640228,0.481222808361,10.7348165512 -5.79500293732,0.482238024473,10.7703924179 -5.80601835251,0.488245934248,10.8699798584 -5.82403230667,0.494252502918,10.9845657349 -5.82005214691,0.498263567686,11.0591487885 -5.81407308578,0.50127518177,11.131726265 -5.80009651184,0.504288256168,11.1883087158 -5.81410169601,0.507290482521,11.25710392 -5.8121213913,0.511301159859,11.3386869431 -5.80914211273,0.516312301159,11.4212598801 -5.80416250229,0.519323587418,11.4988431931 -5.80218267441,0.524334430695,11.5844211578 -5.80120229721,0.528344929218,11.672003746 -5.82520437241,0.533345162868,11.7648019791 -5.81522703171,0.537357509136,11.8363828659 -5.81224679947,0.541368603706,11.9239606857 -5.81326532364,0.546378552914,12.0185499191 -5.82828092575,0.553385972977,12.1461296082 -5.80830574036,0.555400311947,12.1997146606 -5.81732225418,0.561408936977,12.3172941208 -5.8333272934,0.566410839558,12.4000892639 -5.85034179688,0.573417782784,12.5366725922 -5.80237531662,0.572438001633,12.5362434387 -5.8003950119,0.577448785305,12.6338281631 -5.78242015839,0.580462992191,12.6994028091 -5.78643751144,0.586472392082,12.8109922409 -5.78745651245,0.592482626438,12.9195747375 -5.78146839142,0.594489216805,12.961359024 -5.79448366165,0.601496875286,13.0979480743 -5.77051067352,0.603512167931,13.1535272598 -5.70854854584,0.601535379887,13.1260900497 -3.50522279739,0.29499450326,8.17621612549 -3.4682533741,0.294012099504,8.15880012512 -3.42328739166,0.291031807661,8.12536430359 -3.40330386162,0.29004111886,8.11414813995 -3.36433506012,0.28805911541,8.09073162079 -3.34236168861,0.288073807955,8.10831356049 -3.30439352989,0.286091804504,8.08788967133 -3.27542257309,0.286108076572,8.08946418762 -3.24045324326,0.285125553608,8.07603740692 -3.23146533966,0.285132229328,8.08783912659 -3.19749641418,0.284149646759,8.07740879059 -3.16552615166,0.283166408539,8.06998634338 -3.14455246925,0.283180713654,8.08857536316 -3.11858105659,0.283196508884,8.09814357758 -3.08761024475,0.282212793827,8.09073352814 -3.06163835526,0.282228380442,8.09831237793 -3.04465436935,0.282237291336,8.09408664703 -3.01968169212,0.282252460718,8.10267448425 -2.99271059036,0.281268298626,8.10824871063 -2.96673870087,0.281283766031,8.11483097076 -2.94276618958,0.281298875809,8.12741184235 -2.92079281807,0.282313406467,8.14400100708 -2.90380835533,0.281322002411,8.13678836823 -2.88083600998,0.282337069511,8.15336418152 -2.85886263847,0.282351672649,8.17094993591 -2.83589029312,0.283366680145,8.18752574921 -2.81191778183,0.283381730318,8.20010948181 -2.78594613075,0.283397138119,8.20669364929 -2.76297330856,0.283411979675,8.22227668762 -2.74898815155,0.283420056105,8.22406101227 -2.72701478004,0.284434586763,8.24165153503 -2.70204329491,0.284450143576,8.25422096252 -2.68207001686,0.285464525223,8.28079986572 -2.65709757805,0.285479426384,8.28839492798 -2.63612484932,0.286494195461,8.31396579742 -2.61315250397,0.28750911355,8.33154582977 -2.60616445541,0.288515418768,8.35234737396 -2.5851919651,0.289530187845,8.37891769409 -2.56521844864,0.290544301271,8.40550518036 -2.5482442379,0.292558044195,8.44408512115 -2.52927041054,0.293571949005,8.47467422485 -2.50629782677,0.294586777687,8.49325847626 -2.48432540894,0.295601606369,8.51783370972 -2.48633503914,0.298606336117,8.57362747192 -2.47036075592,0.300619870424,8.61920642853 -2.46338295937,0.304631322622,8.69380092621 -2.44740867615,0.30664485693,8.7413816452 -2.4334332943,0.309657782316,8.79497051239 -2.42845511436,0.314668983221,8.88255977631 -2.43246459961,0.31867352128,8.95334625244 -2.42048835754,0.32168596983,9.01694011688 -2.41351079941,0.326697558165,9.10252761841 -2.4025349617,0.330709964037,9.17511367798 -2.38955998421,0.333723038435,9.24468994141 -2.38358235359,0.338734477758,9.34027671814 -5.86853885651,1.14806234837,23.2331809998 -5.78858327866,1.14708912373,23.2257499695 -5.46570253372,1.08816313744,22.2292995453 -5.63567066193,1.14514064789,23.2318954468 -5.55571508408,1.14316701889,23.2154750824 -5.47775936127,1.1421931982,23.2110481262 -5.43678236008,1.14120662212,23.2008342743 -5.35882663727,1.14023268223,23.1974048615 -5.28486967087,1.13925790787,23.2059841156 -5.20491456985,1.13728427887,23.1905555725 -5.14495277405,1.14130675793,23.2631340027 -5.124979496,1.15532135963,23.5207157135 -5.10100746155,1.16833686829,23.7662963867 -5.09401988983,1.17634367943,23.9190826416 -3.24361228943,0.690714716911,15.5214529037 -3.17265510559,0.684739232063,15.4270219803 -3.12668991089,0.685758650303,15.4486017227 -3.07172751427,0.683779716492,15.4231843948 -3.03276062012,0.686797916889,15.4827604294 -2.99179363251,0.688816130161,15.527346611 -2.97480916977,0.690824627876,15.5691385269 -2.92384576797,0.689844965935,15.5677165985 -2.87088274956,0.68886578083,15.5552940369 -2.81692051888,0.687886655331,15.5358724594 -4.82231760025,1.34250974655,26.9466819763 -4.75335979462,1.34753370285,27.0472621918 -4.67440462112,1.34855973721,27.0958385468 -4.64342451096,1.3525711298,27.1716251373 -4.56746864319,1.35559642315,27.2392024994 -4.49851083755,1.36162054539,27.3547801971 -4.42055511475,1.36464631557,27.4173564911 -4.34659910202,1.36867117882,27.5039367676 -4.26964330673,1.37269663811,27.5785140991 -4.23966312408,1.3777077198,27.6713008881 -4.164706707,1.38173282146,27.7658786774 -4.08875131607,1.38575792313,27.8494586945 -4.01179599762,1.39078342915,27.9360351562 -3.93883919716,1.39680802822,28.0516166687 -3.86088395119,1.40083348751,28.1341934204 -3.18111681938,1.15097355843,23.7707157135 -3.10315132141,1.13399374485,23.468503952 -3.01719903946,1.12802052498,23.3830814362 -2.9362449646,1.12504661083,23.332660675 -2.86128902435,1.12407124043,23.3272399902 -2.79633045197,1.12809407711,23.4088172913 -2.72237420082,1.12811851501,23.4074001312 -2.67839837074,1.12413215637,23.3521881104 -2.60344266891,1.1241568327,23.3477668762 -2.53348517418,1.12518048286,23.3793506622 -2.45852947235,1.12420499325,23.3709316254 -2.38957190514,1.12622833252,23.4195137024 -2.31261658669,1.12425327301,23.3930912018 -2.24465894699,1.12827646732,23.4576721191 -2.20768117905,1.12828862667,23.4604625702 -2.14172244072,1.13231146336,23.5500450134 -2.0727648735,1.13633477688,23.6186237335 -1.99081146717,1.13036048412,23.5252075195 -1.941847682,1.14737987518,23.8327922821 -1.8778885603,1.15540218353,23.9763736725 -1.83192396164,1.17742109299,24.3699569702 -1.77895081043,1.16643607616,24.1647510529 -1.6919990778,1.15746259689,24.0183296204 -1.6210423708,1.16148602962,24.0929107666 -1.55608355999,1.1705083847,24.2534980774 -1.49012517929,1.17953085899,24.4250793457 -1.80004835129,1.55148351192,30.9937000275 -1.70809793472,1.55651080608,31.0902843475 -1.66112315655,1.55852460861,31.1320724487 -1.56617379189,1.56155240536,31.1846561432 -1.46922516823,1.56258046627,31.2132396698 -1.37127685547,1.56360888481,31.2208194733 -1.2763273716,1.56663656235,31.2844047546 -1.17837905884,1.56766462326,31.2979869843 -1.12940502167,1.5686788559,31.3217754364 -1.0304569006,1.56570708752,31.2793617249 -0.929509580135,1.56173574924,31.20794487 -0.833560526371,1.5657633543,31.2775287628 -0.737611651421,1.57179117203,31.3881111145 -0.643662035465,1.58381831646,31.598695755 -0.55171173811,1.604845047,31.9822826385 -0.504737079144,1.61885857582,32.2220726013 -0.401790231466,1.6088873148,32.0416603088 -0.3008428514,1.60691571236,32.0082435608 -0.199895575643,1.60594403744,32.0008239746 -0.0999477803707,1.60597193241,31.9884147644 --0.0369798094034,1.57401072979,28.721830368 --0.0819552391768,1.57302379608,28.7076225281 --0.171906068921,1.57104992867,28.6742076874 --0.261856853962,1.56907606125,28.6417922974 --0.350807994604,1.56410193443,28.5523796082 --0.439759135246,1.56212770939,28.5149650574 --0.528710305691,1.56015336514,28.4845504761 --0.574685394764,1.56316661835,28.5373439789 --0.663636565208,1.56219232082,28.5129318237 --0.752587854862,1.56221795082,28.5065193176 --0.841539025307,1.56124341488,28.4901065826 --0.930490136147,1.55926907063,28.460691452 --1.02044093609,1.55929481983,28.4612770081 --1.10839247704,1.55831992626,28.4378681183 --1.15336787701,1.55833280087,28.4316596985 --1.24131953716,1.5573580265,28.4132499695 --1.3312703371,1.5573836565,28.4128360748 --1.42022144794,1.55740892887,28.3984222412 --1.51017248631,1.55843424797,28.4150123596 --1.60012340546,1.55945956707,28.4276008606 --1.64709806442,1.56147265434,28.4503917694 --1.73704910278,1.56149792671,28.4569797516 --1.82700002193,1.56252324581,28.4665718079 --1.91994988918,1.565549016,28.50415802 --2.00790166855,1.56457364559,28.4877490997 --2.10385084152,1.5705999136,28.5623378754 --1.90988051891,1.31357979774,24.4107379913 --2.02782249451,1.34360992908,24.897321701 --2.10477757454,1.34363257885,24.8829135895 --2.13474750519,1.30964708328,24.3345069885 --2.20670413971,1.3066688776,24.2780971527 --2.30165338516,1.31869459152,24.4646835327 --2.41459727287,1.34172332287,24.8272743225 --2.40858888626,1.31372690201,24.3720703125 --2.93940210342,1.5878278017,28.7676467896 --3.0373506546,1.59285366535,28.831237793 --3.13230037689,1.59487903118,28.8608283997 --3.23024916649,1.5989048481,28.9164199829 --3.32119989395,1.59892940521,28.9060115814 --3.42314720154,1.60495567322,28.9876041412 --3.47112202644,1.60596835613,29.0023994446 --3.56707143784,1.60899364948,29.0339927673 --3.66302084923,1.61101877689,29.0595855713 --3.76096963882,1.61404430866,29.0951747894 --3.85691905022,1.61606931686,29.1207714081 --3.95586776733,1.62009477615,29.1633625031 --4.00884103775,1.62310814857,29.2041568756 --4.10379076004,1.62513279915,29.2187538147 --4.20273923874,1.62715828419,29.2513446808 --4.30168771744,1.63018345833,29.2829360962 --4.4036359787,1.63520920277,29.3395328522 --4.5025844574,1.63723444939,29.3681278229 --4.61053037643,1.64426100254,29.4527206421 --4.66350364685,1.6462739706,29.4905204773 --4.77144956589,1.65230059624,29.5641098022 --4.87939548492,1.65832686424,29.640707016 --4.98334312439,1.66235268116,29.6882991791 --5.08729028702,1.66637814045,29.7368984222 --5.19423675537,1.67140424252,29.7964935303 --5.29718494415,1.67442953587,29.8350906372 --5.35715579987,1.67844367027,29.8948841095 --5.4651017189,1.68346953392,29.9584846497 --5.56205177307,1.68449366093,29.9540805817 --5.67199754715,1.6895198822,30.0166740417 --5.77194595337,1.69154441357,30.0292720795 --5.87689352036,1.69556963444,30.063867569 --5.9868388176,1.70059549809,30.1244659424 --6.04581069946,1.70360922813,30.1702632904 --6.16875267029,1.71263706684,30.2898635864 --6.29069519043,1.72066473961,30.4004631042 --6.31066894531,1.6986759901,30.0210571289 --6.35963344574,1.68469178677,29.787651062 --6.44258785248,1.68171286583,29.720249176 --6.49656105042,1.68372559547,29.7410469055 --6.62350177765,1.69375383854,29.8716468811 --6.71645307541,1.69277644157,29.8452453613 --6.80640554428,1.69279849529,29.8098468781 --6.91035366058,1.69482278824,29.8284416199 --6.99830627441,1.6938444376,29.7830410004 --7.09725618362,1.69486773014,29.7836399078 --7.14423179626,1.69487893581,29.7724399567 --7.25017976761,1.69790327549,29.8020420074 --7.3501291275,1.69992649555,29.8016376495 --7.4410815239,1.69894838333,29.7682380676 --7.52803516388,1.69796943665,29.718837738 --7.54301071167,1.67797923088,29.3894348145 --7.50600242615,1.64598083496,28.8690280914 --7.55497694016,1.64699220657,28.8698253632 --7.64992809296,1.64801430702,28.8634281158 --7.748878479,1.65003705025,28.8680286407 --8.07476043701,1.70609486103,29.7056407928 --8.19170475006,1.71112012863,29.768245697 --6.96005964279,1.40593695641,24.99477005 --6.93105840683,1.39093625546,24.7415657043 --6.96602773666,1.3809491396,24.5651569366 --7.03398752213,1.37896704674,24.512758255 --7.14793300629,1.38699197769,24.6183624268 --7.25786018372,1.37702381611,24.4185523987 --7.34781360626,1.38004481792,24.4401550293 --7.37279605865,1.37805223465,24.3859558105 --7.46174955368,1.38007307053,24.402557373 --7.59568929672,1.39210057259,24.5631599426 --7.63265895844,1.38411343098,24.4097576141 --7.71961307526,1.38613367081,24.4173583984 --7.77157783508,1.38114869595,24.313955307 --7.84653520584,1.38016712666,24.2835540771 --7.89151239395,1.38217735291,24.2943572998 --7.97546768188,1.38319706917,24.2909584045 --8.05342388153,1.38421559334,24.2695598602 --8.13038253784,1.38423407078,24.2451591492 --8.21033859253,1.38525283337,24.2327632904 --8.29329490662,1.38627195358,24.2253646851 --8.37325191498,1.38729071617,24.2099666595 --8.41322994232,1.3873000145,24.2027683258 --8.49518585205,1.38831889629,24.1923713684 --8.58214092255,1.39033842087,24.1929683685 --8.6580991745,1.39035618305,24.1675739288 --8.73405742645,1.39037406445,24.138174057 --8.8150138855,1.39139246941,24.1247787476 --8.85899162292,1.39240217209,24.1255760193 --8.94394683838,1.39442098141,24.1241855621 --9.01490688324,1.3934378624,24.081785202 --9.09886264801,1.39445638657,24.0753898621 --9.176820755,1.39447402954,24.0499897003 --9.26477622986,1.3974930048,24.0545959473 --9.34373378754,1.39751064777,24.0342025757 --9.38371181488,1.3985196352,24.0230007172 --9.57363700867,1.417552948,24.2826137543 --9.66655349731,1.39558470249,23.8574180603 --9.84248256683,1.41161561012,24.0720291138 --9.84946155548,1.40062260628,23.8746261597 --9.91343402863,1.40463459492,23.9214305878 --10.0563735962,1.41566061974,24.0520439148 --10.1303329468,1.41567695141,24.0156459808 --12.5135698318,1.74402594566,28.7724952698 --12.6125230789,1.74604451656,28.7511043549 --12.6844835281,1.74305915833,28.6707134247 --12.7514467239,1.7390730381,28.5773181915 --12.8244075775,1.73708772659,28.4979248047 --12.9083652496,1.73610401154,28.4445343018 --12.9813270569,1.73311841488,28.3691444397 --13.0173082352,1.73212563992,28.3289470673 --13.0652761459,1.72613668442,28.2005558014 --13.0652589798,1.71314132214,27.9671516418 --13.0632429123,1.70014560223,27.7357521057 --13.0662250519,1.68815040588,27.5173530579 --13.0502128601,1.67315280437,27.2599468231 --13.0521945953,1.66115760803,27.0455493927 --13.0041999817,1.64815342426,26.838344574 --12.9851875305,1.63415551186,26.5849399567 --13.0211610794,1.62716472149,26.4465427399 --13.1171159744,1.62918174267,26.4321575165 --9.12325191498,1.06466400623,18.2392654419 --9.15222644806,1.06067371368,18.1548690796 --9.16121387482,1.05867803097,18.1006641388 --9.22117900848,1.05869185925,18.0772686005 --9.26814746857,1.05770397186,18.0278682709 --9.34310722351,1.05971968174,18.0334739685 --9.38207817078,1.05773043633,17.9700756073 --9.45603942871,1.05974590778,17.9736824036 --9.55499267578,1.06576430798,18.0232925415 --9.63396167755,1.07177734375,18.103099823 --12.7770452499,1.47618198395,23.8281078339 --12.7810268402,1.46718680859,23.6557064056 --12.761015892,1.45518863201,23.4423065186 --12.7629995346,1.44619321823,23.269903183 --12.8079690933,1.4422031641,23.1785087585 --12.9099235535,1.44622015953,23.1901226044 --12.9109153748,1.44122242928,23.1069259644 --12.9358911514,1.43522977829,22.9805259705 --12.9398736954,1.42723441124,22.8201293945 --12.9298601151,1.41723740101,22.634727478 --12.8888549805,1.40323650837,22.3983192444 --12.8678445816,1.39123809338,22.1999168396 --12.824848175,1.38223493099,22.044708252 --12.8188343048,1.37323844433,21.8743057251 --13.690571785,1.47034800053,23.1960372925 --12.8018054962,1.35424458981,21.5335044861 --12.8067884445,1.34624946117,21.3871021271 --12.6658115387,1.32123661041,21.0006809235 --12.617808342,1.30823504925,20.77227211 --12.5858097076,1.30023348331,20.647069931 --12.6047878265,1.29523980618,20.531671524 --12.7007446289,1.29825520515,20.5432891846 --12.7217226028,1.29326176643,20.4308872223 --12.7746906281,1.29227221012,20.3724956512 --12.8866443634,1.29728925228,20.4071102142 --12.8256454468,1.28328597546,20.1697025299 --12.7436599731,1.27027845383,19.9704875946 --12.7296476364,1.26128089428,19.811088562 --12.731631279,1.25428509712,19.6766853333 --12.755607605,1.25029182434,19.5772857666 --12.7945814133,1.24730014801,19.5028953552 --12.7835693359,1.2393027544,19.3524932861 --12.6895856857,1.22529411316,19.1442775726 --12.674574852,1.21729636192,18.9908752441 --12.6255722046,1.20529472828,18.7884674072 --12.6645450592,1.20230305195,18.7180709839 --12.5845518112,1.18729805946,18.4736557007 --12.5885343552,1.18130230904,18.3542556763 --12.5615262985,1.17230331898,18.1908493042 --12.433552742,1.15529108047,17.9446277618 --12.4895219803,1.15530109406,17.9052410126 --12.5934772491,1.16031634808,17.9318523407 --12.6314516068,1.15832436085,17.8664608002 --12.6984186172,1.15933537483,17.8420734406 --12.6934041977,1.15333855152,17.7156715393 --12.6344041824,1.1413359642,17.5152568817 --12.5914077759,1.13333320618,17.3980541229 --12.4884204865,1.11732590199,17.1416358948 --12.5463886261,1.11733591557,17.1062412262 --12.6823368073,1.12535405159,17.1768608093 --12.4223909378,1.0933303833,16.7134170532 --12.3913841248,1.0843309164,16.5620098114 --12.3883771896,1.08133244514,16.5038108826 --12.3123817444,1.06832838058,16.2943973541 --12.2883720398,1.06032955647,16.156993866 --12.2803592682,1.05433261395,16.0395870209 --12.2783441544,1.04933607578,15.9321870804 --8.99819755554,0.71200555563,11.5902070999 --9.00717830658,0.710011959076,11.5247974396 --9.03816223145,0.711017727852,11.5276050568 --9.07413578033,0.711026787758,11.4972028732 --12.355255127,1.03436052799,15.5673933029 --12.4412174225,1.03837263584,15.5750112534 --12.5341777802,1.04238545895,15.5906295776 --12.5811500549,1.04239356518,15.5472335815 --12.6761102676,1.04740619659,15.5648555756 --12.768078804,1.05341684818,15.6266689301 --12.8400449753,1.05542731285,15.61328125 --12.4711265564,1.01539480686,15.0658092499 --12.9569854736,1.05744504929,15.5545043945 --13.0719404221,1.06345903873,15.5921268463 --13.1559038162,1.06747019291,15.5917415619 --12.2751245499,0.98038828373,14.4983711243 --12.2821073532,0.976392447948,14.4129676819 --12.2810926437,0.972395777702,14.3195667267 --12.2820777893,0.96839928627,14.2291650772 --12.2620687485,0.962400853634,14.1157636642 --13.5877141953,1.08252632618,15.5476303101 --13.685675621,1.08753800392,15.560251236 --12.3260145187,0.957415223122,13.9647760391 --20.2079982758,1.69013285637,22.7800102234 --20.3369541168,1.69514358044,22.7796421051 --12.2529888153,0.93841868639,13.6175546646 --20.5868701935,1.70516371727,22.7699108124 --14.1474819183,1.10559308529,15.5311431885 --12.2459468842,0.926427960396,13.3513479233 --12.2029504776,0.920425832272,13.2621393204 --12.0699539185,0.90042090416,12.950304985 --12.0609426498,0.896423399448,12.8599100113 --12.075922966,0.89342802763,12.793507576 --12.0659122467,0.889430403709,12.7021055222 --12.0639047623,0.887431979179,12.6589002609 --12.1548681259,0.891442835331,12.6745223999 --12.201842308,0.892449975014,12.6431312561 --12.2058258057,0.889453470707,12.5667285919 --12.2038125992,0.885456442833,12.4853277206 --12.1958007812,0.881458938122,12.3979244232 --12.1897878647,0.877461493015,12.3135232925 --12.1687860489,0.8734613657,12.2533187866 --12.1787691116,0.871465206146,12.185921669 --12.1557598114,0.865466475487,12.0855140686 --12.1627435684,0.863470137119,12.0151100159 --12.1717281342,0.860473811626,11.94871521 --12.1627159119,0.856476128101,11.8643131256 --12.1547040939,0.852478504181,11.7809085846 --12.143699646,0.850479185581,11.7316989899 --12.1296882629,0.845481038094,11.6453027725 --12.1366739273,0.843484580517,11.5768966675 --12.1396589279,0.840487718582,11.5075025558 --12.1276473999,0.836489796638,11.4220933914 --12.1286334991,0.83349275589,11.3506937027 --12.1356172562,0.830496251583,11.2842903137 --12.1036186218,0.826495289803,11.2190856934 --12.1056041718,0.823498308659,11.149684906 --12.1085891724,0.820501387119,11.0812835693 --12.1005783081,0.81750369072,11.0028772354 --12.0955648422,0.814506173134,10.9284763336 --12.104549408,0.811509609222,10.8670787811 --12.0735492706,0.807508826256,10.8038673401 --12.0855331421,0.806512475014,10.745467186 --12.0865192413,0.803515315056,10.6780691147 --12.0755081177,0.799517333508,10.5996627808 --12.078494072,0.797520279884,10.5352668762 --12.0774812698,0.794522881508,10.4668655396 --12.0634698868,0.790524661541,10.3874597549 --12.0444688797,0.787524700165,10.3372526169 --12.0514535904,0.78552788496,10.2768535614 --12.0444412231,0.782530128956,10.2044477463 --12.0464277267,0.779532909393,10.1410503387 --12.0434150696,0.776535332203,10.0726461411 --12.0324039459,0.773537218571,9.99824047089 --12.0333900452,0.770539939404,9.93484210968 --12.0333833694,0.769541203976,9.90264129639 --12.0083761215,0.765542268753,9.81722927094 --12.0123615265,0.763545036316,9.75783538818 --12.0173473358,0.760547935963,9.69843482971 --12.0073366165,0.75754982233,9.62702846527 --12.0043239594,0.755552113056,9.5616235733 --12.0143089294,0.753555238247,9.50722503662 --11.9843091965,0.749554693699,9.45201587677 --11.9852962494,0.747557282448,9.39161777496 --11.990281105,0.745559930801,9.33421897888 --11.9762716293,0.742561638355,9.26181221008 --11.9842567444,0.740564465523,9.20741558075 --11.9902420044,0.738567233086,9.15101146698 --11.9652414322,0.735567033291,9.10180568695 --11.9682283401,0.733569562435,9.04440784454 --11.9682159424,0.731571912766,8.98400306702 --11.9592046738,0.728573799133,8.91759777069 --11.941195488,0.724575161934,8.84519290924 --12.0911512375,0.734585225582,8.89783191681 --5.53253698349,0.227251440287,3.98363256454 --11.9251737595,0.7195789814,8.71538162231 --5.55851411819,0.228259220719,3.97522783279 --11.9401264191,0.713587582111,8.52398395538 --11.9311151505,0.71058934927,8.46058177948 --11.9261045456,0.708591282368,8.39917373657 --11.9260921478,0.706593453884,8.34277534485 --11.9180870056,0.704594135284,8.30856990814 --11.9150743484,0.702596187592,8.25016880035 --11.9140625,0.700598299503,8.19276237488 --11.9090509415,0.697600185871,8.13335895538 --11.9030399323,0.695601940155,8.07496547699 --11.9090270996,0.693604290485,8.02356433868 --11.9080142975,0.691606342793,7.96715831757 --11.8890123367,0.689606487751,7.9269528389 --11.8949995041,0.688608765602,7.87655448914 --11.8929872513,0.686610758305,7.82014846802 --11.8969745636,0.684612870216,7.7687497139 --11.8909626007,0.682614564896,7.71135044098 --11.8919506073,0.680616557598,7.65794754028 --11.8819408417,0.678618133068,7.59754037857 --11.8719367981,0.676618635654,7.5643362999 --11.8669261932,0.674620389938,7.50793361664 --11.8709135056,0.672622442245,7.45753288269 --11.8609027863,0.670623958111,7.3981256485 --11.8588914871,0.668625712395,7.34472608566 --11.8558797836,0.666627407074,7.29032182693 --11.8468761444,0.665628015995,7.25912189484 --11.845864296,0.663629829884,7.20672082901 --11.833855629,0.66063117981,7.14731359482 --11.8358430862,0.659633040428,7.09691143036 --11.8288326263,0.657634556293,7.04150819778 --11.8368186951,0.656636536121,6.99510812759 --11.8308095932,0.654638051987,6.94070529938 --11.8248033524,0.652638733387,6.91150093079 --11.8157939911,0.650640130043,6.8561000824 --11.8257808685,0.649642109871,6.81170225143 --11.8237695694,0.648643672466,6.75929164886 --11.8227586746,0.646645247936,6.70889139175 --11.8217477798,0.644646763802,6.65848970413 --11.8147373199,0.642648220062,6.60508728027 --11.8137311935,0.641648948193,6.57988739014 --11.8037214279,0.639650225639,6.52447891235 --11.7997112274,0.638651669025,6.4730758667 --11.7957010269,0.636653125286,6.4216709137 --11.8126859665,0.63665497303,6.38227462769 --11.8846626282,0.639657974243,6.37289571762 --11.8866510391,0.638659358025,6.32549667358 --11.8756475449,0.636659860611,6.29529333115 --11.8836345673,0.636661350727,6.25089263916 --11.9566106796,0.639664053917,6.24151611328 --12.0155897141,0.642666339874,6.22413253784 --12.1065635681,0.647669136524,6.2227563858 --12.1655426025,0.650671243668,6.20437145233 --12.2985086441,0.658674359322,6.22401189804 --12.347495079,0.66067558527,6.22482919693 --12.3604822159,0.660676658154,6.18142700195 --12.3324766159,0.65667706728,6.11801671982 --12.3304672241,0.655677855015,6.06862020493 --12.3374557495,0.654678761959,6.02322053909 --12.3364448547,0.653679430485,5.97381734848 --12.336435318,0.651680231094,5.92541742325 --12.3084344864,0.649680316448,5.8872051239 --12.3304214478,0.649681270123,5.84981250763 --12.3224124908,0.647681832314,5.79740524292 --12.3124036789,0.645682394505,5.74500370026 --12.3303918839,0.64568322897,5.70560741425 --12.3123836517,0.643683671951,5.6491985321 --12.2153949738,0.635683357716,5.57996463776 --12.2763757706,0.638684332371,5.56158733368 --12.4153432846,0.647685647011,5.57823181152 --14.8049526215,0.80869615078,6.61761951447 --14.7299566269,0.801694452763,6.52719449997 --14.6559619904,0.79569286108,6.43776893616 --14.575966835,0.788691401482,6.34634065628 --14.4949760437,0.78269058466,6.28311443329 --14.4289779663,0.776689291,6.19969558716 --14.3549814224,0.770688056946,6.11327171326 --14.2929840088,0.764686822891,6.03184509277 --14.2309865952,0.759685695171,5.95242929459 --14.1549901962,0.752684772015,5.86700344086 --14.0909919739,0.747683823109,5.78758382797 --11.7703256607,0.590692162514,4.74819421768 --11.7713165283,0.589692831039,4.70479154587 --11.7213144302,0.584693670273,4.64137792587 --11.6823101044,0.581694602966,4.58195877075 --11.6753015518,0.579695284367,4.53554916382 --11.6672925949,0.578696012497,4.49015045166 --11.6652889252,0.577696323395,4.46794843674 --11.6742773056,0.577696859837,4.42854785919 --11.6682691574,0.575697481632,4.38314008713 --11.6652593613,0.574698030949,4.33973932266 --11.6632509232,0.573698580265,4.2963347435 --11.6672401428,0.573699057102,4.25593709946 --11.6642313004,0.571699559689,4.21253395081 --11.6542272568,0.570699930191,4.18732500076 --11.651219368,0.569700419903,4.14492940903 --11.6532096863,0.568700790405,4.10352611542 --11.6512012482,0.568701207638,4.0611243248 --11.648191452,0.56670165062,4.01771593094 --11.648182869,0.566702008247,3.97631525993 --11.6351804733,0.564702391624,3.9511115551 --11.6441698074,0.564702510834,3.91271185875 --11.6381616592,0.563702940941,3.86930775642 --11.6341533661,0.562703311443,3.82690668106 --11.6291446686,0.561703681946,3.78349757195 --11.6361351013,0.560703635216,3.74510121346 --11.6291265488,0.559704005718,3.70169591904 --11.6261224747,0.558704197407,3.67948627472 --11.5711212158,0.554705679417,3.62106728554 --11.5031204224,0.549707591534,3.55864048004 --11.4921131134,0.54770809412,3.51523780823 --11.5051031113,0.547707974911,3.47883701324 --11.4880962372,0.546708524227,3.43342804909 --11.4860877991,0.545708715916,3.39302706718 --11.4840841293,0.544708848,3.37282896042 --11.4760761261,0.543709218502,3.33042240143 --11.4730672836,0.542709350586,3.29002141953 --11.4820575714,0.542709112167,3.25261831284 --11.4850492477,0.542708992958,3.21422052383 --11.4900398254,0.541708827019,3.17581725121 --11.4580354691,0.538709938526,3.12740540504 --11.4730291367,0.53970938921,3.11120176315 --11.478020668,0.539709150791,3.0738067627 --11.4610137939,0.537709593773,3.02939391136 --11.4550065994,0.536709725857,2.9889934063 --11.4629974365,0.53670924902,2.95158886909 --11.4629888535,0.535709142685,2.91319346428 --11.4559812546,0.534709215164,2.87178230286 --11.4599781036,0.534708917141,2.85358476639 --11.4429712296,0.532709360123,2.81017446518 --11.4479627609,0.532708883286,2.77277445793 --11.4749517441,0.533707380295,2.74037766457 --11.4339485168,0.530708909035,2.69196462631 --11.4109420776,0.528709590435,2.64755105972 --11.4219341278,0.52870875597,2.61215639114 --11.4339294434,0.52970802784,2.59596085548 --11.4739179611,0.531705677509,2.56656885147 --11.5139064789,0.533703267574,2.53717947006 --11.5358963013,0.534701645374,2.50378656387 --11.5598859787,0.53569984436,2.47039031982 --11.6068744659,0.537696778774,2.44301390648 --11.5588722229,0.533698558807,2.39359116554 --11.4978742599,0.529701471329,2.36137008667 --11.714840889,0.542688250542,2.33064770699 --11.7558298111,0.544685065746,2.30026054382 --11.7968206406,0.546681761742,2.26987600327 --11.8178119659,0.547679543495,2.23447608948 --11.8528022766,0.5496763587,2.20309495926 --11.8857965469,0.551673829556,2.18990564346 --11.9167871475,0.552670776844,2.15651392937 --11.9497785568,0.554667472839,2.12312054634 --11.9997692108,0.557663083076,2.09374403954 --12.0047626495,0.556661248207,2.0553457737 --12.0497531891,0.559656977654,2.02396011353 --12.0937461853,0.561653375626,2.01177406311 --12.1227388382,0.563649892807,1.97738492489 --12.1567296982,0.564645946026,1.9429910183 --12.1947221756,0.566641747952,1.91061377525 --12.2267141342,0.568637728691,1.87521600723 --12.2547073364,0.569633901119,1.83982491493 --12.3066987991,0.572628378868,1.80844676495 --12.319694519,0.573626458645,1.79024899006 --12.3556871414,0.575621843338,1.75586330891 --12.4046792984,0.577616214752,1.7234852314 --12.4326725006,0.579611897469,1.68709230423 --12.4696645737,0.581606984138,1.65271174908 --12.5096588135,0.583601593971,1.61732006073 --12.6276464462,0.590590178967,1.59296536446 --12.6656417847,0.592585980892,1.57778072357 --12.7046356201,0.594580352306,1.5423989296 --12.7326307297,0.596575438976,1.50500893593 --12.782623291,0.598568737507,1.47063207626 --12.8216171265,0.600562751293,1.43424701691 --12.8506126404,0.602557361126,1.39585196972 --12.8926067352,0.60455095768,1.35946893692 --12.9376020432,0.607545614243,1.34429037571 --12.9715976715,0.609539687634,1.30690717697 --13.01359272,0.611532866955,1.26952075958 --13.0565872192,0.613525867462,1.23213636875 --13.0805826187,0.615520358086,1.19274544716 --13.1325769424,0.618512392044,1.15636992455 --13.1785726547,0.620504617691,1.11798131466 --13.2155694962,0.622499585152,1.10080039501 --13.2495660782,0.624492764473,1.06141197681 --13.2875623703,0.626485586166,1.0230332613 --13.3285579681,0.629477858543,0.98364585638 --13.3685541153,0.6314702034,0.944261312485 --13.3815526962,0.632464945316,0.902868688107 --12.2695846558,0.562569320202,0.794185221195 --13.4945459366,0.63844794035,0.847317099571 --13.5195426941,0.64044123888,0.8059258461 --13.5785398483,0.643431007862,0.766548037529 --13.5835380554,0.643426179886,0.724154770374 --12.2655677795,0.561554849148,0.598174750805 --12.1955661774,0.557558834553,0.554740428925 --12.2555608749,0.560549557209,0.519366025925 --12.1455621719,0.554559350014,0.493109196424 --13.7385292053,0.652389466763,0.537419497967 --12.4365501404,0.571522414684,0.430439859629 --12.7555427551,0.591484844685,0.405177950859 --12.6335430145,0.583494186401,0.359725028276 --12.1325464249,0.552545070648,0.300102114677 --12.313542366,0.56352186203,0.26777818799 --12.1665420532,0.554536342621,0.242505058646 --12.1805391312,0.555531442165,0.205118179321 --12.1755361557,0.555528581142,0.16570815444 --12.1785335541,0.555524766445,0.127309858799 --12.1835308075,0.555520713329,0.088912203908 --12.1745290756,0.554518222809,0.049500733614 --12.1665277481,0.554517388344,0.0302988439798 --12.1615247726,0.553514420986,-0.0081019224599 --12.1635227203,0.554510474205,-0.0475116185844 --12.1685199738,0.554506242275,-0.0859092175961 --12.1625185013,0.553503274918,-0.124310947955 --12.1765165329,0.55449783802,-0.162704408169 --12.1705141068,0.554494678974,-0.202117085457 --12.1905136108,0.55549031496,-0.22130677104 --12.1825113297,0.555487453938,-0.259709864855 --12.1645097733,0.554485797882,-0.298119038343 --12.1265068054,0.551486670971,-0.33654114604 --12.1175060272,0.551483869553,-0.374947845936 --12.1505041122,0.553475618362,-0.414337426424 --12.1845026016,0.555467069149,-0.453723996878 --12.2055025101,0.556462287903,-0.472908228636 --12.1405000687,0.55246669054,-0.510344564915 --12.1614990234,0.554459691048,-0.549738883972 --12.1644983292,0.55445510149,-0.588135719299 --12.1634969711,0.55445086956,-0.62754625082 --12.158495903,0.554447233677,-0.665949881077 --12.1584949493,0.554442882538,-0.704349040985 --12.1694946289,0.555439114571,-0.724548876286 --12.1484937668,0.553437650204,-0.761957228184 --12.1644926071,0.554430902004,-0.80135089159 --12.1604919434,0.554426968098,-0.839753746986 --12.1544914246,0.554423213005,-0.878158867359 --12.4585018158,0.573374450207,-0.935419857502 --14.436580658,0.696079730988,-1.09987342358 --14.2405748367,0.684104800224,-1.11016786098 --14.5085887909,0.700057804585,-1.17343604565 --14.5225934982,0.702048003674,-1.22083103657 --14.3965911865,0.694059371948,-1.25728785992 --14.2175865173,0.683078885078,-1.2897785902 --14.4806041718,0.700031161308,-1.35604870319 --14.5116100311,0.702018380165,-1.40543866158 --14.3426027298,0.691040754318,-1.41371667385 --14.1555967331,0.680062174797,-1.44321012497 --14.3306102753,0.691026985645,-1.50452518463 --14.3326148987,0.691018760204,-1.5509275198 --14.1906108856,0.683033585548,-1.58239340782 --13.9285993576,0.667067945004,-1.60192787647 --13.9996070862,0.672048985958,-1.65328752995 --13.9436063766,0.668054163456,-1.67052149773 --14.3816385269,0.69597452879,-1.76270294189 --14.5506544113,0.706938147545,-1.82802093029 --14.3736476898,0.69595938921,-1.85350191593 --16.8978328705,0.852525830269,-2.19964408875 --16.9428443909,0.85650652647,-2.25901675224 --16.9188537598,0.855498790741,-2.3104262352 --16.6218357086,0.836543977261,-2.29977297783 --16.8428630829,0.850494205952,-2.38206005096 --16.7788677216,0.847493350506,-2.42849564552 --16.3368434906,0.82055914402,-2.42211580276 --16.4228591919,0.82653260231,-2.48646783829 --16.3308620453,0.820537388325,-2.52691674232 --16.2398586273,0.815547883511,-2.54016232491 --16.2028636932,0.813543260098,-2.58657455444 --16.1278686523,0.809545338154,-2.62801384926 --16.062871933,0.805545806885,-2.67044663429 --16.2609004974,0.818497896194,-2.75374484062 --16.1378993988,0.811508893967,-2.7872095108 --16.6459579468,0.843402445316,-2.92234373093 --16.1479167938,0.812489688396,-2.86679649353 --15.9899101257,0.803507626057,-2.89328074455 --14.4877662659,0.709781646729,-2.68745112419 --14.4977750778,0.710770010948,-2.7368490696 --14.6958036423,0.723722100258,-2.81914401054 --14.6878108978,0.72371339798,-2.86655497551 --14.6248121262,0.720715582371,-2.90298748016 --14.4457960129,0.709745764732,-2.89327716827 --14.4057998657,0.707743763924,-2.93269467354 --14.8028526306,0.732654750347,-3.05689167976 --13.7657403946,0.667851924896,-2.90283489227 --13.7307500839,0.666840493679,-2.98665618896 --13.7537593842,0.668826699257,-3.036039114 --13.6997566223,0.665832936764,-3.04827404022 --13.7657718658,0.670810103416,-3.10663294792 --13.6767683029,0.665819168091,-3.13307905197 --13.3767366409,0.647872447968,-3.11364078522 --13.4457521439,0.651848912239,-3.17300271988 --13.5337715149,0.658820748329,-3.23836636543 --13.9098300934,0.682730913162,-3.36856651306 --14.647936821,0.729567527771,-3.56037402153 --13.5347900391,0.659796774387,-3.35136795044 --13.5107946396,0.658792376518,-3.39077997208 --13.3867845535,0.651809871197,-3.40624570847 --13.3397855759,0.649810731411,-3.439671278 --13.4188051224,0.654783546925,-3.50403165817 --13.1587734222,0.638831853867,-3.48457217216 --13.2017841339,0.642817437649,-3.51775240898 --13.115778923,0.637827336788,-3.54019761086 --13.1657934189,0.641806483269,-3.59757447243 --13.0567846298,0.634821891785,-3.61302804947 --13.1348056793,0.640794277191,-3.6783926487 --13.1368141174,0.641784012318,-3.72379589081 --13.0408058167,0.635796606541,-3.74224686623 --13.0008029938,0.633801102638,-3.75346851349 --13.05382061,0.637778818607,-3.81284594536 --13.0748329163,0.639763951302,-3.86323571205 --13.1918611526,0.648726165295,-3.94057059288 --13.3168916702,0.656685829163,-4.0219078064 --13.2278862,0.651696920395,-4.04135322571 --13.3289136887,0.659661829472,-4.11670303345 --13.3499221802,0.660651385784,-4.14589214325 --13.511961937,0.672600865364,-4.24020576477 --13.4049520493,0.666616141796,-4.25466632843 --13.4859781265,0.672584950924,-4.32602548599 --13.5209951401,0.675565004349,-4.3834066391 --13.5820178986,0.680538415909,-4.4487695694 --13.6800413132,0.686507999897,-4.50291442871 --13.6730518341,0.687498033047,-4.54831933975 --13.6550598145,0.687490701675,-4.59073448181 --16.3386116028,0.861788630486,-5.50563383102 --16.0525722504,0.843846440315,-5.46919202805 --13.9321537018,0.707382678986,-4.82578372955 --13.9901838303,0.712348639965,-4.91834926605 --16.2906856537,0.863726973534,-5.74846124649 --17.2599124908,0.92745244503,-6.13730621338 --17.5620002747,0.948353290558,-6.3025302887 --16.4247741699,0.875640749931,-5.96757698059 --16.4427967072,0.877618730068,-6.03196287155 --17.8611373901,0.972214341164,-6.59655380249 --17.9501686096,0.978179931641,-6.66070413589 --20.0156669617,1.11459100246,-7.4719119072 --20.0567073822,1.11855614185,-7.55828237534 --20.0277290344,1.11854040623,-7.61969518661 --20.0737724304,1.12350344658,-7.70906591415 --19.945772171,1.11651539803,-7.73353719711 --20.0028152466,1.12147521973,-7.82689762115 --19.93983078,1.11846876144,-7.87533044815 --19.8898353577,1.11647081375,-7.89255952835 --19.979888916,1.12442076206,-7.99889755249 --19.8588886261,1.11743116379,-8.02436447144 --19.8729248047,1.12040245533,-8.10275363922 --19.9109649658,1.12436676025,-8.19012451172 --20.3771190643,1.15720415115,-8.45124721527 --20.4031410217,1.1591835022,-8.49942970276 --20.4141788483,1.16215419769,-8.57881832123 --19.0898609161,1.07552480698,-8.10799217224 --19.0358772278,1.07351696491,-8.15642166138 --20.4412879944,1.16906690598,-8.81698799133 --18.8018741608,1.06154000759,-8.1993560791 --18.7718982697,1.06052553654,-8.25576496124 --18.6308746338,1.05255675316,-8.23105049133 --18.8619709015,1.06946158409,-8.40030765533 --18.6509418488,1.05650258064,-8.37983417511 --18.9290523529,1.07739162445,-8.57206249237 --18.5359706879,1.05249071121,-8.46869182587 --18.6250286102,1.06043803692,-8.57903671265 --18.2819595337,1.03852260113,-8.49564361572 --18.4690303802,1.05245113373,-8.61472702026 --18.47706604,1.05442392826,-8.68912124634 --18.4090766907,1.05142116547,-8.72855854034 --18.5221443176,1.06136000156,-8.85088253021 --18.5901966095,1.06831264496,-8.95424079895 --18.5902309418,1.06928706169,-9.02664089203 --18.5032367706,1.06529045105,-9.05709075928 --18.3652095795,1.05732369423,-9.02636909485 --18.5963172913,1.07522118092,-9.20962905884 --21.0391368866,1.24337530136,-10.468539238 --18.5363674164,1.07418942451,-9.32545852661 --20.8431587219,1.23437976837,-10.5374526978 --20.8131904602,1.2353593111,-10.6038627625 --20.7962265015,1.23633396626,-10.678273201 --22.0816783905,1.32587563992,-11.3666830063 --21.5105342865,1.28903973103,-11.1644277573 --21.4405555725,1.2860314846,-11.2138633728 --21.4626083374,1.28999078274,-11.3112468719 --21.4176368713,1.2889739275,-11.3726634979 --21.5097179413,1.2979080677,-11.5070018768 --21.7588500977,1.31778562069,-11.7252435684 --21.846906662,1.32573711872,-11.8153839111 --21.8389511108,1.3277053833,-11.8997850418 --23.7887077332,1.46596515179,-13.0369701385 --23.7447471619,1.46594202518,-13.1103916168 --23.7067871094,1.46591722965,-13.1858043671 --23.6848373413,1.46688580513,-13.2712106705 --23.6058635712,1.46487569809,-13.3246526718 --23.6739177704,1.47083044052,-13.4118080139 --39.4369697571,2.58490681648,-22.3372955322 --39.359046936,2.58486318588,-22.4557209015 --36.6731185913,2.39980340004,-21.0937957764 --35.0956039429,2.29233431816,-20.3431720734 --34.9766540527,2.28831410408,-20.4226341248 --34.8507041931,2.28329706192,-20.49609375 --34.774723053,2.28029370308,-20.5253334045 --34.6607704163,2.27727198601,-20.6057891846 --34.5488243103,2.27325034142,-20.6862411499 --34.4208717346,2.26923489571,-20.7567043304 --34.3069229126,2.26521372795,-20.8361625671 --34.2109794617,2.2631855011,-20.9256076813 --34.2570991516,2.27110123634,-21.1009616852 --34.4172172546,2.28500437737,-21.2720489502 --34.5393714905,2.29788804054,-21.4963531494 --34.6945381165,2.31475710869,-21.7436389923 --36.6324806213,2.45990180969,-23.1027755737 --36.1113624573,2.42704105377,-22.9364929199 --36.1314811707,2.43396043777,-23.1078605652 --35.3431892395,2.37924861908,-22.6875610352 --35.2832717896,2.37920236588,-22.8049793243 --35.2303543091,2.38115215302,-22.9283981323 --35.0133666992,2.3701710701,-22.9449195862 --34.7183418274,2.35322332382,-22.9094963074 --35.6048583984,2.42377638817,-23.6473007202 --32.7586517334,2.2199139595,-21.9265346527 --32.6876716614,2.21691012383,-21.9537754059 --32.5697174072,2.2128932476,-22.023235321 --32.4367599487,2.20788216591,-22.0827083588 --32.2927932739,2.20287704468,-22.133184433 --32.1838417053,2.1998565197,-22.2076435089 --32.228969574,2.20776844025,-22.3869972229 --32.2901077271,2.21767234802,-22.5793418884 --34.8894348145,2.41448664665,-24.4578323364 --35.9510765076,2.49993801117,-25.3615150452 --34.4645729065,2.40044808388,-24.6482601166 --33.4271621704,2.32784152031,-24.0723285675 --35.2071838379,2.46795701981,-25.5075378418 --35.354385376,2.48481035233,-25.7818222046 --35.4524993896,2.4957253933,-25.9379501343 --33.8297767639,2.37839388847,-24.925409317 --33.7858734131,2.38033699989,-25.0568218231 --33.7339630127,2.38228416443,-25.1822395325 --33.8431396484,2.39715528488,-25.4275512695 --33.7221984863,2.39313387871,-25.5030155182 --32.9809188843,2.34240698814,-25.1108951569 --32.9759750366,2.3453707695,-25.1890926361 --32.9290657043,2.34731578827,-25.3165073395 --32.8151283264,2.34529256821,-25.3939704895 --32.8422622681,2.35320186615,-25.5783348083 --32.9094200134,2.36409044266,-25.7956771851 --32.9555702209,2.37398862839,-25.9980316162 --32.8316230774,2.37096977234,-26.0685005188 --32.5875473022,2.35505008698,-25.9598579407 --32.3145141602,2.34010624886,-25.9094257355 --32.2806167603,2.34304356575,-26.0488357544 --32.5108757019,2.36784815788,-26.4010677338 --32.9562683105,2.40954232216,-26.9301509857 --32.1279029846,2.35087943077,-26.4280986786 --32.0189628601,2.34785413742,-26.50756073 --32.174118042,2.36373448372,-26.7186470032 --32.0671844482,2.36170721054,-26.8011054993 --32.0392990112,2.36663937569,-26.948513031 --32.1434898376,2.38150262833,-27.2068271637 --32.0895881653,2.38344693184,-27.3342494965 --31.9006023407,2.37546277046,-27.3467655182 --31.4184303284,2.34363412857,-27.1074810028 --31.2423858643,2.33268594742,-27.0427951813 --31.2735347748,2.34158611298,-27.2411632538 --31.2386436462,2.34552145004,-27.3825740814 --30.7454566956,2.31270313263,-27.1252994537 --30.9897480011,2.33948779106,-27.5105190277 --30.8007564545,2.33050608635,-27.5170383453 --30.8449192047,2.3413977623,-27.7293949127 --30.8700046539,2.34734106064,-27.8395729065 --31.0092315674,2.36617875099,-28.1388626099 --30.8162403107,2.35719919205,-28.1423873901 --28.1065349579,2.13862872124,-25.8536491394 --28.0095939636,2.1376042366,-25.9271068573 --27.9166526794,2.13657832146,-26.0035610199 --27.8686828613,2.13556575775,-26.0407886505 --27.7727394104,2.13454127312,-26.1142444611 --27.668794632,2.13252139091,-26.1807079315 --27.5768566132,2.13149452209,-26.2581653595 --27.496925354,2.13146066666,-26.3466110229 --27.4179973602,2.1324262619,-26.4360580444 --27.3080463409,2.12941002846,-26.4955253601 --24.1309108734,1.86816871166,-23.6663360596 --24.0379562378,1.86715209484,-23.7248001099 --23.9349937439,1.86414265633,-23.7712631226 --23.8470401764,1.86312377453,-23.8327198029 --23.7610912323,1.86210381985,-23.8961753845 --23.693151474,1.86207330227,-23.9766139984 --23.6371669769,1.86107099056,-23.9958515167 --23.5572223663,1.86004722118,-24.0653038025 --23.4852809906,1.86101901531,-24.1417484283 --23.4023323059,1.85999751091,-24.207201004 --23.3263912201,1.85997068882,-24.2816524506 --23.2594566345,1.86093878746,-24.3640956879 --23.1785106659,1.85991597176,-24.4315471649 --23.1505470276,1.86089682579,-24.4777622223 --23.0655975342,1.85987579823,-24.5422210693 --22.9956607819,1.86084616184,-24.6206626892 --22.9267253876,1.8608148098,-24.7021083832 --22.8137531281,1.85781240463,-24.7355861664 --22.7788448334,1.86175894737,-24.8530063629 --22.7029056549,1.86173284054,-24.925453186 --22.6679382324,1.86171686649,-24.9666805267 --21.2079353333,1.74253487587,-23.6705150604 --21.0258960724,1.73258423805,-23.6170425415 --20.5676136017,1.69782054424,-23.2537689209 --20.3826808929,1.6938034296,-23.3376979828 --20.3316936493,1.69180250168,-23.3529319763 --20.2657489777,1.69277608395,-23.4243774414 --20.1928005219,1.69275391102,-23.4888305664 --20.1278572083,1.69372689724,-23.5612754822 --20.0438995361,1.69271242619,-23.6127338409 --19.9869651794,1.69367980957,-23.6941719055 --19.9120159149,1.69365870953,-23.7566280365 --18.5468044281,1.56759166718,-22.2178115845 --18.258644104,1.54672920704,-22.0154209137 --17.9774894714,1.52586305141,-21.8190250397 --17.749382019,1.51096069813,-21.6825904846 --17.6493930817,1.50796687603,-21.6980628967 --17.5764312744,1.5069527626,-21.7475185394 --17.5214881897,1.50792551041,-21.8189601898 --17.4905109406,1.50891506672,-21.8491802216 --17.4425735474,1.51088225842,-21.9296188354 --17.3696136475,1.50986802578,-21.9790725708 --17.3346881866,1.5128262043,-22.0744953156 --17.2577228546,1.51181530952,-22.1179523468 --17.2097873688,1.5147819519,-22.1993904114 --17.1418323517,1.51476407051,-22.2548427582 --17.2660160065,1.53063356876,-22.4859523773 --16.0098342896,1.41153264046,-21.0072746277 --15.7546730042,1.39166593552,-20.8088607788 --15.5435571671,1.376765728,-20.6664180756 --15.4145269394,1.37080216408,-20.6299152374 --15.3265380859,1.36780643463,-20.6473846436 --15.281542778,1.36680996418,-20.6536178589 --15.2155780792,1.36679697037,-20.7000713348 --15.1576223373,1.36677777767,-20.7565174103 --15.0896568298,1.36676645279,-20.7999725342 --15.0296964645,1.36674952507,-20.8524169922 --14.9897613525,1.36971533298,-20.9338493347 --14.9167900085,1.36870825291,-20.9703063965 --15.0320301056,1.38754498959,-21.2686252594 --14.8598909378,1.37265372276,-21.0979557037 --15.4470348358,1.46387445927,-22.5051345825 --11.900967598,1.08884739876,-17.5261688232 --11.3577184677,1.05607259274,-17.2483978271 --11.3047428131,1.05606424809,-17.2848453522 --11.2627811432,1.05704641342,-17.3372821808 --11.2267827988,1.05605053902,-17.3415126801 --11.1778125763,1.05703878403,-17.3839550018 --11.27302742,1.07389485836,-17.6492958069 --10.9359722137,1.0599745512,-17.604177475 --11.2537403107,1.11946320534,-18.5463600159 --11.1376876831,1.11251163483,-18.4868545532 --11.0146226883,1.10456824303,-18.4133529663 --10.7864103317,1.08472812176,-18.164932251 --10.6993408203,1.07678234577,-18.0842018127 --10.4902534485,1.0658646822,-17.9891796112 --10.5604562759,1.08073234558,-18.235534668 --10.3843078613,1.06584656239,-18.06407547 --9.91969203949,1.07868158817,-18.5635089874 --9.67387485504,1.08360755444,-18.7987422943 --9.65790843964,1.08559048176,-18.8389606476 --9.61395645142,1.0875685215,-18.8984069824 --9.64112186432,1.09946537018,-19.0957984924 --13.4247999191,1.62892603874,-26.8697147369 --13.3578681946,1.63189613819,-26.9441719055 --13.3309164047,1.633872509,-26.9963989258 --18.8717346191,2.4092066288,-38.3765144348 --18.7207450867,2.40522503853,-38.3710365295 --13.4917678833,1.69134545326,-27.9654960632 --13.4258480072,1.69430935383,-28.0509567261 --13.365940094,1.69826447964,-28.1514110565 --13.2519340515,1.69428694248,-28.1369075775 --13.1879177094,1.69130659103,-28.1151618958 --5.48491191864,0.59477353096,-11.9814453125 --5.51704645157,0.604688107967,-12.1478404999 --18.842168808,2.55379271507,-41.0129890442 --18.1882381439,2.47644472122,-39.9259033203 --17.9701271057,2.46354651451,-39.7784843445 --18.3341369629,2.53589653969,-40.9156036377 --18.231098175,2.52993798256,-40.8578910828 --17.6532802582,2.46251130104,-39.904750824 --17.472234726,2.45356845856,-39.8332977295 --17.4054145813,2.46247601509,-40.0177574158 --17.6672611237,2.52193951607,-40.9609603882 --17.6986522675,2.54570770264,-41.3843421936 --17.359287262,2.5129776001,-40.9490203857 --17.5127716064,2.54767084122,-41.4871025085 --12.963602066,1.84977626801,-31.0660705566 --17.236869812,2.54466128349,-41.556137085 --17.0097293854,2.52878284454,-41.3747253418 --9.0719833374,1.26886641979,-22.4223327637 --9.00601577759,1.26985824108,-22.4587955475 --8.9118976593,1.25994277,-22.3250713348 --8.87298965454,1.2648948431,-22.4295158386 --8.87216854095,1.27579081059,-22.6299304962 --8.80319786072,1.27678513527,-22.662399292 --9.48292922974,1.40266370773,-24.6072807312 --9.38992023468,1.39968430996,-24.5947666168 --9.29791259766,1.39670431614,-24.5832519531 --8.58434772491,1.28073406219,-22.8280105591 --8.48831367493,1.27677023411,-22.7884998322 --8.46445083618,1.28469455242,-22.9409332275 --8.46364402771,1.29658210278,-23.1563453674 --7.73506593704,1.18062126637,-21.394323349 --7.6851272583,1.18359375,-21.4637756348 --7.54797172546,1.17070710659,-21.2912960052 --7.45182323456,1.15880930424,-21.1265773773 --7.42794847488,1.16674041748,-21.2670097351 --7.26371765137,1.14790201187,-21.011554718 --7.29498577118,1.16574120522,-21.3099422455 --7.28816175461,1.17764043808,-21.5053653717 --7.22418832779,1.17763566971,-21.5358276367 --7.16322278976,1.1786261797,-21.5742893219 --7.13925886154,1.18060922623,-21.6145172119 --7.08330821991,1.18259036541,-21.6689739227 --7.13064432144,1.20538759232,-22.0403556824 --6.99648046494,1.19250535965,-21.8598747253 --6.83022069931,1.17268407345,-21.5744190216 --6.78028726578,1.17565429211,-21.6478710175 --6.5840382576,1.15583181381,-21.3756484985 --6.52307224274,1.15682244301,-21.4141139984 --6.45909643173,1.15781998634,-21.4405765533 --6.38709688187,1.15583205223,-21.4420509338 --6.30005216599,1.15187299252,-21.393535614 --6.24008893967,1.15286195278,-21.4349994659 --6.20119142532,1.1588101387,-21.5464439392 --6.21936178207,1.17070877552,-21.7326393127 --6.15840148926,1.17169654369,-21.7761058807 --6.11048078537,1.17565953732,-21.8625583649 --6.04249811172,1.17566132545,-21.8820323944 --5.99156999588,1.17962932587,-21.9594860077 --5.92559432983,1.18062710762,-21.9859542847 --5.88257312775,1.17764675617,-21.9631996155 --5.81559419632,1.17864692211,-21.9856700897 --5.75663995743,1.18063116074,-22.0351295471 --5.72378206253,1.18855547905,-22.1885738373 --5.68189525604,1.19549834728,-22.3100261688 --5.56975698471,1.18459737301,-22.1615333557 --5.47668218613,1.17865717411,-22.0810241699 --5.4416847229,1.17866230011,-22.0832557678 --5.38474655151,1.18163704872,-22.149723053 --5.33081674576,1.18460655212,-22.2251834869 --5.25279712677,1.18263208866,-22.2036647797 --5.18280553818,1.18164026737,-22.2121334076 --5.10077047348,1.17867529392,-22.174621582 --5.07796955109,1.19056582451,-22.3870563507 --5.12430810928,1.21336388588,-22.7482318878 --5.05533075333,1.21336364746,-22.7717075348 --5.00844573975,1.22030687332,-22.893163681 --4.9786362648,1.23220396042,-23.0946063995 --4.98599767685,1.25499629974,-23.4780273438 --4.95519828796,1.266887784,-23.6894702911 --4.89828777313,1.27184736729,-23.7829360962 --4.94970035553,1.29860281944,-24.2191143036 --7.54205465317,2.11607885361,-37.3006019592 --7.41805505753,2.11310338974,-37.2851257324 --7.26290464401,2.10121965408,-37.1096725464 --4.53922796249,1.26294970512,-23.7111129761 --7.03499269485,2.10221576691,-37.1707000732 --6.85470199585,2.08041667938,-36.8482627869 --6.83591651917,2.09329891205,-37.066493988 --6.71391296387,2.09132552147,-37.0470123291 --6.52556324005,2.06556153297,-36.6635818481 --6.4186372757,2.06854128838,-36.7260932922 --6.28254795074,2.06061959267,-36.6166229248 --6.14042329788,2.04971909523,-36.4711608887 --6.00633621216,2.04179549217,-36.364692688 --5.92923879623,2.03486657143,-36.2549667358 --5.83336591721,2.0408141613,-36.3734703064 --5.72040224075,2.04081678391,-36.3959846497 --5.56215047836,2.02299165726,-36.1185302734 --5.48842477798,2.03885197639,-36.3890190125 --5.36941814423,2.03588008881,-36.3675422668 --5.30740213394,2.03390240669,-36.3428039551 --5.19745349884,2.03489589691,-36.3813209534 --5.08548974991,2.03589868546,-36.4038391113 --2.18400788307,0.784497439861,-16.1931934357 --2.11990618706,0.777567207813,-16.093662262 --2.05881977081,0.772627711296,-16.0101261139 --1.96447777748,0.750839293003,-15.662610054 --1.90842151642,0.746881663799,-15.6110801697 --1.89046788216,0.749858677387,-15.6623058319 --1.84851539135,0.752839565277,-15.7177600861 --1.80757474899,0.756813704967,-15.7852134705 --1.76764380932,0.760782122612,-15.8626661301 --1.72166371346,0.762779712677,-15.8891210556 --1.67871546745,0.7657584548,-15.9485778809 --1.65976893902,0.768731713295,-16.0068073273 --1.61581528187,0.771714031696,-16.0602645874 --1.56277954578,0.769744336605,-16.0297279358 --1.51681411266,0.771733641624,-16.0711898804 --3.26061964035,1.95477473736,-35.2927017212 --3.15266275406,1.955773592,-35.3232154846 --3.04469919205,1.95677638054,-35.3467292786 --2.99780249596,1.96272850037,-35.444984436 --2.87062716484,1.94985461235,-35.2525177002 --2.74140095711,1.93500971794,-35.0090408325 --2.64153289795,1.94195735455,-35.1295547485 --2.5285012722,1.93799960613,-35.0840759277 --2.41039085388,1.93008756638,-34.9585952759 --2.30242228508,1.93109345436,-34.9771156311 --2.23218798637,1.91524040699,-34.733379364 --2.1252322197,1.91723906994,-34.7649002075 --2.00402283669,1.90238320827,-34.5404205322 --1.89500617981,1.90041649342,-34.5109367371 --1.78496575356,1.89646351337,-34.4574546814 --1.67390346527,1.89152300358,-34.3819732666 --1.56794345379,1.89352405071,-34.4094924927 --1.50984358788,1.8865929842,-34.3027534485 --1.38953721523,1.86679184437,-33.9822769165 --1.27429580688,1.85095286369,-33.7277908325 --1.174446702,1.85889041424,-33.8673057556 --1.07049524784,1.86088633537,-33.9038238525 --0.961387217045,1.85397160053,-33.7833442688 --0.84910941124,1.83515250683,-33.4938545227 --0.790859282017,1.81930577755,-33.2381095886 --0.681554794312,1.80050134659,-32.922618866 --0.570064008236,1.76980161667,-32.4221229553 --0.472211539745,1.77774095535,-32.5586395264 --0.368014872074,1.76487481594,-32.3521499634 --0.26806512475,1.76686918736,-32.3916664124 --0.166814416647,1.75103271008,-32.1321716309 --0.112526372075,1.67276704311,-30.8483810425 --0.0164714511484,1.66881966591,-30.7848911285 -0.097306355834,1.67305290699,-29.7963352203 -0.192382529378,1.67807042599,-29.8816509247 -0.286278784275,1.67298734188,-29.7879734039 -0.380137771368,1.66488337517,-29.6573047638 -0.476240992546,1.67191588879,-29.7696208954 -0.523239314556,1.67190253735,-29.7727794647 -0.615060448647,1.66077816486,-29.6041126251 -0.705907404423,1.65266823769,-29.4604415894 -0.799928426743,1.65465533733,-29.4907627106 -0.900108218193,1.66672992706,-29.6800727844 -1.00335454941,1.68284118176,-29.936378479 -1.05032074451,1.68081009388,-29.9075450897 -1.14427149296,1.67875790596,-29.8678684235 -1.21673643589,1.64543879032,-29.3402290344 -1.3260627985,1.66659343243,-29.6775283813 -1.43536067009,1.68673217297,-29.986825943 -1.5303362608,1.68569409847,-29.9721508026 -1.61614632607,1.67456519604,-29.7904911041 -1.65192377567,1.66143095493,-29.5706710815 -1.15818226337,1.04708826542,-19.7408485413 -1.23742723465,1.06220495701,-19.9881820679 -1.28416216373,1.046043396,-19.7195606232 -1.98728346825,1.62398517132,-28.9600296021 -2.06912922859,1.61487746239,-28.8123703003 -2.15706372261,1.61181819439,-28.7547035217 -2.20407366753,1.61281168461,-28.7688655853 -2.28492760658,1.60470914841,-28.6292076111 -2.36579084396,1.596611619,-28.498550415 -1.84141719341,1.12760221958,-20.9948959351 -1.91649520397,1.13262653351,-21.0752391815 -1.99258375168,1.138656497,-21.1665763855 -2.05183315277,1.15478134155,-21.4217243195 -2.11275792122,1.15072333813,-21.3460788727 -2.18983244896,1.15574526787,-21.4234218597 -2.95929074287,1.57218039036,-28.0449142456 -3.04524350166,1.57013213634,-28.0042533875 -3.11607432365,1.56001925468,-27.838602066 -3.20303583145,1.55797588825,-27.8069400787 -3.262155056,1.56702804565,-27.9330883026 -3.33096981049,1.55590677261,-27.7504482269 -3.37964272499,1.53571081161,-27.4208259583 -3.47972202301,1.5417304039,-27.5101470947 -3.58584594727,1.55077362061,-27.6454601288 -3.70101976395,1.56384265423,-27.8327636719 -3.79906749725,1.56784522533,-27.890089035 -3.84305429459,1.56782698631,-27.8802566528 -3.88873934746,1.54863870144,-27.5616397858 -3.30926060677,1.25626397133,-22.9207344055 -3.37821984291,1.25422382355,-22.8810901642 -3.44617366791,1.25218069553,-22.8354434967 -3.52318477631,1.25416779518,-22.8497886658 -4.22932434082,1.52632164955,-27.1632080078 -3.65731501579,1.26420760155,-22.9892845154 -3.74438548088,1.26922571659,-23.0656166077 -3.83547115326,1.27625143528,-23.1579494476 -3.91146850586,1.27623128891,-23.1582965851 -3.97137737274,1.27116513252,-23.0656585693 -4.03429889679,1.26710534096,-22.9860248566 -4.07330703735,1.26810050011,-22.9961948395 -4.15935707092,1.27210748196,-23.0515327454 -4.24842309952,1.27812302113,-23.1238651276 -4.34251260757,1.28514993191,-23.2201919556 -4.43961191177,1.29218256474,-23.3285179138 -4.5527882576,1.30525386333,-23.5168228149 -4.65188455582,1.31228423119,-23.6221523285 -4.69289255142,1.31427896023,-23.6323204041 -5.33454751968,1.49361741543,-26.4420642853 -5.25677728653,1.44320333004,-25.6335754395 -5.32971382141,1.44015014172,-25.571931839 -5.66583347321,1.51669955254,-26.7650089264 -5.95269870758,1.5771176815,-27.6901359558 -5.59072303772,1.44509315491,-25.5979480743 -5.61463880539,1.44004011154,-25.5111408234 -5.52188158035,1.38963651657,-24.7106666565 -5.59081935883,1.3865852356,-24.6490268707 -5.67381954193,1.38856565952,-24.6533660889 -5.75581264496,1.38954246044,-24.6507091522 -6.11390113831,1.46506989002,-25.818769455 -6.16776943207,1.45798313618,-25.6831417084 -6.19168806076,1.45293211937,-25.5993366241 -6.33891677856,1.47002589703,-25.849615097 -6.42290258408,1.47099840641,-25.8399543762 -7.11414480209,1.62709724903,-28.2546730042 -7.22017526627,1.63109004498,-28.2959976196 -7.3894329071,1.65119540691,-28.5812549591 -7.45448923111,1.65621209145,-28.6464042664 -7.56251716614,1.65920329094,-28.6857299805 -7.6775727272,1.66520798206,-28.7540416718 -7.81369447708,1.67624521255,-28.8943367004 -7.91670084,1.67822551727,-28.9106674194 -8.02773571014,1.68321967125,-28.9569835663 -8.1457862854,1.68922185898,-29.0223007202 -8.20080089569,1.6912176609,-29.0424594879 -8.28775119781,1.69017016888,-28.9978046417 -8.36667728424,1.68711066246,-28.9261569977 -8.45563411713,1.6860666275,-28.888502121 -8.54860591888,1.68602955341,-28.8658409119 -8.64057445526,1.68599164486,-28.841178894 -8.74056720734,1.68796527386,-28.8425102234 -8.7995891571,1.690964818,-28.8716697693 -8.89757347107,1.69193387032,-28.8630046844 -8.98653316498,1.69189119339,-28.8273487091 -9.07448863983,1.69084692001,-28.7876930237 -9.1564245224,1.68879306316,-28.7270469666 -9.22532844543,1.68372416496,-28.6304092407 -9.30124950409,1.68066346645,-28.5527687073 -9.33520126343,1.6786288023,-28.503950119 -9.42015171051,1.67758214474,-28.4573001862 -9.49808311462,1.67452681065,-28.3906536102 -9.57802009583,1.6724742651,-28.3300094604 -9.65394687653,1.67041659355,-28.2573680878 -9.73288249969,1.66736340523,-28.1947250366 -9.81683349609,1.66631782055,-28.1490707397 -9.85179138184,1.66528642178,-28.1062526703 -9.9417552948,1.66524672508,-28.0746021271 -10.0257081985,1.66420257092,-28.0309486389 -10.1046466827,1.66215133667,-27.9713039398 -10.1916074753,1.66211009026,-27.9346523285 -10.284579277,1.66207456589,-27.9119987488 -10.3685331345,1.66103065014,-27.868347168 -10.4125137329,1.66101026535,-27.850522995 -10.4984703064,1.66096794605,-27.8108711243 -10.5804195404,1.65992164612,-27.7612247467 -10.6673793793,1.65888094902,-27.7245750427 -10.7553396225,1.65884053707,-27.6889266968 -10.8433036804,1.65880119801,-27.6552753448 -10.8922977448,1.6597878933,-27.6534385681 -10.9732446671,1.6587407589,-27.6007957458 -11.0802507401,1.66172134876,-27.6151275635 -11.2083005905,1.66872274876,-27.6804389954 -11.3523864746,1.67773997784,-27.784734726 -11.52252388,1.6917809248,-27.948009491 -11.7137050629,1.70784199238,-28.1612586975 -11.8679199219,1.72592878342,-28.4073314667 -12.0681095123,1.74299287796,-28.6315784454 -12.2552719116,1.75904393196,-28.8238334656 -12.4374170303,1.77308702469,-28.9980983734 -12.5814809799,1.78109240532,-29.0793972015 -12.7065048218,1.7860802412,-29.1167144775 -12.8205032349,1.79005551338,-29.1240444183 -12.8684864044,1.79003667831,-29.1102142334 -12.967455864,1.79099917412,-29.0845546722 -13.0734376907,1.79296720028,-29.0728931427 -13.1663951874,1.79292476177,-29.0342407227 -13.258351326,1.79288125038,-28.9925899506 -13.3483009338,1.79283571243,-28.9459400177 -13.4432611465,1.79279410839,-28.9092903137 -13.4842319489,1.79176926613,-28.8794670105 -13.5651636124,1.79071569443,-28.8118286133 -13.6400899887,1.78765916824,-28.7351932526 -13.7240304947,1.78660964966,-28.6765518188 -13.8119821548,1.78656470776,-28.6289024353 -13.9029359818,1.78652107716,-28.5852527618 -13.9908847809,1.78547477722,-28.5346107483 -14.0328559875,1.78545045853,-28.5057888031 -14.1248130798,1.78540837765,-28.465139389 -14.2117614746,1.78536260128,-28.4144935608 -14.2977075577,1.78431558609,-28.3608512878 -14.3886632919,1.78427302837,-28.3182029724 -14.4886341095,1.78523695469,-28.2925491333 -14.5476360321,1.78722608089,-28.2987098694 -14.658624649,1.79019784927,-28.2940444946 -14.6744537354,1.78010082245,-28.1044654846 -14.7363605499,1.77703738213,-28.0048465729 -14.8763980865,1.78303015232,-28.0561561584 -14.9813766479,1.78499770164,-28.0394973755 -15.0873575211,1.78796613216,-28.0248355865 -15.0512046814,1.77688896656,-27.8500862122 -14.966884613,1.75472891331,-27.4825954437 -14.8054485321,1.72152006626,-26.9781742096 -14.8914031982,1.72147846222,-26.9325332642 -14.9322891235,1.71640753746,-26.8049297333 -14.9831905365,1.71134352684,-26.6963176727 -15.0070533752,1.70426297188,-26.5407314301 -14.9959497452,1.69720828533,-26.4219589233 -15.0288276672,1.69013476372,-26.2843647003 -15.0396757126,1.6810489893,-26.1107883453 -15.0825710297,1.67598319054,-25.9931850433 -15.0954256058,1.6679008007,-25.8266048431 -15.1433315277,1.66383981705,-25.720998764 -15.1742134094,1.65676856041,-25.5854091644 -15.1871519089,1.65373253822,-25.5156116486 -15.2020139694,1.6456540823,-25.3570308685 -15.2429141998,1.64059102535,-25.2424316406 -15.2878198624,1.63653051853,-25.1348266602 -15.3497505188,1.63448119164,-25.0582065582 -15.3886518478,1.62941896915,-24.943605423 -15.4195413589,1.62335252762,-24.8160133362 -15.4054470062,1.61730337143,-24.705242157 -15.4824008942,1.61726367474,-24.6546115875 -15.5443353653,1.61521589756,-24.579990387 -15.5501947403,1.60613822937,-24.4164199829 -15.6151351929,1.60509300232,-24.3477973938 -15.6600484848,1.60103738308,-24.2481918335 -15.7009572983,1.59698009491,-24.1425933838 -15.6688461304,1.58892452717,-24.0088367462 -15.7327861786,1.587880373,-23.9412136078 -15.7907190323,1.58483290672,-23.8635997772 -15.8466510773,1.58278489113,-23.7839870453 -15.9135971069,1.58174276352,-23.7213630676 -16.0005664825,1.58271038532,-23.6887226105 -16.0165195465,1.5806812048,-23.6319255829 -16.1064929962,1.58265018463,-23.6032829285 -16.1794452667,1.58161139488,-23.5496559143 -16.2634124756,1.58257758617,-23.5120201111 -16.3503837585,1.58454585075,-23.4793777466 -16.4253406525,1.58450818062,-23.4287490845 -16.509305954,1.58547413349,-23.3901157379 -16.5733127594,1.58846724033,-23.4022789001 -16.6392593384,1.58742570877,-23.3386573792 -16.7272319794,1.58839392662,-23.306016922 -16.8292179108,1.59136855602,-23.2933635712 -16.9051742554,1.59133076668,-23.2417392731 -16.9901428223,1.59329807758,-23.2051010132 -17.0470790863,1.5912528038,-23.1284885406 -17.1461238861,1.59725999832,-23.186624527 -17.2731380463,1.60324442387,-23.2059516907 -17.3661136627,1.60521399975,-23.1773090363 -17.4620895386,1.60718536377,-23.1536636353 -17.5600719452,1.61015665531,-23.1310195923 -17.620010376,1.60811328888,-23.0584030151 -17.7350063324,1.61209106445,-23.0567474365 -17.7669773102,1.61207008362,-23.0229377747 -17.8529472351,1.61303734779,-22.9852981567 -17.98295784,1.61902034283,-23.0016307831 -18.128988266,1.62601006031,-23.0399436951 -18.2139511108,1.62797558308,-22.9973125458 -18.3349514008,1.63195514679,-23.0016479492 -18.3759326935,1.63293719292,-22.9778327942 -18.4699058533,1.63490653038,-22.9471893311 -18.5768928528,1.6378800869,-22.9315395355 -18.6568527222,1.63884425163,-22.8829078674 -18.7538261414,1.64081370831,-22.853269577 -18.8608093262,1.64478707314,-22.8366184235 -18.9998264313,1.65077185631,-22.8599357605 -19.0748405457,1.65476536751,-22.8760967255 -19.2038440704,1.65974509716,-22.883430481 -19.2978153229,1.66171371937,-22.8497886658 -19.4368267059,1.66869604588,-22.8671150208 -19.5428104401,1.67166817188,-22.8464641571 -19.4826374054,1.65858578682,-22.628950119 -19.3554039001,1.63948321342,-22.3354911804 -19.3483409882,1.63545048237,-22.2557125092 -19.3692474365,1.63039636612,-22.137134552 -19.4161777496,1.62835109234,-22.049533844 -19.4380874634,1.62429857254,-21.9339504242 -19.4639987946,1.62024736404,-21.8233680725 -19.4859104156,1.61519551277,-21.7087860107 -19.5098228455,1.6111446619,-21.5972042084 -19.4997596741,1.60711300373,-21.5174293518 -19.5316791534,1.60306477547,-21.4148426056 -19.5485897064,1.59901332855,-21.2982635498 -19.5705013275,1.59496343136,-21.1866817474 -19.5794048309,1.58891034126,-21.0621109009 -19.5903110504,1.58385801315,-20.939540863 -19.5502243042,1.57681953907,-20.8297901154 -19.5711402893,1.5727711916,-20.7202110291 -19.5560264587,1.56571280956,-20.5716629028 -19.5749435425,1.56166470051,-20.4610843658 -19.5848522186,1.55661487579,-20.3425102234 -19.6227836609,1.55357265472,-20.2539138794 -19.6376991272,1.54952442646,-20.1403408051 -19.6156330109,1.54449295998,-20.0535755157 -19.6505622864,1.54245042801,-19.9619884491 -19.6574745178,1.53740143776,-19.8424186707 -19.6894054413,1.5343593359,-19.7498264313 -19.7043228149,1.5303132534,-19.6402492523 -19.7352523804,1.52727079391,-19.5456676483 -19.7831954956,1.52623343468,-19.4700641632 -19.7561283112,1.52020251751,-19.3813056946 -19.7810554504,1.51715970039,-19.2827224731 -19.8079853058,1.51411831379,-19.1881351471 -19.8349170685,1.51107680798,-19.0925502777 -19.8258190155,1.50502717495,-18.9619960785 -19.8387393951,1.50098323822,-18.8544216156 -19.8196372986,1.49393284321,-18.7168731689 -19.8135910034,1.49090826511,-18.6510982513 -19.810503006,1.48586213589,-18.5305347443 -19.8124160767,1.48081743717,-18.4149665833 -19.8303451538,1.47777616978,-18.3143901825 -19.8612823486,1.47473824024,-18.2268047333 -19.8581962585,1.46969354153,-18.1082420349 -19.886133194,1.4676554203,-18.0186576843 -19.8740825653,1.46363115311,-17.949886322 -19.8699970245,1.45858740807,-17.8323230743 -19.8849258423,1.45554733276,-17.7317504883 -19.9068622589,1.45250952244,-17.6391677856 -19.8987751007,1.44746601582,-17.5196075439 -19.9117050171,1.44342672825,-17.4190349579 -19.9416465759,1.44139111042,-17.3344478607 -19.9015789032,1.43536329269,-17.2436981201 -19.9145107269,1.4323246479,-17.1441249847 -19.9214382172,1.42828571796,-17.040555954 -18.3043308258,1.2909617424,-15.5362014771 -18.1821861267,1.27690505981,-15.3317270279 -12.9338188171,0.845974504948,-10.7630548477 -12.9117841721,0.84295976162,-10.7092857361 -12.9207496643,0.840939760208,-10.6477060318 -12.8356571198,0.830904304981,-10.5071973801 -13.0057201385,0.841910898685,-10.5805006027 -8.26680088043,0.458130925894,-6.58936023712 -8.27578830719,0.45712274313,-6.55377197266 -8.34680461884,0.460119247437,-6.54636049271 -8.39481544495,0.462116986513,-6.5417509079 -8.38379192352,0.459105938673,-6.49017620087 -8.43480491638,0.462104022503,-6.48756551743 -8.45079803467,0.461097180843,-6.45797014236 -8.47179317474,0.461090922356,-6.43137931824 -8.49178695679,0.461084485054,-6.40379238129 -8.53080177307,0.463085412979,-6.41297626495 -8.52778339386,0.46207600832,-6.36839485168 -8.57079124451,0.463072866201,-6.35878944397 -8.58678340912,0.46306604147,-6.32820320129 -8.62578868866,0.464062362909,-6.31559753418 -8.6297750473,0.463054120541,-6.27601909637 -8.66878795624,0.46505472064,-6.28420448303 -8.68177986145,0.465047687292,-6.25161743164 -8.7027759552,0.465041726828,-6.22502565384 -8.73277568817,0.465036958456,-6.20542430878 -8.77878379822,0.467033982277,-6.19681882858 -8.77776908875,0.466025561094,-6.15424013138 -8.82377719879,0.468022584915,-6.14563179016 -8.83377456665,0.468019604683,-6.13183641434 -8.86677646637,0.469015210867,-6.11423063278 -8.87776660919,0.468008190393,-6.07965230942 -8.9087677002,0.469003528357,-6.0600528717 -8.93676757812,0.468998610973,-6.03845310211 -8.97777366638,0.470994859934,-6.0248541832 -8.96975421906,0.468986272812,-5.97827672958 -9.00576496124,0.470986038446,-5.98246431351 -9.02876186371,0.470980584621,-5.95687103271 -9.05876255035,0.471975713968,-5.93528079987 -9.0727558136,0.471969485283,-5.90369129181 -9.1157617569,0.472965925932,-5.89108896255 -9.13675785065,0.472960472107,-5.86449193954 -9.15475177765,0.472954601049,-5.83490657806 -9.17875671387,0.473953038454,-5.83010292053 -9.20275497437,0.474947929382,-5.80550289154 -9.20174026489,0.47294062376,-5.76392555237 -9.24174499512,0.474936693907,-5.7483291626 -9.30375957489,0.47793468833,-5.74770736694 -9.32475566864,0.477929234505,-5.72011709213 -9.33774757385,0.477923244238,-5.68753099442 -11.1795549393,0.612060248852,-6.83249998093 -11.0634832382,0.602041304111,-6.7100110054 -11.0054397583,0.596027433872,-6.62646865845 -10.9453954697,0.590013623238,-6.54193162918 -10.9263687134,0.587002754211,-6.4823756218 -10.903342247,0.583992063999,-6.42181253433 -10.8863258362,0.581986427307,-6.38803720474 -10.9053163528,0.581978738308,-6.35344552994 -11.0053405762,0.586976110935,-6.36680650711 -10.9713087082,0.58296495676,-6.2992606163 -10.9662895203,0.581955850124,-6.24969100952 -11.0192947388,0.583950340748,-6.23507785797 -11.0432882309,0.583943009377,-6.20249128342 -11.0222702026,0.581937670708,-6.16771316528 -10.9522266388,0.575925469398,-6.08118581772 -11.0242395401,0.578921079636,-6.07755851746 -11.0862464905,0.581915974617,-6.06694507599 -11.0312099457,0.576905190945,-5.99040460587 -11.1062231064,0.580900669098,-5.98678350449 -10.9511489868,0.568885624409,-5.85530900955 -13.5451183319,0.750997841358,-7.27080059052 -13.5741062164,0.751987278461,-7.23121166229 -13.6551122665,0.755979061127,-7.22058343887 -13.5530519485,0.746963143349,-7.10908651352 -13.5780382156,0.746952950954,-7.06849336624 -13.861117363,0.764952003956,-7.16473674774 -13.5689897537,0.742930173874,-6.95435857773 -13.8310728073,0.760933637619,-7.06540107727 -12.8366985321,0.689889669418,-6.48948287964 -12.8066692352,0.685879051685,-6.42292976379 -12.735625267,0.679867386818,-6.33540439606 -12.7025957108,0.675857305527,-6.26884841919 -12.6965751648,0.673847973347,-6.2152838707 -12.694565773,0.672843456268,-6.18949794769 -12.6845445633,0.670834302902,-6.13493013382 -12.7385444641,0.672826766968,-6.11232233047 -12.7565317154,0.672818422318,-6.07173728943 -12.7945270538,0.674810528755,-6.04113721848 -12.8395242691,0.675802767277,-6.01353597641 -12.8535108566,0.675794482231,-5.97095298767 -12.8755092621,0.67679053545,-5.95615816116 -12.9295091629,0.678782880306,-5.93254995346 -12.9324932098,0.677774608135,-5.88497161865 -13.0044984818,0.681767165661,-5.86935377121 -13.0294885635,0.681759059429,-5.83077192307 -13.0504789352,0.681751012802,-5.79118490219 -13.0854721069,0.682743310928,-5.75858354568 -13.1244745255,0.684739351273,-5.75078010559 -13.1414632797,0.684731423855,-5.70919561386 -13.1674547195,0.685723543167,-5.67160606384 -13.2404594421,0.688715875149,-5.65498590469 -13.2314405441,0.68670797348,-5.60142087936 -13.2864398956,0.689700245857,-5.57680797577 -13.3124303818,0.689692378044,-5.53822422028 -13.3434314728,0.691688597202,-5.5274143219 -13.3834266663,0.692680716515,-5.49482011795 -13.4324245453,0.694672882557,-5.46621751785 -13.4574146271,0.695665240288,-5.42762708664 -13.5104141235,0.697657287121,-5.4000248909 -13.5524091721,0.699649512768,-5.3684220314 -13.5483989716,0.69864577055,-5.34164237976 -13.5843935013,0.699638009071,-5.30704689026 -13.6483945847,0.702629983425,-5.28343582153 -13.6803865433,0.703622281551,-5.24684333801 -13.7053785324,0.704614698887,-5.2072558403 -13.7873830795,0.708606243134,-5.18963670731 -13.8093738556,0.709598779678,-5.14904689789 -13.8353729248,0.710594773293,-5.1342458725 -13.8613643646,0.710587203503,-5.09465837479 -13.8873548508,0.711579680443,-5.05506896973 -13.9073448181,0.711572349072,-5.01348161697 -13.9483394623,0.713564574718,-4.97888851166 -14.0193414688,0.71655601263,-4.95527601242 -14.00532341,0.714549601078,-4.90071105957 -14.049325943,0.717545092106,-4.89189863205 -14.0783185959,0.71853774786,-4.85330438614 -14.1073093414,0.718530237675,-4.81371879578 -14.1813116074,0.722521483898,-4.79010391235 -14.1802968979,0.721514999866,-4.74052906036 -14.2643013,0.726505935192,-4.71990728378 -14.3343019485,0.729497313499,-4.69429206848 -14.3422966003,0.729493737221,-4.67150640488 -14.3822908401,0.731485903263,-4.63491249084 -14.439289093,0.733477592468,-4.60430431366 -14.4832830429,0.735469639301,-4.56870794296 -14.5032730103,0.736462652683,-4.52611637115 -14.5892772675,0.740453124046,-4.50349712372 -14.6042728424,0.741449415684,-4.48270654678 -14.7002782822,0.746439397335,-4.46307754517 -14.8252887726,0.75342810154,-4.45242834091 -14.7222547531,0.746426045895,-4.36892414093 -14.8202590942,0.751415848732,-4.34929084778 -14.8482503891,0.752408564091,-4.30769920349 -14.9082479477,0.755399823189,-4.27509403229 -14.8482294083,0.750399470329,-4.23134803772 -14.9242305756,0.754390001297,-4.20372962952 -14.9552230835,0.756382644176,-4.16214036942 -13.0298624039,0.631470263004,-3.55470633507 -12.861823082,0.619474828243,-3.46223711967 -12.8498125076,0.618471980095,-3.41566991806 -12.8198041916,0.6154717803,-3.38589859009 -12.8247966766,0.615468204021,-3.34432172775 -12.8187885284,0.614465296268,-3.29975152016 -12.8127784729,0.61346244812,-3.25518274307 -12.8307733536,0.6134583354,-3.21660518646 -12.8207654953,0.612455844879,-3.17103934288 -12.8217573166,0.611452817917,-3.12945747375 -12.8427562714,0.612450182438,-3.11266803741 -12.8937578201,0.615444242954,-3.0830655098 -12.9367570877,0.617438912392,-3.05146455765 -12.9687547684,0.618434131145,-3.01687073708 -12.9957513809,0.619429647923,-2.98028612137 -15.9491825104,0.807241737843,-3.65300583839 -15.7581415176,0.794248342514,-3.55454850197 -15.8041419983,0.796242713928,-3.53973507881 -15.8471355438,0.798234641552,-3.49714541435 -15.9951429367,0.807219684124,-3.47948789597 -15.9641256332,0.804216444492,-3.4199359417 -15.9851160049,0.805209815502,-3.37235379219 -16.1661281586,0.816192269325,-3.35968279839 -16.1011066437,0.811191678047,-3.2931470871 -16.1671085358,0.815184533596,-3.28132271767 -16.1780967712,0.815178632736,-3.23074817657 -16.2120895386,0.816171228886,-3.18515944481 -16.2950878143,0.821160197258,-3.1495423317 -16.2980766296,0.820155024529,-3.09697341919 -16.3690719604,0.82414484024,-3.05836296082 -16.4210720062,0.82713842392,-3.0415532589 -16.4430599213,0.828131914139,-2.99296879768 -16.4870548248,0.830123782158,-2.94837331772 -16.5580501556,0.834113478661,-2.9077694416 -16.5970420837,0.835105717182,-2.86217355728 -16.6380348206,0.837097704411,-2.81558585167 -16.6970291138,0.840088367462,-2.77298021317 -16.7520275116,0.844081521034,-2.75516986847 -16.8110218048,0.847072064877,-2.71156787872 -16.8690166473,0.850062727928,-2.66796278954 -16.93501091,0.853052616119,-2.62436127663 -17.0030059814,0.857042372227,-2.58175039291 -17.0930042267,0.862030148506,-2.54113698006 -17.1019916534,0.862024903297,-2.48855805397 -17.1909942627,0.868014931679,-2.47472691536 -17.2409858704,0.870006024837,-2.42713356018 -17.2649765015,0.870999515057,-2.3755531311 -17.3259716034,0.873989701271,-2.3299472332 -17.3969650269,0.877979040146,-2.28533649445 -16.3178596497,0.81007283926,-2.07935976982 -16.1968421936,0.802080631256,-2.01085782051 -16.1408309937,0.799084126949,-1.97710752487 -16.0738182068,0.794087290764,-1.91757047176 -16.0448074341,0.79208701849,-1.86301541328 -15.9827928543,0.788089931011,-1.80348730087 -16.033788681,0.790082335472,-1.75988376141 -15.976776123,0.78708511591,-1.70234513283 -15.9857730865,0.787082910538,-1.67756056786 -15.9857645035,0.787080287933,-1.62699127197 -15.9897565842,0.78607738018,-1.57741582394 -16.0027503967,0.787073671818,-1.52883505821 -16.0287418365,0.788068652153,-1.48025882244 -16.0637378693,0.790062785149,-1.43366730213 -16.0267276764,0.787064194679,-1.3791205883 -16.088727951,0.791056752205,-1.3602989912 -16.1177215576,0.793051600456,-1.31271123886 -16.1667175293,0.795044362545,-1.26611876488 -16.188709259,0.796039879322,-1.21753525734 -16.2767086029,0.802028596401,-1.17392027378 -16.3747062683,0.807016193867,-1.13030302525 -16.5917072296,0.820991039276,-1.09562039375 -18.6958065033,0.950765907764,-1.22972238064 -18.7517967224,0.953756213188,-1.17512595654 -18.8517894745,0.959741771221,-1.12350475788 -9.75538349152,0.396724671125,-0.45964127779 -9.75338840485,0.396727830172,-0.429066836834 -9.73739242554,0.395732581615,-0.397501826286 -9.75139713287,0.395734101534,-0.367919951677 -9.73039913177,0.394737958908,-0.351148247719 -9.74640369415,0.395739197731,-0.322552412748 -9.72640800476,0.394744575024,-0.290989816189 -9.74741363525,0.395745426416,-0.261407703161 -9.73741817474,0.394749730825,-0.230834469199 -9.73442268372,0.394753307104,-0.200262501836 -9.72542476654,0.39375603199,-0.184483394027 -9.75043010712,0.395756393671,-0.155884578824 -9.71743392944,0.393763542175,-0.124327726662 -9.73843955994,0.394764453173,-0.0947417244315 -9.72744464874,0.393769174814,-0.0641718879342 -9.72245025635,0.39377322793,-0.0336018651724 -9.71845531464,0.392777115107,-0.00401857681572 -9.74145889282,0.394776135683,0.0107789672911 -9.71746349335,0.392782539129,0.0413434654474 -9.70646953583,0.392787456512,0.0719103068113 -9.71447467804,0.392790079117,0.101496532559 -9.71747970581,0.392793416977,0.132067620754 -9.71148586273,0.392797768116,0.161648988724 -9.71149158478,0.392801523209,0.192218750715 -9.689494133,0.390806108713,0.206999242306 -9.70950126648,0.392807453871,0.237579286098 -9.70950698853,0.392811179161,0.26716285944 -9.69151210785,0.391817390919,0.297721147537 -9.68251800537,0.390822380781,0.327297747135 -9.71252441406,0.392822474241,0.357888013124 -9.68553066254,0.390829890966,0.387451142073 -9.69153404236,0.391831040382,0.402247369289 -9.68854045868,0.391835510731,0.432814031839 -9.6885471344,0.391839504242,0.462396979332 -9.66955375671,0.389846026897,0.491962403059 -9.69855880737,0.391846477985,0.523544669151 -9.66556549072,0.389854848385,0.552109181881 -9.69256973267,0.391853392124,0.567914068699 -9.67357635498,0.390860110521,0.597477376461 -9.68058300018,0.390863448381,0.62805390358 -9.66058921814,0.389870256186,0.656628131866 -9.68359661102,0.391871571541,0.688210308552 -9.65760326385,0.389879345894,0.716775655746 -9.67060947418,0.390881955624,0.747360944748 -9.6636133194,0.390885084867,0.762143671513 -9.67762088776,0.391887694597,0.793717682362 -9.65562820435,0.390895098448,0.822285175323 -9.66363525391,0.390898495913,0.852865576744 -9.65364170074,0.390904247761,0.881448626518 -9.66364955902,0.390907526016,0.913019120693 -9.64465332031,0.389912426472,0.926795899868 -9.65766048431,0.390915155411,0.957385778427 -9.63166904449,0.389923453331,0.985941827297 -9.64967536926,0.390925616026,1.01752698421 -9.64268302917,0.390931278467,1.04709935188 -9.65969085693,0.391933590174,1.07868540287 -9.63269901276,0.390942126513,1.10625004768 -9.6477022171,0.39194226265,1.12205529213 -9.63471126556,0.390949010849,1.1516160965 -9.64171886444,0.391952753067,1.18220031261 -9.62472629547,0.390960067511,1.21076631546 -9.63773345947,0.391963094473,1.24234902859 -9.61774253845,0.390970826149,1.26992201805 -9.6327495575,0.391973674297,1.30249643326 -9.6187543869,0.390978246927,1.3162740469 -9.63076210022,0.391981482506,1.34785735607 -9.61777114868,0.390988379717,1.37642931938 -9.63177871704,0.392991274595,1.40801906586 -9.61178779602,0.391999423504,1.4365748167 -9.63579463959,0.393000811338,1.46917486191 -9.61379909515,0.392006725073,1.48194539547 -9.61780834198,0.393011212349,1.51252841949 -9.61181640625,0.392017304897,1.54210138321 -9.61682510376,0.393021821976,1.57367408276 -9.60283374786,0.392029196024,1.60224127769 -9.61084270477,0.393033236265,1.63382232189 -9.60185146332,0.393039792776,1.66240179539 -9.60985565186,0.39404129982,1.67918968201 -9.59886455536,0.393048256636,1.70776367188 -9.60987281799,0.394051998854,1.74034130573 -9.59688282013,0.39405938983,1.76891028881 -9.60389137268,0.394063711166,1.80049204826 -9.5889005661,0.394071370363,1.82806861401 -9.59690952301,0.395075678825,1.86064112186 -9.5869140625,0.394080013037,1.87442171574 -9.60492134094,0.396082699299,1.90801072121 -9.58593177795,0.395091205835,1.93557465076 -9.59194087982,0.396095812321,1.9671574831 -9.580950737,0.395103096962,1.9957306385 -9.58895969391,0.396107524633,2.0283074379 -9.56897068024,0.395116209984,2.05487966537 -9.58397388458,0.396116793156,2.07366895676 -9.57598400116,0.396123796701,2.10323810577 -9.58499240875,0.397128045559,2.13582062721 -9.56600379944,0.396136701107,2.16239500046 -9.5830116272,0.398139804602,2.19697856903 -9.56502246857,0.397148489952,2.22454190254 -9.57902622223,0.398149251938,2.24333286285 -9.56703662872,0.398157000542,2.27190279961 -9.57204532623,0.398161947727,2.3034901619 -9.56105709076,0.398169755936,2.33305001259 -9.56806564331,0.39917448163,2.36563205719 -9.55507659912,0.399182409048,2.39321160316 -9.56208515167,0.400187343359,2.42678236961 -9.55609130859,0.399191230536,2.44057369232 -9.54910182953,0.399198353291,2.47014784813 -9.55711174011,0.40020313859,2.50372409821 -9.56812000275,0.40220746398,2.53829956055 -9.54113197327,0.400217920542,2.56286692619 -9.55414199829,0.402221858501,2.59745144844 -9.55115222931,0.402228415012,2.62802958488 -9.55315685272,0.402231276035,2.64481210709 -9.54316806793,0.402238994837,2.67339038849 -9.55617713928,0.40424311161,2.70896625519 -9.52919006348,0.402253806591,2.73353004456 -9.53819942474,0.403258442879,2.76711821556 -9.5402097702,0.404264420271,2.79969263077 -9.53421497345,0.404268652201,2.81447148323 -9.52322673798,0.40427672863,2.84304618835 -9.54423522949,0.406279504299,2.88063526154 -9.50824928284,0.40429186821,2.90219783783 -9.52825832367,0.406295031309,2.940772295 -9.52726840973,0.406301558018,2.97235107422 -9.5242805481,0.407308518887,3.00392246246 -9.51428604126,0.40631338954,3.01671028137 -9.53229427338,0.408316761255,3.05429506302 -9.50530910492,0.407327920198,3.0788538456 -9.51531791687,0.408332586288,3.11344456673 -9.50433063507,0.408341109753,3.14300823212 -9.50234222412,0.408347934484,3.1745865345 -9.50135231018,0.409354567528,3.20617008209 -9.52035522461,0.41135469079,3.22896075249 -9.49037075043,0.409366369247,3.25152897835 -9.50337982178,0.411370903254,3.28910160065 -9.50639057159,0.412377029657,3.32268118858 -9.49640274048,0.412385463715,3.35225176811 -9.48141670227,0.411394715309,3.37982392311 -9.5034236908,0.41339763999,3.42040681839 -9.48843193054,0.413403511047,3.43119597435 -9.49744224548,0.414408773184,3.46777009964 -9.48845481873,0.414417058229,3.49734735489 -9.4894657135,0.415423691273,3.53092288971 -9.47447967529,0.415433317423,3.55948400497 -9.48648929596,0.416438013315,3.59706497192 -9.46449756622,0.415445148945,3.60485577583 -9.47650718689,0.41644987464,3.64243841171 -9.48751735687,0.418455064297,3.68100595474 -9.45753288269,0.417467147112,3.70257997513 -9.46354389191,0.41847294569,3.73816132545 -9.48155403137,0.420476943254,3.77973127365 -9.45756816864,0.419488012791,3.80331015587 -9.47257232666,0.420488864183,3.82610273361 -9.47558307648,0.421495437622,3.86167359352 -9.46359634399,0.421504676342,3.89124107361 -9.45561027527,0.421513110399,3.9218173027 -9.45562171936,0.42252010107,3.95539975166 -9.44663524628,0.422528833151,3.98597168922 -9.45963859558,0.424530148506,4.00875997543 -9.45665073395,0.424537718296,4.04134082794 -9.4456653595,0.424547016621,4.07190418243 -9.45067596436,0.426553100348,4.10749387741 -9.45668697357,0.427559286356,4.14506626129 -9.43070316315,0.42657122016,4.16863298416 -9.4237165451,0.426579713821,4.20020771027 -9.44271945953,0.428579926491,4.22599935532 -9.43773174286,0.428588092327,4.25857543945 -9.42474746704,0.428597807884,4.28814220428 -9.42775917053,0.430604428053,4.3237285614 -9.42077255249,0.430613160133,4.3562951088 -9.42378330231,0.431620001793,4.39287137985 -9.41579818726,0.43162882328,4.42444515228 -9.40680599213,0.431634217501,4.43822717667 -9.23184585571,0.420673668385,4.39274406433 -6.9702167511,0.268094986677,3.37260198593 -9.37184810638,0.43266287446,4.52794742584 -9.39985656738,0.435665160418,4.57653522491 -9.40686893463,0.436671435833,4.61610841751 -9.39988231659,0.437680244446,4.64868211746 -9.40588665009,0.437682658434,4.66848468781 -9.40190029144,0.438691049814,4.70305395126 -9.39191436768,0.438700526953,4.73462295532 -9.39492702484,0.440707504749,4.77220153809 -9.39294052124,0.440715521574,4.80777454376 -9.39595222473,0.442722499371,4.84535598755 -9.39795780182,0.442725837231,4.86415052414 -9.38997268677,0.443735152483,4.89771270752 -9.38698577881,0.44474324584,4.93229484558 -9.37900066376,0.444752573967,4.96585845947 -9.37801361084,0.445760309696,5.00144433975 -9.3740272522,0.446768701077,5.03602361679 -9.37604045868,0.447776138783,5.07459592819 -9.37404727936,0.448780417442,5.09238147736 -9.37205982208,0.448788613081,5.12895298004 -9.3690738678,0.449796944857,5.16453170776 -9.37008666992,0.451804608107,5.20310354233 -9.35810184479,0.451814562082,5.23368215561 -9.35811519623,0.452822387218,5.27126026154 -9.35412979126,0.453830957413,5.30683708191 -9.36313438416,0.454833358526,5.33161973953 -9.35714912415,0.455842345953,5.36619615555 -9.35516262054,0.456850528717,5.40277814865 -9.34717750549,0.456860095263,5.43734312057 -9.35118961334,0.458867222071,5.47792291641 -9.34420490265,0.459876507521,5.51249742508 -9.34321212769,0.459880709648,5.53128480911 -9.34622478485,0.461888104677,5.5718626976 -9.34823894501,0.462895810604,5.61243486404 -9.33525371552,0.462906122208,5.64301586151 -9.33326816559,0.463914692402,5.68158578873 -9.33728122711,0.465922117233,5.72415494919 -9.32529640198,0.46593233943,5.7557349205 -9.3283033371,0.466935843229,5.7775220871 -9.3293170929,0.468943804502,5.81809616089 -9.32533073425,0.468952536583,5.85468006134 -9.32034683228,0.469961762428,5.89224815369 -9.31935977936,0.471970111132,5.93182373047 -9.30437660217,0.471981108189,5.96239900589 -9.31938076019,0.473982334137,5.99218988419 -9.3153963089,0.474991410971,6.03075933456 -9.30241203308,0.475001960993,6.06233978271 -9.29842662811,0.476011067629,6.10091161728 -9.30843925476,0.478017419577,6.14848899841 -9.28745651245,0.47802978754,6.17605781555 -9.28247261047,0.479038953781,6.21363687515 -9.30047512054,0.481039643288,6.24642753601 -9.29549026489,0.482048779726,6.28400945663 -9.28750610352,0.483058720827,6.32058143616 -9.29751873016,0.485065311193,6.3701505661 -9.28653526306,0.486075609922,6.40373373032 -9.28255081177,0.487084984779,6.44429826736 -9.28656387329,0.489092469215,6.48888111115 -9.28057193756,0.489097982645,6.50666093826 -9.27858638763,0.491106659174,6.54724359512 -9.27860069275,0.492115050554,6.58982229233 -9.26261901855,0.493126779795,6.6223859787 -9.26063346863,0.494135648012,6.66396284103 -9.27064609528,0.496142178774,6.7145409584 -9.25666332245,0.497153431177,6.74811267853 -9.26266860962,0.498156487942,6.77390575409 -9.26368427277,0.500164806843,6.81848239899 -9.25469970703,0.501175105572,6.85605478287 -9.24771499634,0.502184987068,6.89463376999 -9.25072956085,0.504192948341,6.94121074677 -9.2337474823,0.504205048084,6.97377634048 -9.24375343323,0.506207346916,7.00356721878 -9.24576759338,0.507215678692,7.05014228821 -9.20179176331,0.506232857704,7.06170845032 -8.6789188385,0.467344820499,6.70814561844 -8.544962883,0.458380162716,6.64868068695 -8.45699691772,0.453406184912,6.62224197388 -8.41802024841,0.451422661543,6.63381004333 -8.39803218842,0.450431138277,6.63958930969 -8.33806037903,0.447451770306,6.6341547966 -8.28208827972,0.444471687078,6.6317191124 -8.24111270905,0.443488776684,6.64128255844 -8.19713783264,0.441506385803,6.64784908295 -8.15916252136,0.440522909164,6.65941333771 -8.12218666077,0.438539117575,6.67098426819 -8.08220291138,0.436551660299,6.65975904465 -8.04322719574,0.434568315744,6.66932964325 -7.97725868225,0.431590646505,6.65787935257 -7.93428373337,0.429608106613,6.66345071793 -7.87631225586,0.426628738642,6.6570110321 -7.825340271,0.424647927284,6.65557813644 -7.81135892868,0.424659758806,6.68515300751 -7.78237342834,0.423669993877,6.68093967438 -7.74939727783,0.422685652971,6.69450807571 -7.73841571808,0.422697037458,6.72707939148 -7.72443532944,0.423708945513,6.75665473938 -7.56048870087,0.411750882864,6.6561923027 -7.65248441696,0.420741856098,6.77878379822 -7.66948890686,0.423742771149,6.81358766556 -7.68750095367,0.426748424768,6.87216520309 -7.61353397369,0.422772377729,6.84872865677 -7.61355066299,0.423781633377,6.89130449295 -7.54158401489,0.419805407524,6.86985874176 -7.54160022736,0.421814441681,6.91144514084 -7.55860471725,0.423815667629,6.94823789597 -7.56961870193,0.426822841167,7.00181245804 -7.51164865494,0.423843681812,6.99138069153 -7.4616765976,0.420862942934,6.98794984818 -7.43969917297,0.420876860619,7.01151418686 -7.44871330261,0.42388433218,7.06309509277 -7.45372867584,0.425892502069,7.11068105698 -7.42674350739,0.424902647734,7.10746002197 -7.31478691101,0.416934639215,7.04500865936 -7.19084978104,0.409978270531,7.01214170456 -7.207862854,0.413984209299,7.07172489166 -7.20987939835,0.415993213654,7.11730289459 -9.1864233017,0.588603556156,9.10432624817 -9.13844203949,0.58561784029,9.08510303497 -7.13893890381,0.414031147957,7.15723085403 -9.09148597717,0.586646020412,9.15124416351 -7.01000452042,0.407076150179,7.11635780334 -9.07852077484,0.590667188168,9.2513961792 -9.08153533936,0.593675911427,9.31197166443 -9.05855751038,0.593690037727,9.34653949738 -9.07756137848,0.596690773964,9.39433765411 -9.06857967377,0.598702013493,9.44390678406 -9.06059741974,0.600712954998,9.49348640442 -9.0606136322,0.603722453117,9.55305767059 -9.05963039398,0.605732142925,9.61163139343 -9.04364967346,0.60674482584,9.65420532227 -9.07165145874,0.610743701458,9.71300601959 -9.03467655182,0.610760807991,9.73456954956 -8.9767074585,0.607782065868,9.73312950134 -8.91173934937,0.604804694653,9.72269535065 -8.86176967621,0.602824449539,9.72925662994 -8.80280017853,0.600845932961,9.72482299805 -8.76382637024,0.599863350391,9.74239063263 -8.76983356476,0.601867079735,9.78017425537 -8.76385116577,0.603877663612,9.83375453949 -8.7568693161,0.605888724327,9.88733005524 -8.73689174652,0.606902420521,9.92690086365 -8.82988452911,0.61889308691,10.094496727 -8.99185943604,0.636869668961,10.3431072235 -8.97787952423,0.638882160187,10.3916807175 -8.72095298767,0.615939259529,10.1274166107 -8.29007911682,0.578036606312,9.68990802765 -8.2141160965,0.57406181097,9.66246604919 -8.19213867188,0.574075937271,9.69704055786 -8.13117027283,0.571098029613,9.68560695648 -8.06720542908,0.568120956421,9.67116546631 -7.99823141098,0.563139915466,9.61993503571 -8.0512342453,0.571138739586,9.74352836609 -7.90928840637,0.560177445412,9.63307857513 -7.86131811142,0.55919700861,9.63564586639 -7.80634975433,0.556217968464,9.62921237946 -7.75138139725,0.554239094257,9.62277698517 -7.71140909195,0.553256988525,9.6343460083 -7.71241760254,0.554261744022,9.66613483429 -7.51348686218,0.537312030792,9.47767829895 -3.41556191444,0.133153319359,4.36566781998 -3.42058038712,0.135162219405,4.39925050735 -3.41160106659,0.13517343998,4.41385364532 -7.32863235474,0.535403966904,9.57532310486 -7.25966787338,0.531427979469,9.54688644409 -7.2216963768,0.530445635319,9.5584564209 -7.18372392654,0.530463218689,9.56903362274 -7.1237578392,0.526485443115,9.55159568787 -7.08678531647,0.526503026485,9.56416416168 -7.04780483246,0.523516058922,9.54294395447 -7.03982496262,0.525527536869,9.59352493286 -6.95586490631,0.520554602146,9.54109096527 -6.95288419724,0.523565292358,9.59966468811 -6.90091609955,0.52058583498,9.59023571014 -6.85694599152,0.519604802132,9.59180641174 -6.78298425674,0.51462996006,9.55137062073 -6.77399587631,0.51563680172,9.57015800476 -6.70403242111,0.510661065578,9.5337266922 -6.70305109024,0.513671278954,9.59530353546 -6.61909198761,0.508698582649,9.53886508942 -6.60211467743,0.509712040424,9.57744216919 -6.52715349197,0.504737257957,9.53101539612 -6.50316905975,0.503747344017,9.52879333496 -6.46219873428,0.502765595913,9.53137111664 -6.40723228455,0.499787122011,9.51493453979 -6.36326265335,0.49880617857,9.51350402832 -6.31429481506,0.495826154947,9.50308132172 -6.29131937027,0.496840953827,9.53265571594 -6.22635555267,0.492864280939,9.4982252121 -6.19937229156,0.491874992847,9.49000453949 -6.15940189362,0.490893036127,9.49158668518 -6.10843467712,0.48791384697,9.4791469574 -6.07346343994,0.487931162119,9.48971843719 -6.04948806763,0.48794606328,9.51629829407 -5.99852132797,0.485966563225,9.500872612 -5.98854255676,0.48797878623,9.55045032501 -5.97255659103,0.487987011671,9.55724143982 -5.9315867424,0.487005740404,9.55880641937 -5.91760969162,0.488018751144,9.60238456726 -5.91263008118,0.491029918194,9.66096305847 -5.90465116501,0.494041800499,9.71554088593 -5.90466976166,0.498051911592,9.78312301636 -5.88069581985,0.498067110777,9.81269359589 -5.89470148087,0.502069354057,9.87048625946 -5.85073232651,0.500088512897,9.86606025696 -5.84975194931,0.50409913063,9.93563270569 -5.89075946808,0.513100862503,10.0752229691 -5.8297958374,0.50912374258,10.0437860489 -5.83981180191,0.514131844044,10.1323719025 -5.83182382584,0.515138626099,10.1551580429 -5.8518371582,0.522144675255,10.2627439499 -5.84385871887,0.525156795979,10.3243141174 -5.83787918091,0.528168201447,10.3878974915 -5.84489631653,0.533177137375,10.4764757156 -5.86590957642,0.540183126926,10.5910577774 -5.8549323082,0.543195605278,10.6486377716 -5.8719367981,0.547197401524,10.7194261551 -5.85596084595,0.549211025238,10.7700004578 -5.85497999191,0.553221464157,10.8475828171 -5.91498231888,0.566219627857,11.0401697159 -5.84002256393,0.560245275497,10.9827365875 -5.85803699493,0.5672519207,11.099319458 -5.86904382706,0.571255028248,11.1631040573 -5.85706615448,0.574267804623,11.2246828079 -5.83009290695,0.575283527374,11.2572631836 -5.84610748291,0.582290649414,11.3748426437 -5.81913471222,0.583306670189,11.4104137421 -5.82615184784,0.589315593243,11.5119953156 -5.81917333603,0.593327343464,11.5865774155 -5.83417892456,0.598329484463,11.6613693237 -5.83119916916,0.602340519428,11.7469463348 -5.82921934128,0.607351541519,11.8365182877 -5.83023834229,0.61336171627,11.932097435 -5.8632478714,0.622365355492,12.0936851501 -5.83327579498,0.624381780624,12.1272630692 -5.83829402924,0.63039124012,12.2348432541 -5.82430791855,0.631399512291,12.2566213608 -5.82432746887,0.636410057545,12.3561983109 -5.82034778595,0.641421318054,12.4477787018 -5.82136726379,0.647431433201,12.5503616333 -5.81638813019,0.652442932129,12.6429395676 -5.8104095459,0.657454848289,12.7355127335 -5.80043172836,0.662467241287,12.8180942535 -5.79244422913,0.663474202156,12.8548784256 -5.88243722916,0.683466434479,13.1624717712 -5.79148340225,0.676495373249,13.0690374374 -3.50116586685,0.330964833498,7.96545410156 -3.46219706535,0.327982902527,7.94303607941 -3.42622852325,0.32700073719,7.92960214615 -3.41224193573,0.326008468866,7.92940139771 -3.3712747097,0.324027210474,7.90297174454 -3.34030413628,0.32304379344,7.89854860306 -3.31333208084,0.323059529066,7.90312719345 -3.28635978699,0.322075009346,7.90571784973 -3.25438976288,0.321091979742,7.89928817749 -3.22941732407,0.321107119322,7.90687608719 -3.21043324471,0.320116251707,7.89665746689 -3.18146157265,0.319132059813,7.89325094223 -3.15848922729,0.319147258997,7.90881919861 -3.13051772118,0.319163113832,7.90940237045 -3.10654473305,0.319178164005,7.91998529434 -3.07357501984,0.318195134401,7.90856266022 -3.05060219765,0.318210065365,7.92214250565 -3.0396156311,0.318217366934,7.92993450165 -3.01164484024,0.318233430386,7.93150901794 -2.98267388344,0.317249685526,7.93008422852 -2.96070027351,0.317264169455,7.94467401505 -2.93172931671,0.316280275583,7.94225406647 -2.91175580025,0.317294567823,7.96383619308 -2.89577078819,0.317302942276,7.95862531662 -2.86779952049,0.316318780184,7.95820760727 -2.84482741356,0.317333966494,7.97377824783 -2.8288526535,0.318347454071,8.0073595047 -2.79688286781,0.317364305258,7.99693441391 -2.76791143417,0.316380113363,7.99152565002 -2.74993777275,0.317394167185,8.0211019516 -2.73895120621,0.318401426077,8.02889633179 -2.70998096466,0.317417770624,8.02746677399 -2.68800759315,0.318432241678,8.04305553436 -2.66603517532,0.318447202444,8.06262588501 -2.64306235313,0.319462001324,8.07621192932 -2.62208938599,0.320476442575,8.09679508209 -2.60111641884,0.320490986109,8.11837387085 -2.59412837029,0.32149747014,8.13916873932 -2.57415509224,0.323511689901,8.16375160217 -2.55218315125,0.32352668047,8.18532085419 -2.53021025658,0.324541330338,8.20390415192 -2.51223635674,0.326555222273,8.23648548126 -2.49426221848,0.327569067478,8.26906871796 -2.48527574539,0.328576236963,8.28785037994 -2.44634962082,0.33761498332,8.44359588623 -2.4403719902,0.341626346111,8.52018451691 -2.42839646339,0.345639228821,8.58076000214 -2.41842079163,0.349651783705,8.65033340454 -2.42043066025,0.352656513453,8.70912647247 -2.41345357895,0.357668429613,8.79170131683 -2.41047549248,0.363679409027,8.88928318024 -2.39750003815,0.367692232132,8.95086860657 -2.3835246563,0.370705246925,9.00945568085 -2.37554836273,0.375717371702,9.09602928162 -2.36262607574,0.397756636143,9.47254943848 -5.54372644424,1.27217233181,23.2503681183 -3.25644111633,0.672626495361,13.817855835 -5.42779254913,1.27021110058,23.2467308044 -5.34883737564,1.2692373991,23.2383041382 -5.27188110352,1.26726317406,23.2348804474 -5.19592428207,1.26728880405,23.2374534607 -5.1269659996,1.26831305027,23.27302742 -5.10699272156,1.28332769871,23.5296096802 -5.12399721146,1.2993298769,23.7894001007 -5.0800318718,1.30834925175,23.9499778748 -3.27360296249,0.783708155155,15.6454906464 -3.21264195442,0.779730379581,15.5950727463 -3.14068460464,0.771754741669,15.4886541367 -3.09471940994,0.772774159908,15.5122318268 -3.04475569725,0.772794365883,15.5158090591 -3.02777147293,0.774802923203,15.5576000214 -2.98180627823,0.775822281837,15.5801820755 -2.92284536362,0.772844195366,15.5377569199 -2.88487792015,0.776862084866,15.6053371429 -2.84890985489,0.780879497528,15.6849184036 -4.45443964005,1.36758375168,25.0395278931 -2.74597239494,0.770914912224,15.53028965 -4.34550428391,1.37062084675,25.1068954468 -4.27254772186,1.37264561653,25.1574707031 -4.1985912323,1.37467062473,25.2000465393 -4.12363481522,1.37669575214,25.2396240234 -4.05067825317,1.37872040272,25.2902011871 -3.97772169113,1.38174510002,25.3437786102 -3.94874095917,1.38575601578,25.4205665588 -3.88178253174,1.39177954197,25.5171451569 -3.81082487106,1.39480376244,25.5877246857 -3.34099030495,1.22690343857,22.9102954865 -3.25203847885,1.21993076801,22.7958774567 -3.20607376099,1.23095035553,22.9954509735 -3.14511346817,1.23697245121,23.0860328674 -3.10613584518,1.23498499393,23.06782341 -3.0141851902,1.22601306438,22.9264030457 -2.93722963333,1.22303819656,22.8949832916 -2.87527012825,1.22806048393,22.9875602722 -2.82330727577,1.23908102512,23.1661376953 -2.75434947014,1.2411044836,23.2007198334 -2.68439221382,1.24212825298,23.2343006134 -2.64841413498,1.24314033985,23.2480869293 -2.57345795631,1.2411648035,23.230670929 -2.50150132179,1.24218893051,23.2472515106 -2.42954468727,1.24321293831,23.2708282471 -2.35058999062,1.23923826218,23.2144107819 -2.27763366699,1.23926234245,23.2169952393 -2.24665379524,1.2422734499,23.2787837982 -2.17869591713,1.246296525,23.3403625488 -2.10873866081,1.24831998348,23.3849430084 -2.03878164291,1.2513436079,23.4345245361 -1.95382905006,1.24236989021,23.3051052094 -1.88787066936,1.24839246273,23.4006843567 -1.82591080666,1.25741446018,23.5472717285 -1.78893303871,1.25742661953,23.5610580444 -1.72897279263,1.26944804192,23.7596378326 -1.6590154171,1.27347135544,23.820224762 -1.59305727482,1.28249406815,23.9728031158 -1.52909827232,1.29351627827,24.154384613 -1.43216001987,1.3105494976,24.4437599182 -1.36420249939,1.32157254219,24.623336792 -1.27825021744,1.31059849262,24.4509220123 -1.40023458004,1.5675868988,28.595489502 -1.31128311157,1.56761348248,28.6000747681 -1.22133219242,1.56764030457,28.6016578674 -1.12938201427,1.5646674633,28.5552368164 -1.08440649509,1.56368076801,28.5400314331 -0.993456184864,1.56270766258,28.5296096802 -0.905504703522,1.56573402882,28.5861949921 -0.820552170277,1.57575964928,28.7477779388 -0.738598883152,1.59578466415,29.0773620605 -0.647648394108,1.5978115797,29.1069450378 -0.55669772625,1.59783816338,29.1045303345 -0.508723437786,1.59185194969,29.0153198242 -0.416773170233,1.58787870407,28.9439048767 -0.325822621584,1.58590519428,28.9164905548 -0.23487201333,1.58193171024,28.8570766449 -0.14392156899,1.58195817471,28.8576602936 -0.0529711134732,1.57898461819,28.8092422485 --0.0469732396305,1.59001421928,26.0407619476 --0.0879498720169,1.5880266428,26.01055336 --0.168903723359,1.58705103397,26.0001411438 --0.25085708499,1.59007561207,26.038728714 --0.331810772419,1.58609998226,25.9793148041 --0.414763659239,1.58812487125,26.0198955536 --0.494717776775,1.58414900303,25.9464836121 --0.534694850445,1.58216106892,25.9232788086 --0.615648388863,1.58018541336,25.8848628998 --0.696602165699,1.57920956612,25.8744506836 --0.778555512428,1.58123385906,25.8960361481 --0.858509540558,1.57825779915,25.8506221771 --0.93946325779,1.57728207111,25.8442115784 --1.02041697502,1.57730603218,25.8377990723 --1.06139361858,1.57731819153,25.8345890045 --1.14234733582,1.5773422718,25.8281764984 --1.22330117226,1.57836604118,25.8327674866 --1.30425477028,1.57739007473,25.8143520355 --1.38520872593,1.57741391659,25.8149414062 --1.46716213226,1.57843780518,25.8225288391 --1.54711604118,1.57746148109,25.7991161346 --1.58809292316,1.57747340202,25.8089122772 --1.67204558849,1.5804977417,25.8384971619 --1.75599849224,1.58352184296,25.8790893555 --1.83295357227,1.57954478264,25.8116760254 --1.91790604591,1.58256912231,25.8522624969 --1.99786007404,1.58159244061,25.8278503418 --2.07881402969,1.58161580563,25.8254432678 --2.12179017067,1.58362793922,25.849237442 --2.09477710724,1.49563288689,24.5598182678 --2.15873646736,1.48465335369,24.4034099579 --2.23769068718,1.48667633533,24.4139957428 --2.4576022625,1.5927233696,25.944601059 --2.53855586052,1.59174656868,25.9241867065 --2.58753013611,1.59775972366,26.0009803772 --2.67648172379,1.6027841568,26.0685749054 --2.76343417168,1.60580813885,26.1111660004 --2.84838652611,1.60783195496,26.1257553101 --2.93433904648,1.60985577106,26.1493453979 --3.01929187775,1.61187922955,26.1699390411 --3.10524463654,1.61390304565,26.1895294189 --3.15221953392,1.61791551113,26.2333259583 --3.23917150497,1.61993932724,26.2589168549 --3.32712364197,1.62396335602,26.2935085297 --3.41207647324,1.62498664856,26.3001003265 --3.50302767754,1.62901091576,26.3546943665 --3.58997988701,1.63103449345,26.3722858429 --3.67693209648,1.63305807114,26.3888778687 --3.72190785408,1.63506996632,26.4086742401 --3.81085944176,1.63809382915,26.4352664948 --3.89881157875,1.64011740685,26.4588603973 --3.98676395416,1.64314079285,26.4794559479 --4.07871437073,1.64616501331,26.5190448761 --4.16666698456,1.64918828011,26.5416431427 --4.25761842728,1.65221226215,26.571231842 --4.30559301376,1.65522444248,26.6060333252 --4.39654445648,1.65824818611,26.6346263885 --4.4894952774,1.66227221489,26.6772212982 --4.57944631577,1.66429555416,26.7008171082 --4.67339706421,1.66831970215,26.7424106598 --4.76334857941,1.67034304142,26.7590045929 --4.81632184982,1.67535591125,26.8138027191 --4.90727376938,1.67737925053,26.8333969116 --5.00222396851,1.6814031601,26.8759937286 --5.09817361832,1.6864272356,26.920589447 --5.19112443924,1.68945086002,26.9451828003 --5.28407621384,1.69247424603,26.9717788696 --5.38002586365,1.69649815559,27.0153808594 --5.42700147629,1.69750988483,27.0261745453 --5.51995229721,1.70053315163,27.0497722626 --5.61190366745,1.70255613327,27.0633678436 --5.70485544205,1.70557928085,27.0839653015 --5.79780626297,1.70860242844,27.1025619507 --5.89575624466,1.7126262188,27.1441612244 --6.00470256805,1.72065162659,27.2347621918 --6.03668260574,1.7166608572,27.1755580902 --6.06765270233,1.69967377186,26.9131507874 --6.15460586548,1.70069563389,26.9007453918 --6.24855661392,1.70271849632,26.9223423004 --6.35150527954,1.70874273777,26.9819431305 --6.43246030807,1.70776343346,26.9455413818 --6.47843647003,1.70877468586,26.9483375549 --6.5663895607,1.70979619026,26.9429397583 --6.6613407135,1.71281898022,26.9645385742 --6.75429201126,1.71484148502,26.9741363525 --6.84524440765,1.71686339378,26.9777355194 --6.93419790268,1.71788477898,26.9733352661 --7.03514671326,1.72290813923,27.0129337311 --7.10111665726,1.7289223671,27.0897331238 --7.19906711578,1.73294508457,27.1173362732 --7.2930188179,1.73496723175,27.1269359589 --7.38896989822,1.73798942566,27.1425361633 --7.4789223671,1.73901081085,27.1341342926 --7.5648765564,1.73903143406,27.113735199 --7.65682888031,1.74105286598,27.1143360138 --7.70480489731,1.74206399918,27.1191368103 --7.39887714386,1.64402449131,25.7266998291 --7.17190599442,1.54900479317,24.3538627625 --7.25486087799,1.55102479458,24.3514614105 --7.34181547165,1.55304539204,24.365064621 --7.41877222061,1.55306434631,24.3416614532 --7.42975902557,1.54706966877,24.2394580841 --7.52770996094,1.55209183693,24.2860603333 --8.50439739227,1.76024603844,27.1497497559 --7.90255832672,1.60316252708,24.9432849884 --7.97251796722,1.60118019581,24.8918838501 --8.04647541046,1.6001983881,24.8524837494 --8.10245037079,1.60421013832,24.893289566 --8.14941596985,1.59722423553,24.7708854675 --8.95715522766,1.75735104084,26.9515628815 --9.04810905457,1.75837135315,26.939163208 --8.34529972076,1.58927416801,24.5816860199 --8.3712720871,1.57828485966,24.4022789001 --8.42223739624,1.57229936123,24.3018779755 --8.45821762085,1.57230806351,24.2826805115 --8.53617477417,1.57232630253,24.2592811584 --8.61613178253,1.57334470749,24.2408809662 --8.7090845108,1.57636499405,24.2604846954 --8.79004192352,1.57738351822,24.2460899353 --8.87099838257,1.57840180397,24.2306900024 --8.94495677948,1.57841908932,24.1962947845 --8.98993396759,1.57942891121,24.2031002045 --9.06689167023,1.57944667339,24.1736965179 --9.15284824371,1.58146548271,24.1713027954 --9.21881008148,1.5794813633,24.1179084778 --9.3087644577,1.58250069618,24.1235084534 --9.37472629547,1.58051633835,24.0701141357 --9.51167583466,1.59953904152,24.309928894 --9.54462909698,1.57755625248,23.9461212158 --9.70254516602,1.57859098911,23.9013252258 --9.78350162506,1.57960855961,23.884929657 --9.86545944214,1.58062601089,23.8705348969 --9.92043399811,1.58363676071,23.8973407745 --7.94299507141,1.21636784077,18.9406795502 --10.1083421707,1.59067499638,23.9235553741 --10.980050087,1.716807127,25.5448570251 --10.4341907501,1.60873758793,24.0583820343 --11.1789560318,1.72384560108,25.5620727539 --11.2319307327,1.72585570812,25.5738792419 --11.3208866119,1.72787320614,25.5574874878 --11.4048452377,1.72789001465,25.529094696 --11.5017995834,1.73090851307,25.5307044983 --11.5887556076,1.73192548752,25.5093135834 --11.6747121811,1.73294246197,25.4829177856 --11.7346868515,1.73595321178,25.507724762 --11.82264328,1.73797011375,25.4883365631 --11.9135990143,1.73898732662,25.4729423523 --12.0075540543,1.74200487137,25.465555191 --12.0945110321,1.74302148819,25.4411621094 --12.1914663315,1.74603939056,25.4387741089 --12.2774238586,1.74605560303,25.4123840332 --12.3134040833,1.74606275558,25.384185791 --12.3963632584,1.74607849121,25.3497943878 --9.25824928284,1.24367165565,18.754940033 --9.09126091003,1.19966197014,18.1241054535 --9.13423061371,1.1976736784,18.0667057037 --9.17819881439,1.19568538666,18.0123062134 --9.20718193054,1.19569218159,17.9981060028 --9.26314735413,1.19570553303,17.9667072296 --9.31111621857,1.19371759892,17.9213104248 --9.37707901001,1.1957321167,17.908914566 --9.47003364563,1.20074975491,17.9495239258 --9.57498645782,1.20776903629,18.0111351013 --9.72993278503,1.22679162025,18.2339572906 --9.83788490295,1.23381090164,18.2975692749 --9.90984630585,1.23582577705,18.2921733856 --12.703037262,1.63118207455,23.3052101135 --12.7400093079,1.62619113922,23.1978130341 --12.8369655609,1.62920761108,23.2014293671 --10.1966943741,1.2438839674,18.2676010132 --12.9429101944,1.62922716141,23.1328392029 --13.0308694839,1.63124227524,23.1194534302 --13.0678415298,1.62625098228,23.0140571594 --13.2497739792,1.64127743244,23.1646842957 --13.5046863556,1.66631269455,23.4413261414 --12.801867485,1.55923092365,22.0518054962 --13.4676647186,1.64131593704,23.0375156403 --13.5516328812,1.64832806587,23.097328186 --13.6255960464,1.64834082127,23.0579414368 --13.7215528488,1.65135622025,23.0535545349 --12.5828380585,1.47922766209,20.8285598755 --12.5778226852,1.47023129463,20.6721572876 --12.5458240509,1.46222960949,20.5469551086 --12.5618028641,1.45523571968,20.4265518188 --12.5627851486,1.447239995,20.2831478119 --12.5467739105,1.436242342,20.113740921 --12.5217647552,1.4252436161,19.9333362579 --12.5067529678,1.41524589062,19.7709369659 --12.5017375946,1.40624952316,19.6245326996 --12.4607410431,1.39724683762,19.4903202057 --12.4677228928,1.39025175571,19.3669223785 --12.4946985245,1.38625895977,19.2735214233 --12.5646629333,1.38727104664,19.2481327057 --12.6606216431,1.39128601551,19.2617473602 --12.6336126328,1.38028693199,19.0883407593 --12.8935260773,1.40532004833,19.3509902954 --12.7175664902,1.38030219078,19.0197544098 --12.5605926514,1.35328865051,18.6543216705 --12.686542511,1.36130666733,18.7149467468 --12.6515359879,1.35030663013,18.535533905 --12.5065593719,1.32529449463,18.1971054077 --12.4495592117,1.31129205227,17.9916934967 --12.5475244522,1.31930482388,18.0715065002 --12.5765008926,1.31631183624,17.9931144714 --12.6384677887,1.3173224926,17.9597225189 --12.7694177628,1.32534050941,18.025346756 --12.6644296646,1.30633282661,17.7569255829 --12.6864089966,1.30233895779,17.6695308685 --12.541431427,1.27832722664,17.3480930328 --12.455447197,1.26531994343,17.171880722 --12.4904222488,1.26332747936,17.1054840088 --12.4534158707,1.25232732296,16.9400691986 --12.4653968811,1.24733233452,16.8446712494 --12.6453332901,1.26235496998,16.9763050079 --12.3264026642,1.21932542324,16.4368400574 --12.3123912811,1.21232771873,16.3104381561 --12.2364034653,1.20032179356,16.1552219391 --12.2393865585,1.19532597065,16.051815033 --8.95122146606,0.81099909544,11.5533132553 --8.9781961441,0.810007214546,11.5119113922 --9.01517009735,0.810016334057,11.4845161438 --9.03215694427,0.810020744801,11.4683151245 --12.2962865829,1.17035245895,15.5546112061 --12.3252639771,1.1683588028,15.4912185669 --12.451215744,1.17637491226,15.5488424301 --12.560172081,1.18338930607,15.5834608078 --12.637137413,1.1864002943,15.5790786743 --12.693107605,1.18740916252,15.5466861725 --12.6511116028,1.18040680885,15.444475174 --12.7920598984,1.19042384624,15.5171031952 --12.9230108261,1.19843971729,15.5767335892 --13.0299682617,1.20545315742,15.60435009 --12.9599723816,1.1924495697,15.4209375381 --12.2601366043,1.11238658428,14.4873800278 --13.2318725586,1.21148145199,15.5451936722 --13.2948503494,1.21548891068,15.5700082779 --12.2331066132,1.09739279747,14.22336483 --13.4507808685,1.22150921822,15.5522375107 --13.5317459106,1.22451937199,15.5468559265 --13.6047134399,1.2275288105,15.5314722061 --13.6836795807,1.23053872585,15.5230913162 --13.9266109467,1.25356221199,15.7499437332 --13.9066019058,1.24556279182,15.626537323 --12.2000179291,1.06341207027,13.6057462692 --14.0235443115,1.24757814407,15.558763504 --14.0865154266,1.24958622456,15.52937603 --12.2779541016,1.05842900276,13.432554245 --14.3184289932,1.26261103153,15.5866270065 --14.3614120483,1.26461589336,15.584438324 --12.0699691772,1.02641916275,12.9934988022 --12.0189676285,1.01741814613,12.8560857773 --12.0189533234,1.01342141628,12.773680687 --12.0209379196,1.00942504406,12.6952819824 --12.0219221115,1.00542831421,12.6148767471 --12.0928907394,1.00843763351,12.6094913483 --12.1638660431,1.01344513893,12.6443090439 --12.1598529816,1.00944817066,12.5589017868 --12.1648368835,1.00545167923,12.4845018387 --12.1628227234,1.00145471096,12.4030990601 --12.163807869,0.998457849026,12.3256988525 --12.1527967453,0.993460118771,12.2352895737 --12.1677780151,0.990464389324,12.1728916168 --12.1167840958,0.983461916447,12.0826768875 --12.1217689514,0.980465352535,12.0112791061 --12.1217546463,0.977468430996,11.9348754883 --12.1197404861,0.973471343517,11.8574743271 --12.1137275696,0.969473958015,11.7750644684 --12.1277103424,0.966478049755,11.7146711349 --12.0867137909,0.961476445198,11.6364536285 --12.0986967087,0.958480298519,11.5750608444 --12.0866851807,0.954482376575,11.4896535873 --12.077673912,0.94948464632,11.4082508087 --12.0776596069,0.946487665176,11.3348445892 --12.0836439133,0.94349104166,11.2684440613 --12.0676336288,0.938492774963,11.1820402145 --12.0416326523,0.934492349625,11.1218318939 --12.0526161194,0.932496130466,11.0604286194 --12.0436048508,0.928498387337,10.9810199738 --12.042591095,0.924501121044,10.9106216431 --12.0465764999,0.921504259109,10.8442192078 --12.0405635834,0.918506681919,10.7698173523 --12.0365514755,0.914509296417,10.6964092255 --12.0235471725,0.911509752274,10.6512088776 --12.0185346603,0.908512175083,10.5778007507 --12.0145215988,0.904514789581,10.5063972473 --12.0255060196,0.902518212795,10.4490003586 --12.0104961395,0.898519992828,10.3685932159 --12.0074825287,0.895522534847,10.2991905212 --12.0204668045,0.893526077271,10.2437896729 --11.9864673615,0.888525247574,10.1815795898 --11.9874534607,0.885528028011,10.1161746979 --11.990439415,0.883530855179,10.0537748337 --11.9844274521,0.879533171654,9.9833688736 --11.985414505,0.877535879612,9.91996860504 --11.9874000549,0.874538600445,9.85756969452 --11.9573993683,0.870538115501,9.7993516922 --11.9623851776,0.868541002274,9.73995113373 --11.9663715363,0.865543782711,9.68055438995 --11.9523620605,0.861545503139,9.60614871979 --11.9613466263,0.85954862833,9.55074882507 --11.9603328705,0.85755109787,9.48734474182 --11.9483222961,0.853552937508,9.4159412384 --11.9403181076,0.851553738117,9.37773132324 --11.933306694,0.848555862904,9.31133079529 --11.9302940369,0.845558106899,9.24792861938 --11.9302806854,0.842560589314,9.1865234375 --11.9292678833,0.840562999249,9.12511920929 --11.9312543869,0.837565481663,9.06672000885 --11.9232435226,0.83456748724,9.00031375885 --11.911239624,0.832568049431,8.9611082077 --11.9302225113,0.83157145977,8.91570854187 --11.9911966324,0.834576964378,8.90332984924 --5.53154993057,0.276247888803,3.99784708023 --5.53153276443,0.275254309177,3.97043824196 --5.55051231384,0.275261491537,3.95804858208 --11.8701648712,0.813581168652,8.54947948456 --11.8841495514,0.812584102154,8.50208091736 --11.8851366043,0.809586405754,8.44568061829 --11.8761262894,0.806588172913,8.38227462769 --11.8721132278,0.80459022522,8.32186603546 --11.8761005402,0.802592635155,8.26846599579 --11.874089241,0.800594687462,8.21106529236 --11.8530874252,0.797594845295,8.16785430908 --11.8580732346,0.795597195625,8.11545276642 --11.851061821,0.792599022388,8.05504798889 --11.8570489883,0.790601432323,8.00364589691 --11.8540372849,0.788603425026,7.94724702835 --11.8530254364,0.786605417728,7.89083814621 --11.8310232162,0.783605515957,7.84862995148 --11.8350095749,0.781607747078,7.79723119736 --11.8379974365,0.779609918594,7.74482774734 --11.8289871216,0.777611553669,7.6854262352 --11.8339738846,0.77561378479,7.63401794434 --11.8299617767,0.773615598679,7.57761192322 --11.831949234,0.771617591381,7.52621412277 --11.8169469833,0.769617974758,7.49000883102 --11.8129348755,0.766619801521,7.43460559845 --11.8089237213,0.764621555805,7.37919998169 --11.8129110336,0.763623595238,7.32879543304 --11.8019018173,0.760625123978,7.27039480209 --11.7998905182,0.758626878262,7.21699047089 --11.8038768768,0.756628870964,7.16758823395 --11.7888746262,0.754629254341,7.13238143921 --11.7958612442,0.753631293774,7.08497905731 --11.7878513336,0.750632822514,7.02857208252 --11.7868385315,0.748634576797,6.97717142105 --11.7868270874,0.747636377811,6.92576408386 --11.789814949,0.745638132095,6.87736654282 --11.777806282,0.742639482021,6.81996154785 --11.7708015442,0.741640090942,6.79075813293 --11.7757892609,0.740641951561,6.7433552742 --11.7647800446,0.737643361092,6.68694925308 --11.7617683411,0.735644876957,6.63554620743 --11.7597579956,0.733646452427,6.58514499664 --11.7587461472,0.732648015022,6.53473854065 --11.7587347031,0.730649590492,6.48533391953 --11.7467308044,0.728650152683,6.45412969589 --11.7397212982,0.726651489735,6.4007191658 --11.7717046738,0.727653741837,6.37033176422 --11.8276834488,0.730656445026,6.35295152664 --11.8336715698,0.729658007622,6.30755186081 --11.8346595764,0.727659404278,6.25914621353 --11.852645874,0.727661073208,6.22075271606 --11.8876342773,0.72966247797,6.21455717087 --11.9866056442,0.735665559769,6.21919059753 --12.0665807724,0.740668177605,6.2128162384 --12.1235609055,0.743670284748,6.19443750381 --12.256526947,0.751673519611,6.21407556534 --12.311507225,0.754675209522,6.19369649887 --12.2865056992,0.751675307751,6.15648889542 --12.2894954681,0.750676214695,6.10908937454 --12.2824859619,0.748677015305,6.05668544769 --12.2784767151,0.74667775631,6.00527715683 --12.2784662247,0.745678603649,5.95687675476 --12.2764568329,0.743679344654,5.90747451782 --12.2714471817,0.741680085659,5.85606527328 --12.2594442368,0.740680336952,5.82686567307 --12.2624330521,0.738681137562,5.77945804596 --12.2624235153,0.737681865692,5.7320599556 --12.2814102173,0.737682700157,5.69265842438 --12.2674026489,0.735683202744,5.63825035095 --12.2523946762,0.732683718204,5.58485269547 --12.265381813,0.73268443346,5.5424451828 --12.1603946686,0.723684251308,5.47020721436 --12.2483711243,0.728685259819,5.46484422684 --12.2403621674,0.726685762405,5.41343212128 --12.2363529205,0.725686311722,5.36502981186 --12.2383432388,0.724686861038,5.3196310997 --12.2393331528,0.72368735075,5.27322626114 --12.2303247452,0.721687793732,5.22282028198 --12.2243213654,0.719688057899,5.19762229919 --12.2303104401,0.719688475132,5.15422296524 --12.2173032761,0.716688871384,5.10180950165 --12.2212924957,0.716689288616,5.05740642548 --12.221282959,0.714689671993,5.01200771332 --12.2202739716,0.713689982891,4.96661090851 --12.1682729721,0.708690524101,4.89918708801 --12.1542692184,0.706690788269,4.86997365952 --11.6293373108,0.666694104671,4.6093788147 --11.6293268204,0.665694892406,4.56597232819 --11.6293172836,0.664695560932,4.5235748291 --11.6233091354,0.662696242332,4.47816801071 --11.6252985001,0.661696910858,4.43576192856 --11.6192941666,0.660697281361,4.4125623703 --11.6222848892,0.660697877407,4.3711605072 --11.6182756424,0.658698499203,4.32675218582 --11.6062679291,0.656699240208,4.27934026718 --11.620256424,0.656699597836,4.24294710159 --11.6112480164,0.655700206757,4.19754219055 --11.6112384796,0.654700756073,4.15513515472 --11.6072340012,0.653701007366,4.13293504715 --11.5942268372,0.651701688766,4.08652925491 --11.6002168655,0.650702059269,4.04713010788 --11.5962076187,0.649702548981,4.00372219086 --11.5902004242,0.648702979088,3.96031975746 --11.5921907425,0.64770334959,3.91891098022 --11.5991802216,0.647703528404,3.88051533699 --11.5891771317,0.645703911781,3.85630917549 --11.5921678543,0.6457041502,3.81590485573 --11.5891590118,0.644704461098,3.77349829674 --11.5751514435,0.642705023289,3.72809314728 --11.5781431198,0.641705214977,3.68768644333 --11.5781335831,0.640705406666,3.64728760719 --11.4781370163,0.632708132267,3.57384467125 --11.4521360397,0.630708873272,3.54563713074 --11.4601259232,0.629708886147,3.50722908974 --11.439119339,0.627709746361,3.46082139015 --11.4331111908,0.626710116863,3.41942048073 --11.4381017685,0.625710070133,3.38101840019 --11.419095993,0.623710811138,3.33561038971 --11.4220867157,0.623710870743,3.29620170593 --11.4120836258,0.622711241245,3.27400255203 --11.4210729599,0.621711015701,3.23659753799 --11.4030675888,0.619711697102,3.19219136238 --11.433054924,0.621710717678,3.16180181503 --11.3950510025,0.617712140083,3.11138296127 --11.4190397263,0.618711233139,3.07898902893 --11.4000339508,0.616711854935,3.03457975388 --11.4000291824,0.616711854935,3.01437115669 --11.4020204544,0.6157117486,2.97596955299 --11.4140110016,0.615711152554,2.940574646 --11.3810062408,0.61271238327,2.892152071 --11.3939971924,0.613711714745,2.85776352882 --11.4079875946,0.613710939884,2.82236266136 --11.395980835,0.611711204052,2.7799487114 --11.3849782944,0.610711574554,2.75774240494 --11.4229660034,0.612709760666,2.72935986519 --11.3739624023,0.608711600304,2.67793154716 --11.3479576111,0.606712460518,2.63352203369 --11.3629484177,0.606711506844,2.59912729263 --11.3909378052,0.608709871769,2.56773662567 --11.4209270477,0.60970801115,2.53634333611 --11.4559202194,0.611706078053,2.52515339851 --11.4859104156,0.613704144955,2.49376273155 --11.5148992538,0.614702165127,2.46237635612 --11.5278911591,0.61570084095,2.42698025703 --11.4558897018,0.609704017639,2.37254858017 --11.4618825912,0.609703063965,2.33514237404 --11.6718540192,0.623690664768,2.32363200188 --11.7018442154,0.624688088894,2.29124259949 --11.7448339462,0.627684772015,2.26085233688 --11.7678251266,0.628682434559,2.22746777534 --11.8048152924,0.630679190159,2.19608139992 --11.8448057175,0.63267570734,2.1646926403 --11.856801033,0.633674383163,2.14749598503 --11.8987922668,0.635670661926,2.11711764336 --11.9417819977,0.638666689396,2.08572936058 --11.961774826,0.639664053917,2.05033683777 --12.0007658005,0.64166021347,2.01794886589 --12.0467567444,0.644655704498,1.98757302761 --12.0607500076,0.644653201103,1.95017278194 --12.1037445068,0.647649645805,1.93799030781 --12.1377353668,0.649645745754,1.90460634232 --12.1467294693,0.649643361568,1.86620533466 --12.0957269669,0.645645022392,1.8177781105 --12.2457122803,0.655632853508,1.80344796181 --12.2777051926,0.657628595829,1.76805365086 --12.2856988907,0.657626032829,1.72965824604 --12.0757102966,0.642640173435,1.67736756802 --12.3826856613,0.663615942001,1.68510401249 --12.4166784286,0.665611147881,1.64971458912 --12.4556713104,0.667605936527,1.61533212662 --12.5536613464,0.674596190453,1.58897399902 --12.5876550674,0.676591038704,1.55258250237 --12.6556472778,0.680583178997,1.52121222019 --12.6866426468,0.68257945776,1.50502610207 --12.7246370316,0.684573769569,1.46964752674 --12.7656316757,0.687567651272,1.43325853348 --12.8066253662,0.689561486244,1.39788198471 --12.8396205902,0.691555857658,1.36049389839 --12.8816146851,0.694549322128,1.3241109848 --12.9156103134,0.696544885635,1.30692148209 --12.9346065521,0.697540163994,1.26752841473 --11.5606613159,0.602654933929,1.07248520851 --11.3596639633,0.588670611382,1.01399326324 --13.0785903931,0.706517755985,1.15839421749 --13.2295818329,0.716500878334,1.13206517696 --13.1515817642,0.711504220963,1.08162426949 --13.1935787201,0.713496685028,1.04324018955 --13.2335758209,0.716491222382,1.02605986595 --13.2725715637,0.718483865261,0.987681031227 --13.3185682297,0.721475720406,0.949301719666 --13.3355646133,0.722470164299,0.907906115055 --13.38256073,0.72546172142,0.869530797005 --13.4335584641,0.729452610016,0.83014768362 --13.4825553894,0.732443571091,0.79076808691 --13.5215530396,0.734437704086,0.772590458393 --13.5645503998,0.737429022789,0.73220717907 --13.605547905,0.740420460701,0.691826581955 --13.6435461044,0.742412149906,0.651448845863 --12.4015684128,0.656534850597,0.531445860863 --13.654542923,0.743401706219,0.564647316933 --12.333565712,0.651537001133,0.468814849854 --13.7345399857,0.748386263847,0.504087924957 --12.4705581665,0.661515712738,0.39707660675 --13.1045475006,0.704444050789,0.386980682611 --12.1035575867,0.6355484128,0.30108833313 --12.1285543442,0.637542426586,0.263699352741 --12.122551918,0.636539876461,0.225298568606 --12.120549202,0.63653844595,0.206097990274 --12.1145467758,0.63553571701,0.166685968637 --12.1195449829,0.636531770229,0.128285706043 --12.1125421524,0.6355291605,0.0898833870888 --12.1225395203,0.636524498463,0.0514846406877 --12.113535881,0.635522127151,0.0130812358111 --12.1185340881,0.635517954826,-0.0253183338791 --12.1225337982,0.636515676975,-0.0445177406073 --12.1095304489,0.635513663292,-0.0829235687852 --12.1135282516,0.635509550571,-0.121323347092 --12.115527153,0.635505616665,-0.1597237885 --12.117524147,0.635501563549,-0.199134662747 --12.1255216599,0.636496782303,-0.237531945109 --12.1115198135,0.635494709015,-0.27594050765 --12.071518898,0.632497787476,-0.295163571835 --12.0155162811,0.628501057625,-0.332589030266 --11.9945144653,0.627499878407,-0.371007084846 --12.0025119781,0.62849509716,-0.408396571875 --12.0735111237,0.632481992245,-0.447762459517 --12.1145114899,0.635472536087,-0.487145632505 --12.121509552,0.636467456818,-0.526552081108 --12.1045084,0.635467708111,-0.544755280018 --12.1135072708,0.635462224483,-0.584159612656 --12.1105070114,0.635458409786,-0.622563183308 --12.1115055084,0.635454058647,-0.660963237286 --12.109503746,0.635450005531,-0.699365913868 --12.1115026474,0.636445403099,-0.737765073776 --12.1065015793,0.635441720486,-0.776170432568 --12.1115016937,0.636438786983,-0.795365929604 --12.1335020065,0.638431072235,-0.835764765739 --12.0895004272,0.635433018208,-0.871179878712 --12.2425050735,0.64540630579,-0.918506324291 --14.3335886002,0.79009693861,-1.07983338833 --14.2015867233,0.78110897541,-1.11730098724 --14.3495960236,0.791079759598,-1.1726295948 --14.1595897675,0.778104245663,-1.18292784691 --14.0425872803,0.770114660263,-1.21938371658 --14.1135931015,0.775096654892,-1.26975131035 --14.0975961685,0.775091826916,-1.31315672398 --14.3406124115,0.792047083378,-1.37743198872 --14.0035982132,0.768091619015,-1.39500200748 --14.1246089935,0.777065336704,-1.45034205914 --14.116610527,0.777062773705,-1.47254955769 --14.0606107712,0.773063957691,-1.51298201084 --14.1046171188,0.776049494743,-1.56135296822 --14.1616249084,0.781032562256,-1.61273026466 --14.2806367874,0.789005696774,-1.66906034946 --14.5596590042,0.80895203352,-1.74432146549 --14.2776432037,0.788994073868,-1.73766446114 --14.091635704,0.777016401291,-1.76416885853 --13.9546308517,0.768031299114,-1.79363632202 --14.0206403732,0.773012459278,-1.8460021019 --14.3546686172,0.795948147774,-1.93022608757 --14.6066923141,0.81389695406,-2.00649094582 --16.0378074646,0.913643300533,-2.23013448715 --15.9998092651,0.910644412041,-2.25135493279 --16.1708316803,0.923604130745,-2.32466220856 --16.5538711548,0.950526177883,-2.42786359787 --16.0728416443,0.917599260807,-2.41550946236 --16.0968532562,0.919583916664,-2.4708969593 --16.1338653564,0.922566115856,-2.52827715874 --16.1298732758,0.922555625439,-2.57967615128 --16.1338787079,0.923549115658,-2.60687732697 --15.9728746414,0.912566900253,-2.63536381721 --15.9468822479,0.911560416222,-2.68277335167 --16.1289081573,0.924515604973,-2.76307630539 --16.1639232635,0.927497625351,-2.82045197487 --16.2369403839,0.933472216129,-2.88481140137 --16.1239395142,0.925481498241,-2.91927266121 --16.1809501648,0.930464982986,-2.95443701744 --16.7820224762,0.972338736057,-3.10951209068 --14.7518205643,0.831714689732,-2.81301450729 --14.6998233795,0.828714489937,-2.85244607925 --14.2337808609,0.796795129776,-2.8160943985 --14.3538017273,0.805761814117,-2.88543534279 --14.4018144608,0.809742689133,-2.94080376625 --14.4738264084,0.814723491669,-2.97796416283 --14.8828821182,0.844631850719,-3.10414385796 --14.1278018951,0.791772603989,-3.00595545769 --13.6767549515,0.760853946209,-2.96360731125 --13.6347570419,0.758853375912,-3.00002932549 --13.6397638321,0.759843111038,-3.04643034935 --13.6207685471,0.758837640285,-3.08784389496 --13.6087713242,0.758835673332,-3.10704374313 --13.5467700958,0.754839122295,-3.13948345184 --13.7538051605,0.769786536694,-3.22876572609 --14.3448915482,0.811652004719,-3.40383648872 --14.4569168091,0.820617437363,-3.47718024254 --13.4837913513,0.752815067768,-3.30511927605 --13.4897994995,0.753804206848,-3.35151696205 --14.7579832077,0.84352517128,-3.66701126099 --13.4878110886,0.754790186882,-3.41912317276 --13.2797880173,0.740826129913,-3.41463875771 --13.2467908859,0.739823818207,-3.45206618309 --13.234796524,0.738817036152,-3.49347233772 --13.1547927856,0.733825445175,-3.51791596413 --13.2238111496,0.739800453186,-3.57927560806 --13.1638050079,0.735809147358,-3.5865111351 --13.2018194199,0.739790856838,-3.64089250565 --13.1658220291,0.737789392471,-3.67631483078 --13.0878171921,0.732797503471,-3.70076322556 --13.1018285751,0.73478448391,-3.74915885925 --13.1078367233,0.735773444176,-3.79454946518 --13.2078590393,0.743744909763,-3.8446996212 --13.3158855438,0.751709461212,-3.91903614998 --13.3468999863,0.754691660404,-3.97342228889 --13.3539113998,0.756679654121,-4.02081775665 --13.3439178467,0.756671607494,-4.06322002411 --13.3939371109,0.760648906231,-4.12359380722 --13.3239336014,0.756655216217,-4.14903306961 --13.3159379959,0.756651639938,-4.17024374008 --13.3009443283,0.75664460659,-4.21165323257 --13.3189582825,0.758629322052,-4.2630443573 --13.3929824829,0.764600038528,-4.33140087128 --13.4099960327,0.766584694386,-4.38278961182 --13.5270290375,0.776543855667,-4.46612691879 --13.4540262222,0.771550834179,-4.49057197571 --13.4360284805,0.7715498209,-4.50777864456 --13.6890907288,0.79047369957,-4.63502931595 --16.5986919403,1.00071334839,-5.61872816086 --16.1966285706,0.97280061245,-5.54636287689 --16.3786849976,0.987737119198,-5.66265249252 --16.5187339783,0.998683750629,-5.7669711113 --16.5657634735,1.00365436077,-5.84134483337 --16.5857868195,1.00563180447,-5.90673208237 --16.5707931519,1.0056271553,-5.93094062805 --16.699842453,1.01657533646,-6.03426504135 --17.0189342499,1.04047191143,-6.20447444916 --16.7969055176,1.0255137682,-6.18700408936 --17.9701919556,1.11217594147,-6.66270589828 --19.9976806641,1.26159989834,-7.45390939713 --19.9766902924,1.26059377193,-7.48212003708 --19.8546924591,1.25360417366,-7.50858402252 --19.8117103577,1.25259256363,-7.56400489807 --19.8557510376,1.25755667686,-7.65137338638 --19.7537555695,1.2515617609,-7.68482971191 --19.7717933655,1.25453269482,-7.76321601868 --19.8338375092,1.26049101353,-7.85857486725 --19.8658618927,1.26346981525,-7.90675354004 --20.1119537354,1.28337466717,-8.07400131226 --20.1950054169,1.29132592678,-8.17934513092 --20.2590560913,1.29828190804,-8.27870464325 --20.2060756683,1.2962719202,-8.33213329315 --20.2781257629,1.30322539806,-8.43448162079 --20.3321743011,1.30918371677,-8.53084373474 --18.8608016968,1.20160806179,-7.96992874146 --18.8918399811,1.20557546616,-8.05230617523 --18.9048748016,1.20854771137,-8.12769508362 --18.8869018555,1.20852935314,-8.19010066986 --18.8509216309,1.20751643181,-8.24552059174 --18.7799339294,1.20451426506,-8.28495693207 --18.8149738312,1.20847940445,-8.37033176422 --18.7999858856,1.20847177505,-8.39954090118 --18.6849861145,1.20148336887,-8.42000675201 --18.2408885956,1.17059791088,-8.29567432404 --18.3119392395,1.177552104,-8.39602851868 --18.4450092316,1.18948626518,-8.52434158325 --18.2659893036,1.17851865292,-8.51485347748 --18.1169757843,1.1685423851,-8.51633930206 --18.4470901489,1.19442451,-8.70133590698 --18.4511222839,1.19739854336,-8.77372932434 --18.3991394043,1.1953908205,-8.82015705109 --18.5042037964,1.20533144474,-8.94049167633 --18.6692905426,1.21925187111,-9.08978748322 --18.6403160095,1.21923589706,-9.14820098877 --18.5653266907,1.21623504162,-9.1846446991 --21.1661739349,1.4143550396,-10.4702339172 --21.1932258606,1.41931521893,-10.5656108856 --21.3693237305,1.43522489071,-10.7338933945 --21.3983783722,1.4401832819,-10.8322715759 --21.3364009857,1.43717253208,-10.8857040405 --21.4284763336,1.44710886478,-11.0160427094 --21.207447052,1.43315279484,-10.989575386 --21.7176418304,1.4729603529,-11.2894535065 --21.8247241974,1.48388969898,-11.4307823181 --21.8787899017,1.49083733559,-11.5451402664 --21.9028453827,1.4957947731,-11.6455211639 --23.3254451752,1.61122024059,-12.5684137344 --21.7559356689,1.4927444458,-11.8317937851 --22.9203796387,1.58430933952,-12.4942560196 --23.1295070648,1.60319685936,-12.6995182037 --21.8100795746,1.50363826752,-12.0817432404 --22.9735584259,1.59717786312,-12.8044061661 --21.6201076508,1.49463748932,-12.1566534042 --23.2087535858,1.62201559544,-13.1220397949 --23.0537509918,1.61303460598,-13.1315307617 --22.9587421417,1.60705041885,-13.126789093 --22.9547939301,1.61001372337,-13.2191820145 --38.2937850952,2.82019639015,-22.003862381 --35.0576324463,2.57035040855,-20.3172912598 --34.9286804199,2.56533455849,-20.389755249 --34.804725647,2.56031703949,-20.464214325 --34.7457504272,2.55830717087,-20.5034446716 --34.6177978516,2.55329084396,-20.5759086609 --34.4928436279,2.54827427864,-20.6483707428 --34.383895874,2.54425120354,-20.7308254242 --34.2629470825,2.5402328968,-20.8052845001 --34.1720085144,2.53820300102,-20.8977279663 --34.28515625,2.55209231377,-21.1130371094 --34.4442710876,2.56699538231,-21.2841262817 --34.5674247742,2.58287906647,-21.508430481 --34.7195930481,2.59975004196,-21.7527160645 --36.3263893127,2.73503041267,-22.9030647278 --35.7832641602,2.69717907906,-22.7217960358 --35.5052528381,2.68022155762,-22.7033557892 --35.2522468567,2.66525411606,-22.6999034882 --35.0321998596,2.65030956268,-22.6372356415 --34.8642349243,2.64230799675,-22.6857280731 --34.962387085,2.65619564056,-22.9050502777 --34.8814620972,2.65515804291,-23.0084819794 --35.0386390686,2.67401957512,-23.2677631378 --32.7226791382,2.48993110657,-21.8986549377 --32.6077270508,2.485912323,-21.9711151123 --32.5257415771,2.48191380501,-21.99036026 --32.3857765198,2.47590613365,-22.0448379517 --32.2698287964,2.47188830376,-22.1152992249 --32.1878890991,2.47085571289,-22.2077388763 --32.2320137024,2.48076796532,-22.387096405 --32.2841491699,2.49067616463,-22.5724468231 --34.5963935852,2.68858289719,-24.3263092041 --34.6404685974,2.69552564621,-24.4374713898 --34.495513916,2.68951439857,-24.4989509583 --31.8743133545,2.47661590576,-22.8120651245 --31.7743721008,2.47359132767,-22.8915176392 --35.2742652893,2.77393174171,-25.5445861816 --35.340423584,2.78682184219,-25.7609272003 --31.7957077026,2.49436998367,-23.3626613617 --34.3350830078,2.71216440201,-25.2851696014 --35.0375709534,2.77776122093,-25.9640846252 --33.9781341553,2.69517421722,-25.3541755676 --33.9202270508,2.69612312317,-25.4765968323 --33.4671058655,2.66425824165,-25.3042831421 --33.5622749329,2.67913484573,-25.540605545 --32.7339477539,2.61545062065,-25.0805435181 --32.6909828186,2.61443281174,-25.1287651062 --32.6650886536,2.61936855316,-25.2711677551 --32.5731582642,2.61833524704,-25.364616394 --32.4692192078,2.61630773544,-25.4480724335 --30.3631515503,2.4402577877,-23.9728775024 --30.8055152893,2.48496842384,-24.4729652405 --30.6715545654,2.47995996475,-24.5244426727 --30.7356491089,2.48889112473,-24.6535930634 --30.5056324005,2.47493028641,-24.6291370392 --30.4697265625,2.47887349129,-24.7575492859 --29.8084545135,2.42713117599,-24.3823871613 --29.638469696,2.41914343834,-24.3998889923 --29.6726055145,2.42905259132,-24.5822525024 --29.554649353,2.42503857613,-24.6417217255 --29.4986763,2.42402911186,-24.674955368 --29.4927883148,2.42995786667,-24.8263492584 --29.4188613892,2.42992091179,-24.921787262 --29.3859577179,2.43386292458,-25.0511951447 --29.2089653015,2.42487978935,-25.0607089996 --29.0349750519,2.41689538956,-25.0712184906 --28.985004425,2.41588401794,-25.1074447632 --28.9861240387,2.42280745506,-25.266834259 --29.8988304138,2.5122423172,-26.2155952454 --29.6928215027,2.50027346611,-26.2011241913 --29.6789398193,2.50720095634,-26.3545246124 --29.5679931641,2.50418066978,-26.422990799 --29.6511764526,2.51905441284,-26.6633243561 --30.0004730225,2.5548222065,-27.0572738647 --29.9355583191,2.55677556992,-27.1687068939 --28.1725025177,2.40267133713,-25.7493171692 --28.0845661163,2.4016418457,-25.8317718506 --27.998632431,2.4006114006,-25.9152202606 --27.9086952209,2.39958357811,-25.9946727753 --27.8077507019,2.39856171608,-26.0641345978 --27.7587776184,2.39755010605,-26.0993614197 --27.6708431244,2.39652061462,-26.1818161011 --27.5749015808,2.39549612999,-26.255273819 --27.4789619446,2.39347147942,-26.3287334442 --27.3860206604,2.39244556427,-26.4041862488 --27.3040885925,2.39241290092,-26.4906349182 --24.105884552,2.09721541405,-23.5762748718 --24.0268821716,2.0932264328,-23.5735282898 --23.945936203,2.09220409393,-23.6409778595 --23.8619880676,2.09118247032,-23.7074337006 --23.7780361176,2.09016132355,-23.7728881836 --23.7201080322,2.09112501144,-23.8633213043 --23.6151428223,2.08811688423,-23.9067897797 --23.6492824554,2.09902358055,-24.0901584625 --23.5502643585,2.09304785728,-24.0654277802 --23.437292099,2.08904480934,-24.10090065 --23.3593502045,2.08901977539,-24.1723537445 --23.3764801025,2.09793567657,-24.3407363892 --23.2715148926,2.09492754936,-24.3842048645 --23.1465320587,2.08993244171,-24.4056873322 --23.0715923309,2.08990526199,-24.4801387787 --23.0316181183,2.08989405632,-24.5133609772 --22.9576797485,2.08986639977,-24.588809967 --22.8947486877,2.09183144569,-24.6762523651 --22.8118000031,2.0908100605,-24.7407035828 --22.7348594666,2.09078407288,-24.8131580353 --22.6659240723,2.09175300598,-24.8936023712 --22.5859794617,2.09172916412,-24.9620552063 --21.1538257599,1.9506367445,-23.4762840271 --20.8446769714,1.92677056789,-23.2829036713 --20.6456165314,1.91283261776,-23.2084445953 --20.4066390991,1.90385127068,-23.2334156036 --20.3376922607,1.9038271904,-23.3008594513 --20.2667446136,1.90380442142,-23.3663101196 --20.2277679443,1.9037951231,-23.3955364227 --20.1548175812,1.90377342701,-23.4589881897 --20.1018867493,1.90573787689,-23.5454235077 --20.1260280609,1.91564834118,-23.7218055725 --20.0540790558,1.91562533379,-23.7872562408 --18.2506923676,1.74472486973,-22.0265731812 --17.9485168457,1.71987426281,-21.8041915894 --17.7023887634,1.69998502731,-21.6457691193 --17.6064071655,1.69698727131,-21.6682434082 --17.5304412842,1.69597601891,-21.7126979828 --17.4785003662,1.69794690609,-21.7871379852 --17.4525279999,1.69893276691,-21.8233528137 --17.3915786743,1.69891023636,-21.886800766 --17.3416404724,1.70187866688,-21.9652404785 --17.2836952209,1.70285356045,-22.0326824188 --17.2167377472,1.70283555984,-22.0881309509 --17.1657981873,1.70480513573,-22.1645698547 --17.0988426208,1.70478665829,-22.2210197449 --17.0459022522,1.70675730705,-22.2954597473 --16.0719528198,1.60147297382,-21.1113815308 --15.7957715988,1.57762098312,-20.8889904022 --15.4855537415,1.55079734325,-20.6186256409 --15.246509552,1.53785657883,-20.568605423 --15.17253685,1.53684997559,-20.6040668488 --15.1495637894,1.53783619404,-20.6392822266 --15.0775918961,1.53682887554,-20.675737381 --15.0196361542,1.53780984879,-20.7321853638 --14.9706897736,1.53878343105,-20.8006267548 --14.9057264328,1.53877019882,-20.847076416 --14.849773407,1.53974926472,-20.9065227509 --14.799826622,1.54172348976,-20.9739627838 --14.7708482742,1.54171383381,-21.0021858215 --14.7178993225,1.54369032383,-21.0656280518 --14.6679525375,1.54566442966,-21.1330680847 --14.6039924622,1.54564940929,-21.1825218201 --11.7207269669,1.20903670788,-17.1931095123 --11.7408390045,1.21796560287,-17.3354988098 --11.3556890488,1.19410836697,-17.1742134094 --11.3057165146,1.19409823418,-17.2136535645 --11.253742218,1.19408929348,-17.2510986328 --11.196762085,1.19408452511,-17.2815494537 --11.1517963409,1.19506955147,-17.3289871216 --11.1338205338,1.19605767727,-17.3602046967 --11.2070064545,1.21193444729,-17.5905570984 --11.0288715363,1.19604027271,-17.43409729 --10.997926712,1.19901132584,-17.5055294037 --10.8879718781,1.19899809361,-17.5724258423 --10.4472589493,1.20588517189,-17.9624271393 --10.4063034058,1.20786440372,-18.019865036 --10.3463191986,1.20686280727,-18.0443153381 --9.93667697906,1.22070646286,-18.5073032379 --9.88370704651,1.22069573402,-18.5477581024 --9.73658847809,1.2077883482,-18.4122772217 --9.68862438202,1.20977365971,-18.4587211609 --9.67082500458,1.22365641594,-18.70154953 --9.6218624115,1.22464096546,-18.75 --9.60589504242,1.22662365437,-18.7902183533 --9.5479183197,1.22661864758,-18.8206691742 --9.5029630661,1.22859883308,-18.8761138916 --9.45901012421,1.23057734966,-18.9345569611 --9.41105079651,1.2325605154,-18.9850025177 --9.37110424042,1.23453426361,-19.0514411926 --9.32715415955,1.23751163483,-19.1118888855 --9.31218910217,1.2394926548,-19.1551017761 --9.2642326355,1.24147415161,-19.2085514069 --9.23130130768,1.24543809891,-19.2919864655 --9.20438194275,1.25039470196,-19.3874168396 --15.515873909,2.25163817406,-32.6308708191 --15.473033905,2.26155209541,-32.8023147583 --5.49501132965,0.690723538399,-12.0838298798 --15.457611084,2.29921722412,-33.435344696 --15.0681285858,2.25356316566,-32.870059967 --15.3228569031,2.31209659576,-33.6912651062 --14.8091287613,2.24460697174,-32.8450737 --14.7552728653,2.25253224373,-32.9975242615 --14.8485803604,2.27633738518,-33.3426551819 --14.8859090805,2.30013990402,-33.705039978 --14.6787586212,2.28226232529,-33.5206069946 --14.6589794159,2.29713749886,-33.7590293884 --14.4768753052,2.28422880173,-33.62758255 --14.2406587601,2.26139450073,-33.369178772 --14.015460968,2.24054765701,-33.1317672729 --14.1478672028,2.27228951454,-33.5858650208 --12.9646673203,2.08276772499,-31.0822048187 --13.9720363617,2.27822160721,-33.7518234253 --13.8109693527,2.26828789711,-33.6633605957 --8.99589729309,1.42494952679,-22.2855758667 --13.4988451004,2.2494134903,-33.4974250793 --13.4820861816,2.26527667046,-33.7568511963 --13.4180841446,2.26328873634,-33.7481040955 --13.2690372467,2.2553422451,-33.6816329956 --9.5469493866,1.58466422558,-24.5879859924 --9.44391822815,1.57969939709,-24.5504817963 --9.35491752625,1.5767147541,-24.5469608307 --8.6314458847,1.45369052887,-22.8969535828 --8.52037620544,1.44674944878,-22.8184528351 --8.50644016266,1.45071458817,-22.889673233 --7.85107040405,1.33661901951,-21.3606033325 --7.7359752655,1.32769346237,-21.255109787 --7.61385917664,1.31678128242,-21.1266212463 --7.50176477432,1.30685436726,-21.0231227875 --7.42575645447,1.30487203598,-21.0145950317 --7.42694473267,1.31776249409,-21.2250099182 --7.16637659073,1.27213537693,-20.5954208374 --7.08334875107,1.26816558838,-20.5659046173 --7.03841543198,1.27213430405,-20.6413555145 --7.18197536469,1.31478607655,-21.2616481781 --7.18517780304,1.32966840267,-21.4860610962 --7.13824892044,1.33363509178,-21.5655117035 --11.0690822601,2.19170594215,-33.5027999878 --7.02323770523,1.33066093922,-21.5542221069 --6.92416906357,1.32371783257,-21.478717804 --6.79300689697,1.30883383751,-21.3012332916 --6.7350487709,1.31081974506,-21.347694397 --6.6891245842,1.31478357315,-21.4321460724 --6.62314367294,1.31478393078,-21.4536132812 --6.55304670334,1.30685186386,-21.3478794098 --6.54623985291,1.32074213028,-21.5593013763 --6.38999128342,1.29991197586,-21.2888412476 --6.26482868195,1.28602731228,-21.1123542786 --6.21288728714,1.28900289536,-21.1768093109 --6.15593099594,1.29098761082,-21.225271225 --6.09596538544,1.2919781208,-21.2637348175 --6.19338274002,1.32372117043,-21.7178630829 --6.15047883987,1.32967364788,-21.8223152161 --6.14971446991,1.34653866291,-22.0777339935 --9.17183971405,2.12319374084,-33.0477523804 --9.05884552002,2.12021183968,-33.0422668457 --5.88957977295,1.33166205883,-21.9321861267 --5.82460594177,1.33265852928,-21.9606533051 --8.05738449097,1.92580270767,-30.3570976257 --8.03667259216,1.9456423521,-30.6585330963 --5.70582962036,1.34655177593,-22.2017917633 --5.62078952789,1.3425899744,-22.1582794189 --5.50864887238,1.33069086075,-22.0067863464 --5.43062496185,1.32771849632,-21.981262207 --5.37468719482,1.33069324493,-22.0477256775 --5.32362937927,1.32573544979,-21.9859714508 --5.29077911377,1.33565580845,-22.1464157104 --5.21476697922,1.33367693424,-22.1328964233 --5.16084003448,1.33764469624,-22.211359024 --5.13000822067,1.34955489635,-22.3898029327 --5.09817457199,1.36046564579,-22.5672473907 --5.05228757858,1.36740994453,-22.6867008209 --5.0303478241,1.37137937546,-22.7509269714 --4.97041034698,1.37535488605,-22.8163967133 --4.94059848785,1.38825368881,-23.014837265 --4.93188381195,1.40809249878,-23.3172626495 --4.89003515244,1.41801464558,-23.4757175446 --4.80901145935,1.41504323483,-23.4491996765 --4.78927183151,1.43289923668,-23.7226390839 --4.70907926559,1.41802346706,-23.518913269 --6.40838813782,2.02798056602,-32.2920303345 --6.34459066391,2.04087877274,-32.4945030212 --6.24261379242,2.03988575935,-32.5080070496 --6.04617261887,2.00617456436,-32.0325813293 --5.99443864822,2.0230345726,-32.3010444641 --5.9746055603,2.03394389153,-32.4712715149 --5.84649753571,2.02403044701,-32.3468017578 --5.73747825623,2.02106356621,-32.3153114319 --5.67973184586,2.03693151474,-32.5707778931 --5.57574892044,2.03594279289,-32.5772895813 --5.45566749573,2.02901315689,-32.4808044434 --5.36173772812,2.03199219704,-32.5433082581 --5.24466753006,2.0250556469,-32.458820343 --5.19267463684,2.02406215668,-32.4610748291 --5.10980463028,2.03200531006,-32.5855674744 --4.96758317947,2.01415944099,-32.3441047668 --4.88069438934,2.02011466026,-32.448600769 --4.79179382324,2.02507638931,-32.5410995483 --4.70692682266,2.03301930428,-32.6675949097 --4.61868715286,2.01517224312,-32.4138717651 --2.1379199028,0.887570858002,-16.0785388947 --2.07683992386,0.881627500057,-16.0020122528 --1.9734442234,0.853870987892,-15.5995121002 --1.9536536932,0.868756115437,-15.8219480515 --1.87743449211,0.852894425392,-15.6024217606 --1.86049449444,0.856863617897,-15.6676511765 --1.82055783272,0.861835360527,-15.7391033173 --1.78062522411,0.866804838181,-15.8145551682 --1.73666131496,0.868792653084,-15.8580093384 --1.69168794155,0.870786190033,-15.891462326 --1.6477342844,0.874768555164,-15.9449214935 --1.59873139858,0.87377935648,-15.9483804703 --1.57776093483,0.875766694546,-15.9816055298 --1.53280055523,0.878753066063,-16.0280647278 --2.95653748512,1.91016638279,-31.0785751343 --2.8827931881,1.92703819275,-31.3300685883 --2.78480839729,1.92705070972,-31.3355751038 --2.67366504669,1.91515493393,-31.1800861359 --2.57465529442,1.91418170929,-31.1605949402 --2.52161097527,1.9102178812,-31.1108512878 --2.43575787544,1.91915392876,-31.2503509521 --2.3246011734,1.90726578236,-31.0818691254 --2.21443510056,1.89438259602,-30.9043807983 --2.07990837097,1.85670733452,-30.3619060516 --1.99607336521,1.86663269997,-30.5204029083 --1.90413212776,1.86961972713,-30.5709095001 --1.83682596684,1.84880614281,-30.2571697235 --1.7377436161,1.8418738842,-30.1656742096 --1.64986872673,1.84982287884,-30.2831821442 --1.5548607111,1.84784805775,-30.2666873932 --1.46289658546,1.84984815121,-30.2941856384 --1.36890351772,1.84886479378,-30.2926921844 --1.2657160759,1.83499240875,-30.096200943 --1.17057991028,1.75665020943,-28.9524593353 --1.07547295094,1.74873101711,-28.8379669189 --0.995739340782,1.76659941673,-29.0974655151 --0.901640057564,1.75867569447,-28.9909687042 --0.80644851923,1.7448040247,-28.7924671173 --0.712298750877,1.73390877247,-28.6359729767 --0.625344276428,1.73690271378,-28.6744709015 --0.577191412449,1.72599887848,-28.5187206268 --0.489250093699,1.72998571396,-28.5702285767 --0.403362900019,1.73694181442,-28.6757259369 --0.313294649124,1.73099994659,-28.6012268066 --0.225339397788,1.73399472237,-28.6387290955 --0.133995831013,1.71020746231,-28.2912254333 --0.0912101641297,1.72409713268,-28.5004825592 -0.0111619150266,1.66328692436,-26.6240634918 -0.0949458926916,1.64914357662,-26.4164009094 -0.179909601808,1.64710044861,-26.3867397308 -0.264989286661,1.65312230587,-26.4720649719 -0.348964184523,1.65208590031,-26.4533977509 -0.436181306839,1.66718423367,-26.6757144928 -0.468566268682,1.62483131886,-26.0669174194 -0.550501406193,1.62077319622,-26.0082550049 -0.63872551918,1.6368752718,-26.2375717163 -0.716486334801,1.62072074413,-26.0049228668 -0.796368837357,1.61363363266,-25.8932647705 -0.914442956448,1.68820440769,-26.9735164642 -0.963401854038,1.61660814285,-25.9379310608 -1.0197994709,1.64481604099,-26.3390636444 -1.101744771,1.64176380634,-26.2904014587 -1.19186639786,1.65080845356,-26.4187259674 -1.31785166264,1.65076720715,-26.4132232666 -1.40080571175,1.64771997929,-26.3735656738 -1.15283381939,1.23043620586,-20.3634853363 -1.18278825283,1.22740268707,-20.3176651001 -1.24675881863,1.22536921501,-20.288022995 -1.68257939816,1.63451969624,-26.1667537689 -1.75540053844,1.62240064144,-25.9921073914 -1.74202680588,1.52663350105,-24.6075935364 -1.87272238731,1.57598996162,-25.3168563843 -1.97803521156,1.59913814068,-25.6391525269 -1.87519264221,1.46913099289,-23.7725448608 -1.94713437557,1.46607971191,-23.7168922424 -2.01503992081,1.46000909805,-23.6242465973 -2.21240115166,1.55672228336,-25.0134162903 -2.18421339989,1.47406280041,-23.8079090118 -2.26828551292,1.47908163071,-23.8852443695 -2.09978866577,1.30272340775,-21.3399333954 -2.12469339371,1.29566347599,-21.2431221008 -2.19268870354,1.29664325714,-21.2394714355 -2.26774287224,1.30065429211,-21.2958164215 -2.34178924561,1.30466103554,-21.34416008 -2.4057404995,1.30161738396,-21.2955188751 -2.45154523849,1.28849577904,-21.0958976746 -2.48554086685,1.28848469257,-21.0920753479 -2.56059885025,1.29249811172,-21.1524162292 -2.63665175438,1.29750835896,-21.2077598572 -2.71372008324,1.30252707005,-21.2790985107 -3.12530851364,1.48987686634,-23.950006485 -3.18013882637,1.47876775265,-23.778377533 -3.27324867249,1.48780620098,-23.8957004547 -3.32836031914,1.49585497379,-24.0128555298 -3.34391927719,1.46460342407,-23.5602798462 -3.3262822628,1.41925024986,-22.9037380219 -3.39221858978,1.41619777679,-22.8401012421 -3.46017789841,1.41415786743,-22.8004512787 -3.52611970901,1.41010892391,-22.742811203 -3.59307098389,1.40806472301,-22.6941680908 -3.62101483345,1.40402638912,-22.6373519897 -3.68897366524,1.40198636055,-22.5967102051 -3.75593233109,1.3999465704,-22.5560626984 -3.90334892273,1.43114411831,-22.9933261871 -4.06684398651,1.46938192844,-23.5135669708 -4.16495513916,1.47842013836,-23.6328887939 -4.26306009293,1.48745501041,-23.746213913 -4.28798532486,1.48240745068,-23.6703987122 -4.35492372513,1.47835612297,-23.6087589264 -4.43292236328,1.47933661938,-23.6111030579 -4.52699756622,1.48635590076,-23.6934318542 -4.59494161606,1.48330783844,-23.6377925873 -4.68700885773,1.48932337761,-23.7121200562 -4.84136962891,1.51748883724,-24.0963764191 -4.92859077454,1.53459179401,-24.3314990997 -5.01160049438,1.53757727146,-24.3458366394 -5.08656930923,1.53654193878,-24.3171863556 -5.20272302628,1.54860055447,-24.4844932556 -5.26262331009,1.54253017902,-24.3828601837 -5.35366106033,1.54752969742,-24.4271945953 -5.41273927689,1.5535595417,-24.5123443604 -5.50276851654,1.55755448341,-24.5476818085 -5.5666885376,1.55249452591,-24.4670448303 -5.6637468338,1.55850422382,-24.533372879 -5.75779390335,1.56350839138,-24.5876998901 -5.84781599045,1.56749975681,-24.6160392761 -5.94989013672,1.57451713085,-24.6993598938 -6.01598453522,1.58255469799,-24.8025035858 -6.14414930344,1.59661710262,-24.9838027954 -6.27030563354,1.61067545414,-25.1560974121 -6.37537479401,1.61768972874,-25.2354202271 -6.49349212646,1.6277282238,-25.3667240143 -6.62063598633,1.64077913761,-25.5260238647 -6.73272514343,1.64980316162,-25.6273345947 -6.82790470123,1.66388189793,-25.8234539032 -7.02729177475,1.69605302811,-26.2466754913 -7.1233086586,1.69904053211,-26.2710094452 -7.19323778152,1.69598460197,-26.2003650665 -7.31935548782,1.70702171326,-26.3336658478 -7.41034984589,1.70899784565,-26.3340072632 -7.48629808426,1.70695161819,-26.2843608856 -7.53129529953,1.70693993568,-26.2845306396 -7.61225652695,1.70689988136,-26.248884201 -7.69723463058,1.7068682909,-26.2312259674 -7.77920198441,1.70683133602,-26.2015762329 -7.86117076874,1.7057954073,-26.1739234924 -7.94815254211,1.70676577091,-26.1602687836 -8.03011894226,1.7067284584,-26.1296195984 -8.06709194183,1.70570480824,-26.1027965546 -8.14905834198,1.70466816425,-26.0731468201 -8.23804759979,1.7066423893,-26.067489624 -8.31700706482,1.70560133457,-26.0278434753 -8.40398979187,1.70657253265,-26.0151863098 -8.48997020721,1.70754289627,-26.0005302429 -8.56291103363,1.70449388027,-25.9418926239 -8.60289287567,1.70447492599,-25.9250679016 -8.68386077881,1.70443856716,-25.8944187164 -8.75680446625,1.70239126682,-25.8387775421 -8.84078025818,1.7023588419,-25.8171272278 -8.91673088074,1.70131504536,-25.7694854736 -8.99469184875,1.70027601719,-25.7318382263 -9.0306634903,1.69925224781,-25.7030200958 -9.1066160202,1.69720876217,-25.655380249 -9.18156814575,1.69616603851,-25.6087360382 -9.26052951813,1.69612753391,-25.5720939636 -9.35754013062,1.69911193848,-25.5884246826 -9.46056175232,1.70310151577,-25.6177597046 -9.5786190033,1.71010792255,-25.6870746613 -9.69178009033,1.72517335415,-25.8691768646 -9.85694694519,1.74123084545,-26.0614471436 -10.0150918961,1.75627732277,-26.2287273407 -10.1842594147,1.77233493328,-26.4229946136 -10.3434028625,1.78738045692,-26.5892677307 -10.4955215454,1.80041456223,-26.72955513 -10.6215810776,1.80742073059,-26.8028640747 -10.6856117249,1.81142389774,-26.8400211334 -10.7956314087,1.81641161442,-26.8693466187 -10.8936214447,1.81838560104,-26.865688324 -10.9735746384,1.81734240055,-26.8190441132 -11.044506073,1.81528949738,-26.7494068146 -11.1194486618,1.81324148178,-26.6907672882 -11.2064151764,1.81320488453,-26.6601219177 -11.2564134598,1.81519329548,-26.6612892151 -11.3423776627,1.81515538692,-26.6276435852 -11.4233341217,1.8141143322,-26.5849971771 -11.4892578125,1.81105828285,-26.5053691864 -11.5621957779,1.80900883675,-26.441734314 -11.627120018,1.80495321751,-26.3621063232 -11.7070741653,1.80491125584,-26.3164653778 -11.7460508347,1.80389010906,-26.2926425934 -11.8139810562,1.80183744431,-26.2200126648 -11.8939361572,1.80079627037,-26.17537117 -11.9889211655,1.80276799202,-26.1637172699 -12.0578565598,1.80071759224,-26.095085144 -12.1307992935,1.79867136478,-26.0364494324 -12.1587553024,1.79664099216,-25.9886398315 -12.2397108078,1.79560041428,-25.9449996948 -12.3276834488,1.79656720161,-25.9193515778 -12.4447069168,1.80255663395,-25.9526767731 -12.5426979065,1.80453109741,-25.9470176697 -12.6567163467,1.80951821804,-25.9743423462 -12.752699852,1.81148993969,-25.9616889954 -12.7305669785,1.80142056942,-25.8109283447 -12.7444057465,1.79132902622,-25.6313514709 -12.8974933624,1.80234646797,-25.7376403809 -12.9884691238,1.80331468582,-25.7149906158 -13.0844535828,1.80628705025,-25.7033367157 -12.9650707245,1.77509903908,-25.2638835907 -12.8867635727,1.75094497204,-24.9123878479 -12.9107170105,1.74791491032,-24.8615837097 -12.9516153336,1.74285006523,-24.7469806671 -12.984500885,1.73578047752,-24.6183853149 -13.0264015198,1.72971713543,-24.5067825317 -13.0693073273,1.72465670109,-24.4011745453 -13.1072044373,1.7185921669,-24.2845745087 -13.1461029053,1.71352899075,-24.1709747314 -13.1460237503,1.70748531818,-24.0801887512 -13.1779155731,1.70141911507,-23.9565925598 -13.2168178558,1.69535779953,-23.8459949493 -13.2617321014,1.69130146503,-23.7483863831 -13.3006381989,1.68624186516,-23.6407852173 -13.3375425339,1.68018174171,-23.5311832428 -13.3834600449,1.6761276722,-23.4375762939 -13.3873910904,1.67208898067,-23.3577899933 -13.4273023605,1.6670320034,-23.2551879883 -13.4802331924,1.66398370266,-23.1765727997 -13.5151376724,1.6579246521,-23.0669765472 -13.5710754395,1.65587902069,-22.9943599701 -13.611989975,1.65182459354,-22.8967571259 -13.6609182358,1.64777541161,-22.8131484985 -13.673866272,1.644744277,-22.7523517609 -13.7288036346,1.64269912243,-22.6797389984 -13.7757291794,1.63864970207,-22.5941314697 -13.8326721191,1.6366070509,-22.5275115967 -13.8475561142,1.62954056263,-22.3909320831 -13.9605741501,1.63452935219,-22.4152641296 -13.923456192,1.62547147274,-22.2745170593 -13.9914140701,1.6244354248,-22.2258911133 -14.0323381424,1.62138545513,-22.1352863312 -14.0592412949,1.61532795429,-22.0216960907 -14.1171884537,1.61328721046,-21.9580802917 -14.1851472855,1.61325216293,-21.9104537964 -14.2611179352,1.61422157288,-21.8758201599 -14.2230052948,1.60516726971,-21.7410678864 -14.3069858551,1.60614073277,-21.7184314728 -14.3739461899,1.60610616207,-21.6708049774 -14.4348983765,1.60506868362,-21.6141853333 -14.5018577576,1.60503387451,-21.5655612946 -14.5788288116,1.60600399971,-21.5319290161 -14.6568031311,1.60697543621,-21.5012931824 -14.6817712784,1.60595357418,-21.4634914398 -14.7577438354,1.60692417622,-21.4298553467 -14.8257045746,1.60689032078,-21.3832321167 -14.9086847305,1.60886371136,-21.3585910797 -14.9716386795,1.607827425,-21.3039722443 -15.0576219559,1.60980212688,-21.2833328247 -15.1446056366,1.6117773056,-21.2636928558 -15.1625680923,1.61075353622,-21.2178916931 -15.2415428162,1.61172497272,-21.186258316 -15.3255214691,1.61369848251,-21.1616210938 -15.4335279465,1.61868238449,-21.1699638367 -15.5105009079,1.61965298653,-21.1353302002 -15.5844688416,1.62062239647,-21.0967006683 -15.62545681,1.62060832977,-21.0818862915 -15.7224502563,1.62458693981,-21.0732364655 -15.8054285049,1.62656021118,-21.0465965271 -15.9044218063,1.62953901291,-21.0389518738 -15.9904022217,1.63251256943,-21.0143146515 -16.0803852081,1.63448798656,-20.9946746826 -16.1903934479,1.63947141171,-21.0020122528 -16.2153625488,1.63845086098,-20.9652099609 -16.3103504181,1.64142799377,-20.9515647888 -16.4033374786,1.64440429211,-20.9349193573 -16.5143432617,1.64938688278,-20.9402637482 -16.5722942352,1.64834952354,-20.8776493073 -16.683298111,1.65333223343,-20.8829879761 -16.7612667084,1.65430188179,-20.8443622589 -16.8302822113,1.65829789639,-20.8635196686 -16.9392814636,1.66327893734,-20.8638648987 -17.0152492523,1.66424834728,-20.8232383728 -17.1262512207,1.66922950745,-20.8245811462 -17.2082252502,1.67120087147,-20.7909469604 -17.2992076874,1.6731749773,-20.7673072815 -17.3911914825,1.67614996433,-20.7456626892 -17.4652080536,1.68114614487,-20.7668228149 -17.5571880341,1.6831202507,-20.743183136 -17.7152328491,1.69311654568,-20.7984867096 -17.6520690918,1.67903888226,-20.5889759064 -17.4717979431,1.65292453766,-20.2445602417 -17.4496765137,1.64386320114,-20.089012146 -17.4236011505,1.6378275156,-19.9932537079 -17.4595336914,1.63478529453,-19.90666008 -17.497467041,1.63174390793,-19.8220672607 -17.5564231873,1.63170981407,-19.7634506226 -17.5973625183,1.6296697855,-19.6828556061 -17.6292934418,1.62562763691,-19.5932655334 -17.6612262726,1.62258553505,-19.5036754608 -17.6671829224,1.62056171894,-19.4478874207 -17.7041187286,1.61752140522,-19.3642940521 -17.7270450592,1.61347794533,-19.266708374 -17.7629814148,1.61043810844,-19.1831169128 -17.7779006958,1.6063927412,-19.077539444 -17.7607936859,1.59833860397,-18.9369888306 -17.7707118988,1.59329283237,-18.8274154663 -17.7396411896,1.58726012707,-18.7336597443 -17.7395496368,1.58121204376,-18.6140975952 -17.7554759979,1.57616901398,-18.5125179291 -17.7673969269,1.57112550735,-18.4079418182 -17.7953338623,1.56808626652,-18.320356369 -17.8172626495,1.56504547596,-18.225774765 -17.8442001343,1.56200683117,-18.1381893158 -17.8251399994,1.55697906017,-18.06042099 -17.8450717926,1.55293881893,-17.9658432007 -17.858997345,1.54889786243,-17.8662643433 -17.8809299469,1.54585874081,-17.774684906 -17.9098720551,1.54282188416,-17.6910972595 -17.9107894897,1.53677845001,-17.5795307159 -17.9217166901,1.53273797035,-17.4789562225 -17.9226760864,1.52971673012,-17.4241733551 -17.9356060028,1.52567732334,-17.3265972137 -17.9625453949,1.52364087105,-17.2420139313 -17.9964923859,1.52160668373,-17.1654224396 -18.038444519,1.51957452297,-17.096824646 -18.0753917694,1.51854121685,-17.0232315063 -18.1053352356,1.5155069828,-16.9436435699 -18.1002941132,1.51248538494,-16.8848648071 -18.1142272949,1.5084477663,-16.7902908325 -18.1401691437,1.50641310215,-16.7077045441 -18.1450977325,1.50137448311,-16.606136322 -18.1540279388,1.49733698368,-16.508562088 -18.1629600525,1.49329936504,-16.410993576 -18.1278991699,1.48727297783,-16.3262405396 -18.1438369751,1.48423814774,-16.237657547 -18.1367607117,1.47919845581,-16.1270999908 -18.1496963501,1.47516310215,-16.0355262756 -18.1386184692,1.46912360191,-15.9229688644 -18.151556015,1.4660885334,-15.8313999176 -18.173500061,1.46305608749,-15.7498159409 -18.1554546356,1.4590344429,-15.6830482483 -18.1703948975,1.45600128174,-15.5964670181 -18.0442447662,1.43994259834,-15.3860015869 -17.9000835419,1.42188203335,-15.1625471115 -17.9430465698,1.42185497284,-15.1019487381 -12.8877897263,0.958954870701,-10.6862716675 -12.8897504807,0.955933988094,-10.6196918488 -12.7636508942,0.942902028561,-10.4780063629 -12.9447231293,0.955910742283,-10.5613002777 -8.23477458954,0.528115093708,-6.51482152939 -8.326795578,0.532110571861,-6.50459289551 -8.32978916168,0.532106339931,-6.48579883575 -8.34878349304,0.532099843025,-6.45820713043 -8.37778282166,0.53209489584,-6.43860912323 -8.40678310394,0.533089876175,-6.41900968552 -8.4357843399,0.534085035324,-6.39940929413 -8.44477176666,0.533076941967,-6.36283540726 -8.48377895355,0.534073591232,-6.3512263298 -8.48176860809,0.533068776131,-6.32843875885 -8.52177524567,0.535065352917,-6.31683444977 -8.53176498413,0.534057974815,-6.28224897385 -8.57377243042,0.536054849625,-6.27263689041 -8.58176040649,0.5350471735,-6.23605823517 -8.62476921082,0.537044107914,-6.22645044327 -8.6307554245,0.535036385059,-6.18886947632 -8.65976428986,0.537035822868,-6.19005489349 -8.68876457214,0.538030982018,-6.16945886612 -8.71476268768,0.538025796413,-6.14686250687 -8.72575378418,0.537018835545,-6.11327600479 -8.75375270844,0.538013935089,-6.09168243408 -8.80276298523,0.54101151228,-6.08606433868 -8.80975151062,0.539004027843,-6.04849243164 -8.84076023102,0.541003584862,-6.05067443848 -8.8497505188,0.539996564388,-6.01509523392 -8.89175796509,0.541993200779,-6.00348711014 -8.90374755859,0.540986537933,-5.96990823746 -8.94175243378,0.542982816696,-5.95530223846 -8.95574569702,0.542976498604,-5.92371559143 -9.00175380707,0.544973433018,-5.91410684586 -9.00174713135,0.543969631195,-5.89332056046 -9.03274822235,0.544965147972,-5.87371778488 -9.05474472046,0.544959902763,-5.84811973572 -9.08974742889,0.54595553875,-5.82952976227 -9.1087436676,0.545950055122,-5.8019323349 -9.13374137878,0.546944975853,-5.77734088898 -9.1417388916,0.54694211483,-5.76254320145 -9.14272499084,0.544935047626,-5.721971035 -9.18473052979,0.546931564808,-5.70935821533 -9.2587518692,0.551930725574,-5.71672821045 -9.27474498749,0.551924824715,-5.685151577 -11.004486084,0.690043628216,-6.70572471619 -10.8744192123,0.67802888155,-6.59903383255 -10.7773580551,0.668012142181,-6.49053049088 -10.7803421021,0.667003154755,-6.44595146179 -10.650267601,0.654984891415,-6.31847238541 -10.6172370911,0.649973750114,-6.25192546844 -10.5301837921,0.641959369183,-6.15341091156 -10.4161186218,0.630943477154,-6.03792953491 -10.2920598984,0.619931578636,-5.94122648239 -10.228017807,0.612919807434,-5.85870075226 -10.1789836884,0.607909321785,-5.78616142273 -10.1229467392,0.601898550987,-5.70963096619 -10.0859174728,0.59788942337,-5.64607524872 -10.0598936081,0.593881070614,-5.58852148056 -10.0288677216,0.589872479439,-5.52797460556 -9.82178020477,0.572858154774,-5.38733673096 -9.78275299072,0.567849993706,-5.32478380203 -9.73572349548,0.562841534615,-5.25724649429 -9.73371124268,0.561835646629,-5.21666622162 -9.73770141602,0.560829818249,-5.17809820175 -9.7506942749,0.559824883938,-5.14650392532 -9.75569152832,0.559822142124,-5.12872028351 -9.76768493652,0.559817135334,-5.09613180161 -9.79668521881,0.560812830925,-5.07253551483 -9.80667877197,0.5598077178,-5.03795862198 -9.80566692352,0.558802366257,-4.99837970734 -9.79965496063,0.556796848774,-4.95581007004 -9.82465362549,0.557792425156,-4.92922449112 -9.86266231537,0.559791207314,-4.93040418625 -9.86665248871,0.558786153793,-4.89283132553 -9.90365600586,0.560782253742,-4.87322807312 -9.82661914825,0.552775084972,-4.79470300674 -9.88963127136,0.556771993637,-4.78808689117 -9.83160209656,0.550765573978,-4.71955490112 -9.86860561371,0.552761912346,-4.69995212555 -9.90961456299,0.55476051569,-4.7011384964 -9.91260719299,0.554756045341,-4.66455602646 -9.88358783722,0.550750911236,-4.61199855804 -12.7095022202,0.766802608967,-5.96346855164 -12.7474975586,0.767794907093,-5.93287134171 -12.7754898071,0.768786966801,-5.89728021622 -12.8364915848,0.77177965641,-5.87766504288 -12.8494882584,0.771775841713,-5.8598651886 -12.8954849243,0.773768126965,-5.83226490021 -12.9454841614,0.776760578156,-5.80665874481 -12.9734754562,0.776752650738,-5.77007246017 -13.0014667511,0.777744889259,-5.73447608948 -13.0494651794,0.779737234116,-5.70687627792 -13.0624599457,0.779733300209,-5.68808269501 -13.0734481812,0.779725551605,-5.64449834824 -13.1544551849,0.783718049526,-5.63187265396 -13.1654424667,0.783710181713,-5.58729553223 -13.2114391327,0.785702526569,-5.55869150162 -13.2384309769,0.786694765091,-5.52110433578 -13.2844266891,0.788687050343,-5.4915060997 -13.3114271164,0.789683163166,-5.47870159149 -13.3624258041,0.792675554752,-5.45208978653 -13.3804149628,0.792667925358,-5.41050624847 -13.4224100113,0.793660223484,-5.37890815735 -13.4834108353,0.797652423382,-5.35529565811 -13.4963979721,0.796644747257,-5.3107213974 -13.5543985367,0.799637019634,-5.28610467911 -13.5513896942,0.79863345623,-5.26032018661 -13.6183919907,0.802625358105,-5.23770952225 -13.6433830261,0.80361777544,-5.19812393188 -13.6753759384,0.804610192776,-5.1615319252 -13.7123699188,0.805602669716,-5.12792682648 -13.7393608093,0.806595146656,-5.08834505081 -13.8073644638,0.810586988926,-5.06572580338 -13.8123569489,0.810583412647,-5.04293727875 -13.8383483887,0.810575962067,-5.00335073471 -13.8923473358,0.81356805563,-4.97474145889 -13.9063358307,0.813560903072,-4.93016433716 -13.9413290024,0.814553320408,-4.89357280731 -14.0253334045,0.819544553757,-4.87494850159 -14.0293273926,0.819541156292,-4.85215520859 -14.0813245773,0.82253319025,-4.82155036926 -14.102314949,0.822525978088,-4.77897071838 -14.15031147,0.824518024921,-4.74636983871 -14.2133102417,0.828509628773,-4.71875953674 -14.2403030396,0.829502463341,-4.67916536331 -14.2612924576,0.829495370388,-4.63658189774 -14.3483047485,0.835489392281,-4.64173936844 -14.3572921753,0.834482729435,-4.59516048431 -14.3762817383,0.835475742817,-4.55157852173 -14.4672870636,0.840466201305,-4.53195047379 -14.5072813034,0.842458367348,-4.49436044693 -14.5312728882,0.84345138073,-4.45276927948 -14.6012792587,0.847445487976,-4.44994306564 -14.5952634811,0.846439659595,-4.39837217331 -14.6492614746,0.848431348801,-4.36477279663 -14.6772527695,0.849424064159,-4.32318639755 -14.7852592468,0.856413424015,-4.30654668808 -14.7532396317,0.853408932686,-4.24699068069 -14.815237999,0.856400191784,-4.21538257599 -12.8848705292,0.717485427856,-3.60881876945 -12.8508548737,0.714483320713,-3.55526542664 -12.79783535,0.709482192993,-3.49573087692 -12.7518196106,0.705480933189,-3.43918681145 -12.7348079681,0.703478395939,-3.39162182808 -12.6847915649,0.699477672577,-3.33507561684 -12.6937856674,0.698474049568,-3.29450273514 -12.6877803802,0.698472797871,-3.27171802521 -12.6697692871,0.695470750332,-3.22415781021 -12.6737623215,0.695467531681,-3.18258547783 -12.6957588196,0.696463406086,-3.14600086212 -12.6907510757,0.695460855961,-3.10243082047 -12.7417516708,0.698455095291,-3.07382369041 -12.7717494965,0.699450612068,-3.03923273087 -12.8097515106,0.70144701004,-3.02742695808 -12.8467512131,0.703442037106,-2.99482679367 -12.8507442474,0.703439116478,-2.95325255394 -12.89174366,0.705433964729,-2.92065739632 -13.0317573547,0.714422523975,-2.91200113297 -15.7231445312,0.904247522354,-3.51578402519 -15.7691459656,0.907241880894,-3.50097036362 -15.8861494064,0.914229035378,-3.47633242607 -15.8491315842,0.911226332188,-3.41578316689 -16.1111564636,0.928203642368,-3.4240527153 -16.0061283112,0.920205533504,-3.34754705429 -16.0371208191,0.922198355198,-3.30195951462 -16.1431217194,0.92818582058,-3.27233028412 -16.1001091003,0.925186276436,-3.23657202721 -16.1621055603,0.928176999092,-3.19796061516 -16.2391033173,0.933166444302,-3.16134691238 -16.2570915222,0.934160172939,-3.1117708683 -16.2810821533,0.935153543949,-3.06418466568 -16.3150749207,0.936146259308,-3.01859235764 -16.3780708313,0.940136730671,-2.97798752785 -16.4810752869,0.94712638855,-2.97114610672 -16.4790630341,0.946121811867,-2.91757726669 -16.554058075,0.951111257076,-2.87896060944 -16.6010532379,0.953102886677,-2.83436369896 -16.6440448761,0.955094754696,-2.78777742386 -16.6810379028,0.957087159157,-2.7411839962 -16.8040370941,0.965072572231,-2.70954060555 -16.8420352936,0.968067169189,-2.68873763084 -16.9320335388,0.973055124283,-2.65011644363 -16.9410228729,0.973049819469,-2.59754109383 -17.0010166168,0.977040231228,-2.55293941498 -17.0510101318,0.980031430721,-2.50634407997 -17.1320056915,0.985019981861,-2.46472835541 -17.1600017548,0.987015366554,-2.44192647934 -17.1859912872,0.988008677959,-2.39134168625 -17.2489871979,0.99199873209,-2.34573912621 -17.3029785156,0.994989573956,-2.29913687706 -16.4378910065,0.934063434601,-2.11906886101 -16.1878604889,0.916082799435,-2.03164291382 -16.0308380127,0.905094027519,-1.95816731453 -16.0738372803,0.908088564873,-1.93935143948 -16.0078220367,0.902091622353,-1.87882649899 -15.9768123627,0.900091707706,-1.82427275181 -15.9558010101,0.898090839386,-1.77071785927 -15.9357910156,0.896090090275,-1.71815645695 -15.9457836151,0.896086513996,-1.66858446598 -15.9477758408,0.896083772182,-1.61900889874 -15.9267702103,0.895084559917,-1.59123718739 -15.9507646561,0.896079778671,-1.54365420341 -15.9617567062,0.896076261997,-1.49408245087 -15.970749855,0.896073102951,-1.44550120831 -15.9817428589,0.897069692612,-1.3959287405 -15.9987373352,0.898065745831,-1.34734928608 -16.0237312317,0.899061083794,-1.29976296425 -16.0537281036,0.901056885719,-1.27696526051 -16.1597270966,0.908043861389,-1.23633539677 -16.2007217407,0.910037398338,-1.18874716759 -16.2737178802,0.915027678013,-1.14413678646 -16.3777160645,0.922014653683,-1.10151040554 -18.9178352356,1.0967425108,-1.2505364418 -18.6918182373,1.08076477051,-1.20387411118 -18.8568153381,1.09174323082,-1.15721845627 -9.67238998413,0.45973443985,-0.445779621601 -9.69839572906,0.460734665394,-0.41719186306 -9.68639945984,0.459738940001,-0.386617004871 -9.68640422821,0.459742069244,-0.356046766043 -9.67440891266,0.458746492863,-0.325473815203 -9.69841194153,0.46074539423,-0.3116735816 -9.66641521454,0.458752125502,-0.280111193657 -9.68142127991,0.459753662348,-0.250530540943 -9.67342567444,0.458757847548,-0.219960510731 -9.68443107605,0.459759891033,-0.190378248692 -9.6604347229,0.457765907049,-0.159808784723 -9.68544101715,0.458766460419,-0.130226224661 -9.65344238281,0.456771820784,-0.114450186491 -9.67044830322,0.457773268223,-0.0848670452833 -9.65745353699,0.456778287888,-0.0543005391955 -9.6684589386,0.457780480385,-0.0247168652713 -9.64346408844,0.45578700304,0.00584559561685 -9.68347072601,0.458785712719,0.0344510562718 -9.63447570801,0.455795317888,0.0659908205271 -9.65647792816,0.456794500351,0.0807881131768 -9.65048408508,0.456798821688,0.110367365181 -9.66749000549,0.457800418139,0.139955416322 -9.63549518585,0.455808132887,0.170508682728 -9.6575012207,0.456809163094,0.200099930167 -9.6335067749,0.454816013575,0.23065418005 -9.64951038361,0.456815928221,0.245453625917 -9.6315164566,0.454822003841,0.275023490191 -9.64452171326,0.455824226141,0.304612219334 -9.63052845001,0.454830020666,0.335169374943 -9.65253448486,0.456831127405,0.364765971899 -9.61954116821,0.454839348793,0.394321620464 -9.63754749298,0.45584115386,0.424902260303 -9.6185503006,0.454845488071,0.438690692186 -9.63755702972,0.455847173929,0.469273388386 -9.6195640564,0.454853653908,0.498837560415 -9.62656974792,0.454856812954,0.52842438221 -9.61357593536,0.453862726688,0.557991683483 -9.62758255005,0.45586514473,0.588572859764 -9.60558700562,0.453870117664,0.602353334427 -9.63159370422,0.455871045589,0.633934497833 -9.59860134125,0.453879743814,0.662491202354 -9.62560653687,0.455880433321,0.693089723587 -9.60561466217,0.453887403011,0.721659660339 -9.61162090302,0.454891055822,0.752233982086 -9.60062885284,0.453897029161,0.781800091267 -9.61563205719,0.454897224903,0.797596693039 -9.5896396637,0.453905284405,0.826155722141 -9.61364555359,0.455906391144,0.856756746769 -9.59165382385,0.453913986683,0.885319411755 -9.6066608429,0.45491656661,0.916895091534 -9.59066867828,0.453923374414,0.945465564728 -9.60067558289,0.454926609993,0.976048886776 -9.58168029785,0.453931629658,0.989822685719 -9.60268688202,0.455933392048,1.0214111805 -9.58369541168,0.454940795898,1.04997467995 -9.59770202637,0.455943495035,1.0805670023 -9.57671070099,0.453951299191,1.10912537575 -9.5997171402,0.455952763557,1.14072191715 -9.57672214508,0.454958438873,1.15349829197 -9.59472942352,0.455960720778,1.18508696556 -9.5717382431,0.454969018698,1.21363937855 -9.5907459259,0.45597115159,1.24523186684 -9.5637550354,0.454980045557,1.27278840542 -9.58176231384,0.455982357264,1.3043807745 -9.56477069855,0.454989880323,1.3329423666 -9.58077430725,0.456990033388,1.34974086285 -9.56078338623,0.454997986555,1.37730896473 -9.59278964996,0.457998275757,1.41090869904 -9.56179904938,0.456008017063,1.4374653101 -9.58080673218,0.458010315895,1.47005236149 -9.55181789398,0.456019818783,1.49661099911 -9.56882476807,0.457022488117,1.52919495106 -9.5608291626,0.457026273012,1.54298245907 -9.57883644104,0.458028763533,1.57557094097 -9.55184745789,0.457038104534,1.60213172436 -9.56185436249,0.458041846752,1.63371562958 -9.54686450958,0.457049548626,1.6622774601 -9.56787204742,0.459051698446,1.6958643198 -9.53988265991,0.457061260939,1.72143244743 -9.56288528442,0.459060460329,1.74023282528 -9.54589557648,0.458068609238,1.76878857613 -9.5549030304,0.459072649479,1.80037415028 -9.54191398621,0.459080159664,1.82894039154 -9.55492115021,0.460083603859,1.86152505875 -9.52793312073,0.458093285561,1.88709139824 -9.5489358902,0.460092753172,1.90589249134 -9.53294658661,0.459100812674,1.93346273899 -9.54695415497,0.461104303598,1.96704018116 -9.51596546173,0.459114730358,1.99160516262 -9.54197311401,0.461116313934,2.02719378471 -9.51898479462,0.460125654936,2.05375480652 -9.53199195862,0.461129188538,2.08634638786 -9.52299785614,0.461133509874,2.10012769699 -9.53900527954,0.462136656046,2.13371706009 -9.51101779938,0.461146950722,2.15927386284 -9.53002548218,0.463149696589,2.19386172295 -9.50203800201,0.461160093546,2.21941637993 -9.5250453949,0.463162243366,2.25500679016 -9.52105522156,0.463168650866,2.28458809853 -9.52305984497,0.464171260595,2.30037927628 -9.5090713501,0.463179558516,2.3289399147 -9.5310792923,0.465181827545,2.3645324707 -9.50309085846,0.464192301035,2.38909745216 -9.51110076904,0.465197116137,2.42266941071 -9.51411056519,0.466202586889,2.45425128937 -9.51411533356,0.466205656528,2.47003698349 -9.49712657928,0.465214341879,2.49661278725 -9.52313423157,0.468216180801,2.53420209885 -9.48414802551,0.465228646994,2.55576181412 -9.49815750122,0.467232614756,2.59133481979 -9.49116802216,0.467239737511,2.61992168427 -9.48917770386,0.467246353626,2.65148806572 -9.48318386078,0.46725037694,2.66527867317 -9.50619125366,0.469252794981,2.70286512375 -9.47520446777,0.468264251947,2.72642421722 -9.48421478271,0.469268918037,2.76001024246 -9.47822570801,0.469276309013,2.79057621956 -9.47123718262,0.469283759594,2.82015156746 -9.45924854279,0.469292163849,2.84871959686 -9.48625087738,0.471290677786,2.87152886391 -9.46026515961,0.470301479101,2.89609146118 -9.47627353668,0.472305178642,2.9326736927 -9.47528362274,0.472311735153,2.96425008774 -9.4592962265,0.472320973873,2.9918153286 -9.46930599213,0.473325669765,3.02640151978 -9.46231746674,0.473333269358,3.05597996712 -9.46732234955,0.474335700274,3.07376766205 -9.44833564758,0.473345547915,3.10033226013 -9.47334289551,0.476347714663,3.13992500305 -9.44135856628,0.474359840155,3.16248321533 -9.456366539,0.476363778114,3.19907236099 -9.44737911224,0.476371943951,3.2286438942 -9.45138549805,0.47637462616,3.2464299202 -9.44939517975,0.477381587029,3.27800869942 -9.45540618896,0.478387236595,3.3125872612 -9.43741893768,0.478397041559,3.33915638924 -9.43743038177,0.478403747082,3.37173342705 -9.43844223022,0.479410231113,3.40431642532 -9.43745326996,0.480417191982,3.43689084053 -9.43645954132,0.480420678854,3.4526822567 -9.4524679184,0.482424706221,3.49126434326 -9.4264831543,0.481436222792,3.5158200264 -9.42749500275,0.482442736626,3.54840683937 -9.42950630188,0.483449399471,3.5829744339 -9.41951847076,0.483457863331,3.61155867577 -9.4155254364,0.483462154865,3.62733674049 -9.43253421783,0.485466063023,3.66691946983 -9.40654945374,0.484477609396,3.6904861927 -9.42355823517,0.486481517553,3.73007202148 -9.42557048798,0.487488210201,3.76464533806 -9.4025850296,0.486499279737,3.78921461105 -9.40259647369,0.487506300211,3.82279109955 -9.42259979248,0.489506274462,3.84758543968 -9.40561389923,0.488516241312,3.87416124344 -9.40162658691,0.489524126053,3.90673160553 -9.39863872528,0.489531755447,3.93930792809 -9.39765071869,0.490539044142,3.97288370132 -9.38566493988,0.490548223257,4.00146245956 -9.39667510986,0.492553412914,4.04004383087 -9.38468265533,0.492559075356,4.05183124542 -9.39469337463,0.493564546108,4.09040927887 -9.38570690155,0.493573367596,4.12098169327 -9.38571929932,0.494580626488,4.15555620193 -9.37673187256,0.495589494705,4.18612957001 -9.3887424469,0.496594548225,4.22571277618 -9.36975765228,0.496605336666,4.25228023529 -9.3817615509,0.497606903315,4.27507066727 -9.37477588654,0.498615443707,4.30664634705 -9.37378883362,0.499623000622,4.34122085571 -9.36280155182,0.499632298946,4.3707985878 -9.36981296539,0.500638246536,4.40838527679 -9.35782718658,0.501648068428,4.4389462471 -9.36383342743,0.502650558949,4.45874357224 -9.35584640503,0.502659499645,4.49031734467 -9.33986186981,0.502670049667,4.51887989044 -9.360871315,0.504673421383,4.56347227097 -9.35788440704,0.505681574345,4.59804344177 -9.34889793396,0.506690859795,4.62961483002 -9.35890960693,0.507696270943,4.66920661926 -9.35691642761,0.508700370789,4.6859960556 -9.34593009949,0.508710205555,4.71755743027 -9.34794330597,0.509717285633,4.75413990021 -9.34595584869,0.510725140572,4.78872203827 -9.33697032928,0.511734426022,4.82029771805 -9.34198284149,0.512741267681,4.85986757278 -9.34099578857,0.51374900341,4.89544868469 -9.34100246429,0.514752745628,4.91324234009 -9.33301639557,0.514761924744,4.9458155632 -9.34202766418,0.516768038273,4.98739337921 -9.33204269409,0.51777780056,5.01995611191 -9.32405757904,0.51778703928,5.05253219604 -9.3320684433,0.519793093204,5.09311962128 -9.32707691193,0.519797861576,5.10890769958 -9.32608890533,0.520805895329,5.14548587799 -9.32810211182,0.52281332016,5.18406200409 -9.315117836,0.522823631763,5.21463251114 -9.31713104248,0.524831056595,5.25321149826 -9.31314373016,0.524839639664,5.28878593445 -9.3091583252,0.525848329067,5.32436180115 -9.31016540527,0.52685213089,5.34414768219 -9.31817626953,0.528858304024,5.38573741913 -9.30519294739,0.528868854046,5.41730165482 -9.3022069931,0.52987742424,5.4538769722 -9.30821990967,0.531884133816,5.49545907974 -9.29923439026,0.532893836498,5.52903079987 -9.30623912811,0.533896565437,5.55281734467 -9.29525566101,0.534906566143,5.58439826965 -9.29526901245,0.535914540291,5.62297821045 -9.30028152466,0.537921726704,5.66555070877 -9.29629611969,0.538930535316,5.70212888718 -9.28431224823,0.538940787315,5.7337064743 -9.2753276825,0.539950728416,5.76827430725 -9.29033088684,0.541951835155,5.79706859589 -9.27934741974,0.54196202755,5.82964515686 -9.27436161041,0.542971074581,5.86622190475 -9.27737522125,0.544978678226,5.90780162811 -9.27039051056,0.545988321304,5.94436740875 -9.26040649414,0.546998381615,5.97794437408 -9.2714176178,0.54900431633,6.02453231812 -9.26842594147,0.550009131432,6.04331541061 -9.26044082642,0.550018906593,6.07888793945 -9.26445388794,0.552026391029,6.12246370316 -9.24947166443,0.553037524223,6.15304231644 -9.24848556519,0.554046034813,6.19361639023 -9.25849819183,0.556052327156,6.24119853973 -9.23851585388,0.556064605713,6.26976490021 -9.25251960754,0.558066010475,6.29956007004 -9.25353431702,0.560073971748,6.3411450386 -9.24554920197,0.561083912849,6.37771749496 -9.23556613922,0.562094330788,6.41328763962 -9.23857975006,0.564102232456,6.45786142349 -9.2265958786,0.564112901688,6.49143886566 -9.23660087585,0.56611508131,6.51923370361 -9.24161434174,0.568122446537,6.56481695175 -9.22563266754,0.569134235382,6.59737873077 -9.22364711761,0.570142924786,6.63796377182 -9.23066043854,0.572150170803,6.68653821945 -9.20668029785,0.572163462639,6.71310329437 -9.20769405365,0.574171662331,6.75668621063 -9.22769737244,0.57717192173,6.79248476028 -9.2097158432,0.577184140682,6.8240480423 -9.20373058319,0.578193724155,6.86263179779 -9.21474266052,0.581200182438,6.91520833969 -9.19576263428,0.581212580204,6.94577646255 -9.19677639008,0.5832208395,6.99035930634 -9.19979095459,0.585228800774,7.03694105148 -9.29377746582,0.594214618206,7.13075304031 -8.54795360565,0.532371461391,6.61208486557 -8.43299388885,0.524403274059,6.56761407852 -8.38301944733,0.521421909332,6.57018327713 -8.31404972076,0.517444491386,6.55873632431 -8.27007484436,0.515461862087,6.56530714035 -8.21010398865,0.511482894421,6.56085538864 -8.18311786652,0.510492622852,6.55964279175 -8.13614368439,0.507510960102,6.56420183182 -8.076171875,0.504531800747,6.55776119232 -8.0301990509,0.502550005913,6.56232309341 -7.97722625732,0.499569535255,6.56088352203 -7.92125415802,0.496589660645,6.5564455986 -7.88926935196,0.494600653648,6.5512213707 -7.84729480743,0.492618054152,6.55778694153 -7.79132318497,0.489638209343,6.55235004425 -7.7573466301,0.487654060125,6.5649189949 -7.73836708069,0.487667024136,6.59048604965 -7.64040565491,0.480695724487,6.54903650284 -7.63941383362,0.481700509787,6.56882190704 -7.55344963074,0.475726783276,6.5363779068 -7.51647472382,0.474743485451,6.54593896866 -7.48249864578,0.47375947237,6.5575056076 -7.4425239563,0.471776604652,6.5630774498 -7.41654682159,0.470791101456,6.58164215088 -7.3345823288,0.465816736221,6.55020046234 -7.30959606171,0.463826477528,6.54897689819 -7.26262378693,0.461845070124,6.54754543304 -7.20165491104,0.457866728306,6.53410196304 -7.1756772995,0.457881093025,6.55067825317 -7.17069482803,0.458891302347,6.58625841141 -7.13172101974,0.456908524036,6.59182262421 -7.14473438263,0.459914952517,6.64341449738 -7.13574504852,0.459921568632,6.65619516373 -7.12176561356,0.460933834314,6.68476486206 -6.97381734848,0.448973208666,6.58929538727 -6.99182987213,0.452978730202,6.64588689804 -6.93885946274,0.449998915195,6.6374464035 -6.4509935379,0.406107544899,6.21886825562 -6.94389247894,0.454016566277,6.72360992432 -6.89791154861,0.45103058219,6.70038700104 -6.8659362793,0.450046479702,6.71095609665 -6.68099784851,0.434093415737,6.5734834671 -6.76499509811,0.44408595562,6.69608020782 -6.76401233673,0.446095436811,6.73566484451 -6.78502416611,0.450100541115,6.79725456238 -6.63406896591,0.436135947704,6.66900253296 -6.75005865097,0.450121939182,6.82560968399 -6.76507234573,0.453128278255,6.88219642639 -6.71910095215,0.451147258282,6.87875795364 -6.68112754822,0.449164420366,6.88232898712 -6.6471529007,0.448180824518,6.88990020752 -6.6641664505,0.452186852694,6.94948673248 -6.62518453598,0.449199467897,6.93027019501 -6.59820890427,0.448214679956,6.94583368301 -6.61822080612,0.452219963074,7.00842809677 -9.0146446228,0.692739605904,9.55370998383 -9.01665973663,0.695748448372,9.61429214478 -9.01467609406,0.698758363724,9.67186832428 -8.98869895935,0.698772966862,9.7034444809 -8.94671821594,0.696786463261,9.69020938873 -8.88175010681,0.692809164524,9.67977523804 -8.82677936554,0.69082981348,9.68033790588 -8.7818069458,0.688848614693,9.6919002533 -8.73283672333,0.686868131161,9.69846439362 -8.73085308075,0.689877986908,9.75604534149 -8.73886013031,0.6918810606,9.79483890533 -8.73487663269,0.694891393185,9.85141563416 -8.72989559174,0.697901964188,9.90699291229 -8.74390792847,0.701908648014,9.98457431793 -8.97586536407,0.729870676994,10.3092184067 -8.97588157654,0.732880353928,10.3747882843 -8.95690345764,0.733893752098,10.4173641205 -8.25009250641,0.662043511868,9.63596439362 -8.20812034607,0.661061763763,9.6475315094 -8.1591501236,0.659081339836,9.65010261536 -8.10818004608,0.656101644039,9.65166091919 -8.0552110672,0.654122114182,9.64922809601 -8.0122385025,0.653140664101,9.65879440308 -7.92327880859,0.646168470383,9.61235523224 -7.92728662491,0.648172676563,9.64813995361 -7.84232616425,0.642199933529,9.60669326782 -7.72037506104,0.632234573364,9.51824569702 -7.77237844467,0.641233623028,9.6418390274 -7.78239345551,0.646241366863,9.71541881561 -7.65744352341,0.635276854038,9.621966362 -3.42757225037,0.174156576395,4.3964343071 -3.42459177971,0.175166726112,4.41903209686 -3.40261697769,0.174181118608,4.41861152649 -3.40963459015,0.17618958652,4.45519638062 -7.33662462234,0.618396937847,9.55256271362 -7.29965257645,0.617414295673,9.56513786316 -7.26766967773,0.615425825119,9.55392074585 -7.21770048141,0.613445878029,9.54949092865 -7.17772912979,0.612464129925,9.55905628204 -7.08777046204,0.605492532253,9.50161266327 -7.06379508972,0.606507241726,9.53019142151 -7.00782775879,0.603528678417,9.51675701141 -6.99484014511,0.603536367416,9.53053951263 -6.93687391281,0.600558280945,9.51410388947 -6.91089868546,0.600573420525,9.53968238831 -6.84693431854,0.59659665823,9.51424503326 -6.95992183685,0.613583385944,9.73284912109 -6.79498434067,0.597627222538,9.56639385223 -6.74301671982,0.594647824764,9.55596256256 -6.69903755188,0.591661930084,9.52574062347 -6.63607311249,0.587684869766,9.4993057251 -6.60609960556,0.587701141834,9.51987457275 -6.54713344574,0.583723187447,9.49744606018 -6.52315807343,0.584738194942,9.5260181427 -6.45019674301,0.579763293266,9.48357868195 -6.42622184753,0.579778194427,9.51115608215 -6.38424253464,0.57679194212,9.48193264008 -6.3382730484,0.574811339378,9.47650718689 -6.31929683685,0.575825333595,9.51208019257 -6.27032899857,0.573845386505,9.50165653229 -6.20636510849,0.56986874342,9.47021484375 -6.17339277267,0.568885624409,9.48378944397 -6.14941835403,0.569900631905,9.51136398315 -6.12943315506,0.568909645081,9.51215457916 -6.07646608353,0.565930783749,9.49571800232 -6.03049755096,0.563950359821,9.48928642273 -6.00152444839,0.563966274261,9.50786685944 -5.95855569839,0.562985420227,9.50642967224 -5.92958164215,0.563001215458,9.52401638031 -5.91759490967,0.563008964062,9.53879642487 -5.8956193924,0.564023435116,9.56837940216 -5.88864040375,0.567035138607,9.62395572662 -5.88066148758,0.570046901703,9.67753696442 -5.85868644714,0.571061551571,9.70911216736 -5.85970497131,0.575071513653,9.77869415283 -5.84472799301,0.577084720135,9.82227230072 -5.86073350906,0.58108663559,9.88406276703 -5.83176040649,0.582102835178,9.90563488007 -5.83577823639,0.5861120224,9.98122501373 -5.84279537201,0.592120885849,10.0648040771 -5.83781528473,0.595131993294,10.1273880005 -5.80084514618,0.594149947166,10.1369562149 -5.82584667206,0.6001496315,10.2147626877 -5.83286428452,0.605158507824,10.3013410568 -5.84288024902,0.611166656017,10.3929271698 -5.85189676285,0.617175221443,10.4855031967 -5.84591722488,0.621186554432,10.5500907898 -5.83493995667,0.624199032784,10.607667923 -5.84495544434,0.630207061768,10.7022590637 -5.86495923996,0.635208129883,10.7780542374 -5.86697864532,0.640218138695,10.8626289368 -5.94097614288,0.65621316433,11.0792284012 -5.87101507187,0.651237785816,11.031794548 -5.81804943085,0.64825886488,11.0143699646 -5.8300652504,0.655266821384,11.1209478378 -5.82008695602,0.659279048443,11.1845340729 -5.83109331131,0.663281977177,11.2483243942 -5.83411216736,0.669291734695,11.3399047852 -5.82413387299,0.672304034233,11.4064884186 -5.81515598297,0.676316261292,11.4770641327 -5.82217311859,0.683325052261,11.5786504745 -5.82019233704,0.688335835934,11.664232254 -5.81721258163,0.693346619606,11.7478189468 -5.83321762085,0.699348688126,11.8266086578 -5.83823537827,0.705358088017,11.930188179 -5.85524988174,0.713364899158,12.0577774048 -5.86026716232,0.72037422657,12.1633605957 -5.83829307556,0.723389148712,12.2149362564 -5.81631946564,0.725404083729,12.2675104141 -5.84831953049,0.734402596951,12.3823137283 -5.81534862518,0.734419763088,12.4128866196 -5.82136631012,0.742429018021,12.5264692307 -5.84437799454,0.752434551716,12.6760625839 -5.87838792801,0.764438271523,12.8556423187 -2.79082512856,0.36033475399,7.7501783371 -2.76685333252,0.360350072384,7.76074981689 -2.76686286926,0.362354934216,7.79655361176 -2.73189401627,0.360372275114,7.77513074875 -2.55712080002,0.367494672537,7.94057607651 -2.42736577988,0.396623194218,8.42041778564 -2.52037811279,0.433625072241,8.94461345673 -2.48440980911,0.431642562151,8.92418956757 -2.38248276711,0.419683635235,8.77333450317 -2.38549160957,0.423688024282,8.83613586426 -2.37151646614,0.427700936794,8.89272403717 -2.36154031754,0.432713270187,8.96730518341 -2.346565485,0.435726612806,9.02488613129 -2.37762761116,0.472756117582,9.56145954132 -5.2468457222,1.37624371052,22.3958244324 -5.21386623383,1.37725555897,22.4136104584 -5.17089939117,1.38627481461,22.5491867065 -5.12293434143,1.39329493046,22.6647663116 -5.04797792435,1.39132034779,22.6623401642 -4.97901916504,1.39234471321,22.689912796 -4.91206026077,1.39336824417,22.7204933167 -4.87408208847,1.39338111877,22.7202777863 -3.28659200668,0.891701221466,15.6056699753 -3.22563123703,0.887723565102,15.5582475662 -3.15867257118,0.881747066975,15.4788246155 -3.09671258926,0.876769661903,15.4234008789 -3.04674863815,0.876789867878,15.4249792099 -3.01677846909,0.882806062698,15.5255641937 -2.98779797554,0.881816983223,15.5083494186 -2.93083643913,0.878838539124,15.4749259949 -2.88187217712,0.878858447075,15.481505394 -2.84890270233,0.883875131607,15.5700941086 -2.79693961143,0.882895708084,15.5626707077 -2.75297403336,0.884914636612,15.5992507935 -2.70500969887,0.885934472084,15.6148281097 -2.67405056953,0.902956008911,15.8762044907 -2.58209991455,0.884984076023,15.63078022 -3.8387298584,1.44075262547,23.6025161743 -3.76877212524,1.44277667999,23.6400928497 -3.55785799026,1.38182771206,22.7786617279 -3.46590709686,1.37285578251,22.6572360992 -3.43992567062,1.37686622143,22.7270259857 -3.37596607208,1.37988901138,22.7826080322 -3.30300951004,1.37991344929,22.7831859589 -3.21005892754,1.36894178391,22.6427631378 -3.13110423088,1.3649674654,22.5993385315 -3.07814145088,1.37398803234,22.7369213104 -3.03816413879,1.37200093269,22.7097110748 -2.96020936966,1.36902630329,22.6712856293 -2.89225125313,1.37004971504,22.7038669586 -2.82929158211,1.37507212162,22.7774486542 -2.76533222198,1.37909471989,22.8450317383 -2.68337845802,1.37312066555,22.7686080933 -2.60942268372,1.37214529514,22.7581863403 -2.56944561005,1.36915802956,22.7269744873 -2.51548314095,1.38017868996,22.8905544281 -2.42853093147,1.37020552158,22.7511386871 -2.36057305336,1.37322866917,22.793718338 -2.29761338234,1.37825095654,22.8843002319 -2.22965550423,1.38227427006,22.936876297 -2.20267438889,1.38828456402,23.0296707153 -2.11972117424,1.38031053543,22.9222507477 -2.06275963783,1.39133143425,23.0938339233 -1.97880685329,1.38235759735,22.9664134979 -1.90085220337,1.37838244438,22.9069919586 -1.84589004517,1.39140295982,23.1105804443 -1.78093135357,1.39942550659,23.2211608887 -1.74295353889,1.39743769169,23.1979522705 -1.672996521,1.40046107769,23.2465324402 -1.60503852367,1.40548408031,23.3211174011 -1.52908313274,1.40250837803,23.2817001343 -1.45812630653,1.40453183651,23.3202819824 -1.39616668224,1.41755354404,23.5138645172 -1.33820569515,1.43657457829,23.7944488525 -1.30722594261,1.44458544254,23.9172382355 -1.26026153564,1.48160433769,24.4548244476 -1.22929191589,1.54562008381,25.3814144135 -1.1663326025,1.57064187527,25.7450008392 -1.09037709236,1.57766592503,25.8505859375 -1.01242244244,1.5836905241,25.9391689301 -0.939466059208,1.59771406651,26.154756546 -0.907486736774,1.61772501469,26.4375457764 -0.825533211231,1.61875009537,26.4571304321 -0.735582351685,1.60177671909,26.2217140198 -0.653628885746,1.60280179977,26.2282981873 -0.570675969124,1.60182702541,26.2218799591 -0.487723022699,1.60185229778,26.2124614716 -0.446746230125,1.60086464882,26.2012557983 -0.363793253899,1.59888982773,26.1758384705 -0.281839758158,1.59691476822,26.1464252472 -0.198886826634,1.59393978119,26.1010074615 -0.116933427751,1.59196460247,26.0795936584 -0.0349800810218,1.59098935127,26.0591773987 --0.06296300143,1.5900195837,24.3126583099 --0.100940674543,1.59003138542,24.3024501801 --0.176895990968,1.58805501461,24.2850379944 --0.253850847483,1.59007871151,24.312620163 --0.329806178808,1.59010219574,24.3012084961 --0.405761301517,1.5871257782,24.2577915192 --0.481716632843,1.58714914322,24.2553787231 --0.557672023773,1.58717250824,24.2539672852 --0.594649970531,1.58318400383,24.2107601166 --0.670605182648,1.58320736885,24.200345993 --0.746560335159,1.58223080635,24.1879310608 --0.821516036987,1.58025383949,24.1585178375 --0.897471249104,1.5802770853,24.1561031342 --0.97342646122,1.58030033112,24.14868927 --1.04938185215,1.58132338524,24.1552772522 --1.08735954762,1.58033502102,24.147069931 --1.16331481934,1.58135795593,24.1486587524 --1.23827052116,1.58038079739,24.1412506104 --1.31522548199,1.58140397072,24.1508369446 --1.39118075371,1.58142697811,24.1414222717 --1.46713626385,1.58244991302,24.1450119019 --1.50611352921,1.58346152306,24.1598052979 --1.58206892014,1.58348429203,24.1573944092 --1.65902388096,1.58450734615,24.1629810333 --1.7359790802,1.58653020859,24.1795711517 --1.81193423271,1.58555305004,24.1631565094 --1.88788974285,1.58557581902,24.15974617 --1.9658446312,1.58759868145,24.184337616 --2.00482201576,1.58861017227,24.1891307831 --2.083776474,1.59163320065,24.2167205811 --2.16173124313,1.59265613556,24.2293071747 --2.24068593979,1.59567904472,24.2599010468 --2.32064008713,1.59770214558,24.28748703 --2.39759516716,1.59872484207,24.284078598 --2.47455048561,1.59874737263,24.2836685181 --2.51552724838,1.6017588377,24.309463501 --2.59648108482,1.60378217697,24.3360500336 --2.6744363308,1.60580456257,24.3496456146 --2.75938868523,1.61082839966,24.4082317352 --2.84134244919,1.61385154724,24.4448204041 --2.92129707336,1.61587417126,24.4644145966 --3.00225090981,1.61889719963,24.4850025177 --3.0472266674,1.62290918827,24.5368003845 --3.12818074226,1.6249320507,24.5523910522 --3.21113443375,1.62795507908,24.5899848938 --3.29208827019,1.62997770309,24.6065750122 --3.37704110146,1.63400113583,24.6491641998 --3.45799541473,1.63602375984,24.6617565155 --3.50197124481,1.63903558254,24.6935520172 --3.58392524719,1.64105832577,24.710144043 --3.66787862778,1.64408123493,24.7417354584 --3.74883294106,1.64610350132,24.7553310394 --3.83078694344,1.64812600613,24.7679233551 --3.91374063492,1.65014874935,24.789516449 --3.99869346619,1.65317153931,24.8161067963 --4.0426697731,1.6561832428,24.8409042358 --4.12562322617,1.6582056284,24.8605003357 --4.21157646179,1.6622287035,24.8910923004 --4.29452991486,1.6642510891,24.9046859741 --4.37948322296,1.66727364063,24.9292793274 --4.46643590927,1.67029666901,24.9608707428 --4.55138921738,1.67331910133,24.9854698181 --4.59936475754,1.67633116245,25.0232639313 --4.68531751633,1.6793538332,25.0488605499 --4.77326965332,1.68337678909,25.0784511566 --4.85822343826,1.68539893627,25.0990505219 --4.94717550278,1.68942189217,25.133644104 --5.03212881088,1.69144415855,25.1472396851 --5.08110380173,1.69545614719,25.1860370636 --5.16905641556,1.69847881794,25.2126331329 --5.25600910187,1.70150125027,25.2302265167 --5.33996295929,1.70252299309,25.2348194122 --5.42891550064,1.70654547215,25.2644195557 --5.51186943054,1.70756709576,25.260011673 --5.6048207283,1.71259009838,25.3046092987 --5.65379571915,1.71560204029,25.3364067078 --5.7447476387,1.71862471104,25.3670024872 --5.85269403458,1.72864997387,25.4706001282 --5.94564533234,1.73267269135,25.5061969757 --5.99860954285,1.72368907928,25.3767967224 --6.04657506943,1.71370470524,25.2233905792 --6.12952899933,1.71472585201,25.2189884186 --6.18750143051,1.72073888779,25.2847881317 --6.28245210648,1.72576165199,25.32538414 --6.36440753937,1.72678244114,25.3159828186 --6.45635938644,1.72980475426,25.3425807953 --6.54031419754,1.73182559013,25.3411827087 --6.62226867676,1.73184621334,25.3257751465 --6.70822286606,1.73386716843,25.3313789368 --6.74920034409,1.73387742043,25.3241767883 --6.83215522766,1.73489809036,25.3117713928 --6.92110872269,1.7379193306,25.3263721466 --7.01106119156,1.74094080925,25.340970993 --7.10301303864,1.74396252632,25.3605690002 --7.18996715546,1.7459833622,25.3641700745 --7.24294137955,1.74999535084,25.3989696503 --7.32789564133,1.75101566315,25.3925704956 --7.40785217285,1.75103533268,25.3711719513 --7.22188854218,1.68201422691,24.450756073 --7.29884576797,1.6820333004,24.4273548126 --7.37880182266,1.68305289745,24.4129524231 --7.46775531769,1.68607378006,24.4295520782 --7.53372573853,1.6930873394,24.5073547363 --7.86660528183,1.75614488125,25.3039703369 --7.94756174088,1.75616431236,25.2825698853 --8.03251647949,1.75818419456,25.2761745453 --8.10947418213,1.75720274448,25.2427749634 --8.1844329834,1.75622093678,25.2033748627 --8.28038406372,1.76024222374,25.2279777527 --8.3183631897,1.76025140285,25.207775116 --8.40831661224,1.76227164268,25.2143802643 --8.49427127838,1.76429128647,25.2069816589 --8.5842256546,1.7663115263,25.2115840912 --6.45184516907,1.26600313187,18.7670288086 --8.7761297226,1.77435326576,25.250787735 --8.82010746002,1.77536296844,25.2515926361 --8.91306018829,1.77838337421,25.2591915131 --8.99101829529,1.77740132809,25.2287998199 --6.53773117065,1.22704970837,18.1732063293 --6.63668203354,1.23607158661,18.2658042908 --9.27487564087,1.7874622345,25.2666091919 --6.87757158279,1.26312148571,18.5630092621 --9.40580940247,1.79049086571,25.2520122528 --6.99350786209,1.26914906502,18.6064128876 --7.03347682953,1.26516222954,18.5340080261 --9.68167114258,1.79854941368,25.2618293762 --7.32735013962,1.3012188673,18.9462203979 --7.07740497589,1.2381901741,18.1307964325 --7.12937068939,1.23720479012,18.0973987579 --7.2903137207,1.2642313242,18.4182033539 --7.22531318665,1.23922920227,18.0867919922 --7.26928138733,1.23724257946,18.0323925018 --9.95645046234,1.73663437366,24.2488307953 --7.74508333206,1.29633057117,18.69921875 --10.3343114853,1.78669631481,24.8342647552 --10.3982744217,1.78471112251,24.7658653259 --10.4152507782,1.77271926403,24.589466095 --10.5481748581,1.76874923706,24.4736747742 --10.5601539612,1.75675654411,24.2902736664 --8.00288486481,1.27341067791,18.254611969 --8.04586219788,1.27641999722,18.2744140625 --10.8130350113,1.76780545712,24.345293045 --10.8889942169,1.76782131195,24.3088989258 --10.9599552155,1.76683664322,24.2615032196 --11.0319166183,1.7668517828,24.2181110382 --11.1218729019,1.76886940002,24.2117156982 --11.1838359833,1.76688313484,24.1473236084 --8.23768424988,1.24448919296,17.7148017883 --11.3037757874,1.76790714264,24.1067352295 --11.381734848,1.76792287827,24.0733375549 --11.4676923752,1.76993954182,24.0589466095 --9.04737567902,1.34462296963,18.8312740326 --9.04435825348,1.33362877369,18.6728687286 --11.6685905457,1.77197909355,23.9919662476 --9.21226406097,1.33766627312,18.6428756714 --9.12027263641,1.31266021729,18.3114643097 --9.14024829865,1.30666899681,18.2060585022 --9.17921924591,1.3036801815,18.1416625977 --9.22218799591,1.30169188976,18.0832576752 --9.24917125702,1.30069828033,18.0670642853 --9.30913543701,1.30171203613,18.0426654816 --9.36210346222,1.3007247448,18.0062713623 --9.40807151794,1.299736619,17.9568748474 --9.51302337646,1.30675601959,18.0164794922 --9.55099487305,1.30376660824,17.9520835876 --9.64395046234,1.30978429317,17.9886894226 --9.71492099762,1.31679606438,18.0524940491 --9.85386371613,1.3288192749,18.1741142273 --9.94482040405,1.33383643627,18.2037200928 --10.0657682419,1.34385716915,18.2873306274 --10.0907440186,1.3388658762,18.195930481 --10.0977249146,1.33187222481,18.0745296478 --10.2276611328,1.33789658546,18.1049423218 --12.8758974075,1.72522854805,22.6279029846 --12.8948755264,1.71723508835,22.4955043793 --12.8898601532,1.70623862743,22.3231010437 --12.8638505936,1.69223964214,22.1166992188 --12.8648338318,1.68224394321,21.9582958221 --13.6116170883,1.78533649445,23.1502056122 --12.8348178864,1.66224646568,21.6726951599 --12.8338012695,1.65225052834,21.5152950287 --12.6828269958,1.62123656273,21.109872818 --12.6178293228,1.60223281384,20.8514595032 --12.6098146439,1.59223616123,20.6900558472 --12.6277942657,1.58524239063,20.5736579895 --12.6027927399,1.57724153996,20.4604568481 --12.596777916,1.56724500656,20.3060531616 --12.58776474,1.55724799633,20.1496524811 --12.5767507553,1.54725086689,19.9912490845 --12.5767345428,1.53825485706,19.8518486023 --12.5787191391,1.53025925159,19.7174510956 --12.5457191467,1.52125751972,19.5962429047 --12.5387048721,1.51226067543,19.4498405457 --12.5336904526,1.50326430798,19.3074378967 --12.5206775665,1.49326682091,19.1560382843 --12.5186624527,1.48427057266,19.0206356049 --12.5156469345,1.47627425194,18.8862361908 --12.5076332092,1.46727740765,18.7448329926 --12.4766340256,1.45927584171,18.6336250305 --12.4686193466,1.45027899742,18.495223999 --12.4466104507,1.44028055668,18.3368186951 --12.4265995026,1.42928230762,18.1834163666 --12.4245843887,1.42228603363,18.0580158234 --12.4165706635,1.41328907013,17.925617218 --12.4345502853,1.40829491615,17.8302173615 --12.4095487595,1.40229427814,17.733007431 --12.4565200806,1.40130329132,17.6826190948 --12.5264854431,1.40231478214,17.6622257233 --12.56346035,1.4003225565,17.5968360901 --12.5704421997,1.3943271637,17.4884338379 --12.5964202881,1.3903336525,17.4080371857 --12.4914398193,1.37332427502,17.2058181763 --12.6333866119,1.38434326649,17.2864437103 --12.6783590317,1.38335156441,17.2340526581 --12.6953392029,1.37935721874,17.1416492462 --12.5863523483,1.35834932327,16.8822307587 --12.6103305817,1.35535550117,16.8038349152 --12.3233919144,1.31332921982,16.3133850098 --12.2843942642,1.30532717705,16.2071762085 --12.2833795547,1.29933083057,16.099773407 --12.2883615494,1.29333508015,16.001373291 --8.99721622467,0.890002608299,11.6294002533 --9.02619171143,0.889010965824,11.5899982452 --9.05416679382,0.88801920414,11.5495958328 --9.12613201141,0.892031788826,11.5662069321 --12.3472776413,1.27435767651,15.6125812531 --12.4162445068,1.27636826038,15.5981931686 --12.5082044601,1.2813808918,15.6118078232 --12.5621757507,1.28238976002,15.5784187317 --12.684129715,1.29040515423,15.62803936 --12.7800893784,1.29641795158,15.6446552277 --12.8010759354,1.29542171955,15.6194572449 --12.8710432053,1.29743182659,15.6040706635 --13.0019950867,1.30744767189,15.6626987457 --13.0709629059,1.3094574213,15.6443090439 --13.1379299164,1.31146681309,15.623922348 --13.2178955078,1.31547749043,15.6195411682 --13.2938613892,1.3184877634,15.6071481705 --13.3668355942,1.32349598408,15.6439676285 --13.4428014755,1.32650589943,15.6315784454 --13.5177679062,1.32951569557,15.6191959381 --13.5907354355,1.3325252533,15.603811264 --13.6846971512,1.33753657341,15.6114282608 --13.7576646805,1.33954572678,15.595044136 --13.9336061478,1.35456430912,15.6946802139 --13.9276008606,1.35056507587,15.6384811401 --14.0105657578,1.35457491875,15.6310958862 --14.1105270386,1.35958623886,15.6427154541 --14.1465034485,1.35859179497,15.5833244324 --14.2394676208,1.36360228062,15.5869455338 --14.3334302902,1.36861264706,15.5905666351 --14.4383897781,1.3746240139,15.6051874161 --12.0839710236,1.11642038822,13.0104990005 --12.0699596405,1.11042249203,12.9120912552 --12.065946579,1.10542547703,12.8256883621 --12.0679311752,1.10142886639,12.7472915649 --12.0899114609,1.09943389893,12.6898956299 --12.172876358,1.10344421864,12.6965122223 --12.2058610916,1.10544860363,12.6893119812 --12.2238426208,1.10245323181,12.6279163361 --12.2298269272,1.09945690632,12.5545186996 --12.2268123627,1.09445977211,12.471113205 --12.2188005447,1.08946228027,12.3837089539 --12.2167873383,1.08546519279,12.3043136597 --12.2117738724,1.08046782017,12.2219133377 --12.196770668,1.07746815681,12.1667032242 --12.1947565079,1.07347106934,12.0883045197 --12.1697492599,1.06647205353,11.9868984222 --12.1687355042,1.06247496605,11.9104995728 --12.166721344,1.05847787857,11.8320932388 --6.6320400238,0.485050410032,6.3805475235 --6.45406627655,0.465042680502,6.16811180115 --6.44006061554,0.462044835091,6.1338968277 --6.43204498291,0.460050523281,6.08648490906 --6.44402503967,0.459057658911,6.0590839386 --6.43600940704,0.456063270569,6.01267719269 --6.44099092484,0.455069899559,5.97826719284 --6.44497299194,0.45307636261,5.94386529922 --6.45695304871,0.45208349824,5.91645812988 --6.45994377136,0.452086627483,5.90126752853 --6.4569272995,0.450092673302,5.85985422134 --6.48490333557,0.450100898743,5.84745168686 --6.4918847084,0.449107557535,5.81604623795 --6.49986553192,0.448114216328,5.78564119339 --6.51784420013,0.448121637106,5.76423740387 --6.52183437347,0.448124974966,5.74903345108 --6.5368142128,0.447132021189,5.7256360054 --6.54479551315,0.446138679981,5.69522714615 --6.56577348709,0.44714614749,5.67682695389 --6.58575153351,0.447153687477,5.65641403198 --6.60373067856,0.44716078043,5.6360206604 --6.62170982361,0.447167992592,5.61461544037 --6.62470006943,0.446171224117,5.59840774536 --6.64267921448,0.446178406477,5.57700252533 --6.66765737534,0.447185844183,5.56261110306 --6.68363666534,0.447192698717,5.5402135849 --6.70161581039,0.447199761868,5.51880884171 --6.72059488297,0.44720685482,5.49840641022 --6.75656986237,0.449214935303,5.49200773239 --6.75956058502,0.448218137026,5.47579860687 --6.79553604126,0.450226128101,5.4694018364 --6.82851171494,0.451233953238,5.46000051498 --6.85348987579,0.452241122723,5.44460487366 --6.87746810913,0.453248351812,5.42719602585 --6.91344308853,0.454256236553,5.41979551315 --6.95441770554,0.457264244556,5.41639947891 --6.99440050125,0.460269361734,5.43020820618 --7.02837657928,0.46127691865,5.42081022263 --11.9722795486,0.921562492847,9.23059749603 --11.9862632751,0.920565724373,9.18019580841 --11.983250618,0.917567908764,9.11779499054 --11.988237381,0.915570557117,9.06139564514 --11.9902238846,0.912572979927,9.00299453735 --11.9742202759,0.909573376179,8.96078777313 --12.0012025833,0.909577131271,8.92139148712 --12.0771741867,0.914583325386,8.91901111603 --11.9651842117,0.901579797268,8.77657985687 --5.60052871704,0.316254764795,4.03464698792 --5.60651063919,0.315261274576,4.01225233078 --11.9391460419,0.88958632946,8.55416965485 --11.9431324005,0.887588739395,8.49977016449 --11.9431200027,0.885590970516,8.44236755371 --11.9391078949,0.882592916489,8.38196086884 --11.9430942535,0.880595266819,8.32755661011 --11.9360837936,0.877597093582,8.26716136932 --11.9230804443,0.875597476959,8.22995567322 --11.9230680466,0.87259966135,8.17355251312 --11.9230556488,0.870601713657,8.11815357208 --11.9140453339,0.867603421211,8.05574512482 --11.9230318069,0.866605818272,8.00735092163 --11.9210195541,0.863607823849,7.94994163513 --11.9150085449,0.860609531403,7.89154243469 --11.9020051956,0.858610033989,7.85533618927 --11.9039926529,0.856612086296,7.80193281174 --11.9019813538,0.854614019394,7.74653148651 --11.8969697952,0.851615726948,7.68912744522 --11.904955864,0.849618017673,7.64072942734 --11.9009447098,0.847619712353,7.58432435989 --11.8949337006,0.844621419907,7.52691936493 --11.884929657,0.842621922493,7.49472141266 --11.8729200363,0.839623391628,7.43431758881 --11.877907753,0.838625371456,7.38491773605 --11.8778963089,0.836627244949,7.33251667023 --11.8738851547,0.833628892899,7.27710914612 --11.8648738861,0.831630408764,7.2197060585 --11.8678617477,0.829632222652,7.16930246353 --11.8518590927,0.826632618904,7.13409996033 --11.8628454208,0.825634717941,7.0886964798 --11.8458366394,0.822635889053,7.02729082108 --11.8498249054,0.820637702942,6.97889280319 --11.8518123627,0.819639444351,6.92848587036 --11.8458023071,0.816640973091,6.87508916855 --11.8487901688,0.815642654896,6.82669115067 --11.8337879181,0.812643051147,6.79248380661 --11.8317756653,0.810644626617,6.74108028412 --11.8287658691,0.808646142483,6.68968009949 --11.824754715,0.806647598743,6.63727426529 --11.8277425766,0.805649220943,6.58987760544 --11.8217325211,0.802650690079,6.53646945953 --11.8127279282,0.80165117979,6.50626134872 --11.8107175827,0.799652636051,6.45686578751 --11.8456993103,0.800654947758,6.42646837234 --11.8926811218,0.802657425404,6.40307855606 --11.90766716,0.802659153938,6.36268472672 --11.8946580887,0.799660205841,6.30728292465 --11.9096441269,0.798661828041,6.26587867737 --11.9796266556,0.803663849831,6.27869701385 --12.0486030579,0.808666348457,6.26732349396 --12.1305789948,0.813668966293,6.26094198227 --12.1985559464,0.817671239376,6.24756288528 --12.2785320282,0.822673559189,6.24018907547 --12.3855037689,0.829676151276,6.24582099915 --12.3854932785,0.827676951885,6.19642066956 --12.4174823761,0.829677820206,6.18722438812 --12.367480278,0.823677897453,6.11280918121 --12.3564720154,0.821678578854,6.05840492249 --12.3364648819,0.81867903471,6.00000095367 --12.3484525681,0.817680001259,5.95659780502 --12.3424444199,0.81568056345,5.90519475937 --12.3704299927,0.816681623459,5.87080621719 --12.3464279175,0.813681721687,5.83459424973 --12.3434181213,0.811682343483,5.7851934433 --12.3544073105,0.811683058739,5.74279928207 --12.3383998871,0.808683514595,5.68739271164 --12.3463888168,0.807684183121,5.64299058914 --12.2523937225,0.798684179783,5.55155611038 --12.3093748093,0.801685035229,5.53117799759 --12.3163690567,0.801685333252,5.50997304916 --12.3143596649,0.799685895443,5.46257686615 --12.323348999,0.798686444759,5.41917419434 --12.3133401871,0.796686828136,5.36776924133 --12.312330246,0.795687317848,5.32036542892 --12.3073225021,0.793687701225,5.27196598053 --12.304318428,0.792687892914,5.24776744843 --12.3053073883,0.791688263416,5.20136260986 --12.3032989502,0.789688646793,5.15395832062 --12.3012895584,0.788689017296,5.10756111145 --12.2922821045,0.786689341068,5.0571513176 --12.2962713242,0.785689592361,5.01274967194 --12.2862634659,0.783689916134,4.96334886551 --12.3052568436,0.784689962864,4.94815254211 --11.7393302917,0.737693309784,4.6715631485 --11.706325531,0.733694136143,4.61515378952 --11.6993169785,0.732694745064,4.5687456131 --11.7013072968,0.731695413589,4.5263428688 --11.70129776,0.730696022511,4.48293685913 --11.6962890625,0.728696644306,4.43853664398 --11.6872844696,0.727696955204,4.41332960129 --11.6832761765,0.725697577,4.36892366409 --11.6912660599,0.725697994232,4.32952547073 --11.685256958,0.723698616028,4.28512477875 --11.6782484055,0.72269910574,4.23971557617 --11.6882381439,0.721699416637,4.20131826401 --11.6602325439,0.718700230122,4.14890623093 --11.6752262115,0.719700276852,4.13371372223 --11.6772165298,0.718700587749,4.09231090546 --11.6582098007,0.715701282024,4.04390478134 --11.6711988449,0.715701401234,4.00650453568 --11.6661901474,0.714701831341,3.96310043335 --11.6601819992,0.712702214718,3.91969895363 --11.6571731567,0.711702525616,3.87729620934 --11.6621685028,0.71170258522,3.85809493065 --11.644162178,0.709703147411,3.81068634987 --11.645152092,0.7087033391,3.76927900314 --11.6551427841,0.7087033391,3.73188400269 --11.6451349258,0.706703722477,3.68747758865 --11.6151304245,0.703704595566,3.63706731796 --11.5361309052,0.696706771851,3.57063388824 --11.5151290894,0.694707393646,3.54443216324 --11.5121212006,0.692707657814,3.50201702118 --11.5191116333,0.692707598209,3.46462321281 --11.5111036301,0.691707968712,3.42221975327 --11.5040960312,0.68970823288,3.37981247902 --11.5170860291,0.689707934856,3.34341073036 --11.4990787506,0.687708556652,3.29901075363 --11.4890756607,0.686708927155,3.27580237389 --11.4980669022,0.686708629131,3.23839950562 --11.4910593033,0.684708833694,3.1969974041 --11.4840517044,0.683709025383,3.15559411049 --11.4910421371,0.68370872736,3.1181948185 --11.4760360718,0.681709170341,3.07478904724 --11.4830265045,0.681708812714,3.03637838364 --11.4890213013,0.68170851469,3.01918745041 --11.4690160751,0.678709149361,2.9737701416 --11.4630079269,0.67770922184,2.93336844444 --11.4689998627,0.677708804607,2.89596819878 --11.4749908447,0.67770832777,2.85856795311 --11.4709835052,0.676708161831,2.81815934181 --11.4639797211,0.675708353519,2.79695606232 --11.4689712524,0.674707889557,2.75955677032 --11.4489650726,0.672708451748,2.71615028381 --11.4249610901,0.670709133148,2.67174005508 --11.4169530869,0.668709218502,2.63133502007 --11.4509429932,0.6707072258,2.60094380379 --11.4919309616,0.673704862595,2.57256031036 --11.5259237289,0.675702989101,2.56036281586 --11.54991436,0.676701247692,2.52797651291 --11.5889034271,0.679698765278,2.49859237671 --11.6268920898,0.681696116924,2.46820235252 --11.5788888931,0.676697909832,2.41878175735 --11.5298862457,0.672699809074,2.36935901642 --11.7448577881,0.687687158585,2.35783958435 --11.7658491135,0.689685046673,2.32344698906 --11.8038387299,0.691681981087,2.29205727577 --11.8388290405,0.693678855896,2.25966405869 --11.8618202209,0.694676399231,2.22527265549 --11.8788127899,0.695674240589,2.18988132477 --11.8958053589,0.695672035217,2.1534807682 --11.9267997742,0.697669565678,2.1402964592 --11.9967880249,0.702663958073,2.11391854286 --12.0317792892,0.704660356045,2.08052587509 --12.0657711029,0.706656754017,2.04713654518 --12.1047611237,0.709652662277,2.01475214958 --12.1307535172,0.710649430752,1.98036766052 --12.1687459946,0.712645232677,1.94697844982 --12.205739975,0.715641915798,1.93278598785 --12.2417325974,0.717637658119,1.89940321445 --12.1397333145,0.709642767906,1.8429633379 --11.7897510529,0.682665288448,1.74641573429 --12.2847137451,0.719628989697,1.78621244431 --12.3777017593,0.72562032938,1.76085054874 --12.3197031021,0.721623420715,1.73162376881 --11.5817432404,0.665674984455,1.58092391491 --12.4766845703,0.732607603073,1.67488646507 --12.4686803818,0.731605947018,1.63348352909 --12.6486654282,0.744589924812,1.61815357208 --11.6007184982,0.665667712688,1.43332231045 --12.7166528702,0.748579502106,1.54537808895 --12.755645752,0.750573694706,1.50898885727 --12.7906417847,0.753569543362,1.49280142784 --12.8346366882,0.756563186646,1.45742154121 --12.8616313934,0.757558047771,1.41902840137 --12.908624649,0.760551273823,1.38365089893 --12.9366197586,0.762545824051,1.34526026249 --12.9856147766,0.765538573265,1.30887651443 --11.6076717377,0.663652837276,1.11590397358 --11.498673439,0.655661225319,1.084649086 --13.0736026764,0.771522760391,1.21391093731 --13.1435976028,0.77651321888,1.17954349518 --13.247590065,0.783500373363,1.14718174934 --11.474653244,0.652656137943,0.935033023357 --13.267583847,0.784491240978,1.0643903017 --13.2995815277,0.786486446857,1.04620468616 --13.3525772095,0.790477752686,1.00883114338 --13.3905735016,0.793470323086,0.969447255135 --13.4215707779,0.795463323593,0.929058432579 --13.4625673294,0.797455310822,0.88866853714 --13.4955644608,0.800447881222,0.848282754421 --13.540561676,0.803439319134,0.808905482292 --13.6955575943,0.814421832561,0.797768115997 --13.6225576401,0.808424592018,0.749337136745 --12.3045854568,0.711552500725,0.621364712715 --12.2985830307,0.710550010204,0.581962287426 --12.5445747375,0.728521645069,0.556663691998 --13.7975482941,0.821388304234,0.585814833641 --12.3135738373,0.711538791656,0.464758574963 --13.039560318,0.764460802078,0.481879323721 --13.9285449982,0.830362141132,0.481868028641 --13.9745435715,0.833352029324,0.439486950636 --12.1385660172,0.697546064854,0.320272982121 --12.588558197,0.731493532658,0.299074500799 --12.1915588379,0.701533734798,0.245498582721 --12.1885566711,0.701530635357,0.206089392304 --12.1295557022,0.696535587311,0.184861332178 --12.1825523376,0.700526177883,0.147480294108 --12.1595497131,0.698525369167,0.109076924622 --12.1865472794,0.700518727303,0.0706836879253 --12.1975450516,0.701513886452,0.0322878696024 --12.1875429153,0.700511455536,-0.00712405238301 --12.2065410614,0.702505528927,-0.0455165877938 --12.218539238,0.703502237797,-0.0647114366293 --12.2045373917,0.702500104904,-0.104125224054 --12.1955356598,0.701497495174,-0.142527267337 --12.1815338135,0.700495421886,-0.180932313204 --12.1415309906,0.697496533394,-0.219351068139 --12.1415290833,0.697492659092,-0.258762061596 --12.1355266571,0.696489572525,-0.297165691853 --12.0995254517,0.694492220879,-0.31537643075 --12.1045236588,0.694487571716,-0.354785680771 --12.1245231628,0.696481108665,-0.393174529076 --12.1355209351,0.697475671768,-0.431568026543 --12.1485204697,0.698469817638,-0.470969796181 --12.2155199051,0.703456819057,-0.511340796947 --12.1765184402,0.70045787096,-0.548758387566 --12.1725168228,0.700456261635,-0.567961096764 --12.1745166779,0.700451672077,-0.607368886471 --12.1735153198,0.700447499752,-0.645768642426 --12.1785144806,0.700442552567,-0.684162855148 --12.1705131531,0.700439214706,-0.7225689888 --12.1725120544,0.700434446335,-0.761976242065 --12.1725111008,0.700429975986,-0.800374746323 --12.1855115891,0.701425790787,-0.820571243763 --12.2275123596,0.705415189266,-0.861956655979 --14.4335975647,0.868091464043,-1.02931201458 --14.5146036148,0.874072372913,-1.07966864109 --14.3926029205,0.865082740784,-1.11812829971 --14.0695915222,0.841123104095,-1.14268839359 --14.1575975418,0.848106503487,-1.17084336281 --14.1486005783,0.847100555897,-1.21524739265 --14.1666049957,0.849090576172,-1.26163864136 --14.2396116257,0.85507196188,-1.31300771236 --14.1046085358,0.845085203648,-1.34747385979 --14.4846324921,0.873018920422,-1.42468869686 --14.2536239624,0.857047080994,-1.45019805431 --14.1386194229,0.848061203957,-1.46346116066 --14.0976209641,0.845060229301,-1.5038728714 --14.0496225357,0.842060089111,-1.54530513287 --14.0706281662,0.844049274921,-1.59168946743 --14.0786323547,0.845040142536,-1.6380906105 --14.0656356812,0.844034612179,-1.68149447441 --14.2796545029,0.860991597176,-1.74978899956 --14.1936511993,0.854001760483,-1.76302981377 --14.1866540909,0.853994786739,-1.80843925476 --14.3576717377,0.866958022118,-1.87375319004 --14.2416687012,0.858969211578,-1.90621292591 --14.457690239,0.875924170017,-1.97850513458 --14.6047067642,0.886890232563,-2.0438337326 --16.2168388367,1.00660276413,-2.2994248867 --16.4278621674,1.02256059647,-2.35352039337 --15.9758348465,0.989628314972,-2.34514164925 --16.0978527069,0.998596012592,-2.41347908974 --16.0728607178,0.997589349747,-2.46189022064 --16.1528778076,1.00456392765,-2.52524805069 --16.1338844299,1.00355613232,-2.57465600967 --16.1618976593,1.00553941727,-2.6320476532 --16.0648937225,0.998551428318,-2.64329481125 --16.2899227142,1.01649880409,-2.73058152199 --16.2169265747,1.011500597,-2.77101063728 --16.1889343262,1.00949406624,-2.81942534447 --16.190946579,1.01048183441,-2.87282681465 --16.5109882355,1.03540968895,-2.97905921936 --16.5590057373,1.03938806057,-3.04143571854 --14.8408308029,0.911709785461,-2.77051115036 --14.6868219376,0.900729179382,-2.79199123383 --14.3547945023,0.876783370972,-2.78056311607 --14.3428001404,0.875775933266,-2.82597446442 --14.4368181229,0.883747756481,-2.89032554626 --14.6148471832,0.897702813148,-2.97062802315 --14.3868293762,0.881737887859,-2.97514939308 --14.8208847046,0.913646221161,-3.08312559128 --13.9897937775,0.852802634239,-2.96795678139 --14.0318059921,0.856784582138,-3.02233457565 --13.7907838821,0.838824033737,-3.01986336708 --13.7037801743,0.832832455635,-3.04730892181 --14.9439468384,0.926566958427,-3.353058815 --14.7329282761,0.911599636078,-3.35757017136 --13.6007852554,0.826830506325,-3.13836312294 --13.7048063278,0.835799217224,-3.20671439171 --14.2618894577,0.877671718597,-3.3758225441 --13.6998214722,0.836781024933,-3.29651689529 --13.5028009415,0.822813570499,-3.29702043533 --13.5638179779,0.827790856361,-3.35639071465 --13.4708080292,0.820806145668,-3.35764288902 --13.3587999344,0.812820971012,-3.37610220909 --13.3268032074,0.811818480492,-3.41352415085 --13.3438129425,0.813805282116,-3.46191215515 --13.3478212357,0.814794838428,-3.50730752945 --13.3428287506,0.81478613615,-3.5517179966 --13.3638401031,0.817771613598,-3.6021091938 --13.309835434,0.813779056072,-3.61033391953 --13.2758388519,0.811776936054,-3.64675545692 --13.2918491364,0.813763320446,-3.69615101814 --13.1558361053,0.80478489399,-3.70462059975 --13.1738471985,0.806770980358,-3.75401139259 --13.1858577728,0.80875813961,-3.8024096489 --13.4249076843,0.827691793442,-3.91368746758 --13.3999071121,0.825692713261,-3.92889475822 --13.3879137039,0.825685083866,-3.97130298615 --13.3339138031,0.822687506676,-4.00173330307 --13.3509263992,0.824672758579,-4.05313253403 --13.261920929,0.818683803082,-4.0725774765 --13.3269414902,0.824657261372,-4.13794946671 --13.36195755,0.828637897968,-4.19433259964 --13.5039949417,0.84059214592,-4.28265190125 --13.5060005188,0.841585993767,-4.30685377121 --13.6740436554,0.855532884598,-4.40516424179 --13.4970197678,0.842565774918,-4.39766120911 --13.5770463943,0.849534153938,-4.47002220154 --13.6280679703,0.854509592056,-4.53339576721 --13.6960935593,0.860480487347,-4.6027598381 --13.8451290131,0.872436523438,-4.67387247086 --13.8461418152,0.874423861504,-4.72327804565 --16.6317310333,1.09068846703,-5.68612623215 --16.4437103271,1.07772052288,-5.6826338768 --16.4527320862,1.07970166206,-5.74302434921 --16.4097423553,1.07769620419,-5.78644800186 --16.5027809143,1.08565437794,-5.87679815292 --16.3377552032,1.07368993759,-5.8490896225 --16.5448207855,1.09161758423,-5.97836828232 --16.9309272766,1.12249600887,-6.17254829407 --17.1379947662,1.14042139053,-6.30683326721 --20.2097187042,1.38156235218,-7.46747922897 --20.1397342682,1.3775575161,-7.51491785049 --20.2837963104,1.39049386978,-7.63922834396 --20.088766098,1.37653625011,-7.60353565216 --19.992773056,1.37053906918,-7.63998556137 --20.065820694,1.3784942627,-7.7403459549 --19.9068145752,1.36751532555,-7.75182819366 --19.8568325043,1.36550533772,-7.80525588989 --19.9108772278,1.3714659214,-7.89761829376 --19.8408908844,1.36746156216,-7.94305610657 --19.9449310303,1.37741911411,-8.02019691467 --19.9509658813,1.37939298153,-8.0945854187 --20.3961105347,1.41623795033,-8.34472370148 --20.2771148682,1.40924739838,-8.37118625641 --20.3641700745,1.41819572449,-8.48153400421 --20.3862094879,1.42216348648,-8.56491374969 --20.3412342072,1.42015051842,-8.62233924866 --19.0509033203,1.31852519512,-8.12528896332 --18.8638820648,1.3055576086,-8.11779499054 --18.9059238434,1.31152129173,-8.20516490936 --18.8149299622,1.30552518368,-8.23661327362 --18.8629760742,1.3114862442,-8.32798576355 --18.9690361023,1.32242929935,-8.44431781769 --18.7400016785,1.30547583103,-8.41585159302 --18.8460502625,1.31543052197,-8.49798965454 --18.5569992065,1.29449665546,-8.44155883789 --18.6250495911,1.30145096779,-8.54191493988 --18.341999054,1.28151643276,-8.48548030853 --18.419052124,1.28946781158,-8.58983039856 --18.3510627747,1.286465168,-8.62926959991 --18.2160549164,1.27748453617,-8.63674449921 --18.4061279297,1.29341077805,-8.75983047485 --18.4221668243,1.29738080502,-8.83821964264 --18.4302005768,1.30035328865,-8.91261100769 --18.5002555847,1.3083050251,-9.01696491241 --18.470281601,1.30728971958,-9.07438087463 --18.4913215637,1.31125700474,-9.15676879883 --21.1992321014,1.53532218933,-10.5445356369 --18.6464233398,1.32816624641,-9.34026908875 --18.6644649506,1.33113372326,-9.42265796661 --21.4754314423,1.5641503334,-10.8883514404 --21.366437912,1.55815541744,-10.9188137054 --21.3174667358,1.55614030361,-10.9782371521 --21.5445899963,1.57802927494,-11.1784973145 --21.3365631104,1.56406879425,-11.1580200195 --21.5536613464,1.58297657967,-11.312084198 --21.5507049561,1.58594453335,-11.3964805603 --21.4817295074,1.58293557167,-11.4469175339 --21.8439044952,1.61577355862,-11.7230882645 --21.8189430237,1.61674797535,-11.7985010147 --21.7839794159,1.61672616005,-11.8679151535 --23.1324920654,1.73022246361,-12.6342840195 --22.9264678955,1.71625983715,-12.6168031693 --21.5680198669,1.60671806335,-11.972035408 --21.9402084351,1.6405466795,-12.2642002106 --21.8452224731,1.63554620743,-12.3016519547 --21.6251926422,1.62059175968,-12.2701864243 --21.6352462769,1.62455296516,-12.3645715714 --35.5546150208,2.79732561111,-20.2320995331 --35.3636360168,2.78633213043,-20.2716007233 --35.1406478882,2.77335119247,-20.2921237946 --35.0327033997,2.76932740211,-20.3765735626 --34.8977470398,2.76331400871,-20.4450397491 --34.8008041382,2.76028585434,-20.535484314 --34.681854248,2.75526642799,-20.6129417419 --34.5898666382,2.75026941299,-20.6321926117 --34.482925415,2.74724555016,-20.7156429291 --34.356967926,2.74122881889,-20.7881069183 --34.2600250244,2.73920154572,-20.8765525818 --34.2311134338,2.74214720726,-21.0059528351 --34.3372612,2.75603795052,-21.2192707062 --34.3433609009,2.76296901703,-21.3706493378 --34.0843009949,2.743039608,-21.2860069275 --33.7942771912,2.72408986092,-21.2545757294 --33.7553634644,2.72603917122,-21.3779850006 --33.6924362183,2.7259979248,-21.4864082336 --33.4974517822,2.71501088142,-21.5109176636 --33.364490509,2.7089984417,-21.5753898621 --33.1935195923,2.70000267029,-21.6128826141 --33.0845184326,2.69401431084,-21.6171474457 --33.0576095581,2.69695830345,-21.747549057 --33.0517082214,2.70289349556,-21.8919372559 --32.8477172852,2.69091248512,-21.9054508209 --32.7627830505,2.68888044357,-21.9988937378 --32.6778411865,2.6878490448,-22.0903320312 --32.5258789062,2.67984628677,-22.1378192902 --32.4288825989,2.67485380173,-22.1470737457 --32.3209342957,2.67083263397,-22.222530365 --32.1759681702,2.66382789612,-22.2720088959 --31.9949836731,2.65383911133,-22.2965126038 --31.8960399628,2.65181422234,-22.3769645691 --31.7870903015,2.64779376984,-22.450422287 --31.7521781921,2.65074062347,-22.5748310089 --31.7082099915,2.6507256031,-22.619052887 --31.487203598,2.63675642014,-22.6115837097 --31.4803066254,2.64269042015,-22.7559757233 --31.4013729095,2.64165663719,-22.8494129181 --31.2474002838,2.63365745544,-22.8889045715 --31.1024303436,2.6276550293,-22.9323825836 --30.9864788055,2.62363886833,-22.9978485107 --30.8794765472,2.61665320396,-22.9951133728 --30.6364536285,2.60069727898,-22.9646587372 --30.5545158386,2.59966611862,-23.0531005859 --30.4235553741,2.59465765953,-23.1055774689 --30.4026508331,2.59959745407,-23.2399787903 --30.3447284698,2.60055470467,-23.3464050293 --30.2277736664,2.59654021263,-23.4078712463 --30.1297740936,2.5905520916,-23.4081287384 --29.9627895355,2.58156228065,-23.4296264648 --29.7607860565,2.56958937645,-23.4241504669 --29.7138690948,2.5725414753,-23.5385723114 --29.5789012909,2.56653690338,-23.5830497742 --29.4319286346,2.55953812599,-23.6185398102 --29.4329833984,2.56250214577,-23.694732666 --29.3840675354,2.56545495987,-23.8071537018 --29.2891235352,2.56343054771,-23.8836097717 --29.1441497803,2.55643177032,-23.918094635 --29.1002349854,2.55938148499,-24.0355148315 --29.0563240051,2.56233143806,-24.15193367 --28.9493732452,2.55931329727,-24.2173938751 --28.8353595734,2.55233597755,-24.1986637115 --28.7954483032,2.55528354645,-24.3190822601 --28.7105121613,2.55425429344,-24.4025287628 --28.7106266022,2.56118059158,-24.5569190979 --28.6036758423,2.55816197395,-24.6223831177 --28.4056663513,2.54719305038,-24.6079063416 --28.332736969,2.54715752602,-24.700345993 --28.2897701263,2.54714298248,-24.7415714264 --28.1888217926,2.54412269592,-24.8090305328 --28.0888748169,2.54210114479,-24.878490448 --27.9949321747,2.54007697105,-24.9529457092 --27.9650306702,2.54501771927,-25.0833568573 --27.8730888367,2.5439927578,-25.1578083038 --27.7941570282,2.54395961761,-25.2462558746 --27.7211685181,2.5399620533,-25.2595005035 --27.6232223511,2.53794002533,-25.3289585114 --27.5162715912,2.53592300415,-25.390422821 --27.4083194733,2.53290653229,-25.4508914948 --27.3263835907,2.53187608719,-25.5343360901 --27.1944141388,2.52687382698,-25.5718212128 --27.0814571381,2.52386069298,-25.626291275 --26.9924564362,2.5188729763,-25.6225471497 --26.9835739136,2.52580046654,-25.7739448547 --26.8105735779,2.51582217216,-25.7714576721 --26.7296409607,2.51579117775,-25.8549060822 --26.7177581787,2.52271914482,-26.0053062439 --24.158000946,2.27015471458,-23.6884727478 --24.0610408783,2.26714134216,-23.7409324646 --24.0050582886,2.26613879204,-23.7611732483 --23.9090995789,2.26312494278,-23.8146324158 --23.820148468,2.26210618019,-23.8760929108 --23.7942409515,2.26705002785,-23.9985027313 --23.6064472198,2.27094626427,-24.2608222961 --23.4834098816,2.26198554039,-24.2111053467 --23.4124698639,2.2619562149,-24.2895507812 --23.2314453125,2.2509958744,-24.2540721893 --23.1826438904,2.26187872887,-24.5068969727 --23.1036987305,2.26085400581,-24.5773506165 --23.0237541199,2.26083040237,-24.6458015442 --23.0027980804,2.26280593872,-24.7010154724 --22.9268550873,2.2627799511,-24.7734622955 --22.8399066925,2.26175999641,-24.8359241486 --22.7819786072,2.26372170448,-24.928358078 --22.703037262,2.26369667053,-24.9988117218 --22.597070694,2.26068973541,-25.0392837524 --20.4916706085,2.05883860588,-23.2371692657 --20.405708313,2.0568253994,-23.2866287231 --20.3367614746,2.05780124664,-23.3540744781 --20.2718219757,2.05877399445,-23.427520752 --20.2778835297,2.06273388863,-23.5077152252 --20.2709941864,2.07066583633,-23.6481208801 --20.0280094147,2.05968928337,-23.6640930176 --19.9650707245,2.06066012383,-23.7395381927 --18.805109024,1.93741035461,-22.5187644958 --18.3978366852,1.89963197708,-22.1764564514 --18.1206874847,1.87576282024,-21.9850540161 --17.8835144043,1.85189950466,-21.7704257965 --17.6854343414,1.83697605133,-21.6689682007 --17.6224822998,1.83795487881,-21.7304172516 --17.5665378571,1.83892810345,-21.8008594513 --17.4995822906,1.83891022205,-21.8563079834 --17.459651947,1.84187209606,-21.9457378387 --17.4186649323,1.84086823463,-21.9649677277 --17.5018596649,1.8587372303,-22.2093086243 --17.3978691101,1.85474586487,-22.2207889557 --17.3419265747,1.85671889782,-22.291229248 --17.2159118652,1.84974479675,-22.2737216949 --17.1769866943,1.85370409489,-22.3671531677 --17.2621898651,1.87156784534,-22.6204910278 --16.0619983673,1.7324616909,-21.1375656128 --15.7788085938,1.70561659336,-20.903169632 --15.4936151505,1.6787737608,-20.6647834778 --15.2926111221,1.66980302334,-20.6647338867 --15.2076263428,1.66780543327,-20.6852016449 --15.1266450882,1.66580462456,-20.7106647491 --15.0886573792,1.66480231285,-20.726896286 --15.0317020416,1.66578257084,-20.7843399048 --14.9707422256,1.66576623917,-20.8357868195 --14.908782959,1.66675007343,-20.8872375488 --14.8558330536,1.66772675514,-20.9506797791 --14.7918710709,1.66771233082,-20.9991321564 --14.7419242859,1.66968643665,-21.0665721893 --14.7319688797,1.67266130447,-21.1207771301 --14.6229553223,1.66668426991,-21.1062660217 --12.0270271301,1.34382462502,-17.5295658112 --11.8449020386,1.3269251585,-17.3831043243 --11.6958150864,1.31499838829,-17.282623291 --11.5917806625,1.30803346634,-17.2461071014 --11.5428104401,1.30902123451,-17.2895507812 --11.3547153473,1.29410421848,-17.183298111 --11.3017416,1.29409599304,-17.219745636 --11.2497673035,1.29508709908,-17.2571907043 --11.199795723,1.29507637024,-17.2976341248 --11.1538276672,1.29606246948,-17.3430690765 --11.1278409958,1.29605770111,-17.3622951508 --11.0758695602,1.29604780674,-17.4017467499 --11.0309047699,1.29703235626,-17.4501857758 --10.9809331894,1.29802191257,-17.4896259308 --10.9269580841,1.29801416397,-17.5250759125 --10.888001442,1.29999279976,-17.5835113525 --10.8290195465,1.2989897728,-17.6109638214 --10.7780485153,1.29997956753,-17.6504096985 --10.7610740662,1.30096578598,-17.684627533 --10.7131071091,1.30195260048,-17.7290706635 --10.6661405563,1.30293869972,-17.7745094299 --10.6151714325,1.30392742157,-17.8159599304 --10.564201355,1.30391657352,-17.8564052582 --10.518237114,1.30590105057,-17.9048480988 --10.4972581863,1.30689144135,-17.9320659637 --10.4482917786,1.3078776598,-17.9775161743 --10.4023284912,1.30886209011,-18.0259571075 --10.3513593674,1.30985069275,-18.0674057007 --10.2993879318,1.30984091759,-18.1058483124 --10.2524242401,1.31082522869,-18.1542930603 --10.2014560699,1.31181383133,-18.1957416534 --10.1784753799,1.31280505657,-18.2219676971 --10.1395254135,1.31578099728,-18.2844028473 --10.0805454254,1.31477737427,-18.3128604889 --10.0345830917,1.31676101685,-18.3623008728 --9.98561763763,1.31774711609,-18.4077453613 --9.93665504456,1.31873214245,-18.4551944733 --9.88568687439,1.31972014904,-18.4976425171 --9.86971759796,1.32170403004,-18.5358581543 --9.83377552032,1.32467544079,-18.6062927246 --9.7707901001,1.32367515564,-18.6287555695 --9.72282886505,1.32565951347,-18.67719841 --9.6738653183,1.32664453983,-18.724647522 --9.63091278076,1.32962298393,-18.7830886841 --9.57694149017,1.32961368561,-18.8205356598 --9.55797195435,1.33159840107,-18.8577632904 --9.51201438904,1.33357977867,-18.9112052917 --9.46806144714,1.33555829525,-18.9696483612 --9.4140920639,1.33654797077,-19.0090999603 --9.36613273621,1.3385310173,-19.059545517 --9.32218170166,1.34050858021,-19.1199913025 --9.30120754242,1.34249651432,-19.1512107849 --9.26226520538,1.34546804428,-19.2216510773 --9.21831703186,1.3484442234,-19.2840995789 --9.17937660217,1.35141456127,-19.3565406799 --9.21056270599,1.36729979515,-19.5739250183 --5.47195482254,0.748768985271,-11.9987230301 --5.4479842186,0.750754237175,-12.0441570282 --13.5073204041,2.16448044777,-29.6085186005 --13.3231887817,2.1485877037,-29.4490680695 --13.1991710663,2.14261865616,-29.4205760956 --13.4328479767,2.20118522644,-30.1848087311 --13.2026224136,2.17635464668,-29.9193916321 --13.2127590179,2.18627381325,-30.0695934296 --13.2851333618,2.21704435349,-30.4859466553 --13.0418787003,2.18923282623,-30.1875419617 --12.9599485397,2.19220590591,-30.2580223083 --12.9611873627,2.20906710625,-30.5194301605 --12.8101148605,2.19913458824,-30.4279556274 --12.7101478577,2.19813227654,-30.456445694 --12.6451320648,2.19415259361,-30.4337005615 --9.06694030762,1.54492795467,-22.3052577972 --12.4825267792,2.21795153618,-30.850063324 --12.4537162781,2.23084640503,-31.0544986725 --12.2425069809,2.20800375938,-30.8090744019 --12.1645898819,2.21196961403,-30.8915462494 --9.6681060791,1.72556900978,-24.7346611023 --9.52498531342,1.71266329288,-24.5961856842 --9.41693973541,1.70570755005,-24.5426769257 --9.32593536377,1.70272529125,-24.5351638794 --9.25597763062,1.7037127018,-24.5796298981 --9.20105648041,1.70867609978,-24.6650867462 --7.89714670181,1.45258104801,-21.4184913635 --7.81704521179,1.44265329838,-21.3057594299 --7.72600460052,1.43769192696,-21.2612419128 --7.66203117371,1.43768715858,-21.2917079926 --11.0997629166,2.19005441666,-30.9875068665 --11.0098199844,2.19203805923,-31.0399913788 --7.41897821426,1.42775857449,-21.2351360321 --7.33987045288,1.41783416271,-21.1164054871 --7.82330846786,1.53892076015,-22.7084560394 --7.21492433548,1.41882383823,-21.1783294678 --7.52794647217,1.50418019295,-22.307516098 --7.2303571701,1.45257115364,-21.6571559906 --7.14432621002,1.44760358334,-21.6236362457 --7.07934951782,1.44760096073,-21.650100708 --7.08647155762,1.45752954483,-21.7843036652 --9.99277019501,2.15724754333,-30.8975200653 --9.87975883484,2.15327429771,-30.8760223389 --9.72162151337,2.13838171959,-30.7155647278 --9.612616539,2.13440394402,-30.7010631561 --6.59512138367,1.41981565952,-21.402759552 --6.53515863419,1.4218044281,-21.4442253113 --6.50317144394,1.42180263996,-21.4584579468 --6.38202571869,1.40790760517,-21.2999668121 --6.31102609634,1.40691959858,-21.3014354706 --6.35739135742,1.43570160866,-21.6998233795 --6.28940629959,1.43470489979,-21.7162914276 --6.24248695374,1.4406671524,-21.8037433624 --6.12233686447,1.42677426338,-21.6412525177 --6.13850736618,1.43967354298,-21.8264560699 --6.13172149658,1.45555186272,-22.0588779449 --8.40951061249,2.09368538857,-30.4835929871 --8.30952548981,2.09269523621,-30.4910907745 --8.16137886047,2.07780623436,-30.3236274719 --8.08446884155,2.08276987076,-30.4111042023 --5.70263195038,1.44068002701,-21.9615077972 --5.64267587662,1.44266557693,-22.0089702606 --5.57368993759,1.44266974926,-22.0244445801 --5.49165534973,1.43870460987,-21.9869270325 --5.41363334656,1.43573117256,-21.9634037018 --5.36371660233,1.44069254398,-22.05286026 --5.29071617126,1.43970608711,-22.0523414612 --5.28483343124,1.4476402998,-22.1775569916 --5.24094343185,1.45558547974,-22.2950077057 --5.22717857361,1.47345411777,-22.5454406738 --5.18430376053,1.48239088058,-22.6778964996 --5.12837696075,1.48635935783,-22.7553577423 --5.04634332657,1.4823936224,-22.7188396454 --5.04449510574,1.49430811405,-22.8790588379 --5.00463914871,1.50423336029,-23.0315074921 --4.98688650131,1.52209591866,-23.2929439545 --4.91892337799,1.52408778667,-23.3304214478 --4.84191799164,1.5221054554,-23.3229026794 --4.78600645065,1.52806556225,-23.4153652191 --4.75320911407,1.54295682907,-23.6278190613 --4.66013050079,1.53501904011,-23.5433120728 --4.62916088104,1.53700757027,-23.5745429993 --4.58129882812,1.54693853855,-23.718006134 --5.67506933212,1.99745810032,-29.7876701355 --5.59917545319,2.00441336632,-29.8901500702 --5.48408317566,1.99448800087,-29.7856616974 --5.37602806091,1.98854076862,-29.7191696167 --5.35014438629,1.99647986889,-29.8374023438 --5.22499656677,1.98358857632,-29.6739234924 --5.12598276138,1.98061597347,-29.651424408 --5.01389122009,1.97168982029,-29.5479335785 --4.90984678268,1.96673583984,-29.4934406281 --4.81887292862,1.9667391777,-29.5129375458 --4.71884489059,1.96277534962,-29.4754390717 --4.67586898804,1.96377027035,-29.4966831207 --4.59092903137,1.96675360203,-29.5511741638 --4.48788404465,1.96179974079,-29.4966831207 --4.39489221573,1.96081399918,-29.4971790314 --4.30391931534,1.96081709862,-29.5176773071 --4.21193265915,1.96082854271,-29.5231723785 --2.37601852417,1.04791510105,-17.1867446899 --2.22213029861,0.980446636677,-16.2700405121 --2.15803599358,0.972511947155,-16.1785144806 --2.09292411804,0.964587330818,-16.068983078 --1.99657082558,0.937805175781,-15.7104635239 --1.97578036785,0.953690588474,-15.9329080582 --1.89150369167,0.931862711906,-15.6543865204 --1.85459041595,0.938820719719,-15.7498369217 --1.83765184879,0.943789303303,-15.8160657883 --1.79469573498,0.946772515774,-15.8675203323 --1.75074100494,0.950755417347,-15.9199829102 --1.70778715611,0.95373749733,-15.9734334946 --1.66081190109,0.955732524395,-16.0048980713 --1.61483490467,0.957728385925,-16.0343532562 --1.56785571575,0.958725571632,-16.0618114471 --1.54587864876,0.960716962814,-16.0880374908 --1.4989105463,0.963708102703,-16.1265048981 --2.62648963928,1.90440642834,-28.943447113 --2.50920438766,1.88159143925,-28.6459636688 --2.40503764153,1.86870706081,-28.4694671631 --2.29276585579,1.84688341618,-28.1869735718 --2.2179312706,1.85780632496,-28.3484649658 --2.17595744133,1.85980069637,-28.371711731 --2.08898544312,1.86080360413,-28.3932094574 --1.99593508244,1.85585165024,-28.3357124329 --1.90591955185,1.85387969017,-28.3132133484 --1.82198309898,1.85786211491,-28.3707084656 --1.72687506676,1.84894323349,-28.2552089691 --1.62158119678,1.82613062859,-27.952709198 --1.57656872272,1.82514727116,-27.9369621277 --1.482432127,1.81424427032,-27.7934570312 --1.39339578152,1.8102837801,-27.7509593964 --1.30536055565,1.80732262135,-27.7094573975 --1.21218824387,1.79343938828,-27.5309486389 --1.12823951244,1.79642903805,-27.5764484406 --1.07907688618,1.78453075886,-27.410697937 --0.99203312397,1.78057444096,-27.3611946106 --0.897760987282,1.75974726677,-27.083688736 --0.807537317276,1.74289226532,-26.8551769257 --0.721427798271,1.73497259617,-26.7406711578 --0.634268522263,1.72208082676,-26.5771656036 --0.553317964077,1.72507095337,-26.6216583252 --0.509154856205,1.71317207813,-26.4569015503 --0.428234696388,1.719145298,-26.5314006805 --0.344055503607,1.7052642107,-26.3488903046 --0.262112170458,1.70925068855,-26.400390625 --0.181170836091,1.71323597431,-26.4538879395 --0.0989808663726,1.69836032391,-26.2613735199 --0.0180042553693,1.70036554337,-26.2798671722 -0.0328684560955,1.69953978062,-25.3141403198 -0.112841270864,1.6975029707,-25.2924728394 -0.193838343024,1.69747960567,-25.2948093414 -0.302945315838,1.63195109367,-24.4163570404 -0.387307703495,1.65913116932,-24.7806758881 -0.463161706924,1.6490291357,-24.6400184631 -0.501064062119,1.64196443558,-24.5451965332 -0.572820186615,1.6248087883,-24.3065452576 -0.645648658276,1.61169350147,-24.1398944855 -0.723639011383,1.61166727543,-24.1342391968 -0.800634264946,1.61164426804,-24.1335773468 -0.877636730671,1.61262512207,-24.1399154663 -0.951542019844,1.60555255413,-24.0492630005 -0.987491488457,1.6025146246,-24.0004348755 -1.06345891953,1.60047650337,-23.971780777 -1.14046537876,1.6014598608,-23.9821205139 -1.21643924713,1.60042500496,-23.9594631195 -1.29446339607,1.60241806507,-23.9878005981 -1.14763712883,1.31631362438,-20.1404895782 -1.21060287952,1.31427741051,-20.1058483124 -1.2446436882,1.31729137897,-20.1470165253 -1.31471955776,1.32331526279,-20.2233638763 -1.37768006325,1.32027649879,-20.1837215424 -1.43052423,1.3091750145,-20.0260887146 -1.49146747589,1.30512714386,-19.9684524536 -1.55851256847,1.30913460255,-20.0137958527 -1.59455907345,1.31215131283,-20.0609664917 -1.66461777687,1.31716573238,-20.1203155518 -1.73569297791,1.32318937778,-20.1966590881 -1.80776619911,1.32921147346,-20.2710056305 -1.88286972046,1.33724987507,-20.3763446808 -1.95493078232,1.34226536751,-20.4386920929 -2.11586833,1.41474938393,-21.3949203491 -2.15087080002,1.41474175453,-21.3980979919 -2.21481800079,1.41169559956,-21.3454551697 -2.27877640724,1.40865564346,-21.3038101196 -2.34172391891,1.40561008453,-21.25116539 -2.40466928482,1.40156340599,-21.1965274811 -2.46963953972,1.39952993393,-21.1668815613 -2.53259134293,1.39648675919,-21.1182403564 -2.75510168076,1.51327741146,-22.6701831818 -2.83212351799,1.51527035236,-22.6955280304 -2.90209364891,1.51423561573,-22.6668796539 -2.9771001339,1.51522040367,-22.6762256622 -3.04203510284,1.51116752625,-22.6115818024 -3.12308359146,1.51617431641,-22.6639232635 -3.19305419922,1.5141402483,-22.6362762451 -3.21495294571,1.50707781315,-22.5324668884 -3.284927845,1.50604617596,-22.5088195801 -3.36497116089,1.51005065441,-22.5561561584 -3.43394041061,1.50901603699,-22.5265083313 -3.50894141197,1.50999796391,-22.5298614502 -3.57489418983,1.50695502758,-22.4832172394 -3.66298007965,1.51498126984,-22.574546814 -3.71305656433,1.52101194859,-22.6557044983 -3.82627701759,1.53910756111,-22.888010025 -3.92440629005,1.5511559248,-23.0253314972 -4.01951122284,1.56019127369,-23.1376571655 -4.10455274582,1.56419372559,-23.1839981079 -4.17251014709,1.56215310097,-23.1423492432 -4.20749044418,1.56113374233,-23.1235256195 -4.31364250183,1.57419312,-23.2858409882 -4.41878223419,1.58724570274,-23.4351577759 -4.50582456589,1.59124851227,-23.4834976196 -4.59588670731,1.59726142883,-23.5518245697 -4.69498157501,1.60629057884,-23.6551513672 -4.79608535767,1.61632418633,-23.7674732208 -4.83709430695,1.61731934547,-23.7786426544 -4.91608905792,1.6182975769,-23.7769889832 -5.00513029099,1.62329936028,-23.8243236542 -5.09216451645,1.62729740143,-23.863658905 -5.17316579819,1.62927889824,-23.8690032959 -5.27224636078,1.63630056381,-23.9583282471 -5.37634325027,1.64632999897,-24.0646495819 -5.45048379898,1.65839111805,-24.2157878876 -5.53348970413,1.66037476063,-24.2261276245 -5.63356304169,1.66739225388,-24.3084526062 -5.73363208771,1.67540717125,-24.3857784271 -5.85076999664,1.68745684624,-24.5370826721 -5.95484876633,1.69547653198,-24.6254062653 -6.04185771942,1.69846129417,-24.6397476196 -6.09489965439,1.70247244835,-24.6869087219 -6.19496107101,1.7094835043,-24.7572288513 -6.28899240494,1.71347916126,-24.7955665588 -6.37299060822,1.71545851231,-24.7979068756 -6.44694900513,1.71441817284,-24.7582607269 -6.52391910553,1.71338355541,-24.7306118011 -6.60992002487,1.71536409855,-24.735956192 -6.64990949631,1.71534907818,-24.7271308899 -6.7298913002,1.71532070637,-24.7124786377 -6.814889431,1.7172999382,-24.7148208618 -6.89788007736,1.71827554703,-24.7091655731 -6.97585248947,1.71824204922,-24.6835193634 -7.06686687469,1.7212293148,-24.7038593292 -7.13982534409,1.72018945217,-24.6632137299 -7.17479848862,1.71916639805,-24.6363945007 -7.25578212738,1.71913921833,-24.6237411499 -7.33375358582,1.7191054821,-24.5970973969 -7.41172885895,1.71907377243,-24.5744457245 -7.48869895935,1.71903944016,-24.5458011627 -7.56466627121,1.71800422668,-24.5151557922 -7.61167621613,1.71999943256,-24.5283241272 -7.69165563583,1.71996963024,-24.5096759796 -7.76862764359,1.7199369669,-24.4840259552 -7.8516163826,1.72091162205,-24.4753742218 -7.93359947205,1.72188425064,-24.461725235 -8.01257705688,1.72285377979,-24.4410762787 -8.09255599976,1.7228243351,-24.4224262238 -8.13354873657,1.7238111496,-24.416601181 -8.21052074432,1.72377836704,-24.3899536133 -8.29350757599,1.72475254536,-24.3793029785 -8.38952827454,1.72874295712,-24.4066390991 -8.49958515167,1.73575007915,-24.4729633331 -8.6246805191,1.74677562714,-24.5822715759 -8.76381015778,1.75981771946,-24.7305622101 -8.87698459625,1.77689015865,-24.9256687164 -9.02512741089,1.79193747044,-25.0889568329 -9.17427158356,1.80698561668,-25.2542419434 -9.29534339905,1.81599915028,-25.338552475 -9.42543125153,1.82602000237,-25.4418621063 -9.53747653961,1.83302080631,-25.4971828461 -9.63348007202,1.83600199223,-25.506521225 -9.68749523163,1.83799910545,-25.5266857147 -9.7694683075,1.838966012,-25.501033783 -9.83439445496,1.83491146564,-25.425409317 -9.89531803131,1.8308557272,-25.3447761536 -9.97528266907,1.83081865311,-25.3101348877 -10.0512399673,1.82977867126,-25.2674942017 -10.1392240524,1.83175110817,-25.2548408508 -10.1792078018,1.83173346519,-25.2390193939 -10.2391300201,1.82767772675,-25.1573925018 -10.2950439453,1.82261753082,-25.0647716522 -10.3529634476,1.81856060028,-24.9791488647 -10.4209051132,1.8155144453,-24.9195156097 -10.5058860779,1.81648552418,-24.9018630981 -10.548874855,1.81747043133,-24.89204216 -10.6368598938,1.81944334507,-24.8793888092 -10.7158269882,1.81940841675,-24.8467464447 -10.8058137894,1.82138252258,-24.8370952606 -10.8877859116,1.82135009766,-24.8104496002 -10.9607391357,1.82030880451,-24.7618141174 -11.0316905975,1.81926703453,-24.7111759186 -11.0676660538,1.81824588776,-24.6853618622 -11.1446285248,1.81820881367,-24.6467227936 -11.2476425171,1.82219517231,-24.66705513 -11.3516559601,1.82718133926,-24.6873912811 -11.4586753845,1.8321698904,-24.7137241364 -11.5556755066,1.83514988422,-24.7180652618 -11.6616916656,1.84013712406,-24.7413959503 -11.6726207733,1.83509576321,-24.6626033783 -11.631362915,1.81396114826,-24.3710765839 -11.7433900833,1.81995379925,-24.4074039459 -11.858423233,1.82594883442,-24.4497280121 -11.9303770065,1.82490813732,-24.400094986 -11.87911129,1.8037712574,-24.097574234 -11.8428764343,1.78464901447,-23.8310394287 -11.8417892456,1.77760088444,-23.7322597504 -11.8776865005,1.77153670788,-23.6166572571 -11.9165887833,1.7654749155,-23.5070533752 -11.9414672852,1.75640273094,-23.3694648743 -11.9763669968,1.75033998489,-23.2558612823 -12.0142717361,1.74427974224,-23.1482582092 -12.0441637039,1.73721420765,-23.0256652832 -12.0370740891,1.73016619682,-22.9228858948 -12.079990387,1.72511100769,-22.8272781372 -12.1178998947,1.72005367279,-22.7246742249 -12.1538057327,1.71399402618,-22.6160774231 -12.1957235336,1.70894050598,-22.5224704742 -12.2406463623,1.70488929749,-22.4348602295 -12.2845687866,1.70083785057,-22.3462505341 -12.2975149155,1.69680583477,-22.2844581604 -12.3354301453,1.69175159931,-22.1868534088 -12.3843631744,1.68870425224,-22.1082420349 -12.4352989197,1.68565893173,-22.0346279144 -12.4882383347,1.68261528015,-21.965013504 -12.5301628113,1.67856550217,-21.8774051666 -12.5441150665,1.67553639412,-21.8216075897 -12.5930500031,1.6724909544,-21.7459964752 -12.6580076218,1.67145514488,-21.6973743439 -12.7099485397,1.66941249371,-21.6287593842 -12.7388563156,1.66335606575,-21.5201644897 -12.763759613,1.65729808807,-21.4065723419 -12.824716568,1.65626204014,-21.3549480438 -12.8536911011,1.65524303913,-21.3261413574 -12.8986244202,1.65219724178,-21.2465343475 -12.9475641251,1.6491549015,-21.1759223938 -12.9524440765,1.64008820057,-21.0333461761 -13.0154056549,1.6400539875,-20.9857254028 -13.0613422394,1.63701081276,-20.9111156464 -13.1202974319,1.63497495651,-20.8574962616 -13.1422662735,1.6339533329,-20.8196926117 -13.2102327347,1.63392221928,-20.7800674438 -13.2842082977,1.63489472866,-20.7504348755 -13.2880935669,1.62683081627,-20.6118602753 -13.3720827103,1.62880921364,-20.5992202759 -13.425031662,1.626770854,-20.5366077423 -13.4859924316,1.62673783302,-20.4889850616 -13.5229797363,1.62672424316,-20.4741687775 -13.5899467468,1.62669348717,-20.4335460663 -13.6479034424,1.62665891647,-20.3809242249 -13.7208786011,1.62763166428,-20.3502941132 -13.7858448029,1.62760055065,-20.3076705933 -13.8608217239,1.62857401371,-20.2790412903 -13.8948078156,1.6285598278,-20.261220932 -13.9567680359,1.62852668762,-20.2126045227 -14.0187301636,1.62749457359,-20.1659832001 -14.0967111588,1.6294696331,-20.1413516998 -14.1676845551,1.63044178486,-20.1077194214 -14.2246408463,1.62940740585,-20.0531044006 -14.3016204834,1.63138222694,-20.0274677277 -14.3666400909,1.63538110256,-20.0516300201 -14.4215946198,1.6343460083,-19.9940185547 -14.4995746613,1.63632071018,-19.9683837891 -14.5665426254,1.63629102707,-19.9277591705 -14.6525316238,1.63926935196,-19.9131202698 -14.7104892731,1.63823568821,-19.8595046997 -14.792473793,1.64121222496,-19.8388671875 -14.8334655762,1.6422008276,-19.8290500641 -14.911444664,1.64417505264,-19.8014183044 -14.9934301376,1.64615178108,-19.7807807922 -15.0744123459,1.64812779427,-19.7581443787 -15.1583976746,1.65110433102,-19.7375106812 -15.2343740463,1.65207850933,-19.7078781128 -15.3093509674,1.65405189991,-19.6762485504 -15.3593511581,1.65604329109,-19.6764240265 -15.4463386536,1.65902125835,-19.659784317 -15.5103034973,1.65899026394,-19.6131629944 -15.6093034744,1.66297256947,-19.6115150452 -15.6992931366,1.6669510603,-19.5968761444 -15.7672605515,1.66692137718,-19.5542526245 -15.8542976379,1.67392623425,-19.6003952026 -15.9202632904,1.67389559746,-19.554775238 -16.0102519989,1.67687380314,-19.5391368866 -16.1062488556,1.68085432053,-19.5314865112 -16.2002410889,1.68483376503,-19.5198440552 -16.2872257233,1.68781006336,-19.4982089996 -16.3762130737,1.69078731537,-19.4795703888 -16.4422264099,1.69478356838,-19.4967308044 -16.575252533,1.70277488232,-19.5290603638 -16.6582336426,1.70574986935,-19.5024242401 -16.6331138611,1.69568908215,-19.3468799591 -16.3937950134,1.66056036949,-18.9425086975 -16.4217281342,1.6575191021,-18.8539180756 -16.4296417236,1.65147185326,-18.7423439026 -16.4255924225,1.64744579792,-18.677564621 -16.4875564575,1.64741587639,-18.6289482117 -16.5234966278,1.64537799358,-18.5503540039 -16.5354175568,1.63933300972,-18.4447803497 -16.5813674927,1.63829863071,-18.3781776428 -16.6103038788,1.63525974751,-18.293586731 -16.6302337646,1.63021838665,-18.199005127 -16.6401977539,1.6281979084,-18.1522121429 -16.6861515045,1.62716472149,-18.0876064301 -16.7000751495,1.6221216917,-17.9860363007 -16.7230091095,1.61908268929,-17.8974456787 -16.7329330444,1.61303985119,-17.7938747406 -16.7118320465,1.60498917103,-17.658323288 -16.7317638397,1.60095012188,-17.5677394867 -16.7527389526,1.59993362427,-17.5339412689 -16.7666664124,1.5958930254,-17.4363670349 -16.7916069031,1.59285640717,-17.3527774811 -16.8275547028,1.58982264996,-17.2801818848 -16.8334789276,1.58478081226,-17.1756153107 -16.847410202,1.58074223995,-17.0820331573 -16.8913631439,1.57971072197,-17.0174350739 -16.8643054962,1.57368302345,-16.93567276 -16.8862419128,1.57064676285,-16.8500900269 -16.9201927185,1.56861388683,-16.7774963379 -16.9211158752,1.56257367134,-16.6729259491 -16.9560661316,1.56054127216,-16.6013336182 -16.9750041962,1.5575054884,-16.5147533417 -16.9689617157,1.55348408222,-16.4559764862 -16.9989109039,1.55145144463,-16.3813838959 -17.0398654938,1.55042135715,-16.3167877197 -17.0548038483,1.54638540745,-16.2272109985 -17.0837497711,1.54435300827,-16.1516227722 -17.1106967926,1.54132056236,-16.0750350952 -17.1246356964,1.53728568554,-15.9864559174 -17.1005821228,1.53226161003,-15.91269207 -17.1095180511,1.52822589874,-15.8201169968 -17.1164531708,1.52419006824,-15.7255477905 -17.133392334,1.52015674114,-15.6409692764 -17.1683483124,1.51912713051,-15.5733766556 -17.187292099,1.51609480381,-15.4917945862 -17.2082386017,1.51306295395,-15.4122104645 -17.2142086029,1.5110462904,-15.3684225082 -17.2221450806,1.50701212883,-15.2768526077 -17.2420940399,1.50398111343,-15.198266983 -17.2660427094,1.5019505024,-15.1216850281 -17.2829875946,1.49791896343,-15.0401058197 -17.3029346466,1.49588835239,-14.961523056 -17.2828903198,1.49086761475,-14.8957567215 -17.3048381805,1.48883759975,-14.8191728592 -17.3267879486,1.48580813408,-14.7435874939 -17.336730957,1.48277628422,-14.6570158005 -17.190574646,1.46371817589,-14.4375610352 -12.9588508606,1.04896843433,-10.7511558533 -12.9598112106,1.04594683647,-10.6825819016 -12.9467830658,1.04293382168,-10.636806488 -13.0007762909,1.04492139816,-10.613193512 -8.27782154083,0.586128234863,-6.57849359512 -8.29781627655,0.586121797562,-6.55189847946 -8.37384414673,0.591123878956,-6.57027006149 -8.39984226227,0.592118144035,-6.54767608643 -8.40483665466,0.591114103794,-6.52988576889 -8.42783260345,0.591108083725,-6.50529003143 -8.45983505249,0.592103362083,-6.48768949509 -8.48683261871,0.593097984791,-6.46609210968 -8.51283073425,0.593092381954,-6.4434967041 -8.52782344818,0.593085467815,-6.41290283203 -8.55982398987,0.594080686569,-6.39430952072 -8.5788269043,0.595078706741,-6.38750839233 -8.60082244873,0.595072746277,-6.36191368103 -8.62481975555,0.595066905022,-6.33732271194 -8.64881706238,0.59506136179,-6.3137216568 -8.67981719971,0.596056461334,-6.29412794113 -8.70981788635,0.597051382065,-6.27353620529 -8.73481559753,0.597046077251,-6.2509303093 -8.73880958557,0.59704220295,-6.23214530945 -8.77381324768,0.598037838936,-6.2155456543 -8.80181217194,0.599032998085,-6.19493865967 -8.82080745697,0.599026799202,-6.16635131836 -8.84780502319,0.599021553993,-6.14375686646 -8.8788061142,0.600016832352,-6.12415790558 -8.88580226898,0.600013554096,-6.10836219788 -8.91580200195,0.601008474827,-6.08677577972 -8.94080066681,0.601003229618,-6.06317615509 -8.95879459381,0.600997209549,-6.03458213806 -8.99379730225,0.602992892265,-6.01698446274 -9.02479743958,0.603988111019,-5.99639081955 -9.04179191589,0.602982103825,-5.96680021286 -9.06079387665,0.603980064392,-5.95899915695 -9.09579658508,0.605975747108,-5.94139814377 -9.12379550934,0.605970740318,-5.91880321503 -9.14078903198,0.605964839458,-5.88921165466 -9.17579174042,0.60696041584,-5.87061786652 -9.19478702545,0.606954693794,-5.84202718735 -9.2407951355,0.609951376915,-5.83141613007 -9.21477603912,0.606945455074,-5.7936463356 -9.23777198792,0.606940090656,-5.76705980301 -9.27377605438,0.607935905457,-5.74945831299 -9.33378887177,0.611933708191,-5.74783325195 -9.35178375244,0.611927866936,-5.71725511551 -11.1515693665,0.767058491707,-6.8164434433 -11.0425014496,0.756040215492,-6.69894599915 -10.8964281082,0.742024540901,-6.58326005936 -10.8904066086,0.740014672279,-6.53268527985 -10.8643770218,0.736003398895,-6.4691324234 -10.7252998352,0.721984803677,-6.33764696121 -10.6902685165,0.716973602772,-6.27009820938 -10.4971704483,0.698952436447,-6.10765361786 -10.4271335602,0.691943883896,-6.0429148674 -10.329076767,0.681929647923,-5.93941116333 -10.2800416946,0.675918936729,-5.86686658859 -10.1619787216,0.663904547691,-5.75436592102 -10.0909357071,0.655893206596,-5.66984081268 -10.0869216919,0.654886007309,-5.62526798248 -9.94985389709,0.640871822834,-5.50477743149 -9.88682174683,0.634865045547,-5.44704008102 -9.79377269745,0.62585401535,-5.35351991653 -9.72473430634,0.61784440279,-5.27398967743 -9.67570400238,0.612836122513,-5.20644521713 -9.61967182159,0.606827616692,-5.13491249084 -9.59165000916,0.60282087326,-5.08035230637 -9.56262874603,0.598814249039,-5.02579069138 -9.5206079483,0.594809770584,-4.98303318024 -9.47558116913,0.589802861214,-4.92048072815 -9.47056865692,0.587797522545,-4.87891530991 -9.46255588531,0.585792303085,-4.83634614944 -9.43753814697,0.581786692142,-4.785779953 -9.44853305817,0.581782341003,-4.7532043457 -9.43952083588,0.579777538776,-4.71162509918 -9.39650058746,0.575773835182,-4.66987133026 -9.41349887848,0.57576996088,-4.64128637314 -9.46250724792,0.578767061234,-4.6296749115 -9.45849704742,0.576762676239,-4.59010457993 -9.44548511505,0.574758052826,-4.54653549194 -9.48649024963,0.576755106449,-4.5309252739 -9.51549625397,0.578753769398,-4.52711629868 -9.54649829865,0.579750418663,-4.50552034378 -9.54448986053,0.577746272087,-4.46695232391 -9.5054693222,0.573741555214,-4.41139602661 -9.52746868134,0.57473808527,-4.38481283188 -9.54546642303,0.574734687805,-4.35722160339 -9.50544643402,0.569730341434,-4.30166959763 -9.55945968628,0.573729336262,-4.30885124207 -9.52344226837,0.569725215435,-4.25529956818 -9.53944015503,0.56972193718,-4.22671222687 -9.52842903137,0.567718446255,-4.18514633179 -13.088508606,0.855747640133,-5.78629159927 -13.1094989777,0.855739712715,-5.74670362473 -13.1344890594,0.856731712818,-5.70811986923 -13.1834955215,0.859727919102,-5.70530414581 -13.2074861526,0.859720051289,-5.66671562195 -13.2484817505,0.861712157726,-5.63512039185 -13.2954788208,0.863704383373,-5.60651683807 -13.3104658127,0.863696575165,-5.56393289566 -13.4034767151,0.869688808918,-5.55529642105 -13.3904561996,0.867681026459,-5.49973678589 -13.4294586182,0.869676887989,-5.4909324646 -13.4364452362,0.868669390678,-5.44534826279 -13.5054483414,0.872661411762,-5.42473363876 -13.5434427261,0.874653577805,-5.39113664627 -13.5794353485,0.875645875931,-5.35654163361 -13.6284322739,0.878637909889,-5.32693958282 -13.6454286575,0.878633856773,-5.30815076828 -13.6734209061,0.879626274109,-5.27055597305 -13.7534255981,0.88461792469,-5.25293397903 -13.752409935,0.883610725403,-5.20335817337 -13.7934055328,0.88560295105,-5.16976213455 -13.8384008408,0.887594938278,-5.13716650009 -13.8743944168,0.888587236404,-5.10157108307 -13.8973922729,0.889583349228,-5.08576869965 -13.9293851852,0.89157563448,-5.04817771912 -13.9533758163,0.891568183899,-5.00759124756 -14.0013723373,0.894560277462,-4.97598838806 -14.0703735352,0.898551702499,-4.95137739182 -14.0793600082,0.897544622421,-4.90480089188 -14.1003570557,0.898540616035,-4.88700723648 -14.1333503723,0.900533080101,-4.84941291809 -14.1833467484,0.902525067329,-4.81780815125 -14.1993360519,0.902517914772,-4.77323055267 -14.2863407135,0.908508777618,-4.75360774994 -14.3043308258,0.908501625061,-4.71002435684 -14.35932827,0.911493420601,-4.67941570282 -14.4003295898,0.914488911629,-4.66860246658 -14.4523258209,0.917480528355,-4.63500833511 -14.4863185883,0.91847294569,-4.59641504288 -14.4973068237,0.918466150761,-4.54983758926 -14.5643072128,0.922457456589,-4.52222061157 -14.5812950134,0.922450423241,-4.47664690018 -14.6873025894,0.92944008112,-4.46100521088 -14.67329216,0.927437543869,-4.43122959137 -14.7302904129,0.930428981781,-4.39862585068 -14.7962884903,0.934420108795,-4.3690123558 -14.8212804794,0.935412943363,-4.32642364502 -14.8342685699,0.935406148434,-4.27885389328 -14.9052677155,0.940397083759,-4.25023555756 -12.9938983917,0.792479813099,-3.63380289078 -12.9428844452,0.787480175495,-3.59605407715 -12.8448572159,0.779481172562,-3.52453136444 -12.8048410416,0.775479495525,-3.46898889542 -12.7858285904,0.772476971149,-3.42042756081 -12.7808208466,0.771473884583,-3.37585926056 -12.758808136,0.769471764565,-3.32729434967 -12.7418012619,0.767471015453,-3.30052495003 -12.7487945557,0.767467498779,-3.25994586945 -12.7497873306,0.766464412212,-3.21836471558 -12.7457790375,0.765461623669,-3.1738038063 -12.7817773819,0.767456650734,-3.14120554924 -12.7647676468,0.765454828739,-3.09463882446 -12.804766655,0.767449617386,-3.0620470047 -12.8427686691,0.769445955753,-3.0502409935 -12.8937702179,0.772440135479,-3.02063703537 -12.8797607422,0.77143830061,-2.97506666183 -12.9287614822,0.773432552814,-2.94446611404 -13.0187673569,0.780424237251,-2.92284750938 -13.0727682114,0.783418118954,-2.89323949814 -15.8721666336,0.994233250618,-3.50505065918 -15.9861764908,1.00222301483,-3.50520157814 -15.9511594772,0.999220132828,-3.44465231895 -16.006155014,1.0022110939,-3.40504860878 -16.0911521912,1.00820016861,-3.37143063545 -16.1701507568,1.01318955421,-3.33581805229 -16.2111434937,1.01518154144,-3.29222202301 -16.2241306305,1.01517546177,-3.24164915085 -16.2491283417,1.01617121696,-3.22084712982 -16.4141368866,1.02815413475,-3.20218372345 -16.333114624,1.02115499973,-3.13166570663 -16.4451160431,1.02914178371,-3.10202527046 -16.4501018524,1.02813637257,-3.04945540428 -16.5050964355,1.03212738037,-3.00685501099 -16.5260925293,1.03312325478,-2.98405981064 -16.6280937195,1.04011058807,-2.94943714142 -16.6320800781,1.03910541534,-2.89686322212 -16.7200775146,1.0450937748,-2.85924506187 -16.7850723267,1.04908370972,-2.81664299965 -16.8260650635,1.05207562447,-2.77004957199 -16.8760585785,1.05506694317,-2.72544622421 -16.9340591431,1.05905973911,-2.70763468742 -16.9390449524,1.05905473232,-2.65406370163 -17.0390434265,1.06504178047,-2.61643815041 -17.0950374603,1.06903243065,-2.57083916664 -17.1940364838,1.07601928711,-2.53221273422 -17.2030239105,1.0760140419,-2.47863960266 -17.2980213165,1.08200120926,-2.4380197525 -17.2820129395,1.08100044727,-2.40824246407 -17.3680095673,1.08598840237,-2.36562848091 -17.423002243,1.08997893333,-2.31803131104 -16.5309123993,1.02305531502,-2.13695287704 -16.2748794556,1.00307512283,-2.04852938652 -16.1868629456,0.996079981327,-1.98500812054 -16.1308498383,0.992082059383,-1.92646765709 -16.106842041,0.989082753658,-1.89769697189 -16.0698299408,0.986083269119,-1.84214603901 -16.2738380432,1.00106108189,-1.81646537781 -16.0408115387,0.983080387115,-1.73702192307 -16.0548038483,0.984076321125,-1.68744897842 -16.0227928162,0.981076717377,-1.63289833069 -16.0277881622,0.981074929237,-1.60811138153 -16.0687847137,0.984068453312,-1.56251525879 -16.0467739105,0.982068121433,-1.50896215439 -16.0737667084,0.983063042164,-1.46137666702 -16.0717601776,0.983060896397,-1.41080594063 -16.0967540741,0.984055995941,-1.36222660542 -16.1347484589,0.987049937248,-1.31563258171 -16.2007484436,0.991042017937,-1.29581713676 -16.2297420502,0.993036806583,-1.24822580814 -16.3217411041,1.00002503395,-1.20461165905 -16.3737354279,1.00301742554,-1.15801179409 -16.4737319946,1.01000463963,-1.11439096928 -18.853843689,1.18574917316,-1.24355792999 -18.8748321533,1.18674314022,-1.18597984314 -18.9368305206,1.19073450565,-1.16116118431 -18.9948196411,1.19472455978,-1.10556507111 -9.77740192413,0.514723658562,-0.446794480085 -9.7774066925,0.514726638794,-0.416220098734 -9.7714099884,0.514730274677,-0.385643839836 -9.76941394806,0.513733446598,-0.355069696903 -9.76841926575,0.513736665249,-0.324495911598 -9.75342082977,0.51273983717,-0.308712869883 -9.76942634583,0.513741195202,-0.27912914753 -9.7664308548,0.513744652271,-0.248555496335 -9.75643539429,0.512749135494,-0.216995552182 -9.7614402771,0.512751698494,-0.18740965426 -9.76044559479,0.512755155563,-0.156837120652 -9.74944782257,0.511758089066,-0.141058117151 -9.75845241547,0.512760341167,-0.111471764743 -9.75545787811,0.511764109135,-0.0809001401067 -9.74446296692,0.510768830776,-0.0503299087286 -9.74746799469,0.511771798134,-0.0207438822836 -9.75347328186,0.511774659157,0.00982886459678 -9.74647808075,0.51077902317,0.0403984561563 -9.73848056793,0.510781705379,0.0551888272166 -9.74148654938,0.510784983635,0.0857607275248 -9.7354927063,0.510789334774,0.116329602897 -9.73949813843,0.510792434216,0.145915836096 -9.73450279236,0.509796738625,0.17648422718 -9.73050880432,0.50980091095,0.206066817045 -9.72651290894,0.50980335474,0.221843108535 -9.72451782227,0.509807288647,0.25142621994 -9.73352432251,0.50981003046,0.282001852989 -9.72152996063,0.509815335274,0.311578720808 -9.71553516388,0.508820056915,0.342144548893 -9.71654224396,0.508823752403,0.371729135513 -9.71454811096,0.508828043938,0.402297645807 -9.70955085754,0.508830666542,0.417085647583 -9.70955753326,0.508834719658,0.447655498981 -9.71056365967,0.508838534355,0.477240145206 -9.71356964111,0.508842289448,0.507812917233 -9.70857620239,0.508846998215,0.537392258644 -9.70558261871,0.508851587772,0.567959368229 -9.70458984375,0.508855819702,0.597542226315 -9.70759296417,0.508857607841,0.613323569298 -9.69659900665,0.507863283157,0.642895340919 -9.69660568237,0.508867502213,0.672479450703 -9.70161247253,0.508871138096,0.703055500984 -9.69962024689,0.508875787258,0.733623504639 -9.69462680817,0.508880794048,0.763201534748 -9.70162963867,0.508882045746,0.7789888978 -9.6936378479,0.508887529373,0.808562874794 -9.68564414978,0.50789308548,0.838136017323 -9.68965148926,0.508897006512,0.868712544441 -9.68965816498,0.508901417255,0.898297190666 -9.68066596985,0.508907198906,0.927868545055 -9.68867397308,0.508910775185,0.959438025951 -9.6756772995,0.507914841175,0.973223686218 -9.68468379974,0.508918106556,1.00380945206 -9.68469142914,0.508922815323,1.03438103199 -9.67169952393,0.508929371834,1.06394457817 -9.672706604,0.508933842182,1.09353160858 -9.66671466827,0.508939445019,1.12310659885 -9.67372226715,0.508943319321,1.15467727184 -9.67172622681,0.508945941925,1.16946661472 -9.66673374176,0.508951485157,1.19904339314 -9.66974163055,0.509955883026,1.22962188721 -9.66775035858,0.50996106863,1.26019084454 -9.66475772858,0.509966373444,1.28977167606 -9.66176605225,0.509971797466,1.32033872604 -9.66377353668,0.509976506233,1.35091638565 -9.66177749634,0.509979248047,1.36570584774 -9.65978622437,0.509984612465,1.39627540112 -9.65679359436,0.509990036488,1.42585670948 -9.65880203247,0.510994791985,1.45643591881 -9.65480995178,0.511000454426,1.48601531982 -9.65181827545,0.511006116867,1.51658320427 -9.65582275391,0.51100808382,1.53237342834 -9.65383148193,0.512013614178,1.56294453144 -9.64184093475,0.511020541191,1.59151828289 -9.64484882355,0.512025237083,1.62210166454 -9.64485645294,0.512030482292,1.65267801285 -9.63386631012,0.51103758812,1.68224000931 -9.63487529755,0.512042701244,1.71281933784 -9.64287853241,0.513044178486,1.72960865498 -9.63988685608,0.513049900532,1.7591919899 -9.6308965683,0.512056708336,1.78875887394 -9.63790512085,0.513060986996,1.82034277916 -9.63591384888,0.514066755772,1.85091614723 -9.63092327118,0.514073073864,1.88148117065 -9.63493251801,0.514077961445,1.91305851936 -9.62693786621,0.514081954956,1.92684566975 -9.6229467392,0.514087975025,1.95642745495 -9.63895511627,0.516091227531,1.99100148678 -9.62196540833,0.515099465847,2.01857209206 -9.62397384644,0.515104830265,2.05014586449 -9.6299829483,0.516109406948,2.08173298836 -9.61498832703,0.515114605427,2.0945110321 -9.60899829865,0.515121221542,2.1240875721 -9.61400699615,0.516126215458,2.1566593647 -9.6140165329,0.517131865025,2.18724274635 -9.6120262146,0.517137885094,2.21781992912 -9.6070356369,0.517144560814,2.24838781357 -9.59104633331,0.516152918339,2.27595853806 -9.60505008698,0.518153607845,2.29475140572 -9.60606002808,0.518159329891,2.32632684708 -9.60307025909,0.519165694714,2.35690259933 -9.58908081055,0.518173754215,2.38448023796 -9.60108947754,0.520177841187,2.41905593872 -9.58810043335,0.519185900688,2.44762349129 -9.583111763,0.519192755222,2.47819328308 -9.59111499786,0.520194351673,2.49499630928 -9.59512424469,0.521199762821,2.52757334709 -9.57413578033,0.520209252834,2.55413770676 -9.586145401,0.52121335268,2.58871912956 -9.57515621185,0.521221220493,2.61729431152 -9.57716655731,0.522227108479,2.64986634254 -9.57517719269,0.522233605385,2.68143677711 -9.57818222046,0.523236215115,2.69822478294 -9.57019233704,0.5232437253,2.72779893875 -9.57420158386,0.524249196053,2.76038146019 -9.5732126236,0.52425557375,2.79195785522 -9.56722354889,0.525262951851,2.82252812386 -9.56623458862,0.525269389153,2.85410547256 -9.56823921204,0.526272237301,2.87089204788 -9.5562505722,0.525280535221,2.8994641304 -9.56225967407,0.52628582716,2.93304634094 -9.54827213287,0.526294648647,2.96161055565 -9.54728317261,0.527301132679,2.99319052696 -9.55329322815,0.528306603432,3.02776265144 -9.5483045578,0.528313875198,3.05833983421 -9.53831100464,0.528318703175,3.07112836838 -9.54432106018,0.529324293137,3.10570263863 -9.54633140564,0.530330359936,3.13828635216 -9.53134441376,0.529339373112,3.16585922241 -9.53635406494,0.530345141888,3.20043182373 -9.53436565399,0.531352162361,3.23299980164 -9.52837181091,0.531356394291,3.24679327011 -9.53338241577,0.532362163067,3.28136873245 -9.53739261627,0.533367991447,3.31495332718 -9.52540493011,0.53337687254,3.34451580048 -9.53041553497,0.53438270092,3.37909412384 -9.5224275589,0.534390628338,3.40867567062 -9.51344013214,0.534399032593,3.43924045563 -9.51844501495,0.535401463509,3.45703625679 -9.51845645905,0.536408305168,3.49060702324 -9.50846862793,0.536416769028,3.52018046379 -9.50948047638,0.537423372269,3.55375742912 -9.50049304962,0.537431895733,3.58432388306 -9.50250339508,0.53843832016,3.61790752411 -9.50251579285,0.539445221424,3.65148210526 -9.491522789,0.539450585842,3.66426491737 -9.50153255463,0.540455818176,3.70184087753 -9.49754428864,0.541463315487,3.73342251778 -9.49055767059,0.541471600533,3.76498961449 -9.4865694046,0.542479097843,3.79657268524 -9.48758029938,0.543486058712,3.83114480972 -9.48359298706,0.543493807316,3.86371660233 -9.48559856415,0.544496953487,3.88150548935 -9.49061012268,0.545503020287,3.91708922386 -9.47662353516,0.54551255703,3.94565987587 -9.47163581848,0.546520650387,3.97822928429 -9.47664737701,0.547526896,4.01480388641 -9.46866035461,0.547535359859,4.04538297653 -9.47266578674,0.548538208008,4.06417322159 -9.47767734528,0.549544453621,4.10075092316 -9.46269130707,0.549554407597,4.1293182373 -9.46870231628,0.55156058073,4.1668920517 -9.46871471405,0.552567839622,4.20147037506 -9.45672798157,0.552577197552,4.23104333878 -9.45474052429,0.553584754467,4.2646241188 -9.4587469101,0.554587721825,4.28440666199 -9.45675849915,0.554595291615,4.31798934937 -9.4497718811,0.555603981018,4.35055685043 -9.45078468323,0.556611120701,4.38613414764 -9.44079780579,0.556620240211,4.41670942307 -9.44381046295,0.558627068996,4.45328855515 -9.43382453918,0.558636426926,4.48485279083 -9.43483066559,0.55963987112,4.50264692307 -9.42784404755,0.559648573399,4.53521776199 -9.4358549118,0.561654567719,4.57479524612 -9.4268693924,0.561663687229,4.60636854172 -9.42388153076,0.562671780586,4.64094209671 -9.42789459229,0.564678490162,4.67852401733 -9.43290042877,0.56568133831,4.69931030273 -9.42091464996,0.565690934658,4.72889137268 -9.4299249649,0.567696869373,4.76947212219 -9.41693973541,0.567706942558,4.8000369072 -9.41995239258,0.568714082241,4.83860731125 -9.41996479034,0.570721507072,4.87419509888 -9.41397953033,0.570730209351,4.9077706337 -9.41898536682,0.571733295918,4.92955064774 -9.41399860382,0.572741925716,4.96412277222 -9.40401363373,0.573751449585,4.995698452 -9.40502548218,0.574758946896,5.03327512741 -9.39803981781,0.575767934322,5.06684875488 -9.39205360413,0.575776696205,5.10042905807 -9.3980588913,0.577779471874,5.12222003937 -9.40007305145,0.578786849976,5.1607966423 -9.39508628845,0.579795658588,5.19636440277 -9.39809894562,0.581803023815,5.23593950272 -9.38711452484,0.581812858582,5.2675151825 -9.38812732697,0.582820475101,5.30609083176 -9.38314151764,0.5838291049,5.34067392349 -9.39214611053,0.585831522942,5.36545753479 -9.38116168976,0.585841357708,5.39703655243 -9.37817573547,0.586850047112,5.43460178375 -9.3791885376,0.588857591152,5.47318410873 -9.37420368195,0.589866697788,5.50975084305 -9.36721801758,0.590875923634,5.54432678223 -9.37822914124,0.592881679535,5.58891439438 -9.36423873901,0.59288841486,5.6006937027 -9.36825084686,0.593895673752,5.64226961136 -9.37326335907,0.595902621746,5.68385505676 -9.35928058624,0.596913397312,5.71542215347 -9.35329532623,0.597922742367,5.75198936462 -9.3563079834,0.598930060863,5.79257583618 -9.34332466125,0.59994083643,5.82514095306 -9.34833049774,0.600943863392,5.84793329239 -9.35034370422,0.602951645851,5.88950681686 -9.33735942841,0.602962195873,5.92108440399 -9.33937263489,0.604969978333,5.96266174316 -9.33638763428,0.605978727341,6.00123643875 -9.32440376282,0.606989324093,6.0348033905 -9.33540821075,0.608991205692,6.06160068512 -9.33742141724,0.610999107361,6.10417318344 -9.32843780518,0.611009180546,6.13974285126 -9.31445407867,0.612020015717,6.17132043839 -9.32346630096,0.614026665688,6.2188949585 -9.31248283386,0.61503714323,6.25346422195 -9.31349658966,0.617045104504,6.29504823685 -9.32350158691,0.619047403336,6.32283639908 -9.30751895905,0.619058907032,6.35440444946 -9.30153465271,0.620068311691,6.39198303223 -9.30754756927,0.622075557709,6.43855762482 -9.29656410217,0.623086094856,6.473133564 -9.29457950592,0.625094950199,6.51470470428 -9.30359172821,0.627101540565,6.56328725815 -9.30059909821,0.628106236458,6.58208036423 -9.29661464691,0.629115521908,6.622651577 -9.29562854767,0.631124138832,6.6652264595 -9.27964687347,0.632135927677,6.6977930069 -9.27666187286,0.633145034313,6.73936605453 -9.28567409515,0.636151611805,6.78895044327 -9.30968379974,0.640155494213,6.85053110123 -9.27469825745,0.638166666031,6.84730768204 -9.27771282196,0.640174627304,6.8938832283 -9.26772880554,0.641185164452,6.93046092987 -9.26374435425,0.643194496632,6.97203636169 -9.25676059723,0.644204437733,7.01161003113 -9.25277519226,0.646213829517,7.05318832397 -9.25178337097,0.647218346596,7.07497596741 -9.33277988434,0.656210958958,7.18157577515 -8.54496383667,0.585375368595,6.6259303093 -8.47399425507,0.580398201942,6.61348772049 -8.44101715088,0.579413592815,6.63005495071 -8.37204647064,0.575435876846,6.61762046814 -8.31106758118,0.570452511311,6.59138774872 -8.30208587646,0.571463108063,6.62596273422 -8.26010894775,0.569480121136,6.63353919983 -8.17514324188,0.563506007195,6.60808944702 -8.13116931915,0.561523675919,6.61465263367 -8.06419849396,0.556545913219,6.60221195221 -7.9932308197,0.551568925381,6.58577346802 -7.99523878098,0.553573191166,6.60855722427 -7.88827753067,0.544603407383,6.56210803986 -7.86529874802,0.544616878033,6.5836853981 -7.8033285141,0.540638446808,6.57423782349 -7.92431783676,0.554623305798,6.71585226059 -7.72737789154,0.537671685219,6.59237623215 -7.64841127396,0.531696379185,6.56594085693 -7.62442493439,0.530705690384,6.56572628021 -7.58545017242,0.528722763062,6.57428359985 -7.50348472595,0.522748112679,6.54384899139 -6.58470869064,0.434940904379,5.78920459747 -6.73269176483,0.450920581818,5.9538192749 -7.3645658493,0.514803409576,6.54454898834 -7.06764936447,0.487872093916,6.32305669785 -6.97467899323,0.479895204306,6.2598285675 -7.2346367836,0.506852686405,6.53145360947 -6.46782875061,0.433015465736,5.88385915756 -6.36586952209,0.425045013428,5.8274230957 -7.12571191788,0.502902328968,6.5541639328 -7.08773708344,0.500919222832,6.55973529816 -7.05375337601,0.497930586338,6.54851913452 -6.82582330704,0.477985560894,6.37805223465 -6.9568104744,0.492968797684,6.53965187073 -6.91683626175,0.490986317396,6.54321479797 -6.86186647415,0.487006723881,6.53178119659 -6.51796340942,0.454084932804,6.24529838562 -6.36101770401,0.44012606144,6.13483715057 -6.34403038025,0.440134257078,6.13762044907 -6.44202470779,0.452123910189,6.2692232132 -6.38205623627,0.447145462036,6.24978876114 -6.38907241821,0.450153619051,6.29536533356 -6.4190826416,0.45515692234,6.36295509338 -6.45609140396,0.461159229279,6.43953084946 -6.35113382339,0.45218989253,6.37508678436 -6.36114025116,0.454192459583,6.40388584137 -6.30517101288,0.451213359833,6.38745069504 -6.36917304993,0.459209918976,6.49104404449 -6.3601937294,0.461221456528,6.52261304855 -6.34221458435,0.461234360933,6.54320001602 -6.33423471451,0.462245643139,6.57577180862 -6.3112487793,0.461255162954,6.57255363464 -6.27727460861,0.459271430969,6.57713270187 -6.30628585815,0.465275377035,6.64870834351 -6.32629871368,0.469280838966,6.71029472351 -6.23933696747,0.462308049202,6.65985631943 -6.28434371948,0.469308495522,6.74844646454 -6.27436447144,0.470320284367,6.78001737595 -6.2703742981,0.471325933933,6.7968044281 -6.25939416885,0.472337722778,6.82638597488 -6.23141908646,0.47135296464,6.8379611969 -6.21844005585,0.472365170717,6.8655424118 -6.22745656967,0.475373268127,6.91911172867 -6.2234749794,0.4773837924,6.9576883316 -6.19150066376,0.476399749517,6.9642701149 -6.20750570297,0.479401469231,7.00405883789 -8.7758808136,0.76588922739,9.93715953827 -8.77689838409,0.76989865303,10.0007343292 -9.03184986115,0.801856458187,10.3543615341 -9.02086925507,0.803868353367,10.4069337845 -9.01188850403,0.80687969923,10.4615097046 -9.00489807129,0.807885944843,10.4862966537 -8.30509281158,0.732038021088,9.7357339859 -8.26511955261,0.73105609417,9.75129318237 -8.1971540451,0.727079510689,9.73186016083 -8.13618659973,0.724101781845,9.72141933441 -8.07122039795,0.720124721527,9.70498371124 -8.05624103546,0.721137464046,9.74756240845 -7.97627019882,0.714158654213,9.68233108521 -7.94229602814,0.713175296783,9.70190429688 -7.88832759857,0.711196064949,9.69746875763 -7.74638080597,0.698234796524,9.58402061462 -7.75539636612,0.702242672443,9.65560245514 -7.77140951157,0.708249330521,9.73718166351 -7.81240749359,0.714245796204,9.81898021698 -7.6274728775,0.696293413639,9.649518013 -3.47855830193,0.20714507997,4.45749330521 -3.46258187294,0.207158252597,4.46507310867 -3.43260979652,0.205174580216,4.45563793182 -7.32264947891,0.679409861565,9.59614181519 -7.29967355728,0.680424392223,9.62771511078 -7.24670505524,0.677445173264,9.62028026581 -7.19173717499,0.674466252327,9.60885238647 -7.14376831055,0.672486066818,9.60741710663 -7.10679578781,0.671503603458,9.61998844147 -7.04682970047,0.667525887489,9.60155200958 -7.00484991074,0.664539337158,9.57533550262 -6.97287654877,0.664555847645,9.59390830994 -6.9289059639,0.662574768066,9.59548187256 -6.88693571091,0.660593450069,9.60104560852 -6.82097148895,0.656616926193,9.57161426544 -6.87597465515,0.667615652084,9.71120643616 -6.73303079605,0.652654826641,9.57276058197 -6.9659781456,0.684612393379,9.93558502197 -6.68107223511,0.651680529118,9.59411525726 -6.61610841751,0.647703826427,9.56368637085 -6.5941324234,0.648718357086,9.59526062012 -6.52516937256,0.643742501736,9.55882549286 -6.4881978035,0.642760157585,9.56839752197 -6.44921731949,0.638773024082,9.54218482971 -6.40624761581,0.637791752815,9.54176044464 -6.36927604675,0.636809706688,9.55232143402 -6.32230710983,0.633829236031,9.54489994049 -6.28533601761,0.633847057819,9.55446624756 -6.23836755753,0.630866646767,9.54704093933 -6.1893992424,0.628886640072,9.53561878204 -6.17341279984,0.627894937992,9.54340457916 -6.11644744873,0.624916851521,9.52097034454 -6.07147884369,0.622936248779,9.51653671265 -6.03450727463,0.621953845024,9.52311420441 -6.01153230667,0.622968614101,9.55169296265 -5.96656370163,0.619988024235,9.54626274109 -5.97657012939,0.623991191387,9.5960483551 -5.95059585571,0.624006509781,9.61962985992 -5.93861865997,0.62701934576,9.66820049286 -5.91564369202,0.628033995628,9.69678401947 -5.9206609726,0.633043110371,9.77236747742 -5.90668392181,0.635056197643,9.81794261932 -5.88770866394,0.637070417404,9.85651302338 -5.88971757889,0.640075266361,9.89529800415 -5.9017329216,0.646082937717,9.98488330841 -5.89975309372,0.650093734264,10.0534563065 -5.87977743149,0.652107894421,10.0900382996 -5.88779449463,0.65811663866,10.1766147614 -5.85482263565,0.657133579254,10.192191124 -5.85184240341,0.662144601345,10.261762619 -5.87284564972,0.667145311832,10.334561348 -5.92285108566,0.67914545536,10.4981451035 -5.89887714386,0.681160748005,10.5327167511 -5.87790203094,0.683175206184,10.5712976456 -5.88591861725,0.68918389082,10.6638746262 -5.88393831253,0.694194614887,10.7384557724 -5.90395212173,0.702200770378,10.8540401459 -5.91095972061,0.705204606056,10.9078273773 -5.89398384094,0.70821839571,10.9574050903 -5.88700485229,0.712230086327,11.0259847641 -5.88202571869,0.717241644859,11.1005573273 -5.88104534149,0.722252130508,11.1821374893 -5.86406946182,0.725266039371,11.2357082367 -5.89107131958,0.732265710831,11.3295049667 -5.88109350204,0.736278176308,11.3970804214 -5.86611652374,0.74029135704,11.4536657333 -5.87013483047,0.746301054955,11.5502433777 -5.84116268158,0.747317373753,11.582816124 -5.85417842865,0.755325078964,11.6983976364 -5.83720254898,0.759339094162,11.7569684982 -5.88819789886,0.770333945751,11.9057655334 -5.88921642303,0.777343988419,12.0003499985 -5.89723348618,0.784352898598,12.1119289398 -5.8692612648,0.786369085312,12.1514997482 -5.87028026581,0.793379366398,12.251077652 -5.87129926682,0.799389600754,12.3516559601 -5.8603219986,0.804402410984,12.4292297363 -5.87932634354,0.811403751373,12.5190248489 -5.85835170746,0.814418375492,12.5756034851 -5.88936233521,0.826422631741,12.7451877594 -5.96336078644,0.847418427467,13.0137653351 -3.58106446266,0.429907113314,7.87815999985 -3.54209637642,0.427925497293,7.85872745514 -3.5201125145,0.425934940577,7.84152173996 -3.49214053154,0.424950689077,7.84310817719 -3.48816251755,0.428962111473,7.90167713165 -3.45219302177,0.426979631186,7.88625574112 -3.42422103882,0.425995409489,7.88784170151 -3.36525845528,0.420017689466,7.81941270828 -3.32928919792,0.418035149574,7.80199432373 -3.31630301476,0.418042868376,7.80478525162 -3.28833127022,0.417058706284,7.80536937714 -3.25636148453,0.416075736284,7.79893636703 -3.22539067268,0.414092242718,7.79251670837 -3.20141768456,0.414107233286,7.80210208893 -3.17644524574,0.414122521877,7.80968427658 -3.14147591591,0.412139862776,7.79326152802 -3.12449145317,0.411148577929,7.78704452515 -3.10151791573,0.411163210869,7.79763698578 -3.0715470314,0.410179466009,7.79221868515 -3.0435757637,0.409195512533,7.7927942276 -3.03160023689,0.412208497524,7.83536481857 -2.99063253403,0.409226924181,7.80094671249 -2.97664666176,0.408234745264,7.79974222183 -3.30457258224,0.4821806252,8.74431419373 -3.27560091019,0.48219653964,8.74790287018 -2.93871974945,0.416273593903,7.92247486115 -2.8777577877,0.408295810223,7.83106279373 -2.84678769112,0.407312572002,7.8236322403 -2.8208155632,0.406327843666,7.82622146606 -2.80283141136,0.40533670783,7.81500768661 -2.78285741806,0.406350851059,7.83459472656 -2.75788521767,0.406366109848,7.84117650986 -2.73091387749,0.405381768942,7.84175920486 -2.71094083786,0.406396359205,7.86532735825 -2.68396902084,0.406411767006,7.86392068863 -2.65299892426,0.404428422451,7.85449266434 -2.69601750374,0.423435628414,8.10686302185 -2.59606719017,0.405465334654,7.88545465469 -2.57409477234,0.40648022294,7.90302705765 -2.55812048912,0.408493846655,7.93860292435 -2.53414797783,0.408508867025,7.94818687439 -2.52117276192,0.411521852016,7.99376583099 -2.51618456841,0.413527935743,8.02056026459 -2.50320935249,0.416541010141,8.06813526154 -2.48623490334,0.418554484844,8.10072422028 -2.4692606926,0.420568287373,8.13630199432 -2.45328640938,0.423581928015,8.17587947845 -2.44331073761,0.427594423294,8.23745346069 -2.45233917236,0.439608365297,8.41282081604 -2.59031915665,0.483591884375,8.99140262604 -2.41639137268,0.444636076689,8.48498630524 -2.53637719154,0.484623402357,9.01655673981 -2.49141073227,0.479642242193,8.96015071869 -2.41745352745,0.466667026281,8.79973220825 -2.39047241211,0.463677734137,8.75751209259 -2.39449214935,0.472687244415,8.8800983429 -2.37651801109,0.474701136351,8.92368030548 -2.36754179001,0.480713397264,9.00425624847 -2.35156750679,0.48472687602,9.05783939362 -2.33959197998,0.488739579916,9.12842178345 -2.34260129929,0.494744122028,9.1992149353 -2.38065314293,0.533768415451,9.73394393921 -2.32968974113,0.526788830757,9.65752029419 -2.3237118721,0.534800112247,9.76311206818 -3.18250727654,0.844661533833,13.8850383759 -3.14354014397,0.846679747105,13.9176111221 -3.48645734787,0.978624224663,15.6721992493 -3.43649291992,0.977644324303,15.6767816544 -3.38153076172,0.975665688515,15.6623563766 -3.32456874847,0.972687244415,15.6349363327 -3.30558514595,0.974696338177,15.667722702 -3.24662351608,0.971718072891,15.6263074875 -3.17966461182,0.964741587639,15.5478858948 -3.08471465111,0.947770535946,15.3304576874 -3.04374790192,0.950788974762,15.375038147 -2.95879459381,0.935815811157,15.1946172714 -2.9848074913,0.964821338654,15.5872030258 -2.95282769203,0.961832821369,15.5539884567 -2.88786864281,0.95585590601,15.4765663147 -2.85589909554,0.962872505188,15.5741491318 -2.81893110275,0.96689003706,15.6467323303 -2.77696490288,0.969908595085,15.6943130493 -2.72900056839,0.970928370953,15.7128887177 -2.69602108002,0.966939926147,15.6676797867 -2.65205550194,0.969958901405,15.7072591782 -3.7497420311,1.49076104164,22.695848465 -3.67478609085,1.48978614807,22.6874237061 -3.59183216095,1.48381257057,22.6200065613 -3.51387691498,1.48083806038,22.5875797272 -3.44491887093,1.48086190224,22.6101608276 -3.40494155884,1.47887480259,22.582950592 -3.3349840641,1.47989881039,22.6055240631 -3.26102757454,1.47792339325,22.5901050568 -3.17507505417,1.46995043755,22.494682312 -3.10711693764,1.47197401524,22.5242614746 -3.05115485191,1.47999501228,22.6398429871 -3.01217746735,1.47800779343,22.6186313629 -2.92122650146,1.46603560448,22.4752101898 -2.848269701,1.46505987644,22.4617900848 -2.7823112011,1.46808302402,22.5123672485 -2.71835184097,1.47210562229,22.5739498138 -2.65339279175,1.47512829304,22.6275310516 -2.57743740082,1.47315323353,22.5981082916 -2.53346133232,1.46616661549,22.5179023743 -2.48449754715,1.48118638992,22.7294807434 -2.40954184532,1.479211092,22.7050590515 -2.32458877563,1.46923744678,22.5716438293 -2.25463151932,1.46926093102,22.588224411 -2.20266890526,1.4842813015,22.7978000641 -2.12971234322,1.48330521584,22.7843837738 -2.09673309326,1.48531663418,22.8211727142 -2.03077459335,1.49033951759,22.8907546997 -1.96281671524,1.4943625927,22.9483318329 -1.87686419487,1.4813888073,22.7729187012 -1.81190550327,1.48741149902,22.8694953918 -1.74794638157,1.49543380737,22.9780788422 -1.68698632717,1.50645530224,23.1306629181 -1.65800619125,1.51446604729,23.2484493256 -1.58804893494,1.51848936081,23.299030304 -1.51509261131,1.51851320267,23.302614212 -1.44813430309,1.52553582191,23.3991985321 -1.38317573071,1.53655815125,23.5637760162 -1.32121598721,1.55257987976,23.7733631134 -1.29123592377,1.56259047985,23.912153244 -1.22127866745,1.56961381435,24.0197353363 -1.14732277393,1.57263755798,24.0583152771 -1.07936513424,1.5856603384,24.2328987122 -1.01940488815,1.61468160152,24.63048172 -0.943449556828,1.61770570278,24.6710643768 -0.858497321606,1.6027315855,24.479642868 -0.819519758224,1.60074365139,24.4474391937 -0.742564916611,1.60176801682,24.4590187073 -0.665609955788,1.60079205036,24.4516029358 -0.589654624462,1.60281610489,24.4861869812 -0.51269954443,1.60084009171,24.4517726898 -0.434744894505,1.59586429596,24.3873577118 -0.395767629147,1.59287655354,24.3561496735 -0.31881275773,1.59190058708,24.3407325745 -0.242857381701,1.59292435646,24.3473186493 -0.165902540088,1.59194839001,24.3369007111 -0.0899471566081,1.59097194672,24.3254890442 -0.0129923643544,1.58999598026,24.3110713959 --0.000999388983473,1.59200036526,22.3529949188 --0.0709566101432,1.59202289581,22.3505802155 --0.14091385901,1.59304535389,22.3611679077 --0.175892412663,1.59105658531,22.3369598389 --0.245849594474,1.59007906914,22.3255462646 --0.315806686878,1.58810162544,22.2931289673 --0.385763823986,1.58812403679,22.2897148132 --0.455720871687,1.58614635468,22.2672996521 --0.524678528309,1.58516848087,22.2558898926 --0.559656977654,1.58417975903,22.2366790771 --0.629614055157,1.58320200443,22.228263855 --0.699571430683,1.58522427082,22.2478542328 --0.769528448582,1.58424651623,22.2354373932 --0.839485645294,1.58526873589,22.2360229492 --0.909443020821,1.58629071712,22.2506160736 --0.980399727821,1.58731305599,22.2571983337 --1.01237940788,1.58232355118,22.1979942322 --1.0833363533,1.58534574509,22.2305831909 --1.15329349041,1.58536779881,22.2221698761 --1.22425031662,1.58638989925,22.231754303 --1.29420745373,1.58641183376,22.229341507 --1.36516451836,1.58843398094,22.2429275513 --1.43612158298,1.5904558897,22.2655200958 --1.47309947014,1.59246718884,22.2913131714 --1.54205703735,1.59148871899,22.2679004669 --1.61301398277,1.59251070023,22.2784900665 --1.68197143078,1.59053230286,22.2530765533 --1.75292873383,1.5925539732,22.2736701965 --1.82488512993,1.59457600117,22.2832546234 --1.89484274387,1.59459757805,22.2828464508 --1.93182063103,1.59660863876,22.3016395569 --2.00377750397,1.59863054752,22.319229126 --2.07373476028,1.59765207767,22.3078174591 --2.14769077301,1.6016740799,22.3424072266 --2.21964740753,1.60269594193,22.3489952087 --2.29060482979,1.60371744633,22.3535881042 --2.32758283615,1.60472846031,22.3653812408 --2.40253853798,1.60775065422,22.3979701996 --2.47449541092,1.60977220535,22.4055595398 --2.54845166206,1.61279392242,22.4351539612 --2.62240791321,1.61481583118,22.4557437897 --2.69736385345,1.61783778667,22.4843349457 --2.7713201046,1.61985945702,22.5029239655 --2.81129717827,1.62287092209,22.5327186584 --2.88425374031,1.62489235401,22.541311264 --2.95721054077,1.62591385841,22.5468997955 --3.03216648102,1.62793552876,22.5684928894 --3.10512328148,1.62895703316,22.5730819702 --3.17808008194,1.63097822666,22.5806789398 --3.25403571129,1.63399994373,22.6052684784 --3.29901146889,1.63901209831,22.6610622406 --3.37296772003,1.64103341103,22.6716556549 --3.44792413712,1.64305484295,22.6862487793 --3.52487945557,1.64507675171,22.7088394165 --3.59983587265,1.64809787273,22.7244358063 --3.6747918129,1.64911937714,22.7320251465 --3.71576881409,1.65213060379,22.7578201294 --3.79372429848,1.65515232086,22.7864151001 --3.86968016624,1.65717363358,22.7980060577 --3.94563603401,1.65919494629,22.8106002808 --4.02259206772,1.66121637821,22.8271923065 --4.09954786301,1.66423761845,22.8477897644 --4.17650318146,1.66625905037,22.859380722 --4.21848011017,1.66927027702,22.8841762543 --4.29543590546,1.67129135132,22.9017753601 --4.37739038467,1.67531347275,22.9363651276 --4.45734548569,1.67933499813,22.9659614563 --4.54029941559,1.68335711956,23.0035533905 --4.61525583267,1.68537771702,23.0071544647 --4.69521045685,1.68739926815,23.0247421265 --4.73618793488,1.68941009045,23.0425415039 --4.813144207,1.69143104553,23.0491371155 --4.8940987587,1.69545245171,23.0737323761 --4.97205448151,1.69747328758,23.0833282471 --5.05500888824,1.70149505138,23.1159229279 --5.13396453857,1.70351588726,23.1285190582 --5.21491956711,1.70653712749,23.1491165161 --5.25489711761,1.70754766464,23.1559123993 --5.33485221863,1.71056866646,23.1705112457 --5.41680717468,1.71358978748,23.194108963 --5.49776220322,1.71661090851,23.2097034454 --5.58271598816,1.72063243389,23.2423000336 --5.67466783524,1.72665512562,23.2988929749 --5.72764158249,1.73266744614,23.3596973419 --5.81059646606,1.73568844795,23.3802947998 --5.81457471848,1.71269714832,23.0828838348 --5.86253976822,1.70471274853,22.9654750824 --5.92450094223,1.70173048973,22.9100761414 --6.01345443726,1.70775222778,22.9566745758 --6.10840511322,1.71477508545,23.021270752 --6.14538431168,1.71478462219,23.0160713196 --6.21734237671,1.71480369568,22.9936676025 --6.29429864883,1.71582341194,22.9892635345 --6.37225484848,1.71784329414,22.9898605347 --6.44421339035,1.71786201,22.9694595337 --6.52316951752,1.71988201141,22.9740619659 --6.60212564468,1.72190177441,22.9756565094 --6.64110422134,1.72291147709,22.9744567871 --6.72805786133,1.72693252563,23.0030555725 --6.81001377106,1.72995269299,23.0136547089 --6.89496850967,1.73297297955,23.0342540741 --6.97292518616,1.73499250412,23.0308532715 --7.05687999725,1.73801255226,23.0464515686 --7.0968580246,1.73902237415,23.0482540131 --7.17081642151,1.7390409708,23.0298538208 --7.25777053833,1.74306154251,23.0524501801 --7.34372520447,1.74708163738,23.0730552673 --6.0660867691,1.39089822769,18.8325119019 --6.09105920792,1.38290977478,18.7061042786 --6.03105688095,1.35190868378,18.322687149 --6.14601325989,1.37392950058,18.5764980316 --6.22097063065,1.37794852257,18.6060962677 --6.32691955566,1.38997173309,18.7277011871 --6.31090450287,1.37097716331,18.4842853546 --6.32787895203,1.36098730564,18.342874527 --6.39184093475,1.36300420761,18.3434791565 --6.44780445099,1.36202013493,18.315071106 --6.4527926445,1.35602462292,18.2378692627 --6.57073831558,1.37104928493,18.3894786835 --6.57771635056,1.35905790329,18.2260684967 --6.51771450043,1.33105671406,17.8806533813 --6.63865947723,1.34608185291,18.0352554321 --6.69762229919,1.34709787369,18.0198535919 --6.70261049271,1.3421022892,17.9466514587 --6.78256797791,1.34712123871,17.9872512817 --6.93550300598,1.36915040016,18.2208633423 --6.97547197342,1.36516344547,18.1534614563 --7.02443790436,1.36317765713,18.1110610962 --7.09739732742,1.36719536781,18.1296615601 --7.11837148666,1.3592056036,18.0132522583 --7.14635372162,1.35921311378,18.0020542145 --7.20231771469,1.35922825336,17.9776554108 --7.24428606033,1.35524141788,17.9172477722 --7.51218891144,1.40128600597,18.4168777466 --7.35221576691,1.35427069664,17.8594493866 --7.47516107559,1.3682949543,17.9980583191 --7.55111980438,1.37231254578,18.019657135 --7.50412321091,1.35730957985,17.8274478912 --7.53009653091,1.35132014751,17.73204422 --7.57706403732,1.3493335247,17.6876430511 --7.61603307724,1.34534597397,17.6232395172 --7.698990345,1.35136425495,17.6628437042 --7.76495218277,1.35338008404,17.6614437103 --7.82792425156,1.36039221287,17.7292499542 --7.97686195374,1.37941920757,17.9158649445 --8.04782295227,1.38143563271,17.92146492 --8.28673458099,1.41747462749,18.3030948639 --10.3331232071,1.80375778675,22.6589679718 --8.45664787292,1.42751085758,18.3673000336 --8.61458301544,1.44753861427,18.5579185486 --8.17370128632,1.35748267174,17.5306549072 --8.64054775238,1.43555164337,18.3843097687 --8.66952133179,1.43056190014,18.2949066162 --8.73448371887,1.43157696724,18.2835121155 --8.78245162964,1.42958962917,18.236114502 --8.81342411041,1.42460000515,18.1537132263 --8.8643913269,1.42361307144,18.1113109589 --8.90736961365,1.4266217947,18.128118515 --8.95233821869,1.4246339798,18.0747184753 --9.01030349731,1.42464780807,18.0473175049 --9.01428413391,1.41465425491,17.9139156342 --9.0832452774,1.41766941547,17.9095172882 --9.11121940613,1.41267907619,17.8251171112 --9.13820266724,1.41168570518,17.808921814 --9.20816421509,1.41470062733,17.8065242767 --9.2321395874,1.40870988369,17.7151222229 --9.30110263824,1.41172468662,17.7107276917 --9.31607913971,1.40373253822,17.6033229828 --9.35005187988,1.40074276924,17.5329227448 --9.44100761414,1.40676021576,17.5695285797 --9.5369720459,1.41877520084,17.6833457947 --9.62792778015,1.42379248142,17.7169513702 --9.68889331818,1.42480587959,17.697561264 --9.85682868958,1.44383251667,17.8711833954 --10.0977430344,1.47486817837,18.1728134155 --9.82780075073,1.42084014416,17.5533657074 --12.2890911102,1.81615006924,21.8143520355 --12.3660621643,1.82316184044,21.8711643219 --9.83075523376,1.3988546133,17.2353515625 --12.6179571152,1.84120166302,21.9923992157 --12.6699266434,1.83821225166,21.9220066071 --12.8048725128,1.84923291206,21.9946231842 --12.840845108,1.8442414999,21.897228241 --12.7448635101,1.82323205471,21.6550121307 --12.7388496399,1.81123542786,21.4896125793 --12.7878189087,1.80824542046,21.4162158966 --12.6188497543,1.77122950554,20.9797840118 --12.5618495941,1.75222682953,20.7373771667 --12.5548353195,1.7412302494,20.5779743195 --12.5838098526,1.73523783684,20.4785728455 --12.554810524,1.7262365818,20.359369278 --12.5557928085,1.71624088287,20.2159633636 --12.5487785339,1.70624411106,20.0625610352 --12.5447635651,1.69624781609,19.9161605835 --12.5337505341,1.68425071239,19.7587528229 --12.5317344666,1.67525458336,19.617351532 --12.5257205963,1.66525793076,19.4719486237 --12.4927215576,1.65525615215,19.3527412415 --12.485707283,1.64525949955,19.2073364258 --12.4836921692,1.63626337051,19.0729370117 --12.4796772003,1.62726688385,18.9345321655 --12.4686632156,1.61626982689,18.7881298065 --12.4656476974,1.60727345943,18.6537227631 --12.4246511459,1.59727084637,18.5295181274 --12.4276351929,1.5892752409,18.4071159363 --12.4206209183,1.58027851582,18.2717132568 --12.4216041565,1.57228267193,18.1483097076 --12.4085922241,1.56228518486,18.0069046021 --12.4115743637,1.55428946018,17.8885002136 --12.4055604935,1.54529285431,17.759098053 --12.3725614548,1.53729116917,17.6528949738 --12.372546196,1.52929508686,17.5334892273 --12.3725299835,1.52129900455,17.4160881042 --12.3605175018,1.51230156422,17.2816791534 --12.3605012894,1.50530552864,17.1662788391 --12.3594856262,1.49730920792,17.0508766174 --12.3454742432,1.48831164837,16.9184741974 --12.3194732666,1.48131084442,16.8262653351 --12.3184576035,1.47331464291,16.7128639221 --12.3154430389,1.46631813049,16.5984611511 --12.3044309616,1.45732080936,16.4740562439 --12.2894182205,1.44832313061,16.3456516266 --12.2734069824,1.43932521343,16.2152423859 --12.237408638,1.43132340908,16.1150379181 --12.2263965607,1.42332601547,15.9946317673 --8.94124317169,0.981994628906,11.5875434875 --8.96222019196,0.98000228405,11.5381393433 --9.00519180298,0.981012046337,11.5177412033 --9.04216480255,0.981021106243,11.4903469086 --9.11712837219,0.986034035683,11.5099525452 --12.3162879944,1.39935576916,15.5424385071 --12.4522371292,1.41037285328,15.6120605469 --12.5421991348,1.41538524628,15.6246814728 --12.5871725082,1.4153932333,15.5782842636 --12.5461673737,1.40339279175,15.4258699417 --12.6971130371,1.41641080379,15.5135068893 --12.8430604935,1.42842829227,15.5921373367 --12.906036377,1.43343603611,15.6179475784 --12.8680324554,1.4224357605,15.4705343246 --13.0109806061,1.43445253372,15.5431642532 --13.1469306946,1.44546866417,15.6057920456 --13.2178983688,1.4484783411,15.5904083252 --13.2898654938,1.45148801804,15.5750207901 --13.3718299866,1.45549869537,15.5706348419 --13.4568014145,1.46250796318,15.6214580536 --12.2450942993,1.30739867687,14.1117858887 --13.5717439651,1.46452414989,15.5546808243 --13.657708168,1.46953475475,15.5543003082 --13.8506450653,1.48655498028,15.6739377975 --12.2290391922,1.28341090679,13.7351694107 --13.9056100845,1.4845635891,15.5873537064 --13.9565839767,1.48457074165,15.5439586639 --14.0065574646,1.48457753658,15.5015735626 --14.0965204239,1.48958790302,15.5031957626 --14.1834859848,1.49459791183,15.4998121262 --12.1979665756,1.25242650509,13.2269515991 --14.3484182358,1.50261664391,15.4820461273 --12.0219869614,1.22341632843,12.9093046188 --12.0219726562,1.21841967106,12.8269014359 --12.0079612732,1.21242177486,12.7304954529 --12.0249423981,1.20942652225,12.6681003571 --12.0759153366,1.2114341259,12.6407051086 --12.3168420792,1.23445761204,12.8133602142 --12.192858696,1.21545040607,12.602930069 --12.6236610413,1.23550486565,12.5234212875 --6.87031030655,0.493303775787,5.07416200638 --5.51055383682,0.353249281645,3.97167038918 --5.50853681564,0.351255536079,3.94326591492 --5.50851917267,0.35026204586,3.91585230827 --11.8641681671,0.979582905769,8.49409198761 --11.8711595535,0.978584349155,8.47089576721 --11.8711471558,0.975586652756,8.41248512268 --11.8681354523,0.973588705063,8.35408496857 --11.8671236038,0.970590889454,8.29668140411 --11.8641109467,0.967592895031,8.23827934265 --11.8650979996,0.964595198631,8.18187046051 --11.8630857468,0.962597191334,8.12547206879 --11.8430843353,0.958597362041,8.08326148987 --11.847070694,0.956599712372,8.03086185455 --11.8480587006,0.954601824284,7.97646093369 --11.8490457535,0.9526039958,7.92205762863 --11.8410348892,0.948605716228,7.86165094376 --11.83502388,0.945607483387,7.80324697495 --11.840010643,0.943609774113,7.75184202194 --11.8290071487,0.941610395908,7.71763801575 --11.8249950409,0.938612222672,7.66123533249 --11.8109855652,0.935613632202,7.59883069992 --11.8169727325,0.933615863323,7.54943037033 --11.8179597855,0.931617856026,7.49602127075 --11.8179483414,0.929619789124,7.44362258911 --11.8099384308,0.925621390343,7.38622045517 --11.8029336929,0.924622118473,7.35501337051 --11.795923233,0.921623706818,7.29861116409 --11.8089084625,0.920626044273,7.2542090416 --11.7938995361,0.916627407074,7.19280099869 --11.7858896255,0.913628995419,7.13639783859 --11.798874855,0.91263115406,7.09299945831 --11.7788724899,0.909631490707,7.05478954315 --11.7778606415,0.907633185387,7.00338935852 --11.7768497467,0.905634939671,6.95097970963 --11.7778377533,0.903636693954,6.9015827179 --11.7758264542,0.901638388634,6.85018205643 --11.7718153,0.898639976978,6.79677295685 --11.7648057938,0.896641492844,6.74236679077 --11.7568006516,0.894642055035,6.71316671371 --11.7587890625,0.892643749714,6.66476631165 --11.752779007,0.890645265579,6.61135911942 --11.7597665787,0.888647019863,6.56595993042 --11.747756958,0.885648369789,6.50955057144 --11.749745369,0.884649991989,6.46114492416 --11.7447347641,0.881651461124,6.40974283218 --11.7357301712,0.879651963711,6.38054037094 --11.8097066879,0.884655117989,6.37316513062 --11.8246917725,0.884656906128,6.33276796341 --11.8256816864,0.882658362389,6.28436326981 --11.8266706467,0.880659759045,6.23595714569 --11.8956460953,0.88566249609,6.22457695007 --11.9706220627,0.890665173531,6.21620082855 --12.0476045609,0.896667122841,6.23302841187 --12.1025838852,0.899669289589,6.21264028549 --12.2035560608,0.906672000885,6.21727848053 --12.2955303192,0.913674473763,6.2159075737 --12.3015184402,0.912675440311,6.169506073 --12.2065238953,0.901674985886,6.07106542587 --12.3074970245,0.909677267075,6.0736989975 --14.0941925049,1.06970131397,6.95312690735 --14.1271781921,1.06970119476,6.91373729706 --14.1671628952,1.0717010498,6.87734746933 --14.2111463547,1.07370102406,6.84296035767 --14.232134819,1.07370054722,6.79857540131 --12.2744464874,0.896681129932,5.79148292542 --12.2604436874,0.894681334496,5.76027297974 --12.2614326477,0.893682062626,5.71287059784 --12.2114305496,0.887682378292,5.64145088196 --12.1934242249,0.883682966232,5.58503818512 --14.4880495071,1.08569765091,6.61346006393 --14.5100383759,1.08569669724,6.56806898117 --14.5500240326,1.08769571781,6.53068304062 --14.5460205078,1.08669495583,6.50047779083 --14.6389989853,1.09269416332,6.48711013794 --14.5650024414,1.08469259739,6.39868974686 --14.500005722,1.07669115067,6.31426668167 --14.4310083389,1.06868994236,6.22783565521 --14.3780078888,1.0626885891,6.15041971207 --14.3060121536,1.05468738079,6.06499481201 --14.2120227814,1.04568696022,5.99675703049 --14.1450242996,1.03768587112,5.91433095932 --14.085026741,1.03068482876,5.83590984344 --14.0120296478,1.02268409729,5.75248336792 --13.9440326691,1.01568317413,5.67206001282 --13.878033638,1.0086824894,5.59263372421 --11.6103544235,0.809694170952,4.60638570786 --11.6283464432,0.810694396496,4.59219074249 --11.6303367615,0.809695124626,4.54978704453 --11.6233282089,0.807695865631,4.50438451767 --11.6213178635,0.806696534157,4.45997238159 --11.6223087311,0.805697143078,4.41857862473 --11.6122999191,0.802697896957,4.37217283249 --11.6172904968,0.802698493004,4.33177232742 --11.6212844849,0.801698684692,4.31156730652 --11.6012783051,0.798699498177,4.26115226746 --11.6022691727,0.797700047493,4.21975326538 --11.6082582474,0.797700464725,4.1803560257 --11.6012496948,0.795701026917,4.13494253159 --11.5962409973,0.793701589108,4.09154033661 --11.6072301865,0.793701887131,4.05414485931 --11.5972280502,0.792702198029,4.02994203568 --11.5952177048,0.79070264101,3.98753762245 --11.5932092667,0.789703071117,3.94513201714 --11.5812015533,0.787703633308,3.89972639084 --11.5901918411,0.787703812122,3.86132407188 --11.5861825943,0.785704195499,3.81892132759 --11.5781755447,0.784704685211,3.77450966835 --11.5711717606,0.782704949379,3.7513024807 --11.5711631775,0.781705200672,3.71090459824 --11.5571556091,0.779705822468,3.66549682617 --11.5501480103,0.778706133366,3.6220870018 --11.4271535873,0.766709506512,3.54163789749 --11.4431428909,0.767709314823,3.50623607635 --11.4291353226,0.765709996223,3.46283864975 --11.4311304092,0.764710009098,3.44262933731 --11.4081249237,0.761710882187,3.39622426033 --11.4201145172,0.761710703373,3.35982227325 --11.4061079025,0.759711265564,3.31540942192 --11.4260959625,0.760710835457,3.28201556206 --11.4040899277,0.757711589336,3.23661136627 --11.406085968,0.757711589336,3.21740984917 --11.3940792084,0.755712032318,3.17399716377 --11.3930702209,0.754712104797,3.13459539413 --11.3910617828,0.753712236881,3.09519529343 --11.384054184,0.752712488174,3.05378651619 --11.3910455704,0.751712203026,3.01638317108 --11.3850383759,0.75071233511,2.97598004341 --11.3770341873,0.749712646008,2.95376968384 --11.3750267029,0.748712658882,2.91436553001 --11.3690185547,0.747712790966,2.87396001816 --11.3820095062,0.747712135315,2.83957076073 --11.3630027771,0.745712697506,2.79515194893 --11.37799263,0.745711922646,2.76075816154 --11.3989839554,0.746710717678,2.72736120224 --11.3589839935,0.742712438107,2.69814538956 --11.3269786835,0.739713549614,2.65172886848 --11.3459692001,0.740712463856,2.6183347702 --11.3779573441,0.742710709572,2.58794522285 --11.4069471359,0.744708955288,2.55655288696 --11.4349374771,0.745707154274,2.52516460419 --11.4729261398,0.748704850674,2.49577784538 --11.4909210205,0.749703705311,2.48058247566 --11.5379095078,0.752700746059,2.4532020092 --11.5339021683,0.751700341702,2.41379785538 --11.4569015503,0.744703710079,2.35735368729 --11.6668701172,0.760691046715,2.32663917542 --11.6948604584,0.76268863678,2.29425263405 --11.7278547287,0.764686286449,2.28206801414 --11.7608451843,0.766683459282,2.24967551231 --11.8018350601,0.769680023193,2.21929192543 --11.8148269653,0.769678175449,2.18289518356 --11.8648166656,0.773674070835,2.15351104736 --11.8798093796,0.773671925068,2.1171131134 --11.7758140564,0.765677630901,2.07787132263 --11.7208118439,0.759679794312,2.02844285965 --11.9777870178,0.780662536621,2.03815412521 --12.0257778168,0.783658027649,2.00777411461 --12.0527696609,0.785654783249,1.97338521481 --12.0927610397,0.7886505723,1.94100034237 --12.1227531433,0.789646923542,1.90661120415 --12.2277402878,0.797638058662,1.88424825668 --11.9457569122,0.774656355381,1.81692636013 --11.3347892761,0.724696874619,1.67624986172 --11.4047784805,0.729690909386,1.65088045597 --11.5307645798,0.739680826664,1.63353073597 --11.7117471695,0.753666460514,1.62420797348 --11.4967546463,0.735680639744,1.55371439457 --11.5357456207,0.738676428795,1.52131950855 --11.532743454,0.738675951958,1.50211632252 --11.7447252274,0.754658579826,1.49581313133 --11.5767288208,0.740669727325,1.4343392849 --11.557723999,0.73866969347,1.39392483234 --11.7517089844,0.754652917385,1.38260769844 --11.46671772,0.730673789978,1.30707740784 --11.419716835,0.726676762104,1.28184854984 --11.5167064667,0.734667420387,1.25749146938 --12.7896413803,0.836561739445,1.37967956066 --11.6736879349,0.746651113033,1.20276391506 --11.6206846237,0.741653680801,1.15833079815 --12.9166250229,0.84554207325,1.27053034306 --11.4276828766,0.725666642189,1.06244111061 --11.4666786194,0.72866243124,1.04825651646 --11.434674263,0.725663423538,1.00783741474 --11.4886665344,0.729656875134,0.976456880569 --11.4496641159,0.726658523083,0.936039984226 --13.1815986633,0.865500092506,1.06844484806 --13.2055940628,0.867494225502,1.02805030346 --13.2565908432,0.870485723019,0.990675091743 --13.2725887299,0.872482419014,0.971487224102 --11.5506381989,0.733640432358,0.779270768166 --13.376581192,0.879464685917,0.894728183746 --13.3885784149,0.880459487438,0.85333609581 --11.5116252899,0.729637742043,0.665039539337 --13.4785728455,0.887442409992,0.774576485157 --13.6555662155,0.901418268681,0.722055494785 --11.4166116714,0.720639586449,0.53058975935 --11.3726081848,0.717641830444,0.491163015366 --13.6875619888,0.903401196003,0.593871772289 --12.2725839615,0.789543688297,0.469792366028 --13.7875585556,0.910381257534,0.512117981911 --13.8415575027,0.914370596409,0.47074085474 --13.8705558777,0.917364895344,0.449548661709 --11.4005842209,0.718626201153,0.292959362268 --12.0675735474,0.772551059723,0.284879416227 --12.16056633,0.779534399509,0.212126985192 --11.8445653915,0.75356644392,0.162566095591 --11.881562233,0.756559193134,0.126183539629 --12.0755605698,0.772535443306,0.112069517374 --12.0965576172,0.773529648781,0.0746825784445 --12.106554985,0.774525046349,0.0362832918763 --12.1035528183,0.774521887302,-0.00211922964081 --12.1045503616,0.774518251419,-0.0405205823481 --12.1065473557,0.774514377117,-0.0789215043187 --12.0945453644,0.77351218462,-0.117327950895 --12.1045446396,0.774509191513,-0.136524885893 --12.0895433426,0.773507297039,-0.174933448434 --12.0915412903,0.773503303528,-0.213334709406 --12.0815382004,0.772500813007,-0.251742035151 --12.0785360336,0.772497355938,-0.290146291256 --12.0605344772,0.770495831966,-0.328559339046 --12.0225315094,0.76749676466,-0.366986215115 --12.0595312119,0.770490109921,-0.386164784431 --12.0795307159,0.772483587265,-0.424554616213 --12.1165294647,0.775474727154,-0.46394148469 --12.1055278778,0.774472117424,-0.502350747585 --12.1045265198,0.774468123913,-0.540753006935 --12.099524498,0.774464607239,-0.579158604145 --12.1025247574,0.774462163448,-0.59835678339 --12.1035232544,0.774457812309,-0.636757254601 --12.0985221863,0.774454176426,-0.675163090229 --12.0985212326,0.774449884892,-0.713564455509 --12.0785198212,0.773448288441,-0.750974476337 --12.1035203934,0.775440335274,-0.791372418404 --12.0935182571,0.774437427521,-0.828772902489 --12.0585174561,0.771440029144,-0.846999526024 --14.2776021957,0.950116753578,-1.00326406956 --15.6466598511,1.05991137028,-1.1259701252 --14.7246265411,0.986037015915,-1.12083756924 --14.9866428375,1.00799059868,-1.18410396576 --14.1416091919,0.940107822418,-1.17593336105 --14.100610733,0.937106728554,-1.21835649014 --14.1186132431,0.938100337982,-1.24255132675 --14.1736192703,0.943084836006,-1.29091715813 --14.0746173859,0.935092389584,-1.32937610149 --14.3276348114,0.95604622364,-1.39363801479 --13.9516181946,0.926096796989,-1.40823400021 --13.9716234207,0.928086400032,-1.45462501049 --14.0276298523,0.933070003986,-1.50500261784 --13.9716291428,0.92907512188,-1.5222312212 --14.2096471786,0.948029637337,-1.5895087719 --13.9116325378,0.924069881439,-1.60505652428 --13.8196306229,0.917077183723,-1.64050662518 --13.765630722,0.913078486919,-1.67994225025 --13.7436323166,0.912074685097,-1.72135102749 --14.7987108231,0.996892154217,-1.88220179081 --14.1226663589,0.943000376225,-1.82975137234 --14.1466722488,0.944988191128,-1.87814116478 --14.0966739655,0.941988527775,-1.91756689548 --16.2378425598,1.114615798,-2.22284150124 --16.7318916321,1.15552008152,-2.33698415756 --16.1698551178,1.1106055975,-2.31867480278 --16.2858734131,1.12057435513,-2.38601279259 --16.2568759918,1.11857390404,-2.40822577477 --16.1058731079,1.10658895969,-2.4407081604 --16.0118732452,1.09959471226,-2.47915291786 --16.1348953247,1.11056160927,-2.54848742485 --16.1549072266,1.11254668236,-2.60387730598 --16.3639354706,1.12949728966,-2.68716430664 --16.3229427338,1.12749314308,-2.73358201981 --16.5929737091,1.14943766594,-2.80163860321 --16.4249668121,1.13645648956,-2.82912611961 --16.3889751434,1.13445103168,-2.87755012512 --16.38098526,1.13444054127,-2.92894864082 --16.5490131378,1.14839684963,-3.01025724411 --17.2620983124,1.20724892616,-3.18527460098 --14.2207870483,0.960817396641,-2.71631479263 --14.6748399734,0.99772554636,-2.81826472282 --14.4428215027,0.979760468006,-2.8247885704 --14.785867691,1.0086838007,-2.93400144577 --14.6398591995,0.996702134609,-2.95548009872 --14.4628477097,0.983726739883,-2.97098207474 --13.9247932434,0.940823793411,-2.91567468643 --13.9898033142,0.945806205273,-2.95083737373 --14.2408418655,0.966746151447,-3.04610133171 --14.3688650131,0.97871029377,-3.11843109131 --14.730919838,1.00862622261,-3.2396376133 --16.4811515808,1.15225636959,-3.64707279205 --14.3388872147,0.977685749531,-3.25464892387 --14.4229068756,0.98565787077,-3.3200032711 --13.8788394928,0.941766262054,-3.22750282288 --13.6818208694,0.925797820091,-3.23101401329 --14.2899122238,0.976659536362,-3.41007471085 --13.5748214722,0.918801248074,-3.2988820076 --14.6719846725,1.00955629349,-3.59266972542 --13.2217874527,0.89185833931,-3.30787873268 --13.3188085556,0.900828123093,-3.3742210865 --13.2608032227,0.895835936069,-3.38345932961 --13.2238054276,0.893834710121,-3.41887950897 --13.1578035355,0.888839900494,-3.44731783867 --13.1378068924,0.888834953308,-3.48673152924 --13.2588338852,0.898798465729,-3.56106448174 --13.2278366089,0.897795855999,-3.597479105 --13.1798372269,0.894796848297,-3.63091683388 --13.2158517838,0.897778987885,-3.68429279327 --13.1928520203,0.896779417992,-3.70050501823 --13.1798582077,0.896772563457,-3.74191451073 --13.2648801804,0.904742956161,-3.80926680565 --13.2788915634,0.906729459763,-3.85866427422 --13.4519309998,0.9216786623,-3.95096421242 --13.2249002457,0.903721809387,-3.93449926376 --13.353928566,0.915686070919,-3.99262261391 --13.3169307709,0.912684440613,-4.02804613113 --13.4299602509,0.923646867275,-4.1053776741 --13.3429546356,0.917657077312,-4.12683296204 --13.3019571304,0.914656221867,-4.16126203537 --13.3999853134,0.924621522427,-4.23560237885 --13.4740095139,0.931592345238,-4.30396032333 --13.3129844666,0.91862654686,-4.27925777435 --13.3019924164,0.918618440628,-4.32166242599 --13.4790382385,0.934562802315,-4.42296695709 --13.5520629883,0.941533088684,-4.49232339859 --13.6620960236,0.952493667603,-4.57365703583 --13.6711091995,0.953479588032,-4.62405109406 --13.7181310654,0.959455490112,-4.68742895126 --13.7491436005,0.962441384792,-4.72161245346 --13.8051671982,0.968414723873,-4.78797960281 --17.050863266,1.24255514145,-5.90748929977 --16.8168354034,1.22459900379,-5.8890209198 --16.2067222595,1.17474269867,-5.74277496338 --16.1757354736,1.1737344265,-5.78919029236 --16.24477005,1.18069922924,-5.87055158615 --16.1097488403,1.16972696781,-5.85283088684 --16.0847625732,1.16971707344,-5.90124416351 --16.3638458252,1.1946246624,-6.05647611618 --20.0977230072,1.51358699799,-7.44569206238 --19.9397449493,1.50358331203,-7.53157329559 --19.9237709045,1.50456380844,-7.59798288345 --19.8937797546,1.50256049633,-7.62219572067 --19.8147907257,1.49755883217,-7.66463899612 --19.8878383636,1.50551450253,-7.76298856735 --19.8288536072,1.50250732899,-7.81241846085 --19.8929004669,1.51046490669,-7.9087767601 --19.9019355774,1.51343774796,-7.98517084122 --20.4090957642,1.55926656723,-8.25526428223 --20.3500976562,1.55527091026,-8.26949691772 --20.3081188202,1.55325770378,-8.32691574097 --20.3971767426,1.5632058382,-8.43726062775 --20.3551998138,1.56219267845,-8.49467754364 --20.3452301025,1.56316936016,-8.56608200073 --20.5593204498,1.58407950401,-8.72834682465 --18.8839015961,1.44155693054,-8.11074352264 --18.8749141693,1.44154775143,-8.1419467926 --18.7529125214,1.43356072903,-8.16141986847 --18.7299365997,1.43354427814,-8.22082614899 --18.7959861755,1.44150006771,-8.31918430328 --18.5989627838,1.42653679848,-8.30469989777 --18.7820453644,1.44445598125,-8.45398616791 --18.699054718,1.43945753574,-8.48843288422 --18.8911247253,1.45738506317,-8.60851669312 --18.6070747375,1.4344496727,-8.55408668518 --18.3540306091,1.41450583935,-8.51063251495 --18.2910442352,1.41150140762,-8.55307388306 --18.2740707397,1.41248273849,-8.61447906494 --18.3171157837,1.41844475269,-8.70384788513 --18.4511890411,1.43237674236,-8.83616352081 --18.4392032623,1.43236815929,-8.86637115479 --18.5152587891,1.44131827354,-8.9727191925 --18.5272960663,1.44528901577,-9.05010986328 --18.4963207245,1.44527375698,-9.10752868652 --18.3823165894,1.43728637695,-9.12399196625 --18.4853858948,1.44922602177,-9.24633026123 --18.573431015,1.45818376541,-9.32447052002 --21.3253707886,1.70522737503,-10.7451753616 --21.2603931427,1.70221793652,-10.7966089249 --21.1854114532,1.69921195507,-10.8430500031 --19.7049541473,1.56968927383,-10.1843605042 --19.7510108948,1.57664430141,-10.2857275009 --19.7670555115,1.58060956001,-10.3721113205 --20.1862220764,1.61944854259,-10.6260509491 --20.1302433014,1.61743748188,-10.678483963 --20.3333568573,1.6383357048,-10.8637495041 --20.3734149933,1.64529013634,-10.9671230316 --20.4474849701,1.6552323103,-11.0884742737 --20.5965843201,1.6711473465,-11.2497730255 --20.7626876831,1.69005525112,-11.4220638275 --21.0228061676,1.71494472027,-11.6040992737 --21.1849136353,1.73285210133,-11.7783956528 --21.339017868,1.75076186657,-11.9486923218 --21.5781574249,1.77563929558,-12.1679372787 --21.6562366486,1.78557515144,-12.300283432 --22.0834503174,1.82838094234,-12.6274061203 --22.3015861511,1.85226249695,-12.8416643143 --22.6707572937,1.88810515404,-13.0966300964 --22.9739303589,1.91895270348,-13.362830162 --34.6155738831,2.99449324608,-20.120891571 --34.5926589966,2.99843764305,-20.2532901764 --34.4787101746,2.99341702461,-20.3317432404 --34.3307495117,2.98640918732,-20.3912200928 --34.1937866211,2.97939777374,-20.4556903839 --34.0487785339,2.96842169762,-20.4429759979 --33.9578361511,2.96639299393,-20.5334148407 --33.907913208,2.96734762192,-20.6488304138 --33.7089271545,2.95436120033,-20.6743412018 --33.519947052,2.94237112999,-20.7048473358 --33.3949928284,2.9373562336,-20.7733097076 --33.2940444946,2.93333172798,-20.8567619324 --33.2040557861,2.92833542824,-20.8730106354 --33.0550880432,2.92033076286,-20.925491333 --32.9481430054,2.91630935669,-21.0029430389 --32.8692054749,2.91527605057,-21.0983791351 --32.7342453003,2.9082660675,-21.1578521729 --32.6182899475,2.90324878693,-21.2283096313 --32.5083427429,2.89922833443,-21.3037700653 --32.4543647766,2.89721822739,-21.3409957886 --32.344417572,2.89319872856,-21.4144515991 --32.1964454651,2.88519501686,-21.462934494 --32.0895004272,2.88117408752,-21.5383892059 --31.9595375061,2.87516379356,-21.5968589783 --31.8395843506,2.87014889717,-21.662322998 --31.7196273804,2.8651342392,-21.7267856598 --31.6206302643,2.85914373398,-21.733045578 --31.5036754608,2.85412812233,-21.7995090485 --31.3907203674,2.84911108017,-21.8669662476 --31.2487545013,2.84210658073,-21.9154491425 --31.1297969818,2.83709287643,-21.9779109955 --31.0288505554,2.83407068253,-22.0533638 --30.9339065552,2.83104586601,-22.1328144073 --30.8449115753,2.82605218887,-22.1430664062 --30.7039432526,2.81904864311,-22.1885471344 --30.5879878998,2.81403398514,-22.2520103455 --30.487039566,2.81101250648,-22.3254642487 --30.3830890656,2.80799221992,-22.3969230652 --30.2701339722,2.80297660828,-22.4603843689 --30.1891441345,2.79898023605,-22.4746322632 --30.1382217407,2.80093574524,-22.5840549469 --30.0252666473,2.79592061043,-22.6465148926 --29.8812942505,2.78892016411,-22.6859989166 --29.7503299713,2.78291368484,-22.7344741821 --29.6823978424,2.78287696838,-22.830909729 --29.6294765472,2.78483343124,-22.9383354187 --29.5604915619,2.78183197975,-22.9595756531 --29.481552124,2.78080129623,-23.0460128784 --29.393611908,2.77877402306,-23.1274642944 --29.2636451721,2.77276802063,-23.1739387512 --29.1556930542,2.76975107193,-23.2383995056 --29.0517425537,2.76573204994,-23.3058624268 --28.9047660828,2.75873541832,-23.337348938 --28.8808059692,2.75971221924,-23.3925571442 --28.800868988,2.75868177414,-23.4780025482 --28.7179298401,2.75765252113,-23.5614490509 --28.6189823151,2.75563240051,-23.629901886 --28.5160312653,2.75261330605,-23.6963634491 --28.3860645294,2.74660873413,-23.7398414612 --28.2661018372,2.74159955978,-23.790309906 --28.1981143951,2.73859858513,-23.8095550537 --28.1061706543,2.73657488823,-23.8830051422 --28.0042209625,2.7335562706,-23.9484653473 --27.9342880249,2.73352074623,-24.0409049988 --27.8803691864,2.73647642136,-24.1473331451 --27.7754154205,2.73246002197,-24.2087936401 --27.6404438019,2.72645950317,-24.2442760468 --27.5524425507,2.72147011757,-24.2445316315 --27.4564971924,2.71844863892,-24.3139915466 --27.3835639954,2.71941494942,-24.4024295807 --27.2525939941,2.71341276169,-24.4399108887 --27.1516418457,2.7103946209,-24.5033721924 --27.0827121735,2.71135878563,-24.5958118439 --26.9547424316,2.70535564423,-24.6342906952 --26.8997650146,2.70434856415,-24.6625270844 --26.8368396759,2.70530986786,-24.7589588165 --26.7458953857,2.70428562164,-24.8314151764 --26.6429424286,2.70126914978,-24.8918781281 --26.5730133057,2.70223379135,-24.9823188782 --26.4500465393,2.6972284317,-25.0237960815 --26.340089798,2.69321584702,-25.0772647858 --26.2620944977,2.68922281265,-25.0825176239 --26.152135849,2.6852107048,-25.1349868774 --26.0691986084,2.68518257141,-25.2134380341 --25.9882602692,2.68415355682,-25.292886734 --25.8642902374,2.67915034294,-25.3303642273 --25.6192321777,2.66121840477,-25.2509288788 --25.5863304138,2.66616129875,-25.3763446808 --25.3772373199,2.64724779129,-25.2506885529 --25.4354019165,2.6621363163,-25.4650421143 --24.9901866913,2.62132811546,-25.1817474365 --23.5233020782,2.47307276726,-24.0215644836 --23.4683742523,2.47503423691,-24.1149959564 --23.4224567413,2.47798895836,-24.2194271088 --23.3654708862,2.47598791122,-24.2366657257 --23.2204742432,2.46800494194,-24.238161087 --24.3004550934,2.60025262833,-25.5067958832 --24.2615470886,2.60519909859,-25.6252174377 --24.1395759583,2.60019803047,-25.657699585 --24.0926647186,2.60414910316,-25.7681274414 --24.0016517639,2.59816789627,-25.7523899078 --23.9227161407,2.59813928604,-25.8298416138 --23.8317680359,2.59711885452,-25.8933010101 --23.7678451538,2.59908056259,-25.9867420197 --23.6839027405,2.59805512428,-26.0581989288 --23.6259841919,2.60101246834,-26.1586360931 --23.5420436859,2.60098719597,-26.2300930023 --23.4340820312,2.59797811508,-26.274564743 --23.560256958,2.61785268784,-26.4966697693 --20.5967998505,2.27276682854,-23.3561840057 --20.3067760468,2.25582098961,-23.3221893311 --20.2238178253,2.25380587578,-23.3746471405 --20.1488666534,2.25378608704,-23.4350986481 --20.234003067,2.26869082451,-23.6072406769 --19.9860115051,2.25671815872,-23.6162128448 --18.5257797241,2.0856730938,-22.0566673279 --18.3847579956,2.07670497894,-22.0301704407 --18.1786727905,2.05978441238,-21.9247188568 --17.9966106415,2.04584741592,-21.8462524414 --17.7394218445,2.01799845695,-21.6076393127 --17.6354293823,2.013007164,-21.6191158295 --17.5764808655,2.01398396492,-21.683555603 --17.5105247498,2.01396512985,-21.7410068512 --17.4725971222,2.01792526245,-21.8334369659 --17.4998455048,2.03876900673,-22.1452178955 --17.3397426605,2.02285408974,-22.0165367126 --17.2888031006,2.0248234272,-22.0929756165 --17.2328605652,2.02679657936,-22.1634178162 --17.0998382568,2.01782822609,-22.1359157562 --17.1139659882,2.02874803543,-22.2953071594 --15.8898105621,1.87862086296,-20.8616065979 --15.6566724777,1.85673630238,-20.6931800842 --15.4995613098,1.83982610703,-20.5554981232 --15.3404979706,1.82788598537,-20.4800186157 --15.2465028763,1.82389545441,-20.4884910583 --15.1775341034,1.82288599014,-20.5289459229 --15.1175746918,1.82286918163,-20.5813922882 --15.0526103973,1.8228559494,-20.6278438568 --15.0016613007,1.82483148575,-20.6932868958 --15.009724617,1.82979202271,-20.7714805603 --14.9387531281,1.82878398895,-20.8089351654 --14.907828331,1.83374238014,-20.9033641815 --14.8368577957,1.83273434639,-20.9408187866 --14.7879133224,1.83470737934,-21.0102577209 --14.7159414291,1.83369958401,-21.0477180481 --14.7119932175,1.83766901493,-21.1109218597 --12.1000728607,1.48580348492,-17.5482749939 --11.8638868332,1.45994877815,-17.3268566132 --11.7107963562,1.44702458382,-17.2223796844 --11.5787267685,1.43508410454,-17.1448841095 --11.4847040176,1.4301109314,-17.1223621368 --11.3527202606,1.42611801624,-17.1552696228 --11.2886886597,1.42014610767,-17.1195278168 --11.2266998291,1.41914713383,-17.1399765015 --11.1787319183,1.42013418674,-17.184425354 --11.1257562637,1.42012643814,-17.219871521 --11.0717792511,1.42011976242,-17.2533149719 --11.0278148651,1.42110407352,-17.3017520905 --11.0058336258,1.42209541798,-17.3279762268 --10.9548597336,1.42208623886,-17.3654174805 --10.9068908691,1.42307364941,-17.4088611603 --10.8619260788,1.42405819893,-17.4573020935 --10.8119564056,1.42504692078,-17.4987506866 --10.7629871368,1.42603480816,-17.5411949158 --10.7150182724,1.42602264881,-17.5836334229 --10.6890325546,1.42701792717,-17.6028594971 --10.6480741501,1.42899823189,-17.6582984924 --10.5940990448,1.42899048328,-17.6937484741 --10.544128418,1.42897951603,-17.7341918945 --10.501168251,1.43096148968,-17.7866306305 --10.4552049637,1.43294584751,-17.8350734711 --10.4022312164,1.43293690681,-17.8725261688 --10.3822555542,1.43392562866,-17.9027462006 --10.3362913132,1.4359099865,-17.9511890411 --10.284318924,1.43590080738,-17.9886341095 --10.2383575439,1.43788421154,-18.0390796661 --10.1893901825,1.4388718605,-18.0815200806 --10.1424264908,1.43985641003,-18.1299667358 --10.093460083,1.44084310532,-18.174413681 --10.0734834671,1.44283235073,-18.20362854 --10.0265216827,1.44381606579,-18.2530765533 --9.98456764221,1.44679474831,-18.3115215302 --9.92758846283,1.44579005241,-18.3409671783 --9.88062667847,1.44777393341,-18.3904132843 --9.83767032623,1.44975411892,-18.4458522797 --9.81369018555,1.45074570179,-18.4710788727 --9.76572704315,1.45273017883,-18.5195274353 --9.7207698822,1.45471155643,-18.572971344 --9.67080402374,1.45569872856,-18.6164131165 --9.6238451004,1.45768094063,-18.6688652039 --9.58189105988,1.45965921879,-18.7273006439 --9.52491664886,1.45965301991,-18.7597541809 --9.50093650818,1.46064472198,-18.7849788666 --9.44997119904,1.462631464,-18.8294315338 --9.39700222015,1.46262097359,-18.8688793182 --9.34904098511,1.46460461617,-18.9183235168 --9.29707622528,1.46659195423,-18.961774826 --9.25512695312,1.46856808662,-19.0242176056 --9.20716667175,1.47055125237,-19.0746631622 --9.19120311737,1.47353231907,-19.1178836823 --9.15827083588,1.47849726677,-19.1993141174 --9.12033176422,1.48246705532,-19.2727546692 --9.08439731598,1.48643422127,-19.3501930237 --9.04044914246,1.48941004276,-19.413640976 --5.40687131882,0.822838246822,-11.8859243393 --5.40594291687,0.829795360565,-11.9793386459 --12.296880722,2.13112688065,-26.7751407623 --12.1437864304,2.11720657349,-26.6626682281 --12.1119213104,2.12713313103,-26.8111000061 --12.0049133301,2.12215518951,-26.7965927124 --11.9359798431,2.12512731552,-26.8680591583 --11.1566514969,1.98902845383,-25.3520736694 --11.7359895706,2.1191546917,-26.8680362701 --11.6399021149,2.10822176933,-26.7653198242 --10.7944059372,1.95723128319,-25.0633831024 --10.6913871765,1.95125842094,-25.0398750305 --10.6033983231,1.94926691055,-25.0483512878 --10.5204210281,1.94826722145,-25.0708312988 --10.4364376068,1.947270751,-25.0873031616 --10.3254003525,1.94031083584,-25.04180336 --10.2633676529,1.9353402853,-25.0030574799 --10.1423063278,1.92639601231,-24.9305648804 --10.0302629471,1.91944003105,-24.8780651093 --9.9603099823,1.92042398453,-24.9285316467 --9.8462600708,1.91247212887,-24.8690338135 --9.63498973846,1.88366377354,-24.5636100769 --9.52684783936,1.86876416206,-24.4028987885 --9.43383693695,1.86478590965,-24.3883838654 --9.33982276917,1.86080992222,-24.3698673248 --9.26385211945,1.86080563068,-24.4003429413 --9.2259683609,1.86974442005,-24.5277881622 --9.16904163361,1.87371194363,-24.6062431335 --7.86614227295,1.59560751915,-21.3776741028 --9.0611000061,1.87469601631,-24.6679496765 --9.00016689301,1.87866818905,-24.7384109497 --7.61198043823,1.57574355602,-21.1999092102 --7.60314226151,1.58865129948,-21.3803329468 --7.63741397858,1.61248862743,-21.6817169189 --7.57845640182,1.61447393894,-21.729177475 --7.79620552063,1.68200445175,-22.5574188232 --7.72612667084,1.67406201363,-22.4696826935 --7.61303663254,1.66313314438,-22.3701858521 --7.59018135071,1.67505383492,-22.5286178589 --9.2678565979,2.10607361794,-27.6737251282 --9.18991184235,2.10805583,-27.7282047272 --7.02828454971,1.58566582203,-21.5433006287 --8.98789310455,2.10010242462,-27.695192337 --8.98301410675,2.11003351212,-27.8254032135 --8.9020614624,2.11102080345,-27.8708839417 --8.81709575653,2.1120159626,-27.9023647308 --6.652156353,1.56580412388,-21.4054679871 --6.65236711502,1.58368313313,-21.635881424 --6.41287851334,1.53700518608,-21.1034851074 --6.35993480682,1.54098200798,-21.1659469604 --6.38210630417,1.5558797121,-21.3531341553 --6.2970662117,1.54991722107,-21.3106174469 --6.3905749321,1.59460926056,-21.8639640808 --6.32560014725,1.59560608864,-21.8914299011 --6.25862121582,1.59560608864,-21.913898468 --7.80077934265,2.05738043785,-27.4991226196 --6.12867498398,1.59659802914,-21.9728336334 --6.10271120071,1.5995824337,-22.0110626221 --6.04476118088,1.60256373882,-22.0655231476 --7.52595853806,2.0643286705,-27.6718025208 --7.40085077286,2.05241322517,-27.5493164062 --5.77258396149,1.58171343803,-21.8749923706 --5.69757461548,1.57973241806,-21.8644676208 --5.65254306793,1.57575845718,-21.8307094574 --5.59459590912,1.578738451,-21.8881778717 --5.57478284836,1.59363543987,-22.0886096954 --5.44357061386,1.57378017902,-21.8611316681 --5.39164304733,1.57874846458,-21.9385890961 --5.32064771652,1.57775890827,-21.943063736 --5.38014698029,1.62046349049,-22.4764328003 --6.48069190979,2.016674757,-27.324016571 --5.25107765198,1.61152648926,-22.4021682739 --5.19313621521,1.61550402641,-22.4636287689 --6.24967765808,2.00972676277,-27.2942504883 --6.15666818619,2.00674962997,-27.2787437439 --6.07972192764,2.00873398781,-27.3302249908 --5.99474573135,2.00873661041,-27.3497123718 --5.9477353096,2.00775122643,-27.3359584808 --5.86476993561,2.00874781609,-27.3664493561 --5.76171016693,2.00080108643,-27.2979469299 --4.88420295715,1.69695556164,-23.5870285034 --5.626912117,2.0147125721,-27.4998989105 --5.53691291809,2.01273012161,-27.4943904877 --5.32032155991,1.96010625362,-26.865978241 --5.37076187134,1.99684739113,-27.3271503448 --5.26367855072,1.98791527748,-27.2336578369 --5.20985126495,2.00082826614,-27.4091243744 --5.11682939529,1.99685883522,-27.3806171417 --5.02180194855,1.99289286137,-27.3461170197 --4.92073440552,1.98595094681,-27.2696151733 --4.82570123672,1.9809885025,-27.2291126251 --4.72137880325,1.95319092274,-26.8894023895 --4.67660617828,1.97007131577,-27.1218605042 --4.58659553528,1.96809506416,-27.1053581238 --4.46439886093,1.9492303133,-26.8948745728 --4.34923219681,1.9343470335,-26.7163848877 --4.32258367538,1.96215415001,-27.0768375397 --4.22049283981,1.95322608948,-26.9763393402 --4.17246294022,1.9492521286,-26.9435882568 --4.07841491699,1.94429814816,-26.8880844116 --4.01656627655,1.95522534847,-27.0395584106 --3.8731970787,1.92346215248,-26.6520900726 --2.372828722,1.1420378685,-16.9605731964 --2.318816185,1.14005494118,-16.9530353546 --2.14900326729,1.07254600525,-16.1195850372 --2.11493253708,1.06659209728,-16.0498142242 --2.03874588013,1.05171203613,-15.8633022308 --1.98974204063,1.05072319508,-15.8657588959 --1.8903580904,1.01895868778,-15.4772548676 --1.86351191998,1.03187692165,-15.6416912079 --1.77860856056,1.03983843327,-15.7536087036 --1.75965070724,1.0438182354,-15.7998342514 --1.71770656109,1.04779481888,-15.8632898331 --1.62676203251,1.05278098583,-15.9322042465 --1.57573795319,1.05080425739,-15.9136629105 --1.53683078289,1.05875957012,-16.0141143799 --1.48984968662,1.05975794792,-16.0395717621 --2.40339303017,1.83721458912,-25.7532520294 --2.32744073868,1.84020376205,-25.7977371216 --2.24441885948,1.8372335434,-25.7712306976 --2.15329909325,1.82731974125,-25.6457233429 --2.03990793228,1.79456281662,-25.2452297211 --1.96698474884,1.79953503609,-25.3197174072 --1.935074687,1.80649137497,-25.4089565277 --1.85708785057,1.80750060081,-25.4184436798 --1.76998198032,1.7975782156,-25.3079357147 --1.68895125389,1.7946126461,-25.2734260559 --1.59980428219,1.78171372414,-25.1219234467 --1.52892053127,1.79066383839,-25.2354106903 --1.44685578346,1.78471755981,-25.1668987274 --1.40176713467,1.77677679062,-25.0761508942 --1.32680881023,1.77976953983,-25.1146354675 --1.23556256294,1.75992691517,-24.8641300201 --1.15652024746,1.75596749783,-24.8186168671 --1.07951283455,1.75498819351,-24.8081035614 --1.00457727909,1.75896835327,-24.8695983887 --0.919376909733,1.74309897423,-24.6660881042 --0.881372511387,1.74210965633,-24.6603298187 --0.803335905075,1.73914706707,-24.6208209991 --0.724247872829,1.73121333122,-24.5303096771 --0.601907968521,1.70342981815,-24.1880340576 --0.523800373077,1.69450700283,-24.0785236359 --0.444573700428,1.67665100098,-23.8510074615 --0.405436962843,1.66573596001,-23.7142467499 --0.33141425252,1.6637648344,-23.6897354126 --0.259474098682,1.66774713993,-23.747220993 --0.185376569629,1.65981793404,-23.6487045288 --0.111325472593,1.65586292744,-23.5961933136 --0.0393561050296,1.65786159039,-23.6246757507 -0.0384008772671,1.66713786125,-22.8372135162 -0.075330927968,1.66208875179,-22.7693901062 -0.147223487496,1.65400922298,-22.6657371521 -0.220317035913,1.6610417366,-22.7610721588 -0.293295621872,1.6600099802,-22.7424201965 -0.365268111229,1.65797531605,-22.7177619934 -0.437222570181,1.65493047237,-22.6751079559 -0.509187042713,1.65189146996,-22.6424560547 -0.546200931072,1.65288925171,-22.6576290131 -0.619242966175,1.65689325333,-22.7019672394 -0.691214621067,1.65485799313,-22.6763114929 -0.763196349144,1.65382862091,-22.6606578827 -0.834143102169,1.64977991581,-22.6100082397 -0.899970948696,1.63666605949,-22.440366745 -0.934941053391,1.63464009762,-22.4115447998 -1.00080704689,1.62354791164,-22.2799015045 -1.08406376839,1.64466917515,-22.5392189026 -1.15707862377,1.64665830135,-22.5565624237 -1.21581852436,1.62549734116,-22.2979373932 -1.17687404156,1.46841990948,-20.345489502 -1.23881530762,1.46337068081,-20.2868480682 -1.26977574825,1.46034026146,-20.2470340729 -1.33173441887,1.45730066299,-20.2053890228 -1.39267921448,1.45325374603,-20.1497440338 -1.45362603664,1.44920778275,-20.0961055756 -1.51658976078,1.4461710453,-20.0594673157 -1.57654297352,1.44312894344,-20.0118198395 -1.64052677155,1.44210290909,-19.99518013 -1.8354985714,1.60415577888,-21.9930953979 -1.90447831154,1.60312652588,-21.9744434357 -1.96536266804,1.59404611588,-21.8588085175 -2.03636145592,1.59502696991,-21.8591594696 -2.08514094353,1.57689094543,-21.6365375519 -2.12987756729,1.55573189259,-21.3699302673 -2.19383382797,1.5526907444,-21.3262825012 -2.25812149048,1.57683539391,-21.6204128265 -2.33316159248,1.58083844185,-21.6627597809 -2.35169386864,1.54257178307,-21.1861858368 -2.41263365746,1.53852236271,-21.125541687 -2.48062443733,1.53849971294,-21.1168956757 -2.61517190933,1.58477199078,-21.6791534424 -2.68919897079,1.58776831627,-21.7084999084 -2.72117519379,1.58574688435,-21.684677124 -2.7941904068,1.58773696423,-21.7020263672 -2.8621711731,1.58770871162,-21.6833782196 -2.93417692184,1.58869373798,-21.6907291412 -3.00417470932,1.58967494965,-21.6900787354 -3.0812151432,1.59367823601,-21.7334213257 -3.11520719528,1.59366500378,-21.7255973816 -3.18016695976,1.59062635899,-21.6859531403 -3.2602250576,1.5966386795,-21.7472953796 -3.33625197411,1.59963476658,-21.7766418457 -3.41731619835,1.60565054417,-21.8449764252 -3.5044093132,1.61468100548,-21.9433078766 -3.59049582481,1.62370789051,-22.0346374512 -3.64158463478,1.63174498081,-22.1277923584 -3.72966837883,1.63977015018,-22.2171287537 -3.82177996635,1.64980995655,-22.3354511261 -3.92695665359,1.66588306427,-22.5217590332 -4.01100635529,1.67189025879,-22.5760993958 -4.10109090805,1.67991530895,-22.6664276123 -4.16905117035,1.67787659168,-22.6277866364 -4.20504665375,1.67786514759,-22.6239566803 -4.29110097885,1.68387460709,-22.6832942963 -4.39625263214,1.69793379307,-22.8446063995 -4.48933410645,1.70695698261,-22.9329357147 -4.58442592621,1.71598529816,-23.0322608948 -4.67046928406,1.72098875046,-23.0805969238 -4.74143838882,1.71995437145,-23.0509529114 -4.78546285629,1.72295737267,-23.0781211853 -4.85844421387,1.72292935848,-23.0614719391 -4.93242788315,1.72290229797,-23.0468215942 -5.00641441345,1.72287690639,-23.0351734161 -5.08140039444,1.72285139561,-23.0235271454 -5.15337753296,1.72282123566,-23.0018787384 -5.22535419464,1.7217912674,-22.9802322388 -5.26435518265,1.72278237343,-22.9824047089 -5.33532953262,1.72175109386,-22.9577579498 -5.41533851624,1.72473716736,-22.9701042175 -5.4913277626,1.72571313381,-22.9614562988 -5.56430959702,1.72568571568,-22.9448070526 -5.64130353928,1.72666430473,-22.941160202 -5.71729516983,1.72764146328,-22.9345092773 -5.75529241562,1.7276314497,-22.9336833954 -5.83228874207,1.72961115837,-22.9320297241 -5.91530370712,1.73259985447,-22.9503765106 -5.99129247665,1.73257613182,-22.9417285919 -6.07029438019,1.73455870152,-22.9460754395 -6.1502995491,1.73754286766,-22.9544200897 -6.18729114532,1.73752951622,-22.9465961456 -6.26327800751,1.73750448227,-22.9349517822 -6.3432803154,1.73948740959,-22.9402999878 -6.41926860809,1.74046337605,-22.9306507111 -6.49024248123,1.74043238163,-22.9050064087 -6.57525920868,1.74342191219,-22.9253501892 -6.64924097061,1.74339497089,-22.9087028503 -6.69526052475,1.74639523029,-22.9308719635 -6.76623344421,1.74636387825,-22.9042263031 -6.84823989868,1.74834859371,-22.9135742188 -6.92723417282,1.75032734871,-22.9099235535 -7.00422334671,1.75130403042,-22.9012775421 -7.09024143219,1.75429463387,-22.9236164093 -7.20133304596,1.76532065868,-23.025932312 -7.25737905502,1.77033340931,-23.0770893097 -7.35442447662,1.77633678913,-23.1294212341 -7.46851730347,1.78736305237,-23.2337360382 -7.59063005447,1.80039858818,-23.3600406647 -7.72276878357,1.81544661522,-23.5153369904 -7.84988975525,1.82848536968,-23.6506404877 -7.97700691223,1.84152257442,-23.7829418182 -8.04407310486,1.84954452515,-23.8570899963 -8.13609218597,1.85353457928,-23.8814258575 -8.22710514069,1.85752177238,-23.899766922 -8.31811714172,1.86050856113,-23.9171066284 -8.40211009979,1.86248576641,-23.9124584198 -8.48509979248,1.8644618988,-23.9048080444 -8.5690946579,1.86644077301,-23.9031505585 -8.60507488251,1.86542129517,-23.8823337555 -8.6730260849,1.86337971687,-23.8326969147 -8.75501441956,1.8653550148,-23.8230476379 -8.84101009369,1.8673337698,-23.8213977814 -8.91297340393,1.86629784107,-23.7847537994 -8.98694038391,1.86626315117,-23.751115799 -9.00788593292,1.86222827435,-23.6923122406 -9.06080245972,1.85717082024,-23.6036930084 -9.11472415924,1.85211527348,-23.519071579 -9.18468570709,1.85107886791,-23.4794330597 -9.2516374588,1.84903764725,-23.4288024902 -9.32059764862,1.84800052643,-23.3871631622 -9.40759658813,1.84998142719,-23.3895111084 -9.44658660889,1.85096693039,-23.3786888123 -9.51654720306,1.84993028641,-23.3380527496 -9.60053730011,1.85190701485,-23.3304042816 -9.66348552704,1.84886467457,-23.274772644 -9.72141933441,1.8458160162,-23.2041511536 -9.78937625885,1.84477770329,-23.1585197449 -9.84731388092,1.84073019028,-23.0898971558 -9.88530254364,1.84171569347,-23.0780735016 -9.97229957581,1.84369623661,-23.0784225464 -10.0602989197,1.84667742252,-23.0807704926 -10.159321785,1.85266911983,-23.1091041565 -10.250328064,1.85565328598,-23.1184482574 -10.3323135376,1.85762810707,-23.1048030853 -10.3782281876,1.85157096386,-23.0101890564 -10.3510866165,1.83949804306,-22.8504333496 -10.4521093369,1.84449005127,-22.8797702789 -10.5511293411,1.84948062897,-22.9051094055 -10.6261024475,1.84944987297,-22.8764686584 -10.6710186005,1.84439396858,-22.7828578949 -10.5967111588,1.81623888016,-22.4333629608 -10.5785102844,1.79913198948,-22.206817627 -10.601474762,1.7971072197,-22.1660060883 -10.6383810043,1.79004764557,-22.0604095459 -10.6782970428,1.78499257565,-21.964799881 -10.7091941833,1.77692937851,-21.8482074738 -10.7471084595,1.77187395096,-21.7506008148 -10.7850227356,1.7658188343,-21.6529979706 -10.8269433975,1.76076674461,-21.5633926392 -10.8218603134,1.75372159481,-21.4676113129 -10.8607778549,1.74766850471,-21.3740081787 -10.8966941833,1.74261462688,-21.2774028778 -10.9376182556,1.73756420612,-21.1898002625 -10.9765396118,1.73251283169,-21.0991973877 -11.025478363,1.72946953773,-21.0295829773 -11.0394306183,1.72544002533,-20.9737854004 -11.0893735886,1.7223982811,-20.9071712494 -11.1333065033,1.71835196018,-20.8285636902 -11.1662225723,1.71329903603,-20.7309627533 -11.1971349716,1.70724523067,-20.6303672791 -11.2410707474,1.70320034027,-20.5537605286 -11.2749900818,1.69814944267,-20.4601612091 -11.2929534912,1.69512534142,-20.4163589478 -11.3408966064,1.69208455086,-20.3497467041 -11.3868379593,1.68904292583,-20.2801361084 -11.4317770004,1.68600022793,-20.2075309753 -11.4777183533,1.68295919895,-20.1389198303 -11.5136461258,1.67791235447,-20.0533161163 -11.5746116638,1.67788124084,-20.0116939545 -11.5925769806,1.67485833168,-19.9698905945 -11.6405229568,1.67281925678,-19.9052810669 -11.6944789886,1.67078459263,-19.8526630402 -11.7344150543,1.66674160957,-19.7760601044 -11.7583293915,1.66068935394,-19.6724700928 -11.7752342224,1.65363395214,-19.558883667 -11.8352003098,1.65360319614,-19.5162677765 -11.856171608,1.65158331394,-19.4814605713 -11.9071264267,1.64954853058,-19.4258460999 -11.9600849152,1.64851510525,-19.3742275238 -12.0130414963,1.64648139477,-19.3216152191 -12.0760126114,1.64745366573,-19.2859916687 -12.1299724579,1.64642131329,-19.236371994 -12.158955574,1.64540612698,-19.2145633698 -12.2039041519,1.64336919785,-19.1509532928 -12.2698802948,1.64334344864,-19.1203269958 -12.3318519592,1.6443157196,-19.0837020874 -12.3848114014,1.64228355885,-19.0330867767 -12.4547920227,1.64425945282,-19.0074596405 -12.5177640915,1.6442322731,-18.9718360901 -12.5467481613,1.64421784878,-18.9510231018 -12.628745079,1.64720070362,-18.9453830719 -12.6927185059,1.64817392826,-18.9107589722 -12.7426748276,1.64614033699,-18.8551464081 -12.8116540909,1.64711642265,-18.8285198212 -12.8896455765,1.65009665489,-18.8148841858 -12.9396018982,1.64806342125,-18.7592735291 -13.0016260147,1.6530649662,-18.7874317169 -13.071606636,1.6540415287,-18.761800766 -13.1325769424,1.65501344204,-18.7221813202 -13.1915435791,1.65398466587,-18.679561615 -13.2525138855,1.65495669842,-18.6399421692 -13.3305034637,1.65693700314,-18.6253051758 -13.3954792023,1.65791118145,-18.5916805267 -13.4364757538,1.65990197659,-18.5868606567 -13.502450943,1.65987610817,-18.553237915 -13.5684261322,1.66085076332,-18.520614624 -13.6414108276,1.66282868385,-18.4979801178 -13.7113904953,1.66480457783,-18.4693565369 -13.7853746414,1.66678273678,-18.4477233887 -13.8173618317,1.66676974297,-18.4299106598 -13.8893432617,1.66874659061,-18.4042816162 -13.9773435593,1.67273032665,-18.4006385803 -14.0603370667,1.67571151257,-18.388999939 -14.1203041077,1.67568325996,-18.3463840485 -14.1842775345,1.67665672302,-18.308763504 -14.2832870483,1.68164432049,-18.3181095123 -14.3242826462,1.68363428116,-18.3102931976 -14.388256073,1.68460822105,-18.2736701965 -14.4802570343,1.68859195709,-18.2710285187 -14.5642499924,1.69157326221,-18.2593860626 -14.64523983,1.69455313683,-18.2427501678 -14.7212228775,1.69753074646,-18.2191200256 -14.8042144775,1.70051109791,-18.2044830322 -14.8522157669,1.70250344276,-18.2046604156 -14.9412126541,1.7064858675,-18.1970176697 -15.0121908188,1.70846152306,-18.1663894653 -15.0811672211,1.70943653584,-18.1327667236 -15.1701622009,1.71341812611,-18.1231269836 -15.2671661377,1.71840274334,-18.1234760284 -15.3341398239,1.71937656403,-18.0858573914 -15.397154808,1.72337400913,-18.1040172577 -15.3420133591,1.70930755138,-17.9214992523 -15.3108949661,1.69824934006,-17.7679615021 -15.1957015991,1.67716538906,-17.5184898376 -15.2436599731,1.67613494396,-17.4618835449 -15.2305631638,1.66808521748,-17.3343276978 -15.2635097504,1.66505074501,-17.2617301941 -15.2834854126,1.66403412819,-17.227935791 -15.3164319992,1.66099977493,-17.1553401947 -15.3603887558,1.65996921062,-17.0957355499 -15.3903331757,1.6569340229,-17.0191478729 -15.4232807159,1.6539003849,-16.9475517273 -15.4392147064,1.64986169338,-16.8559761047 -15.4831724167,1.64883184433,-16.7973709106 -15.4501037598,1.6408008337,-16.706615448 -15.4710426331,1.63676476479,-16.6230316162 -15.4989881516,1.63373088837,-16.5474414825 -15.5099191666,1.62869215012,-16.4528694153 -15.5328617096,1.62565732002,-16.3722858429 -15.5427932739,1.62061941624,-16.278711319 -15.5347499847,1.61659741402,-16.2189292908 -15.5536899567,1.61256241798,-16.1353492737 -15.5896453857,1.61053216457,-16.0707511902 -15.6286029816,1.60950303078,-16.0091514587 -15.6585521698,1.60647130013,-15.9375658035 -15.6824989319,1.6034386158,-15.8609790802 -15.696436882,1.59940338135,-15.7734031677 -15.6893959045,1.59538269043,-15.7166233063 -15.6993322372,1.59134697914,-15.6260509491 -15.7092695236,1.5863121748,-15.5374727249 -15.7242097855,1.58227825165,-15.4528970718 -15.7481594086,1.57924687862,-15.3783111572 -15.7751102448,1.577216506,-15.3067235947 -15.7910547256,1.57318437099,-15.2261400223 -15.7840156555,1.57016468048,-15.1703624725 -15.8139696121,1.56813561916,-15.1027727127 -15.8339176178,1.56410455704,-15.0261898041 -15.8688764572,1.56307697296,-14.9635972977 -15.8858222961,1.55904555321,-14.884018898 -15.9157781601,1.55701768398,-14.8184242249 -15.9237518311,1.55600178242,-14.777639389 -15.9477033615,1.55297267437,-14.7060527802 -15.9776601791,1.55094492435,-14.640460968 -15.9996109009,1.54891562462,-14.5668792725 -16.0025501251,1.54388272762,-14.47631073 -16.0194988251,1.54085314274,-14.3997297287 -16.0354480743,1.53682386875,-14.3231458664 -16.033416748,1.53480708599,-14.2753639221 -16.0423603058,1.53077626228,-14.1917915344 -16.0593090057,1.52774751186,-14.1162109375 -16.0682544708,1.52371704578,-14.0326414108 -16.0862064362,1.52068901062,-13.9590587616 -16.0801429749,1.51465654373,-13.8634996414 -16.1141052246,1.51363158226,-13.8039064407 -16.0860595703,1.50861155987,-13.7361392975 -16.0970077515,1.50458264351,-13.6565675735 -16.0669307709,1.49654746056,-13.5430212021 -16.1549301147,1.50153255463,-13.5303907394 -12.9038181305,1.15394937992,-10.6733427048 -12.9057788849,1.14992809296,-10.6057701111 -12.7996721268,1.13588929176,-10.4472827911 -8.21879768372,0.651118516922,-6.52851915359 -8.22778606415,0.650110423565,-6.49293422699 -8.31480407715,0.654105186462,-6.47870922089 -8.33479881287,0.654098689556,-6.4511256218 -8.35779476166,0.654092788696,-6.42653369904 -8.37179470062,0.655090332031,-6.41673088074 -8.40179538727,0.656085550785,-6.3981294632 -8.43079662323,0.656080663204,-6.37853002548 -8.44878959656,0.656074166298,-6.3499417305 -8.47078609467,0.656068205833,-6.32435178757 -8.50278759003,0.65706372261,-6.30675172806 -8.51578712463,0.658061146736,-6.29595088959 -8.54478740692,0.658056139946,-6.27535867691 -8.56378269196,0.658050000668,-6.24776697159 -8.59178161621,0.659045100212,-6.22716665268 -8.62178230286,0.660040557384,-6.20855951309 -8.64377880096,0.660034835339,-6.18296766281 -8.67077732086,0.66102963686,-6.16037893295 -8.68377780914,0.661027133465,-6.14957618713 -8.71377754211,0.662022471428,-6.12997674942 -8.73777580261,0.662016987801,-6.10538673401 -8.7607717514,0.663011431694,-6.0797996521 -8.78576946259,0.663006186485,-6.05620574951 -8.81377029419,0.664001464844,-6.03560018539 -8.84477043152,0.664996862411,-6.0160036087 -8.85276794434,0.664993822575,-6.00120687485 -8.87776470184,0.664988517761,-5.97662115097 -8.91977310181,0.667985379696,-5.96600151062 -8.93676567078,0.666979193687,-5.93542432785 -8.95376014709,0.666973412037,-5.90682649612 -8.9887638092,0.668969273567,-5.88923072815 -9.02076530457,0.669964909554,-5.87062454224 -9.02876186371,0.669961869717,-5.8548374176 -9.06176376343,0.670957565308,-5.83623600006 -9.09376525879,0.671953082085,-5.81663799286 -9.11476230621,0.672947824001,-5.79004240036 -9.36086368561,0.693962097168,-5.91228532791 -9.16775989532,0.673937916756,-5.74285697937 -9.16575145721,0.672934234142,-5.72107172012 -9.18574810028,0.672928869724,-5.6934800148 -9.25776672363,0.677927792072,-5.69984769821 -9.2937707901,0.679923653603,-5.68224573135 -10.9804925919,0.836037993431,-6.67184972763 -10.8894338608,0.826021492481,-6.56634473801 -10.7803764343,0.814008593559,-6.47364282608 -10.745344162,0.808997094631,-6.40608501434 -10.7573318481,0.807989001274,-6.3674993515 -10.6272592545,0.793971180916,-6.24102210999 -10.5191965103,0.781955301762,-6.12853574753 -10.416135788,0.769940376282,-6.02103853226 -10.2910690308,0.756924569607,-5.90155363083 -10.2460422516,0.751918017864,-5.85279893875 -10.1379833221,0.739903986454,-5.74530172348 -10.0899505615,0.733893930912,-5.67376661301 -10.0399160385,0.726884067059,-5.602227211 -9.83281993866,0.70586591959,-5.43979978561 -9.77678489685,0.698856532574,-5.36626768112 -9.80778503418,0.700851976871,-5.34366893768 -9.64071369171,0.683840274811,-5.22701025009 -9.58167934418,0.67683172226,-5.15446949005 -9.53465080261,0.67082375288,-5.08793544769 -9.47261619568,0.663815498352,-5.01440286636 -9.41158294678,0.656807541847,-4.94187116623 -9.33654499054,0.648799300194,-4.86234855652 -9.28051948547,0.642794549465,-4.81260156631 -9.23649311066,0.636788129807,-4.75105810165 -9.19847011566,0.631781995296,-4.69251871109 -9.1274356842,0.624775052071,-4.61798715591 -9.06940746307,0.6177688241,-4.55045413971 -9.04539108276,0.613763988018,-4.50189208984 -9.03237915039,0.611759603024,-4.45833492279 -8.94934558868,0.603755176067,-4.39759874344 -8.9413356781,0.600751280785,-4.35802984238 -8.89731311798,0.595746457577,-4.299492836 -8.86229515076,0.591742157936,-4.24693822861 -8.82627677917,0.586738049984,-4.19438314438 -8.80826473236,0.583734452724,-4.15082120895 -8.76124286652,0.578730463982,-4.09327602386 -8.75923919678,0.577728927135,-4.07449960709 -8.75323200226,0.575726032257,-4.0379242897 -8.76322937012,0.575723528862,-4.00933790207 -8.79823589325,0.577721476555,-3.99273586273 -8.82823944092,0.578719258308,-3.97314310074 -8.83723735809,0.578716814518,-3.94356298447 -8.80422210693,0.57471382618,-3.89401268959 -8.81022167206,0.574712693691,-3.88021922112 -8.81121635437,0.57371032238,-3.84763789177 -8.79820823669,0.571707904339,-3.80807352066 -8.82221126556,0.572705864906,-3.78548669815 -8.84921455383,0.573703825474,-3.76488924026 -8.81420040131,0.569701552391,-3.71633124352 -8.8262014389,0.569700598717,-3.70553183556 -8.82419681549,0.568698525429,-3.67096614838 -8.82919406891,0.567696630955,-3.64038658142 -8.8722038269,0.570694804192,-3.62677764893 -8.87419986725,0.569692909718,-3.59420824051 -8.78917217255,0.560691297054,-3.52469062805 -8.88819599152,0.568689405918,-3.53603076935 -8.84918308258,0.564688682556,-3.50227928162 -8.88619041443,0.566686928272,-3.48567581177 -13.4064264297,0.959657430649,-5.35302591324 -13.4664258957,0.963649570942,-5.32841920853 -13.5314283371,0.967641711235,-5.30679798126 -13.5214099884,0.964634478092,-5.25323534012 -13.592420578,0.97063010931,-5.25740385056 -13.6084098816,0.970622718334,-5.2148194313 -13.6664085388,0.973614692688,-5.1882147789 -13.7114048004,0.975606918335,-5.15661525726 -13.7223930359,0.975599706173,-5.11203241348 -13.802397728,0.98059129715,-5.09341287613 -13.811384201,0.980584144592,-5.04783201218 -13.8363828659,0.981580257416,-5.03302764893 -13.8513717651,0.981573045254,-4.98944568634 -13.9533815384,0.988564014435,-4.97781467438 -13.9703702927,0.988556861877,-4.93522644043 -13.9653549194,0.987550199032,-4.88366031647 -14.0043487549,0.989542484283,-4.8480682373 -14.0523462296,0.99153470993,-4.81646251678 -14.075343132,0.993530750275,-4.79966497421 -14.1433448792,0.997522294521,-4.77504491806 -14.3053665161,1.01051104069,-4.78237199783 -14.2273349762,1.00250673294,-4.70485305786 -14.2413234711,1.00150001049,-4.66027116776 -14.3093242645,1.00649130344,-4.63365888596 -14.336315155,1.00748407841,-4.59307098389 -14.3643131256,1.00947988033,-4.57727003098 -14.4073085785,1.01147222519,-4.54266500473 -14.4383010864,1.01246476173,-4.50208330154 -14.5073022842,1.01745605469,-4.47546243668 -14.5372934341,1.01844871044,-4.43487596512 -14.6853094101,1.0294367075,-4.43221187592 -14.9323530197,1.05042386055,-4.48626422882 -14.6752872467,1.02742791176,-4.35385942459 -14.6792736053,1.02642178535,-4.30528306961 -14.7242689133,1.02841377258,-4.26868772507 -14.8012695312,1.03440451622,-4.24206781387 -12.7868747711,0.864490389824,-3.58477520943 -12.7618618011,0.861487805843,-3.53322577477 -12.7108469009,0.856488466263,-3.49647259712 -12.7128391266,0.855484962463,-3.45489096642 -12.6708230972,0.851483643055,-3.39934968948 -12.6668148041,0.849480569363,-3.35577750206 -12.6438035965,0.846478521824,-3.30622410774 -12.6587972641,0.847474634647,-3.26764512062 -12.6367864609,0.844472885132,-3.22007751465 -12.6267814636,0.843471944332,-3.19629645348 -12.6457767487,0.843467950821,-3.15871739388 -12.649769783,0.843464910984,-3.11813664436 -12.6897697449,0.845459759235,-3.08554959297 -12.6907625198,0.844457030296,-3.04397273064 -12.7237615585,0.846452355385,-3.010379076 -12.7517585754,0.848448038101,-2.9747941494 -12.7737588882,0.849445462227,-2.95998692513 -12.8147573471,0.852440357208,-2.92739462852 -12.8597574234,0.855434954166,-2.89678764343 -12.9337625504,0.860427737236,-2.87217140198 -13.0807762146,0.871415734291,-2.86451029778 -15.855173111,1.09923160076,-3.47523856163 -15.8531665802,1.09922909737,-3.44845700264 -15.9121618271,1.10322010517,-3.40985298157 -15.9501543045,1.10521245003,-3.36725306511 -16.0371551514,1.11120140553,-3.33363842964 -16.0681438446,1.11319410801,-3.28805017471 -16.118139267,1.11618566513,-3.24645090103 -16.1971378326,1.12117505074,-3.21083402634 -16.2201328278,1.12317085266,-3.19003009796 -16.2931308746,1.12816059589,-3.15241789818 -16.3351230621,1.13115262985,-3.10782599449 -16.511133194,1.14413452148,-3.09015440941 -16.4521121979,1.13813400269,-3.02462291718 -16.4440994263,1.13712978363,-2.97005629539 -16.480091095,1.1391222477,-2.92346906662 -16.5300922394,1.14311599731,-2.90665268898 -16.6180896759,1.14910435677,-2.87003040314 -16.6430797577,1.15009760857,-2.82045197487 -16.9451007843,1.17406868935,-2.82170438766 -16.7700691223,1.15907812119,-2.73623728752 -16.8640670776,1.16606581211,-2.69861459732 -17.0080699921,1.17704939842,-2.66995573044 -17.0420665741,1.17904412746,-2.64815425873 -16.9810466766,1.17404460907,-2.58262705803 -17.3450717926,1.20300924778,-2.58883810043 -17.2660522461,1.19501125813,-2.5203192234 -17.2530384064,1.19400775433,-2.46276116371 -17.3420333862,1.19999551773,-2.42114329338 -17.2990245819,1.19599699974,-2.38738083839 -17.352016449,1.19998788834,-2.33978462219 -17.3760070801,1.20098125935,-2.28820133209 -16.3869075775,1.12106668949,-2.09120845795 -16.1928806305,1.10408103466,-2.01274585724 -16.1068668365,1.09708583355,-1.94922935963 -16.0388507843,1.09108912945,-1.88870227337 -16.0478477478,1.09108686447,-1.86490881443 -15.9748325348,1.08509075642,-1.80438375473 -15.955821991,1.0830899477,-1.75182199478 -15.9698143005,1.08308577538,-1.70225155354 -15.9638061523,1.0820838213,-1.6516803503 -15.9287958145,1.07908463478,-1.5971313715 -15.9597902298,1.08107924461,-1.550542593 -16.0037879944,1.08407354355,-1.52973723412 -15.989780426,1.08307266235,-1.47817218304 -15.9787721634,1.08207130432,-1.42660915852 -16.009765625,1.08406591415,-1.37902581692 -16.0387592316,1.08606088161,-1.33144032955 -16.104757309,1.09105193615,-1.28782904148 -16.2027549744,1.09803962708,-1.24620485306 -16.1677474976,1.09504210949,-1.21744120121 -16.310749054,1.10602521896,-1.17879450321 -16.4807491302,1.11900520325,-1.14212822914 -18.8548660278,1.30975162983,-1.28223776817 -18.9238586426,1.31474041939,-1.22863137722 -19.0218505859,1.32272601128,-1.17601454258 -18.9678440094,1.31772994995,-1.14226126671 -9.6664056778,0.570736289024,-0.433910787106 -9.67041015625,0.570738852024,-0.404328852892 -9.6524143219,0.568743884563,-0.372767686844 -9.66442012787,0.569745659828,-0.343188405037 -9.66042327881,0.569749295712,-0.312618374825 -9.65742874146,0.568752765656,-0.283035427332 -9.65843105316,0.568754255772,-0.268244445324 -9.66243648529,0.56975710392,-0.237676352262 -9.65544128418,0.568761110306,-0.208093583584 -9.65044593811,0.568765044212,-0.177525281906 -9.66045093536,0.568767249584,-0.147943839431 -9.65545654297,0.568771243095,-0.117375940084 -9.65345859528,0.568773150444,-0.102585211396 -9.64846420288,0.567777276039,-0.0720183700323 -9.65346908569,0.567780137062,-0.0424364767969 -9.64047431946,0.566785097122,-0.012857677415 -9.63547992706,0.566789329052,0.0177080184221 -9.64548587799,0.567791700363,0.0472913980484 -9.64649105072,0.567795217037,0.0768725723028 -9.64049434662,0.566797852516,0.0926467999816 -9.63450050354,0.566802203655,0.122225195169 -9.63650608063,0.566805660725,0.151806339622 -9.63851165771,0.566809237003,0.182373657823 -9.63551712036,0.566813409328,0.211952626705 -9.62552261353,0.565818428993,0.241527289152 -9.62452888489,0.5658223629,0.271106630564 -9.62253284454,0.565824687481,0.286881357431 -9.62053775787,0.564828813076,0.316459625959 -9.62454414368,0.565832257271,0.34604242444 -9.62955093384,0.565835654736,0.376612067223 -9.61155605316,0.564841806889,0.40519207716 -9.62056255341,0.565844833851,0.435765236616 -9.62456703186,0.565846323967,0.450558573008 -9.61957263947,0.565851092339,0.48013433814 -9.61857891083,0.565855443478,0.51069945097 -9.61358547211,0.564860224724,0.540274381638 -9.61859226227,0.565863728523,0.569859683514 -9.61359882355,0.564868569374,0.599434375763 -9.60760593414,0.564873635769,0.629007935524 -9.59760951996,0.563877165318,0.643786489964 -9.60161685944,0.564880907536,0.673371076584 -9.6006231308,0.564885497093,0.703935801983 -9.6106300354,0.565888464451,0.733528614044 -9.60663700104,0.565893530846,0.764090061188 -9.60964393616,0.565897524357,0.793674647808 -9.59365177155,0.564904093742,0.822247266769 -9.59465503693,0.564906299114,0.838024795055 -9.59266281128,0.564911067486,0.867602467537 -9.58866977692,0.564916193485,0.897177100182 -9.59567737579,0.565919876099,0.927754759789 -9.57768535614,0.563926994801,0.956321001053 -9.5856924057,0.564930558205,0.986900806427 -9.58669948578,0.564935028553,1.0164835453 -9.58370304108,0.564937829971,1.0312691927 -9.58271121979,0.564942657948,1.06084883213 -9.58571815491,0.565947055817,1.09142208099 -9.59672641754,0.566950261593,1.12201011181 -9.58173465729,0.565957188606,1.15057885647 -9.58674240112,0.566961348057,1.1811568737 -9.58574581146,0.566963911057,1.19594633579 -9.56675434113,0.5649715662,1.22450530529 -9.5767621994,0.56697499752,1.25509428978 -9.5797700882,0.566979587078,1.2856695652 -9.57377815247,0.566985428333,1.31524050236 -9.56078720093,0.565992355347,1.34381008148 -9.56679439545,0.566996514797,1.37439274788 -9.56279945374,0.566999673843,1.38917589188 -9.56580734253,0.567004323006,1.41975259781 -9.56181526184,0.567010045052,1.4493278265 -9.55982398987,0.56701540947,1.47890758514 -9.56683158875,0.568019628525,1.51048147678 -9.55484104156,0.568026602268,1.53905189037 -9.5688495636,0.56902962923,1.57064402103 -9.54885482788,0.568035364151,1.58341526985 -9.55186271667,0.568040192127,1.61399459839 -9.56387138367,0.570043742657,1.6465703249 -9.54088020325,0.568052530289,1.67313861847 -9.55188941956,0.569056093693,1.70472669601 -9.54889774323,0.570062041283,1.73529243469 -9.53890228271,0.569066166878,1.74808645248 -9.54791069031,0.570070326328,1.78065741062 -9.54691982269,0.570075809956,1.81024301052 -9.54592895508,0.571081578732,1.8408151865 -9.54393863678,0.571087479591,1.87138473988 -9.55094623566,0.57209187746,1.90296733379 -9.53395652771,0.571100115776,1.93053472042 -9.54096126556,0.572101831436,1.94732308388 -9.52697086334,0.57110953331,1.97489857674 -9.53098106384,0.57211458683,2.0064740181 -9.5139913559,0.571122944355,2.03403973579 -9.53099918365,0.573125898838,2.06762933731 -9.5040102005,0.571135938168,2.09318995476 -9.51601886749,0.573139667511,2.12577939034 -9.53002262115,0.574140429497,2.14456653595 -9.53203105927,0.575145721436,2.17515301704 -9.51004314423,0.573155164719,2.20171427727 -9.50305271149,0.573162138462,2.23128461838 -9.50106334686,0.574168324471,2.26185798645 -9.50807189941,0.575172960758,2.29344940186 -9.50308227539,0.575179815292,2.32401371002 -9.498087883,0.575183451176,2.3378071785 -9.49509811401,0.575189948082,2.36837887764 -9.5001077652,0.576195240021,2.40095233917 -9.50011730194,0.577201128006,2.43153595924 -9.48712825775,0.576209366322,2.46009898186 -9.48813819885,0.577215075493,2.49068713188 -9.50014209747,0.578216195107,2.5094769001 -9.49215221405,0.578223645687,2.53904604912 -9.48516368866,0.578230917454,2.56861877441 -9.4911737442,0.579236030579,2.60120153427 -9.47018432617,0.578245580196,2.62677383423 -9.47219562531,0.579251587391,2.65934228897 -9.47220611572,0.58025765419,2.68992996216 -9.46821117401,0.580261468887,2.7047150135 -9.47722148895,0.581266343594,2.73928642273 -9.4772310257,0.582272589207,2.77086305618 -9.46124267578,0.581281483173,2.79744076729 -9.47725200653,0.583285212517,2.83401799202 -9.46726322174,0.583293139935,2.86259460449 -9.45526981354,0.582298398018,2.87537336349 -9.46827888489,0.584302604198,2.9109544754 -9.45929050446,0.584310412407,2.93953585625 -9.44630336761,0.584319114685,2.96809983253 -9.45131397247,0.585324823856,3.00167608261 -9.45232391357,0.586331009865,3.03326249123 -9.45033454895,0.586337864399,3.06483578682 -9.44933986664,0.587341248989,3.08062314987 -9.45235061646,0.588347375393,3.11419439316 -9.44136333466,0.588355779648,3.14276838303 -9.44137382507,0.588362276554,3.17435336113 -9.43138599396,0.588370680809,3.20391917229 -9.43539619446,0.589376628399,3.23749828339 -9.43140792847,0.590383887291,3.26807975769 -9.42841339111,0.590387821198,3.28385972977 -9.42642498016,0.591394782066,3.31543850899 -9.43343544006,0.592400252819,3.35002207756 -9.42644786835,0.593408226967,3.38059186935 -9.41646003723,0.593416750431,3.4101600647 -9.42147064209,0.594422757626,3.44473719597 -9.42448234558,0.595428943634,3.47831869125 -9.42148780823,0.595432758331,3.49311304092 -9.42049980164,0.596439778805,3.52568912506 -9.42451000214,0.597445905209,3.56026554108 -9.4115228653,0.597455143929,3.58883428574 -9.41953372955,0.599460721016,3.62540745735 -9.39954853058,0.598471105099,3.65097880363 -9.41055297852,0.59947270155,3.67177033424 -9.41156387329,0.600479424,3.70534873009 -9.40557670593,0.601487338543,3.73592972755 -9.40758800507,0.602494001389,3.77050256729 -9.39360141754,0.602503597736,3.79906797409 -9.39561271667,0.603510200977,3.832654953 -9.38562679291,0.603519022465,3.86222934723 -9.3946313858,0.604520976543,3.88301634789 -9.38864326477,0.60552918911,3.91458845139 -9.38765621185,0.606536507607,3.94816327095 -9.38766765594,0.60754352808,3.98174405098 -9.39367866516,0.608549654484,4.01832199097 -9.38369178772,0.608558535576,4.04789924622 -9.38070487976,0.6095662117,4.08047914505 -9.38370990753,0.610569298267,4.09926366806 -9.38172245026,0.611576914787,4.13283824921 -9.37673568726,0.612585127354,4.16540956497 -9.36974811554,0.612593472004,4.19599437714 -9.37176036835,0.613600492477,4.23156929016 -9.37477207184,0.615607321262,4.26813983917 -9.37077903748,0.615611553192,4.28293657303 -9.36479187012,0.616620063782,4.31550550461 -9.36980342865,0.617626428604,4.35209035873 -9.36381721497,0.618634939194,4.38466119766 -9.36382961273,0.619642198086,4.41924381256 -9.35884284973,0.620650708675,4.45280981064 -9.36385536194,0.621657192707,4.4903883934 -9.35686206818,0.621662080288,4.50418138504 -9.35088729858,0.623678147793,4.57233190536 -9.34590148926,0.624686658382,4.60590219498 -9.34591388702,0.625694155693,4.64147996902 -9.33992767334,0.626702785492,4.67405796051 -9.33993434906,0.62770652771,4.69184780121 -9.34494590759,0.628713190556,4.73042392731 -9.33895969391,0.629721999168,4.76399278641 -9.33597373962,0.630729913712,4.79758071899 -9.34398460388,0.63273614645,4.83815717697 -9.3379983902,0.633744955063,4.87172937393 -9.32201480865,0.633755624294,4.90029716492 -9.33901786804,0.635756254196,4.92709350586 -9.32803249359,0.635765910149,4.95767116547 -9.32704639435,0.637773871422,4.99424409866 -9.32405948639,0.638782024384,5.02882766724 -9.31707382202,0.63979113102,5.06239843369 -9.31408691406,0.6407995224,5.09797334671 -9.32309913635,0.642805695534,5.14054632187 -9.31510734558,0.642811000347,5.15433835983 -9.31311988831,0.643819272518,5.19091129303 -9.31713294983,0.645826339722,5.23049068451 -9.30114936829,0.645837187767,5.25906467438 -9.30216217041,0.647844851017,5.29763841629 -9.30517482758,0.648852169514,5.33721542358 -9.30318927765,0.65086042881,5.3737950325 -9.29819583893,0.650865256786,5.38958644867 -9.30420780182,0.652872025967,5.43116521835 -9.28722476959,0.65288323164,5.4597363472 -9.30023670197,0.655888855457,5.50630998611 -9.29724979401,0.656897366047,5.54288911819 -9.27826690674,0.656908988953,5.57045936584 -9.28727149963,0.657911300659,5.59524965286 -9.29428482056,0.660917878151,5.63783407211 -9.28030014038,0.660928606987,5.66840744019 -9.27631473541,0.661937355995,5.70498514175 -9.27632904053,0.663945555687,5.74455881119 -9.26634407043,0.664955615997,5.77813005447 -9.28635406494,0.667959809303,5.82971572876 -9.27736377716,0.667965710163,5.84449625015 -9.26437950134,0.66897636652,5.87607145309 -9.27039241791,0.670983314514,5.91965103149 -9.26240730286,0.671992897987,5.95423078537 -9.26242160797,0.674001216888,5.99480438232 -9.25743579865,0.675010442734,6.03237533569 -9.26644802094,0.678016781807,6.07796287537 -9.2444601059,0.676025271416,6.08473777771 -9.26347064972,0.68002974987,6.1373257637 -9.25248527527,0.681040108204,6.1709022522 -9.24550151825,0.682049751282,6.20747566223 -9.23751735687,0.683059811592,6.24404382706 -9.24652957916,0.686066150665,6.29063177109 -9.26753902435,0.690070390701,6.34621667862 -9.24055194855,0.688079893589,6.34899568558 -9.26056194305,0.692084372044,6.40457677841 -9.23158168793,0.691098213196,6.42615222931 -9.23459625244,0.693106114864,6.47072649002 -9.21961307526,0.694117605686,6.50329303741 -9.21562862396,0.695126771927,6.54286956787 -9.43359088898,0.71708792448,6.71474313736 -9.22764778137,0.699137091637,6.61523962021 -9.21467876434,0.702156484127,6.69139671326 -9.40065479279,0.722128152847,6.86704158783 -9.21070861816,0.706174314022,6.77554702759 -9.13374710083,0.701202452183,6.78588008881 -9.19674777985,0.7101983428,6.87448883057 -9.19176292419,0.711207985878,6.91506290436 -9.19277858734,0.713216483593,6.96063518524 -9.14080429077,0.710235357285,6.96619653702 -9.163813591,0.715239405632,7.02778244019 -9.18181705475,0.718240082264,7.06357860565 -8.94588279724,0.696295499802,6.92908334732 -6.55941438675,0.45878046751,5.15580606461 -6.56742954254,0.460787951946,5.19438791275 -6.50945854187,0.456808269024,5.18096256256 -6.54946660995,0.461809635162,5.24554347992 -6.53048753738,0.461822420359,5.26312160492 -6.47850751877,0.457837432623,5.23889064789 -6.48552274704,0.459845215082,5.2774682045 -6.4475479126,0.457861959934,5.2800359726 -6.45156335831,0.459870129824,5.31562376022 -6.40459060669,0.45688855648,5.31019496918 -6.31862688065,0.448915094137,5.27374124527 -6.36663341522,0.455914825201,5.34632921219 -6.38163805008,0.458916395903,5.3751244545 -6.37765598297,0.459926277399,5.4047088623 -6.37767314911,0.461935520172,5.43828725815 -6.38268852234,0.463943660259,5.47587156296 -6.39070320129,0.465951025486,5.51546621323 -6.34273195267,0.462970227003,5.51001644135 -6.35873651505,0.465971440077,5.53982067108 -6.34375667572,0.465983778238,5.56139326096 -6.30478286743,0.464000850916,5.56196260452 -6.2638092041,0.461018353701,5.56053161621 -6.25382947922,0.462029963732,5.58709526062 -6.20385742188,0.458049118519,5.57667064667 -6.1958770752,0.459060162306,5.60424375534 -6.22487831116,0.463058680296,5.64605569839 -6.19790220261,0.462073713541,5.65761566162 -6.20491743088,0.465081572533,5.69820308685 -6.22892951965,0.469086050987,5.75479078293 -6.20295286179,0.469100624323,5.76636457443 -6.19297218323,0.469112128019,5.79293680191 -6.16799545288,0.469126343727,5.80452013016 -6.13401222229,0.466138035059,5.79129552841 -6.18801736832,0.474136501551,5.87689208984 -6.15904140472,0.473151981831,5.88645553589 -6.19205093384,0.478154569864,5.95305109024 -6.17807149887,0.479166716337,5.97563409805 -6.17109107971,0.480177730322,6.0062046051 -6.18309688568,0.482179999352,6.03599834442 -6.17111682892,0.483191668987,6.06058454514 -6.15213871002,0.483204960823,6.07916069031 -6.15715551376,0.486213594675,6.12173652649 -6.14817523956,0.487224876881,6.15031528473 -6.14919233322,0.489234149456,6.18889665604 -6.15020942688,0.491243362427,6.22748041153 -6.15521717072,0.493247061968,6.25127410889 -6.14823675156,0.494258075953,6.28284931183 -6.1502532959,0.497266948223,6.32243967056 -6.15127086639,0.499276518822,6.36301136017 -6.11929607391,0.49829235673,6.36859083176 -6.11331558228,0.499303340912,6.40216207504 -6.1213312149,0.50331133604,6.44974470139 -6.13533687592,0.505313098431,6.483543396 -6.11335945129,0.505327105522,6.50012016296 -6.10837841034,0.5073376894,6.53470039368 -6.11339521408,0.510346293449,6.58028078079 -6.08142089844,0.508362531662,6.58685064316 -6.07344055176,0.510373651981,6.61843252182 -6.09844350815,0.514373481274,6.66622304916 -6.08946323395,0.515384793282,6.696808815 -6.08148288727,0.517396092415,6.72938680649 -6.08649969101,0.520404577255,6.77597236633 -6.07851982117,0.522416055202,6.80954456329 -6.0575428009,0.522430002689,6.82812166214 -6.06455898285,0.525438070297,6.87770843506 -6.06756687164,0.527442395687,6.90249681473 -6.07758283615,0.530450105667,6.95707464218 -8.96586608887,0.881866931915,10.2594890594 -8.97887992859,0.887873828411,10.3380718231 -8.9728975296,0.890884578228,10.3956489563 -8.97491455078,0.894893825054,10.4632253647 -8.96792411804,0.895899891853,10.4870176315 -8.26611995697,0.814053654671,9.73840141296 -8.19715499878,0.809077501297,9.71895980835 -8.92798423767,0.903937041759,10.6387395859 -8.08021831512,0.802120685577,9.70209026337 -8.02025127411,0.799142718315,9.69165229797 -7.95128631592,0.794166624546,9.67021083832 -8.00728034973,0.803159832954,9.7670211792 -7.85533666611,0.787200987339,9.64555358887 -7.82436227798,0.787217140198,9.66912078857 -7.71840715408,0.778248608112,9.5996761322 -7.77640962601,0.789246499538,9.73226833344 -3.43257117271,0.238154023886,4.39850711823 -3.4105963707,0.23716840148,4.39808654785 -3.40460824966,0.23717482388,4.4048666954 -3.40162777901,0.238184958696,4.42746639252 -7.39160633087,0.761379480362,9.584856987 -7.34463644028,0.758399009705,9.58542537689 -7.30166530609,0.757417619228,9.5909948349 -7.25469589233,0.75443726778,9.5915594101 -7.20371818542,0.750452637672,9.55533885956 -7.16074705124,0.748471319675,9.55990791321 -7.09978103638,0.74449378252,9.54047393799 -7.08380365372,0.746506989002,9.58104705811 -7.11381292343,0.754510700703,9.68263912201 -6.97186946869,0.739549875259,9.55417728424 -6.92888975143,0.73556381464,9.52695560455 -6.90191507339,0.735579192638,9.55153179169 -6.85094642639,0.732599556446,9.5431022644 -6.80297803879,0.730619668961,9.54065895081 -6.78100204468,0.731633961201,9.57124137878 -6.72403526306,0.727655827999,9.55480289459 -6.68306446075,0.72567397356,9.55838108063 -6.62508964539,0.719691157341,9.50914764404 -6.5851187706,0.718709409237,9.51471805573 -6.58513689041,0.722719371319,9.57730102539 -6.50817584991,0.715745151043,9.52886581421 -6.45320940018,0.712766587734,9.51243114471 -6.50121450424,0.723766684532,9.64602279663 -6.43224287033,0.71578592062,9.576795578 -6.33828639984,0.706815123558,9.50036239624 -6.29131793976,0.704834997654,9.49492645264 -6.25134754181,0.70285320282,9.49849891663 -6.20337963104,0.699873387814,9.49106025696 -6.17240619659,0.699889600277,9.50664234161 -6.12643766403,0.69790905714,9.5002155304 -6.11345052719,0.697916865349,9.51299858093 -6.05348587036,0.693939328194,9.48456764221 -6.03251028061,0.694953858852,9.51713943481 -5.96854686737,0.689977109432,9.48170661926 -5.94157266617,0.689992666245,9.50328731537 -5.92559623718,0.692006111145,9.54386043549 -5.91261863708,0.69501888752,9.58844184875 -5.91062831879,0.697024285793,9.61823177338 -5.89665126801,0.699037432671,9.66280651093 -5.89267110825,0.703048348427,9.7233877182 -5.82071065903,0.697073459625,9.67394733429 -5.86071825027,0.708075344563,9.80753993988 -5.84874010086,0.711087942123,9.85612201691 -5.85175800323,0.716097474098,9.93070316315 -5.82377529144,0.714108169079,9.91749382019 -5.85278606415,0.72311258316,10.0380754471 -5.84780693054,0.728123724461,10.1006574631 -5.84782552719,0.732133865356,10.1722431183 -5.84384536743,0.737144947052,10.238820076 -5.8448638916,0.742154836655,10.3134069443 -5.88086366653,0.751152694225,10.4142017365 -5.84989118576,0.751169085503,10.4337825775 -5.85091018677,0.756179273129,10.5123586655 -5.86992359161,0.765185594559,10.6229457855 -5.87994003296,0.772193849087,10.7195253372 -5.96793365479,0.7921859622,10.9571304321 -5.89997243881,0.787210345268,10.914691925 -5.88798522949,0.787217855453,10.9324836731 -5.88700485229,0.793228209019,11.0110683441 -5.95600366592,0.811224222183,11.2206707001 -5.85805082321,0.800254583359,11.1212291718 -5.87806415558,0.809260845184,11.2428150177 -5.86208820343,0.813274562359,11.2983884811 -5.83811426163,0.815289795399,11.3379659653 -5.8521194458,0.820291876793,11.4067659378 -5.84014177322,0.824304640293,11.4703454971 -5.86115550995,0.83431071043,11.5999307632 -5.85017776489,0.839323401451,11.6685066223 -5.84119987488,0.84433555603,11.7410869598 -5.86821079254,0.855340242386,11.885679245 -5.86822032928,0.858345508575,11.9324674606 -5.85124444962,0.862359285355,11.9910488129 -5.86525964737,0.871366798878,12.1146316528 -5.86128044128,0.878378033638,12.2032089233 -5.85630083084,0.884389340878,12.2887954712 -5.86431789398,0.892398118973,12.4043779373 -5.87833309174,0.902405679226,12.5339612961 -5.79236745834,0.890428364277,12.4017381668 -3.5766685009,0.667215645313,10.2807588577 -3.54169940948,0.666233003139,10.2833375931 -2.63728070259,0.548569738865,9.02292633057 -2.62429499626,0.548577487469,9.03071689606 -2.59232497215,0.547594070435,9.0243024826 -2.4954161644,0.54464417696,9.00304412842 -2.29672431946,0.592806816101,9.66905212402 -3.14653301239,0.93467515707,13.8547735214 -3.16654777527,0.958681881428,14.148355484 -3.41049289703,1.0646443367,15.4479827881 -3.23162007332,1.06071615219,15.4415035248 -2.78177952766,0.902814388275,13.521024704 -3.09870219231,1.04676282406,15.2836589813 -3.06973171234,1.05477893353,15.3862419128 -2.98377895355,1.03880608082,15.2058153152 -2.90882253647,1.02783119678,15.073392868 -2.85286068916,1.02385246754,15.0389671326 -2.84487342834,1.03085923195,15.1257581711 -2.83989572525,1.04887068272,15.3613443375 -2.76194024086,1.03589606285,15.2049236298 -2.78895258904,1.06990134716,15.6275148392 -2.7569835186,1.07791793346,15.7340936661 -2.70701932907,1.07693791389,15.7346792221 -2.69903230667,1.08494472504,15.838467598 -2.62207698822,1.07196986675,15.6830463409 -2.57411241531,1.07298958302,15.6986265182 -2.53814435005,1.07900702953,15.7872085571 -3.39689826965,1.54185199738,21.4879055023 -3.33793735504,1.54687404633,21.5574817657 -3.27297830582,1.54789710045,21.5850601196 -3.25999259949,1.55890464783,21.7238540649 -3.20203113556,1.56492638588,21.8044319153 -3.13507270813,1.5649497509,21.8240127563 -3.0661149025,1.56497335434,21.8295917511 -3.00215530396,1.56799614429,21.8701705933 -2.94019508362,1.57101845741,21.9267520905 -2.87323665619,1.57304155827,21.9493312836 -2.84325647354,1.57605266571,21.9911212921 -2.77529811859,1.57607603073,22.0057010651 -2.70933938026,1.57809889317,22.0372810364 -2.64138126373,1.57912230492,22.0548610687 -2.57042431831,1.57814621925,22.0514392853 -2.500467062,1.57716989517,22.0530185699 -2.42950987816,1.57619380951,22.0445995331 -2.39653038979,1.57720518112,22.0633888245 -2.32857251167,1.57922852039,22.0849666595 -2.26161408424,1.58025145531,22.1095523834 -2.19265651703,1.58027482033,22.1221313477 -2.1256980896,1.58229768276,22.1477165222 -2.05674052238,1.58332109451,22.1642951965 -2.02276134491,1.58433270454,22.1770858765 -1.95280396938,1.58335614204,22.1746673584 -1.88284683228,1.58337962627,22.1822452545 -1.81388914585,1.58340275288,22.18983078 -1.74593114853,1.58542573452,22.2164115906 -1.67597389221,1.58544909954,22.2159938812 -1.60501694679,1.58447277546,22.2105731964 -1.57003831863,1.58448445797,22.2103652954 -1.50208044052,1.58550727367,22.2369499207 -1.430123806,1.58353090286,22.2095298767 -1.35816729069,1.58155465126,22.1861076355 -1.28821003437,1.57957780361,22.175693512 -1.21925234795,1.58060061932,22.1872787476 -1.20326781273,1.60860872269,22.5410709381 -1.13930869102,1.61963069439,22.6716556549 -1.0673520565,1.61765420437,22.6572380066 -0.99039721489,1.60867857933,22.5398178101 -0.919440150261,1.60670173168,22.5224056244 -0.847483754158,1.60572516918,22.5089836121 -0.776526808739,1.60374832153,22.4955692291 -0.741548120975,1.60475981236,22.5003623962 -0.67059135437,1.60378289223,22.4959449768 -0.599634468555,1.6028059721,22.4815292358 -0.526678323746,1.59582936764,22.4011116028 -0.456721097231,1.59685218334,22.4106960297 -0.385764330626,1.59487521648,22.3892784119 -0.315807044506,1.59489786625,22.3838653564 -0.279828935862,1.59290957451,22.3666534424 -0.209871679544,1.59293222427,22.3612422943 -0.139914438128,1.59195482731,22.3508281708 -0.0689578130841,1.59097766876,22.3354072571 --0.00799494236708,1.59200263023,20.8569488525 --0.0729538351297,1.59102416039,20.8485393524 --0.137912675738,1.58904588223,20.8241252899 --0.170891746879,1.58805680275,20.8029155731 --0.23585061729,1.58807837963,20.8045024872 --0.30080935359,1.58609986305,20.779088974 --0.365768164396,1.5851213932,20.7736740112 --0.431726366282,1.5851432085,20.7702579498 --0.496685177088,1.58516454697,20.7698459625 --0.561643898487,1.58418595791,20.7544288635 --0.593623459339,1.58319652081,20.7392253876 --0.658582210541,1.58321785927,20.7328109741 --0.724540650845,1.58423948288,20.7503967285 --0.789499402046,1.58326077461,20.7369823456 --0.85545784235,1.58528220654,20.7585697174 --0.920416593552,1.585303545,20.7471561432 --0.985375404358,1.58532464504,20.7417430878 --1.01835489273,1.58633518219,20.7575397491 --1.08331346512,1.58535647392,20.7461261749 --1.14827239513,1.58537757397,20.7417144775 --1.21523034573,1.58839905262,20.7623004913 --1.28118884563,1.58842027187,20.7678852081 --1.34814703465,1.59044158459,20.7864723206 --1.38012671471,1.5904519558,20.7782688141 --1.44508552551,1.59047293663,20.7698554993 --1.51004445553,1.59049379826,20.7644462585 --1.64196133614,1.59153580666,20.7656173706 --1.70891964436,1.59355700016,20.782207489 --1.77487814426,1.593577981,20.7837963104 --1.80885696411,1.59458851814,20.7925891876 --1.87581551075,1.59660947323,20.8101806641 --1.94177412987,1.59763038158,20.8117694855 --2.00973176956,1.59965157509,20.8253536224 --2.07769012451,1.6026725769,20.8519496918 --2.14464831352,1.60269343853,20.8545360565 --2.21260619164,1.60471451283,20.8671226501 --2.24458622932,1.60472452641,20.8639240265 --2.31454348564,1.60774588585,20.8895072937 --2.38050222397,1.60876643658,20.8901023865 --2.45245909691,1.61278796196,20.9356918335 --2.51841759682,1.61280858517,20.9232769012 --2.58837509155,1.61582958698,20.9528694153 --2.62235450745,1.61684000492,20.9576663971 --2.69031238556,1.61886072159,20.9652557373 --2.75927019119,1.61988151073,20.9758434296 --2.82822823524,1.62290227413,20.994436264 --2.89818572998,1.62492322922,21.0090255737 --2.96914291382,1.62794423103,21.034614563 --3.03910040855,1.62996506691,21.0502052307 --3.07207989693,1.62997508049,21.0470027924 --3.1420378685,1.63299584389,21.0645961761 --3.21299505234,1.63501679897,21.0821838379 --3.28295278549,1.63703751564,21.0927753448 --3.35690903664,1.6410588026,21.1313667297 --3.42586731911,1.64307916164,21.137960434 --3.49382567406,1.64409935474,21.136554718 --3.53380298615,1.64711046219,21.168346405 --3.59976196289,1.64713025093,21.1539402008 --3.66971969604,1.64915060997,21.1645336151 --3.74067735672,1.65117108822,21.1761245728 --3.81063508987,1.65219151974,21.1807155609 --3.88459181786,1.65621232986,21.2093086243 --3.95255041122,1.65723216534,21.206905365 --3.99252772331,1.65924310684,21.2336978912 --4.06548452377,1.66226387024,21.2522926331 --4.13644218445,1.66428399086,21.2598838806 --4.20839977264,1.6663043499,21.2724781036 --4.28235626221,1.66932499409,21.2930698395 --4.35531330109,1.67234551907,21.3086624146 --4.39429140091,1.67535603046,21.3304634094 --4.46524906158,1.67637610435,21.3320541382 --4.54320526123,1.68139708042,21.3706512451 --4.61516284943,1.68241727352,21.3772449493 --4.68811988831,1.68543744087,21.3888397217 --4.7600774765,1.68745732307,21.3954334259 --4.8340344429,1.6894774437,21.411031723 --4.87601184845,1.69348847866,21.4378242493 --4.9459695816,1.69350802898,21.4314193726 --5.01892709732,1.6955280304,21.4390125275 --5.09588336945,1.69954848289,21.4636096954 --5.16584205627,1.70056772232,21.4602069855 --5.24379825592,1.70458829403,21.4848022461 --5.31575536728,1.70560789108,21.4843959808 --5.35273456573,1.7076177597,21.4901943207 --5.42769193649,1.70963764191,21.5037937164 --5.50964641571,1.71465873718,21.5413894653 --5.59759950638,1.72168064117,21.6009864807 --5.68855142593,1.72970294952,21.6675777435 --5.72452116013,1.71871638298,21.5321788788 --5.69951868057,1.69971644878,21.3029727936 --5.75848054886,1.69673371315,21.2545681 --5.82843923569,1.69775247574,21.249168396 --5.90939474106,1.70277297497,21.2797622681 --6.00134658813,1.70979511738,21.3473567963 --6.07630395889,1.71281445026,21.3569564819 --6.16025876999,1.71783518791,21.3945522308 --6.19623804092,1.71884465218,21.3943538666 --5.63138914108,1.52576589584,19.2229194641 --5.68735170364,1.5247824192,19.1895141602 --5.70732593536,1.51279330254,19.0381126404 --5.74329519272,1.50580668449,18.939704895 --5.82025194168,1.51082623005,18.9783039093 --5.86221981049,1.50584053993,18.9018974304 --5.81222438812,1.48283684254,18.6376934052 --5.8601899147,1.47985208035,18.5852890015 --5.86516904831,1.46486055851,18.4008865356 --5.88914203644,1.45487189293,18.275478363 --5.92511081696,1.44888520241,18.1900730133 --5.95508241653,1.44189751148,18.0896701813 --5.97506666183,1.43890440464,18.0534648895 --6.03202962875,1.4389206171,18.0350627899 --6.09699010849,1.44193804264,18.0396614075 --6.13895845413,1.43795180321,17.9782600403 --6.21691513062,1.44297111034,18.0188541412 --6.2508854866,1.43698358536,17.9354553223 --6.29185342789,1.43299734592,17.8700466156 --6.32883262634,1.43600666523,17.8838443756 --6.37479972839,1.43302083015,17.8374481201 --6.41176843643,1.42803382874,17.7620391846 --6.46473312378,1.42704904079,17.7346401215 --6.53069400787,1.43006622791,17.740234375 --6.61564922333,1.43708598614,17.7968349457 --6.6906080246,1.44210422039,17.8284397125 --6.72358798981,1.44311273098,17.8282318115 --6.76055765152,1.43812537193,17.7588348389 --6.81252288818,1.43714022636,17.7254295349 --6.88948106766,1.44315850735,17.7590312958 --6.96343946457,1.44717645645,17.7836341858 --7.02340221405,1.44819223881,17.7702293396 --7.07037878036,1.45220255852,17.8070316315 --7.11434650421,1.44921588898,17.7546310425 --7.16131353378,1.447229743,17.7102298737 --7.2102804184,1.44624376297,17.6708297729 --7.27924013138,1.44926059246,17.6784248352 --7.3601975441,1.45527887344,17.7180309296 --7.44615316391,1.4612981081,17.7636260986 --7.46313858032,1.4593038559,17.728433609 --7.52210235596,1.46031904221,17.7120323181 --7.55307435989,1.45433044434,17.6286258698 --7.66202306747,1.46635246277,17.727230072 --7.71298980713,1.46536624432,17.6938343048 --7.74296188354,1.45937716961,17.6104297638 --7.74794101715,1.44838476181,17.4710235596 --7.81891107559,1.4583978653,17.5568294525 --7.92486143112,1.46841907501,17.6444339752 --7.9648308754,1.46543133259,17.5840320587 --8.08377742767,1.4784539938,17.6986408234 --8.14574146271,1.47946918011,17.6852397919 --8.20170593262,1.48048329353,17.6608428955 --8.29267024994,1.49249887466,17.7816467285 --8.39362239838,1.50151884556,17.8522567749 --8.48857688904,1.50953805447,17.9068622589 --8.51954841614,1.50454866886,17.8254566193 --8.64849376678,1.51857221127,17.9490661621 --8.66846847534,1.51158118248,17.8456611633 --8.71143817902,1.50959312916,17.7912635803 --8.75341701508,1.51160180569,17.8060665131 --8.81238174438,1.5126157999,17.7846698761 --8.75438022614,1.49061453342,17.5282592773 --8.83133983612,1.49463069439,17.5438652039 --8.91029930115,1.49964725971,17.5614681244 --8.99725627899,1.50566470623,17.5950737 --9.08021450043,1.51068150997,17.6196784973 --9.09520053864,1.50868654251,17.5814819336 --9.13817024231,1.50569808483,17.5280818939 --9.1771402359,1.50270903111,17.4686832428 --9.25909996033,1.50772547722,17.4892864227 --9.3410577774,1.51274192333,17.50989151 --9.36803245544,1.50775122643,17.4274902344 --9.33003520966,1.49574935436,17.2922897339 --9.49896812439,1.51677668095,17.4719009399 --9.55293560028,1.51678919792,17.4395046234 --9.69887638092,1.5328130722,17.5751209259 --9.73984718323,1.52982389927,17.5177230835 --9.80681037903,1.53183794022,17.5083293915 --9.82778644562,1.5258461237,17.415927887 --9.77379322052,1.51184213161,17.2567195892 --10.000711441,1.54187583923,17.528345108 --10.0606775284,1.54288864136,17.5049533844 --10.0216712952,1.52688932419,17.3105449677 --11.4072647095,1.75406372547,19.5613250732 --11.4502363205,1.75107371807,19.493932724 --11.519200325,1.75208675861,19.469537735 --11.5421857834,1.75109195709,19.4393424988 --11.599152565,1.75010347366,19.3959503174 --11.6621179581,1.75111567974,19.3615550995 --11.7130880356,1.74912643433,19.3081626892 --11.7820510864,1.75013911724,19.2837696075 --11.8610134125,1.75315308571,19.2753791809 --11.8869981766,1.75215828419,19.2501831055 --11.9409666061,1.75116920471,19.201789856 --11.9879369736,1.74917924404,19.1413917542 --12.0559015274,1.75019145012,19.1150016785 --12.1118707657,1.75020229816,19.0706100464 --12.1488437653,1.74621093273,18.9962158203 --12.1718206406,1.74021780491,18.9008197784 --12.1968069077,1.73922276497,18.8736209869 --12.2627716064,1.74023461342,18.8442268372 --12.3177404404,1.74024498463,18.7988357544 --12.3617124557,1.73725414276,18.7364425659 --12.4166812897,1.73726439476,18.6920528412 --12.4466581345,1.7322717905,18.6096572876 --12.4566383362,1.72527706623,18.4972553253 --12.4176416397,1.71427464485,18.3760471344 --12.4286222458,1.70727992058,18.2676486969 --12.4336051941,1.69928443432,18.1502456665 --12.418592453,1.6882866621,18.0058422089 --12.4155788422,1.67929029465,17.881444931 --12.4155626297,1.67129433155,17.7600402832 --12.3835630417,1.66229271889,17.6558380127 --12.3755493164,1.65229582787,17.525434494 --12.3765325546,1.64429986477,17.4090309143 --12.368519783,1.63530278206,17.2826309204 --12.357506752,1.62530553341,17.1522293091 --12.3624897003,1.61830997467,17.0448284149 --12.3624744415,1.61031377316,16.9314250946 --12.3294754028,1.60231220722,16.8302192688 --12.3204622269,1.59331512451,16.7078208923 --12.3174467087,1.58531856537,16.5934181213 --12.3114337921,1.57632172108,16.4760169983 --12.2964220047,1.56732404232,16.3476142883 --12.2784109116,1.55732595921,16.2162075043 --12.2633991241,1.54732823372,16.0898036957 --12.241396904,1.54132783413,16.0085983276 --8.96924304962,1.07099628448,11.6416311264 --8.96922683716,1.06600165367,11.5662317276 --9.00420093536,1.06601059437,11.5358352661 --9.04417324066,1.06702005863,11.5114364624 --9.09814167023,1.06903076172,11.5050420761 --12.3452777863,1.51336061954,15.5242118835 --12.4572410583,1.52537357807,15.613026619 --12.5532007217,1.53238666058,15.6326465607 --9.15306949615,1.05905473232,11.3126316071 --9.19604206085,1.06006419659,11.2932405472 --12.6981191635,1.53141117096,15.5094718933 --12.852063179,1.54642939568,15.5971012115 --12.9210386276,1.55243778229,15.6299114227 --12.8930311203,1.54143822193,15.4955043793 --13.0109863281,1.55045282841,15.5371255875 --13.1409378052,1.5614682436,15.5917482376 --13.2259025574,1.56647920609,15.5933685303 --13.3008680344,1.56948935986,15.5809803009 --13.3848323822,1.57450008392,15.5795974731 --13.4278144836,1.57650542259,15.5794048309 --13.5067806244,1.58051562309,15.5720233917 --13.5927438736,1.58552634716,15.5706367493 --13.6657114029,1.58853578568,15.5542497635 --13.8656463623,1.60855650902,15.6828927994 --13.888628006,1.6055611372,15.6094999313 --13.8746175766,1.59656238556,15.4940958023 --14.0065774918,1.61057543755,15.5919218063 --14.1115369797,1.61758708954,15.609544754 --14.1105241776,1.61158943176,15.5091438293 --14.2574729919,1.62360453606,15.5717754364 --12.1999721527,1.35642671585,13.2319517136 --14.4593963623,1.63762640953,15.5930156708 --5.83252811432,0.54087972641,6.21695327759 --5.80852508545,0.536880910397,6.17175149918 --5.79750967026,0.532886743546,6.12034225464 --5.79249334335,0.529893040657,6.07593631744 --5.79147529602,0.527899742126,6.0355257988 --5.7854590416,0.523905932903,5.99112510681 --5.7984380722,0.523913860321,5.96571540833 --5.79343080521,0.521916747093,5.94151258469 --5.8094086647,0.521924734116,5.92011117935 --5.81039047241,0.518931567669,5.88269996643 --5.81937074661,0.517939031124,5.8542971611 --5.82535123825,0.516946196556,5.82289266586 --5.84032964706,0.515954256058,5.79947662354 --5.85130929947,0.514961659908,5.77408123016 --5.85230016708,0.513965129852,5.75587081909 --5.86227941513,0.512972652912,5.72846221924 --5.87325954437,0.511979997158,5.70306444168 --5.88823843002,0.511987686157,5.68166685104 --5.88622140884,0.509994149208,5.64326095581 --5.88620328903,0.507000923157,5.60584163666 --5.89618349075,0.506008028984,5.58044862747 --5.91017103195,0.507012486458,5.57524108887 --5.92015123367,0.506019830704,5.54883623123 --5.92113304138,0.504026472569,5.513422966 --5.95910692215,0.506035804749,5.51402902603 --5.96508789062,0.505042731762,5.48361873627 --5.97506761551,0.504050016403,5.45721054077 --5.98804759979,0.50405728817,5.43481636047 --5.99803638458,0.50406140089,5.42560577393 --6.01201581955,0.504068672657,5.40421247482 --6.00300073624,0.500074505806,5.3608007431 --6.02497768402,0.501082539558,5.34539270401 --6.06095170975,0.503091454506,5.34299373627 --6.07693099976,0.503098905087,5.3225903511 --6.08491182327,0.5021058321,5.29518651962 --6.10389852524,0.503110408783,5.29397821426 --6.115878582,0.503117442131,5.27058029175 --6.13585710526,0.503125011921,5.25418376923 --6.16883277893,0.505133390427,5.24878787994 --6.18781089783,0.505140960217,5.23037910461 --6.21378755569,0.506149053574,5.21797275543 --6.23977279663,0.508153855801,5.22277212143 --6.282746315,0.511162757874,5.22537946701 --6.31572151184,0.513170957565,5.21898078918 --6.33869934082,0.51417863369,5.20357465744 --6.36667585373,0.515186607838,5.19216918945 --6.37365722656,0.514193058014,5.16376304626 --6.41763114929,0.517201721668,5.16637372971 --6.4386177063,0.518206059933,5.16617155075 --6.46559524536,0.519213497639,5.15478038788 --6.49957036972,0.52122169733,5.14737224579 --6.55554103851,0.526231169701,5.15696382523 --6.56552219391,0.525237500668,5.13156986237 --6.60549688339,0.52824562788,5.12917280197 --6.64247179031,0.530253708363,5.12377071381 --6.66445875168,0.531257927418,5.12356853485 --6.71243143082,0.535266339779,5.1271777153 --6.75440597534,0.537274539471,5.12477397919 --6.76038885117,0.536280333996,5.09638404846 --6.82935667038,0.542289972305,5.1139831543 --6.83633899689,0.54129588604,5.08558607101 --5.52458000183,0.396240085363,4.02429628372 --5.54855823517,0.397247701883,4.01489782333 --5.54854106903,0.396254122257,3.98749017715 --5.56951904297,0.397261679173,3.97508001328 --7.12217283249,0.560346543789,5.07300519943 --7.14315271378,0.561352968216,5.05360412598 --7.16414022446,0.562356650829,5.05140542984 --7.20311546326,0.565363883972,5.04400062561 --7.24809074402,0.568371295929,5.04160881042 --7.28706693649,0.570378243923,5.03522109985 --11.8870782852,1.04559993744,8.10116958618 --11.8850727081,1.04460084438,8.07196807861 --11.8790607452,1.04060256481,8.01256465912 --11.8790493011,1.03860461712,7.9571595192 --11.8710393906,1.03460645676,7.89776182175 --11.8790245056,1.033608675,7.84836101532 --11.8660154343,1.02961027622,7.7849521637 --11.8620100021,1.02761113644,7.75575447083 --11.859998703,1.0246130228,7.70035123825 --11.8529882431,1.02161467075,7.64194631577 --11.851975441,1.01861655712,7.58754253387 --11.8529644012,1.01661860943,7.53514242172 --11.8499526978,1.01362037659,7.47973585129 --11.8489398956,1.01162230968,7.4263343811 --11.8369369507,1.00862276554,7.39313554764 --11.8279266357,1.00562429428,7.33472919464 --11.8229160309,1.00262594223,7.27932500839 --11.8189048767,0.999627649784,7.22492265701 --11.8128938675,0.996629238129,7.16951990128 --11.7998847961,0.993630647659,7.11011457443 --11.8128700256,0.992632865906,7.06671619415 --11.7938690186,0.989633142948,7.0295085907 --11.7948560715,0.987634956837,6.97910690308 --11.7848463058,0.983636379242,6.92270517349 --11.7828350067,0.981637954712,6.8713054657 --11.7918214798,0.980639994144,6.82489538193 --11.790810585,0.977641582489,6.77449607849 --11.7867994308,0.975643157959,6.72209262848 --11.7777957916,0.97364372015,6.69289684296 --11.7757844925,0.97164529562,6.64148950577 --11.7727737427,0.96864682436,6.5900850296 --11.7617645264,0.965648174286,6.53468132019 --11.7747516632,0.964650094509,6.49227809906 --11.768740654,0.962651431561,6.44088220596 --11.7527322769,0.958652555943,6.383477211 --11.8037176132,0.962654471397,6.38628339767 --11.8516979218,0.965656995773,6.36389684677 --11.8456878662,0.962658286095,6.31249761581 --11.8506755829,0.961659789085,6.26609277725 --11.9086551666,0.964662253857,6.24870872498 --11.9796323776,0.969664871693,6.23833227158 --12.0446147919,0.975666701794,6.24814987183 --12.1285896301,0.981669306755,6.24276828766 --12.194568634,0.985671520233,6.22838926315 --12.3145370483,0.995674431324,6.24203109741 --12.3225250244,0.994675457478,6.19562244415 --12.3125162125,0.991676151752,6.14121723175 --12.2305192947,0.981675863266,6.05179786682 --14.0872030258,1.15970134735,6.95917510986 --14.1201887131,1.16070115566,6.91978549957 --14.1691713333,1.16270124912,6.88840246201 --14.20515728,1.16470098495,6.85001182556 --12.2974529266,0.978681147099,5.818608284 --12.2824449539,0.974681675434,5.76320075989 --12.2954378128,0.975682139397,5.74499988556 --12.2814302444,0.972682654858,5.69059371948 --12.2834205627,0.970683336258,5.6441950798 --14.4690618515,1.17669761181,6.61349868774 --14.5230455399,1.17969691753,6.58311986923 --14.5750293732,1.18269598484,6.55073404312 --14.5960187912,1.18269491196,6.50434017181 --14.6120119095,1.18269431591,6.48414897919 --14.5380163193,1.17369270325,6.39472055435 --14.4110202789,1.15769016743,6.22888231277 --14.3760185242,1.15268886089,6.15947389603 --14.3170194626,1.14568758011,6.08005666733 --14.2340250015,1.13568651676,5.99062919617 --14.1600322723,1.12768602371,5.93139791489 --14.098033905,1.12068498135,5.85197591782 --14.0140390396,1.11068415642,5.76455163956 --13.9480409622,1.10268342495,5.68513154984 --13.9010400772,1.09668266773,5.6137137413 --11.6453504562,0.884694337845,4.59615373611 --11.6563444138,0.884694635868,4.57996463776 --11.6423368454,0.881695449352,4.53055000305 --11.6403264999,0.880696058273,4.48714876175 --11.645316124,0.879696667194,4.44675159454 --11.6413078308,0.877697348595,4.40234661102 --11.6332988739,0.875698029995,4.35593366623 --11.6392889023,0.875698506832,4.3165397644 --11.626285553,0.873698949814,4.29033327103 --11.6252765656,0.8716994524,4.24793243408 --11.6272668839,0.870699942112,4.20653009415 --11.6242580414,0.869700491428,4.16312408447 --11.6212491989,0.867700994015,4.12072658539 --11.6212396622,0.866701424122,4.07831859589 --11.6082324982,0.864702045918,4.03191137314 --11.6072273254,0.863702297211,4.01070928574 --11.6112184525,0.862702608109,3.97030520439 --11.6012105942,0.860703110695,3.92590498924 --11.597202301,0.859703540802,3.88350367546 --11.6041917801,0.858703732491,3.84409785271 --11.5961837769,0.856704115868,3.80069756508 --11.5891799927,0.855704426765,3.77749085426 --11.6011705399,0.855704426765,3.74109816551 --11.5811634064,0.852705061436,3.69267988205 --11.567155838,0.850705683231,3.64727210999 --11.4681596756,0.840708315372,3.57483673096 --11.4571523666,0.838708817959,3.53143382072 --11.4501438141,0.836709260941,3.48902773857 --11.4561386108,0.836709201336,3.4708275795 --11.4461317062,0.834709644318,3.4284286499 --11.4461231232,0.833709836006,3.38802051544 --11.4471139908,0.83270996809,3.34861922264 --11.4431056976,0.831710219383,3.30720996857 --11.4410982132,0.830710411072,3.26781487465 --11.4340896606,0.82871067524,3.22540187836 --11.4200878143,0.826711177826,3.20220208168 --11.4190788269,0.825711250305,3.16280150414 --11.4180707932,0.82471126318,3.12239003181 --11.4250612259,0.824711024761,3.08498811722 --11.4290523529,0.823710858822,3.04759383202 --11.4030475616,0.820711731911,3.00118041039 --11.4200372696,0.82171100378,2.96678328514 --11.394036293,0.818711936474,2.94057559967 --11.396027565,0.817711770535,2.90217256546 --11.383020401,0.815712153912,2.85976314545 --11.3960113525,0.816711485386,2.8243637085 --11.3860034943,0.814711689949,2.7829554081 --11.408993721,0.815710425377,2.75056481361 --11.4059867859,0.814710319042,2.71116018295 --11.3679857254,0.810711860657,2.68294978142 --11.3579788208,0.809712052345,2.64153671265 --11.3819694519,0.810710668564,2.60914349556 --11.4199581146,0.813708543777,2.57975292206 --11.4579467773,0.815706253052,2.55036473274 --11.4889354706,0.817704319954,2.51998257637 --11.4999313354,0.818703532219,2.50278019905 --11.5469198227,0.821700632572,2.47539973259 --11.5939083099,0.825697600842,2.44701123238 --11.4659118652,0.813703536987,2.37955403328 --11.4739046097,0.813702523708,2.34315514565 --11.6748809814,0.830691039562,2.34883832932 --11.7078704834,0.832688331604,2.31644272804 --11.740860939,0.834685564041,2.28505921364 --11.7698545456,0.836683452129,2.27086210251 --11.8028450012,0.838680505753,2.23847126961 --11.8418359756,0.841677188873,2.20809292793 --11.8648281097,0.843674659729,2.1726911068 --11.8798208237,0.843672573566,2.13730335236 --11.7168264389,0.828681230545,2.06683278084 --11.4418392181,0.804697096348,1.97732508183 --11.6078243256,0.818686306477,1.98918926716 --11.9027967453,0.843666493893,2.00389575958 --12.0587797165,0.856655061245,1.9925545454 --12.0987710953,0.859650909901,1.96016943455 --12.1387624741,0.862646639347,1.92778682709 --12.119758606,0.860646128654,1.88437139988 --11.6017894745,0.814680337906,1.77897250652 --11.32280159,0.789698243141,1.69545924664 --11.3957901001,0.795692145824,1.67008376122 --11.49177742,0.803684234619,1.64771604538 --11.5017709732,0.804682314396,1.61232233047 --11.4917650223,0.802681744099,1.57291042805 --11.5107584,0.803679049015,1.53851699829 --11.5667514801,0.80867421627,1.52834188938 --11.4537525177,0.798681259155,1.47388482094 --11.5717391968,0.80767095089,1.45353364944 --11.552734375,0.80567085743,1.41311955452 --11.5857276917,0.808666825294,1.38073682785 --11.5127258301,0.801670908928,1.33329916 --11.4387235641,0.794675350189,1.28686773777 --11.4367208481,0.794674754143,1.26867115498 --11.3467197418,0.786680519581,1.22022533417 --11.325715065,0.783680796623,1.18081045151 --11.3707065582,0.787675559521,1.15043628216 --11.4306983948,0.792668938637,1.12005257607 --12.9456310272,0.923537611961,1.24827682972 --11.4806861877,0.795661270618,1.05126190186 --11.4646844864,0.794661819935,1.03206384182 --11.4696779251,0.794659614563,0.995662331581 --11.5236721039,0.798652946949,0.963272690773 --11.387670517,0.786663293839,0.913817822933 --11.4706630707,0.793654024601,0.885455608368 --11.5276565552,0.798646807671,0.853069245815 --13.2995967865,0.951479315758,0.967418193817 --13.3135948181,0.952476024628,0.947222590446 --11.5236444473,0.797642111778,0.761067152023 --11.5186405182,0.796640455723,0.723660588264 --11.4556369781,0.791644394398,0.682231843472 --11.0666418076,0.757680416107,0.617661178112 --11.3216304779,0.779653429985,0.599363088608 --11.3626251221,0.782647252083,0.565978944302 --11.3676233292,0.782645702362,0.547775447369 --11.3856182098,0.783641755581,0.513389289379 --11.4476127625,0.789633214474,0.480006188154 --11.4416074753,0.788631558418,0.443605512381 --11.4276037216,0.787630677223,0.406194001436 --13.8195667267,0.992374539375,0.483838200569 --13.8855657578,0.998362421989,0.442463219166 --11.3895940781,0.783628761768,0.313166171312 --11.4075899124,0.784624457359,0.277772992849 --12.0105810165,0.83655577898,0.263634860516 --11.4045820236,0.784619867802,0.20496481657 --11.4415779114,0.787613093853,0.169575706124 --11.4465742111,0.787609994411,0.134184747934 --11.4455709457,0.787607431412,0.097781740129 --11.5435686111,0.795594871044,0.081621773541 --12.1135644913,0.844525933266,0.0554664283991 --12.1125621796,0.844522595406,0.0170647818595 --12.1095600128,0.844519376755,-0.0213376488537 --12.1235580444,0.845514118671,-0.0597342960536 --12.088555336,0.842514753342,-0.098148740828 --12.0805540085,0.841513812542,-0.118363581598 --12.1165523529,0.8445058465,-0.155740022659 --12.0785493851,0.841506779194,-0.194159194827 --12.0725479126,0.841503798962,-0.232565015554 --12.0645456314,0.840501010418,-0.27097210288 --12.030544281,0.837501466274,-0.309394568205 --12.0675420761,0.840492963791,-0.347776472569 --12.0775413513,0.841489732265,-0.366971820593 --12.0815401077,0.842485308647,-0.405372023582 --12.0905380249,0.842480063438,-0.444778621197 --12.1155376434,0.845472812653,-0.483162909746 --12.1005353928,0.84347063303,-0.521575212479 --12.1195354462,0.845463931561,-0.560972452164 --12.1225337982,0.845459401608,-0.599370837212 --12.1255331039,0.846456885338,-0.618568897247 --12.1245326996,0.846452713013,-0.656970381737 --12.1065301895,0.844450891018,-0.695387125015 --12.115530014,0.845445334911,-0.733779728413 --12.1215295792,0.846439957619,-0.773185133934 --12.1535291672,0.849430978298,-0.813574194908 --12.0915269852,0.844435453415,-0.84799605608 --12.068526268,0.842436432838,-0.866210460663 --15.3806600571,1.12695145607,-1.10104954243 --14.2446165085,1.0301091671,-1.07898914814 --14.1776170731,1.02411186695,-1.12042546272 --14.125617981,1.02011227608,-1.16184937954 --13.9726133347,1.00712788105,-1.19632709026 --14.1826276779,1.02508914471,-1.25662708282 --14.1986293793,1.02708315849,-1.2798140049 --14.2886381149,1.03506195545,-1.33217024803 --14.2416400909,1.03106153011,-1.374599576 --13.9956293106,1.01009202003,-1.39912045002 --14.1896448135,1.02705454826,-1.46042084694 --13.7456216812,0.98911690712,-1.46503865719 --13.9816398621,1.01007211208,-1.53132307529 --14.0246448517,1.01406145096,-1.55850827694 --14.0226488113,1.0140542984,-1.60290718079 --14.2166662216,1.03101503849,-1.66821599007 --14.0456581116,1.01703512669,-1.69570147991 --13.9456567764,1.00904381275,-1.72914540768 --14.0236663818,1.01602315903,-1.78250598907 --14.0846748352,1.02200508118,-1.83487892151 --14.1356811523,1.02599239349,-1.86405873299 --14.1046829224,1.02398955822,-1.90547215939 --14.163693428,1.02997136116,-1.95784068108 --16.7679042816,1.25551509857,-2.33595395088 --16.4368896484,1.22756075859,-2.34651637077 --16.7419242859,1.25449597836,-2.44076561928 --16.8139400482,1.26147150993,-2.504124403 --16.4379119873,1.22853183746,-2.47951483727 --16.2269039154,1.21155810356,-2.50201463699 --16.0719013214,1.19857430458,-2.53249526024 --16.7489719391,1.25744092464,-2.68455028534 --16.2189331055,1.21252524853,-2.65821433067 --16.4399642944,1.23247313499,-2.74550533295 --16.6719913483,1.25242447853,-2.80858826637 --16.381975174,1.22846591473,-2.8161315918 --16.3759841919,1.22845494747,-2.86853456497 --16.0219593048,1.19850945473,-2.86311388016 --16.1289806366,1.20847761631,-2.93345928192 --15.9749746323,1.19549512863,-2.95893239975 --14.9128713608,1.10368716717,-2.82487630844 --14.8518686295,1.09869384766,-2.8381049633 --14.9058837891,1.1046731472,-2.89647817612 --14.5368499756,1.07273471355,-2.87807178497 --14.101808548,1.03581023216,-2.84368872643 --13.9617986679,1.02382862568,-2.86315941811 --13.9868087769,1.02681410313,-2.91455364227 --14.0978298187,1.03778243065,-2.98189306259 --14.7209100723,1.09265208244,-3.12877321243 --14.3228693008,1.0587221384,-3.09738183022 --14.580909729,1.08165931702,-3.19764995575 --14.1508646011,1.04473733902,-3.15627288818 --14.2838897705,1.05769979954,-3.2305996418 --14.020863533,1.03474414349,-3.22214245796 --14.2679052353,1.05768239498,-3.32241415977 --14.2719144821,1.05867111683,-3.37081360817 --14.5039510727,1.07961678505,-3.44588971138 --14.4669561386,1.07761383057,-3.48631381989 --13.6718521118,1.00777375698,-3.35213160515 --13.6018505096,1.00277912617,-3.3815703392 --13.5848560333,1.00177335739,-3.42197084427 --13.6498737335,1.0087492466,-3.48334097862 --13.9039154053,1.03168821335,-3.56841611862 --13.7539024353,1.01971101761,-3.57789182663 --13.2548341751,0.975812077522,-3.5005569458 --13.1998329163,0.971814930439,-3.53098392487 --13.2508487701,0.977793931961,-3.588357687 --13.2478570938,0.978784799576,-3.63276481628 --13.2628669739,0.9807716012,-3.68115520477 --13.3298826218,0.986751317978,-3.72132110596 --13.3368930817,0.988739550114,-3.76872229576 --13.3178987503,0.987733840942,-3.80913567543 --13.2929039001,0.986729562283,-3.84754991531 --13.4299354553,0.99968701601,-3.93087983131 --13.4289445877,1.00067687035,-3.9762802124 --13.3699445724,0.996680319309,-4.00571537018 --13.3659486771,0.996676146984,-4.02691316605 --13.3039464951,0.992680430412,-4.05535268784 --13.2799520493,0.991675794125,-4.09376478195 --13.4229879379,1.00563013554,-4.18209266663 --13.2479658127,0.990662336349,-4.17558383942 --13.4840202332,1.01259326935,-4.29286003113 --13.5990533829,1.02455329895,-4.3752040863 --13.5620508194,1.02155685425,-4.38742542267 --13.6150722504,1.02753210068,-4.45079612732 --13.4860582352,1.01655340195,-4.45726490021 --13.6931114197,1.03648900986,-4.57055807114 --13.734131813,1.04146683216,-4.63093233109 --16.557723999,1.29772698879,-5.59477853775 --13.7401571274,1.04444098473,-4.7297372818 --13.6411418915,1.03646063805,-4.72099065781 --16.8518352509,1.3276078701,-5.83861780167 --13.6881771088,1.04342401028,-4.83276748657 --13.6731863022,1.04341566563,-4.87617826462 --16.4158000946,1.29367184639,-5.86705732346 --16.3458042145,1.28867352009,-5.90049314499 --16.186788559,1.27569949627,-5.90298271179 --16.1757965088,1.27569401264,-5.92819070816 --16.1858177185,1.27767455578,-5.98857879639 --16.2898616791,1.28862893581,-6.08392095566 --16.3609008789,1.29759204388,-6.16828298569 --19.9457683563,1.62657940388,-7.5406498909 --19.7787590027,1.61260211468,-7.55114507675 --19.5247268677,1.59165012836,-7.52668190002 --19.9498443604,1.63151872158,-7.72163915634 --19.9428730011,1.6334965229,-7.79103899002 --19.941904068,1.63547277451,-7.86243343353 --20.0529632568,1.64741647243,-7.97776699066 --20.4631004333,1.68727338314,-8.21092891693 --20.4731349945,1.69124495983,-8.28931808472 --20.3041248322,1.67726874352,-8.29681015015 --18.5086746216,1.51278209686,-7.61804437637 --20.4712181091,1.69618117809,-8.47530460358 --21.0794143677,1.75497448444,-8.79835319519 --18.7408237457,1.54064512253,-7.91710042953 --18.7738609314,1.54661214352,-7.99947547913 --18.7488861084,1.54659616947,-8.05888843536 --18.7029037476,1.54458653927,-8.10931396484 --18.7489318848,1.54956078529,-8.16348457336 --18.6359291077,1.5415712595,-8.18595123291 --18.6169548035,1.54155385494,-8.24635410309 --18.4869499207,1.53256988525,-8.26083278656 --18.5840072632,1.54351603985,-8.3721704483 --18.861120224,1.57240521908,-8.56440448761 --18.8571357727,1.5723940134,-8.59860706329 --18.3400154114,1.52653300762,-8.4383058548 --18.3610534668,1.53150224686,-8.51769256592 --18.4861221313,1.5454376936,-8.64501953125 --18.4791526794,1.54741549492,-8.71242141724 --18.4781856537,1.54939103127,-8.78281974792 --18.5682468414,1.56033694744,-8.89516067505 --18.558259964,1.56132769585,-8.92636680603 --18.4822692871,1.55632710457,-8.96281242371 --18.466299057,1.55730736256,-9.02621746063 --18.497341156,1.56327164173,-9.11259555817 --18.3283214569,1.54930257797,-9.10309505463 --18.5364246368,1.57220709324,-9.2763710022 --18.7515296936,1.59510862827,-9.45363521576 --18.774553299,1.59908747673,-9.50182056427 --18.7825946808,1.6020578146,-9.58021640778 --18.9636917114,1.6219689846,-9.74450111389 --19.1257820129,1.6408854723,-9.90180492401 --19.3318920135,1.66378629208,-10.0820741653 --19.5370025635,1.68668615818,-10.2643489838 --19.6290740967,1.69862437248,-10.3906936646 --19.8011550903,1.71654927731,-10.5187854767 --20.0812950134,1.74642002583,-10.7450141907 --20.2493991852,1.7663295269,-10.914308548 --20.5025348663,1.79320764542,-11.1305503845 --20.6456298828,1.8111243248,-11.2898588181 --20.8227405548,1.83202779293,-11.4691467285 --21.0118560791,1.85292565823,-11.6574287415 --21.2179584503,1.87483382225,-11.8125009537 --21.4330863953,1.89972054958,-12.0177650452 --21.72224617,1.93157887459,-12.2659826279 --22.0064029694,1.96343803406,-12.5132007599 --22.0774841309,1.97437489033,-12.6445531845 --22.3996620178,2.00921702385,-12.9187498093 --22.7388477325,2.04705142975,-13.2049341202 --22.9259490967,2.06696081161,-13.3600168228 --30.4279880524,2.81306123734,-17.7757549286 --30.3450374603,2.81003761292,-17.8551940918 --30.2520828247,2.80601739883,-17.929643631 --30.1531257629,2.80200004578,-17.9990901947 --30.0651721954,2.7989783287,-18.0755348206 --29.9862232208,2.79595327377,-18.1569728851 --29.9022293091,2.79095864296,-18.170217514 --29.8162784576,2.78793644905,-18.2466602325 --29.7143173218,2.7829208374,-18.3131122589 --29.6183624268,2.77890276909,-18.3825588226 --29.5274066925,2.77588272095,-18.4550056458 --29.4424552917,2.77286052704,-18.5314502716 --29.346496582,2.76884269714,-18.5998973846 --29.2935161591,2.76683592796,-18.6311264038 --29.1885566711,2.76182198524,-18.6935806274 --29.0835933685,2.75680828094,-18.7560367584 --28.9986419678,2.75378656387,-18.8304786682 --28.9086875916,2.75076651573,-18.901927948 --28.8147315979,2.74674844742,-18.9703769684 --28.7177734375,2.74373197556,-19.0358276367 --28.6387786865,2.73773694038,-19.0480709076 --28.5578289032,2.73571324348,-19.1245117188 --28.4718761444,2.73269224167,-19.1969585419 --28.3789196014,2.72967410088,-19.2644062042 --28.2829608917,2.72565793991,-19.3288574219 --28.2030124664,2.72363424301,-19.4053020477 --28.1380233765,2.72063350677,-19.4255371094 --28.0490684509,2.71661424637,-19.4939804077 --27.9671173096,2.71459150314,-19.5684261322 --27.8771629333,2.71157288551,-19.6358737946 --27.7802028656,2.7075574398,-19.6983280182 --27.6972522736,2.705534935,-19.771774292 --27.6203022003,2.70351099968,-19.8472118378 --27.5973358154,2.7044916153,-19.8964214325 --27.5343952179,2.70446062088,-19.9828548431 --27.4264297485,2.69945025444,-20.0363140106 --27.3754940033,2.70141339302,-20.1317424774 --27.3085517883,2.70038461685,-20.2141742706 --27.2366046906,2.69935750961,-20.2936134338 --27.173664093,2.69932675362,-20.3790454865 --27.1156787872,2.69632315636,-20.4032802582 --27.0447349548,2.69529604912,-20.482717514 --26.9637851715,2.69427394867,-20.5541610718 --26.9108486176,2.69523715973,-20.6485900879 --26.8789253235,2.69819164276,-20.7569999695 --26.8299942017,2.70015311241,-20.8544254303 --26.7870674133,2.70211172104,-20.9558467865 --26.7661018372,2.70309138298,-21.0060520172 --26.7051639557,2.70405840874,-21.0944881439 --26.6552333832,2.70601987839,-21.1909122467 --26.5942955017,2.7059867382,-21.2793464661 --26.5363578796,2.70695281029,-21.3687725067 --26.480424881,2.70791697502,-21.4612045288 --26.4254894257,2.70888090134,-21.5536308289 --26.4135341644,2.71185493469,-21.6128368378 --26.3726081848,2.71481132507,-21.7172546387 --26.3486938477,2.71975922585,-21.8356628418 --26.430847168,2.73565173149,-22.0430030823 --26.8181858063,2.78638648987,-22.5041389465 --26.8162918091,2.79432010651,-22.645532608 --26.7093296051,2.79030823708,-22.6989936829 --26.6063175201,2.78232812881,-22.6842594147 --26.4673366547,2.77433276176,-22.7107486725 --26.2793235779,2.76136469841,-22.6932640076 --26.1893730164,2.75934505463,-22.7587165833 --26.0453891754,2.75135326385,-22.779209137 --25.9304199219,2.74534726143,-22.8226776123 --25.8124504089,2.74034285545,-22.8631515503 --25.7294502258,2.73535370827,-22.8624038696 --25.5984687805,2.72835683823,-22.8898849487 --25.4995098114,2.72534275055,-22.946346283 --25.3775367737,2.71934151649,-22.9808216095 --25.1604995728,2.70239281654,-22.9303627014 --25.1606082916,2.71032428741,-23.0737571716 --25.0656509399,2.70730829239,-23.1322154999 --24.6944503784,2.66848254204,-22.8646640778 --24.5994911194,2.66646766663,-22.9211235046 --24.3634338379,2.64653348923,-22.8456783295 --24.3495330811,2.65347290039,-22.9760856628 --24.4497127533,2.67334675789,-23.2134094238 --24.3267364502,2.66734790802,-23.2428894043 --24.1977539062,2.66135287285,-23.2663764954 --24.1377639771,2.65835356712,-23.2806110382 --24.0478096008,2.65633654594,-23.3400688171 --23.9038162231,2.64735078812,-23.3475646973 --23.8058567047,2.64433884621,-23.39802742 --23.7429199219,2.64530587196,-23.482465744 --23.5859146118,2.63532924652,-23.4749698639 --23.4939022064,2.62834954262,-23.4572296143 --23.3438987732,2.61936950684,-23.4547290802 --23.2089099884,2.61138105392,-23.4662208557 --23.0849285126,2.60538578033,-23.488702774 --23.0009765625,2.60436654091,-23.5501556396 --22.8950061798,2.6003613472,-23.5886249542 --22.8090515137,2.59834337234,-23.6480808258 --22.6960773468,2.59334206581,-23.6795578003 --22.6500988007,2.59233522415,-23.7057876587 --22.5761528015,2.59230995178,-23.7772369385 --22.4671821594,2.58830738068,-23.8107089996 --22.396238327,2.58827996254,-23.8851547241 --22.3423118591,2.59124183655,-23.9775924683 --22.2483520508,2.5882294178,-24.027053833 --22.1893615723,2.58523082733,-24.0392951965 --22.1214237213,2.58620142937,-24.1167392731 --21.7942657471,2.55434274673,-23.9123649597 --21.9204921722,2.58018565178,-24.2006778717 --21.8445453644,2.58016204834,-24.2681255341 --21.737575531,2.57615852356,-24.3026008606 --21.6215934753,2.57016158104,-24.3260803223 --21.543586731,2.56517672539,-24.3153343201 --21.4776496887,2.56614637375,-24.3937778473 --21.3856887817,2.56413388252,-24.4432411194 --21.2817192078,2.56112885475,-24.4797172546 --21.1817531586,2.55812239647,-24.5181827545 --21.0357456207,2.54814696312,-24.5056877136 --20.8506984711,2.53419995308,-24.4452152252 --20.7666835785,2.52822041512,-24.4254779816 --19.9400424957,2.42972612381,-23.6124572754 --19.8861122131,2.43169093132,-23.69789505 --19.8121623993,2.43166923523,-23.7613506317 --20.1977729797,2.50324273109,-24.5258789062 --17.7755699158,2.18892097473,-21.7569942474 --17.7576084137,2.19090008736,-21.8052120209 --17.7437038422,2.1978430748,-21.9256191254 --17.6747455597,2.19782590866,-21.9800701141 --17.6097927094,2.19780540466,-22.0405197144 --17.5268230438,2.19579815865,-22.0779819489 --17.4498577118,2.19478702545,-22.1224365234 --17.2658424377,2.18382143974,-22.1031742096 --17.1398277283,2.1758480072,-22.0846672058 --17.1429443359,2.18577623367,-22.2300662994 --17.0940074921,2.18874335289,-22.3105068207 --17.0530815125,2.19270443916,-22.4009380341 --15.6717424393,2.00770950317,-20.7443294525 --15.5076227188,1.98980486393,-20.5966510773 --15.3565664291,1.97685968876,-20.5291576385 --15.2585668564,1.97187173367,-20.5336360931 --15.1835918427,1.97086703777,-20.5660934448 --15.1176261902,1.9698549509,-20.6105442047 --15.0456533432,1.96884775162,-20.6469993591 --15.1348609924,1.99070942402,-20.9033412933 --14.959774971,1.97478544712,-20.7998714447 --14.8668336868,1.97576200962,-20.8755455017 --14.7868537903,1.97376072407,-20.902009964 --14.7349052429,1.97573661804,-20.9664535522 --14.6819562912,1.97671318054,-21.0298976898 --14.6500310898,1.98167181015,-21.1233253479 --12.178196907,1.61873221397,-17.6703109741 --11.9209852219,1.58889579773,-17.4179019928 --11.7158317566,1.56601655483,-17.2374591827 --11.5617351532,1.55009555817,-17.1269741058 --11.4887361526,1.54710447788,-17.1344356537 --11.3957118988,1.54113173485,-17.1109085083 --11.303689003,1.53515779972,-17.0893821716 --11.2636852264,1.53316569328,-17.0876197815 --11.205701828,1.53216266632,-17.1150684357 --11.150724411,1.53215670586,-17.1475162506 --11.1017541885,1.53314483166,-17.1899642944 --11.0527820587,1.53313446045,-17.2294006348 --11.006816864,1.53411972523,-17.2768478394 --10.9638528824,1.53610348701,-17.3262825012 --10.9418716431,1.53709471226,-17.3525066376 --10.8999118805,1.53907632828,-17.4059486389 --10.8549461365,1.54006135464,-17.4533863068 --10.8079795837,1.54104745388,-17.4988288879 --10.7570075989,1.54203784466,-17.537273407 --10.7100419998,1.54302346706,-17.5837192535 --10.6610717773,1.54401159286,-17.6261634827 --10.6370887756,1.54400491714,-17.6483860016 --10.5901231766,1.5449911356,-17.6938285828 --10.548163414,1.54697203636,-17.7482662201 --10.4951906204,1.54796350002,-17.7847175598 --10.4472236633,1.54894971848,-17.8301639557 --10.401260376,1.54993414879,-17.8786048889 --10.3752737045,1.55092978477,-17.8968276978 --10.3303117752,1.55191302299,-17.9472694397 --10.2863521576,1.55389463902,-18.0007133484 --10.2363843918,1.55488312244,-18.0421581268 --10.1894216537,1.55686748028,-18.0906047821 --10.1374502182,1.55685722828,-18.1300544739 --10.0944929123,1.55983805656,-18.1844940186 --10.0735149384,1.56082773209,-18.2127132416 --10.0215454102,1.56181693077,-18.2531642914 --9.97558307648,1.56280076504,-18.3026046753 --9.92561721802,1.56478798389,-18.3460540771 --9.88065910339,1.56676948071,-18.3994979858 --9.82668590546,1.56676089764,-18.4359474182 --9.78272914886,1.56974112988,-18.4913921356 --9.76976585388,1.5717215538,-18.5356063843 --9.71178817749,1.57171654701,-18.5660629272 --9.66683101654,1.57469749451,-18.620508194 --9.62387657166,1.57667684555,-18.6769447327 --9.57191085815,1.57766437531,-18.7204017639 --9.51693725586,1.5786563158,-18.7558517456 --9.58316898346,1.60150969028,-19.0272121429 --9.58222675323,1.60647475719,-19.0974159241 --9.46114635468,1.59554100037,-19.0069217682 --9.37311840057,1.58957052231,-18.9783973694 --9.31413936615,1.5895665884,-19.0068511963 --9.27519702911,1.59353899956,-19.0752906799 --9.3194026947,1.61341047287,-19.3166732788 --9.14929103851,1.59750187397,-19.1934146881 --9.09732818604,1.59948801994,-19.2388706207 --9.07341480255,1.6064401865,-19.342300415 --9.02846431732,1.60941803455,-19.4017448425 --5.45401668549,0.909754037857,-12.0411615372 --10.8112564087,2.00891757011,-23.7366638184 --10.7612457275,2.00593113899,-23.7249069214 --10.6832675934,2.00493121147,-23.7473735809 --10.6052913666,2.00392985344,-23.7728481293 --10.5263109207,2.00293087959,-23.7933177948 --10.380200386,1.9880194664,-23.6648406982 --10.349313736,1.99695813656,-23.7922744751 --10.2842731476,1.99099218845,-23.7455310822 --10.1591997147,1.98005485535,-23.6610412598 --10.0651855469,1.97507822514,-23.6435203552 --9.98720645905,1.97407889366,-23.6649951935 --9.8651342392,1.96314096451,-23.5814990997 --9.86732292175,1.98003077507,-23.7929134369 --9.7552690506,1.97108030319,-23.7304077148 --9.72429656982,1.9730694294,-23.760641098 --9.64531421661,1.9720723629,-23.7781143188 --9.49918460846,1.95517122746,-23.6316375732 --9.48434066772,1.96808362007,-23.8040599823 --9.40435600281,1.96708786488,-23.8195362091 --9.310338974,1.9621130228,-23.7990226746 --9.26142406464,1.96807181835,-23.8924770355 --9.22543907166,1.96806883812,-23.9087104797 --9.16349601746,1.97104680538,-23.969171524 --9.09854412079,1.97302997112,-24.0206336975 --9.04361915588,1.97799575329,-24.1020927429 --8.98969554901,1.9829608202,-24.1845474243 --8.9337682724,1.98792779446,-24.264005661 --8.88586521149,1.99488079548,-24.3674602509 --8.84687423706,1.993881464,-24.377696991 --8.77090072632,1.99387919903,-24.4041690826 --8.6989364624,1.99487125874,-24.4406394958 --8.62095832825,1.99387145042,-24.4631156921 --8.54999828339,1.99586105347,-24.5035858154 --8.47903823853,1.99684989452,-24.5460586548 --8.40005779266,1.99585282803,-24.563533783 --8.36808776855,1.99784088135,-24.5957679749 --8.29712581635,1.9988309145,-24.6352329254 --8.23118114471,2.00181031227,-24.6937046051 --8.13014125824,1.99485123158,-24.6461963654 --8.05717563629,1.99584388733,-24.6816673279 --8.01329231262,2.00478482246,-24.8061199188 --7.93932628632,2.00577807426,-24.840593338 --6.88244915009,1.72161257267,-21.6935749054 --6.80443811417,1.71863222122,-21.6820526123 --6.70837259293,1.71068656445,-21.61054039 --6.66646528244,1.71764063835,-21.7119922638 --6.5924654007,1.71565341949,-21.712469101 --7.55759334564,2.01769280434,-25.1141834259 --7.54267978668,2.02464604378,-25.2064056396 --7.4255862236,2.01372075081,-25.1009140015 --7.33055639267,2.00775456429,-25.0654010773 --7.2676281929,2.01272463799,-25.1398696899 --7.13848876953,1.99682784081,-24.9853858948 --7.06552505493,1.99782001972,-25.0218582153 --7.05075645447,2.01769065857,-25.2682952881 --6.98582315445,2.02166438103,-25.3367614746 --6.01773691177,1.72559916973,-22.0076732635 --6.85682249069,2.0186882019,-25.3304920197 --6.77282428741,2.01670265198,-25.3289718628 --6.67979764938,2.01173496246,-25.2964630127 --6.53458690643,1.98988127708,-25.066991806 --6.454600811,1.98888802528,-25.0784721375 --6.42263698578,1.99087333679,-25.1157093048 --6.31755876541,1.98193728924,-25.0282077789 --6.29578590393,2.00081181526,-25.2686481476 --6.16561508179,1.98293328285,-25.0821666718 --6.10570192337,1.98889493942,-25.1716327667 --5.96950006485,1.96803486347,-24.9531574249 --5.8493514061,1.95214152336,-24.7916641235 --5.83043670654,1.95909667015,-24.8808898926 --5.73337602615,1.95214927197,-24.8133831024 --5.68451213837,1.96208119392,-24.9548454285 --5.61456203461,1.96506619453,-25.004322052 --5.54461240768,1.9680505991,-25.0547962189 --5.40336036682,1.94322013855,-24.7843208313 --5.36755609512,1.95911586285,-24.9887733459 --5.32555150986,1.95812666416,-24.9820175171 --5.20236539841,1.93925523758,-24.7825279236 --5.13141012192,1.94124317169,-24.8270053864 --5.04940843582,1.93926012516,-24.8214931488 --4.92218923569,1.91740834713,-24.5880088806 --4.84319257736,1.91642165184,-24.5884914398 --4.72199344635,1.89655721188,-24.3770046234 --4.74328708649,1.9223870039,-24.6842021942 --4.6622800827,1.92040669918,-24.6736850739 --4.54911375046,1.90352261066,-24.4961948395 --4.30425786972,1.8240531683,-23.5977859497 --4.38206291199,1.89658391476,-24.4371643066 --4.21961450577,1.85386824608,-23.9667034149 --4.1737818718,1.86778271198,-24.1391639709 --4.13981294632,1.86977171898,-24.1704063416 --4.05878829956,1.86680173874,-24.1418876648 --3.98279547691,1.86581242085,-24.1473693848 --3.89372873306,1.85786724091,-24.0758647919 --3.81672739983,1.85688304901,-24.0723457336 --3.70048356056,1.83404350281,-23.8168525696 --3.56813263893,1.80126702785,-23.4513702393 --3.58547544479,1.83107066154,-23.8055763245 --3.51551175117,1.83306407928,-23.8410549164 --3.36501860619,1.78837132454,-23.3295822144 --2.32584142685,1.23705220222,-16.9550285339 --2.17413926125,1.17447674274,-16.2365436554 --2.09492921829,1.15560996532,-16.02602005 --2.03970313072,1.13574790955,-15.7962636948 --1.96047353745,1.11489200592,-15.5667390823 --1.91347551346,1.11489975452,-15.5751934052 --1.87253296375,1.11987507343,-15.6406536102 --1.8325984478,1.12584578991,-15.7141094208 --1.7906485796,1.13082563877,-15.7715625763 --1.77169346809,1.13480377197,-15.8207921982 --1.72974562645,1.13878250122,-15.8802433014 --1.68376851082,1.14077842236,-15.9097003937 --1.6367893219,1.14277565479,-15.9371643066 --1.59384095669,1.14775490761,-15.9956178665 --1.54585790634,1.14875459671,-16.0190849304 --1.50493335724,1.15572023392,-16.1015357971 --2.12974119186,1.74877655506,-23.0225372314 --2.06178331375,1.7517670393,-23.0640182495 --1.99483942986,1.75674951077,-23.1194992065 --1.92283821106,1.75576496124,-23.116979599 --1.84071850777,1.74484920502,-22.9944648743 --1.76365470886,1.73790085316,-22.9289512634 --1.6946849823,1.7398982048,-22.9584331512 --1.65867304802,1.73891246319,-22.9456710815 --1.57855761051,1.72799372673,-22.8281593323 --1.509573102,1.72899961472,-22.8426361084 --1.37818074226,1.69524657726,-22.4463653564 --1.30309128761,1.68631243706,-22.3558483124 --1.24019980431,1.69526493549,-22.4643268585 --1.20824933052,1.69924414158,-22.5135669708 --1.13824057579,1.69826388359,-22.5040473938 --1.06618595123,1.69330966473,-22.4485263824 --0.99209612608,1.68537557125,-22.3580112457 --0.91900318861,1.67744314671,-22.2644939423 --0.845894932747,1.66751921177,-22.1559715271 --0.778926789761,1.66951572895,-22.1874504089 --0.743916153908,1.66852915287,-22.17669487 --0.676947414875,1.67152619362,-22.2071743011 --0.611063838005,1.68047535419,-22.3226623535 --0.541011691093,1.67651963234,-22.2701396942 --0.470949143171,1.67056965828,-22.2076206207 --0.402966171503,1.67157483101,-22.2241020203 --0.331779420376,1.65569448471,-22.0385742188 --0.299956560135,1.67060267925,-22.2138252258 --0.233065664768,1.67955648899,-22.3213100433 --0.162999168038,1.67460894585,-22.2547931671 --0.0937254950404,1.65077650547,-21.9842586517 --0.0256674401462,1.64582383633,-21.926738739 -0.0426755398512,1.65115666389,-21.1032676697 -0.0766873285174,1.6521538496,-21.1154441833 -0.144652158022,1.64911568165,-21.0817966461 -0.212688848376,1.65211772919,-21.1191444397 -0.280725449324,1.65511977673,-21.1564884186 -0.346641927958,1.64805531502,-21.0748405457 -0.416752308607,1.6580978632,-21.1851806641 -0.484754472971,1.65808081627,-21.1885299683 -0.519799411297,1.66209638119,-21.2337017059 -0.586752533913,1.65905201435,-21.1880550385 -0.649616003036,1.64695906639,-21.0534095764 -0.717629373074,1.64794838428,-21.0677585602 -0.788704037666,1.65497088432,-21.1431045532 -0.860810637474,1.66501104832,-21.2504425049 -0.923697590828,1.65493118763,-21.1387996674 -0.955649256706,1.65089571476,-21.0909805298 -1.02059578896,1.64684844017,-21.0383338928 -1.08452427387,1.64079165459,-20.9676914215 -1.15049290657,1.6387565136,-20.937046051 -1.18291974068,1.58942770958,-20.3624477386 -1.24485313892,1.58337414265,-20.2958106995 -1.30781936646,1.5803385973,-20.2621669769 -1.37432932854,1.62560582161,-20.7752857208 -1.4169896841,1.59640479088,-20.4336719513 -1.45865941048,1.56720924377,-20.1010627747 -1.52062237263,1.56517219543,-20.0634212494 -1.58359992504,1.56314313412,-20.0407791138 -1.67896223068,1.59532058239,-20.4070911407 -1.73890399933,1.59027242661,-20.3484458923 -1.77290916443,1.59126627445,-20.3536281586 -1.84093880653,1.59426522255,-20.3839740753 -1.9190633297,1.60631430149,-20.5103130341 -1.98607778549,1.6073050499,-20.5256595612 -2.06418681145,1.61734592915,-20.6370010376 -2.13623690605,1.6223552227,-20.6883449554 -2.17428612709,1.62737286091,-20.7385120392 -2.24330067635,1.62936306,-20.753862381 -2.31231617928,1.63135397434,-20.7702140808 -2.38738036156,1.6373707056,-20.8365573883 -2.46244454384,1.64438736439,-20.9028968811 -2.52943253517,1.64336335659,-20.891254425 -2.60348391533,1.64937329292,-20.9445972443 -2.64554405212,1.65439617634,-21.0067653656 -2.71253490448,1.65437400341,-20.9981174469 -2.78657460213,1.65937721729,-21.0394630432 -2.86262655258,1.6643871069,-21.0938072205 -2.93465423584,1.66738438606,-21.1231517792 -3.00466132164,1.66937065125,-21.1315021515 -3.0706346035,1.66733908653,-21.1048622131 -3.11168289185,1.67235577106,-21.1550273895 -3.20483708382,1.68741858006,-21.3153495789 -3.29395413399,1.69846189022,-21.4376831055 -3.36898446083,1.70245993137,-21.4700260162 -3.44200372696,1.70545256138,-21.4913711548 -3.51702713966,1.70844686031,-21.5167198181 -3.59909272194,1.71546304226,-21.586057663 -3.64816808701,1.72249317169,-21.6652202606 -3.72118067741,1.725481987,-21.6795654297 -3.78815150261,1.7234493494,-21.65092659 -3.85713911057,1.72342526913,-21.6392765045 -3.92612552643,1.72340071201,-21.6266307831 -3.99410748482,1.72337388992,-21.6089859009 -4.06510353088,1.7233543396,-21.606338501 -4.10311412811,1.72535061836,-21.6175117493 -4.17410802841,1.72633004189,-21.6128673553 -4.24611139297,1.7273144722,-21.6182136536 -4.31911659241,1.72929942608,-21.6245651245 -4.3891043663,1.72927558422,-21.6129226685 -4.45809173584,1.72925186157,-21.6012744904 -4.52808332443,1.730230093,-21.5936260223 -4.56508684158,1.73122298717,-21.5978031158 -4.63608026505,1.73120224476,-21.5921573639 -4.70807790756,1.73318374157,-21.5915088654 -4.78007364273,1.73416388035,-21.5878658295 -4.85006427765,1.73414182663,-21.5792179108 -4.92306518555,1.73612487316,-21.5815696716 -4.95806074142,1.73611414433,-21.5777454376 -5.02403068542,1.73508143425,-21.5471076965 -5.09904241562,1.73706996441,-21.5604553223 -5.16601610184,1.7360394001,-21.5338172913 -5.23600721359,1.73701751232,-21.5251693726 -5.30599355698,1.73699367046,-21.5125255585 -5.37397623062,1.73696768284,-21.4948806763 -5.4079656601,1.73695361614,-21.4840621948 -5.48096561432,1.73793661594,-21.485414505 -5.54793977737,1.73790633678,-21.4587783813 -5.61190652847,1.7358726263,-21.4241409302 -5.69293355942,1.73986876011,-21.4544849396 -5.76292181015,1.74084579945,-21.4428405762 -5.83993434906,1.74383473396,-21.4571895599 -5.88897371292,1.7478454113,-21.5003566742 -5.96598434448,1.75083327293,-21.5127067566 -6.05403089523,1.75683891773,-21.564043045 -6.15512084961,1.76786577702,-21.6623649597 -6.26523303986,1.77990305424,-21.7846832275 -6.37735080719,1.7939426899,-21.9129962921 -6.48244190216,1.80396950245,-22.0133190155 -6.5615696907,1.81802272797,-22.1524524689 -6.6736779213,1.830057621,-22.2717685699 -6.77976417542,1.84108138084,-22.3670902252 -6.8738117218,1.84708631039,-22.4204235077 -6.96083927155,1.85208201408,-22.4527587891 -7.04986619949,1.85707676411,-22.4841041565 -7.1429066658,1.86307835579,-22.5304412842 -7.18892478943,1.86607825756,-22.5516090393 -7.2829656601,1.87207961082,-22.5979442596 -7.36096048355,1.87405908108,-22.5942935944 -7.44396686554,1.87704396248,-22.60364151 -7.50792312622,1.875005126,-22.5580043793 -7.57689094543,1.8739720583,-22.5253677368 -7.61187601089,1.87395560741,-22.5095481873 -7.68285036087,1.87292563915,-22.4839096069 -7.7608423233,1.8749037981,-22.4772624969 -7.83081531525,1.87487316132,-22.4496192932 -7.90279150009,1.87484371662,-22.4249801636 -7.95973014832,1.87079691887,-22.3593540192 -8.02067947388,1.86775529385,-22.3057250977 -8.04162979126,1.86472308636,-22.2519187927 -8.106590271,1.86268687248,-22.2102851868 -8.17054748535,1.86064898968,-22.1646556854 -8.2445306778,1.86162340641,-22.1480121613 -8.31851577759,1.8625985384,-22.1323680878 -8.38949108124,1.86256980896,-22.1077270508 -8.45846176147,1.86153805256,-22.0760936737 -8.50547790527,1.86453700066,-22.0952587128 -8.57945919037,1.8655102253,-22.0756225586 -8.64943313599,1.86548089981,-22.0489826202 -8.71439743042,1.86444628239,-22.0093460083 -8.77635097504,1.86240744591,-21.9597206116 -8.84532356262,1.86237752438,-21.9310817719 -8.90727996826,1.86033987999,-21.8834533691 -8.9492816925,1.86133146286,-21.8856296539 -9.02627182007,1.86330962181,-21.8759841919 -9.12029838562,1.86830425262,-21.9073219299 -9.20029354095,1.87128412724,-21.902677536 -9.28830337524,1.87527120113,-21.9160270691 -9.3412437439,1.87122642994,-21.8493995667 -9.33505630493,1.8541238308,-21.6398429871 -9.37505435944,1.85511469841,-21.6390190125 -9.48911952972,1.86512649059,-21.7133407593 -9.5611000061,1.86610019207,-21.6916999817 -9.64009094238,1.86807870865,-21.683057785 -9.68000507355,1.8620223999,-21.5864505768 -9.59367084503,1.82885503769,-21.2079658508 -9.62156772614,1.82079195976,-21.0913658142 -9.61347198486,1.81174111366,-20.9835891724 -9.64437770844,1.80468189716,-20.8759880066 -9.68630313873,1.79863190651,-20.7913818359 -9.71219921112,1.79056882858,-20.67278862 -9.72006511688,1.77849316597,-20.5202064514 -9.73795032501,1.76942574978,-20.3886203766 -9.74188423157,1.7633882761,-20.3128318787 -9.78081130981,1.75833940506,-20.2282276154 -9.82674980164,1.75429606438,-20.1576156616 -9.86567878723,1.74924850464,-20.0750083923 -9.90660953522,1.74420249462,-19.9964027405 -9.94654273987,1.74015688896,-19.9177932739 -9.98146724701,1.73410749435,-19.8291893005 -9.99241733551,1.73007762432,-19.771396637 -10.0363578796,1.72703635693,-19.7027835846 -10.0772953033,1.72299265862,-19.6281757355 -10.1052093506,1.71593952179,-19.5275821686 -10.1421403885,1.71089410782,-19.4469776154 -10.1860847473,1.70785403252,-19.3803653717 -10.2240180969,1.70280957222,-19.3017635345 -10.2319688797,1.69878089428,-19.2439670563 -10.279920578,1.69674408436,-19.1853542328 -10.3128490448,1.69069814682,-19.1007518768 -10.3527879715,1.68665647507,-19.0281486511 -10.3987388611,1.68461990356,-18.968536377 -10.4356775284,1.68057823181,-18.8939285278 -10.4786224365,1.67653954029,-18.8283233643 -10.49559021,1.674518466,-18.7895183563 -10.5275211334,1.66947376728,-18.7059192657 -10.5604534149,1.66442990303,-18.6243228912 -10.6244354248,1.66540670395,-18.599691391 -10.6323308945,1.65634787083,-18.4751167297 -10.6822919846,1.65531635284,-18.4265003204 -10.6742219925,1.64827978611,-18.3437232971 -10.7392063141,1.64925777912,-18.3210964203 -10.7661352158,1.64421331882,-18.2344989777 -10.8090867996,1.64117836952,-18.1748886108 -10.8580465317,1.64014661312,-18.1242790222 -10.9180240631,1.6401219368,-18.0936565399 -10.9699907303,1.63909351826,-18.0510349274 -10.995973587,1.63807892799,-18.0292263031 -11.0539474487,1.63805305958,-17.9946079254 -11.107916832,1.63802576065,-17.9549865723 -11.1598825455,1.63699662685,-17.9103736877 -11.2098464966,1.63596701622,-17.8637599945 -11.270825386,1.63594400883,-17.8361320496 -11.3328056335,1.63692092896,-17.8085098267 -11.359790802,1.63690698147,-17.7877025604 -11.4187660217,1.63688266277,-17.7560787201 -11.483751297,1.63886141777,-17.7334499359 -11.5427274704,1.63883733749,-17.7018280029 -11.6047086716,1.63981437683,-17.6742038727 -11.6576766968,1.63878715038,-17.6325874329 -11.7236604691,1.64076590538,-17.6099624634 -11.7536487579,1.64075386524,-17.5941505432 -11.8296470642,1.6437381506,-17.5875148773 -11.8906259537,1.64471483231,-17.5578918457 -11.9566106796,1.6456938982,-17.5352649689 -12.0245990753,1.64767432213,-17.5166339874 -12.083574295,1.64864945412,-17.4820156097 -12.0955400467,1.64562928677,-17.4402198792 -12.182551384,1.65061843395,-17.4485740662 -12.2445297241,1.65159535408,-17.4189510345 -12.3105144501,1.65257418156,-17.3953266144 -12.3704919815,1.65355074406,-17.363702774 -12.4234600067,1.65352368355,-17.3210906982 -12.4914474487,1.65550374985,-17.3004589081 -12.5334501266,1.65749692917,-17.3006401062 -12.5924253464,1.65747249126,-17.2660236359 -12.668419838,1.66045606136,-17.2563877106 -12.7404108047,1.66343736649,-17.2397575378 -12.8114004135,1.66541838646,-17.2221240997 -12.8713760376,1.66639447212,-17.1885070801 -12.940363884,1.66837465763,-17.1678771973 -12.9823646545,1.67036759853,-17.16705513 -13.0673675537,1.67435383797,-17.1664161682 -13.1433620453,1.67733633518,-17.1537818909 -13.2163515091,1.68031728268,-17.1361541748 -13.2833356857,1.6822963953,-17.1115264893 -13.3423099518,1.68227171898,-17.0749092102 -13.4042873383,1.68324840069,-17.0422916412 -13.475317955,1.68925237656,-17.0784454346 -13.5523118973,1.69223463535,-17.0648117065 -13.6283035278,1.69521653652,-17.0501785278 -13.6982889175,1.69719588757,-17.0265541077 -13.8123188019,1.70619153976,-17.058889389 -13.8933143616,1.70917451382,-17.0482559204 -13.9653015137,1.71215438843,-17.0266265869 -14.0123062134,1.71414840221,-17.029800415 -14.0872945786,1.71712875366,-17.010175705 -14.1552772522,1.71910738945,-16.9835472107 -14.251285553,1.72509527206,-16.989900589 -14.3422908783,1.73008143902,-16.9902553558 -14.4022626877,1.73005604744,-16.9506435394 -14.4702444077,1.73203444481,-16.9230155945 -14.5282583237,1.73603129387,-16.9371833801 -14.1458206177,1.67786300182,-16.3789253235 -14.1557502747,1.67282354832,-16.2843532562 -14.1776924133,1.66878890991,-16.2057628632 -14.2126464844,1.66675794125,-16.1411685944 -14.2586107254,1.6657307148,-16.0895652771 -14.2855968475,1.66571855545,-16.0687599182 -14.3315620422,1.66469180584,-16.0181541443 -14.3765268326,1.66366493702,-15.9665489197 -14.4034748077,1.66063284874,-15.8949565887 -14.408405304,1.6545945406,-15.7993812561 -14.4233446121,1.65055942535,-15.7148017883 -14.4432878494,1.646525383,-15.6352214813 -14.4312429428,1.64150309563,-15.5734415054 -14.4481840134,1.63746905327,-15.4918613434 -14.4821424484,1.635440588,-15.430264473 -14.5080919266,1.63240933418,-15.3586797714 -14.5280380249,1.62837743759,-15.2830905914 -14.5349740982,1.62334191799,-15.1925191879 -14.5489177704,1.61930882931,-15.1109380722 -14.5488824844,1.61629033089,-15.0621547699 -14.5808401108,1.61426222324,-14.9995622635 -14.6107959747,1.61123371124,-14.9349718094 -14.6587667465,1.6112101078,-14.8893651962 -14.6827201843,1.60918080807,-14.8197755814 -14.7046699524,1.60515105724,-14.7481880188 -14.6896257401,1.60112965107,-14.685418129 -14.70657444,1.59709918499,-14.6098327637 -14.7255239487,1.5940694809,-14.5362482071 -14.7314634323,1.58903634548,-14.448679924 -14.7464122772,1.58500611782,-14.3720970154 -14.7653627396,1.58197700977,-14.2995128632 -14.786315918,1.57894861698,-14.228928566 -14.7912883759,1.57693350315,-14.1891365051 -14.8072385788,1.57290399075,-14.1135597229 -14.8291921616,1.56987643242,-14.0449733734 -14.8531494141,1.56784939766,-13.978386879 -14.870100975,1.56382107735,-13.9058036804 -14.8990621567,1.5617954731,-13.8442144394 -14.8939990997,1.55676305294,-13.7516469955 -14.9149837494,1.55575168133,-13.726849556 -14.9339389801,1.55372464657,-13.6572647095 -14.9629011154,1.55169975758,-13.5966739655 -14.9828567505,1.54867351055,-13.529086113 -15.0248279572,1.54865133762,-13.4804887772 -15.0457859039,1.54562556744,-13.4139003754 -15.0577363968,1.5425978899,-13.3383264542 -15.0246858597,1.53557658195,-13.2655687332 -15.0556507111,1.53455305099,-13.2079772949 -15.0726070404,1.53152704239,-13.1383962631 -15.0655469894,1.52549684048,-13.0478343964 -15.077501297,1.52247059345,-12.9752511978 -15.1004619598,1.52044665813,-12.9126615524 -15.1154174805,1.51742076874,-12.8410902023 -15.1043834686,1.5134049654,-12.790312767 -15.1133375168,1.510379076,-12.7167320251 -15.1463069916,1.50935745239,-12.6631374359 -12.9098434448,1.25195240974,-10.6852560043 -12.9158067703,1.24893176556,-10.6206827164 -12.92877388,1.24691271782,-10.5630979538 -12.9667768478,1.24890828133,-10.5602855682 -8.24481868744,0.715119481087,-6.53561544418 -8.25981140137,0.714112341404,-6.50502490997 -8.31682682037,0.718111634254,-6.5084066391 -8.35783481598,0.720108509064,-6.49879741669 -8.36882400513,0.719100654125,-6.4642162323 -8.39483070374,0.721099793911,-6.46340990067 -8.40081787109,0.719091355801,-6.42483329773 -8.43582057953,0.72008728981,-6.4102268219 -8.45781803131,0.721081495285,-6.3856253624 -8.48681640625,0.721076369286,-6.36503458023 -8.50180912018,0.721069574356,-6.33444356918 -8.53481197357,0.722065210342,-6.3178396225 -8.54580879211,0.722062051296,-6.30405378342 -8.57681083679,0.723057627678,-6.28644418716 -8.59780597687,0.723051607609,-6.25985479355 -8.63581085205,0.725047826767,-6.2462515831 -8.64980316162,0.724041104317,-6.21466445923 -8.68180561066,0.72603648901,-6.1960682869 -8.70180034637,0.72603058815,-6.16947126389 -8.72380447388,0.727028846741,-6.16367769241 -8.74079799652,0.727022528648,-6.13409090042 -8.77680110931,0.728018760681,-6.11947870255 -8.78979301453,0.728012025356,-6.08689451218 -8.82779788971,0.72900813818,-6.07229423523 -8.83878803253,0.72800141573,-6.03870820999 -8.86279296875,0.730000019073,-6.03490352631 -8.88478946686,0.729994297028,-6.00831747055 -8.9237947464,0.731990635395,-5.99470901489 -8.93978786469,0.731984615326,-5.96511411667 -8.95978450775,0.731978952885,-5.93752479553 -8.99578666687,0.73397487402,-5.92092466354 -9.02878856659,0.734970331192,-5.9013338089 -9.05279350281,0.735968947411,-5.89752435684 -9.05377960205,0.734961509705,-5.85694789886 -9.10979270935,0.737959265709,-5.85333395004 -9.12078380585,0.736952841282,-5.81974840164 -9.15478610992,0.738948583603,-5.80114936829 -9.21580123901,0.742946684361,-5.80052852631 -9.16676425934,0.735935211182,-5.72699165344 -9.18776702881,0.736933350563,-5.72019004822 -9.24978351593,0.74193161726,-5.72056007385 -9.28578472137,0.743927299976,-5.70196819305 -9.31978797913,0.744923055172,-5.68336343765 -11.1175737381,0.92605227232,-6.7775554657 -11.0765371323,0.920039355755,-6.70400381088 -10.9174480438,0.901018023491,-6.55654191971 -10.8113927841,0.890005707741,-6.4668302536 -10.7293395996,0.878990769386,-6.3693151474 -10.6742982864,0.870978116989,-6.28977584839 -10.6982917786,0.871971011162,-6.25818872452 -10.5302038193,0.852951705456,-6.111723423 -10.3811254501,0.835934221745,-5.97824478149 -10.28307724,0.824924170971,-5.89752578735 -10.2560510635,0.820914983749,-5.83796977997 -10.1680011749,0.809902250767,-5.74245929718 -10.024928093,0.793886959553,-5.61598348618 -9.95388698578,0.784876286983,-5.53345012665 -9.83482646942,0.770863354206,-5.42394971848 -9.76978778839,0.762853562832,-5.34542369843 -9.70775794983,0.755847513676,-5.29066944122 -9.65072441101,0.748838663101,-5.21813440323 -9.58268642426,0.739829659462,-5.1406006813 -9.58067417145,0.73782402277,-5.10002851486 -9.44261169434,0.722812354565,-4.98454427719 -9.41659164429,0.718806147575,-4.93198442459 -9.33855247498,0.709797918797,-4.8514585495 -9.29253101349,0.7037935853,-4.80769968033 -9.22949790955,0.696786463261,-4.73616600037 -9.14645862579,0.686778843403,-4.65464544296 -9.11443901062,0.681773424149,-4.60108995438 -9.07841777802,0.677768051624,-4.54553890228 -9.02839183807,0.670762419701,-4.48398780823 -8.96536254883,0.663756668568,-4.41545248032 -8.90533828735,0.656752943993,-4.36670351028 -8.85631370544,0.650747954845,-4.30616235733 -8.78228187561,0.64174258709,-4.23363447189 -8.72125434875,0.634737730026,-4.16810083389 -8.69824028015,0.631734192371,-4.12253856659 -8.6782283783,0.627730846405,-4.07897281647 -8.67222309113,0.626729309559,-4.0591878891 -8.68522262573,0.626726925373,-4.03259515762 -8.54016876221,0.611721336842,-3.9281141758 -8.50215244293,0.606718301773,-3.87755274773 -8.46913719177,0.602715432644,-3.82801055908 -8.41011333466,0.59571236372,-3.76747226715 -8.41111087799,0.594710469246,-3.7368812561 -8.37309646606,0.589708924294,-3.70212888718 -8.35108661652,0.586706876755,-3.66055941582 -8.34107971191,0.58470505476,-3.62497997284 -8.30506515503,0.5807030797,-3.57643294334 -8.28105449677,0.57670134306,-3.53387641907 -8.28005218506,0.575699925423,-3.50328755379 -8.23703765869,0.570698976517,-3.4675385952 -8.23603439331,0.569697678089,-3.43695354462 -8.25303649902,0.570696592331,-3.41337156296 -8.25703525543,0.569695413113,-3.38478779793 -8.26103496552,0.568694353104,-3.35620474815 -8.23002338409,0.564693331718,-3.31264281273 -8.17900657654,0.558692514896,-3.26010370255 -8.26202964783,0.566691875458,-3.28026485443 -8.22301673889,0.56169116497,-3.23370957375 -8.20701122284,0.558690488338,-3.19713950157 -8.243019104,0.56168961525,-3.18253421783 -8.26502418518,0.56268876791,-3.16095232964 -8.23901557922,0.558688342571,-3.12039136887 -8.2770242691,0.561687469482,-3.10677814484 -8.22700977325,0.556687772274,-3.07103061676 -8.14498806,0.547688364983,-3.00949311256 -8.19399929047,0.551687419415,-2.99889469147 -8.22600746155,0.55368667841,-2.98229384422 -8.24601173401,0.554686069489,-2.96070289612 -8.29902458191,0.558684945107,-2.95110058784 -8.30102443695,0.557684719563,-2.92251968384 -8.3290309906,0.559684097767,-2.91870880127 -8.37604141235,0.563682973385,-2.90611219406 -13.9453811646,1.07255899906,-4.93711566925 -8.26801490784,0.551685214043,-2.80801224709 -14.0403738022,1.07854318619,-4.87291383743 -14.0593633652,1.07853603363,-4.83032989502 -14.1203708649,1.08353114128,-4.82750558853 -14.1253566742,1.08252429962,-4.77992868423 -14.1783533096,1.08551621437,-4.74833059311 -14.2143478394,1.08750867844,-4.71173286438 -14.2693462372,1.09150052071,-4.68112659454 -14.3063392639,1.09349286556,-4.64353656769 -14.3403320312,1.09548521042,-4.60494709015 -14.3913354874,1.09848034382,-4.59713077545 -14.4363307953,1.10147249699,-4.56252908707 -14.4703235626,1.10346496105,-4.52393579483 -14.521320343,1.1064568758,-4.49033594131 -14.5743169785,1.11044859886,-4.45772886276 -14.6973276138,1.11943745613,-4.44608831406 -14.6473035812,1.11443340778,-4.38054323196 -14.713309288,1.11942756176,-4.37572050095 -14.7563047409,1.1214196682,-4.33912038803 -14.7692928314,1.12141311169,-4.29254341125 -14.827290535,1.12540447712,-4.2599363327 -12.8519020081,0.947488725185,-3.61955857277 -12.7508735657,0.937489688396,-3.54604768753 -12.7708692551,0.937485158443,-3.50846576691 -12.7378587723,0.934485018253,-3.47769546509 -12.713845253,0.931482791901,-3.42813396454 -12.7248392105,0.931478917599,-3.38855338097 -12.7078285217,0.928476512432,-3.3409910202 -12.6688137054,0.924475371838,-3.28744244576 -12.652803421,0.921473145485,-3.24087667465 -12.6547994614,0.921471476555,-3.22009086609 -12.6617927551,0.920468151569,-3.1795156002 -12.6337814331,0.917466878891,-3.12995815277 -12.6887836456,0.921460926533,-3.10235214233 -12.6837749481,0.920458495617,-3.05878305435 -12.7077722549,0.921454310417,-3.02220225334 -12.7867774963,0.927447021008,-3.00057697296 -12.7747716904,0.925446331501,-2.9758040905 -12.8317737579,0.930440247059,-2.94819188118 -12.835767746,0.929437398911,-2.90661907196 -12.8877687454,0.933431625366,-2.8770134449 -12.9787759781,0.940423309803,-2.85638546944 -13.0487785339,0.945416152477,-2.82977509499 -15.8961811066,1.19622445107,-3.43955683708 -15.9561824799,1.20021796227,-3.42773246765 -15.9891748428,1.20221054554,-3.38314127922 -16.0761737823,1.20919930935,-3.34952545166 -16.1261672974,1.21219074726,-3.30792689323 -16.2701759338,1.22417545319,-3.28627324104 -16.3531742096,1.23016440868,-3.25065732002 -16.3701610565,1.23115813732,-3.20107722282 -16.336151123,1.22715806961,-3.16731357574 -16.4951572418,1.24014127254,-3.14665222168 -16.5331497192,1.24313342571,-3.100066185 -16.4911308289,1.23813164234,-3.03851914406 -16.4971199036,1.23812627792,-2.9859495163 -16.5481147766,1.24211740494,-2.94235110283 -16.5881118774,1.24511194229,-2.92354059219 -16.6451072693,1.24910283089,-2.8809363842 -16.6900997162,1.25209438801,-2.83534288406 -16.9631175995,1.27506756783,-2.82962536812 -17.0531139374,1.28205549717,-2.79100465775 -7.16102981567,0.418862015009,-1.03188335896 -17.0420875549,1.27904689312,-2.6798722744 -17.092086792,1.28304028511,-2.66105890274 -17.0790729523,1.28103673458,-2.6035027504 -17.2730808258,1.29701566696,-2.58081936836 -17.2880687714,1.29800951481,-2.52724814415 -17.3180580139,1.30000245571,-2.47666287422 -17.3600521088,1.30299413204,-2.42806887627 -17.4550476074,1.30998122692,-2.38645029068 -17.5630512238,1.31896936893,-2.37460517883 -17.7210540771,1.33195066452,-2.34194421768 -17.7830448151,1.33694028854,-2.29334878922 -16.3259086609,1.21006929874,-2.03758764267 -16.1808853149,1.19707942009,-1.96610069275 -16.0888690948,1.18808495998,-1.9025837183 -16.0598564148,1.18508470058,-1.84802937508 -16.0178489685,1.18108713627,-1.81726813316 -16.0158405304,1.18008458614,-1.76669669151 -15.9908294678,1.17808413506,-1.71314013004 -16.0138244629,1.1790792942,-1.66555571556 -15.9988145828,1.17707824707,-1.61299705505 -15.9838056564,1.17607712746,-1.5604391098 -15.9828014374,1.17507612705,-1.53565061092 -16.0197963715,1.17806994915,-1.48906171322 -15.9977855682,1.17606973648,-1.43650281429 -16.1357879639,1.18705356121,-1.39985799789 -16.0397720337,1.17806100845,-1.33934533596 -16.133769989,1.18604922295,-1.29772412777 -16.1647644043,1.18804395199,-1.25013530254 -16.319770813,1.20102667809,-1.23826777935 -16.4547710419,1.21301043034,-1.19763255119 -18.9098968506,1.4237498045,-1.34574329853 -18.9388847351,1.4257427454,-1.28915739059 -18.9718761444,1.4287352562,-1.23157763481 -19.0718688965,1.43672060966,-1.1789598465 -18.9858589172,1.42872786522,-1.14322137833 -19.0518493652,1.43471705914,-1.08861601353 -9.70741653442,0.629732310772,-0.430952042341 -9.69742012024,0.628736376762,-0.400377333164 -9.70742511749,0.629738330841,-0.370795786381 -9.69342899323,0.628742933273,-0.340221136808 -9.7034330368,0.628744959831,-0.310639470816 -9.69143486023,0.627747893333,-0.294858783484 -9.70544052124,0.628749489784,-0.2652772367 -9.67944431305,0.626755714417,-0.233717784286 -9.69645023346,0.627757072449,-0.204136073589 -9.69145488739,0.627760827541,-0.174552202225 -9.68846035004,0.626764595509,-0.143983066082 -9.67746448517,0.625769257545,-0.113414563239 -9.69846725464,0.627768516541,-0.098621532321 -9.6694726944,0.624775290489,-0.0680557861924 -9.69047832489,0.626776337624,-0.0384701937437 -9.66948318481,0.624782323837,-0.00790563970804 -9.68948841095,0.626783490181,0.0216813869774 -9.67049407959,0.624789357185,0.0522445254028 -9.68449687958,0.625789523125,0.0670398250222 -9.67650222778,0.625794053078,0.0966196209192 -9.67950820923,0.625797390938,0.127188906074 -9.66551303864,0.624802708626,0.15676496923 -9.67151927948,0.624805688858,0.186349317431 -9.66752529144,0.624810039997,0.21691519022 -9.67753124237,0.625812590122,0.24650259316 -9.6575345993,0.62381696701,0.261281728745 -9.66154003143,0.623820364475,0.291851490736 -9.6515455246,0.623825490475,0.321426421404 -9.66255283356,0.624828100204,0.352001458406 -9.65055847168,0.623833596706,0.381573855877 -9.65756511688,0.623836636543,0.411160439253 -9.64057064056,0.622842848301,0.440727591515 -9.67057418823,0.624841034412,0.456529945135 -9.64558029175,0.622848391533,0.486089289188 -9.65258693695,0.623851537704,0.515677213669 -9.63559341431,0.622857928276,0.545241892338 -9.65460014343,0.623859643936,0.575828373432 -9.63360691071,0.622866690159,0.605387628078 -9.64661312103,0.623869240284,0.635969281197 -9.63361740112,0.622873008251,0.649759173393 -9.64762306213,0.623875439167,0.680342972279 -9.62863063812,0.622882425785,0.709901630878 -9.64463710785,0.623884618282,0.740489244461 -9.6296453476,0.622891128063,0.770051538944 -9.64165210724,0.623893916607,0.800635576248 -9.63265419006,0.623897254467,0.814428329468 -9.63666248322,0.623901247978,0.845001995564 -9.62267017365,0.622907757759,0.874563753605 -9.62667655945,0.623911619186,0.904151856899 -9.61768436432,0.622917532921,0.933720052242 -9.62369155884,0.623921275139,0.964297890663 -9.61369895935,0.622927367687,0.993863940239 -9.6257019043,0.623928010464,1.00966107845 -9.60971069336,0.622934937477,1.03823077679 -9.62671756744,0.624937236309,1.06981527805 -9.60772609711,0.622944712639,1.09837853909 -9.61873245239,0.624947845936,1.12896800041 -9.60374164581,0.623954832554,1.15753746033 -9.61674785614,0.624957799911,1.18911778927 -9.60975265503,0.62396132946,1.20389616489 -9.61076068878,0.624965965748,1.23348224163 -9.59476852417,0.623973190784,1.26204812527 -9.61777591705,0.625974833965,1.29463779926 -9.59378528595,0.623983323574,1.32220005989 -9.60479259491,0.624986708164,1.35378038883 -9.59679698944,0.624990344048,1.36756968498 -9.60280513763,0.625994682312,1.39914023876 -9.59081363678,0.625001430511,1.42771267891 -9.60682106018,0.627004265785,1.46029353142 -9.58083057404,0.625013172626,1.4868606329 -9.60283756256,0.627015173435,1.52044343948 -9.59084701538,0.626022100449,1.54901516438 -9.59085083008,0.627024650574,1.56380879879 -9.57586097717,0.626032233238,1.59237241745 -9.58786773682,0.627035558224,1.62396192551 -9.57287788391,0.626043200493,1.65252482891 -9.5818862915,0.627047121525,1.6841083765 -9.57589530945,0.627053439617,1.71368074417 -9.582903862,0.628057718277,1.74526047707 -9.56490898132,0.627063274384,1.75803375244 -9.58091640472,0.629066109657,1.79062533379 -9.56192588806,0.628074526787,1.81818938255 -9.57893466949,0.630077421665,1.85177230835 -9.56794452667,0.629084587097,1.88034486771 -9.5659532547,0.629090487957,1.91091585159 -9.54896354675,0.628098726273,1.93848371506 -9.57196617126,0.631097972393,1.95827949047 -9.54797744751,0.629107177258,1.98385334015 -9.55598640442,0.630111634731,2.01642823219 -9.5449962616,0.630118966103,2.04499983788 -9.55300426483,0.631123483181,2.07757639885 -9.54701519012,0.631130158901,2.10715055466 -9.56701755524,0.633129715919,2.12595701218 -9.54702949524,0.6321387887,2.15351366997 -9.54503917694,0.632144868374,2.18408751488 -9.53704833984,0.632151842117,2.21266913414 -9.53805828094,0.633157551289,2.24424052238 -9.52806854248,0.632165014744,2.27281498909 -9.54407691956,0.634168326855,2.30739831924 -9.53308296204,0.634172976017,2.3201854229 -9.5360918045,0.635178565979,2.35275220871 -9.53310203552,0.635184824467,2.38233876228 -9.52611255646,0.635191917419,2.41191148758 -9.51112365723,0.634200513363,2.44046854973 -9.53313159943,0.637203037739,2.47705364227 -9.51413822174,0.635209023952,2.48783683777 -9.51814746857,0.636214375496,2.51942372322 -9.50915908813,0.63622200489,2.5489897728 -9.51916790009,0.638226389885,2.58257484436 -9.50817871094,0.637234330177,2.61114692688 -9.51518821716,0.639239370823,2.6447224617 -9.50220012665,0.638247609138,2.67230010033 -9.50720500946,0.639250040054,2.69008135796 -9.49721622467,0.639257848263,2.71865773201 -9.49922561646,0.640263915062,2.75122928619 -9.4872379303,0.639272153378,2.77979779243 -9.49424743652,0.641277313232,2.81337785721 -9.4922580719,0.641283869743,2.84396147728 -9.49126911163,0.642290353775,2.87553691864 -9.48527431488,0.642294645309,2.89031505585 -9.48628520966,0.643300712109,2.9218993187 -9.48129653931,0.643307983875,2.95247244835 -9.47830677032,0.644315004349,2.98404121399 -9.47831726074,0.644321382046,3.01562333107 -9.47532844543,0.645328521729,3.0471932888 -9.47033977509,0.6453358531,3.07776784897 -9.4813451767,0.647337257862,3.09755706787 -9.46635723114,0.646346330643,3.1251270771 -9.46636772156,0.64735275507,3.15671253204 -9.45838069916,0.647360861301,3.18727517128 -9.47038841248,0.649365246296,3.22286534309 -9.45640182495,0.649374425411,3.25142765045 -9.47240543365,0.651374876499,3.27223134041 -9.46041870117,0.65038383007,3.30179023743 -9.45442962646,0.651391506195,3.33236479759 -9.45643997192,0.652397692204,3.36495184898 -9.44745349884,0.652406156063,3.39551281929 -9.44546508789,0.653413176537,3.42709517479 -9.45147514343,0.654418885708,3.46167874336 -9.45048141479,0.655422568321,3.4784579277 -9.44949245453,0.655429542065,3.51103448868 -9.44450473785,0.65643709898,3.54161739349 -9.44551563263,0.657443761826,3.57519292831 -9.44152832031,0.658451497555,3.60775732994 -9.438539505,0.658458769321,3.6393392086 -9.43655109406,0.659466087818,3.6719148159 -9.43155765533,0.659470438957,3.68670153618 -9.42157077789,0.659479141235,3.71627473831 -9.42758178711,0.661485016346,3.7518556118 -9.4275932312,0.662491977215,3.78543162346 -9.43260478973,0.663498342037,3.82199788094 -9.42261791229,0.664507091045,3.85157346725 -9.42662239075,0.66550976038,3.86937141418 -9.42363452911,0.665517568588,3.90293526649 -9.4196472168,0.666525185108,3.93451929092 -9.41866016388,0.667532444,3.968095541 -9.4286699295,0.669537901878,4.00667047501 -9.40768527985,0.668548822403,4.03223848343 -9.41169643402,0.670555233955,4.06782007217 -9.41470241547,0.671558320522,4.08660507202 -9.42071342468,0.672564387321,4.12318754196 -9.40072822571,0.672575294971,4.14974975586 -9.41273880005,0.674580395222,4.18933153152 -9.40175247192,0.674589574337,4.21890735626 -9.40376472473,0.675596475601,4.25448465347 -9.40377044678,0.676600217819,4.27226829529 -9.40578269958,0.678607165813,4.30784749985 -9.38879680634,0.677617669106,4.33541488647 -9.39780807495,0.679623246193,4.37400054932 -9.39882087708,0.681630373001,4.40957736969 -9.37283706665,0.679642617702,4.43314123154 -9.37884807587,0.681649029255,4.4717130661 -9.3928527832,0.683650135994,4.49551105499 -9.37186813354,0.682661414146,4.52108097076 -9.34288597107,0.681674361229,4.54363822937 -6.89228773117,0.4501324296,3.41041517258 -9.38690376282,0.68868124485,4.63580751419 -9.37691783905,0.688690543175,4.66638565063 -9.36793231964,0.689699709415,4.69795894623 -9.35593986511,0.688705682755,4.70974683762 -9.36995029449,0.69171077013,4.75332117081 -9.36796379089,0.692718625069,4.78790378571 -9.37097644806,0.694725811481,4.82647275925 -9.33299541473,0.692740380764,4.84304380417 -9.33400917053,0.693747937679,4.88061285019 -9.3640165329,0.698749959469,4.93220376968 -9.36302280426,0.69875395298,4.94999217987 -9.36203670502,0.700761914253,4.9865655899 -9.32905483246,0.69877576828,5.00613212585 -9.32506752014,0.699784219265,5.04070997238 -9.32508087158,0.700792074203,5.07827997208 -9.32709503174,0.70279955864,5.11685371399 -9.3231010437,0.703804075718,5.13264799118 -9.33511257172,0.705809772015,5.17722034454 -9.34412384033,0.708815693855,5.21880912781 -9.31414222717,0.706829309464,5.2403717041 -9.33115291595,0.710834026337,5.2879486084 -9.31816864014,0.71084433794,5.31852197647 -9.31618213654,0.711852550507,5.35510015488 -9.30219173431,0.711859285831,5.36687707901 -9.29820537567,0.71286791563,5.4024553299 -6.71368408203,0.459366172552,3.96024274826 -9.29423332214,0.715884566307,5.4766087532 -6.6947183609,0.459386825562,4.0043964386 -6.65374135971,0.456403106451,4.00796556473 -6.66775465012,0.459408938885,4.04355335236 -9.29329490662,0.722920835018,5.65069913864 -9.27931118011,0.72393155098,5.68127298355 -6.69880342484,0.466433137655,4.16008758545 -6.68282270432,0.466444820166,4.17866230011 -9.27135276794,0.727957427502,5.79499530792 -6.6408624649,0.464470237494,4.20980453491 -6.61887407303,0.463478863239,4.2105846405 -6.46391963959,0.448517233133,4.14212322235 -6.63890218735,0.467492341995,4.27975130081 -6.60192584991,0.46550822258,4.28531551361 -6.61393976212,0.467514753342,4.32189273834 -6.63095188141,0.471520185471,4.36147880554 -6.58496856689,0.466533362865,4.3462562561 -6.59498262405,0.469539999962,4.38084888458 -6.59299945831,0.470549404621,4.40941476822 -6.54102516174,0.466568082571,4.4039850235 -6.50504827499,0.464583694935,4.40856361389 -6.51306295395,0.466591030359,4.44314002991 -6.53206777573,0.46959194541,4.47092723846 -6.52908468246,0.470601141453,4.49751472473 -6.51710319519,0.470612406731,4.51908588409 -6.36314964294,0.45565122366,4.44362306595 -6.39516019821,0.460654109716,4.49519968033 -6.44416713715,0.467653363943,4.55779743195 -6.40719032288,0.464669436216,4.5613694191 -6.39520120621,0.464676350355,4.56814956665 -6.42521190643,0.468679428101,4.61873579025 -6.39523410797,0.467694252729,4.62730646133 -6.32526540756,0.461716741323,4.60687208176 -6.32128238678,0.462726503611,4.63345146179 -6.32029914856,0.463735580444,4.6620349884 -6.32331514359,0.465744167566,4.69460630417 -6.32232379913,0.46674901247,4.70938825607 -6.49630498886,0.486723929644,4.86701202393 -6.36434841156,0.473758548498,4.79957008362 -6.36836433411,0.475767105818,4.83413505554 -6.37637901306,0.478774279356,4.86973047256 -6.41838741302,0.484775394201,4.93330478668 -6.36041593552,0.479795664549,4.91987800598 -6.35442590714,0.479801625013,4.93165493011 -6.24046611786,0.469832807779,4.87422323227 -6.29247283936,0.476831912994,4.94580364227 -6.35847520828,0.485827803612,5.02740812302 -6.28250837326,0.478852301836,5.00095129013 -6.27052783966,0.479863673449,5.02253198624 -6.29553079605,0.482863128185,5.05733585358 -6.32054233551,0.487867385149,5.10891962051 -6.27256965637,0.483886033297,5.10248756409 -6.30957841873,0.489887863398,5.16407585144 -6.23161220551,0.48291260004,5.13363075256 -6.20663499832,0.481926739216,5.14520454407 -6.22964668274,0.48593133688,5.19579267502 -6.20466089249,0.483940958977,5.19157361984 -6.1916809082,0.484952777624,5.2131485939 -6.19869661331,0.486960738897,5.25172424316 -6.19771385193,0.488970160484,5.28330469131 -6.17973470688,0.488983005285,5.30087995529 -6.19774770737,0.492988556623,5.34846925735 -6.17976856232,0.492001384497,5.36604595184 -6.17577886581,0.493007004261,5.37982606888 -6.16679763794,0.494018107653,5.40540218353 -6.17581319809,0.497025460005,5.44599056244 -6.19282674789,0.501031696796,5.49555969238 -6.15685176849,0.498048007488,5.49713850021 -6.15786886215,0.500057160854,5.53172063828 -6.16387653351,0.502060711384,5.55450534821 -6.17589092255,0.505067586899,5.59909152985 -6.15091371536,0.505081832409,5.61067008972 -6.1409330368,0.505093276501,5.63624572754 -6.15194797516,0.509100437164,5.68082809448 -6.13996839523,0.509112417698,5.70539665222 -6.14698457718,0.512120366096,5.74697685242 -6.12699747086,0.511129021645,5.74576616287 -6.13501405716,0.514137089252,5.78933668137 -6.13003253937,0.516147434711,5.81991815567 -6.12105178833,0.517158806324,5.84749174118 -6.14206457138,0.52116394043,5.90307760239 -6.13408374786,0.522175014019,5.93165493011 -6.14209938049,0.526182711124,5.97524166107 -6.13510990143,0.526188910007,5.98702716827 -6.13012838364,0.52719938755,6.0186085701 -6.13114595413,0.530208826065,6.05718040466 -6.12816429138,0.532218754292,6.0907664299 -6.1201839447,0.533230185509,6.1213312149 -6.11620235443,0.535240232944,6.15392112732 -6.11221170425,0.535245776176,6.16871070862 -6.117228508,0.538254261017,6.21129417419 -6.11024808884,0.540265381336,6.24286651611 -6.10726690292,0.5422757864,6.27943134308 -6.09928607941,0.543286800385,6.3090171814 -6.10630226135,0.547295093536,6.35559129715 -6.09632253647,0.548306643963,6.38417053223 -6.09333229065,0.549312114716,6.40095567703 -6.09534978867,0.551321387291,6.44253444672 -6.08536958694,0.553332865238,6.47111749649 -6.08538770676,0.555342674255,6.51168870926 -6.09140396118,0.558350801468,6.55727863312 -6.08042478561,0.560362935066,6.58684635162 -6.0884308815,0.562365889549,6.61464834213 -6.09744739532,0.566373944283,6.66621875763 -6.0854678154,0.567385911942,6.69380092621 -6.0884847641,0.570394933224,6.7383813858 -6.0705075264,0.57040822506,6.75995969772 -6.10351753235,0.577411472797,6.83953428268 -6.06654453278,0.575428545475,6.84011077881 -6.06955289841,0.577432870865,6.86489868164 -6.07556915283,0.58044141531,6.91447639465 -6.05459213257,0.580455243587,6.93305683136 -6.09759998322,0.589456379414,7.02564001083 -8.98689365387,0.96987849474,10.3898057938 -8.98890972137,0.974887669086,10.4573822021 -8.96893119812,0.975901484489,10.49995327 -8.96693992615,0.977906703949,10.5307397842 -8.36910820007,0.903038024902,9.89319896698 -8.18517208099,0.883085310459,9.73873138428 -8.10420894623,0.876111626625,9.70428752899 -8.0452413559,0.8721331954,9.69386005402 -7.97127723694,0.866158127785,9.66641807556 -7.94929981232,0.867172241211,9.69999694824 -7.90631961823,0.864185929298,9.67877388 -7.84535312653,0.859208285809,9.66633224487 -7.75539302826,0.851236343384,9.61589717865 -7.70642280579,0.849256157875,9.61646175385 -7.72043704987,0.855263113976,9.69504261017 -7.83942365646,0.875248551369,9.90564727783 -7.59849452972,0.844302594662,9.63339042664 -3.4455769062,0.272155165672,4.42535352707 -3.4286005497,0.272168368101,4.43094110489 -3.40562677383,0.271183371544,4.43050193787 -3.37265443802,0.26819974184,4.41509056091 -7.36364364624,0.832400143147,9.64122486115 -7.34566688538,0.834413707256,9.67979717255 -7.24970054626,0.822438180447,9.58456897736 -7.25771570206,0.828446388245,9.65615463257 -7.19175100327,0.823469817638,9.63072013855 -7.10379266739,0.814497888088,9.57627391815 -7.06981945038,0.814514636993,9.59185028076 -7.00885295868,0.809537053108,9.57141685486 -6.97787046432,0.807548344135,9.5602016449 -6.92690229416,0.804568767548,9.55276870728 -6.89192914963,0.80358594656,9.56733703613 -6.83396291733,0.79960757494,9.547914505 -6.79599094391,0.798625349998,9.55748558044 -6.75202083588,0.795644462109,9.55905151367 -6.73304414749,0.797658264637,9.59463024139 -6.65907287598,0.788678467274,9.52140426636 -6.64009618759,0.790692389011,9.55698013306 -6.58512973785,0.786713719368,9.54154586792 -6.53316164017,0.78373414278,9.52812385559 -6.52418279648,0.786746263504,9.57969284058 -6.47521448135,0.783766448498,9.57225894928 -6.48522996902,0.789774239063,9.64984703064 -6.47724151611,0.790781199932,9.67162704468 -6.36928892136,0.778813004494,9.57320022583 -6.27933216095,0.76984167099,9.50375366211 -6.23436260223,0.766860902309,9.49932765961 -6.19539213181,0.765878796577,9.50290870667 -6.21640491486,0.773884773254,9.60048484802 -6.11945009232,0.762914717197,9.51604747772 -6.09446573257,0.761924743652,9.50883865356 -6.05449581146,0.759943246841,9.51240348816 -6.06151247025,0.765951812267,9.58798885345 -5.97455501556,0.756979644299,9.51555633545 -5.94758176804,0.756995439529,9.5391254425 -5.93460416794,0.760008394718,9.58470058441 -5.91661834717,0.759017109871,9.58848953247 -5.97562074661,0.774015247822,9.75107765198 -5.88266515732,0.764044344425,9.66664505005 -5.87468671799,0.767056167126,9.72122192383 -5.84571361542,0.768072485924,9.74278831482 -5.87772369385,0.77807611227,9.86437606812 -5.86674594879,0.781088411808,9.91495800018 -5.87075424194,0.785092711449,9.9567489624 -5.88376951218,0.792100429535,10.0503263474 -5.8717918396,0.795113027096,10.1009063721 -5.8878068924,0.804120063782,10.2014846802 -5.87582921982,0.807132780552,10.2540626526 -5.89084434509,0.81514018774,10.3556365967 -5.82788085938,0.810163140297,10.3182144165 -5.87787628174,0.8211581707,10.4450063705 -5.87989473343,0.827167868614,10.5235919952 -5.92390155792,0.841169416904,10.6811695099 -5.9179224968,0.846180975437,10.7487478256 -5.92893886566,0.854189097881,10.8483285904 -5.86797475815,0.84921169281,10.81590271 -5.89597654343,0.85721129179,10.9086904526 -5.89599609375,0.863221645355,10.9902687073 -5.90001440048,0.87023127079,11.0808448792 -5.89703416824,0.876242220402,11.1584243774 -5.894053936,0.882253050804,11.2360076904 -5.87607860565,0.88526725769,11.2885761261 -5.85810279846,0.888281285763,11.3401517868 -5.89710140228,0.899278581142,11.4589481354 -5.87312746048,0.901293754578,11.4995260239 -5.8591504097,0.90530693531,11.5601053238 -5.86816740036,0.914315521717,11.6676855087 -5.86718702316,0.921326100826,11.7562665939 -5.86020803452,0.927338004112,11.8348407745 -5.96819734573,0.955326676369,12.1484289169 -5.88622999191,0.943348348141,12.0282115936 -5.91524171829,0.956353127956,12.1847867966 -5.87027359009,0.954372644424,12.1883621216 -5.86929368973,0.962383270264,12.2839403152 -5.86931276321,0.970393717289,12.3825206757 -5.88232851028,0.980401515961,12.5101032257 -5.85334587097,0.978412508965,12.4978933334 -3.60800719261,0.528874456882,7.76827764511 -3.51609396935,0.524923920631,7.75900936127 -3.45115280151,0.52095746994,7.74217224121 -3.43816685677,0.520965337753,7.74595737457 -3.38731336594,0.545042693615,8.06523036957 -3.36034178734,0.544058561325,8.07180500031 -3.32937073708,0.543075025082,8.06738758087 -3.30139946938,0.543091058731,8.07096385956 -3.27542734146,0.542106688023,8.07953929901 -3.24945473671,0.542121887207,8.08513355255 -3.22348284721,0.542137563229,8.09370803833 -3.20849776268,0.542145967484,8.09448719025 -3.1895236969,0.5431599617,8.11907291412 -3.46046566963,0.613116621971,8.89066028595 -2.98166561127,0.517242610455,7.87539148331 -2.97667717934,0.519248664379,7.89818716049 -2.95270514488,0.519264042377,7.91075706482 -2.87276935577,0.511300563812,7.84491634369 -2.84879732132,0.512315750122,7.85549354553 -2.82282495499,0.511331021786,7.85808372498 -2.74696087837,0.527403175831,8.07877349854 -2.72498774529,0.528417825699,8.09635543823 -2.71300172806,0.528425335884,8.10214710236 -2.6033039093,0.597582399845,8.96668624878 -2.53134655952,0.583607077599,8.82325744629 -2.35743904114,0.545661449432,8.41043186188 -2.33648705482,0.555686235428,8.53959655762 -2.32152318954,0.564705014229,8.64595890045 -2.32454276085,0.57471460104,8.76454639435 -2.31156754494,0.579727590084,8.82712650299 -2.29859280586,0.584740638733,8.89170360565 -2.28661704063,0.589753329754,8.96028614044 -2.27864027023,0.596765339375,9.04786396027 -2.28265023232,0.603769958019,9.12564849854 -2.27567315102,0.611781597137,9.2192325592 -2.26471853256,0.628804802895,9.4303855896 -2.26573872566,0.639814913273,9.56497097015 -2.30474829674,0.666817903519,9.8685503006 -2.2517952919,0.663843691349,9.84892368317 -2.23482227325,0.669857740402,9.92248916626 -2.19285511971,0.664875984192,9.87608146667 -2.075963974,0.661934912205,9.85761547089 -2.96975922585,1.09579610825,14.8353252411 -2.92379426956,1.09681558609,14.8479032516 -2.66789245605,1.00187492371,13.7684841156 -2.87785029411,1.11884558201,15.118057251 -2.83587312698,1.10985863209,15.0198545456 -2.80690312386,1.11887490749,15.1304283142 -2.75593924522,1.11689519882,15.1190090179 -2.67198562622,1.09892165661,14.9195919037 -2.66400909424,1.11893379688,15.1511697769 -2.64603567123,1.13394784927,15.3317489624 -2.59107327461,1.12996888161,15.2983293533 -2.61007833481,1.15297055244,15.5621166229 -2.57311058044,1.15898811817,15.6426963806 -2.52114725113,1.15700852871,15.632276535 -2.47218298912,1.15702819824,15.6358623505 -2.42421865463,1.15804791451,15.6504430771 -2.39024996758,1.16606485844,15.7580223083 -2.33928704262,1.16608512402,15.7595968246 -2.31530427933,1.16609477997,15.7633934021 -2.91314411163,1.56099283695,20.3209648132 -2.85018444061,1.56201529503,20.3375415802 -2.7922232151,1.56603705883,20.3911190033 -2.12844586372,1.17317187786,15.871717453 -2.07948207855,1.17419159412,15.886297226 -2.63832306862,1.57009243965,20.4570713043 -2.57836222649,1.57311427593,20.4986515045 -2.51640224457,1.57413649559,20.5262298584 -2.45444250107,1.57615864277,20.5548095703 -2.39148259163,1.57718086243,20.57239151 -2.32752323151,1.57720339298,20.5829753876 -2.26356434822,1.57822608948,20.6015491486 -2.23258399963,1.57923698425,20.6113452911 -2.16862487793,1.58025944233,20.6259231567 -2.10466551781,1.58028185368,20.637506485 -2.04170608521,1.58230412006,20.6640853882 -1.9777469635,1.58332657814,20.6856632233 -1.91478741169,1.58534872532,20.7112445831 -1.88280773163,1.58535981178,20.7180366516 -1.81784892082,1.58638250828,20.7266178131 -1.75189006329,1.58440494537,20.7102050781 -1.68393218517,1.58142805099,20.6857814789 -1.61797356606,1.58045065403,20.6743659973 -1.55301487446,1.58047306538,20.6789474487 -1.49105489254,1.58349478245,20.7195301056 -1.46007525921,1.58650588989,20.755317688 -1.3971157074,1.58852767944,20.7829036713 -1.34015452862,1.60054862499,20.9264812469 -1.28119373322,1.60956978798,21.0330677032 -1.22023379803,1.61759138107,21.1286487579 -1.15227603912,1.61561429501,21.1092281342 -1.08131885529,1.60663735867,21.006816864 -1.04734015465,1.60564875603,21.0026035309 -0.981381475925,1.60467112064,20.9871921539 -0.915423154831,1.60469341278,20.9977722168 -0.848464906216,1.60271596909,20.9723548889 -0.782506585121,1.60273826122,20.9789390564 -0.716547966003,1.60176026821,20.9605236053 -0.649590015411,1.59978282452,20.9481048584 -0.616610646248,1.59879374504,20.927898407 -0.550652265549,1.59781599045,20.9264812469 -0.48469388485,1.59783816338,20.9200649261 -0.418735444546,1.59686028957,20.911649704 -0.35277697444,1.59488224983,20.8862342834 -0.287818014622,1.5939040184,20.8848228455 -0.254838854074,1.59391498566,20.8746128082 -0.18888053298,1.59293711185,20.8691959381 -0.122922226787,1.5909589529,20.8517799377 -0.0579633302987,1.59198069572,20.8613681793 --0.024983715266,1.60600852966,19.6598320007 --0.0869432985783,1.60402965546,19.6414146423 --0.147903472185,1.60205054283,19.6160049438 --0.209863051772,1.60207164288,19.6195869446 --0.240842938423,1.60408210754,19.6403808594 --0.301803022623,1.60210287571,19.6139678955 --0.363762676716,1.60312402248,19.6225528717 --0.424722731113,1.60114467144,19.5941390991 --0.48668217659,1.60016572475,19.5827217102 --0.548641860485,1.60118663311,19.5903053284 --0.578622221947,1.60019683838,19.5841026306 --0.639582276344,1.59921741486,19.569688797 --0.70154184103,1.59923827648,19.5672740936 --0.763501465321,1.60025918484,19.5738582611 --0.824461519718,1.59927964211,19.5594463348 --0.886421322823,1.60030043125,19.5720329285 --0.947381317616,1.59932088852,19.5546207428 --0.978361189365,1.60033118725,19.56341362 --1.04032099247,1.60135173798,19.5690021515 --1.10228085518,1.6023722887,19.5795898438 --1.16424047947,1.60239291191,19.5791759491 --1.22720003128,1.60441362858,19.5977630615 --1.28915965557,1.60543417931,19.5973510742 --1.35011994839,1.60545432568,19.5939426422 --1.38109970093,1.60546457767,19.5877323151 --1.44405937195,1.60748505592,19.6093235016 --1.50401961803,1.6045050621,19.5759086609 --1.56597959995,1.60652530193,19.5825004578 --1.62893903255,1.60754585266,19.5950889587 --1.69289827347,1.61056649685,19.6176757812 --1.72487771511,1.61157667637,19.6224689484 --1.78783726692,1.61259710789,19.6300563812 --1.84879767895,1.61261701584,19.6246490479 --1.91275691986,1.61463749409,19.6412372589 --1.97771596909,1.61765801907,19.6688270569 --2.03867602348,1.6166779995,19.6524162292 --2.10363483429,1.61969852448,19.6710014343 --2.13561463356,1.61970865726,19.6777954102 --2.19957399368,1.62272882462,19.696390152 --2.26353335381,1.62374925613,19.7019748688 --2.32849240303,1.62676954269,19.7245693207 --2.39445114136,1.62978994846,19.7501602173 --2.45941019058,1.63181042671,19.7637481689 --2.5223698616,1.63283014297,19.7653408051 --2.5563492775,1.63484048843,19.7831344604 --2.6213080883,1.63686084747,19.7947254181 --2.68726682663,1.63888120651,19.8133144379 --2.75022673607,1.63990092278,19.8099040985 --2.8161854744,1.64192128181,19.8244934082 --2.88014507294,1.6439409256,19.8310890198 --2.9441049099,1.64496076107,19.8336811066 --2.97808384895,1.64597094059,19.8464736938 --3.04804134369,1.65099167824,19.8860664368 --3.10900187492,1.65001106262,19.8636550903 --3.17695999146,1.65303134918,19.8872451782 --3.23992037773,1.65405070782,19.8838405609 --3.30787873268,1.65707099438,19.9074344635 --3.34085798264,1.65708100796,19.9092254639 --3.40681695938,1.65910077095,19.9178180695 --3.47177624702,1.66012048721,19.9184074402 --3.53973507881,1.66314041615,19.9390029907 --3.60169529915,1.66315948963,19.9225921631 --3.66765475273,1.66517913342,19.9331912994 --3.73661279678,1.66819941998,19.9517784119 --3.77259135246,1.67020952702,19.971578598 --3.83855080605,1.67222905159,19.9781723022 --3.90750908852,1.67524909973,19.9957637787 --3.97346806526,1.67626845837,19.9983577728 --4.05442285538,1.68529033661,20.0769538879 --4.11638355255,1.68430900574,20.0575447083 --4.18034362793,1.68532800674,20.0501403809 --4.22032117844,1.68933868408,20.0839385986 --4.28927898407,1.69135856628,20.0955276489 --4.35923719406,1.6943782568,20.111120224 --4.42919588089,1.69739806652,20.1277141571 --4.49515533447,1.69841718674,20.1273117065 --4.56611299515,1.70143699646,20.145904541 --4.60009288788,1.70244657993,20.1497039795 --4.66905117035,1.70546603203,20.1602993011 --4.73800992966,1.70748543739,20.1678924561 --4.80796813965,1.70950484276,20.179485321 --4.87592744827,1.7115240097,20.1840839386 --4.94588565826,1.7145434618,20.1946773529 --5.0178437233,1.7175630331,20.2132740021 --5.05482244492,1.71957302094,20.2270736694 --5.1207818985,1.7205915451,20.219669342 --5.19573879242,1.72461163998,20.2482643127 --5.26269817352,1.72563016415,20.2428569794 --5.33265686035,1.72864937782,20.2484512329 --5.40161657333,1.73066818714,20.2530517578 --5.47757339478,1.73468804359,20.2836532593 --5.52454900742,1.73969936371,20.330450058 --5.58351039886,1.7377165556,20.2910404205 --5.59348773956,1.71972620487,20.0816364288 --5.64445209503,1.71574211121,20.0192298889 --5.70841264725,1.7157599926,20.002822876 --5.77837181091,1.71877861023,20.0114250183 --5.55642795563,1.63474881649,19.1231937408 --5.59939527512,1.62876331806,19.0457878113 --5.63936328888,1.62277746201,18.9613838196 --5.66433572769,1.6107891798,18.8269748688 --5.68430948257,1.59880030155,18.678565979 --5.69728565216,1.58481013775,18.5101566315 --5.68027019501,1.56081557274,18.24974823 --5.69525575638,1.55682182312,18.1945400238 --5.70423316956,1.54183113575,18.0241336823 --5.73920249939,1.5348443985,17.9357242584 --5.78416919708,1.53185892105,17.8833236694 --5.82113790512,1.52687227726,17.8059196472 --5.88709831238,1.52889001369,17.8155136108 --5.94306182861,1.52890622616,17.7961082458 --5.9550485611,1.52491188049,17.7399082184 --5.9780216217,1.51492297649,17.6245040894 --6.06097745895,1.52294301987,17.6861057281 --6.09794664383,1.51795625687,17.6096935272 --6.16290712357,1.51997351646,17.6182937622 --6.2118730545,1.51898825169,17.5798892975 --6.24185419083,1.51899647713,17.5776920319 --6.2978181839,1.52001225948,17.5592880249 --6.346783638,1.51802718639,17.5198822021 --6.39375019073,1.51604151726,17.4794826508 --6.44971418381,1.51605713367,17.4600791931 --6.52167320251,1.52007508278,17.4846763611 --6.59863138199,1.52609360218,17.5232791901 --6.62361383438,1.52610087395,17.5070819855 --6.67757892609,1.52511608601,17.4816761017 --6.75853538513,1.53213500977,17.5272769928 --6.82249689102,1.53415155411,17.5278739929 --6.86846446991,1.53216540813,17.4834728241 --6.95241975784,1.53918457031,17.5340747833 --6.98839044571,1.53419685364,17.465675354 --7.02636957169,1.53720581532,17.4804763794 --7.0913310051,1.53922224045,17.4810714722 --7.1542930603,1.54123842716,17.4766693115 --7.21725559235,1.54325437546,17.4742717743 --7.29521369934,1.54927241802,17.5068759918 --7.34717941284,1.54828667641,17.4754734039 --7.36516427994,1.54629266262,17.4422740936 --7.45012044907,1.55331158638,17.4878730774 --7.54707336426,1.56333184242,17.5624790192 --7.58204364777,1.55834364891,17.4910774231 --7.66500091553,1.56436192989,17.5326843262 --7.70397043228,1.56137430668,17.4692783356 --7.75593662262,1.56038820744,17.437877655 --7.80691194534,1.56539845467,17.4796829224 --7.8808722496,1.57041537762,17.4962844849 --7.95583105087,1.57443237305,17.5148868561 --8.01579475403,1.57544708252,17.5004882812 --8.05576515198,1.57245922089,17.4420871735 --8.11772823334,1.57347416878,17.4306869507 --8.19968605042,1.5794917345,17.4642963409 --8.21567153931,1.57749724388,17.4260940552 --8.26563835144,1.57651042938,17.3886909485 --8.32660293579,1.57752501965,17.3762969971 --8.37257099152,1.57553768158,17.3298931122 --8.50951290131,1.59256219864,17.4735050201 --8.62346172333,1.60558354855,17.5681190491 --8.63644886017,1.60258841515,17.5239162445 --8.65942382812,1.5955978632,17.4305114746 --8.72938537598,1.59861326218,17.4331150055 --8.77735328674,1.59762573242,17.3927192688 --8.84031677246,1.59864008427,17.3803215027 --8.91927719116,1.60365641117,17.3999290466 --9.041223526,1.61767840385,17.5025405884 --9.04621315002,1.61268210411,17.4443397522 --9.05219268799,1.6036888361,17.321937561 --9.11315822601,1.60470271111,17.3045387268 --9.16112613678,1.60371482372,17.2631397247 --9.17410469055,1.59472262859,17.1547317505 --9.25006484985,1.59973812103,17.1673412323 --9.38101005554,1.61476051807,17.2799549103 --9.42898750305,1.61876952648,17.3037605286 --9.51494503021,1.62478601933,17.3313674927 --9.53392219543,1.61779427528,17.2359657288 --9.58588981628,1.61680650711,17.2005672455 --9.63385868073,1.61581814289,17.1601715088 --9.69582271576,1.61783158779,17.1427745819 --9.71380996704,1.61583662033,17.1115760803 --9.78177261353,1.6188505888,17.1051826477 --9.85573482513,1.62186515331,17.1087875366 --9.93769454956,1.62788069248,17.1263961792 --10.0356492996,1.63589811325,17.1710109711 --10.2235794067,1.65992617607,17.3676357269 --10.2335596085,1.65193283558,17.2592315674 --10.3465185165,1.66694915295,17.3870449066 --10.7823810577,1.73600661755,17.9937133789 --10.8473463058,1.73701941967,17.9733200073 --10.9263067245,1.74103391171,17.9759311676 --10.9842748642,1.74104571342,17.9435367584 --11.0482406616,1.74305808544,17.9221496582 --11.1122055054,1.74407052994,17.8987541199 --11.132191658,1.74307525158,17.8675556183 --11.1951570511,1.74408745766,17.8421611786 --11.2341299057,1.741096735,17.7787628174 --11.294095993,1.74210834503,17.7503738403 --11.3450660706,1.74111902714,17.7059764862 --11.4080324173,1.74213087559,17.6815853119 --11.447013855,1.74413776398,17.6803894043 --11.524974823,1.74815118313,17.6790027618 --11.581943512,1.74816215038,17.6436080933 --11.6559066772,1.75117504597,17.6352176666 --11.7078762054,1.75018525124,17.5928249359 --11.7628450394,1.75019586086,17.5544300079 --11.8158140182,1.75020623207,17.5130367279 --11.8387994766,1.74921095371,17.4878406525 --11.8877706528,1.74822068214,17.4404449463 --11.9387407303,1.74823057652,17.3970527649 --11.9967088699,1.74824106693,17.3646621704 --12.0426807404,1.74725031853,17.3132686615 --12.1136455536,1.74926233292,17.2978744507 --12.1286249161,1.74326789379,17.2034778595 --12.130616188,1.73927009106,17.1482753754 --12.2775621414,1.75429010391,17.2419033051 --12.3045387268,1.74929702282,17.1635036469 --12.3065223694,1.74130117893,17.0510997772 --12.3195028305,1.73530638218,16.9556999207 --12.3134889603,1.72530961037,16.8342971802 --12.3024768829,1.71531236172,16.708896637 --12.2894716263,1.7093129158,16.6346893311 --12.2774591446,1.69931542873,16.5082836151 --12.2704458237,1.69031858444,16.389881134 --12.2334403992,1.677318573,16.2324714661 --12.2204275131,1.66732108593,16.1080646515 --12.2084150314,1.65732371807,15.9866609573 --8.91426944733,1.15298843384,11.6007757187 --8.92525005341,1.14899504185,11.5393743515 --8.96222305298,1.15000414848,11.5119791031 --9.00219535828,1.15001356602,11.4885854721 --9.05816364288,1.15302455425,11.4841861725 --12.2983064651,1.63035333157,15.5344657898 --12.4432544708,1.64437150955,15.6170949936 --12.4552440643,1.64237439632,15.5818986893 --12.4442310333,1.63337695599,15.4654884338 --12.5181970596,1.63738763332,15.4570999146 --12.7031345367,1.65740931034,15.5857372284 --12.7850980759,1.66142058372,15.5863552094 --12.8120756149,1.65842652321,15.5189609528 --12.7380809784,1.64142262936,15.3295450211 --12.9810113907,1.67244768143,15.5733938217 --13.0729732513,1.6784594059,15.5840139389 --13.129942894,1.6794680357,15.5516233444 --12.2111625671,1.54138445854,14.3610200882 --13.2948732376,1.68948948383,15.5468559265 --13.3908338547,1.69650137424,15.558470726 --13.4578018188,1.69851052761,15.5370855331 --13.517780304,1.70351743698,15.5568971634 --13.5897474289,1.70652675629,15.5415172577 --13.7296981812,1.71954226494,15.601140976 --13.7866697311,1.72055006027,15.5667552948 --13.8356437683,1.72055697441,15.5233669281 --14.1035633087,1.75058352947,15.7240200043 --13.9216022491,1.72256839275,15.47078228 --5.80460309982,0.598852694035,6.33341884613 --5.7535982132,0.588854908943,6.23700523376 --5.70745563507,0.560909330845,5.85350370407 --5.72143363953,0.559917449951,5.82908582687 --5.73041296005,0.558924973011,5.80067825317 --5.71440839767,0.554926872253,5.7664809227 --5.73838424683,0.555935740471,5.75307035446 --5.69137716293,0.546938836575,5.66764307022 --5.67036485672,0.541943848133,5.61023283005 --6.75237083435,0.584287941456,5.04179573059 --5.49856472015,0.432247728109,3.96671295166 --5.49555683136,0.431250631809,3.95151734352 --7.32101106644,0.621397137642,4.94285678864 --7.40597867966,0.629405856133,4.96748113632 --11.7980766296,1.11560046673,7.922270298 --11.8100624084,1.1146030426,7.875872612 --11.8120498657,1.1116052866,7.82347536087 --11.812037468,1.1096072197,7.76907157898 --11.8080263138,1.10560917854,7.71267032623 --11.8000154495,1.10261082649,7.6532626152 --11.7900104523,1.09961140156,7.6200594902 --11.7859992981,1.09661340714,7.56365203857 --11.7799882889,1.09361517429,7.50725269318 --11.7809762955,1.09061717987,7.45384120941 --11.779964447,1.08861911297,7.40043735504 --11.7809524536,1.08562099934,7.34903860092 --11.7689428329,1.08162248135,7.28963565826 --11.7609386444,1.07962310314,7.25843095779 --11.7689247131,1.0786254406,7.21102666855 --11.764913559,1.07562708855,7.15662097931 --11.7569026947,1.07162857056,7.10021591187 --11.7518920898,1.06863033772,7.04681873322 --11.7528810501,1.0666321516,6.995408535 --11.7548685074,1.06463396549,6.94600868225 --11.7418651581,1.06163442135,6.91280317307 --11.7498521805,1.06063652039,6.86740541458 --11.7428417206,1.05763804913,6.81300163269 --11.7358312607,1.05463957787,6.75758695602 --11.739818573,1.05264139175,6.71018743515 --11.7338085175,1.04964280128,6.65778970718 --11.7268037796,1.04764354229,6.62858343124 --11.7347917557,1.04664540291,6.5831785202 --11.7157840729,1.04164648056,6.52377605438 --11.7177715302,1.03964817524,6.47536993027 --11.7197599411,1.03764986992,6.42696285248 --11.7347459793,1.03765177727,6.38757276535 --11.6557483673,1.02665150166,6.29514360428 --11.7897186279,1.03965520859,6.34498643875 --11.9006881714,1.04965901375,6.35661649704 --11.9576673508,1.05366146564,6.33923768997 --12.039642334,1.05966436863,6.33385753632 --12.0886116028,1.06066775322,6.26207113266 --12.3205461502,1.07967424393,6.26114654541 --12.2515468597,1.07067406178,6.17571926117 --12.2595357895,1.06867516041,6.13031625748 --12.2485275269,1.06567585468,6.07591152191 --13.7932596207,1.2226973772,6.80904579163 --13.8202457428,1.22369742393,6.7676525116 --13.8572359085,1.22669768333,6.75946950912 --13.8882217407,1.22769761086,6.720079422 --13.9432039261,1.23069787025,6.69269943237 --12.2484712601,1.05568039417,5.80970048904 --12.2384624481,1.05268108845,5.75729799271 --12.2464504242,1.05168175697,5.7128944397 --12.140458107,1.03868174553,5.61445188522 --12.2274398804,1.04668271542,5.63228273392 --14.1481246948,1.23969602585,6.48956155777 --14.1861114502,1.24169552326,6.45317792892 --14.2200965881,1.24269473553,6.41378545761 --14.2850799561,1.2476940155,6.38941049576 --14.3010692596,1.24669313431,6.34201574326 --14.3520536423,1.24969232082,6.31063461304 --14.3650474548,1.2506916523,6.28944063187 --14.3530416489,1.24669063091,6.22903299332 --14.3110408783,1.24068927765,6.15561437607 --14.2540416718,1.23268818855,6.07719802856 --14.1680469513,1.22268712521,5.98576402664 --14.108048439,1.21468603611,5.90734767914 --14.0450496674,1.20668506622,5.82691907883 --13.9570589066,1.19668483734,5.76369094849 --13.8930606842,1.18868398666,5.68426465988 --13.8340616226,1.1806833744,5.60784196854 --11.5823688507,0.953694581985,4.57919740677 --11.5803594589,0.951695382595,4.5357966423 --11.570350647,0.9496961236,4.48939371109 --11.5703458786,0.948696494102,4.46819257736 --11.5743350983,0.947697222233,4.4267873764 --11.5583276749,0.944697976112,4.37838172913 --11.5583181381,0.943698644638,4.33597707748 --11.574306488,0.943699121475,4.29957675934 --11.5563001633,0.940699934959,4.25117349625 --11.5552949905,0.939700245857,4.22997331619 --11.5622844696,0.938700735569,4.18956184387 --11.5472774506,0.935701489449,4.14215373993 --11.5442676544,0.934702038765,4.09975385666 --11.5552568436,0.934702396393,4.06235647202 --11.5442495346,0.931703031063,4.0169506073 --11.5402412415,0.930703520775,3.97354102135 --11.5412359238,0.929703772068,3.95334100723 --11.5352277756,0.927704334259,3.9099354744 --11.5292186737,0.925704777241,3.86652898788 --11.5362091064,0.925705015659,3.82813048363 --11.5262022018,0.92370557785,3.78372383118 --11.5331916809,0.922705769539,3.74532413483 --11.526184082,0.920706212521,3.70191597939 --11.5111808777,0.918706715107,3.6767103672 --11.5081720352,0.917707026005,3.63530778885 --11.3901767731,0.904710233212,3.55585646629 --11.3861694336,0.903710603714,3.51445055008 --11.4011583328,0.903710484505,3.47905015945 --11.3861513138,0.900711238384,3.434643507 --11.3691444397,0.898711919785,3.38923048973 --11.3731403351,0.898711919785,3.37103414536 --11.3661317825,0.896712362766,3.32963204384 --11.3791217804,0.896712124348,3.29423522949 --11.365114212,0.894712686539,3.2498190403 --11.3631057739,0.892712950706,3.21042084694 --11.3640966415,0.891713023186,3.17101335526 --11.3590898514,0.890713274479,3.13061070442 --11.3410863876,0.888713896275,3.10539746284 --11.3530769348,0.888713538647,3.07000088692 --11.3570680618,0.887713432312,3.03260397911 --11.3560600281,0.886713504791,2.99319863319 --11.3450527191,0.884713828564,2.95078539848 --11.3390455246,0.883714020252,2.91037964821 --11.3320417404,0.882714271545,2.88917541504 --11.3380327225,0.881713986397,2.85278105736 --11.3400249481,0.881713807583,2.81437492371 --11.3200187683,0.878714442253,2.77096700668 --11.3430080414,0.87971329689,2.7385737896 --11.3370008469,0.87871336937,2.69816303253 --11.2929973602,0.873715102673,2.64874100685 --11.2939891815,0.872714877129,2.61134314537 --11.3259830475,0.875713229179,2.60015416145 --11.3599710464,0.877711415291,2.56975960732 --11.389960289,0.879709601402,2.53937554359 --11.4269504547,0.882707417011,2.50998854637 --11.4549398422,0.884705543518,2.47759079933 --11.4809303284,0.885703742504,2.4451982975 --11.4479255676,0.881704866886,2.39978599548 --11.4049253464,0.877706766129,2.37056136131 --11.6118936539,0.895694553852,2.33984398842 --11.6388845444,0.897692263126,2.30745697021 --11.6818742752,0.900689005852,2.27807402611 --11.7148647308,0.902686178684,2.24567961693 --11.7278604507,0.903684973717,2.22948908806 --11.7498521805,0.905682682991,2.19509506226 --11.7838420868,0.907679617405,2.16270303726 --11.8288326263,0.911675810814,2.13332629204 --11.8098278046,0.908675670624,2.0899078846 --11.2458620071,0.855709254742,1.94325840473 --11.3468484879,0.864702224731,1.9259070158 --11.4438381195,0.872695684433,1.9247418642 --11.7388105392,0.899675905704,1.94147205353 --12.0527830124,0.928654193878,1.95920526981 --11.9637832642,0.91965842247,1.90376091003 --11.7557907104,0.89967083931,1.82927381992 --11.3578100204,0.8616964221,1.72268950939 --11.3248062134,0.858697712421,1.68027353287 --11.309803009,0.856698155403,1.65906274319 --11.4057912827,0.865690410137,1.63770210743 --11.3897857666,0.863690435886,1.59829509258 --11.4107780457,0.864687681198,1.56389522552 --11.4817676544,0.870681226254,1.53752326965 --11.4077663422,0.863685488701,1.49009668827 --11.4287595749,0.864682555199,1.45569860935 --11.3647594452,0.858686745167,1.42746293545 --11.3157558441,0.85368925333,1.38404119015 --11.2287549973,0.84469473362,1.33560097218 --11.3747415543,0.8586820364,1.31926774979 --11.3577356339,0.856681883335,1.27985274792 --11.2897338867,0.849686026573,1.23441839218 --11.2857275009,0.848684966564,1.19700837135 --11.5447130203,0.872662961483,1.21092700958 --11.5197086334,0.86966329813,1.17051064968 --11.419708252,0.859670042992,1.12206602097 --11.4317016602,0.860667347908,1.08666849136 --11.4826946259,0.865661263466,1.05528616905 --11.4446907043,0.86166280508,1.01487207413 --11.2646913528,0.844676971436,0.95837521553 --11.4186830521,0.858662486076,0.956246733665 --11.2856826782,0.845672667027,0.906786859035 --11.2476787567,0.841674387455,0.866359889507 --11.2326745987,0.840674102306,0.828950226307 --11.3176660538,0.847664415836,0.800586760044 --11.316660881,0.847662687302,0.764182329178 --11.2736577988,0.843664944172,0.724763512611 --11.2376556396,0.839667499065,0.703542590141 --11.2856492996,0.843660950661,0.671159625053 --11.1556482315,0.831671774387,0.625700473785 --11.2456407547,0.839661121368,0.596337020397 --11.3686332703,0.850646853447,0.568992614746 --11.3596286774,0.849645674229,0.53259074688 --11.3856239319,0.851640820503,0.497191309929 --11.3106231689,0.844647467136,0.474960297346 --11.3926172256,0.852636754513,0.443595230579 --11.3366136551,0.846640408039,0.404165536165 --11.3366098404,0.846638143063,0.367759466171 --11.318605423,0.844637811184,0.331354528666 --11.5945978165,0.870605647564,0.307074069977 --11.4045982361,0.852624952793,0.280787885189 --11.2685956955,0.83963739872,0.23831307888 --11.3695907593,0.849623918533,0.206966280937 --11.3505868912,0.847623467445,0.169547736645 --11.4475831985,0.856610119343,0.137199357152 --11.3405790329,0.846619665623,0.0977447032928 --11.3295755386,0.84561830759,0.0613356418908 --11.425573349,0.853605926037,0.0451762862504 --11.7085704803,0.879570186138,0.0149134946987 --11.3415670395,0.846610307693,-0.0286676902324 --11.3115625381,0.843611180782,-0.0650845170021 --12.7345676422,0.973433554173,-0.12519210577 --11.2625513077,0.83860886097,-0.173318952322 --11.2905502319,0.841604053974,-0.191511139274 --12.630563736,0.964435338974,-0.226247042418 --12.5615615845,0.958439469337,-0.266688197851 --12.3835582733,0.941457629204,-0.30517411232 --13.3255729675,1.02833354473,-0.353113263845 --12.3505554199,0.938453316689,-0.384000390768 --11.7165412903,0.880531132221,-0.413720160723 --12.572558403,0.959417998791,-0.446492433548 --11.4035301208,0.851566910744,-0.463482737541 --15.0396165848,1.18608248234,-0.583072125912 --15.064620018,1.18807148933,-0.631459593773 --15.1386260986,1.19505393505,-0.681825995445 --15.2146320343,1.20203590393,-0.732186734676 --15.2356367111,1.20402514935,-0.780570447445 --15.2716398239,1.20801615715,-0.80675804615 --14.0126047134,1.09217596054,-0.849187850952 --12.9335680008,0.993321657181,-0.84312915802 --12.0265331268,0.910445332527,-0.83898961544 --13.7676029205,1.07019102573,-0.969509840012 --14.2156238556,1.11211955547,-1.03868675232 --14.3216295242,1.12210059166,-1.06682837009 --13.9596176147,1.08914637566,-1.09041190147 --13.9766216278,1.09013700485,-1.13580226898 --13.9836244583,1.09112894535,-1.18120312691 --14.1176338196,1.10410153866,-1.23553872108 --14.3706502914,1.12805604935,-1.298807621 --14.2556476593,1.11706590652,-1.33627033234 --14.0986423492,1.10308623314,-1.34654915333 --13.8726329803,1.08311378956,-1.37306451797 --13.9846420288,1.09308922291,-1.42640376091 --13.748632431,1.07211875916,-1.45093047619 --13.8716430664,1.08309209347,-1.50626957417 --13.928650856,1.08907568455,-1.55563771725 --13.9366540909,1.09006690979,-1.60103440285 --13.9616584778,1.09305906296,-1.62622559071 --13.9236602783,1.09005773067,-1.66664195061 --13.9786682129,1.09504115582,-1.71701347828 --14.0236759186,1.10002577305,-1.76739668846 --14.1056861877,1.1080044508,-1.82074737549 --13.9916820526,1.0980155468,-1.85320937634 --13.8756752014,1.08703100681,-1.86247241497 --13.8486785889,1.0850276947,-1.90388739109 --16.8449192047,1.36250841618,-2.31572532654 --16.9149341583,1.36948442459,-2.37908983231 --16.6989269257,1.35051000118,-2.40560007095 --16.2769031525,1.31157195568,-2.40321540833 --16.4459266663,1.32853090763,-2.47852540016 --16.3239212036,1.31754672527,-2.48879170418 --16.1039123535,1.2975744009,-2.51030302048 --16.0279140472,1.29157674313,-2.55174422264 --16.0989284515,1.29855275154,-2.61410617828 --16.0479354858,1.29455065727,-2.65853142738 --16.0319423676,1.29354226589,-2.70793747902 --16.260974884,1.3154886961,-2.79521107674 --16.5060062408,1.33843719959,-2.86128807068 --15.9439601898,1.28752994537,-2.82398223877 --15.8959646225,1.28352761269,-2.86740231514 --15.9579820633,1.29050433636,-2.92976999283 --16.0119972229,1.29648244381,-2.99114108086 --13.9987878799,1.10885679722,-2.69362401962 --14.2438220978,1.13280034065,-2.78289318085 --14.1668205261,1.12680578232,-2.81533312798 --14.0218067169,1.112829566,-2.811606884 --15.1849603653,1.22358012199,-3.12378573418 --14.4388799667,1.154717803,-3.03059005737 --14.0998458862,1.12377607822,-3.0111682415 --14.1708631516,1.13075184822,-3.07253694534 --14.620923996,1.17365562916,-3.18548846245 --11.9145870209,0.921198189259,-2.68438148499 --12.1686229706,0.946139216423,-2.77563691139 --13.7678394318,1.0968003273,-3.15216326714 --13.7068386078,1.09180343151,-3.18459582329 --13.6428375244,1.08680737019,-3.21603035927 --13.6118412018,1.08480453491,-3.25444746017 --13.5738391876,1.08080768585,-3.26866865158 --13.9529008865,1.11771726608,-3.39885878563 --13.7968873978,1.10374045372,-3.41035032272 --14.4359989166,1.16658139229,-3.65179181099 --13.2998390198,1.05981957912,-3.42982363701 --13.2668418884,1.05781710148,-3.46725034714 --13.5108823776,1.08175837994,-3.54831027985 --13.2628517151,1.05880379677,-3.53285193443 --13.2638607025,1.05979394913,-3.57825684547 --13.2338638306,1.05779099464,-3.61466836929 --13.1668615341,1.05279636383,-3.6431157589 --13.3989076614,1.07573366165,-3.74738144875 --13.318903923,1.06974196434,-3.77182888985 --13.3039045334,1.0687404871,-3.79003405571 --13.2369022369,1.06274592876,-3.81747460365 --13.2409124374,1.06473493576,-3.86387634277 --13.1389036179,1.0557487011,-3.88133859634 --13.1449127197,1.05773723125,-3.92773532867 --13.0989141464,1.05473828316,-3.95915794373 --13.0699176788,1.05273485184,-3.99658274651 --13.1519365311,1.06070995331,-4.04273843765 --13.1109390259,1.05870950222,-4.07616472244 --13.1329526901,1.06169378757,-4.12755155563 --13.2089767456,1.06966471672,-4.19490480423 --13.2920026779,1.07863354683,-4.26525688171 --13.2089967728,1.07264328003,-4.28671169281 --13.3840417862,1.09058856964,-4.38600969315 --13.6711034775,1.11851084232,-4.49804639816 --13.6061019897,1.11351537704,-4.52548646927 --13.6001119614,1.11450529099,-4.57089042664 --13.4650964737,1.10252809525,-4.57537031174 --13.6901540756,1.12545859814,-4.69463729858 --16.2727069855,1.37577700615,-5.58454608917 --13.6501703262,1.12444460392,-4.77847099304 --16.9938907623,1.44756376743,-5.90973329544 --16.6808433533,1.41962862015,-5.86430978775 --16.6108493805,1.41462981701,-5.89975070953 --16.3028011322,1.38569486141,-5.85232210159 --16.3098220825,1.38867604733,-5.91271877289 --17.8241825104,1.5372505188,-6.49924182892 --16.2208404541,1.38366603851,-5.99757051468 --17.9502468109,1.55218672752,-6.63876390457 --16.6419677734,1.42652511597,-6.23492336273 --17.0420837402,1.46739685535,-6.43908929825 --19.9007835388,1.74858570099,-7.54282283783 --19.8087902069,1.74158775806,-7.58027124405 --19.8418292999,1.74755489826,-7.66364765167 --19.7458362579,1.74055814743,-7.69909906387 --19.9779090881,1.76448071003,-7.82216119766 --19.9349308014,1.76246845722,-7.87858533859 --20.0789966583,1.77840292454,-8.00589466095 --20.9452476501,1.86612868309,-8.41478061676 --21.0163021088,1.87608194351,-8.51813030243 --20.927312851,1.86908090115,-8.56058216095 --18.4237060547,1.62577807903,-7.67164897919 --18.567773819,1.6427128315,-7.79796266556 --17.0333919525,1.49314689636,-7.24127674103 --18.3927841187,1.62971949577,-7.86285972595 --18.6138763428,1.65463006496,-8.02312755585 --18.6079025269,1.65660858154,-8.08952713013 --18.6229248047,1.65859210491,-8.13071727753 --18.5589351654,1.65458810329,-8.17315387726 --18.8070373535,1.68248832226,-8.34840011597 --19.2842063904,1.73231625557,-8.62551498413 --18.6900672913,1.6754758358,-8.43926811218 --18.8831558228,1.69739115238,-8.59454917908 --18.6971321106,1.6814250946,-8.58305549622 --18.258020401,1.63855183125,-8.42251491547 --18.5901489258,1.67442214489,-8.64171791077 --17.6669025421,1.58469259739,-8.294672966 --17.3208274841,1.55178070068,-8.20428180695 --17.3308601379,1.5557551384,-8.27467060089 --17.3809051514,1.56371593475,-8.36504173279 --17.5179767609,1.57964837551,-8.49535179138 --17.7200584412,1.6015702486,-8.62442970276 --17.8171195984,1.61351454258,-8.7387676239 --17.9792041779,1.63343632221,-8.88607120514 --18.1582946777,1.65435230732,-9.04135513306 --18.2883701324,1.67028319836,-9.17567539215 --18.4594612122,1.6901999712,-9.33096790314 --18.6305541992,1.71111595631,-9.48725795746 --18.8496456146,1.73502779007,-9.63332748413 --19.0537509918,1.75893115997,-9.80859470367 --19.2678604126,1.78382968903,-9.99186038971 --19.4789733887,1.8087284565,-10.1751270294 --19.687084198,1.83262681961,-10.3593978882 --19.7751560211,1.84556651115,-10.4837417603 --19.9272499084,1.86448347569,-10.641040802 --20.1633548737,1.89038491249,-10.8040924072 --20.3844776154,1.91627538204,-11.0013532639 --20.5885944366,1.94117093086,-11.1916227341 --20.7556991577,1.96207892895,-11.3639144897 --20.9478168488,1.98597681522,-11.5511903763 --21.2409725189,2.01983690262,-11.7954053879 --21.4020824432,2.04074430466,-11.9696979523 --21.7282276154,2.07660746574,-12.1916913986 --21.889339447,2.0975124836,-12.3699865341 --22.0604553223,2.11941313744,-12.5552749634 --22.3766307831,2.15625882149,-12.823472023 --22.6998100281,2.19410014153,-13.0986661911 --22.9449615479,2.22396969795,-13.3319044113 --27.3617630005,2.69425487518,-15.9525346756 --27.3337879181,2.69424104691,-15.9937467575 --27.3028488159,2.69620418549,-16.0911579132 --27.1588630676,2.68621087074,-16.1216373444 --26.98686409,2.67322826385,-16.1361370087 --27.0089454651,2.68117070198,-16.2635116577 --27.2491188049,2.71202754974,-16.5217514038 --28.241607666,2.82258653641,-17.2335186005 --28.1816215515,2.81958389282,-17.2577495575 --28.0676517487,2.81257653236,-17.3102111816 --27.987695694,2.8095562458,-17.3816490173 --27.8857307434,2.80454421043,-17.4411067963 --27.7877674103,2.80053114891,-17.5015563965 --27.6747970581,2.79352378845,-17.5530204773 --27.6218128204,2.7905189991,-17.5802459717 --27.5288505554,2.78650355339,-17.6436977386 --27.4268856049,2.78149271011,-17.7001533508 --27.3349246979,2.7774772644,-17.7636051178 --27.23295784,2.77246642113,-17.8190574646 --27.1259880066,2.7664577961,-17.8715171814 --27.0440311432,2.76343846321,-17.9399604797 --26.9490280151,2.75645160675,-17.9392185211 --26.8570652008,2.75243735313,-17.999666214 --26.7450942993,2.74643135071,-18.0471305847 --26.6591339111,2.74341440201,-18.1115760803 --26.5681705475,2.73939990997,-18.1720256805 --26.4742069244,2.73438668251,-18.2304782867 --26.3762435913,2.7303750515,-18.2859344482 --26.3202571869,2.72737288475,-18.3081626892 --26.2292938232,2.72335839272,-18.3676128387 --26.1393318176,2.71934366226,-18.4280662537 --26.0443668365,2.71533107758,-18.4845218658 --25.9644088745,2.71231269836,-18.5499610901 --25.8944568634,2.7112891674,-18.6233997345 --25.7944889069,2.70627951622,-18.6748580933 --25.7395019531,2.70327687263,-18.6970882416 --25.6485385895,2.7002632618,-18.7545413971 --25.5555744171,2.69625067711,-18.8099937439 --25.45860672,2.69124031067,-18.862449646 --25.3466339111,2.68523645401,-18.9039154053 --25.2446651459,2.68022823334,-18.9523773193 --25.1577033997,2.6772134304,-19.0108280182 --25.1137218475,2.67520666122,-19.0390510559 --25.038766861,2.67418599129,-19.1064929962 --24.9407978058,2.6691763401,-19.1569538116 --24.8598403931,2.66715931892,-19.2183971405 --24.752866745,2.66115427017,-19.2608623505 --24.6759090424,2.65913534164,-19.3253059387 --24.5809440613,2.65512466431,-19.3767642975 --24.5349597931,2.65311861038,-19.4029903412 --24.4449958801,2.65010595322,-19.457447052 --24.3820476532,2.64908027649,-19.531879425 --24.2990875244,2.64706420898,-19.5913295746 --24.2231330872,2.64504480362,-19.6557731628 --24.1541805267,2.64402151108,-19.7262134552 --24.0702171326,2.64100646973,-19.7836647034 --24.0102272034,2.63800787926,-19.7979011536 --23.9342708588,2.63598847389,-19.8623485565 --23.840303421,2.63197875023,-19.9108047485 --23.762348175,2.62996053696,-19.9722499847 --23.6863918304,2.62894153595,-20.0356960297 --23.6224422455,2.62791585922,-20.1091346741 --23.5574932098,2.62789106369,-20.1815738678 --23.5045051575,2.6258893013,-20.2008075714 --23.4615707397,2.62785243988,-20.2922325134 --23.3856143951,2.62583422661,-20.3536758423 --23.3106594086,2.62481474876,-20.4171199799 --23.2437095642,2.62379002571,-20.4885635376 --23.1687545776,2.6227710247,-20.5510063171 --23.1208190918,2.62473607063,-20.6394405365 --23.0648288727,2.62173652649,-20.65467453 --23.0088863373,2.62270665169,-20.7341079712 --22.9549446106,2.62367558479,-20.8155384064 --22.8960018158,2.62464666367,-20.8939781189 --22.8400592804,2.62561678886,-20.9734077454 --22.7791137695,2.62658882141,-21.0498466492 --22.7661552429,2.62856554985,-21.1030521393 --22.7052097321,2.62953734398,-21.1794910431 --22.6742858887,2.63349270821,-21.282907486 --22.618347168,2.63446164131,-21.3643436432 --22.5804195404,2.63842058182,-21.461763382 --22.5595054626,2.64436912537,-21.5761756897 --22.5345878601,2.64931941032,-21.6875896454 --22.5126724243,2.65526843071,-21.8010005951 --22.6097946167,2.67117929459,-21.9621315002 --22.7019672394,2.69205975533,-22.1874637604 --22.6510334015,2.694024086,-22.275894165 --22.4900188446,2.68205332756,-22.2584037781 --22.3159942627,2.66909074783,-22.2269229889 --22.1079425812,2.65114974976,-22.1604633331 --21.9959106445,2.64118456841,-22.1177368164 --21.8378944397,2.62921404839,-22.0992469788 --21.6798782349,2.61724472046,-22.0777511597 --21.5909137726,2.61523342133,-22.1262130737 --21.501947403,2.61222267151,-22.172668457 --21.4089832306,2.6092133522,-22.2171344757 --21.2899932861,2.60222148895,-22.2326126099 --21.1989746094,2.59524536133,-22.2078762054 --21.0980014801,2.59124183655,-22.2423477173 --21.029050827,2.59121870995,-22.3087940216 --20.8259925842,2.57328176498,-22.2333297729 --20.7960758209,2.57823371887,-22.341753006 --20.6760845184,2.57124352455,-22.3532352448 --20.5661010742,2.56624770164,-22.374710083 --20.5001010895,2.56225681305,-22.3739566803 --20.3781070709,2.55426907539,-22.3814411163 --20.2971439362,2.55325484276,-22.4328956604 --20.1951675415,2.5482544899,-22.4613666534 --20.0931873322,2.54425406456,-22.4898376465 --19.9802017212,2.53826093674,-22.506319046 --19.8752212524,2.5332634449,-22.5297927856 --19.8112182617,2.52927279472,-22.5280361176 --19.7472743988,2.53024673462,-22.5984840393 --19.6823272705,2.53122210503,-22.666929245 --19.5733413696,2.52522826195,-22.6834030151 --19.4813709259,2.52222180367,-22.7218723297 --19.4004096985,2.52120828629,-22.7713298798 --19.3304595947,2.52118754387,-22.8327770233 --19.2714614868,2.51819348335,-22.8360214233 --19.2095184326,2.51916694641,-22.9074668884 --19.1165466309,2.51616239548,-22.9419326782 --19.0395889282,2.51514649391,-22.9943847656 --18.9245948792,2.50915789604,-23.0028686523 --18.8476390839,2.50814151764,-23.0563259125 --18.7616138458,2.50116801262,-23.0255889893 --18.6776485443,2.49915790558,-23.0690498352 --18.5756664276,2.49416065216,-23.0905227661 --18.4176292419,2.48220491409,-23.0430374146 --18.2996292114,2.4752202034,-23.0435237885 --18.2246723175,2.47420406342,-23.0969772339 --17.2397994995,2.34087085724,-22.010093689 --17.1838569641,2.3428440094,-22.080537796 --17.1759033203,2.34681606293,-22.1397418976 --17.1139545441,2.34779381752,-22.2021884918 --17.0469989777,2.34777474403,-22.25963974 --17.1692409515,2.37660980225,-22.560956955 --17.51171875,2.43827271461,-23.1501064301 --17.3977184296,2.43128824234,-23.1495895386 --17.3026790619,2.42232561111,-23.0998630524 --17.1986885071,2.41733407974,-23.1113395691 --16.0025196075,2.24620866776,-21.6716156006 --15.898519516,2.24122262001,-21.6730957031 --15.6273355484,2.20937180519,-21.4476947784 --15.5043115616,2.2014029026,-21.4201869965 --14.8847904205,2.12080454826,-20.7832508087 --14.8558664322,2.1257622242,-20.8786773682 --14.7598676682,2.12077450752,-20.8821525574 --14.7029132843,2.12175440788,-20.9395980835 --14.6549682617,2.12472748756,-21.0090351105 --12.4915647507,1.79248189926,-18.0850353241 --12.0161008835,1.72582793236,-17.5267925262 --11.7758636475,1.69200408459,-17.2421779633 --11.6167621613,1.67408668995,-17.1256961823 --11.4606637955,1.65816700459,-17.0132217407 --11.3696432114,1.65219211578,-16.9936981201 --11.2946405411,1.64820337296,-16.9971618652 --11.2276468277,1.64520812035,-17.0116195679 --11.1826791763,1.64719438553,-17.0570545197 --11.1596956253,1.64718782902,-17.0792732239 --11.2498989105,1.67105185986,-17.3306179047 --11.2049350739,1.67203605175,-17.3800621033 --11.1729850769,1.67600953579,-17.4464855194 --11.1120014191,1.67500793934,-17.4719409943 --10.9098815918,1.65410840511,-17.3356990814 --10.861913681,1.65509486198,-17.3811511993 --10.8239574432,1.65807378292,-17.4385814667 --10.7709827423,1.65806543827,-17.475030899 --10.7210121155,1.65905463696,-17.5154781342 --10.6740446091,1.66004133224,-17.55991745 --10.6240739822,1.66103053093,-17.6003627777 --10.6071004868,1.66201686859,-17.6345825195 --10.5541257858,1.6630089283,-17.6700286865 --10.5081615448,1.66399347782,-17.7184734344 --10.4611959457,1.66497957706,-17.7639160156 --10.4162340164,1.66696286201,-17.8143596649 --10.3602561951,1.66695737839,-17.8458099365 --10.3213033676,1.66993463039,-17.90625 --10.3083353043,1.67291724682,-17.9464607239 --10.254360199,1.67290985584,-17.9809055328 --10.2023897171,1.67389965057,-18.0203590393 --10.163438797,1.6768758297,-18.0828018188 --10.1064586639,1.67587184906,-18.111246109 --10.0594949722,1.67785668373,-18.1586894989 --10.0175409317,1.68083536625,-18.2171363831 --9.99155521393,1.68083047867,-18.2363567352 --9.93958377838,1.68182063103,-18.2748031616 --9.89863109589,1.68479859829,-18.3342437744 --9.85467529297,1.68677830696,-18.3906917572 --9.80370616913,1.68776679039,-18.432138443 --9.74773216248,1.68876004219,-18.4655952454 --9.71679496765,1.69272661209,-18.5440235138 --9.69181346893,1.6937199831,-18.5662479401 --9.64685535431,1.69670128822,-18.6196899414 --9.6049041748,1.69967865944,-18.6801338196 --9.49684238434,1.68973064423,-18.6136245728 --9.54904842377,1.7116008997,-18.8559951782 --9.45401000977,1.70363807678,-18.8144779205 --9.39909934998,1.7105935812,-18.9231357574 --9.35915374756,1.71356678009,-18.9905796051 --9.28815460205,1.71157693863,-18.9950428009 --9.33936882019,1.73444271088,-19.2454147339 --9.17320346832,1.71156561375,-19.0579509735 --9.15429782867,1.72051310539,-19.1693782806 --9.07434654236,1.72249650955,-19.230052948 --9.00334644318,1.71950662136,-19.2345161438 --5.41093587875,0.975818157196,-11.9271354675 --10.2981758118,2.03764843941,-22.4697628021 --10.1450462341,2.0187485218,-22.3212890625 --10.106051445,2.01775097847,-22.3285255432 --10.0631303787,2.02371239662,-22.4169692993 --9.9600944519,2.0167491436,-22.3764629364 --9.82699680328,2.00182747841,-22.2649726868 --9.75902748108,2.00282049179,-22.2994403839 --9.68504333496,2.00082278252,-22.317905426 --9.61206436157,2.00082230568,-22.3413791656 --9.52998161316,1.9898840189,-22.2466430664 --9.48605823517,1.99484598637,-22.3340911865 --9.43211555481,1.99882125854,-22.3985424042 --9.322057724,1.98887276649,-22.3330402374 --9.29016304016,1.99781668186,-22.4514789581 --9.22620391846,1.99880373478,-22.4959449768 --9.15121650696,1.99780833721,-22.5104122162 --9.10720920563,1.99581933022,-22.5026512146 --9.04124450684,1.9968098402,-22.5411167145 --8.96325206757,1.99481797218,-22.5495910645 --8.84717464447,1.98288166523,-22.463092804 --8.79924869537,1.9888471365,-22.5445423126 --8.74029827118,1.99082827568,-22.5989990234 --8.66030216217,1.9888395071,-22.6024780273 --8.66741085052,1.99877524376,-22.7236785889 --8.59543323517,1.99877405167,-22.7481498718 --8.4713306427,1.98485374451,-22.6336574554 --8.4695186615,2.00274586678,-22.8410758972 --8.34341144562,1.98882877827,-22.7215881348 --8.31353378296,1.99876344204,-22.8560256958 --8.178399086,1.98186349869,-22.7065410614 --8.26671600342,2.01466608047,-23.0566825867 --8.17870044708,2.00969004631,-23.0381679535 --8.09669685364,2.00770568848,-23.0336437225 --8.02872848511,2.00769925117,-23.0671100616 --7.94572305679,2.00471615791,-23.060590744 --7.84867954254,1.9977581501,-23.0110778809 --7.81068611145,1.99676036835,-23.0183181763 --7.71363925934,1.98980391026,-22.9658050537 --7.65670204163,1.99377787113,-23.0332679749 --7.5947508812,1.99676036835,-23.0857315063 --7.52076625824,1.99576449394,-23.1012039185 --7.43976306915,1.9927803278,-23.0966835022 --6.70893144608,1.79795634747,-21.0956554413 --7.13234090805,1.9440754652,-22.6337528229 --6.61497163773,1.79994916916,-21.1413574219 --7.18181943893,1.99079275131,-23.154340744 --7.08075428009,1.98184776306,-23.0818328857 --7.00175428391,1.97886145115,-23.0813121796 --6.90469694138,1.97091126442,-23.0178012848 --6.83372020721,1.97091031075,-23.0422782898 --6.789706707,1.96892607212,-23.0265216827 --6.74079465866,1.97588431835,-23.120973587 --6.66079092026,1.97290074825,-23.1154556274 --6.59783697128,1.97588562965,-23.1639194489 --6.49174833298,1.96495485306,-23.0674228668 --6.44284009933,1.97191143036,-23.1648750305 --6.12906074524,1.89041173458,-22.3245315552 --6.24256324768,1.94010531902,-22.8646564484 --6.17860507965,1.94309270382,-22.9091262817 --5.95710945129,1.89041483402,-22.3757095337 --6.06072425842,1.9510461092,-23.0350532532 --5.93956947327,1.93315625191,-22.867565155 --5.86256694794,1.93117141724,-22.8640460968 --5.81767845154,1.94011616707,-22.9825019836 --5.75257873535,1.9291844368,-22.8757591248 --5.65249156952,1.91925251484,-22.7812576294 --5.61663484573,1.9311773777,-22.9337005615 --5.54364395142,1.93018567562,-22.9421749115 --5.43752717972,1.91727149487,-22.8166770935 --5.34144496918,1.90733599663,-22.7281723022 --5.24034166336,1.89541316032,-22.6176719666 --5.20233488083,1.89342403412,-22.6099071503 --5.12632894516,1.89144122601,-22.60338974 --5.0242099762,1.87852752209,-22.4768867493 --4.98133993149,1.88946211338,-22.6133441925 --4.89327669144,1.88151431084,-22.5458297729 --4.80219841003,1.87257575989,-22.4623184204 --4.73120975494,1.87158250809,-22.4737968445 --4.6881775856,1.86860847473,-22.4400367737 --4.59408378601,1.85767924786,-22.3405342102 --4.53815841675,1.86364793777,-22.4179992676 --4.44505882263,1.85172140598,-22.3134880066 --4.39014148712,1.85868501663,-22.3999557495 --4.29904747009,1.84875559807,-22.3004436493 --4.22001075745,1.8437911272,-22.2619247437 --4.17797994614,1.8398168087,-22.2291679382 --4.11904191971,1.84479296207,-22.293636322 --4.04402589798,1.84181654453,-22.2761192322 --3.9187400341,1.81300151348,-21.9776287079 --3.867841959,1.82095372677,-22.0840911865 --3.80789923668,1.82593286037,-22.1435604095 --3.73790383339,1.8249437809,-22.1480407715 --3.68178892136,1.81301939487,-22.0282936096 --3.62888383865,1.82097625732,-22.1267566681 --3.55586743355,1.8189997673,-22.1092357635 --3.47480225563,1.81105196476,-22.0417175293 --3.39474511147,1.80509984493,-21.982208252 --3.32473874092,1.80311703682,-21.9756813049 --3.29376339912,1.80510926247,-22.0009174347 --3.19860243797,1.78921854496,-21.8344154358 --3.12154960632,1.78326332569,-21.7798976898 --2.34682154655,1.33207261562,-16.9078445435 --2.28374552727,1.32512748241,-16.834312439 --2.09881019592,1.23568880558,-15.8778600693 --2.0256357193,1.21880054474,-15.7053384781 --1.98048400879,1.20489454269,-15.5525836945 --1.92643630505,1.19993150234,-15.5100460052 --1.88649201393,1.20590782166,-15.5734968185 --1.84655737877,1.21187841892,-15.6469554901 --1.80460548401,1.21685934067,-15.7024106979 --1.76164770126,1.22084379196,-15.751865387 --1.71868610382,1.2238304615,-15.7973146439 --1.69973826408,1.22880482674,-15.8535470963 --1.6537592411,1.23080182076,-15.8810043335 --1.60979986191,1.23478734493,-15.9284591675 --1.60546779633,1.29741358757,-16.616109848 --1.55042934418,1.29344582558,-16.5825767517 --1.97331416607,1.74862539768,-21.5417842865 --1.93324697018,1.74167096615,-21.4740257263 --1.86320364475,1.73670959473,-21.4305000305 --1.8012611866,1.74169015884,-21.4889774323 --1.72514474392,1.73077106476,-21.3714561462 --1.65003979206,1.72084522247,-21.2659397125 --1.58606648445,1.72284352779,-21.2934150696 --1.52107727528,1.72285091877,-21.304889679 --1.4738945961,1.70596265793,-21.1211395264 --1.41599392891,1.71491932869,-21.2216110229 --1.3510055542,1.71492624283,-21.2340888977 --1.28500175476,1.71494221687,-21.2305679321 --1.22001957893,1.71594595909,-21.2490463257 --1.15502548218,1.71595621109,-21.2555217743 --1.08494353294,1.70801663399,-21.1739997864 --1.04684555531,1.69907939434,-21.0762405396 --0.979806303978,1.69511544704,-21.0377178192 --0.915817141533,1.69612288475,-21.0491924286 --0.843654572964,1.68122887611,-20.887670517 --0.780702352524,1.68521559238,-20.9361515045 --0.719788491726,1.69318068027,-21.0226268768 --0.690889775753,1.70213019848,-21.1238670349 --0.626921892166,1.70512604713,-21.1563453674 --0.562959074974,1.70811903477,-21.1938228607 --0.494853109121,1.69819271564,-21.0892982483 --0.428823649883,1.69522333145,-21.0607795715 --0.361716359854,1.68529748917,-20.9552555084 --0.297765791416,1.69028389454,-21.0047359467 --0.265781760216,1.6912817955,-21.0209770203 --0.201804831624,1.69328296185,-21.0444526672 --0.136762052774,1.6893209219,-21.0029296875 --0.0706594288349,1.68039250374,-20.9024105072 --0.00652805250138,1.66847956181,-20.7738780975 -0.056437022984,1.66344583035,-19.8523616791 -0.120524778962,1.6714771986,-19.9387073517 -0.153613179922,1.67951738834,-20.0258808136 -0.215437367558,1.66340255737,-19.8522415161 -0.275113075972,1.63320577145,-19.5316181183 -0.341352492571,1.65532112122,-19.767950058 -0.399036109447,1.62612915039,-19.4543323517 -0.462091505527,1.63114285469,-19.5086765289 -0.523024916649,1.62508916855,-19.4420375824 -0.557133197784,1.6351402998,-19.5492038727 -0.612907886505,1.6149995327,-19.3245773315 -0.681066572666,1.62906968594,-19.4819221497 -0.750269412994,1.64816403389,-19.6832523346 -0.806063532829,1.62903428078,-19.4776325226 -0.86090528965,1.61493122578,-19.3189964294 -0.938215792179,1.64408361912,-19.6283245087 -0.972270190716,1.6491048336,-19.6824932098 -1.04138183594,1.65914869308,-19.7938365936 -1.10641849041,1.66315162182,-19.8301830292 -1.1683921814,1.66112053394,-19.8035392761 -1.23036277294,1.65808773041,-19.7738952637 -1.28826713562,1.65001893044,-19.6772632599 -1.3273897171,1.66107702255,-19.8004245758 -1.38834285736,1.65703475475,-19.7527866364 -1.45133078098,1.65701127052,-19.7401428223 -1.52851200104,1.67409205437,-19.9224739075 -1.59859478474,1.68211984634,-20.0058135986 -1.6656229496,1.68511795998,-20.0341644287 -1.72961056232,1.68409430981,-20.021522522 -1.76161181927,1.68508660793,-20.0226974487 -1.826613307,1.68507051468,-20.0240535736 -1.89363563061,1.68806540966,-20.0464057922 -1.9646999836,1.69408285618,-20.111749649 -2.03374648094,1.69909095764,-20.1590919495 -2.10278511047,1.70309472084,-20.1984386444 -2.1728219986,1.70709705353,-20.23579216 -2.2108771801,1.71311807632,-20.2919559479 -2.2839422226,1.72013545036,-20.3582992554 -2.35800695419,1.72615265846,-20.4246444702 -2.42703270912,1.73014914989,-20.4509925842 -2.49807357788,1.73415410519,-20.4933376312 -2.56406760216,1.73413395882,-20.4876918793 -2.6280465126,1.73310554028,-20.4660511017 -2.66205430031,1.73410129547,-20.4742240906 -2.73107099533,1.7370929718,-20.4915752411 -2.79504585266,1.73506259918,-20.4659366608 -2.86104297638,1.73504436016,-20.4632911682 -2.92603445053,1.7350230217,-20.4546432495 -2.99303245544,1.73600518703,-20.452999115 -3.05600857735,1.73497581482,-20.4283561707 -3.09504246712,1.73798489571,-20.4635295868 -3.15701365471,1.73695313931,-20.4338874817 -3.22803783417,1.73994898796,-20.4592380524 -3.29503417015,1.73993003368,-20.4555969238 -3.36505079269,1.74292182922,-20.4729480743 -3.42903351784,1.74189627171,-20.4553031921 -3.50106072426,1.74589347839,-20.4836502075 -3.53003668785,1.74387288094,-20.4588317871 -3.60105419159,1.7468650341,-20.4771842957 -3.66503787041,1.74584007263,-20.4605407715 -3.73001909256,1.74581336975,-20.4409046173 -3.79702115059,1.74679803848,-20.4432525635 -3.86803483963,1.74878811836,-20.4576091766 -3.90002536774,1.74877488613,-20.4477882385 -3.96702456474,1.74975788593,-20.44713974 -4.03200960159,1.74973356724,-20.4315013885 -4.09900474548,1.74971461296,-20.4268569946 -4.16600131989,1.75069630146,-20.4232120514 -4.23601007462,1.75268411636,-20.4325675964 -4.29999160767,1.75265800953,-20.4129257202 -4.3380074501,1.75465786457,-20.4301013947 -4.40299272537,1.75463378429,-20.4144611359 -4.47300243378,1.75662231445,-20.4248123169 -4.53497409821,1.754591465,-20.3951740265 -4.60799217224,1.757584095,-20.4145278931 -4.67197322845,1.75755774975,-20.3938884735 -4.73696041107,1.75753486156,-20.3802471161 -4.77296972275,1.75953161716,-20.3904190063 -4.83895730972,1.75950860977,-20.3767795563 -4.90896368027,1.76149582863,-20.3841323853 -4.99302148819,1.76850795746,-20.4454727173 -5.05900764465,1.76848447323,-20.4308338165 -5.14005279541,1.77449059486,-20.479177475 -5.22511339188,1.78250396252,-20.543510437 -5.29022407532,1.79455041885,-20.6616573334 -5.3893327713,1.80658769608,-20.7779769897 -5.48542165756,1.81761467457,-20.8733062744 -5.58753538132,1.83065414429,-20.9956207275 -5.68763113022,1.84268414974,-21.0989494324 -5.77769327164,1.85069775581,-21.1662826538 -5.8577208519,1.85469448566,-21.1966247559 -5.91378688812,1.86271810532,-21.267780304 -5.98578357697,1.8636995554,-21.2651329041 -6.06881523132,1.86969816685,-21.3004741669 -6.14080762863,1.87067711353,-21.2928352356 -6.2228345871,1.87467324734,-21.323179245 -6.29783773422,1.87765777111,-21.3275299072 -6.34888315201,1.88267111778,-21.3766899109 -6.40683078766,1.87962865829,-21.3210639954 -6.48083114624,1.88161194324,-21.3224143982 -6.55382680893,1.88359284401,-21.3187675476 -6.61979866028,1.88256204128,-21.2891330719 -6.68577337265,1.88153290749,-21.2624950409 -6.7497420311,1.88050067425,-21.2288627625 -6.78172874451,1.87948608398,-21.2150402069 -6.8597369194,1.88247275352,-21.2243919373 -6.91467952728,1.87842845917,-21.1627674103 -6.97965288162,1.87839877605,-21.1341304779 -7.03960943222,1.87536120415,-21.0875034332 -7.10057353973,1.87432742119,-21.048866272 -7.15451478958,1.87028264999,-20.9852466583 -7.18950748444,1.87027072906,-20.9774303436 -7.24746274948,1.86723279953,-20.9287986755 -7.31945514679,1.8692125082,-20.9211578369 -7.3804192543,1.86717867851,-20.881526947 -7.44840192795,1.86815392971,-20.8628864288 -7.52039384842,1.86913335323,-20.8542461395 -7.58737468719,1.86910784245,-20.8336048126 -7.6333937645,1.87310826778,-20.8547801971 -7.69335651398,1.8710744381,-20.8141479492 -7.76835584641,1.87305736542,-20.813501358 -7.83032178879,1.87202465534,-20.7758731842 -7.90231466293,1.87400484085,-20.7682285309 -7.9622759819,1.87197029591,-20.7256031036 -8.03727531433,1.87395334244,-20.7249565125 -8.07928371429,1.87594890594,-20.7341327667 -8.15628623962,1.87893354893,-20.7374858856 -8.22827625275,1.87991249561,-20.7268447876 -8.30728340149,1.88389885426,-20.7341957092 -8.37426185608,1.883872509,-20.710559845 -8.40916919708,1.87581348419,-20.6069564819 -8.46311759949,1.87277328968,-20.5493373871 -8.5311832428,1.8817948103,-20.6224861145 -8.59515666962,1.88076639175,-20.5928516388 -8.65913009644,1.88073754311,-20.5622196198 -8.70806980133,1.87669360638,-20.4946022034 -8.70189380646,1.85959756374,-20.2970428467 -8.65864467621,1.83446824551,-20.0155181885 -8.62850379944,1.81939673424,-19.8567619324 -8.66843223572,1.81434845924,-19.7751541138 -8.71136665344,1.80930304527,-19.7005462646 -8.75530529022,1.80425953865,-19.6299343109 -8.79423522949,1.79921233654,-19.549325943 -8.82414722443,1.79215693474,-19.4477310181 -8.86207580566,1.78610956669,-19.3661251068 -8.86601352692,1.78007411957,-19.2943325043 -8.90795230865,1.7760310173,-19.2227249146 -8.94488143921,1.76998436451,-19.1411209106 -8.98081111908,1.76493740082,-19.0585155487 -9.01774311066,1.75989186764,-18.9789123535 -9.05467510223,1.75384688377,-18.9003067017 -9.09561634064,1.74980556965,-18.8306999207 -9.10657024384,1.74577772617,-18.7769031525 -9.14751338959,1.74173748493,-18.7092914581 -9.18745326996,1.7376960516,-18.6386890411 -9.23140144348,1.73465788364,-18.5760803223 -9.26533317566,1.72861325741,-18.4954795837 -9.29826545715,1.72356879711,-18.4148750305 -9.3422164917,1.72053277493,-18.3562641144 -9.35517787933,1.71750819683,-18.309463501 -9.39311790466,1.71246743202,-18.237865448 -9.42705249786,1.70742464066,-18.1602630615 -9.47000598907,1.70438957214,-18.1026477814 -9.50594711304,1.70034945011,-18.0310459137 -9.54789638519,1.69731295109,-17.9694404602 -9.55885601044,1.69328868389,-17.9216423035 -9.60481452942,1.6912561655,-17.8700294495 -9.65978717804,1.69023013115,-17.8354110718 -9.69573116302,1.68619179726,-17.7668037415 -9.72766876221,1.68215072155,-17.6902046204 -9.78664875031,1.68212783337,-17.6635818481 -9.82059001923,1.67808818817,-17.5909824371 -9.79950237274,1.66804432869,-17.4872150421 -9.85648155212,1.66802108288,-17.4585914612 -9.89242744446,1.6649838686,-17.3909912109 -9.93037700653,1.66094911098,-17.3293838501 -9.96732711792,1.65791356564,-17.2657814026 -10.0192995071,1.65688800812,-17.2291622162 -10.0572519302,1.65385389328,-17.1685562134 -10.0652103424,1.64982998371,-17.11876297 -10.1271982193,1.65181052685,-17.0991382599 -10.1821756363,1.6517868042,-17.0675201416 -10.2321453094,1.65076088905,-17.0289001465 -10.2921304703,1.65174007416,-17.005279541 -10.349111557,1.65171849728,-16.9786529541 -10.3820581436,1.6486825943,-16.9110527039 -10.4190587997,1.64967596531,-16.9102363586 -10.4670276642,1.64864897728,-16.8676242828 -10.5210037231,1.64862549305,-16.8350048065 -10.5799875259,1.64960467815,-16.8103809357 -10.6509866714,1.65259039402,-16.8047485352 -10.7079668045,1.65356826782,-16.7761287689 -10.7229394913,1.65155053139,-16.7413272858 -10.7769165039,1.6515276432,-16.7097053528 -10.8569259644,1.6555172205,-16.7160701752 -10.9028930664,1.65448963642,-16.67045784 -10.955868721,1.6544662714,-16.636838913 -11.0078430176,1.65444231033,-16.6012191772 -11.0728340149,1.65642464161,-16.5845928192 -11.0958166122,1.65541052818,-16.560792923 -11.1768283844,1.66040146351,-16.5701446533 -11.2408180237,1.66238307953,-16.5515193939 -11.2977962494,1.66236066818,-16.520904541 -11.3467683792,1.66233575344,-16.4812850952 -11.4007444382,1.66231262684,-16.4476680756 -11.4617290497,1.66329240799,-16.4230499268 -11.5237607956,1.66929769516,-16.4582061768 -11.5687246323,1.66827023029,-16.4105987549 -11.6437282562,1.67125725746,-16.4079608917 -11.7057123184,1.67323744297,-16.3843402863 -11.7727041245,1.67522025108,-16.3687095642 -11.8366918564,1.67720139027,-16.3480854034 -11.9026832581,1.67918419838,-16.3314533234 -11.9346761703,1.68017458916,-16.3206424713 -11.9956598282,1.6811542511,-16.2950210571 -12.0756664276,1.68614244461,-16.2963829041 -12.1166267395,1.68411362171,-16.2427787781 -12.1836175919,1.68609583378,-16.2251529694 -12.2576160431,1.69008123875,-16.2175178528 -12.331612587,1.69306600094,-16.2078895569 -12.364607811,1.69405734539,-16.1990718842 -12.4466142654,1.69904530048,-16.2004337311 -12.4935817719,1.69801914692,-16.1548233032 -12.5675802231,1.70100438595,-16.146188736 -12.6195526123,1.70098018646,-16.1065769196 -12.6825370789,1.70296049118,-16.0819549561 -12.7445220947,1.70494067669,-16.0563297272 -12.8145532608,1.71094501019,-16.0924892426 -12.8995599747,1.71593332291,-16.0948486328 -12.9795618057,1.71991991997,-16.0912094116 -13.0385417938,1.72189819813,-16.0595932007 -13.1105365753,1.72488188744,-16.0459575653 -13.1745214462,1.72586190701,-16.0203380585 -13.2185249329,1.72885632515,-16.0225162506 -13.289516449,1.73183870316,-16.0048904419 -13.3635101318,1.73482227325,-15.9912595749 -13.4445114136,1.73980844021,-15.986618042 -13.526512146,1.7437940836,-15.9809856415 -13.6115169525,1.74878144264,-15.980340004 -13.6554813385,1.7477543354,-15.9287376404 -13.4732704163,1.71767354012,-15.661108017 -13.3030357361,1.68657767773,-15.3586845398 -13.319978714,1.68154370785,-15.2791032791 -13.3379230499,1.67751061916,-15.2015199661 -13.3628740311,1.67448019981,-15.1329278946 -13.426861763,1.67646205425,-15.1093044281 -13.4368000031,1.67042696476,-15.022731781 -13.4697942734,1.67241811752,-15.0119199753 -13.4937467575,1.66838824749,-14.9433288574 -13.5257043839,1.66636025906,-14.8827362061 -13.5466547012,1.66332983971,-14.8111486435 -13.5746107101,1.6603012085,-14.7465591431 -13.5965614319,1.65627110004,-14.6759748459 -13.6095399857,1.65525686741,-14.6431789398 -13.6214828491,1.65022456646,-14.5626010895 -13.647439003,1.6471965313,-14.498008728 -13.6683912277,1.64416742325,-14.4284210205 -13.6943473816,1.64113950729,-14.3638315201 -13.7022886276,1.63610708714,-14.2802581787 -13.7262439728,1.63307893276,-14.2136735916 -13.7232093811,1.6300611496,-14.1648921967 -13.7481679916,1.62703430653,-14.1013002396 -13.7591133118,1.62200331688,-14.021727562 -13.7990837097,1.62198102474,-13.9751186371 -13.8140335083,1.61795151234,-13.9005422592 -13.8289833069,1.61392259598,-13.826962471 -13.827922821,1.60788989067,-13.7373962402 -13.8298940659,1.60487437248,-13.6956090927 -13.8378400803,1.59984445572,-13.6160354614 -13.8658027649,1.59781980515,-13.5574426651 -13.8597393036,1.59178709984,-13.4648799896 -13.8957080841,1.59076464176,-13.4142827988 -13.908659935,1.5867369175,-13.3417024612 -13.9446296692,1.58571505547,-13.2921028137 -13.9365949631,1.58269751072,-13.2403316498 -13.9805707932,1.58267748356,-13.1987257004 -14.0005292892,1.57965230942,-13.1341381073 -14.0284938812,1.57762873173,-13.07654953 -14.0404462814,1.57360172272,-13.0039730072 -14.0794200897,1.57358086109,-12.9573736191 -14.0833683014,1.5685530901,-12.8787994385 -14.0733346939,1.56453669071,-12.8280239105 -14.0882902145,1.56151115894,-12.7594451904 -14.1132555008,1.5594881773,-12.7008562088 -14.1212072372,1.55546200275,-12.6272773743 -14.1341638565,1.55243682861,-12.5577011108 -14.1851463318,1.55341923237,-12.5230932236 -14.1681089401,1.54840219021,-12.4673223495 -14.1980781555,1.54738080502,-12.4137325287 -14.2330503464,1.54636085033,-12.3661308289 -14.2390022278,1.542334795,-12.290564537 -14.2569646835,1.54031181335,-12.2279777527 -14.2859334946,1.53829085827,-12.1743869781 -14.2998924255,1.53526723385,-12.1078081131 -14.3208818436,1.53525817394,-12.0870065689 -14.3318405151,1.5322343111,-12.0184288025 -12.8578510284,1.34895551205,-10.679019928 -12.8588104248,1.34493410587,-10.6104488373 -12.8637733459,1.34191358089,-10.5458726883 -12.879743576,1.33889520168,-10.4912872314 -8.17078399658,0.77010756731,-6.47365236282 -8.20578861237,0.771103739738,-6.46004581451 -8.26580715179,0.776103496552,-6.46543216705 -8.30481433868,0.778100430965,-6.45581054688 -8.32280826569,0.778093755245,-6.42722320557 -8.34780502319,0.778088092804,-6.40363693237 -8.36880111694,0.778082072735,-6.37804174423 -8.39180660248,0.779080986977,-6.37523460388 -8.40479755402,0.77907371521,-6.34265089035 -8.44080162048,0.780069947243,-6.32904243469 -8.46780014038,0.781064748764,-6.30744838715 -8.49379920959,0.782059431076,-6.28485679626 -8.51279354095,0.781053245068,-6.25726652145 -8.52879524231,0.78205126524,-6.2494559288 -8.55479335785,0.783045768738,-6.22587347031 -8.58779525757,0.784041583538,-6.20926856995 -8.5937833786,0.783033788204,-6.17168855667 -8.62678623199,0.784029722214,-6.15508270264 -8.65978813171,0.7850253582,-6.13748550415 -8.69279098511,0.787020981312,-6.11988639832 -8.69278335571,0.786017119884,-6.10008764267 -8.72078323364,0.787012159824,-6.07849550247 -8.76078891754,0.78900873661,-6.06589031219 -8.78178501129,0.789003014565,-6.03930091858 -8.79877853394,0.788996934891,-6.00971508026 -8.8277797699,0.789992392063,-5.99010658264 -8.85777950287,0.790987730026,-5.96951341629 -8.8677778244,0.790984869003,-5.95571994781 -8.89677715302,0.791980206966,-5.93511962891 -8.92577838898,0.792975664139,-5.91451835632 -8.93276691437,0.791968524456,-5.87695026398 -8.98677921295,0.795966386795,-5.87333106995 -9.00377368927,0.794960737228,-5.84473419189 -9.0227689743,0.794955015182,-5.81614971161 -9.04777431488,0.796953618526,-5.81234550476 -9.07677459717,0.797949016094,-5.7907500267 -9.10377407074,0.798944234848,-5.7681517601 -9.02672386169,0.787930428982,-5.67663145065 -9.11075019836,0.795930564404,-5.69099855423 -9.13574790955,0.795925796032,-5.6673989296 -9.16675567627,0.798924803734,-5.66659545898 -9.21176338196,0.801921665668,-5.65597867966 -9.25777053833,0.803918361664,-5.64437580109 -11.0795755386,1.00105202198,-6.76643848419 -11.0155277252,0.9920373559,-6.67790794373 -10.9224681854,0.979020774364,-6.57140350342 -10.844414711,0.968005537987,-6.47489118576 -10.7323560715,0.954992949963,-6.3811917305 -10.6072845459,0.938975334167,-6.25770950317 -10.6072683334,0.936966717243,-6.21213579178 -10.527217865,0.925953090191,-6.11861515045 -10.4311609268,0.913938641548,-6.01511669159 -10.2910871506,0.896921932697,-5.88664531708 -10.2070379257,0.885909318924,-5.79313182831 -10.0439624786,0.866895914078,-5.67446660995 -10.0149374008,0.861887097359,-5.61491584778 -9.93189048767,0.850875616074,-5.5244011879 -9.78181648254,0.832860767841,-5.39494419098 -9.72378158569,0.824851512909,-5.32140541077 -9.69075679779,0.819843709469,-5.26185846329 -9.64272594452,0.812835454941,-5.19432067871 -9.5576877594,0.802828490734,-5.12659215927 -9.48264789581,0.79381942749,-5.04507255554 -9.4196138382,0.784811317921,-4.9715385437 -9.346575737,0.775802910328,-4.89202356339 -9.34856700897,0.773798108101,-4.85544490814 -9.26352500916,0.763789772987,-4.77093362808 -9.1804895401,0.753784239292,-4.70720434189 -9.13546466827,0.747778058052,-4.64566469193 -9.08043575287,0.739771842957,-4.58012247086 -9.04441547394,0.734766542912,-4.52457427979 -8.97538280487,0.725760281086,-4.45204973221 -8.91935539246,0.718754708767,-4.38652086258 -8.87233161926,0.712749660015,-4.32697677612 -8.7923002243,0.703745603561,-4.26824378967 -8.73827457428,0.696740865707,-4.20570898056 -8.7022562027,0.690736830235,-4.15315818787 -8.63422775269,0.682732105255,-4.0846323967 -8.65722942352,0.683729827404,-4.06204605103 -8.54018497467,0.670724511147,-3.97054815292 -8.55418682098,0.670723557472,-3.96075344086 -8.48315906525,0.662719726562,-3.89322113991 -8.45014381409,0.657716751099,-3.84367871284 -8.38711833954,0.64971357584,-3.78114151955 -8.35010242462,0.644711017609,-3.73158693314 -8.31208705902,0.639708578587,-3.68104505539 -8.2650680542,0.633706212044,-3.62749814987 -8.20104694366,0.626704633236,-3.58175420761 -8.13902378082,0.618702471256,-3.52122855186 -8.10200977325,0.613700807095,-3.47367405891 -8.09000396729,0.611699461937,-3.43809986115 -8.06199359894,0.607698202133,-3.39454936981 -8.08599853516,0.608697235584,-3.37495946884 -8.01997661591,0.600695967674,-3.31542658806 -7.98696613312,0.596695482731,-3.2856631279 -7.97296047211,0.594694674015,-3.25009179115 -7.98396205902,0.594693958759,-3.22451996803 -7.98596143723,0.593693375587,-3.19594120979 -7.94894981384,0.588692903519,-3.15137910843 -7.90293550491,0.583692550659,-3.10184407234 -7.87492704391,0.579692363739,-3.06128311157 -7.83191490173,0.574692428112,-3.02852797508 -7.82091140747,0.572692394257,-2.9959499836 -7.8139090538,0.570692420006,-2.96438121796 -7.8209104538,0.570692300797,-2.93880081177 -7.80690670013,0.56769245863,-2.90424251556 -7.77990007401,0.564692854881,-2.86567640305 -7.79990530014,0.565692722797,-2.8598716259 -7.81090831757,0.565692782402,-2.83628606796 -7.83391427994,0.567692637444,-2.81670260429 -7.80490732193,0.563693404198,-2.7771487236 -7.81991147995,0.563693463802,-2.75555491447 -7.79690647125,0.560694336891,-2.71899223328 -7.8159122467,0.561694443226,-2.69840407372 -7.81091117859,0.560694754124,-2.68261957169 -7.82091426849,0.560695052147,-2.65903115273 -7.79190826416,0.557696402073,-2.62047672272 -7.83291912079,0.560696005821,-2.60886025429 -7.84592294693,0.560696363449,-2.58528661728 -7.84392404556,0.559697151184,-2.55671620369 -7.77490901947,0.55169993639,-2.50517868996 -7.8549284935,0.559697985649,-2.52033042908 -7.88793706894,0.561697900295,-2.50472855568 -7.93194818497,0.56569737196,-2.49212908745 -7.88393878937,0.559699773788,-2.44857692719 -14.279337883,1.17949020863,-4.6067609787 -14.3573408127,1.18548119068,-4.58314323425 -14.3783302307,1.18647396564,-4.53956604004 -14.4933490753,1.19646692276,-4.55369997025 -14.6953773499,1.2154532671,-4.5700006485 -14.822388649,1.22544193268,-4.5603518486 -14.8473796844,1.22643458843,-4.51776266098 -14.7533445358,1.21643185616,-4.43625688553 -14.6673135757,1.20642924309,-4.35873985291 -14.7493228912,1.21342277527,-4.35989809036 -14.7883167267,1.21641504765,-4.32130527496 -14.764298439,1.21240997314,-4.26374816895 -12.8519163132,1.02748990059,-3.63240551949 -12.7378854752,1.01549136639,-3.55490326881 -12.6808662415,1.00849044323,-3.49437189102 -12.679857254,1.00748705864,-3.45080423355 -12.6548480988,1.00448668003,-3.42302465439 -12.6428384781,1.00248384476,-3.37646412849 -12.64083004,1.00148081779,-3.33388733864 -12.6258192062,0.998478353024,-3.28633308411 -12.6178102493,0.996475756168,-3.24176597595 -12.5877971649,0.99247443676,-3.19121313095 -12.5967922211,0.992471039295,-3.15163421631 -12.5577812195,0.988471806049,-3.11987471581 -12.5877790451,0.990467369556,-3.08628034592 -12.613776207,0.991463243961,-3.05168676376 -12.6617774963,0.99545776844,-3.02208566666 -12.6857748032,0.996453762054,-2.98649549484 -12.7267742157,0.999448657036,-2.95390677452 -12.757771492,1.00144422054,-2.92030739784 -12.789773941,1.00444102287,-2.90650773048 -12.8387746811,1.00743544102,-2.87689876556 -12.9197797775,1.01442778111,-2.85427451134 -13.0207881927,1.02341866493,-2.83564138412 -15.8221902847,1.28623199463,-3.44934678078 -15.8921880722,1.29222226143,-3.41373324394 -15.987195015,1.30021345615,-3.40988707542 -16.3052272797,1.32918655872,-3.42912626266 -16.2982139587,1.32718157768,-3.37356686592 -16.3202018738,1.32817494869,-3.3259780407 -16.6352329254,1.3571472168,-3.34022307396 -16.785238266,1.37013101578,-3.31756687164 -16.6632080078,1.35813450813,-3.23806619644 -16.6982059479,1.36012923717,-3.21826100349 -16.6971931458,1.35912406445,-3.1636941433 -16.6351718903,1.35212349892,-3.09716153145 -16.6521606445,1.35311710835,-3.04559111595 -16.6621494293,1.3531113863,-2.9940135479 -16.6581344604,1.35210669041,-2.9394466877 -16.9031524658,1.37408268452,-2.93173313141 -17.0881652832,1.3900655508,-2.93884038925 -17.0901546478,1.3900603056,-2.88426971436 -17.270160675,1.4060407877,-2.86159563065 -17.2841491699,1.40603458881,-2.80901575089 -17.2881355286,1.40502917767,-2.75345134735 -17.2851219177,1.40402460098,-2.69788169861 -17.2691078186,1.40202105045,-2.63932681084 -17.3111038208,1.40501499176,-2.61851906776 -17.3650989532,1.41000580788,-2.57191896439 -17.4990997314,1.4209895134,-2.53826856613 -17.4470825195,1.41598927975,-2.47373509407 -17.4510688782,1.41498434544,-2.41916108131 -17.4970607758,1.41897571087,-2.37056541443 -17.6140651703,1.42896294594,-2.35971570015 -17.6200523376,1.42895781994,-2.3041472435 -16.2239170074,1.29908037186,-2.05039000511 -16.1969051361,1.29607951641,-1.99483895302 -16.1088867188,1.28708457947,-1.93132257462 -16.1138801575,1.2870811224,-1.88075172901 -16.0318641663,1.27808582783,-1.81922924519 -15.9988574982,1.27508747578,-1.79045665264 -15.9978475571,1.27408492565,-1.73889482021 -15.9998397827,1.27408194542,-1.68832612038 -15.9798297882,1.27208137512,-1.63576519489 -16.0258235931,1.27507424355,-1.59017324448 -16.0108146667,1.27407324314,-1.53860652447 -15.9568080902,1.2680773735,-1.50685787201 -15.9718008041,1.26907360554,-1.45827889442 -16.0427970886,1.27506411076,-1.41566610336 -16.0457897186,1.27506148815,-1.36509823799 -16.0857849121,1.27805519104,-1.31850624084 -16.1897850037,1.28704237938,-1.27787661552 -16.2997817993,1.29702889919,-1.2372430563 -16.5277919769,1.31800401211,-1.23133504391 -18.094871521,1.46183764935,-1.31488001347 -18.0788612366,1.45983588696,-1.25632488728 -18.1218528748,1.46382796764,-1.20273554325 -18.1338424683,1.46382343769,-1.14715909958 -18.030828476,1.45483124256,-1.082649827 -18.1398220062,1.46381628513,-1.03402042389 -9.64242076874,0.681739926338,-0.422034919262 -9.65342521667,0.682741761208,-0.392456293106 -9.65143013,0.682745099068,-0.361886978149 -9.65143489838,0.682748198509,-0.332304537296 -9.63743877411,0.680752873421,-0.301733523607 -9.64344501495,0.681755542755,-0.271166831255 -9.6374464035,0.680757761002,-0.256375223398 -9.64545154572,0.681760191917,-0.226794674993 -9.64045715332,0.680764019489,-0.19622695446 -9.62746047974,0.679768919945,-0.165659382939 -9.64346694946,0.680770337582,-0.137064650655 -9.63647174835,0.679774641991,-0.106498070061 -9.63947677612,0.679777681828,-0.0769170746207 -9.63947963715,0.679779410362,-0.0621266514063 -9.62048435211,0.678785204887,-0.0315629318357 -9.6314907074,0.678787410259,-0.00198097643442 -9.61949539185,0.677792489529,0.0285822357982 -9.61850070953,0.677796244621,0.0581616908312 -9.62650680542,0.678798913956,0.0877441614866 -9.62551212311,0.678802788258,0.118309751153 -9.62551498413,0.678804636002,0.13309969008 -9.63352108002,0.678807377815,0.162682965398 -9.61152648926,0.676813840866,0.19225230813 -9.61553287506,0.677817106247,0.221833884716 -9.62753868103,0.678819537163,0.25240623951 -9.60954475403,0.67682570219,0.281974852085 -9.61955070496,0.67782831192,0.311560750008 -9.60655403137,0.676831901073,0.326341688633 -9.61056041718,0.676835477352,0.35690960288 -9.59256649017,0.675841629505,0.385489225388 -9.60957241058,0.676843583584,0.416067540646 -9.61657905579,0.677846729755,0.445653051138 -9.60758590698,0.676851987839,0.475224614143 -9.60558891296,0.67685431242,0.490012556314 -9.60259532928,0.676858961582,0.520575106144 -9.59760189056,0.676863789558,0.55014950037 -9.60460853577,0.676867067814,0.579735994339 -9.59561538696,0.676872491837,0.609305977821 -9.59562206268,0.676876783371,0.638885319233 -9.5986289978,0.676880776882,0.669454276562 -9.58963298798,0.676884055138,0.683247506618 -9.5866394043,0.675888776779,0.712823033333 -9.58464717865,0.675893545151,0.743385910988 -9.57465362549,0.675899267197,0.771966338158 -9.58565998077,0.676902294159,0.802546679974 -9.58966827393,0.676906347275,0.833118140697 -9.5776758194,0.675912380219,0.861694812775 -9.58567810059,0.676913678646,0.877482712269 -9.5816860199,0.676918804646,0.907056987286 -9.58169364929,0.676923334599,0.936637341976 -9.5857000351,0.677927494049,0.96721047163 -9.57670783997,0.676933348179,0.995790481567 -9.57271575928,0.676938593388,1.02536451817 -9.57471942902,0.676940798759,1.04114437103 -9.57472705841,0.677945494652,1.07072556019 -9.57173442841,0.677950680256,1.10030150414 -9.5747423172,0.677955091,1.13087439537 -9.56975078583,0.677960693836,1.16044676304 -9.5607585907,0.676966786385,1.18902516365 -9.56576633453,0.677970945835,1.21960282326 -9.55177116394,0.676975488663,1.23337996006 -9.5687789917,0.678977906704,1.26496863365 -9.57678604126,0.679981648922,1.29555416107 -9.54979515076,0.677990734577,1.32310819626 -9.55180358887,0.677995502949,1.35368108749 -9.55481052399,0.678999960423,1.38327085972 -9.55481910706,0.679005146027,1.41384041309 -9.54282474518,0.67800951004,1.4276188612 -9.55683231354,0.680012524128,1.45920705795 -9.54684066772,0.679019153118,1.48778176308 -9.54684925079,0.680024385452,1.51835238934 -9.53985786438,0.680030584335,1.54693388939 -9.5278673172,0.679037630558,1.57550275326 -9.53587436676,0.680041730404,1.60707986355 -9.55887794495,0.682041049004,1.62587571144 -9.52888774872,0.68005079031,1.65144002438 -9.52989673615,0.681056022644,1.68201470375 -9.52890491486,0.681061446667,1.71159803867 -9.53091526031,0.682066619396,1.74217629433 -9.51992416382,0.681073665619,1.77074670792 -9.53292751312,0.682074546814,1.78853476048 -9.53193664551,0.683080196381,1.81910610199 -9.51094722748,0.681088864803,1.84567534924 -9.52695465088,0.683091878891,1.87826836109 -9.5239648819,0.684098005295,1.90883481503 -9.5129737854,0.683105289936,1.93740487099 -9.52298259735,0.684109210968,1.96899676323 -9.50398826599,0.683115184307,1.98176145554 -9.50599765778,0.684120476246,2.0123436451 -9.50600719452,0.684126138687,2.04292011261 -9.50001716614,0.684132814407,2.07249164581 -9.49602603912,0.6841391325,2.10206985474 -9.50603485107,0.686143279076,2.13465285301 -9.49504089355,0.685147821903,2.14744019508 -9.49105072021,0.685154438019,2.17800521851 -9.48706054688,0.686160802841,2.2075843811 -9.49006938934,0.686166226864,2.23915982246 -9.48707962036,0.687172532082,2.2687432766 -9.49208927155,0.688177704811,2.30131387711 -9.48009967804,0.68718546629,2.32889342308 -9.48410511017,0.688187837601,2.34567785263 -9.47511482239,0.688195228577,2.3742544651 -9.47812461853,0.689200699329,2.40583372116 -9.46913528442,0.689208328724,2.43539714813 -9.47414493561,0.690213382244,2.46698498726 -9.47615432739,0.69121915102,2.49856281281 -9.47116470337,0.691226184368,2.52912831306 -9.47316932678,0.691228866577,2.54492139816 -9.46918106079,0.692235708237,2.57549166679 -9.46519184113,0.692242622375,2.60606193542 -9.46920108795,0.693247973919,2.63765048981 -9.45821285248,0.693256020546,2.66622114182 -9.45622158051,0.693262517452,2.69680023193 -9.42823600769,0.692273557186,2.72135591507 -9.46523761749,0.69527053833,2.74715924263 -9.46124744415,0.696277320385,2.7767457962 -9.44826030731,0.695285916328,2.8053085804 -9.45426940918,0.697291314602,2.83888411522 -9.44528102875,0.697299063206,2.86746406555 -9.41429424286,0.694310605526,2.89002966881 -9.44429779053,0.698308825493,2.9148273468 -9.44730758667,0.699314713478,2.94740629196 -9.44731807709,0.700321316719,2.97997355461 -9.4373292923,0.700329363346,3.0085504055 -9.43534088135,0.700336277485,3.04012298584 -9.42435359955,0.700344622135,3.0686955452 -9.43236351013,0.702349841595,3.10327458382 -9.4533662796,0.704349339008,3.12508249283 -9.35638809204,0.696372568607,3.12661862373 -9.42639064789,0.703367233276,3.18122076988 -9.42440223694,0.704374134541,3.21279716492 -9.42841243744,0.705380141735,3.24637579918 -9.43542289734,0.707385540009,3.28095722198 -9.4254360199,0.707394003868,3.31052422523 -9.4174413681,0.707398593426,3.32331943512 -9.41145324707,0.707406401634,3.35389256477 -9.41646385193,0.709412276745,3.38846755028 -9.42047595978,0.710418522358,3.42303919792 -9.42148590088,0.71142500639,3.45562291145 -9.40549945831,0.711434662342,3.48318815231 -9.41350460052,0.712436556816,3.50198554993 -9.40751647949,0.712444424629,3.53256225586 -9.40952777863,0.714451134205,3.56712841988 -9.40054035187,0.71445953846,3.59670376778 -9.42154884338,0.717462658882,3.63729214668 -9.37956619263,0.714477062225,3.65485239029 -9.40957355499,0.718478679657,3.6994395256 -9.39958095551,0.717483878136,3.71222519875 -9.39959335327,0.718490898609,3.74579906464 -9.40160369873,0.720497429371,3.77938485146 -9.39761543274,0.720505297184,3.81195235252 -9.39762783051,0.722512304783,3.84552955627 -9.38164234161,0.721522271633,3.8730969429 -9.39064598083,0.723524093628,3.89289712906 -9.38265991211,0.723532617092,3.92347049713 -9.38167190552,0.724539935589,3.95704507828 -9.38468360901,0.726546645164,3.99261784554 -9.38569545746,0.727553427219,4.0262055397 -9.37770843506,0.727561950684,4.0567817688 -9.36872196198,0.728570878506,4.08735275269 -9.37872600555,0.72957277298,4.10913944244 -9.36274051666,0.729582905769,4.13670969009 -9.36875247955,0.731588959694,4.17329263687 -9.36676502228,0.732596576214,4.20686912537 -9.36477661133,0.733604431152,4.24143409729 -9.35778999329,0.733612835407,4.27202033997 -9.35380363464,0.734620988369,4.30558776855 -9.35480976105,0.735624492168,4.32337760925 -9.31982707977,0.733638167381,4.3419470787 -9.31383991241,0.734646737576,4.37451601028 -9.31885147095,0.735653102398,4.41110181808 -9.31786441803,0.737660646439,4.4456782341 -9.32787513733,0.739666461945,4.48624944687 -9.29489326477,0.737679958344,4.50581645966 -6.68731975555,0.47416767478,3.30548095703 -6.68433475494,0.475176304579,3.3290643692 -6.68534946442,0.476184278727,3.35464859009 -6.66436815262,0.475196450949,3.37021613121 -6.69937801361,0.480198264122,3.41280698776 -6.68539476395,0.479209035635,3.43138480186 -6.63341188431,0.475223004818,3.41914629936 -6.61842870712,0.474233955145,3.43672847748 -6.61644458771,0.475242614746,3.46130681038 -6.59346437454,0.474255442619,3.47586917877 -6.57248258591,0.473267555237,3.49044704437 -6.54050350189,0.470282047987,3.50000905991 -6.51952219009,0.469294309616,3.51458382607 -6.53352737427,0.471295803785,3.53438258171 -6.52154541016,0.471306502819,3.55395507812 -6.47156953812,0.467324376106,3.55351400375 -6.41859436035,0.463342815638,3.55107331276 -6.48359870911,0.471339166164,3.61167049408 -6.51660776138,0.475341051817,3.65427780151 -6.50562572479,0.475351750851,3.67484545708 -6.47963809967,0.473360896111,3.67362761497 -6.42966270447,0.469378858805,3.67219018936 -6.43567705154,0.471386373043,3.70176649094 -6.45568943024,0.474390894175,3.73836255074 -6.45170593262,0.475400388241,3.76293110847 -6.42872524261,0.473413079977,3.77551388741 -6.40674495697,0.472425788641,3.78908896446 -6.38175773621,0.470435142517,3.78885531425 -6.34078121185,0.467451542616,3.79142212868 -6.33479833603,0.468461275101,3.81400156021 -6.37480688095,0.473462224007,3.86359500885 -6.38482141495,0.476469039917,3.8961751461 -6.38683652878,0.477477222681,3.92375946045 -6.38084554672,0.477482676506,3.93354725838 -6.37086343765,0.477493196726,3.95412683487 -6.36288022995,0.478503286839,3.97571063042 -6.33290290833,0.476518034935,3.98526644707 -6.31392288208,0.475530475378,4.00083494186 -6.31793785095,0.477538198233,4.02942800522 -6.32194471359,0.478541731834,4.04522228241 -6.33095932007,0.480548709631,4.07780647278 -6.30997943878,0.479561656713,4.09237194061 -6.281001091,0.478575915098,4.10094833374 -6.26402044296,0.477588027716,4.1175198555 -6.29103136063,0.481591612101,4.16210842133 -6.28504943848,0.482601523399,4.18568706512 -6.27905845642,0.482607066631,4.19547653198 -6.23108386993,0.478625297546,4.19203805923 -6.2630944252,0.483627945185,4.24062681198 -6.25611162186,0.48463794589,4.26321363449 -6.25212955475,0.485647708178,4.28878688812 -6.22315120697,0.483662247658,4.29735660553 -6.24116373062,0.486667454243,4.33694982529 -6.21317815781,0.484677553177,4.33272171021 -6.22619199753,0.487683832645,4.36931037903 -6.22820806503,0.489692300558,4.39889240265 -6.20922851562,0.488705068827,4.41446208954 -6.1932477951,0.488716900349,4.43104791641 -6.21326112747,0.492722272873,4.47461843491 -6.18828248978,0.490735977888,4.48519802094 -6.20128822327,0.493737965822,4.50898838043 -6.19730520248,0.4947476089,4.53457307816 -6.1963224411,0.49575689435,4.5631480217 -6.18034267426,0.495769053698,4.58072280884 -6.18635702133,0.497776567936,4.61331748962 -6.18137550354,0.498786896467,4.63988304138 -6.16838645935,0.497793823481,4.64467430115 -6.16540336609,0.499803304672,4.67126274109 -6.1574215889,0.499813914299,4.69484090805 -6.16543674469,0.50282138586,4.73042345047 -6.15745592117,0.503832280636,4.7549905777 -6.14747428894,0.503843069077,4.77657842636 -6.13449430466,0.503854930401,4.79714822769 -6.1435008049,0.505857586861,4.81894302368 -6.10952472687,0.503873348236,4.82251930237 -6.13353633881,0.508877933025,4.87209606171 -6.12855482101,0.50988805294,4.89867448807 -6.12557220459,0.510897874832,4.92724943161 -6.13558673859,0.513904750347,4.96484661102 -6.15060043335,0.517910838127,5.00743484497 -6.13061332703,0.515919446945,5.00721693039 -6.14662647247,0.519925296307,5.05080699921 -6.11864948273,0.517940044403,5.05938148499 -6.1306643486,0.521946966648,5.10095930099 -6.1166844368,0.521959066391,5.12153053284 -6.14269590378,0.526962935925,5.17412519455 -6.13470602036,0.526969015598,5.18292093277 -6.12572526932,0.527980268002,5.20848560333 -6.13673973083,0.530987143517,5.24907922745 -6.0937666893,0.528005361557,5.24662971497 -6.13477420807,0.535005927086,5.31224107742 -6.1207947731,0.535018265247,5.33380746841 -6.12181138992,0.537027060986,5.3664021492 -6.10382461548,0.53603553772,5.3681769371 -6.12183761597,0.540041208267,5.41676330566 -6.1098575592,0.541052818298,5.43934345245 -6.1298699379,0.545058012009,5.48993396759 -6.09789466858,0.543073773384,5.49550390244 -6.11090898514,0.54708057642,5.54108428955 -6.08793067932,0.546094357967,5.55366897583 -6.10093736649,0.549096643925,5.58344888687 -6.11695051193,0.553102552891,5.631046772 -6.09797239304,0.553115785122,5.64861822128 -6.13898038864,0.560117065907,5.72120332718 -6.09800767899,0.55713480711,5.71876955032 -6.08402776718,0.557146847248,5.74035167694 -6.08603620529,0.559151291847,5.76013803482 -6.08605337143,0.561160504818,5.79472589493 -6.12906074524,0.569161176682,5.8703212738 -6.10008478165,0.56717646122,5.87889289856 -6.09210395813,0.569187343121,5.90647983551 -6.11011743546,0.573193252087,5.96006298065 -6.0911397934,0.573206663132,5.97863292694 -6.1221408844,0.578204989433,6.02643632889 -6.09316587448,0.577220499516,6.03599882126 -6.10517978668,0.581227302551,6.08359479904 -6.07720470428,0.580242753029,6.09415721893 -6.10321569443,0.585246562958,6.15576076508 -6.0892367363,0.586259126663,6.1803278923 -6.10724067688,0.590259969234,6.21613502502 -6.10126018524,0.591271162033,6.24969673157 -6.09927845001,0.594280898571,6.28528404236 -6.10629415512,0.597289025784,6.33086681366 -6.08531713486,0.597302913666,6.3484377861 -6.08933401108,0.600311517715,6.39102458954 -6.05435991287,0.598328173161,6.39359855652 -6.0693655014,0.601330041885,6.42938661575 -6.0773806572,0.605337738991,6.47598218918 -6.094394207,0.610343813896,6.53356838226 -6.06741857529,0.609358906746,6.54514074326 -6.07943344116,0.613366186619,6.59871912003 -6.06345558167,0.614379107952,6.62229299545 -6.06147384644,0.617389142513,6.66087341309 -6.07048034668,0.619392096996,6.69067049026 -6.06549978256,0.621402919292,6.72724151611 -6.07151603699,0.625411212444,6.77482843399 -6.06453561783,0.62742215395,6.80841207504 -6.05255651474,0.628434300423,6.83699035645 -6.03657865524,0.629447281361,6.86156511307 -6.05759143829,0.63545280695,6.92814588547 -5.98661804199,0.626472055912,6.86892223358 -6.01662826538,0.633475601673,6.94551134109 -8.99289131165,1.05087435246,10.3769464493 -8.97391223907,1.05288779736,10.4195222855 -8.97992801666,1.05789601803,10.4911060333 -8.95994853973,1.05990982056,10.5336771011 -8.91896724701,1.05592286587,10.5184583664 -8.26215267181,0.968067586422,9.81684589386 -8.10820865631,0.951108753681,9.69638633728 -8.03824329376,0.945132791996,9.67394733429 -7.97627639771,0.940155208111,9.66051197052 -7.92730617523,0.938174903393,9.6620798111 -7.90632915497,0.939188957214,9.6976518631 -7.84935188293,0.933205425739,9.65843009949 -7.86436510086,0.939212143421,9.73801136017 -7.87937927246,0.946218907833,9.81859016418 -3.43056297302,0.301148176193,4.3787779808 -3.4135863781,0.301161438227,4.3843626976 -3.39361143112,0.300175637007,4.38693332672 -3.38562369347,0.300182312727,4.39071893692 -7.38662147522,0.902383983135,9.59972572327 -7.32865428925,0.898405730724,9.5862903595 -7.27768516541,0.895426154137,9.58185482025 -7.23271465302,0.893445134163,9.58342933655 -7.21972703934,0.893452882767,9.59820842743 -7.1637597084,0.889474093914,9.5847826004 -7.10379362106,0.884496450424,9.56734275818 -7.04382753372,0.88051867485,9.54890823364 -6.99085950851,0.87653952837,9.53947353363 -6.94388961792,0.873559176922,9.53803825378 -6.89692020416,0.871578752995,9.53560829163 -6.88593196869,0.871585786343,9.5504026413 -6.82996559143,0.867607533932,9.53695869446 -6.7859954834,0.865626633167,9.53852558136 -6.74002552032,0.863645911217,9.53609848022 -6.7220492363,0.864659667015,9.57367229462 -6.63609027863,0.855687260628,9.51423549652 -6.59012126923,0.853706777096,9.51180171967 -6.55313968658,0.849719285965,9.48958683014 -6.51716756821,0.848736822605,9.5011548996 -6.52018547058,0.853746116161,9.56774044037 -6.44322490692,0.846772193909,9.52029323578 -6.40825271606,0.845789313316,9.53186798096 -6.41626882553,0.851797759533,9.60745048523 -6.3133058548,0.837823927402,9.48621940613 -6.31832313538,0.842833042145,9.55779838562 -6.22436761856,0.832862377167,9.48035907745 -6.17639970779,0.829882383347,9.47192573547 -6.14242696762,0.82889932394,9.483502388 -6.09145975113,0.824919879436,9.46907329559 -6.05648756027,0.823937237263,9.47964382172 -6.03350353241,0.822946846485,9.47543430328 -5.99253368378,0.820965528488,9.47700023651 -5.95256328583,0.818983852863,9.47857379913 -5.93158769608,0.820998191833,9.51015281677 -5.91161203384,0.822012424469,9.54372882843 -5.89563560486,0.8250259161,9.58430480957 -5.88365745544,0.828038394451,9.63088607788 -5.86467218399,0.827047586441,9.63466453552 -5.85769319534,0.831059157848,9.69024467468 -5.86870908737,0.839067041874,9.77583026886 -5.90871667862,0.851068913937,9.91042232513 -5.85075187683,0.846091091633,9.88398647308 -5.86876583099,0.855097532272,9.98357486725 -5.89076900482,0.862098157406,10.0563678741 -5.88079071045,0.86611032486,10.109951973 -5.88980674744,0.873118519783,10.1965408325 -5.87083101273,0.875132679939,10.2371149063 -5.88084745407,0.883140742779,10.3277006149 -5.86287117004,0.886154651642,10.3702802658 -5.86888837814,0.89316368103,10.455862999 -5.88589286804,0.899165272713,10.5236577988 -5.92090272903,0.912168443203,10.6632432938 -5.90492582321,0.915181994438,10.7128200531 -5.90694475174,0.922191917896,10.7953987122 -5.8919672966,0.925204992294,10.8459863663 -5.88298892975,0.930217146873,10.9095668793 -5.90300273895,0.94122338295,11.0281486511 -5.89001607895,0.941231250763,11.0459318161 -5.8830370903,0.947242856026,11.1145172119 -5.88605499268,0.954252541065,11.2031011581 -5.87807607651,0.959264338017,11.2716846466 -5.89309120178,0.96927177906,11.3872623444 -5.8701171875,0.972286820412,11.4298381805 -5.87612485886,0.97729074955,11.4846315384 -5.87014579773,0.983302056789,11.559220314 -5.88815975189,0.994308710098,11.683804512 -5.90217494965,1.00431632996,11.8033819199 -5.87720155716,1.00633180141,11.844959259 -5.88621807098,1.01634037495,11.9555435181 -5.88423776627,1.02335107327,12.0451250076 -5.92223644257,1.03534853458,12.1699228287 -5.89726305008,1.03836405277,12.2145013809 -5.88028717041,1.04237771034,12.2760801315 -5.8223233223,1.03839993477,12.2526531219 -2.5843269825,0.653594195843,8.98236370087 -2.55934500694,0.649604380131,8.94815254211 -2.53837156296,0.652618765831,8.97973632812 -2.43946385384,0.647669434547,8.95047092438 -2.21380090714,0.703847467899,9.63506793976 -2.21083259583,0.72086340189,9.82945156097 -2.180945158,0.776920557022,10.447385788 -2.96173405647,1.15278291702,14.4659128189 -2.73582434654,1.06983745098,13.5894603729 -2.96477413177,1.19580304623,14.949090004 -2.67188501358,1.0788705349,13.7086324692 -2.84485220909,1.18384718895,14.8312454224 -2.79188919067,1.18086802959,14.8068218231 -2.74292492867,1.17888784409,14.8014030457 -2.54599666595,1.09193146229,13.8731594086 -2.70796704292,1.19691026211,15.0047750473 -2.67399811745,1.20392727852,15.0833616257 -2.63403105736,1.20794534683,15.1329421997 -2.5900657177,1.20996427536,15.1645174026 -2.56509375572,1.22197949886,15.3031044006 -2.5551071167,1.22998654842,15.3898973465 -2.49614620209,1.22400844097,15.3344726562 -2.44218349457,1.22002899647,15.3020572662 -2.40421581268,1.2260466814,15.3706417084 -2.36224985123,1.23006510735,15.4192218781 -2.33527874947,1.243080616,15.5678043365 -2.31830501556,1.2630944252,15.7893896103 -2.31531620026,1.27710008621,15.9421815872 -2.20337200165,1.23713207245,15.5197515488 -2.14740967751,1.23215293884,15.468337059 -2.09044837952,1.22617411613,15.4139165878 -2.03148770332,1.21919584274,15.3424940109 -2.49236488342,1.57911801338,19.2351455688 -2.46338391304,1.57912862301,19.2409420013 -2.40242409706,1.58015060425,19.2495155334 -2.34346294403,1.58017218113,19.2670974731 -2.28550171852,1.58219349384,19.2916812897 -2.22454166412,1.58221554756,19.2982597351 -2.16957950592,1.58723640442,19.3558387756 -2.11061835289,1.58825778961,19.370426178 -2.08263754845,1.59026825428,19.3972148895 -2.02567625046,1.59428942204,19.4447937012 -1.96371626854,1.59331142902,19.438375473 -1.90575492382,1.59533262253,19.4719600677 -1.84479486942,1.59635448456,19.4835395813 -1.78283500671,1.59537637234,19.4771213531 -1.720875144,1.59439837933,19.4737033844 -1.69189453125,1.59540879726,19.4924964905 -1.62993490696,1.59543073177,19.4910736084 -1.56897473335,1.59545242786,19.4956588745 -1.51201331615,1.60047328472,19.5542411804 -1.45505189896,1.60549414158,19.6158256531 -1.40208947659,1.61751449108,19.7464027405 -1.34912669659,1.62853443623,19.8739910126 -1.32214534283,1.63354444504,19.9337844849 -1.25718688965,1.63156688213,19.9113616943 -1.18922877312,1.62258970737,19.8149471283 -1.12626922131,1.62161147594,19.8045310974 -1.06231021881,1.61863362789,19.7821102142 -1.00135016441,1.62065505981,19.8066940308 -0.969370722771,1.61866605282,19.7894859314 -0.906411290169,1.61768782139,19.7770671844 -0.84445142746,1.61670935154,19.7706546783 -0.781492173672,1.61573112011,19.7632331848 -0.719532489777,1.61675262451,19.7668170929 -0.657572627068,1.61577403545,19.7624034882 -0.59461337328,1.61379563808,19.7469844818 -0.56363338232,1.6128064394,19.7327804565 -0.500674068928,1.61082792282,19.7103614807 -0.43871435523,1.60984933376,19.6999473572 -0.376754552126,1.60787069798,19.6785335541 -0.314794927835,1.60789203644,19.6831150055 -0.252835273743,1.6079133749,19.6836986542 -0.190875589848,1.60593450069,19.6642837524 -0.159895807505,1.60694527626,19.674074173 -0.0989355742931,1.60896611214,19.6976642609 -0.0369759015739,1.60598731041,19.6662483215 --0.0429710671306,1.61501514912,18.4776935577 --0.100932024419,1.61403548717,18.4652767181 --0.158892944455,1.61305594444,18.4538631439 --0.216853752732,1.60907626152,18.4214458466 --0.274814754725,1.61109650135,18.4360313416 --0.302795678377,1.60710644722,18.3978271484 --0.360756665468,1.60912668705,18.4084129333 --0.418717563152,1.60914695263,18.4079971313 --0.475678890944,1.60616695881,18.3765830994 --0.533639729023,1.60618722439,18.3731689453 --0.591600775719,1.60720729828,18.386756897 --0.62058120966,1.60721743107,18.3855476379 --0.678542256355,1.60823750496,18.3891334534 --0.735503673553,1.60725736618,18.3787250519 --0.793464541435,1.60727739334,18.3713092804 --0.850425899029,1.60629713535,18.3588962555 --0.909386336803,1.60731744766,18.3674793243 --0.966347754002,1.60633718967,18.3560676575 --0.995328426361,1.60734701157,18.3658638 --1.05428886414,1.60836732388,18.3744468689 --1.11225008965,1.60938704014,18.3790359497 --1.17121064663,1.61040711403,18.3886203766 --1.22917175293,1.61142683029,18.390209198 --1.28913211823,1.61444699764,18.4157962799 --1.31611335278,1.6114563942,18.3875904083 --1.37507414818,1.61347639561,18.4011802673 --1.43203532696,1.6124958992,18.3837661743 --1.48999667168,1.61351549625,18.3853569031 --1.54795777798,1.61353504658,18.3839454651 --1.60791802406,1.61555504799,18.3985309601 --1.66587913036,1.61557459831,18.3951187134 --1.69585931301,1.61658465862,18.3999118805 --1.75681948662,1.61960446835,18.4295005798 --1.81578040123,1.62162423134,18.4350891113 --1.87374162674,1.62164354324,18.433681488 --1.93370187283,1.62266325951,18.4402656555 --1.99366283417,1.62568295002,18.4598617554 --2.05362319946,1.62670266628,18.4684467316 --2.08460307121,1.62871265411,18.4792385101 --2.14456367493,1.63073217869,18.4898300171 --2.20652365685,1.63375210762,18.5124168396 --2.26448488235,1.63277125359,18.5030059814 --2.32444548607,1.63479077816,18.5095939636 --2.3854060173,1.63681042194,18.5271892548 --2.4463660717,1.63883006573,18.5347747803 --2.47834610939,1.64183998108,18.5585746765 --2.54230523109,1.64486002922,18.5891628265 --2.60326552391,1.64687955379,18.5947494507 --2.66522574425,1.64889919758,18.6113395691 --2.72318696976,1.64891803265,18.600933075 --2.7871465683,1.6529378891,18.6255207062 --2.81912636757,1.6539478302,18.6403160095 --2.8800868988,1.65596699715,18.6489105225 --2.94204688072,1.65798652172,18.656496048 --3.00300788879,1.66000568867,18.667093277 --3.06396818161,1.66102480888,18.6686820984 --3.12892746925,1.66504466534,18.6952705383 --3.18688869476,1.66406321526,18.6798629761 --3.22386717796,1.66907382011,18.7176570892 --3.28182864189,1.66809237003,18.7052536011 --3.34378886223,1.67011165619,18.7078399658 --3.40275025368,1.67013013363,18.7004356384 --3.46770954132,1.67314982414,18.7210254669 --3.52967000008,1.67516887188,18.724615097 --3.59362983704,1.67818808556,18.7412090302 --3.6246099472,1.6781976223,18.7430038452 --3.69156908989,1.68321728706,18.7735977173 --3.75652861595,1.68623638153,18.7931938171 --3.8174893856,1.68725514412,18.7887859344 --3.87745070457,1.68727362156,18.7813796997 --3.94340991974,1.69029307365,18.7999687195 --4.00537014008,1.69231164455,18.8005599976 --4.03335142136,1.69132053852,18.7883605957 --4.09631156921,1.69233942032,18.7889480591 --4.16826915741,1.69835960865,18.8335399628 --4.24422597885,1.70638036728,18.8961372375 --4.3031873703,1.70639836788,18.8787288666 --4.366147995,1.70741677284,18.8833274841 --4.4041261673,1.71142721176,18.9111232758 --4.46708583832,1.71244573593,18.9087104797 --4.52804756165,1.71346390247,18.9023094177 --4.59500694275,1.71648287773,18.9199047089 --4.65896701813,1.71850144863,18.9204940796 --4.72592639923,1.72152042389,18.9360923767 --4.78788757324,1.72253835201,18.9326896667 --4.82086706161,1.72354781628,18.9364852905 --4.88582706451,1.72556626797,18.940076828 --4.95178699493,1.7285848856,18.950674057 --5.01674699783,1.73060333729,18.9522666931 --5.07670879364,1.73062098026,18.9378623962 --5.14466810226,1.73363959789,18.954460144 --5.21262741089,1.73665833473,18.9680557251 --5.24160861969,1.7366669178,18.9558506012 --5.31356668472,1.74168622494,18.9834480286 --5.40051984787,1.75070774555,19.060043335 --5.46448087692,1.7527256012,19.0596446991 --5.51844453812,1.75074195862,19.0182323456 --5.52442264557,1.73175096512,18.8178253174 --5.54040813446,1.72675740719,18.7626228333 --5.58737421036,1.72277235985,18.7072238922 --5.60934734344,1.7097837925,18.5648136139 --5.64131784439,1.70179665089,18.4614105225 --5.65229463577,1.6858061552,18.293006897 --5.58829402924,1.64580452442,17.8855934143 --5.64025878906,1.64482009411,17.8561954498 --5.64724636078,1.63782525063,17.7779865265 --5.6972117424,1.63584053516,17.7425861359 --5.73218107224,1.6288536787,17.6601810455 --5.77214956284,1.62486755848,17.5947761536 --5.81711626053,1.62088215351,17.5433673859 --5.86608123779,1.61889731884,17.5059661865 --5.90904903412,1.61591136456,17.4535655975 --5.93903017044,1.61691975594,17.4513626099 --5.99099493027,1.61593520641,17.422958374 --6.04995775223,1.61695158482,17.416557312 --6.11091947556,1.61896824837,17.4141540527 --6.16488456726,1.61898386478,17.3927536011 --6.22184753418,1.61899983883,17.3783493042 --6.28980779648,1.62301743031,17.39594841 --6.321788311,1.62402582169,17.3967437744 --6.37575292587,1.62404119968,17.3743400574 --6.43971395493,1.62705814838,17.3779373169 --6.50967407227,1.63107562065,17.4005413055 --6.56863689423,1.63209176064,17.3881320953 --6.62859964371,1.63410770893,17.3827362061 --6.62759065628,1.626111269,17.2975311279 --6.67355728149,1.62312531471,17.2541294098 --6.74551677704,1.62814295292,17.2787303925 --6.8254737854,1.63516175747,17.3203258514 --6.87743902206,1.63417637348,17.2919235229 --6.96539354324,1.64319622517,17.3535251617 --7.01136112213,1.64120984077,17.311126709 --7.04134273529,1.64221775532,17.3049221039 --7.10830402374,1.64523434639,17.3135242462 --7.16226863861,1.64524900913,17.2891216278 --7.2312297821,1.64826583862,17.3007221222 --7.27819681168,1.64727938175,17.2613239288 --7.35615491867,1.65329730511,17.2929229736 --7.40412187576,1.65131103992,17.2545223236 --7.47309207916,1.6613240242,17.3393268585 --7.52105951309,1.66033756733,17.3009281158 --7.57402467728,1.6593517065,17.2735271454 --7.6269903183,1.65936589241,17.2451248169 --7.69095277786,1.66138160229,17.2427272797 --7.78890562057,1.67240178585,17.31432724 --7.79589414597,1.66740620136,17.2561244965 --7.85185909271,1.66742038727,17.2367286682 --7.91182279587,1.66943538189,17.2243309021 --7.97778463364,1.67145109177,17.2219257355 --8.01875495911,1.66846311092,17.1695289612 --8.0877161026,1.67247903347,17.1751308441 --8.18666934967,1.68249881268,17.2437362671 --8.22064971924,1.68450677395,17.2455368042 --8.26261901855,1.68151879311,17.1941394806 --8.34157752991,1.68653583527,17.2177391052 --8.42153644562,1.69255292416,17.2443447113 --8.46350574493,1.6895648241,17.1929473877 --8.55246162415,1.69758296013,17.2345466614 --8.60942649841,1.69859659672,17.2131519318 --8.6404094696,1.69960379601,17.2079544067 --8.70237350464,1.70061814785,17.1945514679 --8.77233505249,1.70463347435,17.1991615295 --8.83529758453,1.70664787292,17.1867580414 --8.89626312256,1.70766198635,17.1723632812 --8.92623615265,1.70267188549,17.0979633331 --9.00020599365,1.71268451214,17.1737709045 --9.07416725159,1.71669995785,17.1823749542 --9.12513446808,1.71671247482,17.147977829 --9.15710735321,1.71172249317,17.0765743256 --9.24506473541,1.71873962879,17.1101799011 --9.32302474976,1.72375535965,17.1257896423 --9.39598655701,1.72777044773,17.13139534 --9.44696331024,1.73277974129,17.160200119 --9.49892997742,1.73179197311,17.1247997284 --9.52690505981,1.726801157,17.0494022369 --9.58387088776,1.72781407833,17.0240039825 --9.69782161713,1.73983383179,17.1006164551 --9.75378799438,1.73984634876,17.0732192993 --9.77176570892,1.73285412788,16.9798202515 --6.57965040207,1.10046517849,11.3872289658 --9.83472061157,1.72987020016,16.902217865 --9.89568710327,1.7308832407,16.8838233948 --9.94065666199,1.72989416122,16.83842659 --9.99462509155,1.72990608215,16.8090324402 --10.0515909195,1.73091840744,16.7836380005 --10.0705766678,1.72892320156,16.7554397583 --10.1185464859,1.7279343605,16.7150402069 --10.1725139618,1.72794616222,16.6846427917 --10.2314805984,1.72995841503,16.6622467041 --10.2964458466,1.73197138309,16.64985466 --10.3584117889,1.73398375511,16.6324615479 --10.4243764877,1.73599684238,16.6210670471 --10.4643564224,1.73900389671,16.6268730164 --10.5243234634,1.74001610279,16.6044750214 --10.6102828979,1.74603104591,16.6250896454 --10.6782474518,1.7490439415,16.6146945953 --10.7402133942,1.7510560751,16.5953006744 --10.7951822281,1.75206708908,16.5669116974 --10.8651456833,1.75507998466,16.5585155487 --10.8981285095,1.75608623028,16.551317215 --10.9570960999,1.75709760189,16.5269241333 --11.0190620422,1.75910949707,16.5065307617 --11.0740308762,1.75912034512,16.4761371613 --11.1309986115,1.76013123989,16.4497489929 --11.1879673004,1.76114237309,16.4203510284 --11.2109537125,1.76114714146,16.3991565704 --11.2719202042,1.76215839386,16.3767623901 --11.3388853073,1.76517033577,16.3623695374 --11.3888559341,1.76518034935,16.3239746094 --11.4448242188,1.76519083977,16.2945823669 --11.5017929077,1.76620149612,16.2661895752 --11.5517635345,1.76621127129,16.2277965546 --11.6077404022,1.77121949196,16.2516040802 --8.18363857269,1.18585479259,11.3716621399 --8.17362499237,1.17785966396,11.2822580338 --11.7526540756,1.77024757862,16.1294250488 --11.8086233139,1.77125775814,16.0980300903 --11.8595933914,1.77126717567,16.0606365204 --11.914563179,1.77127707005,16.0292453766 --11.9455480576,1.77228236198,16.0180511475 --11.9925193787,1.77229118347,15.9756584167 --12.050488472,1.77330112457,15.947265625 --12.1064586639,1.77431082726,15.9168748856 --12.1624279022,1.77532041073,15.8854818344 --8.95425415039,1.24999570847,11.6085357666 --8.93125152588,1.2429959774,11.5413341522 --8.92523574829,1.2360008955,11.4569225311 --8.99220085144,1.24101305008,11.4685335159 --9.0401725769,1.24302327633,11.4551391602 --8.88219642639,1.21201276779,11.1807079315 --12.297293663,1.74535822868,15.3948993683 --12.303276062,1.73936247826,15.3024978638 --12.2802743912,1.73136210442,15.2242937088 --12.3342456818,1.73237097263,15.1929035187 --12.5481748581,1.75839543343,15.357542038 --12.808093071,1.79142415524,15.5741834641 --12.330201149,1.70938122272,14.8956975937 --9.24097824097,1.22708749771,11.0807380676 --9.38692474365,1.24410676956,11.1833562851 --13.0789718628,1.80646133423,15.5508375168 --13.1819314957,1.81447410583,15.5724534988 --13.240901947,1.81648266315,15.5430679321 --9.49184036255,1.24113416672,11.0569639206 --9.37585449219,1.21912813187,10.8515415192 --13.4997940063,1.83251547813,15.5459165573 --13.5327777863,1.83451998234,15.5327167511 --13.6217412949,1.84053087234,15.5363388062 --13.7966833115,1.85854947567,15.6369752884 --13.8686513901,1.86255848408,15.6185903549 --13.9396190643,1.86556744576,15.598200798 --14.1915426254,1.89559233189,15.7808542252 --5.63766098022,0.630832850933,6.17767286301 --5.70962524414,0.638846099377,6.21728038788 --5.69960927963,0.634852170944,6.16586637497 --5.6965918541,0.630858838558,6.12245368958 --5.71356964111,0.630867063999,6.10205602646 --5.73654603958,0.631875872612,6.08765459061 --5.77551794052,0.633886158466,6.08924531937 --5.8314948082,0.640894412994,6.12905073166 --5.85047292709,0.640902638435,6.11065673828 --5.85945272446,0.6399102211,6.08024454117 --5.67736387253,0.593945384026,5.61217021942 --5.68534421921,0.592952609062,5.58477210999 --5.69232368469,0.590960144997,5.55435037613 --5.68831682205,0.589963078499,5.53315353394 --5.68729877472,0.586969673634,5.49674797058 --5.69227981567,0.584976792336,5.46634340286 --5.68526363373,0.581982970238,5.42392969131 --5.68824529648,0.57998996973,5.39151906967 --5.69422578812,0.577997148037,5.36210870743 --5.69920730591,0.577003955841,5.33371973038 --5.69619941711,0.575007081032,5.31351423264 --5.71617650986,0.576015412807,5.2970995903 --5.73215484619,0.576023280621,5.27769374847 --5.64815759659,0.56202352047,5.16627883911 --5.75211524963,0.574037790298,5.22889280319 --5.77309322357,0.574045836926,5.21449184418 --5.80206823349,0.576054751873,5.20607757568 --5.82205486298,0.578059315681,5.20788431168 --5.84303188324,0.578067481518,5.19247436523 --5.87500715256,0.580076336861,5.18706846237 --5.90498304367,0.582084774971,5.18067407608 --5.93295955658,0.583093047142,5.17227840424 --5.95593595505,0.584101259708,5.15786361694 --6.00691604614,0.590107798576,5.1866812706 --6.00089979172,0.587113857269,5.14726829529 --6.7164273262,0.639270484447,5.10688447952 --6.70639657974,0.634281337261,5.03106832504 --6.73737287521,0.636288821697,5.02066659927 --6.7803478241,0.639296770096,5.0192694664 --6.79832744598,0.639303386211,4.99886608124 --6.83331203461,0.64230799675,5.00867843628 --5.50057983398,0.478243142366,3.9880027771 --5.51156044006,0.477250218391,3.96859312057 --5.50854349136,0.475256502628,3.93918347359 --5.53252124786,0.477264106274,3.92978334427 --7.47492408752,0.689423203468,4.91532754898 --7.53289699554,0.694430649281,4.91892910004 --7.58687019348,0.698437869549,4.91953039169 --11.8340091705,1.19461321831,7.64704179764 --11.8170003891,1.18961465359,7.5816283226 --11.8289861679,1.18861699104,7.5372376442 --11.8279733658,1.18561899662,7.48282957077 --11.8339614868,1.18362104893,7.43342590332 --11.8119535446,1.17862212658,7.36701869965 --11.8249387741,1.1766244173,7.32362651825 --11.8079366684,1.17362475395,7.28641700745 --11.8109235764,1.17162680626,7.23702144623 --11.7989139557,1.16762828827,7.17660665512 --11.8029022217,1.16563010216,7.12821102142 --11.804889679,1.16263210773,7.07780790329 --11.8038778305,1.15963375568,7.02640867233 --11.7858753204,1.15663409233,6.99020385742 --11.7898626328,1.15463590622,6.94180297852 --11.7858524323,1.15163755417,6.88839673996 --11.7808418274,1.14863908291,6.83499288559 --11.7868289948,1.14664101601,6.78859567642 --11.7918167114,1.1446428299,6.74119329453 --11.7858066559,1.14164423943,6.68778896332 --11.7758026123,1.13964486122,6.65657997131 --11.7657928467,1.13564610481,6.60218238831 --11.7707805634,1.13364779949,6.55578327179 --11.7637701035,1.13064920902,6.50237703323 --11.7637586594,1.12865078449,6.45297145844 --11.7407522202,1.12365186214,6.39156389236 --11.7947311401,1.12765455246,6.37318229675 --11.7967252731,1.12665534019,6.34897375107 --11.8747005463,1.13265836239,6.34259319305 --11.9576749802,1.13966155052,6.33922100067 --12.0326509476,1.14566421509,6.33084440231 --12.1016283035,1.15166676044,6.31846284866 --12.1956014633,1.15966963768,6.31909179688 --12.1875915527,1.15667057037,6.26568889618 --12.1735887527,1.15367078781,6.23348093033 --12.2765617371,1.16267359257,6.23710536957 --12.2835493088,1.16167461872,6.19170808792 --12.2845392227,1.15967547894,6.14330863953 --12.4834957123,1.17967915535,6.19496917725 --13.7822685242,1.31969714165,6.79596757889 --13.827252388,1.32269740105,6.76358032227 --13.8612422943,1.32469761372,6.75339269638 --13.9102258682,1.32769787312,6.72300863266 --13.9262142181,1.32769751549,6.67560958862 --12.2504787445,1.14168035984,5.8106842041 --8.51507472992,0.73264580965,3.9701423645 --8.40507888794,0.719648301601,3.88572096825 --8.43606090546,0.721652150154,3.86732172966 --8.45505046844,0.722654163837,3.85911631584 --8.45303726196,0.721657633781,3.82571482658 --8.45602416992,0.720661222935,3.79431033134 --8.48900604248,0.722664892673,3.77691674232 --8.52598571777,0.725668609142,3.76051592827 --8.53897190094,0.725672006607,3.73412084579 --8.56296062469,0.727673828602,3.7279176712 --8.57294654846,0.727677166462,3.70052671432 --8.57393360138,0.725680530071,3.66812038422 --8.59191703796,0.726683914661,3.64271235466 --8.59290409088,0.725687265396,3.61030435562 --8.60788822174,0.725690484047,3.58491206169 --8.60487651825,0.724693715572,3.55151033401 --8.61286830902,0.724695324898,3.53830528259 --8.61085605621,0.722698569298,3.50489711761 --13.9050664902,1.28568387032,5.68320131302 --13.8660650253,1.2796831131,5.6157913208 --13.8160648346,1.27168226242,5.54337024689 --11.6653652191,1.0426940918,4.61825799942 --11.6433582306,1.03869485855,4.56685352325 --11.6383543015,1.03669524193,4.54264450073 --11.6323461533,1.03469598293,4.49723863602 --11.6363353729,1.03369653225,4.45583486557 --11.6203279495,1.03069734573,4.40743160248 --11.6223182678,1.02869796753,4.36603307724 --11.6193094254,1.02769863605,4.32263088226 --11.6183004379,1.02569913864,4.27922058105 --11.5972986221,1.02269971371,4.25102043152 --11.6052875519,1.02270019054,4.21161699295 --11.6002788544,1.02070057392,4.16821670532 --11.5992698669,1.01870119572,4.12581253052 --11.5902614594,1.01670181751,4.08040332794 --11.5962514877,1.01570212841,4.04100370407 --11.5922431946,1.013702631,3.99759578705 --11.5802402496,1.01170301437,3.97339820862 --11.5742311478,1.00970351696,3.92898416519 --11.5772218704,1.00870382786,3.8895907402 --11.5772132874,1.00770413876,3.84818601608 --11.58020401,1.00670444965,3.80778121948 --11.5711965561,1.00470495224,3.76438188553 --11.5591926575,1.00270533562,3.73916912079 --11.5651826859,1.0017054081,3.70077300072 --11.5661745071,1.00070559978,3.66037106514 --11.4771766663,0.990707993507,3.59093856812 --11.4341726303,0.984709382057,3.53651738167 --11.4231643677,0.982709884644,3.49311208725 --11.4481534958,0.983709454536,3.46071505547 --11.4341506958,0.981709957123,3.43651032448 --11.4231424332,0.979710459709,3.39310216904 --11.4281339645,0.978710532188,3.35570955276 --11.4201259613,0.976710855961,3.31330084801 --11.4221172333,0.97571092844,3.27389431 --11.4251089096,0.974710941315,3.23549509048 --11.4201011658,0.973711192608,3.19509553909 --11.4060983658,0.97171163559,3.1708843708 --11.4090881348,0.97071158886,3.13248300552 --11.4130802155,0.97071146965,3.0950884819 --11.3990736008,0.967711925507,3.05167746544 --11.4030647278,0.966711759567,3.01327157021 --11.4030561447,0.965711712837,2.97487473488 --11.4130477905,0.965711236,2.93847370148 --11.3910455704,0.963711977005,2.91326594353 --11.3890380859,0.962711930275,2.87386131287 --11.393029213,0.961711645126,2.83646297455 --11.3870220184,0.959711670876,2.79605579376 --11.385014534,0.958711564541,2.75664925575 --11.4230012894,0.961709678173,2.72725582123 --11.375998497,0.955711483955,2.67784428596 --11.3399982452,0.951712965965,2.64962792397 --11.3599882126,0.953711748123,2.61623167992 --11.3939781189,0.95570987463,2.58583831787 --11.4159679413,0.956708431244,2.55345106125 --11.455956459,0.960706114769,2.5240585804 --11.4829473495,0.962704241276,2.49166345596 --11.5109367371,0.964702367783,2.46027827263 --11.5269317627,0.96570122242,2.44407725334 --11.4729290009,0.9587033391,2.39365410805 --11.4379253387,0.954704582691,2.34824323654 --11.6638917923,0.975691020489,2.31951856613 --11.7048816681,0.979687869549,2.28912901878 --11.7358722687,0.981685161591,2.25673890114 --11.7628669739,0.983683168888,2.24355578423 --11.7958574295,0.986680209637,2.21116518974 --11.8018512726,0.986678719521,2.17275834084 --11.3558778763,0.940704166889,2.04718136787 --11.2648773193,0.930708944798,1.99274718761 --11.6978387833,0.973681628704,2.03650975227 --11.4008541107,0.943699061871,1.94399774075 --11.2968578339,0.932705163956,1.90575027466 --11.4068431854,0.942697286606,1.88839030266 --11.6118221283,0.962683022022,1.88706803322 --11.7608060837,0.976672053337,1.87472355366 --12.1307754517,1.01364600658,1.89947247505 --12.0917730331,1.00864684582,1.85305178165 --11.5098075867,0.950685799122,1.73762130737 --11.3528108597,0.934695482254,1.67516112328 --11.3138065338,0.929697155952,1.63174045086 --11.4587907791,0.943685770035,1.61739552021 --11.3957891464,0.936689078808,1.56996119022 --11.3357858658,0.930692255497,1.52454018593 --11.3057813644,0.92669326067,1.48312282562 --11.3947734833,0.935686051846,1.47796118259 --11.4847621918,0.943677961826,1.45359385014 --11.4737577438,0.942677378654,1.41417908669 --11.3347587585,0.927686810493,1.35872399807 --11.3047533035,0.924687802792,1.31831085682 --11.3697452545,0.930681288242,1.28993272781 --11.3607397079,0.929680585861,1.25151979923 --11.2307424545,0.915690422058,1.21726644039 --11.2217378616,0.914689838886,1.17985868454 --11.3797245026,0.929675340652,1.16252481937 --11.4527158737,0.936667621136,1.13415181637 --11.4867086411,0.939663052559,1.10075998306 --11.4337062836,0.93366587162,1.05833756924 --11.4157009125,0.931665718555,1.01992952824 --11.2967033386,0.919675350189,0.989681959152 --11.2446994781,0.91467833519,0.948257505894 --11.3656902313,0.925665795803,0.922895014286 --11.3036870956,0.919669747353,0.881474912167 --11.225684166,0.911675155163,0.838037192822 --11.3276758194,0.921663939953,0.810674250126 --11.2316732407,0.911671161652,0.766229212284 --11.2096719742,0.909672439098,0.747024834156 --11.2416648865,0.911667585373,0.713634967804 --11.2126607895,0.908668518066,0.675216555595 --11.2196559906,0.909666001797,0.639815628529 --11.2436504364,0.911661744118,0.605420410633 --11.2836446762,0.915655851364,0.572032928467 --11.2816419601,0.914655029774,0.55383002758 --11.3196372986,0.918649196625,0.520446360111 --11.341632843,0.920644819736,0.486057728529 --11.4186267853,0.927634656429,0.453682869673 --11.406621933,0.926633536816,0.416270375252 --11.3476190567,0.92063754797,0.377851039171 --11.329615593,0.918637156487,0.340435385704 --11.3246107101,0.917635381222,0.304029107094 --11.3336086273,0.918633282185,0.286836713552 --11.334605217,0.91863077879,0.250430077314 --11.2306013107,0.908639848232,0.210984408855 --11.2575969696,0.91063451767,0.175587520003 --11.3465929031,0.919622063637,0.142222464085 --11.3035888672,0.914624452591,0.104798033834 --11.2585849762,0.910627126694,0.0683810263872 --11.3405828476,0.91861641407,0.0522161237895 --11.4575805664,0.929600059986,0.0178611371666 --11.314576149,0.915614128113,-0.020605020225 --11.4645738602,0.93059360981,-0.0549421086907 --11.3135690689,0.915608882904,-0.0924100205302 --11.3915662766,0.923596739769,-0.127776071429 --11.379565239,0.921596705914,-0.145983397961 --11.3115596771,0.915602147579,-0.182419791818 --11.3455572128,0.918595075607,-0.218811318278 --11.4575567245,0.929578185081,-0.255159676075 --11.4035520554,0.924581825733,-0.291592717171 --11.3985500336,0.923579514027,-0.32698905468 --11.7205524445,0.955534994602,-0.368247002363 --11.5255479813,0.936558425426,-0.383536607027 --11.4095430374,0.925570130348,-0.417993932962 --11.3195381165,0.916578710079,-0.452440708876 --11.3995370865,0.924564957619,-0.490810245275 --11.4325361252,0.927557229996,-0.528199791908 --11.4055337906,0.925557494164,-0.563614547253 --11.412530899,0.925553143024,-0.600012540817 --11.4005298615,0.924553155899,-0.617213964462 --14.1496162415,1.19517028332,-0.766354203224 --11.629532814,0.947514355183,-0.699915707111 --11.3305206299,0.918552398682,-0.723462641239 --12.6805686951,1.05135786533,-0.82723981142 --12.1515474319,0.999423623085,-0.878292322159 --14.0816278458,1.18914210796,-1.01059639454 --14.0946311951,1.19113326073,-1.05598914623 --13.8816251755,1.17015779018,-1.08648455143 --13.9046287537,1.17314732075,-1.13288021088 --14.0106372833,1.18312454224,-1.1842263937 --14.041642189,1.18711280823,-1.23161649704 --11.571516037,0.944480836391,-1.08517670631 --14.0466470718,1.18810117245,-1.29921543598 --14.0666513443,1.1900908947,-1.34560585022 --14.0416536331,1.18808734417,-1.38801515102 --13.9806547165,1.18208956718,-1.42744445801 --14.263674736,1.21003746986,-1.49871575832 --14.3206834793,1.21702075005,-1.54908359051 --14.5267000198,1.23697972298,-1.61538755894 --14.3306894302,1.21800708771,-1.61968684196 --12.3085613251,1.01932644844,-1.45805811882 --13.952673912,1.18205273151,-1.67167210579 --11.4415025711,0.934457838535,-1.44227290154 --13.9096794128,1.17804443836,-1.75548648834 --11.7045211792,0.961404919624,-1.54595077038 --13.975692749,1.18601775169,-1.85326147079 --13.8856887817,1.17702913284,-1.86450183392 --11.4074993134,0.932442843914,-1.60410583019 --11.5365095139,0.946416020393,-1.65744972229 --16.289899826,1.41658985615,-2.31052327156 --16.3209114075,1.42057323456,-2.3669052124 --16.4059295654,1.42954707146,-2.43126296997 --11.6675233841,0.961372792721,-1.82499992847 --16.1729240417,1.40757119656,-2.4779779911 --16.1679325104,1.40756082535,-2.52937841415 --16.1209392548,1.40355801582,-2.57480120659 --16.0679416656,1.39955615997,-2.61922860146 --11.7145338058,0.968339920044,-2.00279283524 --11.7095346451,0.968335330486,-2.03918862343 --11.8795518875,0.985301136971,-2.08530783653 --11.8205480576,0.980306208134,-2.11474299431 --16.1349964142,1.40949201584,-2.86499071121 --11.4395112991,0.94336616993,-2.12773633003 --11.8135538101,0.981289744377,-2.228951931 --16.3030452728,1.42842435837,-3.0521030426 --15.9280147552,1.3924844265,-3.03869318962 --11.9915790558,1.00024008751,-2.35787367821 --11.9255743027,0.994246482849,-2.38531112671 --16.4341011047,1.44435536861,-3.26343512535 --11.8965768814,0.993239343166,-2.45813131332 --11.8735771179,0.991237461567,-2.49254250526 --14.7149276733,1.27566170692,-3.08851146698 --14.6279249191,1.26766896248,-3.11895060539 --14.2248792648,1.22774529457,-3.06235814095 --14.0988721848,1.216760993,-3.08382582664 --12.2326383591,1.03013396263,-2.74418234825 --11.9866094589,1.00717759132,-2.73270821571 --11.9786128998,1.0071721077,-2.7711186409 --11.9496126175,1.00417137146,-2.80453538895 --11.8736066818,0.9981803298,-2.82697153091 --12.0826377869,1.01913261414,-2.89306569099 --12.2626667023,1.03808689117,-2.97438120842 --14.471988678,1.26060521603,-3.52064538002 --12.2236719131,1.03607988358,-3.04720640182 --13.9689340591,1.21269273758,-3.49870681763 --12.2736902237,1.0430533886,-3.14098596573 --12.2476911545,1.04105126858,-3.17539715767 --12.2987012863,1.04703605175,-3.20857405663 --12.3397140503,1.05201888084,-3.25995445251 --12.38372612,1.05700063705,-3.31334209442 --12.4167375565,1.06098496914,-3.36272001266 --12.5787696838,1.07893967628,-3.44704532623 --12.9128322601,1.11385452747,-3.57627034187 --13.1618804932,1.13978803158,-3.6855404377 --13.198890686,1.14477455616,-3.71772265434 --13.5089521408,1.17669272423,-3.84596180916 --13.4349489212,1.17069971561,-3.87139964104 --13.2269229889,1.15073823929,-3.8599114418 --13.198925972,1.14873468876,-3.89732861519 --13.1489267349,1.14473628998,-3.9287610054 --13.1199302673,1.14273321629,-3.96517515182 --13.1979494095,1.15170931816,-4.01033687592 --13.2879753113,1.16167712212,-4.08168983459 --13.3539972305,1.16965043545,-4.14705848694 --13.402015686,1.17662787437,-4.20743560791 --13.2890043259,1.1656447649,-4.21989917755 --13.4590473175,1.18459188938,-4.31720638275 --13.5280723572,1.19256329536,-4.38557481766 --13.2270183563,1.16263306141,-4.31593894958 --13.3890609741,1.18058133125,-4.41225004196 --13.5581064224,1.19952714443,-4.5125617981 --16.2576713562,1.47882556915,-5.42248821259 --16.2916965485,1.48380064964,-5.49087285995 --16.3477268219,1.49076986313,-5.56624221802 --16.593788147,1.51769793034,-5.675303936 --16.5127887726,1.51070213318,-5.70674848557 --16.4167881012,1.50271081924,-5.73219776154 --16.4008045197,1.50269794464,-5.78561258316 --16.898935318,1.55654859543,-6.01373338699 --16.2268047333,1.48871099949,-5.84050178528 --16.6039104462,1.52959239483,-6.03069782257 --17.9762325287,1.67321264744,-6.54213237762 --17.739200592,1.65025734901,-6.52166080475 --17.6011943817,1.63827562332,-6.53513431549 --17.4801883698,1.62728941441,-6.55460262299 --17.3711853027,1.61830031872,-6.57706069946 --17.7893104553,1.66416430473,-6.7942276001 --17.8473491669,1.67212796211,-6.879591465 --17.7753448486,1.66513800621,-6.88483095169 --17.7453613281,1.66412627697,-6.93724346161 --16.5020771027,1.53645980358,-6.52734518051 --20.1950283051,1.92638361454,-8.00965309143 --20.2450752258,1.9343444109,-8.10201835632 --20.4611625671,1.9592564106,-8.26129627228 --20.5512180328,1.9712048769,-8.37063503265 --17.2003726959,1.62016201019,-7.10694360733 --18.3346862793,1.74181807041,-7.59450054169 --18.3707237244,1.74778532982,-7.67587375641 --17.0594005585,1.61115324497,-7.2080245018 --18.3247680664,1.74775397778,-7.79269742966 --18.4468307495,1.76369464397,-7.91102361679 --18.0387477875,1.72279524803,-7.80865859985 --19.584192276,1.88831412792,-8.49396800995 --19.6402435303,1.89727187157,-8.5903301239 --16.4573707581,1.56022548676,-7.2985663414 --16.4784011841,1.56519913673,-7.36895132065 --16.5124359131,1.5711684227,-7.44633483887 --16.4774513245,1.56915915012,-7.49275159836 --16.6495285034,1.59008479118,-7.63104915619 --16.6615447998,1.59307062626,-7.66824388504 --16.6685733795,1.59604752064,-7.73463869095 --16.734621048,1.60600543022,-7.82799959183 --17.0177345276,1.63889324665,-8.02123355865 --17.1307983398,1.65383470058,-8.1385679245 --17.2648696899,1.67076873779,-8.26688957214 --17.3279190063,1.68072533607,-8.36325454712 --17.5510044098,1.70564091206,-8.50131988525 --17.7120857239,1.72656428814,-8.64562511444 --17.8291549683,1.74150133133,-8.77095794678 --17.9782352448,1.76042759418,-8.91126346588 --18.1283187866,1.78035247326,-9.05457496643 --18.3524265289,1.8072514534,-9.23584365845 --18.4224853516,1.81820189953,-9.34219932556 --18.6865901947,1.84909904003,-9.50924110413 --18.8586845398,1.87101364136,-9.66853427887 --19.1468200684,1.9058868885,-9.88876342773 --19.2909088135,1.92480933666,-10.037071228 --19.4339962006,1.94373106956,-10.1873855591 --19.6841239929,1.97461462021,-10.3936309814 --19.8782348633,1.99951684475,-10.5729103088 --20.2783966064,2.04536008835,-10.8218708038 --20.354467392,2.05730223656,-10.9432210922 --20.5775909424,2.08619093895,-11.1434831619 --20.6866779327,2.1021194458,-11.2858181 --20.9208087921,2.13200259209,-11.4950695038 --21.4210414886,2.19178771973,-11.8511619568 --21.7202033997,2.2286438942,-12.1023788452 --21.7832508087,2.23760318756,-12.1815376282 --22.9377422333,2.37114167213,-12.9082317352 --23.5780410767,2.4478662014,-13.3582344055 --23.6291179657,2.45780754089,-13.4845981598 --23.6311759949,2.46276664734,-13.5839910507 --23.5852165222,2.46274375916,-13.6564130783 --23.5002403259,2.45773601532,-13.7058572769 --23.7133560181,2.48363471031,-13.8779249191 --23.8004493713,2.49856042862,-14.0272626877 --23.7995109558,2.50351929665,-14.1276597977 --23.9496326447,2.52541947365,-14.3169622421 --23.9416904449,2.52938055992,-14.4133577347 --23.9677639008,2.53732776642,-14.5307340622 --24.0438575745,2.55125498772,-14.6790819168 --24.1369304657,2.56419634819,-14.7872228622 --24.2210292816,2.57911992073,-14.9415626526 --24.2811203003,2.59105157852,-15.0839223862 --24.3432121277,2.60398221016,-15.2272777557 --24.3282718658,2.60794353485,-15.3236789703 --24.1842746735,2.59595680237,-15.3401613235 --24.1123085022,2.5939412117,-15.4005994797 --24.0583190918,2.58994078636,-15.4198303223 --23.9713478088,2.58593130112,-15.471280098 --23.9404010773,2.58689880371,-15.5576934814 --23.8434238434,2.58189368248,-15.6021499634 --23.8404903412,2.58684945107,-15.7065448761 --23.8625679016,2.59479475021,-15.826921463 --23.8856143951,2.60076141357,-15.8971090317 --23.9347057343,2.61269450188,-16.0364685059 --23.9767951965,2.62262988091,-16.1728382111 --23.8688144684,2.61562871933,-16.2103004456 --23.7988510132,2.61361217499,-16.2717380524 --24.7863998413,2.73613572121,-17.0505084991 --24.6824245453,2.73013114929,-17.0939674377 --24.5804138184,2.72115063667,-17.0812320709 --24.5034503937,2.71813464165,-17.1416721344 --24.4334926605,2.71611571312,-17.2071094513 --24.3215103149,2.7091152668,-17.2435760498 --24.1955223083,2.70012140274,-17.2690486908 --24.091545105,2.6941177845,-17.3095092773 --24.0005760193,2.69010853767,-17.3589630127 --23.9135704041,2.68312287331,-17.3542156219 --23.8045883179,2.67612218857,-17.3896789551 --23.7156200409,2.67211270332,-17.4391326904 --23.6086387634,2.66511106491,-17.4755954742 --23.4946556091,2.65811300278,-17.5070667267 --23.4006824493,2.65310645103,-17.5515193939 --23.3087120056,2.64809894562,-17.5969734192 --23.2397117615,2.64310622215,-17.6022148132 --23.1577453613,2.64009380341,-17.655664444 --23.0397567749,2.63209867477,-17.681137085 --22.9297733307,2.62510037422,-17.7116031647 --22.8558101654,2.62308502197,-17.7690467834 --22.749830246,2.61708474159,-17.8025131226 --22.6758651733,2.6140692234,-17.8599567413 --22.6128692627,2.61007475853,-17.867193222 --22.523897171,2.6060667038,-17.9126491547 --22.4349250793,2.6020591259,-17.9571018219 --22.3429508209,2.59705281258,-17.9995594025 --22.2659835815,2.59403991699,-18.0520019531 --22.1750106812,2.59003305435,-18.0954627991 --22.0990447998,2.58701944351,-18.1489086151 --22.0250415802,2.58203077316,-18.1461544037 --21.9420719147,2.57802057266,-18.1946086884 --21.8551006317,2.57401299477,-18.2380599976 --21.790140152,2.57299399376,-18.2994976044 --21.701166153,2.56898713112,-18.3419551849 --21.626203537,2.5669734478,-18.3954029083 --21.541229248,2.56296491623,-18.4398555756 --21.4952430725,2.560962677,-18.4590835571 --21.4122714996,2.55795359612,-18.5045337677 --21.3353061676,2.55494070053,-18.5559864044 --21.261341095,2.55292701721,-18.6084308624 --21.1863765717,2.55091309547,-18.6618824005 --21.1274204254,2.54989123344,-18.7273178101 --21.0814762115,2.55186223984,-18.8047466278 --21.0444927216,2.55085539818,-18.8309688568 --20.9735298157,2.54884004593,-18.8854122162 --20.9135761261,2.54881834984,-18.9508514404 --20.8576221466,2.5497944355,-19.0192871094 --20.78565979,2.54777979851,-19.0727329254 --20.7066917419,2.54476833344,-19.1211853027 --20.6547431946,2.54574203491,-19.1936187744 --20.6357727051,2.54772520065,-19.235830307 --20.5598087311,2.54471230507,-19.286283493 --20.4738349915,2.54170560837,-19.3267383575 --20.419883728,2.54268074036,-19.3961715698 --20.3379154205,2.53967142105,-19.4406280518 --20.2749557495,2.53865146637,-19.5020675659 --20.2589912415,2.54063224792,-19.5482788086 --20.1900291443,2.5396156311,-19.603723526 --20.1190700531,2.53860020638,-19.6581726074 --20.0501079559,2.53758430481,-19.7126140594 --19.9931545258,2.53756070137,-19.7800540924 --19.9362049103,2.53853678703,-19.8474903107 --19.8572368622,2.5355257988,-19.893945694 --19.8452739716,2.53850436211,-19.943151474 --19.8063354492,2.54146957397,-20.0285778046 --19.7413787842,2.54145050049,-20.0880222321 --19.6884307861,2.54242372513,-20.1604595184 --19.6434898376,2.54439234734,-20.2398872375 --19.5795345306,2.54437255859,-20.3003311157 --19.5245876312,2.54534673691,-20.3707695007 --19.5196323395,2.54931974411,-20.4289722443 --19.4766921997,2.55228614807,-20.5124034882 --19.4177417755,2.55326342583,-20.5778427124 --19.3317699432,2.54925656319,-20.6163024902 --19.2898349762,2.55322241783,-20.7007331848 --19.2619094849,2.55817818642,-20.8011569977 --19.2520008087,2.56612324715,-20.9195613861 --19.2220249176,2.56611132622,-20.9527816772 --19.1060295105,2.55912446976,-20.9582633972 --18.9069576263,2.53919315338,-20.871799469 --18.7289066315,2.52324819565,-20.8083248138 --18.588886261,2.51227903366,-20.783821106 --18.4848957062,2.50628590584,-20.7992992401 --18.4139328003,2.50527119637,-20.8507480621 --18.331911087,2.49729585648,-20.8230018616 --18.0978050232,2.4723918438,-20.690568924 --18.1349391937,2.48830389977,-20.8629455566 --18.0579719543,2.48629403114,-20.9054012299 --17.9649887085,2.48129487038,-20.9308700562 --17.8690032959,2.47729849815,-20.951335907 --17.8040466309,2.47728013992,-21.0077857971 --17.7450428009,2.47328996658,-21.0040225983 --17.6520614624,2.46929121017,-21.0284938812 --17.5710868835,2.46628522873,-21.0639476776 --17.4811077118,2.46228456497,-21.0914173126 --17.3891239166,2.45828652382,-21.1138839722 --17.3121547699,2.45627713203,-21.1553401947 --17.2221736908,2.45327734947,-21.180809021 --17.1791858673,2.45127606392,-21.1960411072 --17.0851974487,2.44728016853,-21.2145061493 --16.9992218018,2.44427776337,-21.243970871 --16.8732032776,2.43430542946,-21.2234649658 --16.7682037354,2.42831850052,-21.226940155 --16.6882324219,2.42631196976,-21.2634048462 --16.6192684174,2.4252986908,-21.3108520508 --16.5602626801,2.42131018639,-21.3040962219 --16.4742851257,2.41830897331,-21.3315620422 --16.4103279114,2.4182908535,-21.387014389 --16.3343582153,2.41728210449,-21.4264717102 --16.2293586731,2.41029620171,-21.4279499054 --16.0993328094,2.40033054352,-21.3954467773 --16.0423812866,2.40230751038,-21.4588909149 --16.0134067535,2.40229678154,-21.489112854 --15.9154119492,2.39730644226,-21.4975852966 --15.7603559494,2.38336157799,-21.4301013947 --15.583272934,2.36443591118,-21.3296298981 --15.5663661957,2.37338137627,-21.4460487366 --15.3432312012,2.34749388695,-21.2816143036 --15.2451763153,2.33654046059,-21.2158851624 --14.9179191589,2.29274082184,-20.9035243988 --14.8018980026,2.28376936913,-20.8800144196 --14.7479476929,2.28574705124,-20.9414577484 --14.7541799545,2.30860519409,-21.2282676697 --12.0010566711,1.85087251663,-17.4386291504 --11.8019113541,1.82598721981,-17.2681789398 --11.6607875824,1.8060811758,-17.1214809418 --11.5347251892,1.79413580894,-17.0519790649 --11.430688858,1.785171628,-17.0144634247 --11.3436717987,1.77919363976,-16.9999351501 --11.4248600006,1.8020683527,-17.2332839966 --11.2997970581,1.7901237011,-17.1627826691 --11.1378202438,1.78413057327,-17.2069187164 --11.098862648,1.78710985184,-17.2643566132 --11.0378780365,1.78510904312,-17.2878112793 --11.0700111389,1.80102360249,-17.4541950226 --10.9369316101,1.78608930111,-17.3656978607 --10.962012291,1.79603767395,-17.4638824463 --10.8150100708,1.78905892372,-17.4728145599 --10.7760534286,1.79103791714,-17.530248642 --10.7250814438,1.79202783108,-17.569694519 --10.6821212769,1.79401040077,-17.6211338043 --10.6271438599,1.79400372505,-17.6545829773 --10.6171789169,1.7969840765,-17.6987934113 --10.5652065277,1.79797434807,-17.737241745 --10.5172405243,1.79896116257,-17.7816867828 --10.464266777,1.79895269871,-17.8181343079 --10.4203062057,1.80093479156,-17.8705787659 --10.3743429184,1.8029191494,-17.9190216064 --10.3293809891,1.80490243435,-17.9694633484 --10.304397583,1.80589640141,-17.9906864166 --10.2604379654,1.80787789822,-18.04413414 --10.2094678879,1.80886745453,-18.0835762024 --10.1655092239,1.81084895134,-18.1370201111 --10.112537384,1.81183981895,-18.1744689941 --10.0585632324,1.81183183193,-18.2099170685 --10.0216169357,1.81580555439,-18.2763557434 --10.0016412735,1.81779325008,-18.3085803986 --9.94666671753,1.81778633595,-18.3420295715 --9.90170955658,1.82076728344,-18.3964767456 --9.85274410248,1.82175338268,-18.4419231415 --9.80578231812,1.82373762131,-18.4903640747 --9.75381374359,1.82472622395,-18.5318164825 --9.74085044861,1.8277066946,-18.5760288239 --9.69088554382,1.82969331741,-18.6204776764 --9.64592933655,1.83267366886,-18.6759243011 --9.58394622803,1.8316732645,-18.698381424 --9.55501651764,1.83763587475,-18.7838134766 --9.44507217407,1.83861863613,-18.8567180634 --9.39811325073,1.84160125256,-18.9081630707 --9.38916015625,1.84557521343,-18.9633769989 --9.32216835022,1.8435806036,-18.9758358002 --9.28623008728,1.84854912758,-19.0512771606 --9.21823787689,1.84655475616,-19.063741684 --9.27947425842,1.87340664864,-19.3381099701 --9.11831378937,1.85052525997,-19.1576385498 --9.13440704346,1.86046755314,-19.266834259 --9.07142448425,1.86046731472,-19.2892951965 --9.04350566864,1.86742413044,-19.3847293854 --5.51013374329,1.0786973238,-12.1320734024 --9.51480770111,2.01858925819,-20.8756275177 --9.45985126495,2.0205719471,-20.9270820618 --9.40882873535,2.01659345627,-20.9013290405 --9.33784008026,2.01459789276,-20.9157905579 --9.14461421967,1.9847599268,-20.6613483429 --9.09666824341,1.98773562908,-20.7247943878 --9.1639547348,2.01955795288,-21.0501594543 --9.07192420959,2.01358985901,-21.0176429749 --8.9378080368,1.99667918682,-20.8871536255 --8.90381717682,1.99567914009,-20.8983879089 --8.89194965363,2.00860404968,-21.0488090515 --8.78488731384,1.99865722656,-20.9803066254 --8.57861328125,1.9628494978,-20.6728744507 --8.53968715668,1.96881246567,-20.7583122253 --8.45767402649,1.96483385563,-20.7437934875 --8.39970684052,1.96582341194,-20.7832450867 --8.31861114502,1.95389223099,-20.6765098572 --8.22757434845,1.9469281435,-20.6369953156 --8.15657901764,1.9449365139,-20.6444625854 --8.07255649567,1.93896317482,-20.6209430695 --8.02060508728,1.94194364548,-20.6763973236 --7.93758201599,1.93697071075,-20.6518707275 --7.91461372375,1.93995594978,-20.6880989075 --7.85965538025,1.94194102287,-20.7355518341 --7.78164339066,1.93796050549,-20.7240257263 --7.74372625351,1.94491887093,-20.8174705505 --7.65869808197,1.93994891644,-20.7879524231 --7.57467031479,1.93397891521,-20.7584285736 --7.48863697052,1.92801237106,-20.72290802 --7.42256402969,1.91806530952,-20.6431674957 --7.36560106277,1.92005336285,-20.6856269836 --7.2986125946,1.91905772686,-20.7000923157 --7.19553232193,1.90812146664,-20.6125850677 --7.13856840134,1.9101099968,-20.654045105 --7.06656551361,1.90712356567,-20.6525115967 --7.02464294434,1.91408622265,-20.7389640808 --6.98262500763,1.91110348701,-20.720199585 --6.92466163635,1.91209220886,-20.7616634369 --6.84764432907,1.90811514854,-20.7441368103 --6.77865076065,1.90712308884,-20.7526073456 --6.72770595551,1.91110026836,-20.8140640259 --6.65670490265,1.90911269188,-20.814535141 --6.5766787529,1.90414142609,-20.7870121002 --6.54568910599,1.90414071083,-20.7992401123 --6.48170852661,1.90414047241,-20.8217067719 --6.40769672394,1.90116000175,-20.8101787567 --6.30259561539,1.88823604584,-20.7016811371 --6.15335464478,1.85939919949,-20.4422054291 --6.15757703781,1.88227140903,-20.6846237183 --6.09860754013,1.88326430321,-20.719083786 --6.05658626556,1.88028395176,-20.6963272095 --5.96752119064,1.87133622169,-20.6278076172 --5.92961931229,1.88028693199,-20.7352561951 --5.84557247162,1.87332856655,-20.6857376099 --5.75650644302,1.86438155174,-20.6162242889 --5.70054960251,1.86736702919,-20.663690567 --5.64659452438,1.87035059929,-20.7141437531 --5.5664396286,1.85245299339,-20.5484104156 --5.56667566299,1.87731862068,-20.8028392792 --5.50268888474,1.87632238865,-20.8183021545 --5.42465734482,1.8713542223,-20.7857818604 --5.33859443665,1.8634057045,-20.7192649841 --5.27059221268,1.86141872406,-20.7187328339 --5.21953058243,1.85346257687,-20.6539821625 --5.13045310974,1.84352278709,-20.5724697113 --5.05843448639,1.84054636955,-20.5539417267 --4.98039245605,1.83458447456,-20.5104198456 --4.90335178375,1.82862126827,-20.4688949585 --4.83132982254,1.82464659214,-20.4473686218 --4.76433086395,1.82365822792,-20.4498443604 --4.73233318329,1.82366275787,-20.4530754089 --4.64625453949,1.81372284889,-20.3715610504 --4.58326387405,1.81272912025,-20.3830280304 --4.50722122192,1.80776703358,-20.3395042419 --4.45226669312,1.81075155735,-20.388967514 --4.36919355392,1.80180823803,-20.313451767 --4.3202624321,1.80777800083,-20.3879070282 --4.29329061508,1.80976736546,-20.4181423187 --4.2413482666,1.81474411488,-20.4806003571 --4.18338823318,1.81773233414,-20.5240726471 --4.10934734344,1.81276929379,-20.4825458527 --4.02927875519,1.80382287502,-20.412027359 --3.97734355927,1.80979597569,-20.4814910889 --3.91334915161,1.80880475044,-20.4889602661 --3.87230944633,1.80483484268,-20.4482040405 --3.81032395363,1.80483841896,-20.4646701813 --3.74532294273,1.80385112762,-20.465139389 --3.67027115822,1.79789447784,-20.4126186371 --3.61331152916,1.8008825779,-20.4560852051 --3.54227948189,1.79591393471,-20.4245605469 --3.48129892349,1.7969148159,-20.4460277557 --3.45633983612,1.80089640617,-20.4892597198 --3.38228869438,1.79493939877,-20.4377403259 --3.30521440506,1.78599584103,-20.3622169495 --3.23216605186,1.78003704548,-20.3136978149 --3.19331407547,1.79496157169,-20.4681491852 --3.12931704521,1.79397213459,-20.4726200104 --3.06129479408,1.79099774361,-20.4510955811 --2.49788045883,1.44202506542,-16.928609848 --2.43682670593,1.43706691265,-16.8780822754 --2.38482379913,1.43607807159,-16.8805370331 --2.3267865181,1.4321103096,-16.8470039368 --2.25967693329,1.42118453979,-16.7394695282 --2.20767593384,1.42019474506,-16.7439346313 --2.03560757637,1.31182765961,-15.6502323151 --1.97349667549,1.30090165138,-15.5426912308 --1.92851805687,1.30289804935,-15.571149826 --1.88858366013,1.30986881256,-15.6446094513 --1.84561789036,1.31285762787,-15.6860589981 --1.80266606808,1.31783878803,-15.741522789 --1.75668013096,1.31983959675,-15.7619762421 --1.71373045444,1.32481968403,-15.8194360733 --1.69477665424,1.32879722118,-15.8696632385 --1.65081942081,1.33378183842,-15.9191226959 --1.60181295872,1.33279490471,-15.9185781479 --1.56089019775,1.34075951576,-16.003036499 --1.51189172268,1.34076821804,-16.0104980469 --1.84695422649,1.74442911148,-20.1318588257 --1.81393682957,1.7424454689,-20.1150970459 --1.75294744968,1.74345183372,-20.1275672913 --1.68893158436,1.74147391319,-20.1130428314 --1.6461700201,1.76434934139,-20.355512619 --1.57202637196,1.75044476986,-20.2119884491 --1.50902032852,1.74946117401,-20.2074623108 --1.44702708721,1.74947011471,-20.2159366608 --1.41501772404,1.74848198891,-20.2071723938 --1.34287822247,1.73457455635,-20.068649292 --1.27072060108,1.71867752075,-19.9121227264 --1.20871138573,1.71769547462,-19.9045963287 --1.1446698904,1.71273183823,-19.865070343 --1.08061850071,1.70777380466,-19.8155441284 --1.02369201183,1.71474468708,-19.8910140991 --0.990643322468,1.7097786665,-19.8432502747 --0.931691110134,1.71476447582,-19.8927268982 --0.869684636593,1.71378111839,-19.8882026672 --0.808677256107,1.71279799938,-19.8826732635 --0.746658802032,1.71082139015,-19.866147995 --0.687731802464,1.71779322624,-19.9406261444 --0.623637914658,1.70885920525,-19.8490943909 --0.589528381824,1.69792735577,-19.7413291931 --0.528494656086,1.69495904446,-19.7097988129 --0.462265074253,1.67310094833,-19.4842643738 --0.407532125711,1.69896411896,-19.7507534027 --0.346532613039,1.69897687435,-19.7532291412 --0.284408658743,1.68705904484,-19.6326942444 --0.225515410304,1.69701230526,-19.7401714325 --0.194500565529,1.69602739811,-19.7264118195 --0.133473590016,1.69305551052,-19.7018871307 --0.073502600193,1.69605243206,-19.7323608398 --0.0124117648229,1.68811619282,-19.6448326111 -0.0442667156458,1.67478132248,-18.6703128815 -0.103199496865,1.66872763634,-18.6026687622 -0.16325302422,1.6737408638,-18.6540203094 -0.192098736763,1.6586471796,-18.5012130737 -0.247909963131,1.63952696323,-18.3135757446 -0.309020459652,1.6505715847,-18.4209270477 -0.364875882864,1.63647592068,-18.2762928009 -0.425945788622,1.64349794388,-18.3436508179 -0.478748828173,1.6233741045,-18.1470184326 -0.534677505493,1.61631917953,-18.0743808746 -0.564709842205,1.61932897568,-18.105556488 -0.627836227417,1.63238203526,-18.2289066315 -0.683773100376,1.62633180618,-18.164270401 -0.744840502739,1.63235270977,-18.2296218872 -0.805889964104,1.63736367226,-18.2769775391 -0.870007514954,1.64941191673,-18.3923225403 -0.897967398167,1.6453820467,-18.3515071869 -0.959006607533,1.64938747883,-18.3888626099 -1.02004241943,1.65239107609,-18.4232177734 -1.08208346367,1.65639734268,-18.4625720978 -1.14717555046,1.66643106937,-18.5529212952 -1.21125006676,1.67345547676,-18.6262664795 -1.2732758522,1.67645335197,-18.6506233215 -1.30632650852,1.68147277832,-18.7007923126 -1.37543857098,1.69251704216,-18.8121414185 -1.43948912621,1.69852793217,-18.8614902496 -1.50250947475,1.70052289963,-18.8808498383 -1.56756567955,1.70653688908,-18.9361953735 -1.63058209419,1.70852935314,-18.9515552521 -1.69562315941,1.71253526211,-18.9919071198 -1.73067831993,1.71855688095,-19.0470733643 -1.79671919346,1.72256243229,-19.087430954 -1.86377799511,1.72957754135,-19.1457748413 -1.96586477757,1.73859941959,-19.232301712 -2.02685928345,1.73858034611,-19.2256546021 -2.08986449242,1.73956680298,-19.2300128937 -2.12187457085,1.74056446552,-19.2401885986 -2.18487906456,1.74155056477,-19.2435455322 -2.24788141251,1.74253547192,-19.2449035645 -2.3118994236,1.74552893639,-19.262254715 -2.37590479851,1.74651539326,-19.2666168213 -2.43588733673,1.74549031258,-19.2479763031 -2.49990034103,1.74748110771,-19.2603282928 -2.53391671181,1.74948143959,-19.2765083313 -2.59792757034,1.75047123432,-19.286863327 -2.66193389893,1.75245833397,-19.2922210693 -2.72292327881,1.75143706799,-19.2805786133 -2.78592729568,1.75242328644,-19.2839336395 -2.84993577003,1.75441145897,-19.2912883759 -2.9089050293,1.75237941742,-19.2586555481 -2.94493770599,1.75538849831,-19.2918262482 -3.0099503994,1.75737929344,-19.3041801453 -3.07193922997,1.75735735893,-19.2915439606 -3.12689137459,1.75331676006,-19.2409114838 -3.19089531898,1.75430297852,-19.2442703247 -3.25892400742,1.75830185413,-19.2726230621 -3.29193425179,1.76029920578,-19.2827968597 -3.35292220116,1.75927710533,-19.2691574097 -3.41792821884,1.7612644434,-19.2745170593 -3.47991895676,1.76124382019,-19.2638778687 -3.54392528534,1.76223123074,-19.2692317963 -3.60289907455,1.76120197773,-19.2405986786 -3.66488862038,1.76118099689,-19.2289619446 -3.6999065876,1.76318228245,-19.2471370697 -3.76290416718,1.76416540146,-19.2434940338 -3.8258998394,1.76414740086,-19.2378559113 -3.88990139961,1.76613247395,-19.2382144928 -3.95892572403,1.76912903786,-19.2625675201 -4.03297281265,1.77513706684,-19.3109111786 -4.09998655319,1.77812838554,-19.3242664337 -4.13901376724,1.78113412857,-19.3524436951 -4.22109222412,1.79115784168,-19.4337825775 -4.30718564987,1.8021889925,-19.5311145782 -4.39026021957,1.81121075153,-19.6094532013 -4.48136568069,1.82424736023,-19.7197856903 -4.56744909286,1.8342730999,-19.8071212769 -4.65252637863,1.84329593182,-19.8884544373 -4.7005853653,1.85031723976,-19.9506187439 -4.77662229538,1.85631930828,-19.9889621735 -4.8526558876,1.86131989956,-20.0243110657 -4.92768192291,1.86531662941,-20.0516643524 -5.00572109222,1.87131989002,-20.0930099487 -5.07572841644,1.87330722809,-20.1003646851 -5.14674091339,1.87629759312,-20.1137123108 -5.19177913666,1.88130795956,-20.1538848877 -5.2527513504,1.8802781105,-20.1242485046 -5.32275867462,1.88226556778,-20.1315994263 -5.39075517654,1.88324785233,-20.1279602051 -5.46979045868,1.88924884796,-20.1653060913 -5.53477716446,1.8892261982,-20.1506652832 -5.56476163864,1.88821041584,-20.1338500977 -5.63877630234,1.89120125771,-20.1492061615 -5.69874620438,1.89017045498,-20.1165714264 -5.7687497139,1.89215600491,-20.1199245453 -5.8377456665,1.89313769341,-20.1152896881 -5.89872074127,1.89210939407,-20.0876522064 -5.96069526672,1.89108109474,-20.0600204468 -5.99369192123,1.89207148552,-20.0561943054 -6.05566883087,1.89104425907,-20.0305614471 -6.1136302948,1.88900971413,-19.9889354706 -6.17360258102,1.88798034191,-19.9582996368 -6.22254180908,1.88293516636,-19.8916797638 -6.28652620316,1.88291168213,-19.8740406036 -6.34449195862,1.88087952137,-19.8364105225 -6.37247276306,1.87986207008,-19.8145980835 -6.38932085037,1.86477386951,-19.6490116119 -6.49041318893,1.87680196762,-19.748336792 -6.55540084839,1.87778019905,-19.7336997986 -6.61637592316,1.87675261497,-19.7060680389 -6.68336868286,1.87773358822,-19.697429657 -6.74534893036,1.87770843506,-19.6747932434 -6.78335523605,1.87970328331,-19.6809749603 -6.85335731506,1.88168859482,-19.6823291779 -6.91032171249,1.87965619564,-19.64270401 -6.97631168365,1.88063549995,-19.6300678253 -7.04029607773,1.88061273098,-19.6124324799 -7.1002702713,1.88058483601,-19.5827999115 -7.17026901245,1.88256835938,-19.580160141 -7.20025587082,1.88155448437,-19.5653476715 -7.2552189827,1.87952184677,-19.5237178802 -7.31819963455,1.87949705124,-19.5010871887 -7.36113500595,1.87445163727,-19.4284687042 -7.41609668732,1.87241816521,-19.3848495483 -7.50012922287,1.87841749191,-19.4191951752 -7.58315944672,1.88441598415,-19.4515399933 -7.61214494705,1.8834015131,-19.4347248077 -7.6801366806,1.88538193703,-19.4240932465 -7.71906423569,1.87933325768,-19.3424797058 -7.7219119072,1.86324775219,-19.1709041595 -7.67665243149,1.83511388302,-18.8803825378 -7.69453763962,1.82304596901,-18.749797821 -7.71550798416,1.82102513313,-18.7159900665 -7.75143671036,1.81497776508,-18.6343822479 -7.79337882996,1.80993616581,-18.5667724609 -7.82129335403,1.80188286304,-18.4691696167 -7.85922861099,1.79683852196,-18.3935642242 -7.90217494965,1.79279947281,-18.330953598 -7.93209695816,1.78574955463,-18.2403488159 -7.94204616547,1.78071951866,-18.1825580597 -7.97898483276,1.77567720413,-18.1099472046 -8.01892757416,1.77063715458,-18.0433387756 -8.0518579483,1.76459157467,-17.9617385864 -8.09581279755,1.76155722141,-17.9081192017 -8.12974739075,1.7555129528,-17.8295173645 -8.17370223999,1.75247883797,-17.7759037018 -8.1826543808,1.74844992161,-17.7191104889 -8.22661113739,1.74541652203,-17.6664962769 -8.25654029846,1.73837149143,-17.5838947296 -8.29749298096,1.73533594608,-17.5252838135 -8.34245109558,1.73230350018,-17.4746742249 -8.3793964386,1.72826552391,-17.4090671539 -8.41934871674,1.72423040867,-17.3504562378 -8.43030738831,1.72020542622,-17.3016624451 -8.47226333618,1.71717190742,-17.247051239 -8.51822757721,1.71514260769,-17.2024345398 -8.55016708374,1.71010172367,-17.1278343201 -8.58511257172,1.70606458187,-17.0622272491 -8.63608646393,1.70503985882,-17.0286064148 -8.67403793335,1.70100474358,-16.9680023193 -8.68600177765,1.69798231125,-16.92420578 -8.72896385193,1.69595193863,-16.8755912781 -8.7518901825,1.68890678883,-16.7870006561 -8.80286598206,1.68788290024,-16.7543830872 -8.86385822296,1.68986582756,-16.7407550812 -8.88879108429,1.68382334709,-16.6581611633 -8.9167842865,1.68381404877,-16.6483440399 -8.92969799042,1.67576372623,-16.543762207 -8.94161319733,1.66671431065,-16.4401760101 -8.98758220673,1.66568732262,-16.3985671997 -9.0405626297,1.66566622257,-16.3719444275 -9.08553123474,1.66363966465,-16.330329895 -9.12148571014,1.66060698032,-16.2717285156 -9.14246845245,1.65959310532,-16.2489204407 -9.17541980743,1.65555930138,-16.1863174438 -9.24843025208,1.65955042839,-16.1936855316 -9.28438663483,1.65651905537,-16.1370792389 -9.32735443115,1.65449225903,-16.0934658051 -9.3773317337,1.65446984768,-16.0618476868 -9.43031406403,1.65444934368,-16.0352287292 -9.44729042053,1.65243279934,-16.0044307709 -9.50027275085,1.65341281891,-15.9788093567 -9.54624557495,1.65238809586,-15.9401950836 -9.59321975708,1.65136432648,-15.9035816193 -9.6462020874,1.65134441853,-15.8779582977 -9.7242193222,1.6573381424,-15.8923187256 -9.75316810608,1.65230417252,-15.8257217407 -9.77014636993,1.651288867,-15.7969207764 -9.84616088867,1.65628123283,-15.8072834015 -9.89613723755,1.65525901318,-15.7746706009 -9.9601354599,1.65824508667,-15.7660388947 -10.0241327286,1.66023123264,-15.7574081421 -10.0590906143,1.65820109844,-15.7008066177 -10.1140756607,1.65818178654,-15.6761894226 -10.1630973816,1.66318416595,-15.6993560791 -10.2010593414,1.66015589237,-15.6477537155 -10.2470331192,1.66013205051,-15.6091423035 -10.3020181656,1.66111338139,-15.585518837 -10.348991394,1.66008985043,-15.547911644 -10.3979692459,1.66006791592,-15.5142965317 -10.4499511719,1.66004765034,-15.4856777191 -10.4839515686,1.66204166412,-15.4838600159 -10.5369348526,1.66302192211,-15.4562416077 -10.6189527512,1.66801607609,-15.4715995789 -10.6799440384,1.66999971867,-15.4549760818 -10.7299222946,1.66997790337,-15.4213647842 -10.7939186096,1.67296338081,-15.4097356796 -10.8199081421,1.67295277119,-15.3939313889 -10.8718900681,1.67393290997,-15.3653087616 -10.9088525772,1.67090570927,-15.3137073517 -10.9848613739,1.67589581013,-15.317073822 -11.0458526611,1.67787981033,-15.3004465103 -11.1108484268,1.68086493015,-15.2878217697 -11.1768445969,1.68385076523,-15.2771930695 -11.1988306046,1.68283879757,-15.2563877106 -11.2748384476,1.68782866001,-15.2587528229 -11.3238153458,1.68780660629,-15.2231416702 -11.3828039169,1.68878960609,-15.2025175095 -11.4417915344,1.69077157974,-15.179901123 -11.5167961121,1.69476044178,-15.1792669296 -11.5827932358,1.69774603844,-15.1676359177 -11.612786293,1.69873738289,-15.1568260193 -11.6577596664,1.69871425629,-15.1162157059 -11.730761528,1.7017018795,-15.1115856171 -11.7867469788,1.70368301868,-15.0849666595 -11.8677568436,1.70867359638,-15.0903291702 -11.9397573471,1.71266055107,-15.083697319 -12.0197658539,1.71765053272,-15.087059021 -12.078789711,1.72265231609,-15.1122264862 -12.1417798996,1.72563540936,-15.0926046371 -12.2297954559,1.73162806034,-15.1049594879 -12.2927856445,1.73361122608,-15.0853347778 -12.3627815247,1.73659658432,-15.0737075806 -12.429775238,1.73958098888,-15.0580816269 -12.4677772522,1.74257493019,-15.05626297 -12.5357713699,1.74555945396,-15.0416355133 -12.6067686081,1.7485448122,-15.030008316 -12.6767644882,1.75253009796,-15.0173778534 -12.7157306671,1.75050449371,-14.9667768478 -12.7617015839,1.7504812479,-14.9241714478 -12.7235956192,1.73743081093,-14.7826328278 -12.3452062607,1.67628860474,-14.2891588211 -12.3611536026,1.67125785351,-14.2155752182 -12.3911161423,1.66923201084,-14.1589794159 -12.4290847778,1.6682087183,-14.1113796234 -12.4820690155,1.66919028759,-14.0817642212 -12.5090284348,1.66616392136,-14.0221719742 -12.5419940948,1.6641395092,-13.9695739746 -12.5719890594,1.66613149643,-13.9587640762 -12.5999498367,1.66310572624,-13.9001731873 -12.613899231,1.65807580948,-13.8265914917 -12.6388578415,1.65604937077,-13.7650051117 -12.6548099518,1.65102112293,-13.6954164505 -12.6797714233,1.64899528027,-13.6348276138 -12.7037296295,1.64596927166,-13.5732393265 -12.6896877289,1.64094936848,-13.5154619217 -12.7266597748,1.63992750645,-13.4688625336 -12.7446146011,1.63590025902,-13.4012813568 -12.7615690231,1.63187325001,-13.3336982727 -12.7865314484,1.62984848022,-13.2751073837 -12.7984828949,1.62482082844,-13.2035236359 -12.8034591675,1.62280678749,-13.1667337418 -12.828420639,1.62078249454,-13.1081466675 -12.8493814468,1.61775755882,-13.0465574265 -12.8813514709,1.61573588848,-12.9969587326 -12.9163227081,1.61471450329,-12.9493637085 -12.9152650833,1.60868430138,-12.8647985458 -12.9402303696,1.60666143894,-12.8092012405 -12.9291944504,1.60264396667,-12.7564296722 -12.9611644745,1.60062301159,-12.7078304291 -12.9731197357,1.59659695625,-12.6382522583 -12.986076355,1.5935716629,-12.5706701279 -13.0040369034,1.58954763412,-12.5080871582 -13.0270023346,1.58752524853,-12.4514942169 -13.0499668121,1.58550262451,-12.3939085007 -13.0529432297,1.58248949051,-12.3571205139 -13.067902565,1.57946538925,-12.2925395966 -13.1068792343,1.57944667339,-12.2509403229 -13.120839119,1.57642292976,-12.1863565445 -13.1428050995,1.57340085506,-12.1287717819 -13.1587657928,1.57037782669,-12.0661897659 -13.1957435608,1.57035970688,-12.0245828629 -13.1867113113,1.56634438038,-11.9768104553 -13.2086782455,1.56432294846,-11.9202241898 -13.2306461334,1.56230199337,-11.8646335602 -13.2355995178,1.55727720261,-11.7920656204 -13.2565670013,1.55525636673,-11.7364721298 -13.2995481491,1.55623936653,-11.6988744736 -13.3015031815,1.55121529102,-11.6262979507 -13.3084840775,1.5492041111,-11.5945119858 -13.3494653702,1.55018734932,-11.5569057465 -13.3374109268,1.54316103458,-11.4723424911 -13.1862659454,1.51910960674,-11.2658910751 -13.2052345276,1.51708972454,-11.2103023529 -13.1231365204,1.50105178356,-11.0658025742 -12.919962883,1.46999394894,-10.8203840256 -12.9229440689,1.468983531,-10.7885923386 -12.8668661118,1.45695221424,-10.6710643768 -12.8638238907,1.45193016529,-10.5994949341 -12.8918008804,1.45091342926,-10.5539045334 -12.939789772,1.45290005207,-10.5252971649 -8.20782566071,0.843116760254,-6.51944732666 -8.24883270264,0.845113694668,-6.50984334946 -8.32085990906,0.85211545229,-6.52620697021 -8.35386180878,0.853110790253,-6.50861787796 -8.36284923553,0.852102696896,-6.47303152084 -8.38884735107,0.852097153664,-6.4504404068 -8.4128446579,0.853091478348,-6.42684459686 -8.4128370285,0.851086974144,-6.40605068207 -8.44583892822,0.85308265686,-6.38944864273 -8.46883583069,0.853076815605,-6.36485528946 -8.49683475494,0.854071736336,-6.3442568779 -8.52783584595,0.85506683588,-6.32466888428 -8.54683017731,0.855060636997,-6.29707622528 -8.58183383942,0.857056438923,-6.28147411346 -8.58382701874,0.856052577496,-6.26267623901 -8.62083053589,0.85804861784,-6.24807691574 -8.62781906128,0.85604095459,-6.21149253845 -8.66782569885,0.858037412167,-6.19889163971 -8.68681907654,0.858031392097,-6.17129802704 -8.72482395172,0.860027432442,-6.15670156479 -8.72981929779,0.860023975372,-6.13990449905 -8.75681877136,0.861018836498,-6.11731386185 -8.77781486511,0.861013233662,-6.09171295166 -8.79780960083,0.861007332802,-6.06412601471 -8.83881664276,0.863004028797,-6.05251407623 -8.84780597687,0.861996948719,-6.01693534851 -8.88881206512,0.864993453026,-6.00433063507 -8.89980983734,0.864990711212,-5.99153232574 -8.93481254578,0.866986453533,-5.97393846512 -8.95080757141,0.865980446339,-5.94434404373 -8.99181270599,0.868976771832,-5.93074464798 -8.99279975891,0.866969525814,-5.89115810394 -9.04581069946,0.869966924191,-5.88555002213 -9.05780220032,0.869960665703,-5.85296058655 -9.08280754089,0.870959043503,-5.84816598892 -9.10580444336,0.871953845024,-5.82257270813 -9.14080715179,0.87394964695,-5.80497074127 -9.20982551575,0.879948377609,-5.80934715271 -9.14378166199,0.869935631752,-5.72581005096 -9.15977478027,0.868929922581,-5.69522714615 -9.23379611969,0.875928997993,-5.7025976181 -9.25479888916,0.87692719698,-5.69579410553 -9.28880023956,0.878922820091,-5.6762008667 -11.0865936279,1.08605313301,-6.77337884903 -11.0345506668,1.077039361,-6.69283628464 -10.9384899139,1.06302249432,-6.58433437347 -10.8064136505,1.04600358009,-6.45485401154 -10.764377594,1.03799152374,-6.3823094368 -10.7193489075,1.0319839716,-6.33155345917 -10.598279953,1.01596713066,-6.21206045151 -10.4692087173,0.997950196266,-6.08857679367 -10.378153801,0.985936462879,-5.99005794525 -10.3511276245,0.9809268713,-5.92950582504 -10.2050523758,0.961910426617,-5.79903411865 -10.1700305939,0.955904722214,-5.75726699829 -10.0069494247,0.935888051987,-5.61880540848 -9.96992015839,0.928879320621,-5.55624771118 -9.86086463928,0.914866745472,-5.45174646378 -9.83584117889,0.909859001637,-5.39619064331 -9.72178459167,0.894846975803,-5.29069137573 -9.65774726868,0.885837852955,-5.2141623497 -9.61072349548,0.879832744598,-5.16840028763 -9.51467418671,0.866822719574,-5.07588338852 -9.44463729858,0.856814026833,-4.99736356735 -9.38160324097,0.847806036472,-4.92383480072 -9.36058521271,0.843800365925,-4.87526226044 -9.3015537262,0.83579313755,-4.80572223663 -9.2635307312,0.829786896706,-4.74717855453 -9.18649673462,0.819781661034,-4.68743991852 -9.13547039032,0.812775552273,-4.62389230728 -9.0784406662,0.804769337177,-4.55735301971 -9.03741931915,0.798763990402,-4.49980306625 -8.992395401,0.791758596897,-4.44025993347 -8.9313659668,0.783753037453,-4.37272930145 -8.83632564545,0.770746767521,-4.28921127319 -8.82131671906,0.768744647503,-4.26442956924 -8.70326900482,0.753738224506,-4.16993236542 -8.68425655365,0.750734806061,-4.12636804581 -8.64523792267,0.744730889797,-4.07282018661 -8.59121513367,0.737727046013,-4.01326942444 -8.56720161438,0.73372387886,-3.96771478653 -8.47816944122,0.72272080183,-3.90797996521 -8.46315956116,0.719718277454,-3.86840772629 -8.3901309967,0.710714757442,-3.80087661743 -8.34911346436,0.704712092876,-3.74932408333 -8.31109714508,0.69870954752,-3.69878101349 -8.27108097076,0.693707287312,-3.64921808243 -8.19505500793,0.683704733849,-3.58268594742 -8.18505001068,0.681703865528,-3.56191253662 -8.09902000427,0.671701550484,-3.49139022827 -8.07600975037,0.667700171471,-3.45082211494 -8.05400085449,0.663698792458,-3.4102628231 -8.00298404694,0.657697439194,-3.35771083832 -7.97797393799,0.653696477413,-3.31714344025 -7.93295907974,0.647695481777,-3.26759433746 -7.91995477676,0.645695090294,-3.24681830406 -7.89294528961,0.641694366932,-3.20625019073 -7.8659362793,0.637693822384,-3.16470003128 -7.84692955017,0.633693397045,-3.12812685966 -7.82692289352,0.630693078041,-3.09056520462 -7.81691980362,0.628692805767,-3.0579893589 -7.78290987015,0.623692810535,-3.01543021202 -7.7298951149,0.617693066597,-2.97868204117 -7.7428984642,0.617692947388,-2.95609378815 -7.72389316559,0.614693164825,-2.92052364349 -7.71389007568,0.612693369389,-2.88796067238 -7.65887594223,0.605694174767,-2.8384115696 -7.64287185669,0.603694677353,-2.8048377037 -7.62186670303,0.600695133209,-2.78207302094 -7.6258687973,0.599695503712,-2.75649023056 -7.59386110306,0.595696508884,-2.71692967415 -7.58085870743,0.593697309494,-2.68535161018 -7.55085229874,0.588698506355,-2.64679455757 -7.55485486984,0.588699162006,-2.62121844292 -7.48583936691,0.580701351166,-2.56868195534 -7.48183870316,0.579701900482,-2.55488061905 -7.44083070755,0.57470369339,-2.51332807541 -7.44583320618,0.573704659939,-2.48875045776 -7.42082977295,0.570706427097,-2.45319342613 -7.43083429337,0.570707321167,-2.43159604073 -7.40783119202,0.56770914793,-2.3970386982 -7.3878288269,0.564710974693,-2.36446785927 -7.36682510376,0.561712265015,-2.34468483925 -7.35482501984,0.559714078903,-2.31412696838 -7.35882854462,0.559715390205,-2.29053735733 -7.33282566071,0.555717766285,-2.25597953796 -7.35183238983,0.556718766689,-2.23738455772 -7.34883499146,0.555720448494,-2.21081209183 -7.32983398438,0.552722871304,-2.17924642563 -7.33783721924,0.553723394871,-2.16944956779 -7.32983875275,0.551725506783,-2.1418735981 -7.37185049057,0.555725634098,-2.13026976585 -7.37685489655,0.554727256298,-2.10668921471 -7.41486644745,0.558727622032,-2.09309434891 -7.4218711853,0.558729112148,-2.07050466537 -7.41987228394,0.557730197906,-2.05672645569 -7.41387462616,0.556732416153,-2.03014492989 -7.41687870026,0.555734217167,-2.00557208061 -7.37887477875,0.551737964153,-1.97000300884 -7.44489097595,0.557736992836,-1.96438896656 -7.44989585876,0.556738853455,-1.94080817699 -7.35288143158,0.546745598316,-1.88828039169 -7.42189645767,0.552743375301,-1.89545500278 -7.41689968109,0.551745891571,-1.86888504028 -7.45591068268,0.555746078491,-1.85527873039 -7.20687055588,0.529761373997,-1.76184427738 -7.38890695572,0.54675424099,-1.78716480732 -7.4349193573,0.551754236221,-1.77456653118 -7.40191602707,0.547757208347,-1.75379025936 -7.33090829849,0.539763689041,-1.71025776863 -7.35091638565,0.540765047073,-1.69166040421 -7.38792705536,0.543765485287,-1.67705798149 -7.35092544556,0.539770245552,-1.64349746704 -7.36493301392,0.540772199631,-1.62192642689 -7.34393453598,0.537776112556,-1.59334588051 -7.29592943192,0.532780408859,-1.56958281994 -7.32293891907,0.534781634808,-1.5519926548 -7.40595626831,0.542779266834,-1.54737520218 -7.35395336151,0.536785423756,-1.51082825661 -7.43097019196,0.543783247471,-1.50519752502 -16.192243576,1.42620110512,-3.47160816193 -16.2212352753,1.42719376087,-3.42502236366 -16.184223175,1.42319357395,-3.3902592659 -16.3742351532,1.44117510319,-3.37858223915 -7.312977314,0.529804646969,-1.37115597725 -16.4702205658,1.44815778732,-3.29238605499 -16.4332046509,1.44415509701,-3.23083972931 -16.4831962585,1.4471462965,-3.18724584579 -16.5301895142,1.45113766193,-3.14364624023 -16.5491847992,1.45313382149,-3.12084913254 -16.6091785431,1.45712423325,-3.07924437523 -16.6011657715,1.45611989498,-3.02368187904 -16.658159256,1.46011054516,-2.98107886314 -16.586139679,1.4521112442,-2.9135529995 -16.532119751,1.4461107254,-2.85001564026 -16.6501274109,1.45709908009,-2.84516215324 -16.6991195679,1.46109056473,-2.79957151413 -7.10002613068,0.502861917019,-1.05132830143 -7.15703964233,0.508861064911,-1.03871750832 -16.5990715027,1.44808518887,-2.62191987038 -16.5900611877,1.44608151913,-2.56735491753 -16.6110515594,1.44807565212,-2.5177731514 -16.6470489502,1.45107030869,-2.49696874619 -16.704044342,1.45606136322,-2.45237135887 -16.7420368195,1.45905387402,-2.40478229523 -16.7600269318,1.4600481987,-2.35420250893 -16.8080196381,1.46303999424,-2.30760955811 -16.8710136414,1.46903026104,-2.26300787926 -16.8860034943,1.47002494335,-2.21143078804 -16.8980007172,1.47002196312,-2.18663716316 -16.9149894714,1.47101664543,-2.1350607872 -16.9389801025,1.47301054001,-2.08447980881 -16.76795578,1.45502269268,-2.00900053978 -16.1218929291,1.39107978344,-1.87279105186 -16.1318836212,1.39107584953,-1.82222294807 -16.1838798523,1.39606797695,-1.77762389183 -16.413892746,1.4180444479,-1.77971255779 -16.0828590393,1.38507342339,-1.68932330608 -16.2548618317,1.4010540247,-1.65766358376 -16.2568531036,1.40105116367,-1.60708904266 -16.3298511505,1.40704131126,-1.5634816885 -16.3488426208,1.40903675556,-1.51390266418 -16.2898330688,1.40304124355,-1.4821498394 -16.7118549347,1.44399619102,-1.47235536575 -16.345823288,1.40703070164,-1.38498139381 -16.3928165436,1.41102337837,-1.3383834362 -16.8928394318,1.45996952057,-1.33154654503 -17.2168483734,1.49193310738,-1.30680131912 -17.2378406525,1.49292802811,-1.25422418118 -17.2088336945,1.48992967606,-1.22445833683 -17.2128257751,1.48992645741,-1.17088699341 -17.2008152008,1.48792505264,-1.11632287502 -17.1918067932,1.48692333698,-1.06175923347 -17.2077980042,1.48791921139,-1.00918114185 -9.71942806244,0.751728594303,-0.456561893225 -9.70743274689,0.749732792377,-0.425985813141 -9.70743465424,0.749734401703,-0.41020706296 -9.70143795013,0.748738050461,-0.379634261131 -9.70044326782,0.748741209507,-0.35004940629 -9.70844745636,0.749743402004,-0.320466846228 -9.69645214081,0.747747957706,-0.288908064365 -9.69145584106,0.747751653194,-0.259323269129 -9.69146060944,0.74775493145,-0.228753626347 -9.68646335602,0.746757090092,-0.213961660862 -9.68946838379,0.746760129929,-0.183392569423 -9.69847297668,0.74776238203,-0.153809294105 -9.68347835541,0.74576741457,-0.123240612447 -9.68648338318,0.746770441532,-0.0936573967338 -9.69148826599,0.746773421764,-0.0630880072713 -9.68449115753,0.745775878429,-0.0482976995409 -9.67649650574,0.744780361652,-0.0177306663245 -9.68150234222,0.745783209801,0.01185286697 -9.66850662231,0.743788421154,0.0424173921347 -9.67251205444,0.744791507721,0.0720006152987 -9.67551803589,0.744794845581,0.102569580078 -9.67752361298,0.744798243046,0.132152318954 -9.66352653503,0.743801772594,0.146937415004 -9.675532341,0.744804084301,0.177510544658 -9.65953826904,0.743809759617,0.20708437264 -9.65754413605,0.742813766003,0.236664280295 -9.66954994202,0.743816196918,0.26723870635 -9.64555549622,0.741823077202,0.296805024147 -9.6595621109,0.743825256824,0.327381581068 -9.65656471252,0.74282759428,0.342169910669 -9.64457035065,0.741833090782,0.371742159128 -9.63857746124,0.741837799549,0.401318311691 -9.64958286285,0.742840468884,0.431894093752 -9.63058948517,0.740846991539,0.461458384991 -9.63759613037,0.741850137711,0.491045296192 -9.64060306549,0.741854012012,0.521614909172 -9.62460613251,0.740858018398,0.53540366888 -9.62561225891,0.740862011909,0.564984977245 -9.63061904907,0.740865647793,0.595556676388 -9.63862609863,0.741868972778,0.626132428646 -9.61763286591,0.739875912666,0.654703319073 -9.62763881683,0.741878986359,0.685282111168 -9.61964321136,0.740882217884,0.70006275177 -9.615650177,0.740887105465,0.729638457298 -9.62365627289,0.74189054966,0.760215759277 -9.6226644516,0.741895020008,0.789795696735 -9.61867046356,0.740899980068,0.81937122345 -9.62667751312,0.741903483868,0.849950194359 -9.61068534851,0.740910053253,0.878522396088 -9.61368846893,0.740912020206,0.894303500652 -9.60269641876,0.740918040276,0.922882318497 -9.60270404816,0.740922749043,0.9534496665 -9.61071109772,0.741926312447,0.984030306339 -9.59571838379,0.740933001041,1.01260137558 -9.59972572327,0.740937232971,1.04317581654 -9.58973026276,0.739940941334,1.05696332455 -9.59373760223,0.740945160389,1.08753848076 -9.58874511719,0.740950644016,1.11711156368 -9.58975315094,0.740955233574,1.14669561386 -9.59076023102,0.741960048676,1.17726624012 -9.58576869965,0.740965604782,1.20683920383 -9.57977676392,0.740971386433,1.2364102602 -9.57878017426,0.740974009037,1.25119972229 -9.59078788757,0.742977261543,1.28277981281 -9.58379650116,0.741983175278,1.31136274338 -9.57980442047,0.74198871851,1.34093797207 -9.5748128891,0.74199450016,1.3705111742 -9.56882190704,0.742000520229,1.40008211136 -9.56883049011,0.742005646229,1.43065226078 -9.58683300018,0.744005441666,1.44745802879 -9.56884288788,0.743013381958,1.47601544857 -9.58084964752,0.744016706944,1.50760126114 -9.57785892487,0.745022296906,1.53718018532 -9.57186698914,0.744028449059,1.56675136089 -9.55987644196,0.744035482407,1.59532177448 -9.56987953186,0.745036661625,1.61211228371 -9.51189231873,0.740050673485,1.63366103172 -9.55889797211,0.745048940182,1.67125785351 -9.52590847015,0.742059230804,1.69582641125 -9.53891658783,0.744062662125,1.72840631008 -9.54792404175,0.745066821575,1.76097655296 -9.55093288422,0.746071755886,1.79155921936 -9.55593776703,0.747073709965,1.80735373497 -9.61794281006,0.753069698811,1.84895348549 -9.52395820618,0.744089722633,1.86348092556 -9.55396461487,0.748090565205,1.89907479286 -9.54097366333,0.74709802866,1.926653862 -9.55498218536,0.749101519585,1.96023130417 -9.5419921875,0.748109221458,1.98879671097 -9.50799942017,0.745117306709,1.99757015705 -9.53100776672,0.748119294643,2.03216314316 -9.48402023315,0.744132399559,2.05371618271 -9.53903388977,0.751135230064,2.12589693069 -9.53204441071,0.751142084599,2.1554672718 -9.54605293274,0.753145575523,2.18905305862 -6.78927469254,0.476584047079,1.6127307415 -9.49507141113,0.749162614346,2.22538208961 -9.48308181763,0.748170256615,2.25296139717 -9.49909973145,0.751179516315,2.31812357903 -9.50810909271,0.753184080124,2.35169672966 -9.46911716461,0.749193370342,2.35846424103 -9.48212528229,0.751197218895,2.39205169678 -9.48113632202,0.752203345299,2.4226307869 -9.45814800262,0.750213086605,2.44819641113 -9.50715351105,0.756211340427,2.49178647995 -9.63115119934,0.769197046757,2.55342078209 -9.49217414856,0.756225824356,2.54994153976 -9.51717853546,0.759224891663,2.57272934914 -9.5041885376,0.758233070374,2.60030674934 -9.52019691467,0.760236561298,2.6358897686 -9.5062084198,0.760245025158,2.66346406937 -9.46022415161,0.756258904934,2.68301749229 -9.47723293304,0.758262395859,2.71959328651 -9.49824047089,0.761265099049,2.75618767738 -9.50924491882,0.763266324997,2.7749812603 -9.5012550354,0.763273954391,2.80455350876 -9.4872674942,0.762282788754,2.83311414719 -9.49927616119,0.764286935329,2.86770367622 -9.59027767181,0.77527821064,2.9263112545 -9.48429965973,0.765302419662,2.92784070969 -9.48930358887,0.76630461216,2.94463920593 -9.52831077576,0.771304488182,2.98823142052 -9.4353313446,0.762326657772,2.99276566505 -9.44934082031,0.764330863953,3.02934265137 -9.43535232544,0.76433968544,3.0569152832 -9.48135852814,0.769338428974,3.10350704193 -9.47937011719,0.770345330238,3.13508343697 -9.42138195038,0.765358507633,3.13284897804 -9.41839313507,0.765365481377,3.1634323597 -9.41241550446,0.767379879951,3.22657489777 -9.4214258194,0.769384980202,3.2621512413 -9.44743347168,0.772387087345,3.302744627 -9.41344928741,0.770399808884,3.32430171967 -9.46945858002,0.777400016785,3.39169621468 -9.45547199249,0.777409315109,3.42025995255 -9.44348430634,0.777418136597,3.44883298874 -9.45549488068,0.779422938824,3.48640799522 -9.45050621033,0.779430508614,3.51699066162 -9.44651889801,0.780438005924,3.54856610298 -9.45752239227,0.782439529896,3.56935548782 -9.44453620911,0.782448709011,3.59792542458 -9.43454837799,0.782457351685,3.62749767303 -9.45455741882,0.785460710526,3.66808319092 -6.70793056488,0.49895092845,2.66568279266 -6.67994880676,0.496963530779,2.67825984955 -6.69595384598,0.498964935541,2.69703936577 -6.68996858597,0.498973608017,2.71763038635 -6.60799455643,0.490996181965,2.71016860008 -6.65000295639,0.495996505022,2.74976873398 -6.66901540756,0.499001204967,2.78134822845 -6.64103364944,0.497014045715,2.79391908646 -6.65504646301,0.500019550323,2.82350039482 -6.59106254578,0.493034869432,2.80927228928 -6.67506599426,0.503028035164,2.86787033081 -6.62408733368,0.499044984579,2.87044000626 -6.6311006546,0.500051617622,2.89702630043 -6.58312273026,0.496068447828,2.90157747269 -6.56214046478,0.495080143213,2.91615748405 -6.57214593887,0.496082216501,2.93195748329 -6.56016302109,0.496092677116,2.95151972771 -6.54218053818,0.495103806257,2.96710371971 -6.53119707108,0.495114028454,2.98667287827 -6.53721094131,0.496121019125,3.01325511932 -6.50823068619,0.494134545326,3.02481889725 -6.48824834824,0.493146121502,3.03940105438 -6.45826005936,0.490155756474,3.03817653656 -6.42228078842,0.48717045784,3.04574561119 -6.53427934647,0.500158429146,3.12135314941 -6.41631221771,0.489187985659,3.09090209007 -6.41632699966,0.490196079016,3.11448907852 -6.39934492111,0.489207565784,3.13105559349 -6.39036178589,0.489217400551,3.15063691139 -6.38936901093,0.489221781492,3.16242241859 -6.37738704681,0.489232301712,3.18099594116 -6.37040328979,0.489241808653,3.201577425 -6.33142518997,0.486257433891,3.20713973045 -6.35443639755,0.49026158452,3.24272418022 -6.3424539566,0.489272177219,3.26129698753 -6.32747173309,0.489283204079,3.27787733078 -6.3214802742,0.489288389683,3.28667211533 -6.32849502563,0.491295695305,3.31524276733 -6.30151462555,0.48930901289,3.32581758499 -6.30852937698,0.491316318512,3.35439062119 -6.29554700851,0.490327060223,3.37197113037 -6.3115606308,0.493332743645,3.40554475784 -6.30656909943,0.493337899446,3.41533255577 -6.31158447266,0.495345503092,3.44291090965 -6.2926030159,0.494357466698,3.45748877525 -6.30361652374,0.496363788843,3.48807454109 -6.28763532639,0.496375352144,3.50464677811 -6.27765226364,0.496385723352,3.52422428131 -6.27666854858,0.497394442558,3.54880285263 -6.28167581558,0.49839797616,3.56458616257 -6.27969169617,0.499406695366,3.58817434311 -6.27970790863,0.500415325165,3.61374950409 -6.25872755051,0.499427855015,3.62732386589 -6.26674175262,0.501434803009,3.65691161156 -6.262758255,0.502444267273,3.68048477173 -6.25777482986,0.503453791142,3.70306563377 -6.26778125763,0.504456222057,3.72185492516 -6.24980068207,0.504468381405,3.73742556572 -6.24681758881,0.50547772646,3.76199579239 -6.24283361435,0.50548684597,3.78458929062 -6.23285198212,0.506497561932,3.80515742302 -6.21787023544,0.505508959293,3.82174062729 -6.23787498474,0.508509814739,3.84752321243 -6.23289203644,0.509519219398,3.8701107502 -6.22091054916,0.509530425072,3.88967752457 -6.22492599487,0.51153832674,3.91826081276 -6.20094680786,0.509551644325,3.9298350811 -6.21795940399,0.51355701685,3.96642541885 -6.21397686005,0.514566659927,3.9909965992 -6.22298288345,0.515569269657,4.00979137421 -6.21799993515,0.516579031944,4.03337049484 -6.20701885223,0.516590178013,4.05393648148 -6.20303583145,0.517599761486,4.07851171494 -6.20105266571,0.518608927727,4.10409355164 -6.20006942749,0.520617961884,4.13067150116 -6.19907712936,0.520622491837,4.1434636116 -6.19609451294,0.522632002831,4.16903829575 -6.18211364746,0.521643400192,4.18662261963 -6.1791305542,0.523652911186,4.21219968796 -6.17114877701,0.523663461208,4.23477125168 -6.19616031647,0.528667509556,4.27935552597 -6.17218160629,0.526681065559,4.29092884064 -6.17319011688,0.527685403824,4.30571651459 -6.18020486832,0.53069293499,4.33830022812 -6.18022108078,0.531701683998,4.36588716507 -6.16324090958,0.531713962555,4.3824596405 -6.16325807571,0.532723009586,4.41103458405 -6.16127490997,0.534732222557,4.43761920929 -6.15029382706,0.534743607044,4.45918321609 -6.15830039978,0.536746561527,4.47897768021 -6.17031526566,0.539753317833,4.51655578613 -6.16133403778,0.540764093399,4.53913068771 -6.16235017776,0.541772902012,4.56871175766 -6.15036869049,0.542784035206,4.58829927444 -6.13138961792,0.541796922684,4.60386896133 -6.11341047287,0.541809678078,4.62043428421 -6.12141704559,0.542812407017,4.64023685455 -6.14842844009,0.547816157341,4.6898226738 -6.14344644547,0.549826443195,4.71639108658 -6.12546730042,0.548839151859,4.73296070099 -6.11648607254,0.54984998703,4.75554323196 -6.11850214005,0.551858723164,4.78712177277 -6.11151218414,0.551864683628,4.79690742493 -6.13752412796,0.55686879158,4.84748840332 -6.15453672409,0.560874283314,4.89008712769 -6.10856342316,0.556892454624,4.88465499878 -6.11058044434,0.558901429176,4.91722917557 -6.12359428406,0.56290781498,4.95781803131 -6.11561346054,0.563918948174,4.9833817482 -6.13461828232,0.566919744015,5.01417541504 -6.15163087845,0.570925474167,5.05876398087 -6.1096572876,0.567943096161,5.05633020401 -6.11567354202,0.570951163769,5.09290838242 -6.11569023132,0.571960330009,5.12448835373 -6.13870239258,0.576964914799,5.17507648468 -6.11172533035,0.575979530811,5.18464946747 -6.12373113632,0.578981757164,5.21044540405 -6.12174892426,0.579991400242,5.24102449417 -6.11876678467,0.582001507282,5.27159452438 -6.13278102875,0.58600795269,5.31617593765 -6.11980104446,0.586019814014,5.33775377274 -6.12081813812,0.58902913332,5.37232351303 -6.14282989502,0.5940335989,5.42292881012 -6.14483833313,0.595037937164,5.4417142868 -6.14985513687,0.598046481609,5.48028659821 -6.11987876892,0.596061885357,5.48785543442 -6.133893013,0.600068509579,5.53443336487 -6.13690948486,0.603076934814,5.57002735138 -6.15592336655,0.608082830906,5.62259626389 -6.11094141006,0.603096306324,5.59838628769 -6.1329536438,0.60810136795,5.65296792984 -6.22894954681,0.623091518879,5.77556657791 -6.1529841423,0.615116178989,5.74112939835 -6.10101366043,0.611136138439,5.72869253159 -6.06503915787,0.608152449131,5.72927618027 -6.14502954483,0.620141267776,5.82207679749 -6.13205051422,0.621153593063,5.84664106369 -6.14306545258,0.625160634518,5.89223098755 -6.17007637024,0.631164610386,5.95381879807 -6.13610172272,0.629180848598,5.95739507675 -6.14411783218,0.633189022541,6.00296115875 -6.12014102936,0.632203280926,6.0165348053 -6.14614343643,0.637202858925,6.06032943726 -6.2161450386,0.649198234081,6.16592502594 -6.12718343735,0.639225780964,6.11648082733 -6.13819789886,0.643232882023,6.16407155991 -6.15621137619,0.64823871851,6.21965646744 -6.11723852158,0.64625620842,6.21922159195 -6.11325740814,0.648266673088,6.25379562378 -6.10326862335,0.648273408413,6.26258563995 -6.10528564453,0.651282548904,6.30316448212 -6.11230134964,0.654290676117,6.34874820709 -6.10932016373,0.657300770283,6.38433122635 -6.08334445953,0.656315982342,6.39789056778 -6.09435892105,0.660322964191,6.44748497009 -6.10737371445,0.665330052376,6.50106525421 -6.46229696274,0.717263281345,6.89691638947 -6.10440158844,0.669345140457,6.55842876434 -6.24938440323,0.693325519562,6.75403547287 -6.07844352722,0.671369731426,6.61158227921 -6.09745693207,0.677375555038,6.67316293716 -6.08947753906,0.679387152195,6.70672941208 -6.08448696136,0.679392874241,6.72152280807 -6.1324930191,0.689392626286,6.81511878967 -6.08752202988,0.686411499977,6.80768680573 -6.09053945541,0.689420580864,6.85326576233 -6.07156229019,0.690434217453,6.87483739853 -6.05958271027,0.691446244717,6.90341949463 -6.05260276794,0.69345754385,6.93899106979 -6.15958547592,0.711440742016,7.08279705048 -8.85193157196,1.11690306664,10.2149295807 -8.28608989716,1.03602778912,9.62538719177 -8.98193264008,1.14589571953,10.4941120148 -8.98494720459,1.15090477467,10.5636892319 -8.19616317749,1.0360751152,9.70209789276 -8.15919017792,1.03509247303,9.71966457367 -8.12920475006,1.03310322762,9.7134552002 -8.07323646545,1.02912437916,9.70801925659 -8.01626777649,1.02514576912,9.7005853653 -7.97229719162,1.02316451073,9.70915031433 -7.95831823349,1.02617716789,9.75372314453 -7.86735868454,1.01620554924,9.7042798996 -7.86236810684,1.01821136475,9.72807216644 -7.82539510727,1.01722884178,9.74463748932 -7.93738365173,1.03921580315,9.94623565674 -7.83842611313,1.02824568748,9.88479804993 -3.40657424927,0.333154886961,4.35370159149 -3.40659356117,0.335164576769,4.38029241562 -3.38061976433,0.333179861307,4.37486743927 -7.33665275574,0.975402414799,9.58637237549 -7.34266901016,0.981411159039,9.65595054626 -7.23571491241,0.96844291687,9.57750606537 -7.24472999573,0.97445076704,9.65009403229 -7.1597700119,0.965478122234,9.59965229034 -7.11679077148,0.961491882801,9.57343196869 -7.07082033157,0.958511173725,9.57300567627 -7.01585292816,0.954532504082,9.56156635284 -6.96988248825,0.951551735401,9.56014251709 -6.92591285706,0.949570775032,9.562707901 -6.87894296646,0.946590185165,9.55928516388 -6.82896566391,0.940605580807,9.52205848694 -6.81398773193,0.943618655205,9.56363296509 -6.74302434921,0.936643064022,9.52620220184 -6.70205354691,0.934661448002,9.53077507019 -6.65708398819,0.931680738926,9.5303401947 -6.6221113205,0.930697917938,9.54291439056 -6.55414772034,0.924721717834,9.50748443604 -6.54715919495,0.925728261471,9.52927017212 -6.48219442368,0.919751524925,9.49783802032 -6.46021938324,0.920766234398,9.52941036224 -6.4122505188,0.91778588295,9.52098846436 -6.38927459717,0.918800652027,9.55056285858 -6.32930994034,0.913823127747,9.52612400055 -6.31132364273,0.912831842899,9.53091144562 -6.239361763,0.905856668949,9.48647785187 -6.20439004898,0.904874026775,9.498046875 -6.16441917419,0.902892112732,9.49962902069 -6.163438797,0.907902657986,9.56419849396 -6.16445684433,0.9139123559,9.62978553772 -6.04250812531,0.896947324276,9.50434684753 -6.04151773453,0.89895260334,9.53513717651 -5.97655439377,0.892976164818,9.49870109558 -5.95757818222,0.894990086555,9.53328132629 -5.93060493469,0.896005868912,9.55685043335 -5.89263391495,0.894023776054,9.56142616272 -5.88665533066,0.898035287857,9.61899852753 -5.88467407227,0.904045820236,9.6825799942 -5.91767454147,0.913044154644,9.77037525177 -5.88670253754,0.913060724735,9.7879486084 -5.87972354889,0.917072415352,9.8455247879 -5.89473819733,0.926079571247,9.94010734558 -5.87176322937,0.928094446659,9.97168254852 -5.91876888275,0.9430950284,10.1222715378 -5.90179300308,0.946108818054,10.1658468246 -5.91179990768,0.951111972332,10.2196369171 -5.91281890869,0.957122027874,10.2952136993 -5.91183805466,0.963132679462,10.3687858582 -5.91385698318,0.970142543316,10.4473657608 -5.88688325882,0.971158087254,10.4739494324 -5.91189527512,0.983163535595,10.5965242386 -5.9209022522,0.988166689873,10.6503200531 -5.9619102478,1.00316882133,10.8029031754 -5.93193769455,1.00418519974,10.8284749985 -5.91796064377,1.00819838047,10.8830528259 -5.9029841423,1.01221179962,10.936627388 -5.90900182724,1.02022087574,11.029209137 -5.91501951218,1.02922999859,11.1237850189 -5.91102933884,1.0312359333,11.156580925 -5.89805269241,1.03624904156,11.2171545029 -5.91606712341,1.04725575447,11.337729454 -5.89309263229,1.05027079582,11.3793077469 -5.88311481476,1.05528318882,11.4468870163 -5.88113451004,1.06329393387,11.5304679871 -5.89314079285,1.06929683685,11.5992546082 -5.91715335846,1.08230245113,11.7368354797 -5.92717027664,1.09331059456,11.8474187851 -5.93918561935,1.10431873798,11.9649953842 -5.91021347046,1.10533499718,11.9995737076 -5.88224077225,1.10735106468,12.0371484756 -5.88725852966,1.11736047268,12.1427297592 -5.88726854324,1.12136566639,12.1915168762 -5.97526264191,1.1503585577,12.4731035233 -3.64994239807,0.627837121487,7.68346357346 -3.6029753685,0.622856557369,7.64405250549 -3.55800819397,0.617875874043,7.60963106155 -3.53003621101,0.616891801357,7.61120939255 -3.48906850815,0.612910568714,7.58577775955 -3.46808433533,0.610919833183,7.5705704689 -3.43711352348,0.608936429024,7.56514644623 -3.41114068031,0.607951760292,7.56873512268 -3.38416934013,0.607967793941,7.57330226898 -3.3481991291,0.603985011578,7.55389213562 -3.32122731209,0.604000747204,7.55646896362 -3.29925394058,0.604015469551,7.57004833221 -3.28326845169,0.603023767471,7.56484174728 -3.24529981613,0.599041700363,7.54141950607 -3.22832560539,0.601055681705,7.56798934937 -3.19735431671,0.599072098732,7.55957317352 -3.16038513184,0.596089601517,7.53615856171 -3.14540982246,0.598103106022,7.5667347908 -3.12742495537,0.596111655235,7.5555305481 -3.09245610237,0.593129277229,7.53909730911 -3.07048249245,0.594143927097,7.55168008804 -3.04251074791,0.592159569263,7.54827022552 -3.01453900337,0.591175436974,7.5458521843 -2.99756503105,0.593189477921,7.57342004776 -2.96459460258,0.591206133366,7.55700922012 -2.95260906219,0.591213941574,7.56278800964 -2.92863631248,0.591229021549,7.57036924362 -2.89166736603,0.587246656418,7.54395103455 -2.87069416046,0.588261187077,7.55953025818 -2.84272217751,0.586276948452,7.55511760712 -2.82074928284,0.587291777134,7.56869316101 -2.79277801514,0.585307538509,7.56427955627 -2.77979183197,0.585315287113,7.56507062912 -2.76081824303,0.586329460144,7.58664751053 -2.73584651947,0.586344897747,7.59222221375 -2.7128739357,0.586359858513,7.60280036926 -2.70489645004,0.591371655464,7.65438747406 -2.68292427063,0.592386603355,7.66995620728 -2.69393110275,0.599389612675,7.73974847794 -2.69695043564,0.607399106026,7.82434177399 -2.6799762249,0.609412908554,7.85491800308 -2.65500402451,0.609428167343,7.8614988327 -2.55805301666,0.586457550526,7.6520819664 -2.44720005989,0.593536615372,7.76076745987 -2.43122506142,0.596549928188,7.79335403442 -2.41625070572,0.599563479424,7.83292579651 -2.4002764225,0.602577030659,7.86850404739 -2.36236023903,0.619620740414,8.05704021454 -2.3513841629,0.624633073807,8.11162853241 -2.54535889626,0.707611262798,8.94198513031 -2.51538825035,0.707627475262,8.94156837463 -2.46642374992,0.69964748621,8.87414646149 -2.31648826599,0.653686761856,8.43273830414 -2.42647767067,0.705676317215,8.94830036163 -2.36351680756,0.692698776722,8.82288742065 -2.29455828667,0.67672264576,8.67446327209 -2.28557157516,0.678729593754,8.69525432587 -2.27659440041,0.684741437435,8.76884746552 -2.25962114334,0.689755499363,8.82041358948 -2.25164413452,0.6977673769,8.90399837494 -2.2356698513,0.702780902386,8.95857810974 -2.2246940136,0.708793282509,9.03316497803 -2.21672797203,0.723810493946,9.18653392792 -2.20675206184,0.731822967529,9.27410888672 -2.19477653503,0.739835739136,9.3536901474 -2.18080186844,0.74584877491,9.4262714386 -2.17382478714,0.755860626698,9.53185176849 -2.16284942627,0.764873325825,9.62542438507 -2.14987444878,0.772886276245,9.71000385284 -2.16388034821,0.785888671875,9.84479904175 -2.1539041996,0.795900940895,9.94638442993 -2.14292883873,0.804913699627,10.0509567261 -2.13997149467,0.83493500948,10.3531236649 -2.14399170876,0.852944850922,10.5426950455 -2.14400243759,0.860950112343,10.6284856796 -2.13702583313,0.874962031841,10.7710590363 -2.64189600945,1.15287649632,13.5606241226 -2.75988173485,1.23786461353,14.4132003784 -2.55396461487,1.15191435814,13.5617818832 -2.54998683929,1.17292571068,13.7793617249 -2.67397069931,1.26591277122,14.7149372101 -2.64498972893,1.26192343235,14.6837301254 -2.61202073097,1.26894032955,14.7663097382 -2.5990459919,1.2889534235,14.9698858261 -2.56007838249,1.2929712534,15.0204725266 -2.51911211014,1.29698967934,15.0700454712 -2.48014497757,1.30200755596,15.1266269684 -2.39118218422,1.26202976704,14.7254190445 -2.40819811821,1.30103695393,15.1290035248 -2.37522935867,1.3110537529,15.2325792313 -2.31426882744,1.30207574368,15.1531600952 -2.29529547691,1.32208991051,15.3527393341 -2.26732516289,1.33510565758,15.4973211288 -2.2173614502,1.33412563801,15.4919042587 -2.17738389969,1.32313835621,15.3846940994 -2.14241576195,1.3331553936,15.4862766266 -2.10044980049,1.33817386627,15.5458526611 -2.3713889122,1.58013367653,17.9994258881 -1.99152481556,1.32921516895,15.4650192261 -1.94855904579,1.3332337141,15.5146017075 -2.20350337029,1.58219671249,18.0351657867 -2.17952108383,1.58520638943,18.0699615479 -2.12455916405,1.58722746372,18.096534729 -2.07159638405,1.59024775028,18.1361179352 -2.01463508606,1.59026885033,18.1436958313 -1.95967280865,1.5922896862,18.1632823944 -1.90171194077,1.59131097794,18.1658592224 -1.84375071526,1.59033215046,18.1604404449 -1.81476986408,1.58934271336,18.1512374878 -1.75580894947,1.58736419678,18.1348171234 -1.70084702969,1.58938479424,18.1623973846 -1.64488530159,1.59040546417,18.1789798737 -1.5899232626,1.59342610836,18.2075614929 -1.53496146202,1.59644687176,18.2451381683 -1.51497805119,1.6064555645,18.3449344635 -1.46801352501,1.61947464943,18.4855175018 -1.41904985905,1.63149416447,18.6130962372 -1.36108887196,1.63251531124,18.6266765594 -1.29912912846,1.62853705883,18.5832576752 -1.23616969585,1.62155902386,18.5168399811 -1.17920792103,1.62157964706,18.5244293213 -1.1482282877,1.61959052086,18.5022163391 -1.0902671814,1.61961150169,18.5077991486 -1.03230619431,1.61963236332,18.510383606 -0.973345577717,1.61865353584,18.5029659271 -0.914384961128,1.61667454243,18.4895477295 -0.857423305511,1.61769509315,18.4961357117 -0.827443301678,1.61670577526,18.4849262238 -0.769482135773,1.61572659016,18.4795131683 -0.711521327496,1.6167473793,18.4930934906 -0.653560400009,1.61776816845,18.5026741028 -0.595599293709,1.61678874493,18.494260788 -0.536638855934,1.61580979824,18.4878406525 -0.478677809238,1.61583054066,18.4854259491 -0.449697196484,1.61484074593,18.4732208252 -0.390736728907,1.61186158657,18.4528026581 -0.332775741816,1.61188220978,18.4453868866 -0.27581423521,1.61390244961,18.4699745178 -0.216853827238,1.61092329025,18.4405536652 -0.159892320633,1.6139434576,18.4741439819 -0.101931355894,1.6139639616,18.4727287292 -0.0729508846998,1.61497426033,18.4805221558 -0.0149899022654,1.61299479008,18.4641075134 --0.0119916656986,1.61800432205,17.4179077148 --0.06595415622,1.61702394485,17.4134998322 --0.120916008949,1.62004375458,17.4350852966 --0.175877779722,1.61806368828,17.4206676483 --0.230839625001,1.61908340454,17.4252510071 --0.284802049398,1.61810302734,17.4138412476 --0.312782675028,1.61911296844,17.4236297607 --0.366745144129,1.61813247204,17.4142189026 --0.421706944704,1.61815214157,17.4138031006 --0.476668715477,1.61817193031,17.4063873291 --0.531630814075,1.62019145489,17.4299755096 --0.586592555046,1.61921107769,17.4185581207 --0.613573849201,1.61922073364,17.4193553925 --0.668535590172,1.61924040318,17.4109382629 --0.723497450352,1.6192599535,17.4135246277 --0.777459800243,1.61827921867,17.4011116028 --0.832421720028,1.61929869652,17.4026985168 --0.886384248734,1.61931788921,17.3972892761 --0.941346108913,1.61933732033,17.3978748322 --0.969326734543,1.6193472147,17.3976650238 --1.02428865433,1.62036657333,17.3982505798 --1.07925093174,1.62138581276,17.4088420868 --1.13421273232,1.62140524387,17.4044265747 --1.18317651749,1.61242341995,17.3170146942 --1.2441368103,1.62344360352,17.4106044769 --1.29909861088,1.62246286869,17.4021892548 --1.32608008385,1.62347233295,17.4039859772 --1.38104176521,1.62249147892,17.3965702057 --1.43700385094,1.6255106926,17.4161643982 --1.49296522141,1.62653017044,17.4167461395 --1.5489269495,1.62754940987,17.4253349304 --1.60488891602,1.6295684576,17.4399261475 --1.65985095501,1.62958753109,17.4325122833 --1.68883180618,1.63159716129,17.4533119202 --1.74479353428,1.63361632824,17.4598999023 --1.80175459385,1.63463556767,17.4654827118 --1.85771667957,1.63565456867,17.4750766754 --1.91467821598,1.63867378235,17.4886665344 --1.97063982487,1.63869285583,17.4862499237 --1.99862086773,1.6397023201,17.4910488129 --2.05558252335,1.64172136784,17.5036373138 --2.11354374886,1.64374053478,17.5202274323 --2.17050528526,1.64575958252,17.5308189392 --2.22846651077,1.6487787962,17.5454082489 --2.28642773628,1.64979803562,17.5559940338 --2.34338951111,1.65181684494,17.5655860901 --2.37336993217,1.65382647514,17.5793819427 --2.43133091927,1.65584552288,17.5869674683 --2.48929214478,1.65786457062,17.5985584259 --2.54825353622,1.66088366508,17.6181507111 --2.60421538353,1.66090226173,17.6117401123 --2.66217708588,1.66292095184,17.624332428 --2.72013831139,1.66493988037,17.6329250336 --2.75111842155,1.66694974899,17.6467170715 --2.80808019638,1.66796827316,17.6513137817 --2.8700401783,1.67198777199,17.676897049 --2.92500281334,1.6720058918,17.6674919128 --2.98296427727,1.6740244627,17.672082901 --3.0439248085,1.67704367638,17.6916732788 --3.10188674927,1.67906212807,17.6992683411 --3.1318666935,1.67907178402,17.7010574341 --3.19082832336,1.68209040165,17.7126522064 --3.24878978729,1.68310880661,17.7162456512 --3.30475187302,1.68312692642,17.7068386078 --3.36771178246,1.68714618683,17.731426239 --3.42367434502,1.68816423416,17.7240219116 --3.45565414429,1.69017386436,17.7398166656 --3.51461529732,1.69119238853,17.7424049377 --3.57457637787,1.69421088696,17.7519989014 --3.63353800774,1.69522929192,17.7565937042 --3.69449901581,1.69824790955,17.7711868286 --3.75446009636,1.70026636124,17.7767772675 --3.81342148781,1.7012847662,17.7783679962 --3.8454015255,1.7042940855,17.7911663055 --3.90636253357,1.7063126564,17.8027610779 --3.96632385254,1.70833098888,17.8073539734 --4.02328634262,1.70934855938,17.8019504547 --4.06425285339,1.70136392117,17.720539093 --4.13621091843,1.70938384533,17.7791347504 --4.20516967773,1.71540343761,17.819726944 --4.24014854431,1.71841323376,17.8445281982 --4.30410909653,1.72243189812,17.8631210327 --4.36307048798,1.72344982624,17.8587112427 --4.42303228378,1.72546768188,17.8623085022 --4.48199367523,1.72648561001,17.8568992615 --4.54795360565,1.73050427437,17.8814945221 --4.57993364334,1.73251354694,17.8892936707 --4.63789558411,1.7325309515,17.8818893433 --4.69885730743,1.73454892635,17.8864860535 --4.7588186264,1.73656666279,17.8820743561 --4.82077980042,1.73858463764,17.888671875 --4.88474035263,1.74160277843,17.9032688141 --4.94270277023,1.74262022972,17.8908596039 --4.97568273544,1.74462938309,17.9006576538 --5.03564453125,1.74564671516,17.8982543945 --5.09660577774,1.74766433239,17.9008541107 --5.15856742859,1.74968206882,17.9014434814 --5.22452735901,1.75370025635,17.9190425873 --5.30548286438,1.76272070408,17.9876422882 --5.36744403839,1.7647383213,17.9862346649 --5.41142082214,1.7707490921,18.031036377 --5.43039512634,1.75676000118,17.8876266479 --5.43737268448,1.73876917362,17.7082157135 --5.48133993149,1.73478388786,17.6528091431 --5.53130483627,1.7327991724,17.6194095612 --5.57827091217,1.729814291,17.5750045776 --5.62923574448,1.7288299799,17.5425987244 --5.66021633148,1.7298386097,17.5423946381 --5.71118164062,1.72885406017,17.5129947662 --5.76914405823,1.72887063026,17.5015850067 --5.82610750198,1.72988688946,17.4911899567 --5.86407613754,1.72390043736,17.4197788239 --5.92903757095,1.72791779041,17.4323806763 --5.96001815796,1.728926301,17.43217659 --6.01498174667,1.72894215584,17.412771225 --6.07594394684,1.7309589386,17.4103679657 --6.12291049957,1.72897350788,17.369966507 --6.18687200546,1.73199045658,17.3765640259 --6.24583482742,1.73300671577,17.3681621552 --6.29580020905,1.73102164268,17.3347568512 --6.33078050613,1.73403048515,17.3475608826 --6.39074277878,1.73504686356,17.3401546478 --6.44470739365,1.73506212234,17.3197555542 --6.49867153168,1.73507750034,17.2963504791 --6.56463289261,1.73909425735,17.3079547882 --6.62759494781,1.7411108017,17.3065471649 --6.69055747986,1.74412715435,17.3091506958 --6.6985449791,1.73813199997,17.2489490509 --6.77950191498,1.74615097046,17.2955474854 --6.83946466446,1.74716687202,17.2871456146 --6.89842796326,1.74918246269,17.2777462006 --6.95539236069,1.74919784069,17.2613449097 --7.01535511017,1.75121355057,17.2519397736 --7.04333734512,1.75122094154,17.2447452545 --7.10929870605,1.75423753262,17.2493419647 --7.16426372528,1.75425231457,17.2279396057 --7.22122764587,1.75526738167,17.2125415802 --7.28319072723,1.75728309155,17.2081432343 --7.34515333176,1.75929868221,17.2027416229 --7.40211772919,1.76031374931,17.184337616 --7.43209934235,1.76132130623,17.1801395416 --7.47606801987,1.75833427906,17.1347427368 --7.53803110123,1.76034975052,17.1283397675 --7.60799121857,1.76436626911,17.1389389038 --7.6509604454,1.76237905025,17.0905399323 --7.72891902924,1.76839649677,17.1211452484 --7.7908821106,1.77041172981,17.1137447357 --7.82686233521,1.7724199295,17.121547699 --7.88982486725,1.77443528175,17.1141433716 --7.93679285049,1.77344834805,17.0747451782 --8.00175571442,1.77646374702,17.0743503571 --8.06371879578,1.77747857571,17.0649471283 --8.12568187714,1.77949345112,17.0575523376 --8.14666748047,1.77849960327,17.0323524475 --8.21462917328,1.78251516819,17.0359535217 --8.26259613037,1.78052806854,16.9975528717 --8.32955932617,1.78354334831,16.9991569519 --8.35853290558,1.77855360508,16.9227542877 --8.44349002838,1.78557109833,16.9603614807 --8.49845504761,1.7855848074,16.9349594116 --8.54043388367,1.78959333897,16.9517593384 --8.59739971161,1.79060709476,16.9333667755 --8.65136528015,1.79062044621,16.9059658051 --8.69933414459,1.78963279724,16.8695716858 --8.77629375458,1.79464900494,16.8871746063 --8.82326316833,1.79366123676,16.8467750549 --8.88522624969,1.7956751585,16.8363800049 --8.91420936584,1.79568195343,16.8261795044 --8.97817325592,1.79869627953,16.8177814484 --9.02414226532,1.79670810699,16.7773857117 --9.09110546112,1.7997225523,16.7749919891 --6.48681592941,1.21840250492,11.8461532593 --9.21103572845,1.80374956131,16.7421951294 --9.23801994324,1.8037558794,16.7279949188 --9.28998565674,1.80276823044,16.6965942383 --9.33895587921,1.80278015137,16.6622047424 --6.49272918701,1.18343532085,11.4633140564 --6.57768630981,1.19345295429,11.5269117355 --6.55167531967,1.18045675755,11.3975048065 --9.56282138824,1.8058308363,16.5656108856 --9.59180450439,1.8058372736,16.5554141998 --9.65277004242,1.80785024166,16.5400180817 --9.69573974609,1.80586111546,16.4936218262 --9.73271274567,1.80287110806,16.4372234344 --9.7346944809,1.79287695885,16.3228206635 --9.70168590546,1.77587854862,16.1494064331 --9.76964950562,1.77889227867,16.148015976 --9.78763580322,1.77789711952,16.1198158264 --9.82660770416,1.77490723133,16.0684146881 --9.88457393646,1.77691960335,16.0490207672 --9.93354320526,1.77693080902,16.015625 --9.98951148987,1.77794265747,15.9922275543 --10.0374803543,1.7769536972,15.9568328857 --10.0664644241,1.77795958519,15.9466333389 --10.1174325943,1.77797079086,15.9162406921 --10.1753997803,1.77898287773,15.8948411942 --10.2403650284,1.7819955349,15.8864507675 --10.3003320694,1.78400754929,15.8690567017 --10.3612985611,1.78601944447,15.8546686172 --7.43907117844,1.21869325638,11.2697086334 --10.4422512054,1.78803634644,15.8130712509 --10.5052175522,1.79004848003,15.7996788025 --10.5581855774,1.79105937481,15.7712850571 --10.6251516342,1.79407179356,15.7638950348 --10.6761207581,1.79408240318,15.7314977646 --7.49195766449,1.19273459911,10.9284791946 --7.70988130569,1.22676491737,11.1731157303 --7.7368645668,1.22777116299,11.1739149094 --10.8810071945,1.80012190342,15.6571187973 --10.9079837799,1.7961294651,15.5897188187 --8.23367881775,1.29984366894,11.6587934494 --8.06370639801,1.26183116436,11.3393554688 --8.10067939758,1.26184117794,11.3149557114 --11.1278686523,1.80516946316,15.5363502502 --11.1918354034,1.80718076229,15.5219593048 --11.2368068695,1.80719006062,15.4805631638 --7.98764705658,1.21985030174,10.8955059052 --11.3307495117,1.80620872974,15.4047775269 --8.08558654785,1.22487258911,10.8847160339 --9.20527553558,1.41599535942,12.3265428543 --8.22152423859,1.23989570141,10.9591312408 --11.4956502914,1.80524098873,15.2713975906 --11.5426225662,1.80525016785,15.2330026627 --11.588593483,1.80525898933,15.1926050186 --8.86028862,1.32598412037,11.5116453171 --8.84527587891,1.31698822975,11.415230751 --8.77027893066,1.29898619652,11.243812561 --8.90123558044,1.31800222397,11.3756361008 --8.92521286011,1.31600987911,11.33223629 --8.97418308258,1.31802034378,11.3208427429 --8.99815940857,1.31602799892,11.2764377594 --8.96313476562,1.29803526402,11.0866212845 --8.99211883545,1.3000408411,11.0864238739 --12.0073299408,1.79534041882,14.7496643066 --9.17303943634,1.3190690279,11.164648056 --9.17102336884,1.31307399273,11.0902442932 --9.17400550842,1.3070795536,11.0218381882 --9.22997570038,1.31108999252,11.0184469223 --9.26594924927,1.31109857559,10.9900474548 --9.30093193054,1.31410443783,10.9968557358 --9.40788841248,1.3251196146,11.0524711609 --9.32189464569,1.30611646175,10.8800487518 --9.47283840179,1.32513570786,10.985669136 --9.38784503937,1.3051327467,10.8172531128 --12.2021217346,1.75039672852,14.007475853 --9.60275745392,1.32916235924,10.925488472 --9.69072723389,1.34017276764,10.9913063049 --5.82365465164,0.718835473061,6.46954011917 --5.65067911148,0.688827097416,6.23207426071 --5.64666128159,0.68483376503,6.18665790558 --5.65364170074,0.682841181755,6.15525960922 --5.62963867188,0.67784267664,6.10804128647 --5.71859836578,0.687857270241,6.16665887833 --5.73957490921,0.688866019249,6.14925003052 --5.77654790878,0.690876066685,6.14985322952 --5.79552555084,0.69088435173,6.13145780563 --5.80350542068,0.68889182806,6.10004663467 --5.81548500061,0.687899649143,6.07364273071 --5.63134860992,0.632952749729,5.50748682022 --5.62933111191,0.629959285259,5.47007894516 --5.6073179245,0.623964428902,5.41266012192 --5.62129735947,0.623972117901,5.39226531982 --5.63328552246,0.623976528645,5.38605880737 --5.62726926804,0.620982766151,5.34565114975 --5.6382484436,0.619990408421,5.32124090195 --5.67022323608,0.621999680996,5.31683301926 --5.66120767593,0.61800557375,5.27442932129 --5.72716569901,0.624020576477,5.28482627869 --5.74814319611,0.625028729439,5.27042531967 --5.75212430954,0.623035669327,5.2400188446 --5.69012069702,0.612037837505,5.14859342575 --5.75308895111,0.618048906326,5.17320346832 --5.79006290436,0.621057987213,5.17381048203 --5.80404186249,0.621065616608,5.15240001678 --5.82802772522,0.623070597649,5.15720081329 --5.85700321198,0.625079095364,5.14980173111 --5.88298034668,0.626087248325,5.14041185379 --5.91595554352,0.629095971584,5.13601016998 --5.92993402481,0.628103613853,5.11359071732 --5.95991039276,0.63011187315,5.10719966888 --8.00615787506,0.863341569901,6.1172952652 --6.67442369461,0.684273838997,5.04045963287 --6.68439626694,0.682283163071,4.99684476852 --6.71937274933,0.684290587902,4.99045467377 --6.76334667206,0.688298642635,4.9900598526 --6.79332494736,0.690305709839,4.97967004776 --5.51257276535,0.521246612072,3.9848177433 --5.51655435562,0.520253539085,3.9593937397 --5.4985499382,0.517255663872,3.93319439888 --5.52752590179,0.51926368475,3.92678451538 --7.59485292435,0.75344479084,4.87797451019 --7.64782762527,0.758451640606,4.87858963013 --7.65881729126,0.758454442024,4.86838960648 --11.8099880219,1.27061772346,7.48592042923 --11.8099756241,1.26761972904,7.43352127075 --11.8069639206,1.2646214962,7.37811136246 --11.8029537201,1.26162326336,7.3237118721 --11.8079404831,1.25862526894,7.27430772781 --11.7899370193,1.25562560558,7.23710203171 --11.7869262695,1.25162732601,7.18370103836 --11.7879142761,1.24962925911,7.13229513168 --11.7869024277,1.24663102627,7.08089733124 --11.7838916779,1.24363267422,7.02749109268 --11.7848796844,1.24063444138,6.97608089447 --11.7828683853,1.23763608932,6.92468309402 --11.7718648911,1.23463666439,6.89247608185 --11.7748527527,1.23263847828,6.84407711029 --11.7648429871,1.22863996029,6.78766965866 --11.766831398,1.22664165497,6.73927164078 --11.7608213425,1.22364318371,6.68586730957 --11.7638082504,1.22064495087,6.63746213913 --11.7607984543,1.21764647961,6.58605766296 --11.7467937469,1.21564686298,6.55284738541 --11.7417840958,1.21164834499,6.50144863129 --11.7457723618,1.20965003967,6.45404195786 --11.731762886,1.20565128326,6.39763689041 --11.9307165146,1.22765719891,6.45929956436 --11.7857313156,1.20765554905,6.3298459053 --11.8547086716,1.21365845203,6.31946992874 --11.9336881638,1.22166073322,6.33728790283 --12.0056657791,1.22766339779,6.32791471481 --12.0756425858,1.23366606236,6.31653642654 --12.1676158905,1.24166893959,6.31616306305 --12.1736040115,1.24067008495,6.26976060867 --12.1585969925,1.23567080498,6.21335935593 --12.2525701523,1.24467349052,6.21298646927 --12.2665624619,1.24567401409,6.19579124451 --7.99526357651,0.741612195969,3.94687414169 --7.98525094986,0.738616168499,3.90946102142 --7.99623537064,0.738620340824,3.88305830956 --7.98922252655,0.736624240875,3.84764909744 --7.98920869827,0.734628260136,3.81624746323 --7.97620391846,0.732630074024,3.79404044151 --7.98418855667,0.73263412714,3.76663970947 --7.9731760025,0.72963809967,3.72922229767 --7.97516202927,0.728642106056,3.69881653786 --7.96414995193,0.725645959377,3.66240811348 --7.9631357193,0.724649965763,3.6299905777 --7.9621219635,0.722653865814,3.59858512878 --7.95411586761,0.720655798912,3.57937979698 --7.95110273361,0.719659745693,3.54697036743 --7.96108722687,0.7196636796,3.52056407928 --7.96307373047,0.717667520046,3.49116373062 --7.97805786133,0.718671321869,3.46776843071 --7.9970407486,0.719675302505,3.44536423683 --8.0320224762,0.721679210663,3.42996454239 --8.06401062012,0.725681006908,3.42978477478 --8.12498760223,0.730684816837,3.42539286613 --8.18696498871,0.736688375473,3.42201375961 --8.25994110107,0.743691980839,3.4226334095 --8.33191680908,0.750695347786,3.42225170135 --8.38989639282,0.755698502064,3.41688346863 --8.45487308502,0.761701703072,3.41249656677 --8.48886203766,0.765703201294,3.41131043434 --8.56483840942,0.772706151009,3.41092824936 --8.62181663513,0.777709066868,3.40254354477 --11.6273794174,1.11569416523,4.60828065872 --11.6273698807,1.11369490623,4.56588363647 --11.6253604889,1.11269557476,4.52147340775 --11.6233510971,1.11069631577,4.47807216644 --11.619345665,1.10869657993,4.45587682724 --11.6193361282,1.10769724846,4.41246604919 --11.6153278351,1.10569798946,4.36805868149 --11.614317894,1.10369861126,4.32565975189 --11.6093101501,1.10169923306,4.28125286102 --11.6013011932,1.09869980812,4.2358455658 --11.5972976685,1.09770011902,4.21364593506 --11.595287323,1.09670066833,4.17124557495 --11.5922794342,1.09470117092,4.12783765793 --11.5932693481,1.09270167351,4.08643579483 --11.5952596664,1.09170210361,4.04502916336 --11.5912513733,1.08970248699,4.0026307106 --11.5932416916,1.0887029171,3.96122288704 --11.582239151,1.08670330048,3.93702101707 --11.5762310028,1.08470380306,3.89361643791 --11.5782213211,1.08370411396,3.85321569443 --11.5772123337,1.08170437813,3.81181311607 --11.5762042999,1.08070480824,3.77040958405 --11.5721950531,1.07870519161,3.72800421715 --11.5651865005,1.07670545578,3.68459653854 --11.5601825714,1.07570576668,3.66239142418 --11.4281892776,1.05970919132,3.57793402672 --11.4251813889,1.0577095747,3.53652691841 --11.4191732407,1.05571007729,3.4951274395 --11.4211645126,1.05471014977,3.45572423935 --11.4211549759,1.05371034145,3.41531586647 --11.4251470566,1.05271053314,3.3769159317 --11.4051437378,1.04971110821,3.35070514679 --11.4091348648,1.04971122742,3.31230378151 --11.4121265411,1.04871118069,3.273904562 --11.4001188278,1.04571175575,3.23049378395 --11.4091091156,1.04571151733,3.19409751892 --11.4121007919,1.0447114706,3.15569663048 --11.3890953064,1.04171228409,3.10927939415 --11.3950901031,1.04171204567,3.09208679199 --11.3970813751,1.04071199894,3.05368638039 --11.3920736313,1.0387121439,3.01227164268 --11.3830661774,1.03671240807,2.97086572647 --11.3920574188,1.03671205044,2.934466362 --11.387049675,1.03571200371,2.89405918121 --11.3810415268,1.03371214867,2.85365319252 --11.3800382614,1.03271222115,2.83445572853 --11.3620319366,1.02971279621,2.79104495049 --11.3620233536,1.02871251106,2.75264286995 --11.4000120163,1.0317107439,2.72425937653 --11.3510093689,1.02571249008,2.67283034325 --11.3190040588,1.02171373367,2.62641239166 --11.3569927216,1.02471184731,2.59802961349 --11.3689870834,1.02571105957,2.58183288574 --11.3989772797,1.02770936489,2.55043792725 --11.4349660873,1.0307071209,2.52105355263 --11.4739561081,1.03370475769,2.49166464806 --11.5019454956,1.03570270538,2.45926856995 --11.5699329376,1.04269874096,2.43690013885 --11.4289369583,1.02670538425,2.3664355278 --11.416934967,1.02470576763,2.34523463249 --11.6599006653,1.04869127274,2.32152891159 --11.698890686,1.05268836021,2.29114294052 --11.7358808517,1.05568528175,2.25975203514 --11.7588729858,1.05768299103,2.22636675835 --11.8018665314,1.0616799593,2.21517825127 --11.836856842,1.06467676163,2.18278598785 --11.820851326,1.06167650223,2.14037489891 --11.3828763962,1.01470184326,2.01679182053 --11.2838764191,1.00370717049,1.96034622192 --11.2928695679,1.00370573997,1.92393636703 --11.3148603439,1.00470364094,1.89155006409 --11.2828598022,1.00170528889,1.86733710766 --11.4168434143,1.01469576359,1.85398709774 --11.645822525,1.03867971897,1.85768985748 --11.4918260574,1.02168869972,1.79221355915 --11.4648218155,1.01768946648,1.74979639053 --11.4288167953,1.01369071007,1.7063781023 --11.6117992401,1.0326769352,1.69905483723 --11.3418130875,1.00369513035,1.63673985004 --11.3728046417,1.00569188595,1.60434663296 --11.38879776,1.00668954849,1.56995201111 --11.4267892838,1.01068556309,1.53856396675 --11.5307779312,1.02067661285,1.51720964909 --11.4297761917,1.00968289375,1.4647591114 --11.3447742462,1.00068795681,1.41531574726 --11.4517669678,1.01167917252,1.41216289997 --11.4957580566,1.01567423344,1.38178634644 --11.6087474823,1.02666389942,1.35942947865 --11.2867565155,0.992687880993,1.27887606621 --11.1807556152,0.980695068836,1.22943270206 --11.2497472763,0.987688243389,1.20206129551 --11.2697401047,0.989685177803,1.16766095161 --11.4377298355,1.00667059422,1.17054390907 --11.4817228317,1.0106651783,1.13815307617 --11.4127206802,1.00366938114,1.09372329712 --11.3907155991,1.00066959858,1.05430757999 --11.5397052765,1.01565492153,1.03397464752 --11.1987113953,0.979683160782,0.960407793522 --11.267706871,0.98667627573,0.95024561882 --11.2317018509,0.982677817345,0.909818589687 --11.2746953964,0.986672341824,0.87844067812 --11.2266921997,0.981675028801,0.838018000126 --11.1846876144,0.976677238941,0.797588229179 --11.1236839294,0.96968126297,0.756153762341 --11.1976776123,0.977672576904,0.72678476572 --11.171672821,0.973673343658,0.689375698566 --11.1606702805,0.972673475742,0.670163571835 --11.1296663284,0.969674766064,0.632753014565 --11.2256593704,0.978663504124,0.603385567665 --11.1586551666,0.971668243408,0.56295222044 --11.162651062,0.971665978432,0.527550518513 --11.1626462936,0.971664011478,0.492149829865 --11.1316413879,0.968665242195,0.454732745886 --11.1386394501,0.968663573265,0.437536269426 --11.2276334763,0.977652311325,0.407177180052 --11.2606287003,0.98164665699,0.37278559804 --11.2076253891,0.975650131702,0.334358304739 --11.2686195374,0.981641352177,0.30097848177 --11.3896141052,0.994625985622,0.270636230707 --11.2986135483,0.984634697437,0.248387858272 --11.192609787,0.973644077778,0.208940908313 --11.320605278,0.986627459526,0.17759616673 --11.2146015167,0.975636959076,0.138142064214 --11.1675977707,0.970639884472,0.100711971521 --11.2785930634,0.981624782085,0.06836566329 --11.3785896301,0.992610692978,0.0350131504238 --11.2355880737,0.977625966072,0.0137411085889 --11.2595844269,0.979620575905,-0.0216514561325 --11.3105812073,0.984611928463,-0.0570337176323 --11.2825775146,0.982612490654,-0.0934521481395 --11.3565740585,0.98960095644,-0.127809420228 --11.2755708694,0.981607913971,-0.165262207389 --11.3365678787,0.987597644329,-0.200631827116 --11.366566658,0.990592479706,-0.218820884824 --11.3445625305,0.988592326641,-0.254227280617 --11.4535617828,0.999575555325,-0.291584700346 --11.4035577774,0.994578838348,-0.327006131411 --11.3655548096,0.990580499172,-0.363434791565 --11.4125537872,0.995571374893,-0.399809628725 --11.2945480347,0.983583569527,-0.434274405241 --11.3855485916,0.993570148945,-0.453424543142 --11.4745483398,1.00255513191,-0.491784960032 --11.6285505295,1.01853120327,-0.532110035419 --11.4285430908,0.99755448103,-0.563615560532 --11.4075403214,0.995553910732,-0.599026024342 --11.4145374298,0.996549427509,-0.6364351511 --11.4185352325,0.997545421124,-0.672835350037 --11.4655361176,1.00253713131,-0.693014740944 --11.4165325165,0.997540354729,-0.727442681789 --11.2105226517,0.975565850735,-0.753945469856 --11.4335298538,0.999530732632,-0.800231456757 --11.4625282288,1.00252282619,-0.838624536991 --11.4255256653,0.998524427414,-0.873045444489 --11.5565309525,1.0125014782,-0.917384386063 --11.4795255661,1.00451087952,-0.930618882179 --11.4515228271,1.00251102448,-0.966042518616 --11.5225257874,1.00949656963,-1.00741004944 --13.7506370544,1.24315845966,-1.19867503643 --11.6065273285,1.01947569847,-1.08717358112 --11.4805202484,1.00649058819,-1.11464059353 --11.5965261459,1.01846861839,-1.15997779369 --14.170671463,1.28806960583,-1.38586306572 --11.5845241547,1.01746404171,-1.21458768845 --11.555521965,1.01546406746,-1.25001513958 --11.5165195465,1.01146578789,-1.28343749046 --14.0006771088,1.27206611633,-1.55155587196 --12.2755680084,1.09133529663,-1.42984259129 --11.6165237427,1.02343630791,-1.40358757973 --11.5825223923,1.01943957806,-1.4188066721 --11.5755214691,1.01943612099,-1.45521259308 --11.5515193939,1.01743531227,-1.49063670635 --11.6265249252,1.02541792393,-1.5359992981 --11.6045236588,1.02341687679,-1.57040810585 --11.3945074081,1.00244736671,-1.58392977715 --11.3745059967,1.00044846535,-1.59913313389 --11.4315109253,1.00643408298,-1.64351427555 --11.5945243835,1.02440130711,-1.70083165169 --16.9229717255,1.58447420597,-2.42044520378 --11.508518219,1.01640617847,-1.76367461681 --11.4675149918,1.01240825653,-1.79610729218 --11.4725160599,1.0134023428,-1.83350288868 --11.4835186005,1.0153979063,-1.85369956493 --16.0729427338,1.49857139587,-2.5456867218 --11.7685470581,1.0463360548,-1.97035968304 --11.550526619,1.02337002754,-1.97587680817 --11.4445180893,1.01338410378,-1.99733746052 --11.474521637,1.01637339592,-2.03871846199 --11.5315284729,1.02335739136,-2.08509039879 --11.6285400391,1.03433644772,-2.12024831772 --11.6185398102,1.0333327055,-2.15564703941 --16.1240253448,1.51047587395,-2.94464683533 --11.9285783768,1.06726229191,-2.28428578377 --11.5255355835,1.02533316612,-2.25391077995 --11.5365390778,1.02732551098,-2.29330468178 --11.7695674896,1.05327415466,-2.3735871315 --11.6605558395,1.04129242897,-2.37284469604 --11.846581459,1.06224966049,-2.44615340233 --11.8025779724,1.05825197697,-2.47657728195 --11.8655891418,1.06523323059,-2.52694034576 --11.9936084747,1.08020091057,-2.59127688408 --11.9566068649,1.07720148563,-2.623701334 --11.8305940628,1.06422054768,-2.63716554642 --12.0016183853,1.08318221569,-2.6922826767 --12.1126365662,1.09515237808,-2.75462174416 --12.0956382751,1.09414875507,-2.79103183746 --12.0946426392,1.09514176846,-2.83143997192 --12.0376396179,1.0901465416,-2.85886955261 --12.1136541367,1.09912323952,-2.91522669792 --14.4019832611,1.34362924099,-3.46437454224 --12.1876716614,1.10809636116,-2.99279379845 --12.1616725922,1.10609436035,-3.02720689774 --12.3217010498,1.12405216694,-3.10451865196 --12.1146755219,1.10308921337,-3.09804272652 --12.1966934204,1.11306345463,-3.15840268135 --12.2917137146,1.12403476238,-3.2217476368 --12.2187080383,1.11704277992,-3.24518990517 --12.2027082443,1.11604249477,-3.26139593124 --12.3417367935,1.13200306892,-3.33772659302 --12.1807165146,1.11603105068,-3.33922338486 --12.3387479782,1.13398706913,-3.42053508759 --12.342754364,1.13497769833,-3.46293091774 --12.4667825699,1.14994060993,-3.5372633934 --12.3637714386,1.13995563984,-3.55272817612 --12.5958147049,1.16589736938,-3.63579916954 --13.1719226837,1.22875356674,-3.83387041092 --13.181933403,1.23074114323,-3.88227319717 --13.0789232254,1.22075557709,-3.89772391319 --12.7638759613,1.18882036209,-3.85531592369 --13.1599569321,1.2327157259,-4.01149272919 --13.1599617004,1.2327105999,-4.0336894989 --13.1849746704,1.23669421673,-4.08607673645 --13.338013649,1.25464630127,-4.17639303207 --13.3030166626,1.25264418125,-4.21181249619 --13.2720212936,1.25064110756,-4.24822998047 --13.3270425797,1.25761640072,-4.31160640717 --13.3790636063,1.26459252834,-4.37297153473 --13.5651054382,1.28554010391,-4.45407152176 --13.5381116867,1.28453552723,-4.49248504639 --13.4961147308,1.28153455257,-4.52691507339 --16.3567142487,1.59579193592,-5.48367595673 --16.3587341309,1.59777498245,-5.54207849503 --16.3607540131,1.5997582674,-5.59947299957 --16.3007602692,1.59475755692,-5.63690423965 --16.2357559204,1.58876621723,-5.64414167404 --16.2747840881,1.59473955631,-5.71452045441 --16.3538208008,1.60470199585,-5.79887628555 --16.514875412,1.62464237213,-5.91118049622 --16.1838207245,1.5907137394,-5.85577106476 --16.3908863068,1.61464130878,-5.98504972458 --16.3919067383,1.61762392521,-6.04344701767 --16.2779026031,1.60663759708,-6.06191539764 --17.0090827942,1.68842899799,-6.35169172287 --16.907081604,1.67943871021,-6.37514543533 --17.0411338806,1.69638323784,-6.48446655273 --17.3162250519,1.72928786278,-6.64670562744 --17.6373252869,1.76717853546,-6.82791662216 --17.535326004,1.7581871748,-6.8533744812 --16.5660991669,1.65145134926,-6.52013683319 --17.4183330536,1.74819040298,-6.90403938293 --17.4513664246,1.75416088104,-6.98042201996 --17.2483406067,1.73419928551,-6.96493673325 --15.3488941193,1.52571284771,-6.34185028076 --15.3149061203,1.52470564842,-6.38527584076 --15.3259191513,1.52669405937,-6.41746711731 --15.5539999008,1.55460965633,-6.56573104858 --15.738070488,1.57753741741,-6.69802188873 --15.6790771484,1.57353699207,-6.73245954514 --15.6851005554,1.57551729679,-6.79285430908 --15.6771202087,1.57750177383,-6.84725522995 --15.9162101746,1.60641074181,-7.00651264191 --16.1052761078,1.62934350967,-7.11660194397 --16.0732898712,1.62833428383,-7.16301965714 --16.1513366699,1.63929080963,-7.25737524033 --16.1513614655,1.6422713995,-7.31777238846 --16.3804531097,1.67018020153,-7.47903394699 --16.5215206146,1.6891156435,-7.60334873199 --16.6055717468,1.70106852055,-7.70369911194 --16.7136173248,1.71502363682,-7.78383541107 --16.8856964111,1.73694753647,-7.92513036728 --17.3028526306,1.78779220581,-8.17927646637 --17.2328586578,1.78279221058,-8.21371936798 --17.2679004669,1.78975844383,-8.29609680176 --17.5040035248,1.81965863705,-8.47235107422 --17.7421112061,1.84955692291,-8.65260791779 --17.8821716309,1.86749899387,-8.75272083282 --17.9642314911,1.8804475069,-8.86106872559 --18.1723308563,1.90735340118,-9.03134346008 --18.4004402161,1.93725192547,-9.21260261536 --18.6395530701,1.96714568138,-9.40085315704 --18.9066772461,2.00202894211,-9.6050863266 --18.9947452545,2.01597166061,-9.72343158722 --19.5799617767,2.08575773239,-10.052274704 --19.7320537567,2.10667681694,-10.2065820694 --19.759103775,2.11363863945,-10.2979602814 --19.9282016754,2.13655018806,-10.4632558823 --20.2573604584,2.1794052124,-10.7114496231 --20.2544002533,2.18237566948,-10.7908468246 --20.5485496521,2.22124028206,-11.0260648727 --20.6956253052,2.24017262459,-11.1441717148 --20.9237518311,2.27105951309,-11.3474245071 --20.9378032684,2.2770216465,-11.4398126602 --21.1419258118,2.30491495132,-11.6340827942 --21.368057251,2.33579921722,-11.8423395157 --21.463142395,2.35173010826,-11.981678009 --21.7993183136,2.39557218552,-12.2538661957 --21.8223514557,2.40054583549,-12.311047554 --21.8153991699,2.40451264381,-12.3974485397 --21.8384609222,2.41146874428,-12.4998264313 --21.9365501404,2.42839550972,-12.6461629868 --21.8715782166,2.42438364029,-12.7005977631 --21.9246520996,2.43532681465,-12.8219585419 --21.9607200623,2.44527578354,-12.9353342056 --21.9807548523,2.44924974442,-12.9925165176 --22.0438346863,2.46218800545,-13.1218729019 --22.0528945923,2.46814632416,-13.2212657928 --22.1009693146,2.47908973694,-13.342628479 --22.1150302887,2.48504590988,-13.4450130463 --22.0990791321,2.48801326752,-13.5304193497 --22.0680942535,2.48700618744,-13.5596380234 --22.0781555176,2.49396300316,-13.661028862 --22.0702114105,2.49792695045,-13.7514276505 --22.0742702484,2.50288629532,-13.8488168716 --22.0683250427,2.50784873962,-13.9412164688 --22.0653820038,2.51280975342,-14.0366172791 --22.0664405823,2.51776909828,-14.1340103149 --22.0844802856,2.52274155617,-14.1941986084 --22.0445213318,2.52371764183,-14.2656164169 --22.0025634766,2.52369379997,-14.3370399475 --21.974609375,2.52566480637,-14.4164505005 --21.8986358643,2.5216550827,-14.4658956528 --21.8236618042,2.51764535904,-14.5153388977 --21.79570961,2.51961612701,-14.5947504044 --21.7617263794,2.51860952377,-14.6219711304 --21.7197685242,2.51858568192,-14.6933965683 --21.6758079529,2.51956295967,-14.7628192902 --21.6698665619,2.52452373505,-14.857216835 --21.6539230347,2.52748823166,-14.9466257095 --21.6209697723,2.52946066856,-15.0230388641 --21.589017868,2.53143167496,-15.1014566422 --21.6490802765,2.54138350487,-15.1936178207 --21.6811599731,2.55132651329,-15.3159914017 --21.7262477875,2.56326293945,-15.4493608475 --22.5387248993,2.67285633087,-16.1202316284 --22.4697589874,2.66984128952,-16.1776695251 --22.403793335,2.66782474518,-16.2371082306 --22.3128185272,2.66281914711,-16.2795639038 --22.2438163757,2.65682768822,-16.2828044891 --22.1468353271,2.65082573891,-16.3192634583 --22.0678653717,2.64781522751,-16.3687114716 --21.979888916,2.6428091526,-16.4111652374 --21.8859100342,2.63680648804,-16.4486217499 --21.7919311523,2.63180327415,-16.4860801697 --21.7089557648,2.62779569626,-16.5305290222 --21.6389541626,2.62180519104,-16.5317726135 --21.5479755402,2.6168012619,-16.570230484 --21.4680023193,2.61279225349,-16.6166782379 --21.3820266724,2.60778641701,-16.6581325531 --21.2850437164,2.60178589821,-16.6905918121 --21.2060699463,2.59877681732,-16.7370433807 --21.1150913239,2.59377360344,-16.7735004425 --21.0530910492,2.58878040314,-16.7787380219 --20.9721183777,2.58477282524,-16.8221893311 --20.8921432495,2.58076500893,-16.8656349182 --20.8021640778,2.57576155663,-16.9020957947 --20.7171859741,2.57175636292,-16.9415493011 --20.6382141113,2.56774806976,-16.9859981537 --20.5502338409,2.56274437904,-17.0224552155 --20.4952373505,2.55874872208,-17.0306873322 --20.4212665558,2.55673789978,-17.0781364441 --20.3422927856,2.5527305603,-17.1205844879 --20.2613182068,2.54872369766,-17.1620388031 --20.1823425293,2.54571604729,-17.2044887543 --20.085357666,2.53971815109,-17.2309494019 --20.012386322,2.53670740128,-17.2783985138 --19.9553890228,2.53271317482,-17.2836322784 --19.8684082031,2.52771019936,-17.3180904388 --19.7924346924,2.52470183372,-17.3615379333 --19.7204647064,2.52269077301,-17.4089889526 --19.6344852448,2.51768755913,-17.443447113 --19.5515079498,2.51368308067,-17.4799003601 --19.5155220032,2.51267838478,-17.5021190643 --19.4445514679,2.51066708565,-17.5495700836 --19.3785858154,2.50865340233,-17.6010150909 --19.3096160889,2.50664162636,-17.6484565735 --19.2326431274,2.50363397598,-17.6899108887 --19.1616706848,2.50162386894,-17.7353553772 --19.084695816,2.49761629105,-17.775806427 --19.04570961,2.49661326408,-17.7950325012 --18.9797420502,2.49459934235,-17.8464813232 --18.9187793732,2.49358320236,-17.9009208679 --18.8458061218,2.49157381058,-17.9443702698 --18.7938499451,2.49155282974,-18.0068035126 --18.7258834839,2.49054050446,-18.0552520752 --18.6629180908,2.48952555656,-18.1076965332 --18.6269302368,2.48752093315,-18.1289176941 --18.5649662018,2.48750543594,-18.1823596954 --18.5000019073,2.48549175262,-18.2328071594 --18.4350357056,2.48447799683,-18.2822494507 --18.3680686951,2.48346543312,-18.330696106 --18.3051013947,2.48245096207,-18.3821372986 --18.244140625,2.48143482208,-18.4355792999 --18.2091560364,2.48042917252,-18.4588050842 --18.1451892853,2.4794151783,-18.5092506409 --18.0892314911,2.47939562798,-18.568693161 --18.0182609558,2.47738599777,-18.6111373901 --17.9703083038,2.47936177254,-18.6785736084 --17.9043426514,2.47734856606,-18.7270202637 --17.8473834991,2.47833013535,-18.7844600677 --17.8153991699,2.47732281685,-18.8096847534 --17.7654476166,2.47929954529,-18.875120163 --17.69647789,2.47728872299,-18.9195690155 --17.6395206451,2.47727012634,-18.9770069122 --17.5915679932,2.47924542427,-19.0444450378 --17.5516223907,2.48221564293,-19.1198711395 --17.488658905,2.48120045662,-19.1713161469 --17.4726924896,2.4831829071,-19.2135276794 --17.4207401276,2.48415994644,-19.2779712677 --17.3597774506,2.48414349556,-19.331413269 --17.3188323975,2.48711371422,-19.4068412781 --17.2979068756,2.49307084084,-19.5042572021 --17.272977829,2.49902963638,-19.5986766815 --17.2490501404,2.5039870739,-19.695098877 --17.2410907745,2.50796365738,-19.7473049164 --17.147102356,2.50296854973,-19.7647724152 --17.0110740662,2.49100279808,-19.7342720032 --16.781961441,2.46410226822,-19.594833374 --16.6169033051,2.44815826416,-19.5273513794 --16.5018920898,2.43918037415,-19.5168361664 --16.412902832,2.43418431282,-19.5353012085 --16.3208656311,2.42422008514,-19.4885673523 --16.1187725067,2.40230417252,-19.3741149902 --16.0908374786,2.4072663784,-19.4625377655 --15.9818296432,2.39928555489,-19.4560203552 --15.8517990112,2.38732075691,-19.4225158691 --15.7598056793,2.3823287487,-19.4339828491 --15.6708135605,2.37733507156,-19.4484481812 --15.6027956009,2.37135505676,-19.4277019501 --15.5238132477,2.36835455894,-19.4531593323 --15.4348211288,2.36336159706,-19.466627121 --15.3538360596,2.36036229134,-19.4900913239 --15.2658443451,2.35536885262,-19.5035552979 --15.1538276672,2.34639334679,-19.4870414734 --15.1128349304,2.34539461136,-19.4972724915 --15.0328502655,2.34139585495,-19.519733429 --14.9428548813,2.33640480042,-19.5292015076 --14.8618679047,2.3334069252,-19.5496635437 --14.7748756409,2.32841420174,-19.5621318817 --14.6968927383,2.32541370392,-19.5875968933 --14.6639566422,2.33037877083,-19.6700229645 --14.58897686,2.32837677002,-19.6974811554 --14.5549898148,2.32737326622,-19.7157077789 --14.5000324249,2.32835507393,-19.7701530457 --14.4230489731,2.32535481453,-19.7946147919 --14.3630857468,2.32634067535,-19.8420619965 --14.3041229248,2.32632541656,-19.8915119171 --14.238152504,2.32531690598,-19.9299621582 --14.204164505,2.32431364059,-19.9471874237 --14.0861368179,2.31534671783,-19.9156837463 --13.9861268997,2.30836653709,-19.9061603546 --13.8520755768,2.29541492462,-19.8486633301 --13.7050094604,2.27947497368,-19.7711753845 --13.6550559998,2.28145384789,-19.8306179047 --11.7549114227,1.94800901413,-17.239408493 --11.6278047562,1.93009006977,-17.1147098541 --11.4877262115,1.91415667534,-17.0252189636 --11.3906974792,1.90518701077,-16.9966964722 --11.3737649918,1.9121478796,-17.0851173401 --11.2967596054,1.90716147423,-17.0845794678 --11.173787117,1.9041608572,-17.130487442 --11.1618175507,1.90714418888,-17.1696987152 --11.118853569,1.90912747383,-17.2201385498 --11.0778942108,1.91110897064,-17.2735748291 --11.0259208679,1.91109955311,-17.3120250702 --10.9649362564,1.91009891033,-17.335477829 --11.0521421432,1.93696248531,-17.5878200531 --10.8720016479,1.91207146645,-17.426361084 --10.8080587387,1.91604554653,-17.5030174255 --10.7640981674,1.91802835464,-17.5544624329 --10.7161302567,1.91901516914,-17.5989074707 --10.6751718521,1.9209959507,-17.6533412933 --10.617190361,1.92099225521,-17.6817951202 --10.5752325058,1.92297315598,-17.7362365723 --10.5582580566,1.9249600172,-17.769449234 --10.5052852631,1.92595100403,-17.8069019318 --10.4603242874,1.92793428898,-17.8573455811 --10.4163627625,1.92991697788,-17.9087867737 --10.3643903732,1.93090713024,-17.9472332001 --10.3144226074,1.93189561367,-17.9886779785 --10.3004550934,1.93487799168,-18.0298976898 --10.2514886856,1.93586468697,-18.0743427277 --10.2025203705,1.93685245514,-18.1167831421 --10.1555576324,1.93883681297,-18.1652297974 --10.1085958481,1.94082069397,-18.2146778107 --10.0556240082,1.94181156158,-18.2521266937 --10.0106649399,1.94379365444,-18.3045711517 --9.96370124817,1.9457783699,-18.3520107269 --9.94272613525,1.94776725769,-18.3822364807 --9.89476299286,1.94975221157,-18.429681778 --9.84579753876,1.95173823833,-18.4751281738 --9.79783630371,1.95372259617,-18.5235748291 --9.75588417053,1.95670056343,-18.5830154419 --9.70491695404,1.95768797398,-18.6264667511 --9.68594360352,1.95967519283,-18.6586818695 --9.60593032837,1.95469486713,-18.6471538544 --9.61305999756,1.96961688995,-18.8015594482 --9.56510066986,1.9716001749,-18.8520069122 --9.4351234436,1.96860587597,-18.8859272003 --9.37614440918,1.9686024189,-18.9133796692 --9.36318302155,1.97258114815,-18.9605960846 --9.31021785736,1.97356915474,-19.0030498505 --9.25724887848,1.97455811501,-19.0435009003 --9.30746459961,2.00042390823,-19.2938766479 --9.14530563354,1.97654211521,-19.1144104004 --9.50608253479,2.07603192329,-20.0055484772 --9.42908096313,2.07204461098,-20.0060214996 --9.35300827026,2.06109809875,-19.9252796173 --9.29203414917,2.06209278107,-19.9567394257 --5.44501543045,1.14178657532,-11.9760856628 --9.19112300873,2.06705617905,-20.0626373291 --9.13115215302,2.06804871559,-20.0981006622 --9.04713153839,2.06207323074,-20.0775699615 --8.92503929138,2.04714560509,-19.9760780334 --8.7587890625,2.01331782341,-19.6934108734 --8.67676925659,2.00734233856,-19.6728820801 --8.35928440094,1.94267404079,-19.1285381317 --8.22615623474,1.92376899719,-18.9880523682 --8.46076774597,1.99937653542,-19.6802883148 --8.17232608795,1.94067847729,-19.1859207153 --8.30967617035,1.98345291615,-19.5820217133 --8.21262264252,1.97449946404,-19.5245094299 --8.10855197906,1.9625569582,-19.4480018616 --7.64071369171,1.8541175127,-18.5107688904 --7.7120051384,1.88793706894,-18.841129303 --7.84643554688,1.9406658411,-19.3264369965 --7.39460468292,1.83321928978,-18.4011936188 --7.69432830811,1.92275214195,-19.2111721039 --7.68245315552,1.93668174744,-19.3535995483 --7.58338499069,1.92573678493,-19.2810916901 --7.54745674133,1.93170070648,-19.3645324707 --7.48847532272,1.93169951439,-19.3879852295 --7.39441728592,1.92274820805,-19.3264751434 --7.33443498611,1.92174780369,-19.3489360809 --7.31446695328,1.92473232746,-19.3861579895 --7.24646615982,1.92274403572,-19.3876247406 --7.10529088974,1.89886784554,-19.1971492767 --7.01523447037,1.88991510868,-19.1376304626 --6.99133586884,1.89986038208,-19.2530632019 --6.93135166168,1.89986097813,-19.2735214233 --6.86034202576,1.89687824249,-19.265996933 --6.82332992554,1.89389121532,-19.2542266846 --6.7212395668,1.88096010685,-19.1577205658 --6.66225671768,1.88095963001,-19.1801815033 --6.56718063354,1.87001907825,-19.0996704102 --6.49917459488,1.86703383923,-19.0961418152 --6.47227334976,1.8769813776,-19.207572937 --6.39423894882,1.8710142374,-19.1730480194 --6.32814884186,1.85907673836,-19.0763072968 --6.26214551926,1.85708963871,-19.0757751465 --6.23825645447,1.86802995205,-19.2002105713 --6.17325639725,1.86704111099,-19.2026767731 --5.87660312653,1.78746545315,-18.4943122864 --5.99210882187,1.84515595436,-19.0486488342 --5.94315099716,1.84914028645,-19.0971012115 --5.93321466446,1.85510528088,-19.1683177948 --5.88827085495,1.86008048058,-19.2327709198 --5.82427310944,1.85909044743,-19.2372379303 --5.74221849442,1.85113549232,-19.1817188263 --5.65414333344,1.84019351006,-19.1031990051 --5.65032577515,1.8600897789,-19.3036174774 --5.59324932098,1.85014307499,-19.2228717804 --5.54730463028,1.85511946678,-19.285326004 --5.4843082428,1.85412836075,-19.2917938232 --5.41629505157,1.85114789009,-19.2802639008 --5.33122491837,1.84120261669,-19.2077445984 --5.23912763596,1.82827401161,-19.1062297821 --5.19920492172,1.83523666859,-19.1926822662 --5.18425893784,1.84120857716,-19.2518997192 --5.13731527328,1.84618461132,-19.3153572083 --5.06829547882,1.84220802784,-19.2968273163 --4.9922504425,1.83624708652,-19.2513065338 --4.97240352631,1.85216343403,-19.4177417755 --4.91442012787,1.85216426849,-19.4382019043 --4.82633066177,1.84123063087,-19.3456897736 --4.81540775299,1.84918880463,-19.4289112091 --4.75039958954,1.8462048769,-19.4233779907 --4.68740081787,1.84521567822,-19.4268474579 --4.62640714645,1.84522294998,-19.4363098145 --4.56641817093,1.84522736073,-19.4507751465 --4.49538421631,1.83925938606,-19.4172477722 --4.40326499939,1.82534360886,-19.2937355042 --4.37326812744,1.82434689999,-19.2989654541 --4.32131052017,1.82833242416,-19.3464279175 --4.23219871521,1.81441187859,-19.2309169769 --4.15312576294,1.80546784401,-19.1563968658 --4.09011745453,1.80348372459,-19.1508636475 --4.04920816422,1.81243991852,-19.2493190765 --3.97816419601,1.80647778511,-19.2057933807 --3.93510770798,1.79951751232,-19.1480331421 --3.89319515228,1.80847585201,-19.2424869537 --3.80909180641,1.79554975033,-19.1369762421 --3.76014661789,1.80052769184,-19.1974315643 --3.71823620796,1.80948483944,-19.2938842773 --3.65723776817,1.80849516392,-19.2983531952 --3.58317351341,1.80054545403,-19.2338294983 --3.55317997932,1.80054736137,-19.242067337 --3.50323367119,1.80552649498,-19.3005256653 --3.44123053551,1.80453979969,-19.2999973297 --3.37519860268,1.80057024956,-19.2694625854 --3.32525992393,1.80654501915,-19.3359279633 --3.24113368988,1.79163205624,-19.2074127197 --3.2030878067,1.78566467762,-19.1616477966 --3.10286092758,1.7608114481,-18.9291439056 --3.09616565704,1.79264140129,-19.2475757599 --3.02812290192,1.78767848015,-19.2060508728 --2.94699478149,1.77276587486,-19.0765304565 --2.83668708801,1.73895967007,-18.7620372772 --2.49791646004,1.54701864719,-16.9406814575 --2.43887400627,1.54205358028,-16.9021492004 --2.4038169384,1.53509187698,-16.8463859558 --2.35383009911,1.53609406948,-16.8648452759 --2.29377317429,1.5301374197,-16.8113079071 --2.15516853333,1.46450281143,-16.1968288422 --2.19783496857,1.53612089157,-16.8852329254 --2.14885520935,1.53811907768,-16.9106903076 --1.94351911545,1.3949072361,-15.5470314026 --2.33084058762,1.74997138977,-18.9472293854 --2.29401183128,1.76788282394,-19.1246833801 --2.21787905693,1.75297188759,-18.9921627045 --2.16594052315,1.75894784927,-19.0576305389 --1.73678874969,1.42379534245,-15.8533067703 --1.68778800964,1.4238049984,-15.8587703705 --2.02399015427,1.76394832134,-19.1147994995 --1.94279277325,1.74207472801,-18.9172840118 --1.88176858425,1.73910033703,-18.8957538605 --1.53293287754,1.43975400925,-16.0263710022 --1.77689146996,1.75205290318,-19.0256881714 --1.72293937206,1.75603675842,-19.0771522522 --1.66292834282,1.75505518913,-19.0686225891 --1.63392829895,1.7550611496,-19.0698547363 --1.5769507885,1.75706005096,-19.09532547 --1.52605366707,1.76701283455,-19.201795578 --1.46401679516,1.76304614544,-19.1672668457 --1.40298497677,1.76007640362,-19.1377334595 --1.33386111259,1.74615931511,-19.0162143707 --1.27078819275,1.73821294308,-18.9456806183 --1.24686980247,1.74717247486,-19.0289173126 --1.19090247154,1.75016570091,-19.0643844604 --1.11869859695,1.72929430008,-18.8628635406 --1.05866312981,1.72532629967,-18.8303318024 --1.00473177433,1.73229932785,-18.901802063 --0.94266718626,1.72534799576,-18.8402767181 --0.884663879871,1.72536206245,-18.8397445679 --0.85462552309,1.7213896513,-18.8029747009 --0.794587850571,1.71742320061,-18.7684497833 --0.735544025898,1.71245980263,-18.7279148102 --0.674469172955,1.70551419258,-18.6563892365 --0.614396870136,1.69756698608,-18.5878601074 --0.559459924698,1.70454359055,-18.6533317566 --0.502467513084,1.70555138588,-18.6638031006 --0.471364110708,1.69461548328,-18.5630321503 --0.413324981928,1.69064939022,-18.5275020599 --0.355296880007,1.68767726421,-18.5029754639 --0.297225296497,1.68072938919,-18.4354457855 --0.240184962749,1.67676401138,-18.3989124298 --0.183182150126,1.67677783966,-18.3993873596 --0.127237305045,1.68275904655,-18.4568595886 --0.099229760468,1.68176937103,-18.4510917664 --0.0421823561192,1.67780792713,-18.4075622559 -0.00814649742097,1.67415356636,-17.5431118011 -0.0651788562536,1.67715573311,-17.5724716187 -0.121185831726,1.67814397812,-17.5768260956 -0.177137643099,1.67210197449,-17.5271892548 -0.20620931685,1.68013358116,-17.5963630676 -0.263206928968,1.67911660671,-17.5917263031 -0.319167226553,1.67507910728,-17.5500888824 -0.375171005726,1.67506587505,-17.5514469147 -0.43532460928,1.69113469124,-17.70079422 -0.492310076952,1.68911111355,-17.6841583252 -0.550351083279,1.6931180954,-17.7225131989 -0.579397857189,1.69813609123,-17.7676830292 -0.638428688049,1.7011371851,-17.7960453033 -0.695435464382,1.70212543011,-17.8004016876 -0.757553637028,1.71417427063,-17.9157485962 -0.817605555058,1.72018682957,-17.9651031494 -0.876648962498,1.72419512272,-18.0064525604 -0.938728511333,1.73222267628,-18.0838050842 -0.969767987728,1.73723614216,-18.1219787598 -1.03182446957,1.74325084686,-18.1763343811 -1.09389257431,1.75027215481,-18.2426815033 -1.18494880199,1.75627911091,-18.2962112427 -1.24395084381,1.75626456738,-18.2965698242 -1.30295109749,1.75724887848,-18.2949295044 -1.33194613457,1.75623857975,-18.2891082764 -1.39195942879,1.75822985172,-18.3004684448 -1.45095145702,1.75720989704,-18.2908325195 -1.50996279716,1.75920033455,-18.3001842499 -1.56997382641,1.76019072533,-18.3095436096 -1.62896716595,1.76017141342,-18.3009052277 -1.68796825409,1.76015663147,-18.3002643585 -1.71797633171,1.76115322113,-18.3074417114 -1.77798521519,1.76214241982,-18.3148002625 -1.83597183228,1.76111972332,-18.299161911 -1.89496803284,1.76110219955,-18.2935256958 -1.95397412777,1.76209020615,-18.2978801727 -2.01297283173,1.76307380199,-18.2942409515 -2.07297563553,1.76306009293,-18.2956027985 -2.1029779911,1.76405346394,-18.2967815399 -2.16197896004,1.76403880119,-18.2961406708 -2.22097444534,1.7640209198,-18.2895030975 -2.27997589111,1.76500630379,-18.288860321 -2.34098672867,1.76699674129,-18.2982196808 -2.40199494362,1.76798558235,-18.3045825958 -2.42998409271,1.7669724226,-18.2927646637 -2.48898077011,1.76795530319,-18.2871246338 -2.54797720909,1.76793813705,-18.2814865112 -2.60697746277,1.76792323589,-18.2798442841 -2.66597414017,1.76890623569,-18.2742061615 -2.7249712944,1.7688896656,-18.2695655823 -2.78597760201,1.76987755299,-18.2739295959 -2.81597995758,1.77087116241,-18.2751083374 -2.87698674202,1.77185952663,-18.2804679871 -2.93598222733,1.77184212208,-18.2738304138 -2.99698877335,1.7738301754,-18.2781906128 -3.05296874046,1.77180480957,-18.2555561066 -3.10492181778,1.76776564121,-18.2049274445 -3.17598700523,1.77578413486,-18.270275116 -3.21403646469,1.78180193901,-18.320438385 -3.28308105469,1.78780961037,-18.3647956848 -3.35112261772,1.79281580448,-18.4061470032 -3.42217874527,1.79982936382,-18.4624938965 -3.50027108192,1.81086146832,-18.5568294525 -3.57935857773,1.82189059258,-18.6461734772 -3.65644192696,1.83191800117,-18.7315044403 -3.70452356339,1.84195148945,-18.8156681061 -3.78159785271,1.85097396374,-18.8920059204 -3.85866641998,1.85999333858,-18.962348938 -3.92769670486,1.86399316788,-18.9927005768 -3.99672222137,1.86799049377,-19.0180549622 -4.06675434113,1.87299132347,-19.050403595 -4.13577890396,1.87698805332,-19.0747585297 -4.17581510544,1.88099837303,-19.1119308472 -4.24182796478,1.88398945332,-19.1242809296 -4.31386089325,1.88899040222,-19.1576347351 -4.37786245346,1.89097559452,-19.1579914093 -4.44989347458,1.89497542381,-19.1893444061 -4.50987768173,1.894952178,-19.171705246 -4.54588985443,1.8969502449,-19.1838855743 -4.6118979454,1.89893901348,-19.1912403107 -4.67187976837,1.89891433716,-19.1706047058 -4.73487281799,1.89889538288,-19.1619682312 -4.79786729813,1.89987742901,-19.1553268433 -4.85684347153,1.89885008335,-19.128698349 -4.92084264755,1.89983403683,-19.1260566711 -4.9548459053,1.90082800388,-19.129240036 -5.01282405853,1.89980196953,-19.104598999 -5.07782411575,1.90178644657,-19.1029605865 -5.1428232193,1.90277040005,-19.1003246307 -5.19778823853,1.90073800087,-19.0616950989 -5.25977945328,1.90071856976,-19.0510559082 -5.32477712631,1.90270161629,-19.0464191437 -5.34875011444,1.89968132973,-19.0176048279 -5.4067234993,1.89865267277,-18.9869804382 -5.46369934082,1.89762580395,-18.9593448639 -5.51665830612,1.89459061623,-18.9137210846 -5.57062387466,1.89155876637,-18.8750915527 -5.62458658218,1.88952565193,-18.8334693909 -5.68758153915,1.89050793648,-18.8258304596 -5.71456480026,1.88949239254,-18.8070163727 -5.77454996109,1.88947021961,-18.7893810272 -5.83453369141,1.8884472847,-18.7697505951 -5.89351701736,1.88842439651,-18.7501144409 -5.95450162888,1.88840174675,-18.7314872742 -6.01549053192,1.88938117027,-18.7168521881 -6.07547664642,1.88935983181,-18.7002162933 -6.10847759247,1.89035284519,-18.7003955841 -6.169465065,1.89033186436,-18.6847629547 -6.23045349121,1.89131140709,-18.6701259613 -6.28943347931,1.89028692245,-18.6464996338 -6.35342931747,1.89226996899,-18.6398620605 -6.41942882538,1.89425468445,-18.6372280121 -6.48342466354,1.89523780346,-18.6305904388 -6.51241493225,1.89522576332,-18.6187744141 -6.56638479233,1.89319705963,-18.5841445923 -6.61433744431,1.8891595602,-18.5295295715 -6.67432069778,1.88913679123,-18.5089015961 -6.74934434891,1.89413332939,-18.5332527161 -6.82336521149,1.89912807941,-18.5536060333 -6.85135316849,1.89911484718,-18.5387897491 -6.91935586929,1.90110146999,-18.5401535034 -6.94024419785,1.88903462887,-18.4145622253 -6.94810342789,1.87395489216,-18.2569847107 -6.97701454163,1.86489880085,-18.1553878784 -6.99289798737,1.85283041,-18.0237998962 -7.01279067993,1.84176659584,-17.9022140503 -7.01171398163,1.83272409439,-17.8154277802 -7.04564142227,1.8266762495,-17.7318305969 -7.07856988907,1.81962919235,-17.6492271423 -7.10548686981,1.81057727337,-17.5536270142 -7.13440895081,1.80352735519,-17.4630279541 -7.16834449768,1.79748392105,-17.3874206543 -7.20227956772,1.79144060612,-17.3118171692 -7.21223163605,1.78641164303,-17.2560253143 -7.24917507172,1.78137230873,-17.1894168854 -7.29814434052,1.77934443951,-17.1508026123 -7.33709478378,1.77530813217,-17.0911884308 -7.37303686142,1.76926839352,-17.0225887299 -7.41499471664,1.76623570919,-16.9709739685 -7.45394611359,1.76220047474,-16.9123649597 -7.46991539001,1.75917983055,-16.8755607605 -7.51187229156,1.75614690781,-16.8229541779 -7.54681921005,1.75110960007,-16.7583446503 -7.5827665329,1.74707269669,-16.6947383881 -7.62773180008,1.74404382706,-16.6511268616 -7.66568517685,1.74000954628,-16.5935173035 -7.70564174652,1.73697698116,-16.5399112701 -7.71560144424,1.73295271397,-16.4921150208 -7.76357555389,1.73192775249,-16.4574966431 -7.80253171921,1.72789514065,-16.4028892517 -7.8414888382,1.72486305237,-16.349281311 -7.88044834137,1.7218323946,-16.2986660004 -7.92842197418,1.7198073864,-16.2630558014 -7.95741987228,1.72080004215,-16.2582378387 -7.96031284332,1.70873999596,-16.1306667328 -8.05125713348,1.70668983459,-16.056432724 -8.10524272919,1.70667052269,-16.0348167419 -8.12617301941,1.69962739944,-15.9492225647 -8.17515087128,1.69860494137,-15.9186077118 -8.19813728333,1.69859290123,-15.9007997513 -8.21205615997,1.68954527378,-15.8022174835 -8.27205562592,1.69153177738,-15.7945890427 -8.29399013519,1.68549108505,-15.7139949799 -8.31392288208,1.67844974995,-15.630402565 -8.36390590668,1.678429842,-15.6047811508 -8.38984870911,1.67339253426,-15.5321893692 -8.40983009338,1.67137897015,-15.5093860626 -8.45079898834,1.66935312748,-15.4667758942 -8.49577522278,1.66833019257,-15.4321603775 -8.53674411774,1.66730427742,-15.3895521164 -8.5887298584,1.66728579998,-15.3669347763 -8.63671016693,1.66726529598,-15.3383169174 -8.68369007111,1.66624462605,-15.3086967468 -8.69666385651,1.66422700882,-15.273900032 -8.74063682556,1.66320323944,-15.2362937927 -8.79262542725,1.66318643093,-15.2166662216 -8.83659934998,1.66216313839,-15.1800575256 -8.88758563995,1.66314482689,-15.1564378738 -8.93256187439,1.66212248802,-15.1218280792 -8.98154449463,1.66210317612,-15.0952091217 -9.00853824615,1.66309475899,-15.0854005814 -9.07955360413,1.66708874702,-15.0967607498 -9.10049629211,1.66205275059,-15.0221681595 -9.17852020264,1.66805028915,-15.0435266495 -9.22550010681,1.66802966595,-15.0129117966 -9.27147769928,1.66700804234,-14.97930336 -9.32646942139,1.66799247265,-14.9626779556 -9.35446643829,1.66898488998,-14.9548664093 -9.40144634247,1.6689645052,-14.9242515564 -9.45543575287,1.66994786263,-14.9046316147 -9.5064201355,1.67092967033,-14.8800144196 -9.56241226196,1.67191362381,-14.8623981476 -9.6143989563,1.67289626598,-14.8397769928 -9.6383895874,1.67288684845,-14.825966835 -9.6953830719,1.67487168312,-14.810344696 -9.73935985565,1.67385005951,-14.7747335434 -9.80035877228,1.6768373251,-14.7661046982 -9.84833812714,1.67681729794,-14.73549366 -9.89632129669,1.67679810524,-14.7068767548 -9.96032142639,1.67978596687,-14.7002515793 -9.98931980133,1.68077898026,-14.69343853 -10.051317215,1.68376600742,-14.6838150024 -10.1093120575,1.68575143814,-14.6691894531 -10.157292366,1.68573200703,-14.6395740509 -10.2112808228,1.68771517277,-14.6179552078 -10.2652692795,1.68869805336,-14.5953416824 -10.3222618103,1.69068300724,-14.5787172318 -10.342247963,1.68967139721,-14.5579128265 -10.3942337036,1.69065392017,-14.5332965851 -10.4522266388,1.69263923168,-14.5176706314 -10.5132217407,1.69562494755,-14.5040521622 -10.563205719,1.69560658932,-14.476436615 -10.6161937714,1.69758939743,-14.4528179169 -10.6861991882,1.70157945156,-14.4521865845 -10.7141942978,1.70257139206,-14.4423761368 -10.7681818008,1.70355474949,-14.4197568893 -10.8261756897,1.70553982258,-14.403131485 -10.8761577606,1.70652091503,-14.3735208511 -10.9451618195,1.71050989628,-14.3698921204 -11.0081586838,1.71349656582,-14.3582668304 -11.0451641083,1.71549224854,-14.3604469299 -11.0981502533,1.71647512913,-14.3358268738 -11.1611471176,1.71946144104,-14.3232040405 -11.2171354294,1.72144472599,-14.3005876541 -11.3071603775,1.72844135761,-14.3229398727 -11.3731594086,1.73242890835,-14.3143091202 -11.4501686096,1.73741996288,-14.3176765442 -11.4811668396,1.73941302299,-14.3108606339 -11.5381565094,1.74039661884,-14.2892417908 -11.5981473923,1.74338114262,-14.2706212997 -11.6661481857,1.74636900425,-14.2629899979 -11.7271404266,1.74935352802,-14.2443733215 -11.7751207352,1.74933421612,-14.2117567062 -11.8391170502,1.75332021713,-14.1981296539 -11.8851280212,1.75631773472,-14.2073097229 -11.9441184998,1.75930178165,-14.1866893768 -11.9800853729,1.75727760792,-14.1370925903 -11.9970359802,1.75224792957,-14.0665054321 -12.0169887543,1.748218894,-13.998919487 -11.6555814743,1.68206477165,-13.4796600342 -11.6765394211,1.679038167,-13.4170722961 -11.6785106659,1.67602241039,-13.376282692 -11.7104787827,1.67399954796,-13.3266878128 -11.7334394455,1.6709741354,-13.2670993805 -11.7634067535,1.66895091534,-13.2155056 -11.795375824,1.66692876816,-13.1669092178 -11.8253440857,1.66490614414,-13.116312027 -11.8293180466,1.66189146042,-13.0785236359 -11.8352632523,1.65686142445,-12.9999542236 -11.8662338257,1.6548397541,-12.9513568878 -11.8972034454,1.65281796455,-12.902759552 -11.9241695404,1.65079498291,-12.8491687775 -11.9481344223,1.64777171612,-12.7935762405 -11.9781036377,1.64675009251,-12.7439813614 -11.9780769348,1.64373552799,-12.7041902542 -12.0000391006,1.64071154594,-12.6456069946 -12.0210018158,1.63668787479,-12.5870199203 -12.0399627686,1.63366377354,-12.5264348984 -12.0659303665,1.63164186478,-12.4738426208 -12.0888948441,1.62861895561,-12.4172592163 -12.0938463211,1.62359213829,-12.3436803818 -12.0958223343,1.6215788126,-12.306889534 -12.1077795029,1.61655378342,-12.2403106689 -12.1327466965,1.61453199387,-12.1867256165 -12.1517105103,1.61150968075,-12.1291351318 -12.1786813736,1.60948884487,-12.0785446167 -12.2016487122,1.60746765137,-12.0249538422 -12.2266168594,1.60544657707,-11.9723672867 -12.2125806808,1.60042977333,-11.9195957184 -12.2375516891,1.59840965271,-11.8690004349 -12.2565155029,1.59538781643,-11.811416626 -12.2764816284,1.59236621857,-11.7548351288 -12.2894439697,1.58934378624,-11.6932487488 -12.3084096909,1.58632254601,-11.6366634369 -12.3273763657,1.58430171013,-11.5810747147 -12.3203468323,1.5802873373,-11.5362997055 -12.3403158188,1.57726693153,-11.4817123413 -12.3442716599,1.57324314117,-11.4121370316 -12.3632392883,1.5702227354,-11.3565540314 -12.3872108459,1.56820344925,-11.3059654236 -12.4001741409,1.56518220901,-11.24538517 -12.4191427231,1.56216228008,-11.1907997131 -12.4341316223,1.5621535778,-11.1690006256 -12.4531002045,1.55913388729,-11.1144161224 -12.4830760956,1.55911636353,-11.0698242188 -12.5040464401,1.55709731579,-11.0172405243 -12.5170125961,1.5530769825,-10.958656311 -12.550992012,1.55306065083,-10.9180603027 -12.5599775314,1.55205130577,-10.8912658691 -12.5829496384,1.55003285408,-10.840681076 -12.5879116058,1.54601180553,-10.7761011124 -12.5928735733,1.54199075699,-10.7105283737 -12.5998363495,1.53797030449,-10.6479482651 -12.6318149567,1.53795397282,-10.6053609848 -12.6537885666,1.53593635559,-10.5557718277 -12.661772728,1.53492701054,-10.5279827118 -12.6837472916,1.53290963173,-10.4783945084 -12.7097234726,1.53189313412,-10.432800293 -12.8897972107,1.55190205574,-10.5160894394 -8.20782661438,0.907111048698,-6.49367380142 -8.29185199738,0.914110064507,-6.49824380875 -8.3348608017,0.917107284069,-6.49063014984 -8.35485458374,0.917100727558,-6.46304512024 -8.38085269928,0.917095184326,-6.44045495987 -8.40284919739,0.918089389801,-6.41585493088 -8.42384529114,0.918083369732,-6.39025783539 -8.43984508514,0.918080866337,-6.38046884537 -8.46384239197,0.919075250626,-6.35687255859 -8.48083591461,0.918068826199,-6.32827711105 -8.50783443451,0.91906362772,-6.306681633 -8.53883647919,0.920058965683,-6.28808355331 -8.56083202362,0.920053124428,-6.26249265671 -8.58883190155,0.922048151493,-6.2418923378 -8.60683441162,0.923046350479,-6.23508405685 -8.63083171844,0.923040747643,-6.21049594879 -8.65983104706,0.924035787582,-6.18990087509 -8.67982673645,0.924029946327,-6.16330480576 -8.70782661438,0.925024926662,-6.14171218872 -8.73582649231,0.926020085812,-6.12110853195 -8.76082420349,0.927014887333,-6.09751462936 -8.77282238007,0.927012085915,-6.08472394943 -8.800822258,0.928007125854,-6.06312942505 -8.82581996918,0.929001867771,-6.03953361511 -8.85381984711,0.929996967316,-6.01793766022 -8.87281513214,0.92999124527,-5.99034309387 -8.91282081604,0.931987583637,-5.97674131393 -8.93381595612,0.931982040405,-5.9501490593 -8.94681549072,0.932979464531,-5.93835306168 -8.97981739044,0.933975100517,-5.91975498199 -9.00681686401,0.934970319271,-5.89814805984 -9.03281497955,0.935965299606,-5.87455463409 -9.06381607056,0.937960684299,-5.85396099091 -9.08481216431,0.937955319881,-5.82736682892 -9.10580825806,0.937949776649,-5.79978227615 -9.12981319427,0.939948379993,-5.79596948624 -9.19382953644,0.945946753025,-5.79734659195 -9.11777973175,0.933932900429,-5.70583295822 -9.15878486633,0.935929358006,-5.69222593307 -9.22080039978,0.941927492619,-5.69160699844 -9.25480365753,0.943923294544,-5.67300462723 -9.30281734467,0.947923541069,-5.68318510056 -11.110622406,1.17005705833,-6.79824542999 -11.0405712128,1.15904164314,-6.70571994781 -10.9855270386,1.14902758598,-6.62219429016 -10.9114751816,1.1370126009,-6.52768087387 -10.7633924484,1.11699295044,-6.38921070099 -10.7283592224,1.10998141766,-6.32066869736 -10.6503171921,1.09897172451,-6.24993753433 -10.4942331314,1.07695293427,-6.10947561264 -10.5112247467,1.07694578171,-6.07489061356 -10.3561439514,1.05592787266,-5.93643569946 -10.2730932236,1.04291510582,-5.8429236412 -10.1910448074,1.03090262413,-5.75041532516 -10.1240024567,1.02089166641,-5.66888332367 -10.0559682846,1.01088440418,-5.60814285278 -9.88188457489,0.987868010998,-5.46469640732 -9.83685302734,0.979859113693,-5.39715909958 -9.72679710388,0.964847147465,-5.29267072678 -9.70977878571,0.960840344429,-5.24310588837 -9.63673877716,0.949830889702,-5.16158723831 -9.56770038605,0.939822018147,-5.0830655098 -9.47665977478,0.927815139294,-5.01234722137 -9.40662193298,0.91680675745,-4.93482398987 -9.3545923233,0.90879958868,-4.86828231812 -9.31656837463,0.902793169022,-4.80973434448 -9.29655265808,0.897787690163,-4.76117515564 -9.21051120758,0.88577991724,-4.67765951157 -9.19350147247,0.883777081966,-4.64988613129 -9.11946487427,0.872770130634,-4.57336807251 -9.07143974304,0.864764451981,-4.51182556152 -8.96839523315,0.85175716877,-4.42132902145 -8.95338153839,0.847752988338,-4.37776756287 -8.8883523941,0.838747620583,-4.3092341423 -8.83932876587,0.830742835999,-4.24869966507 -8.70627880096,0.81473761797,-4.16400003433 -8.68326473236,0.809733986855,-4.11745166779 -8.65224838257,0.80473035574,-4.06789922714 -8.58421993256,0.795726120472,-4.00037193298 -8.53719902039,0.788722574711,-3.94382977486 -8.53419303894,0.78672003746,-3.90925812721 -8.4561624527,0.775716304779,-3.8387336731 -8.41614723206,0.770714521408,-3.80297517776 -8.37512969971,0.764711856842,-3.75142264366 -8.31410598755,0.755709052086,-3.6898958683 -8.25208282471,0.747706472874,-3.62935709953 -8.20506477356,0.740704238415,-3.57581615448 -8.15804672241,0.733702301979,-3.52228140831 -8.12803554535,0.728700697422,-3.47772526741 -8.12203216553,0.727700054646,-3.45993757248 -8.05901050568,0.718698382378,-3.40040946007 -8.03200054169,0.714697182178,-3.35785412788 -8.017993927,0.711696207523,-3.32227778435 -7.96397590637,0.703695178032,-3.2677488327 -7.9389667511,0.699694395065,-3.22718930244 -7.90595674515,0.69569414854,-3.19841790199 -7.86194324493,0.689693570137,-3.14987421036 -7.86894369125,0.688693165779,-3.12330198288 -7.82192993164,0.682692945004,-3.07475090027 -7.78992033005,0.677692890167,-3.03220105171 -7.78691864014,0.675692677498,-3.0026242733 -7.72790193558,0.667693078518,-2.94909691811 -7.71789932251,0.666693150997,-2.93130874634 -7.67488765717,0.660693645477,-2.88575959206 -7.66988658905,0.658693909645,-2.85618233681 -7.61887359619,0.651694774628,-2.80764460564 -7.61887407303,0.650695204735,-2.78006982803 -7.58286523819,0.645696163177,-2.7385160923 -7.56386089325,0.642696976662,-2.70395088196 -7.52985286713,0.63869780302,-2.67718482018 -7.52785348892,0.63669860363,-2.64960837364 -7.51485157013,0.634699583054,-2.61705207825 -7.4328327179,0.624702036381,-2.55952548981 -7.42683315277,0.622703135014,-2.53095221519 -7.40983057022,0.619704544544,-2.49838638306 -7.3808259964,0.615706384182,-2.46084046364 -7.35882139206,0.612707495689,-2.44006204605 -7.32281541824,0.607709646225,-2.40150260925 -7.30681371689,0.604711413383,-2.36993861198 -7.31281757355,0.604712665081,-2.34635996819 -7.29881715775,0.602714538574,-2.31579375267 -7.24880886078,0.595717549324,-2.27226138115 -7.25081062317,0.595718324184,-2.26046943665 -7.24181127548,0.593720197678,-2.23288679123 -7.22881174088,0.591722309589,-2.20331931114 -7.23281574249,0.590723931789,-2.17973899841 -7.21381521225,0.587726414204,-2.14817929268 -7.22282075882,0.588728010654,-2.12659144402 -7.23782730103,0.589729309082,-2.10699892044 -7.22082519531,0.586730897427,-2.08921933174 -7.21882867813,0.585732936859,-2.06364703178 -7.20682954788,0.583735466003,-2.03507947922 -7.22783756256,0.585736632347,-2.01748204231 -7.1988363266,0.58174008131,-1.98293995857 -7.19183826447,0.579742491245,-1.95735013485 -7.1618347168,0.575744986534,-1.93558835983 -7.14583587646,0.573747992516,-1.90602970123 -7.16184282303,0.574749529362,-1.88742887974 -7.13784313202,0.57175308466,-1.85587263107 -7.11584329605,0.568756580353,-1.82531154156 -7.08584260941,0.564760565758,-1.79275369644 -7.0578417778,0.560764551163,-1.76119160652 -7.0918507576,0.563764095306,-1.75937449932 -7.06385040283,0.559768199921,-1.72781550884 -7.05485391617,0.558771491051,-1.70125257969 -7.05085849762,0.557774484158,-1.67667746544 -7.05286407471,0.556777119637,-1.65409314632 -7.03786659241,0.554780781269,-1.62652802467 -7.03987264633,0.554783582687,-1.60394525528 -7.04887628555,0.554784536362,-1.59415984154 -7.01587677002,0.550789415836,-1.56259894371 -7.03288507462,0.55179142952,-1.54400646687 -7.04989290237,0.553793370724,-1.5254124403 -7.01889419556,0.549798429012,-1.49386680126 -6.9878950119,0.545803487301,-1.46330761909 -7.0049033165,0.546805560589,-1.44471549988 -7.01890850067,0.54780626297,-1.4369122982 -7.0049123764,0.54581040144,-1.41034889221 -7.05092477798,0.550810575485,-1.39873218536 -7.02892827988,0.547815382481,-1.37017774582 -7.0649394989,0.550816237926,-1.3555752039 -7.09094905853,0.552817702293,-1.338971138 -7.0899515152,0.552819430828,-1.32718372345 -7.11196136475,0.554821252823,-1.30859923363 -7.10296583176,0.552825272083,-1.28402018547 -7.10197210312,0.552828848362,-1.26044988632 -7.12298107147,0.553830742836,-1.24185979366 -7.14699029922,0.555832326412,-1.22425889969 -7.13999605179,0.554836392403,-1.19968783855 -7.13399839401,0.553838610649,-1.18690443039 -7.11700296402,0.551843523979,-1.16034209728 -7.05900239944,0.544851541519,-1.12679040432 -6.93199396133,0.530865311623,-1.07930374146 -7.11402273178,0.549854636192,-1.09160518646 -7.09702730179,0.547859668732,-1.06603181362 -6.95201778412,0.531875252724,-1.01655459404 -7.03803062439,0.540870070457,-1.02169692516 -7.11904716492,0.548867344856,-1.01307713985 -7.18106031418,0.554865956306,-1.00145471096 -7.1540646553,0.551872074604,-0.973895728588 -7.14807081223,0.550876379013,-0.950318396091 -7.13207674026,0.548881709576,-0.924754917622 -16.0149860382,1.48712027073,-2.33975601196 -16.022983551,1.48711776733,-2.31497097015 -7.01908397675,0.535901546478,-0.850876092911 -16.0389633179,1.48710942268,-2.21581745148 -16.034954071,1.48610639572,-2.1632578373 -16.0719490051,1.48909986019,-2.11766672134 -16.0929412842,1.49109470844,-2.07008099556 -16.1419391632,1.49508857727,-2.05126953125 -16.2509384155,1.50607538223,-2.01464104652 -16.4809494019,1.53005087376,-1.99493288994 -16.4499359131,1.52605044842,-1.93838334084 -16.3389186859,1.51305770874,-1.87187922001 -16.3059062958,1.50905776024,-1.81533491611 -16.1788825989,1.49506545067,-1.72305035591 -7.03516769409,0.534945011139,-0.620303571224 -16.308883667,1.50805008411,-1.68740546703 -16.358877182,1.51204252243,-1.64180672169 -16.3748703003,1.51303803921,-1.59123492241 -16.4908695221,1.52502381802,-1.55259621143 -16.3818531036,1.51303195953,-1.48908996582 -16.4658508301,1.52102100849,-1.44647014141 -7.02022457123,0.53097820282,-0.465256810188 -16.6168403625,1.53599905968,-1.33046853542 -16.6498317719,1.5389932394,-1.28187608719 -16.4658126831,1.51900994778,-1.21341121197 -16.4568042755,1.51800847054,-1.16084825993 -16.4387950897,1.51500821114,-1.1072934866 -16.4257926941,1.51400852203,-1.08051598072 -16.4197826385,1.51300704479,-1.02894711494 -16.444776535,1.51500236988,-0.979364156723 -9.67443466187,0.806734144688,-0.446664214134 -9.68643951416,0.807735860348,-0.41708496213 -9.69844436646,0.808737576008,-0.387504786253 -9.6854467392,0.807740569115,-0.371722429991 -9.6794500351,0.806744337082,-0.341151058674 -9.68745613098,0.807746529579,-0.311569362879 -9.6804599762,0.806750535965,-0.280998528004 -9.67846488953,0.805753946304,-0.250429242849 -9.68346977234,0.806756675243,-0.220846608281 -9.67147445679,0.80476129055,-0.190277129412 -9.67047595978,0.804763019085,-0.175485864282 -9.68548202515,0.80576467514,-0.14590343833 -9.66648674011,0.803770244122,-0.11533562094 -9.66149139404,0.803774297237,-0.0847679674625 -9.66849708557,0.803776919842,-0.0551854819059 -9.65950202942,0.802781522274,-0.0246192310005 -9.65950775146,0.802785038948,0.00496222218499 -9.66051006317,0.802786648273,0.0197531487793 -9.65251541138,0.802791237831,0.0503184758127 -9.65552139282,0.802794456482,0.0799004286528 -9.65552711487,0.802798211575,0.110467590392 -9.65153217316,0.801802396774,0.140046820045 -9.64853858948,0.80180644989,0.169626414776 -9.65654373169,0.802809298038,0.200197324157 -9.63454723358,0.799813866615,0.214976012707 -9.64255237579,0.800816655159,0.244560807943 -9.64555835724,0.801820278168,0.275129377842 -9.63356399536,0.79982560873,0.304701924324 -9.63557052612,0.800829231739,0.334283739328 -9.63857650757,0.800832867622,0.364852190018 -9.62658023834,0.799836397171,0.379633277655 -9.63658618927,0.800839066505,0.409221351147 -9.62559223175,0.799844563007,0.43879249692 -9.62459850311,0.799848735332,0.468371659517 -9.62560462952,0.799852848053,0.498938679695 -9.62861156464,0.799856543541,0.528521716595 -9.61361789703,0.798862695694,0.558086931705 -9.6216211319,0.799863696098,0.572885274887 -9.61662769318,0.798868596554,0.602459967136 -9.62463474274,0.799871861935,0.633035242558 -9.61164093018,0.798877954483,0.662600696087 -9.60764884949,0.798882782459,0.692176163197 -9.60465526581,0.798887550831,0.721752643585 -9.60565853119,0.798889577389,0.736543953419 -9.66766548157,0.805885612965,0.770150542259 -9.60068035126,0.798903644085,0.826264441013 -9.60868740082,0.79990708828,0.856842637062 -9.59869480133,0.79891294241,0.885422766209 -9.65970039368,0.805909097195,0.920027792454 -9.59670543671,0.798920154572,0.930777072906 -9.55071353912,0.794931232929,0.957326471806 -9.59772014618,0.799929320812,0.9909273386 -9.5677280426,0.796938061714,1.01750004292 -9.58673477173,0.798940181732,1.04908549786 -9.58774280548,0.79994481802,1.07965517044 -9.5877494812,0.799949586391,1.10923695564 -9.57975482941,0.798953175545,1.1240131855 -9.5827627182,0.799957454205,1.15360081196 -9.57577037811,0.799963355064,1.18316984177 -9.57277774811,0.799968659878,1.21274614334 -9.56978607178,0.799974024296,1.24232244492 -9.57179355621,0.799978733063,1.27289509773 -9.57279777527,0.799980998039,1.28768861294 -9.5708065033,0.800986409187,1.31825387478 -9.56581401825,0.799992144108,1.34782624245 -9.52582454681,0.797002911568,1.37239146233 -9.56383037567,0.801002442837,1.4069892168 -9.52284049988,0.797013700008,1.43253517151 -9.55784702301,0.801013708115,1.46712982655 -9.56185054779,0.802015781403,1.48291766644 -9.54986095428,0.801022648811,1.51148760319 -9.5518693924,0.802027642727,1.54206347466 -9.55387687683,0.802032470703,1.57165336609 -9.54488658905,0.802039146423,1.60121655464 -9.51289653778,0.799049258232,1.62677550316 -9.52390480042,0.801052868366,1.65836131573 -6.83206892014,0.51746404171,1.26073336601 -9.52491760254,0.802060782909,1.70372867584 -6.8430929184,0.519475758076,1.30589437485 -6.68811511993,0.503506362438,1.30238759518 -6.80811977386,0.516494810581,1.34402287006 -9.52695274353,0.804082393646,1.82602643967 -6.89313840866,0.525494992733,1.40124082565 -9.52696609497,0.805090606213,1.87139499187 -9.50997638702,0.803098797798,1.8989610672 -6.87217092514,0.524515151978,1.4521805048 -6.8091878891,0.518531918526,1.46272206306 -6.6292142868,0.499567240477,1.45119607449 -6.81221342087,0.519545197487,1.50688123703 -6.75422382355,0.513557851315,1.50663983822 -6.76923513412,0.515562474728,1.5312268734 -6.55226516724,0.493603825569,1.50969302654 -6.58327579498,0.49660602212,1.53728318214 -6.56529045105,0.495616018772,1.55485129356 -6.67229509354,0.50760602951,1.59848427773 -6.70430517197,0.511607766151,1.62609410286 -6.70431184769,0.511611282825,1.6368843317 -6.72132301331,0.51361566782,1.66246795654 -6.76333189011,0.518615841866,1.69307684898 -6.71934938431,0.514630258083,1.70562446117 -6.67936611176,0.510643780231,1.71818637848 -6.67037963867,0.510652422905,1.73776233196 -6.62939691544,0.506666481495,1.75031256676 -6.60940551758,0.504673242569,1.756098032 -6.67741203308,0.51266926527,1.7937155962 -6.66142749786,0.51167935133,1.81227505207 -6.6564412117,0.511687397957,1.83285188675 -6.59846019745,0.505704283714,1.84039866924 -6.55247783661,0.50171905756,1.84996461868 -6.60048007965,0.506714761257,1.87278115749 -6.68748521805,0.516707777977,1.91739451885 -6.66849994659,0.515718102455,1.93397438526 -6.61151885986,0.509734749794,1.94053316116 -6.58253574371,0.506747186184,1.95508956909 -6.63054418564,0.512746453285,1.9896967411 -6.66555452347,0.517747998238,2.02129364014 -6.67156076431,0.518750667572,2.03408527374 -6.67957353592,0.519756793976,2.05866575241 -6.66758823395,0.519766151905,2.07724523544 -6.69759893417,0.522768735886,2.10882520676 -6.68461322784,0.522778093815,2.12641835213 -6.63963222504,0.517793297768,2.13596987724 -6.60165071487,0.514807403088,2.1475212574 -6.64065265656,0.519804239273,2.16934704781 -6.62966823578,0.518813848495,2.18891119957 -6.60868406296,0.516824841499,2.20448803902 -6.63669490814,0.520827829838,2.23606967926 -6.62771034241,0.520836949348,2.25564694405 -6.56673145294,0.514855086803,2.2591919899 -6.59374237061,0.518857955933,2.28979110718 -6.63574409485,0.523854553699,2.31459856033 -6.61976051331,0.522864997387,2.3321685791 -6.65276956558,0.526866614819,2.36477899551 -6.74177312851,0.537858903408,2.41739368439 -9.43145561218,0.833398044109,3.3372335434 -9.43846511841,0.835403501987,3.37181806564 -9.4504699707,0.837404847145,3.39260673523 -9.44648170471,0.838412106037,3.42319226265 -9.43749332428,0.838420629501,3.45375370979 -9.43350505829,0.838427901268,3.48433995247 -9.44551467896,0.841432750225,3.52191662788 -9.39353275299,0.836448729038,3.53646945953 -9.40854263306,0.839453041553,3.57504963875 -6.46593618393,0.513977050781,2.52748203278 -6.47195053101,0.515984117985,2.55305123329 -6.60494613647,0.530967950821,2.62371468544 -6.55596780777,0.52698469162,2.62926125526 -6.50098991394,0.522002458572,2.6318128109 -6.49600505829,0.522011101246,2.65239930153 -6.5100107193,0.524012863636,2.67017889023 -6.49502706528,0.523023247719,2.68676495552 -6.47904396057,0.522034287453,2.70432472229 -6.46606063843,0.522044479847,2.72190642357 -6.44307851791,0.520056426525,2.73548316956 -6.40309906006,0.516071856022,2.74303603172 -6.45610666275,0.523070335388,2.78763651848 -6.38612365723,0.516086876392,2.77040314674 -6.41413450241,0.520089864731,2.80499410629 -6.36415672302,0.515106976032,2.80755090714 -6.4181637764,0.522105336189,2.85315489769 -6.34518957138,0.515126645565,2.84570336342 -6.32020807266,0.513139367104,2.8582713604 -6.34321975708,0.517143189907,2.89086794853 -6.3642244339,0.520143449306,2.91166448593 -6.37223768234,0.521150112152,2.9382519722 -6.32326030731,0.517167389393,2.94080090523 -6.29627990723,0.515180587769,2.9523665905 -6.30129432678,0.51618796587,2.97794747353 -6.3113079071,0.518194198608,3.00553703308 -6.29532527924,0.518205165863,3.02112221718 -6.28333473206,0.517211675644,3.02789831161 -6.28535032272,0.518219590187,3.05247592926 -6.28336572647,0.519228219986,3.07505631447 -6.27738189697,0.519237518311,3.09563803673 -6.28239679337,0.521245121956,3.12221050262 -6.27841281891,0.522254049778,3.14379405975 -6.25442457199,0.51926279068,3.1445684433 -6.27143716812,0.522267878056,3.17616176605 -6.27445220947,0.524275660515,3.20173931122 -6.28646564484,0.526281774044,3.2313284874 -6.26448440552,0.525294303894,3.24489474297 -6.25950098038,0.526303648949,3.26647377014 -6.26251602173,0.527311444283,3.2920563221 -6.26252365112,0.528315484524,3.30385184288 -6.2585401535,0.528324782848,3.32642483711 -6.24455785751,0.528335988522,3.34399342537 -6.26157093048,0.531341075897,3.37658929825 -6.24458885193,0.530352652073,3.3921649456 -6.24060583115,0.531361937523,3.41474151611 -6.24662017822,0.53336918354,3.44232678413 -6.25062656403,0.534372448921,3.45612955093 -6.23764514923,0.534383654594,3.47469234467 -6.24365997314,0.536390900612,3.50228214264 -6.2516746521,0.53839802742,3.53185939789 -6.22769451141,0.536410987377,3.54343676567 -6.21671247482,0.536421835423,3.56300282478 -6.23371744156,0.539422869682,3.58480072021 -6.23573207855,0.54043084383,3.61039304733 -6.23474884033,0.542439877987,3.63595867157 -6.22576618195,0.542449891567,3.65554714203 -6.21278476715,0.542461156845,3.67411375046 -6.22979688644,0.54546636343,3.70870947838 -6.21481609344,0.54447811842,3.72627425194 -6.19882726669,0.54348552227,3.73005485535 -6.22183895111,0.547489643097,3.76865029335 -6.1928601265,0.545503795147,3.77722406387 -6.20087480545,0.548510909081,3.80780601501 -6.19789171219,0.549520373344,3.83237814903 -6.20990514755,0.552526533604,3.86497235298 -6.18391799927,0.549535989761,3.8627474308 -6.18193483353,0.550545036793,3.88733172417 -6.18095111847,0.552553892136,3.91291189194 -6.19296503067,0.554560363293,3.94649720192 -6.21097755432,0.558565616608,3.9840836525 -6.17000198364,0.555582463741,3.98564195633 -6.17301797867,0.556590676308,4.01422071457 -6.18702316284,0.559592247009,4.0360212326 -6.18403959274,0.560601532459,4.06060504913 -6.18105697632,0.561611115932,4.0861749649 -6.16707611084,0.56162250042,4.10375642776 -6.17509031296,0.564629614353,4.13534879684 -6.17710638046,0.565638065338,4.16392850876 -6.16112661362,0.56565028429,4.18149089813 -6.17513132095,0.567651689053,4.20330238342 -6.17914676666,0.57065987587,4.23387718201 -6.17116451263,0.570670068264,4.25546455383 -6.15618467331,0.570682227612,4.27402496338 -6.15120220184,0.571692168713,4.29860019684 -6.15021848679,0.572701156139,4.32518815994 -6.20222473145,0.581699848175,4.38878583908 -6.13324689865,0.57371789217,4.35555124283 -6.14626026154,0.576724052429,4.39214277267 -6.14627742767,0.578733146191,4.42071771622 -6.13729572296,0.578743755817,4.44230175018 -6.12331581116,0.578755795956,4.46186256409 -6.12933111191,0.58176356554,4.49444770813 -6.12434005737,0.581768751144,4.50424957275 -6.14135360718,0.585774600506,4.54582595825 -6.11937427521,0.584787786007,4.55840539932 -6.11539173126,0.585797488689,4.58399057388 -6.10940980911,0.586807727814,4.60856962204 -6.14841842651,0.593808889389,4.66616725922 -6.1014456749,0.589827537537,4.66171884537 -6.12844753265,0.593826472759,4.69553184509 -6.12346601486,0.595836758614,4.72210025787 -6.12448263168,0.597845673561,4.75267934799 -6.10750246048,0.596858024597,4.76925897598 -6.1065196991,0.598867416382,4.79883384705 -6.12553215027,0.603872418404,4.84243488312 -6.10555362701,0.602885723114,4.85799884796 -6.15055274963,0.609881281853,4.90780735016 -6.18356227875,0.615883886814,4.96439599991 -6.16358375549,0.615897119045,4.97996616364 -6.15060281754,0.615908503532,4.99955749512 -6.12662506104,0.614922642708,5.01212263107 -6.13164138794,0.616930902004,5.04769849777 -6.17564821243,0.624930977821,5.11330938339 -6.1176700592,0.618947446346,5.08306980133 -6.14268159866,0.623951554298,5.1346616745 -6.12670183182,0.62396389246,5.15323829651 -6.13571739197,0.626971364021,5.19281768799 -6.12373733521,0.627983152866,5.21538877487 -6.12175416946,0.629992544651,5.24498081207 -6.12876176834,0.631995916367,5.26776361465 -6.1267786026,0.634005308151,5.29735898972 -6.12679576874,0.636014759541,5.33092737198 -6.10781764984,0.636027872562,5.3475022316 -6.11283349991,0.639035999775,5.3840918541 -6.12584781647,0.643042743206,5.4286737442 -6.15085029602,0.64704221487,5.46647882462 -6.12187480927,0.646057426929,5.47504615784 -6.14388656616,0.651062190533,5.52763795853 -6.11391067505,0.649077653885,5.53520679474 -6.15591859818,0.658078551292,5.60679674149 -6.14593791962,0.65908998251,5.6323723793 -6.10196590424,0.655108094215,5.62694263458 -6.12496852875,0.659108102322,5.66474246979 -6.10999011993,0.660120606422,5.68631219864 -6.04402256012,0.653143465519,5.66087055206 -6.07503223419,0.660146355629,5.72346782684 -6.12203884125,0.669146001339,5.80107402802 -6.15204906464,0.676149368286,5.86466264725 -6.10207843781,0.671169102192,5.85422039032 -6.10608577728,0.673172771931,5.87502193451 -6.11710071564,0.677180051804,5.92160320282 -6.11411905289,0.679190158844,5.95518016815 -6.14013051987,0.686194360256,6.01676559448 -6.1361489296,0.688204526901,6.04934883118 -6.13016796112,0.690215349197,6.08092308044 -6.10419178009,0.689230084419,6.09249830246 -6.14918994904,0.697225630283,6.15530061722 -6.12021398544,0.695240914822,6.16387796402 -6.24720096588,0.717224299908,6.32650899887 -6.11325025558,0.700261235237,6.23204231262 -6.10227108002,0.701273143291,6.25961494446 -6.10828733444,0.705281496048,6.30419445038 -6.116294384,0.707284748554,6.33198308945 -6.11231231689,0.710294783115,6.36557435989 -6.10333299637,0.711306393147,6.39614391327 -6.09235286713,0.713318169117,6.42372369766 -6.11836385727,0.71932220459,6.489320755 -6.31233406067,0.752292096615,6.73196029663 -6.10340356827,0.723344683647,6.5544667244 -6.14540195465,0.731340765953,6.61827611923 -6.08943367004,0.72636193037,6.59983587265 -6.09944868088,0.730369329453,6.65042638779 -6.08147096634,0.731382608414,6.67200136185 -6.10248374939,0.737387895584,6.73559045792 -6.07350873947,0.736403644085,6.74615573883 -6.09852027893,0.743408024311,6.81474781036 -6.08753204346,0.743415117264,6.82353591919 -6.08954906464,0.747424185276,6.8671245575 -6.08056926727,0.748435735703,6.89970064163 -6.08258724213,0.752445161343,6.9452753067 -6.05761098862,0.752459704876,6.95886087418 -8.99588775635,1.21886658669,10.3322839737 -8.99889469147,1.22087061405,10.3670797348 -9.02390575409,1.23087513447,10.4606628418 -8.27411174774,1.11603832245,9.66203975677 -8.97795009613,1.23390376568,10.5388050079 -8.23115634918,1.11906659603,9.73417854309 -8.22017669678,1.12207865715,9.7827501297 -8.10922145844,1.10911095142,9.7123041153 -8.0642414093,1.10512506962,9.690076828 -8.0212688446,1.10214352608,9.69964408875 -7.96929979324,1.09916400909,9.6982088089 -8.00830745697,1.11016559601,9.80580329895 -7.91334867477,1.10019481182,9.75235462189 -8.06932544708,1.13017237186,10.0039806366 -7.94537448883,1.11520767212,9.91452693939 -7.77842617035,1.09024691582,9.74026870728 -3.42458176613,0.371156394482,4.39049100876 -3.40460681915,0.370170533657,4.39306259155 -3.39462947845,0.371182829142,4.40863132477 -3.3846514225,0.371194720268,4.42321491241 -7.4296131134,1.05937254429,9.63886547089 -7.36964654922,1.05439484119,9.62442016602 -7.26469182968,1.04142618179,9.54897880554 -7.27870559692,1.04943323135,9.62856197357 -7.21873903275,1.04445540905,9.61112880707 -7.17376899719,1.04147469997,9.61468791962 -7.11180305481,1.03549730778,9.59325790405 -7.08681917191,1.03450751305,9.59203338623 -7.03285074234,1.02952826023,9.57961273193 -6.98988008499,1.02754712105,9.58417606354 -6.95190858841,1.0265648365,9.59474658966 -6.87594652176,1.01859045029,9.55330467224 -6.83397626877,1.01560926437,9.55787181854 -6.80899190903,1.01461935043,9.5546541214 -6.75602436066,1.00964021683,9.54322147369 -6.71805238724,1.00865781307,9.55179595947 -6.67108297348,1.00567758083,9.54836273193 -6.60211992264,0.998701870441,9.513920784 -6.57614469528,0.998717069626,9.53850078583 -6.52417755127,0.994737744331,9.52607250214 -6.4871969223,0.990750670433,9.50584220886 -6.4572224617,0.990766584873,9.52342700958 -6.41025400162,0.987786412239,9.51898956299 -6.36128616333,0.984806597233,9.51055526733 -6.32731389999,0.983823537827,9.52313137054 -6.26934766769,0.977845489979,9.49970149994 -6.2373752594,0.977862238884,9.51626873016 -6.18939781189,0.971877217293,9.47604560852 -6.16242361069,0.971892654896,9.49762916565 -6.11245536804,0.967913031578,9.48519802094 -6.08048295975,0.967929780483,9.50076770782 -6.0615067482,0.96994382143,9.53634262085 -6.01453876495,0.965963542461,9.52791213989 -5.9515748024,0.959986746311,9.49447536469 -5.95558261871,0.963990807533,9.53227329254 -5.93960571289,0.966004133224,9.57185459137 -5.93262672424,0.971015810966,9.62742996216 -5.89365673065,0.969034075737,9.63199615479 -5.97265338898,0.991027891636,9.82660102844 -5.90868997574,0.984051167965,9.79016876221 -5.88170719147,0.98206192255,9.78094673157 -5.88972330093,0.989070236683,9.86153697968 -5.91473531723,1.00107514858,9.97212600708 -5.89176034927,1.00209009647,10.003704071 -5.89177894592,1.00910019875,10.0742874146 -5.89779615402,1.01610922813,10.1558704376 -5.9078130722,1.02511751652,10.2464485168 -5.91581964493,1.03012084961,10.2962446213 -5.94283103943,1.04212546349,10.4168319702 -5.92385530472,1.04513955116,10.4584102631 -5.92287445068,1.05215001106,10.531993866 -5.93289089203,1.06115829945,10.6265735626 -5.92891120911,1.06716942787,10.6971530914 -5.94891500473,1.07517027855,10.7719488144 -5.94093608856,1.08118212223,10.8355331421 -5.93995571136,1.08819270134,10.9141111374 -5.93297672272,1.09420442581,10.9816923141 -5.92199850082,1.09921693802,11.0432691574 -5.92001819611,1.10622751713,11.1208553314 -5.91103982925,1.11223983765,11.1884288788 -5.92104673386,1.11824285984,11.2482261658 -5.94106006622,1.13024902344,11.3708114624 -5.94307851791,1.13925886154,11.4603948593 -5.90010976791,1.13727796078,11.464966774 -5.88213443756,1.14129221439,11.5185403824 -5.90114784241,1.15429830551,11.6421356201 -5.91216373444,1.16530656815,11.7547130585 -6.0111451149,1.19229161739,11.9965200424 -6.02815961838,1.20429849625,12.1231069565 -5.93520498276,1.19132769108,12.0296764374 -5.90623235703,1.19334387779,12.0652513504 -5.98123025894,1.22033917904,12.3138456345 -3.67191791534,0.679822266102,7.66789197922 -3.65894150734,0.681835174561,7.7014746666 -3.59297037125,0.668853700161,7.59425258636 -3.54900288582,0.66387283802,7.56183052063 -3.51403331757,0.661890387535,7.54940032959 -3.49505877495,0.662904381752,7.56898498535 -3.45708990097,0.658922374249,7.54856061935 -3.42212033272,0.655939757824,7.53413677216 -3.40813469887,0.655947983265,7.53591537476 -3.36916589737,0.651966035366,7.51149511337 -3.34019470215,0.649982213974,7.50907421112 -3.31222295761,0.648998260498,7.50964736938 -3.28525090218,0.64801388979,7.51122808456 -3.24828195572,0.645031630993,7.48980760574 -3.22530913353,0.645046710968,7.50138044357 -3.19532728195,0.640057682991,7.46217870712 -3.15935897827,0.637075603008,7.44473838806 -3.1393840313,0.638089537621,7.45933532715 -3.12140989304,0.639103531837,7.48191165924 -3.09443831444,0.638119399548,7.48348474503 -3.06746673584,0.637135148048,7.4840631485 -3.04449367523,0.637149989605,7.49364566803 -3.02650904655,0.635158896446,7.48343086243 -3.00253629684,0.635173857212,7.49001598358 -2.97556495667,0.634189784527,7.49158525467 -2.95459079742,0.635204017162,7.50417995453 -2.92662024498,0.6342202425,7.5037446022 -2.89664959908,0.632236659527,7.49631977081 -2.8806643486,0.631244957447,7.48911190033 -2.85669159889,0.630260050297,7.49569416046 -2.83371829987,0.630274832249,7.50428056717 -2.8147444725,0.632288813591,7.52386474609 -2.78077530861,0.629306197166,7.50643062592 -2.75780248642,0.629320979118,7.51501607895 -2.74082756042,0.631334543228,7.53960466385 -2.7208442688,0.628343999386,7.52338123322 -2.70287013054,0.630357801914,7.54596614838 -2.67289924622,0.628373980522,7.53554821014 -2.65192604065,0.629388570786,7.55112695694 -2.62695431709,0.628403961658,7.55570363998 -2.59798288345,0.627419829369,7.54629230499 -2.58100914955,0.629433691502,7.57486486435 -2.57002234459,0.629440963268,7.58065795898 -2.40524625778,0.642561137676,7.76010942459 -2.39227056503,0.646574020386,7.80369186401 -2.37629580498,0.649587392807,7.83727884293 -2.35335445404,0.663617730141,7.98423433304 -2.33338093758,0.665631830692,8.00682163239 -2.31442737579,0.676655948162,8.12699699402 -2.30045294762,0.681669354439,8.17656898499 -2.29147577286,0.68768119812,8.24016284943 -2.29548478127,0.693685412407,8.30296039581 -2.28150963783,0.698698461056,8.35354137421 -2.27253293991,0.705710470676,8.42213058472 -2.25455927849,0.708724439144,8.46170520782 -2.24558210373,0.715736269951,8.53130054474 -2.23060750961,0.720749437809,8.5818862915 -2.21963143349,0.727761924267,8.65046691895 -2.2196419239,0.732767224312,8.70725631714 -2.21066570282,0.740779280663,8.78584003448 -2.19868946075,0.747791707516,8.85143375397 -2.18271517754,0.752805233002,8.90601348877 -2.17473816872,0.760817050934,8.99359989166 -2.1607632637,0.767830014229,9.05818557739 -2.1667714119,0.776833891869,9.14498233795 -2.15879440308,0.785845696926,9.23757076263 -2.14581918716,0.792858541012,9.3121547699 -2.12690734863,0.840903162956,9.77950572968 -2.13791418076,0.852905988693,9.90130615234 -2.13493561745,0.866916716099,10.0358982086 -2.13295698166,0.881927490234,10.1824808121 -2.12797904015,0.894938588142,10.315073967 -2.12200188637,0.908950209618,10.4516544342 -2.107026577,0.917963266373,10.5432453156 -2.1080365181,0.927968144417,10.6330404282 -2.09106278419,0.935981750488,10.7226228714 -2.58695030212,1.24890530109,13.6748962402 -2.56297826767,1.25992035866,13.7824811935 -2.5310087204,1.26593673229,13.8490657806 -2.53102946281,1.29094731808,14.0986480713 -2.51004648209,1.29195654392,14.1084394455 -2.46608066559,1.29197537899,14.118019104 -2.43611049652,1.3009916544,14.2076015472 -2.43313193321,1.32700240612,14.4561920166 -2.40116262436,1.33501887321,14.5417776108 -2.36319518089,1.34003663063,14.5993537903 -2.30523371696,1.33205807209,14.5279350281 -2.2752532959,1.3270689249,14.4837284088 -2.23628616333,1.33208692074,14.5363035202 -2.22131156921,1.35310006142,14.7408924103 -2.19434094429,1.36711573601,14.8794717789 -2.17236852646,1.38513028622,15.0550575256 -2.13939905167,1.39414668083,15.1556472778 -2.0864367485,1.39116740227,15.1292200089 -2.08544707298,1.40817272663,15.2950162888 -2.02148771286,1.39619517326,15.1815948486 -1.99651622772,1.41421020031,15.3581809998 -1.96154785156,1.42422711849,15.4647674561 -1.92258059978,1.43224477768,15.5453510284 -1.88561308384,1.44326233864,15.6519298553 -2.03357744217,1.59323918819,17.0847473145 -1.98161411285,1.59425926208,17.1003322601 -1.93364977837,1.59927868843,17.155916214 -1.88168692589,1.60129892826,17.1824913025 -1.82672476768,1.60031950474,17.1780738831 -1.77276217937,1.60033988953,17.175661087 -1.71780025959,1.59936070442,17.175239563 -1.68881976604,1.59737145901,17.1590270996 -1.63785612583,1.59939110279,17.1856155396 -1.58589327335,1.60241127014,17.2161941528 -1.54592680931,1.61942899227,17.379776001 -1.50096130371,1.63044762611,17.488363266 -1.45099794865,1.6364672184,17.5559425354 -1.42501628399,1.63847720623,17.5727367401 -1.36305654049,1.6294990778,17.4933166504 -1.3050955534,1.62552022934,17.458896637 -1.2501333952,1.6245405674,17.4544830322 -1.19617128372,1.62656080723,17.4760608673 -1.1422085762,1.6265809536,17.4796524048 -1.08724677563,1.62660133839,17.4822349548 -1.06026554108,1.62761151791,17.4920253754 -1.00530350208,1.62763190269,17.4906101227 -0.950341701508,1.62765228748,17.4991912842 -0.893380463123,1.62467300892,17.4677715302 -0.838418364525,1.62269318104,17.4583568573 -0.78345644474,1.62271344662,17.4589385986 -0.728494405746,1.62173366547,17.4505252838 -0.70151335001,1.6237436533,17.4653148651 -0.645551979542,1.62176418304,17.4508953094 -0.590589940548,1.62078440189,17.4404811859 -0.535628139973,1.62080466747,17.446062088 -0.481665641069,1.62182438374,17.4516525269 -0.426703631878,1.61984443665,17.4382362366 -0.370742350817,1.61786496639,17.4218158722 -0.344760686159,1.62187445164,17.4556121826 -0.288799375296,1.61889481544,17.4341907501 -0.234836965799,1.62091469765,17.4527797699 -0.179875105619,1.62093472481,17.4463634491 -0.124913230538,1.61995458603,17.4369487762 -0.0699514299631,1.62097465992,17.4505310059 -0.0429701656103,1.62098443508,17.4483261108 --0.00399714056402,1.63300144672,16.5239677429 --0.0559599585831,1.63202083111,16.5195522308 --0.107922799885,1.63304018974,16.5271377563 --0.159885749221,1.63705933094,16.557723999 --0.211848452687,1.63307869434,16.5253067017 --0.263811320066,1.63409793377,16.5278930664 --0.289792776108,1.63510751724,16.5356864929 --0.341755717993,1.63612675667,16.5442733765 --0.393718481064,1.63514590263,16.5338573456 --0.445681601763,1.63716495037,16.5544471741 --0.497644454241,1.63718402386,16.5530319214 --0.549607217312,1.63620328903,16.5386161804 --0.601570188999,1.63722217083,16.5442047119 --0.628551244736,1.64023184776,16.5669975281 --0.679514586926,1.63825070858,16.546585083 --0.731477439404,1.63726961613,16.5421714783 --0.784439861774,1.63928902149,16.5507545471 --0.835403263569,1.63830757141,16.5383453369 --0.88836556673,1.63832676411,16.5409259796 --0.940328598022,1.6393456459,16.5435161591 --0.965310633183,1.63835477829,16.5343132019 --1.01827299595,1.63937389851,16.5388965607 --1.06923651695,1.63839232922,16.5284881592 --1.12219882011,1.63941144943,16.5310707092 --1.1761610508,1.6424305439,16.5526561737 --1.25210630894,1.64045810699,16.5270423889 --1.35803127289,1.64249587059,16.5352115631 --1.41099393368,1.64351463318,16.5428009033 --1.46395683289,1.64453339577,16.5513877869 --1.51591968536,1.64455199242,16.5439758301 --1.56988215446,1.64757072926,16.5605640411 --1.59786295891,1.64958047867,16.5763568878 --1.64982616901,1.6495988369,16.5739479065 --1.70278894901,1.65061736107,16.5805397034 --1.7577508688,1.65363633633,16.596124649 --1.81171321869,1.65565502644,16.6067123413 --1.8626768589,1.65467321873,16.5943031311 --1.9176388979,1.65669202805,16.6098918915 --1.94462013245,1.65770125389,16.615688324 --1.99858248234,1.65871989727,16.6192722321 --2.05354499817,1.66273856163,16.6398658752 --2.10850667953,1.66375744343,16.6474475861 --2.16246962547,1.6657756567,16.6600456238 --2.21743202209,1.66879439354,16.6716327667 --2.27039456367,1.66881263256,16.6662197113 --2.29937529564,1.67082214355,16.6820163727 --2.35533714294,1.67384088039,16.6986026764 --2.40830016136,1.67385911942,16.6941928864 --2.46226263046,1.67487740517,16.6957836151 --2.52022385597,1.67889642715,16.7213687897 --2.57418656349,1.6799145937,16.7229614258 --2.60116791725,1.68092358112,16.7247581482 --2.6581299305,1.68394219875,16.745349884 --2.7120923996,1.6849603653,16.7459411621 --2.76705503464,1.68697869778,16.7505302429 --2.82401657104,1.68899726868,16.76512146 --2.87797927856,1.69001531601,16.7617092133 --2.93494105339,1.69303381443,16.7752971649 --2.96492147446,1.69504332542,16.7920951843 --3.0208837986,1.69706141949,16.8016891479 --3.07284736633,1.69707894325,16.7882804871 --3.12980890274,1.69909739494,16.7978687286 --3.18177247047,1.6991147995,16.7854614258 --3.23773479462,1.70013296604,16.7900524139 --3.29669594765,1.70415151119,16.8086395264 --3.32567715645,1.70616066456,16.8194408417 --3.38063931465,1.70617866516,16.8160266876 --3.43860125542,1.71019685268,16.8316230774 --3.49356365204,1.71021461487,16.8282108307 --3.5495262146,1.71223247051,16.8308029175 --3.60548853874,1.71425044537,16.8343963623 --3.63446950912,1.71525943279,16.8401927948 --3.69543027878,1.71927797794,16.8657855988 --3.75239253044,1.7212959528,16.8703784943 --3.8073554039,1.72231328487,16.8679714203 --3.86531710625,1.72533142567,16.8745613098 --3.92427873611,1.72734940052,16.8871536255 --3.98124098778,1.72936725616,16.8917503357 --4.01222133636,1.73137652874,16.9025440216 --4.07218265533,1.73539447784,16.9191398621 --4.1301445961,1.73741233349,16.9247303009 --4.1881070137,1.73943006992,16.9323272705 --4.25006771088,1.74344825745,16.9539222717 --4.30802965164,1.74546599388,16.9555110931 --4.36599159241,1.74748373032,16.9581012726 --4.39897155762,1.75049293041,16.9769020081 --4.45393466949,1.75151014328,16.9674930573 --4.51289653778,1.75352776051,16.9740867615 --4.57185840607,1.75554525852,16.980682373 --4.6258225441,1.75656211376,16.9682769775 --4.68278455734,1.75757920742,16.967874527 --4.74174690247,1.76059663296,16.9724674225 --4.77272748947,1.76160562038,16.9782619476 --4.83168935776,1.76362299919,16.9818553925 --4.88865232468,1.76564002037,16.9814567566 --4.94761419296,1.76765739918,16.9820461273 --5.00057840347,1.76767361164,16.9666461945 --5.06653833389,1.7726919651,16.9902362823 --5.09651899338,1.7737005949,16.9930343628 --5.15248250961,1.77471721172,16.9866333008 --5.2304391861,1.78373706341,17.0492267609 --5.28640222549,1.78475368023,17.0398235321 --5.35236263275,1.78977179527,17.0614185333 --5.40032815933,1.7877869606,17.0270137787 --5.40130805969,1.76879513264,16.8446063995 --5.39130115509,1.75479769707,16.7224006653 --5.44026613235,1.75381302834,16.6939964294 --5.48823213577,1.75182819366,16.6625919342 --5.55519247055,1.75684607029,16.6881866455 --5.6081571579,1.75786185265,16.6737880707 --5.65612268448,1.75587677956,16.6413822174 --5.7060880661,1.75589203835,16.616979599 --5.74006795883,1.7579010725,16.630777359 --5.79103326797,1.75791633129,16.6083755493 --5.84399795532,1.75793194771,16.5909690857 --5.89896154404,1.75894773006,16.5795650482 --5.95392560959,1.75996363163,16.5681629181 --6.01188850403,1.76097977161,16.5637550354 --6.0388712883,1.76198744774,16.5585594177 --6.09283542633,1.76300299168,16.5441551208 --6.1468000412,1.76301848888,16.5307559967 --6.20376348495,1.76503443718,16.5213470459 --6.26172685623,1.76705026627,16.5189476013 --6.32268953323,1.76906657219,16.5205421448 --6.38165283203,1.77208244801,16.5201454163 --6.40863466263,1.77209019661,16.5099372864 --6.46060037613,1.77210497856,16.4915409088 --6.51956367493,1.77412080765,16.4891395569 --6.56653022766,1.77213490009,16.4557361603 --6.61649560928,1.77214944363,16.4283294678 --6.67745876312,1.77416539192,16.4299278259 --6.73042392731,1.7751802206,16.4115257263 --6.7654042244,1.77818882465,16.4233283997 --6.81637048721,1.77820312977,16.4009284973 --6.87133455276,1.77821815014,16.3865261078 --6.93129777908,1.78123378754,16.3831214905 --6.99026155472,1.78324913979,16.3787212372 --7.04222726822,1.7832634449,16.3583221436 --7.07020950317,1.7842707634,16.3521232605 --7.12417507172,1.78428542614,16.3337173462 --7.17714071274,1.78529977798,16.3163223267 --7.23110580444,1.78531432152,16.2979164124 --7.28407144547,1.78632855415,16.2785167694 --7.33803701401,1.787342906,16.2611160278 --7.39200210571,1.78735721111,16.2427139282 --7.42098426819,1.78836464882,16.2385139465 --7.47095060349,1.78837835789,16.2121124268 --7.52391672134,1.78939223289,16.1937160492 --7.58088159561,1.79040682316,16.1823158264 --7.61585283279,1.78641831875,16.1239128113 --7.67681694031,1.78943324089,16.1205120087 --7.72978258133,1.78944706917,16.100112915 --7.75476646423,1.78945362568,16.0879154205 --7.81073141098,1.79046785831,16.073513031 --7.86869621277,1.79248225689,16.0631122589 --7.9356584549,1.7964977026,16.0717182159 --7.98162651062,1.79551029205,16.037317276 --8.04059028625,1.79752457142,16.0279159546 --8.06657409668,1.79753124714,16.0167179108 --8.11954116821,1.79854464531,15.9963188171 --8.17650604248,1.80055856705,15.9819164276 --8.2304725647,1.8005720377,15.96352005 --6.18503522873,1.29631447792,11.9029073715 --6.18501663208,1.28732156754,11.8125066757 --6.29596567154,1.3053432703,11.9311056137 --6.27596187592,1.29634428024,11.8479013443 --6.30293560028,1.2933549881,11.8084983826 --6.29691791534,1.28336143494,11.7070884705 --6.47984790802,1.31739187241,11.9577064514 --6.5218167305,1.31840419769,11.9443025589 --6.49680519104,1.30440819263,11.8098964691 --6.54577255249,1.30642139912,11.8094921112 --6.40580224991,1.27040731907,11.5142774582 --6.44977140427,1.2724199295,11.5078792572 --6.51773309708,1.2794355154,11.5424757004 --6.54770612717,1.27844643593,11.5090675354 --6.53069162369,1.2664513588,11.3946580887 --6.58965682983,1.27146553993,11.4152669907 --6.49667358398,1.24645757675,11.2120494843 --6.5366435051,1.24746954441,11.1996507645 --6.74356746674,1.28550183773,11.4702634811 --9.22185993195,1.81780922413,15.5771560669 --9.29382228851,1.82282364368,15.5867643356 --9.35478782654,1.82483673096,15.5753631592 --9.41075515747,1.82684910297,15.5579710007 --9.42974090576,1.82585406303,15.5347738266 --9.47371101379,1.82486510277,15.4953727722 --7.06635761261,1.30458498001,11.471663475 --7.07633590698,1.29859280586,11.406255722 --9.65960788727,1.83290374279,15.4681882858 --9.73057174683,1.83791744709,15.4727945328 --9.74754905701,1.83092474937,15.3913936615 --9.75953674316,1.82792901993,15.3561925888 --9.84649562836,1.83594441414,15.3847990036 --7.35715866089,1.31566202641,11.4100599289 --7.33614635468,1.30466616154,11.2986526489 --7.37711668015,1.30567729473,11.2832527161 --7.47307300568,1.317694664,11.3528671265 --7.40708208084,1.30069041252,11.2126512527 --7.4610490799,1.30470299721,11.2172546387 --7.55600547791,1.31672012806,11.2828636169 --7.57598209381,1.31372869015,11.235461235 --7.59695863724,1.31073725224,11.1900606155 --7.67192029953,1.31775212288,11.222659111 --7.71788978577,1.31976354122,11.213259697 --7.72987747192,1.31876802444,11.1920557022 --7.76185131073,1.3187776804,11.1626558304 --8.16072654724,1.38882780075,11.6593103409 --7.99075460434,1.3488150835,11.3388805389 --7.90076112747,1.32481145859,11.1354627609 --8.25164985657,1.3848555088,11.5531072617 --8.1916475296,1.36685490608,11.3926954269 --8.04967689514,1.33684265614,11.1574735641 --8.00167274475,1.32084345818,11.0170631409 --7.91867685318,1.29884064198,10.8286390305 --8.07661724091,1.32186353207,10.9722595215 --8.09959316254,1.31987190247,10.929854393 --8.54845809937,1.39692509174,11.4625253677 --8.67241668701,1.41694092751,11.5903396606 --8.77837085724,1.42895758152,11.6549510956 --8.77335548401,1.42196261883,11.5715456009 --8.63737392426,1.38995397091,11.3171224594 --8.80531311035,1.41397702694,11.4617424011 --8.73831367493,1.39497554302,11.3003311157 --8.9362449646,1.42500138283,11.4809551239 --8.76428127289,1.38998651505,11.2217216492 --8.80925273895,1.39199662209,11.2063264847 --8.87121963501,1.39700829983,11.2129383087 --11.3235683441,1.82825887203,14.2299470901 --9.04913902283,1.41603684425,11.2891530991 --8.84017753601,1.37302136421,10.9567184448 --9.05310535431,1.40404784679,11.1483469009 --9.11908054352,1.41305685043,11.1941595078 --9.09706878662,1.40206003189,11.0937461853 --9.08805465698,1.39506435394,11.0113420486 --9.25399494171,1.4180855751,11.1409664154 --9.19299411774,1.4010848999,10.9955511093 --9.25596141815,1.40609610081,11.0001592636 --9.22796058655,1.39809584618,10.9319562912 --9.36890888214,1.41611433029,11.0285787582 --9.42387771606,1.42012465,11.0211782455 --9.3998670578,1.41012728214,10.9227714539 --9.48682975769,1.41914045811,10.9533824921 --9.30885791779,1.38312888145,10.6779460907 --9.50779247284,1.41015207767,10.8375797272 --5.66373538971,0.756806850433,6.37333345413 --5.74521350861,0.686003565788,5.39795351028 --5.78618621826,0.690013349056,5.40154933929 --5.74617815018,0.681016683578,5.33014774323 --5.95412015915,0.711035847664,5.50697135925 --5.79514026642,0.685030400753,5.3235373497 --5.77112817764,0.678035199642,5.2671289444 --5.76511192322,0.675041258335,5.22772264481 --5.78009080887,0.675049006939,5.20731496811 --5.81306600571,0.677057921886,5.20391798019 --5.83404302597,0.678066015244,5.18850755692 --5.86102819443,0.681071102619,5.1963133812 --5.87400770187,0.680078566074,5.17390489578 --5.90198373795,0.682087004185,5.16550731659 --5.95095539093,0.687096834183,5.17510843277 --5.96993350983,0.687104642391,5.15770053864 --6.75837039948,0.746291935444,5.02450895309 --6.77934980392,0.747298836708,5.00610208511 --6.8273229599,0.75130712986,5.00770044327 --5.54556131363,0.57025128603,3.99662971497 --5.55055141449,0.570254802704,3.98642373085 --5.57253026962,0.571262121201,3.97603344917 --7.79276514053,0.83246922493,4.88358402252 --11.8459434509,1.35662603378,7.31644392014 --11.8649282455,1.35562837124,7.27604675293 --11.8419275284,1.35162854195,7.23584032059 --11.8539133072,1.34963071346,7.19144201279 --11.831905365,1.34463179111,7.12603187561 --11.851890564,1.34363424778,7.08663463593 --11.8298826218,1.3376352787,7.02222776413 --11.846868515,1.33763742447,6.98183393478 --11.8318586349,1.33263874054,6.92142295837 --11.8348531723,1.33163952827,6.89822626114 --11.8088464737,1.3256405592,6.83181190491 --11.8318300247,1.32564294338,6.79542016983 --11.8038244247,1.31864380836,6.72901010513 --11.8198108673,1.31864583492,6.68861532211 --11.7978029251,1.31264674664,6.62620639801 --11.8207874298,1.3126488924,6.58981180191 --11.7827882767,1.30664873123,6.54359912872 --11.8027734756,1.30665075779,6.50519943237 --11.7817668915,1.30165183544,6.44479465485 --12.0037155151,1.32665836811,6.51845788956 --11.8317346573,1.30265593529,6.37400007248 --11.9267072678,1.31165933609,6.37763118744 --11.9836921692,1.31766116619,6.38445043564 --12.0656661987,1.32566416264,6.37907028198 --12.133644104,1.33166658878,6.36568498611 --12.2176189423,1.33966934681,6.36030435562 --12.2566013336,1.34167122841,6.3319196701 --12.2595911026,1.33967208862,6.2835149765 --12.5225305557,1.36867785454,6.34599971771 --8.1122636795,0.816609978676,4.03930664062 --8.07325553894,0.810613334179,3.98688960075 --8.07724189758,0.809617400169,3.95648360252 --8.06422901154,0.805621266365,3.91706609726 --8.06221580505,0.804625093937,3.88466835022 --8.06220149994,0.802629172802,3.85225749016 --8.06519508362,0.802631139755,3.83805918694 --8.06318092346,0.800634920597,3.80565857887 --8.04316997528,0.796638667583,3.76424694061 --8.05515480042,0.796642720699,3.73783731461 --8.05314159393,0.79464662075,3.70543217659 --8.0541267395,0.793650448322,3.67503404617 --8.05411338806,0.791654288769,3.64362740517 --8.05110740662,0.790656208992,3.62642145157 --8.03709506989,0.787659883499,3.58901500702 --8.03808116913,0.78666383028,3.55759859085 --8.00407314301,0.780667424202,3.51219630241 --8.01105880737,0.780671358109,3.48378181458 --8.09603118896,0.789675354958,3.49140644073 --8.12001419067,0.79067915678,3.47100639343 --8.19299602509,0.798681139946,3.48782730103 --8.23797607422,0.802684903145,3.47542357445 --8.28395652771,0.807688355446,3.46504402161 --8.35493278503,0.814691841602,3.46365308762 --8.40691184998,0.819695234299,3.4542632103 --8.46189022064,0.824698448181,3.44587492943 --8.53887271881,0.83369988203,3.46270036697 --8.59585094452,0.838702976704,3.45431089401 --8.63883209229,0.842706024647,3.43991875648 --11.6753749847,1.20269417763,4.60607624054 --11.7013616562,1.20469474792,4.57267522812 --11.6643571854,1.19869565964,4.51526498795 --11.6843500137,1.19969570637,4.50207328796 --11.667342186,1.19569659233,4.45266675949 --11.6783313751,1.19569706917,4.41426801682 --11.6643238068,1.19269776344,4.36585760117 --11.6803121567,1.19269812107,4.32946062088 --11.6573057175,1.18769884109,4.27804803848 --11.6822938919,1.18969905376,4.24565839767 --11.6542921066,1.18569970131,4.21344184875 --11.6562833786,1.18369996548,4.17203998566 --11.6442756653,1.18070065975,4.12563371658 --11.6702632904,1.182700634,4.09324026108 --11.6422576904,1.17770147324,4.04183340073 --11.657245636,1.17770159245,4.0054359436 --11.6422395706,1.17470216751,3.95802354813 --11.6392354965,1.1737023592,3.93682670593 --11.6312265396,1.17070293427,3.89242005348 --11.6422166824,1.17070305347,3.85502290726 --11.641207695,1.16970324516,3.81362199783 --11.6292009354,1.16670370102,3.76821351051 --11.6281909943,1.16470396519,3.72681093216 --11.6311826706,1.16370403767,3.68640494347 --11.588183403,1.1577051878,3.65219187737 --11.4751882553,1.14370810986,3.57474803925 --11.4601812363,1.14070868492,3.53034639359 --11.4621725082,1.13970899582,3.4909453392 --11.4681625366,1.13870894909,3.45254230499 --11.4601554871,1.13670933247,3.4101369381 --11.460146904,1.13470959663,3.36972904205 --11.4641418457,1.13470947742,3.35153412819 --11.4611330032,1.13370966911,3.31113290787 --11.4491262436,1.13071012497,3.26772451401 --11.4471178055,1.12871026993,3.22731876373 --11.4521093369,1.12871015072,3.18891406059 --11.4371023178,1.12571060658,3.14550948143 --11.4570922852,1.12670993805,3.11211633682 --11.4490880966,1.12471020222,3.08990931511 --11.4300823212,1.12171077728,3.04550099373 --11.4620714188,1.12470960617,3.01510858536 --11.427066803,1.1187107563,2.96669650078 --11.4430561066,1.11971008778,2.93129181862 --11.4310493469,1.11771023273,2.88989233971 --11.4160423279,1.11471068859,2.84647774696 --11.4090394974,1.11371088028,2.82527351379 --11.4030323029,1.11171102524,2.78486680984 --11.4260225296,1.11270964146,2.75247645378 --11.4230146408,1.11170959473,2.71307229996 --11.4110078812,1.10970973969,2.67166614532 --11.4070005417,1.10770964622,2.63226222992 --11.4319953918,1.10970830917,2.61906957626 --11.4699831009,1.11370611191,2.58968043327 --11.491973877,1.11470460892,2.55628538132 --11.5299634933,1.11870229244,2.52689981461 --11.5729522705,1.12269949913,2.49750685692 --11.5749444962,1.12169885635,2.46011352539 --11.5249414444,1.11470067501,2.40968489647 --11.5309381485,1.11570012569,2.39249300957 --11.5009326935,1.11070096493,2.34707379341 --11.6869096756,1.13069033623,2.34874296188 --11.7608976364,1.13868534565,2.32536697388 --11.7808895111,1.13968336582,2.28996634483 --11.8098802567,1.14268064499,2.25758242607 --11.8658704758,1.14767634869,2.22919559479 --11.861866951,1.14667594433,2.20899486542 --11.7928657532,1.13867878914,2.1565682888 --11.4338855743,1.09669923782,2.04802250862 --11.5328712463,1.10769236088,2.02966380119 --11.5218648911,1.105692029,1.98925244808 --11.4868612289,1.10069322586,1.94483447075 --11.3608636856,1.08570039272,1.88438165188 --11.3638591766,1.08569967747,1.8671913147 --11.35085392,1.08369970322,1.82677364349 --11.5058364868,1.10068845749,1.81643366814 --11.5378293991,1.10268509388,1.78404200077 --11.9517965317,1.14865577221,1.81480324268 --11.5738134384,1.10568034649,1.71525847912 --11.4658136368,1.09268653393,1.65980684757 --11.36581707,1.08169305325,1.62556743622 --11.3778095245,1.08169102669,1.59016668797 --11.3718042374,1.08069038391,1.55276703835 --11.4257946014,1.08668506145,1.52338111401 --11.4787864685,1.0916800499,1.49400019646 --11.4837808609,1.09167826176,1.45760071278 --11.4997768402,1.09267628193,1.44140779972 --11.5007696152,1.09267473221,1.40400218964 --11.4917650223,1.0906740427,1.36559581757 --11.4927597046,1.09067237377,1.32818925381 --11.4777545929,1.0886721611,1.28978717327 --11.3797531128,1.07667839527,1.24034154415 --11.3487491608,1.07267951965,1.19992637634 --11.376742363,1.07567572594,1.16653382778 --11.1717481613,1.0526920557,1.12424576283 --11.2037401199,1.05568802357,1.09185576439 --11.5077228546,1.0886605978,1.08958351612 --11.3217248917,1.06767487526,1.03209590912 --11.5337114334,1.0906547308,1.01778316498 --11.2267179489,1.05668008327,0.95025485754 --11.2857093811,1.0626732111,0.9198756814 --11.3227062225,1.06666898727,0.905694007874 --11.238702774,1.05667495728,0.861251533031 --11.2636976242,1.05967104435,0.827863335609 --11.4016885757,1.0746563673,0.803517043591 --11.1676902771,1.04767656326,0.74700820446 --11.1326856613,1.04367816448,0.708591341972 --11.2546806335,1.05766558647,0.70044285059 --11.2376756668,1.05466544628,0.663031041622 --11.2386703491,1.05466341972,0.627633333206 --11.3166637421,1.06265377998,0.597265660763 --11.2156610489,1.05166184902,0.553811252117 --11.2016563416,1.04966127872,0.517405211926 --11.1526527405,1.04466438293,0.478983223438 --11.2306499481,1.05265545845,0.465816855431 --11.260643959,1.05565023422,0.431424260139 --11.3296394348,1.06364071369,0.399050623178 --11.3056354523,1.06064116955,0.361635416746 --11.2736320496,1.05664229393,0.324218958616 --11.3316268921,1.06263375282,0.290842264891 --11.2136230469,1.04964435101,0.250389844179 --11.3156204224,1.06063199043,0.236231759191 --11.362616539,1.06562435627,0.201849624515 --11.2766122818,1.05663144588,0.162401512265 --11.2716083527,1.05562973022,0.127003163099 --11.3336048126,1.06262004375,0.0926267728209 --11.2396011353,1.05162835121,0.0541779100895 --11.3135976791,1.05961716175,0.0198077391833 --11.2605953217,1.05362200737,0.000578714592848 --11.2525911331,1.05362045765,-0.034822512418 --11.3785896301,1.06660282612,-0.0691681280732 --11.3155851364,1.0596075058,-0.106608390808 --11.3815832138,1.06759679317,-0.141978576779 --11.26557827,1.05460810661,-0.178435429931 --11.456577301,1.07558166981,-0.214753910899 --11.3515748978,1.06359314919,-0.231996133924 --11.2185697556,1.0496070385,-0.267462611198 --11.3925695419,1.06858217716,-0.304786413908 --11.4995689392,1.08056545258,-0.342138200998 --11.4475650787,1.07456874847,-0.37857273221 --11.3235588074,1.06058180332,-0.412026077509 --11.3385572433,1.06257665157,-0.448423057795 --11.3805570602,1.06756949425,-0.467607200146 --11.3975553513,1.06956398487,-0.503999590874 --11.3325510025,1.06256937981,-0.538434207439 --11.3995504379,1.06955707073,-0.576807320118 --11.4055480957,1.07055282593,-0.613206684589 --11.2975416183,1.0585641861,-0.645664572716 --11.2625389099,1.05556571484,-0.680083572865 --11.344540596,1.06455266476,-0.701242566109 --11.3525390625,1.06554806232,-0.737640678883 --11.4325399399,1.0745331049,-0.778008282185 --11.4565391541,1.07752597332,-0.816407740116 --11.3895349503,1.0705319643,-0.848839223385 --11.3855333328,1.06952869892,-0.885247707367 --11.6135416031,1.09549152851,-0.935538887978 --11.5785398483,1.09149479866,-0.951756358147 --11.5535373688,1.08949434757,-0.987173080444 --11.519534111,1.08549535275,-1.02159142494 --11.5825376511,1.09248173237,-1.06296348572 --11.5525341034,1.08948206902,-1.09838879108 --11.473528862,1.08148992062,-1.12882804871 --11.5165319443,1.08648133278,-1.15000140667 --11.5205307007,1.08747649193,-1.1874049902 --11.4565258026,1.08048224449,-1.21884095669 --11.5125284195,1.08746898174,-1.2612234354 --11.6005334854,1.09745061398,-1.30658555031 --11.5885324478,1.09644818306,-1.34198760986 --11.74954319,1.11441743374,-1.39632225037 --11.7635450363,1.11641287804,-1.41651594639 --11.6055335999,1.09943377972,-1.43698918819 --11.6355352402,1.10242414474,-1.47737538815 --11.5855321884,1.09742760658,-1.50980961323 --11.5695314407,1.09642553329,-1.54522025585 --11.4095191956,1.07944774628,-1.56269240379 --11.3775157928,1.07544851303,-1.59611701965 --11.3515148163,1.07345056534,-1.61133241653 --11.3535146713,1.07344567776,-1.64772903919 --11.5005264282,1.09041535854,-1.70406675339 --11.5425319672,1.09640324116,-1.74644553661 --11.4295215607,1.08441781998,-1.76890993118 --11.5275316238,1.09539568424,-1.81926143169 --11.6025390625,1.10437703133,-1.86763095856 --11.6865472794,1.11435937881,-1.89879369736 --11.6225423813,1.10736548901,-1.92722785473 --11.471529007,1.09138762951,-1.94170033932 --11.4525289536,1.08938574791,-1.9761133194 --11.5235366821,1.09836745262,-2.0244808197 --11.6315488815,1.11134195328,-2.07983589172 --11.5585432053,1.1033500433,-2.10526943207 --11.5735445023,1.1053442955,-2.1274728775 --11.694560051,1.12031579018,-2.18581771851 --11.5575466156,1.10533607006,-2.20028686523 --11.5665493011,1.10732865334,-2.23968577385 --11.6095561981,1.11231458187,-2.28506565094 --11.5775556564,1.10931479931,-2.31748628616 --11.648566246,1.11829507351,-2.36885666847 --11.6725692749,1.12128734589,-2.3920416832 --11.6775722504,1.12228024006,-2.431442976 --11.6635732651,1.1222769022,-2.46684980392 --11.8455991745,1.14323413372,-2.54116249084 --11.7595920563,1.13424491882,-2.56361436844 --12.0406303406,1.16718125343,-2.65987920761 --12.011631012,1.16418027878,-2.69329214096 --12.0276346207,1.16717350483,-2.71648573875 --12.0256385803,1.16716694832,-2.75588917732 --12.038643837,1.17015719414,-2.79828238487 --11.9916419983,1.1651597023,-2.82871580124 --12.0436534882,1.17214167118,-2.88009214401 --12.0386571884,1.17213535309,-2.91950154305 --12.0576648712,1.17612397671,-2.9638941288 --12.0436649323,1.17412340641,-2.98009514809 --12.089676857,1.18110597134,-3.03147888184 --12.2967128754,1.20505332947,-3.12077450752 --12.1796998978,1.19307112694,-3.13424038887 --12.4007396698,1.2190144062,-3.22852611542 --12.407746315,1.2210047245,-3.27192497253 --12.3667430878,1.21700954437,-3.28315258026 --12.18171978,1.19704294205,-3.27764415741 --12.210729599,1.2010281086,-3.3270406723 --12.1857318878,1.20002579689,-3.3614525795 --12.559800148,1.24393200874,-3.50066280365 --12.4037809372,1.2269589901,-3.50214838982 --12.3857841492,1.22595453262,-3.53956151009 --12.5938243866,1.25090181828,-3.61665344238 --13.4189748764,1.34669947624,-3.88462042809 --13.6090183258,1.36964428425,-3.98292207718 --12.6738605499,1.26385545731,-3.76781821251 --13.3669948578,1.3446803093,-4.00785779953 --13.4560203552,1.3556483984,-4.07921266556 --13.4710330963,1.35863399506,-4.12960481644 --13.3200101852,1.34266531467,-4.10888814926 --13.290014267,1.34066212177,-4.14530086517 --13.2820224762,1.34065341949,-4.18870687485 --13.4400634766,1.36060333252,-4.28303098679 --13.424071312,1.36059629917,-4.32443904877 --13.4320840836,1.36258304119,-4.37384033203 --13.8101701736,1.40747654438,-4.53803396225 --16.2266769409,1.68985104561,-5.3501367569 --13.7461748123,1.40247488022,-4.5896692276 --13.7381858826,1.40346503258,-4.63507556915 --16.1727085114,1.68782508373,-5.47416496277 --16.1857299805,1.69180583954,-5.53455400467 --16.4127998352,1.7197303772,-5.66683101654 --16.3187961578,1.71073830128,-5.69328355789 --16.4608364105,1.72869265079,-5.76940250397 --16.6138916016,1.74863517284,-5.87971925735 --16.5969085693,1.74862253666,-5.93212509155 --16.5489177704,1.74561798573,-5.97455263138 --16.4779205322,1.73861968517,-6.00899553299 --16.3549137115,1.72663605213,-6.02345943451 --16.2859172821,1.7206376791,-6.05689573288 --16.1368942261,1.70466971397,-6.03318357468 --16.2749462128,1.72261464596,-6.14050292969 --16.1579380035,1.71062982082,-6.15596818924 --16.241979599,1.72358894348,-6.24532222748 --14.6196022034,1.53402721882,-5.69762611389 --14.7176437378,1.54698467255,-5.78696918488 --14.6316394806,1.53899395466,-5.80741739273 --14.5266218185,1.52801644802,-5.79367589951 --14.7106866837,1.55194854736,-5.91797780991 --14.948764801,1.5818644762,-6.06424427032 --15.1488361359,1.60779035091,-6.19753265381 --15.2368783951,1.62074828148,-6.28788375854 --15.1788825989,1.61574840546,-6.3213224411 --15.1859045029,1.61872982979,-6.37971735001 --15.4409837723,1.65064573288,-6.51177740097 --15.5450325012,1.66559743881,-6.61111688614 --15.3830099106,1.64862835407,-6.60160923004 --15.4020366669,1.65360534191,-6.66599416733 --15.6111154556,1.68052434921,-6.81127548218 --15.7071647644,1.69447684288,-6.91062355042 --15.8282232285,1.71242105961,-7.02196025848 --15.9662742615,1.72936952114,-7.11007547379 --16.0393199921,1.74132752419,-7.20243883133 --16.2414016724,1.76824533939,-7.3507194519 --16.4244823456,1.79316818714,-7.49301528931 --16.5575466156,1.81210589409,-7.61433792114 --16.8156509399,1.84600329399,-7.793592453 --16.8046760559,1.84798562527,-7.85199451447 --17.3228473663,1.91180896759,-8.11989593506 --17.1988391876,1.89982652664,-8.12936782837 --17.2298793793,1.9067940712,-8.20975017548 --17.3789539337,1.9277228117,-8.34606647491 --18.1782398224,2.0284383297,-8.78799629211 --18.1762714386,2.03141403198,-8.85739612579 --18.1833057404,2.0353872776,-8.93078804016 --18.60846138,2.09023308754,-9.17074394226 --18.6775169373,2.10118436813,-9.27609825134 --18.7715854645,2.11712646484,-9.39544487 --19.1807575226,2.17096161842,-9.66959953308 --19.0967674255,2.16396260262,-9.70405101776 --19.3698978424,2.20184159279,-9.91528606415 --19.5830097198,2.2317404747,-10.0985546112 --19.638048172,2.24070668221,-10.1657247543 --19.8731689453,2.27359628677,-10.3629798889 --20.0052566528,2.29352021217,-10.51030159 --19.9592819214,2.29150676727,-10.5657215118 --20.0643615723,2.30943918228,-10.7010593414 --20.1704425812,2.32637095451,-10.8373937607 --20.2195034027,2.33632254601,-10.9447612762 --20.4836235046,2.37221240997,-11.1258010864 --20.5146789551,2.38016963005,-11.2251787186 --20.48371315,2.38014888763,-11.2915916443 --20.4837589264,2.38511610031,-11.375992775 --20.5758399963,2.40104985237,-11.5103349686 --20.5438728333,2.40102910995,-11.576748848 --20.5659065247,2.40600419044,-11.631937027 --20.5489463806,2.40897750854,-11.7073440552 --20.5129776001,2.40895795822,-11.7717599869 --20.5150279999,2.41292357445,-11.8581542969 --20.4960689545,2.41589689255,-11.9335660934 --20.4591026306,2.41587734222,-11.9979839325 --20.4481468201,2.41884756088,-12.0773868561 --20.423160553,2.41784024239,-12.1055984497 --20.380191803,2.41682267189,-12.1670227051 --20.3632335663,2.4197947979,-12.2434301376 --20.3972969055,2.42874693871,-12.3508090973 --20.3833408356,2.43171787262,-12.4292125702 --20.3923969269,2.43867897987,-12.5226068497 --20.4254608154,2.44763064384,-12.6299819946 --20.4705066681,2.45559501648,-12.7021551132 --20.5215797424,2.46753907204,-12.8215198517 --20.5446414948,2.47549366951,-12.9249019623 --20.5657043457,2.48344874382,-13.0272846222 --20.5257396698,2.48342823982,-13.092707634 --20.5878219604,2.49636602402,-13.2220678329 --20.5218467712,2.49335575104,-13.2715072632 --20.5128688812,2.49534130096,-13.3107089996 --20.4498958588,2.49232983589,-13.3621482849 --20.3959255219,2.49031543732,-13.4175748825 --20.3689689636,2.49228858948,-13.4919919968 --20.3190002441,2.49127173424,-13.5514230728 --20.2440223694,2.48726582527,-13.5938673019 --20.2420768738,2.492228508,-13.6842660904 --20.2491073608,2.49620652199,-13.7344589233 --20.2121448517,2.49618411064,-13.8018779755 --20.1841888428,2.49815797806,-13.8752918243 --20.1692409515,2.50212550163,-13.9587020874 --20.1062679291,2.49911379814,-14.0091409683 --20.1043224335,2.50507593155,-14.1005382538 --20.1243915558,2.51302790642,-14.2079229355 --20.1304244995,2.51700544357,-14.2591171265 --20.1154766083,2.52097225189,-14.3435277939 --20.1635608673,2.53391075134,-14.4718942642 --20.7239093781,2.61561751366,-14.9649391174 --20.7249736786,2.62157487869,-15.0643367767 --20.8030757904,2.63849711418,-15.2186822891 --20.6430568695,2.62352752686,-15.2031841278 --20.6951160431,2.63348221779,-15.290348053 --20.5951290131,2.62648558617,-15.3168077469 --20.5011425018,2.62048602104,-15.3482694626 --20.4201641083,2.61548113823,-15.3877162933 --20.3251781464,2.60848259926,-15.4171762466 --20.2441978455,2.60447788239,-15.4556236267 --20.1482124329,2.59747958183,-15.4840869904 --20.1122226715,2.59547543526,-15.5063076019 --20.0162372589,2.58947777748,-15.5337686539 --19.9382572174,2.58547186852,-15.57421875 --19.8522758484,2.57947015762,-15.607670784 --19.765291214,2.57446885109,-15.6401262283 --19.6893157959,2.57046246529,-15.6805715561 --19.6033306122,2.56446123123,-15.7130250931 --19.5243186951,2.55747818947,-15.7012777328 --19.4503421783,2.55347108841,-15.7427244186 --19.3723621368,2.54946637154,-15.780172348 --19.2793750763,2.5434691906,-15.8056316376 --19.1963920593,2.53846669197,-15.8390855789 --19.125415802,2.53545856476,-15.8825330734 --19.0654144287,2.53046679497,-15.88377285 --18.978427887,2.52446722984,-15.9122266769 --18.9044513702,2.52146100998,-15.951675415 --18.8324737549,2.51745414734,-15.9921197891 --18.7434864044,2.51245594025,-16.018579483 --18.6625041962,2.50745368004,-16.0510311127 --18.5835227966,2.50345039368,-16.0854854584 --18.5345249176,2.49945378304,-16.0947189331 --18.4605464935,2.49644827843,-16.1321659088 --18.3795623779,2.49144625664,-16.1636199951 --18.3105869293,2.48843884468,-16.2040596008 --18.2256011963,2.48343896866,-16.2325210571 --18.144618988,2.4794383049,-16.2619724274 --18.0776424408,2.4764289856,-16.3054199219 --18.0226402283,2.47243618965,-16.3076572418 --17.9476623535,2.46843218803,-16.3421058655 --17.8786849976,2.46542453766,-16.3825531006 --17.8077087402,2.46241855621,-16.4199981689 --17.7367286682,2.45941257477,-16.457447052 --17.6787605286,2.45839905739,-16.5068855286 --17.6297988892,2.4583799839,-16.5663261414 --17.5928096771,2.45737814903,-16.5825462341 --17.5408439636,2.45636177063,-16.6369800568 --17.4798736572,2.45534944534,-16.684425354 --17.4088954926,2.45234370232,-16.720872879 --17.3529281616,2.45132946968,-16.7713088989 --17.2989635468,2.45131349564,-16.8247489929 --17.2359905243,2.44930291176,-16.8691940308 --17.2080078125,2.44929552078,-16.8944129944 --17.1350288391,2.44629096985,-16.9288654327 --17.0840644836,2.44627356529,-16.9843025208 --17.0300998688,2.44625782967,-17.0367393494 --16.9631233215,2.44425034523,-17.0761852264 --16.9121627808,2.44423270226,-17.1316223145 --16.8311748505,2.43923330307,-17.1570796967 --16.8202056885,2.44221568108,-17.1992874146 --16.7652397156,2.44220042229,-17.2507286072 --16.6962623596,2.43919372559,-17.2881793976 --16.6463012695,2.44017601013,-17.3436107635 --16.5873317719,2.43916320801,-17.3910560608 --16.5413742065,2.44014239311,-17.4514884949 --16.4824066162,2.43912935257,-17.4989337921 --16.4444141388,2.43812870979,-17.5131587982 --16.3884487152,2.43711400032,-17.5636005402 --16.3384876251,2.43809533119,-17.6200370789 --16.27551651,2.43708539009,-17.6624832153 --16.2345619202,2.43906068802,-17.7289161682 --16.1876049042,2.44003987312,-17.7893543243 --16.1196289062,2.43803334236,-17.8258018494 --16.1136646271,2.44101119041,-17.8750076294 --16.0556983948,2.44099807739,-17.9224491119 --16.0107421875,2.44297575951,-17.9848842621 --15.9537773132,2.44296145439,-18.0343284607 --15.908821106,2.44393897057,-18.0967636108 --15.8488531113,2.44392681122,-18.1422042847 --15.7968921661,2.44390869141,-18.1976470947 --15.7819213867,2.44689273834,-18.2368583679 --15.7479763031,2.44986248016,-18.3122844696 --15.720038414,2.45482730865,-18.3957099915 --15.6710805893,2.45580720901,-18.4541473389 --15.6061086655,2.45479798317,-18.494594574 --15.3149261475,2.4149479866,-18.2702026367 --15.2348937988,2.4059779644,-18.2324581146 --15.1308832169,2.39799761772,-18.2249355316 --15.0899305344,2.40097308159,-18.2903671265 --15.0449752808,2.4029507637,-18.3518028259 --14.9749975204,2.39994645119,-18.3842582703 --14.8890028,2.39495372772,-18.3967247009 --14.8170223236,2.39295125008,-18.4251785278 --14.6979932785,2.38198399544,-18.3946628571 --14.5869274139,2.36703848839,-18.3159446716 --14.5800104141,2.37598824501,-18.4243564606 --14.4769973755,2.36800980568,-18.4128322601 --14.3970069885,2.36401438713,-18.4292926788 --14.3240232468,2.36101365089,-18.454750061 --14.228014946,2.35403060913,-18.4502220154 --14.1870183945,2.35203409195,-18.456451416 --14.1270484924,2.35102319717,-18.4989032745 --14.0460557938,2.34702920914,-18.5123653412 --13.9690666199,2.3430325985,-18.5308246613 --13.8610448837,2.33405971527,-18.5093097687 --13.7790498734,2.32906770706,-18.5197715759 --13.7060642242,2.32606840134,-18.5422286987 --13.6670684814,2.32407045364,-18.5504627228 --13.5800676346,2.31908249855,-18.5539283752 --13.4920654297,2.31309580803,-18.5553970337 --13.4050626755,2.30810832977,-18.5578651428 --13.3230657578,2.30311727524,-18.5663299561 --13.2620925903,2.30210900307,-18.6037807465 --13.2131328583,2.30409097672,-18.6572208405 --13.1621227264,2.3001036644,-18.6474628448 --13.0921382904,2.29710364342,-18.6709156036 --13.0411777496,2.29908704758,-18.722360611 --12.9651861191,2.29509162903,-18.737821579 --12.8881940842,2.29109716415,-18.7512817383 --12.8222150803,2.29009366035,-18.7807369232 --12.6360902786,2.26519298553,-18.6362800598 --12.4168758392,2.22835254669,-18.3796386719 --12.2237386703,2.20146131516,-18.2191829681 --12.1697692871,2.2014503479,-18.2606258392 --11.2028512955,2.04213428497,-17.1755313873 --11.1419124603,2.04610586166,-17.257188797 --11.097949028,2.04808926582,-17.3076343536 --11.0549860001,2.05007243156,-17.3580703735 --10.9919977188,2.04807400703,-17.3775234222 --10.880947113,2.03611922264,-17.3240146637 --11.7372274399,2.22923326492,-18.8540248871 --11.6762523651,2.22922706604,-18.8874797821 --11.616276741,2.22822022438,-18.9209289551 --11.5372753143,2.22423148155,-18.9243946075 --11.4432554245,2.21725702286,-18.9038734436 --11.3782730103,2.21525526047,-18.9293308258 --11.2992715836,2.21126723289,-18.9317970276 --11.2362928391,2.2102637291,-18.9602527618 --11.210310936,2.21125650406,-18.9834766388 --11.1393203735,2.20826053619,-18.9989376068 --11.0713329315,2.20626282692,-19.0173931122 --10.9823160172,2.1992855072,-19.000869751 --10.929350853,2.20027208328,-19.0463180542 --10.8393316269,2.19429636002,-19.0277957916 --10.788312912,2.18931484222,-19.0070362091 --10.7403535843,2.19129705429,-19.0594806671 --10.6763734818,2.19029521942,-19.0849380493 --10.6043787003,2.18730211258,-19.0954017639 --10.5474061966,2.18729376793,-19.1318492889 --10.4714069366,2.18430423737,-19.1363220215 --10.3944044113,2.18031692505,-19.1367874146 --10.3574047089,2.1783220768,-19.1390171051 --10.2914199829,2.17632293701,-19.1594772339 --10.2224292755,2.17432689667,-19.1749401093 --10.1564426422,2.17232894897,-19.1933956146 --10.0774364471,2.16834449768,-19.1888656616 --9.99342060089,2.16236543655,-19.1753406525 --9.94346046448,2.16434955597,-19.2247905731 --9.90746212006,2.16335391998,-19.2280216217 --9.82945632935,2.15836906433,-19.2244930267 --9.7714805603,2.15836262703,-19.256942749 --9.83170890808,2.18721985817,-19.5223140717 --9.46921539307,2.11456370354,-18.9589862823 --9.40422725677,2.11256670952,-18.9754428864 --9.35025691986,2.11355662346,-19.0138931274 --9.3262796402,2.11554741859,-19.0411224365 --9.31751918793,2.14240813255,-19.3219566345 --9.28458881378,2.14837193489,-19.4053916931 --9.22060585022,2.14837169647,-19.427854538 --9.15060997009,2.14538002014,-19.4353160858 --9.08756065369,2.13741827011,-19.3815727234 --9.00453853607,2.13044333458,-19.3600406647 --5.47505569458,1.22976911068,-11.9969186783 --5.42804145813,1.22678351402,-11.9923667908 --8.63023376465,2.07967877388,-19.0235519409 --8.60131168365,2.08763718605,-19.1159858704 --8.52930831909,2.08365082741,-19.1144523621 --8.46525096893,2.07469391823,-19.0517063141 --8.38122272491,2.06772327423,-19.0231838226 --8.31121921539,2.06473565102,-19.0236473083 --8.23921489716,2.06074976921,-19.0211162567 --8.07000923157,2.03089499474,-18.7946529388 --8.02104663849,2.0328810215,-18.8401012421 --7.88290119171,2.0109872818,-18.6796169281 --7.9060177803,2.02491569519,-18.8128051758 --7.83501052856,2.021930933,-18.8082733154 --7.6998667717,2.00003576279,-18.6507892609 --7.65791702271,2.00401306152,-18.7112312317 --7.56786680222,1.99505627155,-18.6587162018 --7.44073152542,1.97415423393,-18.5122203827 --7.2644867897,1.93932414055,-18.2427635193 --7.15631628036,1.91643989086,-18.0550460815 --7.08229207993,1.9104654789,-18.0325145721 --7.03031635284,1.91145968437,-18.0639686584 --7.08458423615,1.94429576397,-18.366350174 --7.02258777618,1.94330394268,-18.3738079071 --6.9315237999,1.93235516548,-18.3072910309 --6.87052965164,1.93136155605,-18.3177528381 --6.83451938629,1.92837297916,-18.3089885712 --6.7464594841,1.91842186451,-18.2464675903 --6.64436435699,1.90449297428,-18.1459598541 --6.58637475967,1.90349638462,-18.1614189148 --6.50633001328,1.8955347538,-18.1168937683 --6.44533109665,1.8945441246,-18.1223526001 --6.40538597107,1.89951896667,-18.1867980957 --6.28114938736,1.86767530441,-17.9290981293 --6.1980919838,1.8587218523,-17.8705749512 --6.15513467789,1.86270403862,-17.9220161438 --6.09012460709,1.85972046852,-17.9154872894 --5.97798728943,1.83981752396,-17.769985199 --5.94204902649,1.84578824043,-17.841424942 --5.90603303909,1.84380316734,-17.8266620636 --5.85305118561,1.8438013792,-17.8511180878 --5.79204845428,1.84181308746,-17.8525829315 --5.71499681473,1.83385527134,-17.8010520935 --5.63192987442,1.82390749454,-17.7325286865 --5.58897542953,1.82788825035,-17.7869796753 --5.59015226364,1.8487868309,-17.9834060669 --5.52404499054,1.83485949039,-17.8686580658 --5.44498538971,1.82490646839,-17.809129715 --5.42510271072,1.8388427496,-17.940568924 --5.3239774704,1.82193148136,-17.8090629578 --5.28102445602,1.82591187954,-17.8645114899 --5.2631521225,1.83984172344,-18.0069484711 --5.20314741135,1.83785438538,-18.0064067841 --5.2102637291,1.85178697109,-18.1336135864 --5.15728616714,1.85278308392,-18.1620750427 --5.13942146301,1.86870956421,-18.3105106354 --5.00918865204,1.83786416054,-18.0650177002 --4.93915319443,1.8328962326,-18.0314903259 --4.89620685577,1.83787322044,-18.0929450989 --4.8301820755,1.83389878273,-18.0704097748 --4.81322479248,1.83787715435,-18.1186351776 --4.75522613525,1.83688652515,-18.1240940094 --4.70325088501,1.83888149261,-18.1545543671 --4.65327978134,1.84087383747,-18.1890068054 --4.6113448143,1.84784412384,-18.2624664307 --4.5302605629,1.83590614796,-18.1769390106 --4.46122407913,1.83093929291,-18.141412735 --4.43724107742,1.8319337368,-18.1616363525 --4.3571600914,1.82099366188,-18.0801181793 --4.31622362137,1.82796478271,-18.1515636444 --4.20802879333,1.80309450626,-17.9490642548 --4.18315839767,1.81802535057,-18.0905036926 --4.12616205215,1.81703364849,-18.0979671478 --4.0641450882,1.81405413151,-18.0844345093 --4.03012132645,1.81007349491,-18.0616664886 --4.01329469681,1.82997858524,-18.2481060028 --3.93420505524,1.81804347038,-18.1575832367 --3.84808301926,1.80312812328,-18.0330677032 --3.80213284492,1.80810821056,-18.0895233154 --3.77426362038,1.82203912735,-18.230966568 --3.75832486153,1.82900750637,-18.2971954346 --3.64004683495,1.79518592358,-18.0096950531 --3.57500743866,1.79022014141,-17.9721622467 --3.51398849487,1.78724181652,-17.9566307068 --3.47708177567,1.79719603062,-18.0580787659 --3.37787532806,1.77233064175,-17.8465709686 --3.36911249161,1.79919862747,-18.0980052948 --3.26486778259,1.7693554163,-17.847492218 --3.27507019043,1.79323995113,-18.0597114563 --3.21103096008,1.7872736454,-18.0231781006 --3.17916345596,1.80220508575,-18.1646270752 --3.12518143654,1.80320513248,-18.1870918274 --3.04102468491,1.78430879116,-18.0285644531 --2.99408221245,1.79028534889,-18.0920295715 --2.95200324059,1.78133761883,-18.0122699738 --2.89399218559,1.77935469151,-18.0047340393 --2.83396840096,1.77637934685,-17.9841995239 --2.75885176659,1.7624591589,-17.8676738739 --2.73001885414,1.78037071228,-18.0441246033 --2.6649620533,1.77341496944,-17.9895935059 --2.45293831825,1.6560292244,-16.9411334991 --2.42190289497,1.65105485916,-16.9073600769 --2.36587882042,1.64807879925,-16.8878250122 --2.31086277962,1.64609837532,-16.8762931824 --2.17023038864,1.57347917557,-16.2337913513 --2.21189808846,1.65009748936,-16.9222126007 --2.16393327713,1.6530867815,-16.9636764526 --1.93960905075,1.50287091732,-15.6162033081 --2.15749526024,1.71677362919,-17.544342041 --2.11660218239,1.72872173786,-17.6578006744 --2.05453777313,1.7207698822,-17.5962657928 --1.98642385006,1.70784664154,-17.4847373962 --1.75487232208,1.53275859356,-15.9122543335 --1.70687890053,1.53376436234,-15.9247140884 --1.84663021564,1.7307587862,-17.7071285248 --1.82164919376,1.73275327682,-17.7283573151 --1.76563179493,1.73077392578,-17.7148208618 --1.73083078861,1.75266981125,-17.9202823639 --1.49597012997,1.5437541008,-16.0437850952 --1.62286353111,1.75567305088,-17.9612178802 --1.56180274487,1.74871909618,-17.9036884308 --1.5017427206,1.74176454544,-17.84715271 --1.47170817852,1.73778986931,-17.8143844604 --1.40657758713,1.72387564182,-17.6868495941 --1.35258567333,1.72388184071,-17.6993160248 --1.29859828949,1.72588586807,-17.7157878876 --1.24561059475,1.7268897295,-17.7322483063 --1.19364511967,1.73088109493,-17.7707138062 --1.1396625042,1.73288249969,-17.7921848297 --1.1106325388,1.72890484333,-17.7644176483 --1.05664718151,1.73090779781,-17.7828884125 --1.00265288353,1.73191583157,-17.7923526764 --0.941520929337,1.71700155735,-17.664812088 --0.88854944706,1.71999669075,-17.6972827911 --0.831495523453,1.71403825283,-17.6477489471 --0.775451898575,1.71007430553,-17.608215332 --0.750511288643,1.71604633331,-17.6694545746 --0.698548257351,1.72103667259,-17.7099189758 --0.642505347729,1.71607208252,-17.6713829041 --0.589537143707,1.72006559372,-17.7068538666 --0.535561859608,1.72306323051,-17.735326767 --0.480546146631,1.72108328342,-17.7237930298 --0.452488839626,1.71512115002,-17.6690196991 --0.398498386145,1.716127038,-17.6824893951 --0.344502031803,1.71713650227,-17.689956665 --0.289466947317,1.71316766739,-17.6594238281 --0.236539781094,1.72213852406,-17.7348957062 --0.181550398469,1.72314429283,-17.749370575 --0.127503171563,1.71818196774,-17.706829071 --0.100582934916,1.72714352608,-17.787071228 --0.0456283651292,1.73213005066,-17.8355484009 -0.002697694581,1.73989033699,-17.0750427246 -0.057741638273,1.74389946461,-17.1154022217 -0.112783744931,1.74890744686,-17.1537570953 -0.16885304451,1.75593042374,-17.2191123962 -0.224885597825,1.75893294811,-17.2484741211 -0.250813961029,1.75088620186,-17.1766548157 -0.30682849884,1.75287866592,-17.1880168915 -0.362864971161,1.75588357449,-17.2213764191 -0.45207041502,1.77897298336,-17.4199047089 -0.50705999136,1.77695214748,-17.4072608948 -0.563069045544,1.77794194221,-17.4136199951 -0.591071486473,1.77793574333,-17.4147987366 -0.648088753223,1.77992963791,-17.4291610718 -0.704089701176,1.77991497517,-17.427520752 -0.759074449539,1.77789163589,-17.4098815918 -0.815068602562,1.77787315845,-17.4012451172 -0.872081577778,1.77886497974,-17.411605835 -0.928083539009,1.77885103226,-17.4109668732 -0.956087172031,1.77984535694,-17.4131469727 -1.01309919357,1.78083670139,-17.4225082397 -1.06809306145,1.77981853485,-17.4138679504 -1.1251001358,1.78080713749,-17.4182319641 -1.18110227585,1.78179323673,-17.417591095 -1.238109231,1.78178191185,-17.4219551086 -1.29411435127,1.78276968002,-17.4243125916 -1.32210993767,1.78275978565,-17.4184970856 -1.37811291218,1.78274655342,-17.4188575745 -1.43411290646,1.78273165226,-17.416217804 -1.49112081528,1.78372108936,-17.421579361 -1.54711985588,1.78370571136,-17.4179420471 -1.60312008858,1.78469085693,-17.4153022766 -1.63111650944,1.78368163109,-17.4104862213 -1.6861089468,1.78366279602,-17.399848938 -1.74311101437,1.78364896774,-17.3992137909 -1.79810023308,1.78262841702,-17.3855781555 -1.85308945179,1.7816079855,-17.3719425201 -1.91009652615,1.78259706497,-17.3763046265 -1.96609377861,1.78258085251,-17.3706703186 -1.99308860302,1.78257083893,-17.3638496399 -2.05009961128,1.78456199169,-17.3722057343 -2.10609388351,1.7835444212,-17.3635730743 -2.16309976578,1.78453290462,-17.36693573 -2.2201063633,1.78652143478,-17.3702964783 -2.27610445023,1.78650593758,-17.3656616211 -2.33613109589,1.78950536251,-17.3900203705 -2.36714839935,1.79250693321,-17.4062004089 -2.42314863205,1.7924926281,-17.4035606384 -2.48619174957,1.79750037193,-17.4449176788 -2.5542678833,1.80752539635,-17.5202674866 -2.61831688881,1.81353616714,-17.5676174164 -2.68638372421,1.82155621052,-17.6339702606 -2.74941730499,1.82655858994,-17.6653270721 -2.78546404839,1.83157551289,-17.7124977112 -2.85151553154,1.8385874033,-17.7628479004 -2.92057943344,1.84660542011,-17.8262004852 -2.99969959259,1.86165225506,-17.9475383759 -3.06775140762,1.86866390705,-17.9988918304 -3.12977313995,1.87166047096,-18.0192451477 -3.18474888802,1.86963307858,-17.9916114807 -3.22681879997,1.87866139412,-18.0627765656 -3.29285120964,1.88266289234,-18.0941352844 -3.35788154602,1.88766360283,-18.1234893799 -3.41889071465,1.88965344429,-18.1308460236 -3.48793554306,1.89566123486,-18.175201416 -3.55195331573,1.89865529537,-18.1915607452 -3.58798241615,1.90266251564,-18.2207355499 -3.65401148796,1.90666234493,-18.2490901947 -3.71601963043,1.90865159035,-18.255449295 -3.77602028847,1.90963697433,-18.2538089752 -3.84104084969,1.91363251209,-18.2731666565 -3.90304708481,1.91562068462,-18.2775268555 -3.96404671669,1.91660547256,-18.2748908997 -4.00208044052,1.9206148386,-18.3090629578 -4.0640835762,1.92260146141,-18.3104248047 -4.1220703125,1.92158019543,-18.2947902679 -4.18307113647,1.92356562614,-18.2931518555 -4.2420630455,1.92354679108,-18.2825164795 -4.29904747009,1.92252421379,-18.263879776 -4.36305618286,1.92551374435,-18.2712440491 -4.38903856277,1.92349755764,-18.2514286041 -4.44602203369,1.92247462273,-18.2317962646 -4.51003170013,1.9254642725,-18.2391586304 -4.56701469421,1.92444133759,-18.2195262909 -4.62098836899,1.92241358757,-18.1888942719 -4.68298912048,1.92439901829,-18.1872596741 -4.73094129562,1.91936123371,-18.1346340179 -4.7579293251,1.91934764385,-18.1198196411 -4.81190347672,1.91732048988,-18.0901889801 -4.86186075211,1.91328513622,-18.0425682068 -4.91583681107,1.9112585783,-18.0139389038 -4.97282218933,1.91123712063,-17.996307373 -5.02479171753,1.90920758247,-17.9606781006 -5.08077192307,1.90818357468,-17.9370536804 -5.10976791382,1.90817439556,-17.9312362671 -5.16173791885,1.90614545345,-17.8966083527 -5.22073078156,1.90712749958,-17.885974884 -5.28072500229,1.90811038017,-17.8773441315 -5.33369827271,1.90608286858,-17.8457183838 -5.38667345047,1.90405666828,-17.8160896301 -5.4476723671,1.90604197979,-17.8124542236 -5.4786734581,1.90703511238,-17.8116378784 -5.5346570015,1.90601277351,-17.7910079956 -5.58963871002,1.90598988533,-17.7683753967 -5.6406083107,1.90296125412,-17.7327518463 -5.69859886169,1.90394222736,-17.7191181183 -5.75458097458,1.9029198885,-17.6974925995 -5.76853227615,1.89788937569,-17.6426944733 -5.81248426437,1.89385223389,-17.5870761871 -5.88050174713,1.89784657955,-17.6034374237 -5.96255970001,1.90685963631,-17.6627788544 -6.03157901764,1.91085469723,-17.681137085 -6.08856630325,1.91083467007,-17.6645030975 -6.15056610107,1.9128203392,-17.6608695984 -6.16552305222,1.90779292583,-17.612071991 -6.18842077255,1.89673113823,-17.4974746704 -6.22535705566,1.89068698883,-17.4238643646 -6.23622608185,1.87561190128,-17.2772865295 -6.26013326645,1.86555480957,-17.1716880798 -6.29907798767,1.85951519012,-17.1070785522 -6.33401346207,1.85347151756,-17.0324726105 -6.30787563324,1.83640086651,-16.8787117004 -6.34782743454,1.83136510849,-16.822095871 -6.39579868317,1.82933795452,-16.7854785919 -6.43775558472,1.82630467415,-16.7338657379 -6.47269773483,1.8202650547,-16.6662540436 -6.51465654373,1.81623232365,-16.615644455 -6.56162548065,1.81420469284,-16.5770301819 -6.56155824661,1.80616724491,-16.5002403259 -6.60552310944,1.80313789845,-16.4566249847 -6.63645982742,1.79709601402,-16.3820209503 -6.66739797592,1.79105460644,-16.3084163666 -6.69332551956,1.78300857544,-16.2228183746 -6.74130105972,1.78098464012,-16.1912021637 -6.78025960922,1.77795267105,-16.1395893097 -6.79522657394,1.77393138409,-16.1007919312 -6.83919668198,1.77190494537,-16.0621738434 -6.88116264343,1.7698764801,-16.0185585022 -6.92312812805,1.76684832573,-15.9749479294 -6.96709775925,1.76482152939,-15.9353342056 -7.00405359268,1.76078903675,-15.8807268143 -7.01401615143,1.75676596165,-15.8359251022 -7.06299781799,1.75574529171,-15.8103055954 -7.09594631195,1.75070953369,-15.7467060089 -7.13190460205,1.74667835236,-15.6940908432 -7.17988538742,1.7466571331,-15.666472435 -7.20682382584,1.73961746693,-15.5918769836 -7.23977708817,1.73558437824,-15.5332689285 -7.27378511429,1.73758149147,-15.5394582748 -7.29972648621,1.73154306412,-15.4668550491 -7.34570360184,1.73052060604,-15.4352416992 -7.39869499207,1.73150444031,-15.4196186066 -7.43265151978,1.72747302055,-15.3640136719 -7.46260166168,1.72243893147,-15.3014087677 -7.50357151031,1.72041344643,-15.2607984543 -7.51353788376,1.71639239788,-15.2190036774 -7.55450820923,1.71436750889,-15.1793928146 -7.5944776535,1.71234190464,-15.1377820969 -7.62643289566,1.70831012726,-15.0801811218 -7.67441749573,1.70829164982,-15.0565595627 -7.71138286591,1.70526432991,-15.0099525452 -7.72530841827,1.69622051716,-14.9183683395 -7.73527812958,1.69320166111,-14.880566597 -7.79328012466,1.69519042969,-14.8759403229 -7.82824420929,1.69216299057,-14.8273334503 -7.85819816589,1.68813121319,-14.7677383423 -7.89716911316,1.68610692024,-14.7271289825 -7.93814468384,1.685084939,-14.6925115585 -7.99514436722,1.68707287312,-14.6848897934 -8.02114105225,1.68706583977,-14.6780757904 -8.05009555817,1.68303418159,-14.617483139 -8.1091003418,1.68602442741,-14.6158504486 -8.15908813477,1.68700766563,-14.5952348709 -8.19205093384,1.68298017979,-14.544631958 -8.24204063416,1.68396437168,-14.5260095596 -8.29503440857,1.68494939804,-14.5103931427 -8.31201839447,1.68393683434,-14.4875860214 -8.36100482941,1.68491947651,-14.464972496 -8.41199588776,1.68590426445,-14.447350502 -8.44295597076,1.68187606335,-14.3937520981 -8.50696754456,1.6858689785,-14.3991165161 -8.56496810913,1.68885755539,-14.3924922943 -8.5879611969,1.68884861469,-14.3796825409 -8.62993717194,1.68782687187,-14.344078064 -8.69394683838,1.69181954861,-14.3484430313 -8.722905159,1.68779063225,-14.2918481827 -8.75386810303,1.68476426601,-14.2412424088 -8.81286907196,1.68675303459,-14.2346220016 -8.86986923218,1.68974101543,-14.2259960175 -8.88685321808,1.68872880936,-14.2031917572 -8.94284915924,1.69071543217,-14.1905765533 -8.98683071136,1.69069683552,-14.1619558334 -9.03281402588,1.69067811966,-14.1333494186 -9.0797996521,1.69066095352,-14.1087303162 -9.12578296661,1.6906427145,-14.0811185837 -9.17577266693,1.6916270256,-14.0604991913 -9.22079372406,1.69662964344,-14.0816707611 -9.28580284119,1.70062112808,-14.0830430984 -9.32878112793,1.69960129261,-14.0504341125 -9.3797712326,1.70058560371,-14.0298185349 -9.42875862122,1.70156931877,-14.0071992874 -9.48175144196,1.70355463028,-13.9895811081 -9.54475593567,1.7065448761,-13.9869537354 -9.57876205444,1.70954155922,-13.9901342392 -9.62975120544,1.71052539349,-13.9685201645 -9.69275474548,1.71351528168,-13.9648942947 -9.73773670197,1.71349644661,-13.9342851639 -9.78672409058,1.71448004246,-13.9106674194 -9.83471012115,1.71546292305,-13.885052681 -9.86771392822,1.71745848656,-13.8852376938 -9.91970443726,1.71844351292,-13.8656177521 -9.97369670868,1.72042894363,-13.8479986191 -10.0296907425,1.72241508961,-13.8323822021 -10.0946969986,1.72640573978,-13.8307495117 -10.1306667328,1.72538268566,-13.7861528397 -10.1846599579,1.72736871243,-13.7695264816 -10.1956377029,1.72435450554,-13.7377347946 -10.2736577988,1.73134994507,-13.7520961761 -10.3136329651,1.73032903671,-13.7134943008 -10.3756332397,1.73331785202,-13.7058677673 -10.4326286316,1.73630452156,-13.691245079 -10.5016365051,1.74029552937,-13.6916160583 -10.5686426163,1.74428582191,-13.6889896393 -10.6046476364,1.74728238583,-13.6921663284 -10.6476268768,1.74726307392,-13.6575593948 -10.7136297226,1.75125217438,-13.6519384384 -10.7816362381,1.75524270535,-13.6503067017 -10.8456382751,1.7592318058,-13.6436738968 -10.8796081543,1.75720906258,-13.5970754623 -10.9386034012,1.76019573212,-13.5824546814 -10.9816150665,1.76419377327,-13.591635704 -11.0315999985,1.76517701149,-13.5650234222 -11.0935993195,1.76816475391,-13.5543956757 -11.130572319,1.76714348793,-13.5117931366 -11.1915683746,1.7701305151,-13.4981737137 -11.2565698624,1.7741189003,-13.4895486832 -11.3025827408,1.77811777592,-13.5017242432 -11.3595752716,1.78010344505,-13.4831056595 -11.3935470581,1.77908146381,-13.4375009537 -11.4345235825,1.77806138992,-13.3988981247 -11.4574832916,1.77503538132,-13.3383131027 -11.0750617981,1.70187735558,-12.8010587692 -11.1000270844,1.69885456562,-12.748462677 -11.1090068817,1.69684195518,-12.717669487 -11.1329717636,1.69381868839,-12.6630792618 -11.1479291916,1.68979287148,-12.5984964371 -11.1728954315,1.68677043915,-12.5459041595 -11.2048692703,1.68575060368,-12.5023021698 -11.2168235779,1.68072414398,-12.4347229004 -11.2397899628,1.67770159245,-12.3801364899 -11.2397632599,1.67468690872,-12.3403501511 -11.2437124252,1.66865921021,-12.2657737732 -11.2746868134,1.66763985157,-12.2221708298 -11.3066606522,1.66562008858,-12.1775808334 -11.3236227036,1.6625970602,-12.1189899445 -11.3385839462,1.65857315063,-12.0574083328 -11.3745622635,1.65755569935,-12.0198030472 -11.363527298,1.65253841877,-11.9680337906 -11.3854951859,1.65051734447,-11.9154405594 -11.4224758148,1.65050029755,-11.8788366318 -11.4364366531,1.64647710323,-11.8172559738 -11.4564037323,1.64345562458,-11.7626686096 -11.4883804321,1.64243769646,-11.7210693359 -11.4723186493,1.63340735435,-11.6295099258 -11.470293045,1.63039410114,-11.5907230377 -11.4882593155,1.62737286091,-11.5351371765 -11.5002202988,1.62335038185,-11.4735555649 -11.5281953812,1.62133193016,-11.4279651642 -11.5411586761,1.61831009388,-11.3683815002 -11.572136879,1.6172927618,-11.3267850876 -11.5820970535,1.61227011681,-11.263212204 -11.5970859528,1.61226153374,-11.2424125671 -11.605047226,1.6082392931,-11.1788311005 -11.6280193329,1.60622060299,-11.1302394867 -11.6569957733,1.60520327091,-11.0866479874 -11.6659584045,1.60018157959,-11.0240716934 -11.6869297028,1.59816300869,-10.9744787216 -11.6949129105,1.59715306759,-10.946688652 -11.7108821869,1.59413349628,-10.8921022415 -11.7248487473,1.59011363983,-10.8355207443 -11.7518253326,1.58909678459,-10.7919244766 -11.7737989426,1.58707892895,-10.7433357239 -11.7837648392,1.58405864239,-10.6837558746 -11.7777175903,1.57703518867,-10.6091918945 -11.7736949921,1.5740237236,-10.5724029541 -11.7786579132,1.57000303268,-10.5088281631 -11.7956285477,1.56698477268,-10.4562473297 -11.8125991821,1.56496691704,-10.4046602249 -11.8295717239,1.56194901466,-10.3530750275 -11.8585519791,1.56193375587,-10.3124790192 -11.8615140915,1.55691325665,-10.2479095459 -11.8705005646,1.55590474606,-10.2231140137 -11.8944778442,1.55488836765,-10.1775283813 -11.9124507904,1.55287158489,-10.1279401779 -11.9294242859,1.54985451698,-10.0773534775 -11.9644088745,1.55084061623,-10.041759491 -11.9753780365,1.54682278633,-9.98617839813 -11.9803628922,1.54581391811,-9.9583864212 -12.0083436966,1.54479920864,-9.91779136658 -12.0143108368,1.54078090191,-9.85821628571 -12.0422916412,1.54076635838,-9.81762313843 -11.9572029114,1.52373361588,-9.68311500549 -8.26388645172,0.987126708031,-6.57030534744 -8.26186752319,0.984116852283,-6.52572631836 -8.33488559723,0.990113794804,-6.52030992508 -8.35888290405,0.990108013153,-6.49671459198 -8.39788818359,0.993104279041,-6.48411750793 -8.41588115692,0.99209779501,-6.45651721954 -8.43787670135,0.992091715336,-6.4309258461 -8.45987319946,0.992085635662,-6.40533447266 -8.47587394714,0.993083357811,-6.3965344429 -8.49286746979,0.993076622486,-6.36694765091 -8.52787017822,0.995072484016,-6.3513469696 -8.53886032104,0.99306511879,-6.31775856018 -8.57086277008,0.995060682297,-6.30015563965 -8.60086250305,0.996055781841,-6.28055858612 -8.61685466766,0.995049118996,-6.24997472763 -8.62885379791,0.996046364307,-6.23817539215 -8.66385650635,0.998042047024,-6.22158050537 -8.68685340881,0.998036444187,-6.19698381424 -8.70384693146,0.998030304909,-6.16838693619 -8.73684883118,0.999025940895,-6.15078639984 -8.7668504715,1.00102102757,-6.13019418716 -8.78884601593,1.00101542473,-6.1045999527 -8.80884933472,1.00201356411,-6.0978012085 -8.82984542847,1.00300776958,-6.07120895386 -8.85384273529,1.00300240517,-6.04661655426 -8.88784408569,1.00499820709,-6.02901697159 -8.9028377533,1.00399196148,-5.99842691422 -8.9338388443,1.00598740578,-5.97882652283 -8.95584201813,1.00698566437,-5.97302770615 -8.98684215546,1.00898098946,-5.95243549347 -9.00783824921,1.00897538662,-5.92584133148 -9.03083610535,1.00997006893,-5.90024900436 -9.05783462524,1.01096510887,-5.8776512146 -9.09683990479,1.01296138763,-5.86304521561 -9.12683963776,1.01495659351,-5.84145307541 -9.12082958221,1.01295256615,-5.81766176224 -9.15983486176,1.01494860649,-5.80206251144 -9.18383216858,1.01594352722,-5.77746295929 -9.18181800842,1.01293623447,-5.73489284515 -9.2068157196,1.0139311552,-5.71029996872 -9.29084014893,1.02293097973,-5.72366476059 -9.32184123993,1.02392613888,-5.70207309723 -11.2506885529,1.27406167984,-6.8583612442 -10.9185199738,1.22702693939,-6.6010222435 -10.9144992828,1.22401714325,-6.55144834518 -10.9374904633,1.22400939465,-6.51885509491 -10.8034143448,1.20399069786,-6.38838434219 -10.7283639908,1.19097685814,-6.29685783386 -10.5892963409,1.17196345329,-6.19016027451 -10.6152906418,1.17295646667,-6.15957832336 -10.5362405777,1.15994334221,-6.06805038452 -10.4962072372,1.15193283558,-5.99950504303 -10.4151592255,1.13892006874,-5.90699052811 -10.26608181,1.11690402031,-5.776512146 -10.200047493,1.10789644718,-5.71577692032 -10.0659799576,1.08788204193,-5.59628534317 -9.95892238617,1.07186937332,-5.49179363251 -9.89788532257,1.06185984612,-5.41625356674 -9.81684017181,1.04884946346,-5.32973051071 -9.7407989502,1.03683972359,-5.24620962143 -9.76879787445,1.03883504868,-5.22161865234 -9.58572101593,1.01382374763,-5.09995222092 -9.60471725464,1.01481926441,-5.07136392593 -9.47865867615,0.996808350086,-4.96287584305 -9.44763755798,0.990802049637,-4.90831327438 -9.41161346436,0.983795702457,-4.85076141357 -9.36958885193,0.976789236069,-4.79021501541 -9.30655574799,0.966782212257,-4.71868610382 -9.23052310944,0.955777287483,-4.65994691849 -9.14048194885,0.942769825459,-4.57543420792 -9.12346744537,0.938765287399,-4.53086185455 -9.00841808319,0.92275762558,-4.43437004089 -9.00040817261,0.919753670692,-4.39479780197 -8.96538829803,0.913749158382,-4.34223604202 -8.8623456955,0.898742854595,-4.25472927094 -8.81832790375,0.89274007082,-4.2149720192 -8.74329471588,0.881735146046,-4.14343976974 -8.71928024292,0.876731693745,-4.09787416458 -8.70526981354,0.873728454113,-4.05631685257 -8.63123989105,0.862724244595,-3.986784935 -8.58321857452,0.854720771313,-3.93023943901 -8.54720401764,0.849718928337,-3.89647269249 -8.42515945435,0.832714557648,-3.80596470833 -8.48017406464,0.838713347912,-3.79935956001 -8.38813972473,0.825709998608,-3.72383904457 -8.36412811279,0.820707798004,-3.68028378487 -8.29410266876,0.810705244541,-3.61674308777 -8.27709388733,0.807703435421,-3.57718229294 -8.18906497955,0.795701861382,-3.52144694328 -8.17405796051,0.792700469494,-3.48387908936 -8.14604568481,0.787698984146,-3.44032382965 -8.11603450775,0.782697618008,-3.39676117897 -8.0750207901,0.776696443558,-3.34821152687 -8.06801605225,0.773695468903,-3.31563186646 -8.07301521301,0.773694634438,-3.28804945946 -7.98398828506,0.761694192886,-3.23431921005 -7.94397544861,0.755693614483,-3.18776512146 -7.91796684265,0.751693069935,-3.14720726013 -7.89996051788,0.747692704201,-3.11063981056 -7.88295507431,0.744692385197,-3.07408046722 -7.82493782043,0.736692488194,-3.02153420448 -7.79893016815,0.731692492962,-2.98296380043 -7.79492902756,0.730692505836,-2.96619200706 -7.75691843033,0.724692881107,-2.92263579369 -7.73691320419,0.72169315815,-2.88706254959 -7.77492284775,0.724692881107,-2.8744597435 -7.70490503311,0.715694010258,-2.81892323494 -7.65589237213,0.70869499445,-2.77138590813 -7.63488721848,0.705695569515,-2.74960803986 -7.57687282562,0.697696983814,-2.70006322861 -7.5698723793,0.695697724819,-2.67048811913 -7.55887079239,0.692698597908,-2.63990926743 -7.54286766052,0.689699649811,-2.6073372364 -7.51486253738,0.685701012611,-2.56978297234 -7.49185800552,0.681702494621,-2.53521203995 -7.48385715485,0.680703163147,-2.51843810081 -7.39683771133,0.66870623827,-2.46090626717 -7.39383935928,0.667707502842,-2.4343225956 -7.35983324051,0.662709653378,-2.39577412605 -7.36583709717,0.66271084547,-2.37219238281 -7.34983587265,0.659712612629,-2.34161281586 -7.32783222198,0.656713962555,-2.3208425045 -7.33883714676,0.656715095043,-2.29925680161 -7.30583238602,0.651717662811,-2.26269650459 -7.28783130646,0.648719847202,-2.23113322258 -7.2858338356,0.647721529007,-2.20555233955 -7.35585260391,0.655720829964,-2.2039270401 -7.24083042145,0.640726745129,-2.14042806625 -7.18982172012,0.634729444981,-2.11166524887 -7.20082712173,0.634730935097,-2.09107232094 -7.1908288002,0.632733345032,-2.06349635124 -7.17783021927,0.630735993385,-2.03394198418 -7.20183849335,0.63273704052,-2.01734375954 -7.17683744431,0.628740131855,-1.98577010632 -7.16783952713,0.626742780209,-1.95820605755 -7.18684530258,0.628742992878,-1.95239591599 -7.17284679413,0.62674587965,-1.92382717133 -7.16284894943,0.624748647213,-1.89626193047 -7.11784505844,0.618753135204,-1.85871481895 -7.09984588623,0.615756392479,-1.83013749123 -7.07884645462,0.612759888172,-1.80056703091 -7.07385015488,0.61076271534,-1.77500009537 -7.0448474884,0.607765555382,-1.7552241087 -7.04685258865,0.606768012047,-1.73263812065 -7.0528588295,0.606770336628,-1.7110517025 -7.03486013412,0.603774130344,-1.68248808384 -7.03486585617,0.603776931763,-1.65891337395 -7.003865242,0.599781513214,-1.62735390663 -7.00486803055,0.598782837391,-1.61655473709 -6.98186969757,0.595787107944,-1.586997509 -6.99787759781,0.596789121628,-1.56840348244 -7.00688505173,0.597791552544,-1.54781615734 -6.9948887825,0.59579539299,-1.52125418186 -7.0178976059,0.597796976566,-1.50464963913 -6.95189332962,0.5888043046,-1.4651184082 -6.97590017319,0.591804385185,-1.45931911469 -6.94090080261,0.586809754372,-1.42875015736 -6.94990777969,0.587812423706,-1.40816688538 -6.92791080475,0.584817171097,-1.3805975914 -6.94491910934,0.585819363594,-1.36200785637 -6.91892194748,0.581824541092,-1.33344686031 -6.91792821884,0.581828057766,-1.31086671352 -6.90592956543,0.57983058691,-1.29708302021 -6.93293952942,0.582832217216,-1.28049039841 -6.8999414444,0.57783806324,-1.25093257427 -6.91295003891,0.578840732574,-1.23134720325 -6.8979549408,0.576845467091,-1.20578014851 -6.8929605484,0.575849413872,-1.18319201469 -6.90296936035,0.576852440834,-1.16261529922 -6.85796689987,0.570857644081,-1.14284670353 -6.87197542191,0.57186037302,-1.12326586246 -6.91598844528,0.576860785484,-1.10966265202 -6.88299131393,0.57286721468,-1.08110594749 -6.85599517822,0.568873047829,-1.05453383923 -6.8600025177,0.568876743317,-1.03296065331 -6.86800718307,0.569877922535,-1.02415335178 -6.89101743698,0.571880221367,-1.00557649136 -6.90902662277,0.573882639408,-0.986983418465 -6.91003417969,0.572886526585,-0.965400099754 -6.91804218292,0.57388985157,-0.944816112518 -6.94305229187,0.575891792774,-0.927218914032 -6.92705821991,0.573897182941,-0.902648448944 -6.94906425476,0.575897455215,-0.894853413105 -6.94007110596,0.574902296066,-0.871282696724 -6.81406545639,0.559917271137,-0.830758810043 -6.89408159256,0.568914532661,-0.821138143539 -6.87208747864,0.565920889378,-0.795582354069 -6.88109636307,0.566924393177,-0.775002479553 -6.95311117172,0.573922216892,-0.763385653496 -6.98011732101,0.576921820641,-0.7565741539 -6.97512435913,0.575926601887,-0.733996927738 -6.966132164,0.574931800365,-0.710431575775 -6.9421377182,0.571938335896,-0.685857892036 -6.98814964294,0.576938331127,-0.670247018337 -6.99315834045,0.576942324638,-0.648670971394 -7.0091676712,0.578945279121,-0.628094673157 -7.02817344666,0.580945730209,-0.619296312332 -7.03518152237,0.580949366093,-0.598702549934 -7.07519292831,0.584949970245,-0.581103682518 -7.04219818115,0.580957651138,-0.555540204048 -7.01520490646,0.577964961529,-0.529989480972 -7.02121353149,0.577968776226,-0.509394526482 -7.03021812439,0.578970134258,-0.499595552683 -7.07423019409,0.583970487118,-0.481011629105 -7.07223796844,0.582975149155,-0.459421932697 -7.05424547195,0.58098167181,-0.435850858688 -7.0962562561,0.585982084274,-0.417256206274 -7.08626461029,0.583987653255,-0.394676476717 -7.06427192688,0.581994891167,-0.370123147964 -7.03427410126,0.578000247478,-0.35733833909 -7.06928491592,0.582001447678,-0.337749481201 -7.08729505539,0.584004282951,-0.317160636187 -7.08430290222,0.583009302616,-0.295571833849 -7.06831121445,0.581016004086,-0.27201128006 -7.09132194519,0.584018409252,-0.251423299313 -7.04932832718,0.579027891159,-0.226866781712 -7.08433437347,0.583026528358,-0.218058645725 -9.73146152496,0.875738978386,-0.340159475803 -7.08235216141,0.582036674023,-0.173905685544 -9.71647071838,0.873746871948,-0.279013901949 -7.01336765289,0.57405424118,-0.12776581943 -9.72747993469,0.874752044678,-0.218859598041 -9.71248435974,0.873757004738,-0.188287869096 -9.68548583984,0.869761824608,-0.171523436904 -9.67949008942,0.869765758514,-0.141940489411 -9.71149730682,0.872765541077,-0.11235589534 -9.67950057983,0.868772566319,-0.0817896723747 -9.74350738525,0.875768601894,-0.0531835630536 -9.68651103973,0.869778692722,-0.0216374471784 -9.67951393127,0.868781268597,-0.00684774853289 -9.67951869965,0.86878490448,0.0237205531448 -9.68452453613,0.869787812233,0.0533043630421 -9.6685295105,0.867793440819,0.0838671922684 -9.5405330658,0.853812515736,0.114385403693 -9.70754241943,0.871796071529,0.144033208489 -9.66354656219,0.866805076599,0.173595562577 -9.69355010986,0.869803249836,0.18840098381 -9.66356086731,0.866814553738,0.24853502214 -9.65556716919,0.865819334984,0.278111368418 -9.65157318115,0.865823805332,0.308675915003 -9.64757919312,0.864828228951,0.338253855705 -9.64458179474,0.864830553532,0.353042125702 -9.65658855438,0.866833090782,0.383618295193 -9.54259490967,0.853851497173,0.410148441792 -9.66260147095,0.866840362549,0.44377180934 -6.97360372543,0.569188952446,0.391099244356 -9.65561389923,0.86684936285,0.502928674221 -9.67461967468,0.868851006031,0.533514916897 -6.94862985611,0.566206634045,0.444034039974 -6.92764091492,0.564215123653,0.464604109526 -6.93265104294,0.565220296383,0.486186176538 -6.95366191864,0.567223489285,0.508771181107 -6.93867254257,0.566231250763,0.529346644878 -9.63766288757,0.865883529186,0.726741731167 -9.63066673279,0.864886701107,0.741523444653 -6.91171073914,0.563255667686,0.602859735489 -6.85872268677,0.557268917561,0.621403694153 -6.84473371506,0.556276619434,0.640990555286 -6.86374473572,0.558280169964,0.663577139378 -6.84575653076,0.557288885117,0.684136092663 -6.8297624588,0.555293917656,0.692930519581 -6.82977390289,0.555300176144,0.714501678944 -6.79078578949,0.551311612129,0.732072114944 -6.78679704666,0.551318287849,0.752652585506 -6.79080867767,0.551324009895,0.774230241776 -6.7878203392,0.551330924034,0.795793294907 -6.75183296204,0.547342181206,0.813359260559 -6.73483896255,0.546347677708,0.822143256664 -6.68585205078,0.540360748768,0.837711453438 -6.70886278152,0.543364048004,0.861292243004 -6.68387556076,0.540374040604,0.879854381084 -6.68488740921,0.541380226612,0.900441229343 -6.71089839935,0.544382929802,0.924034833908 -6.67691135406,0.540394365788,0.941588759422 -6.68791675568,0.54239577055,0.952401340008 -6.70092821121,0.544400453568,0.974983453751 -6.69094133377,0.543408691883,0.995541512966 -6.70395278931,0.544413328171,1.01812589169 -6.72296333313,0.547416806221,1.04073023796 -6.69697618484,0.544427156448,1.05829942226 -6.62099266052,0.536445081234,1.06982958317 -6.60999917984,0.535450041294,1.07861638069 -6.64600944519,0.539451301098,1.10421514511 -6.62402248383,0.537461161613,1.12178826332 -6.65203428268,0.541463911533,1.14736664295 -6.67104530334,0.543467760086,1.17095804214 -6.6500582695,0.541477501392,1.1885330677 -6.61306715012,0.537486374378,1.1933068037 -6.57508134842,0.533498704433,1.20787620544 -6.65208959579,0.542494058609,1.2414791584 -6.62310409546,0.539505362511,1.25804030895 -6.61611700058,0.539513170719,1.27762103081 -6.59613037109,0.537523031235,1.29519152641 -6.59314393997,0.537530422211,1.31576609612 -6.60514831543,0.539531826973,1.32757616043 -6.62716054916,0.542535483837,1.35315155983 -6.6191740036,0.541543602943,1.37272822857 -6.63518476486,0.543547987938,1.39632308483 -6.67419528961,0.548548877239,1.42491686344 -6.66820859909,0.548556864262,1.44548547268 -6.70321893692,0.552558541298,1.4740704298 -6.70722484589,0.553561151028,1.48487555981 -6.65424203873,0.547576546669,1.49641990662 -6.59225940704,0.541593194008,1.50497734547 -6.59527158737,0.542599737644,1.52656197548 -6.51129102707,0.533619999886,1.53010773659 -6.5013051033,0.532628595829,1.54868793488 -6.60830354691,0.544615447521,1.58251297474 -6.61331653595,0.546621799469,1.60509109497 -6.62832832336,0.548626482487,1.62967813015 -6.58634471893,0.544640183449,1.64124929905 -6.56235980988,0.541651368141,1.65780496597 -6.58137178421,0.544655501842,1.68339371681 -6.55538654327,0.542666614056,1.69797646999 -6.55339384079,0.542670786381,1.70875370502 -6.5214099884,0.538683176041,1.72232198715 -6.54542064667,0.542686343193,1.74892067909 -6.54443454742,0.542693912983,1.77049064636 -6.51745033264,0.540705621243,1.78506135941 -6.5374622345,0.543709754944,1.81164491177 -6.4984793663,0.539723455906,1.82320690155 -6.50348567963,0.54072624445,1.83500182629 -6.5034995079,0.54073369503,1.85657727718 -6.49651384354,0.540742218494,1.87615382671 -6.52752447128,0.544744491577,1.90574800968 -6.52553844452,0.54575240612,1.92731618881 -6.53055143356,0.546758830547,1.94990491867 -6.4865694046,0.541773617268,1.95946455002 -6.47557783127,0.540779232979,1.96724832058 -6.48958969116,0.543784081936,1.99185049534 -6.55059719086,0.550781548023,2.03144335747 -6.56161022186,0.552787423134,2.0570166111 -6.56762361526,0.554793834686,2.08060073853 -6.57463598251,0.555800020695,2.10419178009 -6.54264688492,0.552809238434,2.10596394539 -6.53466176987,0.552818179131,2.12554001808 -6.48668050766,0.547833859921,2.13309693336 -6.48269510269,0.547842085361,2.15367603302 -6.45571231842,0.545854330063,2.16724348068 -6.4607257843,0.546861171722,2.19082164764 -6.45773983002,0.546869218349,2.2114071846 -6.54773712158,0.557857751846,2.25123047829 -6.47675943375,0.550877571106,2.25077819824 -6.53076696396,0.557875990868,2.29038071632 -6.52578163147,0.557884514332,2.31095957756 -6.66178035736,0.574869036674,2.37957525253 -9.46846389771,0.904396057129,3.37098813057 -9.47447490692,0.906401872635,3.40655755997 -9.47948646545,0.908407688141,3.44113636017 -9.36451053619,0.895434498787,3.43366861343 -9.63749980927,0.930400431156,3.59692573547 -6.70788049698,0.585918724537,2.56844449043 -6.68089151382,0.583927571774,2.57120895386 -9.46455001831,0.913447797298,3.61780166626 -6.5389380455,0.568967998028,2.56531739235 -6.49295759201,0.563983559608,2.56990194321 -6.49397230148,0.564991354942,2.59347510338 -6.43999433517,0.560008883476,2.59603142738 -6.45500707626,0.56201416254,2.62461471558 -6.46601295471,0.564016222954,2.64040637016 -6.46502780914,0.565024375916,2.66298484802 -6.42404794693,0.561039507389,2.66955494881 -6.49805259705,0.571034431458,2.72215437889 -6.4290766716,0.563054740429,2.71771001816 -6.40809440613,0.562066435814,2.73228144646 -6.43310546875,0.56606978178,2.76488089561 -6.42511415482,0.565075397491,2.77365899086 -6.38013505936,0.561091542244,2.7782227993 -6.38114976883,0.562099456787,2.80180096626 -6.38516426086,0.564106762409,2.82638573647 -6.38817882538,0.565114319324,2.85096430779 -6.3651971817,0.563126683235,2.86453342438 -6.35720586777,0.563132047653,2.87232756615 -6.36721944809,0.565138339996,2.89991044998 -6.3202419281,0.560155272484,2.90346026421 -6.33325481415,0.563160955906,2.93205142021 -6.34626817703,0.566166937351,2.96162748337 -6.35328245163,0.568173885345,2.98821020126 -6.30830430984,0.5631904006,2.99176812172 -6.32730865479,0.566190838814,3.01157426834 -6.33632230759,0.56819742918,3.03915858269 -6.34733629227,0.571203529835,3.06774497032 -6.30235862732,0.566220283508,3.07129645348 -6.35036659241,0.57321959734,3.11690306664 -6.33438396454,0.573230862617,3.13347411156 -6.3044052124,0.570245027542,3.14402723312 -6.3214097023,0.573245942593,3.16382789612 -6.3304233551,0.57525229454,3.19142341614 -6.33843755722,0.577259421349,3.21999597549 -6.30245876312,0.574274361134,3.22656345367 -6.30447435379,0.575282514095,3.25213646889 -6.31048822403,0.577289581299,3.27872920036 -6.31849527359,0.579292476177,3.29551100731 -6.31551074982,0.58030128479,3.31809520721 -6.32352495193,0.582308292389,3.34667658806 -6.29954481125,0.580321192741,3.35924363136 -6.29056167603,0.580331206322,3.37882661819 -6.3145737648,0.585335314274,3.41640591621 -6.3215880394,0.587342560291,3.44498586655 -6.33059453964,0.589344918728,3.46178507805 -6.27961826324,0.584362864494,3.45935463905 -6.28663349152,0.586370408535,3.48892045021 -6.2976474762,0.588376700878,3.51950860023 -6.32165813446,0.593380510807,3.55710482597 -6.32767391205,0.595388293266,3.58666992188 -6.29968595505,0.592397630215,3.58345985413 -6.28970336914,0.592407941818,3.60303997993 -6.32171392441,0.598410606384,3.64662337303 -6.2817363739,0.594426512718,3.64920020103 -6.27075433731,0.594437241554,3.66877222061 -6.27776956558,0.596444904804,3.69933772087 -6.20480632782,0.589471578598,3.6956884861 -6.26681137085,0.59946846962,3.75728535652 -6.29182291031,0.603472352028,3.7978708744 -6.24784660339,0.599489152431,3.79744768143 -6.28085660934,0.605491638184,3.84303665161 -6.2318816185,0.600509822369,3.84059262276 -6.25189495087,0.604514837265,3.87917160988 -6.25490188599,0.605518579483,3.89396500587 -6.24491930008,0.605528950691,3.91355323792 -6.30392503738,0.615526676178,3.97713398933 -6.25495052338,0.610544800758,3.9736995697 -6.2679643631,0.613550961018,4.0082859993 -6.24098491669,0.61156475544,4.01786422729 -6.25399923325,0.614571273327,4.05343914032 -6.27100372314,0.617572188377,4.07724046707 -6.24202537537,0.615586519241,4.08581352234 -6.27803516388,0.622588515282,4.13639736176 -6.25705528259,0.62160128355,4.149974823 -6.28306674957,0.626605153084,4.19455766678 -6.25308942795,0.62361997366,4.20312070847 -6.25509691238,0.625623881817,4.21791601181 -6.23111724854,0.623637318611,4.22949266434 -6.23813247681,0.626644849777,4.26207113266 -6.24914741516,0.629651725292,4.29764795303 -6.24016523361,0.62966221571,4.31923103333 -6.2311835289,0.63067305088,4.34179925919 -6.21320390701,0.629685401917,4.35737848282 -6.2112121582,0.630690217018,4.37016630173 -6.2112288475,0.63269931078,4.39874172211 -6.21624422073,0.634707152843,4.43032693863 -6.22725915909,0.638714075089,4.46690416336 -6.22627544403,0.639723062515,4.49449014664 -6.21529436111,0.640734314919,4.51605939865 -6.24030590057,0.645738363266,4.56264829636 -6.23731470108,0.64574354887,4.57543182373 -6.22133493423,0.645755648613,4.59300899506 -6.21335315704,0.64676630497,4.61658477783 -6.19837284088,0.646778285503,4.63515853882 -6.18239307404,0.646790444851,4.65273523331 -6.18840885162,0.649798452854,4.68730783463 -6.18842554092,0.651807487011,4.71688890457 -6.17543649673,0.650814414024,4.72168064117 -6.17145442963,0.651824533939,4.74924850464 -6.20146512985,0.657827675343,4.80183696747 -6.19348335266,0.658838152885,4.82542276382 -6.19449949265,0.660846948624,4.85600948334 -6.20451402664,0.664854168892,4.89458703995 -6.20952224731,0.666857898235,4.91437005997 -6.30251932144,0.681848704815,5.01797056198 -6.22455263138,0.6728733778,4.98852491379 -6.2765583992,0.682871997356,5.0601272583 -6.21158885956,0.675893962383,5.03969478607 -6.20760774612,0.676904320717,5.06925535202 -6.18661975861,0.674912750721,5.06705474854 -6.17663955688,0.675924241543,5.09161758423 -6.1996512413,0.681928634644,5.14121294022 -6.20866632462,0.684936106205,5.18079090118 -6.20368432999,0.686946153641,5.20837593079 -6.1887049675,0.686958551407,5.22894239426 -6.29369926453,0.703946828842,5.34855318069 -6.20172786713,0.691969811916,5.28831672668 -6.19774580002,0.693979918957,5.31789302826 -6.20076274872,0.696988582611,5.35347080231 -6.18278360367,0.697001457214,5.37104797363 -6.17780208588,0.699011921883,5.40061712265 -6.19181537628,0.703018248081,5.44521045685 -6.20183086395,0.707025647163,5.48778867722 -6.20283937454,0.708030045033,5.50557756424 -6.24384689331,0.717031121254,5.57517147064 -6.20387363434,0.714048564434,5.57473421097 -6.1828956604,0.713062107563,5.59030914307 -6.2339015007,0.723061144352,5.66990613937 -6.15093755722,0.713087201118,5.6304602623 -6.21194076538,0.725084245205,5.72005701065 -6.19895219803,0.724091589451,5.72584295273 -6.18097448349,0.724104821682,5.74540805817 -6.1879901886,0.728112757206,5.78699111938 -6.17001152039,0.728125691414,5.80556917191 -6.17402791977,0.731134414673,5.84514665604 -6.16804647446,0.733144819736,5.87473201752 -6.17405462265,0.736148655415,5.89951038361 -6.18107032776,0.739156603813,5.94209384918 -6.18008756638,0.742166280746,5.97767210007 -6.18310451508,0.745175182819,6.01725149155 -6.19611883163,0.750181794167,6.06584358215 -6.19713592529,0.753191232681,6.10441875458 -6.17915821075,0.753204524517,6.12498569489 -6.19716262817,0.758205473423,6.16078615189 -6.21217632294,0.763211965561,6.21336889267 -6.19019937515,0.762225925922,6.22994041443 -6.38117218018,0.79619705677,6.45955657959 -6.17223882675,0.766248762608,6.28908872604 -6.1672577858,0.768259346485,6.32266664505 -6.15327882767,0.769271731377,6.34724283218 -6.15228796005,0.770276784897,6.36602878571 -6.185297966,0.779279768467,6.43960952759 -6.16132164001,0.778294205666,6.454185009 -6.15134143829,0.780305624008,6.48276996613 -6.14236164093,0.78131711483,6.51334571838 -6.36232614517,0.820282280445,6.78596639633 -6.34034013748,0.8182913661,6.78275918961 -6.15540313721,0.792338550091,6.62829256058 -6.16241884232,0.796346843243,6.67687129974 -6.17443370819,0.801353931427,6.73045825958 -6.14145898819,0.80037021637,6.73603248596 -6.11748361588,0.799384951591,6.75259494781 -6.13649702072,0.806390821934,6.81517839432 -6.1624994278,0.81239014864,6.86398220062 -6.15951776505,0.815400540829,6.90355682373 -6.14054059982,0.815414309502,6.92612218857 -6.13356018066,0.818425357342,6.96070480347 -6.10958433151,0.817440032959,6.97727441788 -6.10660266876,0.820450305939,7.01685619354 -6.14661073685,0.831451714039,7.10545110703 -8.87594223022,1.29390180111,10.2667961121 -9.03791713715,1.32687819004,10.5174150467 -9.00994110107,1.32789373398,10.5519790649 -8.35912132263,1.22203588486,9.85541629791 -8.34114170074,1.22404932976,9.89598941803 -8.26917743683,1.21707367897,9.87354755402 -8.20120334625,1.2080924511,9.82332324982 -8.17222690582,1.20810806751,9.85089206696 -8.0512752533,1.1931425333,9.76744174957 -8.03629589081,1.19515514374,9.81002235413 -8.0423116684,1.20216369629,9.87959957123 -7.98234415054,1.19718587399,9.86916065216 -7.88038778305,1.18421649933,9.80571556091 -7.82540988922,1.1772326231,9.76849365234 -7.89940881729,1.19522726536,9.92308521271 -7.63649320602,1.15429055691,9.65461826324 -3.47856712341,0.41714400053,4.45456266403 -3.45059418678,0.414159685373,4.44713783264 -3.45161294937,0.417169213295,4.47572851181 -3.4256298542,0.413179844618,4.45750045776 -7.40065097809,1.14139318466,9.69324016571 -7.41666412354,1.15039968491,9.77582645416 -7.32370615005,1.13842856884,9.7163848877 -7.21175336838,1.12346148491,9.63093757629 -7.16878271103,1.12148010731,9.63550949097 -7.12280368805,1.11549448967,9.60528850555 -7.16381072998,1.12849605083,9.72287464142 -7.06685352325,1.11652576923,9.65343952179 -6.99689006805,1.10855007172,9.62100219727 -6.94892120361,1.10556995869,9.61856651306 -6.92294549942,1.10658502579,9.64414787292 -6.8739771843,1.10260510445,9.63971233368 -6.80500411987,1.09262418747,9.57449054718 -6.77403068542,1.09264051914,9.59406089783 -6.73805856705,1.09165811539,9.60663127899 -6.66609573364,1.08268272877,9.56719684601 -6.68410921097,1.09268891811,9.65578269958 -6.58015537262,1.07772040367,9.57033729553 -6.52218914032,1.07274234295,9.54990291595 -6.50520277023,1.07175087929,9.55668926239 -6.46323204041,1.06976938248,9.55826377869 -6.40926504135,1.06479048729,9.54183578491 -6.3762922287,1.06380724907,9.55641078949 -6.3183259964,1.05882906914,9.53298473358 -6.29735040665,1.05984342098,9.56555938721 -6.25037288666,1.05385828018,9.52733612061 -6.20040416718,1.04987847805,9.51491069794 -6.16843175888,1.04889523983,9.53048324585 -6.1614522934,1.05390667915,9.58406352997 -6.08649110794,1.04493200779,9.53263092041 -6.03052520752,1.03895390034,9.51119327545 -6.00355148315,1.03996944427,9.53376865387 -5.99256420135,1.04097688198,9.54955387115 -5.96758937836,1.04199182987,9.57413768768 -5.95161294937,1.04500555992,9.6167011261 -5.94263410568,1.04901754856,9.66828346252 -5.9376540184,1.05402863026,9.72686576843 -5.92667675018,1.05904126167,9.77744007111 -5.93668270111,1.06404411793,9.82723617554 -5.89771223068,1.0620623827,9.83180713654 -5.91272783279,1.07206964493,9.9273815155 -5.90274953842,1.07708191872,9.9809589386 -5.92076349258,1.08708834648,10.0815458298 -5.93277931213,1.09709632397,10.1751194 -5.98478364944,1.11609601974,10.3377056122 -5.95780038834,1.11310660839,10.3274936676 -5.97181606293,1.12311387062,10.4250812531 -5.9468421936,1.12512934208,10.4576501846 -5.9718542099,1.13813459873,10.5782299042 -5.94787979126,1.14014971256,10.6118097305 -5.99288654327,1.15815091133,10.7703933716 -5.95091676712,1.15616965294,10.7729701996 -5.96292304993,1.16317248344,10.8347587585 -5.98393678665,1.17517864704,10.954334259 -5.96296167374,1.17819321156,10.9969110489 -5.96198129654,1.18620371819,11.0764923096 -5.95500230789,1.19321548939,11.1470661163 -6.10497951508,1.23619544506,11.5126667023 -6.07100820541,1.23721265793,11.535241127 -5.97604465485,1.21923732758,11.3990125656 -5.93807411194,1.21825516224,11.4115924835 -5.95208978653,1.23026299477,11.5271663666 -5.92011785507,1.23127961159,11.5517473221 -5.99311685562,1.25827527046,11.7843341827 -5.98113965988,1.26428818703,11.8529071808 -6.00314235687,1.27428877354,11.9417028427 -5.97916889191,1.27730417252,11.9872770309 -5.94819736481,1.27932095528,12.0198459625 -6.03319215775,1.30931413174,12.2854442596 -5.91024637222,1.28834939003,12.1310052872 -3.74087738991,0.74579668045,7.74138069153 -3.72890090942,0.748809397221,7.77795982361 -3.67492651939,0.7378256917,7.69773483276 -3.61996197701,0.729846775532,7.6423201561 -2.83373594284,0.689282894135,7.55995512009 -2.81376242638,0.690297245979,7.57853317261 -2.78179240227,0.687313973904,7.56411409378 -2.76880645752,0.687321662903,7.56490468979 -2.5031208992,0.689493000507,7.6760892868 -2.48714661598,0.692506730556,7.70966339111 -2.47915959358,0.694513499737,7.72645139694 -2.45418715477,0.693528652191,7.73003768921 -2.14905357361,1.04897415638,11.084482193 -2.5599732399,1.33991718292,13.6826305389 -2.54799771309,1.35993003845,13.860209465 -2.51602840424,1.36694669724,13.9327878952 -2.41707897186,1.33097589016,13.6233739853 -2.44608092308,1.36397576332,13.9161615372 -2.39911627769,1.36199522018,13.9057397842 -2.34115457535,1.35201668739,13.8263216019 -2.30718612671,1.3590337038,13.8918991089 -2.27121782303,1.36405086517,13.942483902 -2.24224758148,1.37406694889,14.0430641174 -2.25625419617,1.40006971359,14.2798480988 -2.21628713608,1.40408754349,14.3144330978 -2.15232753754,1.38911020756,14.1950139999 -2.10936164856,1.39012873173,14.2095966339 -2.1393737793,1.44813358784,14.7351741791 -2.06341814995,1.42515850067,14.5347499847 -2.04744410515,1.44917201996,14.7553319931 -2.026460886,1.45118117332,14.7721242905 -1.98049581051,1.45120024681,14.781703949 -1.93752992153,1.45421886444,14.8132858276 -1.93555176258,1.49322962761,15.1698665619 -1.87459123135,1.48125135899,15.0644512177 -1.8406226635,1.49326825142,15.1810312271 -1.83363556862,1.51027488708,15.3278198242 -1.83065783978,1.5542858839,15.7273960114 -1.83267867565,1.60529613495,16.1949729919 -1.78771352768,1.61131501198,16.2535533905 -1.73974907398,1.61433434486,16.2841377258 -1.6927844286,1.61835336685,16.3267211914 -1.64282107353,1.62037324905,16.3512973785 -1.6288356781,1.63338088989,16.467092514 -1.57987177372,1.6364004612,16.5006752014 -1.54090487957,1.6524181366,16.6442546844 -1.4919410944,1.65643751621,16.6898345947 -1.43497979641,1.65145862103,16.6444129944 -1.37801814079,1.64447951317,16.5889968872 -1.32605528831,1.64449942112,16.59557724 -1.30007386208,1.64550948143,16.5993690491 -1.24811065197,1.64452922344,16.5989551544 -1.19514799118,1.64254927635,16.5865402222 -1.14518463612,1.64656889439,16.6251182556 -1.09222173691,1.64458882809,16.6067066193 -1.03925931454,1.64460897446,16.6092834473 -0.988295972347,1.64562857151,16.6218719482 -0.960315108299,1.6416387558,16.5896644592 -0.906353056431,1.63965904713,16.5682430267 -0.854390144348,1.63967883587,16.5708236694 -0.802427053452,1.63869857788,16.5684108734 -0.75046402216,1.63771808147,16.5629959106 -0.697501718998,1.63773810863,16.5565757751 -0.671519994736,1.63574779034,16.5403728485 -0.619557261467,1.6367675066,16.5509529114 -0.567594468594,1.63678717613,16.5565376282 -0.515631318092,1.634806633,16.5401248932 -0.463668584824,1.63582634926,16.5497055054 -0.411705881357,1.63784599304,16.564289093 -0.359742879868,1.63586544991,16.5508747101 -0.333761543036,1.63687515259,16.56366539 -0.281798690557,1.63789474964,16.5662498474 -0.229835823178,1.63791418076,16.5698356628 -0.177872881293,1.63593363762,16.5564212799 -0.125909999013,1.63595306873,16.5510044098 -0.0739471018314,1.63297247887,16.528591156 -0.0479656793177,1.63298213482,16.5223827362 --0.00199852744117,1.63600075245,15.6809825897 --0.0269800201058,1.62001037598,15.5477714539 --0.0759439989924,1.6340290308,15.6643590927 --0.125907182693,1.63404810429,15.6679382324 --0.174871116877,1.63506686687,15.6745262146 --0.223834991455,1.63408541679,15.6651124954 --0.272798866034,1.63410413265,15.6606998444 --0.321762800217,1.6341227293,15.6632881165 --0.34674435854,1.63413226604,15.6620769501 --0.395708292723,1.63515079021,15.6626653671 --0.444672167301,1.63416934013,15.6592531204 --0.494635522366,1.63618826866,15.66883564 --0.544598937035,1.63820695877,15.6824197769 --0.59356290102,1.63822543621,15.6810083389 --0.618544578552,1.63823485374,15.6837997437 --0.666508853436,1.63625311852,15.6593885422 --0.716472387314,1.63827168941,15.6739749908 --0.766435921192,1.63929033279,15.6855621338 --0.816399157047,1.64030897617,15.6851434708 --0.86636275053,1.64132750034,15.6977310181 --0.916326522827,1.64434599876,15.7143220901 --0.940308749676,1.64335489273,15.70611763 --0.991271853447,1.64537370205,15.7227020264 --1.04023587704,1.64539182186,15.7192926407 --1.089199543,1.64441025257,15.7018756866 --1.18912672997,1.64644706249,15.7090482712 --1.23909032345,1.64746522903,15.7156381607 --1.2630726099,1.64647424221,15.709435463 --1.31203627586,1.6454924345,15.6950187683 --1.36399924755,1.64951109886,15.7196054459 --1.41396307945,1.65052914619,15.7271976471 --1.46492624283,1.65154767036,15.7337818146 --1.51389014721,1.65156567097,15.7223682404 --1.56485366821,1.65358388424,15.7369594574 --1.59183490276,1.65659332275,15.7567539215 --1.64179837704,1.65661144257,15.7523393631 --1.69276177883,1.65762960911,15.760928154 --1.74272561073,1.65864765644,15.7635202408 --1.79368889332,1.6606657505,15.7691087723 --1.84465241432,1.66168391705,15.7766981125 --1.86963450909,1.66269278526,15.7774953842 --1.92159748077,1.66471123695,15.7890825272 --1.97256076336,1.66572928429,15.7906684875 --2.02152514458,1.66574680805,15.7832622528 --2.07548737526,1.66876542568,15.8058462143 --2.12745046616,1.67078351974,15.8164358139 --2.17941379547,1.67380166054,15.8270273209 --2.20439600945,1.67381048203,15.8258237839 --2.25835824013,1.67682898045,15.845410347 --2.31032156944,1.6788469553,15.8519992828 --2.36228489876,1.68086481094,15.8595895767 --2.41324853897,1.68188261986,15.8621835709 --2.46621131897,1.68390071392,15.8737726212 --2.51917433739,1.68591868877,15.8853635788 --2.54615592957,1.68792784214,15.894159317 --2.59711933136,1.68894541264,15.891749382 --2.65108203888,1.69096362591,15.9063386917 --2.70304536819,1.69298136234,15.9099302292 --2.75500869751,1.69399905205,15.9125213623 --2.80897164345,1.69701695442,15.9271125793 --2.83495330811,1.69802582264,15.9279088974 --2.88591718674,1.69804334641,15.9245004654 --2.93887996674,1.70006108284,15.9280872345 --2.98984408379,1.70107853413,15.9246816635 --3.04480648041,1.7040964365,15.9402723312 --3.09577012062,1.70411384106,15.9318580627 --3.15073275566,1.70713174343,15.9474515915 --3.17571473122,1.7071403265,15.9422483444 --3.23067736626,1.71015822887,15.9548377991 --3.28164148331,1.71117532253,15.9524364471 --3.33460426331,1.71219289303,15.9510211945 --3.38856768608,1.71421051025,15.9596166611 --3.44153094292,1.71622776985,15.9622087479 --3.49349474907,1.71724486351,15.9598026276 --3.52647423744,1.72125482559,15.9875955582 --3.57243990898,1.7192709446,15.9581890106 --3.63040137291,1.72328901291,15.9797801971 --3.683365345,1.72530603409,15.983379364 --3.73432922363,1.72532296181,15.9729690552 --3.79029178619,1.72834062576,15.9845600128 --3.84725379944,1.73135840893,15.9991521835 --3.87323594093,1.7323666811,15.9979505539 --3.92819881439,1.73438417912,16.0035419464 --3.98316192627,1.73640143871,16.0091362 --4.03812456131,1.73841869831,16.0137252808 --4.09108877182,1.74043548107,16.0143280029 --4.14705133438,1.74245297909,16.0199146271 --4.17903184891,1.74546217918,16.0407142639 --4.23799371719,1.75047981739,16.0613117218 --4.29395627975,1.7524971962,16.066904068 --4.35191869736,1.75551450253,16.0814990997 --4.40588188171,1.7575315237,16.0770874023 --4.46384429932,1.76054883003,16.0896835327 --4.5138092041,1.76056492329,16.0742797852 --4.5407910347,1.76157331467,16.0730762482 --4.60075283051,1.76559090614,16.0926742554 --4.65571594238,1.76660776138,16.0912647247 --4.70768022537,1.76762402058,16.081861496 --4.76264333725,1.76964080334,16.0794525146 --4.81460762024,1.76965689659,16.0700492859 --4.86857175827,1.77167332172,16.0656452179 --4.90055179596,1.77368235588,16.0794410706 --4.95651483536,1.77569913864,16.080034256 --5.01347827911,1.77871584892,16.0846309662 --5.07244062424,1.78173291683,16.0952262878 --5.13340234756,1.78575015068,16.1128253937 --5.1963634491,1.79076766968,16.1344203949 --5.22334575653,1.79177570343,16.1312198639 --5.27630996704,1.79179179668,16.1198101044 --5.30228185654,1.78280377388,16.0274047852 --5.31125926971,1.76781308651,15.888001442 --5.34422969818,1.76182591915,15.8195934296 --5.39019584656,1.75984084606,15.7891836166 --5.43716192245,1.75885570049,15.7647809982 --5.45914554596,1.75786292553,15.7485799789 --5.51410961151,1.75987899303,15.7451734543 --5.57507181168,1.76389563084,15.7617750168 --5.6270365715,1.76491129398,15.7493686676 --5.67700195312,1.76492643356,15.7309617996 --5.73596429825,1.76794290543,15.7385587692 --5.78393125534,1.76795756817,15.7181606293 --5.80691432953,1.766964674,15.7039585114 --5.85588026047,1.76697957516,15.6825504303 --5.90884542465,1.7689948082,15.6751527786 --5.95881032944,1.76900982857,15.6557435989 --6.00677728653,1.76802444458,15.6333398819 --6.05974197388,1.76903951168,15.6249408722 --6.0897231102,1.77104783058,15.6277360916 --6.14268827438,1.77206277847,15.6193380356 --6.1886548996,1.77107703686,15.5909328461 --6.23462200165,1.77009105682,15.5635309219 --6.28858757019,1.77210617065,15.5561294556 --6.34055233002,1.77312111855,15.5417222977 --6.3935174942,1.77413582802,15.5323238373 --6.42449903488,1.77614402771,15.5381231308 --6.47846364975,1.77815902233,15.5287189484 --6.53542804718,1.78017425537,15.5283203125 --6.58639383316,1.78118884563,15.5109148026 --6.63436079025,1.78120267391,15.4895172119 --6.68632650375,1.78221714497,15.4751138687 --6.73829174042,1.7822316885,15.4597082138 --6.75727701187,1.78123795986,15.4375095367 --6.80724287033,1.78125202656,15.4181060791 --6.86520719528,1.78426706791,15.4177055359 --6.91017532349,1.78328049183,15.3883056641 --6.95914173126,1.78329432011,15.365899086 --7.01410675049,1.78530883789,15.358499527 --7.03509140015,1.78431510925,15.3413028717 --7.08305835724,1.78432869911,15.3168973923 --5.48949289322,1.32612299919,11.7462434769 --7.18299198151,1.78535628319,15.2790966034 --7.2429561615,1.78837120533,15.2827014923 --7.27892637253,1.78538298607,15.2322940826 --5.62737607956,1.32417201996,11.655632019 --5.73933458328,1.34919059277,11.8414449692 --7.41684007645,1.79041850567,15.2112951279 --7.4658074379,1.79043185711,15.1888914108 --7.51677370071,1.79144537449,15.172495842 --6.00118303299,1.37925481796,11.994852066 --7.63170385361,1.79647397995,15.1626958847 --5.87018156052,1.32525289059,11.5460109711 --5.90016365051,1.32826054096,11.5598115921 --5.88614749908,1.31526613235,11.4413976669 --5.97310447693,1.32828485966,11.5210008621 --5.99907779694,1.32629561424,11.4825992584 --6.15401506424,1.35632276535,11.6902132034 --6.24796962738,1.37034201622,11.7798233032 --6.2389626503,1.36334443092,11.7166128159 --6.16896295547,1.33634293079,11.4951915741 --6.22492837906,1.34135735035,11.5117902756 --6.38486433029,1.3723846674,11.721411705 --6.38984394073,1.364392519,11.6409988403 --6.50579357147,1.38341403008,11.7666158676 --6.53076696396,1.38042426109,11.7232093811 --6.40379285812,1.34541213512,11.4509868622 --6.57272720337,1.37744009495,11.6676044464 --6.49472999573,1.35043764114,11.4421806335 --6.51470518112,1.34644722939,11.3917703629 --6.41571378708,1.31444227695,11.134344101 --6.67062473297,1.36548042297,11.4959802628 --6.59562683105,1.34047818184,11.2845687866 --6.61861133575,1.34148442745,11.2823667526 --6.79254436493,1.37351238728,11.4979915619 --8.754986763,1.81775510311,14.7449245453 --6.9284696579,1.3875426054,11.5591897964 --6.8964600563,1.37254559994,11.4227771759 --6.98641729355,1.38456296921,11.4913921356 --6.92042589188,1.36555874348,11.340171814 --6.8944144249,1.35156238079,11.2167606354 --7.04235506058,1.37658667564,11.3773756027 --7.1832985878,1.40060985088,11.5259981155 --7.22626829147,1.40162158012,11.5125932693 --7.06929254532,1.35860991478,11.1811590195 --7.23123025894,1.3866353035,11.3597831726 --7.25821399689,1.38864183426,11.3625850677 --7.37816286087,1.40766215324,11.4711990356 --7.59208726883,1.44569313526,11.7248315811 --7.36613035202,1.38867390156,11.2933826447 --7.34711694717,1.37767827511,11.184967041 --7.4310760498,1.38769412041,11.236579895 --7.43105745316,1.37970066071,11.1581687927 --7.47303771973,1.38570857048,11.1839771271 --7.51400852203,1.38671946526,11.1685781479 --7.61496305466,1.40073728561,11.2411832809 --7.69292449951,1.4087523222,11.279791832 --7.69890499115,1.40275919437,11.212389946 --7.76886892319,1.41077315807,11.2390003204 --7.70787620544,1.39376962185,11.1117839813 --7.92280101776,1.43079936504,11.346414566 --7.78082084656,1.39479005337,11.0649766922 --8.21568775177,1.47584342957,11.61165905 --7.89375543594,1.40381455421,11.0771894455 --7.973716259,1.4128292799,11.1147956848 --8.59053611755,1.5299012661,11.9035148621 --8.13764667511,1.43485593796,11.2312164307 --8.0576505661,1.41185343266,11.0457963943 --8.16860389709,1.42687118053,11.1244106293 --8.85240745544,1.5559489727,11.9851427078 --8.70742702484,1.5199393034,11.7087078094 --8.60243797302,1.49193406105,11.489279747 --8.59142303467,1.48193860054,11.3988742828 --8.54442691803,1.46993660927,11.2976570129 --8.40644550323,1.4359279871,11.040225029 --8.56138801575,1.4589496851,11.1708459854 --8.59436225891,1.458958745,11.1404466629 --8.74830532074,1.48098003864,11.2680749893 --8.69730186462,1.46498036385,11.127655983 --8.57132530212,1.43797039986,10.9294309616 --8.80224895477,1.47499918938,11.1540756226 --8.77124023438,1.46200156212,11.0416631699 --8.80921268463,1.46301090717,11.0162582397 --8.93016529083,1.47902810574,11.0968809128 --8.93314743042,1.47303390503,11.0284767151 --8.70318984985,1.4240167141,10.6720237732 --8.9251241684,1.4620411396,10.9108638763 --9.07007026672,1.48206043243,11.0184926987 --9.10404491425,1.4820690155,10.9880914688 --9.15601539612,1.48507928848,10.9796962738 --9.17699337006,1.48308646679,10.9342975616 --9.15798187256,1.47308981419,10.8408870697 --9.15096664429,1.46609437466,10.7624797821 --9.208943367,1.47310233116,10.796289444 --9.128947258,1.45209991932,10.6328687668 --9.40886116028,1.49713110924,10.8915214539 --5.58779621124,0.80378484726,6.37518978119 --5.59977483749,0.80279314518,6.34677553177 --5.63070297241,0.79582041502,6.23834609985 --5.65267944336,0.795829236507,6.22294569016 --5.68165445328,0.797838628292,6.21554946899 --5.57529067993,0.712977528572,5.30170106888 --5.61127376556,0.716983616352,5.31950759888 --5.6562461853,0.721993625164,5.32911920547 --5.67920446396,0.720008909702,5.28129768372 --5.69118404388,0.720016419888,5.25889778137 --7.05285406113,0.936122119427,6.50789117813 --5.86911678314,0.744039356709,5.37433242798 --5.68514156342,0.712032496929,5.16888046265 --5.70611858368,0.713040709496,5.15447473526 --5.73409461975,0.714049458504,5.14606618881 --5.75807142258,0.7160577178,5.13466644287 --5.79104614258,0.718066513538,5.13126802444 --5.82302188873,0.721075296402,5.12687063217 --5.82901096344,0.720079123974,5.11465787888 --5.85998725891,0.723087728024,5.10926103592 --5.88996267319,0.725096106529,5.10286521912 --5.90394210815,0.724103450775,5.08246850967 --7.89027309418,0.990308940411,6.23835039139 --6.73837184906,0.794293224812,4.99532651901 --6.75135278702,0.794299542904,4.97192907333 --5.5295882225,0.613242924213,4.01709985733 --5.53656959534,0.612249732018,3.99469089508 --5.52255487442,0.608255624771,3.95626759529 --5.54953241348,0.610263109207,3.94988131523 --7.72978591919,0.881465613842,4.8526673317 --7.84272623062,0.891481399536,4.83768463135 --7.89970111847,0.897487878799,4.83930253983 --7.9546751976,0.902494370937,4.83790397644 --8.0206489563,0.90950101614,4.84452676773 --11.7669296265,1.42162895203,7.10514593124 --11.7849140167,1.42163133621,7.06474781036 --11.7669057846,1.41563260555,7.00233697891 --11.7868900299,1.41563498974,6.96394395828 --11.7718811035,1.41063630581,6.90353155136 --11.7858667374,1.40863847733,6.86113166809 --11.7638654709,1.40463864803,6.82292413712 --11.7708520889,1.40264058113,6.7765212059 --11.7488451004,1.39664161205,6.71411561966 --11.7638301849,1.39564371109,6.67271566391 --11.7458229065,1.39064490795,6.61230421066 --11.7558097839,1.38864672184,6.56890726089 --11.7458000183,1.38464808464,6.51450586319 --11.7427949905,1.38264882565,6.48729562759 --11.7327852249,1.37865018845,6.43289089203 --11.957734108,1.40665686131,6.5095615387 --11.7767553329,1.37965428829,6.36010217667 --11.8667287827,1.38865768909,6.36072731018 --11.9327068329,1.39466035366,6.34835004807 --12.0206794739,1.40366339684,6.34697580338 --12.0856637955,1.41066527367,6.3567905426 --12.1476411819,1.41666769981,6.34141492844 --12.188624382,1.41966950893,6.31402778625 --12.2006120682,1.41867077351,6.27062654495 --12.2805776596,1.42367398739,6.21384954453 --8.00527477264,0.85761141777,3.95894241333 --7.99426984787,0.855613410473,3.93672919273 --7.99125623703,0.853617429733,3.90332388878 --7.98724269867,0.85162127018,3.86992311478 --7.98822879791,0.849625349045,3.83851623535 --7.9882144928,0.84762942791,3.80610084534 --7.98820066452,0.846633434296,3.77469706535 --7.98718690872,0.844637334347,3.74329853058 --7.97018289566,0.84163916111,3.71908664703 --7.97216844559,0.840643167496,3.68868017197 --7.98215293884,0.840647220612,3.66227769852 --7.96914100647,0.836651027203,3.62486600876 --7.96612739563,0.834654867649,3.59245920181 --7.97411251068,0.83465886116,3.56505274773 --7.96010780334,0.831660807133,3.54284143448 --7.96309375763,0.830664694309,3.51343584061 --7.95808029175,0.82866859436,3.48002195358 --7.9860625267,0.830672502518,3.46263241768 --8.05303955078,0.837676405907,3.46225142479 --8.11001682281,0.843680262566,3.45686483383 --8.17399406433,0.850683987141,3.45448470116 --8.21898078918,0.855685710907,3.45930480957 --8.29195594788,0.863689303398,3.45992398262 --8.34193611145,0.868692815304,3.44952726364 --8.38391590118,0.87269616127,3.43613743782 --8.4538936615,0.879699289799,3.43476200104 --8.5068731308,0.885702490807,3.42537498474 --8.56785106659,0.891705453396,3.41899108887 --8.62783718109,0.898706674576,3.42882061005 --11.632390976,1.27569425106,4.59914398193 --11.6433792114,1.27569496632,4.55973672867 --11.6233730316,1.27069568634,4.50933265686 --11.632361412,1.27069628239,4.46993112564 --11.6303529739,1.26869702339,4.42652797699 --11.6223487854,1.26669740677,4.40232658386 --11.5943431854,1.26069831848,4.34790372849 --11.6403264999,1.26469838619,4.32351922989 --11.6523160934,1.26469886303,4.28612422943 --11.6733036041,1.26569902897,4.25172901154 --11.6672954559,1.26269948483,4.20732498169 --11.5962953568,1.25270104408,4.13889741898 --11.6032896042,1.25270116329,4.11968994141 --11.5962810516,1.24970185757,4.07528400421 --11.5962724686,1.24870216846,4.03388357162 --11.5872650146,1.24570274353,3.98948144913 --11.5982532501,1.24570298195,3.95107460022 --11.5772476196,1.2417037487,3.90266728401 --11.5862369537,1.24070382118,3.86426472664 --11.5792331696,1.23870420456,3.84206914902 --11.5802249908,1.23770439625,3.80066037178 --11.5652170181,1.23470497131,3.7542488575 --11.5842065811,1.23570489883,3.71985411644 --11.5492019653,1.22970592976,3.66743898392 --11.4522037506,1.21570849419,3.59500074387 --11.4201993942,1.21070957184,3.54458808899 --11.3981971741,1.20671033859,3.51636743546 --11.4041872025,1.2067104578,3.47897291183 --11.4071779251,1.20571064949,3.43956613541 --11.3921718597,1.20271122456,3.39515829086 --11.3921632767,1.20071148872,3.35575819016 --11.4011535645,1.20071136951,3.31835269928 --11.4021444321,1.19971144199,3.27995872498 --11.3811426163,1.19571220875,3.25374794006 --11.3921327591,1.19571208954,3.21734595299 --11.3801259995,1.19371259212,3.17393255234 --11.4071140289,1.1957116127,3.14355015755 --11.3771095276,1.19071269035,3.09512972832 --11.3821001053,1.18971252441,3.05773139 --11.3870954514,1.1897124052,3.03953099251 --11.3800878525,1.18771255016,2.99812030792 --11.3780794144,1.18671262264,2.95871710777 --11.3730726242,1.1847127676,2.91830992699 --11.3860626221,1.18471205235,2.88291096687 --11.3760557175,1.18271243572,2.84150362015 --11.372048378,1.18071246147,2.80210185051 --11.3650445938,1.17971253395,2.78089666367 --11.3860349655,1.1807115078,2.74749898911 --11.36302948,1.17671215534,2.70308613777 --11.3450222015,1.17371273041,2.66068100929 --11.3550138474,1.17371201515,2.62528610229 --11.4030017853,1.17870950699,2.59789299965 --11.4229917526,1.17970824242,2.56449961662 --11.459985733,1.18370616436,2.55431461334 --11.475976944,1.184705019,2.51992082596 --11.5249652863,1.189702034,2.49253416061 --11.5369567871,1.19070088863,2.45714044571 --11.4739551544,1.1817034483,2.40370440483 --11.4489488602,1.17770421505,2.36029577255 --11.4759397507,1.17970216274,2.32790207863 --11.6629219055,1.20169174671,2.3497800827 --11.7109107971,1.20668828487,2.32139801979 --11.7269029617,1.20768642426,2.28600287437 --11.772892952,1.21268284321,2.25661802292 --11.8008832932,1.21468019485,2.22322559357 --11.8468742371,1.21967637539,2.1938457489 --11.8498668671,1.21867513657,2.15544581413 --11.8578634262,1.2196739912,2.13724517822 --11.8378582001,1.2156740427,2.09382939339 --11.2438936234,1.14470934868,1.94217860699 --11.2738847733,1.14770686626,1.91078794003 --11.3308734894,1.15370237827,1.8834002018 --11.3748645782,1.1576987505,1.85502529144 --11.5328502655,1.17568790913,1.86388325691 --11.2418622971,1.14070594311,1.77535951138 --11.2498559952,1.14070463181,1.73995995522 --11.3528423309,1.15269672871,1.72060096264 --11.2668418884,1.14170157909,1.6691596508 --11.4438247681,1.16168820858,1.66082906723 --11.4428186417,1.1616871357,1.62342584133 --11.4958086014,1.16668212414,1.59505236149 --11.4318094254,1.15868604183,1.56581628323 --11.3318090439,1.14669215679,1.51336801052 --11.3048038483,1.14269304276,1.47295749187 --11.2538003922,1.13569569588,1.42852830887 --11.3687877655,1.14868569374,1.40817368031 --11.471777916,1.16067636013,1.3858178854 --11.4927711487,1.16267335415,1.35142278671 --11.4827690125,1.1606733799,1.33222484589 --11.3537693024,1.14568209648,1.27775943279 --11.3087654114,1.13968443871,1.2353361845 --11.4137544632,1.15167438984,1.21198058128 --11.293753624,1.13668274879,1.16052293777 --11.1757526398,1.12269115448,1.11006546021 --11.3907423019,1.14767241478,1.11695849895 --11.3047389984,1.13667809963,1.0705165863 --11.1047410965,1.11269378662,1.01202213764 --11.1797323227,1.12068593502,0.984656274319 --11.3257226944,1.13767147064,0.964323878288 --11.291718483,1.13367283344,0.923898100853 --11.2097158432,1.12367856503,0.879455149174 --11.2117128372,1.12367761135,0.862261116505 --11.1357097626,1.11368298531,0.818818211555 --11.1467037201,1.11468029022,0.784423410892 --11.1716985703,1.11767625809,0.751033067703 --11.1306943893,1.11267840862,0.711608111858 --11.0976896286,1.10868000984,0.673187673092 --11.0806846619,1.10567986965,0.636781096458 --11.1776800156,1.11666953564,0.625615656376 --11.1146764755,1.10967385769,0.585181117058 --11.1106719971,1.10867249966,0.549780249596 --11.0316677094,1.0996786356,0.509342849255 --11.1966609955,1.11865997314,0.48401093483 --11.1136569977,1.10866653919,0.443571507931 --11.1056528091,1.10666549206,0.407158762217 --11.131649971,1.10966169834,0.39097031951 --11.1356458664,1.11065924168,0.355567187071 --11.1886405945,1.11665153503,0.323194891214 --11.2406368256,1.12264370918,0.289814949036 --11.2576313019,1.1236397028,0.25441634655 --11.0586280823,1.10065925121,0.210920318961 --11.0696239471,1.10165596008,0.17652694881 --11.1616210938,1.11264443398,0.161360666156 --11.1586170197,1.11164259911,0.12595847249 --11.1156139374,1.10664522648,0.0895379334688 --11.0576086044,1.09964942932,0.0520997233689 --11.0876045227,1.10364365578,0.0177120286971 --11.193602562,1.11562883854,-0.0156412478536 --11.2635993958,1.12361800671,-0.0500093586743 --11.3275985718,1.13160920143,-0.0661708936095 --11.2785930634,1.12561225891,-0.103607602417 --11.2405900955,1.12061417103,-0.139020726085 --11.2165870667,1.11861431599,-0.17544233799 --11.1295824051,1.10762238503,-0.210883632302 --11.3415822983,1.13259315491,-0.247190579772 --11.2285766602,1.11960458755,-0.282648205757 --11.2485752106,1.1216006279,-0.30084246397 --11.2655725479,1.12359547615,-0.336231410503 --11.1935691833,1.11560177803,-0.371676027775 --11.4495716095,1.14556562901,-0.410949975252 --11.3795671463,1.13757145405,-0.446391433477 --11.4225654602,1.142562747,-0.482764959335 --11.2225580215,1.11958599091,-0.514268994331 --11.3615598679,1.13556575775,-0.536408364773 --11.3485584259,1.13456428051,-0.57181417942 --11.307554245,1.12956655025,-0.606233775616 --11.2345495224,1.12157320976,-0.639674305916 --11.3285503387,1.13255691528,-0.679029643536 --11.2905464172,1.12855875492,-0.713451385498 --11.3355474472,1.13355076313,-0.733633041382 --11.2445421219,1.12256002426,-0.766088664532 --11.375544548,1.13853788376,-0.808425486088 --11.3645429611,1.13753581047,-0.843831241131 --11.4675455093,1.14951729774,-0.886185824871 --11.4395427704,1.14651751518,-0.920597612858 --11.4665431976,1.15050959587,-0.958989441395 --11.5485467911,1.15949559212,-0.982144773006 --11.405538559,1.14351284504,-1.0096231699 --11.2975311279,1.13152503967,-1.03908872604 --11.2975292206,1.13152134418,-1.07448387146 --11.4075345993,1.14450061321,-1.11882841587 --11.5035390854,1.15648174286,-1.16318464279 --11.472536087,1.1524823904,-1.19760549068 --11.5325403214,1.16047084332,-1.22077345848 --11.4755353928,1.15347540379,-1.25321114063 --11.5085372925,1.15846586227,-1.29259324074 --11.5225381851,1.1604591608,-1.33099102974 --11.6795473099,1.17842948437,-1.38331365585 --11.5965423584,1.16943824291,-1.41276288033 --11.5445394516,1.16444206238,-1.4441883564 --11.4005279541,1.1474634409,-1.44746339321 --11.5155363083,1.16143989563,-1.49680912495 --11.487534523,1.15843975544,-1.53123223782 --11.4935340881,1.15943408012,-1.56862902641 --11.4435319901,1.15443778038,-1.60006165504 --11.3785257339,1.1474442482,-1.62849247456 --11.4485311508,1.1554274559,-1.67385792732 --11.4125289917,1.15243124962,-1.68808186054 --11.4295301437,1.15442347527,-1.72747933865 --11.3955287933,1.15142440796,-1.7599003315 --11.4195308685,1.15441524982,-1.80029344559 --11.4565353394,1.15940380096,-1.84166896343 --11.5475435257,1.17038249969,-1.89202725887 --11.5575466156,1.17237532139,-1.9314302206 --11.441534996,1.15939366817,-1.93268835545 --11.3675298691,1.1514018774,-1.95913493633 --11.3695306778,1.15239644051,-1.99653851986 --11.4125366211,1.15738332272,-2.039914608 --11.5445518494,1.17435336113,-2.09824824333 --11.5365514755,1.17334926128,-2.13465595245 --11.5495557785,1.17634129524,-2.17404770851 --11.5075511932,1.17134642601,-2.18627595901 --11.5645589828,1.1783298254,-2.23364830017 --11.5515604019,1.17832660675,-2.26905679703 --11.6025676727,1.18531095982,-2.31643748283 --11.5405626297,1.17831707001,-2.34286928177 --11.5225629807,1.1773147583,-2.37728023529 --11.53556633,1.17930626869,-2.41767692566 --11.6195783615,1.18928647041,-2.4528362751 --11.6785879135,1.19726860523,-2.50220513344 --11.6365861893,1.1932708025,-2.5326321125 --11.7015972137,1.20225131512,-2.58400058746 --11.7055997849,1.20324409008,-2.62339997292 --11.8826265335,1.22520112991,-2.6987092495 --11.9896430969,1.23817563057,-2.74085569382 --12.0186519623,1.2431627512,-2.78623843193 --11.8826360703,1.22818410397,-2.79671120644 --11.9326477051,1.23516666889,-2.84708714485 --11.8696432114,1.22817277908,-2.87353038788 --11.9526596069,1.23914790154,-2.93189001083 --11.8836536407,1.23215544224,-2.95633292198 --12.1466941833,1.26409542561,-3.03538131714 --12.1827049255,1.26907992363,-3.08476829529 --12.1587057114,1.26707756519,-3.11917638779 --12.1627130508,1.26906871796,-3.16158366203 --12.1287126541,1.26606845856,-3.19400286674 --12.1307182312,1.26706016064,-3.2354054451 --12.2827482224,1.28701817989,-3.31372141838 --12.177734375,1.27503752708,-3.30898833275 --12.2397508621,1.28301548958,-3.36535191536 --12.3677778244,1.29997813702,-3.43968439102 --12.4467973709,1.31095147133,-3.50204229355 --12.5518226624,1.32491862774,-3.57138109207 --12.3818006516,1.30494916439,-3.56887984276 --12.4038105011,1.30893516541,-3.61727285385 --12.4328231812,1.31391942501,-3.6676607132 --12.6058578491,1.33587408066,-3.73676800728 --12.5378541946,1.32888114452,-3.76020169258 --13.3390083313,1.42768025398,-4.02915763855 --13.4240341187,1.43964934349,-4.09951543808 --13.3700332642,1.43365156651,-4.12994623184 --13.3410377502,1.43164801598,-4.16736316681 --13.3360424042,1.43264377117,-4.18856430054 --13.4460744858,1.44760608673,-4.26690101624 --13.3630685806,1.43861556053,-4.28834915161 --13.4640989304,1.45257937908,-4.36569643021 --13.6141395569,1.47253036499,-4.4590177536 --13.5741424561,1.4695289135,-4.49343824387 --13.5681533813,1.47051894665,-4.53884315491 --13.5901641846,1.47350752354,-4.5690279007 --15.750626564,1.73994255066,-5.30620384216 --15.7706480026,1.7449221611,-5.36759138107 --16.1157398224,1.78881704807,-5.53579854965 --16.1537666321,1.79579102993,-5.60517835617 --16.1457843781,1.79677700996,-5.65857744217 --16.1398010254,1.79776215553,-5.7139840126 --14.8755455017,1.64507448673,-5.36730623245 --15.9968166351,1.7857593298,-5.80706310272 --13.6332921982,1.49538064003,-5.03982543945 --14.0904121399,1.55424392223,-5.24895906448 --14.1844491959,1.56720459461,-5.3333106041 --14.2324752808,1.57517766953,-5.40067863464 --14.2414855957,1.57716822624,-5.42987728119 --14.3335237503,1.59112870693,-5.51422262192 --14.2395162582,1.5811406374,-5.53168201447 --14.1845188141,1.57614195347,-5.56211185455 --14.2825584412,1.59109997749,-5.65045833588 --14.4476165771,1.61403858662,-5.76476335526 --14.4566354752,1.61702132225,-5.8201546669 --14.490653038,1.62200415134,-5.859333992 --14.5466852188,1.63197267056,-5.93470859528 --14.776763916,1.66289067268,-6.0779747963 --14.870806694,1.67684733868,-6.16932106018 --14.9448451996,1.68880987167,-6.25267314911 --15.1299142838,1.71373867989,-6.3829703331 --15.2669715881,1.73368120193,-6.49428939819 --15.4190244675,1.7546274662,-6.58439922333 --15.4490528107,1.76060092449,-6.65378141403 --15.5521030426,1.77555263042,-6.75311517715 --15.7201728821,1.79948341846,-6.88242340088 --15.7081918716,1.80146872997,-6.93582963943 --15.8062419891,1.81642043591,-7.0361700058 --15.9983215332,1.84334254265,-7.17745256424 --16.209394455,1.87126731873,-7.29953241348 --16.4604930878,1.90616953373,-7.46978187561 --16.6775836945,1.93708145618,-7.62705135345 --16.944688797,1.97397637367,-7.80929660797 --16.9017047882,1.97096884251,-7.85371685028 --17.2708454132,2.02182936668,-8.08489894867 --17.4589309692,2.04874706268,-8.23618507385 --17.7010211945,2.08165788651,-8.38024139404 --18.1121826172,2.1375014782,-8.63739490509 --18.1332206726,2.14347052574,-8.71577548981 --18.2983055115,2.16839194298,-8.86408138275 --18.4283809662,2.18932437897,-8.99539852142 --18.4144115448,2.19030356407,-9.06080818176 --18.7955684662,2.24315166473,-9.3139705658 --18.7845821381,2.24414181709,-9.34618091583 --18.756608963,2.24412512779,-9.40559387207 --18.8276672363,2.2570745945,-9.5139503479 --19.0007629395,2.28298902512,-9.67324352264 --19.0798282623,2.29793477058,-9.78759479523 --19.0998725891,2.30390048027,-9.87197494507 --19.1128978729,2.30788207054,-9.9171705246 --19.1359424591,2.31484627724,-10.0045528412 --19.1689929962,2.32280659676,-10.0969266891 --19.2600650787,2.3387465477,-10.2202682495 --19.2531013489,2.3417198658,-10.2946748734 --19.2411365509,2.34469556808,-10.3650760651 --19.2371768951,2.34866762161,-10.4414806366 --19.2472000122,2.35164952278,-10.4856729507 --19.2402381897,2.35462284088,-10.5590696335 --19.2332782745,2.35859560966,-10.634475708 --19.2133102417,2.36057329178,-10.7018852234 --19.210351944,2.36454486847,-10.7782812119 --19.2113952637,2.36851406097,-10.8586826324 --19.1954307556,2.37048983574,-10.9290904999 --19.1994533539,2.37347340584,-10.9702835083 --19.1804885864,2.37545013428,-11.0386896133 --19.1875362396,2.38141679764,-11.1230869293 --19.1805763245,2.38438844681,-11.1994895935 --19.1496086121,2.38536930084,-11.2619066238 --19.1356468201,2.3883433342,-11.334312439 --19.1306877136,2.39231419563,-11.4117116928 --19.1437168121,2.39629364014,-11.4599027634 --19.1467628479,2.40126037598,-11.5433006287 --19.1318035126,2.40423464775,-11.6157073975 --19.1248455048,2.40820527077,-11.6931085587 --19.1258926392,2.41317248344,-11.776509285 --19.1219367981,2.41714191437,-11.8559064865 --19.1149806976,2.42111182213,-11.9343090057 --19.1250095367,2.42509150505,-11.9825048447 --19.1170520782,2.42906188965,-12.0599040985 --19.1070976257,2.43303275108,-12.1373100281 --19.1151485443,2.438996315,-12.2257003784 --19.0761795044,2.43897867203,-12.2851228714 --19.0512161255,2.44095468521,-12.3545417786 --19.0252552032,2.44193196297,-12.421954155 --19.0182762146,2.44391798973,-12.459154129 --18.9883117676,2.44489598274,-12.5255756378 --18.9743537903,2.44886779785,-12.600979805 --18.9573974609,2.4518404007,-12.6753902435 --18.944442749,2.45481109619,-12.7527980804 --18.8974704742,2.4537961483,-12.8072242737 --18.8474998474,2.4527823925,-12.8606586456 --18.8975486755,2.46274352074,-12.9368238449 --18.8885955811,2.46671199799,-13.0172290802 --18.894651413,2.47267365456,-13.1086244583 --18.8556842804,2.47365474701,-13.1690473557 --18.8567371368,2.47961878777,-13.25644207 --18.8808040619,2.48857164383,-13.361828804 --19.1910133362,2.53839755058,-13.6650266647 --19.4681816101,2.58025574684,-13.903046608 --19.5502815247,2.59818029404,-14.0523929596 --19.519323349,2.60015511513,-14.1238136292 --19.474357605,2.6001367569,-14.1842403412 --19.3553562164,2.58915185928,-14.1917142868 --19.2743701935,2.58414959908,-14.2261657715 --19.1803798676,2.57615375519,-14.250623703 --19.1183757782,2.57116270065,-14.2518644333 --19.0263843536,2.56416654587,-14.2763185501 --18.9514026642,2.55916190147,-14.3147706985 --18.8614139557,2.5521645546,-14.3402261734 --18.7864322662,2.5481607914,-14.3766727448 --18.7264595032,2.5461499691,-14.4241104126 --18.6564483643,2.53916311264,-14.4183578491 --18.5834674835,2.53515839577,-14.4558057785 --18.5094852448,2.53015494347,-14.4912490845 --18.4174938202,2.52315950394,-14.5137109756 --18.3495140076,2.52015328407,-14.5531511307 --18.2745304108,2.51514959335,-14.5886030197 --18.1885433197,2.50915193558,-14.6140584946 --18.1395435333,2.50515604019,-14.6222915649 --18.0525531769,2.49915909767,-14.6467494965 --17.9825725555,2.4951543808,-14.6831922531 --17.8965816498,2.48915719986,-14.7076501846 --17.8266010284,2.48615193367,-14.7450990677 --17.7456130981,2.48015284538,-14.7725524902 --17.6776313782,2.47714781761,-14.8089914322 --17.6366386414,2.47414851189,-14.8222198486 --17.5596523285,2.46914720535,-14.8526725769 --17.483669281,2.46514606476,-14.8831233978 --17.4166870117,2.46114039421,-14.9205684662 --17.3477058411,2.45813560486,-14.9560136795 --17.2727222443,2.45313405991,-14.9864635468 --17.207742691,2.45112729073,-15.0259113312 --17.1457328796,2.44513988495,-15.0191497803 --17.0827560425,2.44213223457,-15.059595108 --17.0157756805,2.4391272068,-15.0950374603 --16.9387893677,2.43412709236,-15.1234951019 --16.8788127899,2.43211817741,-15.1649332047 --16.8018245697,2.42711830139,-15.1923894882 --16.7358436584,2.42411327362,-15.2278318405 --16.6988506317,2.4221124649,-15.2430610657 --16.6358718872,2.42010569572,-15.280500412 --16.5648899078,2.41610336304,-15.3119516373 --16.513917923,2.41509008408,-15.3603849411 --16.4499397278,2.41308355331,-15.3978309631 --16.399969101,2.41206979752,-15.4472646713 --16.3369922638,2.4100625515,-15.4857130051 --16.3120079041,2.41005587578,-15.5099277496 --16.2480297089,2.4070494175,-15.5473766327 --16.1930561066,2.4060382843,-15.5918140411 --16.1380825043,2.40502738953,-15.6362524033 --16.0871124268,2.40401387215,-15.6846885681 --16.0321388245,2.40300226212,-15.730132103 --15.9741640091,2.40199351311,-15.7705688477 --15.9551839828,2.40298247337,-15.8017864227 --15.8982105255,2.40097260475,-15.8442268372 --15.8422365189,2.39996194839,-15.8876676559 --15.7762556076,2.39695739746,-15.9211158752 --15.7372951508,2.39893698692,-15.9805431366 --15.6893281937,2.39892148972,-16.0319805145 --15.6323547363,2.39791154861,-16.0744228363 --15.6033668518,2.39690685272,-16.0946426392 --15.5604047775,2.39888834953,-16.1510772705 --15.5114364624,2.398873806,-16.200510025 --15.4614686966,2.39885926247,-16.2499485016 --15.4155025482,2.39884281158,-16.3023796082 --15.3615322113,2.39883041382,-16.3488254547 --15.3145666122,2.39881443977,-16.4002590179 --15.2955875397,2.39980316162,-16.4314746857 --15.2396144867,2.39879274368,-16.4739151001 --15.1916484833,2.39977693558,-16.525352478 --15.1476860046,2.40075874329,-16.580783844 --15.090713501,2.39974808693,-16.6232318878 --15.0527563095,2.40172576904,-16.6856613159 --15.0227689743,2.40172171593,-16.7048854828 --14.9647951126,2.40071249008,-16.7453269958 --14.9148273468,2.40069794655,-16.7937641144 --14.8708658218,2.401679039,-16.8501987457 --14.8239011765,2.40266227722,-16.9026355743 --14.7729349136,2.40264797211,-16.9510746002 --14.7329769135,2.40562653542,-17.0115070343 --14.6770057678,2.40461540222,-17.0549526215 --14.6550254822,2.40560555458,-17.0831699371 --14.6180715561,2.4085817337,-17.147600174 --14.5751123428,2.40956139565,-17.2060375214 --14.5361566544,2.41253852844,-17.2684688568 --14.5212230682,2.41949915886,-17.3578796387 --14.4582462311,2.4174926281,-17.3933296204 --14.4232540131,2.41649150848,-17.4075603485 --14.2561779022,2.39556002617,-17.3180789948 --14.0250377655,2.36367511749,-17.1506462097 --13.917014122,2.35270309448,-17.1281261444 --13.8220033646,2.34572148323,-17.1215991974 --13.7750396729,2.34670495987,-17.1730384827 --13.7100572586,2.3447022438,-17.2014884949 --13.701089859,2.34768342972,-17.2446975708 --13.6481189728,2.34767174721,-17.2881393433 --13.6031579971,2.34865355492,-17.3425788879 --13.5441827774,2.34864592552,-17.379026413 --13.4872083664,2.3476369381,-17.4174728394 --13.428232193,2.34662938118,-17.4539203644 --13.36124897,2.34362840652,-17.4793739319 --13.3102378845,2.33964133263,-17.4696140289 --13.2462568283,2.33763766289,-17.4990653992 --13.1822767258,2.33563423157,-17.5285167694 --13.1243009567,2.33462643623,-17.5649662018 --13.0853452682,2.33760404587,-17.6253948212 --13.0183620453,2.33560276031,-17.6518554688 --12.9463720322,2.33160614967,-17.6693115234 --12.9023675919,2.32861423492,-17.667547226 --12.8453931808,2.32860565186,-17.7049942017 --12.7804098129,2.32560372353,-17.7314453125 --12.7014131546,2.32161259651,-17.7399120331 --12.6194086075,2.31562542915,-17.7413749695 --12.52339077,2.30764889717,-17.7248516083 --12.4534025192,2.30465126038,-17.7443122864 --12.4184055328,2.30265331268,-17.752538681 --12.323387146,2.29467725754,-17.7350120544 --12.245388031,2.2906870842,-17.7414779663 --12.1874113083,2.28968024254,-17.7759284973 --12.1054067612,2.28369426727,-17.7753944397 --12.0344142914,2.28069853783,-17.7908535004 --11.956366539,2.27073788643,-17.7361125946 --11.9154100418,2.27271723747,-17.7935466766 --11.8293991089,2.26673531532,-17.7860183716 --11.903585434,2.293612957,-18.0143737793 --11.2138242722,2.16116476059,-17.1082839966 --11.0599031448,2.16213703156,-17.2216205597 --10.9878559113,2.15217494965,-17.1688747406 --10.997961998,2.16611003876,-17.3002738953 --11.1873979568,2.22982168198,-17.8319549561 --11.1324243546,2.22981381416,-17.8674049377 --11.0644330978,2.2268178463,-17.8828659058 --11.0394487381,2.22781133652,-17.9050884247 --10.9744606018,2.2248134613,-17.9235420227 --10.9184846878,2.22480630875,-17.9579944611 --10.8514947891,2.22280979156,-17.9744548798 --10.7774925232,2.21882081032,-17.9779148102 --10.7024908066,2.21383261681,-17.980381012 --10.6124658585,2.20585942268,-17.9568538666 --10.607509613,2.21083402634,-18.0110626221 --10.5535373688,2.21182560921,-18.0475120544 --10.4855442047,2.20883059502,-18.0609741211 --10.4265642166,2.20782709122,-18.0894298553 --10.3755941391,2.20881652832,-18.1288700104 --10.3136091232,2.20781636238,-18.1513252258 --10.2305927277,2.20183730125,-18.1377983093 --10.1935920715,2.19984292984,-18.1390342712 --10.1366138458,2.19883799553,-18.1694831848 --10.0916538239,2.20182061195,-18.2209281921 --10.019654274,2.19783115387,-18.2253913879 --9.95266056061,2.19583654404,-18.2378520966 --9.87865638733,2.1908493042,-18.2383213043 --9.78461933136,2.18188476562,-18.1997947693 --9.76063632965,2.18287801743,-18.2220172882 --6.72593402863,1.45709347725,-12.7856903076 --9.62464523315,2.176892519,-18.240940094 --9.54963874817,2.17290711403,-18.2384128571 --9.47663402557,2.16892075539,-18.2368755341 --9.40763378143,2.16493034363,-18.2423381805 --9.33557224274,2.15397763252,-18.1725940704 --9.25355052948,2.14800214767,-18.1530666351 --9.20859146118,2.14998459816,-18.2045135498 --9.12656974792,2.14400935173,-18.1839885712 --9.06958866119,2.14400601387,-18.2114429474 --9.00960254669,2.14300727844,-18.2308940887 --8.9295835495,2.13703012466,-18.2133693695 --8.89758491516,2.13503360748,-18.2185955048 --8.83559799194,2.13403534889,-18.2370586395 --8.77060222626,2.13204264641,-18.2465171814 --8.70560741425,2.12904906273,-18.2569789886 --8.64061164856,2.12705612183,-18.2664375305 --8.58463287354,2.12705206871,-18.2948932648 --8.51963806152,2.12505936623,-18.3043556213 --5.46102762222,1.30279779434,-11.9428596497 --5.4250330925,1.30279922485,-11.9602956772 --8.35063362122,2.11708664894,-18.3115119934 --8.27361488342,2.11110949516,-18.2939834595 --8.19659614563,2.10613250732,-18.2764549255 --8.05244350433,2.08124303818,-18.1089725494 --7.98042964935,2.07626199722,-18.0984382629 --7.96246004105,2.07924723625,-18.1346626282 --7.87341070175,2.06928920746,-18.0841388702 --7.79037618637,2.06232190132,-18.0496196747 --7.73238945007,2.06132316589,-18.0690765381 --7.69644641876,2.0672955513,-18.1375141144 --7.63745880127,2.06629729271,-18.1559753418 --7.50438261032,2.05136179924,-18.0776958466 --6.69780826569,1.82640051842,-16.3227062225 --6.60172271729,1.81246447563,-16.2341918945 --6.54171466827,1.80947828293,-16.2316532135 --6.52680540085,1.82042789459,-16.3390827179 --6.5590004921,1.84630978107,-16.5624752045 --6.46291065216,1.83137643337,-16.4689540863 --6.41687297821,1.82540535927,-16.4302024841 --6.19449663162,1.77165782452,-16.018781662 --6.05530309677,1.74279129505,-15.8113021851 --6.05141735077,1.7567255497,-15.9447193146 --6.06457328796,1.77663302422,-16.124124527 --6.01057529449,1.77564048767,-16.1325817108 --5.92042589188,1.75474083424,-15.9708566666 --5.86441993713,1.75175273418,-15.9713125229 --5.86755657196,1.76967358589,-16.1277217865 --5.92182350159,1.80451083183,-16.4281044006 --5.53600549698,1.69104325771,-15.5358066559 --5.44390296936,1.67611682415,-15.4302883148 --5.43501091003,1.68905603886,-15.5557146072 --5.40800714493,1.68806242943,-15.5549402237 --5.33495140076,1.67910587788,-15.501411438 --5.26590394974,1.67114388943,-15.4568777084 --5.18683004379,1.66019880772,-15.383354187 --5.15287351608,1.66517913342,-15.4377946854 --5.047727108,1.64428019524,-15.2852907181 --5.00173902512,1.64428043365,-15.3057451248 --4.98676538467,1.64726758003,-15.3379621506 --4.97787952423,1.66220331192,-15.4693870544 --4.92587566376,1.66021406651,-15.4718427658 --4.867852211,1.65623688698,-15.4532985687 --4.928170681,1.69704449177,-15.8056774139 --5.13090658188,1.7935898304,-16.6089439392 --4.87029981613,1.71197974682,-15.9585485458 --4.82725095749,1.70501446724,-15.9097948074 --4.7592010498,1.69705414772,-15.8622608185 --4.67409896851,1.68312644958,-15.7587413788 --4.58699035645,1.66720306873,-15.6482286453 --4.52094078064,1.66024208069,-15.6016931534 --4.54417085648,1.6891067028,-15.8560943604 --4.56540107727,1.71797192097,-16.1094989777 --4.56648683548,1.72892272472,-16.204706192 --4.52251243591,1.73091542721,-16.2381534576 --4.4835562706,1.73589682579,-16.2916030884 --4.41650676727,1.728936553,-16.2440681458 --4.41868972778,1.75083172321,-16.4464855194 --4.33759498596,1.73789942265,-16.3509693146 --4.27255058289,1.73093569279,-16.3094348907 --4.22246837616,1.71999108791,-16.2246837616 --4.23669910431,1.74885761738,-16.4760894775 --4.1475687027,1.73094666004,-16.3435726166 --4.08653640747,1.72597551346,-16.315038681 --3.99438905716,1.70707511902,-16.1645259857 --3.96547412872,1.7170317173,-16.2609710693 --3.94047498703,1.71603524685,-16.2651958466 --3.89550113678,1.71902835369,-16.2986507416 --3.85855722427,1.72500288486,-16.3640956879 --3.80756187439,1.72500920296,-16.3745574951 --3.64311122894,1.66729295254,-15.9050922394 --3.58006191254,1.66033172607,-15.8595647812 --3.55315518379,1.67128372192,-15.9640035629 --3.59955954552,1.72204697132,-16.3953952789 --3.59866404533,1.73398768902,-16.508605957 --3.48339271545,1.70016157627,-16.2291088104 --3.43841981888,1.70215415955,-16.2635650635 --3.35929560661,1.68623840809,-16.1390419006 --3.35349464417,1.71012699604,-16.3534660339 --3.3577466011,1.74098408222,-16.6228847504 --3.33074450493,1.74099028111,-16.6231193542 --3.25764679909,1.72805845737,-16.526594162 --3.21669650078,1.73403763771,-16.5840435028 --3.13254284859,1.71413946152,-16.4295291901 --3.10968184471,1.73006522655,-16.5799674988 --3.05064511299,1.72509658337,-16.5474319458 --3.00869250298,1.73107755184,-16.6018829346 --2.98973035812,1.73505973816,-16.6441116333 --2.93370819092,1.73208236694,-16.62657547 --2.8987994194,1.74303781986,-16.7260246277 --2.84076738358,1.73806631565,-16.6984901428 --2.80586123466,1.74901986122,-16.8009376526 --2.75385975838,1.74903047085,-16.8043937683 --2.68375730515,1.73610091209,-16.703868866 --2.65474009514,1.73311591148,-16.6891040802 --2.59972310066,1.73113584518,-16.676568985 --2.56482696533,1.74308407307,-16.7890205383 --2.52892160416,1.75403761864,-16.8914661407 --2.46786737442,1.74707949162,-16.8409347534 --2.4158718586,1.74708688259,-16.8504009247 --2.35883688927,1.74311721325,-16.8198623657 --2.32176160812,1.73416638374,-16.745098114 --2.22041964531,1.69237685204,-16.4005908966 --2.20970439911,1.72621965408,-16.6970310211 --2.17784380913,1.74314785004,-16.8444786072 --1.956589818,1.59189081192,-15.5710411072 --1.93881285191,1.61876952648,-15.804476738 --2.00067710876,1.72227501869,-16.6898765564 --1.97568547726,1.72327506542,-16.7011108398 --1.91863465309,1.71731448174,-16.6545696259 --1.77486622334,1.62477087975,-15.8800878525 --1.72384417057,1.62279307842,-15.8635473251 --1.6758505106,1.6237988472,-15.8760080338 --1.70152485371,1.70341765881,-16.5644283295 --1.64749836922,1.7004430294,-16.5428943634 --1.62149298191,1.69945108891,-16.5401248932 --1.51089394093,1.62880659103,-15.9406080246 --1.51745772362,1.69549119473,-16.5150432587 --1.47353243828,1.70445823669,-16.5955066681 --1.42151963711,1.70247554779,-16.5879688263 --1.37153577805,1.70447647572,-16.6094379425 --1.3164832592,1.69851660728,-16.5618991852 --1.29553878307,1.7054899931,-16.6201286316 --1.24756801128,1.70848321915,-16.654586792 --1.18846952915,1.69754981995,-16.5610561371 --1.14152276516,1.70352959633,-16.6195201874 --1.09051513672,1.70254421234,-16.616979599 --1.04357945919,1.7105178833,-16.6864471436 --1.02061617374,1.71450209618,-16.7256755829 --0.970634937286,1.71750187874,-16.7491397858 --0.923699498177,1.72447538376,-16.8185997009 --0.874743521214,1.73046112061,-16.867061615 --0.823770225048,1.73345673084,-16.8985328674 --0.774812161922,1.73844349384,-16.9449939728 --0.724852263927,1.74343156815,-16.9894561768 --0.699887394905,1.74741709232,-17.0266952515 --0.649934709072,1.75340127945,-17.0781593323 --0.598970890045,1.75739169121,-17.1186256409 --0.548018395901,1.76337599754,-17.1700954437 --0.497065097094,1.76936089993,-17.2205600739 --0.445074230433,1.77036654949,-17.2340240479 --0.393124014139,1.77635002136,-17.2874946594 --0.367156535387,1.78033733368,-17.3217315674 --0.314167976379,1.78234219551,-17.3372001648 --0.262211889029,1.7873288393,-17.3846664429 --0.182229697704,1.79033613205,-17.408372879 --0.129218786955,1.78935348988,-17.4018363953 --0.0762251988053,1.790361166,-17.4123001099 --0.0492069423199,1.78837704659,-17.3965358734 --0.00378923211247,1.78860807419,-16.572977066 -0.0502021759748,1.7865883112,-16.5613441467 -0.103218309581,1.7885825634,-16.5737037659 -0.156206697226,1.7865613699,-16.5590648651 -0.210216701031,1.78755199909,-16.5654296875 -0.263223409653,1.78754103184,-16.5687904358 -0.290217190981,1.78653013706,-16.5609760284 -0.343226104975,1.78752040863,-16.5663337708 -0.397232115269,1.78850889206,-16.5687007904 -0.450244963169,1.78950130939,-16.5780582428 -0.504242658615,1.78848540783,-16.5724258423 -0.557255446911,1.78947794437,-16.581785202 -0.611265361309,1.79046869278,-16.5881500244 -0.637262225151,1.79045975208,-16.5833263397 -0.691266059875,1.7904471159,-16.583694458 -0.745276927948,1.79143857956,-16.5910568237 -0.798280894756,1.79242610931,-16.5914173126 -0.852283716202,1.79241299629,-16.5907840729 -0.905279397964,1.79139637947,-16.5831489563 -0.93229341507,1.79339683056,-16.59532547 -0.986292123795,1.79238152504,-16.5906944275 -1.0382809639,1.79136133194,-16.5760536194 -1.09228181839,1.79134726524,-16.573425293 -1.14629364014,1.79233920574,-16.581785202 -1.19928574562,1.79232048988,-16.5701522827 -1.2512794733,1.79130315781,-16.5605106354 -1.27726447582,1.78928780556,-16.5437011719 -1.3312715292,1.79027724266,-16.5470638275 -1.38325536251,1.78825449944,-16.5274333954 -1.43827521801,1.7902507782,-16.543794632 -1.490270257,1.79023420811,-16.5351543427 -1.5442712307,1.79022037983,-16.5325241089 -1.5962574482,1.78919875622,-16.5148906708 -1.62730896473,1.79521918297,-16.5650615692 -1.68232369423,1.79721283913,-16.576423645 -1.73431074619,1.79519200325,-16.5597915649 -1.79234647751,1.80019652843,-16.5921554565 -1.8503947258,1.80620801449,-16.637506485 -1.90943789482,1.81121659279,-16.6778659821 -1.97049999237,1.81923508644,-16.7372188568 -2.0095975399,1.83127892017,-16.8343868256 -2.07166671753,1.83930146694,-16.9017333984 -2.13271450996,1.84531199932,-16.9470901489 -2.19880056381,1.8563426733,-17.0314388275 -2.2568256855,1.8593416214,-17.0537967682 -2.31484770775,1.86233890057,-17.0731544495 -2.37185716629,1.86432933807,-17.0795192719 -2.40690493584,1.8703469038,-17.1266956329 -2.46995902061,1.87736070156,-17.1790447235 -2.52897906303,1.88035666943,-17.1964073181 -2.58598637581,1.88234603405,-17.2007713318 -2.64701795578,1.88634800911,-17.2301292419 -2.7040271759,1.88833856583,-17.2364883423 -2.73504519463,1.89034080505,-17.2536640167 -2.79406309128,1.89333570004,-17.2690258026 -2.85106563568,1.89432239532,-17.2683906555 -2.91108632088,1.89731884003,-17.2867507935 -2.97110700607,1.90031516552,-17.305109024 -3.02810907364,1.90130198002,-17.304473877 -3.08812618256,1.90429615974,-17.3188362122 -3.1211566925,1.90830492973,-17.3490047455 -3.17815256119,1.90928804874,-17.341375351 -3.23817205429,1.9122838974,-17.3587322235 -3.29918980598,1.91527855396,-17.3740940094 -3.35418343544,1.91526114941,-17.3644542694 -3.41318917274,1.91624987125,-17.3678226471 -3.47320342064,1.91924250126,-17.3791828156 -3.50019717216,1.91923248768,-17.3713645935 -3.55920529366,1.92122232914,-17.3767261505 -3.61921620369,1.9232134819,-17.3850917816 -3.67219758034,1.92218995094,-17.3624572754 -3.72919511795,1.92217445374,-17.3568229675 -3.78518509865,1.92215514183,-17.3431949615 -3.83917117119,1.92113423347,-17.3255615234 -3.86616325378,1.92112314701,-17.3157463074 -3.92215514183,1.92110490799,-17.3041172028 -3.97413372993,1.91908025742,-17.2784843445 -4.02811813354,1.91805839539,-17.2588577271 -4.08812856674,1.92104935646,-17.2662200928 -4.13709163666,1.91701710224,-17.2245998383 -4.19007349014,1.91599416733,-17.2019691467 -4.2190747261,1.91698741913,-17.2011528015 -4.26302289963,1.91094815731,-17.1435317993 -4.31600666046,1.90992629528,-17.1229019165 -4.37300300598,1.91091036797,-17.115272522 -4.42398118973,1.9088858366,-17.0886421204 -4.47696399689,1.90886354446,-17.0670127869 -4.52994728088,1.90784144402,-17.0453872681 -4.55493402481,1.90582799911,-17.0295753479 -4.60791969299,1.90580737591,-17.0109424591 -4.66290998459,1.90578901768,-16.9973144531 -4.71689796448,1.90576934814,-16.9806842804 -4.77088594437,1.90474975109,-16.964056015 -4.8238697052,1.90472781658,-16.9424324036 -4.84885644913,1.90371465683,-16.9266204834 -4.90184259415,1.90269434452,-16.9079914093 -4.95181894302,1.90166962147,-16.8793621063 -5.00380182266,1.90064752102,-16.8567371368 -5.05176925659,1.89761829376,-16.8181190491 -5.09673023224,1.89358603954,-16.7724990845 -5.15072107315,1.89356827736,-16.7588672638 -5.18273162842,1.89556646347,-16.7680473328 -5.26079416275,1.90558290482,-16.8313922882 -5.32782125473,1.910582304,-16.8567485809 -5.38281154633,1.9115639925,-16.8421230316 -5.4367980957,1.9105437994,-16.8234977722 -5.48376703262,1.90851557255,-16.7858772278 -5.52772760391,1.90448355675,-16.7392578125 -5.5176153183,1.8904235363,-16.6154880524 -5.54252290726,1.87936651707,-16.5108947754 -5.57244968414,1.87131845951,-16.4262886047 -5.61240148544,1.86628270149,-16.3696784973 -5.65636730194,1.86325347424,-16.3280582428 -5.69130706787,1.85621190071,-16.2574577332 -5.72023439407,1.84816503525,-16.1738529205 -5.7301864624,1.84213602543,-16.119058609 -5.76513195038,1.83709764481,-16.0544490814 -5.80809736252,1.83406853676,-16.0118331909 -5.84504747391,1.82803249359,-15.9522285461 -5.87498188019,1.82098889351,-15.8746290207 -5.91093301773,1.81595361233,-15.8160190582 -5.94588136673,1.81091713905,-15.7544126511 -5.96786689758,1.80890405178,-15.7356052399 -6.00582504272,1.80487203598,-15.6839933395 -6.04578781128,1.80184221268,-15.637383461 -6.09276771545,1.80082035065,-15.6097650528 -6.12772035599,1.79578626156,-15.5521554947 -6.16968917847,1.79275965691,-15.5125417709 -6.18365812302,1.78973901272,-15.4747419357 -6.22161912918,1.78570890427,-15.4261312485 -6.26158380508,1.78268051147,-15.3815221786 -6.30054807663,1.77865183353,-15.3359127045 -6.33750963211,1.77562212944,-15.2872982025 -6.37647390366,1.77159368992,-15.2416915894 -6.41544055939,1.7685662508,-15.1980800629 -6.42840862274,1.76554560661,-15.1592845917 -6.46837759018,1.7625194788,-15.1186723709 -6.50634241104,1.75949144363,-15.0730628967 -6.54430866241,1.75646436214,-15.0294494629 -6.57626199722,1.75143134594,-14.9708471298 -6.61823606491,1.74940764904,-14.9352359772 -6.66021060944,1.74738442898,-14.9006233215 -6.66917514801,1.74336290359,-14.8578233719 -6.71114969254,1.7413393259,-14.8222150803 -6.74510955811,1.73730969429,-14.7706108093 -6.78307962418,1.73528456688,-14.7299957275 -6.8410859108,1.73727536201,-14.7303733826 -6.85901641846,1.72923314571,-14.645781517 -6.90800714493,1.7302172184,-14.6281614304 -6.92098045349,1.72719955444,-14.5943641663 -6.96796751022,1.72718203068,-14.5727472305 -6.99792385101,1.72215175629,-14.5171394348 -7.03288936615,1.71912479401,-14.470533371 -7.06985712051,1.71609902382,-14.4269313812 -7.10783052444,1.71407592297,-14.3893165588 -7.14580106735,1.71205151081,-14.3487129211 -7.14875888824,1.7070274353,-14.29692173 -7.17771673203,1.70199775696,-14.241317749 -7.26167631149,1.69995713234,-14.1800966263 -7.29764604568,1.69693303108,-14.1384897232 -7.33261394501,1.69490766525,-14.0938882828 -7.37760066986,1.69489073753,-14.071269989 -7.39358329773,1.69287776947,-14.0474662781 -7.44157457352,1.69386279583,-14.0298471451 -7.48155212402,1.69184195995,-13.9962396622 -7.52553749084,1.69182443619,-13.9716234207 -7.5685210228,1.69180631638,-13.9450073242 -7.60349035263,1.68878185749,-13.9014081955 -7.62648534775,1.6887742281,-13.8915967941 -7.6734752655,1.68975865841,-13.8719797134 -7.71445560455,1.68873929977,-13.8413686752 -7.76344919205,1.68972539902,-13.8257493973 -7.81044006348,1.69071054459,-13.8071289062 -7.85842990875,1.69069504738,-13.787519455 -7.89941167831,1.69067633152,-13.7579050064 -7.91840028763,1.68966627121,-13.7410964966 -7.97240114212,1.69165539742,-13.7334737778 -8.01037693024,1.69063413143,-13.6968698502 -8.05936908722,1.69162011147,-13.6802530289 -8.12839221954,1.69761836529,-13.6986141205 -8.15835666656,1.69359278679,-13.6490163803 -8.19933795929,1.69357395172,-13.6184062958 -8.22733974457,1.69456923008,-13.6165924072 -8.27332878113,1.69555330276,-13.5939788818 -8.32332420349,1.6965405941,-13.5803537369 -8.36730957031,1.69652366638,-13.5547418594 -8.42231082916,1.69951283932,-13.547121048 -8.47030067444,1.70049798489,-13.5275068283 -8.52029514313,1.70148468018,-13.5118875504 -8.52927017212,1.69846904278,-13.4780931473 -8.5782623291,1.70045506954,-13.4604759216 -8.61724185944,1.6994355917,-13.4268684387 -8.67123985291,1.70142400265,-13.4162511826 -8.72023296356,1.70241045952,-13.3996286392 -8.76922512054,1.70339620113,-13.3810148239 -8.79822731018,1.70539164543,-13.379201889 -8.84822177887,1.70737838745,-13.3635797501 -8.88720035553,1.70635902882,-13.3289766312 -8.94420337677,1.70934915543,-13.3233499527 -8.99419689178,1.71033608913,-13.30772686 -9.04118537903,1.71132028103,-13.2841205597 -9.08016586304,1.71030175686,-13.2515087128 -9.10816574097,1.71229612827,-13.2467002869 -9.15014839172,1.7122784853,-13.2170915604 -9.21716213226,1.71727287769,-13.2244606018 -9.25413990021,1.71625328064,-13.1878547668 -9.30112838745,1.71623802185,-13.1652431488 -9.36013317108,1.72022902966,-13.161611557 -9.4101266861,1.72221553326,-13.143992424 -9.43912696838,1.72321033478,-13.1401834488 -9.49812889099,1.72620022297,-13.1335630417 -9.55613231659,1.73019015789,-13.1269359589 -9.5991153717,1.73017323017,-13.0983257294 -9.64910793304,1.731159091,-13.0787124634 -9.6940946579,1.73214316368,-13.0530986786 -9.74608898163,1.73413014412,-13.036482811 -9.77608966827,1.73612523079,-13.0336694717 -9.83609294891,1.73911523819,-13.0270490646 -9.89409446716,1.74310493469,-13.0194196701 -9.94308567047,1.74409031868,-12.9978075027 -10.0030870438,1.74708032608,-12.9911823273 -10.0470724106,1.7480635643,-12.9625740051 -10.1031017303,1.75506901741,-12.9937372208 -10.1480875015,1.75505256653,-12.9661283493 -10.2421245575,1.76505541801,-13.0024747849 -10.2821054459,1.76503741741,-12.9688653946 -10.3411054611,1.76802635193,-12.9592418671 -10.3800849915,1.76800775528,-12.9236364365 -10.4400863647,1.77099716663,-12.9150123596 -10.4640798569,1.77198934555,-12.9022092819 -10.5350914001,1.77698242664,-12.9065771103 -10.5850820541,1.77896797657,-12.8849592209 -10.6340713501,1.77995312214,-12.8613452911 -10.6780548096,1.78093600273,-12.830739975 -10.7230396271,1.78191971779,-12.8021306992 -10.7630205154,1.78090167046,-12.7675247192 -10.7669944763,1.77788722515,-12.7307348251 -10.8109788895,1.77887046337,-12.700129509 -10.8409509659,1.7768497467,-12.6545276642 -10.4745426178,1.70269691944,-12.1352796555 -10.4895029068,1.69767248631,-12.0736989975 -10.5054636002,1.69364857674,-12.0141134262 -10.5154209137,1.68862342834,-11.9485301971 -10.4903707504,1.6806012392,-11.8807659149 -10.5163421631,1.67858099937,-11.8331756592 -10.5463190079,1.67656266689,-11.7915763855 -10.5632820129,1.67354035378,-11.7349891663 -10.5812482834,1.66951847076,-11.6794042587 -10.6122255325,1.66850054264,-11.6388063431 -10.6371965408,1.66648089886,-11.5912179947 -10.6471815109,1.66447067261,-11.5654211044 -10.6741552353,1.6624519825,-11.5208272934 -10.6861162186,1.65842878819,-11.4592485428 -10.7200984955,1.65841269493,-11.4236431122 -10.7340612411,1.65439069271,-11.3650617599 -10.7590341568,1.65237176418,-11.3184728622 -10.7740001678,1.64835047722,-11.2618894577 -10.7659692764,1.64333570004,-11.2171106339 -10.7889413834,1.64131700993,-11.1695194244 -10.8019065857,1.63729572296,-11.1119356155 -10.8248806,1.63527750969,-11.0653409958 -10.838845253,1.63125646114,-11.0077648163 -10.8548145294,1.62823653221,-10.9541778564 -10.8567934036,1.62522482872,-10.9203939438 -10.871761322,1.62220525742,-10.8668041229 -10.8907318115,1.61918640137,-10.8162193298 -10.9077014923,1.61616718769,-10.7636356354 -10.9166650772,1.61214637756,-10.7040548325 -10.9336357117,1.6091272831,-10.6514749527 -10.9496059418,1.60610866547,-10.5998859406 -10.9425792694,1.60209596157,-10.5591049194 -10.9475412369,1.59707462788,-10.4955339432 -10.9765224457,1.59605932236,-10.4569358826 -10.9934940338,1.5940413475,-10.4063510895 -11.0074634552,1.59002280235,-10.3527708054 -11.0254364014,1.58800518513,-10.3031864166 -11.0384054184,1.58498680592,-10.2496032715 -11.0433893204,1.58297753334,-10.2218112946 -11.0663671494,1.58096122742,-10.1772251129 -11.0713329315,1.5769418478,-10.117641449 -11.0883054733,1.57392477989,-10.0680599213 -11.1112833023,1.5719088316,-10.0234775543 -11.1312599182,1.57089304924,-9.97887992859 -11.1402463913,1.56888461113,-9.95409202576 -11.1492147446,1.56586658955,-9.89851093292 -11.1691923141,1.56385087967,-9.85292339325 -11.1891679764,1.56183516979,-9.80733585358 -11.2181510925,1.56182134151,-9.7697429657 -11.2321243286,1.55880475044,-9.71916007996 -11.2501010895,1.55678915977,-9.67257213593 -11.2670936584,1.55678272247,-9.65577602386 -11.2750635147,1.55276525021,-9.60019874573 -11.3030471802,1.55275166035,-9.56260299683 -11.3200235367,1.55073654652,-9.51601314545 -11.3319959641,1.54771995544,-9.46343898773 -11.3499727249,1.54570508003,-9.41785049438 -11.3719530106,1.54369056225,-9.37426757812 -11.380941391,1.54268312454,-9.35147380829 -11.3999204636,1.54166901112,-9.30787849426 -11.4118938446,1.5386531353,-9.25630378723 -8.21887016296,1.04711961746,-6.53330945969 -8.23386192322,1.04611253738,-6.50272035599 -8.30987262726,1.05110549927,-6.47950220108 -8.33888244629,1.05410516262,-6.4816904068 -8.3638792038,1.05409944057,-6.45810317993 -8.38787651062,1.05509376526,-6.43450737 -8.40486907959,1.0540869236,-6.40492153168 -8.43787193298,1.05608260632,-6.38832044601 -8.4508638382,1.05507552624,-6.35672616959 -8.50187587738,1.05907356739,-6.35312080383 -8.49486351013,1.05706822872,-6.32732868195 -8.53787231445,1.06006515026,-6.31772470474 -8.54385852814,1.05805718899,-6.28014183044 -8.5888671875,1.06105422974,-6.27153968811 -8.59285354614,1.05904626846,-6.23295402527 -8.63286018372,1.06204283237,-6.22134494781 -8.63685417175,1.06103897095,-6.20256137848 -8.67485904694,1.06303524971,-6.18895673752 -8.68084621429,1.06102764606,-6.15137672424 -8.72585582733,1.06502485275,-6.14375638962 -8.7398481369,1.06401836872,-6.11217021942 -8.78585624695,1.06801533699,-6.10356378555 -8.7848405838,1.06500709057,-6.06098985672 -8.81885147095,1.06800699234,-6.0651717186 -8.82884120941,1.06700003147,-6.03059005737 -8.8798532486,1.07099759579,-6.02498006821 -8.88383960724,1.06899023056,-5.98640012741 -8.9288482666,1.07298707962,-5.97678852081 -8.94183921814,1.07198059559,-5.94420623779 -8.98184490204,1.07397711277,-5.93060112 -8.98283863068,1.07297337055,-5.91081094742 -9.03685092926,1.0779709816,-5.90619945526 -9.03683662415,1.07496333122,-5.86462783813 -9.07684135437,1.07795977592,-5.85101795197 -9.08983421326,1.07695353031,-5.81843566895 -9.13384151459,1.08095026016,-5.80682706833 -9.14283180237,1.07994377613,-5.77224063873 -9.20585441589,1.08694577217,-5.79340600967 -9.15181541443,1.07693386078,-5.7168712616 -9.19182014465,1.07993018627,-5.70226669312 -9.27584648132,1.0889300108,-5.71563243866 -9.2848367691,1.08692383766,-5.68104505539 -9.31683731079,1.08891928196,-5.66044950485 -11.4207859039,1.38007807732,-6.98206996918 -11.1536445618,1.34004712105,-6.76270008087 -11.1386175156,1.33503615856,-6.70513486862 -10.9935340881,1.31201577187,-6.56567573547 -10.8224401474,1.28499436378,-6.41222953796 -10.8044147491,1.27998411655,-6.35466909409 -10.7023525238,1.26296854019,-6.24617004395 -10.5562810898,1.24195444584,-6.13349962234 -10.5502634048,1.23794591427,-6.08592128754 -10.494222641,1.22793412209,-6.0063996315 -10.2941226959,1.19791424274,-5.84297227859 -10.1900653839,1.18090069294,-5.73847150803 -10.4721679688,1.21690964699,-5.86168766022 -10.1110048294,1.16488194466,-5.60638856888 -10.0269632339,1.15287399292,-5.53666162491 -9.89289569855,1.13186013699,-5.41719102859 -9.80484771729,1.11784946918,-5.32667255402 -9.80583667755,1.11484336853,-5.28610467911 -9.67477321625,1.09483098984,-5.17162895203 -9.63774681091,1.08782362938,-5.11108398438 -9.53869819641,1.07281374931,-5.01658248901 -9.51168251038,1.06781005859,-4.98280858994 -9.3996295929,1.05080008507,-4.8823184967 -9.35460281372,1.04279339314,-4.8197760582 -9.34759044647,1.03978836536,-4.77820730209 -9.27855491638,1.02778112888,-4.7026925087 -9.23052978516,1.019775033,-4.64113903046 -9.15049552917,1.00777006149,-4.57941818237 -9.0994682312,0.9987642169,-4.5158829689 -9.16348361969,1.00576221943,-4.51326131821 -8.972407341,0.978752613068,-4.37782335281 -8.91237926483,0.968747258186,-4.31129455566 -8.84534931183,0.957742094994,-4.24275875092 -8.78732299805,0.948737323284,-4.17823028564 -8.77631473541,0.945735573769,-4.15545129776 -8.68027591705,0.93173032999,-4.0729470253 -8.67226791382,0.928727328777,-4.03537559509 -8.58523273468,0.91572278738,-3.95787453651 -8.54121303558,0.907719492912,-3.90332913399 -8.48418998718,0.898716211319,-3.84378123283 -8.44717311859,0.892713427544,-3.79323387146 -8.41816139221,0.887711882591,-3.76247572899 -8.33312988281,0.875708758831,-3.68995904922 -8.31211948395,0.870706677437,-3.64839744568 -8.24009418488,0.859704196453,-3.58287644386 -8.1710691452,0.849702000618,-3.51935338974 -8.16406345367,0.84670060873,-3.48577642441 -8.13805294037,0.842699110508,-3.44321799278 -8.10104084015,0.836698293686,-3.4104654789 -8.0690279007,0.830697119236,-3.36590957642 -8.0600233078,0.828696072102,-3.33233141899 -7.97699689865,0.816695034504,-3.26482367516 -7.96299123764,0.813694238663,-3.22925448418 -7.93598175049,0.808693647385,-3.18770170212 -7.95398616791,0.809693336487,-3.18090081215 -7.87296152115,0.798693060875,-3.11737155914 -7.84195184708,0.792692780495,-3.07482290268 -7.8249464035,0.7896925807,-3.03925299644 -7.79493761063,0.784692645073,-2.99770331383 -7.78493404388,0.781692624092,-2.96513390541 -7.78093290329,0.779692649841,-2.93555474281 -7.75092458725,0.775692939758,-2.90879249573 -7.7289185524,0.77169328928,-2.87222480774 -7.70391225815,0.767693817616,-2.83367419243 -7.62889289856,0.756695151329,-2.77614760399 -7.57387924194,0.748696446419,-2.72661471367 -7.59788656235,0.750696659088,-2.70901942253 -7.55287504196,0.74369764328,-2.67825675011 -7.51786708832,0.738698959351,-2.63770508766 -7.48586082458,0.73370039463,-2.59815883636 -7.47785949707,0.730701386929,-2.56858730316 -7.45185470581,0.726702868938,-2.53203296661 -7.40284490585,0.719705045223,-2.48748970032 -7.38084173203,0.715706706047,-2.45391774178 -7.36683893204,0.713707625866,-2.4361333847 -7.34783697128,0.709709405899,-2.402582407 -7.34983968735,0.709710657597,-2.3779964447 -7.3468413353,0.707712054253,-2.3514187336 -7.34784412384,0.706713497639,-2.32584619522 -7.28483247757,0.697716891766,-2.27831172943 -7.30584001541,0.699717760086,-2.26071310043 -7.2528295517,0.692720293999,-2.22995829582 -7.29484224319,0.696720600128,-2.21836590767 -7.2118268013,0.685725152493,-2.16583514214 -7.20082759857,0.683727383614,-2.13726639748 -7.21583461761,0.684728682041,-2.11767530441 -7.20883607864,0.682730972767,-2.09011173248 -7.1838350296,0.678733885288,-2.05754828453 -7.14782905579,0.673736333847,-2.03378295898 -7.12282752991,0.669739484787,-2.00122666359 -7.16584062576,0.674739837646,-1.99061775208 -7.13083791733,0.668743610382,-1.95506989956 -7.08983373642,0.663747668266,-1.91851568222 -7.09183835983,0.662749946117,-1.89494049549 -7.03983068466,0.655753552914,-1.86718809605 -7.24587440491,0.680746257305,-1.90546321869 -7.02783727646,0.652759075165,-1.81604361534 -7.02284097672,0.651761829853,-1.79146039486 -7.02184581757,0.650764524937,-1.76787889004 -7.01684951782,0.648767471313,-1.74231600761 -7.02285575867,0.648769855499,-1.72073125839 -6.98585176468,0.644773185253,-1.69896125793 -6.98985767365,0.643775761127,-1.67638838291 -6.96885919571,0.640779733658,-1.64781701565 -6.95186138153,0.637783527374,-1.62024784088 -6.95386743546,0.637786388397,-1.59766972065 -6.94087076187,0.634790122509,-1.57110321522 -6.9078707695,0.630795180798,-1.53954815865 -6.89887189865,0.628797233105,-1.5257666111 -6.8858757019,0.626801252365,-1.4992069006 -6.88088130951,0.625804722309,-1.47562611103 -6.87288570404,0.623808443546,-1.45105350018 -6.86289024353,0.621812283993,-1.42647480965 -6.86589670181,0.621815443039,-1.40489172935 -6.85190105438,0.619819760323,-1.37833762169 -6.81789922714,0.614823639393,-1.35956275463 -6.82090568542,0.614826917648,-1.33798360825 -6.8379149437,0.61682933569,-1.31939959526 -6.82091903687,0.613833963871,-1.2938233614 -6.81792497635,0.612837731838,-1.27124285698 -6.82293272018,0.612841069698,-1.24967241287 -6.80393362045,0.610844135284,-1.23488783836 -6.76993560791,0.605850279331,-1.20533657074 -6.80294704437,0.608851611614,-1.19073176384 -6.78795194626,0.60685646534,-1.16517269611 -6.78495883942,0.60586053133,-1.14259839058 -6.79496717453,0.606863558292,-1.12300944328 -6.77397108078,0.603868961334,-1.09743654728 -6.77397489548,0.603870928288,-1.0866458416 -6.77398204803,0.602874815464,-1.06506514549 -6.7529873848,0.599880576134,-1.03851723671 -6.76899671555,0.601883292198,-1.01992809772 -6.76700353622,0.600887417793,-0.998343408108 -6.74700880051,0.597893178463,-0.972784936428 -6.75701808929,0.598896443844,-0.953197419643 -6.76402235031,0.598897814751,-0.944389879704 -6.72102546692,0.593905687332,-0.914850652218 -6.73803520203,0.594908475876,-0.896263718605 -6.7460436821,0.595911920071,-0.876671016216 -6.74205112457,0.594916641712,-0.854105532169 -6.73305845261,0.593921661377,-0.831528484821 -6.72306537628,0.591926813126,-0.808950781822 -6.73407030106,0.592927932739,-0.800152242184 -6.72207736969,0.59093350172,-0.776590704918 -6.7390871048,0.592936336994,-0.757999420166 -6.71609354019,0.589942932129,-0.733434975147 -6.70910072327,0.588948130608,-0.710869133472 -6.73211145401,0.59095042944,-0.693269908428 -6.73111581802,0.590952813625,-0.682482481003 -6.72412347794,0.589957892895,-0.660898149014 -6.74313354492,0.591960668564,-0.642306983471 -6.71813964844,0.587967693806,-0.617748498917 -6.72214841843,0.587971925735,-0.597167849541 -6.73715877533,0.589975297451,-0.577586710453 -6.72916603088,0.588980674744,-0.556004047394 -6.73717164993,0.588982284069,-0.546213984489 -6.70717811584,0.585989952087,-0.521655678749 -6.71418762207,0.585994124413,-0.501080811024 -6.76319980621,0.591993749142,-0.486449986696 -6.79521083832,0.594995498657,-0.467867791653 -6.72621488571,0.58700722456,-0.440319955349 -6.71222305298,0.585013628006,-0.417754918337 -6.72722864151,0.587014436722,-0.408952087164 -6.77924108505,0.592014074326,-0.392351418734 -6.76524925232,0.591020524502,-0.369785577059 -6.74725723267,0.588027358055,-0.347217738628 -6.69726371765,0.582037508488,-0.322658210993 -6.74627542496,0.588037252426,-0.306044220924 -6.7142829895,0.584045767784,-0.282488137484 -6.7092871666,0.5830488801,-0.271701782942 -6.78030061722,0.591046273708,-0.256078779697 -6.8313126564,0.597045779228,-0.238471284509 -6.7173166275,0.584063351154,-0.209957957268 -6.68532514572,0.580072343349,-0.186413452029 -6.69033479691,0.580076813698,-0.166815459728 -6.67533874512,0.578081250191,-0.1550462991 -6.71234989166,0.582082331181,-0.136444762349 -6.72736024857,0.584085762501,-0.116848893464 -6.76737117767,0.589086532593,-0.0982409194112 -6.70337963104,0.581099331379,-0.073714710772 -6.68238830566,0.578107059002,-0.0521478913724 -6.76240062714,0.588103175163,-0.0345232151449 -6.78040647507,0.590103805065,-0.0247236937284 -6.76541614532,0.588110983372,-0.00315608340316 -6.77842569351,0.589114665985,0.0164480507374 -6.77443599701,0.589120686054,0.038014061749 -6.78544616699,0.5901247859,0.0586003400385 -6.7404551506,0.585135579109,0.0801600515842 -6.76046085358,0.587136149406,0.0909452214837 -6.77847099304,0.589139282703,0.11055368185 -6.7724814415,0.58814561367,0.132117524743 -6.73749160767,0.58415555954,0.153670176864 -6.74150133133,0.585160672665,0.174254953861 -6.7795124054,0.589161634445,0.194856390357 -6.77952241898,0.589167177677,0.215441852808 -6.72952699661,0.583176255226,0.22619587183 -6.71153783798,0.581184208393,0.246766880155 -6.68154811859,0.578193724155,0.267327398062 -6.68755865097,0.578198730946,0.287911295891 -6.6615691185,0.57520788908,0.308469802141 -6.64458036423,0.574216008186,0.329033344984 -6.63259077072,0.572223246098,0.348619282246 -6.62859630585,0.572226881981,0.359393715858 -6.66560697556,0.576227784157,0.380008667707 -6.6496181488,0.574235916138,0.400569796562 -6.66662883759,0.576239526272,0.421167522669 -6.66763973236,0.577245354652,0.441748023033 -6.64765119553,0.574254155159,0.462301254272 -6.63065671921,0.572259485722,0.472077786922 -6.64966773987,0.575262725353,0.492681384087 -6.6466794014,0.57526922226,0.513255476952 -6.60669088364,0.57028067112,0.531813561916 -6.60770225525,0.570286691189,0.552390992641 -6.60371351242,0.570293486118,0.572960674763 -6.61272478104,0.571298360825,0.59355199337 -6.60273075104,0.570302784443,0.603333175182 -6.58374261856,0.568311691284,0.622895479202 -6.56975412369,0.56631988287,0.642464697361 -6.58676528931,0.568323493004,0.663071870804 -6.59077644348,0.569329202175,0.683655679226 -6.58978796005,0.569335699081,0.704229831696 -6.54580163956,0.56434828043,0.721773862839 -6.54380702972,0.564351677895,0.731566607952 -6.53781890869,0.564358830452,0.751147508621 -6.51783132553,0.562368035316,0.769716203213 -6.51984357834,0.5623742342,0.790293395519 -6.51685523987,0.562380969524,0.809879422188 -6.50086832047,0.56038993597,0.829433143139 -6.52387905121,0.563393175602,0.852023005486 -6.49188613892,0.5594009161,0.858798921108 -6.47589921951,0.558409750462,0.877369761467 -6.4759106636,0.558416128159,0.896961390972 -6.48492288589,0.559421539307,0.918537378311 -6.46293592453,0.557431280613,0.936108887196 -6.47694730759,0.559435725212,0.957700371742 -6.4909529686,0.561437010765,0.969496905804 -6.47496604919,0.559446036816,0.988063514233 -6.47997808456,0.560452222824,1.00963139534 -6.47599124908,0.560459375381,1.02921295166 -6.49900150299,0.563462495804,1.05181884766 -6.46801614761,0.56047385931,1.06837546825 -6.47502851486,0.561479687691,1.08995211124 -6.49203300476,0.563480317593,1.10176539421 -6.47304677963,0.561490118504,1.12031769753 -6.45106077194,0.559500038624,1.13689804077 -6.40007638931,0.553514838219,1.15043461323 -6.41508817673,0.555519104004,1.17203938961 -6.41610097885,0.556525886059,1.19261586666 -6.41311311722,0.556533157825,1.21219813824 -6.43311882019,0.558533728123,1.22598826885 -6.42313241959,0.558542132378,1.24456596375 -6.46314239502,0.56354278326,1.27117347717 -6.50115346909,0.568544089794,1.29875874519 -6.43316984177,0.560561358929,1.30731070042 -6.42518377304,0.559569776058,1.3268750906 -6.42319059372,0.559573590755,1.33666527271 -6.43220233917,0.561578989029,1.35825920105 -6.42021656036,0.560588002205,1.37682688236 -6.44222831726,0.563591599464,1.40141761303 -6.41824245453,0.56160223484,1.41699397564 -6.39925670624,0.559612214565,1.4335693121 -6.41826868057,0.562616467476,1.45815122128 -6.41827583313,0.562620222569,1.46893072128 -6.41628885269,0.562627434731,1.48852133751 -6.40630245209,0.561636149883,1.50709557533 -6.40231657028,0.561643898487,1.52667689323 -6.41532897949,0.563649117947,1.55025851727 -6.4013428688,0.56265848875,1.56783330441 -6.41635560989,0.565663456917,1.59240758419 -6.40236330032,0.563669204712,1.59920048714 -6.42537403107,0.566672682762,1.62479639053 -6.37239265442,0.561688661575,1.63433551788 -6.35640764236,0.559698402882,1.65091574192 -6.42641448975,0.568694233894,1.68753659725 -6.39343118668,0.565707027912,1.70109128952 -6.36944675446,0.562718153,1.71566939354 -6.37245368958,0.56372153759,1.72744739056 -6.3944644928,0.56672513485,1.75304973125 -6.37648057938,0.565735459328,1.76961863041 -6.39949178696,0.568738996983,1.79621088505 -6.38750648499,0.567748606205,1.81477248669 -6.38752031326,0.568755865097,1.83536064625 -6.36952924728,0.566762566566,1.84114277363 -6.37054300308,0.567769944668,1.86271679401 -6.36655664444,0.56777793169,1.88230204582 -6.40156698227,0.572779655457,1.91289651394 -6.38058328629,0.57079064846,1.92846417427 -6.37559747696,0.570798873901,1.9480458498 -6.36261320114,0.569808602333,1.96561896801 -6.35762071609,0.569813430309,1.9753947258 -6.34063577652,0.568823575974,1.99098157883 -6.34964990616,0.569829940796,2.01554965973 -6.3266658783,0.567841470242,2.03011775017 -6.34167861938,0.570846438408,2.05570554733 -6.32869338989,0.569855988026,2.07229542732 -6.35769796371,0.573855042458,2.09209012985 -6.37270975113,0.575859963894,2.1176841259 -6.31673049927,0.569877326488,2.12223291397 -6.30674600601,0.569886803627,2.14080190659 -6.3577542305,0.576885521412,2.17742013931 -6.35576868057,0.576893746853,2.19898700714 -6.55376005173,0.602867126465,2.28366732597 -6.5237698555,0.598875880241,2.28445649147 -6.35080480576,0.578913748264,2.25094461441 -6.34182071686,0.578923344612,2.27050471306 -6.33783531189,0.578931510448,2.29009795189 -6.38184404373,0.584931612015,2.32669758797 -6.36686086655,0.583942294121,2.3442568779 -9.43449878693,0.964416325092,3.42908644676 -9.31952476501,0.951443135738,3.42161631584 -6.62787771225,0.61892336607,2.51192903519 -6.64688920975,0.622927725315,2.54152131081 -6.71089553833,0.631924390793,2.58812141418 -6.61292266846,0.619949281216,2.57566332817 -6.57894134521,0.616963386536,2.58721232414 -6.60394477844,0.620962560177,2.60703015327 -6.4989733696,0.608989238739,2.59155631065 -6.43899583817,0.602007806301,2.5921061039 -6.4450097084,0.604014515877,2.61669588089 -6.36303567886,0.594037115574,2.60823726654 -6.33305454254,0.592050671577,2.61979341507 -6.33206224442,0.592054843903,2.63058400154 -6.30408096313,0.589067816734,2.64215159416 -6.34508991241,0.596068501472,2.68075108528 -6.31610870361,0.593081831932,2.69231033325 -6.30312490463,0.592091977596,2.7088997364 -6.30813932419,0.5940990448,2.73348402977 -6.29415655136,0.59310990572,2.7510471344 -6.44614219666,0.613086402416,2.82490491867 -6.43815803528,0.613095760345,2.84448885918 -6.30819225311,0.598127663136,2.81400132179 -6.28021097183,0.595140695572,2.82457876205 -6.29922389984,0.599145531654,2.8561565876 -6.29024028778,0.59915548563,2.87572550774 -6.26225948334,0.59616869688,2.88629961014 -6.33025693893,0.605160236359,2.92712450027 -6.30527591705,0.603173077106,2.93968939781 -6.28929281235,0.602183997631,2.95527362823 -6.29830741882,0.605190694332,2.98285293579 -6.2913236618,0.60520029068,3.0034236908 -6.31733465195,0.609203517437,3.03802633286 -6.2983455658,0.607211351395,3.04179668427 -6.23337078094,0.600231587887,3.03535079956 -6.35736656189,0.617216825485,3.11598825455 -6.28639268875,0.60923820734,3.10654115677 -6.28240919113,0.61024749279,3.12910676003 -6.32041835785,0.61624866724,3.1707072258 -6.28043985367,0.612264335155,3.17527532578 -6.27344894409,0.612269878387,3.18405866623 -6.28346252441,0.615276277065,3.21264648438 -6.28447818756,0.616284489632,3.23722624779 -6.27649497986,0.616294503212,3.25779604912 -6.26851129532,0.616304159164,3.27738332748 -6.28052520752,0.619310438633,3.3079624176 -6.27153491974,0.619316399097,3.31574630737 -6.28354740143,0.622322201729,3.34534549713 -6.30355978012,0.626326858997,3.37993526459 -6.31557369232,0.62933331728,3.41150712967 -6.27359628677,0.624349534512,3.41407680511 -6.26161432266,0.624360322952,3.43264913559 -6.40160512924,0.644342064857,3.53029870987 -6.34462308884,0.63735717535,3.51306200027 -6.2676525116,0.628380358219,3.49760460854 -6.25167131424,0.628391981125,3.51417469978 -6.26168489456,0.630398690701,3.54475545883 -6.29669427872,0.636400341988,3.58835864067 -6.24271965027,0.631419122219,3.58391952515 -6.24773454666,0.63342666626,3.61150765419 -6.24674320221,0.633431375027,3.62428569794 -6.23976039886,0.634441316128,3.64586043358 -6.28876686096,0.642440438271,3.69846630096 -6.26578712463,0.640453338623,3.71103858948 -6.23080873489,0.637468636036,3.71660709381 -6.24682235718,0.641474127769,3.75119781494 -6.2318406105,0.64048576355,3.76876449585 -6.22784996033,0.641490995884,3.77954983711 -6.22986507416,0.642499089241,3.80613803864 -6.2188835144,0.642509937286,3.82571220398 -6.2189002037,0.644518733025,3.8522837162 -6.22791385651,0.647525429726,3.88288187981 -6.21293306351,0.646537184715,3.90045070648 -6.27193021774,0.6555300951,3.94926381111 -6.43791437149,0.68050634861,4.07592439651 -6.41193532944,0.678520143032,4.08749294281 -6.28297615051,0.662554085255,4.03601121902 -6.20000839233,0.652579009533,4.01155567169 -6.22102022171,0.657583594322,4.05114841461 -6.19504165649,0.655597507954,4.06171798706 -6.2460398674,0.663591980934,4.10752630234 -6.22006130219,0.661605834961,4.11809682846 -6.23807382584,0.665611088276,4.15668582916 -6.25008773804,0.669617712498,4.19226408005 -6.21411132812,0.665633380413,4.19583892822 -6.23812198639,0.670637309551,4.23843717575 -6.19014835358,0.66665571928,4.23499202728 -6.27214050293,0.678644061089,4.30281639099 -6.18217468262,0.667670667171,4.27135562897 -6.19718790054,0.671676576138,4.30894470215 -6.19420528412,0.672685921192,4.33452892303 -6.18422365189,0.673696875572,4.35610055923 -6.22023296356,0.680698692799,4.40869665146 -6.16426038742,0.674718558788,4.39826011658 -6.17526674271,0.67672085762,4.42005300522 -6.15428733826,0.675733923912,4.43362855911 -6.16930150986,0.679740130901,4.47320461273 -6.24230289459,0.692734539509,4.55281972885 -6.21232509613,0.689749360085,4.56039190292 -6.14135694504,0.68177241087,4.53894281387 -6.15736150742,0.685773730278,4.56474065781 -6.14338111877,0.685785412788,4.58332014084 -6.1343998909,0.685796260834,4.60589694977 -6.1364159584,0.688804864883,4.63647890091 -6.13643264771,0.690813958645,4.66605520248 -6.14544773102,0.693821370602,4.70263290405 -6.13045978546,0.692828953266,4.70641517639 -6.16246891022,0.699831306934,4.75902175903 -6.14448976517,0.698844075203,4.77559232712 -6.14950561523,0.701852023602,4.80917739868 -6.27349567413,0.722836375237,4.93380451202 -6.28351020813,0.72584348917,4.97238826752 -6.15955352783,0.709877431393,4.9079208374 -6.15056467056,0.709883928299,4.91670179367 -6.1525812149,0.712892770767,4.94927883148 -6.15159797668,0.714901924133,4.97886514664 -6.14461612701,0.715912282467,5.00345468521 -6.16962814331,0.721916556358,5.0550365448 -6.13665246964,0.718932509422,5.06059741974 -6.17366123199,0.72693413496,5.12119913101 -6.16967010498,0.727939248085,5.13299894333 -6.13969326019,0.725954532623,5.14056634903 -6.14171075821,0.727963626385,5.1751332283 -6.14472675323,0.73097205162,5.2087264061 -6.14874315262,0.733980417252,5.24430704117 -6.13576316833,0.734992384911,5.26588249207 -6.1387796402,0.73800110817,5.30145645142 -6.14878606796,0.740003764629,5.32624959946 -6.16579914093,0.746009409428,5.37284374237 -6.19480991364,0.753012776375,5.43043756485 -6.14983701706,0.748031079769,5.42500448227 -6.13585758209,0.749043285847,5.44657611847 -6.14787197113,0.753050088882,5.49016475677 -6.1838722229,0.760047614574,5.53896093369 -6.15189647675,0.758063316345,5.54453468323 -6.18090724945,0.765066742897,5.60412549973 -6.15193080902,0.763081967831,5.61269617081 -6.16294622421,0.767089188099,5.65727615356 -6.15796422958,0.769099354744,5.68686199188 -6.15198278427,0.771109938622,5.71643829346 -6.14399385452,0.771116435528,5.72721910477 -6.19599866867,0.78211504221,5.80882883072 -6.12703132629,0.774138271809,5.78039216995 -6.12804937363,0.777147531509,5.81696939468 -6.13406515121,0.781155884266,5.85854768753 -6.14108085632,0.785163879395,5.90112781525 -6.13709974289,0.787174165249,5.93370389938 -6.15310382843,0.791175305843,5.96551656723 -6.14312410355,0.793186903,5.99308729172 -6.13914203644,0.79519712925,6.0256690979 -6.12616300583,0.796209275723,6.05024194717 -6.15717315674,0.804212331772,6.1168384552 -6.16718769073,0.80921959877,6.16342878342 -6.15120124817,0.8082280159,6.16819524765 -6.12922382355,0.807241857052,6.18377399445 -6.12224292755,0.809252738953,6.21435546875 -6.14325523376,0.816257834435,6.2729473114 -6.14227342606,0.819267630577,6.31052541733 -6.12529468536,0.819280683994,6.33209943771 -6.13231086731,0.824288725853,6.37768554688 -6.14031744003,0.827291846275,6.40547704697 -6.13733625412,0.830302119255,6.44205236435 -6.17434453964,0.839303851128,6.51865625381 -6.1323723793,0.836322069168,6.51522111893 -6.29734945297,0.867297887802,6.72785377502 -6.11641168594,0.840344429016,6.57837963104 -6.10243368149,0.841357171535,6.60494565964 -6.13043546677,0.847356200218,6.65474653244 -6.11245727539,0.848369479179,6.67632293701 -6.10547685623,0.850380480289,6.70990085602 -6.11349201202,0.855388224125,6.758497715 -6.12950706482,0.862394869328,6.81906843185 -6.13152360916,0.866403996944,6.86265659332 -6.13553190231,0.868408024311,6.88844537735 -6.12355232239,0.8704200387,6.91702890396 -6.13256788254,0.875427782536,6.96961450577 -6.13458538055,0.879437148571,7.01519346237 -8.203083992,1.24802207947,9.3913898468 -8.19010353088,1.25103437901,9.43496704102 -8.1661272049,1.25204896927,9.46653747559 -8.15013885498,1.25105690956,9.47732448578 -8.12016391754,1.25107288361,9.50288772583 -8.09418773651,1.25208795071,9.53245830536 -8.07621002197,1.2541012764,9.57103157043 -8.0452337265,1.25411713123,9.5936088562 -8.02725601196,1.25613045692,9.6321849823 -8.01626682281,1.257137537,9.64897441864 -7.97829389572,1.25515508652,9.6655330658 -7.95031833649,1.25617074966,9.69310188293 -8.0423116684,1.2781611681,9.86371707916 -8.1423034668,1.30215060711,10.0483198166 -8.16631507874,1.31315553188,10.1419000626 -8.19532299042,1.32415902615,10.2404956818 -3.45156550407,0.445144176483,4.40578842163 -3.43958806992,0.445156604052,4.41836547852 -3.42960977554,0.446168422699,4.43295097351 -3.4036359787,0.443183660507,4.42752885818 -7.47460603714,1.22136127949,9.68398094177 -7.45562839508,1.22337508202,9.72155380249 -7.40065145493,1.21539127827,9.68133163452 -7.3136920929,1.20441889763,9.62989044189 -7.2567243576,1.19944047928,9.61745262146 -7.23974657059,1.20145404339,9.65702724457 -7.16578388214,1.19347906113,9.62059211731 -7.12281322479,1.190497756,9.62516117096 -7.07884263992,1.18851673603,9.6287279129 -7.04086112976,1.18352949619,9.60850811005 -7.00188970566,1.18154740334,9.61807727814 -6.9529209137,1.17856752872,9.61364555359 -6.92794513702,1.1785825491,9.6412229538 -6.83698749542,1.16661119461,9.57877635956 -6.84200429916,1.173620224,9.64835739136 -6.77803039551,1.16463840008,9.5911283493 -6.73805904388,1.16265666485,9.59769916534 -6.67509460449,1.15567958355,9.57126522064 -6.63612318039,1.15369749069,9.57883453369 -6.56516027451,1.14572227001,9.54039669037 -6.54018497467,1.14573729038,9.56697463989 -6.49121713638,1.14275741577,9.5595407486 -6.47423028946,1.14176595211,9.56632709503 -6.39826917648,1.13279175758,9.51888656616 -6.36929607391,1.13280785084,9.54045391083 -6.30333185196,1.12483131886,9.50502490997 -6.27435874939,1.12484753132,9.52659034729 -6.21739244461,1.11886918545,9.50415992737 -6.17941236496,1.11488211155,9.47894001007 -6.15143823624,1.11489784718,9.49951934814 -6.1104683876,1.11291646957,9.50108909607 -6.05850124359,1.10793721676,9.48565578461 -6.01953029633,1.10595524311,9.48922920227 -6.04354190826,1.11696028709,9.59082221985 -5.97258043289,1.10798513889,9.54538059235 -5.95559453964,1.10799372196,9.55116653442 -5.97460842133,1.11899995804,9.64774990082 -5.923640728,1.11402058601,9.63231945038 -5.94665336609,1.12602591515,9.7359085083 -5.92167901993,1.12704122066,9.7624874115 -5.93369436264,1.136048913,9.85007286072 -5.92471551895,1.14106094837,9.90464878082 -5.94272041321,1.14906227589,9.96944236755 -5.93873977661,1.15507316589,10.0320281982 -5.94975566864,1.16508114338,10.1216106415 -5.95077419281,1.17209112644,10.1951904297 -5.94979381561,1.17910170555,10.2667684555 -5.95381164551,1.18811094761,10.3463535309 -5.96082830429,1.19711971283,10.4319410324 -6.03781652451,1.21910893917,10.6027507782 -6.00284481049,1.21812617779,10.6173276901 -5.99286699295,1.22413873672,10.6778993607 -6.013879776,1.23714458942,10.7924861908 -6.00290155411,1.24215698242,10.851067543 -5.98592567444,1.24617087841,10.9006414413 -6.0129275322,1.25717031956,10.988442421 -6.00894737244,1.2641813755,11.0620241165 -6.0899438858,1.29317522049,11.2936172485 -5.99199056625,1.27720546722,11.195183754 -5.97501420975,1.28221917152,11.2467622757 -6.00602436066,1.29822313786,11.3893508911 -5.97205352783,1.29924046993,11.4109230042 -6.03904390335,1.32023179531,11.5807304382 -6.01406955719,1.32224726677,11.6203079224 -6.00209236145,1.32925999165,11.6858854294 -5.97012042999,1.33027684689,11.7134580612 -5.98313570023,1.34328460693,11.8290424347 -5.97115850449,1.34929740429,11.8966207504 -5.9571814537,1.35531067848,11.9611997604 -5.97118711472,1.3643130064,12.035990715 -3.77283787727,0.796773672104,7.70906352997 -3.7098762989,0.786796927452,7.64262390137 -3.63991641998,0.773821532726,7.55919265747 -3.64793419838,0.782830178738,7.63577604294 -3.55498099327,0.763859272003,7.50234127045 -2.56502199173,0.727439641953,7.54875707626 -2.56804180145,0.737449467182,7.63533830643 -2.56905126572,0.741454184055,7.67613744736 -2.55807495117,0.746466636658,7.72172498703 -2.51510858536,0.739485740662,7.67429208755 -2.57411050797,0.770483672619,7.93090820312 -2.45216846466,0.733518838882,7.64245271683 -2.42919564247,0.73453348875,7.65104150772 -2.42520713806,0.7375395298,7.67983198166 -2.41223168373,0.74155241251,7.72241210938 -2.38426136971,0.740568459034,7.71898365021 -2.21462082863,0.829755723476,8.55376338959 -2.11005449295,1.08197569847,10.7797222137 -2.16404771805,1.12497031689,11.1415309906 -2.13007926941,1.12598729134,11.1551074982 -2.54097270966,1.4039170742,13.4977807999 -2.50800347328,1.40993392467,13.5553627014 -2.45803952217,1.4049539566,13.5219421387 -2.40907549858,1.40097391605,13.495516777 -2.39010190964,1.41698789597,13.6321048737 -2.37011837959,1.4179970026,13.6438941956 -2.36214184761,1.44200885296,13.8544769287 -2.29318356514,1.42403233051,13.7060604095 -2.25321698189,1.42605066299,13.7366333008 -2.21324968338,1.42806863785,13.7592191696 -2.17128348351,1.4290869236,13.7708034515 -2.15729808807,1.43509483337,13.8235931396 -2.12232995033,1.44111204147,13.8861722946 -2.09935736656,1.45712649822,14.0247612 -2.07538580894,1.47314155102,14.1703395844 -2.04141688347,1.48215842247,14.2469234467 -2.00744819641,1.49117517471,14.3275079727 -1.98547565937,1.51018965244,14.497095108 -1.99448311329,1.53719294071,14.727894783 -1.94651854038,1.53521239758,14.7194766998 -1.8945556879,1.53023266792,14.684053421 -1.88457965851,1.56424498558,14.9736394882 -1.82161986828,1.54926717281,14.8502187729 -1.83263719082,1.60527515411,15.3288116455 -1.79866838455,1.61929190159,15.4523973465 -1.77768552303,1.62230110168,15.4851865768 -1.72872149944,1.62232077122,15.4877662659 -1.69375300407,1.63633751869,15.6133537292 -1.65778493881,1.65035450459,15.7369394302 -1.61681842804,1.65937244892,15.8225231171 -1.56585538387,1.65939247608,15.8210983276 -1.51889061928,1.66241157055,15.8496837616 -1.48591136932,1.65242290497,15.7684717178 -1.43594789505,1.65244269371,15.7710514069 -1.38698387146,1.65246212482,15.7806339264 -1.33801960945,1.65248131752,15.7802238464 -1.28705632687,1.65050113201,15.7668056488 -1.23709273338,1.6495206356,15.7643880844 -1.21311056614,1.65053021908,15.7751808167 -1.16314744949,1.65154981613,15.7827558517 -1.11418330669,1.65156912804,15.7883424759 -1.0622202158,1.64658892155,15.7529268265 -1.01225686073,1.64660847187,15.7545061111 -0.963292837143,1.64662766457,15.7570924759 -0.91332924366,1.64564716816,15.7496767044 -0.888347625732,1.64565694332,15.7524652481 -0.837384402752,1.64267647266,15.7270488739 -0.788420498371,1.64369571209,15.7356319427 -0.738456964493,1.64171493053,15.7232160568 -0.689493000507,1.64273405075,15.7288017273 -0.639529585838,1.6407533884,15.7213830948 -0.614547908306,1.64076316357,15.7181749344 -0.564584493637,1.63978242874,15.7097558975 -0.514621019363,1.63780164719,15.6963386536 -0.466656625271,1.6398203373,15.7159290314 -0.416693359613,1.63983976841,15.7165079117 -0.367729395628,1.63985860348,15.7170953751 -0.317766070366,1.63887798786,15.7086763382 -0.293783724308,1.63888716698,15.7084741592 -0.243820428848,1.63690626621,15.6950540543 -0.194856420159,1.63592517376,15.6856431961 -0.144893273711,1.63694441319,15.6952209473 -0.0959293022752,1.63496315479,15.6778087616 -0.0469653829932,1.63498198986,15.6773958206 --0.0229826830328,1.65300893784,15.0837984085 --0.0699472948909,1.65302729607,15.0833864212 --0.117911152542,1.65204596519,15.0809669495 --0.164875775576,1.65306437016,15.0815563202 --0.21184027195,1.6500825882,15.0631418228 --0.258804708719,1.64810097218,15.041727066 --0.282786786556,1.65111029148,15.0635213852 --0.329751372337,1.65012848377,15.0581083298 --0.377715140581,1.65014708042,15.052687645 --0.424679636955,1.64916539192,15.0422735214 --0.471644103527,1.64818358421,15.0328598022 --0.518608868122,1.65020155907,15.0464525223 --0.566572785378,1.65022003651,15.0510349274 --0.589555323124,1.64922904968,15.0418310165 --0.636519908905,1.64924705029,15.0354185104 --0.68448382616,1.65026545525,15.0390005112 --0.730448901653,1.64828324318,15.0225925446 --0.780412077904,1.65330195427,15.0571718216 --0.827376544476,1.65232002735,15.0477581024 --0.874341070652,1.65133798122,15.0413446426 --0.897323727608,1.65134680271,15.0391435623 --0.945287525654,1.65136516094,15.0337228775 --0.991252720356,1.65038263798,15.0243177414 --1.04021632671,1.65240108967,15.036898613 --1.08618152142,1.65141868591,15.0254926682 --1.13614463806,1.65543723106,15.0470724106 --1.1581274271,1.65244579315,15.0238666534 --1.2050921917,1.65246355534,15.0234584808 --1.25305628777,1.65348160267,15.0250434875 --1.30202007294,1.65549969673,15.0386295319 --1.34898507595,1.65651738644,15.0392227173 --1.39894831181,1.65953576565,15.0568056107 --1.44591331482,1.65955328941,15.055398941 --1.47089469433,1.66056239605,15.0571842194 --1.51985871792,1.6625803709,15.0697746277 --1.5688226223,1.66459846497,15.0783605576 --1.614787817,1.66361570358,15.064953804 --1.66575098038,1.66663408279,15.0875377655 --1.71271586418,1.66665136814,15.0851335526 --1.76068007946,1.66766917706,15.0817184448 --1.78566205502,1.66867804527,15.0925159454 --1.8376250267,1.67369639874,15.120100975 --1.8845897913,1.67271387577,15.1096906662 --1.93755245209,1.67773234844,15.1422748566 --1.98351752758,1.67674946785,15.1258659363 --2.03248167038,1.67776703835,15.1334590912 --2.05946326256,1.68077611923,15.1532526016 --2.11042642593,1.68379426003,15.1658372879 --2.16138982773,1.68681228161,15.1804256439 --2.20835447311,1.68582940102,15.1670131683 --2.25731873512,1.68684697151,15.1696043015 --2.30628299713,1.6878644228,15.1701927185 --2.35624670982,1.68988204002,15.17578125 --2.383228302,1.69289112091,15.1975841522 --2.4341917038,1.69490885735,15.2051677704 --2.48115682602,1.69492590427,15.1947603226 --2.53611922264,1.69994425774,15.2283496857 --2.58508324623,1.70096158981,15.226940155 --2.63604712486,1.70297908783,15.236530304 --2.68701052666,1.70499658585,15.2451210022 --2.71199250221,1.70500540733,15.2429113388 --2.76195669174,1.70702254772,15.2495079041 --2.81591939926,1.71104073524,15.2690925598 --2.86288428307,1.71005749702,15.2556858063 --2.91384792328,1.71207487583,15.2602739334 --2.96181297302,1.71309161186,15.2548713684 --3.01677560806,1.71710956097,15.279460907 --3.0417573452,1.71711826324,15.2762508392 --3.09072208405,1.71813511848,15.274848938 --3.14368486404,1.72115290165,15.2834320068 --3.19264960289,1.72216951847,15.2810287476 --3.24461293221,1.7241871357,15.2856140137 --3.29457736015,1.72520387173,15.2872114182 --3.32055926323,1.72621250153,15.2910089493 --3.37252283096,1.72822988033,15.2955970764 --3.42148756981,1.72924649715,15.2901916504 --3.47345113754,1.73126375675,15.2927770615 --3.52441525459,1.73328053951,15.297375679 --3.57238006592,1.73229706287,15.281961441 --3.62434387207,1.73431420326,15.2875547409 --3.65332460403,1.73732316494,15.3003482819 --3.7112865448,1.74234116077,15.3289394379 --3.75825214386,1.74235725403,15.314538002 --3.80921649933,1.74337387085,15.3141317368 --3.86417937279,1.74639117718,15.3287248611 --3.91714286804,1.74940824509,15.3333148956 --3.96910667419,1.75142502785,15.3359098434 --4.00108671188,1.75443446636,15.3567008972 --4.05005168915,1.75545048714,15.3493003845 --4.10401535034,1.75746762753,15.3568916321 --4.15897846222,1.76148462296,15.3684864044 --4.21294164658,1.76350152493,15.3740768433 --4.25890779495,1.76251721382,15.3526716232 --4.29588603973,1.76852703094,15.3914690018 --4.34485149384,1.7685431242,15.3780584335 --4.40181398392,1.77256047726,15.393652916 --4.4497795105,1.77257621288,15.3792495728 --4.50674247742,1.77559328079,15.3938426971 --4.55670690536,1.77660930157,15.3834342957 --4.61167001724,1.77962601185,15.3910303116 --4.63965177536,1.78063452244,15.394824028 --4.69461536407,1.78365111351,15.4024219513 --4.74757957458,1.78566741943,15.4030199051 --4.79654502869,1.78568315506,15.3886127472 --4.85350751877,1.78970003128,15.3982019424 --4.90547180176,1.79071605206,15.3937978745 --4.95243787766,1.79073119164,15.3743944168 --4.98541784286,1.79374027252,15.394194603 --5.04038190842,1.79675662518,15.3967857361 --5.10034370422,1.80077373981,15.4143800735 --5.15230846405,1.80178952217,15.4079742432 --5.20927143097,1.80580604076,15.4175729752 --5.26323604584,1.80782210827,15.4171695709 --5.25622797012,1.79582512379,15.3169631958 --5.26620531082,1.78183448315,15.1905584335 --5.29317712784,1.77384638786,15.1141529083 --5.34114313126,1.77386140823,15.0987491608 --5.37711238861,1.76987481117,15.0473394394 --5.43307590485,1.77289092541,15.05493927 --5.48804044724,1.77590680122,15.0575323105 --5.51402282715,1.77591454983,15.0543298721 --5.55799007416,1.774928689,15.0289297104 --5.61295413971,1.77794468403,15.0295200348 --5.66391944885,1.77895975113,15.0211162567 --5.70688724518,1.77797365189,14.993719101 --5.75685310364,1.77898859978,14.9823141098 --5.80481910706,1.77900314331,14.9659109116 --5.82780218124,1.77901029587,14.9547080994 --5.87976741791,1.78102552891,14.9483041763 --5.92373514175,1.77903938293,14.9208984375 --5.97670030594,1.7820545435,14.9174976349 --6.0266661644,1.78206932545,14.9040899277 --6.07463264465,1.78308367729,14.8886909485 --6.0986161232,1.78309082985,14.880490303 --6.14958143234,1.78410553932,14.8700847626 --6.20054721832,1.78512024879,14.8596811295 --6.24651432037,1.78513407707,14.8392820358 --6.29748010635,1.78714871407,14.827876091 --6.34944581985,1.78816342354,14.8194713593 --6.39541339874,1.78817713261,14.7990751266 --6.43539190292,1.79318630695,14.8268737793 --6.47736024857,1.79219949245,14.7944669724 --6.52032852173,1.79121279716,14.7650632858 --6.58229160309,1.79522848129,14.7806682587 --5.71052455902,1.52011656761,12.7151927948 --5.60053682327,1.47610914707,12.3657770157 --5.61151409149,1.46711838245,12.2863712311 --6.75317525864,1.79827725887,14.7222557068 --5.85641431808,1.52216303349,12.6627779007 --5.55448198318,1.42312979698,11.9113502502 --5.59345149994,1.42314267159,11.8969488144 --5.6764087677,1.43616127968,11.9765548706 --5.63740062714,1.41516363621,11.7971420288 --5.5714097023,1.39015877247,11.6109304428 --5.78432893753,1.44019472599,11.9565372467 --5.76731443405,1.4251999855,11.826130867 --5.88226270676,1.44622278214,11.9657335281 --6.04119777679,1.48025131226,12.1903362274 --5.90421772003,1.43224048615,11.8209228516 --5.97717761993,1.44225752354,11.8735256195 --5.9931640625,1.44126331806,11.8583230972 --5.984146595,1.42826962471,11.7469110489 --5.97513008118,1.41627597809,11.6375026703 --6.04509162903,1.42529225349,11.6841096878 --6.00408363342,1.4042942524,11.5146961212 --5.93008613586,1.37529206276,11.2862873077 --6.11601400375,1.41532337666,11.5508966446 --6.0610203743,1.39532005787,11.4026851654 --6.07699680328,1.39032936096,11.3462820053 --6.13696098328,1.39634442329,11.3708791733 --6.18592786789,1.40035784245,11.3754768372 --6.30687475204,1.42138040066,11.5100784302 --6.24887275696,1.3973801136,11.3196706772 --6.28185415268,1.40138792992,11.3374729156 --6.29583072662,1.39639699459,11.2770633698 --6.38278770447,1.40941488743,11.3486671448 --6.40776205063,1.40642511845,11.3092651367 --6.49071979523,1.41844248772,11.3718681335 --6.52369165421,1.41745352745,11.3454637527 --6.63464260101,1.43647420406,11.4550714493 --6.61363887787,1.42647528648,11.3758611679 --6.52464532852,1.39647126198,11.14245224 --6.60260438919,1.40648782253,11.1930484772 --6.53760433197,1.38248693943,11.0026350021 --6.66954898834,1.40550971031,11.1452484131 --6.73351240158,1.41252434254,11.1718492508 --6.7264957428,1.40253031254,11.0804433823 --6.77647304535,1.40953981876,11.1222410202 --6.81444406509,1.41055119038,11.105843544 --6.84841632843,1.41056215763,11.0814371109 --6.9083814621,1.41657602787,11.1000404358 --6.96034860611,1.42058885098,11.1046390533 --6.97432661057,1.41559720039,11.0492362976 --7.09028577805,1.43761408329,11.1940488815 --7.07827043533,1.42661952972,11.0956344604 --7.1572303772,1.43663537502,11.1412382126 --7.19220256805,1.43664586544,11.1188411713 --7.21617841721,1.43465518951,11.0794429779 --7.36711931229,1.46067893505,11.2340583801 --7.35610389709,1.4506841898,11.1386451721 --7.4560675621,1.46869885921,11.251455307 --7.51503372192,1.47371196747,11.2630586624 --7.4970202446,1.4617164135,11.1586484909 --7.57198238373,1.47073113918,11.1942577362 --7.6599407196,1.48274731636,11.2468614578 --7.71090936661,1.48575925827,11.2454652786 --7.71389007568,1.4787658453,11.1730585098 --7.69288730621,1.47076666355,11.1048526764 --7.66787624359,1.45777010918,10.9944477081 --7.77582979202,1.47278821468,11.074054718 --7.7508187294,1.46079158783,10.9646492004 --7.80978488922,1.46580433846,10.9732484818 --7.88274765015,1.47381830215,11.0018529892 --7.98871088028,1.49283277988,11.1136703491 --8.06067466736,1.49984657764,11.1382703781 --8.31858825684,1.54688024521,11.4189014435 --8.05364131927,1.48385775089,10.9804573059 --8.45651721954,1.5599064827,11.4551124573 --8.54347705841,1.57092130184,11.4967222214 --8.30052375793,1.5139015913,11.0952835083 --8.37649536133,1.52491235733,11.1600914001 --8.36048126221,1.51491653919,11.0646810532 --8.51642417908,1.53993833065,11.1983041763 --8.53240203857,1.53594577312,11.1459035873 --8.51938915253,1.5259500742,11.0554962158 --8.62034511566,1.53896605968,11.1131038666 --8.61932945251,1.53197157383,11.0397024155 --8.58532905579,1.52197086811,10.9604969025 --8.65429401398,1.52898347378,10.976099968 --8.52331066132,1.49597585201,10.7386732101 --8.64026355743,1.51199305058,10.815284729 --8.83919525146,1.54401838779,10.9939165115 --8.9221572876,1.55403196812,11.0255250931 --8.87515258789,1.53803265095,10.8961133957 --8.90113735199,1.54003798962,10.891910553 --9.0920715332,1.57006192207,11.0555438995 --9.09705448151,1.56406760216,10.9901409149 --9.04305076599,1.54706764221,10.8537244797 --9.05503177643,1.5430740118,10.7973184586 --9.0260219574,1.53107643127,10.6939134598 --9.01001834869,1.52407753468,10.640709877 --9.1469669342,1.54409563541,10.7343320847 --9.26292133331,1.56011176109,10.7999410629 --9.42386341095,1.58313190937,10.9185695648 --5.47784423828,0.83676803112,6.28654766083 --5.54378128052,0.838791906834,6.25952863693 --5.56375837326,0.838800668716,6.24212789536 --5.63272237778,0.847814083099,6.27872371674 --5.65669822693,0.848823130131,6.26532268524 --5.69467115402,0.852833330631,6.26792860031 --5.57032442093,0.761966049671,5.3533616066 --5.62929201126,0.768977582455,5.37495279312 --5.70725679398,0.778990149498,5.41657352448 --5.71223688126,0.776997447014,5.38515233994 --5.87916278839,0.799023211002,5.47437810898 --5.71118402481,0.768017232418,5.2809343338 --5.61717987061,0.74802005291,5.14331674576 --5.71014022827,0.761033773422,5.19491434097 --5.73211717606,0.762041985989,5.18151140213 --5.75709438324,0.763050317764,5.17111301422 --5.77807188034,0.764058351517,5.15671110153 --5.80804777145,0.766067028046,5.15031003952 --5.8280339241,0.768071770668,5.1511054039 --5.85800933838,0.770080387592,5.14470767975 --5.89198446274,0.773089170456,5.14130544662 --5.91296243668,0.774097025394,5.12690925598 --5.94493770599,0.777105808258,5.1204957962 --6.7704000473,0.853284060955,5.08510971069 --6.74737262726,0.844294071198,5.00029850006 --6.80134487152,0.850302577019,5.00690174103 --5.54757642746,0.654247760773,4.01385068893 --5.57555341721,0.656255722046,4.00643968582 --5.58154392242,0.656259179115,3.99723911285 --7.68881750107,0.931457877159,4.87117195129 --7.67580461502,0.926462173462,4.82775831223 --7.70378398895,0.928467988968,4.81136226654 --8.01865673065,0.964499950409,4.85161209106 --8.05363559723,0.966505467892,4.83821964264 --8.09961223602,0.971511363983,4.83082389832 --8.15858650208,0.977517545223,4.83143663406 --8.244556427,0.987524688244,4.84704685211 --8.2755355835,0.989529848099,4.82964658737 --8.34550857544,0.997536063194,4.83626937866 --11.8068552017,1.4866412878,6.80860519409 --11.8048439026,1.48364281654,6.7572016716 --11.796833992,1.47964417934,6.70279932022 --11.7998218536,1.4766459465,6.65439558029 --11.7988100052,1.47364759445,6.60399103165 --11.7987995148,1.47064912319,6.55458974838 --11.7767982483,1.46564936638,6.51738071442 --11.7747869492,1.46265077591,6.46697664261 --11.8227672577,1.46665346622,6.44559574127 --11.8227558136,1.46365499496,6.39618968964 --11.9057302475,1.47265815735,6.39281272888 --11.9927043915,1.48166143894,6.39043092728 --12.0636816025,1.48866403103,6.38005495071 --12.1266651154,1.49566590786,6.38887023926 --12.1746463776,1.49966800213,6.36548662186 --12.2516222,1.50767040253,6.35610294342 --12.2386140823,1.50367128849,6.29969739914 --12.3565740585,1.51367509365,6.26192903519 --8.03329372406,0.915606439114,4.01648378372 --8.03927898407,0.914610624313,3.98707842827 --8.0382642746,0.912614703178,3.95366430283 --8.04024982452,0.91161864996,3.92326831818 --8.03923606873,0.909622788429,3.88985133171 --8.02622413635,0.905626475811,3.85245466232 --8.03020954132,0.904630541801,3.82204294205 --8.03120326996,0.904632508755,3.80684232712 --8.02318954468,0.901636362076,3.77143621445 --8.02317619324,0.899640321732,3.74003267288 --8.03016090393,0.898644268513,3.7116253376 --8.02015018463,0.895648002625,3.67622613907 --8.01313686371,0.89365196228,3.64080691338 --8.01912212372,0.892655849457,3.6124022007 --8.01411628723,0.891657710075,3.59520673752 --8.01710128784,0.889661610126,3.56479167938 --8.00508975983,0.886665463448,3.52838253975 --8.00907516479,0.885669231415,3.49998569489 --8.04205703735,0.888673067093,3.48459672928 --8.11003303528,0.896677136421,3.48319959641 --8.17201042175,0.903680860996,3.47981524467 --8.21799659729,0.908682763577,3.48462843895 --8.28197383881,0.915686428547,3.48124170303 --8.33395290375,0.920690000057,3.47184586525 --8.38693141937,0.926693320274,3.46346187592 --8.44790935516,0.933696746826,3.45706629753 --8.51588630676,0.940699875355,3.45367860794 --8.56586647034,0.945702910423,3.44329738617 --8.62285137177,0.952704429626,3.45010185242 --8.69582843781,0.960707187653,3.44872903824 --11.680393219,1.35469377041,4.63126182556 --11.6803836823,1.35269451141,4.5878572464 --11.6783742905,1.35069513321,4.54445886612 --11.673365593,1.34869587421,4.49905014038 --11.6843547821,1.34769630432,4.46065235138 --11.6653528214,1.34469676018,4.43245077133 --11.6443462372,1.33969759941,4.38103580475 --11.6663331985,1.34069800377,4.34663724899 --11.6953201294,1.34269809723,4.31524467468 --11.694311142,1.34069859982,4.27284622192 --11.749294281,1.34569835663,4.25045728683 --11.6542978287,1.33169996738,4.17403316498 --11.6442947388,1.32970035076,4.1488237381 --11.6372861862,1.32670092583,4.10441970825 --11.6372776031,1.32570135593,4.06302070618 --11.6322689056,1.32270181179,4.01860809326 --11.6302604675,1.32070231438,3.97721409798 --11.6392498016,1.32070243359,3.93881416321 --11.6312417984,1.31770288944,3.89440703392 --11.6152391434,1.3147033453,3.86820006371 --11.6262283325,1.3147033453,3.83080220222 --11.6082220078,1.31070411205,3.78339195251 --11.6172122955,1.31070411205,3.74498867989 --11.610203743,1.3077044487,3.70158267021 --11.5881977081,1.30370509624,3.65417909622 --11.4662084579,1.28670823574,3.59393405914 --11.4681987762,1.28570842743,3.55453395844 --11.4651908875,1.2837086916,3.51312732697 --11.4421844482,1.27970957756,3.46571564674 --11.4461755753,1.27870965004,3.42731714249 --11.4421672821,1.27670991421,3.38590979576 --11.4441585541,1.27471005917,3.34650564194 --11.4381551743,1.27371025085,3.3253068924 --11.4371461868,1.27271044254,3.28489875793 --11.4351377487,1.2707105875,3.24449300766 --11.4401292801,1.26971054077,3.20709848404 --11.4311218262,1.26771092415,3.16468858719 --11.4241142273,1.26471114159,3.12328267097 --11.4401044846,1.26571047306,3.08888888359 --11.4221019745,1.26271104813,3.06468582153 --11.4170942307,1.26071119308,3.02428245544 --11.420085907,1.25971114635,2.9858789444 --11.4200782776,1.25871098042,2.94647169113 --11.4220695496,1.25771069527,2.90806937218 --11.4080629349,1.25471115112,2.86566305161 --11.4140539169,1.2547107935,2.82825994492 --11.3860530853,1.25071179867,2.80205273628 --11.4110422134,1.25271046162,2.76965665817 --11.4200344086,1.25270974636,2.73325657845 --11.3830289841,1.24671125412,2.68584394455 --11.3900203705,1.24571061134,2.64843630791 --11.4220104218,1.24870884418,2.61804747581 --11.4549999237,1.25270676613,2.58765792847 --11.4769945145,1.2547056675,2.57346272469 --11.5109834671,1.2577034235,2.54307413101 --11.5499734879,1.26170110703,2.51368808746 --11.577963829,1.26369905472,2.48129439354 --11.5299596786,1.25670087337,2.43187379837 --11.4989547729,1.25170183182,2.38645792007 --11.4899520874,1.2507019043,2.36525225639 --11.5499410629,1.25669813156,2.33987116814 --11.7459173203,1.2806866169,2.34354662895 --11.7719087601,1.28268432617,2.31015563011 --11.7989006042,1.28468179703,2.27676415443 --11.8298912048,1.28767895699,2.24336695671 --11.8628826141,1.29167592525,2.21097826958 --11.8878736496,1.2936732769,2.17658400536 --11.9288682938,1.29767024517,2.16540336609 --11.9478607178,1.29966771603,2.12900066376 --11.5528821945,1.2496907711,2.01544642448 --11.3428897858,1.22270274162,1.93896615505 --11.4258775711,1.23169672489,1.91659331322 --11.2988796234,1.2147039175,1.85714900494 --11.2978725433,1.21470308304,1.81974315643 --11.2848701477,1.21270358562,1.79853177071 --11.3068628311,1.21470117569,1.76513504982 --11.3208551407,1.21469926834,1.73074018955 --11.3658456802,1.21969521046,1.70135712624 --11.5498285294,1.24268138409,1.69402837753 --11.5288228989,1.23868155479,1.65261232853 --11.5298204422,1.23868095875,1.63441574574 --11.6448078156,1.25267124176,1.61405408382 --11.4758110046,1.23068225384,1.55159115791 --11.4578065872,1.22768223286,1.51117575169 --11.3788042068,1.21668684483,1.46274197102 --11.2088069916,1.19569849968,1.40227305889 --11.3117952347,1.20768940449,1.37990987301 --11.376789093,1.21568369865,1.37073814869 --11.2697877884,1.20169067383,1.31928634644 --11.2407846451,1.19769179821,1.27886879444 --11.4507694244,1.22267353535,1.26955783367 --11.5117607117,1.22966706753,1.24018085003 --11.198767662,1.19069135189,1.16564953327 --11.2207612991,1.19268810749,1.13225710392 --11.15376091,1.18469297886,1.10602259636 --11.1267566681,1.18069398403,1.06761407852 --11.2247467041,1.19168412685,1.04224944115 --11.112745285,1.17769241333,0.993793308735 --11.177737236,1.18568527699,0.965424835682 --11.2737293243,1.19667518139,0.938050746918 --11.290722847,1.1986720562,0.903656423092 --11.3287191391,1.20266771317,0.88947468996 --11.1697187424,1.18268060684,0.839008688927 --11.1177148819,1.17568385601,0.798582971096 --11.1207094193,1.17568194866,0.763180375099 --11.1467037201,1.17867767811,0.729789018631 --11.0967006683,1.1726808548,0.690366387367 --11.1786928177,1.18167114258,0.660997331142 --11.1536903381,1.17867267132,0.640779316425 --11.1806850433,1.18166828156,0.607391536236 --11.1706809998,1.18066751957,0.5709836483 --11.121676445,1.17367041111,0.531552672386 --11.0566730499,1.16567516327,0.492121815681 --11.1276664734,1.1746660471,0.460746407509 --11.1576623917,1.17766106129,0.427361369133 --11.1586589813,1.17765986919,0.409154802561 --11.1286554337,1.17366099358,0.372746169567 --11.2076501846,1.18365049362,0.340369850397 --11.2196455002,1.18464708328,0.304969340563 --11.242641449,1.18664228916,0.270580887794 --11.2026376724,1.1816444397,0.233158752322 --11.1716337204,1.17764568329,0.196745470166 --11.295630455,1.19363069534,0.182592853904 --11.2076272964,1.18263816833,0.144152313471 --11.2146234512,1.18263494968,0.10875313729 --11.1156196594,1.17064404488,0.0713124498725 --11.1326150894,1.17263960838,0.0359121412039 --11.2826128006,1.1906195879,0.00256953923963 --11.3346090317,1.1976108551,-0.0328134559095 --11.3266067505,1.19661045074,-0.0500082820654 --11.2356033325,1.18561863899,-0.0874587744474 --11.2325992584,1.18461632729,-0.122859425843 --11.1545953751,1.17562317848,-0.159303426743 --11.2525920868,1.18660843372,-0.194661274552 --11.3235902786,1.19559681416,-0.231036931276 --11.3455896378,1.19859278202,-0.248218417168 --11.2675848007,1.18859946728,-0.283656567335 --11.2315816879,1.18460118771,-0.319076180458 --11.2615795135,1.18859434128,-0.355468899012 --11.2485761642,1.18659305573,-0.390875995159 --11.2935743332,1.19258415699,-0.428266853094 --11.3625736237,1.20057201385,-0.465636521578 --11.4415740967,1.21055996418,-0.485803335905 --11.4185714722,1.20755970478,-0.521213293076 --11.4075689316,1.2065577507,-0.55762642622 --11.2975625992,1.19356942177,-0.590079903603 --11.3395624161,1.19856035709,-0.627461969852 --11.2395563126,1.18657076359,-0.658904969692 --11.321557045,1.19655585289,-0.699281334877 --11.4115591049,1.20754158497,-0.721441566944 --11.3505554199,1.20054662228,-0.754873752594 --11.3505535126,1.20054316521,-0.790268421173 --11.4255542755,1.21052873135,-0.830637574196 --11.5155572891,1.22151196003,-0.873006463051 --11.4315519333,1.21152031422,-0.904447495937 --11.4785528183,1.21750950813,-0.943827331066 --11.4895524979,1.21950590611,-0.96302562952 --11.5145521164,1.22249829769,-1.0014166832 --11.3955459595,1.20851206779,-1.02987933159 --11.391544342,1.20750880241,-1.06527638435 --11.4295444489,1.21349906921,-1.10466170311 --11.4785470963,1.21948730946,-1.1460506916 --11.4495439529,1.2164876461,-1.18046939373 --11.4185419083,1.21249043941,-1.19568097591 --11.4585437775,1.21747994423,-1.23606753349 --11.4835453033,1.2214717865,-1.27445185184 --11.5035457611,1.22446405888,-1.31385290623 --11.4825439453,1.22246313095,-1.34826159477 --11.3935375214,1.21147286892,-1.37671530247 --11.4635419846,1.22045719624,-1.42007803917 --11.3665342331,1.20847094059,-1.42832887173 --11.423538208,1.21645712852,-1.47069966793 --11.4315395355,1.21745109558,-1.50910711288 --11.5275468826,1.23043036461,-1.55746781826 --11.466542244,1.22343599796,-1.58689641953 --11.3795347214,1.21344602108,-1.6133440733 --11.5645503998,1.23640954494,-1.67365956306 --11.5515499115,1.2354092598,-1.69086992741 --11.4505414963,1.22342193127,-1.71431565285 --11.4165391922,1.21942281723,-1.74673509598 --11.4725446701,1.2274081707,-1.79110813141 --11.4755458832,1.22840249538,-1.82951903343 --11.5155496597,1.23339033127,-1.87189614773 --11.3945388794,1.21940684319,-1.89135813713 --11.6395635605,1.25036001205,-1.94644069672 --11.3985414505,1.22039842606,-1.9479663372 --11.3925409317,1.22039437294,-1.98437571526 --11.4445476532,1.22737967968,-2.02874302864 --11.553560257,1.24235391617,-2.08409714699 --11.5515623093,1.24234879017,-2.12150192261 --11.4885559082,1.23535788059,-2.12973356247 --11.509560585,1.23834836483,-2.17112970352 --11.4725570679,1.23434972763,-2.20255351067 --11.6455793381,1.2573107481,-2.27087330818 --11.5845746994,1.25031661987,-2.29830956459 --11.6095790863,1.25430595875,-2.34069848061 --11.5715770721,1.25030755997,-2.37111377716 --11.565577507,1.25030565262,-2.38932204247 --11.5785808563,1.2522970438,-2.42971730232 --11.6455926895,1.26127767563,-2.48108911514 --11.7276058197,1.27225482464,-2.53645896912 --11.6976051331,1.27025449276,-2.56887483597 --11.783618927,1.28123044968,-2.62523555756 --11.7136135101,1.27323830128,-2.64967370033 --11.7956256866,1.2842181921,-2.68582987785 --11.721619606,1.27622687817,-2.70927119255 --11.9776582718,1.30916666985,-2.80354547501 --12.0386705399,1.31814670563,-2.85691952705 --11.8876533508,1.30017149448,-2.86339950562 --11.8556537628,1.29717123508,-2.89581871033 --11.8896627426,1.30215680599,-2.94320487976 --12.0356884003,1.32211792469,-3.01753997803 --11.9986858368,1.31812226772,-3.02875804901 --12.063700676,1.32710063457,-3.08412480354 --12.121714592,1.335080266,-3.1384973526 --12.1317214966,1.3380702734,-3.18189764023 --12.1957378387,1.34704816341,-3.23826479912 --12.2227468491,1.35203397274,-3.2866590023 --12.2677574158,1.3580198288,-3.31883907318 --12.6318235397,1.40492916107,-3.45304989815 --12.375787735,1.37397873402,-3.42958712578 --12.5418224335,1.39693212509,-3.51490163803 --12.4928216934,1.39193451405,-3.54533863068 --12.4458208084,1.38693654537,-3.57476210594 --12.4608297348,1.3899242878,-3.62115621567 --12.4918394089,1.3949123621,-3.65134572983 --12.5648593903,1.40588629246,-3.71370506287 --13.1059656143,1.47574818134,-3.90983319283 --12.7909164429,1.43681359291,-3.8643951416 --12.7439165115,1.43281519413,-3.89482331276 --13.2200145721,1.49469017982,-4.07697105408 --13.5120811462,1.53360819817,-4.20922422409 --13.5440921783,1.53859472275,-4.2424120903 --13.6361207962,1.55156099796,-4.31676483154 --13.6381320953,1.55354917049,-4.36416292191 --13.7961750031,1.5754981041,-4.46048545837 --13.5781431198,1.54954135418,-4.43999767303 --13.7861967087,1.5774769783,-4.5532951355 --13.5211544037,1.54553258419,-4.51683521271 --16.0026760101,1.86589300632,-5.33270740509 --15.9666862488,1.86288690567,-5.37612104416 --15.9236946106,1.85988235474,-5.41854858398 --15.9277143478,1.86186552048,-5.47594833374 --14.3693914413,1.6632578373,-5.01218557358 --15.1795854568,1.77003085613,-5.33615398407 --15.1906042099,1.77301347256,-5.39254188538 --13.6492671967,1.57441544533,-4.89358520508 --13.818318367,1.59835791588,-4.9998922348 --13.9473619461,1.61731040478,-5.09422636032 --13.9793834686,1.62328875065,-5.15460634232 --13.9693956375,1.62427818775,-5.20101499557 --13.8683862686,1.61229264736,-5.21447038651 --13.6693525314,1.5893342495,-5.19198226929 --13.9674310684,1.62924528122,-5.32501888275 --14.0014543533,1.63522219658,-5.38840770721 --14.0284767151,1.64120101929,-5.44879388809 --14.1155128479,1.65416252613,-5.53214788437 --14.2685670853,1.67710518837,-5.64046001434 --14.5366516113,1.71401417255,-5.79572057724 --14.4326429367,1.70302903652,-5.80817842484 --14.5386791229,1.71799111366,-5.87531805038 --14.705739975,1.74192762375,-5.99362611771 --14.7797765732,1.75389039516,-6.07698869705 --14.7717943192,1.75587677956,-6.12839794159 --14.9708652496,1.78380227089,-6.26268720627 --15.4170064926,1.84565377235,-6.49883747101 --15.2979946136,1.83267188072,-6.50730752945 --15.4680519104,1.85661256313,-6.6054110527 --15.4890794754,1.86158883572,-6.67079544067 --15.6941585541,1.89150881767,-6.81508636475 --15.7591991425,1.90347099304,-6.90044641495 --15.8642520905,1.91942024231,-7.00479221344 --16.1983737946,1.96729850769,-7.2080039978 --16.5244941711,2.01417803764,-7.41021871567 --16.7115592957,2.04011011124,-7.52230930328 --16.9516563416,2.07501387596,-7.6915769577 --17.0757217407,2.09495425224,-7.80990171432 --17.1547737122,2.10890746117,-7.91025781631 --17.3608646393,2.13981986046,-8.06854057312 --17.5959663391,2.17472243309,-8.24180698395 --17.726020813,2.19366908073,-8.33493232727 --17.7960758209,2.20662355423,-8.43428707123 --17.8231124878,2.21359109879,-8.51567459106 --17.8961677551,2.22754359245,-8.61802959442 --17.9842300415,2.24249076843,-8.72837543488 --17.9502506256,2.24147748947,-8.78179454803 --17.9312763214,2.24245977402,-8.84220314026 --17.9212913513,2.24345064163,-8.87240886688 --17.9363288879,2.24942111969,-8.94980144501 --17.9523658752,2.25539088249,-9.02819347382 --18.0024166107,2.26534867287,-9.12356376648 --17.9964485168,2.26832556725,-9.19096374512 --18.0074863434,2.27429652214,-9.26735591888 --18.0125236511,2.27826952934,-9.3407497406 --18.0335483551,2.28324913979,-9.38794136047 --18.0635929108,2.29121303558,-9.47431850433 --18.0766334534,2.29718208313,-9.55371379852 --18.0986785889,2.30414819717,-9.6370973587 --18.1197223663,2.31111431122,-9.72148799896 --18.1457691193,2.31907844543,-9.80786991119 --18.1578102112,2.32504725456,-9.88725948334 --18.1868400574,2.33102345467,-9.93944168091 --18.1848754883,2.33499670029,-10.0128450394 --18.1889152527,2.33996772766,-10.0892429352 --18.2219676971,2.3489279747,-10.1816215515 --18.217004776,2.35190224648,-10.2530202866 --18.2060375214,2.35487818718,-10.3224287033 --18.1940727234,2.35785460472,-10.3908338547 --18.1950931549,2.35983991623,-10.4290323257 --18.1961326599,2.36481118202,-10.5054321289 --18.212179184,2.37177658081,-10.5898189545 --18.2192230225,2.376745224,-10.670214653 --18.1782474518,2.3757314682,-10.7236413956 --18.1532783508,2.3767118454,-10.7860574722 --18.1393146515,2.37968802452,-10.8544635773 --18.126329422,2.38067865372,-10.8846693039 --18.1133670807,2.38265395164,-10.9540748596 --18.0843963623,2.38363575935,-11.0144939423 --18.0574264526,2.38461637497,-11.0759105682 --18.0354595184,2.38659524918,-11.1403236389 --18.0204963684,2.38957118988,-11.2087306976 --18.0045318604,2.39154720306,-11.2771396637 --17.9975509644,2.39353513718,-11.3113412857 --17.9855899811,2.39650893211,-11.3837547302 --17.9476184845,2.39649391174,-11.4381742477 --17.9206504822,2.3974738121,-11.5005941391 --17.9006843567,2.39945149422,-11.5659999847 --17.8737163544,2.40043139458,-11.6284179688 --17.8457489014,2.40141153336,-11.6898345947 --17.8427715302,2.4043970108,-11.7280387878 --17.8338127136,2.40836954117,-11.8014411926 --17.8078460693,2.40934872627,-11.864859581 --17.8078918457,2.41431665421,-11.9452590942 --17.8159427643,2.42128133774,-12.0306520462 --17.8660125732,2.434227705,-12.1450214386 --17.8570575714,2.43819880486,-12.2204265594 --17.8400726318,2.43818950653,-12.2506408691 --17.804101944,2.43917226791,-12.3080625534 --17.8391685486,2.44912385941,-12.4144430161 --18.0793361664,2.49098515511,-12.6616945267 --18.3805370331,2.54181838036,-12.9529037476 --18.3765869141,2.54678487778,-13.0363063812 --18.3846168518,2.55076384544,-13.0844993591 --18.3126354218,2.54576015472,-13.1209468842 --18.240650177,2.54175686836,-13.1563911438 --18.1526584625,2.534760952,-13.1808490753 --18.1036834717,2.53274726868,-13.2322797775 --18.0276985168,2.52774643898,-13.2637252808 --17.9457073212,2.52174854279,-13.2901735306 --17.9247245789,2.5217397213,-13.319393158 --17.8457336426,2.51574039459,-13.3478412628 --17.7687473297,2.50974011421,-13.3782920837 --17.7027645111,2.50673484802,-13.4157323837 --17.6337814331,2.50173139572,-13.4511766434 --17.5627975464,2.49772882462,-13.4846229553 --17.4928092957,2.49272584915,-13.5180644989 --17.4548168182,2.49072623253,-13.5322875977 --17.3618202209,2.48273396492,-13.5487499237 --17.3098449707,2.48072314262,-13.5951805115 --17.2138442993,2.47273278236,-13.6086454391 --17.156867981,2.4697239399,-13.6510810852 --17.0678691864,2.46273088455,-13.6685400009 --17.0208969116,2.46171736717,-13.7189722061 --16.9718971252,2.45772314072,-13.7242059708 --16.9049129486,2.45371961594,-13.7576475143 --16.8329257965,2.44871854782,-13.7880983353 --16.7599372864,2.44471883774,-13.8155412674 --16.7079620361,2.44270730019,-13.8619813919 --16.6389770508,2.43870520592,-13.8934288025 --16.5759944916,2.43570041656,-13.9288682938 --16.5269927979,2.43070650101,-13.9331035614 --16.463010788,2.42770218849,-13.9675455093 --16.3930225372,2.42370152473,-13.9959878922 --16.342048645,2.42169046402,-14.0414237976 --16.2800655365,2.41968488693,-14.0778684616 --16.2220859528,2.41667747498,-14.1173095703 --16.1591033936,2.41367292404,-14.1517524719 --16.1081008911,2.40868115425,-14.1519861221 --16.0481185913,2.40667486191,-14.1894302368 --15.9991455078,2.4056634903,-14.2348613739 --15.9311590195,2.40166187286,-14.2643070221 --15.8661746979,2.39765834808,-14.2967557907 --15.8071947098,2.39565253258,-14.3331947327 --15.7502145767,2.39364504814,-14.3716344833 --15.7042121887,2.38965129852,-14.3748636246 --15.6542387009,2.38864016533,-14.4192991257 --15.5952577591,2.38563418388,-14.4557409286 --15.5462837219,2.38562250137,-14.5011768341 --15.4772968292,2.3816215992,-14.5286283493 --15.427321434,2.38061094284,-14.5720615387 --15.3593349457,2.37661027908,-14.5995092392 --15.349357605,2.37859630585,-14.6357192993 --15.294380188,2.37658786774,-14.6751585007 --15.2343988419,2.37458276749,-14.709602356 --15.1884269714,2.37456941605,-14.7570352554 --14.9283590317,2.34564185143,-14.6900138855 --15.0054798126,2.3665561676,-14.8563680649 --15.009513855,2.37153315544,-14.9065694809 --14.9395246506,2.36653447151,-14.9300165176 --14.9035615921,2.36851501465,-14.9874458313 --14.8415775299,2.36551141739,-15.0188913345 --14.8016109467,2.36649441719,-15.0723228455 --14.7496347427,2.36548519135,-15.1127576828 --14.7286520004,2.36647677422,-15.1389760971 --14.6736745834,2.36446881294,-15.1774187088 --14.6447181702,2.36844444275,-15.2428455353 --14.5857362747,2.36543941498,-15.2762861252 --14.5327596664,2.36442995071,-15.3167276382 --14.4937963486,2.36641216278,-15.3711576462 --14.443821907,2.36540102959,-15.4145975113 --14.4068593979,2.36738181114,-15.4710254669 --14.3878774643,2.36837267876,-15.4982376099 --14.3489141464,2.37035369873,-15.5546751022 --14.3009433746,2.37034130096,-15.600112915 --14.2559738159,2.37032723427,-15.6475429535 --14.2120056152,2.37131166458,-15.6979799271 --14.1630344391,2.37129974365,-15.7424182892 --14.1510591507,2.37328529358,-15.7786312103 --14.0960826874,2.37227749825,-15.8160715103 --14.0501127243,2.37226366997,-15.8635063171 --14.0131521225,2.37524366379,-15.9209356308 --13.9581756592,2.3742351532,-15.9593811035 --13.9232168198,2.37621355057,-16.0198116302 --13.8832530975,2.3781952858,-16.0742435455 --13.8622722626,2.37918639183,-16.1014633179 --13.8193063736,2.38016986847,-16.1528987885 --13.7733392715,2.38115525246,-16.201335907 --13.7343759537,2.38313627243,-16.2567653656 --13.691411972,2.38411927223,-16.3092021942 --13.6474456787,2.38510346413,-16.3596363068 --13.6114883423,2.3880815506,-16.4200668335 --13.5965127945,2.3900680542,-16.4542827606 --13.5615558624,2.393045187,-16.5167140961 --13.5175914764,2.39402890205,-16.5671463013 --13.4255809784,2.38704681396,-16.5616207123 --13.3025379181,2.37308835983,-16.5161094666 --13.097413063,2.34319090843,-16.3686561584 --12.9893836975,2.33222222328,-16.340139389 --12.9653978348,2.33221650124,-16.3613548279 --13.0175275803,2.3521296978,-16.5297260284 --12.9445323944,2.34713554382,-16.5431804657 --12.9105768204,2.3511121273,-16.6056118011 --12.8766231537,2.35408830643,-16.6690444946 --12.7946186066,2.34810137749,-16.6705093384 --12.7226238251,2.34410667419,-16.684967041 --12.6696100235,2.33912277222,-16.6702079773 --12.6046218872,2.33612298965,-16.6926612854 --12.5436382294,2.33412051201,-16.7201080322 --12.4886608124,2.33311319351,-16.7555561066 --12.4126625061,2.3281223774,-16.7630176544 --12.3106327057,2.31815314293,-16.7344913483 --12.2596187592,2.31316828728,-16.7207336426 --12.1836175919,2.30817866325,-16.7261924744 --12.1446580887,2.31015896797,-16.7826309204 --12.0696573257,2.30516839027,-16.7890872955 --11.9946565628,2.30117869377,-16.7945461273 --11.9366760254,2.2991745472,-16.8249988556 --11.847659111,2.29219603539,-16.8114700317 --11.7696533203,2.28620934486,-16.8119316101 --11.7076253891,2.27823495865,-16.7801780701 --11.6356258392,2.27424383163,-16.7876338959 --11.574640274,2.2722427845,-16.8120880127 --11.4976348877,2.2672560215,-16.8125495911 --11.4446582794,2.26624822617,-16.8479976654 --11.3756628036,2.26325488091,-16.859457016 --11.3396635056,2.26125955582,-16.8626842499 --11.3207273483,2.26822328568,-16.9461040497 --11.2757606506,2.26920843124,-16.9935474396 --11.2127714157,2.26721024513,-17.0129985809 --11.1547889709,2.26620697975,-17.0404510498 --11.1088228226,2.26719355583,-17.085893631 --11.0458335876,2.26519465446,-17.1063499451 --11.0228500366,2.26618790627,-17.1285686493 --10.9308242798,2.25721597672,-17.1040458679 --10.8428010941,2.24924111366,-17.0835151672 --10.7918272018,2.24923205376,-17.1209640503 --10.7398509979,2.24922466278,-17.1554050446 --10.6408147812,2.23926019669,-17.1178894043 --10.5968494415,2.24124526978,-17.1653308868 --10.5508346558,2.23625993729,-17.1515693665 --10.4958553314,2.2362549305,-17.1820220947 --10.426856041,2.23226451874,-17.1874732971 --10.3508472443,2.2272799015,-17.1839408875 --10.3178977966,2.2312541008,-17.2493743896 --10.2408876419,2.22627091408,-17.2428398132 --10.1909141541,2.22626161575,-17.2802829742 --10.1689329147,2.22825336456,-17.3055095673 --10.0959272385,2.22326660156,-17.3049736023 --10.0299301147,2.22027373314,-17.3144283295 --9.9809589386,2.22126364708,-17.3538742065 --9.91796779633,2.21926665306,-17.3703346252 --9.86398792267,2.21826219559,-17.3997783661 --9.83399486542,2.21826267242,-17.4100074768 --8.157579422,1.81793129444,-14.6005754471 --9.71201705933,2.21426653862,-17.4469165802 --9.65503406525,2.21326422691,-17.4723701477 --9.58603191376,2.20927500725,-17.4758300781 --9.5150270462,2.20528769493,-17.4762954712 --8.03281021118,1.84381008148,-14.9117307663 --7.90164756775,1.81592440605,-14.7280311584 --7.94680547714,1.83882415295,-14.9194145203 --6.77401638031,1.54904806614,-12.859629631 --7.67955112457,1.79401183128,-14.6424245834 --7.83589315414,1.84578692913,-15.0457344055 --7.79090929031,1.84678375721,-15.0721759796 --7.69684457779,1.83383512497,-15.005654335 --7.65982866287,1.82984948158,-14.9918899536 --7.56676292419,1.8179012537,-14.92436409 --7.51576900482,1.81590461731,-14.9398174286 --7.56494474411,1.84179389477,-15.1491966248 --7.55402088165,1.85175025463,-15.2446222305 --7.51204252243,1.85274338722,-15.2770614624 --7.48108482361,1.85672259331,-15.3334989548 --7.57630205154,1.88958084583,-15.585644722 --7.28788805008,1.82286596298,-15.1202526093 --7.15574741364,1.79896724224,-14.9687604904 --7.11376810074,1.80096101761,-15.0002069473 --7.27716350555,1.85970509052,-15.4575071335 --6.99474334717,1.79299235344,-14.988114357 --7.20323038101,1.86567640305,-15.5483894348 --5.44907331467,1.37978136539,-11.9851999283 --6.92195606232,1.8188778162,-15.2566204071 --6.89701128006,1.8248488903,-15.3270568848 --6.79391527176,1.80891990662,-15.2265434265 --6.83610153198,1.83480477333,-15.4439277649 --6.79312324524,1.83579802513,-15.4763765335 --6.60079526901,1.78601813316,-15.1107187271 --6.64999866486,1.8148920536,-15.3471002579 --6.47174406052,1.77406692505,-15.0686340332 --6.37465190887,1.75913476944,-14.973118782 --6.32465457916,1.75814032555,-14.9845714569 --6.44501304626,1.80991327763,-15.3939094543 --6.57233572006,1.85670661926,-15.7580299377 --6.4682302475,1.83878338337,-15.6475191116 --6.37314081192,1.82384955883,-15.5549983978 --6.2449798584,1.79896247387,-15.3825054169 --6.20600938797,1.80095112324,-15.422949791 --6.04376554489,1.76411688328,-15.1594734192 --6.07494974136,1.78900516033,-15.3718719482 --6.06899547577,1.7949795723,-15.4260883331 --5.90073251724,1.75515758991,-15.1416168213 --5.87478923798,1.76212859154,-15.2120523453 --5.80274105072,1.75316727161,-15.1665201187 --5.55227518082,1.68447518349,-14.6591062546 --5.61253261566,1.7203168869,-14.9514875412 --5.62066936493,1.73923647404,-15.1098966599 --5.69089984894,1.77109229565,-15.368065834 --5.56171035767,1.7432217598,-15.1665687561 --5.51672363281,1.74322080612,-15.1890192032 --5.43765258789,1.73227393627,-15.1184921265 --5.3686041832,1.72331249714,-15.0729541779 --5.31258869171,1.72033011913,-15.0634126663 --5.27261304855,1.72232210636,-15.097858429 --5.20550489426,1.70639491081,-14.9831142426 --5.13545131683,1.69743657112,-14.9325838089 --5.08845424652,1.69644224644,-14.9430274963 --5.06452131271,1.70540761948,-15.0234651566 --5.02253913879,1.70640361309,-15.0509119034 --4.95047712326,1.69645035267,-14.9913816452 --4.90147733688,1.69545829296,-14.9988365173 --4.88349437714,1.69745135307,-15.0210571289 --4.82346391678,1.69247829914,-14.9955205917 --4.77245521545,1.69049119949,-14.993970871 --4.76356887817,1.70542752743,-15.1243982315 --4.70153236389,1.69845795631,-15.0928649902 --4.64350509644,1.69448316097,-15.0703239441 --4.65167188644,1.71638631821,-15.2577362061 --4.66980028152,1.73331010342,-15.3999385834 --4.59071063995,1.72037410736,-15.3104095459 --4.54371881485,1.72037672997,-15.3268661499 --4.49872970581,1.72037804127,-15.3453102112 --4.4166264534,1.70545017719,-15.2417869568 --4.37163877487,1.70645046234,-15.2622385025 --4.38175201416,1.72138416767,-15.3874511719 --4.32673168182,1.71740472317,-15.3729057312 --4.27371931076,1.71542060375,-15.3663635254 --4.22772884369,1.71542263031,-15.3838148117 --4.19077062607,1.72040510178,-15.4352655411 --4.13775730133,1.71742165089,-15.4277210236 --4.08775472641,1.71643126011,-15.4321784973 --4.03072595596,1.71245706081,-15.4086380005 --4.05288934708,1.73336064816,-15.5858335495 --3.97378396988,1.71843385696,-15.4803085327 --3.90270233154,1.70649194717,-15.4007740021 --3.85169553757,1.70550465584,-15.4002342224 --3.78964424133,1.69754421711,-15.3526945114 --3.72759270668,1.69058394432,-15.3051586151 --3.70258784294,1.68959093094,-15.3033828735 --3.63451433182,1.67864406109,-15.2328577042 --3.55137443542,1.65973746777,-15.0923318863 --3.50839114189,1.66173553467,-15.1167821884 --3.47846126556,1.66970074177,-15.1982269287 --3.41539716721,1.66074776649,-15.1376895905 --3.35735201836,1.65478348732,-15.0971498489 --3.36347532272,1.67071259022,-15.2303571701 --3.31246066093,1.66772985458,-15.2218141556 --3.27349734306,1.67271590233,-15.2672643661 --3.17828774452,1.6448507309,-15.0547475815 --3.17046380043,1.66675269604,-15.2461833954 --3.16766619682,1.69363903999,-15.4646129608 --3.10158348083,1.68169724941,-15.3850793839 --3.10973191261,1.70161211491,-15.5432872772 --3.02757549286,1.68071484566,-15.3867702484 --3.03785634041,1.71655476093,-15.6861953735 --3.0089533329,1.728505373,-15.7936401367 --2.95392394066,1.72453188896,-15.7691011429 --2.89587759972,1.71756827831,-15.727563858 --2.86698079109,1.73051548004,-15.8410110474 --2.85906672478,1.74146866798,-15.9332294464 --2.81107401848,1.74247324467,-15.9466848373 --2.75001263618,1.73451888561,-15.8891525269 --2.70704746246,1.73850703239,-15.9316082001 --2.6872112751,1.75841867924,-16.1070480347 --2.63922572136,1.76041960716,-16.1275119781 --2.60129499435,1.76838767529,-16.2049617767 --2.56422543526,1.75943338871,-16.1361999512 --2.493090868,1.74252188206,-16.0036621094 --2.43906807899,1.73954474926,-15.9861316681 --2.37899565697,1.72959649563,-15.9175882339 --2.33704185486,1.73557853699,-15.9710454941 --2.27797985077,1.72762429714,-15.9135131836 --2.2370300293,1.73360383511,-15.9709625244 --2.20497846603,1.72663855553,-15.9211959839 --2.14187812805,1.71370661259,-15.8246593475 --2.08582854271,1.70774483681,-15.780125618 --2.04085040092,1.7107411623,-15.8085794449 --1.98278391361,1.7017891407,-15.747048378 --1.92773008347,1.69482958317,-15.6985082626 --1.89988875389,1.71474635601,-15.8659563065 --1.88295292854,1.72271382809,-15.9341878891 --1.83798122406,1.72670662403,-15.9686431885 --1.77284348011,1.7087957859,-15.835108757 --1.71879673004,1.70383238792,-15.7935724258 --1.68189585209,1.71578431129,-15.9000244141 --1.63894796371,1.72276353836,-15.958480835 --1.61395001411,1.72276723385,-15.9637184143 --1.56595575809,1.72377347946,-15.9751758575 --1.51089000702,1.71582078934,-15.9146347046 --1.48615050316,1.74768054485,-16.1830978394 --1.4381582737,1.74868571758,-16.1965522766 --1.39119505882,1.75367450714,-16.2390193939 --1.34523487091,1.75866150856,-16.2844791412 --1.32327008247,1.76264619827,-16.3227081299 --1.27529108524,1.76564407349,-16.3491687775 --1.22530007362,1.7666490078,-16.3636360168 --1.18138206005,1.7766122818,-16.4510993958 --1.13037633896,1.77662575245,-16.4505634308 --1.08342278004,1.78260934353,-16.5020256042 --1.03445184231,1.78560304642,-16.536491394 --1.01351058483,1.79257464409,-16.5977172852 --0.963523089886,1.7945779562,-16.6151809692 --0.913542687893,1.79757726192,-16.6396484375 --0.83755594492,1.79958546162,-16.6603469849 --0.786556303501,1.79959559441,-16.6658115387 --0.735555768013,1.79960644245,-16.6702747345 --0.710556685925,1.80061101913,-16.6735038757 --0.659559071064,1.80062007904,-16.6809692383 --0.608563661575,1.801628232,-16.6904354095 --0.557567298412,1.8026368618,-16.6989002228 --0.506570696831,1.80264544487,-16.7073669434 --0.455583482981,1.8046489954,-16.7248325348 --0.404583245516,1.80565977097,-16.7292976379 --0.37958920002,1.80666172504,-16.7375259399 --0.327593803406,1.80767023563,-16.7469978333 --0.27659240365,1.80768167973,-16.7504615784 --0.225592970848,1.80769205093,-16.7559261322 --0.173579365015,1.80671048164,-16.7473945618 --0.122583150864,1.80771934986,-16.7558574677 --0.0715676173568,1.80673873425,-16.7453193665 --0.0455775372684,1.80773878098,-16.7575588226 --0.00342117971741,1.80724549294,-15.9319734573 -0.0485810376704,1.80623245239,-15.9303417206 -0.0995866432786,1.80722117424,-15.9317045212 -0.150584831834,1.80620598793,-15.9260663986 -0.202592253685,1.80619573593,-15.92943573 -0.227604746819,1.80819559097,-15.9396114349 -0.279612153769,1.80818533897,-15.9429798126 -0.33060541749,1.80716741085,-15.9323425293 -0.381606847048,1.80715405941,-15.9297046661 -0.433604151011,1.80613839626,-15.9230766296 -0.484600454569,1.80512225628,-15.9154415131 -0.535601913929,1.80510890484,-15.9128046036 -0.561617314816,1.8071103096,-15.9259853363 -0.612621724606,1.8070987463,-15.9263477325 -0.664620101452,1.8060836792,-15.9207191467 -0.715628623962,1.8070744276,-15.9250793457 -0.766613006592,1.80505180359,-15.9054527283 -0.818628668785,1.80704629421,-15.9168167114 -0.868619859219,1.80502784252,-15.9041786194 -0.893601119518,1.80301070213,-15.8833665848 -0.946630656719,1.80601274967,-15.9087305069 -0.996624112129,1.8049955368,-15.8980922699 -1.04862785339,1.80598342419,-15.8974628448 -1.10165631771,1.80898487568,-15.9218254089 -1.15164589882,1.80796563625,-15.9071884155 -1.20466828346,1.80996382236,-15.9255552292 -1.23269355297,1.81297028065,-15.9487371445 -1.28774416447,1.81998336315,-15.995092392 -1.34581744671,1.82900857925,-16.064453125 -1.40389049053,1.83803355694,-16.133808136 -1.46297240257,1.84806323051,-16.2121620178 -1.52203929424,1.85608458519,-16.2755203247 -1.57908892632,1.86209714413,-16.3218765259 -1.60811507702,1.86610376835,-16.3460559845 -1.67020952702,1.87813961506,-16.4374046326 -1.72623431683,1.88113868237,-16.458770752 -1.77822041512,1.87911736965,-16.4411411285 -1.83727383614,1.88613140583,-16.4914970398 -1.88825428486,1.88410711288,-16.4678668976 -1.91929852962,1.88912367821,-16.5110378265 -1.97329974174,1.89011013508,-16.5084056854 -2.02629780769,1.89009523392,-16.5027713776 -2.08634805679,1.89710748196,-16.5501289368 -2.14337468147,1.90010738373,-16.5734920502 -2.1963737011,1.9000929594,-16.5688533783 -2.25641489029,1.90610027313,-16.6072158813 -2.2834148407,1.90609323978,-16.6053981781 -2.33641004562,1.9060767889,-16.5967655182 -2.39745688438,1.91208720207,-16.6411247253 -2.45246505737,1.91407740116,-16.6454868317 -2.50646281242,1.91406238079,-16.6398544312 -2.56348228455,1.91705858707,-16.6562175751 -2.6164765358,1.91704177856,-16.6465816498 -2.64548516273,1.91803920269,-16.6537666321 -2.70149683952,1.92003142834,-16.6621284485 -2.75750756264,1.92202305794,-16.6694927216 -2.81150698662,1.92300879955,-16.6648578644 -2.86751770973,1.92500042915,-16.6722202301 -2.92553305626,1.92699432373,-16.6845874786 -2.97953224182,1.92798018456,-16.6799526215 -3.01055335999,1.93098425865,-16.7001266479 -3.06957268715,1.9339799881,-16.7164955139 -3.12055850029,1.93295907974,-16.6978569031 -3.17354869843,1.93194043636,-16.6842269897 -3.2285490036,1.93292665482,-16.6805953979 -3.28153753281,1.93190705776,-16.6649684906 -3.3355345726,1.93289196491,-16.6583347321 -3.36253356934,1.93288469315,-16.6555175781 -3.41552329063,1.93286573887,-16.6408901215 -3.46951889992,1.93284976482,-16.6322574615 -3.52251052856,1.93283188343,-16.6196269989 -3.56947588921,1.92880105972,-16.5800018311 -3.62447547913,1.92978715897,-16.5753707886 -3.6774699688,1.9297709465,-16.5657348633 -3.69844222069,1.92675042152,-16.5349254608 -3.74942278862,1.92472696304,-16.5103054047 -3.79940414429,1.92370414734,-16.4866752625 -3.85038924217,1.9226834774,-16.467048645 -3.90036964417,1.92066037655,-16.4424209595 -3.95235681534,1.91964042187,-16.4247970581 -3.97634553909,1.918628335,-16.4109802246 -4.02732849121,1.91760623455,-16.3883571625 -4.07731151581,1.91658473015,-16.3667297363 -4.12930202484,1.91656661034,-16.3521003723 -4.1822977066,1.91655147076,-16.3434658051 -4.2342839241,1.91553139687,-16.3248462677 -4.28527259827,1.9155125618,-16.3082141876 -4.31227016449,1.91550457478,-16.3034000397 -4.36526489258,1.91648900509,-16.2937698364 -4.41725254059,1.91546964645,-16.2761478424 -4.46623516083,1.91444814205,-16.2535171509 -4.51922655106,1.9144307375,-16.2398929596 -4.56018161774,1.90939569473,-16.1872730255 -4.60715723038,1.90737092495,-16.1566505432 -4.63616132736,1.90836620331,-16.1588344574 -4.70320034027,1.91537213326,-16.1961936951 -4.77826595306,1.92539048195,-16.2615394592 -4.83125829697,1.92537367344,-16.2489128113 -4.87823200226,1.92334783077,-16.2162914276 -4.93323230743,1.92433536053,-16.2126579285 -4.96215295792,1.91528403759,-16.1220531464 -4.95203590393,1.89922165871,-15.9942836761 -4.98095846176,1.89017152786,-15.9056816101 -5.01389551163,1.88212883472,-15.833073616 -5.0568614006,1.8790999651,-15.7914581299 -5.09481477737,1.87406504154,-15.7358465195 -5.13778400421,1.87103772163,-15.6972284317 -5.16470623016,1.86098814011,-15.6076316833 -5.18569087982,1.85997486115,-15.5888195038 -5.22665643692,1.85694611073,-15.5462017059 -5.26561594009,1.85191440582,-15.4965896606 -5.29956245422,1.84587681293,-15.4329843521 -5.32448530197,1.83682799339,-15.3433885574 -5.36144304276,1.83179605007,-15.2917757034 -5.38944673538,1.83279156685,-15.2929611206 -5.42039012909,1.82675278187,-15.2253541946 -5.45734882355,1.82172143459,-15.1747436523 -5.50433158875,1.82070112228,-15.1501293182 -5.53928804398,1.81566882133,-15.0965175629 -5.57223844528,1.81063354015,-15.0359125137 -5.62223291397,1.81061911583,-15.0242853165 -5.63219213486,1.80559420586,-14.9764919281 -5.67316532135,1.80356991291,-14.9408740997 -5.70711946487,1.79853665829,-14.884270668 -5.75009918213,1.79651558399,-14.8556489944 -5.784055233,1.79148352146,-14.8010444641 -5.82402610779,1.78945827484,-14.7624340057 -5.86299562454,1.78643214703,-14.721824646 -5.87596654892,1.78241324425,-14.6870203018 -5.91293334961,1.77938616276,-14.6434087753 -5.94689273834,1.77535605431,-14.591802597 -5.98586416245,1.77233123779,-14.5531921387 -6.02984809875,1.77131283283,-14.5295696259 -6.06481075287,1.76728403568,-14.4809656143 -6.09777069092,1.76325428486,-14.429359436 -6.12176656723,1.76324677467,-14.4215497971 -6.15572977066,1.75921869278,-14.3739395142 -6.18468284607,1.7541860342,-14.3143367767 -6.2266626358,1.75216555595,-14.2847261429 -6.26262998581,1.74913930893,-14.2411203384 -6.29759836197,1.74611389637,-14.1985063553 -6.34759569168,1.74710118771,-14.1878871918 -6.35956716537,1.74408304691,-14.153090477 -6.38752222061,1.73905146122,-14.0944871902 -6.424492836,1.73602735996,-14.0548810959 -6.49643564224,1.73097980022,-13.9756603241 -6.54643392563,1.73196780682,-13.9660396576 -6.57839775085,1.72794055939,-13.9174365997 -6.58937072754,1.72492349148,-13.8836345673 -6.62434101105,1.7218991518,-13.8420295715 -6.65931224823,1.7198754549,-13.8014211655 -6.69929265976,1.71785593033,-13.7718076706 -6.73827028275,1.71683502197,-13.7382040024 -6.75921678543,1.70980083942,-13.6696090698 -6.7882232666,1.71179795265,-13.6727972031 -6.81618404388,1.70777010918,-13.6201915741 -6.85215759277,1.70474791527,-13.5825853348 -6.89614677429,1.70473229885,-13.5619697571 -6.94013690948,1.705717206,-13.5423498154 -6.97310686111,1.70269346237,-13.499745369 -7.02711343765,1.70568549633,-13.4991178513 -7.04509973526,1.7036741972,-13.4793214798 -7.08107566833,1.70165324211,-13.4437112808 -7.12606668472,1.7026386261,-13.4250946045 -7.16504764557,1.70161962509,-13.3944854736 -7.20302772522,1.70060038567,-13.3628749847 -7.25202465057,1.70158851147,-13.3512573242 -7.28099012375,1.69756305218,-13.3026561737 -7.31500530243,1.70156419277,-13.3158330917 -7.3559885025,1.70054650307,-13.2882270813 -7.40698957443,1.70253610611,-13.2806043625 -7.44396781921,1.70151650906,-13.2469968796 -7.47894382477,1.69949567318,-13.2103891373 -7.52894306183,1.70148491859,-13.2007684708 -7.57793998718,1.70247280598,-13.1881523132 -7.59693098068,1.70246374607,-13.1733446121 -7.64592838287,1.7034522295,-13.1617240906 -7.68090343475,1.70143139362,-13.1241226196 -7.72789859772,1.70341849327,-13.108505249 -7.77489280701,1.70440542698,-13.0928869247 -7.82188606262,1.70539224148,-13.0762748718 -7.84388065338,1.70538473129,-13.0654678345 -7.8938794136,1.70737361908,-13.0548477173 -7.92685317993,1.70535254478,-13.0152435303 -7.98286008835,1.70834493637,-13.0146160126 -8.02284431458,1.70832765102,-12.9860095978 -8.06983757019,1.70931470394,-12.9693946838 -8.10982131958,1.70929741859,-12.9407873154 -8.14683818817,1.7122989893,-12.9559602737 -8.18682193756,1.71228182316,-12.9273529053 -8.22680568695,1.71226525307,-12.8997411728 -8.27880477905,1.71425426006,-12.889128685 -8.32279586792,1.71524000168,-12.8685092926 -8.36678504944,1.71522510052,-12.8459005356 -8.41477870941,1.71721255779,-12.8302841187 -8.42976570129,1.71520209312,-12.8094797134 -8.48076438904,1.71819090843,-12.7978620529 -8.53276348114,1.72018051147,-12.7882413864 -8.58176040649,1.72216832638,-12.7736244202 -8.63175678253,1.72415661812,-12.7600078583 -8.67875003815,1.7251431942,-12.741396904 -8.7207365036,1.72512757778,-12.7157869339 -8.75074100494,1.72712433338,-12.7169704437 -8.80274009705,1.73011362553,-12.7063493729 -8.84672832489,1.73009872437,-12.6827411652 -8.8967256546,1.73208701611,-12.6691217422 -8.94071388245,1.73307228088,-12.6455125809 -8.99271297455,1.73506128788,-12.6338939667 -9.01170349121,1.7350525856,-12.6180896759 -9.07371520996,1.74004650116,-12.6214580536 -9.12170791626,1.74103331566,-12.6028470993 -9.16469478607,1.74201798439,-12.5772390366 -9.20568180084,1.74200248718,-12.5506238937 -9.26969337463,1.74699628353,-12.5539989471 -9.30667304993,1.74597847462,-12.5203933716 -9.33267211914,1.7469727993,-12.5135860443 -9.39167785645,1.75096476078,-12.5109586716 -9.43766975403,1.75195086002,-12.4893465042 -9.48466014862,1.75393676758,-12.4677391052 -9.54166316986,1.75692760944,-12.4611158371 -9.57063484192,1.75490665436,-12.4165182114 -9.63064193726,1.75889873505,-12.4138908386 -9.66865348816,1.76289784908,-12.4230690002 -9.74667739868,1.76989603043,-12.4414348602 -9.79667186737,1.77188336849,-12.4238204956 -9.84566497803,1.77387082577,-12.4061994553 -9.89565944672,1.77585780621,-12.387588501 -9.96066761017,1.78085052967,-12.3879642487 -10.0146665573,1.78383946419,-12.3753433228 -10.0476703644,1.78583574295,-12.3755331039 -10.1106777191,1.79082787037,-12.3739042282 -10.1576681137,1.79181396961,-12.3512926102 -10.1986532211,1.7927980423,-12.3216819763 -10.253651619,1.79578649998,-12.3080663681 -10.3006420135,1.79677271843,-12.2854537964 -10.3406248093,1.79675626755,-12.2538480759 -10.3415975571,1.7927416563,-12.2150611877 -10.3565568924,1.78871679306,-12.1534767151 -10.3665122986,1.78269052505,-12.0859003067 -10.026134491,1.71054983139,-11.6056060791 -10.0380945206,1.70552611351,-11.5440263748 -10.0630683899,1.70350718498,-11.4994277954 -10.0800333023,1.69948530197,-11.4438457489 -10.0609903336,1.69246566296,-11.3840789795 -10.0799598694,1.68944549561,-11.333483696 -10.1079359055,1.68742787838,-11.2918901443 -10.1209001541,1.68340551853,-11.2333097458 -10.1428718567,1.68038642406,-11.1857185364 -10.1628427505,1.67736697197,-11.1361293793 -10.1778326035,1.67735886574,-11.1173286438 -10.1887950897,1.67233681679,-11.0577478409 -10.2087659836,1.66931784153,-11.0091562271 -10.2317409515,1.66729974747,-10.9635639191 -10.2567157745,1.66528201103,-10.9199733734 -10.2606744766,1.65925908089,-10.8543958664 -10.2956600189,1.65924477577,-10.8227930069 -10.2956380844,1.65623283386,-10.7880067825 -10.3186120987,1.65421509743,-10.7424201965 -10.3335819244,1.65119612217,-10.690826416 -10.3545560837,1.648178339,-10.6442375183 -10.3705253601,1.64515900612,-10.5916576385 -10.3965044022,1.64314305782,-10.5510635376 -10.4084711075,1.63912332058,-10.4954833984 -10.4264650345,1.64011669159,-10.480679512 -10.4424352646,1.63609850407,-10.4300937653 -10.4564056396,1.63307976723,-10.3775091171 -10.481385231,1.63206410408,-10.3369121552 -10.4983568192,1.62904632092,-10.2873296738 -10.5103254318,1.62502777576,-10.2337446213 -10.5153093338,1.62301838398,-10.205953598 -10.5322828293,1.62000072002,-10.1563749313 -10.5472555161,1.6169834137,-10.1067848206 -10.5662307739,1.61496686935,-10.0601987839 -10.5741977692,1.61094808578,-10.003619194 -10.5851688385,1.6069303751,-9.9510307312 -10.6051445007,1.60491430759,-9.90544891357 -10.6121301651,1.60290586948,-9.88065433502 -10.6271038055,1.59988903999,-9.83107280731 -10.6610918045,1.60087656975,-9.80047035217 -10.6690607071,1.59685862064,-9.74489212036 -10.6860361099,1.59384274483,-9.69830417633 -10.701010704,1.59182667732,-9.64972019196 -10.7159852982,1.58881080151,-9.60213184357 -10.7109642029,1.58480024338,-9.56635093689 -10.7319431305,1.58378565311,-9.52376270294 -10.7579259872,1.58277225494,-9.48616790771 -10.7538881302,1.57675278187,-9.42060375214 -10.7748680115,1.57573866844,-9.37901210785 -10.7908449173,1.57272350788,-9.33242893219 -10.8118247986,1.57170963287,-9.29083919525 -10.8138093948,1.56970119476,-9.26304721832 -10.8257846832,1.56668567657,-9.21346569061 -10.8447637558,1.56467187405,-9.17087459564 -10.8717489243,1.56465911865,-9.13428401947 -10.8847236633,1.5616440773,-9.08570480347 -10.9057044983,1.55963051319,-9.04411888123 -10.9206838608,1.55761659145,-8.99952411652 -10.9236688614,1.55560839176,-8.97174263 -10.9436502457,1.5545951128,-8.93015384674 -10.938615799,1.54857814312,-8.86857891083 -10.9966211319,1.55357086658,-8.85796833038 -8.26790332794,1.11512315273,-6.55443668365 -8.28789806366,1.1141166687,-6.52784252167 -8.35090923309,1.11911189556,-6.51344013214 -8.3729057312,1.11910569668,-6.48784923553 -8.4189157486,1.12310326099,-6.48223304749 -8.4309053421,1.12209570408,-6.4486489296 -8.46290588379,1.12309098244,-6.43104934692 -8.48190021515,1.12308466434,-6.40345573425 -8.4938993454,1.12308180332,-6.39165687561 -8.52890205383,1.12607753277,-6.37605667114 -8.54689693451,1.12507116795,-6.34746551514 -8.57589626312,1.12606596947,-6.32687187195 -8.5968914032,1.12605988979,-6.3002820015 -8.62188911438,1.1270544529,-6.27668952942 -8.64288425446,1.12704849243,-6.25009918213 -8.66588878632,1.12904703617,-6.24629402161 -8.69088745117,1.13004159927,-6.22269964218 -8.71788597107,1.13103652,-6.20109939575 -8.7398815155,1.13103055954,-6.17451477051 -8.76988220215,1.13202595711,-6.15491294861 -8.78387355804,1.13101923466,-6.1233253479 -8.82287979126,1.13401556015,-6.10972070694 -8.83888053894,1.13501346111,-6.10091495514 -8.86888027191,1.13700854778,-6.08031988144 -8.88087177277,1.13600170612,-6.04673910141 -8.91887569427,1.13799798489,-6.03213453293 -8.93486881256,1.13799166679,-6.00154924393 -8.98087787628,1.14198851585,-5.99194145203 -8.98087024689,1.13998484612,-5.97214412689 -9.01087093353,1.14197993279,-5.95055532455 -9.03886985779,1.14297497272,-5.92796373367 -9.0678691864,1.14397013187,-5.90636730194 -9.08686447144,1.14396452904,-5.87876939774 -9.1258687973,1.14696073532,-5.86416196823 -9.15086746216,1.14795541763,-5.83857917786 -9.16486740112,1.14895296097,-5.8277759552 -9.18086051941,1.14794719219,-5.79718971252 -9.20885944366,1.14894223213,-5.77459383011 -9.20584392548,1.14593470097,-5.73102712631 -9.23484420776,1.14793014526,-5.70942640305 -9.29886054993,1.15392827988,-5.70980501175 -9.34286689758,1.15792477131,-5.69719600677 -11.1977014542,1.42606341839,-6.85210132599 -10.9545717239,1.38803493977,-6.64970397949 -10.7074432373,1.34900712967,-6.44730758667 -10.7524442673,1.35200119019,-6.42870330811 -10.815454483,1.35799658298,-6.42207670212 -10.8954715729,1.36699306965,-6.42444705963 -10.6753587723,1.33196949959,-6.24402856827 -10.7573852539,1.34197032452,-6.27019071579 -10.6913404465,1.3299574852,-6.18466329575 -10.5782756805,1.310942173,-6.07216453552 -10.685303688,1.322940588,-6.09151029587 -10.4251804352,1.28291714191,-5.89312076569 -10.3041143417,1.26290273666,-5.77863073349 -10.5151939392,1.29191088676,-5.88069009781 -10.6022148132,1.30190777779,-5.88606595993 -10.0379714966,1.2188706398,-5.51887512207 -9.95192337036,1.20485961437,-5.42835855484 -9.73182296753,1.17084252834,-5.26293373108 -9.81084251404,1.17984032631,-5.26730442047 -9.68978309631,1.15982890129,-5.1598110199 -9.68577671051,1.15782594681,-5.1380238533 -9.6427488327,1.14981842041,-5.07448196411 -9.57071018219,1.13780999184,-4.99595546722 -9.48766899109,1.12380135059,-4.91243314743 -9.45264530182,1.11679494381,-4.85488653183 -9.34859657288,1.09978616238,-4.76138019562 -9.43461894989,1.10878479481,-4.76974582672 -9.28756046295,1.08777725697,-4.67305803299 -9.64468193054,1.1347849369,-4.82324504852 -9.15849590302,1.06576454639,-4.53199291229 -9.13147926331,1.05975973606,-4.48242759705 -9.06144523621,1.04775381088,-4.40990591049 -9.01342201233,1.03974878788,-4.35035562515 -8.90037536621,1.0217423439,-4.25785636902 -8.87636375427,1.01774013042,-4.22808742523 -8.77632236481,1.00173461437,-4.14456558228 -8.78131771088,1.00073170662,-4.11298561096 -8.68828105927,0.985726773739,-4.03248071671 -8.64225959778,0.977723300457,-3.97692894936 -8.61524581909,0.972720205784,-3.93037319183 -8.54622077942,0.96271777153,-3.88062930107 -8.55621910095,0.961715698242,-3.8530421257 -8.32513904572,0.92871004343,-3.71061873436 -8.31913280487,0.925708174706,-3.6770336628 -8.35714149475,0.92970687151,-3.66244244576 -8.33113002777,0.92470484972,-3.61888122559 -8.26010417938,0.913702607155,-3.55534386635 -8.23009395599,0.908701658249,-3.52656817436 -8.25109672546,0.909700393677,-3.50498080254 -8.19807720184,0.900698721409,-3.44944906235 -8.15106010437,0.89269733429,-3.39888882637 -8.10304450989,0.88469606638,-3.34734225273 -8.0540266037,0.876695096493,-3.29579615593 -8.04902553558,0.87569463253,-3.27802038193 -8.06402778625,0.87569385767,-3.25542473793 -7.97099876404,0.861693203449,-3.18590497971 -7.96699619293,0.859692692757,-3.15433859825 -7.89297389984,0.848692595959,-3.09479546547 -7.86896657944,0.844692349434,-3.05524301529 -7.84795999527,0.839692294598,-3.01866745949 -7.85396099091,0.839692115784,-3.00588941574 -7.80894851685,0.83269238472,-2.95933508873 -7.8299536705,0.834692180157,-2.9397418499 -7.76093435287,0.823692917824,-2.8842010498 -7.73692846298,0.819693386555,-2.84663915634 -7.74092960358,0.818693637848,-2.8200647831 -7.72292566299,0.814694166183,-2.78549551964 -7.63890361786,0.803695678711,-2.73974728584 -7.59489297867,0.796696901321,-2.6952021122 -7.56288576126,0.790698111057,-2.65564894676 -7.5428814888,0.786699235439,-2.62108588219 -7.56988954544,0.789699435234,-2.60547542572 -7.56589031219,0.787700355053,-2.57690548897 -7.57289361954,0.787701129913,-2.55233097076 -7.44686365128,0.770704448223,-2.49360847473 -7.44086360931,0.768705666065,-2.46503806114 -7.45086812973,0.768706560135,-2.44245553017 -7.40185832977,0.760709106922,-2.39890909195 -7.40786218643,0.76071023941,-2.37532544136 -7.32584524155,0.749713897705,-2.32178401947 -7.31684494019,0.747714996338,-2.3050160408 -7.33985233307,0.749715685844,-2.28840923309 -7.36886167526,0.751716315746,-2.27281475067 -7.2598400116,0.736721515656,-2.21030950546 -7.2788476944,0.738722622395,-2.1917181015 -7.2618470192,0.735724925995,-2.16114926338 -7.27885389328,0.736726105213,-2.14156460762 -7.25084972382,0.732728123665,-2.11979627609 -7.21884632111,0.727731227875,-2.0852291584 -7.26585960388,0.732731342316,-2.07562065125 -7.23685693741,0.727734446526,-2.04205513 -7.23786115646,0.726736426353,-2.01748132706 -7.288875103,0.73273640871,-2.00886750221 -7.12284564972,0.710745751858,-1.93339598179 -7.09984302521,0.706747889519,-1.91461718082 -7.22487211227,0.721744537354,-1.9279640913 -7.10585308075,0.705752372742,-1.86845803261 -7.12786149979,0.707753717899,-1.85086846352 -7.09085941315,0.702757954597,-1.81631171703 -7.06485891342,0.698761701584,-1.78573822975 -7.12287378311,0.704761445522,-1.77813136578 -7.03986120224,0.693766891956,-1.7433848381 -7.02886390686,0.691770195961,-1.71681380272 -7.02686882019,0.690773010254,-1.69323027134 -7.01987266541,0.688776195049,-1.66766214371 -7.01587724686,0.687779247761,-1.6430901289 -7.01788282394,0.687782049179,-1.62050819397 -6.97287797928,0.681785941124,-1.5977345705 -7.0058889389,0.684787034988,-1.58313834667 -6.98589134216,0.681791245937,-1.55457830429 -6.99189710617,0.681793928146,-1.53299808502 -6.94889640808,0.675799548626,-1.49944317341 -6.9358997345,0.672803521156,-1.4738650322 -6.95090818405,0.673805832863,-1.45428681374 -6.92190647125,0.670809149742,-1.43650400639 -6.93691444397,0.671811401844,-1.41790807247 -6.90791654587,0.666816592216,-1.38834953308 -6.86191606522,0.660823106766,-1.35480606556 -6.86892318726,0.660826027393,-1.33422088623 -6.82792377472,0.654832303524,-1.30266749859 -6.85193347931,0.657834112644,-1.2860699892 -6.8799405098,0.660833954811,-1.28126132488 -6.80893754959,0.651842474937,-1.24372327328 -6.86395168304,0.657842278481,-1.23311805725 -6.85295677185,0.655846714973,-1.208548069 -6.79495620728,0.647854566574,-1.17499411106 -6.79396247864,0.646858453751,-1.15242576599 -6.79797029495,0.64686191082,-1.13183605671 -6.79597377777,0.646863877773,-1.12103784084 -6.78297901154,0.644868791103,-1.09647107124 -6.79098749161,0.644872128963,-1.07589530945 -6.78499364853,0.643876433372,-1.05331456661 -6.76399850845,0.640882074833,-1.02774786949 -6.75800514221,0.639886558056,-1.00517058372 -6.74600744247,0.637889504433,-0.992385208607 -6.7770190239,0.640891194344,-0.975799977779 -6.80102872849,0.643893122673,-0.959191739559 -6.77703380585,0.639899253845,-0.933624207973 -6.7870426178,0.64090269804,-0.913053691387 -6.763048172,0.637908875942,-0.887490451336 -6.72705173492,0.632916033268,-0.86091953516 -6.72105503082,0.631918728352,-0.84913700819 -6.76506757736,0.636919260025,-0.834537148476 -6.78407764435,0.638921916485,-0.815949678421 -6.74608135223,0.633929491043,-0.789381802082 -6.70208501816,0.627937793732,-0.761824667454 -6.7190952301,0.629940629005,-0.743234276772 -6.70910215378,0.627946019173,-0.720661580563 -6.72410821915,0.629946947098,-0.711869835854 -6.7131152153,0.627952516079,-0.68929618597 -6.749127388,0.631953775883,-0.672702312469 -6.81314086914,0.639952242374,-0.660081148148 -6.75514411926,0.631962239742,-0.631532847881 -6.71214914322,0.625970959663,-0.604980528355 -6.73315954208,0.628973603249,-0.586391329765 -6.76516675949,0.632972836494,-0.579584717751 -6.71117115021,0.624982774258,-0.552040338516 -6.71117973328,0.62498742342,-0.531453669071 -6.72318935394,0.625991046429,-0.511866688728 -6.79520368576,0.634988665581,-0.498251736164 -6.72620725632,0.626000463963,-0.469717472792 -6.70721006393,0.624004602432,-0.457926362753 -6.69521856308,0.622010827065,-0.435364305973 -6.7112288475,0.624013900757,-0.416761636734 -6.73323917389,0.626016736031,-0.397184759378 -6.79425191879,0.634015321732,-0.381572455168 -6.78226041794,0.63202136755,-0.359989374876 -6.78226995468,0.632026433945,-0.338420450687 -6.72627067566,0.625034749508,-0.323657006025 -6.71727991104,0.623040795326,-0.30208337307 -6.69528770447,0.620048224926,-0.279518723488 -6.68729686737,0.61905425787,-0.257949143648 -6.68230581284,0.618059813976,-0.237363353372 -6.68031549454,0.618065178394,-0.216780409217 -6.68432044983,0.618067264557,-0.206982880831 -6.68032979965,0.618073046207,-0.185418814421 -6.68333959579,0.618077993393,-0.164839819074 -6.6783490181,0.617083728313,-0.144256383181 -6.66735839844,0.616090297699,-0.122690685093 -6.67636823654,0.617094516754,-0.103094756603 -6.66237783432,0.615101456642,-0.0815299376845 -6.66638278961,0.615103602409,-0.0717317610979 -6.66939258575,0.615108728409,-0.0511533729732 -6.78540706635,0.630100727081,-0.0345160961151 -6.73441505432,0.623112022877,-0.0119632622227 -6.69742393494,0.619121670723,0.00960259512067 -6.66243267059,0.614131271839,0.0311634782702 -6.66044330597,0.61413705349,0.0517420172691 -6.6554479599,0.613140523434,0.0625206530094 -6.63545799255,0.611148357391,0.0830959305167 -6.65146875381,0.613152146339,0.103675991297 -6.64247894287,0.61215877533,0.124251291156 -6.64048910141,0.611164689064,0.144827514887 -6.61849975586,0.609173059464,0.165396004915 -6.63250494003,0.610174059868,0.175199612975 -6.6425151825,0.612178564072,0.195781126618 -6.65652608871,0.613182663918,0.216365650296 -6.63653659821,0.611190855503,0.236931473017 -6.65654754639,0.613194167614,0.257521510124 -6.63855838776,0.61120223999,0.278086274862 -6.74356985092,0.624194741249,0.299726814032 -6.71157455444,0.620201647282,0.309502005577 -6.68758535385,0.617210626602,0.330062121153 -6.75459623337,0.62520802021,0.352665871382 -6.94260787964,0.649189710617,0.378341168165 -6.6936173439,0.618227362633,0.39180880785 -6.68162870407,0.617234945297,0.412375897169 -6.65463972092,0.61424434185,0.431943535805 -6.6266450882,0.61025083065,0.440728187561 -6.67765617371,0.616250157356,0.463330507278 -6.62966680527,0.611262440681,0.481885820627 -6.64867830276,0.61326611042,0.503469586372 -6.62768983841,0.611274957657,0.523037075996 -6.61270093918,0.609283030033,0.542611122131 -6.62571239471,0.611287534237,0.564188361168 -6.6827173233,0.618283033371,0.57800000906 -6.64172887802,0.613294541836,0.595571517944 -6.61674022675,0.610303938389,0.614146232605 -6.60275220871,0.60831207037,0.633717894554 -6.62176370621,0.611315906048,0.656290113926 -6.5667757988,0.604329407215,0.671861290932 -6.57978200912,0.606330931187,0.683644175529 -6.59179353714,0.608335673809,0.70522415638 -6.5748052597,0.606344163418,0.723805069923 -6.57081699371,0.605351209641,0.744371771812 -6.54982852936,0.603360235691,0.761961102486 -6.53984117508,0.602367997169,0.781532764435 -6.52585315704,0.601376593113,0.801094055176 -6.52485942841,0.601379871368,0.810888469219 -6.51887130737,0.60038715601,0.83046734333 -6.55288267136,0.605388760567,0.854065954685 -6.50889587402,0.599401772022,0.870608627796 -6.49890804291,0.598409473896,0.889195919037 -6.48692083359,0.597417652607,0.907776892185 -6.50693225861,0.600421369076,0.930364429951 -6.50193834305,0.599425494671,0.940147340298 -6.48295164108,0.597434937954,0.958707034588 -6.49096298218,0.599440217018,0.979303777218 -6.47697591782,0.597448885441,0.997875928879 -6.47998809814,0.598455071449,1.01845836639 -6.50299978256,0.601458489895,1.04204332829 -6.48600625992,0.599464297295,1.04982793331 -6.46501970291,0.597474098206,1.06739580631 -6.51003026962,0.603474259377,1.09399592876 -6.48504447937,0.600484907627,1.11154973507 -6.43705892563,0.595498561859,1.12412369251 -6.49306821823,0.602496981621,1.15272939205 -6.42308568954,0.594514548779,1.16326093674 -6.45308971405,0.597513437271,1.17806327343 -6.55009746552,0.610505700111,1.21368789673 -6.3881187439,0.590536952019,1.20819604397 -6.37713193893,0.589545309544,1.22578704357 -6.3851442337,0.59155100584,1.24736905098 -6.43315458298,0.597550690174,1.27596628666 -6.43116760254,0.597558140755,1.29653418064 -6.42617416382,0.597562193871,1.30533277988 -6.41818809509,0.596570611,1.32489669323 -6.40520143509,0.595579445362,1.34247994423 -6.41721391678,0.597584605217,1.36506545544 -6.44222545624,0.601587891579,1.39064764977 -6.41724014282,0.598598718643,1.40621995926 -6.46025037766,0.604599416256,1.43580448627 -6.42525911331,0.600608170033,1.43859219551 -6.40227365494,0.597618699074,1.4541695118 -6.39428758621,0.597627282143,1.47373199463 -6.40530014038,0.599632680416,1.49632060528 -6.38731431961,0.597642540932,1.51289701462 -6.37032938004,0.595652639866,1.53045630455 -6.36733627319,0.595656812191,1.54024136066 -6.38334846497,0.59866130352,1.56383645535 -6.40735960007,0.601664602757,1.58943295479 -6.41137266159,0.602671146393,1.61101484299 -6.38938808441,0.600681900978,1.62658858299 -6.39440107346,0.601688563824,1.6491560936 -6.40341377258,0.603694319725,1.6717454195 -6.39442157745,0.602699577808,1.68052136898 -6.39443492889,0.6037068367,1.70110559464 -6.47044229507,0.613701939583,1.74071133137 -6.45545721054,0.612711668015,1.75828182697 -6.36247873306,0.601734101772,1.75582933426 -6.38449048996,0.60473793745,1.78241431713 -6.39849567413,0.606739282608,1.79621458054 -6.40350914001,0.607745945454,1.818790555 -6.37652540207,0.605757653713,1.83236765862 -6.40053653717,0.608761250973,1.8599524498 -6.38355255127,0.607771456242,1.87652480602 -6.37456655502,0.606780409813,1.89510214329 -6.38057994843,0.608786821365,1.9176876545 -6.38958692551,0.609789311886,1.93146681786 -6.37960147858,0.609798550606,1.95003926754 -6.37261581421,0.609807014465,1.96862864494 -6.35163211823,0.607818186283,1.984192729 -6.3516459465,0.607825517654,2.00478410721 -6.36265897751,0.610831320286,2.02936601639 -6.36267328262,0.610839009285,2.05094027519 -6.37167930603,0.612841427326,2.06472539902 -6.3596944809,0.611850976944,2.08230423927 -6.38970565796,0.616853535175,2.11289548874 -6.43071508408,0.622854411602,2.14748430252 -6.35273742676,0.613875031471,2.14404821396 -6.3427529335,0.612884402275,2.16261959076 -6.31576967239,0.609896659851,2.1751947403 -6.31277751923,0.60990101099,2.18498277664 -6.32279109955,0.612907290459,2.21055006981 -6.34880208969,0.616910457611,2.24014949799 -6.33281850815,0.615921020508,2.25671935081 -9.45746612549,1.0203909874,3.33344888687 -9.47047519684,1.02339553833,3.37102437019 -9.4694814682,1.02439892292,3.38681554794 -9.48349094391,1.02740323544,3.42439818382 -6.31388568878,0.616959273815,2.34782481194 -6.2959022522,0.615970253944,2.36339640617 -6.29991674423,0.616977572441,2.38697099686 -6.3009314537,0.61798542738,2.40954446793 -6.29394626617,0.617994248867,2.42813706398 -6.3069524765,0.619996249676,2.44491124153 -6.32196521759,0.62300157547,2.4724957943 -6.41096925735,0.63599395752,2.52810001373 -6.31699514389,0.624018192291,2.51465845108 -6.35000562668,0.630020260811,2.54925251007 -6.58898973465,0.661986351013,2.66390156746 -6.37203216553,0.635032236576,2.60242271423 -6.41203451157,0.640029489994,2.63020825386 -6.33405923843,0.631051003933,2.62177228928 -6.31707715988,0.63006234169,2.63833212852 -6.31509160995,0.631070613861,2.65991401672 -6.33310413361,0.634075403214,2.68950414658 -6.32012081146,0.633085846901,2.70707631111 -6.33212661743,0.635087549686,2.7228782177 -6.35013914108,0.639092504978,2.75345730782 -6.34215497971,0.639102041721,2.77303433418 -6.40816068649,0.649098277092,2.82363629341 -6.3381857872,0.641118943691,2.81719398499 -6.3621969223,0.645122766495,2.85077619553 -6.33921575546,0.64313519001,2.86434316635 -6.35522031784,0.646136164665,2.88215112686 -6.34323787689,0.645146608353,2.90071702003 -6.30925703049,0.642160654068,2.90829920769 -6.44125318527,0.661145269871,2.99090743065 -6.40727329254,0.657159566879,2.99947595596 -6.39329099655,0.65717035532,3.0170481205 -6.33430671692,0.64918500185,3.0018248558 -6.32732343674,0.650194585323,3.02239847183 -6.31633996964,0.649204850197,3.04097366333 -6.31935548782,0.65121281147,3.06654453278 -6.33236885071,0.654218554497,3.09613204002 -6.31038713455,0.652230978012,3.10970211029 -6.29940462112,0.652241289616,3.12827849388 -6.31240987778,0.655242919922,3.14607810974 -6.33342218399,0.659247517586,3.18065524101 -6.39042901993,0.668245315552,3.23225617409 -6.31645488739,0.659267067909,3.21982216835 -6.32746934891,0.66227376461,3.25038862228 -6.40547227859,0.674267530441,3.31300091743 -6.31050252914,0.662293314934,3.2895591259 -6.33550596237,0.666292905807,3.31435585022 -6.31152582169,0.66430580616,3.32692408562 -6.29754400253,0.664316892624,3.34449577332 -6.34055233002,0.671317279339,3.39108991623 -6.34056854248,0.673325955868,3.4166560173 -6.42156982422,0.685319125652,3.48327088356 -6.47457695007,0.694317758083,3.536860466 -6.28661680222,0.669357299805,3.45058512688 -6.31162786484,0.67436093092,3.48818206787 -6.30264472961,0.674371182919,3.50875282288 -6.30266046524,0.675379514694,3.5333404541 -6.41765737534,0.693366706371,3.6219432354 -6.27269744873,0.674402296543,3.56748747826 -6.27770423889,0.675405740738,3.58327150345 -6.27372074127,0.676414906979,3.60585784912 -6.29573249817,0.681419312954,3.64344549179 -6.30674695969,0.68442606926,3.67601466179 -6.28776597977,0.683438181877,3.6905939579 -6.2777838707,0.683448851109,3.71116065979 -6.30079555511,0.688452959061,3.74975371361 -6.2968044281,0.68845808506,3.76054000854 -6.24482917786,0.683476567268,3.75610613823 -6.25084447861,0.685484111309,3.78568410873 -6.24086236954,0.685494542122,3.80526828766 -6.25487565994,0.689500629902,3.83984851837 -6.25189256668,0.690509915352,3.86442422867 -6.25190925598,0.692518770695,3.89099907875 -6.24791717529,0.692523539066,3.9008026123 -6.27292919159,0.697527766228,3.94337487221 -6.26594686508,0.698537945747,3.96594834328 -6.26796245575,0.700546145439,3.99353408813 -6.2689781189,0.702554762363,4.02111148834 -6.23300170898,0.699570477009,4.02567720413 -6.23401737213,0.701579093933,4.05325555801 -6.28201627731,0.708574235439,4.09706068039 -6.22604370117,0.70259386301,4.08862304688 -6.21506118774,0.702604651451,4.10820674896 -6.20408010483,0.70361572504,4.12877511978 -6.20509576797,0.70462423563,4.15635919571 -6.24210548401,0.712625920773,4.2079501152 -6.20112133026,0.707638323307,4.19472885132 -6.22113466263,0.712643563747,4.23630189896 -6.22514915466,0.714651346207,4.26589441299 -6.20516967773,0.71366417408,4.28046607971 -6.2081861496,0.7156727314,4.31103610992 -6.22319936752,0.720678508282,4.34862947464 -6.23320579529,0.722680985928,4.36942386627 -6.29321098328,0.733678519726,4.44000530243 -6.19824552536,0.721705853939,4.40256357193 -6.1832652092,0.721717596054,4.42014455795 -6.20227861404,0.725723087788,4.46271753311 -6.20329427719,0.728731572628,4.49130916595 -6.2932934761,0.743723273277,4.58490180969 -6.35328960419,0.753716111183,4.64270353317 -6.18334007263,0.730758011341,4.5492515564 -6.17535829544,0.731768667698,4.57282447815 -6.18737316132,0.735775589943,4.61139726639 -6.17639160156,0.735786557198,4.63198328018 -6.15741205215,0.734799385071,4.64755487442 -6.17542552948,0.739804804325,4.69014263153 -6.23642158508,0.750797510147,4.75094127655 -6.16745281219,0.742820203304,4.72949934006 -6.17746686935,0.745827078819,4.76609277725 -6.18948125839,0.74983394146,4.80566978455 -6.23348903656,0.758834302425,4.86926460266 -6.22550773621,0.760845243931,4.89482688904 -6.33150243759,0.778833389282,5.00743818283 -6.18354129791,0.756866872311,4.90720081329 -6.17156076431,0.757878482342,4.92877483368 -6.18857526779,0.762884676456,4.97434043884 -6.18859148026,0.764893651009,5.00492620468 -6.17561149597,0.765905320644,5.02550649643 -6.17362928391,0.767915129662,5.05607414246 -6.16563892365,0.767921209335,5.06486845016 -6.17865276337,0.771927654743,5.10645723343 -6.1766705513,0.773937404156,5.1370306015 -6.16568994522,0.774948656559,5.15961074829 -6.17870426178,0.779955565929,5.20318317413 -6.17172288895,0.780966281891,5.22975873947 -6.18773698807,0.785972237587,5.27534484863 -6.18274641037,0.786977767944,5.28713750839 -6.16576719284,0.786990463734,5.30570983887 -6.16778421402,0.789999425411,5.34028863907 -6.19979381561,0.798002302647,5.4008731842 -6.33178281784,0.821985423565,5.54847812653 -6.2328209877,0.808014214039,5.4960436821 -6.15985441208,0.799038231373,5.46660137177 -6.19785499573,0.807035505772,5.517390728 -6.19787168503,0.810044467449,5.54998731613 -6.18889188766,0.811055958271,5.57754802704 -6.38686418533,0.846025586128,5.78817892075 -6.18292760849,0.816075801849,5.6407084465 -6.18294477463,0.819085121155,5.67528915405 -6.17995405197,0.820090413094,5.690076828 -6.17897129059,0.822099864483,5.72366142273 -6.16099357605,0.822113096714,5.74322509766 -6.15501213074,0.824123740196,5.77280521393 -6.21901464462,0.838120222092,5.8674030304 -6.15904569626,0.831141531467,5.84697198868 -6.15906333923,0.834151208401,5.88354349136 -6.22105789185,0.84614354372,5.96034431458 -6.17708539963,0.84116178751,5.95491600037 -6.16810560226,0.843173205853,5.9834856987 -6.15112638474,0.843185901642,6.00306940079 -6.17613792419,0.851190209389,6.06365919113 -6.17815494537,0.854199409485,6.10323429108 -6.25815439224,0.871192932129,6.21982336044 -6.16118621826,0.856217324734,6.14358997345 -6.17220020294,0.861224353313,6.19118261337 -6.1622209549,0.863236248493,6.22074270248 -6.14524173737,0.863248825073,6.24033546448 -6.1482591629,0.867257833481,6.28191280365 -6.13528060913,0.869270324707,6.30847597122 -6.17727899551,0.878266513348,6.37027788162 -6.19629192352,0.884272217751,6.42886161804 -6.17531490326,0.884285986423,6.4464392662 -6.15233755112,0.884300172329,6.46201610565 -6.190346241,0.894302129745,6.54160165787 -6.15137386322,0.891319870949,6.54215908051 -6.34934425354,0.930289447308,6.79178142548 -6.17039585114,0.899330377579,6.62253475189 -6.18241119385,0.905337572098,6.67611694336 -6.18842744827,0.910345971584,6.72369813919 -6.13945674896,0.905365526676,6.71226644516 -6.13647508621,0.908375680447,6.74985122681 -6.15148973465,0.915382444859,6.80842876434 -6.13450288773,0.914390802383,6.81121015549 -6.13951921463,0.918399453163,6.85879182816 -6.15853261948,0.926405310631,6.92237472534 -6.17854547501,0.933410763741,6.98696470261 -6.19555997849,0.941417276859,7.05053710938 -6.13959121704,0.934438407421,7.03110218048 -7.92116928101,1.27008605003,9.10905265808 -7.90218257904,1.26909470558,9.11583614349 -7.88520431519,1.27210783958,9.15340900421 -7.86722564697,1.27412116528,9.18998146057 -7.84024953842,1.27413630486,9.21555709839 -7.81127405167,1.27415204048,9.2401227951 -7.79429531097,1.27616512775,9.27769947052 -7.7663192749,1.27618062496,9.30326652527 -7.76632785797,1.27918541431,9.33205890656 -7.74735021591,1.28119897842,9.36763572693 -7.71437597275,1.28021550179,9.38720321655 -7.69639778137,1.28222894669,9.42477607727 -7.66342353821,1.28224551678,9.44434547424 -7.64244651794,1.28325951099,9.47792053223 -7.61946964264,1.28527402878,9.50949478149 -7.62147808075,1.28827881813,9.54327487946 -7.49552726746,1.26931416988,9.44582939148 -3.47256159782,0.481139779091,4.43180036545 -3.45558547974,0.480153292418,4.43837451935 -3.43660974503,0.479167044163,4.44195461273 -3.42063379288,0.479180276394,4.44953155518 -3.40764641762,0.477187722921,4.44632720947 -7.34766244888,1.27239859104,9.59047889709 -7.33368396759,1.27541124821,9.63305950165 -7.29471158981,1.27342915535,9.64462471008 -7.31572389603,1.28443467617,9.73420906067 -7.21576786041,1.26946508884,9.66376876831 -7.16279983521,1.26548600197,9.65632915497 -7.15481042862,1.26649260521,9.67711448669 -7.12083673477,1.26550936699,9.69269561768 -7.04787397385,1.25653409958,9.65625953674 -7.03289604187,1.26054728031,9.69883346558 -6.95493459702,1.25057327747,9.65539073944 -6.91896247864,1.24859046936,9.66796588898 -6.87098312378,1.24160516262,9.63175296783 -6.83001279831,1.23962366581,9.63831806183 -6.76104927063,1.23164784908,9.60488033295 -6.74207210541,1.23366165161,9.64045906067 -6.67610836029,1.22668528557,9.61002349854 -6.61914157867,1.2207069397,9.59159183502 -6.56117486954,1.21472883224,9.57116031647 -6.53719091415,1.21273863316,9.56794643402 -6.48122358322,1.20676004887,9.54852199554 -6.47924280167,1.21277058125,9.61009502411 -6.43127393723,1.2087906599,9.60366249084 -6.35531282425,1.19881618023,9.55423069 -6.31134271622,1.19583511353,9.55180454254 -6.28636837006,1.19685053825,9.57937335968 -6.23938989639,1.18886494637,9.53916168213 -6.19842004776,1.18688356876,9.54172897339 -6.14745187759,1.18190395832,9.52730369568 -6.10148286819,1.17892348766,9.52087497711 -6.05751419067,1.17494273186,9.51843833923 -6.03253936768,1.17595803738,9.5440158844 -6.01856231689,1.17997097969,9.58759212494 -5.99057912827,1.17698180676,9.57637500763 -5.96760416031,1.17899668217,9.60495471954 -5.94262981415,1.18001186848,9.63152885437 -5.95764398575,1.19001889229,9.72211456299 -5.98265695572,1.20302426815,9.83268642426 -5.94268655777,1.20104265213,9.83526229858 -5.98468446732,1.21503937244,9.94005203247 -5.97170686722,1.21905183792,9.9866399765 -5.96272850037,1.22406411171,10.0432109833 -5.99173974991,1.23906850815,10.1637926102 -5.96976470947,1.24108326435,10.1993646622 -5.989777565,1.25408923626,10.3049554825 -5.96880292892,1.25710391998,10.3435258865 -6.00080347061,1.26810252666,10.4353246689 -6.01081943512,1.27911055088,10.5279064178 -5.98684501648,1.28112578392,10.5614833832 -6.00186061859,1.29313325882,10.667052269 -6.09085512161,1.32412552834,10.9036445618 -6.03988790512,1.32014608383,10.8912200928 -6.06789922714,1.3351508379,11.0227985382 -6.04891395569,1.3351598978,11.0285873413 -6.03693628311,1.34117257595,11.0881643295 -6.22990226746,1.40014386177,11.5277662277 -6.10595560074,1.37717926502,11.3823318481 -6.03199577332,1.36720454693,11.3289003372 -6.00302267075,1.36822104454,11.3604707718 -6.01102972031,1.37522447109,11.418261528 -5.97106027603,1.3742429018,11.4278383255 -5.93808889389,1.37525999546,11.4514122009 -5.95910215378,1.39026606083,11.578997612 -5.91813278198,1.38928472996,11.5885667801 -5.89115953445,1.39130055904,11.6241455078 -5.86118745804,1.39331710339,11.6547212601 -5.84720134735,1.39432501793,11.6725063324 -5.81422948837,1.3953422308,11.6980781555 -5.78225803375,1.39635920525,11.7246551514 -3.7338719368,0.841792404652,7.69361829758 -3.69990158081,0.838809609413,7.68419599533 -3.72791433334,0.853814423084,7.80477237701 -3.56596970558,0.811852157116,7.49654817581 -3.59098267555,0.824857354164,7.6091337204 -3.10044622421,0.791120648384,7.5133972168 -3.04048371315,0.779143035412,7.43397188187 -3.07448387146,0.794141173363,7.5487742424 -2.71785306931,0.776346445084,7.52831411362 -2.66990852356,0.776376724243,7.54247140884 -2.64193749428,0.774392843246,7.53904390335 -2.61199736595,0.785424470901,7.64200258255 -2.57102966309,0.779442846775,7.59858560562 -2.5540561676,0.782456874847,7.6291513443 -2.53108334541,0.782471656799,7.63873529434 -2.51210927963,0.784485578537,7.65932512283 -2.50213360786,0.789498209953,7.71189498901 -2.47315216064,0.783509016037,7.6626868248 -2.44618058205,0.781524598598,7.66026878357 -2.41123270988,0.787552237511,7.71642875671 -2.39325833321,0.789566099644,7.74301147461 -2.3812828064,0.794578790665,7.78959465027 -2.13102769852,1.13696122169,10.7071475983 -2.10905575752,1.14497601986,10.7757225037 -2.16106176376,1.20097672939,11.2322969437 -2.52999424934,1.49892771244,13.630443573 -2.47503137589,1.48994863033,13.5670289993 -2.46205663681,1.51096177101,13.7446022034 -2.45007061958,1.51796936989,13.8013935089 -2.3771135807,1.49699366093,13.6379728317 -2.33714652061,1.49901175499,13.6605539322 -2.2841835022,1.49103224277,13.607134819 -2.25221395493,1.49904870987,13.6767187119 -2.21024775505,1.50006735325,13.6912965775 -2.16928100586,1.50108540058,13.7068815231 -2.15229701996,1.50509393215,13.7416677475 -2.11133003235,1.50711214542,13.7612504959 -2.07236289978,1.5101300478,13.7968292236 -2.03839445114,1.51814687252,13.8664102554 -2.01442313194,1.53516197205,14.0119867325 -2.00344753265,1.56517446041,14.2535676956 -1.99347174168,1.59718692303,14.5171442032 -1.9674898386,1.5931968689,14.4919404984 -1.9495164156,1.61921072006,14.7065210342 -1.90954995155,1.62622880936,14.7650966644 -1.86458456516,1.62724769115,14.7786808014 -1.81761980057,1.62626683712,14.778263092 -1.7736543417,1.62828552723,14.8048429489 -1.75567030907,1.63429415226,14.8526334763 -1.73469781876,1.66230845451,15.0812149048 -1.69872999191,1.67432558537,15.1887960434 -1.64876639843,1.67234539986,15.1753749847 -1.60180163383,1.67236447334,15.1819610596 -1.55383729935,1.67238378525,15.1845407486 -1.49987483025,1.66440415382,15.1241235733 -1.47589278221,1.66441392899,15.1259126663 -1.42692875862,1.66243338585,15.1144952774 -1.37896466255,1.66245269775,15.1150741577 -1.33299934864,1.6624712944,15.1246652603 -1.28503525257,1.66249060631,15.1242465973 -1.23707091808,1.66150963306,15.1198301315 -1.21308898926,1.66151940823,15.1236181259 -1.16412508488,1.65953874588,15.1072006226 -1.1151611805,1.6565580368,15.0887842178 -1.06819653511,1.65657699108,15.0933685303 -1.02023255825,1.65659618378,15.0939474106 -0.973267734051,1.65661489964,15.0945358276 -0.926303207874,1.65663385391,15.1031188965 -0.901321709156,1.65564370155,15.0909061432 -0.854357004166,1.65566241741,15.0914936066 -0.807392477989,1.65668118,15.1010770798 -0.75942838192,1.65570032597,15.0956583023 -0.711464464664,1.65571939945,15.097237587 -0.664499938488,1.65573811531,15.1028232574 -0.617535233498,1.65575683117,15.1044111252 -0.592553734779,1.65376651287,15.0871973038 -0.546588599682,1.65578496456,15.1047887802 -0.498624533415,1.65380382538,15.0943717957 -0.450660586357,1.65382277966,15.0909509659 -0.403696030378,1.65484130383,15.0985374451 -0.355732023716,1.65286028385,15.0871191025 -0.308767408133,1.65387880802,15.0917062759 -0.284785419703,1.65288817883,15.0854969025 -0.237820833921,1.65290665627,15.0860843658 -0.189856916666,1.6519254446,15.0806655884 -0.142892330885,1.65194392204,15.0822534561 -0.0959276929498,1.65096247196,15.0748414993 -0.0479638427496,1.65098118782,15.0724201202 -0.0249811597168,1.649990201,15.0602197647 --0.0179860908538,1.64700710773,14.4318351746 --0.0629513636231,1.6490252018,14.451423645 --0.0859335809946,1.64803433418,14.4412136078 --0.130898833275,1.64805233479,14.4418020248 --0.176863312721,1.64807069302,14.4433822632 --0.221828445792,1.64608860016,14.4239683151 --0.266793757677,1.6481064558,14.4365596771 --0.311758965254,1.64712429047,14.430147171 --0.356724053621,1.64514219761,14.414732933 --0.379706263542,1.64515137672,14.4135227203 --0.424671500921,1.64516913891,14.4121112823 --0.469636559486,1.64418709278,14.4006967545 --0.515601098537,1.64520514011,14.4062786102 --0.5605661273,1.64422309399,14.3918628693 --0.605531334877,1.64424085617,14.3894519806 --0.628513634205,1.64424979687,14.3942432404 --0.673478782177,1.64426755905,14.3878297806 --0.71944385767,1.64728534222,14.4114217758 --0.76540851593,1.64830327034,14.4190063477 --0.811373174191,1.64932119846,14.4215898514 --0.856338381767,1.64933884144,14.4161777496 --0.901303529739,1.64835643768,14.4077653885 --0.924286007881,1.6493653059,14.41355896 --0.962253272533,1.6353815794,14.303147316 --1.01421618462,1.64840042591,14.3967323303 --1.06118071079,1.65141844749,14.4153184891 --1.10414636135,1.64743554592,14.379904747 --1.14911162853,1.64745295048,14.3754930496 --1.19607639313,1.65047073364,14.3990850449 --1.22105789185,1.65348005295,14.4168729782 --1.26702308655,1.65449750423,14.4264650345 --1.31298780441,1.65551507473,14.4260501862 --1.3589527607,1.65653264523,14.4296398163 --1.40491783619,1.6575499773,14.4362316132 --1.45188236237,1.65956771374,14.4468183517 --1.47586464882,1.66157662868,14.4586143494 --1.52282893658,1.66259431839,14.4591932297 --1.57079327106,1.66561210155,14.4777822495 --1.61575877666,1.66562914848,14.4743776321 --1.66272354126,1.66764676571,14.482966423 --1.70868837833,1.66766405106,14.4785528183 --1.7566524744,1.66968178749,14.4881353378 --1.77963519096,1.67069029808,14.49193573 --1.82659995556,1.67270767689,14.4995260239 --1.87356436253,1.67372512817,14.4991092682 --1.92052936554,1.67474246025,14.5067024231 --1.96749413013,1.67675971985,14.5112924576 --2.01245927811,1.67577672005,14.4988803864 --2.06042385101,1.67779433727,14.5074672699 --2.09240365028,1.68680429459,14.5692634583 --2.13836860657,1.68682134151,14.5618505478 --2.18233442307,1.68483793736,14.5454435349 --2.23029875755,1.68685531616,14.550028801 --2.27826356888,1.68887245655,14.5616254807 --2.32622790337,1.69088995457,14.564209938 --2.37219309807,1.69090688229,14.557800293 --2.39717483521,1.69191563129,14.5655937195 --2.44413995743,1.69393253326,14.5671863556 --2.49410367012,1.69695007801,14.5807723999 --2.54206824303,1.69796717167,14.5863656998 --2.59003329277,1.69998407364,14.5939617157 --2.6379981041,1.70200109482,14.5965518951 --2.66397929192,1.70401000977,14.6063432693 --2.71194410324,1.70502710342,14.6089344025 --2.75990891457,1.70604419708,14.6095228195 --2.80687403679,1.7070608139,14.6081171036 --2.85483884811,1.70907759666,14.610710144 --2.90380263329,1.71009480953,14.6122932434 --2.95176768303,1.71211159229,14.6128845215 --2.97874927521,1.71512043476,14.6296844482 --3.02571439743,1.71513700485,14.6252765656 --3.07467889786,1.71715390682,14.6308698654 --3.12064433098,1.71717023849,14.6204605103 --3.17260789871,1.72118771076,14.636048317 --3.22257184982,1.72320473194,14.6426382065 --3.26953721046,1.72322106361,14.6362304688 --3.29551911354,1.72522974014,14.6440267563 --3.34048485756,1.72524571419,14.6296205521 --3.38944983482,1.72726225853,14.6342163086 --3.43941402435,1.72927927971,14.637804985 --3.48637938499,1.72929549217,14.630396843 --3.53934288025,1.73331260681,14.6479892731 --3.56532478333,1.73532116413,14.6537847519 --3.61428952217,1.73633766174,14.6543779373 --3.66825294495,1.74135482311,14.6769762039 --3.71721744537,1.74237143993,14.6725616455 --3.77118086815,1.74638843536,14.6931591034 --3.82614398003,1.75040566921,14.7137498856 --3.87510871887,1.75242221355,14.7103414536 --3.89109373093,1.74842894077,14.6771373749 --3.9420580864,1.75144541264,14.6837329865 --3.99502158165,1.75446224213,14.6953248978 --4.04498672485,1.75647854805,14.6979227066 --4.09794998169,1.75949537754,14.7075128555 --4.14991426468,1.76151192188,14.7131032944 --4.19987916946,1.76352798939,14.7157039642 --4.22786092758,1.76653659344,14.7255010605 --4.27982473373,1.76855301857,14.7290887833 --4.32778978348,1.76956892014,14.7206830978 --4.3757557869,1.77058470249,14.7122764587 --4.42672014236,1.77260077,14.7148742676 --4.47868442535,1.77461719513,14.7174634933 --4.50266742706,1.77562487125,14.7162685394 --4.55663108826,1.77864134312,14.7248592377 --4.60759592056,1.78065752983,14.7244520187 --4.65656089783,1.78167307377,14.7190494537 --4.70852565765,1.784689188,14.7216444016 --4.75549125671,1.78470444679,14.708237648 --4.80945539474,1.78772091866,14.7148284912 --4.83843708038,1.79072916508,14.7276344299 --4.88740205765,1.79074478149,14.7182245255 --4.93936634064,1.79376065731,14.7188177109 --4.99333143234,1.79677665234,14.7274188995 --5.05029439926,1.80079329014,14.743016243 --5.09925985336,1.80180847645,14.7346124649 --5.15422344208,1.80482470989,14.7402019501 --5.17820644379,1.80583238602,14.7339982986 --5.18918323517,1.7918419838,14.6175918579 --5.19316196442,1.77585065365,14.4831829071 --5.223133564,1.76986312866,14.4217729568 --5.26909971237,1.77087771893,14.4083738327 --5.31106805801,1.76889169216,14.3819684982 --5.33804988861,1.77089965343,14.3847646713 --5.38601589203,1.77191436291,14.3753623962 --5.43598175049,1.77292966843,14.3689546585 --5.4819483757,1.77394402027,14.3535509109 --5.52591609955,1.77295827866,14.3321447372 --5.57488155365,1.77497315407,14.3247423172 --5.62484788895,1.77598798275,14.3203430176 --5.6498298645,1.77699542046,14.3161363602 --5.70079565048,1.77901041508,14.3127336502 --5.7417640686,1.77802395821,14.2853326797 --5.79172992706,1.77903878689,14.2779254913 --5.84069633484,1.78105330467,14.2705259323 --5.88966226578,1.78206789494,14.2601184845 --5.92663240433,1.78008067608,14.2227163315 --5.95661401749,1.78208863735,14.2315158844 --6.00757980347,1.78410327435,14.2271137238 --6.05154800415,1.78411698341,14.2067127228 --6.09951400757,1.78513121605,14.1943082809 --6.14947986603,1.78714573383,14.1848993301 --5.39367628098,1.52904987335,12.3203802109 --5.46964550018,1.54806423187,12.4421901703 --5.4576292038,1.5310703516,12.3087806702 --5.4975976944,1.53208363056,12.2923707962 --5.45559072495,1.50608551502,12.0959625244 --5.51155471802,1.51210093498,12.117559433 --5.51453447342,1.50110912323,12.022149086 --5.57549715042,1.50812518597,12.0527410507 --5.58948373795,1.50713074207,12.0355482101 --5.51648426056,1.47312879562,11.7761173248 --5.5594534874,1.47514224052,11.7727222443 --5.56843090057,1.46615123749,11.6933059692 --5.65438699722,1.48117005825,11.779914856 --5.70135402679,1.48418414593,11.7805051804 --5.64335107803,1.45618402958,11.5660896301 --5.68133068085,1.46219289303,11.5978918076 --5.74629306793,1.47020888329,11.6384963989 --5.7822637558,1.47022116184,11.6180906296 --5.80723714828,1.46623194218,11.5766878128 --5.83121109009,1.46324265003,11.5312747955 --5.8591837883,1.46025371552,11.4968738556 --5.82518386841,1.44625306129,11.3846645355 --5.88114881516,1.45126783848,11.4042596817 --5.96210718155,1.46428561211,11.4738693237 --5.92009973526,1.4422878027,11.3034505844 --5.92407894135,1.43329560757,11.2240419388 --5.97804450989,1.43830990791,11.240644455 --6.03001070023,1.44332408905,11.2502326965 --6.03300094604,1.43932795525,11.2150392532 --6.03698015213,1.43033587933,11.1356229782 --6.05395650864,1.42634534836,11.0832195282 --6.03794193268,1.41235077381,10.9698057175 --6.09990549088,1.41936588287,11.0004081726 --6.16786766052,1.42838144302,11.042016983 --6.28181743622,1.44940280914,11.1636247635 --6.27680921555,1.44340574741,11.1124162674 --6.31277990341,1.44341742992,11.0940151215 --6.3737449646,1.45043194294,11.1206216812 --6.40271759033,1.44844269753,11.0882120132 --6.4506855011,1.45145571232,11.0898103714 --6.4676618576,1.44746494293,11.0374011993 --6.53263521194,1.45947623253,11.1102161407 --6.56560754776,1.45948719978,11.0858135223 --6.54359388351,1.44449174404,10.9663925171 --6.62755250931,1.4575086832,11.0290021896 --6.65052747726,1.45351839066,10.9875955582 --6.6844997406,1.4535292387,10.9661989212 --6.71647262573,1.45353996754,10.9397935867 --6.78144550323,1.4645512104,11.0065984726 --6.86340475082,1.47656750679,11.0632133484 --6.85138940811,1.46557307243,10.964799881 --6.91335439682,1.47158706188,10.9864015579 --6.95232534409,1.47259843349,10.9709997177 --7.01528978348,1.47961235046,10.9946088791 --7.11924314499,1.49663102627,11.0802173615 --7.18021774292,1.50664126873,11.1380300522 --7.17720031738,1.49764764309,11.0546159744 --7.26715755463,1.51066458225,11.1162233353 --7.19415855408,1.48466289043,10.9267997742 --7.24712657928,1.48967540264,10.9324054718 --7.28909730911,1.49168658257,10.9200029373 --7.39106035233,1.51070141792,11.0358171463 --7.49701404572,1.52771961689,11.119433403 --7.5819735527,1.53873550892,11.170044899 --7.59495210648,1.53374326229,11.1126384735 --7.67091464996,1.54275786877,11.1492519379 --7.69189071655,1.53976655006,11.1028423309 --7.74285936356,1.54377841949,11.1014461517 --7.72785425186,1.535779953,11.0412349701 --7.73783349991,1.53078722954,10.9808301926 --7.74681329727,1.52479434013,10.9204292297 --7.89275741577,1.54981637001,11.0530500412 --7.82175827026,1.52581489086,10.8786268234 --7.85773086548,1.52682495117,10.8552236557 --7.89170408249,1.52683460712,10.8298244476 --7.94368171692,1.53384315968,10.8656320572 --8.11761856079,1.56486749649,11.0332679749 --8.21057701111,1.57688319683,11.0858764648 --8.2055606842,1.56788873672,11.0044631958 --8.2125415802,1.56289505959,10.9420642853 --8.23451900482,1.55990338326,10.8986616135 --8.26949214935,1.55991280079,10.8732624054 --8.18750476837,1.53890728951,10.7290449142 --8.33244991302,1.56192803383,10.8476610184 --8.46539878845,1.58294737339,10.9502830505 --8.42639064789,1.56794905663,10.827870369 --8.45536613464,1.56695759296,10.7944717407 --8.5083360672,1.56996870041,10.7910728455 --8.51432514191,1.56797218323,10.7628679276 --8.69026279449,1.59799516201,10.9165029526 --8.61626529694,1.57499337196,10.752081871 --8.77320766449,1.60001444817,10.8777036667 --8.87216567993,1.61402952671,10.9303197861 --8.88914489746,1.61003649235,10.8809213638 --8.89712619781,1.605042696,10.8195142746 --8.91111469269,1.60404670238,10.802318573 --8.85911083221,1.58704710007,10.6678953171 --8.97606372833,1.60306370258,10.7405157089 --8.9500541687,1.59106636047,10.6411123276 --8.9570350647,1.58607232571,10.5797023773 --9.00100803375,1.5880818367,10.5633049011 --5.65782403946,0.919776022434,6.54908847809 --5.47286128998,0.881762385368,6.31084108353 --5.46984291077,0.87676936388,6.26542234421 --5.46882534027,0.872776210308,6.22401762009 --5.45581007004,0.866782128811,6.16860485077 --5.45379209518,0.861789047718,6.12619447708 --5.4587726593,0.859796583652,6.09178256989 --5.44275808334,0.852802217007,6.03437137604 --5.45374631882,0.852806687355,6.02716970444 --5.44872903824,0.847813248634,5.98276185989 --5.44671154022,0.843820214272,5.94134712219 --5.42069911957,0.835824966431,5.87392854691 --5.45167350769,0.837834775448,5.8695230484 --5.45665359497,0.834842205048,5.83711624146 --5.44864702225,0.83184492588,5.80991411209 --5.4506278038,0.828852117062,5.77450561523 --5.45937252045,0.784949958324,5.28177452087 --5.4713511467,0.783958017826,5.2583565712 --5.53631830215,0.792969763279,5.28796720505 --5.52630233765,0.787975907326,5.24354982376 --5.57227420807,0.792985916138,5.25516796112 --5.57926368713,0.792989850044,5.24496650696 --5.56724882126,0.787995696068,5.1995549202 --5.60920381546,0.790012300014,5.17174625397 --5.61118507385,0.787019252777,5.1393289566 --5.63416147232,0.788027763367,5.12692117691 --5.65913820267,0.790036261082,5.11651659012 --5.67712545395,0.791040658951,5.11732769012 --5.70810127258,0.794049441814,5.11293363571 --5.73307752609,0.79505777359,5.10253286362 --5.76005411148,0.797066390514,5.09312391281 --5.78903007507,0.79907476902,5.08673238754 --5.8130068779,0.801083087921,5.07432174683 --5.83799171448,0.803088247776,5.07911396027 --5.87196731567,0.807096898556,5.07672262192 --6.70340585709,0.884284377098,5.00979804993 --6.69337463379,0.87729549408,4.93396854401 --5.48161554337,0.682235896587,4.00036048889 --5.48159837723,0.680242359638,3.97295045853 --5.48857927322,0.679249286652,3.95053768158 --5.51055812836,0.680256724358,3.94014239311 --6.86326599121,0.893329381943,4.91018819809 --7.65481901169,0.971459388733,4.82891750336 --7.6228094101,0.964463174343,4.7724852562 --7.53677225113,0.943476915359,4.59903240204 --7.95666456223,1.00250017643,4.79436779022 --8.00064086914,1.0065060854,4.78698062897 --8.03361988068,1.00851154327,4.77157783508 --8.07660484314,1.01451516151,4.78038978577 --8.1275806427,1.01952111721,4.77599811554 --8.17855739594,1.0245269537,4.77161026001 --8.2395324707,1.03153288364,4.77322912216 --8.29450798035,1.03753876686,4.7698340416 --8.35248279572,1.04354441166,4.7684469223 --8.41945648193,1.05155038834,4.77206420898 --8.47843933105,1.05955398083,4.7888841629 --11.7308340073,1.53464496136,6.58915328979 --11.7428207397,1.53364682198,6.54776334763 --11.7448091507,1.53064846992,6.49935865402 --11.7367992401,1.52664995193,6.44494533539 --11.7107982635,1.52065014839,6.40573406219 --11.722784996,1.51965200901,6.36433982849 --11.8207559586,1.53165566921,6.36996889114 --11.9017314911,1.53965878487,6.36559247971 --11.9797077179,1.54866170883,6.35921621323 --12.0486841202,1.55566442013,6.34783983231 --12.1146621704,1.56266689301,6.33345413208 --12.163649559,1.56766831875,6.33527183533 --12.1556396484,1.56366920471,6.28186845779 --12.2695999146,1.57467317581,6.24310112 --7.99629497528,0.955608427525,3.97720932961 --7.99128198624,0.95361238718,3.94280552864 --7.98426866531,0.95061647892,3.90638637543 --7.99325990677,0.950618565083,3.89518928528 --7.9802479744,0.947622418404,3.85677862167 --7.9842338562,0.945626437664,3.82737851143 --7.97522115707,0.942630410194,3.79096531868 --7.98920536041,0.94363451004,3.76656723022 --7.97519302368,0.939638495445,3.72714185715 --7.98317813873,0.938642382622,3.70075249672 --7.96817350388,0.93564426899,3.67753958702 --7.97115898132,0.93464833498,3.64712572098 --7.97414445877,0.933652281761,3.6177239418 --7.97313070297,0.931656122208,3.58631849289 --7.9581193924,0.927660048008,3.54790019989 --7.96910429001,0.927663981915,3.5225019455 --7.95609235764,0.923667728901,3.48609471321 --7.97008323669,0.92566972971,3.47689270973 --8.03206062317,0.932673752308,3.47451043129 --8.08203887939,0.937677621841,3.46612143517 --8.13301849365,0.943681418896,3.45773029327 --8.19499588013,0.950685083866,3.45434951782 --8.25197315216,0.956688702106,3.447961092 --8.3099527359,0.963692069054,3.44258475304 --8.36293792725,0.969693779945,3.449395895 --8.42691612244,0.977696955204,3.44602251053 --8.47889518738,0.982700228691,3.43562555313 --8.54487323761,0.990703225136,3.43225193024 --8.5908536911,0.995706319809,3.41885495186 --11.6324052811,1.41269421577,4.60719013214 --11.6194019318,1.41069459915,4.58098983765 --11.6063947678,1.40669536591,4.53258085251 --11.6143827438,1.40569603443,4.49217271805 --11.6023759842,1.40169680119,4.44577598572 --11.6043663025,1.39969742298,4.40336799622 --11.5963573456,1.39669811726,4.35796403885 --11.6053466797,1.3966987133,4.31855869293 --11.6103410721,1.39569890499,4.29935932159 --11.6223297119,1.39569926262,4.26196289062 --11.6453170776,1.39669954777,4.2285695076 --11.5843162537,1.38670086861,4.1631398201 --11.5893068314,1.38570129871,4.1237449646 --11.5742988586,1.38170206547,4.07633495331 --11.5682954788,1.37970232964,4.053129673 --11.5752849579,1.37970268726,4.01372528076 --11.5712766647,1.37670314312,3.97132587433 --11.5642690659,1.37470376492,3.92691469193 --11.5692596436,1.3737039566,3.88751459122 --11.5702495575,1.37170433998,3.84711623192 --11.5592422485,1.36870479584,3.8017039299 --11.5572376251,1.36770498753,3.78050160408 --11.5582284927,1.36570525169,3.7401008606 --11.542222023,1.36170589924,3.69368982315 --11.5192155838,1.35770666599,3.64527702332 --11.38722229,1.33771026134,3.56182837486 --11.3992118835,1.33771026134,3.52542686462 --11.3922042847,1.33571076393,3.48301887512 --11.395198822,1.3347107172,3.46381616592 --11.3781919479,1.33171141148,3.41941452026 --11.399181366,1.33271110058,3.38601660728 --11.3761749268,1.32771205902,3.33859848976 --11.3931646347,1.32871174812,3.30420088768 --11.3831567764,1.32571220398,3.26179552078 --11.3841485977,1.32471215725,3.22339963913 --11.3631467819,1.32171297073,3.19718694687 --11.3811359406,1.32271242142,3.16278600693 --11.3641290665,1.31871318817,3.11938405037 --11.375120163,1.31871283054,3.08298015594 --11.3701124191,1.3167129755,3.04257583618 --11.3701038361,1.31571304798,3.00316786766 --11.3630962372,1.31271314621,2.96276688576 --11.3700914383,1.31371283531,2.94456028938 --11.3640832901,1.31171298027,2.90415501595 --11.3580760956,1.30971312523,2.86475896835 --11.3560686111,1.30771315098,2.82535243034 --11.3330631256,1.30371391773,2.7809419632 --11.3770503998,1.30771195889,2.75355291367 --11.3520498276,1.30471289158,2.72834610939 --11.3290424347,1.2997136116,2.68393182755 --11.3490333557,1.30171251297,2.65053510666 --11.3830223083,1.30471074581,2.62013983727 --11.4010133743,1.30570960045,2.5867497921 --11.4390029907,1.30970728397,2.55736017227 --11.4749917984,1.31370508671,2.52696585655 --11.5059814453,1.31670308113,2.49658417702 --11.5239772797,1.31770193577,2.48138904572 --11.4719743729,1.31070399284,2.43096446991 --11.4489679337,1.30670452118,2.38755273819 --11.4549608231,1.30570375919,2.35014629364 --11.6109409332,1.32569468021,2.34580397606 --11.6899271011,1.33468961716,2.32443618774 --11.7189188004,1.33768713474,2.29204797745 --11.7479133606,1.34068500996,2.27886009216 --11.7949028015,1.3456813097,2.24947452545 --11.8118944168,1.34667932987,2.21408081055 --11.8448858261,1.35067617893,2.18169188499 --11.8618783951,1.3516740799,2.14629983902 --11.8458738327,1.3486738205,2.10388827324 --11.8218717575,1.34467458725,2.07967615128 --11.3688964844,1.28470146656,1.95508348942 --11.6528711319,1.32168269157,1.9697920084 --11.2498912811,1.26770734787,1.85822248459 --11.3768758774,1.28369820118,1.84387052059 --11.3188734055,1.27570104599,1.79644334316 --11.3488645554,1.27869808674,1.76404726505 --11.2258682251,1.26170599461,1.72479760647 --11.2908582687,1.2697006464,1.69942629337 --11.288851738,1.26869976521,1.66201984882 --11.243847847,1.26170194149,1.61759376526 --11.3668346405,1.27769219875,1.60024094582 --11.2058362961,1.25570261478,1.53877425194 --11.2148303986,1.25670099258,1.5033711195 --11.2768230438,1.26369583607,1.49419343472 --11.4918060303,1.29067873955,1.4898904562 --11.2078151703,1.25369882584,1.41136038303 --11.1578111649,1.24670147896,1.36793470383 --11.276799202,1.26169121265,1.34858775139 --11.0638036728,1.23270654678,1.28308749199 --11.0657968521,1.23270535469,1.24768614769 --11.0857925415,1.2357032299,1.23249411583 --11.1707830429,1.24569511414,1.20712471008 --11.127779007,1.23969733715,1.16570162773 --11.147772789,1.24169456959,1.1323081255 --11.1467657089,1.24069321156,1.09590029716 --11.0657634735,1.22969865799,1.05045711994 --11.1067562103,1.23469388485,1.02007973194 --11.0677547455,1.22969663143,0.997859418392 --11.0607500076,1.22769582272,0.961452066898 --11.1987390518,1.24568223953,0.940110504627 --11.2397327423,1.24967706203,0.907720088959 --11.1937294006,1.24367952347,0.867296814919 --11.0987262726,1.23068666458,0.822854101658 --11.0897216797,1.2296859026,0.786446154118 --11.0837182999,1.22868573666,0.768242776394 --11.1617116928,1.23867678642,0.738868653774 --11.2687044144,1.25166487694,0.712520599365 --11.1527013779,1.23667418957,0.667061626911 --11.1816959381,1.23966944218,0.633672356606 --11.1246919632,1.23167335987,0.593236744404 --11.1206865311,1.23167192936,0.557835996151 --11.1006851196,1.22867298126,0.538624107838 --11.1126804352,1.22966992855,0.504229307175 --11.1166744232,1.22966754436,0.468825697899 --11.1226701736,1.2306650877,0.433421641588 --11.1736650467,1.23665785789,0.401045024395 --11.1146612167,1.22866201401,0.362617433071 --11.2096557617,1.24064970016,0.331251293421 --11.1326541901,1.23065686226,0.310016930103 --11.1546497345,1.2336524725,0.275624781847 --11.2036447525,1.23964488506,0.242245748639 --11.1096410751,1.22765302658,0.202796012163 --11.1736373901,1.23564362526,0.169419839978 --11.18663311,1.23763978481,0.13401953876 --11.0586309433,1.22065317631,0.112762331963 --11.0996265411,1.2256462574,0.0783747211099 --11.0866231918,1.22364544868,0.0429676249623 --11.3246202469,1.25461542606,0.0126770185307 --11.2776165009,1.24861824512,-0.023743852973 --11.2126121521,1.23962330818,-0.0611850991845 --11.1086082458,1.22663331032,-0.0976337566972 --11.1856069565,1.23662269115,-0.114801771939 --11.2056035995,1.23861765862,-0.150195047259 --11.1605987549,1.23262047768,-0.185615777969 --11.1645965576,1.23361718655,-0.222028002143 --11.2335948944,1.2426058054,-0.257394641638 --11.2115907669,1.23960578442,-0.292806595564 --11.2075881958,1.23960340023,-0.3282096982 --11.2925882339,1.24959123135,-0.347375124693 --11.249584198,1.24459373951,-0.382800638676 --11.2055797577,1.23959636688,-0.417218565941 --11.2705793381,1.24758481979,-0.454595208168 --11.208574295,1.23958992958,-0.489028930664 --11.2365722656,1.24358320236,-0.525418698788 --11.225569725,1.2425814867,-0.560827314854 --11.1535654068,1.23258960247,-0.57605946064 --11.119562149,1.22859120369,-0.610480606556 --11.1815624237,1.23657953739,-0.64886111021 --11.2845640182,1.25056195259,-0.688209295273 --11.2555599213,1.24656271935,-0.722623825073 --11.2635583878,1.24755811691,-0.759025096893 --11.275557518,1.24955296516,-0.795421540737 --11.1675519943,1.23656654358,-0.808686494827 --11.3695583344,1.26253402233,-0.854985833168 --11.4495611191,1.27251875401,-0.895343482494 --11.2745504379,1.25054049492,-0.921840846539 --11.2765493393,1.25053656101,-0.957234919071 --11.2545471191,1.24853610992,-0.992659509182 --11.2515449524,1.24853277206,-1.02806055546 --11.279545784,1.25252664089,-1.04825055599 --11.4095516205,1.26950311661,-1.09358334541 --11.3855495453,1.266502738,-1.1279964447 --11.4615526199,1.27648687363,-1.17136979103 --11.4425506592,1.27448570728,-1.20577514172 --11.4095478058,1.27048659325,-1.24020242691 --11.3665447235,1.26548922062,-1.27262508869 --11.2925395966,1.25649893284,-1.28386282921 --11.2235336304,1.24750578403,-1.31329894066 --11.2655363083,1.25349485874,-1.35368347168 --11.3845443726,1.26947128773,-1.40202653408 --11.4435482025,1.27745735645,-1.44439506531 --11.435546875,1.27745401859,-1.48080790043 --11.4175462723,1.27545237541,-1.51521623135 --11.4515476227,1.27944457531,-1.53739976883 --11.3095369339,1.26246368885,-1.55787730217 --11.2225294113,1.25147390366,-1.58432972431 --11.2555322647,1.2564637661,-1.6247177124 --11.4435491562,1.28142690659,-1.68401646614 --11.3665418625,1.27143537998,-1.71146392822 --11.4995546341,1.28940975666,-1.74760115147 --11.4355487823,1.28141593933,-1.77603530884 --11.3635425568,1.27342367172,-1.80347931385 --11.358543396,1.27341973782,-1.83887732029 --11.3615436554,1.27441430092,-1.8762806654 --11.4465532303,1.28539383411,-1.92563974857 --11.4725561142,1.28938388824,-1.96703279018 --11.4575557709,1.28838396072,-1.98324048519 --11.4405555725,1.28638184071,-2.01764988899 --11.4665594101,1.29037165642,-2.05903983116 --11.4075546265,1.28337728977,-2.08748030663 --11.5015659332,1.29635429382,-2.13983082771 --11.4835662842,1.29535222054,-2.17424201965 --11.64158535,1.3163163662,-2.2385597229 --11.5505752563,1.30533087254,-2.24281907082 --11.5305757523,1.30332899094,-2.27622318268 --11.5315771103,1.30432295799,-2.31463027 --11.5625839233,1.3093110323,-2.3580160141 --11.7136039734,1.32927536964,-2.42434239388 --11.6245965958,1.31928682327,-2.44579005241 --11.7226104736,1.33226108551,-2.50314354897 --11.7446165085,1.33625030518,-2.54552912712 --11.8116264343,1.34523355961,-2.57870125771 --11.7456216812,1.33824050426,-2.60413599014 --11.6426115036,1.32525491714,-2.62259984016 --11.6856203079,1.33223962784,-2.66997933388 --11.7086267471,1.33622837067,-2.71336817741 --11.7186317444,1.33821976185,-2.75375986099 --11.74563694,1.34221053123,-2.77995634079 --11.8426542282,1.3561835289,-2.83929777145 --11.948674202,1.37115395069,-2.90264821053 --11.9746818542,1.37614119053,-2.94803404808 --11.9216794968,1.37014520168,-2.97647118568 --12.5277748108,1.45000696182,-3.15553593636 --12.1397218704,1.40108311176,-3.10715579987 --12.1297235489,1.4000813961,-3.12536501884 --12.1547317505,1.40406823158,-3.17175102234 --12.1037302017,1.39907169342,-3.2001812458 --12.0457258224,1.39307677746,-3.22661566734 --12.2807703018,1.42501616478,-3.32589006424 --12.228767395,1.4190196991,-3.35432243347 --12.5108203888,1.45794737339,-3.46756696701 --12.3367948532,1.43498277664,-3.44386363029 --12.4098138809,1.44595742226,-3.50422096252 --12.412820816,1.44794809818,-3.54762673378 --12.5148458481,1.46291565895,-3.61697125435 --12.4068336487,1.44993197918,-3.63043475151 --12.5128602982,1.46589815617,-3.70177793503 --12.6868991852,1.48984754086,-3.79308533669 --12.5248737335,1.46888148785,-3.76937556267 --12.6899118423,1.49283277988,-3.85868358612 --12.9259653091,1.52576625347,-3.96995615959 --13.2570371628,1.57067596912,-4.11017227173 --13.3060560226,1.5796533823,-4.17055082321 --13.7001428604,1.63354599476,-4.33272790909 --13.680150032,1.63253939152,-4.37414169312 --15.669549942,1.89804065228,-4.99723005295 --13.2180747986,1.57363724709,-4.30500936508 --13.9842414856,1.67743396759,-4.58697938919 --13.4611463547,1.60955393314,-4.47267627716 --13.1580953598,1.57061946392,-4.42425107956 --13.2271203995,1.58159101009,-4.49160909653 --13.3891658783,1.60453808308,-4.58991765976 --13.3841705322,1.60553348064,-4.61212444305 --13.4131889343,1.61151432991,-4.66850948334 --13.4332046509,1.6154974699,-4.72189664841 --13.5022315979,1.62646746635,-4.79225873947 --13.4712371826,1.6244635582,-4.82967996597 --13.4942550659,1.62944531441,-4.88506793976 --13.5322761536,1.63642275333,-4.94645166397 --13.6573114395,1.65438306332,-5.01357889175 --13.6763296127,1.65936517715,-5.06897115707 --13.7353572845,1.66933655739,-5.13833713531 --13.7803821564,1.67731118202,-5.20371484756 --13.8854217529,1.69326913357,-5.291056633 --13.9574537277,1.7052359581,-5.36641120911 --13.9734725952,1.71021771431,-5.42280626297 --14.1025123596,1.72817480564,-5.49593448639 --14.2015523911,1.74413311481,-5.58327484131 --14.2995929718,1.76009106636,-5.67162036896 --14.3126125336,1.76407289505,-5.72801113129 --14.5556917191,1.79998838902,-5.87427902222 --14.7137508392,1.82392776012,-5.98858880997 --14.8107948303,1.83988416195,-6.07993078232 --14.7897987366,1.83788216114,-6.09914636612 --15.0258798599,1.87279748917,-6.24640655518 --15.4370098114,1.93166029453,-6.46556425095 --15.4040222168,1.92965257168,-6.50999069214 --15.5400800705,1.95159494877,-6.62231206894 --15.6931438446,1.97553145885,-6.74262237549 --15.7741775513,1.98749816418,-6.80477190018 --16.1863155365,2.04735565186,-7.03493070602 --16.2323513031,2.05732250214,-7.11430263519 --16.5444660187,2.10320782661,-7.30752182007 --16.6195144653,2.11716461182,-7.40187978745 --16.7885894775,2.14309239388,-7.5361738205 --16.912651062,2.16403317451,-7.65350198746 --17.0607089996,2.18597626686,-7.75061798096 --17.1847743988,2.20691633224,-7.86893987656 --17.2278156281,2.21588087082,-7.95331478119 --17.2268447876,2.21885895729,-8.01871681213 --17.2098674774,2.21984267235,-8.07612228394 --17.1898899078,2.22082662582,-8.13353919983 --17.1939201355,2.2248032093,-8.2009344101 --17.1889343262,2.22579360008,-8.231133461 --17.1819610596,2.22877311707,-8.29454040527 --17.1919956207,2.23374724388,-8.3659362793 --17.2010269165,2.23872160912,-8.43632793427 --17.1980571747,2.24169945717,-8.50172996521 --17.2140922546,2.24767112732,-8.57611751556 --17.2161254883,2.25164723396,-8.64451694489 --17.2371482849,2.25662875175,-8.68770027161 --17.2631874084,2.26359629631,-8.76808357239 --17.2722225189,2.26856946945,-8.84047794342 --17.2682533264,2.27254700661,-8.9068813324 --17.2922935486,2.27951455116,-8.98726654053 --17.2773208618,2.2814950943,-9.04867649078 --17.2833576202,2.2864689827,-9.12006950378 --17.3013801575,2.29045009613,-9.16426086426 --17.2924098969,2.29342865944,-9.22866439819 --17.2964458466,2.29840254784,-9.30006122589 --17.3114852905,2.30437207222,-9.37744998932 --17.3285255432,2.31034088135,-9.45684146881 --17.3065509796,2.31132340431,-9.51525306702 --17.2915821075,2.31430315971,-9.57766246796 --17.2805957794,2.31429433823,-9.6068687439 --17.2996368408,2.3212621212,-9.68725299835 --17.2996730804,2.32523608208,-9.75865459442 --17.2927055359,2.32921242714,-9.82605838776 --17.2757377625,2.33119249344,-9.88847064972 --17.2887783051,2.33716130257,-9.9668598175 --17.2728099823,2.33914089203,-10.0292663574 --17.2868328094,2.34312224388,-10.0734586716 --17.2798690796,2.34709787369,-10.1418628693 --17.2739028931,2.35107326508,-10.211268425 --17.2769432068,2.35604476929,-10.2856664658 --17.2749786377,2.36001825333,-10.3570632935 --17.2400035858,2.36000394821,-10.4104890823 --17.2340393066,2.36297893524,-10.4798898697 --17.2310600281,2.36596608162,-10.5150928497 --17.2110900879,2.36694645882,-10.5765018463 --17.1601066589,2.3639383316,-10.619934082 --17.1611480713,2.36990976334,-10.6943321228 --17.0261306763,2.3539352417,-10.6868181229 --17.1002025604,2.36987733841,-10.8061714172 --17.0892391205,2.37385344505,-10.8735761642 --17.0692501068,2.37284684181,-10.8987894058 --17.0622882843,2.37682080269,-10.9701986313 --17.0503234863,2.37979698181,-11.0376052856 --17.035358429,2.38277387619,-11.1030111313 --17.0113887787,2.38475465775,-11.1634273529 --17.0124320984,2.38972496986,-11.2398262024 --17.0184555054,2.39370727539,-11.2820243835 --17.0034923553,2.39668393135,-11.3484325409 --17.0005340576,2.40165519714,-11.422832489 --16.9915733337,2.40562868118,-11.4942407608 --16.9776096344,2.40860414505,-11.5626525879 --16.9836578369,2.41457152367,-11.6430444717 --17.1417789459,2.44447231293,-11.8273468018 --17.3759155273,2.48335552216,-12.0243988037 --17.5610523224,2.5172431469,-12.2296800613 --17.5691051483,2.52420711517,-12.3160734177 --17.4981174469,2.51920509338,-12.349521637 --17.39311409,2.50921845436,-12.3589906693 --17.3161239624,2.50321984291,-12.3864374161 --17.259141922,2.50021243095,-12.4278736115 --17.2131443024,2.49621653557,-12.4361028671 --17.1461582184,2.4912135601,-12.4705467224 --17.0851745605,2.4882080555,-12.5089883804 --17.0301952362,2.48519968987,-12.5514249802 --16.9612064362,2.48019814491,-12.5828666687 --16.8842144012,2.47420024872,-12.6083154678 --16.7912158966,2.46521019936,-12.6217746735 --16.7672271729,2.46520471573,-12.6449899673 --16.6992397308,2.46020245552,-12.6774396896 --16.6302509308,2.45520210266,-12.7068786621 --16.5762729645,2.45319342613,-12.7493200302 --16.4992790222,2.44719648361,-12.7727680206 --16.4422988892,2.44418954849,-12.8122091293 --16.3713092804,2.43919014931,-12.8396539688 --16.3283081055,2.4351940155,-12.8478832245 --16.2713279724,2.43318748474,-12.8863229752 --16.203338623,2.42818641663,-12.9157686234 --16.1263465881,2.42219018936,-12.9382219315 --16.0713634491,2.41918349266,-12.9766559601 --16.0123806,2.41617798805,-13.0130977631 --15.933385849,2.4101831913,-13.0325508118 --15.901391983,2.40818190575,-13.0477705002 --15.8364048004,2.40418028831,-13.0782155991 --15.7834253311,2.40217232704,-13.1186552048 --15.7294445038,2.40016531944,-13.1570901871 --15.6644563675,2.39516377449,-13.1865339279 --15.6074733734,2.39315867424,-13.2219705582 --15.5604972839,2.39214777946,-13.2664041519 --15.5074901581,2.38615751266,-13.2646446228 --15.4605140686,2.38514661789,-13.3090801239 --15.3885211945,2.38014984131,-13.3305244446 --15.3365421295,2.3781414032,-13.3709659576 --15.2785587311,2.37513661385,-13.4054069519 --15.2195739746,2.37213277817,-13.4378461838 --15.1605892181,2.36912894249,-13.4702854156 --15.1215906143,2.36613225937,-13.4785137177 --15.066608429,2.36412620544,-13.5149536133 --15.0076236725,2.36112236977,-13.5473966599 --14.9516410828,2.35911655426,-13.5828399658 --14.895658493,2.35611176491,-13.6172790527 --14.8346719742,2.35310935974,-13.6467189789 --14.7906970978,2.35309743881,-13.692152977 --14.7536993027,2.35009980202,-13.701379776 --14.6967153549,2.34709525108,-13.7348222733 --14.6497392654,2.34608483315,-13.7772579193 --14.6007604599,2.34507632256,-13.8166904449 --14.562789917,2.34606099129,-13.8671188354 --14.4978017807,2.3420612812,-13.8925666809 --14.4808177948,2.34305262566,-13.9197807312 --14.4248352051,2.34104752541,-13.9532222748 --14.3818616867,2.34103488922,-13.9996576309 --14.3348846436,2.34002494812,-14.0410919189 --14.2758998871,2.3370218277,-14.0715360641 --14.2369289398,2.33800697327,-14.1209659576 --14.1889514923,2.33699774742,-14.1614017487 --14.1439771652,2.33698654175,-14.204834938 --14.1119823456,2.33498620987,-14.2180624008 --14.0870227814,2.33796310425,-14.2804784775 --14.0260353088,2.33496165276,-14.307923317 --13.9800605774,2.33495044708,-14.3513641357 --13.9420919418,2.3359348774,-14.4017934799 --13.884106636,2.33393192291,-14.4312324524 --13.8741292953,2.33591794968,-14.4664449692 --13.8241519928,2.33490967751,-14.5048837662 --13.7801780701,2.33489775658,-14.5493183136 --13.736205101,2.33488559723,-14.593752861 --13.6852264404,2.3338778019,-14.631193161 --13.6172323227,2.32988142967,-14.649641037 --13.6172962189,2.33784079552,-14.7410478592 --13.6063194275,2.33982753754,-14.7752590179 --13.5543403625,2.33882021904,-14.8116998672 --13.527381897,2.34279727936,-14.874121666 --13.4834089279,2.34278488159,-14.9185552597 --13.4394388199,2.34277176857,-14.9649972916 --13.4074754715,2.34575176239,-15.0214176178 --13.3554973602,2.34474396706,-15.0588645935 --13.3355121613,2.34473705292,-15.0820741653 --13.3015499115,2.34771704674,-15.139509201 --13.2595796585,2.3487033844,-15.1859388351 --13.2035970688,2.34669876099,-15.217382431 --13.1756410599,2.35067462921,-15.2818126678 --13.1306686401,2.35066270828,-15.3252458572 --13.0866975784,2.35164904594,-15.3716869354 --13.0707178116,2.35263872147,-15.4008989334 --13.0357551575,2.35561966896,-15.4563274384 --12.987780571,2.35560917854,-15.4977684021 --12.9608259201,2.35958433151,-15.5621891022 --12.9268655777,2.36156344414,-15.6206216812 --12.883895874,2.3625497818,-15.66705513 --12.8689546585,2.36951541901,-15.7474708557 --12.8609828949,2.37249851227,-15.7876806259 --12.8150129318,2.37348604202,-15.8321208954 --12.768040657,2.37347412109,-15.8755626678 --12.7010478973,2.37047743797,-15.8930120468 --12.543967247,2.34854698181,-15.8005285263 --12.3448410034,2.31764888763,-15.6540746689 --12.2928256989,2.31266450882,-15.6393156052 --12.25385952,2.3136484623,-15.6897497177 --12.2198991776,2.31662797928,-15.7471828461 --12.1649169922,2.31562328339,-15.7776279449 --12.105931282,2.31362199783,-15.8030757904 --12.0299282074,2.30763363838,-15.8065376282 --11.972943306,2.30563092232,-15.833984375 --11.9119548798,2.30363130569,-15.8564357758 --11.8819599152,2.30263161659,-15.8666553497 --11.8319835663,2.30162358284,-15.9030990601 --11.7729978561,2.29962229729,-15.9285526276 --11.7230205536,2.29961466789,-15.9639921188 --11.6680374146,2.29861068726,-15.9934396744 --11.6090517044,2.29660964012,-16.0178909302 --11.5850639343,2.29660511017,-16.0371112823 --11.5300827026,2.29560089111,-16.0665607452 --11.4801054001,2.29559254646,-16.1030044556 --11.4271249771,2.29458737373,-16.1344490051 --11.3641328812,2.29159045219,-16.1519012451 --11.3061475754,2.28958916664,-16.1763496399 --11.2391500473,2.28559565544,-16.1878032684 --11.2161655426,2.28658986092,-16.2090263367 --11.163184166,2.28558492661,-16.2394695282 --11.1142091751,2.28557610512,-16.2769165039 --11.0532197952,2.28357744217,-16.2973709106 --10.9962348938,2.28257536888,-16.3228206635 --10.9412508011,2.28057289124,-16.3492622375 --10.8822641373,2.27957224846,-16.372718811 --10.8592786789,2.27956628799,-16.3939418793 --10.7812671661,2.27358388901,-16.3864040375 --10.7262840271,2.27258014679,-16.414855957 --10.658285141,2.26858901978,-16.4223117828 --10.5742645264,2.26061248779,-16.4047775269 --10.5322980881,2.2625977993,-16.4512176514 --10.4733104706,2.26059794426,-16.4736747742 --10.4242916107,2.25461626053,-16.453912735 --10.3542871475,2.25062775612,-16.4563713074 --10.3193283081,2.2536072731,-16.512802124 --10.2563352585,2.25161170959,-16.527261734 --10.1893358231,2.24762034416,-16.5347194672 --10.0973014832,2.23765301704,-16.5011940002 --10.0552892685,2.23366570473,-16.4904289246 --9.97627162933,2.22668671608,-16.476896286 --9.94031333923,2.23066687584,-16.5323314667 --9.89634418488,2.23165416718,-16.5757751465 --9.83835506439,2.23065543175,-16.5952262878 --9.77435970306,2.22766184807,-16.6066875458 --9.73940372467,2.23164010048,-16.6651268005 --8.31941890717,1.88501727581,-14.3453569412 --8.18129920959,1.86110699177,-14.2148752213 --8.20641326904,1.87903523445,-14.3572664261 --8.10834789276,1.86508691311,-14.2907476425 --8.01629066467,1.85313332081,-14.2332248688 --7.99934434891,1.85910344124,-14.304646492 --7.80012607574,1.82026028633,-14.060210228 --7.73907279968,1.80929994583,-14.0034608841 --7.72112321854,1.81627225876,-14.0708789825 --7.47081851959,1.76248717308,-13.7274770737 --7.55803155899,1.79634833336,-13.9838275909 --7.4489402771,1.77841687202,-13.8883190155 --7.48407459259,1.79933214188,-14.0527019501 --6.76000452042,1.61806619167,-12.8276472092 --6.74501657486,1.61906087399,-12.8468637466 --7.48327827454,1.82821071148,-14.3107328415 --7.33412122726,1.79932427406,-14.1392593384 --7.23604393005,1.78438329697,-14.0597438812 --7.06384134293,1.74952673912,-13.8362770081 --7.18612718582,1.79434049129,-14.1735982895 --7.23128890991,1.8192384243,-14.3679800034 --7.07206439972,1.78139317036,-14.1153078079 --6.67146587372,1.6818022728,-13.4400110245 --6.97306585312,1.77740573883,-14.1352024078 --6.99919843674,1.79732370377,-14.2955980301 --6.88508701324,1.77740490437,-14.1780967712 --6.84209823608,1.77740430832,-14.1995353699 --6.82515668869,1.78537213802,-14.2749595642 --6.77711677551,1.77740228176,-14.2342071533 --6.62292861938,1.74553453922,-14.0297365189 --6.77529573441,1.80229711533,-14.455037117 --6.82948684692,1.83117675781,-14.6804046631 --5.42304515839,1.43880999088,-11.938287735 --6.59027814865,1.79333305359,-14.4656152725 --6.45010662079,1.7644534111,-14.2811307907 --6.54638767242,1.80727493763,-14.6064805984 --6.43627071381,1.78735911846,-14.4829692841 --6.42133903503,1.79632127285,-14.5683937073 --6.39138031006,1.80130112171,-14.6238384247 --6.12995862961,1.73358571529,-14.1584386826 --6.25124979019,1.77839779854,-14.4895572662 --6.18822288513,1.7724224329,-14.4680194855 --6.14022636414,1.77142739296,-14.4804735184 --6.12930440903,1.78238344193,-14.5758914948 --6.09533548355,1.78536999226,-14.6193265915 --6.04333114624,1.78338015079,-14.6227827072 --5.87808704376,1.7435464859,-14.3593244553 --5.83504581451,1.73657679558,-14.3175601959 --5.79005289078,1.73657917976,-14.3340091705 --5.77312088013,1.7455419302,-14.4184389114 --5.80429410934,1.77043676376,-14.6188249588 --5.72923755646,1.76048076153,-14.5642995834 --5.61007881165,1.7345905304,-14.3967990875 --5.53802394867,1.72563326359,-14.3442668915 --5.55411672592,1.73857688904,-14.4514694214 --5.5251584053,1.74355685711,-14.505900383 --5.48417520523,1.74455296993,-14.5333480835 --5.41312170029,1.73559498787,-14.4818143845 --5.35209131241,1.72962141037,-14.457280159 --5.26499605179,1.7146897316,-14.3607578278 --5.20897531509,1.70971024036,-14.3462162018 --5.18096399307,1.70772075653,-14.3384447098 --5.21917295456,1.73759424686,-14.5758295059 --5.1832036972,1.74158227444,-14.6172761917 --4.95174074173,1.67188465595,-14.1188583374 --4.89972686768,1.66890060902,-14.1123189926 --4.90786409378,1.68782019615,-14.2707242966 --4.93004369736,1.71371328831,-14.4751310349 --4.90202999115,1.71072542667,-14.4643535614 --4.87708902359,1.71869528294,-14.5367918015 --4.84613370895,1.72367453575,-14.5932340622 --4.77907991409,1.7147154808,-14.5437021255 --4.67993593216,1.69281375408,-14.3951873779 --4.72819852829,1.73065567017,-14.6875705719 --4.71121692657,1.73264753819,-14.7117910385 --4.66221284866,1.73065769672,-14.7152442932 --4.60618829727,1.72668039799,-14.6967039108 --4.58325958252,1.73564350605,-14.7811412811 --4.53826475143,1.73564767838,-14.794585228 --4.50931978226,1.74262058735,-14.8620262146 --4.42220163345,1.72470200062,-14.7425069809 --4.42134189606,1.7436221838,-14.90092659 --4.40837669373,1.74860441685,-14.9421491623 --4.35736608505,1.74561846256,-14.9386034012 --4.31137275696,1.74562227726,-14.9530582428 --4.28544044495,1.75458753109,-15.0334939957 --4.21035385132,1.74164938927,-14.9479675293 --4.15332317352,1.73667621613,-14.9224271774 --4.11026096344,1.72771883011,-14.8596696854 --4.04821109772,1.71975719929,-14.8141326904 --3.93799805641,1.68889653683,-14.594628334 --3.91106367111,1.69786381721,-14.6720685959 --3.80285096169,1.66700255871,-14.4535665512 --3.72072315216,1.6480884552,-14.32604599 --3.64762210846,1.63415813446,-14.2265138626 --3.6547267437,1.6480973959,-14.3417186737 --3.60972881317,1.64810359478,-14.3521785736 --3.54565763474,1.63715481758,-14.2846412659 --3.54180836678,1.65806984901,-14.4520635605 --3.48476409912,1.65110433102,-14.413526535 --3.45582437515,1.65907502174,-14.4849643707 --3.42889332771,1.6680406332,-14.5654010773 --3.4169383049,1.67401719093,-14.6166267395 --3.39302277565,1.68597340584,-14.7130622864 --3.31288647652,1.66606402397,-14.5775432587 --3.25483393669,1.65910375118,-14.5300035477 --3.228910923,1.669064641,-14.618437767 --3.17688417435,1.66508877277,-14.5978984833 --3.12786960602,1.6631052494,-14.5903568268 --3.12495326996,1.67405867577,-14.6815681458 --3.08799242973,1.67904305458,-14.7300186157 --3.04701137543,1.68103921413,-14.7574663162 --3.00703620911,1.68403220177,-14.7909145355 --2.95199418068,1.67806565762,-14.7543764114 --2.91804981232,1.68504011631,-14.8198251724 --2.90219044685,1.70396375656,-14.9732561111 --2.89929103851,1.71790778637,-15.0814762115 --2.84726524353,1.71393144131,-15.0619363785 --2.8012676239,1.71393835545,-15.0713911057 --2.74722671509,1.70797097683,-15.0358448029 --2.696205616,1.70499181747,-15.0213098526 --2.65422463417,1.70698869228,-15.0477552414 --2.62330722809,1.71794784069,-15.1402015686 --2.6073474884,1.72292804718,-15.1854248047 --2.57643818855,1.73488283157,-15.2858762741 --2.5324575901,1.73788011074,-15.3123340607 --2.47238135338,1.72693359852,-15.2407951355 --2.43443012238,1.73391342163,-15.2972402573 --2.40453457832,1.74686026573,-15.411690712 --2.35250926018,1.74388408661,-15.3921546936 --2.32548475266,1.73990261555,-15.3703794479 --2.27546787262,1.73792123795,-15.3598394394 --2.22746610641,1.73793137074,-15.3643016815 --2.1834871769,1.73992753029,-15.3927574158 --2.1405146122,1.74392032623,-15.4272117615 --2.09653496742,1.74591696262,-15.4546642303 --2.07152915001,1.74592506886,-15.4518976212 --2.03157830238,1.75190508366,-15.5083465576 --1.98660004139,1.75490140915,-15.5368070602 --1.9406080246,1.75590574741,-15.5512590408 --1.8976483345,1.76089131832,-15.5987205505 --1.85670089722,1.76786983013,-15.6581735611 --1.81172287464,1.77086615562,-15.6866283417 --1.77461349964,1.75693428516,-15.5788631439 --1.74174404144,1.77386784554,-15.7173213959 --1.6907197237,1.77089118958,-15.6987829208 --1.65280711651,1.78184986115,-15.7932338715 --1.61087179184,1.78982198238,-15.8646965027 --1.56387937069,1.79082679749,-15.8781490326 --1.51083350182,1.78586280346,-15.8376102448 --1.49290192127,1.79382812977,-15.9098415375 --1.44793450832,1.79881882668,-15.9482965469 --1.39994311333,1.79982352257,-15.9627571106 --1.32796680927,1.80282449722,-15.9954557419 --1.27896177769,1.80283713341,-15.9959144592 --1.2299643755,1.80284535885,-16.0043773651 --1.20596778393,1.80384814739,-16.0106067657 --1.15797269344,1.80485498905,-16.021062851 --1.10897052288,1.80486607552,-16.0245227814 --1.0599732399,1.80487430096,-16.0329875946 --1.0109770298,1.80588197708,-16.0424518585 --0.961972892284,1.80589413643,-16.0439109802 --0.912970721722,1.80590522289,-16.0473709106 --0.888981103897,1.80690431595,-16.0606040955 --0.839977025986,1.80691659451,-16.0620632172 --0.789976716042,1.8069268465,-16.067533493 --0.741983652115,1.8079328537,-16.0799884796 --0.692980587482,1.80794453621,-16.0824489594 --0.643985569477,1.8089517355,-16.092912674 --0.59498667717,1.80996131897,-16.0993747711 --0.569988965988,1.80996513367,-16.1046104431 --0.520992040634,1.81097352505,-16.113073349 --0.470984011889,1.81098842621,-16.11054039 --0.421992987394,1.81199347973,-16.1250038147 --0.373001277447,1.81399917603,-16.1384677887 --0.324001222849,1.81400942802,-16.1439285278 --0.300008893013,1.81501019001,-16.1541557312 --0.25000089407,1.81502509117,-16.1516246796 --0.201009258628,1.81703078747,-16.1650848389 --0.151018321514,1.81803631783,-16.1795558929 --0.102020576596,1.81904542446,-16.1870155334 --0.0520073883235,1.81806337833,-16.1794834137 --0.00300048314966,1.81807756424,-16.177942276 -0.0120045514777,1.81591308117,-15.3500871658 -0.0610012896359,1.81489753723,-15.3424501419 -0.111006312072,1.81488633156,-15.3428201675 -0.160014465451,1.81587707996,-15.3461818695 -0.210025414824,1.81586933136,-15.3525505066 -0.260025471449,1.81585538387,-15.3479204178 -0.309027463198,1.8158428669,-15.345284462 -0.334019631147,1.81383168697,-15.3354721069 -0.3830268085,1.81482195854,-15.3378334045 -0.432018488646,1.81280386448,-15.3252010345 -0.481002360582,1.81078135967,-15.3045701981 -0.531019449234,1.81177699566,-15.3169374466 -0.581032812595,1.81377065182,-15.325304985 -0.629016399384,1.81074845791,-15.3046703339 -0.657085835934,1.81977891922,-15.3708496094 -0.70710080862,1.82077360153,-15.3812150955 -0.757108986378,1.82176434994,-15.3845815659 -0.808144152164,1.82576990128,-15.4149436951 -0.861202478409,1.83278775215,-15.4683055878 -0.9112226367,1.83578515053,-15.483663559 -0.967321932316,1.84782493114,-15.5780200958 -0.997395634651,1.85685765743,-15.6491956711 -1.05145156384,1.86387395859,-15.7005567551 -1.10348439217,1.86787796021,-15.7289133072 -1.15550100803,1.86987328529,-15.7412805557 -1.20853602886,1.87487816811,-15.7716398239 -1.26156640053,1.87788081169,-15.798002243 -1.28959798813,1.88289070129,-15.8271808624 -1.34362637997,1.88589203358,-15.8515491486 -1.39665400982,1.88989317417,-15.8749094009 -1.44967627525,1.89189147949,-15.8932714462 -1.50471866131,1.89790034294,-15.9316310883 -1.55571317673,1.89688372612,-15.9219999313 -1.60973978043,1.90088391304,-15.9443626404 -1.63574981689,1.90188264847,-15.9525403976 -1.68875837326,1.90287339687,-15.956911087 -1.74480056763,1.90888190269,-15.9952707291 -1.79882097244,1.91187894344,-16.0116348267 -1.85183310509,1.91287195683,-16.0200004578 -1.90585935116,1.91687214375,-16.0423564911 -1.95987772942,1.91986811161,-16.0567188263 -1.98688101768,1.9198628664,-16.0579071045 -2.03989028931,1.92185413837,-16.0632724762 -2.09290146828,1.92284655571,-16.0706348419 -2.14288449287,1.9208240509,-16.0490074158 -2.19589400291,1.92281544209,-16.0543708801 -2.25091123581,1.92481076717,-16.0677394867 -2.30089902878,1.9237909317,-16.0511074066 -2.32790327072,1.92478632927,-16.0532932281 -2.37889671326,1.92376959324,-16.0426616669 -2.42888569832,1.92275059223,-16.0270271301 -2.48289418221,1.92474138737,-16.0314006805 -2.53388905525,1.92472529411,-16.0217666626 -2.58588767052,1.92471122742,-16.0161361694 -2.6368803978,1.92369413376,-16.0045051575 -2.6638906002,1.92569291592,-16.0126838684 -2.717897892,1.92668318748,-16.0160541534 -2.76889181137,1.9266667366,-16.0054206848 -2.82088971138,1.92665231228,-15.9987916946 -2.87389731407,1.928642869,-16.002155304 -2.9289085865,1.93063533306,-16.0095252991 -2.98090529442,1.9306204319,-16.0018959045 -3.00590372086,1.93061327934,-15.9980754852 -3.05991220474,1.93260419369,-16.0024414062 -3.11090159416,1.93158531189,-15.9868173599 -3.16089367867,1.93156838417,-15.9741840363 -3.21490120888,1.93255901337,-15.9775524139 -3.26488852501,1.93153941631,-15.9599237442 -3.28988218307,1.93152964115,-15.9511117935 -3.34087538719,1.93151307106,-15.9394817352 -3.39086389542,1.93049418926,-15.9228544235 -3.43683409691,1.92746627331,-15.8872337341 -3.48581957817,1.92544603348,-15.867606163 -3.53681182861,1.92542910576,-15.8549814224 -3.58479118347,1.92340552807,-15.8283605576 -3.60677742958,1.92239248753,-15.811542511 -3.65776872635,1.92137515545,-15.7979202271 -3.7057518959,1.92035388947,-15.7752923965 -3.75574231148,1.91933631897,-15.7606668472 -3.80473041534,1.9193174839,-15.7430381775 -3.85471820831,1.91829836369,-15.7254180908 -3.90470981598,1.91828155518,-15.7117900848 -3.92669534683,1.91626799107,-15.6939754486 -3.97769093513,1.9162530899,-15.6843471527 -4.02667808533,1.91523396969,-15.6657238007 -4.07466220856,1.91421353817,-15.6441001892 -4.1186299324,1.91118466854,-15.6044845581 -4.16461038589,1.90916275978,-15.5788564682 -4.22363138199,1.91316020489,-15.5962266922 -4.26569128036,1.92218327522,-15.6573848724 -4.32972860336,1.92818832397,-15.6917495728 -4.37871742249,1.92817044258,-15.6751194 -4.4246931076,1.92514610291,-15.6445007324 -4.47268009186,1.92512702942,-15.624871254 -4.50260162354,1.91507649422,-15.5362768173 -4.52249717712,1.90101373196,-15.4196815491 -4.54749345779,1.90100562572,-15.4128694534 -4.58243894577,1.89396703243,-15.3492603302 -4.61939096451,1.88893127441,-15.2916526794 -4.65433740616,1.88189327717,-15.2290458679 -4.69329929352,1.87786281109,-15.1824302673 -4.73426628113,1.87383508682,-15.1418170929 -4.74823045731,1.86981165409,-15.1000175476 -4.772149086,1.85876059532,-15.0064210892 -4.80509471893,1.85272264481,-14.9418172836 -4.83202552795,1.84367775917,-14.8612155914 -4.87299633026,1.84065198898,-14.8236036301 -4.91898298264,1.83963370323,-14.802983284 -4.96597337723,1.83961725235,-14.786359787 -4.98094320297,1.83559703827,-14.7505626678 -5.0219168663,1.8325728178,-14.7159471512 -5.05085897446,1.82553350925,-14.6463432312 -5.08882522583,1.82150614262,-14.6037321091 -5.12979984283,1.8194822073,-14.5691204071 -5.15974617004,1.81244564056,-14.5045175552 -5.20272779465,1.81142532825,-14.4779005051 -5.21669912338,1.80740606785,-14.4431009293 -5.25065946579,1.80337631702,-14.3934879303 -5.29263925552,1.80135548115,-14.3648738861 -5.33161115646,1.79833078384,-14.3272647858 -5.36857938766,1.7943046093,-14.2856550217 -5.40755367279,1.79228103161,-14.2500419617 -5.44953632355,1.79126191139,-14.2244215012 -5.45949983597,1.7862392664,-14.1806287766 -5.49246025085,1.78120970726,-14.1300230026 -5.52642393112,1.77718186378,-14.0834140778 -5.56239271164,1.77415621281,-14.041806221 -5.60036611557,1.77113282681,-14.005197525 -5.64134836197,1.77011370659,-13.9785785675 -5.68132734299,1.76809287071,-13.9479665756 -5.69530344009,1.76507616043,-13.9171686172 -5.73027229309,1.76205098629,-13.8755588531 -5.76824617386,1.75902783871,-13.8389558792 -5.80722522736,1.75700747967,-13.8083410263 -5.84419965744,1.75498509407,-13.77272892 -5.88418197632,1.75396597385,-13.7451124191 -5.91514348984,1.74893760681,-13.6945114136 -5.92912197113,1.74692261219,-13.6667098999 -5.97010374069,1.74490356445,-13.6391029358 -6.01008605957,1.74388468266,-13.611489296 -6.05407857895,1.74387037754,-13.5948667526 -6.11099624634,1.73381197453,-13.4866695404 -6.11295223236,1.72778737545,-13.4338769913 -6.14792442322,1.72476422787,-13.394276619 -6.19291973114,1.72575139999,-13.3806533813 -6.22989702225,1.72373068333,-13.3470478058 -6.26587438583,1.72171020508,-13.3134355545 -6.29784250259,1.71868526936,-13.2688360214 -6.33983325958,1.71867084503,-13.2502117157 -6.34279298782,1.71264779568,-13.2004261017 -6.38077354431,1.71162879467,-13.1698198318 -6.41975736618,1.71061122417,-13.14320755 -6.45373153687,1.7075895071,-13.1056022644 -6.48870849609,1.70556914806,-13.0709934235 -6.52969551086,1.70455288887,-13.0473842621 -6.56968259811,1.70453691483,-13.023768425 -6.58666992188,1.70352625847,-13.0049676895 -6.62665557861,1.70250976086,-12.9803571701 -6.66363763809,1.70149171352,-12.9507455826 -6.70262145996,1.70047414303,-12.9231395721 -6.7396030426,1.6994560957,-12.8935289383 -6.77758693695,1.69843888283,-12.8659181595 -6.81657314301,1.69742286205,-12.8413028717 -6.84457874298,1.69942009449,-12.8434944153 -6.88356542587,1.69840419292,-12.8188781738 -6.93356847763,1.70139527321,-12.8132600784 -6.97055196762,1.70037782192,-12.7846469879 -7.02055454254,1.70236885548,-12.7790279388 -7.06054210663,1.70235335827,-12.7554140091 -7.07051897049,1.69933831692,-12.7236242294 -7.12152385712,1.70133066177,-12.7209978104 -7.14748811722,1.6973054409,-12.6704044342 -7.18847799301,1.69729089737,-12.6487922668 -7.23848104477,1.70028209686,-12.6431694031 -7.2984995842,1.70527982712,-12.6555366516 -7.32847070694,1.70225727558,-12.6119441986 -7.35347318649,1.7032533884,-12.6101284027 -7.39546442032,1.70423972607,-12.5905103683 -7.4434633255,1.70522928238,-12.5798950195 -7.47243356705,1.70220673084,-12.5353021622 -7.52443933487,1.70519912243,-12.5326766968 -7.55841827393,1.70418024063,-12.4980726242 -7.60341310501,1.70516824722,-12.4824581146 -7.62541055679,1.70516216755,-12.4746465683 -7.66740131378,1.70614850521,-12.4540338516 -7.73442745209,1.71314883232,-12.4743995667 -7.75739049911,1.70812404156,-12.4218072891 -7.79737901688,1.70810937881,-12.3981933594 -7.84637928009,1.71109950542,-12.3885755539 -7.89738130569,1.71309018135,-12.3809604645 -7.91837739944,1.71308350563,-12.3711509705 -7.96136903763,1.71407032013,-12.3515386581 -7.99034261703,1.71204972267,-12.3099365234 -8.04434776306,1.71504175663,-12.3063201904 -8.0843372345,1.71502780914,-12.2837018967 -8.12632846832,1.7160140276,-12.262090683 -8.15933799744,1.7190130949,-12.269276619 -8.20633506775,1.72000205517,-12.2556600571 -8.25833797455,1.72299277782,-12.2480459213 -8.28530883789,1.71997201443,-12.2044429779 -8.33430862427,1.72296202183,-12.193821907 -8.37629890442,1.72294807434,-12.1712150574 -8.42529773712,1.72593772411,-12.1595983505 -8.45129966736,1.72693359852,-12.1567840576 -8.49729442596,1.72892177105,-12.140171051 -8.53528022766,1.72790634632,-12.1125612259 -8.58628082275,1.73089635372,-12.1019496918 -8.63327693939,1.73288476467,-12.0863370895 -8.67626857758,1.73387217522,-12.0667181015 -8.72326469421,1.73486053944,-12.0511045456 -8.74626255035,1.73585450649,-12.042298317 -8.79125499725,1.73684179783,-12.022690773 -8.84125423431,1.73983192444,-12.0120687485 -8.89125347137,1.74282181263,-12.0004501343 -8.92323207855,1.74080359936,-11.962852478 -8.96722507477,1.74179112911,-11.9432373047 -9.03624534607,1.74878907204,-11.9575986862 -9.05023193359,1.7477786541,-11.9348087311 -9.09021949768,1.74776434898,-11.9091978073 -9.14922904968,1.75175797939,-11.9095678329 -9.20423316956,1.75574934483,-11.9029474258 -9.26424121857,1.76074254513,-11.9023256302 -9.30422782898,1.76072800159,-11.8757171631 -9.35923194885,1.76371955872,-11.869093895 -9.39023780823,1.76671659946,-11.8702793121 -9.42922210693,1.76670110226,-11.8406791687 -9.48822975159,1.77069365978,-11.8380556107 -9.53822803497,1.77368307114,-11.8244352341 -9.59623241425,1.77767503262,-11.8198127747 -9.65223693848,1.78166663647,-11.8131885529 -9.70923995972,1.78465759754,-11.8055734634 -9.74725055695,1.78865647316,-11.8137559891 -9.79424476624,1.79064452648,-11.7951393127 -9.83923721313,1.79163169861,-11.7735271454 -9.8662109375,1.78961217403,-11.728934288 -9.90719890594,1.79059827328,-11.7033205032 -9.92616462708,1.78657650948,-11.6497335434 -9.92513751984,1.7825615406,-11.608956337 -9.64681816101,1.71944093704,-11.200630188 -9.58370876312,1.69939386845,-11.05311203 -9.61268901825,1.69837749004,-11.0155134201 -9.6346616745,1.69535887241,-10.9689273834 -9.61960124969,1.685328722,-10.8803672791 -9.64157485962,1.68331050873,-10.8347787857 -9.64955997467,1.68130099773,-10.8099784851 -9.66753101349,1.67828178406,-10.760392189 -9.69751167297,1.67726624012,-10.7238006592 -9.72449207306,1.67525017262,-10.6852045059 -9.74246406555,1.67223215103,-10.6376085281 -9.77044391632,1.67121613026,-10.5990200043 -9.78641414642,1.66719734669,-10.5484333038 -9.79239845276,1.66518747807,-10.5216379166 -9.80937004089,1.66216909885,-10.4720535278 -9.82734203339,1.65915083885,-10.4234714508 -9.85332202911,1.65813541412,-10.3848743439 -9.87529945374,1.6561191082,-10.3422803879 -9.89427375793,1.65310180187,-10.2956943512 -9.89625358582,1.65009093285,-10.2639112473 -9.91422748566,1.64707374573,-10.2173213959 -9.93120098114,1.64405655861,-10.1697330475 -9.95117664337,1.64204001427,-10.1251449585 -9.97615814209,1.64002513885,-10.0865497589 -9.9871263504,1.63600635529,-10.0319747925 -10.0151100159,1.6349927187,-9.99737262726 -10.0100860596,1.63198077679,-9.95959281921 -10.0250587463,1.62796354294,-9.91001415253 -10.046037674,1.62594842911,-9.86841964722 -10.0660161972,1.62393295765,-9.8258266449 -10.0789871216,1.62091553211,-9.77425289154 -10.0989656448,1.61890029907,-9.7316608429 -10.1189441681,1.61688518524,-9.6890707016 -10.121928215,1.61387622356,-9.66127967834 -10.1399040222,1.61186039448,-9.61569881439 -10.1588830948,1.60984563828,-9.57310581207 -10.1688537598,1.60582840443,-9.52052974701 -10.1928358078,1.60481476784,-9.48194122314 -10.2058105469,1.60179901123,-9.43435001373 -10.2167835236,1.59778273106,-9.38377094269 -10.2247714996,1.59677517414,-9.36097812653 -10.2387475967,1.59375989437,-9.3143901825 -10.2517232895,1.59074413776,-9.26581287384 -10.2697019577,1.58873009682,-9.22322177887 -10.2896823883,1.58671617508,-9.1816368103 -10.2976541519,1.58270025253,-9.13005542755 -10.3276424408,1.5826883316,-9.09746551514 -10.3366327286,1.58168148994,-9.07666873932 -10.3476076126,1.57866644859,-9.02808570862 -10.3575820923,1.57565116882,-8.97850513458 -10.3785638809,1.57463824749,-8.93891716003 -10.40254879,1.5736259222,-8.90232467651 -10.4215297699,1.57161259651,-8.86074066162 -10.4265174866,1.57060539722,-8.83694553375 -10.4364919662,1.56659066677,-8.78737163544 -10.4554738998,1.56557774544,-8.74678325653 -10.4674510956,1.56256377697,-8.70020103455 -10.4764270782,1.55954933167,-8.65062522888 -10.4924077988,1.55753624439,-8.60803890228 -10.5213956833,1.55752551556,-8.57644081116 -10.4063081741,1.5354988575,-8.45174598694 -10.5193510056,1.54950213432,-8.49108219147 -8.19587135315,1.15811312199,-6.50140619278 -8.21486568451,1.15810680389,-6.47480773926 -8.32689857483,1.16910529137,-6.48056697845 -8.34189033508,1.16809809208,-6.4489865303 -8.3528881073,1.16809499264,-6.43619251251 -8.39789867401,1.17209255695,-6.43057012558 -8.40588569641,1.17008435726,-6.39299964905 -8.4388885498,1.17208015919,-6.37738847733 -8.4718914032,1.1740758419,-6.36078643799 -8.49788951874,1.17507040501,-6.33819389343 -8.5168838501,1.17506420612,-6.31060218811 -8.54188919067,1.17706298828,-6.30780363083 -8.5528793335,1.17605578899,-6.27421617508 -8.57787799835,1.17605054379,-6.25161600113 -8.6148815155,1.17904639244,-6.23701667786 -8.63787841797,1.17904090881,-6.21242141724 -8.66187572479,1.18003535271,-6.1878323555 -8.67687606812,1.18103301525,-6.17803287506 -8.69887161255,1.18102729321,-6.15244007111 -8.73487567902,1.18302345276,-6.13782978058 -8.74986934662,1.18301701546,-6.10723972321 -8.78186988831,1.18401241302,-6.08765125275 -8.80986976624,1.18600749969,-6.06605577469 -8.83586788177,1.18700230122,-6.04345703125 -8.84786701202,1.18699967861,-6.03165626526 -8.8658618927,1.18699359894,-6.00207567215 -8.89386081696,1.18798875809,-5.98047828674 -8.91485691071,1.18798327446,-5.95388698578 -8.95586204529,1.19197964668,-5.94127893448 -8.98986530304,1.19397556782,-5.92367601395 -9.00285625458,1.192969203,-5.89109325409 -9.03386497498,1.19596850872,-5.89227676392 -9.05586242676,1.19696319103,-5.86667823792 -9.07885837555,1.19695770741,-5.84009599686 -9.10185623169,1.19795250893,-5.8145031929 -9.12885475159,1.19894778728,-5.79190397263 -9.1298418045,1.19594049454,-5.75133132935 -9.14483451843,1.19593477249,-5.72074174881 -9.14682865143,1.19393134117,-5.70096063614 -9.16682529449,1.19492590427,-5.67337036133 -9.24084568024,1.20292496681,-5.68073892593 -9.26584339142,1.20392012596,-5.65614509583 -9.29784488678,1.20591580868,-5.63653993607 -10.5764112473,1.39700567722,-6.40699005127 -10.5633955002,1.39300012589,-6.37521791458 -10.5923919678,1.39399325848,-6.34762191772 -10.6403951645,1.39898788929,-6.33200883865 -10.7584295273,1.41298735142,-6.3593454361 -10.8704614639,1.42698597908,-6.381690979 -10.7413873672,1.40396845341,-6.25621700287 -10.7593784332,1.40396106243,-6.22162723541 -10.5632858276,1.3729442358,-6.07999134064 -10.4652280807,1.35593008995,-5.97649097443 -10.439201355,1.34892070293,-5.91693592072 -10.3831624985,1.33790969849,-5.83940887451 -10.069018364,1.28788459301,-5.61206531525 -10.0910129547,1.28887879848,-5.58247900009 -10.1040048599,1.28787267208,-5.54789638519 -9.93593025208,1.26186060905,-5.43023347855 -9.81086730957,1.240847826,-5.31775093079 -9.77384090424,1.23283994198,-5.25620555878 -9.6917963028,1.21783018112,-5.16969442368 -9.65577125549,1.20982289314,-5.1101436615 -9.65475940704,1.20781743526,-5.07056617737 -9.58372116089,1.19480884075,-4.9910569191 -9.53069591522,1.18580412865,-4.94330072403 -9.42164421082,1.16779458523,-4.84481239319 -9.43463897705,1.16679024696,-4.81422519684 -9.33859443665,1.1507819891,-4.72472190857 -8.84340190887,1.07675993443,-4.42252397537 -9.15250778198,1.11876690388,-4.55171012878 -9.16650867462,1.11976528168,-4.54091215134 -9.1624994278,1.11776101589,-4.50234174728 -8.93640995026,1.08275043964,-4.3489317894 -8.91539573669,1.07774627209,-4.30237865448 -8.85936927795,1.06774139404,-4.23884344101 -8.83835506439,1.06273770332,-4.19328689575 -8.74731826782,1.04773247242,-4.11376905441 -8.74031257629,1.04573082924,-4.09298992157 -8.67428398132,1.03372657299,-4.02646064758 -8.63026332855,1.0257229805,-3.97092056274 -8.53322505951,1.00971877575,-3.89041280746 -8.50321102142,1.00371587276,-3.84286141396 -8.51120948792,1.00371384621,-3.81427812576 -8.4331817627,0.991711556911,-3.76054763794 -8.34414768219,0.976708352566,-3.68603682518 -8.30813312531,0.969706177711,-3.63748502731 -8.26111507416,0.961703956127,-3.58394408226 -8.25310897827,0.958702325821,-3.54838252068 -8.15007400513,0.942700088024,-3.46988105774 -8.14507007599,0.940698862076,-3.43730425835 -8.15106964111,0.940698325634,-3.42451548576 -8.0740442276,0.927696824074,-3.35998558998 -8.0450334549,0.922695755959,-3.316437006 -8.02402496338,0.917694866657,-3.27688074112 -7.9620051384,0.907694041729,-3.22034263611 -7.9810090065,0.908693432808,-3.19875907898 -7.89698314667,0.895693063736,-3.13324022293 -7.88597917557,0.892692863941,-3.11445355415 -7.84196615219,0.885692715645,-3.06592059135 -7.84996747971,0.885692417622,-3.0413274765 -7.7949514389,0.875692605972,-2.98978829384 -7.79595136642,0.874692499638,-2.96122002602 -7.74493694305,0.866693019867,-2.91266870499 -7.72193050385,0.861693322659,-2.8751103878 -7.74393701553,0.864693164825,-2.86931800842 -7.63890886307,0.848694741726,-2.79980564117 -7.6159029007,0.84369546175,-2.76324415207 -7.56489086151,0.83569675684,-2.71471977234 -7.57189321518,0.835697233677,-2.69112634659 -7.56289196014,0.832697987556,-2.66055703163 -7.52688312531,0.826699018478,-2.63280034065 -7.49287605286,0.821700453758,-2.59324383736 -7.47987413406,0.81870162487,-2.56167721748 -7.46787261963,0.815702855587,-2.5311024189 -7.4288649559,0.808704733849,-2.48956394196 -7.38085508347,0.801707088947,-2.44601607323 -7.37985658646,0.799708247185,-2.42042851448 -7.35285139084,0.795709550381,-2.39765954018 -7.28683805466,0.785712778568,-2.34714627266 -7.37286090851,0.796711683273,-2.35348892212 -7.28584337234,0.783715724945,-2.29697585106 -7.27884435654,0.781717538834,-2.26841664314 -7.25084114075,0.776720046997,-2.23385357857 -7.24384260178,0.774721980095,-2.20628261566 -7.26984977722,0.777721941471,-2.20247793198 -7.26885271072,0.77572375536,-2.17690443993 -7.22584629059,0.769727051258,-2.13834381104 -7.23885250092,0.769728422165,-2.11775875092 -7.17284202576,0.760732889175,-2.07123041153 -7.15684270859,0.756735563278,-2.04166245461 -7.13384103775,0.752738595009,-2.01009774208 -7.12084054947,0.750740230083,-1.99332630634 -7.49992179871,0.800726294518,-2.08848047256 -7.1688580513,0.755742549896,-1.9601329565 -7.16186094284,0.753745079041,-1.93356275558 -7.36990594864,0.780737876892,-1.97283637524 -7.05584859848,0.737754702568,-1.85347867012 -7.11486244202,0.744753181934,-1.85865902901 -7.02184915543,0.731760025024,-1.80813026428 -7.00985145569,0.729763269424,-1.78056955338 -7.00085496902,0.727766335011,-1.75498890877 -7.10587930679,0.740763604641,-1.76134181023 -7.03787136078,0.730769872665,-1.71782243252 -6.96386289597,0.719776570797,-1.67428648472 -6.9728679657,0.720777571201,-1.66450381279 -6.99187612534,0.722779273987,-1.64690577984 -6.98087930679,0.71978276968,-1.62132513523 -6.90987253189,0.709789872169,-1.57880473137 -6.90987825394,0.709792852402,-1.55622172356 -6.95389175415,0.714793324471,-1.54461801052 -6.88288545609,0.703800737858,-1.5030964613 -6.97590303421,0.715796589851,-1.51622962952 -6.85989046097,0.699806928635,-1.46373832226 -6.84989500046,0.697810769081,-1.43915951252 -6.83389854431,0.695815145969,-1.41259598732 -6.88391256332,0.700815320015,-1.40199041367 -6.91392374039,0.704816758633,-1.38639640808 -6.8709230423,0.697822928429,-1.35384619236 -6.79991579056,0.688829421997,-1.32610523701 -6.78091907501,0.685834109783,-1.30052268505 -6.80392932892,0.687836229801,-1.28294360638 -6.77293157578,0.682841956615,-1.254378438 -6.76793718338,0.681845903397,-1.23179483414 -6.78694725037,0.683848321438,-1.21321940422 -6.76194667816,0.67985188961,-1.19743657112 -6.73895072937,0.676857352257,-1.17087113857 -6.72595643997,0.674862146378,-1.14630424976 -6.73196411133,0.674865603447,-1.12572526932 -6.72096967697,0.672870278358,-1.10214877129 -6.76998376846,0.678870558739,-1.08955228329 -6.7139840126,0.670878827572,-1.05700957775 -6.7199883461,0.670880377293,-1.04722058773 -6.79200458527,0.679878652096,-1.03959095478 -6.72900438309,0.670887708664,-1.00605547428 -6.72301149368,0.669892251492,-0.983480870724 -6.69001483917,0.66489893198,-0.956908106804 -6.71002531052,0.66690158844,-0.938332796097 -6.7620382309,0.673901319504,-0.926706671715 -6.69203472137,0.663909256458,-0.903962314129 -6.67404031754,0.661915063858,-0.879400730133 -6.8240647316,0.680906534195,-0.882731676102 -6.73106241226,0.667918801308,-0.846209585667 -6.68406581879,0.661927163601,-0.817656755447 -6.67907381058,0.660932123661,-0.795094430447 -6.67508125305,0.659936845303,-0.773515880108 -6.67008495331,0.658939421177,-0.762719988823 -6.63809013367,0.653946757317,-0.737158060074 -6.6410984993,0.653951048851,-0.716579496861 -6.64610767365,0.653955221176,-0.696005403996 -6.66211748123,0.655958235264,-0.677414476871 -6.88314533234,0.683942079544,-0.686688005924 -6.81614351273,0.675950586796,-0.666940867901 -6.70114183426,0.659966051579,-0.630438148975 -6.72515296936,0.66296851635,-0.611856579781 -6.68815851212,0.657976686954,-0.586299538612 -6.61816167831,0.648988246918,-0.556768238544 -6.64417266846,0.65199047327,-0.539172053337 -6.64718151093,0.651995003223,-0.518594622612 -6.64618587494,0.650997400284,-0.508792102337 -6.62619352341,0.649004340172,-0.485238194466 -6.62120199203,0.648009598255,-0.464650124311 -6.6422123909,0.650012433529,-0.446060627699 -6.61522006989,0.646020174026,-0.422502279282 -6.68023347855,0.654018521309,-0.407889038324 -6.91825294495,0.684996128082,-0.420935690403 -6.66924619675,0.653026878834,-0.376511067152 -6.61425256729,0.645037889481,-0.349985271692 -6.61026144028,0.645043313503,-0.32940235734 -6.61527109146,0.645047783852,-0.30980989337 -6.62528181076,0.646052002907,-0.289241880178 -6.59528923035,0.642060339451,-0.266676038504 -6.60129451752,0.643062233925,-0.256883144379 -6.60530424118,0.643066883087,-0.237289905548 -6.64631557465,0.64806753397,-0.219684630632 -6.63732481003,0.647073864937,-0.198119282722 -6.60733366013,0.643082499504,-0.175561919808 -6.59434223175,0.641089141369,-0.154978126287 -6.60935306549,0.643092751503,-0.135390505195 -6.6123585701,0.643095254898,-0.124614149332 -6.61136865616,0.643100738525,-0.104037478566 -6.60037755966,0.641107320786,-0.0834575891495 -6.59138727188,0.640113770962,-0.0628795772791 -6.5963973999,0.641118705273,-0.0423061586916 -6.70941114426,0.655110895634,-0.0266511440277 -6.57741212845,0.638129174709,-0.0109515478835 -6.58642292023,0.639133512974,0.00864128116518 -6.55143165588,0.634143233299,0.0301956441253 -6.55744218826,0.635147988796,0.0497878603637 -6.57745361328,0.638151407242,0.070361815393 -6.57046318054,0.637157678604,0.0899541005492 -6.58247423172,0.638162016869,0.110529229045 -6.57847976685,0.638165175915,0.120325185359 -6.57148933411,0.637171804905,0.140895977616 -6.5514998436,0.63417994976,0.161460831761 -6.54751110077,0.634186267853,0.18203048408 -6.57752132416,0.637188255787,0.201636835933 -6.57553243637,0.637194335461,0.222208693624 -6.61154413223,0.642195701599,0.242804378271 -6.56354808807,0.63620454073,0.25257024169 -6.54955863953,0.634211957455,0.272152483463 -6.60257053375,0.641211390495,0.293745219707 -6.56058120728,0.635222494602,0.313304156065 -6.61959171295,0.643220722675,0.333930164576 -6.53860282898,0.633237242699,0.353447198868 -6.53561353683,0.632243454456,0.373035013676 -6.55361938477,0.635244131088,0.383829593658 -6.58063030243,0.638246536255,0.404431849718 -6.59164142609,0.640251100063,0.425018697977 -6.53565263748,0.633264482021,0.443563222885 -6.52466344833,0.631272017956,0.463139712811 -6.60167455673,0.641267955303,0.486755758524 -6.62468004227,0.64426779747,0.497565746307 -6.50469207764,0.629290044308,0.513066649437 -6.52370357513,0.632293581963,0.533665597439 -6.53471517563,0.633298516273,0.555233359337 -6.56272602081,0.637300848961,0.576831459999 -6.57373714447,0.638305425644,0.597423791885 -6.57674837112,0.639311254025,0.618003606796 -6.52875518799,0.633320808411,0.624774456024 -6.51876688004,0.632328510284,0.644347608089 -6.50177907944,0.630337238312,0.663905978203 -6.54378938675,0.635337591171,0.686520278454 -6.54180145264,0.635344326496,0.707089424133 -6.52081394196,0.633353590965,0.725658535957 -6.47582674026,0.627366304398,0.742212593555 -6.61282873154,0.64535009861,0.76309043169 -6.49484395981,0.630373060703,0.773600757122 -6.47885656357,0.628382086754,0.793154299259 -6.46586847305,0.627390265465,0.811733901501 -6.43788194656,0.624400794506,0.829294979572 -6.44189405441,0.624406814575,0.849873185158 -6.43490028381,0.624410927296,0.858670294285 -6.45191192627,0.62641531229,0.881242930889 -6.43092489243,0.624424755573,0.898816943169 -6.41693735123,0.622433423996,0.91738730669 -6.40395021439,0.62144190073,0.935959339142 -6.42596149445,0.62444537878,0.958550274372 -6.41097402573,0.622454047203,0.976136207581 -6.45497894287,0.628451049328,0.991940677166 -6.39599370956,0.62146627903,1.00449442863 -6.41300535202,0.623470664024,1.02707505226 -6.39101886749,0.621480405331,1.04365611076 -6.38203239441,0.620488762856,1.06321561337 -6.40904331207,0.624491512775,1.0868127346 -6.38805675507,0.62150156498,1.10437297821 -6.35506439209,0.617509782314,1.10915696621 -6.34507799149,0.616518080235,1.12773036957 -6.37108945847,0.620520949364,1.15132915974 -6.35210323334,0.618530869484,1.16889095306 -6.36511516571,0.620535612106,1.19048714638 -6.36012840271,0.62054336071,1.21005868912 -6.32514333725,0.616555690765,1.22461760044 -6.30615091324,0.614562034607,1.23139989376 -6.35316085815,0.620561718941,1.25900793076 -6.3501739502,0.620569169521,1.27858698368 -6.38018512726,0.625571608543,1.30417728424 -6.36719846725,0.623580515385,1.32175815105 -6.34721374512,0.621590912342,1.33930897713 -6.35721969604,0.623592913151,1.35110640526 -6.36123180389,0.624599158764,1.37169647217 -6.34624624252,0.622608661652,1.38926637173 -6.34625959396,0.623615860939,1.40983974934 -6.34827232361,0.624622583389,1.43042254448 -6.34228610992,0.623630523682,1.44901025295 -6.33030080795,0.622639775276,1.4675706625 -6.33230733871,0.623643159866,1.47835683823 -6.32232046127,0.622651696205,1.49594569206 -6.33033418655,0.62465775013,1.51851785183 -6.32734727859,0.624665439129,1.53809940815 -6.32136106491,0.624673426151,1.5566868782 -6.32537460327,0.625680148602,1.57826268673 -6.30938243866,0.623686373234,1.58504271507 -6.3143954277,0.624692857265,1.60662388802 -6.33540678024,0.627696573734,1.63122689724 -6.32042169571,0.62670648098,1.64878976345 -6.3144364357,0.626714944839,1.66835772991 -6.28445291519,0.62272721529,1.68191993237 -6.28146648407,0.623735010624,1.70150208473 -6.3144698143,0.627733170986,1.71931684017 -6.32848262787,0.630738377571,1.74389326572 -6.3634929657,0.63573974371,1.77250647545 -6.38050508499,0.638744473457,1.79808580875 -6.3445224762,0.634757757187,1.80965161324 -6.34653568268,0.635764956474,1.83122837543 -6.34754896164,0.636772036552,1.85182034969 -6.33155822754,0.634778618813,1.85859179497 -6.30857419968,0.63278990984,1.87316429615 -6.31658792496,0.633796215057,1.89673686028 -6.36459636688,0.641795575619,1.93034946918 -6.38060855865,0.643800377846,1.95593619347 -6.32862758636,0.637816607952,1.96249246597 -6.30964326859,0.635827302933,1.9780652523 -6.31864976883,0.63782954216,1.99086546898 -6.31066513062,0.637838721275,2.01042628288 -6.33767604828,0.641841650009,2.03902721405 -6.39068412781,0.649840056896,2.07563853264 -6.33670425415,0.643856942654,2.08118796349 -6.45870447159,0.660843610764,2.13883757591 -6.312728405,0.641872823238,2.10653352737 -6.28774547577,0.638884723186,2.12010240555 -6.26276254654,0.635896742344,2.1336684227 -6.25477790833,0.635905742645,2.15224719048 -6.26379060745,0.63791179657,2.17584133148 -6.24780750275,0.636922478676,2.19240570068 -6.26981925964,0.640926480293,2.22099351883 -6.23983001709,0.636935532093,2.22177147865 -6.3508310318,0.652923882008,2.27941083908 -9.42647361755,1.06739592552,3.32146835327 -6.24487304688,0.639958024025,2.28751564026 -6.26488447189,0.643962085247,2.31511855125 -6.2199048996,0.638977944851,2.32166910172 -6.21691942215,0.63898640871,2.34224557877 -6.20292854309,0.637992799282,2.34803080559 -6.2219414711,0.641997516155,2.37661242485 -6.21995592117,0.642005622387,2.39719796181 -6.23396873474,0.645011007786,2.42378687859 -6.20598745346,0.642023921013,2.43535423279 -6.21000146866,0.64403128624,2.45892882347 -6.22000741959,0.646033227444,2.47273826599 -6.22902107239,0.648039698601,2.4983150959 -6.22203683853,0.648048996925,2.51788663864 -6.22605133057,0.649056315422,2.54146647453 -6.24806261063,0.653060078621,2.57107281685 -6.27207422256,0.65806388855,2.60266089439 -6.29908514023,0.663066923618,2.63525795937 -6.29309415817,0.662072360516,2.64502811432 -6.29110908508,0.663080692291,2.66660904884 -6.28312444687,0.663089931011,2.68519902229 -6.28414011002,0.664098083973,2.70876765251 -6.27615594864,0.664107680321,2.72833991051 -6.28117036819,0.666114807129,2.75292420387 -6.27317905426,0.666120231152,2.76071548462 -6.27619314194,0.667127668858,2.78430366516 -6.27520847321,0.668136000633,2.806879282 -6.27822303772,0.670143485069,2.83047032356 -6.27323913574,0.670152783394,2.85203361511 -6.30624914169,0.676154732704,2.88863873482 -6.30126523972,0.677164018154,2.91020584106 -6.29027414322,0.676170110703,2.91699099541 -6.28828907013,0.677178442478,2.93858289719 -6.28130578995,0.677188038826,2.95915198326 -6.27332210541,0.677197694778,2.97873067856 -6.28233623505,0.679204404354,3.00631093979 -6.26235389709,0.678216099739,3.01989555359 -6.25837087631,0.679225444794,3.04245638847 -6.2843747139,0.683224797249,3.06625580788 -6.26439189911,0.681236505508,3.07983994484 -6.28040552139,0.685241997242,3.11141848564 -6.26642274857,0.684252738953,3.12800168991 -6.26543855667,0.685261368752,3.15157580376 -6.28645038605,0.690265655518,3.18517041206 -6.26246976852,0.68827855587,3.19773650169 -6.2634768486,0.688282310963,3.20953798294 -6.26449203491,0.690290510654,3.23411679268 -6.26350784302,0.691299080849,3.25769639015 -6.26052474976,0.692308425903,3.28125905991 -6.26753807068,0.695315063,3.30786180496 -6.26955318451,0.696323156357,3.33343815804 -6.2555642128,0.695330262184,3.33921027184 -6.26557779312,0.698336541653,3.36781001091 -6.25859498978,0.698346555233,3.38937568665 -6.29460382462,0.705347955227,3.43198180199 -6.27862262726,0.704359531403,3.44855237007 -6.25364208221,0.702372729778,3.46012306213 -6.22566318512,0.700386703014,3.47068047523 -6.29265928268,0.710378170013,3.51850295067 -6.25068235397,0.705394685268,3.52106451988 -6.23969984055,0.705405116081,3.53964757919 -6.25371313095,0.709411025047,3.57223463058 -6.23073291779,0.707423985004,3.58480477333 -6.2317481041,0.709432303905,3.61038756371 -6.22076654434,0.709443092346,3.62995576859 -6.22577428818,0.711446583271,3.64574241638 -6.20479297638,0.709458887577,3.65832948685 -6.19881010056,0.710468828678,3.68089723587 -6.20482492447,0.71247625351,3.70948457718 -6.21583890915,0.716482698917,3.74107456207 -6.23085212708,0.719488441944,3.77565741539 -6.20687294006,0.71850168705,3.78723239899 -6.22887659073,0.722501754761,3.81303167343 -6.21389579773,0.72151350975,3.83059859276 -6.22290945053,0.724520146847,3.86119508743 -6.26191854477,0.732521355152,3.91078996658 -6.25993537903,0.733530521393,3.93636369705 -6.21095991135,0.728548645973,3.93292737007 -6.19797086716,0.727555751801,3.93870425224 -6.23997974396,0.735556483269,3.99129509926 -6.42895936966,0.765528202057,4.13396453857 -6.22001552582,0.735577583313,4.03146123886 -6.26802206039,0.745576918125,4.08806562424 -6.16105937958,0.730606853962,4.04858875275 -6.21605682373,0.739600360394,4.09640693665 -6.19607686996,0.738613128662,4.1109752655 -6.18609428406,0.739623606205,4.13056850433 -6.193110466,0.742631316185,4.16313838959 -6.16913127899,0.740644812584,4.17471027374 -6.17614603043,0.743652224541,4.20629835129 -6.17016363144,0.744662284851,4.22987556458 -6.26115369797,0.759648740292,4.30370426178 -6.1651892662,0.746676623821,4.2682390213 -6.15220785141,0.746687948704,4.28682041168 -6.16722154617,0.751693785191,4.32441091537 -6.1722369194,0.753701865673,4.35598993301 -6.15025854111,0.752715289593,4.36955356598 -6.17127037048,0.757720053196,4.4121427536 -6.21226978302,0.765716195107,4.45395898819 -6.23928165436,0.771719872952,4.50154733658 -6.172311306,0.763741970062,4.48310613632 -6.17132854462,0.765751302242,4.51167678833 -6.16534614563,0.766761541367,4.53625440598 -6.20035600662,0.774763464928,4.58985280991 -6.18137645721,0.773776233196,4.60542535782 -6.150390625,0.769786775112,4.59720993042 -6.19539785385,0.779786765575,4.65881109238 -6.15542316437,0.774803817272,4.65937137604 -6.14944124222,0.776813983917,4.6839556694 -6.14945793152,0.778823018074,4.71353626251 -6.14947462082,0.780832052231,4.7431178093 -6.17047834396,0.785832464695,4.77391386032 -6.15449905396,0.785844922066,4.79247951508 -6.14451742172,0.785855710506,4.81406879425 -6.21651887894,0.799850583076,4.89966964722 -6.22453451157,0.803858280182,4.93724346161 -6.1565656662,0.7948808074,4.91480779648 -6.1445851326,0.795892357826,4.93638086319 -6.18058586121,0.80288952589,4.9791932106 -6.14560985565,0.799905717373,4.98276042938 -6.15662479401,0.803912639618,5.02234649658 -6.15664196014,0.806921839714,5.05392217636 -6.13466358185,0.805935442448,5.06749725342 -6.14667797089,0.809942305088,5.10907554626 -6.16069221497,0.814948558807,5.15166711807 -6.15770053864,0.815953552723,5.16446495056 -6.15571832657,0.817963302135,5.19504165649 -6.14673757553,0.818974554539,5.22060728073 -6.15975141525,0.823981046677,5.2631983757 -6.14877080917,0.82499229908,5.28578424454 -6.14078998566,0.826003313065,5.31235265732 -6.15079641342,0.82900595665,5.3371462822 -6.15781164169,0.833013772964,5.37573194504 -6.15582990646,0.836023449898,5.40730905533 -6.14884805679,0.83703404665,5.43389511108 -6.17386007309,0.844038367271,5.48947763443 -6.16587877274,0.846049308777,5.5160574913 -6.14889955521,0.846061944962,5.53463697433 -6.17490243912,0.852061331272,5.57443666458 -6.14992570877,0.851075828075,5.58700227737 -6.15794086456,0.85508364439,5.62858295441 -6.16595554352,0.859090983868,5.66917943954 -6.1559753418,0.860102415085,5.69475841522 -6.15399312973,0.863112270832,5.72833204269 -6.21999597549,0.87810832262,5.82393169403 -6.15901756287,0.869125127792,5.78471469879 -6.20902442932,0.880124628544,5.8672990799 -6.19004535675,0.880137681961,5.88488149643 -6.1630692482,0.879152536392,5.89545536041 -6.13909196854,0.878166854382,5.90902757645 -6.13611125946,0.880177199841,5.94359207153 -6.20910215378,0.895166933537,6.03041315079 -6.14613437653,0.887189090252,6.00697517395 -6.1821436882,0.897191345692,6.07856464386 -6.16316556931,0.897204637527,6.09714078903 -6.14418745041,0.897217929363,6.11571788788 -6.15820121765,0.903224408627,6.16630887985 -6.13622426987,0.902238488197,6.18287658691 -6.1582274437,0.908238530159,6.22268295288 -6.12425374985,0.905255258083,6.22823810577 -6.15326404572,0.914258718491,6.29483413696 -6.16427898407,0.919265985489,6.34441804886 -6.16829586029,0.924274623394,6.38700342178 -6.1513171196,0.924287617207,6.40858078003 -6.14032888412,0.924294710159,6.41736316681 -6.15934181213,0.931300342083,6.47595310211 -6.15436029434,0.934310972691,6.51053142548 -6.27434921265,0.960295855999,6.6751537323 -6.27936553955,0.964304506779,6.72173213959 -6.12542057037,0.940345585346,6.60026693344 -6.17242670059,0.95234555006,6.69086074829 -6.14044380188,0.94835704565,6.67763757706 -6.16645479202,0.957360982895,6.74523973465 -6.13847970963,0.956376373768,6.75680923462 -6.13249874115,0.958387374878,6.79238319397 -6.12351894379,0.961398720741,6.82396554947 -6.18552112579,0.97639554739,6.93357133865 -6.14254999161,0.972414135933,6.92913579941 -6.18354845047,0.982410490513,6.99593877792 -6.17656803131,0.985421657562,7.03151655197 -7.6992058754,1.2821187973,8.78555107117 -7.68322658539,1.28413152695,8.82113361359 -7.65924978256,1.28514611721,8.84870624542 -7.63127422333,1.28516161442,8.87227344513 -7.61329555511,1.28717494011,8.9068479538 -7.60630559921,1.28818106651,8.92564201355 -7.57733058929,1.28819680214,8.9482088089 -7.5583524704,1.28921020031,8.98178386688 -7.53737545013,1.29122436047,9.01434993744 -7.51339864731,1.29223895073,9.0419254303 -7.48942184448,1.29225349426,9.06950187683 -7.48943042755,1.29525828362,9.09729671478 -7.46245479584,1.29627370834,9.12286186218 -7.4324798584,1.29528951645,9.14343643188 -7.41750144958,1.29830265045,9.18400382996 -7.52749013901,1.32628953457,9.375623703 -7.37154769897,1.30033159256,9.24315357208 -3.38160252571,0.493166595697,4.34043693542 -3.38361144066,0.495171070099,4.35623264313 -3.36563515663,0.494184404612,4.35982322693 -3.367654562,0.497194170952,4.39039516449 -7.24367761612,1.30741155148,9.40581512451 -7.2266998291,1.30942499638,9.44438648224 -7.21371221542,1.3104326725,9.45816993713 -7.18973636627,1.31144738197,9.48674869537 -7.17175865173,1.31346106529,9.52432250977 -7.14678287506,1.31447601318,9.55289268494 -7.12180709839,1.31549108028,9.58146476746 -7.11082839966,1.31950330734,9.62903881073 -7.08885097504,1.3215174675,9.65962696075 -7.16883993149,1.34150624275,9.80042648315 -7.16085910797,1.34651768208,9.8520116806 -7.17987203598,1.35752356052,9.94159984589 -7.02493143082,1.33056557178,9.79413223267 -6.89698314667,1.30960178375,9.68068027496 -6.80102682114,1.29463148117,9.6092414856 -6.81004238129,1.30363976955,9.68581771851 -6.81405067444,1.30764400959,9.72360610962 -6.86305570602,1.32564377785,9.8562040329 -6.97204494476,1.35663127899,10.0768117905 -6.57916784286,1.27572238445,9.57928943634 -6.54119634628,1.27374005318,9.58785915375 -6.47123384476,1.26476454735,9.54942321777 -6.44026041031,1.26478099823,9.56799316406 -6.41327667236,1.26179158688,9.5597782135 -6.34831237793,1.25381481647,9.52634906769 -6.29934406281,1.24983513355,9.51791286469 -6.26537179947,1.24885201454,9.53048706055 -6.22540140152,1.245870471,9.5350522995 -6.19142913818,1.24488759041,9.54762554169 -6.14445114136,1.23790228367,9.50740909576 -6.12147569656,1.23891687393,9.53598690033 -6.06750917435,1.23393833637,9.51854705811 -6.02354001999,1.22995758057,9.51511573792 -6.00956201553,1.23397028446,9.55670261383 -5.98358821869,1.23498594761,9.58227062225 -5.96961069107,1.23899888992,9.62584877014 -5.98061752319,1.24500179291,9.67664241791 -6.00362920761,1.25800693035,9.77923679352 -5.98565340042,1.26102077961,9.81781482697 -5.95468091965,1.26103746891,9.83638286591 -5.99768733978,1.27903854847,9.97498035431 -5.96571588516,1.27905547619,9.99354362488 -5.94473981857,1.28106999397,10.0281248093 -5.99873447418,1.29906404018,10.1539268494 -5.97575950623,1.30107867718,10.1855115891 -6.04575872421,1.32607448101,10.3761110306 -5.99479198456,1.32209527493,10.3636760712 -6.03180074692,1.33909785748,10.5012664795 -6.06481075287,1.3561013937,10.6348495483 -6.16079282761,1.38508677483,10.8396654129 -6.02684926987,1.35912442207,10.6832151413 -5.96188592911,1.35114789009,10.6447877884 -6.02088880539,1.37514615059,10.8273801804 -5.99991369247,1.37816083431,10.8699512482 -5.92295408249,1.36718678474,10.8105163574 -5.93097066879,1.3781952858,10.9031076431 -5.88799238205,1.37120914459,10.8648881912 -5.93499851227,1.39320993423,11.0324764252 -5.90402555466,1.39422643185,11.0560560226 -5.87905168533,1.3962417841,11.0916337967 -5.84608030319,1.39725887775,11.1132068634 -5.81110954285,1.39727640152,11.1317749023 -5.78113698959,1.39829289913,11.1583518982 -5.76715040207,1.39930093288,11.1741371155 -5.73817825317,1.40131723881,11.2037115097 -5.70220708847,1.40033471584,11.218290329 -5.67523384094,1.40335059166,11.250869751 -5.64726161957,1.40536653996,11.2824459076 -5.70426464081,1.43136537075,11.4840373993 -5.57930994034,1.40039598942,11.2788009644 -3.74985384941,0.884781479836,7.6809387207 -3.73187923431,0.886795401573,7.70451784134 -3.70090794563,0.884812057018,7.7020907402 -3.64294433594,0.874833881855,7.64166975021 -3.57998275757,0.862857222557,7.57223033905 -3.27727127075,0.843021571636,7.52999734879 -3.0514485836,0.811123967171,7.35465860367 -3.05946588516,0.821132302284,7.43625640869 -3.04649043083,0.825145483017,7.47182798386 -2.95258903503,0.821200311184,7.4723572731 -2.93661379814,0.82321369648,7.49894332886 -2.89764595032,0.818232059479,7.4695110321 -2.87567257881,0.818246722221,7.48109436035 -2.84270262718,0.81526362896,7.46467208862 -2.80874371529,0.815286040306,7.48103618622 -2.78377079964,0.814301133156,7.48362398148 -2.75879907608,0.814316511154,7.48820018768 -2.73382687569,0.813331961632,7.49277591705 -2.69885706902,0.809349000454,7.46736478806 -2.68488168716,0.812362074852,7.50094795227 -2.67489528656,0.813369333744,7.51073265076 -2.64192533493,0.809386134148,7.491314888 -2.58200502396,0.814429223537,7.54604911804 -2.55603265762,0.812444448471,7.54464006424 -2.53505945206,0.813458859921,7.55922412872 -2.52807235718,0.81646579504,7.58000087738 -2.50709867477,0.817479968071,7.59359264374 -2.48012781143,0.81549590826,7.59316205978 -2.47315001488,0.822507321835,7.64975547791 -2.44917750359,0.822522342205,7.65633869171 -2.42020654678,0.820538341999,7.64692306519 -2.3902361393,0.817554652691,7.63549900055 -2.38424825668,0.820560932159,7.65729379654 -2.37627124786,0.827572822571,7.71587610245 -2.25050473213,0.876695394516,8.15191936493 -2.23353028297,0.880708873272,8.18751049042 -2.24053883553,0.890712797642,8.26529502869 -2.21558713913,0.903737962246,8.37547397614 -2.1469476223,1.12692022324,10.1796741486 -2.13297319412,1.13893353939,10.2752475739 -2.12399601936,1.15294539928,10.3908405304 -2.12201738358,1.17195594311,10.5464296341 -2.09904551506,1.17897081375,10.6050081253 -2.11206173897,1.20897853374,10.8426046371 -2.14607191086,1.25498211384,11.1991987228 -2.51099038124,1.54192614555,13.409655571 -2.47202277184,1.54294395447,13.4302425385 -2.43405532837,1.54696166515,13.4628181458 -2.39308857918,1.54798007011,13.4783964157 -2.35312151909,1.54899799824,13.4949827194 -2.31715345383,1.55401551723,13.5425577164 -2.29317092896,1.55202519894,13.5263528824 -2.24720597267,1.54904448986,13.5139293671 -2.2162361145,1.55806076527,13.589512825 -2.1772685051,1.56107854843,13.6150989532 -2.13130354881,1.55809772015,13.6016788483 -2.09533548355,1.56411504745,13.65325737 -2.06935405731,1.56012523174,13.6270456314 -2.05038070679,1.58113920689,13.7916297913 -2.01341295242,1.58615660667,13.8392124176 -1.97944366932,1.59417319298,13.9058017731 -1.93547844887,1.59419214725,13.9133777618 -1.89851057529,1.60020935535,13.967959404 -1.8555444479,1.60122787952,13.9755458832 -1.83756041527,1.60523641109,14.0093345642 -1.81058967113,1.62225198746,14.1469182968 -1.78561782837,1.64126670361,14.2995090485 -1.76364576817,1.66528141499,14.496088028 -1.73067653179,1.6782977581,14.6006765366 -1.68171226978,1.67431724072,14.576259613 -1.65673077106,1.67332732677,14.5650463104 -1.60976588726,1.67134642601,14.5546312332 -1.55780291557,1.66436648369,14.5032100677 -1.51083827019,1.66238558292,14.4917936325 -1.46387386322,1.66040480137,14.484372139 -1.41890871525,1.66142356396,14.4969520569 -1.37294352055,1.66044235229,14.4905376434 -1.3489613533,1.65845191479,14.4763317108 -1.30399632454,1.65947067738,14.4919080734 -1.25703179836,1.6574896574,14.4764928818 -1.21206665039,1.65750837326,14.4840755463 -1.16510224342,1.65652740002,14.4746541977 -1.12013673782,1.65554583073,14.4742431641 -1.07417213917,1.65556466579,14.4738235474 -1.05118966103,1.6545740366,14.4726142883 -1.00522506237,1.65459287167,14.474193573 -0.960259735584,1.65461134911,14.4787788391 -0.91429489851,1.65363013744,14.4713630676 -0.869329512119,1.65364849567,14.4729509354 -0.824364423752,1.65466690063,14.4835338593 -0.777400255203,1.65268599987,14.4721107483 -0.754417836666,1.65269529819,14.4669027328 -0.709452569485,1.65271365643,14.4704885483 -0.664487361908,1.65273189545,14.4760751724 -0.618522763252,1.65275061131,14.4736557007 -0.57155829668,1.64776933193,14.4382381439 -0.527592658997,1.65078747272,14.4628276825 -0.504610478878,1.65179669857,14.4676160812 -0.459645301104,1.65281498432,14.4762010574 -0.413680672646,1.65183353424,14.4717826843 -0.368715405464,1.65185177326,14.4763689041 -0.322750777006,1.65087032318,14.4629516602 -0.277785420418,1.64988839626,14.4575414658 -0.231820896268,1.64890694618,14.454120636 -0.208838656545,1.64891624451,14.4519109726 -0.163873448968,1.64993429184,14.4624986649 -0.118908129632,1.64895236492,14.452088356 -0.0729436054826,1.6469707489,14.4386672974 --0.0179857667536,1.67300736904,13.8788280487 --0.0399683751166,1.67301630974,13.8826198578 --0.0829343572259,1.67203402519,13.8742103577 --0.126899555326,1.67205190659,13.8697910309 --0.169865459204,1.6700694561,13.8563804626 --0.212831184268,1.66508698463,13.8219661713 --0.256796360016,1.66610503197,13.8265476227 --0.278779327869,1.67111372948,13.8643445969 --0.321745038033,1.66813123226,13.8409309387 --0.365710198879,1.66814911366,13.8395118713 --0.408676028252,1.6671667099,13.8280992508 --0.452641278505,1.6681843996,13.8336830139 --0.495607018471,1.66720187664,13.820268631 --0.538572847843,1.66621923447,13.8138580322 --0.559556186199,1.66622781754,13.8106565475 --0.603521466255,1.66724550724,13.8152399063 --0.646487414837,1.66626274586,13.8108291626 --0.690452575684,1.66728055477,13.8104114532 --0.733418226242,1.66529786587,13.7949953079 --0.778383255005,1.66831552982,13.8185796738 --0.799366593361,1.66832399368,13.8163795471 --0.842332482338,1.66834127903,13.8099679947 --0.886297821999,1.66935884953,13.8125534058 --0.930262982845,1.66937637329,13.8091335297 --0.974228858948,1.67139351368,13.8257284164 --1.06115972996,1.67042827606,13.8088951111 --1.0821428299,1.6694368124,13.8006906509 --1.12710821629,1.67245423794,13.8202810287 --1.17107367516,1.67347145081,13.8228673935 --1.21603894234,1.67648887634,13.8364553452 --1.2570053339,1.67250561714,13.8040428162 --1.30296993256,1.67552316189,13.8216247559 --1.34893488884,1.67954075336,13.8442144394 --1.36991834641,1.67854905128,13.8400125504 --1.41488349438,1.68056631088,13.8496007919 --1.45984864235,1.68258368969,13.8581886292 --1.50481402874,1.68460094929,13.8667764664 --1.54777991772,1.68361771107,13.8553638458 --1.59374439716,1.68563532829,13.8639440536 --1.63970947266,1.68865263462,13.8785324097 --1.66169214249,1.68866109848,13.8773269653 --1.70365858078,1.68667781353,13.8599176407 --1.74762427807,1.68769466877,13.8605089188 --1.79159009457,1.6887114048,13.8601007462 --1.83755493164,1.69072878361,13.8696861267 --1.88252019882,1.69174575806,13.8732748032 --1.90850174427,1.69575500488,13.899066925 --1.95646643639,1.70077228546,13.9266605377 --1.99343430996,1.69478785992,13.8722486496 --2.04439759254,1.70080590248,13.9128341675 --2.09336185455,1.70582354069,13.9414243698 --2.13832736015,1.70684027672,13.9420137405 --2.18429231644,1.70785737038,13.9465999603 --2.20627498627,1.70786571503,13.9413919449 --2.2502412796,1.70888209343,13.9389877319 --2.29620623589,1.71089923382,13.9435758591 --2.34217143059,1.71191608906,13.9471635818 --2.38713669777,1.71293282509,13.9457530975 --2.43410158157,1.71494984627,13.953338623 --2.47906708717,1.71596646309,13.9529314041 --2.50504899025,1.71997523308,13.9737300873 --2.55201339722,1.72099232674,13.9773130417 --2.59797883034,1.72300899029,13.9809045792 --2.64494419098,1.72502577305,13.9894971848 --2.69090914726,1.72604250908,13.9880819321 --2.73487520218,1.72705864906,13.9816770554 --2.78483915329,1.73107600212,14.0012655258 --2.80782175064,1.73108422756,14.0010604858 --2.85578656197,1.73410117626,14.0106487274 --2.89975261688,1.73411726952,14.0012407303 --2.94371891022,1.73413348198,13.9918327332 --2.99168372154,1.73714995384,14.0034294128 --3.04164743423,1.74016726017,14.0170125961 --3.06463050842,1.74117529392,14.0198154449 --3.11159610748,1.74319171906,14.0234079361 --3.1575615406,1.74420809746,14.0209980011 --3.20652604103,1.74722492695,14.0315885544 --3.25249147415,1.74824106693,14.028178215 --3.30145597458,1.75125789642,14.0367679596 --3.34242320061,1.74927318096,14.0143623352 --3.37240362167,1.75328242779,14.0401544571 --3.41636991501,1.75329816341,14.0287475586 --3.46833395958,1.75831520557,14.0503416061 --3.51629900932,1.7603315115,14.0529308319 --3.56426358223,1.76234805584,14.0545196533 --3.61122941971,1.76336407661,14.0541124344 --3.65919446945,1.76538038254,14.0577068329 --3.6821770668,1.76638829708,14.0535001755 --3.73314142227,1.76940500736,14.0670928955 --3.78210639954,1.77142131329,14.0716838837 --3.83007144928,1.77343738079,14.0722751617 --3.87703728676,1.77545332909,14.0718736649 --3.92700195312,1.77846956253,14.0794649124 --3.94598603249,1.77647686005,14.0622625351 --3.99795007706,1.78049349785,14.0758543015 --4.0439157486,1.78150904179,14.0684461594 --4.0928812027,1.78352510929,14.0710382462 --4.14484500885,1.78754174709,14.0836324692 --4.19481039047,1.79055774212,14.0912303925 --4.23977661133,1.79057312012,14.0778188705 --4.26675796509,1.79258155823,14.0856122971 --4.31472349167,1.7945971489,14.0852098465 --4.36068964005,1.7946126461,14.0747995377 --4.40965509415,1.79662835598,14.0753927231 --4.46161937714,1.80064463615,14.0859889984 --4.50458621979,1.79965937138,14.0675830841 --4.55655097961,1.80367553234,14.0781822205 --4.58053398132,1.80468320847,14.0759773254 --4.6265001297,1.80469834805,14.0665721893 --4.67746496201,1.80771434307,14.0701627731 --4.72643041611,1.80972969532,14.0707626343 --4.7713971138,1.80974471569,14.0553503036 --4.82436132431,1.81376075745,14.0659475327 --4.87232732773,1.81577599049,14.0615434647 --4.89730978012,1.81678378582,14.0613393784 --4.94627523422,1.81879901886,14.0599374771 --4.99724006653,1.82081472874,14.0605258942 --5.05220460892,1.82583081722,14.0761270523 --5.10117006302,1.82684612274,14.0707168579 --5.15413475037,1.83086180687,14.0793161392 --5.16312170029,1.82486712933,14.0331068039 --5.17809820175,1.81387722492,13.9407091141 --5.19607257843,1.80488777161,13.8553037643 --5.21704673767,1.79589891434,13.7768917084 --5.260014534,1.79591298103,13.7604913712 --5.29198551178,1.79092550278,13.7140865326 --5.34295082092,1.79394066334,13.7166814804 --5.36293506622,1.79394757748,13.7024745941 --5.41190052032,1.79596245289,13.7000694275 --5.45586824417,1.79597651958,13.6846656799 --5.50283479691,1.79699099064,13.6762599945 --5.54480314255,1.7970045805,13.6568593979 --5.59776830673,1.80102002621,13.6624536514 --5.64073610306,1.80103385448,13.6440477371 --5.6717171669,1.8040419817,13.6588506699 --5.71368551254,1.80305552483,13.6374444962 --5.763651371,1.80607032776,13.6350393295 --5.80362033844,1.80508339405,13.6106386185 --5.84858798981,1.80609738827,13.5962333679 --5.89955377579,1.80911195278,13.5968322754 --5.8695526123,1.79111158848,13.4696273804 --5.47564697266,1.64506483078,12.4581928253 --5.37565660477,1.5990588665,12.1267795563 --5.39563179016,1.59306919575,12.0703802109 --5.38061618805,1.57507503033,11.9329633713 --5.41258716583,1.57408702374,11.9055681229 --5.49354457855,1.58810591698,11.9811592102 --5.49453496933,1.58210980892,11.9349622726 --5.4735212326,1.56311476231,11.7895479202 --5.54448127747,1.57413196564,11.8451509476 --5.57745265961,1.57314395905,11.8187494278 --5.57643318176,1.56115150452,11.7193384171 --5.53542566299,1.53615367413,11.5389289856 --5.54240465164,1.52716219425,11.4605236053 --5.41343164444,1.48214888573,11.1483078003 --5.42340946198,1.47415792942,11.0799045563 --5.56434965134,1.5061841011,11.2775087357 --5.59532165527,1.50519585609,11.2501039505 --5.66728210449,1.51621294022,11.3047008514 --5.68925619125,1.51222348213,11.2582921982 --5.61026906967,1.48321664333,11.060090065 --5.67423200607,1.49223268032,11.0986871719 --5.75818872452,1.50625097752,11.1752872467 --5.75117206573,1.49425756931,11.075881958 --5.85112428665,1.51227807999,11.180478096 --5.87509822845,1.50928854942,11.1400728226 --5.91706705093,1.51130139828,11.1336679459 --5.97204256058,1.5223120451,11.1944713593 --6.00901269913,1.52232420444,11.1780653 --6.02398967743,1.51733326912,11.1226682663 --6.03996658325,1.51134264469,11.0682630539 --6.07093906403,1.51035392284,11.0418605804 --6.13790082932,1.5193696022,11.0794563293 --6.17587137222,1.52038168907,11.0650520325 --6.19685602188,1.52138793468,11.0618534088 --6.2478222847,1.52540147305,11.0694465637 --6.27579641342,1.52341210842,11.0370435715 --6.33676052094,1.53142678738,11.0636482239 --6.37573099136,1.53243863583,11.050245285 --6.40770339966,1.53144967556,11.0248432159 --6.46767711639,1.54246044159,11.0876464844 --6.46865844727,1.53346765041,11.0092420578 --6.497631073,1.53247821331,10.9778337479 --6.50161170959,1.52448570728,10.9054288864 --6.56257629395,1.53150010109,10.9290294647 --6.59254932404,1.52951073647,10.8996229172 --6.66551065445,1.53952634335,10.9422264099 --6.67749834061,1.5385311842,10.924030304 --6.73146486282,1.54354465008,10.9326219559 --6.83241844177,1.56056344509,11.0182266235 --6.81340503693,1.54656791687,10.9108228683 --6.86937141418,1.55258131027,10.9224185944 --6.9163403511,1.5555934906,10.9210243225 --6.94931316376,1.55560410023,10.8966226578 --6.90531539917,1.53960239887,10.7884082794 --7.02826404572,1.56162345409,10.9050197601 --7.08523035049,1.56763660908,10.9176216125 --7.17118930817,1.5806530714,10.9742288589 --7.18716621399,1.57566154003,10.9218196869 --7.22413825989,1.57667219639,10.903424263 --7.23712587357,1.57567691803,10.8852214813 --7.27509737015,1.57668793201,10.8668174744 --7.31306886673,1.57669866085,10.8484134674 --7.30805253983,1.56770455837,10.7680139542 --7.40800762177,1.58372211456,10.8406171799 --7.44198036194,1.58373224735,10.8172197342 --7.53193855286,1.59674870968,10.8728189468 --7.56791973114,1.60075581074,10.888625145 --7.61089086533,1.60376679897,10.8772287369 --7.63886547089,1.60177612305,10.8438272476 --7.66783952713,1.60078561306,10.8114233017 --7.7358045578,1.60879898071,10.8350305557 --7.74278450012,1.60180604458,10.7716236115 --7.82074642181,1.61182057858,10.8072252274 --7.98569393158,1.64584136009,10.9990472794 --7.92669200897,1.62484097481,10.8456382751 --7.95766639709,1.62385046482,10.8152351379 --7.94965028763,1.61385560036,10.7318239212 --8.00661754608,1.61986756325,10.7384328842 --8.11557197571,1.63688492775,10.8130426407 --8.13355922699,1.63688969612,10.8018465042 --8.15453624725,1.63389778137,10.7584447861 --8.19550800323,1.63590788841,10.7420492172 --8.22148418427,1.63391649723,10.7046432495 --8.28744888306,1.64092898369,10.7202501297 --8.31542491913,1.63993752003,10.6858472824 --8.41038322449,1.65295302868,10.7374563217 --8.46036148071,1.65996086597,10.7662630081 --8.46634292603,1.65396714211,10.7038602829 --8.55630302429,1.66598176956,10.7474689484 --8.66225814819,1.68199789524,10.8100805283 --8.59225940704,1.65899646282,10.6526632309 --8.66222476959,1.6670088768,10.6702718735 --8.7421875,1.6770222187,10.6988763809 --8.82315826416,1.6910327673,10.7636899948 --8.85713386536,1.69104146957,10.7352905273 --8.85511779785,1.68304657936,10.6638879776 --8.9790687561,1.70206391811,10.7445058823 --8.99704742432,1.69907093048,10.6961021423 --8.97603607178,1.68707418442,10.6016902924 --9.10499572754,1.7110888958,10.7205123901 --9.01700115204,1.68508589268,10.5480928421 --5.51486825943,0.95276081562,6.39215898514 --5.50385284424,0.945766866207,6.33774757385 --5.49983501434,0.940773665905,6.29133176804 --5.49381828308,0.935780107975,6.2439250946 --5.48080348969,0.928785741329,6.18952417374 --5.47079753876,0.924788296223,6.15832090378 --5.46977853775,0.920795321465,6.11690807343 --5.46476221085,0.915801763535,6.0725069046 --5.46774291992,0.911809146404,6.03609418869 --5.45472812653,0.905815005302,5.98268413544 --5.46170806885,0.903822541237,5.95228242874 --5.46368932724,0.899829745293,5.91587305069 --5.45768213272,0.896832644939,5.89067316055 --5.45966339111,0.893839895725,5.85425949097 --5.45264673233,0.888846278191,5.80884885788 --5.43163394928,0.880851387978,5.74944353104 --5.42361783981,0.875857591629,5.70403575897 --5.43159770966,0.873865246773,5.67562818527 --5.4155921936,0.868867397308,5.6404209137 --5.40657663345,0.863873541355,5.59501552582 --5.43055295944,0.864882349968,5.58461952209 --5.49436664581,0.844953000546,5.31475734711 --5.59232521057,0.860967636108,5.37535858154 --5.6593003273,0.871976315975,5.42316770554 --5.61929225922,0.860979855061,5.34975481033 --5.66426324844,0.8659902215,5.35734272003 --5.85618305206,0.895018160343,5.47056627274 --5.68520545959,0.860011875629,5.27412605286 --5.67218208313,0.853020787239,5.2115187645 --5.66716527939,0.849027037621,5.17311048508 --5.68914365768,0.850035130978,5.1607170105 --5.72111797333,0.853044390678,5.15530014038 --5.74309539795,0.854052305222,5.14290904999 --5.77407121658,0.857061088085,5.13750696182 --5.80005645752,0.860066235065,5.14430904388 --5.81803417206,0.860074043274,5.12690401077 --5.84501075745,0.862082660198,5.11648797989 --5.88298463821,0.866091489792,5.11810445786 --5.89496469498,0.865098893642,5.09469175339 --5.92494058609,0.868107438087,5.08728551865 --5.96091508865,0.871116161346,5.08589267731 --5.98090171814,0.87312066555,5.08669424057 --5.99988031387,0.874128401279,5.06928491592 --6.05585050583,0.881138443947,5.08388853073 --6.07982730865,0.882146418095,5.07048034668 --6.11680269241,0.886154949665,5.06908893585 --6.15577697754,0.890163660049,5.06869220734 --6.16175794601,0.888170421124,5.03927230835 --6.19374275208,0.892175376415,5.05008649826 --6.23671579361,0.897184312344,5.05168056488 --6.25869369507,0.898191809654,5.03627681732 --6.29666852951,0.90220028162,5.03387737274 --6.3266453743,0.904208242893,5.0244717598 --6.35362243652,0.906215846539,5.01307296753 --6.38659906387,0.909223794937,5.00667905807 --6.41958284378,0.913228869438,5.01547288895 --6.44955968857,0.916236519814,5.0060749054 --6.47753763199,0.91824388504,4.99568557739 --6.50651407242,0.92025154829,4.98427629471 --6.53949069977,0.92325925827,4.97688007355 --6.57246685028,0.926267027855,4.96847391129 --6.6154499054,0.932272255421,4.98528623581 --6.63342905045,0.932279169559,4.96487474442 --6.67540407181,0.936287164688,4.96347951889 --6.69638299942,0.937293946743,4.94607973099 --6.74235677719,0.942302167416,4.94667768478 --6.79532909393,0.949310600758,4.95227909088 --5.58956623077,0.744252979755,4.0316491127 --5.58655786514,0.742256104946,4.01544189453 --5.58753967285,0.740262627602,3.98802423477 --6.90525007248,0.958335578442,4.91588687897 --6.96422147751,0.965344071388,4.92448854446 --6.99319934845,0.967350840569,4.91209506989 --7.02517700195,0.970357894897,4.9006896019 --7.07615089417,0.976365625858,4.90329742432 --7.09713840485,0.978369355202,4.90109825134 --7.1451125145,0.983376920223,4.90070056915 --7.19208717346,0.988384366035,4.89930295944 --7.21906661987,0.990390658379,4.88491392136 --7.2640414238,0.995397865772,4.88151359558 --7.29801893234,0.998404622078,4.87010812759 --7.34799337387,1.00341176987,4.87072372437 --7.37398004532,1.00641560555,4.87051868439 --7.42595434189,1.01242268085,4.87112379074 --7.46493148804,1.01642942429,4.86272525787 --7.50490808487,1.0204359293,4.85533428192 --7.54688453674,1.02444255352,4.84894275665 --7.59286022186,1.02944922447,4.84454727173 --7.6278386116,1.03245532513,4.83315420151 --7.67082214355,1.0384594202,4.84295368195 --7.71679830551,1.04346597195,4.83755540848 --7.74677753448,1.04547190666,4.82215881348 --7.72776603699,1.03947579861,4.77575016022 --7.77174282074,1.04448211193,4.76834821701 --7.89270496368,1.06149089336,4.80998134613 --7.9286904335,1.06549441814,4.81478691101 --7.9646692276,1.06950008869,4.80239391327 --8.02564334869,1.07650661469,4.80399513245 --8.08061790466,1.08251285553,4.80260658264 --8.12259483337,1.08651840687,4.793217659 --8.16757202148,1.09152436256,4.7838101387 --8.22554779053,1.09753024578,4.78342485428 --8.26153373718,1.10253345966,4.7872338295 --8.31450939178,1.10853922367,4.7828412056 --8.37148475647,1.11454486847,4.78044986725 --8.42446136475,1.12055039406,4.77606487274 --8.48243713379,1.12755596638,4.77367544174 --8.55141067505,1.13556182384,4.77627849579 --8.60538673401,1.14156711102,4.77088832855 --8.66436958313,1.14957046509,4.78670787811 --11.8127765656,1.6276538372,6.41636705399 --11.855758667,1.63065636158,6.39097642899 --11.9427318573,1.64065957069,6.38960027695 --12.0207080841,1.64966261387,6.38221693039 --12.0686950684,1.65566408634,6.38403463364 --12.1256742477,1.66166639328,6.36565351486 --12.2076501846,1.67066919804,6.35927200317 --12.2386341095,1.67267072201,6.32587766647 --12.2486219406,1.67067193985,6.28147745132 --12.2596092224,1.66967308521,6.23808050156 --12.3025922775,1.67267477512,6.21069002151 --8.08427429199,1.03061318398,3.99487996101 --8.09525775909,1.02961742878,3.96747040749 --8.06724834442,1.0236209631,3.92105579376 --8.07323360443,1.02262508869,3.89164805412 --8.07521915436,1.02162897587,3.86125135422 --8.08420467377,1.02063298225,3.83385014534 --8.07219982147,1.01763486862,3.81163883209 --8.0591878891,1.01463854313,3.77423763275 --8.06817245483,1.01364254951,3.74683380127 --8.06415939331,1.01164638996,3.71342778206 --8.05514717102,1.00865018368,3.67701053619 --8.06113147736,1.00765407085,3.64860868454 --8.04912662506,1.00465595722,3.62740254402 --8.04711341858,1.00265979767,3.59499263763 --8.04610061646,1.00066363811,3.56358838081 --8.05408477783,1.00066745281,3.53618454933 --8.0460729599,0.997671186924,3.50177836418 --8.07305526733,0.999674975872,3.4833855629 --8.12303447723,1.00567889214,3.47398519516 --8.16602134705,1.01068079472,3.47779965401 --8.2289981842,1.01868450642,3.4744143486 --8.29297542572,1.02568805218,3.4710290432 --8.34595489502,1.03269159794,3.462641716 --8.41893196106,1.04169487953,3.46225810051 --8.45991230011,1.0456982851,3.44786453247 --8.52189064026,1.05270147324,3.44147014618 --8.57587623596,1.05970287323,3.44828724861 --8.63385486603,1.06670582294,3.4398958683 --8.73182868958,1.07970845699,3.44751644135 --11.7073993683,1.51069390774,4.62205076218 --11.7073898315,1.50869464874,4.57864665985 --11.7043800354,1.50569522381,4.53424215317 --11.7023715973,1.5036958456,4.49084281921 --11.6963682175,1.50169622898,4.46663618088 --11.6893596649,1.49869680405,4.42123270035 --11.6843509674,1.49569737911,4.37683105469 --11.6843414307,1.49369800091,4.33342027664 --11.687330246,1.49269843102,4.29201793671 --11.6843223572,1.48969888687,4.24861526489 --11.6853122711,1.48769938946,4.20721817017 --11.6693105698,1.4846997261,4.18000984192 --11.6832990646,1.48469996452,4.14361763 --11.6632928848,1.47970068455,4.09420681 --11.6542844772,1.47670137882,4.04879808426 --11.66127491,1.4757014513,4.00939655304 --11.6552667618,1.47370195389,3.96599555016 --11.6392641068,1.46970236301,3.93979072571 --11.6502542496,1.46970248222,3.90239405632 --11.6422462463,1.46670293808,3.85798668861 --11.6292390823,1.46270346642,3.81157255173 --11.6412286758,1.46270334721,3.77518105507 --11.652217865,1.46270334721,3.73778271675 --11.6512098312,1.46070349216,3.69637989998 --11.6272087097,1.45670413971,3.66716170311 --11.5052146912,1.43770742416,3.5877263546 --11.4822072983,1.4327082634,3.53930854797 --11.5011968613,1.43370783329,3.50592017174 --11.4851903915,1.42970848083,3.46050953865 --11.5001802444,1.43070828915,3.42511200905 --11.4791736603,1.42570900917,3.37870240211 --11.4821691513,1.42570900917,3.35950016975 --11.4671621323,1.4217094183,3.31509160995 --11.4701528549,1.42070949078,3.27669405937 --11.4671459198,1.41870951653,3.23629164696 --11.4651374817,1.41670966148,3.19588565826 --11.4731283188,1.41670942307,3.15848302841 --11.472120285,1.41570937634,3.11908340454 --11.4601173401,1.41270983219,3.09587645531 --11.4511098862,1.40971004963,3.05346441269 --11.4710998535,1.41170918941,3.02007126808 --11.4520931244,1.40770983696,2.97566127777 --11.4700832367,1.40870893002,2.94126296043 --11.4530773163,1.40470945835,2.89785599709 --11.4560689926,1.40370905399,2.86046218872 --11.4460668564,1.40170943737,2.83825540543 --11.4440593719,1.40070915222,2.79885101318 --11.4470500946,1.39970886707,2.76044487953 --11.4680404663,1.4007076025,2.72705030441 --11.4420347214,1.39670836926,2.68163466454 --11.4300279617,1.39370858669,2.6402285099 --11.4500188828,1.39470732212,2.60683560371 --11.5070104599,1.40170443058,2.60064935684 --11.5060033798,1.40070390701,2.56225085258 --11.5549907684,1.40670108795,2.53486394882 --11.5919809341,1.41069865227,2.50447273254 --11.6079730988,1.41169714928,2.47008347511 --11.6239643097,1.4126957655,2.434684515 --11.5549621582,1.40169858932,2.38025021553 --11.5259618759,1.39769983292,2.35504150391 --11.6079483032,1.40769469738,2.33467364311 --11.7729282379,1.42868471146,2.33032679558 --11.7999200821,1.43168222904,2.29693436623 --11.8249111176,1.43467986584,2.26354718208 --11.8769006729,1.44067573547,2.234156847 --11.8928928375,1.44167363644,2.19876742363 --11.9408864975,1.44767022133,2.18858456612 --11.9428806305,1.44666874409,2.14917874336 --11.4529085159,1.37869727612,2.01658630371 --11.4738998413,1.3806951046,1.98319542408 --11.7478752136,1.41667699814,1.99589979649 --11.5338821411,1.38668942451,1.91841053963 --11.2478981018,1.34770715237,1.8491063118 --12.0338411331,1.45365524292,1.94899654388 --11.3758764267,1.36269712448,1.79734885693 --11.3038749695,1.35270094872,1.74791705608 --11.3258666992,1.35469841957,1.71452152729 --11.2868623734,1.34870028496,1.67110192776 --11.3958501816,1.36269152164,1.65174245834 --11.2778530121,1.3456993103,1.61449408531 --11.2748470306,1.34469842911,1.57708716393 --11.309838295,1.34869492054,1.54569792747 --11.3188323975,1.34969305992,1.51029849052 --11.2838277817,1.34369456768,1.46888613701 --11.3808164597,1.35668611526,1.44551587105 --11.2958145142,1.34369134903,1.39708161354 --11.2348146439,1.33569538593,1.370860219 --11.2198095322,1.33269536495,1.33245074749 --11.2428026199,1.33569228649,1.29905545712 --11.2357969284,1.33369159698,1.26164758205 --11.1967926025,1.32769334316,1.22022545338 --11.2127857208,1.32969081402,1.18582630157 --11.2937774658,1.33968269825,1.15945863724 --11.2427768707,1.33268630505,1.1352353096 --11.2157716751,1.32868719101,1.09581935406 --11.211766243,1.3276860714,1.05941593647 --11.1837615967,1.32268702984,1.02100872993 --11.2057552338,1.32568359375,0.986606001854 --11.2487478256,1.33067834377,0.955223917961 --11.2477436066,1.33067679405,0.918817877769 --11.2537403107,1.33067548275,0.901621878147 --11.2367353439,1.32767534256,0.864214658737 --11.2087306976,1.32367622852,0.824789583683 --11.2357254028,1.32667195797,0.791399717331 --11.3137187958,1.33766293526,0.762030184269 --11.3367128372,1.33965885639,0.727636516094 --11.2387123108,1.3266671896,0.70240020752 --11.1747093201,1.31767165661,0.660962343216 --11.238702774,1.32566356659,0.629583001137 --11.2746973038,1.33065807819,0.596195161343 --11.3006925583,1.33365356922,0.5618019104 --11.3066883087,1.33365082741,0.526404678822 --11.1846847534,1.31666111946,0.48294827342 --11.2476797104,1.32565283775,0.451580137014 --11.2196769714,1.32165455818,0.431358069181 --11.1936740875,1.31765520573,0.394951671362 --11.2166690826,1.32065069675,0.35954862833 --11.1876649857,1.31665158272,0.323140084743 --11.3256597519,1.33463454247,0.292790144682 --11.3666553497,1.33962774277,0.258405536413 --11.2426519394,1.32363903522,0.217950493097 --11.2776498795,1.32763385773,0.200758501887 --11.2866458893,1.3286305666,0.165361508727 --11.1606416702,1.31164228916,0.12590329349 --11.1396369934,1.30864238739,0.0904978886247 --11.1146335602,1.30564296246,0.0540784150362 --11.2706308365,1.32662236691,0.0217443518341 --11.2386283875,1.32162487507,0.0035317230504 --11.1666240692,1.31163072586,-0.0339111015201 --11.2256212234,1.31962120533,-0.0682829841971 --11.2626180649,1.32461416721,-0.10366986692 --11.2346143723,1.32161474228,-0.140091344714 --11.2326116562,1.32061243057,-0.175491824746 --11.2446079254,1.3226082325,-0.210886225104 --11.2406072617,1.32160723209,-0.22909347713 --11.2916040421,1.32859802246,-0.265477836132 --11.351603508,1.33658742905,-0.301853299141 --11.259598732,1.32459628582,-0.33629244566 --11.5126008987,1.35856068134,-0.376587837934 --11.2785921097,1.32758772373,-0.409100294113 --11.2285890579,1.32059133053,-0.443522244692 --11.2235870361,1.31959044933,-0.460720002651 --11.4115896225,1.34556233883,-0.502045214176 --11.2515821457,1.32358050346,-0.533520460129 --11.2765808105,1.32757389545,-0.569909989834 --11.2515773773,1.32457399368,-0.605329692364 --11.2165746689,1.31957554817,-0.639748752117 --11.2645730972,1.32656562328,-0.6771261096 --11.1985692978,1.31757318974,-0.692360281944 --11.3175725937,1.333553195,-0.733709871769 --11.3075695038,1.33255112171,-0.769116163254 --11.3185691833,1.33454585075,-0.806523323059 --11.428571701,1.34952640533,-0.848876297474 --11.2545623779,1.32654798031,-0.874353885651 --11.2925624847,1.33153879642,-0.912740588188 --11.2895612717,1.33153736591,-0.930948078632 --11.274559021,1.32953608036,-0.96535140276 --11.2905578613,1.33252990246,-1.00275051594 --11.3215579987,1.3365213871,-1.04113948345 --11.2675542831,1.32952570915,-1.07357275486 --11.274553299,1.33152079582,-1.10997092724 --11.3465566635,1.34150576591,-1.15234386921 --11.3845586777,1.34649789333,-1.1735253334 --11.3385543823,1.34050095081,-1.20595061779 --11.3115510941,1.33750104904,-1.23936188221 --11.3195514679,1.33949565887,-1.27676594257 --11.4185581207,1.35347568989,-1.32312679291 --11.4395589828,1.35646796227,-1.36151599884 --11.3425512314,1.3434792757,-1.38796329498 --11.2995481491,1.33848416805,-1.40219175816 --11.311548233,1.34047782421,-1.43958687782 --11.3745527267,1.34946298599,-1.4829595089 --11.3725528717,1.34945881367,-1.51936411858 --11.3765525818,1.35045361519,-1.5567690134 --11.3735523224,1.35044944286,-1.59317493439 --11.3795537949,1.35244369507,-1.63057518005 --11.3655529022,1.35044384003,-1.64677929878 --11.5145654678,1.37141335011,-1.70311450958 --11.4225578308,1.35942423344,-1.72856724262 --11.4085569382,1.35842204094,-1.76297056675 --11.4835653305,1.36940383911,-1.81033754349 --11.4315605164,1.36240792274,-1.84077298641 --11.4705648422,1.36839842796,-1.86495614052 --11.474565506,1.36939263344,-1.90235316753 --11.4965686798,1.37338340282,-1.94274401665 --11.4545660019,1.36838579178,-1.97417354584 --11.4895706177,1.37437415123,-2.01655578613 --11.4825716019,1.37337005138,-2.05296373367 --11.5485801697,1.38335227966,-2.10133647919 --11.5085763931,1.37835693359,-2.11355781555 --11.4945764542,1.37735402584,-2.14897012711 --11.5665864944,1.38833475113,-2.1993432045 --11.5765895844,1.39032709599,-2.23873972893 --11.6405992508,1.40030896664,-2.28811192513 --11.6866064072,1.40729415417,-2.3344912529 --11.6546049118,1.40329432487,-2.36690998077 --11.6686086655,1.40628862381,-2.38809919357 --11.5916013718,1.39629769325,-2.41254758835 --11.6016054153,1.399289608,-2.45294976234 --11.600607872,1.39928376675,-2.49034643173 --11.6126127243,1.40227508545,-2.53175187111 --11.7066278458,1.41624963284,-2.58910775185 --11.7396354675,1.42223644257,-2.63449335098 --11.7496385574,1.42323112488,-2.65568637848 --11.788646698,1.43021643162,-2.70307254791 --11.7386436462,1.42422008514,-2.73150134087 --11.8966693878,1.44718027115,-2.8048248291 --11.8906726837,1.4471745491,-2.84323263168 --11.9156799316,1.45216214657,-2.88862514496 --11.9026832581,1.4511578083,-2.92503094673 --11.8946838379,1.45115590096,-2.94323849678 --11.9807024002,1.46413004398,-3.00360417366 --12.0167121887,1.47011482716,-3.05198717117 --12.1387357712,1.48808062077,-3.12132716179 --12.1487436295,1.49107062817,-3.16472744942 --12.1007404327,1.48507332802,-3.19415831566 --12.1777582169,1.49704837799,-3.25351643562 --12.2487726212,1.50802850723,-3.291680336 --12.2257757187,1.50602555275,-3.3270945549 --12.1747732162,1.50002884865,-3.35552573204 --12.3778133392,1.52997422218,-3.44982600212 --12.4848384857,1.54594099522,-3.52017474174 --12.4348363876,1.5409437418,-3.54960751534 --12.4888534546,1.54992258549,-3.60597705841 --12.4898576736,1.55091762543,-3.62818408012 --12.4788637161,1.55091130733,-3.66759133339 --12.5858898163,1.56687700748,-3.73993682861 --12.6189031601,1.57285988331,-3.79232239723 --12.8189496994,1.60280227661,-3.89362835884 --12.8059558868,1.60279583931,-3.93303012848 --12.8839797974,1.61476683617,-4.00039577484 --13.1440343857,1.65269827843,-4.09946298599 --13.1090373993,1.648696661,-4.13387918472 --13.0240306854,1.63870692253,-4.15433359146 --12.9870319366,1.63570582867,-4.18775272369 --13.1490755081,1.65965461731,-4.28307247162 --13.0950737,1.65465760231,-4.31149959564 --13.1370887756,1.66164159775,-4.3476805687 --13.236120224,1.67660546303,-4.42503213882 --13.3211488724,1.69057250023,-4.49838829041 --13.3191595078,1.69256162643,-4.54479551315 --13.4652023315,1.71451234818,-4.63911819458 --13.4722166061,1.71749889851,-4.68851518631 --13.4282178879,1.71349859238,-4.72093868256 --13.5732564926,1.73545432091,-4.79406833649 --13.5832719803,1.73843944073,-4.8454656601 --13.5782833099,1.74042856693,-4.89187145233 --13.5742950439,1.74141740799,-4.9382724762 --13.5523033142,1.74041092396,-4.97868585587 --13.5503168106,1.74239909649,-5.02608776093 --13.6733589172,1.76235258579,-5.1194319725 --13.6643629074,1.7623488903,-5.13962984085 --13.9654502869,1.80725300312,-5.29786920547 --14.196521759,1.84217536449,-5.43315029144 --14.0575027466,1.82520008087,-5.43262624741 --14.2415647507,1.85413467884,-5.55192756653 --14.3866167068,1.87707936764,-5.65825128555 --14.5006628036,1.89603221416,-5.75459671021 --14.7227363586,1.92995393276,-5.89187145233 --14.8987913132,1.95689570904,-5.98697805405 --15.0608510971,1.98283314705,-6.10428953171 --14.9948530197,1.97583639622,-6.13272285461 --15.0848970413,1.99179375172,-6.22407960892 --15.5680465698,2.06463527679,-6.47321510315 --15.6770973206,2.08358573914,-6.57455587387 --15.7081165314,2.0895678997,-6.61573696136 --15.8771848679,2.1164996624,-6.74304389954 --15.9372243881,2.1284635067,-6.82640981674 --16.081287384,2.15240168571,-6.94573068619 --16.3023757935,2.18831562996,-7.09901046753 --16.3874225616,2.20327019691,-7.19535970688 --16.4214572906,2.2112402916,-7.27174425125 --16.4234695435,2.21322965622,-7.30294084549 --16.4415016174,2.21920442581,-7.37233018875 --16.4115180969,2.21819376945,-7.42074584961 --16.3995399475,2.22017741203,-7.47815752029 --16.4025650024,2.22315597534,-7.54155635834 --16.4025917053,2.22713589668,-7.60395765305 --16.3756122589,2.2261235714,-7.65437459946 --16.3786239624,2.2281126976,-7.68657064438 --16.380651474,2.23209142685,-7.74996900558 --16.3836803436,2.23606944084,-7.81436920166 --16.3817062378,2.23904943466,-7.87576675415 --16.3777332306,2.2420296669,-7.93717050552 --16.3677558899,2.24401211739,-7.99557542801 --16.3687858582,2.24799013138,-8.05997848511 --16.3687992096,2.24997973442,-8.09117507935 --16.3728294373,2.25395655632,-8.15757751465 --16.3758602142,2.25893378258,-8.22297668457 --16.370885849,2.26191401482,-8.28437805176 --16.3539085388,2.26289772987,-8.34079170227 --16.3859481812,2.27086472511,-8.4211730957 --16.3859786987,2.27484250069,-8.48557090759 --16.3889942169,2.2778301239,-8.51977062225 --16.3930244446,2.28180623055,-8.58717060089 --16.3920555115,2.28578424454,-8.65156936646 --16.3810825348,2.28876519203,-8.71197891235 --16.3901176453,2.29373884201,-8.78237533569 --16.3981513977,2.29871344566,-8.85176563263 --16.3901805878,2.30169296265,-8.9141740799 --16.4011993408,2.30567717552,-8.95336914062 --16.4032306671,2.30965304375,-9.02076721191 --16.3882579803,2.3116350174,-9.07917499542 --16.3922920227,2.31660938263,-9.1485748291 --16.3743190765,2.31859207153,-9.20598697662 --16.3753509521,2.32256746292,-9.27438926697 --16.3543758392,2.32355117798,-9.3297996521 --16.3433895111,2.32454276085,-9.35801029205 --16.3394203186,2.32852005959,-9.42341327667 --16.35846138,2.33548855782,-9.50180053711 --16.3274841309,2.33547520638,-9.55322360992 --16.2965068817,2.33546209335,-9.60364151001 --16.2725315094,2.33544635773,-9.65805435181 --16.270565033,2.34042191505,-9.72545623779 --16.2635803223,2.34141182899,-9.7566652298 --16.2456073761,2.34339332581,-9.81507778168 --16.2396411896,2.34737038612,-9.8804807663 --16.2196674347,2.34835267067,-9.93789291382 --16.2066993713,2.35133218765,-9.99929904938 --16.1807231903,2.35231637955,-10.0537176132 --16.1587505341,2.35329914093,-10.1101312637 --16.1647720337,2.35728359222,-10.1493310928 --16.152803421,2.35926222801,-10.2117366791 --16.137834549,2.36224198341,-10.273147583 --16.1338710785,2.36621689796,-10.3415527344 --16.1249027252,2.37019371986,-10.4069595337 --16.1149368286,2.37417078018,-10.4723701477 --16.122959137,2.37715435028,-10.5125617981 --16.1139945984,2.38113045692,-10.5789718628 --16.1080303192,2.38510584831,-10.6463727951 --16.1050682068,2.39007949829,-10.7167778015 --16.1021060944,2.39505267143,-10.7881860733 --16.0921440125,2.39902925491,-10.8535890579 --16.1732215881,2.41696643829,-10.9809446335 --16.4433727264,2.46383666992,-11.1969795227 --16.5524673462,2.4867606163,-11.3453159332 --16.6045360565,2.50070810318,-11.4566879272 --16.5155353546,2.49171710014,-11.4721403122 --16.4255332947,2.48272609711,-11.4876003265 --16.3385334015,2.47473454475,-11.5030508041 --16.2915554047,2.47272515297,-11.5474853516 --16.2545585632,2.4697265625,-11.5597076416 --16.1975727081,2.46572184563,-11.5961446762 --16.1345844269,2.46171975136,-11.62758255 --16.0725975037,2.45771718025,-11.661028862 --16.0216140747,2.45471000671,-11.7004585266 --15.954624176,2.44971013069,-11.7289018631 --15.8896341324,2.44470953941,-11.7583436966 --15.8536376953,2.44171071053,-11.770567894 --15.8146619797,2.44169807434,-11.8189954758 --15.7336626053,2.4337053299,-11.8354444504 --15.6856832504,2.43169641495,-11.8778829575 --15.6096858978,2.42470169067,-11.8973283768 --15.5907211304,2.42767977715,-11.9597425461 --15.5077209473,2.42068791389,-11.9752016068 --15.4617176056,2.41569471359,-11.9774246216 --15.4057312012,2.4126906395,-12.0118627548 --15.3467445374,2.40868759155,-12.0443058014 --15.2857561111,2.4046857357,-12.0747489929 --15.2237663269,2.40068507195,-12.103187561 --15.1677808762,2.39668083191,-12.1376304626 --15.1167974472,2.39467477798,-12.1740617752 --15.0687923431,2.38968253136,-12.1752958298 --15.0098047256,2.38568019867,-12.2057352066 --14.9608230591,2.38367319107,-12.2441701889 --14.8838233948,2.37668037415,-12.2596206665 --14.8068237305,2.37068748474,-12.2750740051 --14.8078727722,2.37665510178,-12.3534765244 --14.7388782501,2.3716583252,-12.3749237061 --14.7098836899,2.36965703964,-12.3901443481 --14.6548986435,2.36665344238,-12.4225816727 --14.5919065475,2.3626537323,-12.4480247498 --14.5509300232,2.36164283752,-12.4924573898 --14.4929409027,2.35864067078,-12.5218982697 --14.4409570694,2.35663580894,-12.5563344955 --14.3929758072,2.35462856293,-12.5937690735 --14.3559761047,2.35163187981,-12.6009922028 --14.3079948425,2.34962439537,-12.6394309998 --14.2530069351,2.34662127495,-12.6698665619 --14.2120313644,2.34661006927,-12.714302063 --14.1450357437,2.34161376953,-12.7337446213 --14.0920505524,2.3386092186,-12.7671871185 --14.0610809326,2.34059333801,-12.8186092377 --14.0200777054,2.33659911156,-12.8218374252 --13.9710950851,2.33459305763,-12.8572721481 --13.9211120605,2.33258676529,-12.8927116394 --13.8781337738,2.33257699013,-12.9341468811 --13.8241472244,2.32957363129,-12.9645833969 --13.7851715088,2.32956194878,-13.009013176 --13.7491722107,2.32656526566,-13.0162401199 --13.7021913528,2.32555770874,-13.0536775589 --13.6652154922,2.32654500008,-13.0991020203 --13.6062269211,2.32254433632,-13.1255493164 --13.5712547302,2.32352995872,-13.1739788055 --13.5292768478,2.32351970673,-13.2154092789 --13.4893007278,2.32350873947,-13.2578353882 --13.4613075256,2.32250738144,-13.273062706 --13.4193305969,2.32149720192,-13.3144950867 --13.3653440475,2.31949424744,-13.3439340591 --13.3233671188,2.31948399544,-13.3853673935 --13.2723817825,2.31747913361,-13.4178056717 --13.2354097366,2.31846570969,-13.4642362595 --13.197435379,2.3184530735,-13.5096673965 --13.1704416275,2.31745171547,-13.5238857269 --13.134469986,2.31843781471,-13.5713157654 --13.095495224,2.31942534447,-13.6157464981 --13.0565214157,2.31941318512,-13.6601781845 --13.0045366287,2.31740903854,-13.691619873 --12.9675645828,2.31839489937,-13.7390556335 --12.9355955124,2.32037878036,-13.789475441 --12.9206132889,2.32236909866,-13.8176937103 --12.8686285019,2.32036519051,-13.8481330872 --12.8386621475,2.32234668732,-13.9025602341 --12.7966861725,2.32233595848,-13.9439935684 --12.7577133179,2.3233230114,-13.9894285202 --12.722743988,2.32530760765,-14.0388612747 --12.6747636795,2.32430124283,-14.0732955933 --12.6637830734,2.32628941536,-14.1045036316 --12.6468305588,2.33126187325,-14.1739234924 --12.5928440094,2.32925891876,-14.2023649216 --12.5588760376,2.33124279976,-14.2527933121 --12.5108957291,2.33023571968,-14.288233757 --12.4689207077,2.33122444153,-14.3306713104 --12.4399576187,2.33420443535,-14.387096405 --12.4199714661,2.33419823647,-14.4093132019 --12.3840017319,2.33618307114,-14.457742691 --12.3440303802,2.33717012405,-14.5031814575 --12.3130655289,2.33915114403,-14.5576066971 --12.2700910568,2.34014058113,-14.5990438461 --12.2431316376,2.34411811829,-14.6594724655 --12.2051610947,2.34510397911,-14.7059011459 --12.1951847076,2.34809041023,-14.740111351 --12.1632213593,2.35107135773,-14.7955446243 --12.1172437668,2.35006260872,-14.8329801559 --12.0612573624,2.34806060791,-14.8594274521 --12.0423069,2.35403227806,-14.9298467636 --12.0273609161,2.36100029945,-15.0062665939 --12.0114135742,2.366969347,-15.0806818008 --12.0124511719,2.37194633484,-15.1308898926 --11.9424495697,2.36695504189,-15.1393432617 --11.8814582825,2.36395716667,-15.1587905884 --11.8124599457,2.35896468163,-15.1692495346 --11.6303434372,2.3300588131,-15.034778595 --11.4462223053,2.30015540123,-14.8963117599 --11.3702116013,2.29317069054,-14.8927669525 --11.3201951981,2.28718709946,-14.8770093918 --11.2281684875,2.27721476555,-14.8534832001 --11.1861934662,2.27820396423,-14.8939199448 --11.2062864304,2.29214477539,-15.0153121948 --11.1963472366,2.30010867119,-15.0987281799 --11.1974210739,2.31106281281,-15.1981401443 --11.1784362793,2.31205558777,-15.2213554382 --11.1224489212,2.31005501747,-15.244805336 --11.0504426956,2.30406761169,-15.2462625504 --11.0024633408,2.30406093597,-15.2797040939 --10.9284543991,2.29807519913,-15.2781658173 --10.8654575348,2.29408097267,-15.2906179428 --10.8034610748,2.2910861969,-15.3040685654 --10.7364606857,2.2860956192,-15.3105239868 --10.7114696503,2.28609251976,-15.3267507553 --10.6604852676,2.2850894928,-15.3541908264 --10.5924825668,2.28009986877,-15.3586473465 --10.5144662857,2.2731192112,-15.348110199 --10.4634838104,2.2721157074,-15.3765573502 --10.38646698,2.2651348114,-15.3660163879 --10.2994012833,2.25018572807,-15.2912845612 --10.2374019623,2.24619317055,-15.3007316589 --10.1874198914,2.24618887901,-15.3301820755 --10.178486824,2.25514936447,-15.4185972214 --10.1525344849,2.26012349129,-15.4840288162 --9.14334011078,2.02697491646,-14.0701236725 --9.08333396912,2.02298617363,-14.0725708008 --9.00226783752,2.00803685188,-13.997836113 --8.91722869873,1.99807107449,-13.9613018036 --8.79413986206,1.97814023495,-13.8657960892 --8.75716209412,1.97913062572,-13.9032363892 --8.67212200165,1.96916604042,-13.8647050858 --8.55303478241,1.95023345947,-13.7721986771 --8.48100948334,1.94225800037,-13.751657486 --8.43598365784,1.93627882004,-13.7268924713 --8.36896324158,1.92929923534,-13.713347435 --8.25688171387,1.91236233711,-13.6278390884 --8.17584323883,1.90239644051,-13.5913095474 --8.0847864151,1.88944160938,-13.5357809067 --7.97169923782,1.8705085516,-13.4432678223 --8.01683521271,1.89342057705,-13.613658905 --7.95177793503,1.88146352768,-13.5508995056 --7.9899058342,1.90238130093,-13.7112941742 --7.88783168793,1.88643932343,-13.6337690353 --7.81580114365,1.87846672535,-13.6082344055 --7.82288551331,1.89141511917,-13.7166433334 --7.79992628098,1.89639353752,-13.7740707397 --7.70385980606,1.88244569302,-13.7065525055 --7.63579559326,1.86949288845,-13.6368055344 --7.59881496429,1.87048602104,-13.6692428589 --7.36553621292,1.81868302822,-13.3558177948 --7.30752086639,1.81369960308,-13.3482675552 --7.3085975647,1.82565331459,-13.447684288 --7.28163194656,1.82963645458,-13.4971179962 --7.22758483887,1.8206717968,-13.4473581314 --7.14352846146,1.80871605873,-13.3928337097 --6.87918138504,1.74495756626,-13.0024175644 --6.86022615433,1.75093317032,-13.0648517609 --6.81622838974,1.7499371767,-13.078291893 --6.80829143524,1.75890088081,-13.1607122421 --6.91153907776,1.80073988438,-13.4550580978 --6.86754465103,1.79974234104,-13.4715023041 --6.92868757248,1.82364904881,-13.6406736374 --6.77951526642,1.79177117348,-13.4531812668 --6.68143033981,1.77583479881,-13.3656692505 --6.49619054794,1.73300135136,-13.1022043228 --6.60445785522,1.77682840824,-13.4175491333 --6.59852981567,1.78778672218,-13.5089702606 --6.70475721359,1.82563781738,-13.773103714 --6.63471746445,1.81667053699,-13.7375631332 --6.55566215515,1.80571401119,-13.6840333939 --6.49664068222,1.80073451996,-13.6694879532 --6.38051557541,1.77782428265,-13.5369825363 --6.34854412079,1.78081166744,-13.5794286728 --6.33460426331,1.78977835178,-13.6568508148 --6.29457330704,1.78380227089,-13.626083374 --5.44613742828,1.54076349735,-12.0254802704 --6.11349344254,1.76587367058,-13.5654535294 --6.0975522995,1.77384150028,-13.6408805847 --6.06057071686,1.77483582497,-13.6713228226 --5.98651647568,1.76487791538,-13.6197910309 --5.95149230957,1.75989711285,-13.5970201492 --5.90448904037,1.75790524483,-13.6034660339 --5.8675069809,1.75989985466,-13.6329078674 --5.77741861343,1.74396455288,-13.5433931351 --5.79654979706,1.76388478279,-13.6997919083 --5.70846414566,1.74894762039,-13.613275528 --5.68751430511,1.75592112541,-13.6787014008 --5.70259571075,1.76787149906,-13.7739048004 --5.6395573616,1.76090288162,-13.740357399 --5.60357904434,1.76289534569,-13.7738018036 --5.54555368423,1.75791823864,-13.7552642822 --5.44042110443,1.73501086235,-13.6167430878 --5.37337398529,1.7260478735,-13.5742139816 --5.53177690506,1.78979051113,-14.0253171921 --5.45871686935,1.77883601189,-13.9677829742 --5.40970897675,1.77684760094,-13.9682292938 --5.36972427368,1.77784478664,-13.993678093 --5.33073997498,1.7788412571,-14.0201206207 --5.30178070068,1.78482210636,-14.0735588074 --5.25979185104,1.78482174873,-14.0950098038 --5.25583744049,1.79179596901,-14.1492204666 --5.20683145523,1.78980660439,-14.1516742706 --5.09467124939,1.7629160881,-13.984167099 --5.01759195328,1.74997353554,-13.905629158 --4.98061227798,1.75196731091,-13.9370727539 --4.91456079483,1.74300682545,-13.8895378113 --4.86354446411,1.73902380466,-13.8809890747 --4.87363052368,1.75197279453,-13.9792022705 --4.81559753418,1.74600076675,-13.9516592026 --4.74553012848,1.735049963,-13.8871183395 --4.73060941696,1.7460064888,-13.982550621 --4.72170543671,1.75995290279,-14.0949726105 --4.75391769409,1.79182600975,-14.3343820572 --4.63672161102,1.76095664501,-14.1298713684 --4.62876224518,1.76593458652,-14.1780872345 --4.53563070297,1.74502420425,-14.0445709229 --4.47057390213,1.73606729507,-13.9910316467 --4.39649009705,1.72212648392,-13.9095010757 --4.34847784042,1.71914112568,-13.9049482346 --4.29946565628,1.71715569496,-13.9004058838 --4.28054046631,1.72711575031,-13.9898414612 --4.27960443497,1.73707926273,-14.0630559921 --4.32387018204,1.77592039108,-14.3574457169 --4.27887296677,1.77592587471,-14.3688983917 --4.2469162941,1.78190636635,-14.4233436584 --4.21495866776,1.78688728809,-14.4767837524 --4.15491390228,1.77992224693,-14.4372444153 --4.10088682175,1.77494668961,-14.4156980515 --4.05682086945,1.76499164104,-14.3489437103 --3.91349816322,1.71619832516,-14.0124454498 --3.93872737885,1.74906349182,-14.2658557892 --3.82851171494,1.7162040472,-14.0443544388 --3.77247071266,1.71023654938,-14.0088119507 --3.73749876022,1.71322619915,-14.047249794 --3.71650290489,1.71422743797,-14.0554761887 --3.70461654663,1.7301646471,-14.1849107742 --3.67567253113,1.73813772202,-14.2523555756 --3.64873409271,1.74610710144,-14.3257913589 --3.59972119331,1.7441226244,-14.3202524185 --3.54267549515,1.73715794086,-14.2797107697 --3.47659349442,1.72421550751,-14.201171875 --3.46563506126,1.73019349575,-14.2493906021 --3.41862511635,1.72820711136,-14.2468442917 --3.3555533886,1.71725821495,-14.179309845 --3.31255745888,1.71726310253,-14.1917610168 --3.28763198853,1.72822523117,-14.2781972885 --3.26773333549,1.74217140675,-14.3926391602 --3.21670556068,1.73819577694,-14.3710927963 --3.1906914711,1.73620820045,-14.3603239059 --3.16476821899,1.74616920948,-14.44876194 --3.12579464912,1.75016093254,-14.4842157364 --3.08280396461,1.75116312504,-14.5016698837 --3.03579139709,1.74917840958,-14.4961185455 --2.98978829384,1.74818813801,-14.5005760193 --2.9498128891,1.75118112564,-14.534031868 --2.93685650826,1.75715899467,-14.5832529068 --2.89486813545,1.75915980339,-14.6027002335 --2.85690522194,1.7641453743,-14.6491556168 --2.81391215324,1.76514923573,-14.6636018753 --2.77494573593,1.76913714409,-14.7060575485 --2.73195719719,1.7701382637,-14.7255105972 --2.68997430801,1.77313625813,-14.7499628067 --2.67300629616,1.77712118626,-14.787191391 --2.63604831696,1.7831043005,-14.837635994 --2.59407162666,1.78609871864,-14.8690948486 --2.55410385132,1.79008793831,-14.9095487595 --2.51514101028,1.79507410526,-14.9549970627 --2.4751727581,1.80006361008,-14.9944467545 --2.43320202827,1.80405473709,-15.031908989 --2.42025756836,1.81102609634,-15.092124939 --2.37828350067,1.81501936913,-15.1255788803 --2.33329749107,1.817019701,-15.1470422745 --2.29132342339,1.82001280785,-15.1804933548 --2.24532818794,1.82101881504,-15.191950798 --2.19731903076,1.81903266907,-15.1894073486 --2.1753256321,1.82003307343,-15.1996326447 --2.12932944298,1.82103955746,-15.2100896835 --2.08232808113,1.82004904747,-15.2155485153 --2.03532862663,1.82005739212,-15.2230110168 --1.98832070827,1.81907057762,-15.2214612961 --1.94232451916,1.82007718086,-15.231918335 --1.8963303566,1.82108283043,-15.2443761826 --1.84831833839,1.8190984726,-15.2388334274 --1.82532227039,1.82010066509,-15.2460641861 --1.77932596207,1.82010734081,-15.2565202713 --1.73232102394,1.82011902332,-15.2579755783 --1.68431305885,1.81913268566,-15.256439209 --1.6383177042,1.81913876534,-15.2678966522 --1.59232664108,1.8211427927,-15.2833576202 --1.56932759285,1.82114672661,-15.2875843048 --1.52333450317,1.82215166092,-15.3010435104 --1.47632741928,1.821164608,-15.3004970551 --1.43033742905,1.82316803932,-15.3169593811 --1.38434433937,1.82417309284,-15.3304166794 --1.33733844757,1.82318556309,-15.3308725357 --1.29135239124,1.82518684864,-15.3513364792 --1.26835358143,1.82619071007,-15.3555631638 --1.22134947777,1.82520210743,-15.3580207825 --1.17435157299,1.82621026039,-15.3664836884 --1.1283608675,1.82821428776,-15.3819417953 --1.08035290241,1.82722818851,-15.3804063797 --1.0343619585,1.82823228836,-15.395863533 --0.987365186214,1.82923972607,-15.4053258896 --0.964373528957,1.83123993874,-15.4165563583 --0.917363464832,1.82925474644,-15.4130105972 --0.87036383152,1.83026409149,-15.419470787 --0.823365211487,1.8312728405,-15.4269332886 --0.776363432407,1.83128333092,-15.431391716 --0.730382919312,1.83428180218,-15.4568510056 --0.682363033295,1.83230257034,-15.4433116913 --0.65937513113,1.83330047131,-15.4585418701 --0.612381637096,1.83530652523,-15.4710044861 --0.564355671406,1.83233070374,-15.4514627457 --0.517368078232,1.8343334198,-15.4699277878 --0.470369577408,1.83534228802,-15.4773874283 --0.422368735075,1.83535265923,-15.4828557968 --0.375375390053,1.83735871315,-15.4953165054 --0.352374643087,1.83736383915,-15.4975414276 --0.304371863604,1.83737528324,-15.5010089874 --0.257379591465,1.83938097954,-15.5144701004 --0.210385099053,1.84038758278,-15.5259284973 --0.162383615971,1.84139859676,-15.5303964615 --0.115389198065,1.84240531921,-15.5418548584 --0.0673959255219,1.84441184998,-15.5543231964 --0.044389013201,1.84342038631,-15.5505456924 -0.00361663172953,1.84343361855,-15.5510120392 -0.0404020138085,1.84255814552,-14.7333021164 -0.0873827636242,1.83853459358,-14.7096691132 -0.134393498302,1.83952713013,-14.7150316238 -0.182411491871,1.84152376652,-14.7274017334 -0.23040381074,1.83950603008,-14.7147760391 -0.253404557705,1.83949995041,-14.7129545212 -0.301425486803,1.84149825573,-14.7283229828 -0.348411828279,1.83947741985,-14.7096910477 -0.396416515112,1.83946669102,-14.7090644836 -0.443420082331,1.83945560455,-14.7074298859 -0.490410447121,1.83743739128,-14.6927995682 -0.513391911983,1.83442080021,-14.6719856262 -0.561416864395,1.83742129803,-14.6913509369 -0.609432578087,1.8384168148,-14.7017202377 -0.656408190727,1.83539021015,-14.6720972061 -0.706475436687,1.84341371059,-14.7334566116 -0.755506396294,1.84741723537,-14.7588233948 -0.804534196854,1.8504191637,-14.7811899185 -0.830577433109,1.85643589497,-14.8213672638 -0.880610227585,1.86044037342,-14.848736763 -0.93064302206,1.86444485188,-14.8761043549 -0.982716679573,1.87347149849,-14.9444589615 -1.03780674934,1.88550615311,-15.0288228989 -1.08885419369,1.89151859283,-15.07117939 -1.13988173008,1.89551997185,-15.0935487747 -1.16893851757,1.90254354477,-15.14772892 -1.21794581413,1.90353429317,-15.1500940323 -1.26695489883,1.90452623367,-15.1544589996 -1.35814964771,1.93060946465,-15.3419885635 -1.40816271305,1.93260335922,-15.3503513336 -1.45816493034,1.93259108067,-15.3477220535 -1.48518443108,1.93559467793,-15.364906311 -1.53418552876,1.93558228016,-15.3612718582 -1.58519768715,1.93757534027,-15.368639946 -1.6362067461,1.93856692314,-15.3730115891 -1.68722677231,1.94156432152,-15.3883714676 -1.73521482944,1.93954503536,-15.3717412949 -1.78723394871,1.94254183769,-15.3861083984 -1.81021380424,1.93952465057,-15.3633012772 -1.86223649979,1.94252359867,-15.3816633224 -1.91223585606,1.94251000881,-15.376036644 -1.96223902702,1.94349861145,-15.3744039536 -2.01224017143,1.94348621368,-15.3707752228 -2.06224608421,1.94447636604,-15.3721399307 -2.11325240135,1.9454665184,-15.3735113144 -2.13926577568,1.9474670887,-15.3846893311 -2.19127988815,1.94946122169,-15.3940572739 -2.24127817154,1.94944727421,-15.3874311447 -2.29228711128,1.95143902302,-15.3917970657 -2.34228920937,1.95142734051,-15.3891649246 -2.3943002224,1.95342004299,-15.3955354691 -2.41728615761,1.95140624046,-15.3787250519 -2.4693031311,1.95440220833,-15.3910865784 -2.51527714729,1.9513759613,-15.3594646454 -2.56829380989,1.95337176323,-15.3718328476 -2.61527776718,1.95235061646,-15.3502063751 -2.66628098488,1.95233941078,-15.3485794067 -2.7142739296,1.9523229599,-15.3359470367 -2.73726081848,1.95030999184,-15.3201379776 -2.78525042534,1.94929206371,-15.3045110703 -2.83223342896,1.94727063179,-15.2818870544 -2.87922072411,1.94625139236,-15.263258934 -2.92721128464,1.9452341795,-15.248632431 -2.97721219063,1.94622170925,-15.2440032959 -3.02520465851,1.94520568848,-15.2313737869 -3.04718899727,1.94319152832,-15.2125654221 -3.09618210793,1.94317519665,-15.1999435425 -3.14317035675,1.94215667248,-15.1823158264 -3.19216609001,1.94214200974,-15.1726894379 -3.23915433884,1.94112360477,-15.1550617218 -3.28915381432,1.94111096859,-15.1494369507 -3.33714795113,1.94109559059,-15.1378068924 -3.35913252831,1.93908154964,-15.1190013885 -3.40411496162,1.93706071377,-15.0953731537 -3.45009660721,1.93503916264,-15.0707550049 -3.49809002876,1.93502342701,-15.0581283569 -3.54708695412,1.93500959873,-15.0495014191 -3.58905649185,1.93098211288,-15.0118818283 -3.63905644417,1.93196976185,-15.0062570572 -3.67209076881,1.93798065186,-15.0394296646 -3.73614358902,1.94599425793,-15.0897912979 -3.78915858269,1.94898951054,-15.1001520157 -3.83714723587,1.9479714632,-15.0825338364 -3.88915395737,1.94996237755,-15.0839061737 -3.93514060974,1.94894361496,-15.0642776489 -3.95211029053,1.94492280483,-15.0294752121 -3.98404431343,1.93587827682,-14.9538698196 -4.01397371292,1.92683172226,-14.8732662201 -4.03988981247,1.91477906704,-14.77866745 -4.07082843781,1.90673720837,-14.7070569992 -4.11681652069,1.90571939945,-14.6884374619 -4.15477991104,1.90169012547,-14.6438207626 -4.17275667191,1.89867281914,-14.6160182953 -4.1986823082,1.88762509823,-14.530415535 -4.24366903305,1.88660681248,-14.5097980499 -4.28966093063,1.88659143448,-14.4951725006 -4.31458520889,1.87654304504,-14.4075746536 -4.34051418304,1.86649739742,-14.3249769211 -4.39653682709,1.87049686909,-14.3433456421 -4.40749692917,1.8654717207,-14.2965478897 -4.44647073746,1.86244773865,-14.2619285583 -4.48945522308,1.86042928696,-14.2393083572 -4.52441549301,1.85539877415,-14.1897010803 -4.55937576294,1.85036838055,-14.1400957108 -4.60035657883,1.84834778309,-14.1124773026 -4.63431787491,1.84431815147,-14.0638647079 -4.65631103516,1.84330916405,-14.0530595779 -4.69027328491,1.83828020096,-14.0054483414 -4.72523832321,1.8342525959,-13.9608364105 -4.76321220398,1.83122897148,-13.9252243042 -4.80218791962,1.82820618153,-13.8916139603 -4.84216928482,1.82718634605,-13.8639955521 -4.87813806534,1.82316076756,-13.823387146 -4.89211320877,1.82014358044,-13.7925844193 -4.92607736588,1.81511557102,-13.7459812164 -4.95904111862,1.81108796597,-13.6993713379 -5.00203132629,1.81007254124,-13.6817502975 -5.03399372101,1.80504417419,-13.633143425 -5.07397651672,1.8040252924,-13.6065282822 -5.11295700073,1.80200541019,-13.5779151917 -5.12593173981,1.79798817635,-13.5461139679 -5.16090154648,1.79496347904,-13.5055103302 -5.19888067245,1.79294300079,-13.4748973846 -5.23786354065,1.79092442989,-13.4482803345 -5.29288291931,1.79592251778,-13.4616527557 -5.29979133606,1.78187000751,-13.3530673981 -5.31978464127,1.78186142445,-13.341258049 -5.3627743721,1.78084623814,-13.3226480484 -5.40376281738,1.78083050251,-13.3020296097 -5.43472719193,1.77580356598,-13.2544288635 -5.46368932724,1.7707760334,-13.2048225403 -5.49165058136,1.76574778557,-13.1532173157 -5.53063392639,1.76472973824,-13.1266078949 -5.53158569336,1.75770270824,-13.0688228607 -5.58359909058,1.76069819927,-13.0751962662 -5.6185760498,1.75867760181,-13.0415849686 -5.66958665848,1.76167190075,-13.0449609756 -5.73653459549,1.75562775135,-12.969748497 -5.77451753616,1.75460982323,-12.9421396255 -5.79451322556,1.75460290909,-12.9333248138 -5.82448101044,1.75057828426,-12.8887214661 -5.84843730927,1.7445486784,-12.8311252594 -5.89143180847,1.74453616142,-12.8165092468 -5.94644927979,1.74953341484,-12.8268861771 -5.95137023926,1.73748850822,-12.729306221 -5.97532939911,1.73146057129,-12.6747055054 -6.00033378601,1.73345720768,-12.6748943329 -6.0333108902,1.73043727875,-12.6402854919 -6.0722990036,1.73042190075,-12.6176719666 -6.10227012634,1.72639930248,-12.5760698318 -6.14426422119,1.72738671303,-12.5604534149 -6.18425416946,1.72737240791,-12.5398426056 -6.22424411774,1.72635805607,-12.5192327499 -6.23622560501,1.72434508801,-12.4934310913 -6.27120637894,1.72232687473,-12.4628248215 -6.30618906021,1.72130942345,-12.4332151413 -6.34317350388,1.72029292583,-12.4066085815 -6.38316488266,1.72027921677,-12.3869953156 -6.42616033554,1.72126734257,-12.3723831177 -6.44515419006,1.72025978565,-12.3605775833 -6.49516201019,1.72325325012,-12.359957695 -6.51512050629,1.71822607517,-12.303355217 -6.54609632492,1.71520578861,-12.2657546997 -6.58909320831,1.71619462967,-12.2521381378 -6.64310693741,1.72019064426,-12.258515358 -6.67308139801,1.71717023849,-12.2199134827 -6.69407844543,1.71816396713,-12.2111101151 -6.73707485199,1.7191529274,-12.1974925995 -6.76905345917,1.71713411808,-12.1628885269 -6.825070858,1.72113180161,-12.1732578278 -6.84503173828,1.71610569954,-12.1176624298 -6.88001394272,1.71508836746,-12.087064743 -6.93603086472,1.71908628941,-12.0974321365 -6.9620347023,1.72108280659,-12.0966272354 -7.00102472305,1.72106897831,-12.0750169754 -7.04502296448,1.72205841541,-12.0623998642 -7.07900524139,1.72104156017,-12.031794548 -7.12801170349,1.72403478622,-12.0291662216 -7.16900444031,1.72502207756,-12.010556221 -7.20599079132,1.72400712967,-11.9849500656 -7.22498512268,1.72399997711,-11.9731454849 -7.2669801712,1.72498810291,-11.9565315247 -7.30396604538,1.7239729166,-11.9299297333 -7.34696340561,1.72596228123,-11.9163074493 -7.38595294952,1.72594845295,-11.8937015533 -7.43595790863,1.72894096375,-11.889084816 -7.47294569016,1.7279266119,-11.8644742966 -7.49194049835,1.72791957855,-11.8526697159 -7.52892827988,1.72790527344,-11.8280572891 -7.56591463089,1.72689020634,-11.8014574051 -7.62092685699,1.73188555241,-11.8048334122 -7.6448969841,1.72786438465,-11.7592353821 -7.7009100914,1.73285996914,-11.7636108398 -7.71987390518,1.72783613205,-11.710021019 -7.74888181686,1.73083472252,-11.7142057419 -7.79287815094,1.73182344437,-11.6985969543 -7.83787631989,1.73381364346,-11.6859798431 -7.89188623428,1.73780786991,-11.6863574982 -7.93087625504,1.73779451847,-11.6637487411 -7.97186899185,1.73878240585,-11.6441373825 -7.99386739731,1.73977684975,-11.6363315582 -8.03986549377,1.74176692963,-11.6237182617 -8.07685279846,1.74175286293,-11.5981111526 -8.11884784698,1.74274086952,-11.579501152 -8.15983963013,1.74272882938,-11.5598897934 -8.2058391571,1.7457190752,-11.5472726822 -8.24883365631,1.74670767784,-11.5296630859 -8.27383518219,1.74770343304,-11.5258541107 -8.30781936646,1.74768829346,-11.4962472916 -8.35682201385,1.74967944622,-11.4866333008 -8.39881515503,1.75166749954,-11.4670257568 -8.44281005859,1.75265645981,-11.4504146576 -8.47879695892,1.75264203548,-11.4228096008 -8.53080177307,1.75563454628,-11.4171895981 -8.56581401825,1.75963449478,-11.4263744354 -8.60180187225,1.7596206665,-11.3997621536 -8.65881252289,1.76461493969,-11.400138855 -8.7088136673,1.7676063776,-11.3915185928 -8.75280952454,1.76859521866,-11.3739089966 -8.78278923035,1.76757824421,-11.3373117447 -8.82978725433,1.7695684433,-11.3236970901 -8.86980438232,1.77457010746,-11.3388738632 -8.90278720856,1.77355444431,-11.3062734604 -8.95879459381,1.77754771709,-11.3036527634 -9.01480293274,1.78254103661,-11.301030159 -9.05979824066,1.78352999687,-11.2834205627 -9.10479450226,1.78551924229,-11.2668046951 -9.14080524445,1.78951835632,-11.2739944458 -9.18880462646,1.79250884056,-11.2613735199 -9.27383995056,1.80251193047,-11.2927322388 -9.3208360672,1.80450105667,-11.2761240005 -9.37083625793,1.80749177933,-11.2645044327 -9.41783428192,1.8104814291,-11.2488880157 -9.45982551575,1.81146883965,-11.2262802124 -9.45279312134,1.80545282364,-11.1805038452 -9.48177337646,1.80443668365,-11.1438989639 -9.51175308228,1.80342006683,-11.106306076 -9.18939495087,1.72828722,-10.6510047913 -9.17833995819,1.71825933456,-10.5694360733 -9.20331954956,1.71624338627,-10.530837059 -9.21828842163,1.71222400665,-10.4792556763 -9.20024967194,1.7052063942,-10.4244832993 -9.21321773529,1.70118689537,-10.3718986511 -9.23819732666,1.69917094707,-10.3323106766 -9.24616241455,1.69415080547,-10.2757234573 -9.27314472198,1.69313585758,-10.2391319275 -9.29211997986,1.69011902809,-10.1945419312 -9.31609916687,1.68810343742,-10.1549520493 -9.32108402252,1.68609428406,-10.129152298 -9.33705615997,1.68207645416,-10.0805721283 -9.36203670502,1.68006169796,-10.0429792404 -9.38101387024,1.67804551125,-9.99938774109 -9.39598655701,1.67402803898,-9.95080471039 -9.41996765137,1.67301356792,-9.91320800781 -9.42595291138,1.6710048914,-9.88841152191 -9.44593143463,1.667989254,-9.84582424164 -9.47291469574,1.66697573662,-9.81122875214 -9.49189281464,1.66496014595,-9.76863670349 -9.51187133789,1.6629447937,-9.72605323792 -9.54085636139,1.66193199158,-9.69345855713 -9.55383014679,1.65891551971,-9.64586639404 -9.56782341003,1.65790903568,-9.62906932831 -9.589802742,1.65589463711,-9.58948135376 -9.61078453064,1.65488040447,-9.54988670349 -9.61374950409,1.64886188507,-9.49230670929 -9.63973426819,1.64784860611,-9.45671749115 -9.65070724487,1.64383220673,-9.40713405609 -9.67368984222,1.64281868935,-9.36954307556 -9.68067741394,1.6408110857,-9.34674835205 -9.68864822388,1.63679409027,-9.29417133331 -9.70462703705,1.63477957249,-9.25058174133 -9.72861099243,1.63276660442,-9.21399307251 -9.73458099365,1.62874960899,-9.16041660309 -9.75356197357,1.6267362833,-9.12082004547 -9.76953983307,1.62372195721,-9.07723522186 -9.75951576233,1.61971104145,-9.03845691681 -9.77449512482,1.61669683456,-8.99486923218 -9.78947257996,1.61368250847,-8.95028972626 -9.80845451355,1.61266946793,-8.91069889069 -9.83243942261,1.61165761948,-8.87610149384 -9.86042881012,1.6116464138,-8.84450817108 -9.86139678955,1.60562968254,-8.78793811798 -9.86038208008,1.60362148285,-8.75914764404 -9.88436698914,1.60260987282,-8.72455406189 -9.90134811401,1.60059690475,-8.68396472931 -9.91132450104,1.59758281708,-8.63638591766 -9.94331645966,1.5975728035,-8.60879039764 -9.95629501343,1.59555923939,-8.56420898438 -9.97928142548,1.59454798698,-8.5296125412 -9.98727226257,1.59354162216,-8.50882053375 -9.99524784088,1.58952784538,-8.46123600006 -10.0092287064,1.58751511574,-8.41864967346 -10.0292129517,1.58550333977,-8.38106155396 -10.0371894836,1.58248960972,-8.33248901367 -10.0551729202,1.58047783375,-8.29389953613 -10.0641651154,1.58047187328,-8.27410697937 -10.0821485519,1.57846033573,-8.23551845551 -10.0841226578,1.57444643974,-8.1839389801 -10.1171159744,1.57543718815,-8.15734386444 -8.3399810791,1.25913977623,-6.63710355759 -8.30193901062,1.24912381172,-6.56156158447 -8.3269367218,1.25011813641,-6.53896284103 -8.37595748901,1.25612080097,-6.55713939667 -8.4049577713,1.25811588764,-6.53753805161 -8.43896007538,1.26011121273,-6.52094221115 -8.46395683289,1.26010537148,-6.49735116959 -8.47894859314,1.25909805298,-6.46576690674 -8.51995563507,1.26309502125,-6.45614910126 -8.54295158386,1.26308882236,-6.43056154251 -8.55695152283,1.26308619976,-6.41976642609 -8.58194828033,1.26408064365,-6.39716243744 -8.60194301605,1.26407408714,-6.3685836792 -8.6319437027,1.26606929302,-6.34997415543 -8.66194343567,1.26706445217,-6.33037424088 -8.67793560028,1.26605761051,-6.29978752136 -8.69393730164,1.26705527306,-6.28999376297 -8.72693920135,1.26905071735,-6.27239227295 -8.74593257904,1.26904428005,-6.24380540848 -8.77393245697,1.27003920078,-6.22220945358 -8.80393218994,1.27203440666,-6.2026052475 -8.82792854309,1.27202868462,-6.17702102661 -8.85192584991,1.27302312851,-6.15242671967 -8.87092781067,1.27502131462,-6.1456193924 -8.89092350006,1.27501523495,-6.11802864075 -8.92292404175,1.27601051331,-6.09843492508 -8.94291877747,1.27600455284,-6.07084369659 -8.96891784668,1.27799940109,-6.04724931717 -8.9959154129,1.27899420261,-6.02465105057 -9.02691650391,1.28098940849,-6.00405788422 -9.04491901398,1.28198742867,-5.99625110626 -9.0629119873,1.28198134899,-5.96666622162 -9.09291172028,1.28297650814,-5.94507455826 -9.11991119385,1.28497159481,-5.92247343063 -9.14490890503,1.2849663496,-5.8978805542 -9.16090202332,1.28496026993,-5.86729240417 -9.19490432739,1.28695583344,-5.84869194031 -9.21290493011,1.28895366192,-5.83989191055 -9.27191925049,1.2949514389,-5.83727550507 -9.22988510132,1.2849406004,-5.76872873306 -9.24487876892,1.28493475914,-5.73813581467 -9.32390117645,1.29393398762,-5.74751091003 -9.3609046936,1.29692971706,-5.72991132736 -9.36489295959,1.29492306709,-5.69133377075 -10.5444221497,1.48100888729,-6.41571187973 -10.5674142838,1.48100161552,-6.38412189484 -10.5914077759,1.4819945097,-6.35352802277 -10.600394249,1.4799861908,-6.31295061111 -10.6924171448,1.49098372459,-6.3233165741 -10.6994028091,1.48897564411,-6.28272867203 -10.7113990784,1.48897194862,-6.26693487167 -10.6413526535,1.47495889664,-6.17940664291 -10.6583433151,1.47495138645,-6.14382553101 -10.5983009338,1.4619396925,-6.06329107285 -10.5352582932,1.44892776012,-5.98076677322 -10.4672145844,1.43591606617,-5.89723443985 -10.375161171,1.41790318489,-5.79972600937 -10.3081254959,1.40589570999,-5.73898696899 -10.3211174011,1.40488922596,-5.70340585709 -10.1900491714,1.38187539577,-5.58591938019 -10.0469789505,1.35686135292,-5.46244573593 -10.0749769211,1.35885620117,-5.4368519783 -9.85787773132,1.32183969021,-5.27442407608 -9.834856987,1.31583285332,-5.22185897827 -9.76382350922,1.30382657051,-5.16212415695 -9.72379684448,1.2948192358,-5.10057592392 -9.71478271484,1.29081344604,-5.05600976944 -9.6387424469,1.27680492401,-4.97548866272 -9.56970596313,1.26379716396,-4.89995670319 -9.50767230988,1.25178992748,-4.82842493057 -9.43563652039,1.23778259754,-4.7528924942 -9.36460494995,1.22577786446,-4.69615840912 -9.24855327606,1.20576965809,-4.59865665436 -9.29856395721,1.21176707745,-4.58804607391 -9.34557151794,1.21576428413,-4.57544088364 -9.10647773743,1.17775344849,-4.41701841354 -9.07546043396,1.17074894905,-4.36546468735 -8.97842216492,1.15474450588,-4.29874134064 -9.04443836212,1.16274273396,-4.29612922668 -8.76333427429,1.11873281002,-4.12173271179 -8.81134414673,1.1237308979,-4.11112928391 -8.76232147217,1.11372709274,-4.05357933044 -8.76231575012,1.11172425747,-4.01901292801 -8.68428421021,1.09872031212,-3.94847917557 -8.67327880859,1.09571886063,-3.92669630051 -8.59524726868,1.08171522617,-3.85617399216 -8.52722072601,1.06971204281,-3.79163789749 -8.47319889069,1.05970931053,-3.73409461975 -8.42717933655,1.0507068634,-3.68054890633 -8.4081697464,1.04670476913,-3.63998413086 -8.35014820099,1.0367026329,-3.58144974709 -8.28612613678,1.02570128441,-3.53670215607 -8.27111816406,1.02169978619,-3.49913144112 -8.23410415649,1.01469838619,-3.45157933235 -8.21609687805,1.01069700718,-3.41301250458 -8.16807937622,1.00169575214,-3.36146473885 -8.15007209778,0.997694730759,-3.32389163971 -8.0800485611,0.984693825245,-3.26237535477 -8.01402854919,0.974693536758,-3.21962070465 -7.97101449966,0.966692984104,-3.17206645012 -7.96901273727,0.964692473412,-3.141497612 -7.95400714874,0.960692107677,-3.10593152046 -7.90199136734,0.951692044735,-3.05538535118 -7.87398290634,0.946691989899,-3.01581478119 -7.86998128891,0.944691896439,-2.99904108047 -7.80796337128,0.934692382812,-2.94549965858 -7.79496002197,0.930692493916,-2.91193175316 -7.76795196533,0.925692915916,-2.87336611748 -7.80696249008,0.929692625999,-2.86076617241 -7.72994232178,0.917693912983,-2.80322623253 -7.71393823624,0.913694500923,-2.76866912842 -7.66992759705,0.906695365906,-2.73889183998 -7.64792203903,0.902696251869,-2.70233988762 -7.62591743469,0.897697269917,-2.66677618027 -7.59591054916,0.891698539257,-2.6292052269 -7.56790494919,0.886699855328,-2.59164857864 -7.53989934921,0.881701350212,-2.55409598351 -7.51689481735,0.876702785492,-2.51952648163 -7.48388767242,0.871704101562,-2.49475049973 -7.47988891602,0.8697052598,-2.46618914604 -7.4658870697,0.86670678854,-2.43561005592 -7.47989273071,0.867707550526,-2.41403102875 -7.37787055969,0.851711690426,-2.35251188278 -7.38587474823,0.851712822914,-2.32992434502 -7.39587974548,0.851713955402,-2.30734682083 -7.35487174988,0.845715999603,-2.28058218956 -7.337870121,0.84171807766,-2.25000500679 -7.33487272263,0.840719819069,-2.22343277931 -7.30486869812,0.834722459316,-2.18886327744 -7.31087303162,0.834724068642,-2.16528892517 -7.28287029266,0.829726874828,-2.13073515892 -7.29387378693,0.830727398396,-2.12193751335 -7.3028793335,0.830728888512,-2.10034632683 -7.29688119888,0.828731000423,-2.0737683773 -7.30288648605,0.828732728958,-2.05019712448 -7.26088094711,0.821736514568,-2.01264095306 -7.25088262558,0.819738984108,-1.98506736755 -7.14886569977,0.804745614529,-1.93053686619 -7.15987014771,0.805746257305,-1.9217416048 -7.13887023926,0.801749587059,-1.8911793232 -7.13987493515,0.800751805305,-1.86759805679 -7.1218752861,0.796755135059,-1.8380368948 -7.09587526321,0.79275894165,-1.80647814274 -7.10788202286,0.79376077652,-1.78687942028 -7.06887674332,0.787764072418,-1.7641119957 -7.05787944794,0.784767210484,-1.73753893375 -7.04088163376,0.781770825386,-1.70897734165 -7.06089019775,0.783772528172,-1.69138014317 -7.03989171982,0.779776453972,-1.6618231535 -7.01389217377,0.775780618191,-1.63224852085 -7.00989627838,0.773783743382,-1.60767865181 -6.99889755249,0.771785914898,-1.59290218353 -6.97189807892,0.76779037714,-1.56333124638 -6.9839053154,0.768792688847,-1.54373955727 -7.00291442871,0.770794689655,-1.52515673637 -6.97791576385,0.765799343586,-1.49560046196 -6.94991731644,0.761804163456,-1.46603620052 -6.9169178009,0.755809485912,-1.43547534943 -6.91992139816,0.755810797215,-1.42566978931 -6.91492652893,0.754814326763,-1.40209054947 -6.92993497849,0.755816817284,-1.38251292706 -6.90393686295,0.751821935177,-1.35395073891 -6.88994121552,0.74982625246,-1.32837975025 -6.85394239426,0.743832230568,-1.29782617092 -6.85694932938,0.743835568428,-1.27624619007 -6.83594942093,0.739838659763,-1.26145303249 -6.85195827484,0.741841137409,-1.24286317825 -6.89197063446,0.746842026711,-1.22827804089 -6.82096719742,0.735850691795,-1.19173312187 -6.8189740181,0.735854625702,-1.16915929317 -6.80997991562,0.733859062195,-1.14558279514 -6.8049826622,0.732861280441,-1.13379359245 -6.80498981476,0.731865048409,-1.11221003532 -6.80099630356,0.730869233608,-1.08963346481 -6.7840013504,0.727874577045,-1.06407546997 -6.81301212311,0.731876075268,-1.04846680164 -6.82302093506,0.731879353523,-1.02789509296 -6.78402376175,0.72688639164,-0.999334216118 -6.78402709961,0.725888431072,-0.988544762135 -6.93605232239,0.746880114079,-0.993872404099 -6.79604387283,0.72689563036,-0.947381138802 -6.81105279922,0.727898418903,-0.92878484726 -6.83406257629,0.730900526047,-0.911188840866 -6.80706739426,0.726907074451,-0.884635210037 -6.81607627869,0.727910459042,-0.865040898323 -6.83508205414,0.72991091013,-0.857240974903 -6.84809112549,0.730913996696,-0.837654531002 -6.76309013367,0.718925714493,-0.803125143051 -6.82010412216,0.726925134659,-0.789527177811 -6.79510974884,0.722931563854,-0.764952003956 -6.79511785507,0.721935987473,-0.743376731873 -6.86213254929,0.73093444109,-0.730769574642 -6.87013721466,0.731935858727,-0.72097748518 -6.93015050888,0.739934742451,-0.707365274429 -6.89515542984,0.734942257404,-0.681791722775 -6.88816261292,0.732947409153,-0.659218072891 -6.94217586517,0.739946842194,-0.643622457981 -6.95118427277,0.740950405598,-0.623037159443 -7.01719379425,0.749946296215,-0.620207130909 -7.15621328354,0.767937421799,-0.613565802574 -6.75218915939,0.712980926037,-0.547182381153 -6.7251958847,0.708988368511,-0.522628605366 -6.73520517349,0.709992110729,-0.503037452698 -6.78121757507,0.715992391109,-0.486439943314 -6.73022270203,0.709002137184,-0.460875570774 -6.7532286644,0.712002336979,-0.452084928751 -6.78023958206,0.715004503727,-0.433494001627 -6.88725566864,0.728998482227,-0.421864002943 -6.84426164627,0.723007500172,-0.397295325994 -6.71926212311,0.70602530241,-0.365774989128 -6.69927024841,0.703032374382,-0.343207776546 -6.69927930832,0.703037321568,-0.322624444962 -6.70628499985,0.704039335251,-0.31184977293 -6.75529670715,0.710039079189,-0.295233786106 -6.73530483246,0.707046329975,-0.272669434547 -6.76631593704,0.711048007011,-0.254070669413 -6.74232387543,0.708055734634,-0.23150524497 -6.69633102417,0.701065897942,-0.207947552204 -6.69734096527,0.701070964336,-0.187366276979 -6.68834495544,0.700074493885,-0.176579669118 -6.68135452271,0.699080646038,-0.155014485121 -6.74736738205,0.708078622818,-0.137406647205 -6.70937490463,0.702088117599,-0.114845745265 -6.69438409805,0.700094878674,-0.0942580476403 -6.68339347839,0.699101626873,-0.0726933777332 -6.6723985672,0.697105586529,-0.0619102567434 -6.67440843582,0.697110772133,-0.0413312390447 -6.96242904663,0.736083030701,-0.0296165980399 -6.66242742538,0.696122944355,-0.00017084144929 -6.679438591,0.698126494884,0.0204070787877 -6.70144891739,0.701129317284,0.0400072745979 -6.69245958328,0.699136018753,0.061567183584 -6.67446374893,0.697140991688,0.0723452940583 -6.67847394943,0.697145819664,0.0919450446963 -6.68748426437,0.698150336742,0.112526506186 -6.6554942131,0.694159924984,0.134076699615 -6.6655049324,0.696164429188,0.154658406973 -6.66751527786,0.69616985321,0.175237640738 -6.72752714157,0.704168200493,0.195845618844 -6.74153184891,0.706169188023,0.205654010177 -6.81454372406,0.716165959835,0.227259889245 -9.71459674835,1.10681188107,0.277227938175 -9.727602005,1.10781383514,0.306819826365 -9.70560741425,1.10482060909,0.337374269962 -7.05358839035,0.748158633709,0.315689712763 -9.71661949158,1.10682713985,0.397535473108 -6.91060209274,0.729185163975,0.344990998507 -7.07861375809,0.75116944313,0.370650589466 -6.91562318802,0.729196071625,0.388143867254 -6.69263267517,0.700230240822,0.401630759239 -6.64464378357,0.693242549896,0.421174973249 -6.65565443039,0.695246994495,0.441766291857 -6.60665988922,0.688256204128,0.449543714523 -6.65267086029,0.694256305695,0.472139805555 -6.69968175888,0.701256155968,0.494743406773 -6.63969373703,0.693270266056,0.513277947903 -6.59870481491,0.688281595707,0.530854225159 -6.62971591949,0.692283689976,0.553438127041 -6.67572689056,0.698283791542,0.577030658722 -6.60573339462,0.689296126366,0.582794427872 -6.69174337387,0.701290667057,0.608419179916 -9.69771385193,1.10689079762,0.834370315075 -6.60176706314,0.689315140247,0.643536269665 -6.60677862167,0.690320611,0.664122402668 -6.58679103851,0.687329828739,0.683679640293 -6.57879686356,0.686334073544,0.693461477757 -6.57680797577,0.686340451241,0.713053047657 -6.55182027817,0.683350384235,0.731615483761 -6.55783176422,0.684355795383,0.752202928066 -6.55784368515,0.684362232685,0.772777676582 -6.55185556412,0.684369444847,0.792359054089 -6.52686882019,0.681379497051,0.810914456844 -6.60687208176,0.692371487617,0.828744053841 -6.51188611984,0.679391145706,0.839288115501 -6.51389837265,0.679397404194,0.859866082668 -6.59290790558,0.690392613411,0.888484597206 -6.5389213562,0.683406829834,0.903039813042 -6.50893497467,0.680417835712,0.92059391737 -6.51294660568,0.681423783302,0.941179096699 -6.51995277405,0.682426035404,0.951976120472 -6.4939661026,0.678436458111,0.96953612566 -6.51297712326,0.681440293789,0.992125928402 -6.4689912796,0.67645329237,1.00668942928 -6.47000360489,0.676459848881,1.02726519108 -6.47801589966,0.678465485573,1.04884362221 -6.48002147675,0.678468346596,1.05864703655 -6.47303438187,0.678476214409,1.07821905613 -6.47504711151,0.678482651711,1.09879994392 -6.46205997467,0.677491366863,1.11737132072 -6.47107219696,0.678496778011,1.13895642757 -6.44808578491,0.676506876945,1.15553212166 -6.44909858704,0.67651361227,1.1761097908 -6.44210529327,0.675518333912,1.18588197231 -6.45811700821,0.678522706032,1.2084748745 -6.49212741852,0.683524310589,1.23407638073 -6.44014358521,0.677539288998,1.24661958218 -6.4301571846,0.676547646523,1.26519715786 -6.43516921997,0.677553653717,1.28579223156 -6.4411816597,0.678559720516,1.30737197399 -6.46318721771,0.681559979916,1.32215797901 -6.40820360184,0.674575448036,1.33271420002 -6.44621419907,0.680576622486,1.36030614376 -6.46222639084,0.683581233025,1.38389158249 -6.43824052811,0.680591821671,1.39946997166 -6.43425321579,0.68059939146,1.4190518856 -6.42726707458,0.679607689381,1.43862044811 -6.41327476501,0.67861354351,1.44639873505 -6.4282875061,0.681618273258,1.4699845314 -6.4073009491,0.678628444672,1.48556959629 -6.43031311035,0.682632088661,1.51115465164 -6.42832660675,0.682639658451,1.53172671795 -6.40034151077,0.679651200771,1.54629659653 -6.39234924316,0.678656160831,1.55507874489 -6.39436197281,0.679662823677,1.57566893101 -6.39737558365,0.680669665337,1.59724462032 -6.385389328,0.679678678513,1.61482715607 -6.39940214157,0.682684004307,1.63939929008 -6.41841411591,0.685688316822,1.66497898102 -6.42342710495,0.68669462204,1.6865695715 -6.40743494034,0.684700906277,1.69334983826 -6.42944717407,0.688704788685,1.7199306488 -6.46945714951,0.694705545902,1.75053036213 -6.46047115326,0.69471424818,1.76911258698 -6.43948698044,0.692725241184,1.7856695652 -6.50749492645,0.70272153616,1.82427406311 -6.42951488495,0.692741453648,1.82483446598 -6.45951890945,0.69674038887,1.8436280489 -6.41653680801,0.691754758358,1.85319721699 -6.39955186844,0.689764916897,1.8697706461 -6.41556453705,0.692769765854,1.89535415173 -6.40757846832,0.692778408527,1.9139393568 -6.44858837128,0.69877910614,1.94653511047 -6.42259788513,0.695787250996,1.9503082037 -6.42261219025,0.696794867516,1.97188305855 -6.43362426758,0.698800504208,1.99646568298 -6.42863893509,0.698808729649,2.01605153084 -6.40965509415,0.696819722652,2.03261089325 -6.41666841507,0.6988260746,2.05619215965 -6.43567991257,0.702830255032,2.08279109001 -6.45168542862,0.704831421375,2.09858369827 -6.44370031357,0.704840481281,2.11815404892 -6.45471286774,0.706846058369,2.14274764061 -6.38773441315,0.698865234852,2.14428925514 -6.33075523376,0.691882550716,2.14784884453 -6.34276819229,0.693888306618,2.17342686653 -6.33278274536,0.693897485733,2.19101715088 -6.34478902817,0.695899307728,2.20580863953 -6.38579893112,0.702900230885,2.24139285088 -6.42580795288,0.708900928497,2.27599573135 -6.40982437134,0.707911372185,2.29257035255 -6.55682229996,0.729894161224,2.36518645287 -6.60283041,0.736893713474,2.40279459953 -6.69083452225,0.750886380672,2.45639777184 -6.31888532639,0.697954297066,2.33806657791 -6.28990268707,0.694967091084,2.34963750839 -6.28591918945,0.69597607851,2.37119269371 -6.28693294525,0.696983635426,2.39278364182 -6.24995183945,0.692997932434,2.40134882927 -6.38794994354,0.712981939316,2.4739677906 -6.33996295929,0.706993997097,2.46675515175 -6.30698204041,0.703007876873,2.47731161118 -6.32499408722,0.707012593746,2.50590229034 -6.51098537445,0.734987914562,2.59854316711 -6.69797563553,0.762963056564,2.69318056107 -6.70098972321,0.763970255852,2.71776533127 -6.35804891586,0.716038703918,2.6082265377 -6.33805847168,0.71404594183,2.61102223396 -6.36706972122,0.719049036503,2.64559960365 -6.37008428574,0.72105640173,2.66918563843 -6.35510063171,0.720067083836,2.68576288223 -6.36011505127,0.721074461937,2.71132946014 -6.35513067245,0.722083330154,2.73191094398 -6.3591375351,0.723086535931,2.74470710754 -6.36315202713,0.725093901157,2.76928782463 -6.37316560745,0.728100299835,2.79686331749 -6.39817714691,0.73210388422,2.83045172691 -6.35819768906,0.728119254112,2.83701205254 -6.35721302032,0.729127585888,2.85959386826 -6.35222911835,0.729136765003,2.8811621666 -6.35023641586,0.730140864849,2.89096856117 -6.35825014114,0.73214751482,2.91755461693 -6.34726715088,0.732158005238,2.93711185455 -6.36927843094,0.736162006855,2.96970939636 -6.36029481888,0.736171841621,2.9892847538 -6.35731124878,0.737180709839,3.01185727119 -6.35032749176,0.737190246582,3.03243207932 -6.36333322525,0.740191996098,3.05022621155 -6.36834764481,0.742199480534,3.07679867744 -6.36636304855,0.743207991123,3.09938359261 -6.3643784523,0.744216501713,3.12196946144 -6.34939622879,0.744227766991,3.13953208923 -6.32941436768,0.742239713669,3.1541030407 -6.35242605209,0.747243642807,3.1886985302 -6.34543514252,0.746249139309,3.19748401642 -6.34645032883,0.748257279396,3.22206521034 -6.36546278,0.752262115479,3.25565075874 -6.34548139572,0.751274168491,3.27022266388 -6.35449552536,0.754281103611,3.29979348183 -6.34151268005,0.753291785717,3.31737518311 -6.34352016449,0.754295408726,3.33017373085 -6.33553647995,0.755305290222,3.35074996948 -6.33555269241,0.75631403923,3.37631344795 -6.52853679657,0.787286281586,3.49996781349 -6.36657857895,0.764324963093,3.44149041176 -6.35959529877,0.764334797859,3.46306347847 -6.33461475372,0.762347877026,3.47463965416 -6.32962369919,0.762353003025,3.4844288826 -6.34063720703,0.765359282494,3.51501774788 -6.3276553154,0.765370309353,3.53358697891 -6.31767272949,0.765380620956,3.5531668663 -6.32768726349,0.768387556076,3.58473587036 -6.31970405579,0.769397437572,3.60531973839 -6.31572055817,0.770406842232,3.62889266014 -6.3157286644,0.771411180496,3.64168190956 -6.29574775696,0.769423604012,3.65625143051 -6.29676389694,0.771432161331,3.68282437325 -6.28278160095,0.771443009377,3.69941830635 -6.28479766846,0.773451447487,3.72698688507 -6.2858133316,0.775459945202,3.7535636425 -6.28582143784,0.776464223862,3.76635599136 -6.30683326721,0.781468629837,3.80395245552 -6.31184864044,0.783476471901,3.83352565765 -6.28886842728,0.782489478588,3.84609937668 -6.27388715744,0.781501114368,3.86367034912 -6.29090023041,0.786506593227,3.90025448799 -6.29091596603,0.787515282631,3.9268321991 -6.26992750168,0.785523474216,3.92662739754 -6.2729434967,0.787531614304,3.95520472527 -6.31595230103,0.796532571316,4.00977468491 -6.33796405792,0.802536725998,4.04937648773 -6.35097789764,0.806543111801,4.08495521545 -6.28800582886,0.79856389761,4.07251787186 -6.28401422501,0.798568964005,4.08331012726 -6.39001131058,0.817557692528,4.1789059639 -6.46401357651,0.831552028656,4.25351524353 -6.28606319427,0.804595172405,4.16704130173 -6.32107257843,0.81259727478,4.21762609482 -6.26210021973,0.804617643356,4.20718336105 -6.25811719894,0.806627094746,4.23176860809 -6.28312015533,0.811626493931,4.26157474518 -6.25614213943,0.80964076519,4.27213716507 -6.28115367889,0.815644741058,4.31672477722 -6.26517295837,0.814656794071,4.33429718018 -6.24719285965,0.814669072628,4.34987735748 -6.3741850853,0.837653458118,4.4654841423 -6.28421831131,0.824679732323,4.43204545975 -6.26123142242,0.821688711643,4.43082380295 -6.23925256729,0.820702016354,4.4443936348 -6.36824369431,0.844686031342,4.56399869919 -6.2382850647,0.824719965458,4.50056028366 -6.23030424118,0.825730919838,4.52511787415 -6.24431753159,0.830736994743,4.56370735168 -6.23333692551,0.830748260021,4.58527994156 -6.432305336,0.865713715553,4.74312734604 -6.22836303711,0.833762764931,4.62564706802 -6.24737596512,0.839768111706,4.66922855377 -6.32137727737,0.853762447834,4.75283432007 -6.26540470123,0.846782445908,4.74140119553 -6.2734208107,0.850790083408,4.77797460556 -6.21843957901,0.84280538559,4.75175237656 -6.23645305634,0.848810851574,4.79533672333 -6.24446821213,0.85281842947,4.83191537857 -6.24048614502,0.853828370571,4.85949087143 -6.23550367355,0.855838418007,4.88607120514 -6.31750297546,0.872831165791,4.97967815399 -6.26953029633,0.866849958897,4.97423696518 -6.24954271317,0.864858448505,4.97402381897 -6.32254457474,0.879853188992,5.06262016296 -6.35655403137,0.888855576515,5.12120819092 -6.21560049057,0.866892516613,5.04075574875 -6.2336139679,0.872898340225,5.0873298645 -6.23862981796,0.875906467438,5.12291240692 -6.21665143967,0.874920189381,5.1374797821 -6.21466064453,0.875925004482,5.1512761116 -6.22367525101,0.880932450294,5.19085550308 -6.22169303894,0.882942140102,5.2214345932 -6.21471166611,0.88495272398,5.24801254272 -6.21772813797,0.887961506844,5.28358507156 -6.2127456665,0.889971494675,5.31117534637 -6.20076608658,0.890983343124,5.33474111557 -6.21677112579,0.894984722137,5.36453771591 -6.21278858185,0.896994769573,5.39411783218 -6.23480129242,0.903999745846,5.44669818878 -6.23181867599,0.907009541988,5.47728252411 -6.25483131409,0.914014399052,5.53185749054 -6.23485326767,0.913027763367,5.54843235016 -6.23986101151,0.916031479836,5.57021903992 -6.22588062286,0.916043519974,5.59179925919 -6.21989965439,0.918054163456,5.62137126923 -6.23391342163,0.924060583115,5.66796016693 -6.22793245316,0.926071166992,5.69753646851 -6.22594928741,0.929080784321,5.73012304306 -6.2279586792,0.931085407734,5.75089645386 -6.2279753685,0.93409460783,5.78548431396 -6.22799301147,0.93710398674,5.82106351852 -6.22701072693,0.940113842487,5.85663318634 -6.24302387238,0.947119653225,5.90623140335 -6.22904443741,0.947131991386,5.92980241776 -6.19306993484,0.944148778915,5.93237113953 -6.20407629013,0.948151350021,5.96116113663 -6.21009254456,0.952159583569,6.00373792648 -6.23710393906,0.961163580418,6.06632566452 -6.21412706375,0.960177838802,6.08189296722 -6.21014499664,0.963187932968,6.11448097229 -6.21616172791,0.968196511269,6.15904808044 -6.2001824379,0.968209087849,6.18062877655 -6.20319080353,0.97121322155,6.20242071152 -6.20920705795,0.975221633911,6.24699449539 -6.26321172714,0.98922008276,6.33859348297 -6.23923492432,0.989234626293,6.35415935516 -6.25024986267,0.994241893291,6.40374660492 -6.19727993011,0.988262116909,6.38931179047 -6.18830013275,0.990273654461,6.41988372803 -6.19130802155,0.993277549744,6.44168424606 -6.20232343674,0.999285101891,6.49325942993 -6.19934129715,1.00229525566,6.52984046936 -6.20435857773,1.00730407238,6.57640886307 -6.2593626976,1.02230238914,6.67400884628 -6.25238180161,1.02431333065,6.70758724213 -6.2363948822,1.02332139015,6.71137189865 -6.20541954041,1.02133715153,6.71895074844 -6.19144105911,1.02234971523,6.74552440643 -6.18745994568,1.02636039257,6.78409004211 -6.2014746666,1.03336703777,6.84067869186 -6.18249702454,1.03338062763,6.86225223541 -6.15052270889,1.03139698505,6.86981964111 -6.22151470184,1.04838740826,6.96962547302 -6.22653055191,1.05339598656,7.01820755005 -6.27053785324,1.06639671326,7.11079883575 -7.45326662064,1.3121663332,8.49361515045 -7.43828773499,1.31417918205,8.53018379211 -7.43130683899,1.31819021702,8.57476520538 -7.41132879257,1.31920385361,8.60533905029 -7.40833806992,1.32220947742,8.62912464142 -7.38836050034,1.32322323322,8.65969944 -7.36638355255,1.32423734665,8.6882724762 -7.35140419006,1.3262501955,8.72484874725 -7.32342910767,1.32626581192,8.74741363525 -7.31344890594,1.33027720451,8.78900051117 -7.2934627533,1.32828629017,8.79278469086 -7.27748394012,1.33129942417,8.82935619354 -7.24750947952,1.33031523228,8.84892559052 -7.22053432465,1.33133065701,8.87249279022 -7.20455503464,1.33334362507,8.90807437897 -7.17957925797,1.33435857296,8.93364715576 -7.16060113907,1.33537209034,8.96622467041 -7.12561941147,1.33138418198,8.95100593567 -7.12263822556,1.33639466763,9.00458049774 -3.45357894897,0.546148240566,4.42061328888 -3.45059967041,0.548159003258,4.44518375397 -3.43862223625,0.548171341419,4.45776367188 -3.40764927864,0.545187354088,4.44535017014 -6.99876737595,1.34347426891,9.1642370224 -6.98079061508,1.34648799896,9.20080184937 -6.95781421661,1.34750247002,9.22937870026 -6.93883705139,1.34951639175,9.26395130157 -6.90786314011,1.34953272343,9.28252315521 -6.88888597488,1.35154640675,9.31610393524 -6.87989759445,1.35255324841,9.33488559723 -6.8579211235,1.35456776619,9.36546134949 -6.82994651794,1.35458338261,9.38803577423 -6.80597066879,1.35559821129,9.4166059494 -6.78799343109,1.35861182213,9.45218849182 -6.75901937485,1.35862791538,9.4747543335 -6.73404407501,1.35964310169,9.50232410431 -6.73405313492,1.36264812946,9.53311634064 -6.70407915115,1.36266410351,9.55269432068 -6.67810440063,1.36367940903,9.57926368713 -6.66412639618,1.36769247055,9.62283802032 -6.63515233994,1.3677085638,9.64540672302 -6.60617876053,1.36772441864,9.66698265076 -6.5891919136,1.3677328825,9.67377281189 -6.52322816849,1.35875654221,9.64233207703 -6.54124164581,1.37076282501,9.73291778564 -6.56025505066,1.38276910782,9.82649993896 -6.58326816559,1.3957747221,9.92807674408 -6.56129169464,1.39778923988,9.96165275574 -6.31237649918,1.34485018253,9.65018844604 -6.24240446091,1.33086919785,9.57497215271 -6.21742963791,1.33188438416,9.60055351257 -6.15646505356,1.32490706444,9.57311248779 -6.10749673843,1.31992709637,9.56168556213 -6.0755238533,1.31894397736,9.57725811005 -6.05954742432,1.3229572773,9.61783409119 -6.03357315063,1.32397294044,9.64340400696 -5.99659204483,1.31798541546,9.61719036102 -5.997610569,1.32599532604,9.68477344513 -6.0136256218,1.3380023241,9.77835273743 -5.99464941025,1.34101641178,9.81592559814 -6.00466585159,1.35102450848,9.90050888062 -6.00468444824,1.35903465748,9.96909427643 -6.02169895172,1.37204170227,10.0696630478 -6.03770446777,1.38104343414,10.1314582825 -6.0557179451,1.39404988289,10.233042717 -6.04673957825,1.40006220341,10.2916135788 -6.03076267242,1.40407562256,10.3371925354 -6.00278949738,1.40509152412,10.3627681732 -5.97881555557,1.40810680389,10.3963403702 -5.96982717514,1.40911376476,10.4181270599 -5.93985414505,1.41013002396,10.4397087097 -5.9098815918,1.41114652157,10.4632787704 -5.88190841675,1.41216242313,10.4898519516 -5.8469376564,1.4121799469,10.5044231415 -5.82496213913,1.4141947031,10.5410032272 -5.79499006271,1.4152110815,10.5645751953 -5.7850022316,1.41721820831,10.5853633881 -5.75103092194,1.41723537445,10.6009407043 -5.72505664825,1.41925096512,10.6305217743 -5.69808387756,1.42126691341,10.6610898972 -5.67311000824,1.42328226566,10.6936674118 -5.64013814926,1.42329919338,10.7112445831 -5.62715148926,1.42430698872,10.7270317078 -5.60017824173,1.4263228178,10.756608963 -5.57020568848,1.427339077,10.7801856995 -5.53823471069,1.42835605145,10.8007602692 -5.50626277924,1.42837297916,10.8213338852 -5.47929000854,1.43038892746,10.8529024124 -5.44831800461,1.43140542507,10.8744831085 -5.43633079529,1.43341314793,10.8932685852 -5.53232383728,1.47240424156,11.1728563309 -3.77083492279,0.944769322872,7.67726993561 -3.71487045288,0.934790790081,7.62284660339 -3.6838991642,0.932807385921,7.6194229126 -3.65392780304,0.930823802948,7.61799812317 -3.62395596504,0.928839862347,7.61458539963 -3.60897064209,0.928848385811,7.61536169052 -3.52803349495,0.917885065079,7.56452322006 -3.49006390572,0.912902891636,7.54310798645 -3.46309256554,0.911918997765,7.54866886139 -3.38916325569,0.906959354877,7.53962516785 -3.35319375992,0.902976751328,7.52120828629 -3.33122014999,0.902991533279,7.53478622437 -3.30624747276,0.903006851673,7.54136562347 -3.27927565575,0.902022659779,7.54394054413 -3.24230647087,0.897040367126,7.52251958847 -3.22632145882,0.896048843861,7.51830387115 -3.20434737206,0.896063327789,7.52989292145 -3.16637897491,0.89108145237,7.50646352768 -3.12643146515,0.894110262394,7.54261827469 -3.09146118164,0.890127241611,7.52220964432 -3.05849075317,0.88614410162,7.50779104233 -3.04250621796,0.885152697563,7.5035700798 -3.0165336132,0.884168028831,7.50515651703 -2.99556064606,0.885182797909,7.52172756195 -2.9655892849,0.882198929787,7.51331186295 -2.9406170845,0.88221436739,7.51888799667 -2.90364813805,0.877232015133,7.49246931076 -2.88967227936,0.880245089531,7.52505254745 -2.87568616867,0.8792527318,7.52185249329 -2.8457159996,0.877269387245,7.51541948318 -2.82374215126,0.877283811569,7.52601051331 -2.7957713604,0.876299917698,7.52358293533 -2.77179884911,0.875314891338,7.53016519547 -2.74082803726,0.872331380844,7.51774644852 -2.73084163666,0.873338699341,7.527531147 -2.70786881447,0.873353600502,7.53711175919 -2.6928935051,0.87736672163,7.56769990921 -2.65892362595,0.872383773327,7.54628038406 -2.61299967766,0.883424282074,7.64500761032 -2.561024189,0.866439223289,7.52781534195 -2.54005169868,0.867454051971,7.54538249969 -2.51907777786,0.868468165398,7.55797719955 -2.49610519409,0.868483126163,7.56755685806 -2.47313308716,0.869498252869,7.57912635803 -2.46315646172,0.875510394573,7.62771272659 -2.44318342209,0.877524912357,7.6482872963 -2.43719553947,0.879531264305,7.67107582092 -2.41822171211,0.882545351982,7.69365882874 -2.35326099396,0.863568305969,7.56824302673 -2.37727499008,0.885573983192,7.72982692719 -2.28643751144,0.918659567833,8.01108646393 -2.26646351814,0.920673429966,8.03268146515 -2.25348830223,0.926686406136,8.08326053619 -2.23652553558,0.937705695629,8.1736164093 -2.23354721069,0.949716627598,8.26419639587 -2.22457051277,0.958728671074,8.33278274536 -2.21661472321,0.981751024723,8.5159444809 -2.17379570007,1.0848429203,9.3035774231 -2.15791630745,1.17790353298,10.0142631531 -2.15593743324,1.19691419601,10.1578483582 -2.14696121216,1.21192646027,10.2744274139 -2.14398336411,1.23193764687,10.4250040054 -2.13100862503,1.24595069885,10.5325756073 -2.1200325489,1.26096308231,10.6471643448 -2.08906292915,1.26197934151,10.6647462845 -2.16605067253,1.32897007465,11.1545314789 -2.15007662773,1.34298360348,11.2621107101 -2.50099420547,1.62792766094,13.3496704102 -2.46602535248,1.6329447031,13.3922548294 -2.4230594635,1.63296365738,13.3978281021 -2.38309240341,1.63398170471,13.4144115448 -2.36110925674,1.63299095631,13.4102058411 -2.31814312935,1.63200974464,13.4117860794 -2.27917575836,1.63502764702,13.4373655319 -2.23820948601,1.63604593277,13.4539422989 -2.1972424984,1.63706421852,13.4665241241 -2.15827560425,1.64008200169,13.4941043854 -2.11730861664,1.64110016823,13.508685112 -2.0983247757,1.64310896397,13.5234804153 -2.05535888672,1.64312779903,13.5300550461 -2.01739144325,1.64714515209,13.5626411438 -1.97742462158,1.64916324615,13.590215683 -1.93645763397,1.65018129349,13.601805687 -1.89949011803,1.65619874001,13.6513824463 -1.85852384567,1.65921700001,13.6739597321 -1.84053969383,1.66222560406,13.7007522583 -1.81256902218,1.67724108696,13.8173379898 -1.78559863567,1.69525682926,13.9589109421 -1.74263226986,1.69527506828,13.9634990692 -1.69666731358,1.69329416752,13.9510812759 -1.64670372009,1.68631398678,13.9066581726 -1.60173869133,1.68533289433,13.9032363892 -1.58075523376,1.68534183502,13.9060344696 -1.53479027748,1.68336081505,13.8906154633 -1.49182450771,1.68337917328,13.9011964798 -1.44685924053,1.68239796162,13.8947753906 -1.40489292145,1.68341600895,13.9093637466 -1.35992777348,1.68243479729,13.9029436111 -1.33794510365,1.6824439764,13.9027347565 -1.29397964478,1.68246257305,13.9063138962 -1.24901425838,1.67948114872,13.8908987045 -1.20404911041,1.67749977112,13.8784818649 -1.16008377075,1.67751836777,13.8810606003 -1.11611807346,1.67653667927,13.8746471405 -1.0731523037,1.67655491829,13.88422966 -1.05016994476,1.67556428909,13.8710212708 -1.0072042942,1.67658257484,13.8856019974 -0.963238835335,1.67560088634,13.8831834793 -0.919273197651,1.67461907864,13.8737707138 -0.875307738781,1.67363750935,13.8703536987 -0.833341538906,1.67665541172,13.8939390182 -0.811358630657,1.6756644249,13.8867330551 -0.767393410206,1.67568278313,13.8873147964 -0.723427832127,1.6737010479,13.8788986206 -0.679462492466,1.67271924019,13.8754816055 -0.630498588085,1.65773844719,13.7600641251 -0.591531693935,1.67075574398,13.8606481552 -0.547566413879,1.670773983,13.8582286835 -0.526583254337,1.67178285122,13.8700237274 -0.48361748457,1.67380082607,13.8856086731 -0.440651595592,1.67481863499,13.8941965103 -0.396686345339,1.6748367548,13.8937778473 -0.352721065283,1.67485487461,13.8943586349 -0.309755116701,1.6748726368,13.8989477158 -0.265789806843,1.67489075661,13.893529892 -0.243807092309,1.67289984226,13.8813228607 -0.199841827154,1.67191803455,13.8739051819 -0.15687584877,1.67193567753,13.8764953613 -0.112910583615,1.6709536314,13.8640766144 -0.0689451023936,1.65397167206,13.7426633835 -0.0259794034064,1.66698944569,13.8362483978 --0.00699429307133,1.67000293732,13.1949300766 --0.0479608587921,1.66902017593,13.1905193329 --0.0689437165856,1.66902911663,13.1863088608 --0.110909506679,1.67004656792,13.1958885193 --0.151875987649,1.66806387901,13.1794776917 --0.192842617631,1.66908109188,13.1880683899 --0.234808340669,1.66909861565,13.1846485138 --0.27577483654,1.66811573505,13.1762361526 --0.296757698059,1.66812455654,13.1770267487 --0.337724089622,1.66614174843,13.1616125107 --0.379689961672,1.66815912724,13.1721944809 --0.419657111168,1.66617596149,13.1567907333 --0.46162301302,1.66719341278,13.1633729935 --0.50258910656,1.66421067715,13.1389541626 --0.543555855751,1.66522753239,13.1475477219 --0.564538598061,1.66523623466,13.142334938 --0.605504989624,1.66425335407,13.1339225769 --0.647470891476,1.66527056694,13.1395044327 --0.688437581062,1.66628754139,13.1430969238 --0.729403972626,1.66530454159,13.134683609 --0.771369934082,1.66632175446,13.1412687302 --0.812336206436,1.66533875465,13.1288528442 --0.831319987774,1.6623468399,13.1056489944 --0.872286140919,1.66136395931,13.0922298431 --0.913252949715,1.66238057613,13.1008262634 --0.955218970776,1.66339766979,13.1054105759 --0.997185111046,1.66541469097,13.1119976044 --1.03815150261,1.66443157196,13.1065855026 --1.08011758327,1.66644847393,13.1121730804 --1.10110032558,1.66545712948,13.106959343 --1.14206719398,1.6664737463,13.1085538864 --1.18503284454,1.66949093342,13.1221389771 --1.22599947453,1.66950762272,13.117729187 --1.26796531677,1.66952455044,13.1153106689 --1.30993151665,1.67054128647,13.1188983917 --1.3319144249,1.67354977131,13.1346969604 --1.37488031387,1.67556679249,13.143280983 --1.41684675217,1.67658352852,13.1508760452 --1.45881295204,1.67760026455,13.1514644623 --1.50277853012,1.68061721325,13.1700525284 --1.54574418068,1.68263435364,13.1726331711 --1.58271217346,1.67765009403,13.1362285614 --1.60569477081,1.68065857887,13.1530227661 --1.64866030216,1.68167555332,13.1556053162 --1.69262599945,1.68469250202,13.1711940765 --1.73559188843,1.68570923805,13.17578125 --1.77655863762,1.68572556973,13.1693735123 --1.81952476501,1.68774223328,13.1769647598 --1.86548948288,1.69175946712,13.1985473633 --1.88547325134,1.69176745415,13.1933460236 --1.93043863773,1.69478452206,13.2099342346 --1.97340476513,1.69680094719,13.2155256271 --2.017370224,1.69881772995,13.2211103439 --2.05933690071,1.69983410835,13.2197027206 --2.10430216789,1.70285093784,13.234292984 --2.14926791191,1.70586776733,13.2488832474 --2.16925144196,1.70487570763,13.2406787872 --2.21221733093,1.70589220524,13.2392644882 --2.25418353081,1.70590853691,13.2318506241 --2.29914927483,1.70892512798,13.2444419861 --2.34311509132,1.71094167233,13.2520341873 --2.3840816021,1.70995759964,13.2386217117 --2.40706443787,1.71196591854,13.2484197617 --2.45202994347,1.71498250961,13.2580089569 --2.4969959259,1.71799910069,13.2686014175 --2.53996181488,1.71801543236,13.2641859055 --2.585927248,1.72203195095,13.2797813416 --2.62789416313,1.72204780579,13.2743749619 --2.67285943031,1.72406446934,13.279961586 --2.69484257698,1.72507250309,13.2807569504 --2.739808321,1.72708880901,13.2873468399 --2.78177499771,1.72810459137,13.2819433212 --2.82674050331,1.72912120819,13.2845277786 --2.8667075634,1.72813653946,13.267118454 --2.91267323494,1.73115301132,13.2777109146 --2.95963859558,1.73516941071,13.293305397 --2.98362088203,1.7361779213,13.3000974655 --3.02558803558,1.73719334602,13.2936935425 --3.07255291939,1.7402099371,13.3052835464 --3.11851882935,1.74322617054,13.3138771057 --3.16148495674,1.74324202538,13.3054628372 --3.20445156097,1.74425780773,13.3010568619 --3.22843408585,1.74626600742,13.3088531494 --3.27439951897,1.74828207493,13.3144435883 --3.32136511803,1.7522983551,13.3260393143 --3.36633110046,1.75331425667,13.3266305923 --3.4092977047,1.75432980061,13.3202228546 --3.46026182175,1.75934660435,13.3428134918 --3.50222873688,1.75936198235,13.3314037323 --3.52621126175,1.7603700161,13.3372011185 --3.57417631149,1.76438641548,13.34678936 --3.61914253235,1.76540219784,13.3463821411 --3.6611096859,1.76541733742,13.3349761963 --3.71107411385,1.7694337368,13.351568222 --3.7530412674,1.76944899559,13.3391599655 --3.79900741577,1.77246463299,13.342757225 --3.82598924637,1.77547299862,13.3595590591 --3.8699555397,1.77648842335,13.352148056 --3.91792082787,1.77950441837,13.3587379456 --3.96488666534,1.78152012825,13.3633327484 --4.00685453415,1.78253495693,13.3519306183 --4.05381965637,1.78455078602,13.3535194397 --4.10278463364,1.78756666183,13.3631134033 --4.1247677803,1.78757429123,13.3589076996 --4.17073392868,1.78958976269,13.358502388 --4.21969985962,1.79360556602,13.3680992126 --4.25966787338,1.79261994362,13.3486948013 --4.30563354492,1.79463529587,13.3452835083 --4.35259962082,1.79665064812,13.3468780518 --4.3735833168,1.79665791988,13.3416805267 --4.42054891586,1.79867351055,13.3402681351 --4.47051477432,1.80268919468,13.3508653641 --4.50848340988,1.80070316792,13.3244590759 --4.55844831467,1.80371892452,13.3330535889 --4.61141300201,1.8087348938,13.3516521454 --4.64838171005,1.80674850941,13.3212423325 --4.6793627739,1.8107572794,13.3420391083 --4.7233300209,1.81177186966,13.3326349258 --4.76829624176,1.81278681755,13.3242254257 --4.81426286697,1.81480157375,13.3218250275 --4.86222934723,1.81781673431,13.3214149475 --4.91219472885,1.82083201408,13.3300189972 --4.9671587944,1.82584822178,13.34760952 --5.00013971329,1.83085691929,13.3734140396 --5.04110717773,1.83087086678,13.3530044556 --5.10007047653,1.83688747883,13.3816022873 --5.12604284286,1.83089923859,13.3221931458 --5.11902475357,1.81190621853,13.177778244 --5.12500333786,1.79791510105,13.0713739395 --5.13399076462,1.79292035103,13.0331687927 --5.17195987701,1.79193365574,13.0087633133 --5.20992898941,1.79094719887,12.9833545685 --5.26989173889,1.79796350002,13.0139522552 --5.30386257172,1.79597616196,12.9805498123 --5.35282850266,1.79899084568,12.9841489792 --5.3947968483,1.79900479317,12.9677391052 --5.4147810936,1.79901134968,12.9595413208 --5.45175027847,1.79702436924,12.9311304092 --5.49371910095,1.79803800583,12.916727066 --5.39472770691,1.74703216553,12.571305275 --5.26374530792,1.68602216244,12.1558732986 --5.31071233749,1.68903636932,12.1604766846 --5.31269168854,1.67704451084,12.0590620041 --5.26269626617,1.65204167366,11.8928480148 --5.28766918182,1.64805293083,11.8474416733 --5.27765226364,1.63105940819,11.7250328064 --5.30162620544,1.62707042694,11.6796283722 --5.32859897614,1.62408196926,11.6402196884 --5.31858158112,1.60808837414,11.5208072662 --5.37555599213,1.62109994888,11.5966110229 --5.32355070114,1.59110093117,11.3871889114 --5.31253385544,1.57510733604,11.2687740326 --5.33350849152,1.57011783123,11.2213697433 --5.34348630905,1.56212687492,11.1509618759 --5.34346675873,1.55013465881,11.0605545044 --5.46541261673,1.57915854454,11.22315979 --5.4204158783,1.55815660954,11.083943367 --5.50237321854,1.57417488098,11.1645555496 --5.50635290146,1.56418311596,11.0831441879 --5.58631086349,1.57820117474,11.1557455063 --5.57429456711,1.56320726871,11.0433349609 --5.64225625992,1.57322371006,11.0909357071 --5.64923524857,1.5652320385,11.0185308456 --5.66522073746,1.56423807144,11.0053224564 --5.72218608856,1.57125294209,11.0309247971 --5.74216079712,1.56626307964,10.9825115204 --5.7461400032,1.55727100372,10.9061059952 --5.8011059761,1.56328558922,10.9267063141 --5.84307479858,1.56629836559,10.9223041534 --5.89105224609,1.57530796528,10.972114563 --5.92202425003,1.57431936264,10.9457073212 --5.9370007515,1.568328619,10.8902997971 --5.96397399902,1.5663394928,10.8568916321 --6.00294446945,1.56735169888,10.8464899063 --6.04291439056,1.56936395168,10.8380899429 --6.11587524414,1.58038032055,10.8876905441 --6.16485214233,1.58939003944,10.9344930649 --6.15983438492,1.57839667797,10.844080925 --6.18180942535,1.57440662384,10.8036813736 --6.23577594757,1.58042037487,10.8182792664 --6.3077378273,1.5914362669,10.8648872375 --6.32571315765,1.5864456892,10.8154764175 --6.40967178345,1.60046291351,10.8810853958 --6.42665815353,1.60046851635,10.870885849 --6.46762752533,1.60248064995,10.8604793549 --6.50559854507,1.60349214077,10.8460788727 --6.51857662201,1.59750080109,10.7896718979 --6.56854391098,1.60251367092,10.7952737808 --6.61051416397,1.6045255661,10.7868700027 --6.61350393295,1.6005294323,10.7536687851 --6.68146657944,1.60954427719,10.788274765 --6.72843551636,1.61355674267,10.7868709564 --6.74441242218,1.60856544971,10.7364664078 --6.83337020874,1.62258279324,10.8020706177 --6.86934185028,1.62359368801,10.7836723328 --6.91831016541,1.62760603428,10.7852745056 --6.92030096054,1.62360966206,10.7510728836 --6.99026346207,1.63362431526,10.7856807709 --7.0342335701,1.63563609123,10.7782793045 --7.09519863129,1.64264965057,10.7968816757 --7.10917663574,1.63765799999,10.7424716949 --7.20913219452,1.65467572212,10.8200836182 --7.23010826111,1.65068471432,10.7776832581 --7.22310066223,1.64468717575,10.7294750214 --7.28006744385,1.65070009232,10.7410793304 --7.31404066086,1.65071034431,10.7176780701 --7.36900758743,1.65672290325,10.7252807617 --7.37198877335,1.64872980118,10.6558704376 --7.45394945145,1.66074514389,10.7024793625 --7.48093318939,1.66275119781,10.7052822113 --7.52590370178,1.66576242447,10.697886467 --7.57687234879,1.66977441311,10.6974840164 --7.61084508896,1.66978442669,10.673081398 --7.65881490707,1.67379570007,10.6696882248 --7.71378231049,1.67880785465,10.674287796 --7.76875114441,1.6838196516,10.6809024811 --7.75874423981,1.67782175541,10.6296882629 --7.80271530151,1.67983269691,10.6192903519 --7.86368179321,1.68684506416,10.6329011917 --7.93364620209,1.69485855103,10.6565055847 --7.95962142944,1.69386720657,10.6201000214 --7.92861223221,1.67786991596,10.5086898804 --8.08955287933,1.70789265633,10.6533155441 --8.08754444122,1.70389533043,10.6151103973 --8.17950344086,1.7179107666,10.6667251587 --8.21347808838,1.71792006493,10.6403217316 --8.22345733643,1.71192681789,10.5839204788 --8.20044612885,1.69893026352,10.4845085144 --8.27640914917,1.70894384384,10.5121097565 --8.26440429688,1.70194542408,10.4629087448 --8.40035152435,1.72596478462,10.5675315857 --8.38833808899,1.71596932411,10.4831209183 --8.45330429077,1.72298133373,10.4967308044 --8.54326534271,1.73599565029,10.5413484573 --8.51125526428,1.7209982872,10.4319295883 --8.54822921753,1.72200739384,10.409529686 --8.61420440674,1.73301649094,10.4573440552 --8.70416545868,1.74603068829,10.4989566803 --8.72414302826,1.74303793907,10.4555568695 --8.68013763428,1.72603929043,10.3341369629 --8.8780708313,1.76206326485,10.5047779083 --5.47490024567,1.00574982166,6.38756084442 --5.43189191818,0.991753160954,6.29412984848 --5.4208855629,0.987755656242,6.26092529297 --5.40487098694,0.979761242867,6.20151233673 --5.40685224533,0.975768625736,6.16309928894 --5.38483858109,0.966773688793,6.09768438339 --5.38182163239,0.961780428886,6.05528116226 --5.38780164719,0.9587880373,6.02287387848 --5.37279605865,0.95379036665,5.98565912247 --5.36477899551,0.947796881199,5.93724155426 --5.36876010895,0.944804191589,5.903840065 --5.3587436676,0.938810586929,5.85341691971 --5.36672401428,0.936818301678,5.8250169754 --5.36370611191,0.93182516098,5.78360271454 --5.36668729782,0.928832530975,5.74919128418 --5.35867977142,0.924835324287,5.72198581696 --5.36166143417,0.921842575073,5.68858146667 --5.37064027786,0.919850409031,5.66117095947 --5.36162424088,0.913856744766,5.61475753784 --5.37360334396,0.912864744663,5.59135341644 --5.37658405304,0.909872055054,5.55794000626 --5.38656377792,0.908879876137,5.53253364563 --5.37455749512,0.903882324696,5.50232887268 --5.42940855026,0.888938963413,5.2952671051 --5.44238758087,0.887946844101,5.27386140823 --5.49835634232,0.895958125591,5.29446220398 --5.46834564209,0.886962652206,5.23104810715 --5.47432613373,0.884970068932,5.20263624191 --5.49031400681,0.885974407196,5.20245027542 --5.49029588699,0.882981359959,5.16803216934 --5.51227283478,0.883989810944,5.15563011169 --5.53424978256,0.884998261929,5.14322853088 --5.53923130035,0.883005261421,5.11482429504 --5.57520437241,0.887014865875,5.11441278458 --5.59518241882,0.888023018837,5.10001039505 --5.61116981506,0.88902759552,5.09780454636 --5.63914585114,0.89103615284,5.0914144516 --5.67012071609,0.894045114517,5.0860042572 --5.6960978508,0.896053433418,5.07761526108 --5.72407341003,0.898062109947,5.06920528412 --5.76404714584,0.903071343899,5.07281494141 --5.77902555466,0.902079105377,5.05240154266 --5.79001522064,0.903082966805,5.0462064743 --5.82599020004,0.907091856003,5.04581546783 --5.83197116852,0.9050989151,5.01739931107 --5.87994241714,0.911108672619,5.02599668503 --5.8999209404,0.91211616993,5.01160764694 --5.93589544296,0.915125131607,5.00920057297 --5.94887542725,0.915132284164,4.98779964447 --5.97786092758,0.919137299061,4.99660873413 --6.00583696365,0.921145439148,4.98720264435 --6.03681325912,0.924153745174,4.98080587387 --6.0697889328,0.92716217041,4.97540283203 --6.10176515579,0.930170238018,4.97001266479 --6.13174104691,0.93217843771,4.96160697937 --6.17272377014,0.939183950424,4.97941827774 --6.18170452118,0.937190890312,4.95300197601 --6.22667837143,0.942199587822,4.95761537552 --6.25465488434,0.945207357407,4.94721221924 --6.27463388443,0.946214616299,4.9308142662 --6.3156080246,0.950223147869,4.93041276932 --6.34658527374,0.953230798244,4.92302370071 --6.37357091904,0.956235349178,4.9278254509 --6.41054677963,0.960243403912,4.92443227768 --6.44852161407,0.96425151825,4.92103290558 --6.48249769211,0.96725922823,4.91463661194 --6.50847530365,0.969266653061,4.9012298584 --6.54445123672,0.973274469376,4.89583110809 --6.57442808151,0.975281894207,4.88542842865 --6.59741592407,0.978285908699,4.88724136353 --6.64338970184,0.983294129372,4.88884544373 --5.51060390472,0.780242085457,4.00205421448 --5.50958681107,0.777248561382,3.97364044189 --5.5285654068,0.778255999088,3.96023392677 --5.55054426193,0.780263364315,3.94984173775 --6.82427120209,1.00233149529,4.85786771774 --6.840259552,1.00333499908,4.85266590118 --6.88223457336,1.00834274292,4.84926366806 --6.91821193695,1.01134979725,4.84287881851 --6.95318841934,1.0153567791,4.83448028564 --6.99916362762,1.02036440372,4.83409023285 --7.01914358139,1.02137076855,4.81468725204 --7.08211517334,1.0293790102,4.82529592514 --7.11110067368,1.0323830843,4.82809305191 --7.15107727051,1.03738999367,4.82270240784 --7.1890540123,1.04139685631,4.81530714035 --7.23202991486,1.04540383816,4.81192302704 --7.27200698853,1.05041062832,4.80552911758 --7.31898212433,1.05541777611,4.80313062668 --7.34596920013,1.05842125416,4.80494260788 --7.37294816971,1.0604275465,4.78853607178 --7.43492031097,1.0684350729,4.79615163803 --7.46290016174,1.07044112682,4.78075456619 --7.51687431335,1.07744801044,4.78236675262 --7.55185222626,1.08045423031,4.77096986771 --7.60582637787,1.08746111393,4.77157735825 --7.62781524658,1.08946418762,4.76938962936 --7.67379140854,1.09447073936,4.76399040222 --7.8097205162,1.10948944092,4.74681377411 --7.87569332123,1.11849629879,4.753428936 --7.90267324448,1.12050175667,4.73502540588 --7.93566036224,1.12450504303,4.7388420105 --7.98663568497,1.13051116467,4.7344417572 --8.02561473846,1.134516716,4.7240562439 --8.07559013367,1.14052248001,4.71966934204 --8.12156772614,1.14552819729,4.71227788925 --8.16754436493,1.15053391457,4.7038769722 --8.21452140808,1.15553939342,4.69749689102 --8.26050662994,1.16154289246,4.70630121231 --8.30448436737,1.1665481329,4.69691085815 --8.36545944214,1.17355382442,4.69753170013 --8.41843605042,1.18055927753,4.69213724136 --8.47141170502,1.1865645647,4.68674707413 --8.54038619995,1.19457018375,4.69036483765 --8.62435817719,1.20657598972,4.70198774338 --11.4858436584,1.66664612293,6.24533748627 --11.4798345566,1.66264772415,6.19493627548 --11.4628257751,1.65664899349,6.1385307312 --11.4688129425,1.65465092659,6.09412527084 --11.4568033218,1.64965224266,6.04071903229 --11.4697904587,1.64865422249,6.0003156662 --11.4527873993,1.64365470409,5.96811103821 --11.4647741318,1.64265656471,5.9277100563 --11.4827594757,1.64265847206,5.8903093338 --11.5307407379,1.64766073227,5.86993026733 --8.01829242706,1.0816116333,3.96489453316 --8.01128673553,1.0796135664,3.9456949234 --8.00627326965,1.07661759853,3.91027736664 --8.00125980377,1.07362163067,3.87587070465 --8.01224327087,1.07362580299,3.84946751595 --7.99823188782,1.06962954998,3.81106066704 --8.0012178421,1.06763362885,3.78065252304 --8.00120353699,1.06663751602,3.74924826622 --7.98619890213,1.06263947487,3.72603797913 --7.98918437958,1.06164336205,3.69562625885 --7.97417259216,1.05764722824,3.65721511841 --7.98115825653,1.05665111542,3.62981677055 --7.98214435577,1.05465507507,3.59941339493 --7.99312877655,1.05465912819,3.5730035305 --7.98011684418,1.05066287518,3.53660011292 --7.96611213684,1.04766476154,3.51438736916 --7.96809864044,1.04666852951,3.48498678207 --7.98908185959,1.04767251015,3.46358394623 --8.04006004333,1.05367636681,3.45619940758 --8.10403728485,1.06168031693,3.45381307602 --8.16701412201,1.06968402863,3.45042419434 --8.21799468994,1.07668757439,3.44203996658 --8.27097988129,1.08368945122,3.44985890388 --8.32195949554,1.08969283104,3.44046902657 --8.39893531799,1.09969615936,3.44209003448 --8.44291591644,1.10469937325,3.42970633507 --8.51289367676,1.11370253563,3.4273223877 --8.5528755188,1.11870551109,3.41294050217 --8.62985134125,1.12870836258,3.41255760193 --11.6254205704,1.58469438553,4.59506511688 --11.6214103699,1.5816950798,4.55066251755 --11.6254014969,1.5796957016,4.50925970078 --11.6253910065,1.5776964426,4.46585083008 --11.6213817596,1.57469713688,4.42144489288 --11.6003799438,1.57069766521,4.39223909378 --11.6023712158,1.56869828701,4.35083961487 --11.6083602905,1.56769871712,4.31043481827 --11.5963525772,1.56369936466,4.26403188705 --11.5973434448,1.56169998646,4.22162246704 --11.5923347473,1.55870056152,4.17822265625 --11.5933246613,1.55670106411,4.13682126999 --11.5903205872,1.55570137501,4.11461639404 --11.5823125839,1.55170190334,4.06920337677 --11.5723047256,1.54870247841,4.02480554581 --11.5692958832,1.54570317268,3.98139286041 --11.5722856522,1.54470336437,3.94199991226 --11.5742769241,1.54270374775,3.90058994293 --11.570268631,1.54070413113,3.85818767548 --11.5672636032,1.53870439529,3.83698916435 --11.5552568436,1.53570497036,3.79157924652 --11.5672464371,1.53570497036,3.75417542458 --11.5682373047,1.53370523453,3.71377444267 --11.556230545,1.53070569038,3.66937065125 --11.5002279282,1.51970732212,3.60994386673 --11.4412260056,1.5097091198,3.55052042007 --11.4122247696,1.50470995903,3.52131080627 --11.4092159271,1.50171029568,3.47990179062 --11.422205925,1.50271010399,3.44349694252 --11.4012002945,1.49771094322,3.39708614349 --11.3951911926,1.49471139908,3.35568261147 --11.4081821442,1.49571120739,3.32028651237 --11.4041728973,1.49371147156,3.27988576889 --11.3891706467,1.48971188068,3.25466895103 --11.3971614838,1.48971176147,3.21827507019 --11.3891544342,1.48671221733,3.17586183548 --11.3781461716,1.48371267319,3.13345503807 --11.3931369781,1.48471212387,3.09906220436 --11.3821296692,1.48171257973,3.05665302277 --11.3841209412,1.48071241379,3.01825118065 --11.3801174164,1.47871255875,2.99704194069 --11.3651103973,1.47571313381,2.95463943481 --11.367102623,1.47371292114,2.91623592377 --11.3730945587,1.47371268272,2.8788318634 --11.359087944,1.47071301937,2.83642315865 --11.363079071,1.46971273422,2.79902291298 --11.3700704575,1.46871232986,2.76262593269 --11.381064415,1.46971166134,2.74542045593 --11.3690576553,1.46671199799,2.7040143013 --11.3450517654,1.46171271801,2.65960144997 --11.3520450592,1.46171212196,2.62320232391 --11.3890333176,1.46571016312,2.59381198883 --11.4210224152,1.46970820427,2.56342339516 --11.4510135651,1.47270643711,2.53203034401 --11.4720077515,1.47470510006,2.51783800125 --11.5079965591,1.47870290279,2.48845648766 --11.5339870453,1.48170101643,2.45505452156 --11.4929838181,1.47470247746,2.40763878822 --11.4669790268,1.46970319748,2.36322188377 --11.4569721222,1.4667031765,2.32281470299 --11.6369552612,1.4926930666,2.34369397163 --11.7029428482,1.50068867207,2.31931948662 --11.7299337387,1.50368630886,2.2859249115 --11.760925293,1.50668358803,2.25353503227 --11.7959156036,1.51068043709,2.22215056419 --11.8169078827,1.51267814636,2.18674969673 --11.8528995514,1.51667487621,2.155367136 --11.899892807,1.52367150784,2.14518618584 --11.9128856659,1.52366936207,2.10778188705 --11.56990242,1.47368919849,2.0032351017 --11.4129066467,1.44969797134,1.93576574326 --11.3829011917,1.444699049,1.89234542847 --11.3148984909,1.43370246887,1.84291565418 --11.2448968887,1.42270624638,1.79348349571 --11.3478870392,1.4376989603,1.79332709312 --11.2468862534,1.42170476913,1.73888230324 --11.2308807373,1.41870498657,1.69947290421 --11.1998758316,1.41370618343,1.65704977512 --11.2178678513,1.41570401192,1.62365627289 --11.16086483,1.40670716763,1.57823121548 --11.1948566437,1.41070365906,1.54683828354 --11.2158517838,1.41270172596,1.53164327145 --11.2228460312,1.41370010376,1.49624288082 --11.2828369141,1.42069470882,1.46886754036 --11.2858295441,1.42069327831,1.4324631691 --11.3438215256,1.42868757248,1.40408468246 --11.3278169632,1.42568767071,1.36568057537 --11.1888170242,1.40469717979,1.31021738052 --11.1988124847,1.4056956768,1.29301512241 --11.1818084717,1.40269589424,1.25460457802 --11.2647981644,1.4136878252,1.2292393446 --11.1677970886,1.39969456196,1.18079304695 --11.1797895432,1.40069210529,1.14538562298 --11.1637849808,1.39769220352,1.10798084736 --11.173781395,1.39869058132,1.09077942371 --11.1347780228,1.39269268513,1.05035829544 --11.1637706757,1.39668869972,1.01797032356 --11.1577653885,1.3946877718,0.981565892696 --11.1477603912,1.3926872015,0.94415217638 --11.1387557983,1.39168643951,0.907747805119 --11.1387500763,1.39068496227,0.872348487377 --11.1617441177,1.39368128777,0.838957190514 --11.1237421036,1.38768386841,0.816729187965 --11.1227369308,1.3876824379,0.78132891655 --11.1417312622,1.38967907429,0.74692940712 --11.1627264023,1.39267539978,0.713541328907 --11.1217212677,1.38567757607,0.674114584923 --11.120716095,1.38567590714,0.638713240623 --11.1607103348,1.39067018032,0.606330573559 --11.1757078171,1.3926678896,0.589130580425 --11.1227045059,1.38467133045,0.549702048302 --11.1126995087,1.38367044926,0.514302611351 --11.1176948547,1.38366806507,0.47889867425 --11.1116895676,1.38266670704,0.442485779524 --11.1766853333,1.3916580677,0.411116808653 --11.1716823578,1.39065742493,0.392911553383 --11.169678688,1.38965570927,0.35751080513 --11.151673317,1.38765537739,0.321099489927 --11.2046689987,1.39464759827,0.287717729807 --11.1956653595,1.39264643192,0.251306325197 --11.2106609344,1.39464259148,0.216917440295 --11.251657486,1.40063560009,0.182531058788 --11.1156549454,1.38164961338,0.159257799387 --11.2056503296,1.39363718033,0.12689897418 --11.1096467972,1.38064575195,0.0884490981698 --11.1626434326,1.38763725758,0.0550780370831 --11.212638855,1.39462912083,0.0196870397776 --11.2366361618,1.3976238966,-0.0146956210956 --11.108631134,1.3796364069,-0.0531682632864 --11.0896291733,1.3766374588,-0.0703706741333 --11.1076259613,1.37963283062,-0.105769589543 --11.1036224365,1.37863075733,-0.141175583005 --11.1396188736,1.38362371922,-0.176564767957 --11.1886167526,1.39061498642,-0.211945265532 --11.0836114883,1.37562537193,-0.247399732471 --11.2186107635,1.39460575581,-0.282732069492 --11.1686077118,1.3876105547,-0.300966024399 --11.1706047058,1.38860750198,-0.336367279291 --11.1536016464,1.38560676575,-0.37178003788 --11.1555995941,1.38660371304,-0.407181620598 --11.1785964966,1.38959789276,-0.442567914724 --11.1655931473,1.387596488,-0.477979242802 --11.1865911484,1.39059066772,-0.514376461506 --11.2095909119,1.39458608627,-0.53256469965 --11.2265892029,1.39658069611,-0.568962216377 --11.1405830383,1.38458919525,-0.601402640343 --11.0935792923,1.37859249115,-0.63583701849 --11.1375780106,1.384583354,-0.672211110592 --11.157576561,1.38757717609,-0.708605587482 --11.1205720901,1.38257908821,-0.743033885956 --11.1295728683,1.38457632065,-0.761231958866 --11.1895723343,1.39256441593,-0.799604356289 --11.1775693893,1.39156270027,-0.834006786346 --11.1855688095,1.39255809784,-0.870409607887 --11.3055725098,1.41053688526,-0.913759231567 --11.2755699158,1.40653777122,-0.947168827057 --11.2775678635,1.40653371811,-0.983574211597 --11.3865737915,1.42251563072,-1.00871908665 --11.273566246,1.40652871132,-1.03717970848 --11.2415628433,1.40252971649,-1.07160782814 --11.2465610504,1.40352499485,-1.1080095768 --11.2415599823,1.40352189541,-1.14341366291 --11.3315649033,1.41650402546,-1.18677020073 --11.351565361,1.42049694061,-1.22516798973 --11.2675590515,1.40850806236,-1.23540604115 --11.1395492554,1.39052426815,-1.2598747015 --11.2215547562,1.40250730515,-1.30323541164 --11.198551178,1.39950680733,-1.33765792847 --11.2795572281,1.4114896059,-1.38101160526 --11.2125511169,1.40349626541,-1.4104514122 --11.2145519257,1.40349376202,-1.42865169048 --11.2025499344,1.40249156952,-1.4640686512 --11.3585624695,1.42546129227,-1.51739013195 --11.2655544281,1.41247236729,-1.54283642769 --11.3435602188,1.42445468903,-1.58819818497 --11.4025659561,1.43343985081,-1.63257813454 --11.3865652084,1.43143796921,-1.66698527336 --11.4075670242,1.43443202972,-1.68817782402 --11.3935661316,1.4334294796,-1.72359251976 --11.323559761,1.42443692684,-1.75103092194 --11.3465623856,1.42842805386,-1.79041826725 --11.3545637131,1.43042182922,-1.82882344723 --11.4245710373,1.44040441513,-1.87518584728 --11.4145717621,1.44040107727,-1.91059243679 --11.4165716171,1.44039809704,-1.92979693413 --11.4595775604,1.44738507271,-1.9731760025 --11.4975824356,1.45437276363,-2.01656270027 --11.620595932,1.47234475613,-2.07289767265 --11.4795827866,1.45336544514,-2.08837676048 --11.4545822144,1.45036458969,-2.12179374695 --11.6786088943,1.48331689835,-2.19607543945 --11.5395946503,1.46334028244,-2.19235563278 --11.9506435394,1.52325606346,-2.30054330826 --11.7236194611,1.49229335785,-2.3000664711 --11.6776161194,1.48629629612,-2.33049583435 --11.6146116257,1.478302598,-2.35692739487 --11.5886106491,1.47530162334,-2.39034509659 --11.6926259995,1.49127519131,-2.44769048691 --11.7006292343,1.49327039719,-2.46889281273 --11.6046190262,1.48028337955,-2.48834037781 --11.7956466675,1.50823867321,-2.56464886665 --11.5836219788,1.47927510738,-2.56116271019 --11.6546344757,1.49025440216,-2.61352467537 --11.8636665344,1.52220499516,-2.69582462311 --11.7976608276,1.51321172714,-2.72126197815 --11.8056640625,1.5152066946,-2.74245858192 --11.7726631165,1.51120686531,-2.77488231659 --11.8036718369,1.51719367504,-2.82026410103 --11.793674469,1.51718878746,-2.85767579079 --11.8486862183,1.52617001534,-2.90904664993 --11.880695343,1.53215622902,-2.95542812347 --12.0687294006,1.56010830402,-3.03873300552 --11.8546981812,1.53015089035,-3.00904750824 --11.9147129059,1.54013037682,-3.06342363358 --11.9427213669,1.54511702061,-3.10980892181 --12.168762207,1.57905948162,-3.20408415794 --12.1337633133,1.57605934143,-3.23650693893 --12.2567892075,1.59502375126,-3.3088517189 --12.1817827225,1.58603239059,-3.33129525185 --12.2177906036,1.5910204649,-3.36047172546 --12.5698575974,1.64393186569,-3.49268722534 --12.4798488617,1.63294374943,-3.5111322403 --12.4688539505,1.63293755054,-3.55054068565 --12.4128513336,1.62594175339,-3.57797408104 --12.4138584137,1.62793278694,-3.6203751564 --12.4498691559,1.63391983509,-3.65155887604 --12.5748996735,1.65388131142,-3.72889709473 --12.6169147491,1.66186213493,-3.7832736969 --12.6099214554,1.66185450554,-3.82468175888 --12.6789426804,1.67382848263,-3.8870408535 --13.0570240021,1.73072731495,-4.04023838043 --12.9810190201,1.72173559666,-4.06268024445 --13.0200309753,1.72872078419,-4.09686326981 --12.9700298309,1.7227230072,-4.12628746033 --13.0170497894,1.73170089722,-4.18566703796 --13.0000562668,1.7306946516,-4.22608327866 --12.9210500717,1.72070395947,-4.2465262413 --13.4271650314,1.79756581783,-4.4486451149 --13.2231330872,1.76960623264,-4.43115997314 --13.3111572266,1.78357827663,-4.4823141098 --13.5442180634,1.82050704956,-4.60358858109 --13.6442518234,1.83646965027,-4.68293094635 --13.724281311,1.85043716431,-4.7562828064 --13.6642808914,1.84444022179,-4.78572702408 --13.569272995,1.83245301247,-4.80218267441 --13.4852666855,1.82146310806,-4.82163047791 --13.5783004761,1.83742630482,-4.90097999573 --13.8103590012,1.87335836887,-5.00404691696 --13.6773433685,1.85538113117,-5.00752782822 --13.763376236,1.8713452816,-5.08587884903 --13.7873954773,1.87632584572,-5.14326572418 --13.6623802185,1.86034715176,-5.14773654938 --13.9114542007,1.90026581287,-5.28599500656 --14.3405666351,1.96614050865,-5.46695947647 --14.515625,1.9940778017,-5.58226013184 --14.4866342545,1.9930716753,-5.62266969681 --14.7697219849,2.03797745705,-5.78091430664 --14.8467588425,2.05194044113,-5.86327219009 --15.1068439484,2.09385108948,-6.01552343369 --14.9038105011,2.0658929348,-5.9930434227 --15.2869186401,2.12577557564,-6.16702127457 --15.3589572906,2.13873839378,-6.25037765503 --15.495013237,2.16268205643,-6.35970020294 --15.3800029755,2.14769864082,-6.37116909027 --15.4850530624,2.16665077209,-6.46950912476 --15.4990777969,2.17162966728,-6.53189992905 --15.5281057358,2.17960333824,-6.60128736496 --15.5181150436,2.1795976162,-6.6254901886 --15.5291395187,2.1845767498,-6.68788766861 --15.5261602402,2.18655967712,-6.74428987503 --15.5161790848,2.18854522705,-6.79769515991 --15.5342073441,2.19452166557,-6.86308479309 --15.5072212219,2.19351172447,-6.90949964523 --15.5082445145,2.19649338722,-6.96789884567 --15.514257431,2.19948220253,-7.00009870529 --15.5132808685,2.20246458054,-7.05749559402 --15.5023002625,2.20444941521,-7.11190795898 --15.5173282623,2.20942592621,-7.17729949951 --15.4883432388,2.20841646194,-7.2227139473 --15.4953689575,2.21339535713,-7.28511285782 --15.4813890457,2.21438074112,-7.33852577209 --15.4884033203,2.21736931801,-7.37071800232 --15.4824256897,2.21935200691,-7.42712020874 --15.4924545288,2.22432947159,-7.49151659012 --15.4534664154,2.22232294083,-7.53294038773 --15.455491066,2.22630286217,-7.5933380127 --15.4785251617,2.23327565193,-7.66472816467 --15.4555425644,2.23326349258,-7.71414422989 --15.4845657349,2.24024391174,-7.75832796097 --15.4855918884,2.24422335625,-7.81973075867 --15.4676113129,2.24420952797,-7.87113904953 --15.4646368027,2.24819016457,-7.93054246902 --15.4836702347,2.25416350365,-8.00093173981 --15.4696922302,2.25614786148,-8.05534172058 --15.4647169113,2.25912880898,-8.11374282837 --15.4997444153,2.26710629463,-8.16292667389 --15.4927692413,2.27008795738,-8.22032642365 --15.5027999878,2.27506327629,-8.28772354126 --15.5128316879,2.28103852272,-8.35511779785 --15.4998559952,2.2830221653,-8.41052532196 --15.4948825836,2.28600215912,-8.47093105316 --15.485909462,2.28898382187,-8.52934074402 --15.481921196,2.28997421265,-8.55854225159 --15.4679450989,2.29195737839,-8.61395072937 --15.4609718323,2.29493808746,-8.67335605621 --15.4429950714,2.29692268372,-8.72676753998 --15.4360227585,2.29990339279,-8.78617095947 --15.4330511093,2.30388188362,-8.84857559204 --15.4080724716,2.30386853218,-8.8989944458 --15.3940830231,2.30386257172,-8.923204422 --15.3891115189,2.3078417778,-8.98460865021 --15.3411226273,2.30383729935,-9.02103614807 --15.3261480331,2.30582022667,-9.07744979858 --15.3461875916,2.31378960609,-9.15283489227 --15.3352155685,2.31677031517,-9.21224880219 --15.3192243576,2.31676506996,-9.23546028137 --15.3172550201,2.32074260712,-9.29885959625 --15.2882757187,2.32073020935,-9.34728050232 --15.2602958679,2.32071781158,-9.39569664001 --15.2613296509,2.32569360733,-9.46209907532 --15.2443552017,2.32767653465,-9.51751041412 --15.2393865585,2.33165431023,-9.5809173584 --15.2334012985,2.332644701,-9.61012077332 --15.2034215927,2.33263278008,-9.657538414 --15.2264661789,2.34159898758,-9.73892974854 --15.2355041504,2.34757089615,-9.81031894684 --15.2185316086,2.35055279732,-9.86773777008 --15.2235689163,2.35652589798,-9.93813705444 --15.2216033936,2.36050152779,-10.0045394897 --15.2176198959,2.36249065399,-10.035741806 --15.2426662445,2.37145519257,-10.1191234589 --15.4528007507,2.4123415947,-10.3233947754 --15.6329240799,2.44823932648,-10.5106859207 --15.4968967438,2.43027019501,-10.4921731949 --15.4299030304,2.42427206039,-10.5176134109 --15.507979393,2.44321203232,-10.639966011 --15.4539737701,2.43722128868,-10.640206337 --15.3929815292,2.43222045898,-10.6696443558 --15.3179836273,2.42522573471,-10.6900939941 --15.2770032883,2.42321681976,-10.7325201035 --15.2230148315,2.42021298409,-10.7669582367 --15.1620235443,2.41521263123,-10.7953968048 --15.1180410385,2.41320490837,-10.8358259201 --15.106054306,2.41419649124,-10.863035202 --15.0370578766,2.40820002556,-10.8854799271 --14.9700641632,2.40220212936,-10.9099273682 --14.9170761108,2.39819860458,-10.943362236 --14.8650894165,2.39519453049,-10.9778003693 --14.8161039352,2.39318919182,-11.0132312775 --14.7711200714,2.39118242264,-11.0516605377 --14.7221136093,2.38519096375,-11.0518941879 --14.6721277237,2.38218593597,-11.0873317719 --14.6221408844,2.37918138504,-11.1217651367 --14.556145668,2.37418437004,-11.1442098618 --14.5081605911,2.37117910385,-11.17964077 --14.4461679459,2.36617970467,-11.2060909271 --14.3961811066,2.36417555809,-11.2395238876 --14.3401708603,2.35718822479,-11.2327604294 --14.3101949692,2.35717463493,-11.2811794281 --14.2492008209,2.35317516327,-11.3066253662 --14.2042179108,2.35116863251,-11.3440589905 --14.1522302628,2.34816551208,-11.375494957 --14.0932378769,2.34316587448,-11.4009332657 --14.0362462997,2.34016537666,-11.4283752441 --14.0112524033,2.33816337585,-11.4445924759 --13.9572629929,2.33516144753,-11.4740314484 --13.9172821045,2.33415269852,-11.5144615173 --13.8652935028,2.33114981651,-11.5448980331 --13.8163070679,2.32814526558,-11.578335762 --13.7773265839,2.32813620567,-11.6187620163 --13.7243375778,2.32513356209,-11.6492061615 --13.6843338013,2.32013988495,-11.6514282227 --13.6403512955,2.31913280487,-11.6888656616 --13.5913629532,2.31712889671,-11.7202978134 --13.5503826141,2.31612062454,-11.7597312927 --13.5053977966,2.3141143322,-11.795165062 --13.4604139328,2.31210827827,-11.8305988312 --13.422410965,2.3091135025,-11.8348264694 --13.3754253387,2.30710840225,-11.868262291 --13.334444046,2.3061003685,-11.9066934586 --13.2854566574,2.30309700966,-11.9371242523 --13.2364702225,2.30109286308,-11.9695672989 --13.192486763,2.30008625984,-12.0050010681 --13.1424980164,2.29708337784,-12.0344333649 --13.1084985733,2.29408621788,-12.0426654816 --13.0795249939,2.29607224464,-12.0900821686 --13.0215320587,2.29207324982,-12.113530159 --12.9725446701,2.2900698185,-12.1439666748 --12.9325637817,2.28906130791,-12.1823968887 --12.8955850601,2.28905105591,-12.2238264084 --12.8475980759,2.28704690933,-12.2552652359 --12.8316116333,2.28804039955,-12.2784795761 --12.7866268158,2.28603482246,-12.3119115829 --12.7376394272,2.28403139114,-12.3413467407 --12.7026615143,2.28502011299,-12.3847780228 --12.6656837463,2.28500962257,-12.4262075424 --12.6176977158,2.28300523758,-12.457649231 --12.5797185898,2.28299593925,-12.4970750809 --12.5617294312,2.28299021721,-12.5182914734 --12.5257520676,2.28397917747,-12.5607213974 --12.4787664413,2.28197479248,-12.5921583176 --12.4387865067,2.28196597099,-12.6305923462 --12.39980793,2.28195667267,-12.6700248718 --12.362830162,2.28194618225,-12.7114562988 --12.3098392487,2.27894568443,-12.7358932495 --12.2938528061,2.27993822098,-12.7601127625 --12.2578754425,2.28092741966,-12.8015394211 --12.2158946991,2.27991986275,-12.8379745483 --12.1719121933,2.27891349792,-12.8724117279 --12.1449422836,2.28189659119,-12.9238367081 --12.1029605865,2.28088903427,-12.9592666626 --12.0659828186,2.28187847137,-13.0006980896 --12.0550012589,2.283867836,-13.0299119949 --12.0040130615,2.28186631203,-13.0563526154 --11.9620323181,2.28085875511,-13.0917835236 --11.9150466919,2.27985405922,-13.1232261658 --11.9080953598,2.28682374954,-13.1966352463 --11.8621120453,2.28481841087,-13.2290754318 --11.8191299438,2.28481149673,-13.2635087967 --11.8041448593,2.28580379486,-13.2877197266 --11.7681703568,2.28679180145,-13.3311548233 --11.7392015457,2.28977489471,-13.3825845718 --11.6992225647,2.28976559639,-13.4210186005 --11.6612453461,2.28975558281,-13.4604444504 --11.6262722015,2.29174280167,-13.5048770905 --11.5922994614,2.29372882843,-13.5513114929 --11.5653047562,2.29172897339,-13.5625333786 --11.5183200836,2.2907242775,-13.5929718018 --11.4853487015,2.29270982742,-13.6404047012 --11.4493741989,2.29369783401,-13.6828327179 --11.4174041748,2.29568266869,-13.7312631607 --11.3814306259,2.29767036438,-13.7746953964 --11.3514633179,2.30065321922,-13.8261260986 --11.3424835205,2.30264091492,-13.8573293686 --11.3035087585,2.30363035202,-13.8977642059 --11.2615299225,2.30362153053,-13.9352035522 --11.2295598984,2.30560612679,-13.9836320877 --11.1895847321,2.30659556389,-14.0240726471 --11.1506090164,2.30758547783,-14.063501358 --11.1476373672,2.31156754494,-14.1047105789 --11.1226768494,2.31654596329,-14.1631364822 --11.0867042542,2.3175330162,-14.2075681686 --11.0707530975,2.32350468636,-14.2769842148 --11.0327806473,2.32549238205,-14.3204221725 --10.9827947617,2.32348942757,-14.3478651047 --10.8186893463,2.29657387733,-14.2293891907 --10.7576904297,2.2925798893,-14.2418413162 --10.6195774078,2.26566648483,-14.1081390381 --10.5485677719,2.25968074799,-14.1066007614 --10.4645423889,2.24970626831,-14.0860643387 --10.3985376358,2.24471735954,-14.0895195007 --10.3515520096,2.24371361732,-14.1179618835 --10.3315963745,2.24968838692,-14.1823863983 --10.3246221542,2.25267386436,-14.2175912857 --10.2916526794,2.25465869904,-14.2650241852 --10.2206411362,2.24867415428,-14.2614850998 --9.85830020905,2.17292714119,-13.8591508865 --9.58505344391,2.1171104908,-13.5737533569 --9.34484195709,2.06926894188,-13.3293323517 --9.25479984283,2.05730509758,-13.2898015976 --9.16672992706,2.04135894775,-13.2100696564 --9.11072635651,2.03736758232,-13.2175197601 --9.02268600464,2.02540326118,-13.1789913177 --8.95967292786,2.0204179287,-13.175444603 --8.85661315918,2.00446677208,-13.1149320602 --8.74754428864,1.98752200603,-13.0434188843 --8.69454193115,1.98452961445,-13.051864624 --8.63750457764,1.97555971146,-13.0121126175 --8.54645442963,1.96260094643,-12.9635839462 --8.44439029694,1.94665193558,-12.8990697861 --8.38237571716,1.94066798687,-12.8935279846 --8.30233764648,1.93070077896,-12.8589944839 --8.30440330505,1.941660285,-12.9484043121 --8.2273683548,1.93169140816,-12.9168653488 --8.19535827637,1.92870056629,-12.9120969772 --8.17039108276,1.93268382549,-12.9615297318 --8.14842605591,1.93666505814,-13.0139503479 --8.12145614624,1.93965041637,-13.0593776703 --8.09648799896,1.94363355637,-13.1088056564 --8.01544761658,1.93366837502,-13.0712814331 --7.93841028214,1.92370009422,-13.0387516022 --7.88036346436,1.91373562813,-12.9889907837 --7.80833244324,1.90476322174,-12.9634590149 --7.75532627106,1.90177357197,-12.9669084549 --7.53909111023,1.85394215584,-12.7024688721 --7.49209213257,1.85194718838,-12.714922905 --7.4180521965,1.84198021889,-12.6793804169 --7.48117494583,1.8648982048,-12.8285427094 --7.50327396393,1.88083577156,-12.9549369812 --7.3751578331,1.85692155361,-12.8304433823 --7.21499300003,1.82304060459,-12.649974823 --7.17900657654,1.82403695583,-12.676407814 --7.0819311142,1.8080945015,-12.5998935699 --7.2332239151,1.86089920998,-12.9511947632 --7.13114023209,1.84296238422,-12.8646774292 --7.085105896,1.83598899841,-12.829916954 --7.06714868546,1.84196543694,-12.8903427124 --6.89295244217,1.80310487747,-12.6748876572 --6.61759519577,1.73535358906,-12.2735004425 --6.70580053329,1.77121925354,-12.5218505859 --6.84508895874,1.82302939892,-12.864153862 --6.86816167831,1.83598291874,-12.9533443451 --6.76807451248,1.81804764271,-12.8638286591 --6.74410963058,1.82302963734,-12.9152641296 --6.7071223259,1.82302701473,-12.9396953583 --6.63708257675,1.81405949593,-12.9051647186 --6.55101442337,1.80011129379,-12.8376369476 --6.45092153549,1.78217947483,-12.7421207428 --6.45496559143,1.78915250301,-12.798327446 --6.41597414017,1.7891523838,-12.8187675476 --6.35995578766,1.7841707468,-12.8082284927 --6.36604166031,1.79811894894,-12.9166345596 --6.3180346489,1.79512941837,-12.9190778732 --6.24999380112,1.78616225719,-12.8835439682 --6.17894554138,1.77620029449,-12.8390054703 --6.09283256531,1.75527846813,-12.7162799835 --6.03079986572,1.7483061552,-12.689743042 --5.98479318619,1.74531590939,-12.6931858063 --5.94079113007,1.74332284927,-12.7016305923 --5.8917798996,1.74033617973,-12.6990785599 --5.82473421097,1.73137199879,-12.6585407257 --5.70258569717,1.70347583294,-12.5020484924 --5.42710494995,1.61879587173,-11.9664554596 --5.8379611969,1.76723623276,-12.9405660629 --5.79596424103,1.76724028587,-12.9540109634 --5.68383169174,1.74233353138,-12.8155097961 --5.67489910126,1.75329530239,-12.9009342194 --5.64793014526,1.75728058815,-12.9463663101 --5.62793397903,1.7572811842,-12.9555912018 --5.44565391541,1.70747005939,-12.6531352997 --5.53291511536,1.75130498409,-12.9554872513 --5.43981266022,1.73237788677,-12.8509683609 --5.39781475067,1.73238265514,-12.8634185791 --5.30771493912,1.71345341206,-12.7628984451 --5.30679988861,1.72740387917,-12.867307663 --5.40304803848,1.76924538612,-13.1484470367 --5.36506032944,1.77024376392,-13.1718931198 --5.29299783707,1.75829029083,-13.1123571396 --5.23496580124,1.75231719017,-13.0868177414 --5.21000432968,1.75729835033,-13.1392469406 --5.20909786224,1.77224397659,-13.252664566 --5.09694480896,1.74534904957,-13.0931663513 --5.24833297729,1.81010186672,-13.5262594223 --5.24542760849,1.82404696941,-13.6406803131 --5.120241642,1.79217302799,-13.4451828003 --5.11533308029,1.80612099171,-13.5546045303 --5.03324270248,1.79018509388,-13.4650754929 --5.03234529495,1.80612611771,-13.5864944458 --4.91216278076,1.77524924278,-13.3959980011 --4.83001804352,1.75034487247,-13.242269516 --4.7469201088,1.7334138155,-13.1447477341 --4.68386936188,1.72445225716,-13.0992126465 --4.65690660477,1.72943472862,-13.1496477127 --4.64799022675,1.74238801003,-13.2500705719 --4.61401081085,1.74538075924,-13.2825098038 --4.50383758545,1.71649730206,-13.1030082703 --4.52394247055,1.73243367672,-13.2221975327 --4.51904010773,1.74837827682,-13.3376188278 --4.43192243576,1.72845923901,-13.2190990448 --4.39593887329,1.73045516014,-13.2465429306 --4.35594511032,1.73045742512,-13.2629919052 --4.33700847626,1.73942375183,-13.3414230347 --4.33612346649,1.75735807419,-13.4748430252 --4.31412172318,1.75736260414,-13.47706604 --4.30421257019,1.77131187916,-13.5844869614 --4.26723146439,1.77330672741,-13.6139354706 --4.15803956985,1.74143338203,-13.416425705 --4.08695697784,1.72849166393,-13.3368997574 --4.11917591095,1.76236152649,-13.5812950134 --4.07009315491,1.74841654301,-13.4965353012 --4.05417299271,1.76037311554,-13.5919675827 --4.01618862152,1.76237034798,-13.6174144745 --3.98923707008,1.76934707165,-13.6778507233 --3.94523358345,1.76835584641,-13.6833000183 --3.90022706985,1.76736688614,-13.6847496033 --3.85923576355,1.76736843586,-13.7032060623 --3.8141579628,1.75541985035,-13.6244411469 --3.78921675682,1.7643904686,-13.6958818436 --3.72414398193,1.75244224072,-13.6273488998 --3.65605807304,1.7385020256,-13.5448141098 --3.65018296242,1.75743210316,-13.6862440109 --3.63628149033,1.77237832546,-13.7996730804 --3.58826255798,1.76839673519,-13.7881221771 --3.56425499916,1.76740515232,-13.7843513489 --3.52025079727,1.76641452312,-13.7888031006 --3.49230194092,1.7733900547,-13.851234436 --3.4533200264,1.7763864994,-13.8786907196 --3.40730953217,1.7743999958,-13.8761444092 --3.37334275246,1.77838671207,-13.9195861816 --3.33335590363,1.78038597107,-13.9420375824 --3.31536841393,1.7823818922,-13.9592571259 --3.26935982704,1.78039443493,-13.9587154388 --3.2293715477,1.78239452839,-13.9791612625 --3.20143079758,1.79036581516,-14.0495977402 --3.14839363098,1.78439557552,-14.0190601349 --3.11643981934,1.79137504101,-14.075501442 --3.09553670883,1.80532407761,-14.1849431992 --3.07554268837,1.80632400513,-14.1951627731 --3.03957676888,1.81131100655,-14.238609314 --2.99557828903,1.81131780148,-14.2480659485 --2.96463608742,1.81929051876,-14.3165102005 --2.92766952515,1.82427823544,-14.3589601517 --2.8836710453,1.82428491116,-14.3684139252 --2.82459950447,1.8133354187,-14.3018712997 --2.82269597054,1.82728147507,-14.406088829 --2.77668809891,1.82629406452,-14.4055433273 --2.73369169235,1.82629954815,-14.4169893265 --2.68869042397,1.82630825043,-14.4234485626 --2.64569544792,1.82731306553,-14.4358978271 --2.60270380974,1.82831597328,-14.4523534775 --2.58171200752,1.82931506634,-14.4645824432 --2.53570222855,1.82732880116,-14.4620351791 --2.49070096016,1.82733750343,-14.4684944153 --2.44871258736,1.82933855057,-14.4879436493 --2.40370583534,1.82735037804,-14.4883918762 --2.35870456696,1.82735919952,-14.4948511124 --2.3167181015,1.82935917377,-14.5163040161 --2.26869869232,1.82637882233,-14.5037641525 --2.24870920181,1.82837665081,-14.5179853439 --2.20370697975,1.82738602161,-14.5234422684 --2.16071200371,1.82839107513,-14.5358905792 --2.11571192741,1.82839930058,-14.5433511734 --2.07171416283,1.82940626144,-14.5528068542 --2.02469921112,1.8274230957,-14.5452661514 --2.00270175934,1.82742583752,-14.5514945984 --1.95970869064,1.82842993736,-14.5659456253 --1.91369998455,1.82744324207,-14.5644054413 --1.86868953705,1.82645761967,-14.5608530045 --1.82570433617,1.8284573555,-14.583313942 --1.78069663048,1.82747006416,-14.5827655792 --1.73569571972,1.82747900486,-14.5892267227 --1.71470630169,1.82947707176,-14.6034545898 --1.66767990589,1.82550060749,-14.58390522 --1.6246919632,1.82750201225,-14.6033601761 --1.58069813251,1.82850706577,-14.6168193817 --1.53569042683,1.82751977444,-14.6162719727 --1.48967480659,1.82553720474,-14.6077280045 --1.44669008255,1.82853710651,-14.6301851273 --1.42469954491,1.82953596115,-14.6434202194 --1.38069689274,1.82954585552,-14.6478691101 --1.33670449257,1.83155035973,-14.6623268127 --1.29068982601,1.82956731319,-14.6547851562 --1.24669110775,1.8295750618,-14.6632375717 --1.20270645618,1.83257508278,-14.6857023239 --1.15769982338,1.83158755302,-14.6861572266 --1.13570761681,1.83358764648,-14.697388649 --1.09171724319,1.8355909586,-14.713848114 --1.04670763016,1.83460497856,-14.7113008499 --1.0027141571,1.83561015129,-14.7247552872 --0.957720577717,1.83661544323,-14.7382202148 --0.913719415665,1.83762490749,-14.7436695099 --0.868717849255,1.83763468266,-14.7491283417 --0.846735775471,1.84062922001,-14.7703638077 --0.802738547325,1.84163653851,-14.7798147202 --0.757744073868,1.84264230728,-14.7922763824 --0.713755905628,1.84464478493,-14.8107309341 --0.667744398117,1.84366035461,-14.8061933517 --0.622757315636,1.84666240215,-14.8256578445 --0.57775080204,1.84567499161,-14.8261127472 --0.554748594761,1.84568083286,-14.8273458481 --0.509744286537,1.84569239616,-14.8298015594 --0.464751243591,1.84769773483,-14.8432617188 --0.419734716415,1.84571611881,-14.8337135315 --0.373739600182,1.84772288799,-14.8451833725 --0.328722089529,1.84574186802,-14.8346357346 --0.282685190439,1.84177172184,-14.8050937653 --0.260708421469,1.84476339817,-14.83132267 --0.215728804469,1.84876155853,-14.8577852249 --0.169713303447,1.84777963161,-14.8492498398 --0.124699644744,1.84579646587,-14.8427047729 --0.0796995908022,1.84680593014,-14.8491621017 --0.0336974188685,1.84781682491,-14.8536291122 --0.0116819674149,1.84582984447,-14.8418512344 -0.0217007044703,1.84416389465,-14.0281744003 -0.0667212978005,1.84616267681,-14.0425395966 -0.11275138706,1.85016608238,-14.0659103394 -0.157771885395,1.85216462612,-14.0802745819 -0.203783348203,1.85315811634,-14.0856466293 -0.248788505793,1.85314834118,-14.0850124359 -0.271793603897,1.8531447649,-14.0871992111 -0.316759973764,1.84711360931,-14.048576355 -0.364882618189,1.86416780949,-14.1629314423 -0.414000689983,1.87921917439,-14.2732906342 -0.461043566465,1.88522958755,-14.3096532822 -0.510110497475,1.89325296879,-14.3700218201 -0.556124687195,1.89524793625,-14.3783836365 -0.580144822598,1.89725255966,-14.395567894 -0.628188431263,1.90326321125,-14.4329319 -0.675186276436,1.90224909782,-14.4253072739 -0.749278128147,1.9142793417,-14.5078496933 -0.796288013458,1.91527199745,-14.5122175217 -0.843300819397,1.91626608372,-14.5195837021 -0.868328094482,1.92027437687,-14.5437650681 -0.915329039097,1.9202619791,-14.5391368866 -0.963339924812,1.92125487328,-14.5445108414 -1.01035487652,1.92325019836,-14.5538740158 -1.0583717823,1.92524659634,-14.5652418137 -1.10536539555,1.92323029041,-14.5536184311 -1.1533895731,1.92723059654,-14.5719795227 -1.17738735676,1.92622292042,-14.5671710968 -1.2264200449,1.93022787571,-14.5945339203 -1.27241301537,1.9292113781,-14.5819034576 -1.32042372227,1.93020451069,-14.5872735977 -1.36943972111,1.9322000742,-14.5976467133 -1.41745448112,1.93419539928,-14.6070127487 -1.465462327,1.93518686295,-14.6093835831 -1.48946833611,1.93618369102,-14.6125679016 -1.53647017479,1.93617212772,-14.6089372635 -1.58649790287,1.94017410278,-14.6313037872 -1.63450288773,1.94116401672,-14.6306762695 -1.68351960182,1.94316029549,-14.6420450211 -1.73152339458,1.94314968586,-14.6404190063 -1.75351035595,1.9411367178,-14.6246070862 -1.79950451851,1.94112110138,-14.6129760742 -1.84851622581,1.94211483002,-14.6193494797 -1.89854192734,1.94611573219,-14.6397123337 -1.94453585148,1.94510030746,-14.6280822754 -1.99254179001,1.94609081745,-14.628452301 -2.04155039787,1.94708299637,-14.6318273544 -2.06454658508,1.94707477093,-14.6250133514 -2.11355948448,1.94906890392,-14.6323814392 -2.16256833076,1.95006108284,-14.6357555389 -2.20554089546,1.94603466988,-14.6021318436 -2.25153017044,1.94501686096,-14.5855093002 -2.29752707481,1.94400322437,-14.576877594 -2.3455312252,1.9449930191,-14.5752506256 -2.36953520775,1.94598889351,-14.5764331818 -2.41652941704,1.94497358799,-14.5648136139 -2.46352791786,1.94496047497,-14.5571870804 -2.50952315331,1.94494593143,-14.5465583801 -2.55450963974,1.94292700291,-14.5269355774 -2.59949612617,1.94090795517,-14.5073137283 -2.64951014519,1.94390273094,-14.5156850815 -2.67351388931,1.94389879704,-14.516869545 -2.71850085258,1.94288003445,-14.4972476959 -2.76349329948,1.94186425209,-14.4836168289 -2.80948495865,1.94084787369,-14.4689970016 -2.8544728756,1.93982970715,-14.4503755569 -2.89544415474,1.93580329418,-14.4147548676 -2.93641376495,1.93177616596,-14.3771381378 -2.95840811729,1.93076741695,-14.3683252335 -3.00038456917,1.92774367332,-14.3377056122 -3.04336500168,1.92472195625,-14.311088562 -3.09237337112,1.9267141819,-14.3134641647 -3.15042448044,1.93472802639,-14.3608207703 -3.2084748745,1.94274139404,-14.4071769714 -3.23850131035,1.94774830341,-14.4313592911 -3.28449583054,1.94673383236,-14.4197340012 -3.32848119736,1.94571459293,-14.3981132507 -3.36845111847,1.94168794155,-14.3604955673 -3.40942311287,1.93766224384,-14.324883461 -3.43935489655,1.92761695385,-14.2472763062 -3.47731947899,1.92258787155,-14.2036619186 -3.49730658531,1.92157578468,-14.1868524551 -3.5182056427,1.90651464462,-14.0742607117 -3.54512691498,1.89446413517,-13.9846696854 -3.59012508392,1.89545202255,-13.9760408401 -3.6311044693,1.89243042469,-13.947426796 -3.66606259346,1.88639879227,-13.8968172073 -3.7140724659,1.88939213753,-13.9001846313 -3.72803997993,1.88437068462,-13.8623838425 -3.75697779655,1.87532925606,-13.7897853851 -3.80398106575,1.87631940842,-13.7861642838 -3.83794188499,1.87128925323,-13.7375516891 -3.87089800835,1.86425685883,-13.6839456558 -3.91489195824,1.86424279213,-13.6703281403 -3.95086050034,1.86021661758,-13.6297149658 -3.96282577515,1.85519421101,-13.5889148712 -4.00381231308,1.85317671299,-13.5672969818 -4.03978061676,1.84915065765,-13.5266895294 -4.07775831223,1.84612882137,-13.4950761795 -4.11473274231,1.843105793,-13.4604625702 -4.15371465683,1.84108638763,-13.4338464737 -4.18768167496,1.83705997467,-13.3912343979 -4.20967769623,1.83605217934,-13.3824338913 -4.24063777924,1.83102238178,-13.3318243027 -4.27761316299,1.82800006866,-13.2982149124 -4.31760120392,1.82698380947,-13.2775936127 -4.34755754471,1.81995236874,-13.222992897 -4.38553857803,1.81793260574,-13.1943807602 -4.42352056503,1.81591379642,-13.1677646637 -4.4364938736,1.81189596653,-13.134967804 -4.47547960281,1.81087851524,-13.1113519669 -4.51646900177,1.8098628521,-13.0917406082 -4.54943990707,1.80583882332,-13.0521278381 -4.57940149307,1.80081045628,-13.0025243759 -4.62239933014,1.80079889297,-12.9919033051 -4.63236713409,1.79677867889,-12.9531068802 -4.67335939407,1.79576480389,-12.9364900589 -4.71034097672,1.79374575615,-12.9078798294 -4.75133323669,1.79373180866,-12.8912649155 -4.78129673004,1.78870427608,-12.8426656723 -4.81727647781,1.78568506241,-12.8130550385 -4.84824562073,1.78166031837,-12.7704486847 -4.84919548035,1.77363240719,-12.7116565704 -4.89519929886,1.77562379837,-12.7070446014 -4.93218564987,1.77460741997,-12.6834249496 -4.9651594162,1.77058517933,-12.6458234787 -5.01116466522,1.77257752419,-12.6432037354 -5.03612232208,1.76654791832,-12.5876026154 -5.06508874893,1.76252269745,-12.5420007706 -5.08709049225,1.76251888275,-12.5401859283 -5.12307500839,1.76150155067,-12.5135736465 -5.15605020523,1.75848007202,-12.4769744873 -5.19203519821,1.75646388531,-12.4523572922 -5.22801971436,1.75544667244,-12.4257469177 -5.26801109314,1.75443279743,-12.4071407318 -5.29096794128,1.7484036684,-12.3505420685 -5.292927742,1.74238061905,-12.3007478714 -5.33592605591,1.74337005615,-12.290137291 -5.37391614914,1.74235582352,-12.269525528 -5.39787721634,1.73632872105,-12.2169265747 -5.43887329102,1.73731732368,-12.2033128738 -5.47786521912,1.73730385303,-12.1847028732 -5.510846138,1.73428583145,-12.1540927887 -5.52783679962,1.73427700996,-12.139289856 -5.56883430481,1.73426604271,-12.1266727448 -5.5837802887,1.72623288631,-12.0570783615 -5.62277173996,1.72621929646,-12.0374755859 -5.66477155685,1.72720968723,-12.0278549194 -5.69575023651,1.72419095039,-11.9942474365 -5.70873355865,1.72217869759,-11.9704523087 -5.75473976135,1.72417199612,-11.9678344727 -5.78571796417,1.72215282917,-11.9332323074 -5.82471227646,1.72214114666,-11.9176139832 -5.85969877243,1.72112572193,-11.8920059204 -5.89368391037,1.72010993958,-11.865395546 -5.9276676178,1.71809327602,-11.8367938995 -5.94866847992,1.71908915043,-11.8329792023 -5.98465585709,1.71807408333,-11.8083772659 -6.02765607834,1.71906495094,-11.7987651825 -6.05563211441,1.71604526043,-11.7611579895 -6.08561038971,1.71402680874,-11.7265539169 -6.13261795044,1.71702051163,-11.724937439 -6.18964290619,1.72202193737,-11.7433071136 -6.19561767578,1.71800673008,-11.7095098495 -6.2195854187,1.71398353577,-11.6619205475 -6.26959896088,1.7179800272,-11.6672925949 -6.30058050156,1.71596300602,-11.635684967 -6.32555103302,1.71194112301,-11.5910930634 -6.37155675888,1.71493446827,-11.587474823 -6.42557668686,1.71993362904,-11.5998420715 -6.44857788086,1.72092950344,-11.5960407257 -6.48356723785,1.71991598606,-11.5734243393 -6.52356243134,1.7209045887,-11.5568180084 -6.57056856155,1.72389793396,-11.5532016754 -6.5975446701,1.72087907791,-11.5155963898 -6.63553714752,1.72086679935,-11.4959888458 -6.67252826691,1.72085404396,-11.4753789902 -6.69052362442,1.72084760666,-11.4645719528 -6.7315196991,1.72183668613,-11.44896698 -6.77251911163,1.72282743454,-11.4373426437 -6.81251430511,1.7238162756,-11.4207353592 -6.8424949646,1.72179949284,-11.3881320953 -6.88148927689,1.72178816795,-11.3705215454 -6.91948223114,1.72277617455,-11.3509130478 -6.93747758865,1.72276985645,-11.3401060104 -6.97547006607,1.72275781631,-11.3204994202 -7.01947164536,1.7247492075,-11.3108844757 -7.05946588516,1.72573792934,-11.2932815552 -7.09145116806,1.72472298145,-11.2646741867 -7.13545274734,1.72671449184,-11.2550582886 -7.15444898605,1.72670865059,-11.2452545166 -7.1984500885,1.72870028019,-11.2356376648 -7.23544216156,1.72868824005,-11.2150268555 -7.27343559265,1.72967636585,-11.1954164505 -7.31643390656,1.73066699505,-11.1828079224 -7.35442781448,1.7316557169,-11.1641921997 -7.39742660522,1.73364603519,-11.1505861282 -7.4174246788,1.73364090919,-11.1427774429 -7.45641946793,1.73462998867,-11.125164032 -7.49941778183,1.73662042618,-11.1115570068 -7.53941345215,1.73760974407,-11.0949430466 -7.57640504837,1.73759758472,-11.0733346939 -7.60838937759,1.73658251762,-11.0427398682 -7.64738368988,1.73757135868,-11.0241298676 -7.65336465836,1.73456001282,-10.9963293076 -7.72640037537,1.74356472492,-11.0266942978 -7.7613902092,1.74355208874,-11.0030813217 -7.79938220978,1.74453997612,-10.9814786911 -7.83537244797,1.74452745914,-10.9578723907 -7.87937259674,1.74651885033,-10.9462566376 -7.92036867142,1.74750840664,-10.9296474457 -7.93135595322,1.74649906158,-10.9078502655 -7.9823641777,1.75049352646,-10.9062261581 -8.01434993744,1.74947917461,-10.876625061 -8.0453338623,1.74846434593,-10.8450288773 -8.10334968567,1.75346171856,-10.8523988724 -8.14134216309,1.75444984436,-10.8307933807 -8.15633296967,1.75344252586,-10.8149929047 -8.21735191345,1.76044034958,-10.8243675232 -8.23532295227,1.75642085075,-10.7767734528 -8.27932167053,1.75841200352,-10.7641563416 -8.31831550598,1.75940048695,-10.7425575256 -8.4163236618,1.76538646221,-10.7293176651 -8.45534229279,1.77038836479,-10.7444972992 -8.50434589386,1.77438116074,-10.7368793488 -8.55234909058,1.77737307549,-10.7272663116 -8.58933925629,1.77736103535,-10.703660965 -8.63634109497,1.78035283089,-10.6930446625 -8.69835758209,1.78634989262,-10.7004203796 -8.75636959076,1.79234552383,-10.7027959824 -8.78537654877,1.79534351826,-10.7049770355 -8.83237743378,1.79733502865,-10.6933612823 -8.85835647583,1.79531860352,-10.6547698975 -8.92037296295,1.80231535435,-10.6611413956 -8.95235729218,1.80130147934,-10.6305398941 -8.97533416748,1.79928445816,-10.5889472961 -9.00431632996,1.79726958275,-10.5543518066 -9.00629615784,1.79425811768,-10.5225610733 -8.69094562531,1.71712779999,-10.0752754211 -8.70291519165,1.71210896969,-10.023692131 -8.72389316559,1.71009325981,-9.98310184479 -8.74987697601,1.70807933807,-9.94850635529 -8.74082565308,1.69905412197,-9.8729429245 -8.74881362915,1.69804561138,-9.85014915466 -8.76278686523,1.69402837753,-9.80256175995 -8.78776931763,1.69201481342,-9.7679643631 -8.80574703217,1.68899869919,-9.72438049316 -8.83072948456,1.68798482418,-9.6887922287 -8.84470367432,1.68396830559,-9.64220333099 -8.87068843842,1.68295550346,-9.60960292816 -8.87467288971,1.67994594574,-9.5818195343 -8.89665412903,1.67893195152,-9.5442276001 -8.91663455963,1.67591750622,-9.5046377182 -8.93961715698,1.67490375042,-9.46804618835 -8.96460151672,1.67289102077,-9.43444919586 -8.97357368469,1.66887414455,-9.3838634491 -8.99455451965,1.66686022282,-9.34527683258 -9.02656364441,1.66985917091,-9.34946250916 -9.03653621674,1.66584265232,-9.29988002777 -9.05951976776,1.66482961178,-9.26428699493 -9.07349586487,1.66081416607,-9.21870613098 -9.08146858215,1.65679764748,-9.16812229156 -9.10044956207,1.65478396416,-9.12853431702 -9.13844585419,1.6557751894,-9.10892868042 -9.11841201782,1.64876115322,-9.0591583252 -9.14339923859,1.6487493515,-9.02656173706 -9.15437412262,1.64473390579,-8.97898387909 -9.16735076904,1.64171934128,-8.93439865112 -9.17932796478,1.63770473003,-8.88881587982 -9.21432209015,1.63869559765,-8.8662147522 -9.21228790283,1.63267767429,-8.80664634705 -9.22628307343,1.63267230988,-8.79185009003 -9.24026203156,1.62965893745,-8.75025463104 -9.24823665619,1.62564373016,-8.7006816864 -9.25921344757,1.62262952328,-8.65509986877 -9.27819824219,1.6206176281,-8.61850452423 -9.28917598724,1.61760354042,-8.57292461395 -9.30015277863,1.61358952522,-8.52734851837 -9.31414794922,1.61358475685,-8.51354598999 -9.31712055206,1.60956943035,-8.46097278595 -9.3421087265,1.60855877399,-8.42938232422 -9.35709190369,1.6065466404,-8.38978862762 -9.3850812912,1.60653662682,-8.36020183563 -9.3920583725,1.60252285004,-8.31262111664 -9.40505218506,1.60251784325,-8.2978219986 -9.41603279114,1.59950506687,-8.25423812866 -9.4280128479,1.59649252892,-8.21165466309 -9.45300197601,1.59648263454,-8.18105792999 -9.46498298645,1.5934702158,-8.13847732544 -9.48596954346,1.59245955944,-8.10388851166 -9.50495529175,1.59044873714,-8.06829738617 -9.50594329834,1.58844172955,-8.04251289368 -9.50991916656,1.58442854881,-7.99393415451 -9.5319070816,1.58341825008,-7.9603471756 -9.5488910675,1.58140730858,-7.92276239395 -9.55787181854,1.57839536667,-7.87917804718 -9.57085418701,1.57638394833,-7.83859491348 -9.58183574677,1.57337224483,-7.79601716995 -9.5858259201,1.57236635685,-7.77422380447 -9.58780193329,1.56735348701,-7.72465133667 -8.243932724,1.31512355804,-6.5541806221 -8.23791122437,1.31011295319,-6.50561237335 -8.28392124176,1.31411063671,-6.5000038147 -8.31292152405,1.31610560417,-6.48040676117 -8.33492660522,1.31810426712,-6.476603508 -8.3499174118,1.31709718704,-6.44601297379 -8.36591053009,1.31609046459,-6.41642093658 -8.38390350342,1.31508374214,-6.38783359528 -8.43291568756,1.32008183002,-6.38421773911 -8.42789554596,1.31607186794,-6.3366560936 -8.45589542389,1.31706702709,-6.31704998016 -8.47589874268,1.31906545162,-6.3112487793 -8.49489307404,1.3180590868,-6.28365850449 -8.51288700104,1.31805276871,-6.25507116318 -8.55689620972,1.32204985619,-6.24646282196 -8.57689094543,1.32204389572,-6.21986865997 -8.60188961029,1.32303881645,-6.19726848602 -8.63389015198,1.32503414154,-6.17867517471 -8.64188766479,1.3250310421,-6.16387891769 -8.67188739777,1.32602643967,-6.14428091049 -8.68888187408,1.32602035999,-6.11568593979 -8.7218837738,1.3280159235,-6.09808635712 -8.73287391663,1.3260089159,-6.06351280212 -8.77488136292,1.33000576496,-6.05289983749 -8.79587650299,1.33000004292,-6.02631044388 -8.8218832016,1.33299911022,-6.02449989319 -8.84688186646,1.33399391174,-6.00090456009 -8.86187362671,1.33298778534,-5.97031593323 -8.89587688446,1.33598351479,-5.95271682739 -8.92687797546,1.33797895908,-5.93311786652 -8.94187068939,1.33697283268,-5.90153932571 -8.97087097168,1.33896827698,-5.88093614578 -8.99987792969,1.34196734428,-5.88012838364 -9.01587200165,1.3409614563,-5.85053539276 -9.03086566925,1.34095525742,-5.81895637512 -9.06886959076,1.34395170212,-5.80434513092 -9.08986568451,1.34394609928,-5.77676153183 -9.11586475372,1.34494113922,-5.75316762924 -9.13886833191,1.34793972969,-5.74835824966 -9.15586280823,1.34693408012,-5.718770504 -9.19086551666,1.34992992878,-5.70116662979 -9.26788806915,1.3599293232,-5.71053123474 -9.28988456726,1.3599241972,-5.6839389801 -9.32388591766,1.36291968822,-5.66434431076 -10.1662569046,1.50097692013,-6.15911912918 -10.1482410431,1.49597132206,-6.12534809113 -10.1752376556,1.49796497822,-6.09775781631 -10.2052345276,1.49895906448,-6.07216405869 -10.199215889,1.49495077133,-6.02558374405 -10.1671857834,1.48594045639,-5.96104431152 -10.2101898193,1.48993575573,-5.94443178177 -10.2231788635,1.48892867565,-5.90785694122 -10.2121667862,1.48592412472,-5.88007259369 -10.23716259,1.48691809177,-5.85148334503 -10.2371473312,1.48391079903,-5.80890274048 -10.2071199417,1.47490143776,-5.74735927582 -10.2531242371,1.47989678383,-5.73174905777 -10.051027298,1.44387865067,-5.57132387161 -10.1780653,1.46087861061,-5.6026597023 -10.1100301743,1.44887149334,-5.54192686081 -10.0319852829,1.43286085129,-5.45541095734 -9.98595428467,1.42285215855,-5.38787174225 -9.79486560822,1.38883674145,-5.23943519592 -9.83186817169,1.3918325901,-5.21983575821 -9.75182533264,1.37582314014,-5.13532018661 -9.71180438995,1.36781847477,-5.09257125854 -9.68378257751,1.36081194878,-5.03801441193 -9.59573745728,1.34380304813,-4.95050859451 -9.65775108337,1.35080039501,-4.94588375092 -9.6447353363,1.34679472446,-4.89932727814 -9.52468013763,1.32478535175,-4.79683971405 -9.38661956787,1.29977583885,-4.68537092209 -9.29458141327,1.28377068043,-4.61864566803 -9.32058238983,1.28576731682,-4.59505605698 -9.20153045654,1.26475954056,-4.49656534195 -9.07047557831,1.24075174332,-4.39308309555 -8.98143577576,1.22474563122,-4.31157684326 -9.02444458008,1.22874343395,-4.29797410965 -8.96741771698,1.21773862839,-4.23443555832 -8.90739345551,1.20673561096,-4.18669462204 -8.86637306213,1.19873154163,-4.13115596771 -8.73132038116,1.17472577095,-4.03067207336 -8.70930767059,1.16972267628,-3.9861137867 -8.56225299835,1.14371752739,-3.88065195084 -8.64327526093,1.1547164917,-3.88701605797 -8.495221138,1.1297121048,-3.78354287148 -8.45720672607,1.12271034718,-3.74878883362 -8.4321937561,1.11670815945,-3.70423865318 -8.38317489624,1.1067057848,-3.64969348907 -8.37116718292,1.10270392895,-3.61213040352 -8.29113864899,1.0887016058,-3.54361319542 -8.28913497925,1.08670020103,-3.51203203201 -8.28613185883,1.08469939232,-3.49425840378 -8.22210979462,1.0736978054,-3.43472337723 -8.15008544922,1.06069636345,-3.37219381332 -8.06205558777,1.04469513893,-3.30268287659 -8.03304481506,1.0386942625,-3.26012587547 -8.04104614258,1.03869354725,-3.23354887962 -7.99903202057,1.02969300747,-3.18599891663 -7.95901918411,1.02269279957,-3.15325093269 -7.94101333618,1.01869237423,-3.11668252945 -7.88199520111,1.00769233704,-3.06215500832 -7.85798740387,1.00269210339,-3.02359175682 -7.83898162842,0.998692154884,-2.98702907562 -7.7959690094,0.98969244957,-2.94048857689 -7.74395465851,0.980693042278,-2.8909497261 -7.7379527092,0.978693246841,-2.87515616417 -7.71094560623,0.973693788052,-2.83560967445 -7.66093254089,0.964694738388,-2.78905081749 -7.62892436981,0.957695603371,-2.74850273132 -7.61592149734,0.95469635725,-2.71593761444 -7.5979180336,0.950697243214,-2.68137907982 -7.59191703796,0.947697937489,-2.6518099308 -7.58691644669,0.9466984272,-2.63701534271 -7.54990816116,0.939699888229,-2.59547352791 -7.53490543365,0.935701012611,-2.56389498711 -7.48989582062,0.927703022957,-2.52035236359 -7.42988300323,0.917705535889,-2.47181773186 -7.41588115692,0.913707017899,-2.44025611877 -7.40587949753,0.911707878113,-2.42347693443 -7.37887525558,0.906709849834,-2.3879172802 -7.37387704849,0.904711306095,-2.36034393311 -7.34287166595,0.898713588715,-2.32378721237 -7.36187887192,0.90071451664,-2.30519175529 -7.33687543869,0.895716786385,-2.27063798904 -7.28986787796,0.886719942093,-2.22909474373 -7.28486824036,0.885720968246,-2.21431779861 -7.27386856079,0.882723033428,-2.18574357033 -7.27187108994,0.881724894047,-2.16016530991 -7.222864151,0.872728526592,-2.11862874031 -7.21186494827,0.870730817318,-2.09104585648 -7.24187469482,0.873731672764,-2.07545828819 -7.16386032104,0.861735701561,-2.03871154785 -7.16586399078,0.860737740993,-2.01414632797 -7.15386533737,0.857740402222,-1.98656725883 -7.15286922455,0.856742560863,-1.96199011803 -7.11286497116,0.849746644497,-1.92544031143 -7.09286546707,0.845749914646,-1.89488375187 -7.08286762238,0.843752741814,-1.86830639839 -7.07686853409,0.841754198074,-1.8545229435 -7.06387042999,0.839757323265,-1.82695233822 -7.03286981583,0.833761453629,-1.79340970516 -7.02787303925,0.831764280796,-1.76882767677 -7.02087688446,0.829767286777,-1.74325597286 -6.99987792969,0.825771152973,-1.71369588375 -6.98888063431,0.823774337769,-1.68811070919 -6.99188375473,0.823775589466,-1.67731964588 -6.9958896637,0.823778271675,-1.65474665165 -6.97689151764,0.819782197475,-1.6261857748 -6.98889875412,0.820784449577,-1.60659384727 -6.9348950386,0.811790585518,-1.56905639172 -6.94490242004,0.812793016434,-1.54847681522 -6.94290781021,0.811796247959,-1.52490353584 -6.94991159439,0.811797440052,-1.51511263847 -6.88590669632,0.801804423332,-1.47657036781 -6.89491462708,0.802807152271,-1.45599007607 -6.86191511154,0.796812415123,-1.42543232441 -6.86892223358,0.796815276146,-1.40484642982 -6.89393234253,0.799817025661,-1.38825368881 -6.87093162537,0.795820236206,-1.37148177624 -6.85893630981,0.79382455349,-1.3459186554 -6.84394073486,0.790828943253,-1.32034683228 -6.83194494247,0.788833260536,-1.29576945305 -6.80594778061,0.783838748932,-1.26721978188 -6.80895519257,0.783842027187,-1.24662446976 -6.79195928574,0.780846834183,-1.2210547924 -6.79596328735,0.780848503113,-1.21027588844 -6.8119726181,0.782851040363,-1.19168770313 -6.78797578812,0.777856469154,-1.16511809826 -6.77598142624,0.775861263275,-1.14055252075 -6.78098869324,0.77586466074,-1.11996734142 -6.7689948082,0.773869514465,-1.09540474415 -6.78300380707,0.774872303009,-1.07681012154 -6.76000452042,0.771876096725,-1.06104457378 -6.73100805283,0.766882240772,-1.03447377682 -6.76201868057,0.770883798599,-1.0188729763 -6.75802612305,0.769888222218,-0.996302008629 -6.74703216553,0.766893148422,-0.972731769085 -6.74803972244,0.766897261143,-0.951157689095 -6.73504590988,0.764902472496,-0.927584528923 -6.76205253601,0.767902195454,-0.921773433685 -6.72405672073,0.761909544468,-0.894212663174 -6.77207708359,0.767913997173,-0.85903185606 -6.75408315659,0.764919877052,-0.834469914436 -6.84810113907,0.777915894985,-0.827830851078 -7.00012016296,0.79990452528,-0.840936839581 -6.80910921097,0.771925806999,-0.789487659931 -6.83611965179,0.774927735329,-0.771894335747 -6.88213205338,0.78192782402,-0.75728136301 -6.87913894653,0.780932366848,-0.735694825649 -6.97315597534,0.793928027153,-0.727057754993 -6.82915115356,0.772946000099,-0.684590220451 -6.8731584549,0.778943955898,-0.680753707886 -7.07418441772,0.806929469109,-0.685056686401 -6.79816865921,0.766960084438,-0.627651870251 -6.80117750168,0.766964554787,-0.606084048748 -6.80318641663,0.766968846321,-0.585494935513 -6.83319664001,0.770970523357,-0.567894697189 -6.75519943237,0.75998288393,-0.537368893623 -6.73120212555,0.755987763405,-0.523604631424 -6.67020654678,0.746998608112,-0.496060520411 -6.65121412277,0.744005262852,-0.473488241434 -6.67322444916,0.747007966042,-0.454898416996 -6.68523454666,0.74801158905,-0.435312271118 -6.66524219513,0.745018482208,-0.4127420187 -6.66925096512,0.745023071766,-0.392165213823 -6.73726034164,0.755018413067,-0.388328611851 -6.6722650528,0.745030164719,-0.36178585887 -6.6642742157,0.744036078453,-0.340214908123 -6.64628219604,0.74104309082,-0.317654818296 -6.64329147339,0.741048455238,-0.297071874142 -6.65930223465,0.743051946163,-0.277487367392 -6.62430477142,0.737058162689,-0.264716029167 -6.62931442261,0.738062977791,-0.244142130017 -6.64332485199,0.740066587925,-0.224554851651 -6.64633464813,0.74007153511,-0.203978314996 -6.62634325027,0.737078905106,-0.18240647018 -6.64535427094,0.739082157612,-0.162820458412 -6.63636302948,0.738088309765,-0.142237126827 -6.62136745453,0.736092567444,-0.131450682878 -6.64337825775,0.739095509052,-0.111863531172 -6.6373872757,0.738101482391,-0.0912833064795 -6.75640296936,0.755093276501,-0.0756428539753 -6.64040803909,0.738112032413,-0.0501292981207 -6.61541700363,0.734120368958,-0.0285672880709 -6.63042736053,0.736123979092,-0.00897331815213 -6.61843252182,0.735128164291,0.00180635345168 -6.68844461441,0.74512553215,0.0204199440777 -6.7444562912,0.752124249935,0.0390413589776 -6.80046796799,0.760123074055,0.0586499199271 -6.69247531891,0.7451415658,0.0821606367826 -6.60948324203,0.733157277107,0.104682855308 -6.68149518967,0.743153989315,0.123317860067 -6.66349983215,0.741159021854,0.134092211723 -6.94051599503,0.780130565166,0.150851458311 -6.99052667618,0.787129998207,0.172448515892 -6.99653720856,0.788134813309,0.19403000176 -7.04854774475,0.795133829117,0.215637341142 -9.65459537506,1.16381430626,0.238753557205 -9.650598526,1.16281676292,0.253541469574 -6.57056713104,0.727207839489,0.267294883728 -6.58457803726,0.72921204567,0.287878215313 -6.56058883667,0.726220786572,0.307451933622 -6.54859972,0.724228441715,0.328012913465 -6.57761096954,0.729230582714,0.348612368107 -6.59862232208,0.732233703136,0.369207024574 -6.64962720871,0.739229977131,0.380037844181 -6.74863815308,0.753223121166,0.403665393591 -6.6406493187,0.738243162632,0.421182870865 -6.52366018295,0.72126442194,0.437695622444 -6.52467155457,0.722270488739,0.458267152309 -6.55968332291,0.727271914482,0.479865163565 -6.53168869019,0.723278641701,0.488642573357 -6.53869962692,0.724283874035,0.509223639965 -6.53171110153,0.723290860653,0.528804659843 -6.59972190857,0.733287930489,0.55242317915 -6.53273391724,0.723302960396,0.568968951702 -6.52574539185,0.723310351372,0.589528560638 -6.54275655746,0.72531414032,0.610129952431 -6.5297627449,0.723319113255,0.619902670383 -6.6337723732,0.738311052322,0.646547436714 -6.72078227997,0.751305401325,0.673172652721 -6.56379652023,0.729333221912,0.682666182518 -6.52280950546,0.723345220089,0.700216829777 -6.50682163239,0.721353709698,0.718795478344 -6.64982938766,0.742340087891,0.75045645237 -6.78283214569,0.761324524879,0.771328210831 -6.5328502655,0.72536611557,0.77175283432 -6.48886346817,0.720378816128,0.788304328918 -6.46387577057,0.716388702393,0.805875718594 -6.45388841629,0.715396761894,0.825440824032 -6.45390033722,0.715403139591,0.845030367374 -6.49590539932,0.722400546074,0.859831809998 -6.44891834259,0.715413570404,0.874402046204 -6.48992919922,0.721414268017,0.899000883102 -6.46794271469,0.718424201012,0.917553067207 -6.42395591736,0.713437020779,0.932122290134 -6.43196821213,0.71444272995,0.953693687916 -6.48097848892,0.721442043781,0.979306519032 -6.45198583603,0.71744966507,0.986077487469 -6.47299671173,0.72145318985,1.00867247581 -6.46000957489,0.719461798668,1.02724564075 -6.4300236702,0.715472996235,1.0438041687 -6.42603635788,0.715480327606,1.06338262558 -6.411049366,0.713489115238,1.08096516132 -6.41406154633,0.714495480061,1.1015458107 -6.42406797409,0.716497480869,1.11333489418 -6.42408037186,0.716504395008,1.13390672207 -6.40109395981,0.713514626026,1.15047907829 -6.40810680389,0.715520560741,1.17205536366 -6.39311981201,0.713529527187,1.18963348866 -6.39913272858,0.715535700321,1.21120715141 -6.39014625549,0.714543938637,1.22978615761 -6.3931517601,0.71454668045,1.23959362507 -6.41316318512,0.718550503254,1.26318311691 -6.39217805862,0.715560972691,1.28073549271 -6.36919212341,0.712571263313,1.2963180542 -6.37720489502,0.714577376842,1.31888258457 -6.36721849442,0.713585913181,1.33745527267 -6.34222650528,0.710593104362,1.34224927425 -6.36223888397,0.713597238064,1.36682450771 -6.37225055695,0.715602576733,1.38842082024 -6.40326166153,0.720604896545,1.41500926018 -6.38827562332,0.718614339828,1.43258094788 -6.39528846741,0.720620274544,1.45416903496 -6.38730192184,0.720628559589,1.47275114059 -6.39530801773,0.721630811691,1.48454618454 -6.38732194901,0.720639467239,1.50410795212 -6.38533496857,0.721646785736,1.52369749546 -6.35135126114,0.716659486294,1.53725588322 -6.37836265564,0.721662461758,1.56384277344 -6.37037658691,0.720670878887,1.58242368698 -6.36939048767,0.721678376198,1.60299885273 -6.36339712143,0.720682919025,1.61178910732 -6.33741283417,0.717694282532,1.6263589859 -6.35442447662,0.72069889307,1.65094459057 -6.35143852234,0.721706569195,1.67053031921 -6.35145187378,0.721713840961,1.69111144543 -6.3794631958,0.726716697216,1.7187012434 -6.41346693039,0.731714844704,1.73750400543 -6.40048122406,0.730724275112,1.75508117676 -6.36649847031,0.726737260818,1.76764309406 -6.38251066208,0.729741930962,1.79223632812 -6.39852285385,0.732746839523,1.81781280041 -6.40153598785,0.733753740788,1.83939826488 -6.47854185104,0.745748102665,1.88002669811 -6.37055969238,0.73076993227,1.86275517941 -6.33257770538,0.725784003735,1.87430346012 -6.46657800674,0.746768891811,1.93095695972 -6.37760019302,0.7337911129,1.9275046587 -6.42160987854,0.741791307926,1.96110033989 -6.38562726974,0.736804962158,1.97265708447 -6.37164306641,0.735814929008,1.99022471905 -6.37264966965,0.736818492413,2.00101733208 -6.37866306305,0.737824857235,2.0236082077 -6.34268093109,0.733838498592,2.03417611122 -6.32169675827,0.730849862099,2.04973578453 -6.33271026611,0.73385566473,2.07431936264 -6.3037276268,0.730868220329,2.08688497543 -6.31274032593,0.732874155045,2.11047697067 -6.40773677826,0.746861755848,2.15031170845 -6.36175632477,0.741877377033,2.15786647797 -6.33877325058,0.738889098167,2.17243051529 -6.35878515244,0.742893278599,2.20002484322 -6.36379909515,0.744900226593,2.22360062599 -6.34981441498,0.743910193443,2.24018478394 -6.34682178497,0.743914544582,2.24997448921 -6.33683776855,0.7429240942,2.26854634285 -9.46447944641,1.20938754082,3.32463932037 -9.4614906311,1.2103946209,3.35621547699 -9.468501091,1.21340024471,3.3917889595 -6.25490522385,0.734969735146,2.32782101631 -6.25192022324,0.734978079796,2.34839940071 -6.25392723083,0.735981762409,2.36018490791 -6.28293800354,0.741984426975,2.39178419113 -6.36594200134,0.754977405071,2.4424161911 -6.45394468307,0.768969714642,2.49603915215 -6.30097913742,0.747004747391,2.46353983879 -6.29699468613,0.748013436794,2.48411822319 -6.83893108368,0.829920828342,2.69318079948 -6.71196222305,0.811951339245,2.67069125175 -6.37902069092,0.763018667698,2.57010674477 -6.41003131866,0.76902115345,2.60469460487 -6.36905097961,0.764036297798,2.61126375198 -9.44565200806,1.23149347305,3.81527495384 -6.61104726791,0.803008854389,2.75053620338 -6.32609367371,0.760064005852,2.6511900425 -6.34810590744,0.765068173409,2.68277406693 -6.34012126923,0.765077352524,2.70136737823 -6.32213926315,0.763089001179,2.71791934967 -6.31315517426,0.763098537922,2.73650431633 -6.33216714859,0.76710319519,2.7670917511 -6.3151845932,0.766114294529,2.7826693058 -6.33219003677,0.769115328789,2.80146121979 -6.31720685959,0.768126130104,2.81803655624 -6.32122087479,0.770133435726,2.84262013435 -6.3222360611,0.772141456604,2.86619877815 -6.31325292587,0.772151350975,2.88576889038 -6.31926679611,0.774158358574,2.91135454178 -6.35827589035,0.781159162521,2.950963974 -6.33528661728,0.778167486191,2.95274090767 -6.31430530548,0.776179730892,2.96730327606 -6.32331895828,0.779186308384,2.99488401413 -6.35532903671,0.786188602448,3.03248333931 -6.32134962082,0.782203197479,3.04104280472 -6.3323636055,0.785209357738,3.06962871552 -6.31337356567,0.783216893673,3.07241630554 -6.35238265991,0.790217876434,3.11401605606 -6.33440065384,0.789229512215,3.12958693504 -6.31941843033,0.788240492344,3.14616513252 -6.34043073654,0.793245077133,3.18074250221 -6.36144256592,0.797249317169,3.21434044838 -6.32846307755,0.794263899326,3.22290205956 -6.31647253036,0.793270111084,3.22869515419 -6.32148694992,0.795277535915,3.25527787209 -6.32550239563,0.79728525877,3.28185343742 -6.31951856613,0.798294782639,3.30342769623 -6.31253528595,0.798304378986,3.32401061058 -6.29555368423,0.797316253185,3.34057188034 -6.28057146072,0.796327412128,3.35715031624 -6.29157781601,0.799329519272,3.37494587898 -6.36058139801,0.811324775219,3.43456244469 -6.28161048889,0.800348341465,3.41910004616 -6.28562545776,0.80335599184,3.44568562508 -6.26464414597,0.801368355751,3.45925974846 -6.29065561295,0.807371854782,3.49785065651 -6.273665905,0.805379152298,3.50064444542 -6.28867959976,0.809385001659,3.53422141075 -6.27869701385,0.809395372868,3.55379939079 -6.28971099854,0.813401997089,3.5853767395 -6.27072954178,0.811414003372,3.59995388985 -6.27874422073,0.814420998096,3.62953948975 -6.27276134491,0.815430879593,3.65210914612 -6.45073747635,0.845400750637,3.76299262047 -6.27178525925,0.818443834782,3.68948459625 -6.26480197906,0.818453788757,3.71106290817 -6.25781917572,0.819463670254,3.73264217377 -6.36881542206,0.839450955391,3.82226657867 -6.26085042953,0.823480308056,3.78580617905 -6.2538599968,0.823485910892,3.79459524155 -6.25787496567,0.826493859291,3.82317304611 -6.24589347839,0.826504707336,3.84175515175 -6.27690315247,0.833507418633,3.88634705544 -6.24492549896,0.829522430897,3.89390897751 -6.24294233322,0.831531643867,3.91948127747 -6.22496080399,0.830543518066,3.93406867981 -6.2459654808,0.834543764591,3.95987010002 -6.24698162079,0.837552428246,3.98744511604 -6.31098556519,0.849548876286,4.05404472351 -6.25301265717,0.84256875515,4.04460906982 -6.55197191238,0.894519209862,4.25831317902 -6.3410282135,0.860569059849,4.15380811691 -6.32804679871,0.860580444336,4.17337846756 -6.22507429123,0.844604730606,4.121134758 -6.20909404755,0.844616889954,4.13869905472 -6.29509353638,0.860608875751,4.22131490707 -6.22512340546,0.851631522179,4.20386314392 -6.2491350174,0.857635438442,4.24646234512 -6.21615791321,0.853650867939,4.25302124023 -6.25116729736,0.862652778625,4.30362081528 -6.22518062592,0.858662366867,4.30039930344 -6.21319961548,0.858673453331,4.31997966766 -6.2382106781,0.865677416325,4.36457395554 -6.22323036194,0.865689396858,4.38314056396 -6.23924350739,0.870694935322,4.42173624039 -6.21726417542,0.868708312511,4.43530511856 -6.2012758255,0.867715775967,4.43809509277 -6.25228214264,0.878714859486,4.50268602371 -6.21730566025,0.87473076582,4.50724983215 -6.19132709503,0.872744560242,4.5168337822 -6.19134378433,0.874753773212,4.54640340805 -6.23435211182,0.884754180908,4.60600137711 -6.20737409592,0.882768452168,4.61557626724 -6.18938589096,0.880776524544,4.61735773087 -6.30837774277,0.903761923313,4.73298406601 -6.20841550827,0.88879096508,4.69051790237 -6.18143796921,0.886805295944,4.700091362 -6.21444749832,0.895807623863,4.75369167328 -6.22246265411,0.899815261364,4.79026603699 -6.18248748779,0.894832134247,4.78983926773 -6.18649482727,0.896835803986,4.80763435364 -6.24249982834,0.909833669662,4.88023614883 -6.24551582336,0.912842094898,4.91282176971 -6.19054460526,0.905862510204,4.90236854553 -6.21055698395,0.911867439747,4.94796323776 -6.2045750618,0.913877546787,4.97355079651 -6.20359230042,0.915886998177,5.00412559509 -6.19660234451,0.915893137455,5.01490402222 -6.19861841202,0.918901801109,5.04748821259 -6.19563627243,0.921911418438,5.07607316971 -6.26863718033,0.937905848026,5.16568517685 -6.23366212845,0.933922290802,5.17024374008 -6.20868444443,0.932936370373,5.18181800842 -6.19969415665,0.931942522526,5.18961668015 -6.1987118721,0.934952318668,5.22218036652 -6.20972681046,0.939959347248,5.26376199722 -6.20174503326,0.941969811916,5.28835630417 -6.16876983643,0.938985824585,5.29391908646 -6.19678020477,0.946989238262,5.34951686859 -6.17879247665,0.944997668266,5.35129451752 -6.20180511475,0.952002286911,5.40388154984 -6.19082450867,0.953013956547,5.42844963074 -6.17784452438,0.954025685787,5.4500336647 -6.21485328674,0.964027523994,5.51562595367 -6.20687246323,0.966038346291,5.5422077179 -6.19989109039,0.968049228191,5.57077741623 -6.20389842987,0.970052838326,5.5905790329 -6.26090288162,0.984050631523,5.67517948151 -6.22792768478,0.981066703796,5.680747509 -6.23594284058,0.986074268818,5.72233581543 -6.26695299149,0.995077252388,5.78493118286 -6.2179813385,0.989096641541,5.77648925781 -6.22499704361,0.99410456419,5.81807374954 -6.1900138855,0.989116311073,5.8038520813 -6.20602703094,0.995122313499,5.85344600677 -6.1740527153,0.993138551712,5.8609995842 -6.18806648254,0.999145030975,5.90958881378 -6.18608379364,1.00215470791,5.94317626953 -6.20109796524,1.00916111469,5.99376106262 -6.19211769104,1.01117241383,6.02233314514 -6.17912912369,1.01017975807,6.02812147141 -6.19114398956,1.01618683338,6.07670307159 -6.18816232681,1.01919698715,6.11127948761 -6.18717908859,1.02220642567,6.14686870575 -6.25318145752,1.0392023325,6.24847650528 -6.20121145248,1.0332224369,6.23603487015 -6.20122003555,1.03522717953,6.25482797623 -6.17924261093,1.03424119949,6.27139949799 -6.17326164246,1.03725194931,6.30397605896 -6.18527603149,1.04325890541,6.35357189178 -6.22528409958,1.05526018143,6.43316268921 -6.18831110001,1.05227744579,6.43572282791 -6.16233444214,1.05029213428,6.44730758667 -6.31130695343,1.08326637745,6.62014532089 -6.42229795456,1.11025321484,6.77575826645 -6.18437337875,1.0653116703,6.57025814056 -6.18639039993,1.07032084465,6.61283779144 -6.16941261292,1.07133388519,6.63541412354 -6.20142221451,1.08133673668,6.70901536942 -6.17244672775,1.08035230637,6.71958446503 -6.19545030594,1.08735251427,6.76537656784 -6.1754732132,1.08736634254,6.78594589233 -6.16049385071,1.08837878704,6.81053161621 -6.1955037117,1.10038137436,6.89111852646 -6.19552135468,1.10439109802,6.93369817734 -6.16854572296,1.10340607166,6.94627475739 -6.15555810928,1.10341358185,6.95306301117 -6.14857721329,1.10642457008,6.98764705658 -6.11760282516,1.10444068909,6.99621725082 -7.14136552811,1.32724010944,8.19510650635 -7.11338996887,1.32625544071,8.21368217468 -7.09941101074,1.32926797867,8.24925422668 -7.08343267441,1.33128094673,8.28183269501 -7.06644535065,1.33028912544,8.28762054443 -7.04346895218,1.33030366898,8.31318950653 -7.03448820114,1.33431518078,8.35377216339 -7.00851202011,1.33433020115,8.37534618378 -6.99453353882,1.33734285831,8.41191577911 -6.9775557518,1.33935618401,8.44448947906 -6.95157957077,1.33937120438,8.46606445312 -6.95858669281,1.34337449074,8.50085735321 -6.926612854,1.3423910141,8.51642131805 -6.90963411331,1.34440410137,8.54800701141 -6.90165424347,1.34841561317,8.59258174896 -6.87067985535,1.34843182564,8.60914707184 -3.4345870018,0.57915276289,4.39858675003 -3.43159747124,0.580158233643,4.40837907791 -3.42161989212,0.58117043972,4.42394924164 -3.3996450901,0.579184889793,4.42352819443 -6.76180648804,1.35750830173,8.77480602264 -6.74982643127,1.36052024364,8.81339836121 -6.72185230255,1.36053609848,8.83495903015 -6.7188615799,1.36254167557,8.85875225067 -6.68588829041,1.36155831814,8.87232303619 -6.66491174698,1.36357247829,8.90189552307 -6.65793180466,1.36758387089,8.94947719574 -6.62395858765,1.36660075188,8.96204662323 -6.60298252106,1.36861503124,8.99162197113 -6.60199165344,1.37162017822,9.01941108704 -6.56701898575,1.3696372509,9.02998447418 -6.54704236984,1.37165129185,9.06155872345 -6.53206443787,1.37466430664,9.09914016724 -6.50808858871,1.37567913532,9.12571048737 -6.48111391068,1.37669467926,9.14728736877 -6.47213506699,1.38070654869,9.1948633194 -6.45015001297,1.37971615791,9.1946439743 -6.43817090988,1.38372850418,9.23722648621 -6.41619539261,1.38474309444,9.26680088043 -6.39321994781,1.38675773144,9.29437923431 -6.36524534225,1.38677358627,9.31594848633 -6.34926843643,1.38978683949,9.3545255661 -6.31429672241,1.38880419731,9.36609363556 -6.30230855942,1.38981163502,9.37888526917 -6.29032993317,1.39382398129,9.42346477509 -6.26735448837,1.39483880997,9.45204162598 -6.24637889862,1.39785325527,9.48461341858 -6.22540330887,1.39986765385,9.51718616486 -6.19742918015,1.39988338947,9.53776741028 -6.17345428467,1.4018985033,9.56633758545 -6.16446590424,1.40290534496,9.58413028717 -6.12249612808,1.39992427826,9.5856924057 -6.07352828979,1.39494431019,9.57426452637 -6.04755353928,1.39595985413,9.59883975983 -6.04457330704,1.40297043324,9.65942287445 -6.01759910583,1.40398609638,9.68299770355 -6.01360988617,1.40699207783,9.71078205109 -5.98963499069,1.40900707245,9.73935699463 -5.96366119385,1.41002261639,9.76493167877 -5.94068622589,1.41203737259,9.79451274872 -5.90571451187,1.41105484962,9.80608177185 -5.8837389946,1.41306948662,9.83766269684 -5.86276388168,1.41608405113,9.87223720551 -5.84377861023,1.4150929451,9.87502479553 -5.8148059845,1.41510915756,9.89659500122 -5.78583240509,1.41612529755,9.91717243195 -5.75685977936,1.41614151001,9.93874359131 -5.72988605499,1.41815721989,9.96331882477 -5.7099108696,1.42117154598,9.99989795685 -5.69692373276,1.42117929459,10.0136823654 -5.67094993591,1.42319476604,10.0392637253 -5.64497613907,1.42421030998,10.0658407211 -5.61400365829,1.42522680759,10.0844125748 -5.58702993393,1.42624247074,10.1079969406 -5.56105661392,1.42725801468,10.1355705261 -5.52508640289,1.42627584934,10.1461362839 -5.51709747314,1.42828249931,10.167930603 -5.48612594604,1.42929923534,10.1865034103 -5.45715284348,1.43031537533,10.2090759277 -5.43217897415,1.43233060837,10.237657547 -5.40820550919,1.43434607983,10.2702283859 -5.373234272,1.43336343765,10.2818002701 -5.34426164627,1.43437969685,10.3033800125 -5.3362736702,1.43738651276,10.3271684647 -5.31329917908,1.43940138817,10.360748291 -5.27932834625,1.43941855431,10.3733263016 -5.25435447693,1.44143390656,10.4039030075 -5.16340017319,1.42346286774,10.3054609299 -2.59197831154,0.91441398859,7.47759485245 -2.58000230789,0.919426679611,7.51817655563 -2.56002879143,0.921440899372,7.53575897217 -2.53905558586,0.922455310822,7.55034255981 -2.5300681591,0.923462212086,7.56213474274 -2.5230910778,0.930473923683,7.61971664429 -2.49911880493,0.930489063263,7.62729358673 -2.47214746475,0.929504871368,7.62586975098 -2.45117402077,0.930519163609,7.64045810699 -2.4661898613,0.948526322842,7.76805114746 -2.38923382759,0.924552261829,7.61160945892 -2.12901186943,1.31895184517,10.5345497131 -2.09604310989,1.31896877289,10.5431251526 -2.07307076454,1.32598340511,10.5997095108 -2.15106725693,1.40797829628,11.1733188629 -2.41601634026,1.64794182777,12.8477592468 -2.37504959106,1.64696002007,12.8493423462 -2.33308339119,1.64597856998,12.8499174118 -2.29711508751,1.64999592304,12.8804988861 -2.25914692879,1.65101337433,12.8970861435 -2.21718096733,1.65003204346,12.8976621628 -2.19919633865,1.65204048157,12.9104576111 -2.1602294445,1.6530585289,12.9290332794 -2.12226176262,1.65607607365,12.9506149292 -2.08029556274,1.65409457684,12.9491949081 -2.03632998466,1.65211343765,12.9357719421 -1.99536287785,1.65113139153,12.9353590012 -1.95639550686,1.65214920044,12.9509410858 -1.94141066074,1.6571573019,12.9897317886 -1.90144371986,1.65817534924,13.0003128052 -1.8674749136,1.66519212723,13.052895546 -1.84750163555,1.68620610237,13.2034845352 -1.8165320158,1.6962223053,13.2840671539 -1.77456569672,1.69624054432,13.286649704 -1.75358247757,1.69624972343,13.2874412537 -1.71061694622,1.69526827335,13.2870168686 -1.66365218163,1.6892875433,13.2505970001 -1.62068593502,1.68730580807,13.2391834259 -1.57872021198,1.68732428551,13.247756958 -1.53575408459,1.68534266949,13.2383403778 -1.49378788471,1.68436074257,13.2369251251 -1.47180521488,1.68337011337,13.2297134399 -1.43183803558,1.68438780308,13.2433013916 -1.38887238503,1.68340623379,13.2358808517 -1.34690618515,1.68242430687,13.2334651947 -1.30493998528,1.68244242668,13.235045433 -1.26197421551,1.68046081066,13.2246265411 -1.23899197578,1.67747032642,13.2074127197 -1.19802510738,1.67648816109,13.2070035934 -1.15605914593,1.6765062809,13.2075834274 -1.11409294605,1.67552423477,13.2011680603 -1.0731266737,1.6765422821,13.2157468796 -1.03116035461,1.67556011677,13.2073326111 -0.989194393158,1.67457818985,13.2059144974 -0.968211472034,1.67458724976,13.2077026367 -0.927245020866,1.67560505867,13.2152872086 -0.884279370308,1.67262327671,13.1988668442 -0.844312250614,1.67464053631,13.2104587555 -0.802346229553,1.67365860939,13.2070417404 -0.760380148888,1.67267644405,13.2006244659 -0.718414127827,1.67069447041,13.1952056885 -0.698430716991,1.67270314693,13.2060003281 -0.656464576721,1.67072093487,13.1935853958 -0.613499224186,1.66873919964,13.1791610718 -0.572532832623,1.66875684261,13.1867456436 -0.532566070557,1.6737742424,13.2213306427 -0.4906001091,1.67279207706,13.2129135132 -0.449633389711,1.6718095541,13.2085046768 -0.428650617599,1.67281842232,13.2162914276 -0.387684047222,1.67283594608,13.217880249 -0.34571814537,1.67185378075,13.2124614716 -0.304751753807,1.67487120628,13.2310466766 -0.262785553932,1.66888892651,13.1936349869 -0.220819696784,1.66790664196,13.1822156906 -0.199836954474,1.66991555691,13.1980028152 -0.158870398998,1.67093288898,13.2035913467 -0.116904594004,1.66895067692,13.1941719055 -0.0759380012751,1.66796791553,13.1857614517 -0.0339722409844,1.66598570347,13.1663417816 --0.0249792281538,1.67101073265,12.7957410812 --0.0449626147747,1.67101931572,12.7975358963 --0.0849295035005,1.67603635788,12.8321256638 --0.124896168709,1.67205345631,12.7997102737 --0.165862202644,1.67407095432,12.8142900467 --0.205829069018,1.67508780956,12.8198785782 --0.24679505825,1.67510533333,12.8204574585 --0.286761939526,1.67612230778,12.8230476379 --0.306745290756,1.67513072491,12.8188400269 --0.346712112427,1.67514765263,12.8174295425 --0.386678755283,1.67416477203,12.8060150146 --0.427644789219,1.67418205738,12.8075942993 --0.467611759901,1.67619895935,12.8141860962 --0.507578492165,1.67521572113,12.8077716827 --0.546545386314,1.67023253441,12.772356987 --0.56652879715,1.67024099827,12.7731513977 --0.607495188713,1.67325806618,12.7887372971 --0.647461593151,1.67127501965,12.77231884 --0.686428904533,1.66929161549,12.7599115372 --0.727395176888,1.67130863667,12.7694959641 --0.767362117767,1.6723253727,12.7710866928 --0.785346150398,1.66733336449,12.7378807068 --0.827312171459,1.67135047913,12.762465477 --0.858281672001,1.6523655653,12.6270532608 --0.907245457172,1.67038393021,12.7496366501 --0.985179543495,1.66641700268,12.7158107758 --1.02814507484,1.67143440247,12.7413911819 --1.0481287241,1.6714425087,12.7461910248 --1.08909487724,1.67245948315,12.7477731705 --1.12806224823,1.67147576809,12.738366127 --1.17002856731,1.6754925251,12.7579565048 --1.21099472046,1.67650938034,12.7575378418 --1.25196135044,1.67752611637,12.7651281357 --1.29292798042,1.67954266071,12.7707176208 --1.31391096115,1.68055105209,12.7745084763 --1.35487723351,1.68156778812,12.7770957947 --1.39684355259,1.68358445168,12.7906847 --1.43780994415,1.68460118771,12.7892684937 --1.47777664661,1.68361759186,12.7808542252 --1.52074253559,1.68763458729,12.7984418869 --1.56170940399,1.68965089321,12.8050365448 --1.58069312572,1.68765890598,12.7928304672 --1.62165939808,1.68767547607,12.7894134521 --1.66162621975,1.68769168854,12.7820014954 --1.70159351826,1.68870770931,12.7805976868 --1.74555909634,1.69172465801,12.8001823425 --1.81150722504,1.69775009155,12.8265600204 --1.85447347164,1.70076668262,12.8411512375 --1.895439744,1.70078313351,12.834733963 --1.93840610981,1.70379960537,12.848326683 --1.98237156868,1.70681643486,12.8629131317 --2.02333855629,1.70783257484,12.8625068665 --2.06530451775,1.70884883404,12.8630914688 --2.08728790283,1.71085715294,12.8738927841 --2.12925410271,1.71187341213,12.8744783401 --2.1692211628,1.71188938618,12.8650693893 --2.21118760109,1.71290576458,12.863653183 --2.25615286827,1.71592259407,12.8812417984 --2.29112172127,1.71193742752,12.8448352814 --2.33908605576,1.71795475483,12.8764200211 --2.36006951332,1.71896278858,12.8782186508 --2.4060344696,1.72297954559,12.8978042603 --2.44600200653,1.72299516201,12.8914031982 --2.48996782303,1.72501158714,12.896985054 --2.53293395042,1.72702777386,12.9005746841 --2.57690024376,1.7300440073,12.9131727219 --2.5968837738,1.73005175591,12.9069662094 --2.6398499012,1.7310680151,12.9095563889 --2.6838157177,1.73308432102,12.9141407013 --2.72778177261,1.73610055447,12.9207305908 --2.76974844933,1.73711633682,12.9183216095 --2.81471419334,1.74013257027,12.9299144745 --2.85468149185,1.73914825916,12.9165019989 --2.87866401672,1.74215650558,12.9293003082 --2.92163038254,1.74317240715,12.9298906326 --2.96359682083,1.74418818951,12.9234762192 --3.00756311417,1.7462041378,12.929069519 --3.05252885818,1.74922037125,12.9366598129 --3.09449577332,1.75023579597,12.9342556 --3.13746237755,1.75125169754,12.9318437576 --3.16244459152,1.75425994396,12.94764328 --3.20641064644,1.75627601147,12.947227478 --3.24837756157,1.7572914362,12.9438238144 --3.29134392738,1.75830698013,12.9414148331 --3.33830952644,1.76232326031,12.9550065994 --3.37827730179,1.76233828068,12.9426021576 --3.42624211311,1.76635456085,12.9581918716 --3.45122432709,1.76836287975,12.9679832458 --3.49319124222,1.76837825775,12.9605741501 --3.54115653038,1.77339434624,12.9771709442 --3.58212375641,1.77340960503,12.9637565613 --3.62908935547,1.77642548084,12.9753522873 --3.67505502701,1.77944147587,12.9799404144 --3.69503903389,1.77844882011,12.9727373123 --3.74300432205,1.78246486187,12.985329628 --3.78996992111,1.78548073769,12.9939222336 --3.82893800735,1.7844953537,12.9755153656 --3.87390422821,1.78651082516,12.9761066437 --3.91687130928,1.78852581978,12.9717025757 --3.95983839035,1.78954100609,12.966296196 --3.98582029343,1.79154920578,12.9770898819 --4.03478574753,1.79556524754,12.9896821976 --4.07675266266,1.79658007622,12.9802761078 --4.12071990967,1.79859507084,12.9788742065 --4.16668605804,1.8006105423,12.9804649353 --4.20965242386,1.80162549019,12.9720544815 --4.25162029266,1.80164003372,12.9626502991 --4.27560281754,1.803647995,12.9664468765 --4.31657075882,1.80366253853,12.953040123 --4.36253738403,1.80567777157,12.9536314011 --4.41050291061,1.80969321728,12.9602241516 --4.45247030258,1.8097076416,12.9498195648 --4.4984369278,1.81272268295,12.9524202347 --4.5224199295,1.81373047829,12.9542140961 --4.56438732147,1.81474483013,12.9428071976 --4.60835409164,1.81575965881,12.9353952408 --4.65332126617,1.81777441502,12.9339962006 --4.69928741455,1.81978940964,12.9315853119 --4.74525403976,1.82180428505,12.931180954 --4.79521942139,1.82581961155,12.9417791367 --4.81620359421,1.82582676411,12.9345722198 --4.8591709137,1.82784104347,12.9261703491 --4.91513490677,1.83385717869,12.9507675171 --4.95610284805,1.83387124538,12.9333553314 --5.01006698608,1.83888709545,12.9519519806 --5.05303525925,1.83990120888,12.9415473938 --5.10500049591,1.84491670132,12.9541444778 --5.09599256516,1.83291935921,12.8709383011 --5.10297060013,1.81892836094,12.7695274353 --5.10894918442,1.80593717098,12.6691236496 --5.14591884613,1.80495035648,12.6447153091 --5.17988967896,1.80296289921,12.615316391 --5.20886135101,1.79897499084,12.5729112625 --5.22384738922,1.79698097706,12.5517044067 --5.2518196106,1.79299283028,12.5083026886 --5.27379369736,1.78600370884,12.4508991241 --5.30176591873,1.78201544285,12.4064893723 --5.31574201584,1.77302527428,12.3310832977 --5.30472564697,1.75403153896,12.1996774673 --5.29670858383,1.73803818226,12.0772714615 --5.18473148346,1.69002652168,11.772064209 --5.18571138382,1.67703461647,11.6736545563 --5.21168422699,1.67304611206,11.6322469711 --5.20366716385,1.65805268288,11.5178451538 --5.19964838028,1.64306020737,11.4104280472 --5.26760911942,1.65407717228,11.4640293121 --5.2415971756,1.63308143616,11.3126192093 --5.1826043129,1.60607719421,11.140417099 --5.21357631683,1.60508930683,11.1150131226 --5.24754667282,1.60410165787,11.0946025848 --5.26952123642,1.6001124382,11.0512008667 --5.30249261856,1.59912455082,11.0297937393 --5.39444684982,1.61914455891,11.1303920746 --5.40843296051,1.61715018749,11.1151924133 --5.43540620804,1.61516141891,11.0817899704 --5.47137594223,1.61517393589,11.0653810501 --5.53633832932,1.62519013882,11.1079788208 --5.55031490326,1.61819970608,11.0475702286 --5.59628295898,1.62221312523,11.0531740189 --5.57826900482,1.60521841049,10.930762291 --5.64024162292,1.61923027039,11.0085611343 --5.69320774078,1.62524461746,11.0271654129 --5.69618749619,1.61525261402,10.9467544556 --5.74215555191,1.61826610565,10.949347496 --5.76413011551,1.61527633667,10.9079465866 --5.8011007309,1.61528849602,10.8935394287 --5.8440694809,1.6183013916,10.8921432495 --5.91104078293,1.63331365585,10.974943161 --5.88802862167,1.61631798744,10.8495340347 --5.94899225235,1.62433314323,10.8791322708 --5.999958992,1.62934696674,10.8897275925 --6.00793790817,1.62135517597,10.8233242035 --6.03891038895,1.62036645412,10.7979183197 --6.14487123489,1.64638340473,10.946723938 --6.11286115646,1.62738656998,10.8093166351 --6.16482782364,1.63240015507,10.8209133148 --6.16980791092,1.62340795994,10.7515144348 --6.20177984238,1.6234190464,10.7281103134 --6.24874830246,1.62743198872,10.7307081223 --6.3357052803,1.6424498558,10.8003063202 --6.314702034,1.63145065308,10.7261047363 --6.35667133331,1.63346302509,10.7186985016 --6.40863847733,1.63947629929,10.729300499 --6.47660112381,1.64849162102,10.7648983002 --6.48957872391,1.64250016212,10.7094936371 --6.53654766083,1.64651274681,10.7110967636 --6.59051418304,1.65252614021,10.7216901779 --6.60650014877,1.65153157711,10.7094888687 --6.64047241211,1.65154254436,10.6880836487 --6.67644453049,1.65255355835,10.6706838608 --6.84238052368,1.68857991695,10.8603000641 --6.79137611389,1.66558074951,10.7028846741 --6.79235744476,1.65658760071,10.6304836273 --6.8623290062,1.67059922218,10.7012796402 --7.03126525879,1.70762562752,10.8888940811 --6.95326805115,1.67762303352,10.694486618 --6.9862408638,1.67663371563,10.6700792313 --7.10319137573,1.69965362549,10.7746906281 --7.17515420914,1.7096683979,10.8102989197 --7.18213367462,1.7026758194,10.7458896637 --7.21711492538,1.70668303967,10.7606887817 --7.23509216309,1.70269155502,10.7142887115 --7.2590675354,1.70070064068,10.6768875122 --7.37201929092,1.7207198143,10.7694950104 --7.47997283936,1.73973822594,10.8531017303 --7.37498283386,1.70373296738,10.6276817322 --7.41895294189,1.70674419403,10.6182775497 --7.47492933273,1.71675348282,10.6630859375 --7.52389860153,1.72076523304,10.6606855392 --7.57986593246,1.72677755356,10.6682891846 --7.64483070374,1.73379087448,10.6878929138 --7.65581035614,1.72879827023,10.6314878464 --7.7147769928,1.73481082916,10.6420907974 --7.74775934219,1.73881733418,10.6518917084 --7.79172992706,1.7418282032,10.6414937973 --7.83370161057,1.74383878708,10.6280965805 --7.86967468262,1.74384880066,10.6056928635 --7.92564249039,1.74986052513,10.6112995148 --7.96861362457,1.75187110901,10.5978965759 --7.98459196091,1.7478787899,10.5484895706 --8.01657485962,1.75088512897,10.5562944412 --8.05854606628,1.75289535522,10.5418958664 --8.09651947021,1.75490510464,10.5224981308 --8.19847583771,1.77092134953,10.5861101151 --8.17446517944,1.75692462921,10.4867067337 --8.27642154694,1.77394092083,10.5473098755 --8.31939315796,1.77595090866,10.5339164734 --8.29339122772,1.76595127583,10.4657049179 --8.29637432098,1.75895726681,10.4023065567 --8.44031906128,1.78497707844,10.5149259567 --8.47029495239,1.7839858532,10.4825172424 --8.526263237,1.7889970541,10.4831190109 --8.58523178101,1.79500830173,10.4887304306 --8.62221336365,1.80001473427,10.4995317459 --8.67418384552,1.80402517319,10.4951372147 --8.66416835785,1.79402959347,10.4147281647 --8.69114589691,1.79303753376,10.3803310394 --8.78210544586,1.80605173111,10.4219417572 --8.68611335754,1.77704799175,10.2415237427 --5.51989507675,1.05575251579,6.44965076447 --5.47889614105,1.04375219345,6.38044071198 --5.46088171005,1.03475773335,6.31701993942 --5.45086622238,1.02876377106,6.26562213898 --5.45084810257,1.02377080917,6.2252163887 --5.43983268738,1.01677691936,6.17180204391 --5.4488120079,1.01478469372,6.14239883423 --5.42879915237,1.00578975677,6.08099794388 --5.40979480743,0.999791502953,6.03978967667 --5.42377281189,0.998799860477,6.01638364792 --5.40575933456,0.990805327892,5.95696783066 --5.4187374115,0.988813638687,5.93255805969 --5.41172122955,0.983819901943,5.88715553284 --5.4077038765,0.978826582432,5.84474658966 --5.40668582916,0.974833667278,5.805331707 --5.39967823029,0.970836520195,5.77912807465 --5.39266204834,0.965842843056,5.73472309113 --5.40764045715,0.964851021767,5.71432352066 --5.40662288666,0.960857868195,5.67692089081 --5.40360498428,0.955864667892,5.63650512695 --5.39558887482,0.950870931149,5.59209918976 --5.39757919312,0.949874639511,5.57589292526 --5.3975610733,0.945881485939,5.54049062729 --5.39854288101,0.941888689995,5.50507450104 --5.4105219841,0.940896511078,5.48267745972 --5.4095044136,0.936903357506,5.4462685585 --5.42048358917,0.935911297798,5.42185688019 --5.41646671295,0.931917726994,5.38345527649 --5.40246105194,0.926919996738,5.35225152969 --5.4074420929,0.923927307129,5.32284593582 --5.45441246033,0.929938077927,5.33443784714 --5.42840099335,0.921942770481,5.27503252029 --5.44937801361,0.922951281071,5.26162910461 --5.46235704422,0.921959161758,5.24022245407 --5.48633384705,0.922967791557,5.22982168198 --5.47632646561,0.918970584869,5.20260810852 --5.51130104065,0.922979950905,5.20321464539 --5.5352768898,0.924988687038,5.19180297852 --5.55325508118,0.92499679327,5.17540025711 --5.58523035049,0.928005933762,5.17199802399 --5.58021402359,0.924012124538,5.13459873199 --5.60419034958,0.925020694733,5.12318944931 --5.63817358017,0.930026531219,5.13799142838 --5.64315509796,0.928033530712,5.10958814621 --5.67712926865,0.932042717934,5.10718250275 --5.72510051727,0.938052773476,5.1177854538 --5.7390794754,0.937060475349,5.09637069702 --5.76405668259,0.939068734646,5.08597183228 --5.79004192352,0.943073809147,5.09277439117 --5.81401872635,0.944082140923,5.08036422729 --5.82999801636,0.944089651108,5.06196641922 --5.85397481918,0.94509780407,5.04955768585 --5.89994764328,0.951107382774,5.05716562271 --5.92792367935,0.954115748405,5.04775524139 --5.95789957047,0.95612424612,5.040350914 --5.98388528824,0.960129141808,5.04615259171 --5.99986457825,0.96013635397,5.02776050568 --6.03683948517,0.964145064354,5.0263633728 --6.07381343842,0.968153774738,5.02395677567 --6.09779167175,0.969161510468,5.0115609169 --6.1277680397,0.972169697285,5.00315523148 --6.16074323654,0.97517812252,4.99674606323 --6.19172716141,0.979183197021,5.00554609299 --6.20770740509,0.97919023037,4.98614883423 --6.24768161774,0.98419880867,4.9857506752 --6.28765583038,0.98820745945,4.98434305191 --6.3106341362,0.990214645863,4.97095537186 --6.3636059761,0.997223973274,4.97955179214 --6.3875837326,0.99823141098,4.96514558792 --6.40857076645,1.00023567677,4.9649438858 --6.45254468918,1.00624418259,4.96654891968 --6.48552131653,1.00925195217,4.95914936066 --6.50749969482,1.01025903225,4.94274377823 --6.54247570038,1.01326692104,4.93634176254 --6.57945108414,1.01727473736,4.9319486618 --6.60842895508,1.02028214931,4.92054462433 --6.63541460037,1.02328646183,4.92434692383 --6.65439462662,1.02429318428,4.90595006943 --6.69536972046,1.0283010006,4.90355443954 --5.56858921051,0.82124710083,4.03693914413 --5.57756900787,0.820254266262,4.0145111084 --5.58655071259,0.819260776043,3.9951274395 --5.59154129028,0.819264233112,3.98492217064 --6.86826038361,1.04733514786,4.88076114655 --6.90523672104,1.05134260654,4.87335395813 --6.9352145195,1.05334937572,4.86196088791 --7.02316474915,1.06336450577,4.85716342926 --7.08213663101,1.07137262821,4.86476707458 --7.11412239075,1.07637679577,4.87057495117 --7.13810157776,1.0773832798,4.85316944122 --7.17107915878,1.08038985729,4.84277677536 --7.23605060577,1.08939802647,4.85338306427 --7.26003026962,1.09040427208,4.83598327637 --7.29700660706,1.09441101551,4.82657814026 --7.34498214722,1.10041809082,4.82518577576 --7.38396692276,1.10542225838,4.83500051498 --7.41294527054,1.10842859745,4.81959295273 --7.43992471695,1.11043465137,4.80319070816 --7.50389671326,1.11844217777,4.81079626083 --7.55987071991,1.12544906139,4.81441879272 --7.59284925461,1.12845528126,4.80101490021 --7.63782501221,1.133461833,4.7956199646 --7.6688117981,1.13746535778,4.79842615128 --7.71778726578,1.14347195625,4.79503107071 --7.75376558304,1.14747810364,4.78262615204 --7.79174375534,1.15148389339,4.77324438095 --7.85271692276,1.15949070454,4.77584457397 --7.89069509506,1.16249656677,4.76444530487 --7.94567012787,1.16950285435,4.76406002045 --7.98365545273,1.17450630665,4.76986694336 --8.01963424683,1.1785119772,4.75646591187 --8.07960796356,1.18551838398,4.75706863403 --8.13058376312,1.19152414799,4.75267791748 --8.1535654068,1.19352912903,4.73229026794 --8.22353839874,1.20253551006,4.73789644241 --8.25751781464,1.20554065704,4.7224984169 --8.28750514984,1.20954358578,4.72230291367 --8.33048343658,1.21454882622,4.71190929413 --8.39345836639,1.22255468369,4.71251821518 --8.45143318176,1.2295601368,4.71012878418 --8.51040840149,1.23656570911,4.70773696899 --8.5733833313,1.24457120895,4.70734786987 --8.64336490631,1.25557470322,4.72917079926 --11.5018405914,1.72764730453,6.23214435577 --11.5098285675,1.72564911842,6.18874168396 --11.5018177032,1.72065067291,6.13733959198 --11.5078058243,1.7186524868,6.0929350853 --11.5047950745,1.71465396881,6.04453372955 --11.4877920151,1.70965445042,6.01233053207 --11.489780426,1.70765602589,5.96693086624 --11.4807710648,1.70265746117,5.91552495956 --11.4877586365,1.70065927505,5.87211894989 --11.4727506638,1.69466042519,5.81871747971 --11.4687395096,1.69166183472,5.77031087875 --8.04729175568,1.12761163712,3.98394846916 --8.03828620911,1.12461364269,3.96273708344 --8.02827358246,1.12161755562,3.9253256321 --8.03525924683,1.120621562,3.89692378044 --8.02724647522,1.11662554741,3.86050987244 --8.02323246002,1.11462926865,3.82710766792 --8.03421783447,1.11363351345,3.80070447922 --8.02520561218,1.11063718796,3.76530432701 --8.02619743347,1.10963928699,3.74908995628 --8.0161857605,1.10664308071,3.71369242668 --8.01217269897,1.10364699364,3.68028378487 --8.00516033173,1.10065078735,3.64587783813 --8.00914573669,1.09965467453,3.61647129059 --8.01413059235,1.09865868092,3.58705830574 --8.01511764526,1.09666264057,3.55665445328 --7.99711275101,1.09266424179,3.53345298767 --8.00309848785,1.09166824818,3.50504469872 --8.03108119965,1.09467196465,3.48765659332 --8.08405971527,1.10067605972,3.48026275635 --8.13303852081,1.10667991638,3.47086882591 --8.18601703644,1.11368358135,3.46348333359 --8.24500179291,1.12268543243,3.47329282761 --8.29998111725,1.12868905067,3.46590447426 --8.35495948792,1.13569247723,3.45750761032 --8.41093826294,1.1436958313,3.45012259483 --8.47191619873,1.15069913864,3.44372940063 --8.53089523315,1.15870213509,3.43735098839 --8.60087203979,1.16770517826,3.43396091461 --8.64585971832,1.17470657825,3.43677568436 --11.6584272385,1.64769375324,4.63430404663 --11.6574163437,1.64469444752,4.5898938179 --11.6534080505,1.64269518852,4.5454916954 --11.6593971252,1.64069569111,4.50509214401 --11.6423912048,1.63569653034,4.45568561554 --11.6423816681,1.63369715214,4.41328477859 --11.640376091,1.63169753551,4.39108181 --11.6373682022,1.62969815731,4.34768009186 --11.6333580017,1.62669873238,4.30327177048 --11.6363487244,1.62469923496,4.26186752319 --11.6333398819,1.62269973755,4.21846294403 --11.6353311539,1.62070012093,4.17807006836 --11.6343212128,1.61870062351,4.13566589355 --11.615319252,1.61470115185,4.10745573044 --11.602312088,1.60970175266,4.06104946136 --11.6103010178,1.60970211029,4.02164268494 --11.5972948074,1.60570275784,3.97624325752 --11.5982847214,1.60370314121,3.93483781815 --11.6112747192,1.60370314121,3.89844369888 --11.5922679901,1.59870386124,3.85002851486 --11.587264061,1.5967041254,3.82782673836 --11.6052532196,1.59770393372,3.793435812 --11.5952453613,1.59470438957,3.74902939796 --11.5942363739,1.59270477295,3.70762515068 --11.6062269211,1.59270465374,3.67022156715 --11.4512357712,1.56670856476,3.5797727108 --11.4532270432,1.56470882893,3.54037189484 --11.4572219849,1.56470882893,3.52116775513 --11.4342164993,1.55970966816,3.47375607491 --11.4362068176,1.55770993233,3.43435287476 --11.4461975098,1.55770981312,3.39795732498 --11.4321908951,1.55371034145,3.353546381 --11.432182312,1.55271053314,3.31414604187 --11.4501714706,1.55370998383,3.27974796295 --11.423169136,1.54871094227,3.2525434494 --11.4211616516,1.54671108723,3.21213626862 --11.4271526337,1.5457110405,3.1747379303 --11.4191446304,1.54271125793,3.13232445717 --11.4101381302,1.5407115221,3.09092211723 --11.4241285324,1.54071092606,3.05552220345 --11.4061222076,1.5367115736,3.01110982895 --11.4031181335,1.53571164608,2.99090862274 --11.4131088257,1.53571116924,2.95450735092 --11.4001016617,1.53171157837,2.91209983826 --11.4000940323,1.53071141243,2.87370109558 --11.3980865479,1.52871131897,2.83429598808 --11.3940792084,1.52671134472,2.79489469528 --11.3910751343,1.52571129799,2.77469086647 --11.4250640869,1.52970969677,2.74429535866 --11.3740606308,1.52071166039,2.69388389587 --11.3600540161,1.51671206951,2.65146970749 --11.4110422134,1.52270948887,2.62609052658 --11.4160337448,1.52270889282,2.58868694305 --11.4540233612,1.52670657635,2.55929756165 --11.493016243,1.53170442581,2.54910898209 --11.515007019,1.53370285034,2.51571440697 --11.5439968109,1.53770089149,2.48331665993 --11.5889863968,1.5426980257,2.45493149757 --11.4849872589,1.52570259571,2.39349293709 --11.4779806137,1.52370238304,2.35409188271 --11.5149707794,1.52769982815,2.32370090485 --11.6989526749,1.55468952656,2.34356498718 --11.7389431,1.55968642235,2.3131775856 --11.7719335556,1.56368350983,2.28078436852 --11.8009252548,1.5666809082,2.2483997345 --11.8419160843,1.57167744637,2.21700620651 --11.8729076385,1.57467448711,2.18361139297 --11.898900032,1.57767176628,2.15022611618 --11.9358940125,1.58266890049,2.13804221153 --11.9608860016,1.58566594124,2.10264062881 --11.4559135437,1.50969600677,1.97005140781 --11.3069171906,1.48670446873,1.90559601784 --11.2689123154,1.47970604897,1.86117303371 --11.3569002151,1.49169957638,1.83980464935 --11.3398952484,1.48869967461,1.79939186573 --11.3158931732,1.48470079899,1.77718615532 --11.2708892822,1.47670292854,1.73276734352 --11.2648820877,1.47470235825,1.69435536861 --11.2518768311,1.472702384,1.65595209599 --11.2418708801,1.46970200539,1.61754357815 --11.223865509,1.46670246124,1.57813322544 --11.2278623581,1.46670162678,1.56093835831 --11.2608537674,1.47069811821,1.52853870392 --11.2468481064,1.46769809723,1.49013268948 --11.2418422699,1.46669745445,1.45272552967 --11.3178329468,1.47669053078,1.42735660076 --11.3048267365,1.4746901989,1.38894879818 --11.3528194427,1.48068523407,1.35856211185 --11.3428134918,1.47868466377,1.3201508522 --11.2168169022,1.45969390869,1.28590381145 --11.2218112946,1.45969235897,1.25050497055 --11.2748022079,1.46668672562,1.22011530399 --11.2957954407,1.46868360043,1.18672573566 --11.2147932053,1.45668888092,1.14028358459 --11.2057876587,1.45468831062,1.10388505459 --11.2487802505,1.46068322659,1.07249832153 --11.2137794495,1.4546854496,1.05027925968 --11.2057733536,1.45268464088,1.01286709309 --11.2897663116,1.46467578411,0.985498130322 --11.1947631836,1.45068264008,0.940059006214 --11.1787586212,1.44768249989,0.902649998665 --11.1737537384,1.44668138027,0.866243600845 --11.1047525406,1.43568694592,0.842013835907 --11.2397441864,1.45567286015,0.818669140339 --11.2417383194,1.4556709528,0.78226017952 --11.2447338104,1.45566892624,0.746861994267 --11.1707296371,1.44367432594,0.705432713032 --11.1947240829,1.44667005539,0.671033740044 --11.2207193375,1.45066583157,0.637646794319 --11.1707172394,1.44266974926,0.615416049957 --11.1817131042,1.44466674328,0.581023156643 --11.2387065887,1.4526591301,0.548639416695 --11.1547040939,1.43966567516,0.508208036423 --11.1406993866,1.43766522408,0.471798658371 --11.1546945572,1.43866169453,0.436393976212 --11.1626901627,1.43965888023,0.400991022587 --11.1416883469,1.43666017056,0.382787793875 --11.1636829376,1.43965578079,0.348394453526 --11.1506786346,1.43765509129,0.311982423067 --11.1626749039,1.43865156174,0.276579856873 --11.1896696091,1.44264650345,0.242189303041 --11.2246656418,1.4476402998,0.207800909877 --11.1186618805,1.43164992332,0.16935968399 --11.1196603775,1.43164861202,0.151152163744 --11.0786552429,1.42565107346,0.114731840789 --11.1076517105,1.42964541912,0.080342695117 --11.1396474838,1.43463933468,0.0449445061386 --11.1346445084,1.43363749981,0.00954018626362 --11.1276397705,1.43263602257,-0.0258651897311 --11.1396360397,1.43463206291,-0.0612653233111 --11.1576356888,1.4366286993,-0.0784551799297 --11.1566314697,1.43662619591,-0.113858282566 --11.156627655,1.4366235733,-0.149261027575 --11.2136259079,1.44461405277,-0.184638768435 --11.2216234207,1.44661021233,-0.221047312021 --11.1706180573,1.43861377239,-0.256473660469 --11.237616539,1.44860267639,-0.291839182377 --11.314617157,1.4595913887,-0.311012476683 --11.2766132355,1.45459330082,-0.346432477236 --11.2126083374,1.44459855556,-0.38086014986 --11.1106033325,1.43060898781,-0.414307117462 --11.1776018143,1.43959712982,-0.451686292887 --11.2046003342,1.44459056854,-0.48807951808 --11.2135982513,1.44558632374,-0.523473024368 --11.1835956573,1.44158875942,-0.540691792965 --11.1485919952,1.43659043312,-0.575111269951 --11.1095876694,1.43059265614,-0.609536707401 --11.171587944,1.43958103657,-0.646906614304 --11.1505851746,1.43758070469,-0.681317031384 --11.1665830612,1.43957519531,-0.717714726925 --11.1645803452,1.43957221508,-0.753118395805 --11.1625795364,1.43957078457,-0.771327078342 --11.2555818558,1.45355415344,-0.811685085297 --11.2495794296,1.45255148411,-0.847089707851 --11.2135763168,1.4475530386,-0.88151794672 --11.2255744934,1.44954776764,-0.917914271355 --11.2705755234,1.45653748512,-0.956291854382 --11.3835811615,1.47351884842,-0.982446372509 --11.3105754852,1.4635258913,-1.01388716698 --11.2485704422,1.4545314312,-1.04531848431 --11.2775707245,1.45952320099,-1.08371055126 --11.2545690536,1.45652282238,-1.11812722683 --11.2755689621,1.4595156908,-1.15551638603 --11.2745676041,1.45951187611,-1.1919246912 --11.2315635681,1.45351660252,-1.20614659786 --11.2185621262,1.45251464844,-1.24055206776 --11.228562355,1.45450901985,-1.27795648575 --11.2605628967,1.45949983597,-1.31633603573 --11.288564682,1.46449112892,-1.35573101044 --11.2575616837,1.46049201488,-1.38915395737 --11.2955636978,1.46648144722,-1.42954051495 --11.2225580215,1.45549142361,-1.43876636028 --11.2325592041,1.45748543739,-1.47616708279 --11.2555599213,1.46147716045,-1.51556611061 --11.3915719986,1.48244976997,-1.56790351868 --11.3555688858,1.47745132446,-1.60032534599 --11.3705692291,1.48044407368,-1.63872039318 --11.3055639267,1.47145068645,-1.66715598106 --11.3875713348,1.4844340086,-1.69632101059 --11.4065732956,1.48742592335,-1.73571574688 --11.3765716553,1.48342633247,-1.76812946796 --11.4225759506,1.49141335487,-1.81151211262 --11.4605808258,1.49740147591,-1.85389637947 --11.4065761566,1.49040603638,-1.88332784176 --11.4945869446,1.50438511372,-1.93369066715 --11.634601593,1.52535688877,-1.97382760048 --11.4615850449,1.50038313866,-1.9843082428 --11.5605964661,1.51635956764,-2.03766870499 --11.5235948563,1.51136088371,-2.07009792328 --11.5295963287,1.51335430145,-2.10849690437 --11.494594574,1.50935542583,-2.13991379738 --11.5335998535,1.51534235477,-2.18429970741 --11.4975976944,1.51034653187,-2.19651460648 --11.5046005249,1.51233935356,-2.23592066765 --11.4885997772,1.51133692265,-2.27032756805 --11.6536216736,1.53629899025,-2.33865642548 --11.6446228027,1.53629469872,-2.37506246567 --11.6206226349,1.53329336643,-2.40847396851 --11.6176252365,1.53428781033,-2.44688677788 --11.6296281815,1.53628242016,-2.46808004379 --11.6046276093,1.53428125381,-2.50149607658 --11.5916290283,1.53327763081,-2.53690266609 --11.6176357269,1.53826618195,-2.58029103279 --11.6426420212,1.54325449467,-2.6246907711 --12.123711586,1.61614894867,-2.7638502121 --11.9646940231,1.59317481518,-2.77033448219 --11.8156747818,1.57120215893,-2.75861501694 --11.791674614,1.56920051575,-2.79202413559 --11.8316850662,1.57618510723,-2.84041047096 --11.8586931229,1.58117246628,-2.88579893112 --11.8887014389,1.58715891838,-2.93218684196 --11.8957071304,1.59015023708,-2.97358751297 --11.9147129059,1.59314262867,-2.99777817726 --11.9727258682,1.60312247276,-3.05216002464 --12.0007352829,1.60910892487,-3.09854435921 --11.9997406006,1.61010146141,-3.13895153999 --12.2017784119,1.64204895496,-3.22925376892 --12.174779892,1.63904702663,-3.26367115974 --12.1627845764,1.63904154301,-3.30208420753 --12.2007932663,1.64502882957,-3.33226585388 --12.2098007202,1.64801871777,-3.37566280365 --12.2768182755,1.65899527073,-3.43402647972 --12.443854332,1.68594813347,-3.52034807205 --12.5638828278,1.70591139793,-3.59569787979 --12.4238653183,1.68593513966,-3.60017037392 --12.4968852997,1.69890916348,-3.66253519058 --12.5789041519,1.71188533306,-3.70669555664 --12.7359409332,1.73783898354,-3.79301118851 --13.1760311127,1.80572402477,-3.96219301224 --12.8219738007,1.75379908085,-3.90577960014 --13.213057518,1.81569457054,-4.06297540665 --12.9980268478,1.78473639488,-4.04549217224 --12.9250211716,1.77474403381,-4.06893587112 --13.0760612488,1.79969656467,-4.15926170349 --12.9670438766,1.78471839428,-4.14851713181 --12.9380474091,1.78171527386,-4.18493843079 --12.9090509415,1.77871215343,-4.22035121918 --13.0110826492,1.79667592049,-4.29770565033 --13.0931100845,1.81164455414,-4.36805725098 --13.155134201,1.82261765003,-4.43443441391 --13.2731647491,1.84158182144,-4.49557590485 --13.5192289352,1.88150703907,-4.62184715271 --13.6102609634,1.89747166634,-4.69920158386 --13.6602840424,1.90744650364,-4.76357650757 --13.5432710648,1.89146530628,-4.77203798294 --13.5322809219,1.89245593548,-4.81644916534 --13.5552988052,1.89843785763,-4.87183666229 --13.6453256607,1.91340756416,-4.92699098587 --13.8963975906,1.95432758331,-5.06326389313 --14.2865028381,2.01620912552,-5.24945497513 --14.2165021896,2.00821447372,-5.2758975029 --14.2725305557,2.01918554306,-5.34626579285 --14.3855743408,2.03914022446,-5.43860960007 --14.4856138229,2.05709862709,-5.52695894241 --14.6266565323,2.08105230331,-5.60407876968 --14.6746854782,2.09102416039,-5.67445373535 --14.8607501984,2.12195658684,-5.79776000977 --14.9097795486,2.13292741776,-5.87013578415 --14.9408063889,2.13990330696,-5.93551683426 --14.9968395233,2.15187144279,-6.01189184189 --15.0168638229,2.15784955025,-6.07428264618 --15.0358781815,2.16183638573,-6.10846853256 --15.025894165,2.16382288933,-6.15987873077 --15.044919014,2.1698012352,-6.22226810455 --15.0679445267,2.17577815056,-6.2866563797 --15.0469589233,2.17576789856,-6.33407258987 --15.0299739838,2.17575621605,-6.38248205185 --15.0620031357,2.18373012543,-6.45086336136 --15.0630130768,2.18572163582,-6.47906255722 --15.0560321808,2.18770670891,-6.53247070312 --15.0510520935,2.18969106674,-6.58687829971 --15.0220651627,2.18868303299,-6.63029289246 --15.0410909653,2.19465994835,-6.69468355179 --15.0451135635,2.1986413002,-6.75308465958 --15.0331315994,2.19962763786,-6.80449342728 --15.0251407623,2.2006213665,-6.82869434357 --15.0471687317,2.20759677887,-6.89609003067 --15.0271854401,2.2075855732,-6.94349813461 --15.018204689,2.20957040787,-6.99690723419 --15.0082235336,2.21055603027,-7.04931259155 --15.001244545,2.21353983879,-7.10372018814 --15.0012674332,2.21652173996,-7.16112136841 --15.0092811584,2.21950984001,-7.19432258606 --15.0133066177,2.22349023819,-7.25372028351 --14.9983243942,2.22547698021,-7.30412721634 --15.0183553696,2.2324514389,-7.37252378464 --15.0283823013,2.23742961884,-7.43491506577 --15.0274066925,2.24041104317,-7.49331998825 --15.0184278488,2.2433950901,-7.54772758484 --15.0124378204,2.24338769913,-7.57392978668 --15.014462471,2.24736785889,-7.63332700729 --15.003484726,2.2493519783,-7.68774032593 --14.9945068359,2.25233578682,-7.74214553833 --14.9955320358,2.25631570816,-7.80255079269 --15.0005598068,2.26029443741,-7.86394453049 --15.0055875778,2.26527261734,-7.92735099792 --14.9885940552,2.26526880264,-7.94755506516 --14.999625206,2.27024483681,-8.01395511627 --14.9736423492,2.27023386955,-8.06037044525 --14.9686670303,2.2732155323,-8.11777305603 --14.9596910477,2.27619862556,-8.17317771912 --14.9327077866,2.27618765831,-8.21959686279 --14.9407253265,2.27917432785,-8.25479698181 --14.936750412,2.28215503693,-8.31319904327 --14.9047660828,2.2811460495,-8.35661792755 --14.8877878189,2.28313136101,-8.40903377533 --14.8738098145,2.285115242,-8.46244239807 --14.8548316956,2.28610110283,-8.51385879517 --14.8408546448,2.28808522224,-8.56726741791 --14.8408689499,2.29007434845,-8.59847068787 --14.8278932571,2.29205775261,-8.65288066864 --14.8049125671,2.29304504395,-8.70229911804 --14.7919368744,2.29502820969,-8.75670719147 --14.737944603,2.29102706909,-8.78814411163 --14.7349729538,2.29500627518,-8.84854793549 --14.7510089874,2.3019785881,-8.91993713379 --14.7470226288,2.30396866798,-8.94914150238 --14.734046936,2.30595159531,-9.00455284119 --14.7450838089,2.31292510033,-9.07394695282 --14.6920909882,2.30792331696,-9.10538101196 --14.6931228638,2.31290030479,-9.1697845459 --14.7021589279,2.31887388229,-9.2391834259 --14.6821813583,2.32085871696,-9.29059791565 --14.6851987839,2.32384610176,-9.32479858398 --14.6902332306,2.32982087135,-9.3921995163 --14.6542491913,2.32781195641,-9.43462562561 --14.6342735291,2.3297970295,-9.48603630066 --14.6683216095,2.34075927734,-9.57242012024 --14.7043714523,2.35172057152,-9.66080188751 --14.892493248,2.38961791992,-9.84809589386 --15.1176156998,2.43151187897,-10.0261592865 --15.0946407318,2.43249607086,-10.0795783997 --15.012638092,2.42350578308,-10.0930252075 --14.9436407089,2.41650938988,-10.1154689789 --14.8996553421,2.4145026207,-10.1549034119 --14.8636741638,2.4134926796,-10.1983251572 --14.8146867752,2.41048812866,-10.2337598801 --14.7826890945,2.40748929977,-10.2459793091 --14.7297000885,2.40348649025,-10.2784156799 --14.6937189102,2.40347647667,-10.3218402863 --14.6237201691,2.39648127556,-10.3422870636 --14.5897397995,2.39547085762,-10.3857040405 --14.5577611923,2.39545893669,-10.4321289062 --14.4757566452,2.38646936417,-10.4435844421 --14.4047384262,2.37748837471,-10.4278306961 --14.3887672424,2.3794696331,-10.4842405319 --14.3227710724,2.37347316742,-10.5056848526 --14.2667789459,2.36947250366,-10.5341234207 --14.2358007431,2.36946034431,-10.5805482864 --14.1587982178,2.36146974564,-10.5929985046 --14.1218156815,2.36046028137,-10.6344242096 --14.0858163834,2.35746407509,-10.6426506042 --14.0338258743,2.35346150398,-10.6730871201 --13.9838371277,2.35045862198,-10.7045211792 --13.9368495941,2.34845423698,-10.737953186 --13.8838577271,2.34445309639,-10.7663869858 --13.8218631744,2.33945560455,-10.7888326645 --13.7848796844,2.33844685555,-10.8292579651 --13.7458782196,2.33445191383,-10.834487915 --13.7048940659,2.33244490623,-10.8719158173 --13.6559047699,2.32944154739,-10.9033517838 --13.5979099274,2.3254430294,-10.9267892838 --13.5549259186,2.32343673706,-10.9632253647 --13.520945549,2.32342648506,-11.0056495667 --13.4809417725,2.31943249702,-11.0088787079 --13.4199457169,2.31443572044,-11.0293188095 --13.3889665604,2.31442403793,-11.0737409592 --13.3369760513,2.31142258644,-11.1021814346 --13.2999944687,2.31041383743,-11.1416063309 --13.2500047684,2.30741143227,-11.1710453033 --13.210021019,2.30640411377,-11.2084760666 --13.1740198135,2.30340862274,-11.2137012482 --13.1370372772,2.30240011215,-11.2531290054 --13.0840454102,2.29939937592,-11.2795696259 --13.0510663986,2.29938864708,-11.3219928741 --13.0090818405,2.29738235474,-11.3574256897 --12.9620933533,2.29537892342,-11.3878583908 --12.912103653,2.29237699509,-11.4162969589 --12.8801040649,2.28938007355,-11.4235162735 --12.8211078644,2.28538298607,-11.4439620972 --12.8011369705,2.28836536407,-11.4973783493 --12.7491455078,2.28436422348,-11.5238189697 --12.7081623077,2.28335785866,-11.5592517853 --12.6531686783,2.27935862541,-11.582695961 --12.6211900711,2.28034758568,-11.6251163483 --12.585187912,2.27735257149,-11.6293458939 --12.5442028046,2.27534651756,-11.6637744904 --12.5062208176,2.27533793449,-11.702208519 --12.4632358551,2.27433252335,-11.7356443405 --12.4052391052,2.26933550835,-11.7550888062 --12.3812665939,2.27232003212,-11.8045034409 --12.3382816315,2.27031469345,-11.8369340897 --12.3212919235,2.27030920982,-11.8581523895 --12.2863130569,2.27129936218,-11.8985815048 --12.2393245697,2.2692964077,-11.9280195236 --12.2013425827,2.26828789711,-11.9654502869 --12.1733694077,2.27027368546,-12.0128774643 --12.1333866119,2.27026677132,-12.0483083725 --12.0823945999,2.26726603508,-12.0737514496 --12.0714092255,2.26825761795,-12.0989551544 --12.0314273834,2.26824998856,-12.135392189 --11.9954471588,2.26824045181,-12.1748228073 --11.9554643631,2.26723337173,-12.2102556229 --11.9054727554,2.26523303986,-12.2346897125 --11.8744974136,2.26621985435,-12.280122757 --11.8235063553,2.26321983337,-12.3035583496 --11.8125228882,2.26521062851,-12.3307723999 --11.769536972,2.26420545578,-12.3622026443 --11.741563797,2.26619100571,-12.4096269608 --11.6935749054,2.26418852806,-12.4370679855 --11.6636009216,2.26617527008,-12.4824943542 --11.6266212463,2.26616621017,-12.5209264755 --11.5836372375,2.26516032219,-12.5543689728 --11.5666475296,2.2651553154,-12.5735750198 --11.5366754532,2.26714086533,-12.6210107803 --11.4986944199,2.26713275909,-12.6574382782 --11.4597129822,2.26712465286,-12.6938714981 --11.4337434769,2.27010774612,-12.7453012466 --11.3867559433,2.26810503006,-12.7727384567 --11.3517780304,2.26909470558,-12.813167572 --11.3357915878,2.2700881958,-12.8353824615 --11.3008136749,2.27107739449,-12.8758115768 --11.2668371201,2.27206635475,-12.9172391891 --11.2288589478,2.27305650711,-12.9566812515 --11.1948823929,2.27404522896,-12.9981079102 --11.1559019089,2.27403688431,-13.0345401764 --11.1449203491,2.27602696419,-13.0627536774 --11.0959310532,2.2740252018,-13.0881958008 --11.0679607391,2.27700972557,-13.1366186142 --11.0399913788,2.27999329567,-13.187048912 --10.9890012741,2.27699279785,-13.2104949951 --10.9640350342,2.28097462654,-13.2629165649 --10.9200496674,2.27996993065,-13.2933511734 --10.8900794983,2.28295469284,-13.3417844772 --10.8770961761,2.28394556046,-13.3679971695 --10.8541326523,2.2879254818,-13.4244213104 --10.8201589584,2.28991270065,-13.4678535461 --10.7831811905,2.29090285301,-13.506280899 --10.7472066879,2.29189133644,-13.5487213135 --10.7032232285,2.29188585281,-13.580160141 --10.6862363815,2.29287981987,-13.6013746262 --10.6632738113,2.29685878754,-13.6587972641 --10.6293020248,2.29884552956,-13.7032327652 --10.596329689,2.30083227158,-13.7476596832 --10.5663604736,2.30381584167,-13.7970895767 --10.5253810883,2.30380797386,-13.8325271606 --10.4683847427,2.30081295967,-13.8469743729 --10.4283742905,2.29582357407,-13.8402099609 --10.3883962631,2.29681491852,-13.8766460419 --10.245306015,2.27288746834,-13.7771501541 --10.0992097855,2.24796295166,-13.6726579666 --9.99215602875,2.23200917244,-13.6171350479 --9.884100914,2.21605610847,-13.5606193542 --9.70596504211,2.1821603775,-13.4071435928 --9.55482673645,2.15026283264,-13.2464532852 --9.40872383118,2.12434339523,-13.1329593658 --9.25360965729,2.09643149376,-13.0064783096 --9.15055084229,2.08047962189,-12.9469490051 --9.0975522995,2.07648515701,-12.9594039917 --8.99949741364,2.06252980232,-12.9058761597 --8.91646194458,2.05156183243,-12.8733434677 --8.89046192169,2.04956459999,-12.879570961 --8.75436115265,2.02564239502,-12.770070076 --8.67432594299,2.01467299461,-12.7395353317 --8.64435005188,2.0176615715,-12.7799663544 --8.60836601257,2.01765584946,-12.8103942871 --8.5663766861,2.01765418053,-12.8348388672 --8.47632789612,2.00369477272,-12.7873096466 --8.41828727722,1.99472653866,-12.744556427 --8.33023834229,1.98176658154,-12.6980247498 --8.24218940735,1.96880686283,-12.6514978409 --8.14512729645,1.95285618305,-12.5889701843 --8.06608867645,1.94188916683,-12.554438591 --8.0100774765,1.93790245056,-12.5528869629 --7.97806692123,1.93391263485,-12.5461139679 --7.85897302628,1.91298377514,-12.4466047287 --7.78894233704,1.90401077271,-12.4220628738 --7.73292922974,1.89902508259,-12.4185123444 --7.66490125656,1.89105033875,-12.3969755173 --7.62891483307,1.89204633236,-12.4244117737 --7.64299583435,1.90599548817,-12.5308103561 --7.60400676727,1.90599346161,-12.5552549362 --7.60604095459,1.91197228432,-12.6014585495 --7.53200292587,1.90200436115,-12.5679216385 --7.4409403801,1.88705301285,-12.5063972473 --7.40495443344,1.88804900646,-12.5338335037 --7.33491945267,1.87907862663,-12.5042915344 --7.22883224487,1.85914409161,-12.4137735367 --7.2258605957,1.86412715912,-12.4529857635 --7.137799263,1.85017502308,-12.3924617767 --7.0687623024,1.8402056694,-12.360915184 --7.05380535126,1.8471814394,-12.422337532 --6.9046497345,1.81529355049,-12.2528505325 --6.85864686966,1.81230080128,-12.261300087 --6.77758932114,1.79934489727,-12.2067680359 --6.74256849289,1.79436182976,-12.1879940033 --6.73562479019,1.80432903767,-12.2644195557 --6.76273202896,1.82326114178,-12.3998088837 --6.65363025665,1.80133533478,-12.2942991257 --6.56555938721,1.78638887405,-12.2237710953 --6.53257513046,1.7883836031,-12.2532100677 --6.49358034134,1.7873852253,-12.2706480026 --6.52566623688,1.80332994461,-12.3748350143 --6.53374910355,1.81727933884,-12.4812450409 --6.45769691467,1.8053201437,-12.4327173233 --6.40768480301,1.80133342743,-12.4301633835 --6.37971019745,1.80532228947,-12.4695968628 --6.38378858566,1.8182746172,-12.5710105896 --6.3297700882,1.81329274178,-12.5604572296 --6.32079267502,1.8162804842,-12.591676712 --6.29782629013,1.82126331329,-12.6411027908 --6.1195936203,1.77642452717,-12.3866357803 --6.08861351013,1.77841687202,-12.4200725555 --6.03960037231,1.77543079853,-12.4165172577 --5.98257493973,1.76845312119,-12.3989782333 --5.96958971024,1.7704461813,-12.4211959839 --5.98669528961,1.78938138485,-12.5515975952 --5.92065238953,1.77941524982,-12.5140581131 --5.87464618683,1.77742528915,-12.5175075531 --5.83164310455,1.77543258667,-12.5249462128 --5.7826294899,1.77144694328,-12.5203914642 --5.73261547089,1.76846170425,-12.5158491135 --5.46314382553,1.68177580833,-11.9892234802 --5.62653160095,1.75152528286,-12.4375391006 --5.62961864471,1.76547384262,-12.5459594727 --5.55655813217,1.75351929665,-12.4884262085 --5.5175614357,1.75252258778,-12.5028619766 --5.45752334595,1.74455273151,-12.4713144302 --5.45860910416,1.75950241089,-12.5777368546 --5.43861055374,1.75850403309,-12.5849590302 --5.39159917831,1.75551724434,-12.582406044 --5.33957719803,1.75053703785,-12.5688581467 --5.31661558151,1.75651776791,-12.6222934723 --5.29265117645,1.76150047779,-12.6717195511 --5.25666332245,1.76249814034,-12.6961650848 --5.21265745163,1.76050722599,-12.7006120682 --5.15758514404,1.74755764008,-12.6248598099 --5.15667152405,1.76150715351,-12.7312765121 --5.12569332123,1.76449871063,-12.765709877 --5.09271430969,1.76749134064,-12.7991580963 --5.0647444725,1.77147769928,-12.8425941467 --5.06583976746,1.78742206097,-12.9580078125 --5.01682567596,1.78343725204,-12.9524650574 --5.00484514236,1.78642773628,-12.978676796 --4.95983886719,1.7844376564,-12.9821281433 --4.89879417419,1.77547252178,-12.9425840378 --4.82471847534,1.76252675056,-12.8700561523 --4.76467370987,1.75356137753,-12.8305101395 --4.72166919708,1.75157010555,-12.8359565735 --4.69971704483,1.75954568386,-12.8983955383 --4.68974304199,1.76353216171,-12.9316101074 --4.68082237244,1.77548766136,-13.0280303955 --4.62278175354,1.76851952076,-12.9934883118 --4.58178424835,1.76752436161,-13.00593853 --4.55983304977,1.77549910545,-13.0693712234 --4.52083921432,1.77550137043,-13.0858125687 --4.51086759567,1.77948665619,-13.1210279465 --4.46886873245,1.77949202061,-13.1324825287 --4.40982151031,1.77052795887,-13.0909357071 --4.34876918793,1.7615673542,-13.0433931351 --4.32581996918,1.76854169369,-13.1078310013 --4.27078151703,1.76257193089,-13.0762844086 --4.24081420898,1.7665579319,-13.1207256317 --4.21279287338,1.76257419586,-13.1029529572 --4.17881584167,1.76656615734,-13.1374025345 --4.12477970123,1.75959515572,-13.1078577042 --4.09380912781,1.76358282566,-13.1492986679 --4.09693956375,1.78450798988,-13.2987184525 --4.04490995407,1.7795330286,-13.2761735916 --4.01594638824,1.78451657295,-13.3246078491 --4.00497865677,1.78949987888,-13.3638324738 --3.99607849121,1.80544424057,-13.4802570343 --3.95909667015,1.80743968487,-13.5087070465 --3.91107749939,1.80345821381,-13.4971542358 --3.87911057472,1.80844438076,-13.54159832 --3.82908582687,1.80446636677,-13.5240507126 --3.79310703278,1.80746018887,-13.5554971695 --3.76909995079,1.80546796322,-13.5527305603 --3.7281024456,1.80547308922,-13.5641727448 --3.70115399361,1.81344819069,-13.627612114 --3.64912319183,1.80747389793,-13.6040716171 --3.59909582138,1.80349767208,-13.5835227966 --3.57515954971,1.8124653101,-13.6599597931 --3.54018568993,1.81645619869,-13.6964044571 --3.52521109581,1.82044434547,-13.7276334763 --3.4862241745,1.82244324684,-13.7500801086 --3.45125055313,1.82543408871,-13.7865200043 --3.41929125786,1.83141636848,-13.8379650116 --3.37026834488,1.82743728161,-13.8224191666 --3.31020283699,1.81748425961,-13.7618808746 --3.28426742554,1.82745218277,-13.8383216858 --3.27029776573,1.83143734932,-13.874546051 --3.22830152512,1.8314422369,-13.8869962692 --3.18931722641,1.8344399929,-13.9114437103 --3.15234088898,1.83743274212,-13.9448900223 --3.09628748894,1.82847237587,-13.8973503113 --3.06634235382,1.8374465704,-13.9627943039 --3.04936242104,1.84043812752,-13.9880189896 --3.00937509537,1.84143781662,-14.0094671249 --2.96537423134,1.84144580364,-14.0169258118 --2.92639112473,1.84344315529,-14.0423707962 --2.88037800789,1.84145843983,-14.0368242264 --2.83737921715,1.84146511555,-14.0462770462 --2.79538702965,1.84246790409,-14.0627326965 --2.74836921692,1.83948624134,-14.0521879196 --2.72737026215,1.83948922157,-14.0574102402 --2.6843688488,1.83949756622,-14.0638589859 --2.64036631584,1.8385065794,-14.0693149567 --2.59535527229,1.83752071857,-14.0657663345 --2.55537295341,1.8395178318,-14.0922203064 --2.51036190987,1.83853197098,-14.0886716843 --2.49137568474,1.84052765369,-14.1068973541 --2.44938206673,1.8405315876,-14.1213493347 --2.40135908127,1.83755290508,-14.1058111191 --2.36036658287,1.83855605125,-14.1212558746 --2.3193795681,1.84055602551,-14.1427087784 --2.27336454391,1.83857274055,-14.1351671219 --2.23137187958,1.83957624435,-14.1506204605 --2.21037149429,1.83958029747,-14.153840065 --2.16737508774,1.84058606625,-14.1652975082 --2.12236666679,1.83859884739,-14.1647567749 --2.08238506317,1.84159600735,-14.1912059784 --2.03737092018,1.83961200714,-14.1846570969 --1.99437189102,1.84061944485,-14.193110466 --1.95037066936,1.84062826633,-14.1995716095 --1.92735731602,1.83863985538,-14.1897935867 --1.88537061214,1.84064018726,-14.2112541199 --1.84337556362,1.84164535999,-14.2237024307 --1.7993683815,1.8406573534,-14.2241544724 --1.75536704063,1.8406662941,-14.2306156158 --1.71337294579,1.84167087078,-14.2440643311 --1.66836285591,1.84068489075,-14.2415246964 --1.64737021923,1.84168481827,-14.2527542114 --1.60537791252,1.84268832207,-14.268204689 --1.5603621006,1.84070563316,-14.2596588135 --1.51736414433,1.84171283245,-14.269112587 --1.47437286377,1.84371602535,-14.285574913 --1.42935693264,1.84173345566,-14.2770299911 --1.3873667717,1.84273588657,-14.2944812775 --1.36637532711,1.84473538399,-14.3067111969 --1.32136213779,1.84275114536,-14.3011693954 --1.2783614397,1.84375989437,-14.3076210022 --1.23637640476,1.8457596302,-14.3300762177 --1.19237554073,1.84676873684,-14.3365364075 --1.14837157726,1.84677946568,-14.3399944305 --1.10638284683,1.84878146648,-14.3584442139 --1.0833684206,1.84679400921,-14.3476734161 --1.03936350346,1.84680533409,-14.3501300812 --0.997389614582,1.8507989645,-14.3835906982 --0.952369809151,1.8488188982,-14.3710460663 --0.909369945526,1.84882724285,-14.37849617 --0.865370154381,1.84983587265,-14.3859567642 --0.821361303329,1.84884941578,-14.3844118118 --0.798347890377,1.8478615284,-14.3746452332 --0.755365252495,1.85086047649,-14.399105072 --0.711360454559,1.85087192059,-14.4015636444 --0.667350590229,1.84988629818,-14.3990182877 --0.624355852604,1.85089182854,-14.4114704132 --0.580352365971,1.85190284252,-14.4149284363 --0.546045124531,1.80807888508,-14.1161432266 --0.514355242252,1.85291445255,-14.4286193848 --0.469320058823,1.84894311428,-14.4010753632 --0.424272537231,1.84297835827,-14.3615283966 --0.382330983877,1.85195481777,-14.425989151 --0.338349580765,1.85495352745,-14.4514532089 --0.292232513428,1.83902740479,-14.3439006805 --0.271278172731,1.84600651264,-14.3921327591 --0.227280795574,1.8480142355,-14.401594162 --0.184382498264,1.86296713352,-14.50806427 --0.140388265252,1.86497330666,-14.5205230713 --0.0963817089796,1.86498606205,-14.5209779739 --0.0524016581476,1.86798417568,-14.5474367142 --0.00743815861642,1.87397348881,-14.5899057388 -0.001492804382,1.87804663181,-13.8129930496 -0.0465446859598,1.88506221771,-13.8573617935 -0.0916013866663,1.89208078384,-13.9067258835 -0.16177727282,1.91615760326,-14.0692710876 -0.206776276231,1.91514456272,-14.0626392365 -0.25278159976,1.91513454914,-14.0620145798 -0.275786697865,1.91513097286,-14.064201355 -0.320798009634,1.91612458229,-14.069565773 -0.366811424494,1.91711914539,-14.0769386292 -0.412824809551,1.9181137085,-14.0843105316 -0.457830935717,1.91810452938,-14.0846757889 -0.503851592541,1.92110311985,-14.0990438461 -0.549852728844,1.92009115219,-14.094420433 -0.572851002216,1.92008364201,-14.0896081924 -0.618875265121,1.92208445072,-14.1079740524 -0.664881706238,1.92307507992,-14.1083469391 -0.710899114609,1.92507207394,-14.1197147369 -0.756909430027,1.92606508732,-14.1240854263 -0.801909506321,1.92505276203,-14.1184539795 -0.848931074142,1.92805159092,-14.1338253021 -0.872952401638,1.93105685711,-14.1520080566 -0.91793936491,1.92803740501,-14.1333847046 -0.964958906174,1.93103528023,-14.1467552185 -1.00996398926,1.93102586269,-14.1461200714 -1.05697333813,1.93201828003,-14.1494970322 -1.10298359394,1.93301129341,-14.1538658142 -1.12598562241,1.93300628662,-14.15305233 -1.17199778557,1.9340004921,-14.1594181061 -1.21800231934,1.93499052525,-14.1577911377 -1.26602840424,1.93799209595,-14.1781606674 -1.31102466583,1.9369777441,-14.1685314178 -1.35803806782,1.93897247314,-14.1759033203 -1.40504431725,1.93896329403,-14.176281929 -1.42905855179,1.94196462631,-14.1874628067 -1.47506654263,1.94195687771,-14.1898317337 -1.52106404305,1.94194304943,-14.1812086105 -1.56808125973,1.94393992424,-14.1925754547 -1.6140806675,1.94392728806,-14.1859512329 -1.66109001637,1.94491994381,-14.189324379 -1.70709812641,1.94591212273,-14.1916904449 -1.73211038113,1.9479123354,-14.2008800507 -1.7781175375,1.94890403748,-14.2022457123 -1.8221039772,1.94688498974,-14.1826219559 -1.86911046505,1.94787609577,-14.1829977036 -1.91712462902,1.94987130165,-14.1913709641 -1.96111512184,1.94785439968,-14.1757421494 -2.00711727142,1.94784367085,-14.1721153259 -2.02910995483,1.94683361053,-14.1613054276 -2.07511520386,1.94782447815,-14.1606740952 -2.12212157249,1.94881570339,-14.1610488892 -2.16711354256,1.9477994442,-14.1464281082 -2.21311879158,1.94879031181,-14.1457967758 -2.25811243057,1.9477751255,-14.1331739426 -2.30210208893,1.94575786591,-14.1165494919 -2.32510352135,1.94675266743,-14.1147356033 -2.37210893631,1.94774353504,-14.114112854 -2.41811156273,1.94773304462,-14.1104850769 -2.46009373665,1.94571208954,-14.085858345 -2.50910973549,1.94770860672,-14.0962333679 -2.55108714104,1.94468522072,-14.066617012 -2.57207798958,1.94367456436,-14.0538053513 -2.62109875679,1.94667363167,-14.0691699982 -2.66006064415,1.94164252281,-14.0235586166 -2.69701600075,1.93460834026,-13.9709472656 -2.74302244186,1.93560004234,-13.9713144302 -2.78701448441,1.93458449841,-13.9566926956 -2.84507632256,1.94460391998,-14.0140504837 -2.87912607193,1.95262277126,-14.0622320175 -2.92311811447,1.95160710812,-14.0476074219 -2.96108412743,1.94657874107,-14.0059871674 -3.00909090042,1.94757032394,-14.0063676834 -3.05208110809,1.94655394554,-13.9897403717 -3.08502459526,1.93851423264,-13.9241323471 -3.12901759148,1.93749940395,-13.9105100632 -3.13594841957,1.92745912075,-13.8347206116 -3.17191004753,1.92142891884,-13.788105011 -3.19080018997,1.90436327457,-13.6665143967 -3.23479747772,1.9043507576,-13.6568908691 -3.27176570892,1.90032374859,-13.6162776947 -3.30973911285,1.8962996006,-13.581662178 -3.34771203995,1.89227497578,-13.5460500717 -3.36268496513,1.88825631142,-13.5142440796 -3.40066170692,1.88523387909,-13.4826259613 -3.43963956833,1.8822119236,-13.4520149231 -3.47861909866,1.87919092178,-13.4233999252 -3.51659607887,1.87616872787,-13.3917856216 -3.55758452415,1.87515211105,-13.3721666336 -3.58653211594,1.86711597443,-13.3095579147 -3.60752654076,1.86610758305,-13.2997541428 -3.64450550079,1.86308681965,-13.2701320648 -3.68047809601,1.86006271839,-13.2335186005 -3.71644997597,1.85603809357,-13.1959123611 -3.75543403625,1.85401964188,-13.1712961197 -3.78940272331,1.84899401665,-13.1306829453 -3.83039236069,1.8479783535,-13.1120710373 -3.83834767342,1.84095144272,-13.0602769852 -3.88134765625,1.84194099903,-13.052652359 -3.91933107376,1.83992254734,-13.0270357132 -3.95430421829,1.8358989954,-12.9904279709 -3.97924733162,1.82686150074,-12.92182827 -4.02124452591,1.82684981823,-12.9112071991 -4.03622579575,1.82483530045,-12.8864021301 -4.07320547104,1.82181537151,-12.856795311 -4.11119270325,1.82079911232,-12.8351745605 -4.14516544342,1.8167757988,-12.7975683212 -4.18014335632,1.81375515461,-12.7659549713 -4.21913194656,1.81273937225,-12.7453422546 -4.25110197067,1.80771505833,-12.7047328949 -4.26407909393,1.80469918251,-12.6759309769 -4.30607652664,1.8046875,-12.664317131 -4.33504104614,1.7996609211,-12.6177062988 -4.37202453613,1.79764282703,-12.5910997391 -4.40800905228,1.79562592506,-12.5664796829 -4.44699907303,1.79461097717,-12.546869278 -4.478972435,1.79158842564,-12.5092592239 -4.50297880173,1.79258620739,-12.5114526749 -4.52693080902,1.7855540514,-12.4508552551 -4.56291627884,1.78353726864,-12.4262399673 -4.59789896011,1.78151929379,-12.3986272812 -4.63187885284,1.77950024605,-12.368016243 -4.67187261581,1.77848732471,-12.3524065018 -4.70184373856,1.77446424961,-12.3117990494 -4.71783256531,1.7734541893,-12.2949924469 -4.75181245804,1.77043533325,-12.2643861771 -4.7867975235,1.76841855049,-12.2387714386 -4.83280563354,1.77141225338,-12.2381591797 -4.86378192902,1.76839196682,-12.2035446167 -4.92573308945,1.7613503933,-12.1313314438 -4.9417219162,1.75934052467,-12.114528656 -4.97770833969,1.7583245039,-12.0899219513 -5.00066804886,1.75229692459,-12.036318779 -5.04768037796,1.75529277325,-12.0406970978 -5.07264328003,1.75026643276,-11.9901008606 -5.10462331772,1.74724805355,-11.9584941864 -5.1236205101,1.74724209309,-11.9506835938 -5.16061019897,1.74622762203,-11.9290790558 -5.19058656693,1.7432076931,-11.8934726715 -5.22857999802,1.74319541454,-11.8768577576 -5.26156330109,1.74117851257,-11.8482494354 -5.29053783417,1.73715806007,-11.8106470108 -5.32452344894,1.73614239693,-11.7850370407 -5.33650588989,1.73312973976,-11.7602405548 -5.37149381638,1.73211491108,-11.7366323471 -5.40347671509,1.73009836674,-11.7080202103 -5.45148992538,1.73409473896,-11.7124032974 -5.485476017,1.73207914829,-11.6867961884 -5.51244878769,1.72805798054,-11.6461963654 -5.55044317245,1.72804617882,-11.6295843124 -5.56443166733,1.72703671455,-11.611779213 -5.60342884064,1.72802627087,-11.5981636047 -5.6404209137,1.72701370716,-11.5795536041 -5.67040014267,1.7249956131,-11.5459508896 -5.70639038086,1.72398209572,-11.524348259 -5.7403793335,1.72296833992,-11.5017318726 -5.78638887405,1.72596335411,-11.5021114349 -5.80438375473,1.72595655918,-11.491309166 -5.83736944199,1.72394144535,-11.4647035599 -5.87135839462,1.72392737865,-11.4410924911 -5.90033769608,1.72090959549,-11.4074878693 -5.93833255768,1.72089827061,-11.3908786774 -5.98434114456,1.72389304638,-11.3902597427 -6.02433872223,1.7248827219,-11.3766527176 -6.05736017227,1.72988736629,-11.3958320618 -6.0843372345,1.72686874866,-11.3592252731 -6.11932659149,1.7258554697,-11.3366193771 -6.15031003952,1.72383952141,-11.307015419 -6.19030761719,1.72482943535,-11.2934074402 -6.22529888153,1.72481703758,-11.2727918625 -6.2672996521,1.72580814362,-11.2621850967 -6.27327680588,1.72279405594,-11.230389595 -6.3242931366,1.7267922163,-11.2387619019 -6.35627794266,1.72577691078,-11.2101621628 -6.43527317047,1.72775733471,-11.182934761 -6.48128080368,1.73075151443,-11.180316925 -6.4912648201,1.7277405262,-11.1565179825 -6.52825832367,1.72872912884,-11.1379089355 -6.56324768066,1.72771573067,-11.1143093109 -6.59323072433,1.72570014,-11.0837068558 -6.63923931122,1.72969472408,-11.0820808411 -6.67723464966,1.72968411446,-11.0654706955 -6.71522951126,1.73067319393,-11.0478630066 -6.73122215271,1.72966587543,-11.0340623856 -6.77121925354,1.73065602779,-11.0194559097 -6.81722593307,1.7336499691,-11.0158367157 -6.84520816803,1.7316339016,-10.9832305908 -6.89121437073,1.73462760448,-10.9786157608 -6.93021011353,1.7356171608,-10.9620103836 -6.9662027359,1.73560571671,-10.9423971176 -6.98720264435,1.73660135269,-10.9365921021 -7.01418304443,1.73458480835,-10.9019899368 -7.06118965149,1.73757886887,-10.8983745575 -7.09918451309,1.73856794834,-10.8797712326 -7.13217258453,1.73755455017,-10.8541669846 -7.18218374252,1.74155032635,-10.8555450439 -7.23419761658,1.74654710293,-10.859919548 -7.24218034744,1.7435362339,-10.8341245651 -7.27717113495,1.74352407455,-10.8115186691 -7.29814481735,1.73950493336,-10.7679252625 -7.35616445541,1.74550402164,-10.779302597 -7.38214445114,1.74348771572,-10.7437009811 -7.42314338684,1.74547863007,-10.7300891876 -7.45315408707,1.74847865105,-10.7372751236 -7.48714399338,1.74846601486,-10.7126731873 -7.52814245224,1.74945688248,-10.6990594864 -7.56814002991,1.75144731998,-10.6834487915 -7.6091375351,1.75243782997,-10.668841362 -7.64212656021,1.75242507458,-10.6432361603 -7.70314836502,1.75942468643,-10.6566104889 -7.70712852478,1.75641298294,-10.6268148422 -7.75213098526,1.75840520859,-10.6172037125 -7.79613208771,1.76039719582,-10.6065912247 -7.83713006973,1.76238799095,-10.5919780731 -7.87712717056,1.76437830925,-10.5753698349 -7.90210676193,1.76136231422,-10.5387706757 -7.95712041855,1.76735854149,-10.5421514511 -7.99213552475,1.77136003971,-10.5543327332 -8.01010608673,1.7673407793,-10.5067481995 -8.05110454559,1.76933181286,-10.4921331406 -8.10111236572,1.7733259201,-10.4885139465 -8.15011787415,1.77631962299,-10.4829006195 -8.18611049652,1.77730810642,-10.4602937698 -8.21809673309,1.77629482746,-10.4316978455 -8.24810600281,1.77929413319,-10.436879158 -8.29511070251,1.7822868824,-10.4282646179 -8.33710861206,1.78427791595,-10.4136505127 -8.38811588287,1.78827178478,-10.40903759 -8.44012451172,1.79326629639,-10.406416893 -8.47711658478,1.79425537586,-10.3848085403 -8.50912666321,1.79725444317,-10.389998436 -8.54111480713,1.79724180698,-10.3623914719 -8.58511352539,1.79923272133,-10.3477869034 -8.63111591339,1.80222499371,-10.3371686935 -8.67811775208,1.80521714687,-10.3265571594 -8.71210670471,1.80520486832,-10.2999563217 -8.74909973145,1.80619370937,-10.2773513794 -8.75908756256,1.80518555641,-10.2565507889 -8.7230091095,1.78914988041,-10.1460113525 -8.43869304657,1.71703326702,-9.74367141724 -8.46267604828,1.71501922607,-9.70808029175 -8.498670578,1.71600914001,-9.68648052216 -8.49963283539,1.70998859406,-9.62589645386 -8.49859237671,1.70196688175,-9.56132888794 -8.49957466125,1.69895708561,-9.53253269196 -8.51254844666,1.6949403286,-9.48495197296 -8.53352832794,1.69292593002,-9.44636631012 -8.57052612305,1.69391715527,-9.42775630951 -8.57549285889,1.6888988018,-9.37317276001 -8.59147071838,1.68588328362,-9.32958984375 -8.63046836853,1.68687486649,-9.31198883057 -8.62344455719,1.68286335468,-9.27519893646 -8.64842987061,1.68185114861,-9.24260520935 -8.67041397095,1.67983806133,-9.20701313019 -8.69740200043,1.67882680893,-9.17741298676 -8.70237159729,1.6738089323,-9.12283992767 -8.73436355591,1.67379903793,-9.09823989868 -8.75334453583,1.67178559303,-9.05965137482 -8.76633834839,1.6717799902,-9.04484939575 -8.7643032074,1.66476106644,-8.98427772522 -8.79129219055,1.66375005245,-8.95468235016 -8.79926490784,1.65973436832,-8.90609645844 -8.82825565338,1.65972399712,-8.87850093842 -8.83623027802,1.65570855141,-8.82991695404 -8.85421180725,1.65269553661,-8.79133033752 -8.87721347809,1.65469241142,-8.78553104401 -8.87317943573,1.64867460728,-8.72595214844 -8.89716720581,1.64766347408,-8.69435501099 -8.9121465683,1.64464998245,-8.65277385712 -8.92612743378,1.64163672924,-8.6111869812 -8.94010734558,1.63862359524,-8.56960201263 -8.94909858704,1.63761746883,-8.55080795288 -8.96007633209,1.6346039772,-8.50721931458 -8.97105407715,1.63059020042,-8.46264076233 -9.00304889679,1.63158142567,-8.4390411377 -9.01602935791,1.62856853008,-8.39745426178 -9.01900196075,1.62355351448,-8.34587955475 -9.0449924469,1.62354362011,-8.31628799438 -9.04397773743,1.62053573132,-8.2885017395 -9.0539560318,1.61752283573,-8.24491500854 -9.07294178009,1.61551165581,-8.20932674408 -9.08492279053,1.61249935627,-8.16774082184 -9.10590934753,1.61148881912,-8.13415145874 -9.12689685822,1.61047840118,-8.10056304932 -9.14288139343,1.60846698284,-8.06297397614 -9.14987373352,1.60746157169,-8.04417324066 -9.17486286163,1.60745179653,-8.01358795166 -9.18184185028,1.60343897343,-7.96800804138 -9.19282245636,1.60042715073,-7.92642307281 -9.20980834961,1.59841644764,-7.88983631134 -9.22679424286,1.59640610218,-7.85424280167 -9.2347869873,1.59640061855,-7.83545207977 -9.24576854706,1.59338903427,-7.79387044907 -9.26675701141,1.5923794508,-7.76128005981 -9.2727355957,1.58836722374,-7.71570301056 -9.30173015594,1.58935940266,-7.6910982132 -9.30570793152,1.58534705639,-7.64451885223 -9.3236951828,1.58333706856,-7.60893726349 -9.33469009399,1.5833325386,-7.5931429863 -9.34067058563,1.58032083511,-7.5485625267 -9.34564876556,1.5763092041,-7.50298643112 -8.30597686768,1.37413167953,-6.59719324112 -8.2949514389,1.36812019348,-6.54462623596 -8.3179473877,1.36911416054,-6.52003335953 -8.34394645691,1.36910879612,-6.49843358994 -8.3579454422,1.37010610104,-6.48764038086 -8.38294219971,1.3711001873,-6.46405172348 -8.40493869781,1.37109434605,-6.43945169449 -8.4339389801,1.37208938599,-6.41985177994 -8.46293830872,1.37408423424,-6.39926052094 -8.48893642426,1.37507879734,-6.37666749954 -8.51093292236,1.37507307529,-6.35206651688 -8.51992893219,1.37506973743,-6.33727645874 -8.54592704773,1.37606430054,-6.31468248367 -8.56191921234,1.37505757809,-6.28409957886 -8.60392856598,1.37905442715,-6.27448511124 -8.63592910767,1.38104999065,-6.25688123703 -8.67193317413,1.38404583931,-6.24128198624 -8.76296710968,1.39604842663,-6.26664161682 -9.50937080383,1.53013527393,-6.79830503464 -9.62541484833,1.54713928699,-6.83863735199 -9.67041969299,1.55113434792,-6.82503175735 -9.6754026413,1.54812455177,-6.78146219254 -9.69039058685,1.54711639881,-6.74687051773 -9.69637584686,1.54410707951,-6.70529079437 -9.70436954498,1.5441031456,-6.68849420547 -9.7213602066,1.54309535027,-6.65490674973 -9.73634910583,1.54108715057,-6.61932706833 -9.75834178925,1.54107999802,-6.58973264694 -9.76332569122,1.53907108307,-6.54815101624 -9.7773141861,1.53706288338,-6.51157712936 -9.79330539703,1.53605544567,-6.47798633575 -9.79229545593,1.53405070305,-6.45519685745 -9.79127693176,1.53004157543,-6.40962362289 -9.79726314545,1.52803325653,-6.36904525757 -9.8062505722,1.52602505684,-6.33046579361 -9.80223178864,1.52101612091,-6.28389072418 -9.69616413116,1.49899816513,-6.1693944931 -9.61210727692,1.48098266125,-6.07087898254 -9.53806400299,1.46597218513,-6.00015258789 -9.47101688385,1.450958848,-5.91462039948 -9.34094142914,1.4249407053,-5.78913354874 -9.299908638,1.41493022442,-5.72158765793 -9.35692024231,1.42092776299,-5.71697282791 -9.35790729523,1.41792070866,-5.67639923096 -9.89713859558,1.50795400143,-5.97444009781 -9.9111366272,1.50895106792,-5.96164321899 -9.91712474823,1.50594365597,-5.92206811905 -9.91410827637,1.50193595886,-5.87749433517 -9.93410205841,1.50192975998,-5.84690761566 -9.94309139252,1.50092303753,-5.81032180786 -9.93807506561,1.49691534042,-5.76475191116 -9.96107769012,1.49891328812,-5.75794363022 -9.97506904602,1.49790680408,-5.72336578369 -9.98906040192,1.49690067768,-5.68977880478 -9.99604892731,1.4948939085,-5.65120601654 -9.99703598022,1.4918872118,-5.61062288284 -10.0170316696,1.49288129807,-5.58003807068 -9.95199012756,1.47787106037,-5.50051259995 -10.0170106888,1.48787128925,-5.51767539978 -9.93796539307,1.4718606472,-5.43115472794 -9.90193748474,1.46285247803,-5.3696064949 -9.79688358307,1.4418412447,-5.27010154724 -9.75385475159,1.43183326721,-5.2055606842 -9.83887577057,1.44283127785,-5.21292638779 -9.75383090973,1.42582190037,-5.12640762329 -9.66479110718,1.40981531143,-5.05768251419 -9.67678546906,1.40881037712,-5.0250992775 -9.66477012634,1.40380454063,-4.9795331955 -9.61674118042,1.39379763603,-4.91499042511 -9.59172153473,1.38679170609,-4.86343002319 -9.57570552826,1.38178634644,-4.81686353683 -9.4186372757,1.35277628899,-4.6963968277 -9.31359481812,1.33477056026,-4.62268257141 -9.14652442932,1.30376112461,-4.49922180176 -9.27756404877,1.32376122475,-4.53055667877 -9.10749530792,1.29275250435,-4.40808725357 -9.10948848724,1.29074883461,-4.37350893021 -9.11748409271,1.28974533081,-4.34093999863 -8.95442295074,1.26173961163,-4.24225378036 -8.98142528534,1.26373696327,-4.220662117 -8.93140220642,1.25373268127,-4.16112089157 -8.8993844986,1.24572908878,-4.11155986786 -8.72531986237,1.21572291851,-3.99309682846 -8.70330619812,1.20971989632,-3.94854211807 -8.77732658386,1.21971857548,-3.95091199875 -8.59126186371,1.18871462345,-3.84525370598 -8.61826610565,1.19071269035,-3.82565450668 -8.5452375412,1.17670965195,-3.75912237167 -8.54123210907,1.17470753193,-3.7245528698 -8.38117694855,1.14670407772,-3.61907672882 -8.38817596436,1.14570248127,-3.59049892426 -8.34415817261,1.13670063019,-3.53895354271 -8.35015869141,1.13669991493,-3.52615952492 -8.2611284256,1.12069809437,-3.4556350708 -8.22711467743,1.11369681358,-3.41007637978 -8.17509651184,1.10369551182,-3.35653543472 -8.13608264923,1.09469437599,-3.30898809433 -8.08306503296,1.08469355106,-3.25643992424 -8.05105400085,1.07769298553,-3.21288490295 -8.03104686737,1.07369267941,-3.18911552429 -8.00703811646,1.06869220734,-3.14955353737 -7.97002649307,1.06069195271,-3.10499691963 -7.91300916672,1.05069196224,-3.0524532795 -7.86299419403,1.04069209099,-3.00291109085 -7.83498620987,1.03469216824,-2.96334600449 -7.80897855759,1.02969241142,-2.93857431412 -7.76496601105,1.02169287205,-2.89301919937 -7.74396038055,1.01669323444,-2.85645842552 -7.69494724274,1.00769424438,-2.80990195274 -7.6789431572,1.00369477272,-2.77534532547 -7.71995449066,1.00769460201,-2.76374340057 -7.74896287918,1.0116944313,-2.74813556671 -7.62092924118,0.990696907043,-2.6854262352 -7.60992717743,0.987697780132,-2.65386033058 -7.64893817902,0.991697669029,-2.6412627697 -7.66094255447,0.992698132992,-2.61867761612 -7.52490949631,0.969701886177,-2.54217505455 -7.50790691376,0.965703248978,-2.50960588455 -7.49390411377,0.962704122066,-2.49083399773 -7.5289144516,0.966704308987,-2.47723293304 -7.47890377045,0.957706689835,-2.43367695808 -7.40688896179,0.945709884167,-2.38214421272 -7.40589094162,0.944711208344,-2.35557389259 -7.38488817215,0.939713180065,-2.32300233841 -7.362885952,0.934715390205,-2.28944540024 -7.33288002014,0.929717063904,-2.26667189598 -7.33188247681,0.928718686104,-2.2410929203 -7.32388353348,0.925720572472,-2.21351385117 -7.28087711334,0.91872382164,-2.17396473885 -7.30788564682,0.920724570751,-2.15737748146 -7.23787403107,0.909729003906,-2.10984015465 -7.26788377762,0.912729799747,-2.09523487091 -7.21487379074,0.903732836246,-2.06548666954 -7.19587373734,0.899735629559,-2.03492021561 -7.1858754158,0.897737979889,-2.00833106041 -7.18387889862,0.895740270615,-1.98276400566 -7.16587877274,0.892743229866,-1.95319247246 -7.14387845993,0.887746393681,-1.92262327671 -7.13588094711,0.885749101639,-1.89605128765 -7.13388252258,0.884750366211,-1.88326644897 -7.11588335037,0.880753695965,-1.85370457172 -7.1238899231,0.881755709648,-1.83212161064 -7.0948882103,0.875759601593,-1.80055058002 -7.0818901062,0.872762799263,-1.77298307419 -7.05188989639,0.867766916752,-1.74141478539 -7.04389047623,0.86576873064,-1.72664475441 -7.04789590836,0.865771114826,-1.70505034924 -7.03689908981,0.862774550915,-1.67848169804 -7.02890253067,0.86077773571,-1.65290987492 -6.97989940643,0.852783322334,-1.61734879017 -6.97190284729,0.850786685944,-1.59178245068 -6.95890617371,0.847790420055,-1.56521570683 -6.96891069412,0.84879142046,-1.55641853809 -6.97291707993,0.848794162273,-1.53483140469 -6.92491436005,0.8398001194,-1.50027573109 -6.98192977905,0.847799837589,-1.49067974091 -6.92392587662,0.838806629181,-1.45412838459 -6.90792942047,0.83581084013,-1.42756104469 -6.9349398613,0.838812351227,-1.41195595264 -6.9059381485,0.833815932274,-1.39319598675 -6.90794467926,0.83381909132,-1.37160778046 -6.90495014191,0.831822752953,-1.34803903103 -6.89395523071,0.829826891422,-1.32346081734 -6.94796943665,0.836826682091,-1.3128541708 -6.83195829391,0.818838119507,-1.26533865929 -6.8569688797,0.821839988232,-1.24874293804 -6.8319683075,0.817843616009,-1.23197507858 -6.82497406006,0.815847814083,-1.2084017992 -6.80997896194,0.813852488995,-1.18382179737 -6.80098438263,0.811856865883,-1.16024506092 -6.80499219894,0.811860442162,-1.13867390156 -6.80699872971,0.810863912106,-1.11807775497 -6.79000043869,0.807867228985,-1.10330879688 -6.79400777817,0.807870745659,-1.08272004128 -6.77501249313,0.804876148701,-1.05715668201 -6.77301979065,0.803880214691,-1.0355707407 -6.76702642441,0.802884697914,-1.01299262047 -6.77703523636,0.802888035774,-0.992423713207 -6.78104305267,0.802891731262,-0.971836924553 -6.78304719925,0.802893698215,-0.96105325222 -6.84906244278,0.812892198563,-0.95142352581 -6.77306079865,0.800902605057,-0.916889131069 -6.88808202744,0.816897332668,-0.913265168667 -6.76207494736,0.79791200161,-0.871746242046 -6.75808238983,0.796916484833,-0.850160837173 -6.77109193802,0.798919737339,-0.830578923225 -6.7670955658,0.797922313213,-0.818800985813 -6.71709823608,0.789930939674,-0.790244579315 -6.71610593796,0.788935303688,-0.769651651382 -6.73711633682,0.791937887669,-0.751069545746 -6.7421245575,0.79194188118,-0.730489373207 -6.82914161682,0.804938495159,-0.720868289471 -6.79714679718,0.798945844173,-0.69530415535 -6.74014520645,0.790953278542,-0.677537500858 -6.75015497208,0.79195702076,-0.656967163086 -7.13619709015,0.847925245762,-0.684176921844 -7.27421712875,0.86791652441,-0.678525030613 -6.75418043137,0.790970385075,-0.594223916531 -7.0812163353,0.838943600655,-0.610476255417 -6.77819490433,0.793974936008,-0.56583160162 -7.19223737717,0.854939520359,-0.589057505131 -7.25925016403,0.863937199116,-0.574430942535 -6.80922365189,0.797986090183,-0.505087971687 -11.8176031113,1.53248918056,-0.981858074665 -6.91024827957,0.811985552311,-0.471889257431 -6.74024438858,0.787007212639,-0.435377985239 -6.66924381256,0.776017010212,-0.417638778687 -6.6982550621,0.780018866062,-0.400033921003 -6.66826200485,0.775026977062,-0.376473337412 -6.67027187347,0.775031745434,-0.355893969536 -6.68028116226,0.777035653591,-0.336303144693 -6.66828966141,0.775041937828,-0.314728587866 -6.66029882431,0.773047924042,-0.293159842491 -6.66830396652,0.774049639702,-0.283367186785 -6.65831327438,0.77305585146,-0.261797338724 -6.64032125473,0.770062923431,-0.240222617984 -6.67333269119,0.774064540863,-0.221629172564 -6.65234088898,0.771071970463,-0.200053870678 -6.64835071564,0.770077884197,-0.178492337465 -6.64736032486,0.770083248615,-0.157912939787 -6.65236568451,0.771085262299,-0.148116275668 -6.66137552261,0.772089362144,-0.128521889448 -6.69138669968,0.776091456413,-0.108935378492 -6.75839948654,0.786089122295,-0.0913182720542 -7.08142232895,0.833057761192,-0.082587018609 -6.67241573334,0.773109674454,-0.0462085753679 -7.0294342041,0.825071334839,-0.0482400618494 -6.67342996597,0.773117542267,-0.0158296637237 -7.03445339203,0.825081348419,-0.00409701419994 -6.74845314026,0.784119963646,0.0243478175253 -6.90546798706,0.806106984615,0.041999168694 -7.00448083878,0.821100771427,0.0616241171956 -6.83548593521,0.796125948429,0.08513366431 -6.82349061966,0.794130146503,0.0959157124162 -6.81950044632,0.794136226177,0.117483258247 -6.80650997162,0.792143166065,0.138066753745 -9.70758533478,1.21479654312,0.149061098695 -9.69359111786,1.2128020525,0.179623365402 -9.6935968399,1.21280574799,0.209205791354 -9.67459869385,1.20981001854,0.223986402154 -9.65660381317,1.20781612396,0.25454351306 -9.70561027527,1.21481382847,0.285141825676 -6.69557476044,0.775193572044,0.273272186518 -6.70758581161,0.777197778225,0.293861985207 -6.60959529877,0.763215839863,0.312400132418 -6.59360647202,0.761223912239,0.332960605621 -6.57961177826,0.759228587151,0.34274455905 -6.58962249756,0.760233223438,0.363327711821 -6.66163396835,0.771230041981,0.385938405991 -6.93664598465,0.811200559139,0.415647357702 -6.62065553665,0.765247046947,0.425086826086 -6.63966655731,0.768250703812,0.446666657925 -6.64167737961,0.768256425858,0.467246592045 -6.55568265915,0.75627052784,0.473010390997 -6.55469417572,0.756276845932,0.493581235409 -6.54970502853,0.755283415318,0.513166368008 -6.590716362,0.76128423214,0.535761058331 -6.54972839355,0.755295932293,0.554310679436 -6.60673952103,0.764294505119,0.577917456627 -6.5547451973,0.756304502487,0.584688007832 -6.56875658035,0.759308874607,0.606265604496 -6.52776861191,0.75332069397,0.623825550079 -6.56277990341,0.758322179317,0.646422624588 -6.53879165649,0.75533169508,0.66499042511 -6.52580308914,0.753339588642,0.683577477932 -6.60881376266,0.76633477211,0.7111800313 -6.58881998062,0.763340651989,0.719956994057 -6.60083150864,0.765345394611,0.741539120674 -6.58084344864,0.762354433537,0.760112226009 -6.53785610199,0.756366848946,0.77667081356 -6.52086830139,0.754375576973,0.795245110989 -6.53288030624,0.7563803792,0.816826879978 -6.54989099503,0.759384274483,0.838422894478 -6.53189754486,0.756390213966,0.847195446491 -6.5119099617,0.753399312496,0.864778935909 -6.50392246246,0.7534070611,0.884351611137 -6.47793531418,0.749417364597,0.901914954185 -6.46994781494,0.74842518568,0.921484768391 -6.47095966339,0.749431371689,0.941079616547 -6.56296873093,0.763424813747,0.972695052624 -6.6479716301,0.775415837765,0.993520140648 -6.45499134064,0.74745041132,0.990012526512 -6.46500301361,0.749455630779,1.01159453392 -6.46201562881,0.749462664127,1.0311781168 -6.46902799606,0.751468539238,1.05275309086 -6.46704006195,0.751475393772,1.07234036922 -6.47904539108,0.753476977348,1.08413624763 -6.5450553894,0.763474225998,1.11472904682 -6.80605554581,0.802442133427,1.17342817783 -6.58007860184,0.769482374191,1.16090834141 -6.72708368301,0.791467308998,1.20454490185 -6.57210350037,0.769497096539,1.20106506348 -6.47812080383,0.75551789999,1.20660710335 -6.47712802887,0.755521714687,1.21738183498 -6.4211435318,0.747536897659,1.22795128822 -6.43915510178,0.751541137695,1.2515335083 -6.4451675415,0.752547204494,1.27311217785 -6.42418146133,0.749557256699,1.28968656063 -6.43119382858,0.751563191414,1.31127011776 -6.36721038818,0.742579877377,1.3198287487 -6.40621471405,0.748577535152,1.33762347698 -6.38322925568,0.74558788538,1.35320436954 -6.39124202728,0.747593998909,1.3757724762 -6.4062538147,0.750598490238,1.39837217331 -6.39926719666,0.749606788158,1.41793882847 -6.39528083801,0.749614477158,1.43751847744 -6.42228555679,0.753613889217,1.45331633091 -6.37330198288,0.747628688812,1.46387636662 -6.4063129425,0.752630710602,1.49146306515 -6.43132448196,0.75763386488,1.51705801487 -6.39634037018,0.752646684647,1.53061592579 -6.40535306931,0.754652380943,1.55319857597 -6.51335811615,0.771642565727,1.59781897068 -6.40837287903,0.755662620068,1.58457481861 -6.44438314438,0.762664079666,1.61317372322 -6.40339994431,0.756677865982,1.62473499775 -6.40441322327,0.757685184479,1.64630317688 -6.38242864609,0.754695951939,1.66187465191 -6.3684425354,0.753705203533,1.67846524715 -6.39245462418,0.757709026337,1.70603334904 -6.38646173477,0.757713615894,1.71482431889 -6.39147472382,0.758719980717,1.7364153862 -6.40748643875,0.76172465086,1.76100730896 -6.44049739838,0.767726719379,1.79059505463 -6.40251493454,0.762740314007,1.80215549469 -6.38053035736,0.760751366615,1.81772124767 -6.37954425812,0.760758936405,1.83830296993 -6.37255191803,0.760763823986,1.84708750248 -6.3655667305,0.759772598743,1.86665546894 -6.37957906723,0.762777686119,1.89124536514 -6.41258907318,0.76877951622,1.9208496809 -6.37760734558,0.764793157578,1.93339490891 -6.37262153625,0.764801442623,1.95297634602 -6.37762784958,0.765804350376,1.96477222443 -6.36564254761,0.76481372118,1.9823513031 -6.35265779495,0.763823509216,1.99992358685 -6.35467147827,0.764830648899,2.02150845528 -6.33168792725,0.761842191219,2.03607654572 -6.31070423126,0.759853184223,2.05065488815 -6.3577132225,0.767852962017,2.08625054359 -6.33972263336,0.765860021114,2.09202218056 -6.36973381042,0.770862579346,2.12261414528 -6.57672548294,0.803835272789,2.20926523209 -6.40375852585,0.777872204781,2.17677927017 -6.36377668381,0.772886574268,2.18535065651 -6.39378786087,0.778889238834,2.21693634987 -6.48278522491,0.792877912521,2.25675916672 -6.52279472351,0.799878895283,2.29234719276 -6.4318189621,0.786902010441,2.28390216827 -6.64480876923,0.820873141289,2.37755799294 -6.67282009125,0.825876057148,2.41014242172 -9.52949905396,1.26839017868,3.41479682922 -9.49851512909,1.26540231705,3.43735742569 -6.87383174896,0.85986071825,2.53815484047 -6.8308506012,0.854875802994,2.54672002792 -6.34992218018,0.780966877937,2.39913201332 -6.30594158173,0.775982141495,2.40470910072 -6.35295057297,0.783982038498,2.44429349899 -6.33996677399,0.782992243767,2.46186518669 -6.89291286469,0.869903445244,2.68863749504 -6.80693101883,0.857922554016,2.66938567162 -6.84594011307,0.864923238754,2.70699477196 -6.81895780563,0.861935973167,2.72155237198 -6.72998285294,0.848959267139,2.71110868454 -6.39704036713,0.798025846481,2.60656905174 -9.48465251923,1.28348720074,3.83326458931 -6.5880446434,0.831007957458,2.72679805756 -6.87301492691,0.875961601734,2.8516767025 -6.7240486145,0.853996038437,2.81719708443 -6.41110467911,0.8060593009,2.71468043327 -6.35912704468,0.799076855183,2.71722984314 -6.3641409874,0.801083862782,2.74181628227 -6.36915445328,0.803090929985,2.76640486717 -6.35416460037,0.802097797394,2.77218055725 -6.36917686462,0.805103003979,2.80077672005 -6.36419296265,0.806112170219,2.82234382629 -6.35620880127,0.806121647358,2.84192323685 -6.35722398758,0.807129561901,2.86550354958 -6.39223384857,0.814131498337,2.90409111977 -9.45980930328,1.30458450317,4.27073669434 -6.37725877762,0.814146339893,2.9324593544 -6.59424257278,0.850115299225,3.0521094799 -6.3612909317,0.814165711403,2.97260785103 -6.43729496002,0.828160047531,3.03021526337 -6.35632181168,0.81618309021,3.01776027679 -6.35933685303,0.818190634251,3.04234862328 -6.35035324097,0.818200528622,3.06192517281 -6.36235904694,0.821202516556,3.07971286774 -6.36737394333,0.823210060596,3.10628724098 -6.37938737869,0.827216088772,3.13587093353 -6.37940216064,0.828224182129,3.15945863724 -6.39641523361,0.833229482174,3.19203853607 -6.36943387985,0.83024251461,3.20262074471 -6.34244632721,0.826251864433,3.20238876343 -6.34546136856,0.828259646893,3.22797036171 -6.3394780159,0.829269170761,3.24954342842 -6.35449075699,0.833274722099,3.28113079071 -6.33051013947,0.830287516117,3.29370045662 -6.33352470398,0.833295285702,3.31928730011 -6.32154226303,0.832305967808,3.33786034584 -6.33054876328,0.835308432579,3.35465431213 -6.32056570053,0.835318744183,3.37422919273 -6.33258008957,0.838325202465,3.4058008194 -6.32959508896,0.839333951473,3.42839050293 -6.31061458588,0.8383461833,3.44395256042 -6.34762430191,0.846347808838,3.48854184151 -6.31563711166,0.84135812521,3.4843173027 -6.30565404892,0.841368079185,3.50291180611 -6.30567026138,0.843376755714,3.52848315239 -6.30168676376,0.844386219978,3.55205154419 -6.31570005417,0.848392009735,3.58464074135 -6.35470914841,0.857393085957,3.63123750687 -6.32672977448,0.854407131672,3.64180016518 -6.33673524857,0.85740929842,3.65960216522 -6.26976299286,0.847430706024,3.64815211296 -6.28477668762,0.852436304092,3.68174314499 -6.26679563522,0.85044836998,3.69731402397 -6.26481151581,0.852457344532,3.72189211845 -6.26882696152,0.854465425014,3.75046467781 -6.28584003448,0.859470784664,3.78605270386 -6.29884624481,0.863472640514,3.80684399605 -6.27386617661,0.860486149788,3.81841301918 -6.28088140488,0.86349350214,3.84899020195 -6.29489469528,0.868499577045,3.8835747242 -6.2609167099,0.86451458931,3.88915014267 -6.35291624069,0.882505893707,3.97175097466 -6.27094697952,0.870530128479,3.94830942154 -6.24495983124,0.866539597511,3.94608473778 -6.23797702789,0.867549479008,3.96767282486 -6.26798772812,0.874552607536,4.01325654984 -6.27100324631,0.877560734749,4.04183959961 -6.28601694107,0.88256663084,4.07842206955 -6.66096401215,0.949503362179,4.34410619736 -6.47200679779,0.917544007301,4.23784399033 -6.33304834366,0.895579397678,4.17638921738 -6.25807952881,0.885603070259,4.15692663193 -6.25409650803,0.886612594128,4.18150901794 -6.22511720657,0.883626759052,4.18909502029 -6.26512670517,0.892628073692,4.24367570877 -6.24714660645,0.891640365124,4.25925397873 -6.26215171814,0.895641803741,4.28305006027 -6.23917245865,0.894655108452,4.29562282562 -6.23918914795,0.896664202213,4.32419347763 -6.25720214844,0.901669681072,4.36477518082 -6.27321529388,0.907675266266,4.40336894989 -6.23523902893,0.902691662312,4.4059343338 -6.22125911713,0.902703523636,4.42549800873 -6.23126459122,0.905705988407,4.44629669189 -6.23727989197,0.909713625908,4.47888183594 -6.21730041504,0.907726466656,4.49345684052 -6.23831319809,0.914731621742,4.53803062439 -6.26232481003,0.920735657215,4.58362531662 -6.2593421936,0.922745347023,4.61119842529 -6.26535797119,0.926753461361,4.64576816559 -6.22237443924,0.920766174793,4.62855625153 -6.23638820648,0.925772368908,4.66814136505 -6.22040891647,0.924784779549,4.68670654297 -6.21142673492,0.925795435905,4.70929050446 -6.21544313431,0.929803967476,4.74286031723 -6.2214589119,0.933811843395,4.77744007111 -6.2284655571,0.935814857483,4.79723930359 -6.21348571777,0.935827076435,4.81680488586 -6.22549962997,0.940833806992,4.85638666153 -6.22051763535,0.942843616009,4.88197994232 -6.22853279114,0.946851313114,4.91955184937 -6.21255254745,0.946863353252,4.93713855743 -6.19956445694,0.945870935917,4.94390439987 -6.20657968521,0.949878454208,4.97949743271 -6.24258899689,0.959880411625,5.0390868187 -6.22560930252,0.958893179893,5.05765295029 -6.25362062454,0.966896653175,5.11124515533 -6.20964670181,0.961914658546,5.10781049728 -6.22965908051,0.968919694424,5.15540075302 -6.27065896988,0.977916300297,5.20519590378 -6.24068307877,0.974931657314,5.21375703812 -6.20170783997,0.970948457718,5.21333456039 -6.20872354507,0.974956393242,5.25190973282 -6.19874238968,0.976967453957,5.27549505234 -6.21275663376,0.981974005699,5.32007598877 -6.20077705383,0.982985854149,5.3436422348 -6.2227807045,0.988985955715,5.37844181061 -6.20180225372,0.987999498844,5.39401245117 -6.20781850815,0.993007659912,5.43259191513 -6.21083450317,0.996016204357,5.46817874908 -6.21884965897,1.00102388859,5.50876092911 -6.204870224,1.00203633308,5.53132581711 -6.20588731766,1.00504517555,5.56591033936 -6.2148938179,1.00904810429,5.59070539474 -6.22091007233,1.01305639744,5.63127613068 -6.25591945648,1.02305865288,5.69686889648 -6.25693655014,1.02706801891,5.73344039917 -6.21896219254,1.02308487892,5.7340130806 -6.38394212723,1.05906105042,5.91963577271 -6.23798370361,1.03209495544,5.80339765549 -6.26199579239,1.04009974003,5.86197328568 -6.21602392197,1.03511846066,5.85553836823 -6.19804525375,1.03513157368,5.87510824203 -6.19706296921,1.0381411314,5.90969371796 -6.19508075714,1.04215097427,5.94427013397 -6.21409416199,1.04915654659,5.99885320663 -6.19610643387,1.04716479778,5.99964284897 -6.19912290573,1.0521736145,6.03922462463 -6.21613693237,1.05917966366,6.09280633926 -6.19315910339,1.05819380283,6.10738515854 -6.21217250824,1.06619954109,6.16396284103 -6.20719194412,1.0692101717,6.19753360748 -6.18921375275,1.06922340393,6.21810436249 -6.20221948624,1.07422542572,6.24989891052 -6.23922777176,1.08522737026,6.32449483871 -6.31522846222,1.10522186756,6.44107818604 -6.21226978302,1.08825206757,6.37564086914 -6.1922917366,1.08826553822,6.39421749115 -6.24129867554,1.10226547718,6.48479700089 -6.40826749802,1.13923633099,6.67563438416 -6.18933725357,1.098290205,6.49016141891 -6.20835018158,1.10629594326,6.54974603653 -6.20036935806,1.10830700397,6.58132696152 -6.24037837982,1.12130880356,6.66490650177 -6.17841005325,1.11233079433,6.63947820663 -6.21441984177,1.12533307076,6.71906375885 -6.18743515015,1.12134361267,6.71183681488 -6.18745231628,1.12535309792,6.75242424011 -6.16447639465,1.12536752224,6.76998996735 -6.19148778915,1.13637185097,6.8415722847 -6.16051292419,1.13338768482,6.84915113449 -6.20651960373,1.14838802814,6.94273710251 -6.19554042816,1.15040004253,6.97331571579 -6.24253797531,1.16339552402,7.04810810089 -6.22356033325,1.16440880299,7.06969118118 -7.01438522339,1.34325814247,8.01042461395 -6.99140882492,1.34327244759,8.03399944305 -6.97642993927,1.34628534317,8.06756877899 -6.96345043182,1.34829759598,8.10215091705 -6.94546413422,1.34730613232,8.10693359375 -6.92948532104,1.34931910038,8.13851261139 -6.90050983429,1.34833455086,8.15508842468 -6.87753343582,1.34934914112,8.17965602875 -6.86655378342,1.35236096382,8.21723842621 -6.83058071136,1.35037827492,8.22680091858 -6.81260251999,1.3523914814,8.25638008118 -6.81761026382,1.35639548302,8.28817176819 -6.7966337204,1.35740959644,8.31573867798 -6.77165794373,1.35742461681,8.33830738068 -6.76067829132,1.36143660545,8.37688827515 -6.7317032814,1.36045217514,8.39346504211 -6.72372341156,1.36446380615,8.43703842163 -6.63275527954,1.3464871645,8.34981155396 -6.68476009369,1.36448645592,8.46840000153 -3.48957920074,0.618143975735,4.4744977951 -3.47260308266,0.617157399654,4.48107528687 -3.45562624931,0.616170525551,4.48666572571 -3.41365671158,0.610189020634,4.4612364769 -6.62586545944,1.3825480938,8.66627502441 -6.58588409424,1.37556087971,8.64106273651 -6.56490802765,1.37757527828,8.66963195801 -6.56092691422,1.38258612156,8.72021007538 -6.52895307541,1.38160252571,8.73378372192 -6.50297784805,1.38161766529,8.75535678864 -6.48700094223,1.38463103771,8.79092884064 -6.45802640915,1.38464665413,8.80751132965 -6.45803594589,1.38765192032,8.83729076385 -6.44105815887,1.39066529274,8.87087154388 -6.41008424759,1.38968157768,8.88644123077 -6.39510631561,1.39269459248,8.92302131653 -6.38012886047,1.39570772648,8.96059703827 -6.34515619278,1.39372491837,8.97116184235 -6.32318067551,1.39573943615,8.99873924255 -6.31819057465,1.39774537086,9.02053260803 -6.29521560669,1.39976012707,9.0481004715 -6.27523946762,1.40177440643,9.07967281342 -6.25826263428,1.40478789806,9.11524868011 -6.23328733444,1.40480291843,9.13882637024 -6.20831251144,1.40581810474,9.16240596771 -6.19932413101,1.40782499313,9.18019104004 -6.17035102844,1.4078412056,9.19975566864 -6.14537572861,1.40885615349,9.22333621979 -6.12639951706,1.41087019444,9.25691127777 -6.09442663193,1.40988695621,9.2714805603 -6.07644987106,1.41290056705,9.30606174469 -6.05947351456,1.4159142971,9.34363365173 -6.04148721695,1.41592299938,9.34742259979 -6.01351356506,1.41593885422,9.36799430847 -6.00253534317,1.42095124722,9.41457366943 -5.97956037521,1.42196595669,9.44314670563 -5.95458555222,1.42398118973,9.46772766113 -5.92661237717,1.42399728298,9.4892950058 -5.91362524033,1.42500507832,9.50207805634 -5.88765096664,1.42602038383,9.52466106415 -5.86667537689,1.4280346632,9.55624103546 -5.83070373535,1.42605233192,9.56480979919 -5.80672931671,1.42806744576,9.59238433838 -5.78075504303,1.42908298969,9.61695671082 -5.74878358841,1.4290997982,9.63153076172 -5.73779582977,1.4301071167,9.647315979 -5.71082210541,1.43112277985,9.6698923111 -5.68784713745,1.43313765526,9.69946956635 -5.65287590027,1.43115496635,9.70804786682 -5.62390327454,1.43217122555,9.7286157608 -5.59293031693,1.43118774891,9.74419307709 -5.57295513153,1.43520200253,9.77976799011 -5.5549697876,1.43421089649,9.78355503082 -5.532995224,1.43622565269,9.8161277771 -5.50002336502,1.4362424612,9.827709198 -5.47105026245,1.43625879288,9.848279953 -5.44607639313,1.43827402592,9.8748588562 -5.42410135269,1.44028878212,9.90743541718 -5.38713169098,1.43930673599,9.91400337219 -5.38314199448,1.44231271744,9.94279670715 -5.35716867447,1.44432830811,9.96936702728 -5.31319999695,1.4403475523,9.96193885803 -5.29122591019,1.44336235523,9.99551486969 -5.26625156403,1.44437766075,10.0220975876 -5.24227809906,1.44739282131,10.0516777039 -5.22229385376,1.44640219212,10.0534534454 -5.19831991196,1.44841730595,10.083032608 -5.16334915161,1.44743478298,10.0916099548 -5.14137458801,1.45044958591,10.1271810532 -5.11740064621,1.45246469975,10.1567640305 -5.02344608307,1.4324940443,10.048330307 -3.77781152725,1.03375518322,7.61779689789 -3.74483108521,1.02676713467,7.58157920837 -3.70286250114,1.02078568935,7.55515861511 -3.66989183426,1.01780259609,7.54673814774 -3.63592147827,1.01381981373,7.53631448746 -3.60794878006,1.01283550262,7.53690052032 -3.56698060036,1.00685405731,7.51147460938 -3.53900837898,1.0048699379,7.51205587387 -3.53102087975,1.00687682629,7.52584171295 -3.51404595375,1.00889074802,7.55141401291 -3.49607110023,1.01090455055,7.57299947739 -3.45710229874,1.0049226284,7.55057382584 -3.44012713432,1.00793635845,7.57515478134 -3.40215802193,1.00295436382,7.55373239517 -2.93162703514,0.971218526363,7.51179647446 -2.91165328026,0.973232865334,7.52937746048 -2.88268208504,0.970248997211,7.52395582199 -2.86869645119,0.969256997108,7.5227432251 -2.8397257328,0.967273294926,7.5183134079 -2.81775259972,0.968287944794,7.52989864349 -2.79078030586,0.966303408146,7.52748680115 -2.76580882072,0.966319024563,7.53405380249 -2.74083638191,0.965334355831,7.53863191605 -2.71286463737,0.963349938393,7.53222417831 -2.70687675476,0.966356396675,7.55301094055 -2.66093111038,0.966386139393,7.57217311859 -2.64595603943,0.970399439335,7.60475492477 -2.61398649216,0.966416299343,7.5903263092 -2.5770175457,0.960433959961,7.55890750885 -2.56704139709,0.967446327209,7.60748529434 -2.54505753517,0.962455570698,7.57928514481 -2.52308487892,0.96347039938,7.59286117554 -2.50011205673,0.963485121727,7.60144710541 -2.47214078903,0.961501061916,7.59602642059 -2.45216703415,0.963515281677,7.61460924149 -2.43519306183,0.966529071331,7.64418554306 -2.15389299393,1.26389122009,9.80879020691 -2.14391708374,1.27790379524,9.91236877441 -2.13694047928,1.29591572285,10.0349416733 -2.14994668961,1.31591820717,10.1717395782 -2.14297032356,1.33393025398,10.3013124466 -2.15798687935,1.36793768406,10.5388946533 -2.135014534,1.37595236301,10.5934801102 -2.10504484177,1.37896871567,10.6190538406 -2.09506869316,1.39598107338,10.745634079 -2.15107369423,1.46698105335,11.2242088318 -2.36702013016,1.65094518661,12.4649953842 -2.32805323601,1.65096330643,12.4775657654 -2.28908538818,1.65098106861,12.4821519852 -2.25011825562,1.65099906921,12.4907312393 -2.21215057373,1.65201675892,12.5033121109 -2.17418265343,1.65303432941,12.5138988495 -2.1541993618,1.65304350853,12.5186824799 -2.11623167992,1.65406095982,12.5292692184 -2.08026337624,1.65707838535,12.5568475723 -2.04629468918,1.66209518909,12.5964279175 -2.00832700729,1.6631128788,12.6120090485 -1.97235906124,1.66713011265,12.6425867081 -1.93139231205,1.66614842415,12.639169693 -1.9114086628,1.66515719891,12.6379642487 -1.87943971157,1.67317390442,12.7005376816 -1.85246896744,1.68718934059,12.7961177826 -1.8214994669,1.69720566273,12.8676967621 -1.78553116322,1.70122277737,12.9022817612 -1.75056254864,1.70623970032,12.9448680878 -1.72957932949,1.70524871349,12.9416589737 -1.6826145649,1.69826793671,12.8972415924 -1.64064848423,1.69728636742,12.8938179016 -1.59868216515,1.69530451298,12.8834028244 -1.55771553516,1.69432258606,12.881986618 -1.5177488327,1.69534039497,12.8925657272 -1.47578239441,1.6923584938,12.8811502457 -1.45579922199,1.69336760044,12.8889369965 -1.41483283043,1.69338572025,12.8905172348 -1.37286639214,1.69040369987,12.8751039505 -1.33189976215,1.68942165375,12.8726873398 -1.28893387318,1.68543994427,12.8492708206 -1.24796748161,1.68545794487,12.8488512039 -1.20700097084,1.6834757328,12.8424358368 -1.18801760674,1.68648469448,12.8642196655 -1.14705097675,1.6845023632,12.8548078537 -1.10608422756,1.68352019787,12.8463935852 -1.06611764431,1.68453776836,12.8549757004 -1.02515137196,1.68355584145,12.8545541763 -0.984185039997,1.68257367611,12.8511352539 -0.944218277931,1.68359136581,12.8577194214 -0.92523419857,1.68459963799,12.8645191193 -0.884267926216,1.68361759186,12.8630990982 -0.843301475048,1.68163537979,12.855682373 -0.801335632801,1.67965328693,12.8382616043 -0.761368870735,1.6796708107,12.8438463211 -0.721402049065,1.67968833447,12.8484315872 -0.700419187546,1.67869746685,12.8412189484 -0.661451756954,1.6797144413,12.8508119583 -0.620485663414,1.67973232269,12.8523893356 -0.579518914223,1.67574977875,12.8239803314 -0.540552318096,1.682767272,12.870557785 -0.49858635664,1.67778503895,12.838139534 -0.458619505167,1.6778024435,12.8397264481 -0.43763667345,1.67581140995,12.8265142441 -0.358702600002,1.67984580994,12.8556919098 -0.317736506462,1.67886352539,12.85227108 -0.276770293713,1.67688107491,12.8348522186 -0.236803427339,1.67589831352,12.8314418793 -0.217819541693,1.68190670013,12.8732385635 -0.176853328943,1.67892420292,12.8518199921 -0.135887235403,1.67694175243,12.8374004364 -0.0959203839302,1.67595887184,12.8339881897 -0.0559535175562,1.67397606373,12.8155765533 -0.0149875329807,1.66999351978,12.7901544571 --0.0149872200564,1.68500649929,12.2898387909 --0.0529548116028,1.68302321434,12.2754297256 --0.0919216200709,1.68604028225,12.2900123596 --0.110905282199,1.68104863167,12.2588043213 --0.149872213602,1.6850656271,12.2873878479 --0.187839493155,1.67908239365,12.2469730377 --0.225807026029,1.67909908295,12.2435646057 --0.26477381587,1.68011593819,12.2521457672 --0.30274116993,1.67813265324,12.2337331772 --0.322724401951,1.68114125729,12.2525224686 --0.360691875219,1.68015778065,12.2451114655 --0.398659408092,1.68017423153,12.2437028885 --0.437626093626,1.68019127846,12.239282608 --0.476593226194,1.68320798874,12.2578706741 --0.514560580254,1.68122458458,12.2454576492 --0.553527235985,1.68024134636,12.2400369644 --0.572511136532,1.68124961853,12.2428340912 --0.610478520393,1.68026602268,12.2344226837 --0.648445904255,1.67928254604,12.2260093689 --0.687412917614,1.68029916286,12.2315950394 --0.725380122662,1.67931580544,12.2171792984 --0.763347685337,1.67933213711,12.2157707214 --0.80131483078,1.67734861374,12.2013530731 --0.810301423073,1.65335512161,12.0461454391 --0.859265446663,1.67837333679,12.2007312775 --0.897232592106,1.67638981342,12.1883144379 --0.935200154781,1.6764061451,12.1849040985 --0.975166738033,1.67942285538,12.1984882355 --1.01413416862,1.6814391613,12.2110824585 --1.05210149288,1.68045544624,12.2016687393 --1.07108533382,1.68146348,12.2014656067 --1.11205148697,1.6844804287,12.219045639 --1.15001916885,1.68449652195,12.215637207 --1.1899856329,1.6865131855,12.2232208252 --1.22795331478,1.68652915955,12.2208147049 --1.26692056656,1.68754553795,12.2224025726 --1.2879036665,1.69055402279,12.2361955643 --1.32687091827,1.69157016277,12.2397861481 --1.36583781242,1.69158649445,12.2363710403 --1.40480482578,1.69160270691,12.2339553833 --1.44577145576,1.69561934471,12.2505435944 --1.48473846912,1.69563555717,12.2491312027 --1.5237057209,1.69665157795,12.2487201691 --1.54468894005,1.69865989685,12.259513855 --1.58065700531,1.6956756115,12.2341022491 --1.6226234436,1.70069217682,12.2586946487 --1.66059100628,1.69970798492,12.2492837906 --1.70255708694,1.70272469521,12.2648658752 --1.74352407455,1.70674085617,12.2804613113 --1.78249144554,1.70675683022,12.2780513763 --1.80047523975,1.70476472378,12.2638425827 --1.83244431019,1.69777965546,12.2104244232 --1.88340806961,1.71079754829,12.2870159149 --1.92337501049,1.71181356907,12.2896051407 --1.9653416872,1.71582984924,12.3071994781 --2.00630831718,1.71784603596,12.3137865067 --2.02429246902,1.71685373783,12.3005781174 --2.06525921822,1.71886980534,12.3111743927 --2.10722541809,1.72188615799,12.3197574615 --2.14719295502,1.72390198708,12.3243551254 --2.18715953827,1.72391808033,12.3189344406 --2.22912621498,1.72693407536,12.33152771 --2.26809382439,1.72694957256,12.3281230927 --2.28807759285,1.72795748711,12.3279190063 --2.33004379272,1.73097372055,12.3355045319 --2.37001085281,1.73098957539,12.3320913315 --2.41297745705,1.73500561714,12.3496894836 --2.4529440403,1.73502147198,12.3432712555 --2.49091219902,1.73503673077,12.3328647614 --2.53587794304,1.74005329609,12.3534517288 --2.55886101723,1.7430614233,12.3692531586 --2.59682822227,1.74107694626,12.3528356552 --2.6377954483,1.74309253693,12.3554296494 --2.6797618866,1.74510848522,12.3600168228 --2.72072911263,1.74712407589,12.3636140823 --2.75969696045,1.74713933468,12.3562078476 --2.80066370964,1.74915504456,12.3547935486 --2.8186480999,1.7481623888,12.3445911407 --2.86161470413,1.75117826462,12.3541841507 --2.90558075905,1.75419425964,12.365773201 --2.94454813004,1.75420963764,12.3543596268 --2.98851442337,1.75722551346,12.3679561615 --3.02948188782,1.75924086571,12.3675489426 --3.05046486855,1.76024866104,12.3663387299 --3.09143209457,1.76126420498,12.3639278412 --3.13539862633,1.76427984238,12.3765268326 --3.17536616325,1.7652951479,12.3701171875 --3.21833252907,1.76731073856,12.374707222 --3.2612991333,1.77032637596,12.3782958984 --3.30426573753,1.77234184742,12.3828878403 --3.32624912262,1.77434968948,12.3866834641 --3.36721634865,1.77536487579,12.3852815628 --3.40918326378,1.77738022804,12.3838691711 --3.45514917374,1.78039610386,12.3974609375 --3.4951171875,1.78141081333,12.3920602798 --3.53608441353,1.78242611885,12.3856468201 --3.58005070686,1.78544151783,12.3912391663 --3.60803222656,1.79045021534,12.4140338898 --3.64899992943,1.79146492481,12.4116344452 --3.6909673214,1.79348015785,12.4092245102 --3.73393392563,1.79449534416,12.4088134766 --3.77490186691,1.79651010036,12.4044103622 --3.81686878204,1.79752516747,12.4010009766 --3.84584999084,1.80253386497,12.4247961044 --3.87981963158,1.80054759979,12.3973941803 --3.92578577995,1.80356311798,12.4059848785 --3.96975255013,1.80557835102,12.4075746536 --4.00772094727,1.80559253693,12.391166687 --4.05668640137,1.81060826778,12.4097642899 --4.10065317154,1.81262338161,12.4103536606 --4.12063741684,1.81263065338,12.4051504135 --4.16360425949,1.81464552879,12.4027414322 --4.2095708847,1.81866061687,12.4123439789 --4.25053834915,1.81867527962,12.4019298553 --4.29250621796,1.8206897974,12.397526741 --4.33247423172,1.82070398331,12.3871231079 --4.37244272232,1.82171809673,12.3767194748 --4.39742517471,1.8237259388,12.3845148087 --4.44239187241,1.82674098015,12.3851032257 --4.47736120224,1.82475435734,12.3596963882 --4.52132892609,1.82776892185,12.3602952957 --4.56529569626,1.82978355885,12.3598918915 --4.60226488113,1.82879734039,12.3374767303 --4.62624835968,1.83080470562,12.3452854156 --4.6742143631,1.8348197937,12.3538780212 --4.7141828537,1.83483362198,12.3414726257 --4.75715065002,1.83684802055,12.3370676041 --4.80611610413,1.84086310863,12.3476629257 --4.84808444977,1.84287726879,12.3392543793 --4.89804935455,1.84689259529,12.3508472443 --4.92403268814,1.84990012646,12.3616533279 --4.96500062943,1.85091400146,12.3492422104 --5.01096773148,1.85392844677,12.3518428802 --5.05393600464,1.85594248772,12.3464403152 --5.05391550064,1.83995068073,12.2330226898 --5.06089401245,1.82695960999,12.1416168213 --5.09186506271,1.82397186756,12.1072092056 --5.10685110092,1.82297790051,12.0900087357 --5.13482284546,1.8179898262,12.0475950241 --5.14480018616,1.80799925327,11.9651842117 --5.20476388931,1.81601524353,12.001789093 --5.21274137497,1.80502426624,11.9153766632 --5.18173074722,1.77902793884,11.7429666519 --5.17572212219,1.76903104782,11.6787595749 --5.19669675827,1.76304197311,11.6253490448 --5.22166967392,1.75905323029,11.5819406509 --5.12367773056,1.70904779434,11.2675189972 --5.12965631485,1.69805645943,11.1861095428 --5.1566286087,1.69506812096,11.1496963501 --5.16760635376,1.68607747555,11.0812902451 --5.18359231949,1.68508338928,11.0710935593 --5.20456647873,1.68009412289,11.0236825943 --5.27452659607,1.69311141968,11.0802774429 --5.29850101471,1.68912231922,11.0418796539 --5.31547689438,1.68313229084,10.9874706268 --5.32345485687,1.67314112186,10.9150619507 --5.40441274643,1.69015944004,10.9936656952 --5.3374209404,1.66015470028,10.8104400635 --5.37339162827,1.66116702557,10.7990455627 --5.44835138321,1.67518460751,10.8626413345 --5.49831771851,1.68019866943,10.877243042 --5.52029275894,1.67620921135,10.8348350525 --5.51827287674,1.66421663761,10.7444181442 --5.53126001358,1.66222202778,10.7292232513 --5.60422086716,1.67523908615,10.786822319 --5.630194664,1.67324995995,10.7544231415 --5.69215774536,1.68226540089,10.789018631 --5.74112462997,1.68727910519,10.7986154556 --5.77209663391,1.68629062176,10.7742099762 --5.80806779861,1.68730258942,10.759809494 --5.8550453186,1.69631230831,10.8056077957 --5.89401531219,1.69832456112,10.796207428 --5.91199111938,1.69333422184,10.7478017807 --5.96395730972,1.69834804535,10.7613992691 --5.99892950058,1.69935977459,10.7450008392 --5.99391174316,1.68736636639,10.6555900574 --6.07187128067,1.70138335228,10.7151927948 --6.12284755707,1.71139323711,10.7659978867 --6.15182065964,1.71040403843,10.7375946045 --6.20578670502,1.71641790867,10.7521905899 --6.23375988007,1.71442866325,10.721786499 --6.24373865128,1.70743703842,10.6603784561 --6.29170703888,1.71144986153,10.6659832001 --6.33168649673,1.71845817566,10.6957883835 --6.37065696716,1.72047019005,10.6833820343 --6.39963054657,1.71848058701,10.6549787521 --6.47459125519,1.73149657249,10.7035837173 --6.51556158066,1.73350846767,10.6941795349 --6.55553197861,1.73552024364,10.6837797165 --6.58550548553,1.73353075981,10.6563749313 --6.61448812485,1.73753774166,10.6651744843 --6.65745830536,1.74054968357,10.6597776413 --6.68643188477,1.7385597229,10.6313772202 --6.72840213776,1.7415715456,10.6229743958 --6.76737260818,1.74258303642,10.6095705032 --6.85633039474,1.75860011578,10.6751794815 --6.90229988098,1.76261210442,10.6727819443 --6.90928888321,1.75961625576,10.6455755234 --6.96025705338,1.76462876797,10.651181221 --6.97523403168,1.75863730907,10.5987682343 --7.02620267868,1.76364982128,10.6033716202 --7.03218317032,1.75665688515,10.5399694443 --7.13213825226,1.77467477322,10.6175794601 --7.18911409378,1.78568446636,10.6663856506 --7.20109224319,1.77969229221,10.6109800339 --7.26305818558,1.78770565987,10.6305875778 --7.29003286362,1.78571522236,10.5971822739 --7.33600282669,1.78972673416,10.5917816162 --7.39596891403,1.79673981667,10.6073894501 --7.43394088745,1.7977502346,10.5899877548 --7.4629240036,1.80075669289,10.5947847366 --7.41791772842,1.77975809574,10.4593706131 --7.56586170197,1.810780406,10.5979909897 --7.58083963394,1.80578827858,10.5485906601 --7.63180875778,1.81080007553,10.5481891632 --7.67477989197,1.81281077862,10.5377950668 --7.73374652863,1.81982326508,10.5483970642 --7.74773406982,1.81882786751,10.5311899185 --7.77670907974,1.81783699989,10.5017957687 --7.83267688751,1.82384896278,10.5073976517 --7.85765266418,1.82185769081,10.4709939957 --7.88562822342,1.82086646557,10.4395952225 --7.92160081863,1.82087635994,10.4171895981 --7.98957490921,1.83488631248,10.4740066528 --8.09053134918,1.8519026041,10.5366134644 --8.14050197601,1.85591363907,10.5332212448 --8.17847442627,1.85692334175,10.5128183365 --8.23044490814,1.86193418503,10.5124320984 --8.23542499542,1.85494065285,10.4480161667 --8.28239536285,1.85795104504,10.4406261444 --8.3343744278,1.866959095,10.4724330902 --8.30436420441,1.85096204281,10.3650131226 --8.39532470703,1.86597657204,10.4126329422 --8.45429325104,1.87198793888,10.4182386398 --8.47227096558,1.86899530888,10.3728370667 --8.53323841095,1.87500679493,10.3794384003 --8.54921722412,1.87101387978,10.332036972 --8.59319877625,1.87802088261,10.3528490067 --8.60517883301,1.8730275631,10.2994394302 --8.58916568756,1.86103153229,10.2140331268 --5.47991943359,1.11074447632,6.42788505554 --5.45790672302,1.10074949265,6.36047649384 --5.42989444733,1.08875405788,6.28504991531 --5.42287778854,1.08276069164,6.23563623428 --5.40787267685,1.07676267624,6.19843387604 --5.40185594559,1.07076919079,6.15102148056 --5.39183950424,1.06377542019,6.09961032867 --5.39881944656,1.06078326702,6.06719446182 --5.37980604172,1.05178868771,6.00678634644 --5.38778543472,1.04879653454,5.97637414932 --5.37577915192,1.04479908943,5.94316339493 --5.36976194382,1.03880560398,5.89775085449 --5.35974645615,1.03181183338,5.84833812714 --5.37572383881,1.03182041645,5.82793045044 --5.36770772934,1.02482664585,5.78152036667 --5.36569023132,1.02083361149,5.7421131134 --5.36967039108,1.01784098148,5.70869827271 --5.35166549683,1.01184284687,5.67149686813 --5.35464715958,1.00785017014,5.63808917999 --5.36662578583,1.00685834885,5.61367416382 --5.34661245346,0.997863709927,5.55626153946 --5.36159038544,0.997872054577,5.53585243225 --5.36257171631,0.993879020214,5.50144720078 --5.36655282974,0.990886330605,5.47003889084 --5.35354709625,0.985888779163,5.43883085251 --5.37052440643,0.985897123814,5.42142868042 --5.36050844193,0.979903519154,5.37500333786 --5.37448740005,0.978911399841,5.35561084747 --5.37846851349,0.975918829441,5.32419347763 --5.38244915009,0.973926126957,5.29378509521 --5.38942909241,0.971933603287,5.26637601852 --5.39841842651,0.971937775612,5.25817251205 --5.39940023422,0.96794462204,5.22577142715 --5.42137718201,0.968953311443,5.21336555481 --5.4373550415,0.96896147728,5.19495677948 --5.44633579254,0.967968821526,5.17055654526 --5.47031164169,0.968977749348,5.15914106369 --5.4892988205,0.971982300282,5.16195726395 --5.49228000641,0.968989551067,5.13053894043 --5.53125333786,0.972999274731,5.1341381073 --5.54623222351,0.97300696373,5.11574316025 --5.55521202087,0.97201448679,5.09032869339 --5.59918403625,0.977024435997,5.09792757034 --5.61216402054,0.977031946182,5.07753038406 --5.62615203857,0.978036224842,5.0743355751 --5.66012620926,0.982045412064,5.07192802429 --5.68610286713,0.984053909779,5.06252574921 --5.72007846832,0.987062752247,5.06113576889 --5.73505687714,0.987070560455,5.04071998596 --5.7660317421,0.990079283714,5.03531646729 --5.80300664902,0.994088232517,5.03592538834 --5.82199382782,0.997092664242,5.03673171997 --5.85496902466,1.00010144711,5.03232622147 --5.86394929886,0.999108612537,5.00691556931 --5.92291879654,1.00711882114,5.02552509308 --5.92990016937,1.00612568855,4.99912452698 --5.95787715912,1.00813376904,4.99072885513 --5.9948515892,1.01214253902,4.9893283844 --6.00284147263,1.01214635372,4.97911930084 --6.04581451416,1.01815533638,4.98272371292 --6.07579135895,1.02016341686,4.97532701492 --6.13974237442,1.02718007565,4.96252346039 --6.17771816254,1.03118824959,4.96214056015 --6.20769405365,1.03419649601,4.95272684097 --6.2336807251,1.03820085526,4.95854282379 --6.26365661621,1.04020881653,4.94913339615 --6.29763269424,1.04421699047,4.94373607635 --6.32960891724,1.04722487926,4.9363360405 --6.36658477783,1.05123305321,4.93294000626 --6.38756322861,1.05224025249,4.91653728485 --6.42654657364,1.05824542046,4.93033885956 --6.45152521133,1.06025266647,4.91795110703 --6.49849796295,1.0662612915,4.92054462433 --6.52847528458,1.06926870346,4.91115188599 --6.56445169449,1.07327651978,4.90575456619 --6.59242916107,1.07528376579,4.89435863495 --6.64440202713,1.08229219913,4.90096950531 --5.53062057495,0.866237640381,4.04039239883 --5.54460000992,0.867244958878,4.02298307419 --5.54358291626,0.864251315594,3.99457216263 --5.58155870438,0.869259417057,3.99618816376 --6.81929349899,1.10232651234,4.88219213486 --6.84027242661,1.10333323479,4.86378526688 --6.88724660873,1.10934102535,4.86438846588 --6.91623306274,1.11334514618,4.86919975281 --6.9562087059,1.1183526516,4.86379528046 --6.99918413162,1.1233600378,4.86140489578 --7.03016233444,1.12636685371,4.85000801086 --7.06213998795,1.12937355042,4.83961725235 --7.10711479187,1.13438093662,4.83721876144 --7.14509153366,1.13838791847,4.82981967926 --7.18507623672,1.14539217949,4.84163951874 --7.20905590057,1.1463984251,4.82423686981 --7.26402902603,1.15340602398,4.8278427124 --7.29100799561,1.15541231632,4.81244468689 --7.34698152542,1.16341972351,4.81604957581 --7.3789601326,1.16642618179,4.8036532402 --7.42693567276,1.17243301868,4.80226755142 --7.45292234421,1.17543661594,4.80206680298 --7.50789690018,1.1834435463,4.80468177795 --7.54187488556,1.18644988537,4.79227924347 --7.59185028076,1.19245660305,4.7908911705 --7.62182950974,1.19546246529,4.77649927139 --7.66780567169,1.20146894455,4.77109861374 --7.72477960587,1.20847570896,4.77371740341 --7.74576854706,1.21147871017,4.76951694489 --7.78574609756,1.21548485756,4.76012086868 --7.85271883011,1.22549176216,4.76773738861 --7.89569568634,1.22949779034,4.75933885574 --7.93367433548,1.2345033884,4.74895429611 --7.99164867401,1.24150979519,4.74956417084 --8.01963615417,1.24551284313,4.74937152863 --8.06161403656,1.25051856041,4.73997879028 --8.10059261322,1.25452411175,4.72858572006 --8.14656925201,1.25952970982,4.72119569778 --8.19754600525,1.26653552055,4.71579837799 --8.2325258255,1.26954066753,4.70241641998 --8.34149265289,1.28654766083,4.73104572296 --8.64143180847,1.3385579586,4.88793516159 --8.58342838287,1.32556021214,4.81750917435 --8.46543502808,1.30156111717,4.71306180954 --8.48441791534,1.30256557465,4.68866682053 --8.54539299011,1.31057095528,4.68727779388 --8.62636470795,1.32157671452,4.69689702988 --11.5008525848,1.8226467371,6.24624967575 --11.515838623,1.82164871693,6.20685100555 --11.5128278732,1.81765043736,6.15744495392 --11.5088167191,1.81365191936,6.10804128647 --11.5128059387,1.81065368652,6.06263685226 --11.5077953339,1.80665516853,6.01323413849 --11.5127830505,1.80365681648,5.96883106232 --11.4967794418,1.79965734482,5.93662166595 --11.4947690964,1.79565894604,5.88921928406 --11.5027570724,1.79366052151,5.84681749344 --8.02431201935,1.19060838223,3.99521875381 --8.03929519653,1.19061267376,3.97081971169 --8.02928256989,1.18661653996,3.93340945244 --8.03826713562,1.18562066555,3.90600776672 --8.01126480103,1.18062245846,3.87578821182 --8.03124713898,1.18162667751,3.8533821106 --8.01823616028,1.1776304245,3.8159828186 --8.02522087097,1.17663443089,3.78757715225 --8.01120948792,1.17163825035,3.7491672039 --8.02719306946,1.17264246941,3.72475767136 --8.0041885376,1.1676441431,3.69855499268 --8.01817321777,1.16764831543,3.67314338684 --7.99816274643,1.16265201569,3.63273477554 --8.01514625549,1.16365599632,3.60933065414 --7.99813508987,1.15865969658,3.57092642784 --8.01911830902,1.15966367722,3.54952549934 --7.99810791016,1.15466737747,3.5091137886 --8.00209999084,1.15466940403,3.49490332603 --8.05807876587,1.16167342663,3.48951649666 --8.10805702209,1.16867721081,3.48112797737 --8.17003440857,1.17668104172,3.4777431488 --8.22801399231,1.18468463421,3.47235870361 --8.28799152374,1.1926882267,3.46798157692 --8.33797073364,1.19869172573,3.45758390427 --8.39895629883,1.20869326591,3.46941781044 --8.44193649292,1.21369671822,3.45501232147 --8.50391483307,1.22169983387,3.45064163208 --8.57189273834,1.23170280457,3.44725823402 --8.63187122345,1.2397056818,3.43986916542 --8.68485164642,1.24670851231,3.4304933548 --11.5334501266,1.71669471264,4.5711312294 --11.6284313202,1.73169445992,4.58896636963 --11.6564188004,1.73369503021,4.55757570267 --11.6584091187,1.73169565201,4.51517105103 --11.6434011459,1.72669649124,4.46575737 --11.6463909149,1.72469699383,4.42435693741 --11.6493816376,1.72269749641,4.38295555115 --11.6433725357,1.71969819069,4.33855485916 --11.6323699951,1.71669864655,4.31335163116 --11.6423587799,1.71569895744,4.27495336533 --11.6193523407,1.70969974995,4.22353792191 --11.6273422241,1.70870029926,4.18413496017 --11.6373319626,1.70870053768,4.14573431015 --11.6143245697,1.70270133018,4.09532260895 --11.6123161316,1.69970178604,4.05291986465 --11.6133117676,1.69870197773,4.03272151947 --11.6023044586,1.69470250607,3.98731613159 --11.6022949219,1.69270288944,3.94490432739 --11.6052856445,1.69170320034,3.90551137924 --11.5902786255,1.68670380116,3.85809445381 --11.5932693481,1.68570411205,3.81869959831 --11.606259346,1.68570411205,3.78129410744 --11.5882558823,1.68170452118,3.75509023666 --11.5832490921,1.67870485783,3.71268773079 --11.5892391205,1.67770504951,3.67328166962 --11.4462471008,1.65270876884,3.58481860161 --11.45723629,1.65270876884,3.54842162132 --11.446228981,1.64870917797,3.505017519 --11.4372205734,1.64570963383,3.46160578728 --11.4242181778,1.64271020889,3.43840837479 --11.4452075958,1.64370977879,3.40501213074 --11.4162015915,1.6377106905,3.35559177399 --11.4311914444,1.63871049881,3.32019090652 --11.4341831207,1.63671052456,3.28179240227 --11.418176651,1.63271105289,3.23738265038 --11.4161720276,1.63171124458,3.21718144417 --11.4191637039,1.63071119785,3.17878079414 --11.4131565094,1.62771141529,3.13737201691 --11.4131479263,1.62671148777,3.09796714783 --11.4201383591,1.62571108341,3.06056475639 --11.4031324387,1.62171173096,3.01716017723 --11.4071235657,1.62071144581,2.97976374626 --11.4051198959,1.6197116375,2.95854902267 --11.394112587,1.6157118082,2.91714715958 --11.3761062622,1.61171245575,2.87373948097 --11.399096489,1.61371135712,2.84134721756 --11.3720903397,1.60771226883,2.79492688179 --11.3870820999,1.60871148109,2.76053261757 --11.3970718384,1.60871088505,2.72412896156 --11.3610725403,1.6027122736,2.69591474533 --11.3790626526,1.60371124744,2.66252374649 --11.4090518951,1.60770952702,2.6311275959 --11.4240436554,1.60870850086,2.59673404694 --11.4730319977,1.6147056818,2.5693423748 --11.4970226288,1.61670410633,2.53695344925 --11.5280122757,1.62070202827,2.50556135178 --11.5520076752,1.62370061874,2.492374897 --11.5849971771,1.62769830227,2.46098184586 --11.4829978943,1.61070287228,2.39954018593 --11.4879903793,1.60970199108,2.36213684082 --11.5379800797,1.61669874191,2.3347530365 --11.7239589691,1.64468789101,2.33642435074 --11.7449502945,1.64668571949,2.30203080177 --11.7799444199,1.65168333054,2.28984236717 --11.8029356003,1.6536809206,2.25544762611 --11.8509263992,1.66067707539,2.22606301308 --11.8739175797,1.66267466545,2.19167113304 --11.908908844,1.66667127609,2.15928149223 --11.9369010925,1.66966843605,2.12589478493 --11.9798955917,1.67666506767,2.11471295357 --11.9848890305,1.67566347122,2.0763130188 --11.595908165,1.61368644238,1.96374213696 --11.568903923,1.60868704319,1.92032361031 --11.2859134674,1.56370413303,1.83180594444 --11.4458990097,1.58769285679,1.82347381115 --11.6228818893,1.61467993259,1.81613874435 --11.2128982544,1.54970645905,1.70856559277 --11.3028898239,1.5636998415,1.7054015398 --11.2838850021,1.55970025063,1.66498613358 --11.2858781815,1.5586990118,1.62858450413 --11.2738733292,1.55569899082,1.59017920494 --11.2788658142,1.55569756031,1.55377268791 --11.2588605881,1.55169785023,1.51436448097 --11.2838535309,1.55469489098,1.48096573353 --11.2888498306,1.55569398403,1.46377015114 --11.3518419266,1.56468808651,1.43639552593 --11.3258371353,1.55968880653,1.39598178864 --11.312830925,1.55668842793,1.35757374763 --11.3198251724,1.55768668652,1.32116508484 --11.3928155899,1.56767952442,1.29480028152 --11.2268209457,1.54169201851,1.25452387333 --11.242814064,1.54368937016,1.22012543678 --11.3088054657,1.55268275738,1.19174802303 --11.2908000946,1.5496827364,1.15333926678 --11.2027978897,1.53568863869,1.10690033436 --11.234790802,1.53968453407,1.0745112896 --11.2007875443,1.53368592262,1.03408753872 --11.238781929,1.53968191147,1.01989853382 --11.2277774811,1.53768146038,0.983500361443 --11.2237730026,1.53568017483,0.947096288204 --11.1727685928,1.52768325806,0.905666828156 --11.183763504,1.52868056297,0.870261192322 --11.167757988,1.52568042278,0.83285009861 --11.138753891,1.52068150043,0.794433653355 --11.1427507401,1.52068030834,0.777237057686 --11.1337461472,1.51967954636,0.740829825401 --11.366736412,1.55465567112,0.724532067776 --11.3027324677,1.54465985298,0.683099985123 --11.240729332,1.53466403484,0.641662240028 --11.3397226334,1.54965233803,0.61330717802 --11.1327209473,1.51767098904,0.562812447548 --11.1377182007,1.51766955853,0.545615851879 --11.1897134781,1.52566230297,0.513233363628 --11.1647090912,1.52066290379,0.475816965103 --11.1917037964,1.52465820312,0.441421508789 --11.3536987305,1.54963922501,0.415095597506 --11.2426948547,1.53264868259,0.372636556625 --11.1716909409,1.52065396309,0.333199620247 --11.2026891708,1.52564954758,0.317013442516 --11.1836843491,1.5226495266,0.280602574348 --11.1716804504,1.52064859867,0.244190141559 --11.200676918,1.52464318275,0.209800809622 --11.1936721802,1.52364170551,0.174399644136 --11.1176681519,1.51164793968,0.135956645012 --11.1146640778,1.51064586639,0.100552454591 --11.1426620483,1.51564157009,0.0833603069186 --11.1146583557,1.51064240932,0.0479520373046 --11.1366548538,1.51363754272,0.0125529654324 --11.0776500702,1.50464212894,-0.023877684027 --11.0946455002,1.50763750076,-0.0592783205211 --11.1286430359,1.51263105869,-0.0936602205038 --11.0946388245,1.50763261318,-0.129076912999 --11.1766386032,1.51962149143,-0.146241128445 --11.1626358032,1.51762056351,-0.181649282575 --11.1466312408,1.51561975479,-0.21807102859 --11.1786289215,1.52061295509,-0.253457993269 --11.1626253128,1.51761233807,-0.288868546486 --11.187623024,1.5216063261,-0.324256628752 --11.2976226807,1.53858923912,-0.361613273621 --11.1966180801,1.52360081673,-0.377859205008 --11.2596178055,1.53258979321,-0.414229333401 --11.161611557,1.51759958267,-0.448686271906 --11.1336078644,1.51360023022,-0.483098179102 --11.2376089096,1.52958345413,-0.521454513073 --11.1506032944,1.51659190655,-0.554902553558 --11.1566019058,1.51758956909,-0.573104560375 --11.178601265,1.52158343792,-0.608487784863 --11.195599556,1.52357792854,-0.644885003567 --11.1765966415,1.52157723904,-0.680304050446 --11.0935897827,1.50858569145,-0.711741328239 --11.1395893097,1.51657605171,-0.749121665955 --11.076584816,1.50658166409,-0.781556427479 --11.0795841217,1.50757944584,-0.799761474133 --11.1665859222,1.52056360245,-0.840125977993 --11.2455873489,1.53354883194,-0.879482150078 --11.2565870285,1.53554344177,-0.916890025139 --11.2565851212,1.53553986549,-0.952287495136 --11.24858284,1.53453743458,-0.987694978714 --11.2295808792,1.53253662586,-1.02210593224 --11.3765888214,1.55551254749,-1.05124270916 --11.2575798035,1.53752660751,-1.07870495319 --11.1815748215,1.52653443813,-1.10813903809 --11.1865730286,1.52752995491,-1.14454257488 --11.2135744095,1.53152179718,-1.18293607235 --11.2615766525,1.53951025009,-1.22331881523 --11.2545757294,1.53950738907,-1.25872552395 --11.252573967,1.53950572014,-1.27592098713 --11.2745752335,1.54349803925,-1.31431591511 --11.3185777664,1.55048680305,-1.35469579697 --11.3585805893,1.5574760437,-1.39507901669 --11.3255777359,1.55247700214,-1.42850339413 --11.2835731506,1.54647958279,-1.45992279053 --11.2565717697,1.54347968102,-1.49334144592 --11.2735729218,1.54647469521,-1.51353657246 --11.3655805588,1.56045472622,-1.56089746952 --11.241569519,1.54247117043,-1.58235967159 --11.2655715942,1.54646253586,-1.62175321579 --11.4765911102,1.58042180538,-1.68404364586 --11.3955841064,1.56843090057,-1.71149706841 --11.7556171417,1.62436318398,-1.79571592808 --11.9156332016,1.64933252335,-1.83583343029 --11.4265880585,1.57441318035,-1.80748534203 --11.3625831604,1.56541955471,-1.83592569828 --11.4165887833,1.5744048357,-1.88029921055 --11.5286006927,1.59337961674,-1.93364465237 --11.567606926,1.60036718845,-1.97702920437 --11.4585962296,1.58338189125,-1.99748289585 --11.4535961151,1.58338010311,-2.01569104195 --11.4595985413,1.58537364006,-2.05409312248 --11.4676008224,1.58736670017,-2.09248995781 --11.4485998154,1.58536481857,-2.12690448761 --11.4816055298,1.59135305882,-2.17029619217 --11.5116109848,1.59734177589,-2.21268129349 --11.548617363,1.60332894325,-2.25706839561 --11.6896352768,1.62629902363,-2.30019140244 --11.6066274643,1.61430907249,-2.3236374855 --11.5926275253,1.61330592632,-2.35904693604 --11.8346614838,1.65225231647,-2.44232821465 --11.7596549988,1.64126086235,-2.46676683426 --11.6866474152,1.63126909733,-2.49120545387 --11.7156534195,1.63626015186,-2.51639533043 --11.6856527328,1.63225972652,-2.54881072044 --11.7106590271,1.63724815845,-2.59320950508 --11.7186632156,1.6402400732,-2.63360929489 --11.688662529,1.63623988628,-2.66602635384 --11.8566894531,1.66419863701,-2.73933434486 --11.8176879883,1.65919983387,-2.77076220512 --11.8326931,1.66219317913,-2.7939593792 --11.774687767,1.65419852734,-2.82039046288 --11.9117116928,1.67716264725,-2.88971924782 --11.8967142105,1.67615866661,-2.92613124847 --11.8767156601,1.67415571213,-2.96154737473 --11.9837369919,1.69212543964,-3.02589273453 --12.1077613831,1.71309089661,-3.09523129463 --12.1877765656,1.7260696888,-3.13438987732 --12.0597610474,1.7080899477,-3.1448636055 --12.0867710114,1.71307635307,-3.19124507904 --12.1657896042,1.72705078125,-3.25160837173 --12.1968002319,1.73403596878,-3.29999136925 --12.2258119583,1.740021348,-3.34837770462 --12.4918632507,1.78295266628,-3.4576356411 --12.5158748627,1.78893852234,-3.50602459908 --12.4258623123,1.77595472336,-3.50427961349 --12.4578752518,1.78193867207,-3.55466270447 --12.3848695755,1.77194678783,-3.5781109333 --13.2270298004,1.90774083138,-3.84805369377 --13.235039711,1.91072905064,-3.89444375038 --13.2060432434,1.9077256918,-3.93186426163 --13.1540384293,1.90073287487,-3.94009518623 --13.1200418472,1.89673089981,-3.97551608086 --13.0720415115,1.89073216915,-4.00694561005 --13.0850543976,1.89471888542,-4.05533838272 --13.0590581894,1.89271485806,-4.09275484085 --13.0530662537,1.89370596409,-4.13616228104 --13.0120687485,1.88870561123,-4.16959238052 --12.9850683212,1.88570702076,-4.18380689621 --12.9370679855,1.87970852852,-4.2142367363 --13.1041126251,1.90865623951,-4.31054639816 --13.1741380692,1.92162775993,-4.37790966034 --13.2171583176,1.9316059351,-4.43728780746 --13.4002075195,1.9625480175,-4.54158735275 --13.4662332535,1.97551977634,-4.60894632339 --13.6222734451,2.0014731884,-4.68406915665 --13.6742973328,2.01244783401,-4.74843883514 --13.6943149567,2.01743078232,-4.80282688141 --13.8693666458,2.0483725071,-4.90912818909 --14.0154132843,2.07432103157,-5.00744915009 --14.110449791,2.09228253365,-5.08980131149 --14.1794805527,2.10525083542,-5.16416883469 --14.2274990082,2.11423134804,-5.20533752441 --14.3405408859,2.13518714905,-5.2956776619 --14.3755645752,2.14316391945,-5.35905838013 --14.3875827789,2.14814662933,-5.41445207596 --14.3245830536,2.14015007019,-5.44288635254 --14.3546066284,2.14812755585,-5.50527191162 --14.3596248627,2.15211176872,-5.5596780777 --14.3576316833,2.15310525894,-5.5838727951 --14.3256406784,2.15009975433,-5.62429666519 --14.3476629257,2.1560792923,-5.68368005753 --14.3266744614,2.15607047081,-5.72809743881 --14.3386936188,2.1610519886,-5.78549814224 --14.3327102661,2.16303920746,-5.83489942551 --14.336728096,2.16602301598,-5.88930225372 --14.3397378922,2.1680150032,-5.9154920578 --14.3347539902,2.17000126839,-5.96690320969 --14.3237695694,2.17098927498,-6.01531219482 --14.3237867355,2.17397403717,-6.0677113533 --14.2977981567,2.17296648026,-6.11012983322 --14.3418283463,2.18293809891,-6.18050098419 --14.3418464661,2.18592238426,-6.23390388489 --14.3428573608,2.18791437149,-6.26110601425 --14.3458757401,2.19189786911,-6.31550359726 --14.337893486,2.19388413429,-6.36591148376 --14.3399133682,2.19686770439,-6.42031145096 --14.3389320374,2.19985198975,-6.47371339798 --14.3189458847,2.19984197617,-6.51912784576 --14.311964035,2.20282769203,-6.5705370903 --14.3219776154,2.20581650734,-6.60173034668 --14.2969894409,2.20480799675,-6.64514780045 --14.2930088043,2.20779275894,-6.69755125046 --14.2890281677,2.20977735519,-6.74995326996 --14.3010530472,2.21575689316,-6.81035041809 --14.2960720062,2.21874165535,-6.86275482178 --14.2790880203,2.21872997284,-6.91016864777 --14.2790985107,2.22072172165,-6.93736791611 --14.2891225815,2.22570133209,-6.99676036835 --14.2751407623,2.22668838501,-7.04617595673 --14.2601575851,2.2286760807,-7.09458780289 --14.2551774979,2.23066067696,-7.14698696136 --14.2531995773,2.23464345932,-7.20239543915 --14.2682161331,2.23862957954,-7.23758745193 --14.2802410126,2.24460792542,-7.29897880554 --14.2602577209,2.24459671974,-7.34539318085 --14.2482767105,2.24658274651,-7.3958029747 --14.2382965088,2.24856805801,-7.44721078873 --14.2203140259,2.24955582619,-7.49563074112 --14.2103338242,2.2515411377,-7.54703712463 --14.2133464813,2.2545311451,-7.57623147964 --14.2113704681,2.25751328468,-7.6326379776 --14.2003898621,2.25949835777,-7.6840467453 --14.1924114227,2.26248264313,-7.73644924164 --14.1794319153,2.26446819305,-7.78786563873 --14.1644506454,2.26545476913,-7.83727550507 --14.1654758453,2.27043557167,-7.89467191696 --14.1444807053,2.26843333244,-7.91288995743 --14.1325016022,2.27041864395,-7.96429920197 --14.1115188599,2.27140688896,-8.01071357727 --14.1045417786,2.27438998222,-8.06512069702 --14.1365814209,2.28435850143,-8.14150619507 --14.0815849304,2.27835941315,-8.16893768311 --14.069606781,2.28134393692,-8.22135162354 --14.0666189194,2.28233528137,-8.24855136871 --14.0596427917,2.28631782532,-8.30396175385 --14.0556678772,2.28929948807,-8.36036491394 --14.0466918945,2.29228234291,-8.41477489471 --14.0437173843,2.29626321793,-8.47217750549 --14.0127325058,2.29525470734,-8.5135974884 --14.0017557144,2.29823827744,-8.56700897217 --14.0097732544,2.30222511292,-8.60120201111 --14.0068006516,2.30620551109,-8.65960788727 --13.9908218384,2.30819058418,-8.71001815796 --13.9998550415,2.31416583061,-8.77641868591 --13.9758739471,2.31515407562,-8.82283973694 --13.9799041748,2.3201315403,-8.88523387909 --13.9829359055,2.32610845566,-8.94863796234 --14.0009584427,2.33109021187,-8.99083042145 --14.1180419922,2.35802102089,-9.12516021729 --14.3161621094,2.39791798592,-9.31143760681 --14.3241977692,2.40489172935,-9.37983608246 --14.3052215576,2.40687608719,-9.43225574493 --14.2482271194,2.401876688,-9.45969390869 --14.1862306595,2.39587950706,-9.48313331604 --14.1542310715,2.39188170433,-9.49334907532 --14.1052408218,2.38887882233,-9.52578639984 --14.0512475967,2.38387823105,-9.55422306061 --13.9642715454,2.37886881828,-9.62408256531 --13.9282875061,2.37786078453,-9.6645116806 --13.8822984695,2.37485742569,-9.69694042206 --13.8643054962,2.37385296822,-9.71715450287 --13.8183164597,2.37084960938,-9.749584198 --13.7563180923,2.36485338211,-9.77102470398 --13.7063274384,2.36085128784,-9.80146408081 --13.6503324509,2.35685229301,-9.82690429688 --13.6173496246,2.35584306717,-9.86832904816 --13.5633554459,2.35084366798,-9.89376163483 --13.5313558578,2.34784579277,-9.90398693085 --13.4703588486,2.34284925461,-9.92543315887 --13.4213666916,2.3388478756,-9.95386219025 --13.387383461,2.33783912659,-9.99428939819 --13.3313884735,2.3338406086,-10.0187320709 --13.2803955078,2.32984018326,-10.0451622009 --13.2583999634,2.32783818245,-10.061378479 --13.2084083557,2.32483696938,-10.0898180008 --13.1344032288,2.31684756279,-10.0992670059 --13.121430397,2.31982898712,-10.1546821594 --13.0634346008,2.3148317337,-10.1761236191 --13.0224466324,2.31282663345,-10.2105569839 --12.9664506912,2.30782914162,-10.2319908142 --12.9554624557,2.308822155,-10.2562007904 --12.903468132,2.3048222065,-10.2816400528 --12.8474712372,2.29982495308,-10.3030776978 --12.8234949112,2.30181145668,-10.3505029678 --12.7715005875,2.2978117466,-10.3749389648 --12.7215070724,2.2938117981,-10.4003715515 --12.6925268173,2.29480051994,-10.4437999725 --12.6655292511,2.29280161858,-10.4550189972 --12.6155357361,2.28880143166,-10.4804544449 --12.5725469589,2.2867975235,-10.511888504 --12.5265569687,2.28379535675,-10.5403223038 --12.4865694046,2.28279018402,-10.5737533569 --12.451584816,2.28178238869,-10.6111803055 --12.4115982056,2.28077721596,-10.644613266 --12.3815984726,2.27777981758,-10.6528348923 --12.3476142883,2.27777171135,-10.6902580261 --12.3036251068,2.27476835251,-10.7206954956 --12.2556333542,2.27176737785,-10.7471342087 --12.1696548462,2.26776075363,-10.8069972992 --12.137673378,2.26775145531,-10.8464231491 --12.1026697159,2.26475644112,-10.8506546021 --12.0756921768,2.26574492455,-10.8940753937 --12.0226955414,2.26174664497,-10.915517807 --11.9887132645,2.26173877716,-10.9519376755 --11.9427223206,2.25873661041,-10.9803829193 --11.9047355652,2.25773072243,-11.0138101578 --11.8667497635,2.25772500038,-11.0472383499 --11.8497600555,2.25772070885,-11.0664558411 --11.7987642288,2.25372219086,-11.0878915787 --11.7757892609,2.25570750237,-11.1363172531 --11.7247953415,2.2527089119,-11.1577548981 --11.6908121109,2.25270056725,-11.195183754 --11.6508255005,2.25169563293,-11.2266149521 --11.6228475571,2.25268387794,-11.2700414658 --11.5928468704,2.24968743324,-11.276263237 --11.5598649979,2.25067830086,-11.3146924973 --11.5208787918,2.24967288971,-11.3471231461 --11.4888982773,2.24966335297,-11.3865528107 --11.4439077377,2.24766111374,-11.4139928818 --11.4259376526,2.25164318085,-11.4664087296 --11.3799467087,2.24864196777,-11.4918441772 --11.3579511642,2.24764060974,-11.5060653687 --11.3169651031,2.24663639069,-11.5364999771 --11.2859840393,2.24762630463,-11.5759220123 --11.2419939041,2.24562382698,-11.6033592224 --11.2030086517,2.24461841583,-11.6357927322 --11.1780347824,2.24760437012,-11.6822166443 --11.1240367889,2.24360799789,-11.6996631622 --11.1090478897,2.24460244179,-11.7198734283 --11.0770673752,2.24459266663,-11.759303093 --11.0330781937,2.24359059334,-11.785736084 --11.0041007996,2.24457859993,-11.828163147 --10.9731216431,2.24556803703,-11.8685903549 --10.9271316528,2.24356675148,-11.8940324783 --10.9141435623,2.24455952644,-11.9172468185 --10.876159668,2.2445538044,-11.9496765137 --10.840177536,2.244546175,-11.9851093292 --10.8152036667,2.24753141403,-12.032535553 --10.7682113647,2.24453139305,-12.0549697876 --10.7242221832,2.24352908134,-12.0814065933 --10.7122612,2.24950528145,-12.1438264847 --10.6592645645,2.24550890923,-12.1602697372 --10.6362686157,2.24450850487,-12.1724901199 --10.6233072281,2.25048542023,-12.2329025269 --10.5833215714,2.2494802475,-12.2643404007 --10.5403337479,2.24847722054,-12.2917766571 --10.530374527,2.25445175171,-12.3561878204 --10.4763774872,2.25145626068,-12.371635437 --10.4583873749,2.25145196915,-12.3898544312 --10.4394207001,2.25543284416,-12.444270134 --10.3934297562,2.25343155861,-12.468711853 --10.3584499359,2.25442242622,-12.5061483383 --10.3224697113,2.25541472435,-12.5415802002 --10.3015012741,2.25939631462,-12.5939970016 --10.261516571,2.25839066505,-12.6254339218 --10.2515363693,2.26138019562,-12.6546535492 --10.213552475,2.26137375832,-12.6870822906 --10.1905851364,2.26535582542,-12.7395095825 --10.1686191559,2.26933717728,-12.7929344177 --10.1286344528,2.26933193207,-12.8233652115 --10.0906524658,2.26932477951,-12.8578033447 --10.0626802444,2.27231049538,-12.9032268524 --10.0476932526,2.27330374718,-12.9254426956 --10.0067090988,2.27329874039,-12.9558811188 --9.97573471069,2.2752866745,-12.9983081818 --9.93875408173,2.27627801895,-13.0347480774 --9.9177904129,2.28025794029,-13.0901689529 --9.89182281494,2.28424096107,-13.1405992508 --9.85183906555,2.28423500061,-13.1720333099 --9.82884502411,2.28323435783,-13.1842546463 --9.77785015106,2.28123688698,-13.2017002106 --9.71884727478,2.27624583244,-13.209154129 --9.66885280609,2.27424764633,-13.2275981903 --9.52175140381,2.24632740021,-13.1161108017 --9.36263465881,2.2164182663,-12.9856271744 --9.2115240097,2.18750333786,-12.8641395569 --9.10243034363,2.1645731926,-12.7584257126 --8.97834777832,2.14263796806,-12.670920372 --8.86727905273,2.12369275093,-12.6004095078 --8.80326366425,2.11670994759,-12.5928621292 --8.73224067688,2.10873270035,-12.5763254166 --8.62016677856,2.08879041672,-12.5008134842 --8.53910064697,2.07283997536,-12.4280796051 --8.46807479858,2.06386470795,-12.4075345993 --8.35900211334,2.04492163658,-12.3330221176 --8.23190689087,2.02099466324,-12.2315235138 --8.20493030548,2.02398300171,-12.2719478607 --8.14191150665,2.01700186729,-12.2614049911 --8.06287193298,2.00603485107,-12.2268743515 --8.00285625458,2.00005173683,-12.2193279266 --7.97084474564,1.99606204033,-12.212556839 --7.87578248978,1.98011088371,-12.1510295868 --7.79674100876,1.96914565563,-12.1134977341 --7.7357211113,1.96216475964,-12.1019525528 --7.67069578171,1.9541875124,-12.0844106674 --7.59966230392,1.9452162981,-12.0568742752 --7.58567333221,1.94621109962,-12.0760908127 --7.51563930511,1.93623948097,-12.0485486984 --7.45862340927,1.93125629425,-12.0410003662 --7.38258075714,1.92029082775,-12.0034675598 --7.33257341385,1.91630113125,-12.0069189072 --7.28556919098,1.91330945492,-12.0133619308 --7.22354412079,1.90633153915,-11.9968214035 --7.18051481247,1.89835453033,-11.9680547714 --7.16855859756,1.90632927418,-12.0314779282 --7.15059423447,1.91130983829,-12.0849018097 --7.09457588196,1.90532755852,-12.0753479004 --7.02754259109,1.89735543728,-12.0488119125 --6.96351242065,1.88838136196,-12.0252666473 --6.81636190414,1.85548961163,-11.862786293 --6.82240200043,1.86346483231,-11.9149913788 --6.82747077942,1.87542271614,-12.00639534 --6.73239326477,1.85748064518,-11.9288778305 --6.67737388611,1.85249888897,-11.9183301926 --6.64338493347,1.85249638557,-11.9427614212 --6.60338878632,1.85149896145,-11.9592084885 --6.56439208984,1.85050165653,-11.9746427536 --6.5584154129,1.85448825359,-12.0078582764 --6.5134100914,1.85249686241,-12.0132989883 --6.44136381149,1.84153354168,-11.9717683792 --6.40837669373,1.84252977371,-11.9982023239 --6.36938095093,1.84153211117,-12.0146436691 --6.28531360626,1.82658278942,-11.9491214752 --6.32040214539,1.84352552891,-12.0562982559 --6.27940368652,1.84252953529,-12.0697460175 --6.23640012741,1.84053695202,-12.0771837234 --6.24949026108,1.85648167133,-12.1915893555 --6.1984744072,1.85149741173,-12.1850366592 --6.10638999939,1.83355915546,-12.1005182266 --6.07841205597,1.83654952049,-12.1369504929 --6.10850000381,1.8534938097,-12.2421426773 --5.99237203598,1.82658433914,-12.1086397171 --5.948366642,1.82459282875,-12.1140861511 --5.91537952423,1.82558965683,-12.1395168304 --5.82328939438,1.8066546917,-12.0489969254 --5.81234169006,1.81562519073,-12.1194190979 --5.77434635162,1.8156273365,-12.1358594894 --5.77137756348,1.82060909271,-12.1770687103 --5.68930244446,1.80466413498,-12.1035423279 --5.60221767426,1.78772568703,-12.0190229416 --5.6453704834,1.8156298399,-12.2024021149 --5.54525947571,1.79370832443,-12.0888900757 --5.44414424896,1.77078962326,-11.9703760147 --5.43520212173,1.78075659275,-12.0467967987 --5.46129131317,1.79670035839,-12.1529941559 --5.43331432343,1.79969072342,-12.1894264221 --5.3822927475,1.79470992088,-12.1768770218 --5.38237142563,1.80866396427,-12.2752885818 --5.38445615768,1.82361412048,-12.3807048798 --5.29636144638,1.80468130112,-12.2861852646 --5.2723941803,1.8096653223,-12.3336172104 --5.2433757782,1.80567979813,-12.3188447952 --5.24145507812,1.81963396072,-12.4172620773 --5.19444131851,1.81564843655,-12.4127082825 --5.15544462204,1.81565177441,-12.4271535873 --5.1695599556,1.83558261395,-12.5655584335 --5.08346319199,1.81665086746,-12.4690341949 --5.04747200012,1.81765055656,-12.4894723892 --5.03148269653,1.81864666939,-12.5066976547 --5.0305685997,1.83359670639,-12.6121120453 --4.97854423523,1.82861816883,-12.5955657959 --4.91348981857,1.81765890121,-12.5460271835 --4.87449264526,1.81766271591,-12.559469223 --4.8685708046,1.83061814308,-12.6558876038 --4.84656763077,1.82962334156,-12.6571121216 --4.78952980042,1.82165312767,-12.6265716553 --4.77459049225,1.83162033558,-12.7030000687 --4.72757482529,1.82763576508,-12.6964473724 --4.68156433105,1.82564878464,-12.6949043274 --4.64457178116,1.8256496191,-12.7133436203 --4.59855747223,1.82266449928,-12.7077875137 --4.58758211136,1.82665193081,-12.7400131226 --4.56562805176,1.83362841606,-12.800444603 --4.54768419266,1.84359896183,-12.8708677292 --4.4996676445,1.83961546421,-12.8633260727 --4.46267747879,1.84061515331,-12.883767128 --4.42669010162,1.8416134119,-12.9072093964 --4.37065076828,1.83464407921,-12.8746681213 --4.36468982697,1.8406226635,-12.9218845367 --4.32067966461,1.83863520622,-12.9203252792 --4.27366447449,1.83465087414,-12.9137802124 --4.22664737701,1.83166778088,-12.9052314758 --4.21773386002,1.84561920166,-13.0086536407 --4.1717209816,1.84263372421,-13.0041065216 --4.13473320007,1.84463274479,-13.026553154 --4.11774158478,1.84563016891,-13.040769577 --4.06270360947,1.83866047859,-13.0092334747 --4.01267719269,1.83368313313,-12.990688324 --3.99875330925,1.84564161301,-13.0821094513 --3.97380256653,1.85361742973,-13.1445503235 --3.95185899734,1.86258864403,-13.2139797211 --3.91687774658,1.8655834198,-13.2434215546 --3.90691375732,1.87156450748,-13.286646843 --3.87594676018,1.87655067444,-13.3310890198 --3.83895921707,1.87754929066,-13.3535261154 --3.80398130417,1.88154244423,-13.385972023 --3.75496006012,1.87756240368,-13.3724308014 --3.70493006706,1.87158703804,-13.3498773575 --3.65891695023,1.8686016798,-13.3453330994 --3.64795088768,1.87458443642,-13.3855543137 --3.60895872116,1.87558615208,-13.4029989243 --3.55792713165,1.86961233616,-13.3784542084 --3.53097677231,1.87758862972,-13.4398908615 --3.50001502037,1.88357186317,-13.4893350601 --3.44998502731,1.87759697437,-13.4667863846 --3.42396974564,1.87560987473,-13.4550228119 --3.39802622795,1.8845821619,-13.5234613419 --3.35702681541,1.88358843327,-13.5329027176 --3.31703591347,1.88558995724,-13.5513572693 --3.27603960037,1.88559472561,-13.5638065338 --3.22901749611,1.88161492348,-13.5492534637 --3.1880209446,1.88161981106,-13.5617036819 --3.14301013947,1.87963342667,-13.5591611862 --3.12201070786,1.87963652611,-13.5643882751 --3.08101463318,1.880641222,-13.576839447 --3.03800678253,1.87865281105,-13.5772838593 --2.99700927734,1.87865817547,-13.5887327194 --2.95802164078,1.8806579113,-13.6101827621 --2.90999484062,1.87668120861,-13.5906362534 --2.89100241661,1.87768030167,-13.6028594971 --2.84900212288,1.87768745422,-13.6113128662 --2.80298566818,1.87470459938,-13.6027727127 --2.76198673248,1.87471115589,-13.6122179031 --2.72199440002,1.87571358681,-13.6286668777 --2.67697763443,1.87273073196,-13.6201181412 --2.63497853279,1.87273752689,-13.6295747757 --2.613976717,1.87274217606,-13.6317987442 --2.56996488571,1.8707562685,-13.6282510757 --2.52997255325,1.87175893784,-13.6447000504 --2.48897862434,1.87276291847,-13.6591567993 --2.4439573288,1.86978268623,-13.6456022263 --2.4009513855,1.86879348755,-13.6480579376 --2.36096215248,1.87079453468,-13.6675128937 --2.33794879913,1.86880612373,-13.6577367783 --2.29594659805,1.86781466007,-13.6641893387 --2.25494813919,1.86882126331,-13.6736373901 --2.21194314957,1.867831707,-13.6770954132 --2.16893458366,1.86684417725,-13.6765480042 --2.12793755531,1.86784982681,-13.6879987717 --2.08593273163,1.86686003208,-13.6914482117 --2.06392431259,1.86586880684,-13.6866722107 --2.02092027664,1.86487877369,-13.6911344528 --1.97891354561,1.86388993263,-13.6925811768 --1.93590605259,1.86390209198,-13.6930379868 --1.89692413807,1.86689925194,-13.7194900513 --1.85290467739,1.86391806602,-13.7079391479 --1.81191074848,1.86492216587,-13.7223949432 --1.79292476177,1.86791801453,-13.7406225204 --1.75091731548,1.86692976952,-13.74106884 --1.70891654491,1.86693799496,-13.7485246658 --1.66893184185,1.86993694305,-13.7719802856 --1.6269261837,1.86894774437,-13.7744293213 --1.58492767811,1.86995494366,-13.7838869095 --1.54292595387,1.86996364594,-13.7903423309 --1.52091729641,1.86897265911,-13.7855701447 --1.47891259193,1.8679831028,-13.789021492 --1.43792331219,1.87098491192,-13.8074789047 --1.39490878582,1.86900115013,-13.8009300232 --1.3529073,1.86900985241,-13.8073835373 --1.31292200089,1.87200951576,-13.8298339844 --1.26890039444,1.86902976036,-13.8162899017 --1.2478967905,1.86903584003,-13.8165140152 --1.20690917969,1.87103664875,-13.8369722366 --1.16288566589,1.86805820465,-13.8214263916 --1.12189245224,1.87006247044,-13.8358783722 --1.07888197899,1.8690764904,-13.8333368301 --1.03587245941,1.86809015274,-13.8317956924 --1.01587986946,1.86908984184,-13.8430185318 --0.973875522614,1.86910045147,-13.8464717865 --0.931871175766,1.8691110611,-13.8499231339 --0.88988083601,1.87111389637,-13.8673858643 --0.846860468388,1.86913371086,-13.8548383713 --0.800801515579,1.86117529869,-13.8042974472 --0.756760597229,1.85520648956,-13.7717504501 --0.740846216679,1.86916255951,-13.8599796295 --0.702909827232,1.87913501263,-13.9304294586 --0.656846523285,1.87017905712,-13.8758907318 --0.61484348774,1.87118911743,-13.8803443909 --0.572851419449,1.87319326401,-13.8958034515 --0.531878709793,1.87818646431,-13.9302597046 --0.491938829422,1.88816154003,-13.9967184067 --0.471962571144,1.8911523819,-14.0239429474 --0.431005626917,1.89913702011,-14.0733995438 --0.389034241438,1.90412986279,-14.1088590622 --0.329221010208,1.93303954601,-14.3025560379 --0.286223441362,1.93404710293,-14.3120098114 --0.242215573788,1.93406045437,-14.3114709854 --0.220216333866,1.93506455421,-14.3157024384 --0.176202341914,1.9340814352,-14.3091630936 --0.133211955428,1.93608510494,-14.3256158829 --0.0892061069608,1.9360973835,-14.3270778656 --0.0461974479258,1.93611121178,-14.3255290985 --0.00219061225653,1.93612420559,-14.3259906769 -0.0282017029822,1.93286550045,-13.5021934509 -0.0502051152289,1.93286108971,-13.5023803711 -0.093218959868,1.93385660648,-13.5097446442 -0.137238115072,1.93585467339,-13.5221166611 -0.181237757206,1.93484210968,-13.5154924393 -0.225260823965,1.93684244156,-13.5318622589 -0.269278913736,1.93884003162,-13.5432329178 -0.31329280138,1.93983542919,-13.5506048203 -0.335307478905,1.94183719158,-13.5617866516 -0.379311263561,1.94182693958,-13.5591602325 -0.423330247402,1.94382500648,-13.5715284348 -0.467337936163,1.94381701946,-13.5729017258 -0.512355029583,1.94581389427,-13.5832777023 -0.556365907192,1.94680762291,-13.587647438 -0.57836920023,1.94680333138,-13.5878343582 -0.622383952141,1.9477994442,-13.5962018967 -0.666382551193,1.94678640366,-13.5885782242 -0.710394620895,1.94878077507,-13.5939464569 -0.754393279552,1.94776797295,-13.5863227844 -0.799409329891,1.94976437092,-13.595697403 -0.843422055244,1.95075917244,-13.6020650864 -0.865423381329,1.95075392723,-13.6002521515 -0.909430086613,1.95074546337,-13.6006240845 -0.954447031021,1.9527425766,-13.6109952927 -0.999467015266,1.95574104786,-13.6243648529 -1.04244852066,1.95171928406,-13.5997457504 -1.08645451069,1.95271062851,-13.5991182327 -1.13146722317,1.95370531082,-13.6054916382 -1.15346860886,1.95370018482,-13.6036787033 -1.19747745991,1.95469307899,-13.6060476303 -1.24046909809,1.95267689228,-13.5914239883 -1.28548002243,1.95367062092,-13.5957984924 -1.32948279381,1.95366024971,-13.5921726227 -1.37449300289,1.95565354824,-13.5955476761 -1.41849768162,1.95564436913,-13.593919754 -1.44251990318,1.95865023136,-13.6131019592 -1.48551487923,1.95763599873,-13.601474762 -1.53052866459,1.95963144302,-13.6088447571 -1.57452464104,1.95861744881,-13.5982265472 -1.61650681496,1.95559632778,-13.5736083984 -1.66051280499,1.95658779144,-13.5729780197 -1.70451653004,1.9565782547,-13.5703516006 -1.72551107407,1.9555696249,-13.5615386963 -1.77152407169,1.95756459236,-13.5679178238 -1.81351602077,1.95554900169,-13.5532894135 -1.85650920868,1.95453381538,-13.5396680832 -1.90051209927,1.95452392101,-13.5360431671 -1.94451141357,1.95451176167,-13.5284233093 -1.96953558922,1.9585185051,-13.5496025085 -2.01152849197,1.95650362968,-13.5359745026 -2.0545232296,1.95648908615,-13.523352623 -2.09752011299,1.95547616482,-13.5137290955 -2.13950848579,1.95345878601,-13.4951095581 -2.17546153069,1.94642353058,-13.440495491 -2.22147655487,1.94841969013,-13.4488706589 -2.24146723747,1.94640946388,-13.4360589981 -2.28244900703,1.94338870049,-13.4104452133 -2.32846426964,1.94638502598,-13.4188194275 -2.38152289391,1.95540356636,-13.4721736908 -2.43256402016,1.9624131918,-13.5075407028 -2.47455263138,1.96039605141,-13.4889230728 -2.51955986023,1.96138834953,-13.4892978668 -2.53552746773,1.95636630058,-13.452495575 -2.57952857018,1.95635569096,-13.4468736649 -2.61046504974,1.94631254673,-13.3742666245 -2.64140057564,1.93626892567,-13.3006649017 -2.6713373661,1.92622613907,-13.2280569077 -2.71232938766,1.92521107197,-13.2124347687 -2.7472910881,1.91918122768,-13.1658239365 -2.76226115227,1.91416072845,-13.1310214996 -2.80023884773,1.91113865376,-13.1004076004 -2.8331952095,1.90410602093,-13.0477972031 -2.87217783928,1.90108656883,-13.0221853256 -2.90915560722,1.89806485176,-12.991566658 -2.94814014435,1.89504635334,-12.9679536819 -2.98411083221,1.89102089405,-12.9293470383 -3.00109505653,1.88800799847,-12.909538269 -3.03405690193,1.88197851181,-12.8619289398 -3.07304477692,1.87996184826,-12.8413124084 -3.11002492905,1.87694144249,-12.8126983643 -3.14499568939,1.87291646004,-12.7740917206 -3.18298339844,1.8709000349,-12.7534704208 -3.22197055817,1.86888313293,-12.7318601608 -3.2349421978,1.86486411095,-12.6980543137 -3.2719244957,1.86184501648,-12.6714420319 -3.30991148949,1.85982835293,-12.6498260498 -3.34689497948,1.85780978203,-12.624212265 -3.38387823105,1.85479152203,-12.5986003876 -3.42186546326,1.85277485847,-12.5769872665 -3.43885374069,1.85176408291,-12.5601787567 -3.46780967712,1.84473264217,-12.5055770874 -3.50278973579,1.84171271324,-12.4759626389 -3.53776788712,1.83769178391,-12.444355011 -3.5747551918,1.8356757164,-12.4227390289 -3.61174201965,1.834659338,-12.4001245499 -3.64271092415,1.82963418961,-12.3585147858 -3.66070270538,1.8286254406,-12.3457098007 -3.69768953323,1.82660901546,-12.3230991364 -3.73066496849,1.82258725166,-12.2884893417 -3.76665019989,1.82057023048,-12.2638788223 -3.80363917351,1.81855499744,-12.2432661057 -3.83461093903,1.81453180313,-12.2046546936 -3.86959457397,1.8125140667,-12.1780443192 -3.88858938217,1.8115067482,-12.1682415009 -3.91956186295,1.8074836731,-12.1296348572 -3.95454692841,1.80546700954,-12.1050205231 -3.98752593994,1.80244731903,-12.0734119415 -4.02351284027,1.80043113232,-12.0498056412 -4.05749607086,1.79841375351,-12.023191452 -4.09548950195,1.79740071297,-12.0065822601 -4.1074681282,1.79438626766,-11.9797763824 -4.14345693588,1.79237127304,-11.9581670761 -4.18345689774,1.7933614254,-11.9485521317 -4.21042203903,1.78733575344,-11.9019498825 -4.2474155426,1.78732311726,-11.8853340149 -4.28741598129,1.78731381893,-11.8767175674 -4.32140016556,1.78529691696,-11.850110054 -4.34240198135,1.78629279137,-11.8473043442 -4.3653588295,1.77926337719,-11.7907085419 -4.39934635162,1.77724850178,-11.7680912018 -4.43633937836,1.7772359848,-11.7514772415 -4.47834444046,1.77822852135,-11.7468662262 -4.51333332062,1.7772141695,-11.7252540588 -4.52431297302,1.77420032024,-11.6984500885 -4.56731939316,1.77519381046,-11.6958398819 -4.5842666626,1.76716041565,-11.6282444 -4.61524772644,1.76414251328,-11.5976362228 -4.65324306488,1.76413118839,-11.5830278397 -4.67921209335,1.75910806656,-11.5394268036 -4.7162065506,1.75909602642,-11.522819519 -4.7291932106,1.75708544254,-11.5030117035 -4.76618719101,1.75607347488,-11.4864053726 -4.80117797852,1.75506031513,-11.4667930603 -4.83516693115,1.75404620171,-11.4441843033 -4.86414480209,1.75102710724,-11.4095811844 -4.89612960815,1.74901139736,-11.3829727173 -4.93011951447,1.74799776077,-11.3613624573 -4.94110155106,1.74498534203,-11.3365631104 -4.97108221054,1.74196779728,-11.3049612045 -5.01008319855,1.74295902252,-11.2953462601 -5.04307031631,1.74194443226,-11.2707414627 -5.07806253433,1.74093222618,-11.2521295547 -5.11606121063,1.74192249775,-11.2395191193 -5.14704561234,1.73990666866,-11.2119121552 -5.16003370285,1.73789691925,-11.1931085587 -5.19201803207,1.73588132858,-11.165512085 -5.23001813889,1.73687255383,-11.1548919678 -5.26000118256,1.7348562479,-11.1252880096 -5.29599571228,1.73484504223,-11.1086788177 -5.33098888397,1.73383331299,-11.0900697708 -5.37199354172,1.73582649231,-11.0844545364 -5.38598299026,1.73481762409,-11.067653656 -5.41997432709,1.7338051796,-11.0470457077 -5.46198034286,1.73579919338,-11.043428421 -5.49597215652,1.73478674889,-11.0228204727 -5.53096532822,1.73477506638,-11.0042123795 -5.57096719742,1.73676729202,-10.995598793 -5.54785728455,1.71571147442,-10.8600492477 -5.62095499039,1.73574912548,-10.965177536 -5.65494537354,1.73473632336,-10.9435749054 -5.68593215942,1.73372232914,-10.917965889 -5.73995923996,1.73972511292,-10.9373369217 -5.76192855835,1.73470306396,-10.890753746 -5.79992866516,1.73569488525,-10.8801326752 -5.81391954422,1.73468673229,-10.8643302917 -5.86894655228,1.7416895628,-10.8837041855 -5.89392328262,1.73767125607,-10.8461055756 -5.92991924286,1.73866081238,-10.8294963837 -5.96591424942,1.73865032196,-10.8128871918 -5.99690008163,1.73663580418,-10.7852916718 -6.03389883041,1.73762691021,-10.7726688385 -6.06191205978,1.7416280508,-10.7818584442 -6.09690570831,1.74161696434,-10.763250351 -6.12689208984,1.73960256577,-10.7356472015 -6.16288709641,1.73959231377,-10.719037056 -6.19988393784,1.74058246613,-10.7034301758 -6.22986984253,1.73856830597,-10.67582798 -6.2668671608,1.73955881596,-10.6612148285 -6.2868680954,1.74055504799,-10.6564083099 -6.32386445999,1.74154531956,-10.6408004761 -6.3648686409,1.74353837967,-10.6331834793 -6.39585542679,1.74252474308,-10.606584549 -6.43485546112,1.74351644516,-10.5949707031 -6.46984910965,1.7435053587,-10.5753688812 -6.50985097885,1.74549782276,-10.5657510757 -6.52284193039,1.74448990822,-10.548951149 -6.56785058975,1.74748516083,-10.5473299026 -6.59783697128,1.74647152424,-10.5197296143 -6.643846035,1.74946665764,-10.5181159973 -6.67183017731,1.74845218658,-10.4875154495 -6.71183109283,1.7494443655,-10.4769020081 -6.72782659531,1.74943828583,-10.4650993347 -6.7668261528,1.75142991543,-10.4524869919 -6.80482435226,1.75242078304,-10.4378786087 -6.8418211937,1.75341153145,-10.4222660065 -6.87881755829,1.75440168381,-10.4056606293 -6.91481304169,1.75439167023,-10.3880519867 -6.94480037689,1.75337851048,-10.360452652 -6.96780443192,1.75537621975,-10.3596420288 -7.00680351257,1.7563675642,-10.3460330963 -7.03979587555,1.75635647774,-10.32442379 -7.07779359818,1.75834715366,-10.3088178635 -7.11579179764,1.75933837891,-10.2942056656 -7.15478992462,1.76032948494,-10.2796001434 -7.17977237701,1.75831460953,-10.2459993362 -7.25479030609,1.7653093338,-10.2485733032 -7.29078578949,1.76629972458,-10.2309598923 -7.34480333328,1.77129793167,-10.2383375168 -7.35977220535,1.76627802849,-10.1887550354 -7.39877080917,1.76826941967,-10.1741466522 -7.43977165222,1.77026164532,-10.1625347137 -7.45777082443,1.7712572813,-10.1547222137 -7.48875951767,1.77024483681,-10.1281251907 -7.52976036072,1.77223718166,-10.1165122986 -7.56575536728,1.77322745323,-10.0979032516 -7.61376476288,1.77722251415,-10.0952863693 -7.65376329422,1.77921402454,-10.0806818008 -7.6687579155,1.77820813656,-10.0678758621 -7.70375156403,1.77919781208,-10.0472707748 -7.7437505722,1.78118932247,-10.0326652527 -7.78575229645,1.78318166733,-10.0210552216 -7.82074594498,1.78417146206,-10.0004482269 -7.85874319077,1.78516244888,-9.98383808136 -7.90875339508,1.79015827179,-9.98321437836 -7.93175554276,1.79115474224,-9.9784154892 -7.98677062988,1.79715240002,-9.9837884903 -8.01776027679,1.79714035988,-9.95718765259 -8.06576728821,1.80113494396,-9.95256996155 -8.11577606201,1.80513000488,-9.94995212555 -8.15277099609,1.80612015724,-9.93034744263 -8.19376945496,1.80811178684,-9.91574001312 -8.22878646851,1.81311333179,-9.92791366577 -8.26478004456,1.81410336494,-9.90730762482 -8.32079410553,1.82010018826,-9.91068553925 -8.35478496552,1.82008886337,-9.88609027863 -8.37176132202,1.81707239151,-9.84249782562 -8.41876602173,1.82006621361,-9.83488178253 -8.2735824585,1.77799487114,-9.59544658661 -8.07437038422,1.72691762447,-9.32583808899 -8.09635257721,1.72490417957,-9.2902507782 -8.13335227966,1.7258964777,-9.27463340759 -8.14432525635,1.72187995911,-9.22705078125 -8.12827301025,1.71085464954,-9.14749622345 -8.15125846863,1.70884251595,-9.11489963531 -8.16923999786,1.70682871342,-9.0763092041 -8.17522621155,1.70482063293,-9.05252456665 -8.20221614838,1.70380985737,-9.02492427826 -8.2151927948,1.69979500771,-8.98133659363 -8.24918937683,1.70078623295,-8.96073722839 -8.26717090607,1.69877302647,-8.92314434052 -8.27414226532,1.69375658035,-8.87256813049 -8.30113315582,1.69274604321,-8.84497070312 -8.31612873077,1.69274115562,-8.83217525482 -8.32210063934,1.68772482872,-8.7815952301 -8.34208488464,1.68571293354,-8.74700069427 -8.36307048798,1.68470096588,-8.71241378784 -8.38005256653,1.68168830872,-8.67482185364 -8.38202190399,1.67567133904,-8.62025165558 -8.39401626587,1.67566609383,-8.60545063019 -8.39898872375,1.67065036297,-8.55487537384 -8.41497039795,1.6676377058,-8.51628780365 -8.43795871735,1.66662716866,-8.48569107056 -8.44093132019,1.66061151028,-8.43411445618 -8.47192573547,1.66160285473,-8.41052150726 -8.49091053009,1.65959143639,-8.37592983246 -8.48489189148,1.65558207035,-8.34314441681 -8.50687885284,1.6545715332,-8.3115530014 -8.52486515045,1.65256011486,-8.27596378326 -8.53784561157,1.6495475769,-8.2353811264 -8.5578327179,1.64753711224,-8.20278549194 -8.57681846619,1.64652585983,-8.16720581055 -8.58479595184,1.6425126791,-8.12262248993 -8.5967912674,1.641507864,-8.10782814026 -8.61878108978,1.64149808884,-8.07723140717 -8.62976074219,1.63748574257,-8.03564929962 -8.64974880219,1.63647556305,-8.00305747986 -8.66973686218,1.63546550274,-7.97046613693 -8.67871665955,1.63145315647,-7.92788124084 -8.6907119751,1.63144850731,-7.91308832169 -8.7046957016,1.62843751907,-7.8754992485 -8.71267604828,1.62542521954,-7.83191919327 -8.72966194153,1.62341475487,-7.79633617401 -8.74664783478,1.62140464783,-7.76174592972 -8.76763820648,1.62039518356,-7.73015832901 -8.77861976624,1.6173838377,-7.68957948685 -8.79361915588,1.61838018894,-7.67877388 -8.80560112,1.61536931992,-7.63919496536 -8.81558418274,1.61235845089,-7.59960317612 -8.83457279205,1.61134874821,-7.56602239609 -8.85156059265,1.60933923721,-7.53242921829 -8.86054229736,1.60632812977,-7.49085140228 -8.88053226471,1.60531914234,-7.4592628479 -8.89052677155,1.60531485081,-7.44445943832 -8.89850902557,1.60130381584,-7.40188694 -8.92150115967,1.6012955904,-7.37329387665 -8.93548679352,1.59928584099,-7.33671092987 -8.93946743011,1.5952745676,-7.29213237762 -8.95845794678,1.59426605701,-7.26054096222 -8.97244358063,1.59225642681,-7.22396183014 -8.97143268585,1.59025061131,-7.20016765594 -8.99042224884,1.58924221992,-7.16857814789 -9.0094127655,1.58823382854,-7.13698863983 -9.02540111542,1.5862249136,-7.10240793228 -8.36397171021,1.45111203194,-6.51537895203 -8.38396644592,1.45110547543,-6.48779344559 -8.41096496582,1.45210015774,-6.46718883514 -8.75816631317,1.51814687252,-6.72412109375 -9.08434295654,1.57718443871,-6.9402756691 -9.10333442688,1.57717657089,-6.90968132019 -9.12632751465,1.57716917992,-6.88109493256 -9.13831424713,1.57516038418,-6.84451150894 -9.16230869293,1.57515323162,-6.81692266464 -9.16229915619,1.57314813137,-6.79413509369 -9.1752872467,1.57113981247,-6.75855112076 -9.19727993011,1.57113265991,-6.72995996475 -9.20826816559,1.5691242218,-6.69337368011 -9.21725463867,1.56711530685,-6.65479469299 -9.23724651337,1.56610822678,-6.62520170212 -9.25623893738,1.56610095501,-6.59461212158 -9.25722980499,1.5640963316,-6.57282543182 -9.263215065,1.56108748913,-6.53225040436 -9.29421329498,1.56308174133,-6.51065063477 -9.29819774628,1.55907297134,-6.4690747261 -9.32719516754,1.56106698513,-6.44548177719 -9.32917881012,1.55705809593,-6.40290498734 -9.34016799927,1.55505049229,-6.36731767654 -9.34316062927,1.55404603481,-6.34653806686 -9.36515522003,1.55403971672,-6.3189406395 -9.36814022064,1.55103135109,-6.27736520767 -9.38213062286,1.5500241518,-6.24377918243 -9.4071264267,1.55101835728,-6.21818208694 -9.42011737823,1.54901099205,-6.18360090256 -9.42510318756,1.54600334167,-6.14402151108 -9.43910217285,1.54700028896,-6.13123178482 -9.44108772278,1.54399251938,-6.09064674377 -9.44407367706,1.540984869,-6.05006885529 -9.46106529236,1.53997826576,-6.01848506927 -9.46405124664,1.53697061539,-5.97791004181 -9.45803356171,1.53196227551,-5.93134403229 -9.4310131073,1.52495622635,-5.89257764816 -9.30093669891,1.49793791771,-5.766102314 -9.29091739655,1.49292981625,-5.7175450325 -9.33092212677,1.49692606926,-5.7029337883 -9.34791660309,1.49592041969,-5.67334127426 -9.38992214203,1.50091660023,-5.65873861313 -9.38390636444,1.49590933323,-5.61416816711 -9.45193004608,1.50691092014,-5.63633012772 -9.50994300842,1.51390826702,-5.63171100616 -9.55094718933,1.51790428162,-5.61610507965 -9.55193519592,1.51489758492,-5.57553195953 -9.56192493439,1.51289153099,-5.5409488678 -9.58192157745,1.5138862133,-5.5123591423 -9.57290458679,1.50887918472,-5.46678638458 -9.56489467621,1.50587534904,-5.44101285934 -9.58889198303,1.50687038898,-5.41442584991 -9.59788322449,1.5048648119,-5.37984132767 -9.60687446594,1.50385916233,-5.34525680542 -9.61586666107,1.50185358524,-5.31067276001 -9.60484981537,1.49684679508,-5.26312017441 -9.61484241486,1.49584150314,-5.2295331955 -9.55981349945,1.48483598232,-5.1787815094 -9.54479694366,1.47882938385,-5.13022565842 -9.54978752136,1.47682404518,-5.0936498642 -9.46074008942,1.45781457424,-5.00513839722 -9.38770103455,1.44180607796,-4.92562294006 -9.50673770905,1.45980608463,-4.95296144485 -9.4467086792,1.44780111313,-4.90121412277 -9.56874656677,1.46680116653,-4.92954921722 -9.55973148346,1.46179568768,-4.8859834671 -9.51770591736,1.4517891407,-4.82543611526 -9.45767402649,1.43878233433,-4.75491142273 -9.44666004181,1.43477725983,-4.71134567261 -9.41163825989,1.42577171326,-4.65579319 -9.32260131836,1.4087665081,-4.59007787704 -9.24356365204,1.39276015759,-4.51255750656 -9.21854686737,1.38575530052,-4.46300411224 -9.12950706482,1.36774909496,-4.38149356842 -9.05347251892,1.35174357891,-4.30697727203 -9.01845359802,1.34373939037,-4.25442361832 -9.08246898651,1.35173749924,-4.25080871582 -8.86138820648,1.31273090839,-4.1231842041 -8.80636405945,1.30172681808,-4.06165075302 -8.8243637085,1.3017244339,-4.03705596924 -8.72432422638,1.28271996975,-3.95455431938 -8.73632240295,1.28271758556,-3.92598152161 -8.6883020401,1.27171444893,-3.87043213844 -8.68529605865,1.26971209049,-3.83585906029 -8.51323699951,1.23870885372,-3.73720955849 -8.47221946716,1.22970628738,-3.68566513062 -8.4862203598,1.23070478439,-3.66106700897 -8.54023361206,1.23770332336,-3.65345883369 -8.42619419098,1.21570086479,-3.56897068024 -8.27114200592,1.18769848347,-3.46750330925 -8.25313472748,1.18369781971,-3.44373106956 -8.16410541534,1.16669619083,-3.37321901321 -8.20211410522,1.17169523239,-3.35961675644 -8.17610454559,1.16569423676,-3.31805562973 -8.10908222198,1.15269339085,-3.25852942467 -8.02905654907,1.13669276237,-3.19401192665 -8.11608028412,1.14969193935,-3.20137858391 -8.04205799103,1.1366918087,-3.15464782715 -7.99804353714,1.12769150734,-3.1070959568 -7.92802286148,1.11369168758,-3.04856991768 -7.89701318741,1.1066917181,-3.0070130825 -7.77497816086,1.08569264412,-2.92753243446 -7.77597856522,1.08369278908,-2.89995312691 -7.72496414185,1.07469332218,-2.8652009964 -7.73596763611,1.07469344139,-2.84161901474 -7.73296642303,1.07269370556,-2.81303787231 -7.70195817947,1.06569457054,-2.7724916935 -7.69495677948,1.06269514561,-2.74192452431 -7.61993837357,1.0496969223,-2.68540024757 -7.64894628525,1.05269694328,-2.66979718208 -7.62594127655,1.04769778252,-2.6470310688 -7.73697042465,1.06469607353,-2.66237068176 -7.82699346542,1.07769477367,-2.66873121262 -7.59393644333,1.03870069981,-2.55432105064 -7.48391056061,1.01870429516,-2.48682594299 -7.46090650558,1.01370596886,-2.45226359367 -7.4549074173,1.01170742512,-2.42369484901 -7.45890855789,1.01170790195,-2.41289067268 -7.42590284348,1.00471007824,-2.37434911728 -7.38189506531,0.996712684631,-2.33378958702 -7.37589597702,0.993714332581,-2.3052303791 -7.3668961525,0.990716099739,-2.27665781975 -7.33189105988,0.983718812466,-2.23910665512 -7.33789539337,0.983720302582,-2.21553015709 -7.30588960648,0.977722227573,-2.19275355339 -7.32689714432,0.979723155499,-2.17416882515 -7.28889226913,0.972726345062,-2.13661599159 -7.21587944031,0.95973098278,-2.0880856514 -7.23988771439,0.962731957436,-2.07148551941 -7.27789974213,0.967732489109,-2.05789899826 -7.20588636398,0.955736458302,-2.02315211296 -7.21889257431,0.956737995148,-2.00256824493 -7.18989038467,0.950741410255,-1.96901190281 -7.20589733124,0.951742947102,-1.94942605495 -7.13688707352,0.939748227596,-1.90488278866 -7.13489151001,0.938750743866,-1.879322052 -7.10188913345,0.93175470829,-1.84576308727 -7.09388971329,0.92975628376,-1.8319709301 -7.06788921356,0.924760043621,-1.80041384697 -7.06289291382,0.923762977123,-1.77484726906 -7.06289768219,0.922765612602,-1.75126874447 -7.05089998245,0.919768810272,-1.72469258308 -7.0279006958,0.914772748947,-1.69512498379 -7.00390148163,0.909776866436,-1.66457426548 -6.9929022789,0.907778918743,-1.64979541302 -6.9779047966,0.90478259325,-1.62321567535 -7.01491641998,0.909783422947,-1.609618783 -6.97891521454,0.90278840065,-1.5770637989 -6.94991588593,0.896793186665,-1.54650592804 -6.93191862106,0.893797338009,-1.51894104481 -6.93592500687,0.893800139427,-1.49735665321 -6.99193716049,0.9017983675,-1.49953877926 -6.94593524933,0.893804430962,-1.46499562263 -6.93193864822,0.890808463097,-1.43941617012 -6.89693927765,0.883814036846,-1.40787017345 -6.88894414902,0.881817936897,-1.38330030441 -6.89395141602,0.881821036339,-1.36172437668 -6.9159579277,0.884821176529,-1.35591495037 -6.8589553833,0.875828504562,-1.32037425041 -6.84796047211,0.872832715511,-1.29580020905 -6.83196401596,0.869837343693,-1.27022874355 -6.84097242355,0.86984038353,-1.24965298176 -6.82597637177,0.86684513092,-1.22408866882 -6.81898260117,0.865849256516,-1.20051562786 -6.81698560715,0.864851176739,-1.18971610069 -6.80799102783,0.862855732441,-1.16515767574 -6.77999448776,0.857861638069,-1.137596488 -6.7820019722,0.856865286827,-1.11602079868 -6.79601049423,0.858868062496,-1.09742534161 -6.77901554108,0.855873346329,-1.07186710835 -6.76102018356,0.851878583431,-1.04728972912 -6.77102518082,0.853879749775,-1.03849160671 -6.76703214645,0.851884067059,-1.01591980457 -6.7770409584,0.852887332439,-0.996331393719 -6.7730474472,0.851891696453,-0.973760426044 -6.80605888367,0.856893062592,-0.958158016205 -6.76706218719,0.849900484085,-0.929607629776 -6.77307033539,0.849904119968,-0.909027516842 -6.74707126617,0.845908343792,-0.894248068333 -6.83008813858,0.857905507088,-0.886615514755 -6.76408863068,0.846915364265,-0.854083299637 -6.77309703827,0.84791880846,-0.834491431713 -6.78410673141,0.849922299385,-0.813922703266 -6.80711698532,0.852924525738,-0.796323239803 -6.72111225128,0.838934421539,-0.772589564323 -6.76712465286,0.845934689045,-0.757985472679 -6.74613046646,0.841940820217,-0.734405100346 -6.90415430069,0.865930914879,-0.73474085331 -7.26519536972,0.920901656151,-0.763914942741 -7.02518081665,0.883928179741,-0.708491146564 -6.72616243362,0.836960911751,-0.646120071411 -7.02619314194,0.882934689522,-0.675130784512 -6.73217535019,0.836967170238,-0.61573857069 -6.67817926407,0.828976929188,-0.58818936348 -6.66318655014,0.825983345509,-0.564637303352 -6.7992067337,0.846974670887,-0.559968531132 -11.2555704117,1.53354108334,-1.05360269547 -6.69021511078,0.828994750977,-0.505870103836 -6.68521928787,0.827997863293,-0.494099676609 -6.77223443985,0.840993762016,-0.483447253704 -6.70323848724,0.830005645752,-0.454917818308 -6.71124792099,0.831009805202,-0.434343934059 -6.72525787354,0.833013236523,-0.414757370949 -6.67026329041,0.824023723602,-0.389202535152 -6.78828001022,0.842016518116,-0.37856182456 -6.6652765274,0.823031663895,-0.357833772898 -6.68128681183,0.82503503561,-0.338250160217 -6.68229579926,0.825039982796,-0.317669063807 -6.65230369568,0.820048391819,-0.294117718935 -6.65031290054,0.820053637028,-0.273535847664 -6.65732336044,0.821058213711,-0.252962201834 -6.6643280983,0.82106000185,-0.243168339133 -7.03235721588,0.878024637699,-0.248349919915 -6.93736076355,0.863039970398,-0.220820441842 -6.71035909653,0.828070402145,-0.184397563338 -6.78037166595,0.838067770004,-0.167775645852 -6.64737558365,0.818087995052,-0.139280229807 -6.98439979553,0.869055092335,-0.136495247483 -6.63138961792,0.815097689629,-0.107916094363 -6.83340740204,0.846079945564,-0.0972119197249 -7.00842428207,0.873065173626,-0.0835348442197 -6.67342042923,0.821109056473,-0.0481549017131 -6.61142873764,0.811121821404,-0.0246249064803 -6.96145057678,0.865086257458,-0.0168289709836 -7.09045934677,0.8850736022,-0.0109520731494 -6.81846046448,0.843110918999,0.0194596759975 -6.77546882629,0.836121559143,0.0420060418546 -6.75847864151,0.834129095078,0.0635699108243 -6.80248975754,0.840129256248,0.0831811651587 -6.73549795151,0.830142915249,0.10571307689 -7.03751516342,0.87611168623,0.121482014656 -9.69058418274,1.28279197216,0.0938531830907 -9.68758869171,1.28179585934,0.123434104025 -9.68359470367,1.28180015087,0.154000684619 -9.67359924316,1.2798050642,0.183577552438 -9.67960548401,1.28080809116,0.214148432016 -9.67961120605,1.28081178665,0.24373023212 -9.67561721802,1.27981626987,0.274295479059 -9.67761993408,1.28081786633,0.289087802172 -6.58558988571,0.807212769985,0.290839880705 -6.58860015869,0.807218313217,0.311415731907 -6.58861112595,0.807224273682,0.331989377737 -6.57662200928,0.806231558323,0.351571917534 -6.56763315201,0.804238796234,0.37213537097 -6.62163829803,0.813234627247,0.382969468832 -6.58064937592,0.807245969772,0.402519345284 -6.57266044617,0.805252850056,0.422103315592 -6.55767154694,0.803261101246,0.442657500505 -6.56268215179,0.804266273975,0.4622566998 -6.55669355392,0.803273260593,0.482820928097 -6.60070466995,0.810273349285,0.504436671734 -6.54071092606,0.801284432411,0.512186408043 -6.54772186279,0.80228972435,0.532768666744 -6.96372938156,0.866239666939,0.573600053787 -7.04773950577,0.879234433174,0.600216627121 -6.69475412369,0.825288116932,0.601597368717 -6.55776691437,0.804313004017,0.614096224308 -6.5327796936,0.801322877407,0.633643627167 -6.53978490829,0.80232489109,0.643453001976 -6.52579641342,0.800333142281,0.663018465042 -6.52680873871,0.801339387894,0.683592438698 -6.62981796265,0.817331373692,0.711236178875 -6.51183223724,0.79935413599,0.722745239735 -6.566842556,0.8073528409,0.747356534004 -6.56785440445,0.808359086514,0.767934262753 -6.51586151123,0.800369560719,0.773693799973 -6.49587392807,0.797378838062,0.792259454727 -6.53288507462,0.803380072117,0.815859615803 -6.57489538193,0.810380280018,0.839477181435 -6.47791004181,0.795400857925,0.850989222527 -9.61582374573,1.27895748615,1.18633031845 -6.46692895889,0.794412314892,0.880347192287 -6.47094106674,0.795418262482,0.900928676128 -6.62994670868,0.820401489735,0.937615871429 -6.46596479416,0.79543197155,0.940098047256 -6.61297178268,0.81841725111,0.977750718594 -6.42599105835,0.790451228619,0.97622436285 -6.41600418091,0.788459300995,0.994804143906 -6.43000984192,0.791460573673,1.00660133362 -6.44002151489,0.793465912342,1.02818262577 -6.42503499985,0.791474938393,1.0467466116 -6.42804765701,0.79248124361,1.06732726097 -6.43105983734,0.793487548828,1.08790850639 -6.83805179596,0.856432974339,1.16373682022 -6.70907020569,0.837459087372,1.16723752022 -6.44209051132,0.795502841473,1.13986670971 -6.42310380936,0.793512582779,1.15743398666 -6.41811704636,0.793520212173,1.17700910568 -6.40712976456,0.791528701782,1.19558191299 -6.41214227676,0.793534755707,1.21617329121 -6.88512802124,0.867469131947,1.31201732159 -6.43815994263,0.797540962696,1.25056159496 -6.3921751976,0.791554927826,1.26312077045 -6.40818786621,0.794559657574,1.28669607639 -6.40820074081,0.794566690922,1.30727052689 -6.39721345901,0.793575108051,1.32486152649 -6.40722608566,0.795580685139,1.34743714333 -6.40523910522,0.796587884426,1.36702501774 -6.39824581146,0.795592427254,1.37581384182 -6.39425945282,0.795600414276,1.3963726759 -6.3962726593,0.796607136726,1.41695773602 -6.41328430176,0.799611508846,1.44054925442 -6.61128282547,0.831587076187,1.49924826622 -6.41731071472,0.801625132561,1.48270499706 -6.39732503891,0.798635482788,1.49927318096 -6.39533185959,0.79863935709,1.50906336308 -6.40334415436,0.800644993782,1.53066027164 -6.4083571434,0.802651405334,1.55224430561 -6.39837121964,0.801660180092,1.57081758976 -6.39538526535,0.801668047905,1.59138405323 -6.39139842987,0.801675856113,1.61096584797 -6.41141033173,0.805680036545,1.63654780388 -6.39241838455,0.802686691284,1.64233398438 -6.37443304062,0.800696849823,1.65890514851 -6.39444494247,0.80470097065,1.6844907999 -6.38945960999,0.804709076881,1.70406889915 -6.39647245407,0.806715250015,1.72665059566 -6.51647520065,0.826702833176,1.77629888058 -6.3854932785,0.805728018284,1.75501990318 -6.42050361633,0.812729656696,1.78461694717 -6.39251947403,0.80874145031,1.79819107056 -6.4275302887,0.814743280411,1.82877445221 -6.38054800034,0.808758378029,1.83733963966 -6.37556266785,0.80876660347,1.85691928864 -6.3925743103,0.811771214008,1.88250625134 -6.38858175278,0.811775684357,1.89228832722 -6.37659692764,0.810785055161,1.90986835957 -6.37361097336,0.811793148518,1.93044137955 -6.39062309265,0.814797699451,1.95603442192 -6.38863706589,0.81580555439,1.97661542892 -6.38365125656,0.815813779831,1.99619817734 -6.37066030502,0.813820123672,2.00396513939 -6.35967493057,0.812829375267,2.02154970169 -6.38968610764,0.818832039833,2.05213356018 -6.36470270157,0.815843701363,2.06571006775 -6.34971809387,0.814853727818,2.08228898048 -6.32673454285,0.811865329742,2.09685444832 -6.31675004959,0.810874819756,2.11542344093 -6.46874046326,0.835852503777,2.17229652405 -6.45675563812,0.834862291813,2.1908621788 -6.46676826477,0.83786803484,2.21545505524 -6.44978475571,0.835878670216,2.23202633858 -6.39380502701,0.827896237373,2.23656821251 -6.24783658981,0.805929243565,2.21107625961 -6.69479799271,0.878859102726,2.37789011002 -6.63481235504,0.869873344898,2.3696501255 -6.50984144211,0.850902915001,2.35116291046 -6.45586204529,0.842920184135,2.3557100296 -6.64785289764,0.874894082546,2.44239592552 -6.66886472702,0.879898250103,2.47297763824 -6.76186752319,0.895889818668,2.52859568596 -9.49454498291,1.34041714668,3.50548052788 -9.49755001068,1.34141993523,3.52228045464 -6.4729385376,0.851959943771,2.48441004753 -6.64793109894,0.881936967373,2.57006788254 -6.83792114258,0.913910984993,2.66174483299 -6.41398954391,0.845994114876,2.53111243248 -6.82395076752,0.913928806782,2.70390796661 -6.39001464844,0.844010055065,2.55547976494 -6.36203241348,0.841022849083,2.56705451012 -6.6580080986,0.889977991581,2.70176959038 -6.7180147171,0.900975227356,2.74837517738 -6.68003416061,0.896989643574,2.75694799423 -6.81403064728,0.919973731041,2.8335776329 -6.70105981827,0.903001785278,2.81311130524 -6.53608942032,0.87603533268,2.75982642174 -6.40312290192,0.856067359447,2.73034262657 -6.41313648224,0.85907381773,2.75791621208 -6.42514944077,0.862079501152,2.7855079174 -6.37717103958,0.855096280575,2.78906488419 -6.36318826675,0.855107009411,2.80663299561 -6.34220552444,0.852118968964,2.82119846344 -6.42220211029,0.866108417511,2.86602854729 -6.43321466446,0.870114386082,2.89362120628 -6.35224151611,0.858137071133,2.88217163086 -6.35225629807,0.859145402908,2.90574550629 -6.33527374268,0.858156502247,2.92132425308 -6.36628484726,0.864159286022,2.95890498161 -6.34329605103,0.861167609692,2.9606821537 -6.36530733109,0.86617153883,2.99328231812 -6.45430898666,0.883163452148,3.05689764023 -6.35433912277,0.868189930916,3.03543972969 -6.36035346985,0.870197117329,3.06201910973 -6.37036752701,0.873203575611,3.0905995369 -6.34738540649,0.871215820312,3.10318112373 -6.60035467148,0.915173351765,3.23307204247 -6.40639972687,0.883217632771,3.16756010056 -6.3554224968,0.876235187054,3.16712784767 -6.35143899918,0.877244412899,3.18969917297 -6.33145713806,0.875256419182,3.2042696476 -6.33947086334,0.878263115883,3.23186039925 -6.32948064804,0.878269314766,3.23963689804 -6.32549619675,0.878278195858,3.26122713089 -6.32551193237,0.880286633968,3.28580236435 -6.36552095413,0.889287590981,3.33039355278 -6.32354307175,0.883303880692,3.33395576477 -6.32755804062,0.886311531067,3.36053681374 -6.32457399368,0.88732033968,3.38312411308 -6.36357593536,0.89531737566,3.41592144966 -6.34259414673,0.893329620361,3.42950081825 -6.40259933472,0.905326604843,3.48511242867 -6.3536233902,0.898344278336,3.48467230797 -6.33164262772,0.896356940269,3.4982419014 -6.33265829086,0.898365199566,3.52382278442 -6.32267522812,0.898375511169,3.54340267181 -6.34667921066,0.903375267982,3.56919741631 -6.3256983757,0.901387691498,3.5827755928 -6.30971622467,0.901399195194,3.59935069084 -6.32772922516,0.906404435635,3.63493275642 -6.28775215149,0.901420652866,3.63849401474 -6.27077102661,0.90043258667,3.6550579071 -6.28078508377,0.903439104557,3.68565034866 -6.2787938118,0.904443800449,3.69743800163 -6.2758102417,0.905453264713,3.72200679779 -6.28682374954,0.909459531307,3.75359869003 -6.3068356514,0.915464103222,3.79019999504 -6.27285814285,0.9114792943,3.79676270485 -6.31486606598,0.920479893684,3.84735894203 -6.30687570572,0.920485854149,3.85614061356 -6.40787315369,0.940474927425,3.94176650047 -6.26791477203,0.917510569096,3.88529086113 -6.25293397903,0.917522251606,3.90286183357 -6.25794887543,0.920530021191,3.93244123459 -6.27196216583,0.924535930157,3.96703314781 -6.31497049332,0.934536516666,4.02062129974 -6.38696479797,0.948526620865,4.07745265961 -6.41797494888,0.956529378891,4.12404346466 -6.3739991188,0.950546383858,4.12361526489 -6.34302091599,0.947561383247,4.13217496872 -6.51100492477,0.980537176132,4.26483392715 -6.43903541565,0.969560205936,4.24837064743 -6.26108551025,0.939603805542,4.16287565231 -6.27309131622,0.942605674267,4.18368005753 -6.2421131134,0.939620554447,4.19124698639 -6.22813224792,0.939632177353,4.20981884003 -6.30313396454,0.955626308918,4.28642988205 -6.49811267853,0.993596971035,4.44308710098 -6.24817752838,0.950654923916,4.30656147003 -6.29118537903,0.960655272007,4.3631606102 -6.30619049072,0.96465665102,4.38696289062 -6.26121616364,0.958674550056,4.38551807404 -6.26423168182,0.961682915688,4.41609668732 -6.2442522049,0.960695683956,4.43067312241 -6.25026750565,0.964703381062,4.46325683594 -6.25028324127,0.966711997986,4.49085330963 -6.23029565811,0.964720487595,4.49163103104 -6.2233133316,0.965730786324,4.5152130127 -6.29331636429,0.981725931168,4.59381532669 -6.2873339653,0.982736229897,4.61938619614 -6.21336603165,0.971759915352,4.59593772888 -6.24437570572,0.979762792587,4.64752960205 -6.25338220596,0.982765316963,4.66832923889 -6.22640419006,0.980779588223,4.67790555954 -6.27241182327,0.991779506207,4.74149894714 -6.22743797302,0.986797690392,4.73905229568 -6.21645641327,0.986808896065,4.76063108444 -6.25146579742,0.996810853481,4.8162317276 -6.21748924255,0.992826521397,4.82080221176 -6.48144245148,1.04477846622,5.03469324112 -6.20351743698,0.99484282732,4.85517454147 -6.23352861404,1.002846241,4.9097495079 -6.24254274368,1.00785326958,4.94634771347 -6.2395606041,1.00986325741,4.97591400146 -6.44153404236,1.05183172226,5.16357755661 -6.24659252167,1.01787984371,5.04308605194 -6.26159763336,1.02188158035,5.07087755203 -6.21662378311,1.01589953899,5.06644678116 -6.30562162399,1.03689074516,5.16806936264 -6.23165512085,1.02491521835,5.14260053635 -6.25366687775,1.0329195261,5.19120311737 -6.21769142151,1.02893590927,5.193775177 -6.19871234894,1.02794885635,5.21034955978 -6.27270555496,1.04493892193,5.28815317154 -6.22273302078,1.03795826435,5.27971458435 -6.30473136902,1.05695056915,5.37933778763 -6.23476409912,1.04697394371,5.35389566422 -6.22778272629,1.04798471928,5.38146781921 -6.21880149841,1.04999577999,5.40704488754 -6.24780368805,1.05799436569,5.44785070419 -6.21882724762,1.05500972271,5.45741128922 -6.22584295273,1.06001758575,5.49699401855 -6.22686004639,1.06402659416,5.53157567978 -6.27086734772,1.07602715492,5.60416793823 -6.27388334274,1.08003544807,5.63976716995 -6.21991348267,1.0730561018,5.62831020355 -6.301902771,1.09104394913,5.71714067459 -6.26192903519,1.08706128597,5.7167057991 -6.31293487549,1.10106027126,5.79730558395 -6.29295682907,1.10007369518,5.81487846375 -6.27797651291,1.10108602047,5.83645868301 -6.2530002594,1.09910058975,5.85002279282 -6.24202013016,1.1011121273,5.87560129166 -6.31301212311,1.11810219288,5.95842218399 -6.24704456329,1.1081250906,5.93397712708 -6.23306465149,1.10813713074,5.95656061172 -6.24308013916,1.11514472961,6.00313568115 -6.20910549164,1.11116111279,6.00770521164 -6.19912481308,1.11317241192,6.03428983688 -6.22812700272,1.12117135525,6.08108139038 -6.20914888382,1.12118458748,6.09965991974 -6.21516466141,1.12619268894,6.14224815369 -6.20018577576,1.12720537186,6.16581726074 -6.19020557404,1.1292167902,6.19339799881 -6.24620962143,1.14521503448,6.28699111938 -6.24822664261,1.1502238512,6.32658147812 -6.24823570251,1.15222871304,6.34636688232 -6.22325897217,1.15124320984,6.35994195938 -6.21627807617,1.15425407887,6.39152383804 -6.20729827881,1.15626561642,6.42209529877 -6.24730587006,1.16926681995,6.50169372559 -6.30330944061,1.18626487255,6.59829902649 -6.19035434723,1.16529762745,6.52283668518 -6.21735668182,1.17429685593,6.57063674927 -6.23437023163,1.1823028326,6.62822723389 -6.20439529419,1.18031859398,6.63779449463 -6.26339912415,1.19831633568,6.74138784409 -6.28241157532,1.20632171631,6.80198478699 -6.25743532181,1.20533657074,6.81755256653 -6.20045804977,1.19535303116,6.77732610703 -6.2184715271,1.20435893536,6.83890771866 -6.1665019989,1.19737923145,6.82447338104 -6.19751214981,1.20938253403,6.90006685257 -6.22252416611,1.21938717365,6.97064971924 -6.27552843094,1.23638570309,7.07125616074 -6.32753324509,1.25338470936,7.17285203934 -6.30054950714,1.25039517879,7.16562700272 -6.78744602203,1.36730468273,7.75536870956 -6.76846837997,1.36831843853,7.78293466568 -6.75348997116,1.37033092976,7.81351661682 -6.73451185226,1.37134456635,7.84009313583 -6.71153497696,1.3723590374,7.86266422272 -6.71254396439,1.37536358833,7.88845300674 -6.68556833267,1.3743789196,7.90602684021 -6.65959215164,1.37439393997,7.92460203171 -6.64761304855,1.3774061203,7.96017742157 -6.61963748932,1.37642145157,7.97575759888 -6.60665893555,1.37943410873,8.01132488251 -6.59267997742,1.38144648075,8.0439081192 -6.57369375229,1.38045537472,8.04668903351 -6.55771589279,1.38246834278,8.07726955414 -6.54273700714,1.38448119164,8.10984420776 -6.51976156235,1.38549590111,8.13341236115 -6.51278114319,1.39050710201,8.17599201202 -3.44958949089,0.648151159286,4.42153501511 -3.44960832596,0.651160657406,4.44813299179 -3.42362594604,0.647171616554,4.43089103699 -3.43364214897,0.653179228306,4.47048902512 -6.40190839767,1.39758396149,8.32265663147 -6.37993240356,1.39859819412,8.34723186493 -6.36295461655,1.40061175823,8.3788061142 -6.34397792816,1.40262567997,8.40837478638 -6.348985672,1.4076294899,8.44117164612 -6.31801176071,1.40564572811,8.45474147797 -6.30703306198,1.40965783596,8.49431991577 -6.29405450821,1.41367042065,8.53090286255 -6.2620806694,1.41168677807,8.5424785614 -6.24410438538,1.41470062733,8.57504177094 -6.24411296844,1.41770553589,8.60183906555 -6.20714044571,1.41472291946,8.60641479492 -6.18916416168,1.41773664951,8.63798713684 -6.16918754578,1.41875076294,8.66656303406 -6.14221286774,1.41876637936,8.68613147736 -6.12723493576,1.42177915573,8.72071743011 -6.10725927353,1.42379367352,8.75128078461 -6.09427165985,1.42380106449,8.76007938385 -6.07629442215,1.42681467533,8.79165840149 -6.05631875992,1.42882907391,8.822224617 -6.03534269333,1.43084335327,8.84980297089 -6.02136516571,1.43385624886,8.88837814331 -6.00738716125,1.43786895275,8.92596244812 -5.99040079117,1.4368776083,8.93074798584 -5.96542692184,1.43789279461,8.95431518555 -5.94445037842,1.43990707397,8.9818983078 -5.91447734833,1.43892335892,8.99746894836 -5.89050245285,1.44093835354,9.02204322815 -5.87052631378,1.44295239449,9.0516242981 -5.84655189514,1.44396746159,9.07619857788 -5.83756303787,1.44497430325,9.09298801422 -5.80259180069,1.44399178028,9.10155391693 -5.78361558914,1.44600582123,9.13412952423 -5.76064062119,1.44802057743,9.15970993042 -5.73566627502,1.44903564453,9.18229007721 -5.71069192886,1.45005106926,9.20685768127 -5.68471765518,1.45106637478,9.22744083405 -5.67173099518,1.45107448101,9.24021625519 -5.64375686646,1.45108997822,9.25680446625 -5.61778306961,1.45210564137,9.27937698364 -5.58980941772,1.4521214962,9.29795265198 -5.56383562088,1.45313692093,9.3205242157 -5.53486251831,1.45315301418,9.33710289001 -5.51288795471,1.45516777039,9.36667537689 -5.49990129471,1.45617568493,9.37845897675 -5.47492694855,1.45719099045,9.40203762054 -5.44395446777,1.45720744133,9.41561412811 -5.41898012161,1.45822274685,9.44018745422 -5.39200687408,1.45923852921,9.46076488495 -5.36103487015,1.45825505257,9.47533512115 -5.34904766083,1.45926260948,9.48812484741 -5.32007455826,1.45927870274,9.50470542908 -5.29310131073,1.4602946043,9.52627849579 -5.26812744141,1.46230983734,9.55085468292 -5.23615598679,1.46132671833,9.56342697144 -5.21318149567,1.46334159374,9.59200286865 -5.17921066284,1.46235883236,9.60057735443 -5.17422103882,1.46536493301,9.62637042999 -5.14324903488,1.46538150311,9.63994789124 -5.11427640915,1.46539759636,9.65752410889 -5.09330224991,1.46841216087,9.6910982132 -5.06432962418,1.46942853928,9.70967006683 -5.03435754776,1.46944487095,9.72524833679 -5.00738477707,1.47046077251,9.74782085419 -4.99639701843,1.4714679718,9.76261520386 -4.9694237709,1.47248375416,9.78419399261 -5.04742145538,1.50947809219,10.0127906799 -3.80179476738,1.09774398804,7.62906551361 -3.75082945824,1.08876478672,7.58762788773 -3.72085809708,1.08678126335,7.58719778061 -3.68287873268,1.07779407501,7.53898763657 -3.64590907097,1.07281184196,7.52256298065 -3.60794019699,1.06783008575,7.50512838364 -3.57097029686,1.0628477335,7.48671197891 -3.5399992466,1.05986428261,7.48228359222 -3.51102733612,1.05788016319,7.47986936569 -3.48005628586,1.05589675903,7.47444438934 -3.46007204056,1.05290603638,7.4622297287 -3.42810153961,1.04992306232,7.45480060577 -3.40012955666,1.0479388237,7.45438146591 -3.36815905571,1.04495573044,7.44595575333 -3.33818745613,1.04197192192,7.4405374527 -3.31421422958,1.04198694229,7.44812107086 -3.28724265099,1.04000306129,7.45168542862 -3.2752559185,1.04001045227,7.4544839859 -3.24228549004,1.03702735901,7.44206237793 -3.21531367302,1.03504300117,7.44363737106 -3.19234061241,1.03505802155,7.45421409607 -3.16136956215,1.03207468987,7.44579172134 -3.14939332008,1.03708732128,7.48137521744 -3.13740730286,1.03709495068,7.48615980148 -3.11443352699,1.03710961342,7.49474954605 -3.08646178246,1.035125494,7.49332618713 -3.06248903275,1.03414070606,7.50090694427 -3.02751970291,1.03015804291,7.48248004913 -3.00754618645,1.03117263317,7.50105190277 -2.984572649,1.03118729591,7.5096411705 -2.96958780289,1.03019571304,7.50742053986 -2.94561481476,1.0302106142,7.51400613785 -2.91364431381,1.026227355,7.50058698654 -2.88667321205,1.02524340153,7.50215387344 -2.85570240021,1.02225995064,7.49073410034 -2.79277205467,1.02029824257,7.50067949295 -2.66691064835,1.01637470722,7.51558971405 -2.63993954659,1.01439082623,7.51615524292 -2.62095570564,1.01139986515,7.49994182587 -2.6009812355,1.01241374016,7.51453924179 -2.57600951195,1.01242923737,7.51911258698 -2.54903793335,1.01044487953,7.51669168472 -2.52906441689,1.0124591589,7.53427457809 -2.50509214401,1.01247441769,7.541847229 -2.49410533905,1.01248145103,7.54564905167 -2.474132061,1.01449584961,7.56522321701 -2.45415830612,1.01550996304,7.58280944824 -2.42818689346,1.01452565193,7.58438253403 -2.41521120071,1.02053844929,7.62496566772 -2.34730267525,1.02758765221,7.69651842117 -2.34432458878,1.03959870338,7.77409601212 -2.32635045052,1.04261255264,7.80167913437 -2.30637717247,1.0446267128,7.82326078415 -2.28940320015,1.04964053631,7.85683679581 -2.28741383553,1.05464601517,7.89463233948 -2.26843976974,1.05765998363,7.92021846771 -2.2494661808,1.0606739521,7.94580602646 -2.33250260353,1.1516879797,8.53458690643 -2.30353164673,1.14970397949,8.53217029572 -2.28554725647,1.14671254158,8.51696681976 -2.23758268356,1.13473260403,8.44653224945 -2.18079519272,1.26384079456,9.32361698151 -2.17081904411,1.27685308456,9.41319942474 -2.16184258461,1.29086530209,9.50977993011 -2.16985034943,1.30686867237,9.61257743835 -2.15587496758,1.31788170338,9.68916511536 -2.15689539909,1.33989179134,9.83775043488 -2.1609146595,1.36490106583,10.0003471375 -2.16093564034,1.38791155815,10.1539297104 -2.15995597839,1.40992164612,10.3015270233 -2.18096017838,1.43792271614,10.4823217392 -2.16698479652,1.45193564892,10.5779094696 -2.13401556015,1.45195245743,10.5864877701 -2.10604500771,1.45596826077,10.6190690994 -2.29902720451,1.6639509201,11.9632873535 -2.26405835152,1.66596806049,11.9828701019 -2.24407482147,1.66497707367,11.9786624908 -2.20510721207,1.6629948616,11.9752473831 -2.16913890839,1.66501224041,11.9918251038 -2.1321709156,1.66502964497,12.0004081726 -2.09720230103,1.66804671288,12.021987915 -2.06023454666,1.66906416416,12.0335664749 -2.04524922371,1.67207229137,12.0583600998 -2.01028108597,1.67508947849,12.0839366913 -1.97231352329,1.67510712147,12.0895166397 -1.94534230232,1.68512248993,12.1601037979 -1.90937387943,1.68713951111,12.1766901016 -1.89040052891,1.70615363121,12.3072719574 -1.85143327713,1.70517122746,12.3088550568 -1.84344637394,1.71817803383,12.3896436691 -1.80447864532,1.71719574928,12.3892326355 -1.76551175117,1.71721363068,12.3988056183 -1.72054648399,1.71123242378,12.3603868484 -1.68157923222,1.71025013924,12.3639678955 -1.64061260223,1.7082682848,12.3525495529 -1.60364449024,1.70928549767,12.3651380539 -1.58266162872,1.70829463005,12.3599233627 -1.54069542885,1.70431292057,12.3385047913 -1.50272798538,1.70533049107,12.3510837555 -1.46176147461,1.70234835148,12.3356666565 -1.42079472542,1.69936645031,12.3162527084 -1.38282728195,1.70038378239,12.3278331757 -1.34485960007,1.70040118694,12.3354187012 -1.32187747955,1.69641077518,12.3102016449 -1.28390991688,1.69642806053,12.3157892227 -1.24494302273,1.69644570351,12.3193683624 -1.20697534084,1.69746303558,12.3269538879 -1.16800820827,1.69648051262,12.3245391846 -1.12904119492,1.69649803638,12.3251209259 -1.10805797577,1.69350707531,12.3069133759 -1.07009088993,1.69552445412,12.3224916458 -1.03012430668,1.69354224205,12.3130712509 -0.992156386375,1.69255924225,12.3136634827 -0.953189373016,1.6925766468,12.3122463226 -0.91522192955,1.69359397888,12.3208312988 -0.875255644321,1.69261169434,12.317404747 -0.856271982193,1.69362044334,12.3241958618 -0.818304359913,1.69363749027,12.3287849426 -0.778337657452,1.69065499306,12.3113679886 -0.739370405674,1.68867230415,12.3009557724 -0.700403869152,1.69068980217,12.3125295639 -0.662436246872,1.6907068491,12.3171186447 -0.642453014851,1.68971574306,12.3079080582 -0.604485630989,1.69073271751,12.3194942474 -0.565518498421,1.68975007534,12.312078476 -0.526551783085,1.6897674799,12.3176574707 -0.488584339619,1.69178438187,12.3292446136 -0.444619089365,1.67180275917,12.1978235245 -0.410650223494,1.68781876564,12.3074159622 -0.390667170286,1.68782758713,12.3052005768 -0.352699875832,1.69184470177,12.329785347 -0.31373244524,1.68486154079,12.2853784561 -0.274765849113,1.6868789196,12.3019542694 -0.236798375845,1.6898958683,12.3175430298 -0.197831302881,1.68491280079,12.2901296616 -0.158864662051,1.68793010712,12.3087072372 -0.139880746603,1.68593847752,12.2945051193 -0.101913273335,1.69095528126,12.3300933838 -0.0629464313388,1.69097232819,12.3276748657 -0.0239795390517,1.68298947811,12.2782583237 --0.00599461421371,1.67300271988,11.3269300461 --0.0419622696936,1.67101931572,11.3125095367 --0.0769307240844,1.66703557968,11.2860984802 --0.0949145257473,1.66704380512,11.2858886719 --0.129882931709,1.66505992413,11.2694768906 --0.165850535035,1.66507649422,11.2720565796 --0.200819075108,1.66609251499,11.2756471634 --0.235787451267,1.6641087532,11.2642354965 --0.271754920483,1.66312527657,11.2558116913 --0.305723935366,1.66014099121,11.2344074249 --0.324707210064,1.66414952278,11.257191658 --0.359675437212,1.66216552258,11.24177742 --0.394644021988,1.66218149662,11.2463693619 --0.429612338543,1.66219758987,11.2389574051 --0.465579986572,1.66221392155,11.2425374985 --0.500548243523,1.66123008728,11.2331237793 --0.535516560078,1.6602460146,11.2247095108 --0.554500043392,1.66425442696,11.2454986572 --0.58946865797,1.66527020931,11.2490921021 --0.623437285423,1.66128599644,11.2236804962 --0.660404801369,1.66530227661,11.246263504 --0.695372819901,1.66331839561,11.231844902 --0.73034119606,1.66233420372,11.2254323959 --0.766309201717,1.66435039043,11.2330188751 --0.783293426037,1.66235816479,11.2218122482 --0.818261861801,1.66237401962,11.2184009552 --0.852230727673,1.66138958931,11.2039928436 --0.890197694302,1.6654061079,11.2275724411 --0.925166070461,1.66442191601,11.221159935 --0.960134387016,1.66443777084,11.2137460709 --0.97811871767,1.6664454937,11.2235460281 --1.0130866766,1.66446149349,11.2081251144 --1.05005478859,1.66847729683,11.2317209244 --1.08402347565,1.66649281979,11.2143087387 --1.11999118328,1.66650891304,11.2128896713 --1.15795874596,1.67152500153,11.2364778519 --1.19392693043,1.67254078388,11.240067482 --1.21191072464,1.6725487709,11.2378568649 --1.24687886238,1.6715644598,11.227440834 --1.28284716606,1.67358005047,11.2330341339 --1.32081472874,1.6765961647,11.2516222 --1.35678267479,1.67761206627,11.2492055893 --1.39175105095,1.67662751675,11.2427949905 --1.43071806431,1.68064367771,11.2633781433 --1.44870245457,1.68165147305,11.2671785355 --1.48367083073,1.68166697025,11.2577648163 --1.52263784409,1.6846832037,11.276348114 --1.55760669708,1.6856982708,11.2729454041 --1.59457421303,1.68671417236,11.2755279541 --1.63254189491,1.68973004818,11.2891187668 --1.66850996017,1.6897456646,11.2857055664 --1.68449497223,1.68875288963,11.2735042572 --1.72546124458,1.69376933575,11.3000850677 --1.76242935658,1.69578504562,11.3046760559 --1.79939687252,1.69680070877,11.3042583466 --1.83636510372,1.69881606102,11.3098535538 --1.87233304977,1.69883155823,11.3034362793 --1.89031744003,1.69883918762,11.304236412 --1.92928493023,1.70285499096,11.3198280334 --1.96725213528,1.70387077332,11.3224086761 --2.00222110748,1.70388579369,11.3160047531 --2.04118847847,1.70690155029,11.3265914917 --2.07715654373,1.70691692829,11.3201770782 --2.11212563515,1.70693182945,11.3127727509 --2.1351082325,1.71094036102,11.336566925 --2.17407560349,1.71395611763,11.3451528549 --2.20904397964,1.71297109127,11.333741188 --2.25001072884,1.71698701382,11.3513259888 --2.28497982025,1.71700179577,11.3439245224 --2.32194709778,1.71801733971,11.3375024796 --2.35891580582,1.71903240681,11.3380966187 --2.37889957428,1.72104024887,11.3458957672 --2.41786694527,1.72305572033,11.351480484 --2.45683431625,1.72607123852,11.3580694199 --2.49080371857,1.72508573532,11.344666481 --2.52777147293,1.7251008749,11.3402519226 --2.57073783875,1.73011696339,11.3628387451 --2.5877225399,1.73012411594,11.3566379547 --2.62569046021,1.73213934898,11.3572273254 --2.66565799713,1.73515474796,11.3678207397 --2.70162653923,1.73516952991,11.3594102859 --2.73659515381,1.73418450356,11.3439922333 --2.77856183052,1.73820006847,11.3615846634 --2.81752943993,1.74021530151,11.3641729355 --2.83851337433,1.74322295189,11.3749761581 --2.87448167801,1.74223780632,11.3635597229 --2.91544914246,1.74625301361,11.377158165 --2.95441651344,1.74826824665,11.3767404556 --2.98938560486,1.74728286266,11.3633298874 --3.03135228157,1.75129830837,11.3769216537 --3.06532216072,1.75031232834,11.3625192642 --3.08930468559,1.75432050228,11.3803157806 --3.12527346611,1.75433492661,11.3709077835 --3.16124224663,1.75434947014,11.360496521 --3.20420861244,1.75836503506,11.374083519 --3.2431769371,1.76037979126,11.3756771088 --3.2801451683,1.76039433479,11.3682670593 --3.32211232185,1.76440966129,11.37885952 --3.34109663963,1.765417099,11.3766527176 --3.37906479836,1.76643157005,11.3732461929 --3.42203140259,1.77044701576,11.3848342896 --3.46099972725,1.77146148682,11.3854312897 --3.49996781349,1.77347624302,11.3830194473 --3.53993582726,1.77549099922,11.3866167068 --3.5609190464,1.77749860287,11.3884057999 --3.59688806534,1.77751278877,11.376996994 --3.63985538483,1.78152775764,11.3895969391 --3.67782378197,1.78254210949,11.3831853867 --3.71479225159,1.7825564146,11.3727712631 --3.75675964355,1.78557133675,11.3793640137 --3.79772758484,1.78858590126,11.3839616776 --3.8167116642,1.78859305382,11.3797540665 --3.85468053818,1.79060721397,11.3753528595 --3.89964723587,1.79462242126,11.3889436722 --3.9346165657,1.79463613033,11.3735361099 --3.97658395767,1.79765081406,11.3781280518 --4.01455307007,1.79866480827,11.3727264404 --4.05452108383,1.80067920685,11.3703165054 --4.07250595093,1.80068600178,11.3641138077 --4.12147092819,1.80670166016,11.3857011795 --4.16043949127,1.80771577358,11.3812961578 --4.19540929794,1.80772924423,11.3658905029 --4.2333779335,1.80774319172,11.3564786911 --4.27434587479,1.81075739861,11.3570747375 --4.29033184052,1.80976378918,11.3468780518 --4.32530164719,1.80977702141,11.3314723969 --4.37326717377,1.81479227543,11.3480625153 --4.40923690796,1.81480586529,11.33365345 --4.44820594788,1.81681978703,11.3272457123 --4.49417209625,1.82083451748,11.3378362656 --4.52614307404,1.81884729862,11.3144321442 --4.55512475967,1.82385551929,11.3342266083 --4.59909248352,1.82786977291,11.3418292999 --4.62806415558,1.82488191128,11.3104228973 --4.66903209686,1.82689595222,11.3080158234 --4.71899795532,1.83291113377,11.3256034851 --4.75296831131,1.83192396164,11.3072023392 --4.79493665695,1.8349378109,11.307800293 --4.83691501617,1.84494769573,11.3565988541 --4.87888240814,1.84696173668,11.3531847 --4.91885137558,1.84897518158,11.3487873077 --4.96381902695,1.85298919678,11.3543834686 --5.00278806686,1.85400271416,11.3439712524 --5.00876712799,1.84201133251,11.2625722885 --4.99376153946,1.83001327515,11.1803636551 --4.98974323273,1.8140206337,11.077960968 --5.02171421051,1.81303298473,11.0545511246 --5.06668186188,1.81704699993,11.0601453781 --5.09065532684,1.81305801868,11.0207414627 --5.11462879181,1.80906927586,10.9803323746 --5.1416015625,1.80608069897,10.9479293823 --5.14459133148,1.80108499527,10.9097270966 --5.162566185,1.79509520531,10.8583202362 --5.19853687286,1.79510772228,10.8459186554 --5.2365064621,1.79712069035,10.8355073929 --5.27847528458,1.79913413525,10.8351049423 --5.32344293594,1.80314791203,10.8386945724 --5.35041618347,1.80115902424,10.8082952499 --5.3753991127,1.80316627026,10.8150911331 --5.41336965561,1.80517876148,10.8066921234 --5.44534063339,1.80419075489,10.7842845917 --5.46331644058,1.79820072651,10.7348766327 --5.50128650665,1.80021321774,10.7254734039 --5.53425788879,1.80022513866,10.7060689926 --5.55524253845,1.8012316227,10.705871582 --5.58421516418,1.79924297333,10.6774606705 --5.64018011093,1.80725777149,10.7010545731 --5.68214893341,1.81027054787,10.6986532211 --5.7101225853,1.80828166008,10.6702518463 --5.76108884811,1.81429553032,10.6848535538 --5.78906202316,1.81230652332,10.6544427872 --5.83404016495,1.8213160038,10.6972455978 --5.87401008606,1.82332837582,10.6898422241 --5.91497945786,1.82534098625,10.6834354401 --5.95394992828,1.82735311985,10.6750392914 --5.99291992188,1.82936549187,10.6636266708 --6.03089046478,1.83037722111,10.6532306671 --6.07186031342,1.83338975906,10.6458234787 --6.08384752274,1.83139491081,10.627620697 --6.11282062531,1.83040547371,10.6012229919 --6.14579248428,1.8304169178,10.5798149109 --6.18776226044,1.83242917061,10.5754156113 --6.22573280334,1.83444106579,10.5620059967 --6.25970506668,1.83445227146,10.5436058044 --6.27069234848,1.832457304,10.5234012604 --6.29866600037,1.83046758175,10.4949989319 --6.31964159012,1.82747733593,10.4545946121 --6.35961198807,1.8294891119,10.4461956024 --6.41857719421,1.83750319481,10.467792511 --6.47454357147,1.84451687336,10.4843921661 --6.51951313019,1.8475291729,10.4829931259 --6.53449964523,1.84753441811,10.4697904587 --6.56747198105,1.84754526615,10.4483861923 --6.60444355011,1.84855639935,10.4339857101 --6.65141248703,1.85256886482,10.4345836639 --6.68838405609,1.85357987881,10.4201860428 --6.72235679626,1.85459065437,10.3997802734 --6.77032518387,1.85860300064,10.4013786316 --6.78631162643,1.85860812664,10.3911848068 --6.81328582764,1.85661804676,10.3587722778 --6.85125780106,1.85862910748,10.3453731537 --6.88822984695,1.85964000225,10.3299732208 --6.91420459747,1.85764968395,10.2975673676 --6.9441781044,1.85765969753,10.2721691132 --6.96816301346,1.85966563225,10.2729721069 --7.00913333893,1.86167693138,10.2615613937 --7.04810523987,1.86368775368,10.2491636276 --7.08007860184,1.86369788647,10.2267665863 --7.11305189133,1.86370801926,10.2043609619 --7.15502262115,1.8667191267,10.1959629059 --7.18399715424,1.86572897434,10.167555809 --7.20198345184,1.86573410034,10.1593599319 --7.23795557022,1.86674439907,10.140953064 --7.27092933655,1.86775445938,10.1195554733 --7.30190372467,1.8667640686,10.0951547623 --7.33487701416,1.8677740097,10.0727519989 --7.36285161972,1.8667832613,10.0443525314 --7.40682268143,1.86979436874,10.0369501114 --7.42680883408,1.87079954147,10.0317564011 --7.4647808075,1.87280988693,10.0153484344 --7.49075651169,1.87081885338,9.98394870758 --7.53172826767,1.87382936478,9.9725484848 --7.56170272827,1.87283849716,9.94715213776 --7.58367967606,1.87084710598,9.90974617004 --7.59566783905,1.86985123158,9.89354896545 --7.63463973999,1.87186145782,9.87814235687 --7.6696138382,1.87287116051,9.8587436676 --7.70258808136,1.87288045883,9.83734893799 --7.72756433487,1.87188899517,9.80494689941 --7.7605381012,1.8718984127,9.78153896332 --7.80051088333,1.87390840054,9.76914691925 --7.81349849701,1.87391269207,9.75294208527 --7.83847427368,1.87192106247,9.72053909302 --7.87044906616,1.87293016911,9.69714069366 --7.90742254257,1.87393975258,9.67974090576 --7.93639802933,1.87394845486,9.6523399353 --7.9663734436,1.87395715714,9.62593746185 --8.00434589386,1.8749666214,9.60953807831 --8.03033161163,1.8779720068,9.61034393311 --8.06830501556,1.87998127937,9.59394645691 --5.4529466629,1.22773659229,6.42717123032 --5.4589266777,1.2237443924,6.39175653458 --5.47190523148,1.22175252438,6.36635923386 --5.454890728,1.21275806427,6.30494594574 --5.43688631058,1.20575976372,6.26374197006 --5.41887331009,1.19676506519,6.20334148407 --5.4168548584,1.19177210331,6.15992355347 --5.40383958817,1.18377792835,6.10551691055 --5.38682603836,1.17478346825,6.04711055756 --5.3808093071,1.16878986359,6.00170707703 --5.37879180908,1.16379678249,5.96029424667 --5.369784832,1.1597994566,5.93109035492 --5.37276554108,1.15580689907,5.8956785202 --5.35875034332,1.1478126049,5.84226942062 --5.35173416138,1.14181911945,5.79686021805 --5.35971450806,1.1398267746,5.76845598221 --5.34869861603,1.13283288479,5.71904325485 --5.34968042374,1.12883996964,5.6836400032 --5.3446726799,1.12584292889,5.66044092178 --5.34165477753,1.12084984779,5.62002420425 --5.34263706207,1.11685681343,5.58562517166 --5.34561777115,1.11386418343,5.55221128464 --5.34060049057,1.10787081718,5.51079797745 --5.34358215332,1.10487794876,5.47940206528 --5.3535618782,1.10288584232,5.45399045944 --5.33455705643,1.09688770771,5.41678333282 --5.3405380249,1.09389507771,5.38838005066 --5.34551906586,1.09190237522,5.3589758873 --5.33450317383,1.08490848541,5.31356906891 --5.34848213196,1.08491659164,5.29316091537 --5.36246013641,1.08392465115,5.27275276184 --5.3464550972,1.07792699337,5.23954296112 --5.35843420029,1.07693469524,5.21814346313 --5.37341356277,1.07694268227,5.19974470139 --5.38939094543,1.07695114613,5.18032169342 --5.41836690903,1.0799601078,5.17593050003 --5.44734191895,1.08196914196,5.17052841187 --5.39533615112,1.06697201729,5.08710861206 --5.45131444931,1.07797980309,5.12391233444 --5.46129417419,1.07698726654,5.10050916672 --5.4722738266,1.07499492168,5.07810640335 --5.49425077438,1.07700335979,5.06570053101 --5.52522563934,1.08001255989,5.06129312515 --5.52920722961,1.07701933384,5.03289413452 --5.56018257141,1.08002841473,5.02848911285 --5.58516788483,1.08403348923,5.03529262543 --5.59914684296,1.08304131031,5.01488161087 --5.62812280655,1.08605003357,5.00847816467 --5.66909599304,1.09205949306,5.01308202744 --5.68107557297,1.09106719494,4.99066972733 --5.71705007553,1.09507620335,4.99027061462 --5.7570233345,1.1000854969,4.9928689003 --5.76701211929,1.10008966923,4.98465776443 --5.79898834229,1.10409796238,4.98127126694 --5.8359618187,1.10810720921,4.97985839844 --5.85494089127,1.10911476612,4.96446418762 --5.89591407776,1.11412394047,4.96706390381 --5.91789197922,1.11513197422,4.95265293121 --5.92788076401,1.11613595486,4.94444608688 --5.98085260391,1.12414550781,4.95806598663 --6.00882863998,1.12615358829,4.94865989685 --6.03080701828,1.12716126442,4.9342546463 --6.06678152084,1.13117003441,4.93084621429 --6.10275650024,1.13617861271,4.92743968964 --6.13073348999,1.13818645477,4.91804122925 --6.16271877289,1.14319133759,4.92885732651 --6.19269418716,1.1461994648,4.91944265366 --6.22467088699,1.1492074728,4.91304779053 --6.25964689255,1.15321552753,4.90865135193 --6.29062271118,1.15622353554,4.9002456665 --6.32659864426,1.16023159027,4.8958439827 --6.36757326126,1.16523993015,4.89544677734 --6.3815612793,1.16724395752,4.8892364502 --6.41753768921,1.17125189304,4.88484144211 --6.44551515579,1.17325913906,4.87444972992 --6.47949171066,1.17726695538,4.86805295944 --6.5154671669,1.18127477169,4.86265277863 --6.56743955612,1.18828332424,4.8692574501 --6.5834197998,1.18829011917,4.84784650803 --6.62240362167,1.19529521465,4.86065149307 --5.52459907532,0.972248852253,3.98664045334 --5.53957796097,0.972256302834,3.96921849251 --5.46157693863,0.954258561134,3.88580441475 --6.79328680038,1.21333241463,4.82064294815 --6.83726167679,1.21833992004,4.82025766373 --6.86924695969,1.22334432602,4.82605361938 --6.90222406387,1.22735142708,4.81665658951 --6.95219802856,1.23335933685,4.81825304031 --6.98717498779,1.2373663187,4.80985689163 --7.03015041351,1.24237370491,4.80645799637 --7.06312847137,1.24638044834,4.79707098007 --7.11111068726,1.25438547134,4.81287050247 --7.12809181213,1.25439143181,4.79147148132 --7.17806577682,1.26039874554,4.79207611084 --7.22504043579,1.26640617847,4.78967094421 --7.26101827621,1.27041268349,4.78128433228 --7.31099271774,1.27742004395,4.78088665009 --7.34597063065,1.28142642975,4.77048826218 --7.3789563179,1.28643035889,4.77529144287 --7.42093276978,1.29143702984,4.76889228821 --7.47090768814,1.29744410515,4.76749563217 --7.51588392258,1.30345058441,4.76310443878 --7.55586099625,1.30745708942,4.75470542908 --7.59283876419,1.31246328354,4.74430799484 --7.63281583786,1.31646943092,4.73591470718 --7.6847987175,1.32447373867,4.75172424316 --7.72477579117,1.32947993279,4.74232435226 --7.76875305176,1.3344861269,4.73593473434 --7.820728302,1.34149265289,4.73353815079 --7.86970424652,1.34849882126,4.72914361954 --7.91868066788,1.35450482368,4.72475194931 --7.95066022873,1.3575104475,4.70935153961 --7.99364471436,1.36451399326,4.71816110611 --8.02462387085,1.36651945114,4.70176029205 --8.14958667755,1.38752746582,4.74138593674 --8.19356441498,1.39253306389,4.73299980164 --8.22454452515,1.39553821087,4.71559715271 --8.2325296402,1.39454269409,4.68519449234 --8.27350711823,1.3985478878,4.67379903793 --8.30549526215,1.40355086327,4.67460393906 --8.33747386932,1.40655589104,4.65720081329 --8.37245464325,1.41056060791,4.64281463623 --8.39843559265,1.41256546974,4.62140607834 --8.59438705444,1.44557416439,4.69605588913 --8.66236209869,1.45457947254,4.69867706299 --8.65934848785,1.45158314705,4.66026258469 --10.7249755859,1.82063341141,5.73121929169 --10.7359609604,1.81963586807,5.69281673431 --10.7459478378,1.81863832474,5.65441846848 --10.7799291611,1.82064116001,5.62801933289 --10.7979154587,1.8206435442,5.59462976456 --10.7909107208,1.81864452362,5.56842041016 --10.8178939819,1.81964695454,5.53902673721 --10.8298807144,1.81864929199,5.50162744522 --10.8428668976,1.81765151024,5.46422290802 --10.8548545837,1.81665349007,5.42783212662 --8.0353012085,1.31161403656,3.95664191246 --8.02128887177,1.30761790276,3.91722917557 --8.01328372955,1.30461990833,3.89702177048 --8.01027011871,1.30162382126,3.86361503601 --8.01425552368,1.30062782764,3.83421564102 --8.02823925018,1.30063211918,3.80880713463 --8.00522994995,1.2946356535,3.76640033722 --8.01521492004,1.29363965988,3.74000096321 --7.9942035675,1.28764355183,3.69757676125 --8.005194664,1.28864550591,3.68737983704 --7.99618291855,1.28564929962,3.65197277069 --8.00716686249,1.28565323353,3.62657761574 --7.99215650558,1.28065705299,3.5881626606 --8.00214004517,1.2806609869,3.56175875664 --7.98912906647,1.27566480637,3.52535486221 --7.99511432648,1.27466869354,3.49694561958 --7.97911024094,1.27067053318,3.4747428894 --8.00809288025,1.27467441559,3.45734810829 --8.05207252502,1.27967834473,3.44595122337 --8.11005020142,1.28768217564,3.44055962563 --8.16702747345,1.29568600655,3.43416523933 --8.2290058136,1.30468952656,3.43078780174 --8.27998542786,1.31169295311,3.4213950634 --8.34596920013,1.32169473171,3.43320250511 --8.39894866943,1.32869803905,3.42482066154 --8.45492744446,1.33670115471,3.41642737389 --8.51990604401,1.34570431709,3.41204452515 --8.57088565826,1.35270738602,3.40064692497 --8.63286495209,1.36171030998,3.3942630291 --11.4334726334,1.84069550037,4.51492214203 --11.450460434,1.84169638157,4.47851514816 --11.457449913,1.83969700336,4.44012451172 --11.4784374237,1.84169781208,4.4057226181 --11.4934263229,1.84169840813,4.36932277679 --11.5124139786,1.84169888496,4.33492898941 --11.536400795,1.84369933605,4.30253791809 --11.5303974152,1.84169971943,4.27933597565 --11.542386055,1.84170019627,4.24193668365 --11.5503759384,1.84070062637,4.20253133774 --11.5543661118,1.83870112896,4.16212892532 --11.5623550415,1.83770155907,4.12373304367 --11.5683460236,1.83670186996,4.08433246613 --11.5723361969,1.83470237255,4.0439286232 --11.5683317184,1.83270263672,4.0217256546 --11.5733222961,1.83170294762,3.98232698441 --11.571313858,1.8297034502,3.93992042542 --11.5733041763,1.82770371437,3.89952015877 --11.5822944641,1.82670390606,3.86111712456 --11.5832862854,1.82470417023,3.82071852684 --11.5662784576,1.81970489025,3.7733039856 --11.568274498,1.81970500946,3.75410890579 --11.5652656555,1.8167052269,3.7127096653 --11.5532579422,1.81270587444,3.66729617119 --11.5582485199,1.81170594692,3.62789106369 --11.5192451477,1.80270707607,3.57548236847 --11.4612426758,1.79170882702,3.51605391502 --11.4402360916,1.78570950031,3.46964693069 --11.446231842,1.78570950031,3.4514465332 --11.4312238693,1.78171014786,3.40703988075 --11.4382152557,1.78071010113,3.36964178085 --11.4512052536,1.78170990944,3.33424711227 --11.4321994781,1.77671051025,3.28782725334 --11.4391899109,1.77571034431,3.25042772293 --11.4381809235,1.77371048927,3.2110285759 --11.4241790771,1.77071094513,3.18782830238 --11.4271697998,1.76971101761,3.14841675758 --11.4391613007,1.76971054077,3.1130232811 --11.4141550064,1.76371133327,3.0666103363 --11.4181470871,1.76271116734,3.02820444107 --11.418138504,1.76171112061,2.98980808258 --11.4111299515,1.75871133804,2.94839715958 --11.4121265411,1.7577111721,2.92919588089 --11.4121189117,1.75671112537,2.89079761505 --11.3971118927,1.75171148777,2.84738254547 --11.4061040878,1.75171101093,2.81199264526 --11.4040956497,1.75071072578,2.77258634567 --11.3830900192,1.74571144581,2.7281703949 --11.3730831146,1.74171173573,2.68776988983 --11.3520812988,1.73771238327,2.66356277466 --11.3400745392,1.73471271992,2.62215280533 --11.3720636368,1.73871099949,2.59176182747 --11.4110527039,1.74370872974,2.56236815453 --11.4390439987,1.74670708179,2.53097891808 --11.4720335007,1.75070488453,2.50059103966 --11.5210256577,1.75770223141,2.49240493774 --11.5180187225,1.75570178032,2.45299863815 --11.5350103378,1.75770032406,2.41860461235 --11.4720077515,1.74570298195,2.36617708206 --11.451002121,1.74070346355,2.32275915146 --11.5109910965,1.74969959259,2.2983880043 --11.7019691467,1.77968835831,2.3000535965 --11.7079658508,1.77968752384,2.28185415268 --11.7449569702,1.78468441963,2.2504632473 --11.7829475403,1.78968119621,2.21907234192 --11.8099384308,1.79267859459,2.18568181992 --11.8559293747,1.79867458344,2.15529251099 --11.890920639,1.80367136002,2.12290239334 --11.9059143066,1.80466914177,2.0865046978 --11.9419078827,1.80966627598,2.07432389259 --11.9609003067,1.81166362762,2.03792190552 --11.5359210968,1.74168932438,1.92236185074 --11.4769191742,1.73169207573,1.87393474579 --11.4929122925,1.73268997669,1.83954250813 --11.5109043121,1.73468768597,1.80514776707 --11.5598945618,1.74168324471,1.77475309372 --11.4708976746,1.72668874264,1.74152195454 --11.4788913727,1.72768700123,1.70511889458 --11.5688800812,1.74067950249,1.68275821209 --11.5278759003,1.73368120193,1.63833582401 --11.4748725891,1.72368371487,1.59291446209 --11.5698623657,1.73867547512,1.56954491138 --11.6418533325,1.74866878986,1.54216623306 --11.5728530884,1.73767316341,1.51394498348 --11.3978557587,1.70868492126,1.45147252083 --11.2968549728,1.69169127941,1.40002429485 --11.288848877,1.6896905899,1.36262083054 --11.3048419952,1.69168806076,1.32822394371 --11.3748340607,1.70168125629,1.30084979534 --11.3568315506,1.69868206978,1.27963507175 --11.3438262939,1.69568169117,1.24223649502 --11.3228216171,1.69168186188,1.2028220892 --11.3998126984,1.70267403126,1.17544996738 --11.3358097076,1.69267785549,1.13101708889 --11.3488044739,1.69367527962,1.09561514854 --11.5157938004,1.71965920925,1.07727956772 --11.341794014,1.69167256355,1.02180492878 --11.3097915649,1.68567466736,1.0005941391 --11.2507886887,1.67567825317,0.958165109158 --11.2327842712,1.67267823219,0.920759618282 --11.2497787476,1.674675107,0.886363565922 --11.2487726212,1.67367339134,0.849957048893 --11.2917671204,1.6806678772,0.817569673061 --11.2847623825,1.67866659164,0.781167507172 --11.2337617874,1.67067062855,0.758945822716 --11.2987546921,1.68066263199,0.727561950684 --11.1897516251,1.66267120838,0.683114647865 --11.1867465973,1.66166973114,0.647716701031 --11.1887426376,1.66166770458,0.61231637001 --11.1897373199,1.66066563129,0.575905203819 --11.1667356491,1.65766716003,0.556695640087 --11.1537303925,1.65466654301,0.520287513733 --11.2527246475,1.67065453529,0.490928769112 --11.2207212448,1.66465568542,0.452503979206 --11.2247161865,1.66565310955,0.417103827 --11.218711853,1.66365170479,0.380694299936 --11.2187080383,1.66364955902,0.345294713974 --11.1957063675,1.65965092182,0.32607999444 --11.1917009354,1.65864920616,0.29067966342 --11.1826972961,1.65764808655,0.254267394543 --11.2026939392,1.66064357758,0.219877868891 --11.1876897812,1.65764296055,0.183465138078 --11.1886854172,1.65764057636,0.148063912988 --11.195681572,1.65863740444,0.112663462758 --11.1306791306,1.64864361286,0.0934362635016 --11.1596755981,1.65263795853,0.0580380409956 --11.2076730728,1.66062986851,0.023657284677 --11.1826686859,1.65563035011,-0.0127611467615 --11.1516637802,1.65063154697,-0.0481720082462 --11.1656608582,1.65362727642,-0.0835706442595 --11.1756572723,1.65462362766,-0.118969343603 --11.235657692,1.66461491585,-0.137153223157 --11.1886529922,1.65661799908,-0.172572866082 --11.1186485291,1.64562392235,-0.208006665111 --11.0956449509,1.64162421227,-0.243422269821 --11.1366424561,1.64861631393,-0.278805702925 --11.1046380997,1.64361763,-0.314227581024 --11.2026386261,1.65960228443,-0.350584506989 --11.1796350479,1.65560376644,-0.367793619633 --11.2106332779,1.66059684753,-0.404186546803 --11.1756296158,1.65459859371,-0.438600093126 --11.1636266708,1.65359711647,-0.474011182785 --11.1566238403,1.65259504318,-0.509418964386 --11.1736221313,1.65458965302,-0.545819044113 --11.1526184082,1.65158939362,-0.580227315426 --11.1006155014,1.64359498024,-0.596456408501 --11.1586151123,1.65358388424,-0.633831679821 --11.1806135178,1.65657770634,-0.670224547386 --11.1866111755,1.65857350826,-0.706631779671 --11.2036104202,1.66056776047,-0.743026733398 --11.2136087418,1.66256308556,-0.779427945614 --11.2016067505,1.6615613699,-0.813829541206 --11.2086057663,1.6625585556,-0.833038926125 --11.1826028824,1.65855884552,-0.866445422173 --11.2006025314,1.66155266762,-0.903847634792 --11.2196006775,1.66554629803,-0.940235972404 --11.290602684,1.67653203011,-0.981614410877 --11.3746070862,1.69051575661,-1.02398228645 --11.3426036835,1.68651664257,-1.05739498138 --11.3196020126,1.68251824379,-1.07360553741 --11.3166007996,1.68251478672,-1.11001563072 --11.230594635,1.66952395439,-1.13946342468 --11.2205924988,1.66852164268,-1.17386412621 --11.2545938492,1.67451238632,-1.21325671673 --11.2655935287,1.67650663853,-1.25065875053 --11.3045959473,1.68249845505,-1.27183616161 --11.2795934677,1.67949819565,-1.30625832081 --11.3015947342,1.68349051476,-1.34465157986 --11.2825927734,1.68148934841,-1.3790653944 --11.3655986786,1.69447159767,-1.42342126369 --11.3655986786,1.69546711445,-1.46083474159 --11.3125934601,1.68747138977,-1.49126172066 --11.2985925674,1.68547165394,-1.50746583939 --11.4136018753,1.70444774628,-1.55781948566 --11.3545970917,1.69645309448,-1.5872490406 --11.3605985641,1.69744741917,-1.62465000153 --11.2735910416,1.68445777893,-1.65009367466 --11.3565979004,1.69843876362,-1.69745886326 --11.4736099243,1.71841359138,-1.74980652332 --11.4266061783,1.71041929722,-1.76203083992 --11.4486083984,1.71541047096,-1.80242812634 --11.4276065826,1.71240901947,-1.83684504032 --11.3936052322,1.70841026306,-1.86825752258 --11.429608345,1.71439862251,-1.91064453125 --11.457613945,1.71938836575,-1.95203471184 --11.4676151276,1.72238123417,-1.99144029617 --11.4356126785,1.71738445759,-2.00465273857 --11.4236125946,1.71638154984,-2.04006314278 --11.4606180191,1.72336924076,-2.08345031738 --11.4786224365,1.72736036777,-2.12384557724 --11.4646224976,1.72635746002,-2.15925931931 --11.5676355362,1.74333226681,-2.21461367607 --11.5086307526,1.73533785343,-2.24204564095 --11.4706277847,1.72934222221,-2.25426721573 --11.4716300964,1.73033642769,-2.29166603088 --11.509636879,1.73832321167,-2.33705949783 --11.5456428528,1.74531018734,-2.38144373894 --11.6286563873,1.75928795338,-2.43480205536 --11.6636638641,1.76627469063,-2.48019146919 --11.641664505,1.76327288151,-2.51460909843 --11.655667305,1.76626694202,-2.53680610657 --11.593662262,1.75727319717,-2.56223464012 --11.6886787415,1.77424740791,-2.62059664726 --11.7376880646,1.78323090076,-2.66897034645 --11.7716960907,1.79021716118,-2.71535992622 --11.7606983185,1.78921282291,-2.75176548958 --11.7697038651,1.79220414162,-2.79316806793 --11.8777217865,1.81017780304,-2.83732438087 --11.9057302475,1.81616485119,-2.88270950317 --11.8567266464,1.81016838551,-2.91113591194 --11.8987388611,1.81815218925,-2.96051955223 --11.9457502365,1.82713460922,-3.01190543175 --11.9947633743,1.83611643314,-3.06328177452 --11.9687643051,1.83411478996,-3.09669280052 --12.1287918091,1.86107575893,-3.1558175087 --12.1157960892,1.86007070541,-3.19423532486 --12.1928138733,1.87404584885,-3.25359416008 --12.4608650208,1.91997742653,-3.36286830902 --12.4278659821,1.91597628593,-3.39628601074 --12.3358564377,1.90198874474,-3.41473770142 --12.4648828506,1.92395508289,-3.46887040138 --12.5769090652,1.94392049313,-3.54122185707 --12.6579313278,1.95889282227,-3.60558390617 --12.7439537048,1.97486364841,-3.67194342613 --12.7529630661,1.97885227203,-3.71733760834 --12.8769950867,2.00081348419,-3.79568099976 --12.8980073929,2.0057990551,-3.84506821632 --12.8860092163,2.00479698181,-3.86428070068 --12.8430099487,1.99979746342,-3.8957016468 --12.8250160217,1.99879205227,-3.93511867523 --12.8480291367,2.00477671623,-3.98550581932 --12.9060497284,2.01575231552,-4.04788732529 --12.9720726013,2.02872610092,-4.11124753952 --13.0270929337,2.03970193863,-4.17362928391 --13.0951118469,2.05267977715,-4.21679496765 --13.094121933,2.05466961861,-4.26119184494 --13.0361204147,2.04667329788,-4.28963422775 --13.1641578674,2.07063031197,-4.37496709824 --13.2561883926,2.08759593964,-4.45032262802 --13.2471971512,2.08858680725,-4.49373006821 --13.2502098083,2.0915749073,-4.54113197327 --13.2502212524,2.09356355667,-4.58753395081 --13.2342233658,2.09156179428,-4.60574483871 --13.239235878,2.09454917908,-4.6541466713 --13.2402486801,2.09753751755,-4.70054388046 --13.2142543793,2.0955324173,-4.73896455765 --13.2322702408,2.10051608086,-4.79236078262 --13.238284111,2.10450267792,-4.84075546265 --13.2162857056,2.10150265694,-4.85697126389 --13.1772890091,2.09750127792,-4.89039611816 --13.211309433,2.10547995567,-4.94978284836 --13.2093219757,2.10846853256,-4.99618625641 --13.2093343735,2.11045646667,-5.04358911514 --13.214348793,2.11344265938,-5.09299039841 --13.2143621445,2.11643052101,-5.14039230347 --13.2173700333,2.1184232235,-5.16559410095 --13.2053804398,2.11841392517,-5.20900440216 --13.1933917999,2.1194050312,-5.25241565704 --13.1984071732,2.12339091301,-5.30181217194 --13.2004213333,2.12637782097,-5.35021114349 --13.2044363022,2.12936353683,-5.40061759949 --13.1864461899,2.12935590744,-5.44203186035 --13.1974563599,2.13234615326,-5.47022533417 --13.197470665,2.13533306122,-5.51862812042 --13.1854820251,2.13632369041,-5.56203460693 --13.1894989014,2.13930916786,-5.61243677139 --13.1945152283,2.14329433441,-5.66283369064 --13.1805257797,2.14428496361,-5.70624685287 --13.1695384979,2.14527463913,-5.75065660477 --13.1825504303,2.14826393127,-5.78085231781 --13.177564621,2.15025186539,-5.82826137543 --13.1655769348,2.15124154091,-5.87267255783 --13.1655931473,2.15522789955,-5.92207670212 --13.1496047974,2.15521883965,-5.96448707581 --13.1466207504,2.15720558167,-6.01289272308 --13.1286306381,2.15719723701,-6.05430316925 --13.1406431198,2.16118621826,-6.08449792862 --13.1426610947,2.16517162323,-6.13489723206 --13.1416778564,2.16815710068,-6.18530750275 --13.1306915283,2.16914653778,-6.22971057892 --13.1227064133,2.17113423347,-6.27712488174 --13.106719017,2.17212510109,-6.31953287125 --13.1167402267,2.1771068573,-6.37493228912 --13.1137475967,2.17810058594,-6.39913845062 --13.1037626266,2.17908883095,-6.44454193115 --13.0927772522,2.1810772419,-6.49095821381 --13.1218042374,2.18905258179,-6.55534124374 --13.0958147049,2.18804597855,-6.59476566315 --13.107837677,2.19402623177,-6.65216493607 --13.0848493576,2.19301891327,-6.69157505035 --13.1098680496,2.20000243187,-6.72976350784 --13.0838785172,2.19899559021,-6.76918649673 --13.0878992081,2.20297861099,-6.82258462906 --13.0709123611,2.20396852493,-6.86599874496 --13.0719337463,2.20795249939,-6.91840076447 --13.0439434052,2.20594620705,-6.95581626892 --13.002948761,2.20294427872,-6.98724651337 --13.0289678574,2.20892691612,-7.02743768692 --13.0219860077,2.21191334724,-7.07584285736 --13.0160045624,2.21489906311,-7.12524938583 --13.007021904,2.21688556671,-7.17366123199 --13.0060434341,2.22086954117,-7.22606611252 --12.9910583496,2.22185826302,-7.2704744339 --12.988079071,2.22484230995,-7.32288599014 --12.9910907745,2.22783279419,-7.35108566284 --12.991112709,2.23181581497,-7.40448856354 --12.9741287231,2.23280477524,-7.44890403748 --12.9751520157,2.23678708076,-7.50330781937 --12.9631690979,2.23877477646,-7.54971265793 --12.9641923904,2.24375677109,-7.60512161255 --12.9762086868,2.24774312973,-7.63931846619 --12.9682283401,2.2507288456,-7.68872356415 --12.9672517776,2.25471115112,-7.7431306839 --12.962272644,2.25769495964,-7.79554176331 --12.9572944641,2.2616789341,-7.84694385529 --12.9403123856,2.26266717911,-7.89236021042 --12.950340271,2.26864504814,-7.95375919342 --12.9333457947,2.26764249802,-7.9709687233 --12.9483766556,2.27561807632,-8.03536224365 --12.9504022598,2.28059864044,-8.09276866913 --13.0324640274,2.29954719543,-8.19912624359 --13.1745519638,2.33147096634,-8.34244537354 --13.3016357422,2.35940027237,-8.47877693176 --13.2876558304,2.3613858223,-8.52818775177 --13.2246417999,2.35240125656,-8.51843070984 --13.1746463776,2.34740138054,-8.54586791992 --13.1136465073,2.34140634537,-8.56530666351 --13.0576477051,2.33540940285,-8.58774375916 --13.0146551132,2.3324072361,-8.61817264557 --12.9356470108,2.32241988182,-8.62562561035 --12.8996572495,2.32041478157,-8.66004943848 --12.9076747894,2.32440114021,-8.69424629211 --12.8366689682,2.31641101837,-8.70569229126 --12.8116846085,2.31640100479,-8.74811553955 --12.7556858063,2.31040477753,-8.76854896545 --12.6826782227,2.30241584778,-8.77799892426 --12.6697006226,2.30440092087,-8.82740974426 --12.6277074814,2.30139827728,-8.85784339905 --12.5786972046,2.29440951347,-8.85307025909 --12.5417079926,2.293405056,-8.88650131226 --12.498714447,2.28940367699,-8.91492843628 --12.4467172623,2.28540563583,-8.9373664856 --12.4047250748,2.28240346909,-8.96679878235 --12.3807411194,2.28339362144,-9.00821590424 --12.3207397461,2.27639961243,-9.0246591568 --12.2837343216,2.27240562439,-9.02788543701 --12.2537479401,2.27139830589,-9.06531143188 --12.2077522278,2.26739859581,-9.09074211121 --12.1717634201,2.26639413834,-9.12316703796 --12.1327724457,2.26439094543,-9.15359687805 --12.0867776871,2.26039099693,-9.17903232574 --12.0467853546,2.25838828087,-9.20846176147 --12.0297908783,2.25738573074,-9.22467041016 --11.9817943573,2.25338673592,-9.24911308289 --11.9488067627,2.25238060951,-9.28353786469 --11.9098157883,2.25037789345,-9.31296539307 --11.863820076,2.2473783493,-9.3374004364 --11.8218269348,2.24437665939,-9.36483287811 --11.7818346024,2.24237442017,-9.39326190948 --11.748831749,2.23837947845,-9.39748477936 --11.7178440094,2.23737287521,-9.43290901184 --11.6808538437,2.236369133,-9.46333599091 --11.6338577271,2.23237037659,-9.48576927185 --11.6018695831,2.23136425018,-9.52019500732 --11.5648803711,2.23036026955,-9.55163002014 --11.5138816833,2.22536349297,-9.57106971741 --11.4978866577,2.22536063194,-9.58727741241 --11.4558944702,2.22335910797,-9.61471843719 --11.4118995667,2.21935939789,-9.6381444931 --11.3568973541,2.21436548233,-9.65258216858 --11.3179063797,2.21236252785,-9.68202018738 --11.269908905,2.20836472511,-9.7024564743 --11.2519140244,2.20836281776,-9.71767044067 --11.2229280472,2.20835542679,-9.75309085846 --11.1719293594,2.20335912704,-9.77153396606 --11.1469459534,2.20434951782,-9.81095504761 --11.0999488831,2.20135164261,-9.83138942719 --11.0549526215,2.19835233688,-9.85382556915 --11.040977478,2.20133662224,-9.90324306488 --11.0309877396,2.20233035088,-9.92545413971 --10.9859924316,2.19933152199,-9.94688510895 --10.9490013123,2.19832801819,-9.9763174057 --10.9070081711,2.19532752037,-10.0007505417 --10.868016243,2.19332504272,-10.0281848907 --10.8360290527,2.19331932068,-10.0606069565 --10.8010396957,2.19231510162,-10.0910348892 --10.7720365524,2.18931913376,-10.0962600708 --10.744052887,2.19031071663,-10.1336898804 --10.7030601501,2.18830990791,-10.1581201553 --10.6620664597,2.1863090992,-10.182551384 --10.6340827942,2.18630051613,-10.2199802399 --10.6000938416,2.18629598618,-10.2504053116 --10.5641040802,2.18529224396,-10.2798366547 --10.5381031036,2.18229484558,-10.2870588303 --10.5041160583,2.18228983879,-10.3184900284 --10.468126297,2.18128609657,-10.3479232788 --10.4291353226,2.17928385735,-10.3743581772 --10.3821372986,2.17628717422,-10.3917913437 --10.3391418457,2.17328739166,-10.414229393 --10.3211660385,2.17627310753,-10.4606485367 --10.2831554413,2.17128348351,-10.4548740387 --10.2691841125,2.17626619339,-10.5062971115 --10.2331943512,2.17526268959,-10.5347261429 --10.2042093277,2.17525529861,-10.5691452026 --10.1772279739,2.17624568939,-10.6075744629 --10.1322307587,2.1742477417,-10.6270103455 --10.109251976,2.17623567581,-10.6694374084 --10.0942602158,2.17623209953,-10.6866493225 --10.0672779083,2.17722272873,-10.7250776291 --10.0212802887,2.17422556877,-10.7425117493 --9.98228931427,2.17322325706,-10.7689523697 --9.95130348206,2.17321634293,-10.8023786545 --9.91431427002,2.17221355438,-10.8298110962 --9.88633155823,2.17420482635,-10.8662347794 --9.86933803558,2.17420196533,-10.8824567795 --9.8353509903,2.17319726944,-10.9118795395 --9.79535865784,2.17219614983,-10.9363164902 --9.7553653717,2.17019486427,-10.9607543945 --9.72538280487,2.17118692398,-10.9961862564 --9.69439792633,2.17218017578,-11.0296134949 --9.66741752625,2.17317008972,-11.0680408478 --9.64541912079,2.17217135429,-11.0772562027 --9.61243343353,2.17216515541,-11.1096925735 --9.57244110107,2.17116427422,-11.1331253052 --9.54846286774,2.17315244675,-11.1745481491 --9.51948165894,2.17514371872,-11.2109766006 --9.49450302124,2.17713212967,-11.2524061203 --9.46552085876,2.17812347412,-11.2888336182 --9.44752693176,2.17812132835,-11.3030509949 --9.41854476929,2.17911267281,-11.3394775391 --9.38456058502,2.18010687828,-11.3709135056 --9.35157489777,2.18010091782,-11.4023418427 --9.32659721375,2.18208885193,-11.4447727203 --9.28560447693,2.18108892441,-11.4662036896 --9.27161502838,2.18208384514,-11.4854192734 --9.24563694,2.18407273293,-11.5258455276 --9.21165084839,2.18406701088,-11.5572805405 --9.17766571045,2.18506145477,-11.5877113342 --9.15468978882,2.18804788589,-11.6321353912 --9.11469936371,2.18704628944,-11.6565761566 --9.08471775055,2.18803787231,-11.6920022964 --9.04973220825,2.18803262711,-11.7224378586 --9.03674411774,2.19002628326,-11.7436552048 --9.00776481628,2.19201683998,-11.7810850143 --8.98379039764,2.1950032711,-11.825512886 --8.95180702209,2.19599580765,-11.8589410782 --8.9168214798,2.19599056244,-11.8893766403 --8.88383769989,2.19698405266,-11.9218072891 --8.8748550415,2.19897413254,-11.9490232468 --8.83586597443,2.19897198677,-11.9744625092 --8.81389427185,2.20295667648,-12.0208816528 --8.77390289307,2.20195555687,-12.0443172455 --8.74192047119,2.20294761658,-12.0787496567 --8.70693588257,2.20294165611,-12.1101884842 --8.69097328186,2.20892071724,-12.1666107178 --8.67898750305,2.21091341972,-12.1898260117 --8.66602897644,2.21788954735,-12.251247406 --8.63604927063,2.21887969971,-12.2886762619 --8.58704853058,2.21588540077,-12.3001184464 --8.54105186462,2.21388912201,-12.3155603409 --8.47102642059,2.20491218567,-12.2980222702 --8.37997627258,2.19095420837,-12.2484912872 --8.30291175842,2.17400240898,-12.1777439117 --8.2068529129,2.1580491066,-12.120221138 --8.10378456116,2.13910269737,-12.0507001877 --8.01273059845,2.12414646149,-11.9981746674 --7.93268728256,2.11218166351,-11.9596376419 --7.83762550354,2.09623003006,-11.8991155624 --7.75758123398,2.08326649666,-11.8585767746 --7.69653224945,2.0713031292,-11.8068227768 --7.61848926544,2.05933856964,-11.768286705 --7.55246067047,2.05036330223,-11.7467403412 --7.46840858459,2.03640460968,-11.6982116699 --7.38235282898,2.02144837379,-11.6446800232 --7.32733678818,2.01646447182,-11.6381292343 --7.28133153915,2.01347279549,-11.6445684433 --7.24931812286,2.0094845295,-11.6347999573 --7.18328666687,2.00051140785,-11.6102581024 --7.13828229904,1.99751925468,-11.6176986694 --7.06323719025,1.98555517197,-11.5771589279 --7.00221157074,1.97757780552,-11.5596179962 --6.95820713043,1.97458541393,-11.5670557022 --6.91918230057,1.9686050415,-11.54429245 --6.82811260223,1.95165765285,-11.4757680893 --6.78611040115,1.9496639967,-11.4852046967 --6.72808456421,1.94268620014,-11.4676504135 --6.68307828903,1.93969500065,-11.4730978012 --6.6300611496,1.9337117672,-11.46555233 --6.58605480194,1.93072044849,-11.470993042 --6.53704214096,1.92673397064,-11.4684400558 --6.50702667236,1.92274677753,-11.4566631317 --6.42496299744,1.90779483318,-11.3951244354 --6.36793756485,1.90081679821,-11.3785839081 --6.32893705368,1.89882171154,-11.3900165558 --6.26489925385,1.88985168934,-11.3594760895 --6.1798286438,1.87390446663,-11.2899456024 --6.16984319687,1.87589681149,-11.31316185 --6.12984037399,1.87390303612,-11.3226003647 --6.08182621002,1.86991775036,-11.3180484772 --6.03280925751,1.86493349075,-11.3114967346 --5.98178815842,1.85995197296,-11.2999429703 --5.92275524139,1.85097897053,-11.2743988037 --5.89477109909,1.85397279263,-11.3048305511 --5.89580488205,1.8599524498,-11.3500461578 --5.84878921509,1.85596728325,-11.3444862366 --5.81179094315,1.85497117043,-11.3579235077 --5.75576066971,1.84699571133,-11.3363780975 --5.72978115082,1.85098659992,-11.3718137741 --5.71281671524,1.85696768761,-11.4242391586 --5.68683719635,1.85995864868,-11.4596719742 --5.69488477707,1.86892926693,-11.5198793411 --5.67191076279,1.87291669846,-11.5613069534 --5.62689876556,1.86892926693,-11.5597505569 --5.59991836548,1.87192082405,-11.5941829681 --5.56893205643,1.8739169836,-11.6206178665 --5.53093385696,1.87292063236,-11.6350669861 --5.51397228241,1.87989974022,-11.6904935837 --5.5039896965,1.88289093971,-11.7157087326 --5.48302173615,1.88787472248,-11.7631349564 --5.44302082062,1.88688051701,-11.7735843658 --5.42806386948,1.89385664463,-11.8340053558 --5.38205051422,1.88987064362,-11.8304519653 --5.34104633331,1.8888784647,-11.836894989 --5.32204818726,1.888879776,-11.845123291 --5.31811618805,1.90084040165,-11.9325447083 --5.28412389755,1.90084004402,-11.9529752731 --5.24111652374,1.89885020256,-11.9554204941 --5.20111560822,1.89785611629,-11.9658699036 --5.17313814163,1.90084660053,-12.0023078918 --5.14816570282,1.90483391285,-12.0437345505 --5.10712242126,1.89686441422,-12.0019769669 --5.06511592865,1.89387404919,-12.0054197311 --5.02611541748,1.89387965202,-12.0158624649 --4.99713659286,1.89687120914,-12.0502996445 --4.96414756775,1.89786922932,-12.0737323761 --4.93015909195,1.89886724949,-12.0971755981 --4.90118169785,1.90285789967,-12.1336183548 --4.89120149612,1.90584778786,-12.1608295441 --4.8522028923,1.90485239029,-12.1732788086 --4.81620883942,1.90585386753,-12.1907167435 --4.78623056412,1.90884542465,-12.2251586914 --4.74021482468,1.90486109257,-12.2186059952 --4.71223783493,1.90885126591,-12.2550344467 --4.68927621841,1.9148324728,-12.3074703217 --4.67629146576,1.91782546043,-12.3296880722 --4.63929748535,1.91782712936,-12.3471336365 --4.61232852936,1.9228130579,-12.391576767 --4.56531000137,1.91883039474,-12.382024765 --4.53833961487,1.92381727695,-12.4244585037 --4.51036882401,1.92780447006,-12.4668998718 --4.45533037186,1.92083454132,-12.4353542328 --4.43332386017,1.91884148121,-12.4335756302 --4.40434980392,1.92283070087,-12.4720125198 --4.38139200211,1.92980957031,-12.5284490585 --4.34540271759,1.930809021,-12.5498952866 --4.31843423843,1.93679475784,-12.594326973 --4.27843570709,1.93579959869,-12.6067829132 --4.23943758011,1.93580460548,-12.6182260513 --4.22545146942,1.93779850006,-12.6384382248 --4.18545055389,1.93680477142,-12.6478834152 --4.14144039154,1.93481755257,-12.6463356018 --4.09642648697,1.93183207512,-12.6417894363 --4.06043434143,1.93283295631,-12.6602249146 --4.01943206787,1.93184041977,-12.6676769257 --3.99441814423,1.92885220051,-12.6579065323 --3.95942997932,1.93085086346,-12.6803445816 --3.92444443703,1.93284785748,-12.7057905197 --3.88444375992,1.93185424805,-12.7152395248 --3.84644818306,1.93185758591,-12.7296819687 --3.80143117905,1.92887437344,-12.7211294174 --3.76644563675,1.93087136745,-12.7465744019 --3.74945521355,1.93286848068,-12.7617998123 --3.70443797112,1.92888534069,-12.7532482147 --3.66844844818,1.93088507652,-12.7736883163 --3.62744426727,1.92989373207,-12.7791376114 --3.5844335556,1.92690646648,-12.7775878906 --3.54844641685,1.92890501022,-12.8010368347 --3.50543403625,1.92691862583,-12.7974834442 --3.48242402077,1.92492806911,-12.7917118073 --3.44242191315,1.92393565178,-12.7991580963 --3.4054312706,1.92593622208,-12.8186063766 --3.36241769791,1.92295062542,-12.8140525818 --3.32341885567,1.92295634747,-12.8244962692 --3.28542423248,1.92395937443,-12.8399448395 --3.24241089821,1.92097377777,-12.835392952 --3.21839523315,1.91798651218,-12.8236188889 --3.17839431763,1.91799354553,-12.8320713043 --3.14039707184,1.91799807549,-12.8445119858 --3.09738469124,1.91601216793,-12.8409662247 --3.06039237976,1.91701376438,-12.8584079742 --3.01637482643,1.91403067112,-12.8498620987 --2.97436642647,1.91304254532,-12.850317955 --2.95335912704,1.91104996204,-12.8475379944 --2.91034221649,1.90906667709,-12.8389835358 --2.87134408951,1.90907204151,-12.850435257 --2.83033561707,1.90708363056,-12.8508825302 --2.78731846809,1.90510046482,-12.8423309326 --2.74530696869,1.90311396122,-12.8397836685 --2.70831847191,1.90511369705,-12.8612365723 --2.6853017807,1.9021269083,-12.8484592438 --2.64730668068,1.90313065052,-12.8629074097 --2.60428929329,1.90014755726,-12.8543596268 --2.55825304985,1.89417564869,-12.825802803 --2.51322388649,1.88919949532,-12.8052549362 --2.48326778412,1.89718019962,-12.8597021103 --2.46125483513,1.89419126511,-12.8509254456 --2.4232609272,1.89619445801,-12.8663778305 --2.38425993919,1.89620161057,-12.8748254776 --2.34325242043,1.89521288872,-12.8762807846 --2.3012342453,1.89223027229,-12.8667268753 --2.26223444939,1.89223694801,-12.8761777878 --2.22021818161,1.89025330544,-12.8686294556 --2.1832253933,1.89125585556,-12.8850708008 --2.16221928596,1.89026296139,-12.8833007812 --2.11819005013,1.88628673553,-12.8627529144 --2.07918858528,1.88629448414,-12.8702011108 --2.04119372368,1.88729834557,-12.8846511841 --1.99716484547,1.88332235813,-12.864107132 --1.96017205715,1.88432478905,-12.8805484772 --1.9411765337,1.88532567024,-12.8897762299 --1.89915537834,1.88234496117,-12.8772258759 --1.86015295982,1.88235330582,-12.8836736679 --1.82014644146,1.88236415386,-12.8861265182 --1.77712202072,1.87838542461,-12.8705854416 --1.73811590672,1.87839603424,-12.8730278015 --1.70012390614,1.87939822674,-12.8904819489 --1.67810511589,1.87741279602,-12.87570858 --1.64111745358,1.87941265106,-12.8971576691 --1.60009837151,1.87743079662,-12.8866043091 --1.5600925684,1.87644124031,-12.8900613785 --1.52311098576,1.88043797016,-12.9175167084 --1.48713040352,1.88343369961,-12.9459609985 --1.44611310959,1.88145077229,-12.9374113083 --1.425101161,1.88046145439,-12.9296398163 --1.39013254642,1.88545048237,-12.970085144 --1.34912025928,1.88446497917,-12.9665441513 --1.31314790249,1.88945639133,-13.00299263 --1.27818667889,1.89644169807,-13.0504417419 --1.24121034145,1.90043544769,-13.0828933716 --1.20323324203,1.90543007851,-13.1143541336 --1.1852452755,1.90742683411,-13.1305732727 --1.14524710178,1.90843343735,-13.1410322189 --1.10625398159,1.91043698788,-13.1564836502 --1.06826913357,1.91343593597,-13.1799325943 --1.02725493908,1.91145169735,-13.1743860245 --0.989277243614,1.916446805,-13.2048387527 --0.950292348862,1.91944599152,-13.2282953262 --0.931313514709,1.923437953,-13.253528595 --0.893342792988,1.92842912674,-13.2909822464 --0.8533411026,1.92943799496,-13.2974338531 --0.811313807964,1.92546117306,-13.2788877487 --0.772321224213,1.92746472359,-13.2943334579 --0.731321334839,1.92847275734,-13.3027973175 --0.690307438374,1.92748844624,-13.2972517014 --0.670308351517,1.9274917841,-13.3024778366 --0.630310893059,1.92949855328,-13.3129310608 --0.589298903942,1.9285132885,-13.309387207 --0.549299180508,1.92952108383,-13.3178386688 --0.50827306509,1.92654359341,-13.3002882004 --0.467267155647,1.9265550375,-13.3027477264 --0.427276551723,1.92855787277,-13.3202028275 --0.408289283514,1.93155479431,-13.3364229202 --0.367280215025,1.93056797981,-13.3358812332 --0.327283829451,1.93257415295,-13.3473320007 --0.286272823811,1.93158853054,-13.344789505 --0.245270133018,1.93259835243,-13.3502502441 --0.205271631479,1.93360567093,-13.3596992493 --0.185282111168,1.93560397625,-13.3739271164 --0.144262969494,1.93362283707,-13.3633823395 --0.103267528117,1.93562877178,-13.3758430481 --0.0622557774186,1.93564379215,-13.3723020554 --0.0222407355905,1.93366026878,-13.3657484055 -0.00325545994565,1.93133413792,-12.5529985428 -0.0442714095116,1.93233108521,-12.5613746643 -0.0642732083797,1.93232643604,-12.5595588684 -0.105268619955,1.93031227589,-12.5479373932 -0.146289736032,1.93231213093,-12.5613126755 -0.187301680446,1.93330705166,-12.5656881332 -0.228316575289,1.93430376053,-12.5730638504 -0.268319189548,1.93429374695,-12.5684318542 -0.309321820736,1.93328368664,-12.5638113022 -0.330346107483,1.93629109859,-12.5839977264 -0.371356040239,1.93728494644,-12.5863723755 -0.412383049726,1.94028818607,-12.6057415009 -0.474400758743,1.94128060341,-12.6123065948 -0.515410661697,1.94227457047,-12.6146802902 -0.555405020714,1.94026017189,-12.6020545959 -0.576403856277,1.93925380707,-12.5972499847 -0.616399466991,1.93824005127,-12.5856227875 -0.657417356968,1.9402384758,-12.595993042 -0.698417067528,1.93922698498,-12.5883741379 -0.739421844482,1.93921816349,-12.5857524872 -0.780437529087,1.94021546841,-12.5941228867 -0.822456419468,1.94221436977,-12.6054992676 -0.842453479767,1.9422069788,-12.5986871719 -0.882441997528,1.93918967247,-12.5800695419 -0.924465000629,1.94219076633,-12.5954418182 -0.965471744537,1.94218313694,-12.5948190689 -1.00546848774,1.94117033482,-12.5841932297 -1.04546713829,1.94015860558,-12.5755681992 -1.08646607399,1.93914675713,-12.5669527054 -1.10748004913,1.94114863873,-12.5771360397 -1.14949584007,1.94314587116,-12.5855121613 -1.18948876858,1.94113111496,-12.5708932877 -1.22949063778,1.94112110138,-12.5652656555 -1.26948034763,1.93810474873,-12.5476512909 -1.31049418449,1.9401011467,-12.554019928 -1.3325111866,1.94210457802,-12.5672073364 -1.36948013306,1.93707740307,-12.5285902023 -1.40746200085,1.93305718899,-12.5029697418 -1.44745635986,1.93204307556,-12.4893541336 -1.4854413271,1.92902457714,-12.4667329788 -1.52241754532,1.92500138283,-12.4351148605 -1.56947135925,1.93301844597,-12.4814863205 -1.59551799297,1.94003713131,-12.5246677399 -1.63753378391,1.94203472137,-12.5330400467 -1.67954468727,1.94302940369,-12.5364189148 -1.71753001213,1.94101107121,-12.5137987137 -1.75752711296,1.93999874592,-12.5031805038 -1.80256164074,1.94500589371,-12.5305500031 -1.84054327011,1.94198560715,-12.5039377213 -1.85249006748,1.93295300007,-12.4461364746 -1.88343119621,1.92291224003,-12.3785276413 -1.91437339783,1.91287219524,-12.3119211197 -1.94632923603,1.90483939648,-12.259305954 -1.98532605171,1.90482711792,-12.2476882935 -2.02130770683,1.90080749989,-12.2210693359 -2.05628061295,1.89578342438,-12.185459137 -2.07226037979,1.8927680254,-12.1606521606 -2.10622882843,1.88674151897,-12.1200447083 -2.14322066307,1.88572728634,-12.1034221649 -2.17819809914,1.88170540333,-12.0718097687 -2.21518874168,1.87969064713,-12.0541915894 -2.24715447426,1.87366318703,-12.0105791092 -2.28615522385,1.87365341187,-12.0029611588 -2.29912233353,1.86763203144,-11.9651603699 -2.33711838722,1.86661994457,-11.9525461197 -2.3741106987,1.86560583115,-11.9359302521 -2.41110181808,1.86359143257,-11.9183177948 -2.44508075714,1.85957086086,-11.8877058029 -2.48006510735,1.8565530777,-11.8630914688 -2.49605298042,1.8545422554,-11.8462810516 -2.53103756905,1.85152471066,-11.8216686249 -2.56501746178,1.84850466251,-11.7920589447 -2.59900403023,1.84548842907,-11.7694358826 -2.63599944115,1.84547626972,-11.7558202744 -2.67399597168,1.84446465969,-11.7432117462 -2.7079808712,1.84144747257,-11.7185964584 -2.7219619751,1.8384335041,-11.6947879791 -2.75694823265,1.83541667461,-11.6711807251 -2.78993010521,1.8323982954,-11.6435651779 -2.82993841171,1.83439266682,-11.6429491043 -2.8558909893,1.82535970211,-11.5843496323 -2.88887691498,1.8233435154,-11.5607280731 -2.92286038399,1.82032573223,-11.5341262817 -2.94286775589,1.82132470608,-11.5373096466 -2.97083044052,1.81529676914,-11.4887104034 -3.00682806969,1.81428623199,-11.4770898819 -3.03880691528,1.81126654148,-11.4454851151 -3.07379984856,1.80925369263,-11.4288702011 -3.10477972031,1.80623459816,-11.3982563019 -3.14177799225,1.80622422695,-11.3866472244 -3.15576338768,1.80321276188,-11.3668403625 -3.18674135208,1.79919278622,-11.334236145 -3.21571421623,1.79517030716,-11.295633316 -3.25171399117,1.79516112804,-11.2860107422 -3.2796857357,1.79013848305,-11.2464036942 -3.31769037247,1.79113149643,-11.2417860031 -3.3486700058,1.78711235523,-11.2101860046 -3.36366152763,1.78610384464,-11.1963748932 -3.39865684509,1.78509259224,-11.1817617416 -3.43866729736,1.78708851337,-11.1831445694 -3.46262717247,1.78006029129,-11.1305503845 -3.49361085892,1.7770434618,-11.1029424667 -3.5316157341,1.7780367136,-11.0983276367 -3.55758523941,1.77301323414,-11.055724144 -3.57358050346,1.77200686932,-11.0459127426 -3.60556793213,1.76999187469,-11.0223054886 -3.63655424118,1.76797664165,-10.9976930618 -3.66753816605,1.76496005058,-10.9700918198 -3.70955610275,1.76795971394,-10.979467392 -3.7345252037,1.76293635368,-10.9358673096 -3.74851250648,1.76092588902,-10.9170713425 -3.77147865295,1.75490140915,-10.8704652786 -3.80146336555,1.75188577175,-10.8438568115 -3.83545899391,1.7518748045,-10.8282470703 -3.87446665764,1.75286972523,-10.826634407 -3.90144443512,1.74885082245,-10.7920293808 -3.9324324131,1.7478364706,-10.7684211731 -3.94842910767,1.74683070183,-10.7596120834 -3.98042082787,1.74581825733,-10.7399997711 -4.00739812851,1.74179947376,-10.7053995132 -4.04540395737,1.74279332161,-10.7007894516 -4.06536626816,1.73676764965,-10.6491909027 -4.10537815094,1.73876464367,-10.6515712738 -4.13536643982,1.73675084114,-10.6279602051 -4.14735174179,1.73473966122,-10.6061668396 -4.18235015869,1.73473036289,-10.5935602188 -4.21334171295,1.7327183485,-10.5739450455 -4.23931980133,1.72969973087,-10.5383481979 -4.27532148361,1.72969222069,-10.5297365189 -4.30430746078,1.72767746449,-10.5031318665 -4.34031057358,1.72867059708,-10.4955158234 -4.35329914093,1.7266613245,-10.4777193069 -4.3782787323,1.72364389896,-10.4441099167 -4.41327810287,1.7236354351,-10.4325017929 -4.44727659225,1.72362661362,-10.4198884964 -4.47927093506,1.72261571884,-10.4022779465 -4.50625324249,1.72059965134,-10.3716783524 -4.54926967621,1.72359848022,-10.3780670166 -4.56226062775,1.72159028053,-10.3622646332 -4.59425497055,1.7215795517,-10.3446550369 -4.62123918533,1.71856462955,-10.3160486221 -4.658244133,1.72055876255,-10.3104333878 -4.6922416687,1.72054934502,-10.2958297729 -4.73525857925,1.72454857826,-10.3032083511 -4.74524307251,1.72153782845,-10.2804136276 -4.77824020386,1.72152853012,-10.2657995224 -4.81524515152,1.7225228548,-10.2601823807 -4.84623718262,1.72151112556,-10.2395792007 -4.87722969055,1.72149956226,-10.2189769745 -4.91523456573,1.72249388695,-10.2133674622 -4.94322347641,1.72148084641,-10.1887559891 -4.9632267952,1.72147834301,-10.1869564056 -4.99522161484,1.72146809101,-10.1693487167 -5.02821922302,1.72145903111,-10.1547365189 -5.06121587753,1.72144961357,-10.139128685 -5.0902056694,1.72043776512,-10.1165189743 -5.12620735168,1.72143018246,-10.1059141159 -5.16321134567,1.72242426872,-10.0992984772 -5.17920875549,1.7224189043,-10.0895004272 -5.22122192383,1.72641670704,-10.0928783417 -5.25020980835,1.72440361977,-10.067284584 -5.28020238876,1.72339272499,-10.0466756821 -5.31119680405,1.72338247299,-10.0280647278 -5.35521125793,1.72738063335,-10.0324525833 -5.38820791245,1.72737145424,-10.0168447495 -5.40320396423,1.72636580467,-10.0060434341 -5.43720340729,1.72735786438,-9.99342727661 -5.4742064476,1.72835147381,-9.98481845856 -5.50820493698,1.72934269905,-9.9702129364 -5.53519296646,1.72733008862,-9.94460391998 -5.57119274139,1.72832214832,-9.93200683594 -5.60018444061,1.72731113434,-9.91039466858 -5.61217594147,1.72630369663,-9.8945941925 -5.64917898178,1.72729742527,-9.8859834671 -5.67616605759,1.72628426552,-9.85838794708 -5.7131690979,1.72727763653,-9.84878158569 -5.75317811966,1.73027396202,-9.84715747833 -5.77816200256,1.72725939751,-9.8155670166 -5.81316328049,1.72925245762,-9.80494689941 -5.83216571808,1.73024964333,-9.80114269257 -5.86115598679,1.72923803329,-9.77754402161 -5.89615631104,1.73023056984,-9.76493453979 -5.93315887451,1.73122394085,-9.75532627106 -5.98418140411,1.73722541332,-9.76870727539 -6.01517629623,1.73721587658,-9.75009632111 -6.03417873383,1.73821306229,-9.74628925323 -6.05816173553,1.7361985445,-9.71369934082 -6.09716701508,1.73819315434,-9.70708751678 -6.13016462326,1.73818469048,-9.69147586823 -6.16316080093,1.73917543888,-9.67387676239 -6.19315433502,1.73816549778,-9.65326881409 -6.22915458679,1.74015808105,-9.64066505432 -6.25015926361,1.74115622044,-9.6398563385 -6.27614688873,1.74014389515,-9.61225509644 -6.31415176392,1.74213826656,-9.604637146 -6.33813619614,1.74012458324,-9.57304573059 -6.36712789536,1.7391140461,-9.55044174194 -6.42115211487,1.74611616135,-9.56581783295 -6.46115779877,1.74811089039,-9.55920791626 -6.47715616226,1.74810647964,-9.5504026413 -6.50414514542,1.7470946312,-9.52380466461 -6.56117296219,1.75509786606,-9.54317474365 -6.57013940811,1.74807775021,-9.49058914185 -6.60613870621,1.75006985664,-9.47599220276 -6.64414262772,1.75206410885,-9.46737480164 -6.66712760925,1.75005090237,-9.43577671051 -6.69413805008,1.75305104256,-9.44097328186 -6.72613382339,1.75304210186,-9.42236804962 -6.76413631439,1.75503599644,-9.41275501251 -6.79513072968,1.75502645969,-9.39215373993 -6.83313417435,1.75802052021,-9.3825378418 -6.86012363434,1.75700902939,-9.35594177246 -6.88012599945,1.75800645351,-9.35213565826 -6.91212129593,1.7579972744,-9.33253574371 -6.94711971283,1.75898945332,-9.3169336319 -6.97911643982,1.75998103619,-9.29932022095 -7.01611804962,1.7619740963,-9.28671264648 -7.04410886765,1.76096367836,-9.26211261749 -7.08411312103,1.76395773888,-9.25250911713 -7.10211372375,1.76495444775,-9.24669742584 -7.14011526108,1.76694762707,-9.2340965271 -7.17010879517,1.76693809032,-9.21249198914 -7.20010232925,1.76692831516,-9.18989276886 -7.24811506271,1.77092587948,-9.19127655029 -7.28111219406,1.77191758156,-9.17366695404 -7.31911420822,1.77491128445,-9.16205596924 -7.35212945938,1.7789131403,-9.17324447632 -7.39713859558,1.78290891647,-9.16963195801 -7.43013525009,1.78390049934,-9.15102672577 -7.48315191269,1.78989934921,-9.1574048996 -7.51314496994,1.78988969326,-9.13480186462 -7.54814291,1.79088163376,-9.11720371246 -7.57513332367,1.79087090492,-9.09060382843 -7.60514450073,1.79387152195,-9.0977897644 -7.64815139771,1.79786646366,-9.09117412567 -7.67013549805,1.79585385323,-9.05758476257 -7.69812726974,1.79584395885,-9.03297996521 -7.71811008453,1.79283058643,-8.99639892578 -7.7290854454,1.78881514072,-8.95180606842 -7.46280956268,1.71871685982,-8.60524940491 -7.47779130936,1.71570396423,-8.56765365601 -7.49677658081,1.71369218826,-8.53406238556 -7.52376937866,1.71368300915,-8.50946617126 -7.51873159409,1.70566368103,-8.4478969574 -7.51870012283,1.6986464262,-8.39331912994 -7.52867794037,1.694632411,-8.34973716736 -7.54167461395,1.69462811947,-8.33793449402 -7.54664802551,1.68861269951,-8.28935527802 -7.56463336945,1.68660151958,-8.25576496124 -7.58462190628,1.68559110165,-8.22516822815 -7.59760284424,1.68157851696,-8.18558692932 -7.62159442902,1.68156933784,-8.15899181366 -7.64258337021,1.67955935001,-8.12939739227 -7.64557170868,1.67755198479,-8.10561275482 -7.66055631638,1.67454099655,-8.07101249695 -7.67954349518,1.67253041267,-8.03842830658 -7.68351793289,1.66751611233,-7.99084806442 -7.7155175209,1.66950953007,-7.97324752808 -7.73750829697,1.66850030422,-7.94465684891 -7.74248456955,1.66348683834,-7.89907360077 -7.75548171997,1.66348278522,-7.88727426529 -7.77246856689,1.66147243977,-7.85368776321 -7.78244972229,1.65746057034,-7.81409788132 -7.80844402313,1.6574524641,-7.78950977325 -7.82643270493,1.65644276142,-7.7579164505 -7.83241128922,1.65143024921,-7.71433353424 -7.84939956665,1.65042042732,-7.68174362183 -7.8694024086,1.65141832829,-7.67694139481 -7.88839101791,1.65040910244,-7.64635133743 -7.89837360382,1.64639770985,-7.60676908493 -7.92436933517,1.64739048481,-7.58416604996 -7.93635368347,1.64437973499,-7.54658460617 -7.94033145905,1.63936722279,-7.50101232529 -7.96132421494,1.63935923576,-7.47440719604 -7.95830917358,1.6353520155,-7.44662809372 -7.97930145264,1.63534390926,-7.4190325737 -7.99228715897,1.6323338747,-7.38344717026 -8.00327205658,1.62932384014,-7.34685659409 -8.01025485992,1.62531268597,-7.3052816391 -8.03024578094,1.624304533,-7.27669143677 -8.03523731232,1.62329924107,-7.25690698624 -8.05522918701,1.62229156494,-7.22930812836 -8.07021808624,1.62028264999,-7.19671726227 -8.08220481873,1.618273139,-7.16113185883 -8.09319019318,1.61526334286,-7.12355804443 -8.11918735504,1.6162570715,-7.10195207596 -8.12617015839,1.61224675179,-7.061378479 -8.13316440582,1.61124253273,-7.04557657242 -8.15515804291,1.61123538017,-7.01898765564 -8.15513801575,1.60622417927,-6.97341060638 -8.18113422394,1.60721790791,-6.95081567764 -8.20412921906,1.60721123219,-6.92621707916 -8.19810581207,1.60119926929,-6.87564706802 -8.21809768677,1.60019207001,-6.84805631638 -8.22609424591,1.6001881361,-6.83226394653 -8.23407936096,1.5971788168,-6.79368925095 -8.25006961823,1.59517109394,-6.76309919357 -8.2610578537,1.59316277504,-6.72851037979 -8.27104568481,1.59115433693,-6.69292545319 -8.28903770447,1.59014701843,-6.66334152222 -8.29102897644,1.58814251423,-6.64354753494 -8.19495105743,1.56411755085,-6.52103900909 -8.28999233246,1.57912278175,-6.55539798737 -8.315990448,1.58011722565,-6.53379774094 -8.33098125458,1.57811009884,-6.50320720673 -8.33596611023,1.57510137558,-6.46363306046 -8.3629655838,1.57609605789,-6.44203996658 -8.36495780945,1.5740916729,-6.42225074768 -8.3759469986,1.57208418846,-6.38866329193 -8.40995025635,1.57508003712,-6.37306070328 -8.4209394455,1.57307267189,-6.33947372437 -8.44993972778,1.57506752014,-6.31888437271 -8.44992351532,1.57105898857,-6.27730226517 -8.45390892029,1.56705057621,-6.23772954941 -8.4609041214,1.56604731083,-6.22193861008 -8.47989940643,1.56604146957,-6.19534111023 -8.49188995361,1.56503450871,-6.16275548935 -8.51588821411,1.56502914429,-6.13916349411 -8.51987457275,1.5620213747,-6.10058546066 -8.53486728668,1.56101536751,-6.07099246979 -8.53785419464,1.55800747871,-6.0314207077 -8.54284954071,1.55700409412,-6.01462841034 -8.55183887482,1.55499720573,-5.98004817963 -8.56583118439,1.55399107933,-5.94946146011 -8.57482147217,1.55098438263,-5.91488409042 -8.58881473541,1.54997849464,-5.88528871536 -8.59380340576,1.54797172546,-5.84870624542 -8.60979652405,1.54696583748,-5.81912517548 -8.60378646851,1.54396140575,-5.79434680939 -8.62878608704,1.54495704174,-5.77274274826 -8.63477611542,1.54295063019,-5.73716020584 -8.64776802063,1.54094469547,-5.70558309555 -8.65775966644,1.53993880749,-5.67299699783 -8.66374874115,1.53693246841,-5.63741827011 -8.66674423218,1.53592932224,-5.61962938309 -8.67073345184,1.53292298317,-5.58304977417 -8.68872928619,1.53291797638,-5.55546569824 -8.69071769714,1.52991163731,-5.5178861618 -8.69770812988,1.5279058218,-5.48330783844 -8.70369911194,1.52589988708,-5.44872426987 -8.70969009399,1.52289438248,-5.41414213181 -8.71268463135,1.52189135551,-5.39635658264 -8.72367858887,1.52088606358,-5.36477470398 -8.72266578674,1.51688015461,-5.32619524002 -8.74066352844,1.51687562466,-5.29960441589 -8.73664951324,1.51286959648,-5.2590303421 -8.73663806915,1.50986385345,-5.22144985199 -8.75463581085,1.50985944271,-5.19387197495 -8.75162887573,1.50785636902,-5.17308664322 -8.74661540985,1.50385057926,-5.13251256943 -8.76161193848,1.50384616852,-5.10392856598 -8.76160144806,1.50084090233,-5.06734371185 -8.77159500122,1.49883627892,-5.03576469421 -8.78659152985,1.49883198738,-5.00718212128 -8.79258441925,1.49682748318,-4.97459173203 -8.78957748413,1.49482476711,-4.95381164551 -8.79757118225,1.4928201437,-4.9212346077 -8.79856204987,1.48981535435,-4.88466262817 -8.80555534363,1.48881101608,-4.85306978226 -8.82055282593,1.48880708218,-4.82449054718 -8.82454490662,1.48580265045,-4.78991699219 -8.82353973389,1.48480045795,-4.77211809158 -8.82753276825,1.48279607296,-4.73754549026 -8.83252620697,1.48079204559,-4.70495700836 -8.84852313995,1.48078835011,-4.67737531662 -8.85851860046,1.47978448868,-4.64679336548 -8.87551593781,1.47978103161,-4.62020540237 -8.87050628662,1.47577679157,-4.58163309097 -8.87450408936,1.47577488422,-4.56584262848 -8.88950061798,1.47577154636,-4.53825616837 -8.87848949432,1.47076714039,-4.49668931961 -8.88648414612,1.46976351738,-4.46511220932 -8.89447975159,1.46876013279,-4.43452358246 -8.87446498871,1.46175575256,-4.38797187805 -8.86445331573,1.45775198936,-4.34839439392 -8.84144210815,1.45274960995,-4.31961536407 -8.85944080353,1.45274662971,-4.2930393219 -8.82942390442,1.44474244118,-4.24347925186 -8.76139259338,1.43073761463,-4.1749458313 -8.73437690735,1.42273390293,-4.12738752365 -8.81739997864,1.43573284149,-4.13376617432 -8.75637245178,1.42172861099,-4.07022380829 -8.75837039948,1.42072725296,-4.05443286896 -8.71635055542,1.41172361374,-3.99988913536 -8.70333957672,1.40672075748,-3.96031975746 -8.64331436157,1.39371728897,-3.89877748489 -8.65231227875,1.3937151432,-3.87019348145 -8.56727981567,1.37571167946,-3.7966811657 -8.36120986938,1.3387080431,-3.68402695656 -8.34319972992,1.33370602131,-3.64445590973 -8.48824214935,1.3567057848,-3.67879724503 -8.47323417664,1.35170388222,-3.64022779465 -8.41020965576,1.3387016058,-3.57969450951 -8.43321418762,1.34070014954,-3.55909562111 -8.44121265411,1.33969867229,-3.53150963783 -8.46021652222,1.3416980505,-3.5237159729 -8.50422763824,1.34769666195,-3.51210451126 -8.33817386627,1.3166949749,-3.4076423645 -8.19412708282,1.28969395161,-3.31515002251 -8.16211605072,1.28269302845,-3.27060222626 -8.18412017822,1.28469216824,-3.25001072884 -8.09109115601,1.26669180393,-3.18148398399 -8.02007007599,1.25369179249,-3.13674283028 -8.02707099915,1.25269126892,-3.11016464233 -7.99906158447,1.24569106102,-3.06960272789 -7.92904043198,1.23269128799,-3.01206803322 -7.90503263474,1.22669148445,-2.97350811958 -7.86502122879,1.21769177914,-2.92895555496 -7.87202262878,1.21769165993,-2.90337443352 -7.80100297928,1.20469260216,-2.86162304878 -7.80200386047,1.20269286633,-2.83305978775 -7.75799179077,1.19369375706,-2.78850293159 -7.74198770523,1.1896944046,-2.75493121147 -7.76199293137,1.19069445133,-2.73533654213 -7.73098611832,1.18469548225,-2.6957821846 -7.67297124863,1.17369687557,-2.66003322601 -7.6629691124,1.17069780827,-2.62945699692 -7.67097234726,1.16969835758,-2.60488247871 -7.65897035599,1.16669940948,-2.57331490517 -7.57195043564,1.15070235729,-2.51479291916 -7.58195400238,1.15070307255,-2.49220347404 -7.53294372559,1.14070534706,-2.44865059853 -7.63396883011,1.15770328045,-2.47080516815 -7.56595468521,1.14470624924,-2.42027211189 -7.48093605042,1.1287099123,-2.36474347115 -7.5039434433,1.13171052933,-2.34714365005 -7.4129242897,1.11471474171,-2.2906165123 -7.43593215942,1.11671555042,-2.27203655243 -7.45493793488,1.1197155714,-2.26622486115 -7.42593383789,1.11371815205,-2.23066973686 -7.37292480469,1.10372161865,-2.18811917305 -7.28690862656,1.08772647381,-2.13460040092 -7.27590990067,1.0847287178,-2.10603117943 -7.27391242981,1.08273077011,-2.08045649529 -7.25991249084,1.07973325253,-2.05187678337 -7.22990846634,1.07373559475,-2.03010749817 -7.24391460419,1.07473695278,-2.01051020622 -7.21391201019,1.0687404871,-1.97596478462 -7.21291589737,1.06774258614,-1.95138502121 -7.17591190338,1.06074643135,-1.91681516171 -7.18291759491,1.06074845791,-1.89424109459 -7.15791702271,1.05475199223,-1.86268031597 -7.13991546631,1.0517539978,-1.84589397907 -7.12791728973,1.04875695705,-1.81832635403 -7.12692165375,1.04675960541,-1.79375684261 -7.08191776276,1.03876447678,-1.75720822811 -7.08392238617,1.03776705265,-1.73462045193 -7.06392335892,1.03377068043,-1.7060457468 -7.04892587662,1.03077411652,-1.67847716808 -7.03292560577,1.0267765522,-1.66171205044 -7.01592731476,1.02378034592,-1.63413953781 -7.02693462372,1.02478253841,-1.6145414114 -7.01993846893,1.02178585529,-1.5889775753 -6.9889383316,1.0157905817,-1.5584089756 -6.99494504929,1.01579320431,-1.53682887554 -6.96094179153,1.00979685783,-1.51705574989 -6.98895215988,1.01379835606,-1.50047230721 -7.0009598732,1.01480066776,-1.48087966442 -7.13098669052,1.03579568863,-1.48922336102 -7.18600082397,1.0437951088,-1.47861838341 -6.93996763229,1.00281405449,-1.39817738533 -6.91796970367,0.997818887234,-1.37061011791 -6.95297861099,1.00381839275,-1.36681032181 -6.87297201157,0.989826917648,-1.3272588253 -6.86697769165,0.987830996513,-1.30270135403 -6.96799898148,1.00382745266,-1.30305397511 -6.89199399948,0.989836335182,-1.26353156567 -6.85399484634,0.982842504978,-1.23396086693 -6.84300041199,0.980846881866,-1.20939147472 -6.83600282669,0.978849351406,-1.19661211967 -6.83600950241,0.978852987289,-1.17502522469 -6.83901643753,0.977856516838,-1.15344893932 -6.80801868439,0.972862482071,-1.12587821484 -7.14207029343,1.0258409977,-1.16812169552 -6.90404605865,0.986862957478,-1.09968268871 -6.79703903198,0.968875050545,-1.05815327168 -6.81104469299,0.97087597847,-1.04936611652 -6.79904985428,0.967880785465,-1.02578747272 -6.79005622864,0.965885579586,-1.00221908092 -6.80506515503,0.96788829565,-0.983624339104 -6.79707193375,0.965892970562,-0.961041390896 -6.93409585953,0.9878860116,-0.961409807205 -6.79308223724,0.964899539948,-0.927681088448 -6.7910900116,0.963903784752,-0.906097710133 -6.80009841919,0.964907288551,-0.885523736477 -6.78010368347,0.960913181305,-0.860953748226 -6.77811145782,0.959917545319,-0.839372694492 -6.7681183815,0.957922816277,-0.815811812878 -6.76712608337,0.956927239895,-0.794234931469 -6.80613422394,0.96292591095,-0.78942155838 -6.80714178085,0.96293002367,-0.768828094006 -6.77714729309,0.95693731308,-0.742283642292 -6.74515199661,0.95194464922,-0.716719210148 -6.72815799713,0.948950469494,-0.694131851196 -6.71516561508,0.945956349373,-0.670574784279 -6.73417568207,0.948959112167,-0.651984453201 -6.71317768097,0.944963276386,-0.639198184013 -6.74218845367,0.948965191841,-0.621606171131 -6.7281961441,0.94697111845,-0.599030435085 -6.71920394897,0.944976687431,-0.576465845108 -7.00223636627,0.989953994751,-0.587730646133 -6.68321800232,0.937989711761,-0.530331134796 -6.67022609711,0.935995578766,-0.508745610714 -6.65522861481,0.932999432087,-0.496960222721 -6.78524780273,0.953991353512,-0.48931568861 -6.68724966049,0.938006162643,-0.45780223608 -6.67325735092,0.935012280941,-0.436219155788 -6.68326663971,0.936016082764,-0.416629940271 -6.68327617645,0.936021208763,-0.395066678524 -6.73728466034,0.945018172264,-0.389252096415 -6.72529268265,0.942024350166,-0.367672234774 -6.654296875,0.931036651134,-0.341127723455 -6.78631448746,0.951027929783,-0.330486685038 -6.75232172012,0.94603651762,-0.306924402714 -6.68132638931,0.934048950672,-0.281372368336 -6.66733503342,0.932055592537,-0.259798586369 -6.66833972931,0.932058155537,-0.24901920557 -6.65134859085,0.929065108299,-0.227445617318 -6.6453576088,0.928070902824,-0.206862077117 -6.65436792374,0.929075241089,-0.186289429665 -6.66137742996,0.930079579353,-0.166694477201 -6.70438957214,0.936080098152,-0.148098140955 -6.67939805984,0.932088375092,-0.125544548035 -6.63840103149,0.926095485687,-0.113766379654 -6.64541149139,0.92710018158,-0.0931914746761 -6.66642189026,0.930103123188,-0.0736002027988 -6.61042928696,0.921114861965,-0.0510470531881 -6.64044046402,0.925116896629,-0.031457465142 -6.71845340729,0.938113212585,-0.0138299101964 -6.61045885086,0.920131146908,0.00969906523824 -6.62246465683,0.922132492065,0.0194963160902 -6.64447593689,0.926135599613,0.0400728955865 -6.61748456955,0.92114418745,0.0606476515532 -6.68749761581,0.932141602039,0.0802536085248 -6.715508461,0.937143921852,0.100839555264 -6.80652141571,0.951138556004,0.120466060936 -6.77252531052,0.946145415306,0.131239250302 -6.81853675842,0.953145384789,0.151841104031 -6.65854310989,0.928170382977,0.173340141773 -6.59355211258,0.917183995247,0.193885922432 -6.97657060623,0.978142738342,0.215652316809 -6.62957334518,0.923190951347,0.234075963497 -6.59758377075,0.918200790882,0.254630386829 -9.71463871002,1.4128152132,0.303938984871 -6.56759929657,0.913213074207,0.283998787403 -6.62861061096,0.923211395741,0.305601596832 -6.61062145233,0.920219659805,0.326161533594 -6.61563253403,0.921224892139,0.34674140811 -6.64164304733,0.925227344036,0.367343276739 -6.65464878082,0.927228748798,0.378135353327 -6.5966591835,0.918242037296,0.396689176559 -6.60067033768,0.919247508049,0.417268365622 -6.64668178558,0.926247656345,0.439859569073 -6.5826921463,0.916261911392,0.457414627075 -6.59470319748,0.918266355991,0.478004813194 -6.59371471405,0.918272614479,0.498578041792 -6.67772054672,0.932264745235,0.513397157192 -6.6337313652,0.925276398659,0.530970752239 -6.64774227142,0.927280724049,0.552550077438 -6.62475442886,0.924290001392,0.572111070156 -9.65773963928,1.40688896179,0.783120155334 -6.78277540207,0.949281036854,0.623343408108 -6.81078577042,0.954283237457,0.645941734314 -6.64679288864,0.928308427334,0.644662618637 -6.54880571365,0.913327991962,0.658194541931 -6.50981807709,0.907339632511,0.675750792027 -6.5628285408,0.915338814259,0.700349390507 -6.52784109116,0.910349965096,0.717910528183 -6.58385133743,0.919348478317,0.742524087429 -6.50185871124,0.906362891197,0.745282709599 -6.50187063217,0.907369434834,0.765853941441 -6.49088287354,0.90537750721,0.785419642925 -6.51389408112,0.909380495548,0.807025671005 -6.4989066124,0.90738928318,0.826581478119 -6.4709186554,0.903399467468,0.843163847923 -6.49093055725,0.906403303146,0.86574536562 -6.46393680573,0.902410268784,0.872531533241 -6.46794891357,0.903416216373,0.893112659454 -6.46396160126,0.903423666954,0.913672506809 -6.45797348022,0.902430832386,0.932267129421 -6.45298624039,0.902438521385,0.952823579311 -6.4979968071,0.909438610077,0.978425323963 -6.48900938034,0.908446311951,0.997012913227 -6.46501636505,0.905453383923,1.00477766991 -6.45602893829,0.90446126461,1.02336287498 -6.44004201889,0.90247040987,1.04192495346 -6.43705463409,0.902477562428,1.06150710583 -6.43806695938,0.902484238148,1.08208191395 -6.54707479477,0.920474767685,1.11771583557 -6.585085392,0.92747604847,1.14430403709 -6.50509500504,0.914491057396,1.14207196236 -6.50010871887,0.914498865604,1.16263198853 -6.4701218605,0.909510076046,1.17820310593 -6.44513607025,0.906520664692,1.19476914406 -6.43414878845,0.905529201031,1.21334373951 -6.48815870285,0.914527714252,1.24195969105 -6.43916797638,0.906538784504,1.24471437931 -6.42618083954,0.905547499657,1.26230049133 -6.5181889534,0.920540511608,1.2989128828 -6.44820594788,0.909558236599,1.30745768547 -6.42921972275,0.907567918301,1.32403898239 -6.42823266983,0.907575130463,1.34461152554 -6.41624641418,0.906584143639,1.36317896843 -6.45725011826,0.913581311703,1.38098847866 -6.41126585007,0.906595349312,1.39255309105 -6.42027854919,0.908601105213,1.4151289463 -6.39929246902,0.905611217022,1.43071568012 -6.40930509567,0.908616781235,1.45329761505 -6.37832021713,0.903628826141,1.46785664558 -6.36433458328,0.902638196945,1.48543024063 -6.45133543015,0.916628241539,1.51424777508 -6.4103512764,0.910641729832,1.52581954002 -6.42936325073,0.914645850658,1.55040991306 -6.44037532806,0.916651427746,1.57398474216 -6.40839147568,0.912663638592,1.58755338192 -6.42340373993,0.915668666363,1.61212933064 -6.40941143036,0.913674414158,1.61892175674 -6.42842340469,0.917678713799,1.64450025558 -6.41943693161,0.916687369347,1.6630795002 -6.6054353714,0.947664618492,1.72774112225 -6.59644937515,0.947673380375,1.74731242657 -6.44747495651,0.923704862595,1.73282420635 -6.41849088669,0.919716715813,1.74639797211 -6.4094991684,0.918722093105,1.75517356396 -6.42751073837,0.922726452351,1.78075885773 -6.40752601624,0.919737040997,1.79633748531 -6.36454343796,0.91375130415,1.80590641499 -6.36055755615,0.9137596488,1.82647037506 -6.40556716919,0.922759532928,1.85907387733 -6.42257928848,0.925764143467,1.88466227055 -6.47758102417,0.935758948326,1.91046786308 -6.37260437012,0.918783724308,1.90300774574 -6.38461732864,0.921789228916,1.92758905888 -6.39263057709,0.92479544878,1.95116901398 -6.3846449852,0.923804223537,1.96975302696 -6.39865732193,0.926809430122,1.99533224106 -6.40367078781,0.928816139698,2.01791810989 -6.39767837524,0.928820848465,2.02670860291 -6.38969326019,0.92782998085,2.04627418518 -6.36870908737,0.925840854645,2.06085658073 -6.35272455215,0.923851191998,2.07742929459 -6.52672052383,0.953829407692,2.15207648277 -6.56373071671,0.960830807686,2.18566799164 -6.39675521851,0.933862745762,2.14439964294 -6.37877178192,0.931873619556,2.16096067429 -6.39178419113,0.93487906456,2.18654823303 -6.3488035202,0.928894340992,2.19509792328 -6.42180919647,0.941889345646,2.23971939087 -6.5168132782,0.958880901337,2.29332590103 -6.46083307266,0.950898110867,2.29688572884 -6.38884830475,0.939914286137,2.28365278244 -6.40086174011,0.942920207977,2.3102247715 -6.24789333344,0.917954266071,2.27975201607 -6.23590946198,0.916964232922,2.29732322693 -6.22492551804,0.916973948479,2.31490063667 -6.25393629074,0.922976732254,2.34649324417 -6.46991872787,0.959943413734,2.43435049057 -6.35694599152,0.941970765591,2.41589832306 -9.44958591461,1.46443915367,3.55761814117 -9.43759822845,1.46444797516,3.58619213104 -6.52096939087,0.972965657711,2.54269599915 -6.35200500488,0.946003258228,2.50320577621 -6.61098718643,0.990965783596,2.6228749752 -6.6179933548,0.992968380451,2.63667559624 -6.33604288101,0.94602560997,2.5521633625 -6.32405996323,0.946035981178,2.57072353363 -6.32607364655,0.947043418884,2.59331417084 -6.35708475113,0.954045891762,2.62790441513 -6.34910011292,0.9540553689,2.64747881889 -6.35211515427,0.95606315136,2.6720457077 -6.33412456512,0.953070223331,2.67583537102 -6.36413574219,0.960072815418,2.71042919159 -6.35415172577,0.959082901478,2.72999024391 -6.32816982269,0.956095457077,2.74157118797 -6.34218263626,0.960100948811,2.77015662193 -6.52817296982,0.994076013565,2.87178659439 -6.43620014191,0.979100525379,2.85633826256 -6.42120933533,0.977107048035,2.86113238335 -6.46721792221,0.987107038498,2.90471863747 -6.40824079514,0.978125572205,2.90228796005 -6.4862446785,0.993119716644,2.95989084244 -6.36527681351,0.973149597645,2.93043136597 -6.39228820801,0.980153024197,2.96601676941 -6.3722987175,0.97716063261,2.96880125999 -6.35231637955,0.975172460079,2.9833741188 -6.4283208847,0.990167081356,3.04196763039 -6.41133880615,0.989178538322,3.05853414536 -6.39335632324,0.987190008163,3.0741083622 -6.36837482452,0.984202563763,3.0856924057 -6.37138986588,0.986210346222,3.1112678051 -6.39539384842,0.991210281849,3.13505578041 -6.43440294266,1.00021111965,3.17666506767 -6.37642765045,0.99123030901,3.17420911789 -6.34044790268,0.987245082855,3.18078160286 -6.32746505737,0.986255764961,3.19836068153 -6.33847904205,0.99026209116,3.22794270515 -6.36649036407,0.996265470982,3.26652193069 -6.37949562073,1.0002669096,3.28433012962 -6.3485159874,0.996281266212,3.29389095306 -6.40152311325,1.00727987289,3.34547948837 -6.40253782272,1.00928795338,3.37007069588 -6.34256315231,1.00030755997,3.36462521553 -6.35957622528,1.00531280041,3.39820766449 -6.35558462143,1.00531792641,3.40898871422 -6.35060071945,1.00632715225,3.43057799339 -6.32462072372,1.00334048271,3.44214439392 -6.56359767914,1.04830431938,3.59379315376 -6.32165193558,1.00635790825,3.49030470848 -6.48164176941,1.03733670712,3.60192346573 -6.31268501282,1.00937652588,3.5354642868 -6.31569242477,1.01038038731,3.55024528503 -6.29971075058,1.00939202309,3.56681871414 -6.30672502518,1.01239895821,3.59540939331 -6.31973934174,1.01740539074,3.62897729874 -6.29875850677,1.01541781425,3.6425538063 -6.29277515411,1.01642739773,3.66414093971 -6.31477928162,1.02142775059,3.68992829323 -6.29679822922,1.02043962479,3.70550084114 -6.29081535339,1.02144956589,3.72807455063 -6.306828022,1.02645492554,3.76266694069 -6.2868475914,1.02446746826,3.77723693848 -6.29386281967,1.02747488022,3.8078110218 -6.29287862778,1.02948379517,3.83338975906 -6.3458776474,1.0404779911,3.87819075584 -6.31389951706,1.03749299049,3.88575816154 -6.31091499329,1.0385017395,3.90935349464 -6.33392763138,1.04550635815,3.950922966 -6.299949646,1.04152143002,3.95649933815 -6.26497173309,1.0365370512,3.96206307411 -6.28998327255,1.04354071617,4.00365829468 -6.27499437332,1.04254829884,4.00843334198 -6.31000375748,1.0505502224,4.05702543259 -6.30302143097,1.05156028271,4.07960510254 -6.28704071045,1.05157220364,4.09717226028 -6.30605363846,1.05757749081,4.13675403595 -6.32806539536,1.06358194351,4.17834043503 -6.25909471512,1.05360388756,4.16090631485 -6.31809186935,1.06559693813,4.21271657944 -6.30111122131,1.06460928917,4.2302775383 -6.28413009644,1.06362104416,4.24586772919 -6.24415445328,1.05863797665,4.24841785431 -6.29416131973,1.0706371069,4.30902004242 -6.27718067169,1.06964921951,4.32559633255 -6.26619148254,1.06965577602,4.33238172531 -6.23821306229,1.06667017937,4.34194755554 -6.26722383499,1.07467341423,4.38954114914 -6.29923391342,1.08367609978,4.44012784958 -6.35723924637,1.09667384624,4.50971317291 -6.26927280426,1.08269989491,4.47727108002 -6.23729562759,1.07971513271,4.48383903503 -6.26329851151,1.08571434021,4.51564884186 -6.23632049561,1.08272874355,4.52621030807 -6.27033042908,1.0927311182,4.57979488373 -6.24835157394,1.09074449539,4.59336709976 -6.29335927963,1.10274457932,4.65496253967 -6.27337932587,1.10175728798,4.66954469681 -6.2703962326,1.10376703739,4.69712209702 -6.23741149902,1.09877800941,4.68790102005 -6.23142910004,1.09978818893,4.71347522736 -6.23044633865,1.10279762745,4.74304819107 -6.24146127701,1.10780465603,4.78162574768 -6.23447942734,1.10981488228,4.8062081337 -6.23849487305,1.11282336712,4.83978557587 -6.24151134491,1.11683177948,4.87236833572 -6.25551700592,1.12083375454,4.89915132523 -6.27053022385,1.12683975697,4.9407453537 -6.26354837418,1.12885022163,4.96632289886 -6.23657131195,1.12686479092,4.97688770294 -6.26058292389,1.13386905193,5.02647972107 -6.23560571671,1.13288342953,5.03904008865 -6.24161243439,1.13488662243,5.05884027481 -6.25462627411,1.14089310169,5.1004281044 -6.22464990616,1.13790845871,5.10898733139 -6.25665998459,1.14791119099,5.16657686234 -6.24867868423,1.14992213249,5.19215488434 -6.25269508362,1.15393042564,5.22773504257 -6.23770666122,1.15193831921,5.23250865936 -6.24972105026,1.15794479847,5.27410173416 -6.24074029922,1.1599560976,5.29967403412 -6.23175907135,1.16096711159,5.32524728775 -6.27776622772,1.17396712303,5.39684104919 -6.25178861618,1.17198169231,5.40840959549 -6.24880647659,1.17499148846,5.43899154663 -6.2508149147,1.17699575424,5.45777797699 -6.26082992554,1.18300318718,5.50035667419 -6.28684139252,1.19200730324,5.55694150925 -6.24086856842,1.18602573872,5.55051517487 -6.24388456345,1.19003427029,5.58709812164 -6.24590158463,1.19404327869,5.62367343903 -6.29090881348,1.20704364777,5.69826507568 -6.28791809082,1.20904898643,5.71305418015 -6.35691976547,1.22704446316,5.81064605713 -6.41892385483,1.24404168129,5.90323257446 -6.40994262695,1.2460526228,5.93081521988 -6.4509510994,1.25905394554,6.00539875031 -6.25301265717,1.22010290623,5.85893678665 -6.22803497314,1.21911728382,5.87151193619 -6.25903654099,1.2271156311,5.91830968857 -6.2490568161,1.22912728786,5.94587945938 -6.28406572342,1.24112975597,6.01546621323 -6.33707141876,1.25712859631,6.10305404663 -6.44506454468,1.28411626816,6.24365949631 -6.74601268768,1.35506498814,6.57131195068 -6.35511064529,1.27114844322,6.21401119232 -6.37412405014,1.27915430069,6.27158403397 -6.30415725708,1.26817774773,6.24115228653 -6.30917310715,1.27318608761,6.2837395668 -6.31918859482,1.28019368649,6.33231973648 -6.25722026825,1.27121567726,6.30988025665 -6.26423597336,1.27722382545,6.35546302795 -6.24624919891,1.27523231506,6.35724401474 -6.26826190948,1.2842373848,6.41882514954 -6.3012714386,1.29624021053,6.49141597748 -6.1893157959,1.27527248859,6.41696643829 -6.22732448578,1.28927433491,6.49555444717 -6.23334026337,1.29528284073,6.54213047028 -6.23835659027,1.30029118061,6.58671951294 -6.23036766052,1.30129778385,6.5994977951 -6.30936670303,1.32429134846,6.72309684753 -6.27639198303,1.32130777836,6.72966718674 -6.22842168808,1.3153270483,6.72023296356 -6.27242851257,1.33032774925,6.80882263184 -6.22345781326,1.32334721088,6.79739618301 -6.23246431351,1.32835030556,6.82818698883 -6.31246328354,1.35234391689,6.95877218246 -6.22050333023,1.33537209034,6.90033578873 -6.26850938797,1.35137212276,6.99592590332 -6.25852966309,1.35438382626,7.02849960327 -6.25254869461,1.3583946228,7.06508016586 -6.31055307388,1.37739276886,7.17466688156 -6.31356143951,1.38039696217,7.20045566559 -6.34457159042,1.39340043068,7.28103542328 -6.32459449768,1.39441430569,7.30360841751 -6.31061506271,1.39642655849,7.33120107651 -6.29363775253,1.39744007587,7.35876226425 -6.27566003799,1.39945340157,7.38334083557 -6.25168371201,1.39846813679,7.40190935135 -6.24269485474,1.39947474003,7.41370344162 -6.23071575165,1.40248680115,7.44528532028 -6.21973657608,1.40549910069,7.47985315323 -6.19676017761,1.4055134058,7.49843454361 -6.17078495026,1.40452861786,7.51500034332 -6.15980577469,1.40754055977,7.54857969284 -6.15081691742,1.40854728222,7.56136751175 -6.12984037399,1.40856134892,7.58294534683 -6.11286258698,1.41057467461,7.60952329636 -6.09888458252,1.41258752346,7.64109230042 -6.08390665054,1.41560041904,7.67066860199 -6.07492637634,1.41861200333,7.7072520256 -3.46559500694,0.756149947643,4.44746303558 -3.43761205673,0.751160740852,4.42624473572 -3.4366312027,0.7541705966,4.45183897018 -3.41765618324,0.75318467617,4.45640325546 -3.3916823864,0.750199973583,4.45097923279 -5.96105623245,1.42368984222,7.83390569687 -5.95307683945,1.42870140076,7.87348461151 -5.93009185791,1.42571091652,7.86827135086 -5.91811323166,1.42872357368,7.90384054184 -5.90013647079,1.43073689938,7.92942762375 -5.877161026,1.43075180054,7.95099163055 -5.8571844101,1.43276584148,7.97556591034 -5.84120702744,1.43477880955,8.00415325165 -5.80923366547,1.43279540539,8.01272296906 -5.80624341965,1.43480086327,8.03451251984 -5.79226589203,1.43881392479,8.0680847168 -5.76329231262,1.4378298521,8.08065700531 -5.73831748962,1.43784511089,8.09922599792 -5.72234010696,1.43985819817,8.12880897522 -5.69036722183,1.43787479401,8.13737869263 -5.67538976669,1.4408878088,8.16896057129 -5.66840076447,1.44289422035,8.18574905396 -5.63942718506,1.44191038609,8.19832038879 -5.61845159531,1.44292461872,8.22189903259 -5.60147476196,1.44493818283,8.25246906281 -5.57050180435,1.44395458698,8.26104831696 -5.5515255928,1.44596850872,8.28861999512 -5.52855062485,1.44698345661,8.31019306183 -5.51756191254,1.44699048996,8.3199930191 -5.49258804321,1.44700574875,8.33856582642 -5.46761369705,1.44802081585,8.35713863373 -5.43964004517,1.44703674316,8.37071418762 -5.42466306686,1.45105004311,8.40528488159 -5.40568637848,1.4520637989,8.43186855316 -5.38470172882,1.45007324219,8.42864990234 -5.36572599411,1.45208752155,8.45722103119 -5.34275150299,1.45310223103,8.4787979126 -5.31677675247,1.45311737061,8.49438285828 -5.2978014946,1.4561316967,8.52395057678 -5.27582645416,1.45714640617,8.54752540588 -5.24685335159,1.4561624527,8.56009864807 -5.237865448,1.45816934109,8.57488918304 -5.21089172363,1.4581849575,8.59046459198 -5.18691682816,1.45819985867,8.61004638672 -5.1689414978,1.46121394634,8.64161682129 -5.14196777344,1.46122956276,8.65719223022 -5.11599397659,1.46124517918,8.67476654053 -5.11100482941,1.46425104141,8.69556522369 -5.08403205872,1.46426701546,8.71312999725 -5.05805873871,1.46528255939,8.73070526123 -5.03708314896,1.46729695797,8.75628566742 -5.01310873032,1.46731197834,8.77686500549 -4.98613595963,1.4683277607,8.79343700409 -4.96616029739,1.47034204006,8.82101917267 -4.95217370987,1.47035002708,8.82880306244 -4.92720031738,1.4713653326,8.84837913513 -4.90622520447,1.47337985039,8.87595176697 -4.87825250626,1.47339570522,8.88953304291 -4.84927988052,1.47241199017,8.90210914612 -4.83130407333,1.47642576694,8.93468761444 -4.79733324051,1.47444295883,8.9382610321 -4.79234457016,1.4774492979,8.96304607391 -4.76437187195,1.47746527195,8.97762107849 -4.74239778519,1.47947990894,9.00320053101 -4.71442461014,1.47949588299,9.01777744293 -4.69344997406,1.48151040077,9.04535770416 -4.66447782516,1.48152649403,9.05793571472 -4.64250326157,1.48354125023,9.08451080322 -4.62951612473,1.48354899883,9.09330272675 -4.60754299164,1.48656404018,9.12186908722 -4.58456897736,1.48857903481,9.14644813538 -4.47761821747,1.46061098576,9.00301551819 -3.76383495331,1.21476471424,7.62853479385 -3.71186923981,1.20478522778,7.58112001419 -3.68188786507,1.19779670238,7.5508980751 -3.64191842079,1.19181478024,7.52648687363 -3.60594892502,1.18783259392,7.51305294037 -3.57597732544,1.1848487854,7.50963449478 -3.54100704193,1.18086588383,7.4952173233 -3.50503706932,1.17588341236,7.47879695892 -3.47306632996,1.17290019989,7.47137069702 -3.45308208466,1.16990959644,7.45915555954 -3.43010854721,1.1699244976,7.46973705292 -3.40313625336,1.16794002056,7.47131967545 -3.37418460846,1.17496645451,7.53048229218 -3.30622410774,1.15799045563,7.44204950333 -3.26125717163,1.1490098238,7.40262699127 -3.25026988983,1.14901697636,7.40742588043 -3.21829938889,1.14603388309,7.39799642563 -3.19132733345,1.14404964447,7.39857530594 -3.15835666656,1.14006626606,7.38415956497 -3.13738322258,1.14108097553,7.39873695374 -3.1194088459,1.14309501648,7.42130994797 -3.08542823792,1.13410675526,7.37110710144 -3.05745697021,1.13212275505,7.36967802048 -3.03448343277,1.13213741779,7.37726736069 -3.01450943947,1.13315188885,7.39384651184 -2.97654104233,1.1271699667,7.36741638184 -2.95656681061,1.12818396091,7.38200759888 -2.93359351158,1.12819886208,7.39058971405 -2.91360998154,1.12520825863,7.37536764145 -2.88963675499,1.12422323227,7.37995767593 -2.8596663475,1.12123978138,7.37252569199 -2.8386926651,1.12225413322,7.38610696793 -2.89469718933,1.1572535038,7.60169172287 -2.87172484398,1.1582685709,7.61426019669 -2.77977108955,1.12729692459,7.43884658813 -2.7627863884,1.12430560589,7.42863559723 -2.73381495476,1.12132143974,7.42022132874 -2.71184182167,1.12233614922,7.43179988861 -2.68586993217,1.1213517189,7.43237876892 -2.65989756584,1.11936700344,7.43096828461 -2.63192677498,1.11738312244,7.42753601074 -2.62093997002,1.117390275,7.43233060837 -2.59796762466,1.11840546131,7.44190454483 -2.57499456406,1.11842024326,7.44948959351 -2.55002212524,1.11743533611,7.45107555389 -2.52704906464,1.11745011806,7.45866060257 -2.50107741356,1.11546576023,7.45923471451 -2.47710514069,1.1154807806,7.46481370926 -2.46611857414,1.11548805237,7.46960878372 -2.4481446743,1.11850202084,7.49418497086 -2.42517161369,1.11851680279,7.50177049637 -2.40319895744,1.11953163147,7.51434659958 -2.37922692299,1.11954689026,7.52092170715 -2.36325192451,1.12356007099,7.55050992966 -2.34627771378,1.12657380104,7.57908964157 -2.34228944778,1.13157987595,7.6088757515 -2.32931399345,1.13759291172,7.65145587921 -2.30534148216,1.13660764694,7.65604639053 -2.29236674309,1.14362084866,7.70261335373 -2.27639198303,1.14763438702,7.73619699478 -2.25741839409,1.15164852142,7.76177358627 -2.25244021416,1.16165959835,7.83336448669 -2.25744915009,1.17166376114,7.89715528488 -2.25147223473,1.18367552757,7.97272443771 -2.23349833488,1.18768942356,8.00330924988 -2.22654271126,1.2137118578,8.17746067047 -2.21956539154,1.22572362423,8.25403881073 -2.22657394409,1.23772740364,8.33183002472 -2.23659229279,1.2597360611,8.47640705109 -2.22061753273,1.26674950123,8.52299022675 -2.19764494896,1.26876413822,8.54257488251 -2.1936674118,1.28377556801,8.64114761353 -2.18269085884,1.29378771782,8.7087392807 -2.17571425438,1.30779969692,8.79931354523 -2.18172287941,1.32080376148,8.88310432434 -2.19773960114,1.35081124306,9.07268047333 -2.17776608467,1.35682547092,9.11326408386 -2.16679024696,1.36883795261,9.19484329224 -2.14681744576,1.37585234642,9.24141788483 -2.33587813377,1.64187395573,10.9150953293 -2.2519235611,1.60290026665,10.6826810837 -2.2099571228,1.59691905975,10.6502561569 -2.19397211075,1.59692716599,10.654053688 -2.16100263596,1.59694385529,10.6616363525 -2.12503480911,1.59596121311,10.6582098007 -2.09806323051,1.60097670555,10.6957941055 -2.11308050156,1.64198458195,10.9583654404 -2.09710621834,1.65799808502,11.0629444122 -2.06713581085,1.66101396084,11.0905342102 -2.05315065384,1.66502201557,11.1133213043 -2.01918148994,1.66503882408,11.1229047775 -1.98921191692,1.67005515099,11.1604776382 -1.96523988247,1.68007004261,11.2280607224 -1.94326782227,1.69308483601,11.3136377335 -1.91429746151,1.6991007328,11.3582181931 -1.88732624054,1.7071160078,11.4128046036 -1.86834263802,1.7071249485,11.4115905762 -1.83637309074,1.71014130116,11.4381761551 -1.79740571976,1.70715904236,11.4237575531 -1.75244021416,1.6981780529,11.3703374863 -1.71447241306,1.69519555569,11.357922554 -1.67750477791,1.69321298599,11.3555011749 -1.66052007675,1.69422137737,11.3612947464 -1.62555146217,1.69423818588,11.3678808212 -1.58558499813,1.69025623798,11.3474531174 -1.55161583424,1.6912728548,11.3580436707 -1.51464831829,1.69029021263,11.3566188812 -1.47768008709,1.68830740452,11.3452091217 -1.44271206856,1.68932449818,11.3587837219 -1.42472803593,1.68933308125,11.3605737686 -1.38975977898,1.69034993649,11.3711538315 -1.35279142857,1.68836688995,11.3567457199 -1.31682324409,1.68738389015,11.3573284149 -1.27885603905,1.68440139294,11.3429069519 -1.24288761616,1.68341839314,11.3384952545 -1.22490394115,1.68342709541,11.3442792892 -1.18893587589,1.6824439764,11.3418636322 -1.15396749973,1.68346071243,11.3504476547 -1.11699986458,1.68247795105,11.3420276642 -1.08003175259,1.67849493027,11.3236169815 -1.04506397247,1.68151199818,11.3421897888 -1.01009523869,1.68152856827,11.3447809219 -0.992111027241,1.68053686619,11.3405752182 -0.955143451691,1.67755401134,11.3291559219 -0.919175863266,1.678571105,11.3337316513 -0.885206758976,1.6795873642,11.3463249207 -0.848239421844,1.67860460281,11.3389005661 -0.812271416187,1.67762136459,11.3334856033 -0.778302431107,1.67963767052,11.3510742188 -0.759319007397,1.67764639854,11.3398618698 -0.724350571632,1.67866301537,11.347448349 -0.688382565975,1.67767977715,11.3420324326 -0.650415599346,1.67269706726,11.3136081696 -0.617446303368,1.67771315575,11.3492002487 -0.582478523254,1.68272995949,11.3797740936 -0.546509981155,1.67874646187,11.3553695679 -0.52752661705,1.6767551899,11.3421554565 -0.491558641195,1.67477166653,11.331741333 -0.456590056419,1.67478811741,11.3353300095 -0.420622110367,1.67280483246,11.3239154816 -0.384654641151,1.67482161522,11.3364896774 -0.349685907364,1.67383790016,11.330083847 -0.331702142954,1.67484629154,11.3358716965 -0.295734256506,1.67286300659,11.3224563599 -0.259766578674,1.67287969589,11.3250341415 -0.224797859788,1.6708959341,11.3136281967 -0.18883036077,1.6739127636,11.3292045593 -0.15386159718,1.66992878914,11.3077993393 -0.11789406836,1.67294549942,11.3253774643 -0.0999100729823,1.66795372963,11.296169281 -0.0649416148663,1.6719700098,11.3157587051 -0.0289739426225,1.67098665237,11.3113384247 --0.00699346745387,1.67500329018,10.6729135513 --0.039962682873,1.67601907253,10.6775054932 --0.073930926621,1.67403531075,10.669084549 --0.106900162995,1.67505097389,10.6746759415 --0.140868633986,1.67906713486,10.697259903 --0.190821602941,1.67309105396,10.6566352844 --0.223790720105,1.67210686207,10.6502246857 --0.257758796215,1.67012298107,10.638800621 --0.290728032589,1.67113864422,10.6413936615 --0.324696153402,1.67015480995,10.6359701157 --0.357665002346,1.66817057133,10.620554924 --0.374649316072,1.66917860508,10.6293478012 --0.407618314028,1.66819417477,10.6219367981 --0.440587371588,1.66820979118,10.6165246964 --0.474555969238,1.67022562027,10.6301116943 --0.507524847984,1.66924142838,10.6186971664 --0.540494024754,1.66925692558,10.6182889938 --0.573462843895,1.66727268696,10.6068744659 --0.591446340084,1.66928088665,10.6156578064 --0.624415576458,1.66929638386,10.6152496338 --0.657384455204,1.66831195354,10.6068353653 --0.690353631973,1.66932737827,10.6064281464 --0.725321531296,1.67134356499,10.6170063019 --0.756291210651,1.66635859013,10.5845947266 --0.792259216309,1.67237472534,10.6191825867 --0.841212749481,1.67039775848,10.5995607376 --0.874181985855,1.67041313648,10.598154068 --0.908150494099,1.67142879963,10.6007385254 --0.942119300365,1.6734443903,10.6073284149 --0.976087749004,1.67346000671,10.6079111099 --1.00905692577,1.6734752655,10.6045026779 --1.0270409584,1.67648327351,10.6162958145 --1.06100928783,1.67649900913,10.6128768921 --1.0949780941,1.67751443386,10.6184673309 --1.12894666195,1.6785299778,10.6170501709 --1.16291546822,1.67954540253,10.6206407547 --1.19888353348,1.68356120586,10.6382265091 --1.21486794949,1.68156886101,10.6280174255 --1.24783742428,1.68258392811,10.6256132126 --1.28380537033,1.68559968472,10.6411981583 --1.31777393818,1.68561506271,10.6377820969 --1.35074329376,1.68563020229,10.6333751678 --1.38471221924,1.68664550781,10.6349668503 --1.4216799736,1.69166135788,10.6555528641 --1.43766474724,1.69066882133,10.6493492126 --1.4716334343,1.69068419933,10.6459331512 --1.50660181046,1.69269955158,10.6505203247 --1.5425696373,1.69471526146,10.6591033936 --1.57553911209,1.69473016262,10.6536970139 --1.61250698566,1.69874572754,10.6722869873 --1.64747560024,1.700761199,10.6758747101 --1.66645908356,1.70276916027,10.6846647263 --1.70442688465,1.70778489113,10.7082567215 --1.73639667034,1.70679950714,10.694849968 --1.77136480808,1.70681488514,10.6924295425 --1.81033229828,1.71283078194,10.7200222015 --1.84430122375,1.71284580231,10.7156114578 --1.86428499222,1.71685361862,10.7324094772 --1.90025305748,1.71886920929,10.7369947433 --1.93422210217,1.71888411045,10.7325849533 --1.97019016743,1.7208994627,10.7361707687 --2.00715827942,1.72391486168,10.7467594147 --2.04112744331,1.72392964363,10.7433538437 --2.07609605789,1.72494471073,10.7409391403 --2.09707927704,1.72895288467,10.7587347031 --2.1310479641,1.72896778584,10.7513217926 --2.16401743889,1.72798228264,10.7409133911 --2.20198583603,1.73199748993,10.7585124969 --2.23595476151,1.73201227188,10.7511005402 --2.27192306519,1.73402750492,10.7526874542 --2.30789136887,1.73504257202,10.7532730103 --2.32487559319,1.735049963,10.7490663528 --2.36084461212,1.73806476593,10.7546644211 --2.39381408691,1.73707914352,10.7432556152 --2.43278121948,1.74009478092,10.7548370361 --2.46575117111,1.74010896683,10.7464351654 --2.50171947479,1.74212408066,10.7460212708 --2.53868746758,1.74413919449,10.7496070862 --2.55867147446,1.74614691734,10.7584028244 --2.59264087677,1.74616134167,10.7519979477 --2.62960886955,1.74817633629,10.7545833588 --2.66457796097,1.74919092655,10.7521791458 --2.70054650307,1.75020563602,10.7507658005 --2.7355158329,1.7522200346,10.7493648529 --2.75549912453,1.75322782993,10.754152298 --2.78946852684,1.75324225426,10.7447404861 --2.8284368515,1.75725710392,10.759344101 --2.86240577698,1.75727164745,10.747926712 --2.89537525177,1.75628566742,10.7345151901 --2.93434309959,1.76030063629,10.7441072464 --2.97830986977,1.7673163414,10.7737064362 --2.99929332733,1.76932406425,10.7824993134 --3.03526186943,1.77033877373,10.7780847549 --3.07522988319,1.7743537426,10.7906799316 --3.10420084,1.77136695385,10.7642745972 --3.1441681385,1.77438211441,10.7728595734 --3.17114019394,1.77139484882,10.7414588928 --3.20910811424,1.77340960503,10.7440462112 --3.23209095001,1.77641761303,10.7578382492 --3.26805996895,1.7784318924,10.7544317245 --3.30203008652,1.77844572067,10.7460289001 --3.34399676323,1.78246104717,10.7596149445 --3.38196539879,1.78547549248,10.7622089386 --3.41493535042,1.78448915482,10.7488021851 --3.43891811371,1.78849697113,10.7655992508 --3.47188830376,1.7885106802,10.7521944046 --3.50585770607,1.78852450848,10.7397813797 --3.54882526398,1.79353964329,10.7583818436 --3.58479428291,1.7945536375,10.7519693375 --3.6277616024,1.7995685339,10.7685670853 --3.65973210335,1.79858195782,10.751159668 --3.68171525002,1.80158948898,10.7599563599 --3.72168278694,1.8036043644,10.7625370026 --3.75665259361,1.80461788177,10.7541322708 --3.79062223434,1.80463147163,10.7417230606 --3.83358979225,1.80964612961,10.7573251724 --3.86556005478,1.80865955353,10.7379112244 --3.907528162,1.81267404556,10.7495107651 --3.93550944328,1.81768238544,10.7723035812 --3.96348166466,1.81569480896,10.7449026108 --3.99945092201,1.81670856476,10.7374944687 --4.04541730881,1.82172369957,10.7560853958 --4.07538843155,1.81973648071,10.7316741943 --4.11535692215,1.8227506876,10.7342662811 --4.13534069061,1.8247576952,10.7350616455 --4.17031049728,1.82477104664,10.7256593704 --4.20628070831,1.82678449154,10.7192583084 --4.2492480278,1.83079898357,10.7278490067 --4.2782201767,1.82881128788,10.7034482956 --4.32218742371,1.83282589912,10.7130336761 --4.35815668106,1.83383929729,10.7046289444 --4.37214279175,1.83284521103,10.6914281845 --4.41611051559,1.83785963058,10.7030267715 --4.4490814209,1.83687257767,10.6866188049 --4.48205184937,1.83688545227,10.6692066193 --4.52601957321,1.84089970589,10.6798048019 --4.56398820877,1.84291315079,10.6743955612 --4.59495973587,1.84192562103,10.6539916992 --4.62294197083,1.84693348408,10.6737957001 --4.65591239929,1.84594619274,10.6553812027 --4.68988323212,1.84695899487,10.6419792175 --4.73685026169,1.85197341442,10.657576561 --4.78181743622,1.85698759556,10.6671695709 --4.81678819656,1.85800039768,10.6547641754 --4.83977174759,1.86000752449,10.6615657806 --4.88473892212,1.86502170563,10.6691541672 --4.92370843887,1.8670347929,10.6657524109 --4.93768501282,1.85904467106,10.6073446274 --4.92366886139,1.84005093575,10.4889297485 --4.94264411926,1.83406126499,10.443526268 --4.94562339783,1.82306945324,10.3651208878 --4.96860742569,1.82507646084,10.3709173203 --5.00557756424,1.8270894289,10.3635110855 --5.04654598236,1.83010280132,10.3631010056 --5.08751535416,1.83311593533,10.3647012711 --5.13248348236,1.83812963963,10.3732976913 --5.16745328903,1.83914220333,10.3598861694 --5.20242404938,1.84015452862,10.348484993 --5.21641111374,1.83916020393,10.3352813721 --5.25138187408,1.84017252922,10.3238811493 --5.28435277939,1.84018468857,10.3064699173 --5.31832408905,1.8401966095,10.2930688858 --5.35129594803,1.84120845795,10.2776689529 --5.39026546478,1.84322118759,10.2722616196 --5.40725183487,1.84322702885,10.2660646439 --5.44622135162,1.84623968601,10.2606582642 --5.48319149017,1.84725213051,10.2512512207 --5.5081653595,1.84526288509,10.2198467255 --5.54513597488,1.84627509117,10.2104406357 --5.585105896,1.84928762913,10.2070388794 --5.62507534027,1.85230028629,10.2026319504 --5.63706302643,1.85030555725,10.1864309311 --5.6770324707,1.853317976,10.1820268631 --5.709004879,1.85332930088,10.1636228561 --5.74497556686,1.85434126854,10.1522197723 --5.77694797516,1.85435259342,10.1338176727 --5.80792045593,1.8543637991,10.1134128571 --5.83589363098,1.85337460041,10.0880098343 --5.85887765884,1.85538113117,10.0908088684 --5.88985061646,1.85539221764,10.0704040527 --5.91982364655,1.85440325737,10.0479984283 --5.95679426193,1.85641491413,10.0385990143 --5.98476791382,1.85542559624,10.0131959915 --6.01973962784,1.85643696785,9.99878883362 --6.04972171783,1.86044430733,10.0125875473 --6.07969522476,1.86045503616,9.99118804932 --6.11366701126,1.86146616936,9.97578620911 --6.15063858032,1.86247777939,9.96438026428 --6.17761278152,1.86148798466,9.93797969818 --6.21358394623,1.86249947548,9.92457103729 --6.24055814743,1.86150968075,9.89817047119 --6.26054286957,1.86251568794,9.89396381378 --6.30151414871,1.86652731895,9.89056968689 --6.33248662949,1.86553800106,9.86916255951 --6.37245750427,1.86854958534,9.8637676239 --6.4024310112,1.86855995655,9.84136486053 --6.44140195847,1.8705714941,9.8319568634 --6.47437477112,1.87158203125,9.8145570755 --6.48436307907,1.86958658695,9.79635810852 --6.51133775711,1.86859667301,9.76895141602 --6.54730987549,1.87060749531,9.75655460358 --6.58628082275,1.87261867523,9.74715042114 --6.62325286865,1.87462961674,9.73575210571 --6.65322637558,1.87463986874,9.71234321594 --6.66321468353,1.87264442444,9.69313716888 --6.69218873978,1.8726541996,9.67074298859 --6.73016023636,1.87466526031,9.65833187103 --6.7571349144,1.87367498875,9.63193130493 --6.79210758209,1.87468528748,9.61753368378 --6.82808017731,1.87669587135,9.6031293869 --6.85405540466,1.87470543385,9.57472419739 --6.86404371262,1.87370979786,9.55752849579 --6.89501714706,1.87371981144,9.53511810303 --6.9319896698,1.87573027611,9.52271842957 --6.96396350861,1.876740098,9.50432491302 --6.98993825912,1.87474954128,9.47491264343 --7.01991271973,1.87475919724,9.45250988007 --7.04988718033,1.87476885319,9.43010807037 --7.07187271118,1.87677419186,9.42891311646 --7.09384918213,1.87478291988,9.3965139389 --7.13182210922,1.87779319286,9.38511657715 --7.1657948494,1.87880325317,9.36670780182 --7.19876861572,1.87981295586,9.34830665588 --7.22974300385,1.8798224926,9.32690525055 --7.24572992325,1.87982726097,9.31670379639 --7.2797036171,1.88183701038,9.29930210114 --7.30667924881,1.88084602356,9.27290058136 --7.33765363693,1.88085532188,9.25149917603 --7.35963058472,1.8788639307,9.21809196472 --7.38960552216,1.87987279892,9.19669914246 --7.41458177567,1.87888145447,9.16829872131 --7.43656730652,1.88088667393,9.16610145569 --7.47753953934,1.88389694691,9.15569400787 --7.50451564789,1.88290560246,9.1302986145 --7.52849197388,1.88191390038,9.09989452362 --7.44449567795,1.85191202164,8.93846797943 --5.41997814178,1.30772614479,6.43057155609 --5.38596820831,1.29373002052,6.34815788269 --5.36396360397,1.28473174572,6.29993629456 --5.35094881058,1.27673768997,6.24352502823 --5.33693408966,1.26774334908,6.18712043762 --5.35591077805,1.26775240898,6.16871166229 --5.35189342499,1.26175904274,6.12430524826 --5.34987545013,1.25576615334,6.08189296722 --5.34385824203,1.2497729063,6.034471035 --5.33985042572,1.24577593803,6.01127624512 --5.34882974625,1.24378395081,5.98186254501 --5.36380767822,1.24279236794,5.96046113968 --5.36178970337,1.23679924011,5.91904592514 --5.35577249527,1.23080599308,5.87363100052 --5.36275243759,1.2278137207,5.8432226181 --5.34474754333,1.22081577778,5.8040099144 --5.33373212814,1.21382176876,5.7546005249 --5.33771276474,1.20982933044,5.72118616104 --5.32669687271,1.20283555984,5.67176914215 --5.3286781311,1.19884264469,5.63736200333 --5.33165931702,1.19484984875,5.60496282578 --5.31864404678,1.18685591221,5.55454683304 --5.32063484192,1.18585956097,5.53833866119 --5.32761478424,1.18286716938,5.50993156433 --5.31959867477,1.17687368393,5.46551513672 --5.3145813942,1.17088019848,5.42510652542 --5.33055925369,1.17088854313,5.40670251846 --5.32754182816,1.16589534283,5.36828804016 --5.32752418518,1.16190230846,5.33388233185 --5.33051395416,1.16090607643,5.31967878342 --5.32949638367,1.15591299534,5.28426933289 --5.33547687531,1.15392053127,5.25585794449 --5.35845279694,1.15492928028,5.24445009232 --5.3484377861,1.1489354372,5.20104408264 --5.35941696167,1.14694333076,5.1776304245 --5.39738988876,1.15195322037,5.1812286377 --5.39638137817,1.14995634556,5.16403102875 --5.4103603363,1.14996421337,5.14463090897 --5.44133472443,1.15297365189,5.14021682739 --5.43631839752,1.14797997475,5.10281562805 --5.45429611206,1.1479883194,5.08640527725 --5.47327470779,1.14899647236,5.07200860977 --5.48126363754,1.14900052547,5.0628027916 --5.51123952866,1.15200936794,5.05840539932 --5.54121446609,1.15501832962,5.05299758911 --5.56019210815,1.15602660179,5.03759145737 --5.59316778183,1.16003537178,5.0362033844 --5.62414264679,1.16304445267,5.03078985214 --5.64112138748,1.164052248,5.01439666748 --5.6611084938,1.16605687141,5.01619768143 --5.67908620834,1.16706502438,4.99878168106 --5.70206403732,1.16807293892,4.98738765717 --5.73004007339,1.17108142376,4.97998952866 --5.7560172081,1.17308974266,4.97058916092 --5.78799295425,1.17709839344,4.96618938446 --5.81896877289,1.18010699749,4.96078968048 --5.83695602417,1.1831111908,4.96059513092 --5.87392997742,1.18712031841,4.95918560028 --5.89890766144,1.18912827969,4.94879198074 --5.92788362503,1.19213664532,4.94038295746 --5.96785783768,1.19814562798,4.94198703766 --5.99583482742,1.20015358925,4.93359327316 --6.03280973434,1.20516216755,4.93219661713 --6.06779336929,1.21116745472,4.94500017166 --6.10076951981,1.21517586708,4.93959903717 --6.12274742126,1.21618354321,4.92418622971 --6.16672134399,1.22219216824,4.92880487442 --6.19969701767,1.22620046139,4.92239809036 --6.22667455673,1.22820830345,4.91099023819 --6.26364994049,1.23321640491,4.90859889984 --6.28863620758,1.23722088337,4.91240310669 --6.31761312485,1.24022853374,4.90300655365 --6.35558795929,1.24423694611,4.89960050583 --6.39556360245,1.25024485588,4.89921522141 --6.42354154587,1.25225234032,4.88882160187 --6.45051908493,1.25525987148,4.87641382217 --6.49050283432,1.26226484776,4.89122486115 --6.52547836304,1.26627278328,4.88482189178 --6.56145429611,1.27028048038,4.87942457199 --6.59743070602,1.27428817749,4.87402963638 --5.52161407471,1.04124510288,3.9998588562 --5.52659606934,1.03925168514,3.97645568848 --5.44460344315,1.02025103569,3.90121388435 --6.7683224678,1.29532253742,4.85324859619 --6.80929851532,1.30132997036,4.85086154938 --6.83927631378,1.30433702469,4.83946180344 --6.88525104523,1.31034493446,4.8390622139 --6.91822814941,1.31435191631,4.8296661377 --6.96020364761,1.31935930252,4.82626962662 --6.99518823624,1.32536375523,4.8340716362 --7.03016614914,1.32937061787,4.82567739487 --7.07414102554,1.3353780508,4.82328510284 --7.10611915588,1.33838474751,4.81188440323 --7.15409421921,1.34539222717,4.81148958206 --7.19707012177,1.35039913654,4.80810260773 --7.23804664612,1.35640609264,4.8027100563 --7.26703310013,1.36040985584,4.80551433563 --7.32000732422,1.36841726303,4.80711698532 --7.35198545456,1.37142372131,4.79471826553 --7.39196300507,1.37643027306,4.78833246231 --7.44193744659,1.38343727589,4.78693294525 --7.48691368103,1.38944399357,4.78253889084 --7.5248913765,1.39445030689,4.77415275574 --7.56087636948,1.39945411682,4.77995347977 --7.60585308075,1.40546047688,4.77556848526 --7.65182924271,1.41146707535,4.77016687393 --7.69880533218,1.41847348213,4.76577281952 --7.74178266525,1.42347967625,4.75938796997 --7.79775762558,1.43148624897,4.75999593735 --7.83573579788,1.43649208546,4.74960565567 --7.88072013855,1.44349598885,4.7604174614 --7.91269922256,1.44650149345,4.74501419067 --7.94467926025,1.45050704479,4.73062515259 --8.03864765167,1.46551442146,4.75324821472 --8.12961578369,1.48052155972,4.77387619019 --8.15359687805,1.48252665997,4.75247001648 --8.1765871048,1.48552942276,4.7492814064 --8.20356750488,1.4875344038,4.72988080978 --8.29853630066,1.50354135036,4.75050210953 --8.29850769043,1.49754953384,4.67968940735 --8.35148334503,1.50455510616,4.67530250549 --8.35246944427,1.50255906582,4.64090061188 --8.39245605469,1.50856220722,4.64570522308 --8.39244174957,1.50556612015,4.61029815674 --8.43142032623,1.51057100296,4.59690237045 --8.58737945557,1.53757870197,4.64854192734 --10.1600999832,1.83861720562,5.48866605759 --10.1960821152,1.84162068367,5.46728134155 --10.2050676346,1.84062337875,5.42987728119 --10.2260580063,1.84262514114,5.41967582703 --10.2310447693,1.8406277895,5.38128137589 --10.2420310974,1.83863055706,5.3448767662 --10.2710142136,1.84163367748,5.31848096848 --10.2829999924,1.84063625336,5.28308010101 --10.3029842377,1.84063911438,5.25168037415 --10.3039722443,1.83764147758,5.21128320694 --7.99633836746,1.39760696888,3.98927569389 --8.00932216644,1.3976111412,3.96387505531 --8.00930786133,1.39561510086,3.93247818947 --8.0012960434,1.39161908627,3.89606547356 --8.00528049469,1.38962328434,3.86565375328 --7.99126911163,1.3846269846,3.82724809647 --7.99325466156,1.38263106346,3.79583334923 --7.98724842072,1.38063299656,3.77662205696 --7.98723459244,1.37763702869,3.74521756172 --7.98522090912,1.37564098835,3.71281003952 --7.98420763016,1.37264478207,3.68140864372 --7.97819471359,1.3696488142,3.64699602127 --7.98318052292,1.36865270138,3.61859583855 --7.96917581558,1.36465454102,3.59638690948 --7.98115968704,1.36465847492,3.57098340988 --7.96814823151,1.3596624136,3.5335662365 --7.96913433075,1.35766625404,3.50315880775 --7.97112035751,1.35667026043,3.47375774384 --8.00810146332,1.36067414284,3.45935726166 --8.06008052826,1.36867797375,3.45298171043 --8.1130657196,1.37767994404,3.46079063416 --8.17104434967,1.38568365574,3.45540308952 --8.22902202606,1.39468729496,3.45001959801 --8.28900146484,1.40369069576,3.44564366341 --8.33798122406,1.41069412231,3.43525195122 --8.39696025848,1.41969752312,3.42886376381 --8.45093917847,1.42770063877,3.42048048973 --8.51692390442,1.43770217896,3.43229842186 --8.56990432739,1.4457051754,3.42291522026 --8.47890377045,1.427708745,3.35348105431 --10.84856987,1.85769820213,4.29993963242 --10.8735561371,1.85969936848,4.27055025101 --10.8805456161,1.85870075226,4.23314905167 --10.8925333023,1.85770189762,4.1977481842 --10.9195241928,1.86170232296,4.18855667114 --10.9305124283,1.86170339584,4.15215063095 --10.9355010986,1.85970449448,4.11374568939 --10.9524888992,1.86070549488,4.08034753799 --10.9814758301,1.86370623112,4.05195808411 --10.9764661789,1.8597073555,4.01055717468 --10.9954538345,1.86070811749,3.97715306282 --11.0104475021,1.86270844936,3.96396756172 --11.0204362869,1.86170935631,3.92756485939 --11.0314254761,1.86171019077,3.89115786552 --11.0604114532,1.86471045017,3.86277222633 --11.0674009323,1.86371123791,3.82536911964 --11.0773906708,1.86371195316,3.78896594048 --11.0953788757,1.86471235752,3.75556707382 --11.0983734131,1.86371278763,3.73737215996 --11.1103630066,1.86371326447,3.70197272301 --11.1413497925,1.86671340466,3.67257452011 --11.1283416748,1.86271417141,3.6291718483 --11.1483306885,1.86371445656,3.59576797485 --11.1743183136,1.86671447754,3.56537699699 --11.1823091507,1.86571478844,3.52898025513 --11.181303978,1.86471509933,3.5087761879 --11.2112913132,1.86771476269,3.47938513756 --11.224281311,1.86871492863,3.44398331642 --11.2322711945,1.86771512032,3.40758657455 --11.2502613068,1.86871504784,3.3741915226 --11.233253479,1.86371588707,3.3287730217 --11.252243042,1.8657156229,3.29537463188 --11.2832355499,1.86971497536,3.28619337082 --11.2812271118,1.86771512032,3.24578261375 --11.2802181244,1.86571550369,3.20637845993 --11.3002080917,1.86771500111,3.17398953438 --11.3011989594,1.86571514606,3.13457918167 --11.3081903458,1.86471498013,3.0981836319 --11.3221845627,1.86671459675,3.08298969269 --11.310177803,1.86271500587,3.04058074951 --11.329167366,1.86471438408,3.0071849823 --11.3581562042,1.86771333218,2.97578549385 --11.3551483154,1.86571347713,2.93638348579 --11.3421421051,1.86171388626,2.89397358894 --11.3611326218,1.86271297932,2.86057925224 --11.3581285477,1.86171317101,2.84037542343 --11.3541212082,1.85971307755,2.80097293854 --11.3631124496,1.8597124815,2.76457071304 --11.3531045914,1.85571277142,2.72315955162 --11.3320989609,1.85071349144,2.67975091934 --11.3060941696,1.84471440315,2.63534092903 --11.2770881653,1.83771550655,2.5899245739 --11.2870836258,1.83871495724,2.57271957397 --11.2890758514,1.83771455288,2.53531765938 --11.2830686569,1.83571457863,2.49591112137 --11.2970600128,1.83671343327,2.4615149498 --11.2910528183,1.83371353149,2.42311763763 --11.2980442047,1.83371281624,2.38671445847 --11.2940378189,1.83171248436,2.3473007679 --11.2920341492,1.83071243763,2.32809925079 --11.2940263748,1.82971179485,2.29170513153 --11.2940196991,1.8287113905,2.25329256058 --11.2840127945,1.82571136951,2.2138876915 --11.3050041199,1.82770967484,2.18048882484 --11.298997879,1.82570946217,2.14208626747 --11.3059902191,1.82570838928,2.10669183731 --11.3019866943,1.82370829582,2.08648109436 --11.3039798737,1.82270753384,2.05008435249 --11.3009729385,1.82170689106,2.01167368889 --11.3079652786,1.82170581818,1.97627866268 --11.3009595871,1.81870555878,1.93686294556 --11.3149518967,1.8207038641,1.9024668932 --11.3239479065,1.82170283794,1.88627684116 --11.333940506,1.82170128822,1.85087716579 --11.3409337997,1.82169997692,1.81447136402 --11.3549261093,1.82369816303,1.78007698059 --11.3819189072,1.82669532299,1.74768638611 --11.3589134216,1.8216958046,1.70626938343 --11.331908226,1.81669664383,1.66485571861 --11.3239021301,1.81369614601,1.62644731998 --11.3148994446,1.81169629097,1.60623836517 --11.3418922424,1.81569337845,1.57384872437 --11.3748846054,1.8206897974,1.54246401787 --11.3368806839,1.81269133091,1.49903643131 --11.3128757477,1.80769193172,1.45862185955 --11.3398685455,1.81168866158,1.42623460293 --11.381860733,1.81768417358,1.39484322071 --11.4078569412,1.82168149948,1.38065958023 --11.4318504333,1.82567834854,1.34726917744 --11.4408445358,1.82567608356,1.31086313725 --11.4318389893,1.82367539406,1.27245271206 --11.4008350372,1.81767630577,1.23204052448 --11.3918294907,1.81567561626,1.19362735748 --11.4248256683,1.82067203522,1.17944192886 --11.4488191605,1.82366847992,1.14605545998 --11.4468135834,1.82266700268,1.10864794254 --11.4158096313,1.81666791439,1.06822991371 --11.401804924,1.81366741657,1.02981841564 --11.4447984695,1.82066202164,0.998441636562 --11.4327936172,1.8176612854,0.960028409958 --11.4407920837,1.81865978241,0.942834019661 --11.4027872086,1.81166124344,0.902413964272 --11.3827829361,1.80766129494,0.862991034985 --11.3977775574,1.80965805054,0.828602254391 --11.2597761154,1.78566896915,0.779128909111 --11.2807703018,1.78866517544,0.744733214378 --11.2817659378,1.78866326809,0.709337055683 --11.2887630463,1.7896617651,0.692141532898 --11.2267599106,1.77866578102,0.650704145432 --11.28175354,1.78765869141,0.619330048561 --11.2787485123,1.78665685654,0.582923531532 --11.1807460785,1.7696647644,0.540478289127 --11.220741272,1.77565872669,0.507089555264 --11.3247356415,1.79364609718,0.477733373642 --11.3177337646,1.7916457653,0.459531754255 --11.3297290802,1.79364228249,0.423122406006 --11.4027252197,1.80563247204,0.39176145196 --11.4217205048,1.80862808228,0.356366366148 --11.435716629,1.81062424183,0.319961756468 --11.5197124481,1.82461261749,0.287600487471 --11.450709343,1.81261765957,0.248166367412 --11.3527069092,1.79562711716,0.225918129086 --11.2987031937,1.78663063049,0.187485918403 --11.2996997833,1.7866281271,0.152088701725 --11.2576951981,1.77963042259,0.114663310349 --11.2646913528,1.78062713146,0.079265512526 --11.2866888046,1.78362202644,0.0438712835312 --11.2556848526,1.7786231041,0.00745453033596 --11.2776832581,1.7826192379,-0.0107452888042 --11.181678772,1.76562786102,-0.0481941476464 --11.1766748428,1.76462602615,-0.0835976973176 --11.2336730957,1.77461659908,-0.117967866361 --11.2206687927,1.77261555195,-0.154384657741 --11.2616672516,1.77960777283,-0.189767375588 --11.2306632996,1.77360880375,-0.225180923939 --11.2456607819,1.77660548687,-0.24337951839 --11.1946573257,1.76760911942,-0.27880603075 --11.2336559296,1.77460134029,-0.315197050571 --11.223651886,1.77259969711,-0.350603044033 --11.42765522,1.80757045746,-0.388907670975 --11.1826448441,1.7665990591,-0.421431809664 --11.2866458893,1.78358244896,-0.458782225847 --11.2266435623,1.77358877659,-0.476019352674 --11.2776422501,1.78257894516,-0.512391865253 --11.244638443,1.77758014202,-0.547816753387 --11.2776374817,1.78257250786,-0.584199547768 --11.2976360321,1.7865664959,-0.620591640472 --11.339635849,1.79355728626,-0.658984541893 --11.2506303787,1.77856791019,-0.673225462437 --11.2306280136,1.77556729317,-0.708643734455 --11.1956243515,1.77056896687,-0.742055773735 --11.2156229019,1.77356266975,-0.779458165169 --11.2396221161,1.77855587006,-0.815843641758 --11.282623291,1.78554606438,-0.854228377342 --11.312623024,1.79153823853,-0.891613841057 --11.3426237106,1.79653191566,-0.911805093288 --11.3166208267,1.79253208637,-0.946219682693 --11.2866172791,1.7875328064,-0.980640888214 --11.300617218,1.79052686691,-1.01703083515 --11.3466186523,1.79851603508,-1.05742263794 --11.3286161423,1.79651498795,-1.09182965755 --11.3706178665,1.80350458622,-1.13121092319 --11.3616170883,1.80250406265,-1.14841425419 --11.3056125641,1.79350852966,-1.18085372448 --11.3276138306,1.79750108719,-1.21924984455 --11.3326129913,1.79949617386,-1.25564742088 --11.3526134491,1.80348873138,-1.29404354095 --11.347612381,1.802485466,-1.32944345474 --11.5796298981,1.84244370461,-1.38873064518 --11.4436197281,1.82046341896,-1.39400434494 --11.334610939,1.80247676373,-1.41946232319 --11.4166173935,1.8164588213,-1.46482658386 --11.4126176834,1.81645488739,-1.50123357773 --11.453619957,1.82444345951,-1.54261672497 --11.4616212845,1.8264374733,-1.58001172543 --11.5096263885,1.83542478085,-1.62238776684 --11.5076255798,1.83542263508,-1.64058923721 --11.4936246872,1.83342027664,-1.67599999905 --11.4296197891,1.82342636585,-1.70544135571 --11.5206298828,1.84040546417,-1.75480473042 --11.4746255875,1.83340871334,-1.7852243185 --11.4246225357,1.82541239262,-1.81565475464 --11.572637558,1.85138106346,-1.87398886681 --11.6266431808,1.86136877537,-1.90016031265 --11.5726394653,1.85237312317,-1.92958641052 --11.572640419,1.85336780548,-1.96698820591 --11.5456390381,1.85036718845,-2.0014154911 --11.5716438293,1.8553570509,-2.04280328751 --11.508638382,1.84536325932,-2.07023620605 --11.4876375198,1.84336173534,-2.1046538353 --11.5016403198,1.84635639191,-2.12585043907 --11.5016422272,1.84735071659,-2.16325259209 --11.4876422882,1.84534788132,-2.19866514206 --11.5026454926,1.84933936596,-2.238052845 --11.6716690063,1.87930119038,-2.30536818504 --11.6806726456,1.88229334354,-2.34577274323 --11.6576719284,1.87929177284,-2.3801908493 --11.712679863,1.88927793503,-2.40936326981 --11.6366739273,1.87728667259,-2.43380784988 --11.7046852112,1.8902670145,-2.48517727852 --11.6896858215,1.88926386833,-2.52058601379 --11.6746873856,1.88726043701,-2.55599498749 --11.7877063751,1.90823113918,-2.61734127998 --11.8207130432,1.91422116756,-2.64352560043 --11.8607215881,1.92220628262,-2.69090890884 --11.8557252884,1.9232006073,-2.72830605507 --11.9147377014,1.9341814518,-2.78068399429 --11.9417448044,1.94016885757,-2.82607316971 --11.9737548828,1.94715499878,-2.87245631218 --12.0037631989,1.95414149761,-2.91884255409 --12.0347709656,1.96013128757,-2.94603061676 --12.0357751846,1.96212363243,-2.98643350601 --12.0537834167,1.96611237526,-3.03082728386 --12.0487880707,1.96710586548,-3.07023572922 --12.0647954941,1.97109484673,-3.11463260651 --12.0838041306,1.97608304024,-3.1590192318 --12.0898113251,1.97907376289,-3.20142269135 --12.1218185425,1.9850628376,-3.22960710526 --12.1568307877,1.99304711819,-3.27899050713 --12.184841156,2.00003266335,-3.32738208771 --12.2208538055,2.0080165863,-3.37776637077 --12.2778701782,2.01899504662,-3.43414163589 --12.307882309,2.02597975731,-3.48352789879 --12.3528966904,2.0359609127,-3.53690361977 --12.4129152298,2.04793834686,-3.59527659416 --12.4479255676,2.05492568016,-3.62545585632 --12.4919404984,2.06490635872,-3.67983436584 --12.5119524002,2.06989240646,-3.72822833061 --12.5119600296,2.07188344002,-3.77062749863 --12.5029659271,2.07187652588,-3.81103587151 --12.5129766464,2.07586455345,-3.85743927956 --12.5029783249,2.07486248016,-3.87564253807 --12.5129890442,2.07885074615,-3.92103505135 --12.5049962997,2.07984304428,-3.96244812012 --12.4609956741,2.07384443283,-3.99287867546 --12.4850091934,2.07982873917,-4.04326868057 --12.4710149765,2.07982254028,-4.08167362213 --12.4910287857,2.08580803871,-4.13106489182 --12.5030345917,2.08879995346,-4.15726661682 --12.5190486908,2.09378600121,-4.20565891266 --12.4820489883,2.08978533745,-4.23808717728 --12.5040636063,2.09576964378,-4.28847455978 --12.504073143,2.09775972366,-4.33187389374 --12.4870796204,2.0967540741,-4.37028694153 --12.5000925064,2.10174012184,-4.41868448257 --12.4940958023,2.10173654556,-4.43889093399 --12.4961061478,2.10472583771,-4.48328924179 --12.4971170425,2.10671496391,-4.52869939804 --12.4891252518,2.10770654678,-4.57010602951 --12.4761333466,2.10769939423,-4.60951185226 --12.4921474457,2.11368441582,-4.65990972519 --12.4831571579,2.11467599869,-4.70131826401 --12.4891633987,2.11666893959,-4.72551393509 --12.4731712341,2.11666250229,-4.7649307251 --12.4921865463,2.12264609337,-4.81632089615 --12.4851961136,2.12363696098,-4.85872793198 --12.4872083664,2.12662553787,-4.90412712097 --12.4912214279,2.12961292267,-4.95153522491 --12.4782295227,2.13060545921,-4.99093770981 --12.474234581,2.13060069084,-5.01214170456 --12.4932518005,2.1365840435,-5.06453227997 --12.4832620621,2.13757491112,-5.10694789886 --12.4862756729,2.14156246185,-5.15334653854 --12.4962902069,2.1455476284,-5.20375108719 --12.4933023453,2.14853668213,-5.24815416336 --12.4893140793,2.15052604675,-5.29255962372 --12.4923219681,2.15251922607,-5.31675958633 --12.483332634,2.15350985527,-5.359167099 --12.4963493347,2.15849375725,-5.41056156158 --12.4743566513,2.15748810768,-5.44797897339 --12.4713697433,2.16047668457,-5.49338626862 --12.4253702164,2.15447831154,-5.5198097229 --12.4593935013,2.16445541382,-5.58119773865 --12.4493980408,2.16345214844,-5.60040616989 --12.4384088516,2.16444301605,-5.64181041718 --12.4414243698,2.16842937469,-5.6902141571 --12.42943573,2.16942024231,-5.73263072968 --12.4064435959,2.16841459274,-5.76904344559 --12.421462059,2.17439675331,-5.82344341278 --12.3934688568,2.17239284515,-5.85786056519 --12.4044790268,2.17638278008,-5.88605260849 --12.406496048,2.17936897278,-5.93445539474 --12.3825035095,2.17836332321,-5.97188043594 --12.3915224075,2.18334698677,-6.02327489853 --12.3785333633,2.18433785439,-6.06468391418 --12.3555412292,2.1833319664,-6.10210323334 --12.3565587997,2.18731784821,-6.15050697327 --12.3435621262,2.18631529808,-6.16871929169 --12.3425788879,2.19030189514,-6.21612167358 --12.3115844727,2.18729829788,-6.24954462051 --12.305598259,2.19028687477,-6.29394435883 --12.2966117859,2.19227576256,-6.33835744858 --12.2746219635,2.19126915932,-6.37577199936 --12.2736301422,2.19326233864,-6.3999786377 --12.2646446228,2.19525122643,-6.44439029694 --12.2526569366,2.19624114037,-6.48679828644 --12.248673439,2.19922828674,-6.53320121765 --12.2246828079,2.19822216034,-6.57062530518 --12.1776828766,2.19322419167,-6.59505414963 --12.1696977615,2.1952123642,-6.6404671669 --12.2087211609,2.20519137383,-6.68463993073 --12.1727256775,2.2021894455,-6.71506547928 --12.1627407074,2.20417785645,-6.75947761536 --12.1487541199,2.2051680088,-6.80189323425 --12.1647787094,2.21214723587,-6.86028814316 --12.1667985916,2.21613144875,-6.91068649292 --12.1618156433,2.21911787987,-6.95809412003 --12.1628265381,2.2211098671,-6.98430013657 --12.1698484421,2.22709178925,-7.03769397736 --12.1478595734,2.22708392143,-7.07712078094 --12.1458778381,2.23006939888,-7.12551736832 --12.1428985596,2.23405480385,-7.17492628098 --12.1179075241,2.23304820061,-7.21134328842 --12.134935379,2.24102568626,-7.27274227142 --12.1519527435,2.24601125717,-7.30793237686 --12.1469717026,2.24999690056,-7.35633850098 --12.1870098114,2.26196503639,-7.43172216415 --12.3230886459,2.2928955555,-7.56303834915 --12.4351596832,2.31983494759,-7.6823759079 --12.5292234421,2.34278082848,-7.79172134399 --12.5292472839,2.34676289558,-7.84612798691 --12.4682321548,2.33777785301,-7.83636760712 --12.414232254,2.33178162575,-7.85780620575 --12.3752384186,2.328779459,-7.88722896576 --12.3322429657,2.32477879524,-7.9156665802 --12.2712392807,2.31778550148,-7.93210983276 --12.2292442322,2.31378483772,-7.9595375061 --12.1762447357,2.30778861046,-7.97997236252 --12.1542463303,2.305788517,-7.99318933487 --12.1222553253,2.30478382111,-8.02661132812 --12.0672540665,2.2987883091,-8.04605484009 --12.0252590179,2.29478812218,-8.0724811554 --11.9972696304,2.29378151894,-8.10890674591 --11.9362649918,2.28678917885,-8.12335014343 --11.9002733231,2.28478598595,-8.1537771225 --11.867269516,2.28079104424,-8.15899944305 --11.8282747269,2.27778935432,-8.1874294281 --11.7822771072,2.27279067039,-8.2108631134 --11.7572898865,2.27278327942,-8.24828338623 --11.7202968597,2.27078080177,-8.27771377563 --11.6672954559,2.26478552818,-8.29615402222 --11.6453094482,2.26577687263,-8.33456611633 --11.6133050919,2.2617816925,-8.33978939056 --11.5653076172,2.25678443909,-8.36122703552 --11.5303144455,2.25478100777,-8.39165687561 --11.490319252,2.25178027153,-8.41808700562 --11.4483232498,2.24878048897,-8.4425163269 --11.4223356247,2.24877333641,-8.4789390564 --11.3693332672,2.24277853966,-8.49537658691 --11.3423318863,2.2397813797,-8.5035982132 --11.3113412857,2.23877668381,-8.53602409363 --11.2623414993,2.23378062248,-8.55445575714 --11.22935009,2.23277640343,-8.58588790894 --11.2003602982,2.23177099228,-8.6193113327 --11.1643686295,2.22976851463,-8.64774036407 --11.1213569641,2.22377920151,-8.64296913147 --11.1123800278,2.22776436806,-8.69138145447 --11.0593767166,2.22177004814,-8.70682239532 --11.0323886871,2.22176361084,-8.74124336243 --10.99239254,2.21876335144,-8.76567173004 --10.9543991089,2.21676206589,-8.7921037674 --10.9154033661,2.21376132965,-8.81753540039 --10.8944044113,2.21276187897,-8.82875156403 --10.8534088135,2.20976233482,-8.85218238831 --10.8154144287,2.20676088333,-8.87861824036 --10.7744178772,2.20376133919,-8.90205097198 --10.7424278259,2.20275735855,-8.93247890472 --10.6944265366,2.19876170158,-8.94890975952 --10.6464252472,2.19376540184,-8.96735572815 --10.6274271011,2.19276547432,-8.97856140137 --10.5844306946,2.18976712227,-8.99999904633 --10.5704517365,2.19275379181,-9.04541969299 --10.5434627533,2.19274759293,-9.07883930206 --10.5084705353,2.19074511528,-9.10626888275 --10.4784812927,2.19074010849,-9.13769435883 --10.431479454,2.18574404716,-9.15513420105 --10.3964719772,2.18175244331,-9.15335559845 --10.3654813766,2.18074798584,-9.18378353119 --10.3254852295,2.17774820328,-9.20722198486 --10.2974967957,2.17774248123,-9.23964309692 --10.2815170288,2.18072986603,-9.2830619812 --10.2385187149,2.17773222923,-9.30249404907 --10.1985225677,2.17473292351,-9.32492828369 --10.1825275421,2.17473077774,-9.34014606476 --10.1365270615,2.17073464394,-9.35658168793 --10.11054039,2.17072749138,-9.39100456238 --10.0775489807,2.169724226,-9.41943454742 --10.0415554047,2.16872286797,-9.44486618042 --9.99655532837,2.16472625732,-9.4623041153 --9.95755958557,2.1627266407,-9.48473739624 --9.94156455994,2.16172480583,-9.49895000458 --9.91157531738,2.16172003746,-9.52937507629 --9.87658214569,2.16071772575,-9.555809021 --9.84459114075,2.15971422195,-9.58423614502 --9.80959892273,2.15871214867,-9.6106710434 --9.77460575104,2.15671038628,-9.63609886169 --9.74161434174,2.15570735931,-9.66352748871 --9.72361755371,2.15570688248,-9.67574119568 --9.69663143158,2.15569972992,-9.71017456055 --9.66564083099,2.15569543839,-9.7396030426 --9.6306476593,2.15469408035,-9.76402664185 --9.58264541626,2.14969968796,-9.77747058868 --9.53464317322,2.14570569992,-9.78991031647 --9.49364471436,2.14270758629,-9.80934619904 --9.47965145111,2.14370441437,-9.82556056976 --9.46567440033,2.14669013023,-9.87097263336 --9.43068218231,2.14568829536,-9.89640522003 --9.39769172668,2.14568519592,-9.92383861542 --9.35569286346,2.14268803596,-9.94127178192 --9.34071540833,2.14567375183,-9.98668861389 --9.32173633575,2.14866161346,-10.0291147232 --9.30674171448,2.14865922928,-10.0443296432 --9.27375125885,2.14865636826,-10.0707550049 --9.24276256561,2.1486518383,-10.1001853943 --9.20676898956,2.14665031433,-10.1246213913 --9.17477893829,2.14664697647,-10.152048111 --9.13678455353,2.14464664459,-10.1744861603 --9.12479305267,2.145642519,-10.1926984787 --9.09280204773,2.14563894272,-10.2201242447 --9.05280590057,2.14364027977,-10.2395601273 --9.02281761169,2.14363503456,-10.269990921 --8.99483203888,2.14462852478,-10.3024187088 --8.96084022522,2.14362597466,-10.3288545609 --8.92384719849,2.1426255703,-10.3512887955 --8.89686012268,2.1436188221,-10.3837089539 --8.88587093353,2.14461326599,-10.4039239883 --8.85288143158,2.14460968971,-10.4313592911 --8.81088256836,2.14161300659,-10.4477958679 --8.79991149902,2.14759469032,-10.4992084503 --8.75591182709,2.1445991993,-10.5136499405 --8.73693466187,2.14758586884,-10.5570726395 --8.72494411469,2.14858150482,-10.5752830505 --8.69195365906,2.14857816696,-10.6027173996 --8.66597080231,2.15056967735,-10.6381454468 --8.63598442078,2.15056419373,-10.6685752869 --8.60499668121,2.15155959129,-10.6980056763 --8.57901382446,2.15255093575,-10.7334327698 --8.55603408813,2.15554022789,-10.7728595734 --8.53603553772,2.15454101562,-10.7820768356 --8.50805091858,2.15553426743,-10.8145017624 --8.48607349396,2.15852236748,-10.8559293747 --8.44907951355,2.15752148628,-10.8783664703 --8.4261007309,2.16051054001,-10.9177894592 --8.39411354065,2.16050624847,-10.9462213516 --8.35812091827,2.16050481796,-10.9696559906 --8.34613132477,2.16149973869,-10.9888687134 --8.31614589691,2.16249370575,-11.0203008652 --8.27514839172,2.16049575806,-11.0377407074 --8.23915576935,2.15949463844,-11.0611763 --8.21217441559,2.16148614883,-11.0966072083 --8.18319034576,2.16347908974,-11.1290359497 --8.14619731903,2.1624789238,-11.1504678726 --8.1442193985,2.16646528244,-11.183675766 --8.10822677612,2.16546392441,-11.2071113586 --8.0722360611,2.16546201706,-11.2315511703 --8.05126094818,2.16944909096,-11.2739696503 --8.0182723999,2.16944503784,-11.3014011383 --7.98127985001,2.16844439507,-11.3238391876 --7.96130752563,2.17342925072,-11.3702688217 --7.92829418182,2.16844129562,-11.3604927063 --7.90431785583,2.17142915726,-11.4019260406 --7.87233066559,2.17242455482,-11.430355072 --7.84334802628,2.17441701889,-11.4637861252 --7.81036090851,2.17441272736,-11.4922227859 --7.79539489746,2.18039298058,-11.5456428528 --7.77039051056,2.17839860916,-11.5468626022 --7.72639131546,2.17640304565,-11.5603113174 --7.68839788437,2.17540335655,-11.5807476044 --7.66041707993,2.17739462852,-11.6161785126 --7.63043403625,2.17938756943,-11.6486091614 --7.61146497726,2.18437075615,-11.6980361938 --7.52340841293,2.168415308,-11.6435060501 --7.46539020538,2.16143274307,-11.6349649429 --7.40433931351,2.1484708786,-11.5812101364 --7.35833406448,2.14447879791,-11.5876493454 --7.2442407608,2.12054848671,-11.4911422729 --7.21826267242,2.12353825569,-11.5295791626 --7.1472234726,2.1125702858,-11.4960355759 --7.07217931747,2.09960532188,-11.4575061798 --7.03816080093,2.09462046623,-11.4417295456 --6.96511793137,2.082654953,-11.4041938782 --6.90909767151,2.07567334175,-11.3936491013 --6.84005832672,2.06470513344,-11.3601064682 --6.77802848816,2.05673027039,-11.3385658264 --6.71399497986,2.04675793648,-11.3120212555 --6.66297912598,2.04177308083,-11.3064689636 --6.6219496727,2.03379583359,-11.2787075043 --6.57393741608,2.02980875969,-11.2771530151 --6.52292013168,2.02382493019,-11.2695951462 --6.46789836884,2.01784467697,-11.2570543289 --6.41788196564,2.01186037064,-11.250497818 --6.36986780167,2.00787425041,-11.2469396591 --6.31885099411,2.0018901825,-11.2403974533 --6.26680135727,1.98992609978,-11.1896362305 --6.21578216553,1.98494362831,-11.1800832748 --6.16676664352,1.97995889187,-11.1745347977 --6.12375926971,1.97696816921,-11.1789798737 --6.07273960114,1.97098577023,-11.1694326401 --6.02672624588,1.96699917316,-11.1668758392 --5.98672294617,1.96500599384,-11.1753158569 --5.97172880173,1.96500408649,-11.1885328293 --5.92471408844,1.96101856232,-11.1839790344 --5.89272356033,1.9620167017,-11.2074174881 --5.85271930695,1.95902407169,-11.2148561478 --5.80370092392,1.95404052734,-11.2073116302 --5.76069164276,1.95105135441,-11.2087516785 --5.75671577454,1.95603764057,-11.2419586182 --5.72372245789,1.95603728294,-11.2623939514 --5.697742939,1.95902848244,-11.2978315353 --5.66374826431,1.9590293169,-11.3162660599 --5.63576459885,1.962023139,-11.3466978073 --5.62280750275,1.96999943256,-11.407122612 --5.59382343292,1.97199344635,-11.4375619888 --5.57281970978,1.97099804878,-11.4397850037 --5.53682374954,1.97000026703,-11.4562292099 --5.49080848694,1.96601510048,-11.4506702423 --5.45681524277,1.96601545811,-11.4701089859 --5.42783069611,1.96900987625,-11.49954319 --5.40084981918,1.97200202942,-11.5329742432 --5.36685800552,1.97200131416,-11.5544204712 --5.36288404465,1.97698628902,-11.5896224976 --5.31286287308,1.9720056057,-11.5770778656 --5.24580764771,1.95904648304,-11.5275421143 --5.24688005447,1.97300374508,-11.6199493408 --5.20887994766,1.97200882435,-11.6313915253 --5.19392490387,1.9809845686,-11.6928186417 --5.17496109009,1.98696553707,-11.7452440262 --5.16097164154,1.988961339,-11.7624635696 --5.13199090958,1.99195361137,-11.7959060669 --5.10000371933,1.99395048618,-11.8213443756 --5.066010952,1.99395060539,-11.8407773972 --5.03202104568,1.99494946003,-11.8632230759 --4.99402046204,1.99395477772,-11.8736591339 --4.95301532745,1.99196338654,-11.8791055679 --4.93501806259,1.99296402931,-11.8883304596 --4.90303087234,1.99396073818,-11.913766861 --4.86603355408,1.99396455288,-11.9272060394 --4.83504915237,1.99595963955,-11.9556436539 --4.80206203461,1.99795675278,-11.981089592 --4.76005458832,1.99596691132,-11.9835367203 --4.73107290268,1.99896001816,-12.0149641037 --4.71107149124,1.99796354771,-12.0191898346 --4.68409729004,2.00195217133,-12.0586252213 --4.64509630203,2.00095844269,-12.068069458 --4.60408973694,1.99896800518,-12.0715112686 --4.5690984726,1.9999679327,-12.0919561386 --4.52809333801,1.99897658825,-12.097407341 --4.50809049606,1.99798119068,-12.0996265411 --4.47710752487,1.9999755621,-12.1290626526 --4.42908477783,1.99499535561,-12.1155166626 --4.39409399033,1.99599516392,-12.1359624863 --4.35809850693,1.99699783325,-12.1513996124 --4.31308364868,1.99301302433,-12.1458559036 --4.27708768845,1.99301552773,-12.1612930298 --4.25808763504,1.99301838875,-12.1665143967 --4.21307182312,1.98903393745,-12.1599683762 --4.17507123947,1.98904001713,-12.1694087982 --4.14007902145,1.9900405407,-12.1888504028 --4.09806966782,1.98705196381,-12.1892995834 --4.05906677246,1.98605930805,-12.1967449188 --4.02307319641,1.98706102371,-12.2141904831 --4.00206708908,1.98606777191,-12.2124099731 --3.96406745911,1.98507297039,-12.2238559723 --3.92606830597,1.98507809639,-12.2353048325 --3.88405632973,1.98209118843,-12.2327480316 --3.84605646133,1.98209691048,-12.2431936264 --3.80905842781,1.98210132122,-12.2556352615 --3.76303577423,1.97712099552,-12.2420892715 --3.74403524399,1.97712433338,-12.2463092804 --3.71205306053,1.98011898994,-12.2757520676 --3.66903805733,1.97713398933,-12.2702007294 --3.62502026558,1.97315073013,-12.2616539001 --3.592035532,1.97614717484,-12.2880973816 --3.54901957512,1.97316277027,-12.2815465927 --3.50800871849,1.97017538548,-12.2799911499 --3.49201655388,1.97217345238,-12.2932062149 --3.44899964333,1.96818959713,-12.2856559753 --3.41200375557,1.96919310093,-12.3001060486 --3.3740029335,1.96919941902,-12.3095531464 --3.32897853851,1.96422028542,-12.2940034866 --3.29197978973,1.96422529221,-12.3054456711 --3.25498199463,1.96422994137,-12.3178911209 --3.22996211052,1.96124505997,-12.3021230698 --3.1919605732,1.96025192738,-12.3105678558 --3.15395736694,1.96025979519,-12.3170099258 --3.111941576,1.95727550983,-12.310459137 --3.07093048096,1.95528817177,-12.3089122772 --3.03493452072,1.95529150963,-12.3233537674 --3.01191759109,1.95230484009,-12.3105754852 --2.96990180016,1.94932055473,-12.304028511 --2.93390679359,1.95032334328,-12.3194742203 --2.89289331436,1.94833791256,-12.3149232864 --2.85288596153,1.94734859467,-12.3173799515 --2.81588721275,1.94735383987,-12.3288249969 --2.77386784554,1.94437170029,-12.3182735443 --2.73184871674,1.94038903713,-12.3087244034 --2.71385002136,1.94139134884,-12.3149442673 --2.67283439636,1.93840694427,-12.3083934784 --2.63282418251,1.93641924858,-12.3078460693 --2.59883666039,1.93941807747,-12.3302869797 --2.555809021,1.93444061279,-12.3117322922 --2.51579785347,1.93245339394,-12.3101854324 --2.50081562996,1.93644607067,-12.3334102631 --2.45879387856,1.93246519566,-12.3208618164 --2.4187810421,1.93047916889,-12.3173112869 --2.38579821587,1.93347513676,-12.3447504044 --2.34277176857,1.92949736118,-12.3272047043 --2.30376267433,1.92850899696,-12.3276538849 --2.26575636864,1.9275188446,-12.3310985565 --2.24474239349,1.92553031445,-12.3213195801 --2.20473027229,1.92354393005,-12.3187761307 --2.16973972321,1.92554461956,-12.3382196426 --2.12872004509,1.92256271839,-12.3276720047 --2.09171772003,1.92257022858,-12.3351144791 --2.05471658707,1.92257738113,-12.3435602188 --2.01470255852,1.92059206963,-12.339015007 --1.9936902523,1.918602705,-12.331243515 --1.95769309998,1.91960740089,-12.3436851501 --1.9186822176,1.91862034798,-12.3421354294 --1.88168108463,1.91862750053,-12.3505821228 --1.84569180012,1.92162799835,-12.3710365295 --1.80768203735,1.92064011097,-12.3704786301 --1.77370357513,1.92463421822,-12.401927948 --1.76174664497,1.93261241913,-12.4501466751 --1.72676420212,1.93560886383,-12.4775972366 --1.69379591942,1.94159722328,-12.5190448761 --1.65982484818,1.94758749008,-12.5574979782 --1.62181925774,1.94759750366,-12.5609426498 --1.58583509922,1.95059514046,-12.5863962173 --1.54984736443,1.95359492302,-12.607843399 --1.52782022953,1.94861388206,-12.5850639343 --1.48982143402,1.94962024689,-12.5955181122 --1.45484471321,1.95461392403,-12.6279668808 --1.41583108902,1.95262861252,-12.6234111786 --1.37581527233,1.95064461231,-12.6168661118 --1.3388248682,1.95364630222,-12.6353178024 --1.29880416393,1.95066511631,-12.6237659454 --1.28081393242,1.95266318321,-12.6379919052 --1.24382531643,1.95566380024,-12.6584453583 --1.2048176527,1.95467531681,-12.6598978043 --1.16580700874,1.95368850231,-12.6583480835 --1.12780845165,1.95469486713,-12.668800354 --1.08980703354,1.95570278168,-12.6762485504 --1.05079829693,1.9547150135,-12.6767015457 --1.0317991972,1.95571815968,-12.681927681 --0.994805932045,1.957721591,-12.6973714828 --0.954793214798,1.95673620701,-12.6938323975 --0.917799055576,1.95874011517,-12.7082748413 --0.877785146236,1.9567553997,-12.7037353516 --0.839777886868,1.9567668438,-12.7051782608 --0.820786714554,1.95876562595,-12.7184095383 --0.781773328781,1.9577807188,-12.7138595581 --0.742766797543,1.95779180527,-12.7163162231 --0.703759133816,1.95680356026,-12.7177696228 --0.665749013424,1.95681667328,-12.716211319 --0.626748502254,1.95782458782,-12.7246723175 --0.5877379179,1.95683801174,-12.7231245041 --0.568740844727,1.95784020424,-12.7303504944 --0.529727339745,1.95685529709,-12.7258033752 --0.491723001003,1.95686519146,-12.7302484512 --0.452716529369,1.95687639713,-12.7327041626 --0.413705199957,1.95689058304,-12.7301578522 --0.375710189342,1.95889544487,-12.7436084747 --0.337721288204,1.96189701557,-12.7630596161 --0.317701607943,1.95891177654,-12.7482862473 --0.278704494238,1.96091806889,-12.7597455978 --0.239696100354,1.96093058586,-12.7602005005 --0.182759702206,1.97290742397,-12.8348855972 --0.143738120794,1.97092723846,-12.8223361969 --0.104732811451,1.9709379673,-12.8257894516 --0.0857102349401,1.96795427799,-12.808008194 --0.0467061437666,1.96896445751,-12.8124628067 --0.00768122868612,1.96598613262,-12.7969150543 -0.0146761527285,1.95899713039,-11.9601049423 -0.0536721050739,1.95698368549,-11.9484844208 -0.0926772505045,1.95597541332,-11.9458627701 -0.131677463651,1.95496428013,-11.9382429123 -0.150679573417,1.95495998859,-11.9364280701 -0.189671456814,1.95194458961,-11.9208106995 -0.227674484253,1.95093548298,-11.916182518 -0.26669639349,1.95393633842,-11.9295568466 -0.30569767952,1.95292592049,-11.9229393005 -0.34470897913,1.95292115211,-11.926317215 -0.382706195116,1.95190882683,-11.9156904221 -0.402727842331,1.95491492748,-11.9328784943 -0.441726922989,1.95290362835,-11.9242620468 -0.480755746365,1.95690834522,-11.9446296692 -0.520774483681,1.9589073658,-11.9550132751 -0.558775603771,1.95789730549,-11.9483852386 -0.596759557724,1.95387792587,-11.9247694016 -0.616777122021,1.95688188076,-11.9379558563 -0.655787408352,1.95687675476,-11.9403324127 -0.692769348621,1.95285642147,-11.9147100449 -0.731779932976,1.9538513422,-11.9170875549 -0.766719520092,1.94280838966,-11.849480629 -0.805732131004,1.94380450249,-11.8538579941 -0.843723654747,1.94178926945,-11.8372440338 -0.861712515354,1.938778162,-11.8224334717 -0.900728225708,1.94077587128,-11.8298091888 -0.939745783806,1.94277477264,-11.8391819 -0.980779707432,1.94778192043,-11.8645591736 -1.02181231976,1.95178866386,-11.8889341354 -1.06183218956,1.95478832722,-11.9003124237 -1.10186052322,1.95879304409,-11.9206790924 -1.12186670303,1.95879101753,-11.922870636 -1.15986514091,1.95777964592,-11.9132509232 -1.19786667824,1.95777010918,-11.9066267014 -1.23686552048,1.95675873756,-11.8970155716 -1.26881086826,1.94672000408,-11.8344020844 -1.30479335785,1.94270050526,-11.8087854385 -1.33875524998,1.93567025661,-11.7621765137 -1.35372054577,1.92864727974,-11.7233753204 -1.388697505,1.92462491989,-11.6917619705 -1.4196395874,1.91358470917,-11.6251592636 -1.45260667801,1.9075576067,-11.5835447311 -1.4885956049,1.90454173088,-11.5639314651 -1.52257275581,1.89951992035,-11.5323181152 -1.55756092072,1.89750397205,-11.5116987228 -1.57253181934,1.89248383045,-11.4779005051 -1.60852873325,1.89047253132,-11.4662799835 -1.64250552654,1.88645040989,-11.433672905 -1.67950749397,1.88544166088,-11.4270563126 -1.71248590946,1.88142073154,-11.3964395523 -1.74747645855,1.87940609455,-11.3778238297 -1.76547586918,1.87840104103,-11.3730154037 -1.7974486351,1.87337732315,-11.3364019394 -1.83344316483,1.87136471272,-11.3217935562 -1.86944067478,1.87035369873,-11.3101787567 -1.90041160583,1.86532926559,-11.2715644836 -1.93540334702,1.86331546307,-11.2539539337 -1.9724085331,1.86330854893,-11.2503376007 -1.99040842056,1.86330366135,-11.2455291748 -2.02540206909,1.86129081249,-11.2299156189 -2.06642985344,1.86529529095,-11.24929142 -2.10042142868,1.86328172684,-11.231672287 -2.13340568542,1.86026406288,-11.2060613632 -2.17141413689,1.8612588644,-11.205447197 -2.20741844177,1.86125171185,-11.2008228302 -2.21436285973,1.85121917725,-11.1390304565 -2.24835371971,1.84920525551,-11.1204185486 -2.28033423424,1.8451859951,-11.0908136368 -2.31432533264,1.84317219257,-11.0722036362 -2.34932255745,1.8421612978,-11.0595903397 -2.37929916382,1.83814060688,-11.0259780884 -2.41429901123,1.83713126183,-11.0163593292 -2.42727422714,1.83311414719,-10.9855680466 -2.45725178719,1.82809400558,-10.952958107 -2.49024510384,1.82708156109,-10.9363384247 -2.51520061493,1.81805074215,-10.8807401657 -2.54417490959,1.81302893162,-10.8441362381 -2.57616281509,1.81101381779,-10.8215265274 -2.61216759682,1.81100726128,-10.8169126511 -2.62715625763,1.80899703503,-10.800113678 -2.66115474701,1.80798745155,-10.7884979248 -2.69716000557,1.80898082256,-10.7838821411 -2.72814488411,1.80596458912,-10.7582759857 -2.7611413002,1.80495417118,-10.7446565628 -2.79313206673,1.80294084549,-10.7250442505 -2.82110762596,1.79792010784,-10.6894397736 -2.8320851326,1.79390466213,-10.6606397629 -2.86708641052,1.7938965559,-10.6520299911 -2.89506244659,1.78887605667,-10.6164293289 -2.93207263947,1.79087221622,-10.616812706 -2.96908259392,1.79286837578,-10.6171951294 -2.99505376816,1.78684580326,-10.576593399 -3.0100467205,1.78583800793,-10.563791275 -3.04605484009,1.78683340549,-10.5621700287 -3.08406686783,1.78883039951,-10.5645570755 -3.09097695351,1.77177882195,-10.458978653 -3.12096571922,1.76976490021,-10.4363689423 -3.15195536613,1.7677513361,-10.4147663116 -3.1859562397,1.76774322987,-10.4051551819 -3.20095276833,1.7667375803,-10.3963422775 -3.23294734955,1.7657263279,-10.379734993 -3.2659444809,1.76471662521,-10.3661279678 -3.2969379425,1.76370513439,-10.3485145569 -3.32492113113,1.75968885422,-10.3199110031 -3.35591292381,1.75867652893,-10.3003072739 -3.3869073391,1.75766563416,-10.2836923599 -3.39788866043,1.75365257263,-10.2579040527 -3.43189239502,1.75464606285,-10.2512845993 -3.45987796783,1.75163114071,-10.2246780396 -3.49488282204,1.75262510777,-10.2190656662 -3.53791069984,1.75762999058,-10.2384395599 -3.57191300392,1.75762283802,-10.2298269272 -3.59588575363,1.75260174274,-10.1892366409 -3.60987901688,1.75159454346,-10.1764326096 -3.63987159729,1.74958312511,-10.1578197479 -3.66986298561,1.74857091904,-10.1372146606 -3.69985461235,1.74655878544,-10.1166114807 -3.73085093498,1.74554932117,-10.1019954681 -3.75984048843,1.74353635311,-10.0793905258 -3.79183864594,1.74352729321,-10.0657806396 -3.80683302879,1.74252057076,-10.0539865494 -3.84877467155,1.73147785664,-9.96779251099 -3.88578629494,1.7334754467,-9.9691734314 -3.91878795624,1.73446822166,-9.95955944061 -3.95178866386,1.73446071148,-9.94894981384 -3.95475506783,1.72744131088,-9.90617084503 -3.98274421692,1.72542846203,-9.88256835938 -4.01574659348,1.72642183304,-9.87395191193 -4.04574108124,1.72541165352,-9.85634422302 -4.07774019241,1.72540342808,-9.84373474121 -4.10974025726,1.72539567947,-9.83212089539 -4.14274072647,1.72538793087,-9.82051753998 -4.1577372551,1.72538244724,-9.81071949005 -4.19274282455,1.72637712955,-9.80510902405 -4.22073554993,1.7253664732,-9.78549194336 -4.25674295425,1.72636198997,-9.7818813324 -4.28874111176,1.72635352612,-9.76827716827 -4.35481214523,1.74137723446,-9.83463287354 -4.36276197433,1.73134720325,-9.76704406738 -4.36072254181,1.72332596779,-9.71726799011 -4.3947262764,1.72432005405,-9.70965576172 -4.42371988297,1.7233093977,-9.6900510788 -4.4557185173,1.72330117226,-9.67644786835 -4.49373102188,1.72629928589,-9.67882442474 -4.51871728897,1.72328579426,-9.65122127533 -4.54771089554,1.72227525711,-9.63161849976 -4.57272768021,1.7262789011,-9.6448059082 -4.60973739624,1.7282756567,-9.64319038391 -4.63672733307,1.72726368904,-9.61958694458 -4.66572093964,1.7262532711,-9.59998512268 -4.69772005081,1.72624564171,-9.58737564087 -4.72771596909,1.72523617744,-9.56977367401 -4.76873254776,1.72923588753,-9.57615375519 -4.78773832321,1.73123455048,-9.57634353638 -4.81172227859,1.72822022438,-9.54575061798 -4.84472465515,1.72921395302,-9.53613567352 -4.88373708725,1.73221170902,-9.53751945496 -4.90972566605,1.73019945621,-9.51191997528 -4.95074033737,1.73319840431,-9.51630592346 -4.98073577881,1.73318910599,-9.49870300293 -4.99272823334,1.73218214512,-9.48390483856 -5.02673244476,1.73317682743,-9.47628688812 -5.05973291397,1.73416936398,-9.46368503571 -5.07871007919,1.72915244102,-9.42509365082 -5.1067032814,1.72814238071,-9.40448951721 -5.16674995422,1.73915457726,-9.44485092163 -5.16872596741,1.73414075375,-9.41106510162 -5.19171047211,1.7311270237,-9.3804693222 -5.22671604156,1.73312211037,-9.3738527298 -5.2587146759,1.73311424255,-9.35925388336 -5.28470516205,1.73210310936,-9.33564758301 -5.32071113586,1.73409855366,-9.33003330231 -5.35070753098,1.73408973217,-9.31243133545 -5.4007101059,1.73508012295,-9.29601860046 -5.42770242691,1.73406994343,-9.27441215515 -5.46370840073,1.73606514931,-9.26780223846 -5.50171613693,1.73906099796,-9.26319789886 -5.53171253204,1.73905229568,-9.24559497833 -5.56070756912,1.73804330826,-9.22698974609 -5.57169961929,1.7370364666,-9.21119308472 -5.61070966721,1.74003350735,-9.2095785141 -5.63569927216,1.73802220821,-9.18397808075 -5.67470884323,1.74101889133,-9.18136787415 -5.70670843124,1.7420116663,-9.16775894165 -5.74271345139,1.74400663376,-9.16015052795 -5.77471256256,1.74399912357,-9.14554786682 -5.7897105217,1.74399495125,-9.13674640656 -5.81670475006,1.74398553371,-9.11613368988 -5.8537106514,1.74598097801,-9.10952663422 -5.88570976257,1.74697363377,-9.09492206573 -5.92071294785,1.74796807766,-9.085313797 -5.95371294022,1.74896097183,-9.07171154022 -5.97271680832,1.75095891953,-9.06890678406 -5.99169874191,1.74694490433,-9.03431224823 -6.01769065857,1.74593484402,-9.01071071625 -6.06471014023,1.75193548203,-9.02008628845 -6.1047205925,1.75493264198,-9.01846790314 -6.14773321152,1.75893044472,-9.0188627243 -6.15369939804,1.75191044807,-8.96527671814 -6.17170143127,1.75290775299,-8.96047496796 -6.20069694519,1.75289940834,-8.94186782837 -6.23670053482,1.75489401817,-8.93226337433 -6.27570867538,1.75789022446,-8.92765140533 -6.30069923401,1.7568795681,-8.90205383301 -6.3417096138,1.760876894,-8.90043830872 -6.38171863556,1.7638733387,-8.89682579041 -6.41974496841,1.77087986469,-8.92100048065 -6.45674991608,1.77287471294,-8.91239261627 -6.47473192215,1.7698611021,-8.87680053711 -6.50172424316,1.76885139942,-8.8532075882 -6.51169776917,1.76383495331,-8.80761623383 -6.54870271683,1.76582992077,-8.79900741577 -6.57869911194,1.76682174206,-8.78040599823 -6.60270881653,1.76982200146,-8.78458976746 -6.62869977951,1.76881182194,-8.75900173187 -6.66370296478,1.77080631256,-8.74838733673 -6.70170783997,1.77280139923,-8.73978424072 -6.73370695114,1.77379441261,-8.72417736053 -6.76470470428,1.77478671074,-8.70657444 -6.79071521759,1.77778708935,-8.71176433563 -6.8086977005,1.77477407455,-8.67617893219 -6.84970760345,1.77877080441,-8.67256164551 -6.89672279358,1.78376996517,-8.6769361496 -6.92271518707,1.78376030922,-8.6523399353 -6.97273254395,1.78975987434,-8.65872192383 -7.01574277878,1.79375684261,-8.65610790253 -7.0257358551,1.79275095463,-8.6403093338 -7.06874608994,1.7967479229,-8.63769340515 -7.10174560547,1.79774105549,-8.62208843231 -7.14375305176,1.80173707008,-8.61648273468 -7.16373968124,1.79972553253,-8.5848865509 -7.21075296402,1.80472362041,-8.58626937866 -7.24475383759,1.80571722984,-8.57166290283 -7.24273395538,1.80170702934,-8.53988456726 -7.28574371338,1.80570363998,-8.53626918793 -7.30573034286,1.80369246006,-8.50467300415 -7.11550998688,1.74561011791,-8.21928215027 -7.07944393158,1.72958099842,-8.12174415588 -7.10543823242,1.72957313061,-8.10013961792 -7.10941171646,1.72355759144,-8.05057048798 -7.1043920517,1.71854794025,-8.01878261566 -7.11036777496,1.71353375912,-7.97320365906 -7.11534357071,1.70851933956,-7.92662572861 -7.12932777405,1.7055079937,-7.8910369873 -7.15432262421,1.70450031757,-7.86843776703 -7.1653046608,1.70148837566,-7.82985019684 -7.17928934097,1.69847726822,-7.79426622391 -7.18928432465,1.69747269154,-7.78046607971 -7.20226764679,1.69446122646,-7.74289226532 -7.2122502327,1.69044947624,-7.70430231094 -7.24525260925,1.6924444437,-7.69069766998 -7.24322319031,1.68542921543,-7.6381278038 -7.27022123337,1.68642270565,-7.61852359772 -7.28921079636,1.68441367149,-7.5889377594 -7.28219223022,1.67940473557,-7.55715322495 -7.30718755722,1.6793974638,-7.53455924988 -7.32617855072,1.678388834,-7.5059671402 -7.33616161346,1.67437767982,-7.46738767624 -7.3471455574,1.67136716843,-7.43080091476 -7.37814712524,1.67336189747,-7.41519784927 -7.37813472748,1.67035508156,-7.39041614532 -7.40313148499,1.67034864426,-7.36980772018 -7.42412376404,1.66934049129,-7.34222698212 -7.42810344696,1.66432881355,-7.29964065552 -7.44709444046,1.66332054138,-7.27105522156 -7.46608686447,1.66231262684,-7.24346017838 -7.48207616806,1.6603038311,-7.21187829971 -7.4880695343,1.65929913521,-7.1950802803 -7.51006412506,1.65829205513,-7.17048501968 -7.51704645157,1.65428113937,-7.12991333008 -7.53603887558,1.65327382088,-7.10331344604 -7.56303787231,1.65426802635,-7.08371448517 -7.57102155685,1.65125787258,-7.04513597488 -7.58000659943,1.64724802971,-7.00755882263 -7.58199739456,1.64524269104,-6.98676872253 -7.60999679565,1.64623725414,-6.96817016602 -7.61197757721,1.64122629166,-6.92459535599 -7.63597393036,1.6422201395,-6.90200233459 -7.646961689,1.63921153545,-6.8684091568 -7.65895032883,1.63720297813,-6.83482408524 -7.67495107651,1.63820075989,-6.82702684402 -7.67092847824,1.63218927383,-6.77944993973 -7.68491840363,1.63018131256,-6.74786567688 -7.70291090012,1.62917411327,-6.71928548813 -7.71289873123,1.62616562843,-6.68470001221 -7.71988487244,1.62315678596,-6.64811229706 -7.72887182236,1.62014842033,-6.61253118515 -7.74287128448,1.62014579773,-6.60273885727 -7.75586175919,1.61813819408,-6.5711517334 -7.76785182953,1.61613070965,-6.53955841064 -7.78084182739,1.61412298679,-6.50698328018 -7.80083751678,1.61411714554,-6.4823846817 -7.81182670593,1.61210942268,-6.44880533218 -7.82081508636,1.60910153389,-6.41422224045 -7.8308134079,1.60909867287,-6.40241861343 -7.83279657364,1.60508942604,-6.36085271835 -7.85079097748,1.60408341885,-6.33426189423 -7.8627820015,1.60207641125,-6.30267524719 -7.88277816772,1.60207080841,-6.27808046341 -7.89176654816,1.59906315804,-6.24350309372 -7.90175676346,1.59705603123,-6.20992422104 -7.90675163269,1.59605252743,-6.19412517548 -7.92274570465,1.59504652023,-6.16653203964 -7.93973970413,1.59404051304,-6.13894701004 -7.9407248497,1.59003210068,-6.09837627411 -7.95471763611,1.58902597427,-6.06879091263 -7.96070623398,1.58601868153,-6.03320932388 -7.9817032814,1.58601367474,-6.00961494446 -7.97969436646,1.58300936222,-5.98783016205 -8.0026922226,1.58400464058,-5.96524047852 -8.01268386841,1.58199834824,-5.93365049362 -8.02567768097,1.58099222183,-5.90307188034 -8.03566837311,1.5789860487,-5.87148284912 -8.04465961456,1.57697951794,-5.83790874481 -8.04465198517,1.57497572899,-5.81812143326 -8.06364917755,1.57497096062,-5.79352617264 -8.06363582611,1.57096362114,-5.75395345688 -8.07162570953,1.56795752048,-5.72136592865 -8.0886220932,1.56795251369,-5.69477939606 -8.09561252594,1.56494617462,-5.66020774841 -8.10760593414,1.56394088268,-5.63061904907 -8.10559844971,1.56193709373,-5.60983276367 -8.11459064484,1.55993151665,-5.5782456398 -8.12358188629,1.55792582035,-5.54567098618 -8.14157962799,1.55792140961,-5.5210723877 -8.15157222748,1.55591595173,-5.4894952774 -8.16656780243,1.55491113663,-5.46190977097 -8.17055702209,1.55190515518,-5.42633581161 -8.17955589294,1.55190312862,-5.4145321846 -8.19255161285,1.55089819431,-5.38495588303 -8.2035446167,1.54989326,-5.35536670685 -8.21654033661,1.5488884449,-5.32678079605 -8.22953510284,1.54788386822,-5.29819536209 -8.24453163147,1.54787945747,-5.2716012001 -8.26052856445,1.54687511921,-5.24501419067 -8.25952243805,1.54487216473,-5.22523355484 -8.25751018524,1.54086637497,-5.18666219711 -8.26650428772,1.53986167908,-5.1560754776 -8.27349758148,1.53785681725,-5.12349891663 -8.2774887085,1.53485167027,-5.08892631531 -8.28248119354,1.53284704685,-5.05633878708 -8.27947425842,1.52984404564,-5.03556108475 -8.28946876526,1.52883970737,-5.00597429276 -8.30446529388,1.52883589268,-4.97938632965 -8.30245494843,1.52483081818,-4.94181442261 -8.31745243073,1.52482700348,-4.91522741318 -8.32444667816,1.52282273769,-4.88364696503 -8.31943511963,1.5188177824,-4.8450717926 -8.33043479919,1.51881623268,-4.83427286148 -8.34143161774,1.51781237125,-4.80469751358 -8.33942222595,1.51480770111,-4.76812124252 -8.34141349792,1.5118033886,-4.73354959488 -8.36241436005,1.51280045509,-4.71095657349 -8.35540294647,1.50879573822,-4.67237710953 -8.37340164185,1.50879251957,-4.64680194855 -8.38040065765,1.50879096985,-4.63400173187 -8.3723897934,1.50378644466,-4.59443235397 -8.3873872757,1.50378334522,-4.56883907318 -8.40138530731,1.50378012657,-4.54126405716 -8.39537525177,1.49977612495,-4.50368690491 -8.39836978912,1.49777245522,-4.47110652924 -8.42037010193,1.49876976013,-4.44852161407 -8.41036224365,1.49576747417,-4.42574119568 -8.42336082458,1.49476468563,-4.39915084839 -8.43335819244,1.49376142025,-4.36957931519 -8.43535137177,1.49175822735,-4.33699703217 -8.45535182953,1.49275553226,-4.31341218948 -8.46234798431,1.49175262451,-4.28382349014 -8.4473400116,1.48675048351,-4.25904464722 -8.46333885193,1.48774778843,-4.23346185684 -8.48233985901,1.48874545097,-4.20987129211 -8.47432994843,1.48374211788,-4.1713104248 -8.47532463074,1.48173928261,-4.13872909546 -8.47731971741,1.47973632812,-4.10615444183 -8.48231601715,1.47773373127,-4.07557296753 -8.48731517792,1.47773253918,-4.06177806854 -8.506316185,1.47873032093,-4.03818941116 -8.51131248474,1.47672784328,-4.00760936737 -8.51530742645,1.47472524643,-3.97603726387 -8.53230857849,1.47572314739,-3.95144939423 -8.48528766632,1.46471977234,-3.89590191841 -8.51229095459,1.46671807766,-3.87630820274 -8.51529026031,1.46671700478,-3.86151623726 -8.37423801422,1.43771231174,-3.76005530357 -8.33722019196,1.42770981789,-3.71050524712 -8.41124153137,1.43970894814,-3.71387505531 -8.36222076416,1.42770648003,-3.65834259987 -8.49225997925,1.44970619678,-3.68766832352 -8.54527187347,1.4577049017,-3.68104219437 -8.4852514267,1.44570350647,-3.63729786873 -8.34520339966,1.41770076752,-3.54083108902 -8.3341960907,1.41269922256,-3.50426793098 -8.35820102692,1.41569793224,-3.48466444016 -8.31818580627,1.40569639206,-3.43512558937 -8.30917930603,1.40169513226,-3.40055203438 -8.15513134003,1.37269437313,-3.31688165665 -8.11211585999,1.3626935482,-3.26734519005 -8.05409622192,1.3496928215,-3.21280455589 -7.87104082108,1.31369292736,-3.10436463356 -8.01808261871,1.33869183064,-3.13768768311 -8.06809616089,1.34669113159,-3.13006639481 -8.02408123016,1.33669090271,-3.08251786232 -7.99907398224,1.33069086075,-3.05675888062 -7.98006772995,1.32569074631,-3.02019119263 -7.88804101944,1.30669152737,-2.95368099213 -7.89304161072,1.30569148064,-2.92710280418 -7.89904260635,1.3046913147,-2.90053009987 -7.89404153824,1.30269157887,-2.87094497681 -7.87303495407,1.29769194126,-2.84817624092 -7.83902597427,1.2896926403,-2.80662465096 -7.83402442932,1.28669297695,-2.77704644203 -7.71699476242,1.26469552517,-2.70356035233 -7.75400447845,1.26869535446,-2.68996238708 -7.70699310303,1.25969696045,-2.64540791512 -7.55395507812,1.22970092297,-2.55995440483 -7.70999526978,1.25769793987,-2.60505056381 -7.61197185516,1.23770093918,-2.54154634476 -7.61897468567,1.23770165443,-2.51697063446 -7.56596326828,1.22670412064,-2.47142577171 -7.63798236847,1.23770308495,-2.47079753876 -7.55696392059,1.2217066288,-2.41527962685 -7.4889497757,1.20870983601,-2.36475586891 -7.56196784973,1.22070813179,-2.37790560722 -7.48695278168,1.20571184158,-2.32538676262 -7.48895549774,1.20471310616,-2.29981374741 -7.48795747757,1.20271456242,-2.27422761917 -7.3849363327,1.18371975422,-2.21372437477 -7.36293411255,1.17772221565,-2.1811606884 -7.32992982864,1.1707252264,-2.14461398125 -7.31292772293,1.16672670841,-2.12683176994 -7.38994789124,1.17972552776,-2.12620902061 -7.48297071457,1.19472360611,-2.1315536499 -7.36294794083,1.17173039913,-2.06707692146 -7.29093647003,1.15773546696,-2.01954913139 -7.25693273544,1.15073895454,-1.9840003252 -7.18091869354,1.13674330711,-1.94924855232 -7.16591978073,1.13274633884,-1.91969382763 -7.16292285919,1.13074862957,-1.89510965347 -7.15992689133,1.12975132465,-1.8695435524 -7.13492584229,1.12375485897,-1.83798587322 -7.1149263382,1.11875832081,-1.80841898918 -7.11393070221,1.11776089668,-1.78385019302 -7.1259355545,1.11976158619,-1.77604115009 -7.08493232727,1.11176633835,-1.74049496651 -7.05893230438,1.1057703495,-1.70992994308 -7.0519361496,1.10377347469,-1.68435978889 -7.03493785858,1.09977722168,-1.65580284595 -7.05394601822,1.10177898407,-1.63820099831 -7.0159444809,1.09378397465,-1.60465168953 -7.01394701004,1.09278559685,-1.59187602997 -6.9959487915,1.08878970146,-1.56430566311 -6.98895311356,1.08679306507,-1.53972756863 -6.97095537186,1.08279716969,-1.51216208935 -7.00396633148,1.0877982378,-1.49756109715 -6.94796323776,1.07680499554,-1.46003472805 -6.97597360611,1.08080649376,-1.44443190098 -6.93496990204,1.07281076908,-1.42267882824 -6.91897296906,1.06981492043,-1.39709508419 -6.91797924042,1.06881856918,-1.37353205681 -6.90398263931,1.06482279301,-1.34795999527 -6.91499090195,1.06582546234,-1.32836818695 -6.89299345016,1.06183040142,-1.30080771446 -6.88299560547,1.05983293056,-1.28703212738 -6.86499881744,1.05583763123,-1.26145339012 -6.85600423813,1.05284190178,-1.23688912392 -6.82800722122,1.04784762859,-1.20833778381 -6.88302135468,1.05584716797,-1.19870758057 -6.84702301025,1.04885363579,-1.16817069054 -6.88403463364,1.05485451221,-1.15455126762 -6.85503435135,1.0498585701,-1.13777840137 -6.81503629684,1.04186546803,-1.10723793507 -6.9640622139,1.06685769558,-1.1145607233 -6.82705116272,1.04287230968,-1.06606972218 -6.88706588745,1.05187141895,-1.05545461178 -6.83306646347,1.04187953472,-1.02390241623 -6.85307598114,1.0448820591,-1.00531947613 -6.78307151794,1.03288984299,-0.981579005718 -6.84508609772,1.04288876057,-0.970960855484 -6.83309173584,1.03989374638,-0.947384774685 -6.90510797501,1.05189180374,-0.937763988972 -6.78210163116,1.02990627289,-0.895264327526 -6.80311155319,1.03290879726,-0.876682758331 -6.79711866379,1.03091347218,-0.854109585285 -6.77311944962,1.02691757679,-0.840320110321 -6.79412937164,1.02992022038,-0.82173705101 -6.73313093185,1.01892983913,-0.79119259119 -6.74614048004,1.02093303204,-0.771611392498 -6.76715087891,1.02393567562,-0.753027379513 -6.74615621567,1.019941926,-0.729447484016 -6.65015125275,1.00295293331,-0.704729199409 -6.9751906395,1.05792748928,-0.728943049908 -6.88519001007,1.04194009304,-0.695410311222 -6.70818138123,1.01096117496,-0.649952173233 -6.73419237137,1.01496338844,-0.632355391979 -6.70319843292,1.00997114182,-0.606806993484 -6.70420694351,1.00897562504,-0.586222350597 -6.72521305084,1.01297593117,-0.578416764736 -6.68421840668,1.00498473644,-0.551877677441 -7.04325580597,1.06595396996,-0.573056817055 -6.74024009705,1.01398861408,-0.516678750515 -6.69924545288,1.00699746609,-0.491127222776 -6.65625095367,0.999006688595,-0.46557828784 -6.69726324081,1.00600743294,-0.448974698782 -6.94428539276,1.04698455334,-0.464018791914 -6.81628513336,1.02500247955,-0.429527670145 -6.81829357147,1.02500700951,-0.408939212561 -6.70829486847,1.00602340698,-0.37743461132 -6.67530202866,1.00003182888,-0.35387262702 -6.70031261444,1.00403416157,-0.335278004408 -6.69232177734,1.0030400753,-0.31370651722 -6.72032833099,1.00703978539,-0.304913133383 -6.7283372879,1.00804388523,-0.285316646099 -6.66134309769,0.997056365013,-0.258793860674 -6.69435405731,1.00205779076,-0.241180583835 -6.69336366653,1.00206291676,-0.220597848296 -6.657371521,0.995072245598,-0.197051823139 -6.66437673569,0.996074020863,-0.187256723642 -6.69238758087,1.00107610226,-0.16865350306 -6.65839529037,0.995085179806,-0.146094352007 -6.77341032028,1.014077425,-0.131449148059 -6.70041656494,1.00209105015,-0.106913499534 -6.63642406464,0.991103887558,-0.0823903977871 -6.6884355545,0.99910312891,-0.0647678226233 -6.90544939041,1.03608071804,-0.0638420879841 -6.79545450211,1.01709866524,-0.0383275896311 -6.73546218872,1.00711119175,-0.0147929927334 -6.75747299194,1.01111376286,0.00480861961842 -6.76248264313,1.01111888885,0.0263728573918 -6.78049325943,1.01412200928,0.0459782555699 -6.76349830627,1.01112699509,0.057739701122 -6.85851049423,1.02712106705,0.0763785988092 -6.7835187912,1.01513552666,0.0989130958915 -6.69352626801,0.999152004719,0.121433652937 -6.88554096222,1.03213405609,0.139138430357 -6.64054536819,0.990169584751,0.162572547793 -6.63255548477,0.989176273346,0.183145672083 -6.63356113434,0.989179134369,0.193924129009 -6.65657186508,0.993182063103,0.214513227344 -6.66058206558,0.994187057018,0.234113588929 -6.62459230423,0.988197386265,0.254667162895 -6.60160255432,0.984206140041,0.275225788355 -6.7196149826,1.00419700146,0.296874821186 -6.79962587357,1.01719260216,0.318505257368 -6.66763019562,0.995212435722,0.327210813761 -6.67664051056,0.997217059135,0.347798109055 -6.60965108871,0.985231697559,0.367328733206 -6.57566213608,0.980242013931,0.386887252331 -6.57667255402,0.980247676373,0.40648162365 -6.58168363571,0.981253027916,0.427060842514 -6.58968925476,0.982255101204,0.437847286463 -6.6047000885,0.985259115696,0.458441078663 -6.69071149826,1.00025379658,0.482073158026 -6.7587223053,1.01125061512,0.505690038204 -6.81273269653,1.0212495327,0.529295146465 -6.79974412918,1.01925730705,0.549863576889 -6.66475582123,0.996281325817,0.563374638557 -6.75476074219,1.01127243042,0.579201579094 -6.90376996994,1.03725814819,0.607879340649 -6.84878206253,1.02827179432,0.626417577267 -6.97579097748,1.04926037788,0.655079305172 -6.59980726242,0.98631811142,0.652431309223 -6.61081790924,0.988322734833,0.673029065132 -6.5478310585,0.978337883949,0.689559578896 -6.58283615112,0.984336197376,0.702367722988 -6.52984905243,0.975349962711,0.718911767006 -6.51886034012,0.97335755825,0.737500727177 -6.51687240601,0.973364412785,0.758068323135 -6.61488199234,0.990356981754,0.78670501709 -6.61489391327,0.991363346577,0.807283818722 -6.52090787888,0.975383043289,0.818815648556 -6.53191328049,0.977384865284,0.830599009991 -6.52192544937,0.976392567158,0.849188268185 -6.49293804169,0.971403241158,0.866747260094 -6.47295093536,0.968412816525,0.885306596756 -6.48996257782,0.971416771412,0.906903684139 -6.48997497559,0.972423434258,0.927476227283 -6.5439786911,0.981418788433,0.943303287029 -6.46299409866,0.968437314034,0.954828560352 -6.46600580215,0.969443559647,0.975408911705 -6.46401834488,0.969450354576,0.994995176792 -6.46703052521,0.970456600189,1.01557660103 -6.50404119492,0.976457953453,1.04116392136 -6.51305294037,0.978463351727,1.06274783611 -6.44306230545,0.967477023602,1.06350231171 -6.44407510757,0.967483699322,1.08407759666 -6.45108652115,0.969489276409,1.10467374325 -6.44210004807,0.968497514725,1.1242364645 -6.4471116066,0.969503462315,1.14482700825 -6.42812585831,0.967513203621,1.1623942852 -6.44113779068,0.969518184662,1.18497371674 -6.41614484787,0.965525209904,1.19076085091 -6.47315454483,0.976523578167,1.2203630209 -6.49916601181,0.981526434422,1.24495708942 -6.4491815567,0.973541021347,1.25750625134 -6.43019485474,0.970550656319,1.2740893364 -6.45020723343,0.974554777145,1.29866313934 -6.43521404266,0.972560286522,1.30546271801 -6.48722362518,0.981559216976,1.33506810665 -6.46123838425,0.977570414543,1.35162222385 -6.44325256348,0.975580334663,1.369186759 -6.4362654686,0.974588215351,1.38777577877 -6.43427848816,0.975595712662,1.40834593773 -6.43629169464,0.976602315903,1.42893350124 -6.41429901123,0.972609221935,1.43471705914 -6.4493098259,0.979610860348,1.46231067181 -6.40332651138,0.972625255585,1.47386491299 -6.37534189224,0.968637049198,1.48941588402 -6.34835672379,0.964648425579,1.5039883852 -6.42736387253,0.978642940521,1.54061543941 -6.41537857056,0.977652132511,1.55918037891 -6.49237823486,0.990643024445,1.58502960205 -6.49139213562,0.991650640965,1.60659205914 -6.43140983582,0.981667459011,1.61414432526 -6.42442417145,0.981675922871,1.63371384144 -6.78340816498,1.04462480545,1.73548936844 -6.48844575882,0.994679987431,1.68991065025 -6.46646022797,0.991690635681,1.70548641682 -6.44846916199,0.988697469234,1.71225714684 -6.45348119736,0.990703701973,1.7338514328 -6.43549633026,0.987713873386,1.75042438507 -6.42851066589,0.987722456455,1.76999533176 -6.46952056885,0.995723247528,1.80158853531 -6.41053962708,0.986740350723,1.8081343174 -6.42554473877,0.989741444588,1.82194197178 -6.43355751038,0.991747617722,1.84551763535 -6.4355711937,0.9927546978,1.86710035801 -6.39458847046,0.986768960953,1.87765645981 -6.44759702682,0.996767342091,1.91227567196 -6.43261241913,0.99577742815,1.92984223366 -6.42562675476,0.994786083698,1.94941473007 -6.41263484955,0.993791937828,1.95620405674 -6.44964504242,1.00079321861,1.9878026247 -6.42666149139,0.997804820538,2.0033595562 -6.47966957092,1.00780332088,2.0399646759 -6.39069271088,0.993825852871,2.0355079174 -6.34071159363,0.985841810703,2.04206681252 -6.3837146759,0.99383854866,2.06586766243 -6.36373090744,0.991849541664,2.08143568039 -6.37874269485,0.99485450983,2.10702896118 -6.40875387192,1.0018569231,2.13762426376 -6.41776704788,1.00386309624,2.16220474243 -6.3527879715,0.993882000446,2.16375136375 -6.44279241562,1.01087415218,2.21337938309 -6.40580320358,1.0048841238,2.21215987206 -6.35582304001,0.996900737286,2.21870040894 -6.37983417511,1.0029040575,2.2473077774 -6.34485292435,0.997917890549,2.25786614418 -6.34186697006,0.997926175594,2.27844715118 -6.34288215637,0.999933898449,2.30101799965 -6.37389183044,1.00593614578,2.33262467384 -6.40589523315,1.01293432713,2.35443019867 -6.36891412735,1.00694859028,2.36398911476 -6.33793258667,1.00296199322,2.37554860115 -6.31994915009,1.00097298622,2.39112138748 -6.35695934296,1.00897455215,2.42670750618 -6.37397146225,1.01297926903,2.45430612564 -6.64895153046,1.06393826008,2.57502579689 -6.64395904541,1.06394302845,2.58481359482 -6.34901094437,1.01200342178,2.5012357235 -6.32602834702,1.00901544094,2.51480841637 -6.34704017639,1.01401948929,2.54440665245 -6.35805368423,1.01802551746,2.5709900856 -6.36506748199,1.02003228664,2.59656429291 -6.3890709877,1.02503180504,2.61637663841 -6.38608598709,1.02604031563,2.63795351982 -6.38410186768,1.02704882622,2.66052031517 -6.4111123085,1.03405177593,2.69312620163 -6.4531211853,1.0430521965,2.73272418976 -6.3911447525,1.03307151794,2.73127102852 -6.40015792847,1.03607797623,2.75785470009 -6.40716409683,1.03808045387,2.77165770531 -6.40017986298,1.03808987141,2.79222798347 -6.58516931534,1.07406449318,2.89188838005 -6.47819900513,1.05609202385,2.87141561508 -6.45521736145,1.05310416222,2.8849902153 -6.43623495102,1.05111575127,2.90055942535 -6.58522748947,1.08009660244,2.98721575737 -6.54824018478,1.0741071701,2.98299574852 -6.40127706528,1.0491424799,2.94448971748 -6.42028903961,1.05414712429,2.97608232498 -6.39630746841,1.05115950108,2.98866081238 -6.40032148361,1.05316698551,3.01423931122 -6.45832824707,1.06616449356,3.06384706497 -6.46933412552,1.06916642189,3.08064460754 -6.39236068726,1.056188941,3.07018351555 -6.54835224152,1.08716821671,3.16484212875 -6.64035367966,1.10615956783,3.23245120049 -6.43739938736,1.07020545006,3.16294288635 -6.38942146301,1.06222248077,3.16450500488 -6.39743566513,1.066229105,3.1920940876 -6.3894443512,1.06523501873,3.20087265968 -6.42745399475,1.07423615456,3.24346637726 -6.38247585297,1.06725287437,3.24603033066 -6.39348936081,1.07125902176,3.27561736107 -6.38950538635,1.0722681284,3.29819464684 -6.44451189041,1.08526611328,3.3498005867 -6.38452959061,1.0742815733,3.33256292343 -6.36954689026,1.07329285145,3.35012936592 -6.36456346512,1.07430195808,3.37171673775 -6.35957956314,1.07531154156,3.39428830147 -6.48857402802,1.10229551792,3.48492622375 -6.40460300446,1.08831965923,3.46647906303 -6.35062789917,1.07933831215,3.46402812004 -6.34663629532,1.08034348488,3.47481012344 -6.35065078735,1.08235096931,3.50140070915 -6.3536658287,1.08535885811,3.52798438072 -6.34168291092,1.08536958694,3.54656338692 -6.33969926834,1.08637845516,3.57113623619 -6.30972003937,1.08339297771,3.58069610596 -6.37472486496,1.09738898277,3.64130616188 -6.32974004745,1.09040176868,3.62908411026 -6.33575439453,1.09340906143,3.65767073631 -6.32677173615,1.09341931343,3.6782476902 -6.31379032135,1.09343039989,3.69682002068 -6.31280612946,1.09543931484,3.72239303589 -6.38680887222,1.11243355274,3.79000782967 -6.32983446121,1.10345315933,3.78356480598 -6.36783599854,1.1114500761,3.81837153435 -6.33585786819,1.10746502876,3.82692575455 -6.38286447525,1.1184643507,3.87954139709 -6.38488006592,1.12147259712,3.90712451935 -6.39089536667,1.12548017502,3.93770122528 -6.31992387772,1.11350250244,3.92225146294 -6.30593442917,1.11250948906,3.92703795433 -6.3379445076,1.12051188946,3.97263455391 -6.30196714401,1.11552774906,3.97819137573 -6.32897758484,1.12353110313,4.02079248428 -6.36998653412,1.13453197479,4.07338285446 -6.30201530457,1.12355399132,4.0589299202 -6.29203367233,1.12356460094,4.07950973511 -6.35902929306,1.13855600357,4.13532161713 -6.33204984665,1.13556969166,4.14490509033 -6.38205623627,1.14756882191,4.20449876785 -6.30308771133,1.13459324837,4.18204402924 -6.28210735321,1.13260579109,4.19562339783 -6.47008800507,1.17357766628,4.34428787231 -6.51109600067,1.18457865715,4.3998799324 -6.35213470459,1.1536141634,4.31060218811 -6.32115697861,1.14962911606,4.31817293167 -6.41615486145,1.17161941528,4.40978431702 -6.32918787003,1.156645298,4.38033151627 -6.29821062088,1.15366017818,4.38790035248 -6.28922843933,1.15467095375,4.41047382355 -6.27124786377,1.15368318558,4.42605686188 -6.28525400162,1.15768504143,4.45083856583 -6.28027105331,1.15969491005,4.47542667389 -6.29028558731,1.16470205784,4.51199817657 -6.28130435944,1.1657127142,4.53457641602 -7.60505533218,1.44045972824,5.49068975449 -6.27433824539,1.1697319746,4.58773612976 -6.28234481812,1.1727347374,4.60753631592 -6.27636194229,1.17474472523,4.63212203979 -6.27637863159,1.1777536869,4.66170072556 -6.45435905457,1.21772742271,4.82034492493 -6.38538980484,1.20575022697,4.80089664459 -6.36041164398,1.20376420021,4.81346082687 -6.28043603897,1.18878448009,4.76922893524 -6.31044626236,1.19778764248,4.82181692123 -6.28146886826,1.19480240345,4.83038949966 -6.24449300766,1.19081878662,4.8329577446 -6.25950717926,1.19682478905,4.87454509735 -6.28051948547,1.20482969284,4.92113304138 -6.28953409195,1.20983684063,4.9587187767 -6.33753252029,1.22183191776,5.01152038574 -6.30055713654,1.21684837341,5.01409053802 -6.26658058167,1.21286427975,5.0186624527 -6.29359197617,1.22186791897,5.07125043869 -6.27261352539,1.2208814621,5.08681726456 -6.27263021469,1.22389054298,5.11839866638 -6.26364803314,1.22590124607,5.14198923111 -6.31064653397,1.23789644241,5.19579362869 -6.3426566124,1.2478992939,5.25437879562 -6.25569200516,1.23292577267,5.21593427658 -6.28570270538,1.24292886257,5.2725276947 -6.31171369553,1.25193309784,5.32710981369 -6.28173780441,1.24894845486,5.33567428589 -6.24776172638,1.24496412277,5.33925676346 -6.25176906586,1.24796795845,5.35904836655 -6.36076211929,1.27495527267,5.48366689682 -6.41476726532,1.29095351696,5.56326436996 -6.29681015015,1.26898646355,5.49680805206 -6.27483224869,1.2680003643,5.51237392426 -6.26085281372,1.26801264286,5.5349407196 -6.32584667206,1.28400409222,5.60775756836 -6.31786489487,1.28601467609,5.63434648514 -6.36587142944,1.30101418495,5.71094369888 -6.2919049263,1.28803873062,5.6814904213 -7.15772771835,1.48687243462,6.48139095306 -6.68085193634,1.38397848606,6.09779071808 -7.09977436066,1.48290288448,6.51051855087 -6.55290603638,1.36201822758,6.03812551498 -6.46794223785,1.34704482555,5.99867105484 -6.50994968414,1.36004555225,6.07327032089 -6.53196191788,1.3700504303,6.13085603714 -6.51898193359,1.37106251717,6.15643167496 -6.50100326538,1.37107563019,6.17799949646 -6.4560303688,1.36509406567,6.17356729507 -6.4230465889,1.36010539532,6.16134786606 -6.41306638718,1.36211705208,6.18992137909 -6.38808917999,1.36113131046,6.20349979401 -6.30512571335,1.34615755081,6.16205358505 -6.29614543915,1.34816896915,6.19162511826 -6.29116344452,1.35117936134,6.22420930862 -6.32516431808,1.36217713356,6.27601289749 -6.26319646835,1.35219931602,6.25456476212 -6.21822452545,1.34621810913,6.24912500381 -6.20724534988,1.3482298851,6.27669906616 -6.20526266098,1.35223960876,6.31228780746 -6.26326608658,1.37023723125,6.40888834 -6.3702583313,1.4012247324,6.55550909042 -6.28628730774,1.38324677944,6.49126529694 -6.31229782104,1.39425098896,6.55686044693 -6.2563290596,1.38527190685,6.53942584991 -6.24934864044,1.38928294182,6.57299661636 -6.2603635788,1.39629018307,6.62458181381 -6.25138282776,1.39930152893,6.65516662598 -6.24140310287,1.40231323242,6.6857419014 -6.25040960312,1.40631604195,6.71553659439 -6.23743057251,1.40832853317,6.74410247803 -6.23544883728,1.41333842278,6.78268957138 -6.2174706459,1.41435170174,6.80526256561 -6.2044916153,1.41636395454,6.83284187317 -6.1855134964,1.41637742519,6.85441541672 -6.17752504349,1.41738402843,6.86719894409 -6.16154670715,1.41839694977,6.89177656174 -6.15156602859,1.42140841484,6.92236280441 -6.13058996201,1.42142260075,6.94292545319 -6.1096124649,1.42143642902,6.96150827408 -6.09063482285,1.42245006561,6.98308420181 -6.08565425873,1.42646086216,7.02165365219 -6.06766700745,1.42446911335,7.02145290375 -6.05368852615,1.42648172379,7.04902887344 -6.04270982742,1.42949402332,7.08159208298 -6.02273225784,1.42950761318,7.10117912292 -6.00975322723,1.43251991272,7.12975978851 -5.99477529526,1.43453288078,7.15732955933 -5.97578954697,1.43254184723,7.15810585022 -5.9668097496,1.43555343151,7.19168806076 -5.94783258438,1.43656718731,7.21426010132 -5.91785764694,1.43458294868,7.22283792496 -5.90387916565,1.43659555912,7.25042152405 -5.89090108871,1.43960809708,7.28099060059 -5.86192703247,1.43762397766,7.2915596962 -5.85493707657,1.43862998486,7.30436182022 -5.84795761108,1.44264149666,7.34292936325 -3.45559120178,0.807147264481,4.42166805267 -3.4396147728,0.806160509586,4.42924499512 -3.43563508987,0.809171199799,4.45182657242 -3.41765904427,0.807184696198,4.45640993118 -5.73408699036,1.4467189312,7.45559883118 -3.41068053246,0.809196233749,4.47598171234 -5.71011161804,1.44573378563,7.47217226028 -5.69413375854,1.4477468729,7.49875164032 -5.68115568161,1.45075953007,7.5303235054 -5.65418100357,1.44977498055,7.5428981781 -5.63320541382,1.45078921318,7.56347370148 -5.61922740936,1.45380198956,7.59305381775 -5.60923862457,1.45380890369,7.60384368896 -5.58626365662,1.45382368565,7.62241411209 -5.56928682327,1.45583724976,7.64898777008 -5.55131006241,1.45785069466,7.67356729507 -5.52133607864,1.45586669445,7.68114900589 -5.50935792923,1.45987939835,7.715716362 -5.49737071991,1.45988690853,7.72450065613 -5.47639417648,1.45990097523,7.74408864975 -5.45541858673,1.46091532707,7.76566076279 -5.42944431305,1.46093046665,7.77923965454 -5.41146802902,1.46294438839,7.80580711365 -5.39049243927,1.46395885944,7.8273806572 -5.36451721191,1.46297383308,7.83996772766 -5.35852861404,1.46498024464,7.85775184631 -5.3395524025,1.46699428558,7.88232660294 -5.31057929993,1.46501040459,7.89289474487 -5.29360198975,1.46702361107,7.91848659515 -5.27262687683,1.46903812885,7.94105482101 -5.24865198135,1.4690529108,7.95763540268 -5.24066352844,1.47005963326,7.97242259979 -5.21468925476,1.47007501125,7.98600292206 -5.19371414185,1.4710893631,8.0085735321 -5.1747379303,1.47310328484,8.03315353394 -5.14776420593,1.47211909294,8.04672145844 -5.12878847122,1.47413301468,8.07130336761 -5.10681343079,1.47514760494,8.09187984467 -5.09382677078,1.47515547276,8.09966278076 -5.07085180283,1.47617018223,8.11824321747 -5.05187606812,1.47818410397,8.14381980896 -5.02790164948,1.47819912434,8.16139602661 -5.00192785263,1.47821462154,8.17597007751 -4.98095273972,1.4792290926,8.19854640961 -4.95897769928,1.48024356365,8.21813392639 -4.94898986816,1.48125076294,8.2309179306 -4.92501544952,1.48226594925,8.24948883057 -4.90104103088,1.48228085041,8.26607513428 -4.8780670166,1.4832957983,8.28664398193 -4.85809135437,1.48531007767,8.31122207642 -4.83611726761,1.48732483387,8.33279895782 -4.81214284897,1.48733997345,8.35137176514 -4.80315494537,1.48934674263,8.36516475677 -4.78018045425,1.49036169052,8.38474369049 -4.75720643997,1.4913765192,8.40531730652 -4.73623180389,1.49339127541,8.42988872528 -4.71425676346,1.49440562725,8.45047473907 -4.69428157806,1.49642002583,8.47704696655 -4.68129491806,1.49642789364,8.48483371735 -4.66031980515,1.498442173,8.50742053986 -4.63534641266,1.49945759773,8.52499389648 -4.61137294769,1.50047290325,8.54456615448 -4.59039831161,1.50248730183,8.56914329529 -4.56542491913,1.50250256062,8.58572483063 -4.54245042801,1.50451755524,8.60729789734 -4.53346300125,1.50552463531,8.62308311462 -4.50549030304,1.50554025173,8.63267326355 -4.48151636124,1.50655543804,8.65224933624 -4.45554351807,1.50657117367,8.66881847382 -4.43156909943,1.50758624077,8.68740177155 -4.40859603882,1.50960123539,8.70997333527 -4.38462162018,1.51061630249,8.72855758667 -4.32664775848,1.49363327026,8.64733695984 -4.28268003464,1.48765254021,8.62690830231 -3.7488515377,1.29677248001,7.6253490448 -3.70388436317,1.28879213333,7.5949139595 -3.65991711617,1.28081142902,7.56548166275 -3.62994503975,1.2778275013,7.56206703186 -3.60096311569,1.27183866501,7.53185367584 -3.56499385834,1.26685655117,7.5184173584 -3.53202319145,1.26387345791,7.50899410248 -3.50005221367,1.2598900795,7.50157022476 -3.46708154678,1.25590705872,7.49115037918 -3.43511080742,1.25292396545,7.48372220993 -3.40414023399,1.24994063377,7.47829341888 -3.38915371895,1.24794840813,7.47409582138 -3.36418104172,1.24796378613,7.48067378998 -3.3362095356,1.24598002434,7.48224020004 -3.3062376976,1.24299609661,7.47582817078 -3.28126525879,1.24201142788,7.48240375519 -3.25729250908,1.24202680588,7.49197483063 -3.23032021523,1.24104249477,7.49255943298 -3.21133589745,1.2380515337,7.48134231567 -3.19136166573,1.23906576633,7.49792718887 -3.16938853264,1.24008047581,7.51150226593 -3.15041446686,1.24209463596,7.53207874298 -3.10544753075,1.23211419582,7.49065113068 -3.04548478127,1.21613633633,7.41023302078 -3.02650094032,1.21314573288,7.39900779724 -2.99852895737,1.21116137505,7.39459562302 -2.97255659103,1.20917677879,7.39617586136 -2.94158649445,1.20619368553,7.38773918152 -2.91661381721,1.20520889759,7.39032745361 -2.89264130592,1.20522415638,7.39789915085 -2.85667204857,1.19924163818,7.37347698212 -2.84468531609,1.19824910164,7.3752746582 -2.80571746826,1.19126737118,7.34384250641 -2.79474067688,1.19627952576,7.3814368248 -2.79776000977,1.20928907394,7.45802402496 -2.76279091835,1.20330667496,7.43659353256 -2.74381685257,1.20532083511,7.45617437363 -2.70984697342,1.2003377676,7.43475532532 -2.69586157799,1.19934594631,7.43353796005 -2.67388796806,1.19936037064,7.44312810898 -2.64691662788,1.19837629795,7.44170188904 -2.62294387817,1.19739127159,7.44728279114 -2.6049695015,1.20040500164,7.46887016296 -2.57299947739,1.19542181492,7.45244550705 -2.54902768135,1.19543719292,7.46001434326 -2.54004025459,1.1974439621,7.47080898285 -2.51406812668,1.19545936584,7.46939516068 -2.49109530449,1.19547426701,7.47797489166 -2.47112202644,1.19748866558,7.49655056 -2.44515013695,1.19650399685,7.49513530731 -2.42117834091,1.19651925564,7.50270462036 -2.41618919373,1.19952511787,7.52450942993 -2.4042134285,1.20553779602,7.56709480286 -2.37924146652,1.20555317402,7.57067155838 -2.36826515198,1.21256542206,7.61725854874 -2.34229326248,1.21058094501,7.61684083939 -2.32431960106,1.21459496021,7.64441394806 -2.31134343147,1.22060751915,7.68500709534 -2.3073554039,1.22561371326,7.71679019928 -2.2863817215,1.22662782669,7.73138427734 -2.27540612221,1.23564052582,7.78495740891 -2.26742887497,1.24465227127,7.8465461731 -2.26644945145,1.25866258144,7.93313884735 -2.24647641182,1.26267707348,7.95871210098 -2.2484858036,1.27068150043,8.01151180267 -2.25150489807,1.28769111633,8.116106987 -2.25352501869,1.30570089817,8.22169303894 -2.24254894257,1.31471335888,8.28227615356 -2.23557114601,1.32672476768,8.3568687439 -2.22259616852,1.33573782444,8.41444587708 -2.2256155014,1.35474729538,8.53004074097 -2.22562599182,1.36375248432,8.58483123779 -2.20669317245,1.40578687191,8.84659481049 -2.19671702385,1.41879928112,8.92617225647 -2.19073915482,1.43381047249,9.01876831055 -2.17776370049,1.44482326508,9.08835124969 -2.20476603508,1.47482323647,9.26414585114 -2.394749403,1.65680599213,10.3313694 -2.3687775135,1.66182124615,10.3629608154 -2.33480834961,1.66083824635,10.3645372391 -2.30583810806,1.66385436058,10.3881149292 -2.27286863327,1.66287112236,10.3916978836 -2.25688362122,1.66287946701,10.3964881897 -2.22791266441,1.66589522362,10.4170761108 -2.19394421577,1.66491234303,10.4196510315 -2.16297388077,1.66592860222,10.4332342148 -2.13100409508,1.66694509983,10.4418172836 -2.10203409195,1.66996121407,10.4693918228 -2.09204721451,1.67496812344,10.5011911392 -2.06007766724,1.67598474026,10.5137672424 -2.03410601616,1.6819999218,10.5523576736 -2.01213335991,1.6920144558,10.615940094 -1.99515962601,1.70702815056,10.711517334 -1.96918773651,1.71404337883,10.754108429 -1.93621897697,1.71506011486,10.7676820755 -1.92123377323,1.71706819534,10.7794761658 -1.88726496696,1.71608507633,10.7840566635 -1.85129654408,1.71410226822,10.7756404877 -1.8093303442,1.70612084866,10.7362136841 -1.77136278152,1.70213830471,10.7157945633 -1.73639369011,1.70015513897,10.7073850632 -1.72040951252,1.70116364956,10.7201662064 -1.68644058704,1.70118045807,10.7227468491 -1.65247166157,1.70019710064,10.7233324051 -1.61750292778,1.69821405411,10.716917038 -1.58353424072,1.69823074341,10.7194986343 -1.55056512356,1.69924736023,10.7280807495 -1.51559686661,1.69826447964,10.7266569138 -1.49561357498,1.69427347183,10.7074451447 -1.46564304829,1.69728910923,10.7310390472 -1.43167471886,1.69830608368,10.7386112213 -1.39670610428,1.69632291794,10.7311954498 -1.36173772812,1.69433987141,10.7247781754 -1.32576978207,1.69135701656,10.7113571167 -1.29280042648,1.69237327576,10.7169446945 -1.27481675148,1.6913819313,10.712729454 -1.24084770679,1.69039845467,10.7103157043 -1.20787894726,1.69141507149,10.7218942642 -1.17191040516,1.68643188477,10.6974849701 -1.13894188404,1.68844854832,10.7130594254 -1.10497283936,1.68746483326,10.7066488266 -1.0710041523,1.68648147583,10.7052335739 -1.05501937866,1.68748950958,10.7130260468 -1.02005112171,1.68550634384,10.7016096115 -0.98508310318,1.68352329731,10.6961841583 -0.953113436699,1.68553924561,10.7087755203 -0.919144928455,1.6855558157,10.709356308 -0.885176181793,1.68457221985,10.7059402466 -0.868192195892,1.68458068371,10.7107257843 -0.835222899914,1.68459677696,10.7133169174 -0.800254940987,1.68361365795,10.7058916092 -0.768285691738,1.68662977219,10.7294769287 -0.735316872597,1.68864607811,10.7430582047 -0.700348436832,1.68566262722,10.7236433029 -0.667379498482,1.68667888641,10.7352275848 -0.650395214558,1.68668711185,10.7320203781 -0.614427149296,1.67970371246,10.6926059723 -0.580458641052,1.67872035503,10.6911859512 -0.548489153385,1.68173611164,10.7107782364 -0.514520525932,1.68075251579,10.7063598633 -0.480551987886,1.67976880074,10.6989440918 -0.463567644358,1.67877697945,10.69373703 -0.429599583149,1.68079352379,10.7043113708 -0.396630436182,1.68080949783,10.709900856 -0.362661808729,1.67882585526,10.6984863281 -0.328693568707,1.67984223366,10.7030639648 -0.295724272728,1.67985808849,10.7016563416 -0.261755883694,1.67887449265,10.6982364655 -0.244771614671,1.67788255215,10.691028595 -0.211802408099,1.67789840698,10.6946201324 -0.17783395946,1.6759147644,10.6812019348 -0.143865704536,1.67693114281,10.6847801208 -0.110896483064,1.67694699764,10.6853723526 -0.0769281610847,1.67596316338,10.6789531708 -0.0429598800838,1.67497944832,10.6765317917 -0.0269748177379,1.67598712444,10.6823339462 --0.0,1.6779999733,10.1619997025 --0.0319690704346,1.67201590538,10.125582695 --0.063938125968,1.67103159428,10.1211643219 --0.0959072858095,1.67404735088,10.1367492676 --0.127876341343,1.67306303978,10.1303319931 --0.143860891461,1.67407095432,10.1331243515 --0.175830021501,1.67408668995,10.1347084045 --0.206800058484,1.67410194874,10.1313037872 --0.23776961863,1.66811728477,10.0988912582 --0.270737946033,1.67113339901,10.1134643555 --0.301707953215,1.67114853859,10.1120615005 --0.333677113056,1.67216420174,10.1146459579 --0.350660949945,1.67417240143,10.1254291534 --0.380630910397,1.6661875248,10.0810184479 --0.411600768566,1.66520261765,10.0756111145 --0.443569868803,1.66621828079,10.0771942139 --0.475538998842,1.66723382473,10.0797786713 --0.506508708,1.66524899006,10.0693683624 --0.523492753506,1.66825711727,10.0841560364 --0.554462611675,1.66727232933,10.0787496567 --0.586431503296,1.66728794575,10.0723276138 --0.618400990963,1.66930317879,10.0819196701 --0.6493704319,1.66731846333,10.0675048828 --0.681339740753,1.66833376884,10.0710916519 --0.713308811188,1.66834914684,10.0706758499 --0.729293227196,1.66835701466,10.0664644241 --0.762262701988,1.67337226868,10.0920610428 --0.7942314744,1.67238795757,10.0826377869 --0.825201153755,1.67140293121,10.0742273331 --0.856171071529,1.67041790485,10.0688199997 --0.888140201569,1.67143321037,10.0674057007 --0.919109940529,1.66944825649,10.0589942932 --0.937093496323,1.67245650291,10.0727777481 --0.969062924385,1.67347157001,10.0753688812 --1.00103199482,1.6734868288,10.0719509125 --1.03400111198,1.67650222778,10.0835418701 --1.06597030163,1.67651748657,10.080124855 --1.09794008732,1.67853236198,10.0857219696 --1.1149238348,1.67854034901,10.0855035782 --1.14889264107,1.68255579472,10.1030931473 --1.17886281013,1.680570364,10.087685585 --1.2118319273,1.68258571625,10.0932722092 --1.24580049515,1.68560099602,10.1068592072 --1.27777016163,1.68661606312,10.1064510345 --1.31073915958,1.68763124943,10.111038208 --1.32772350311,1.68963897228,10.1168308258 --1.36069250107,1.69065415859,10.1204175949 --1.39466118813,1.69366943836,10.1290016174 --1.42862951756,1.69568502903,10.1355829239 --1.45959949493,1.69469952583,10.1271762848 --1.49056959152,1.69471418858,10.11977005 --1.52653765678,1.69872975349,10.1403551102 --1.54052305222,1.69673681259,10.1261510849 --1.57549154758,1.7007522583,10.1397371292 --1.61045980453,1.70376753807,10.1523227692 --1.64342904091,1.70478260517,10.1539125443 --1.67539834976,1.70479750633,10.1464958191 --1.70936739445,1.70681238174,10.1550884247 --1.74233675003,1.70882725716,10.1566801071 --1.76232028008,1.71283531189,10.1764736176 --1.79528915882,1.71285033226,10.1730556488 --1.82725858688,1.712864995,10.1666431427 --1.8622276783,1.71687996387,10.1802406311 --1.89619624615,1.71789515018,10.1808204651 --1.93116486073,1.72091031075,10.190410614 --1.94614994526,1.71991741657,10.1812047958 --1.98211836815,1.72393262386,10.1957950592 --2.01508784294,1.72494721413,10.1953878403 --2.05105614662,1.7279624939,10.2059726715 --2.08102631569,1.72597658634,10.1895637512 --2.11599493027,1.72799170017,10.1951494217 --2.14896440506,1.72900629044,10.1927404404 --2.167948246,1.73201394081,10.2025327682 --2.20091795921,1.73302841187,10.2011270523 --2.23288726807,1.73204290867,10.1917133331 --2.26685643196,1.73405766487,10.1933040619 --2.30282473564,1.73707270622,10.2008867264 --2.33579421043,1.73808717728,10.1974782944 --2.36876392365,1.73910152912,10.1950731277 --2.38674759865,1.74010908604,10.1968603134 --2.41771793365,1.73912322521,10.1854534149 --2.45568561554,1.74313855171,10.2000379562 --2.48965525627,1.74515283108,10.2016334534 --2.51862597466,1.74316644669,10.1822280884 --2.55659413338,1.74718177319,10.1968164444 --2.57257914543,1.74718880653,10.192612648 --2.60554814339,1.74720323086,10.1851959229 --2.64251661301,1.75121808052,10.1957864761 --2.67748570442,1.7532324791,10.1983785629 --2.71045541763,1.75424671173,10.1939716339 --2.74842309952,1.75726187229,10.2035522461 --2.78039312363,1.75727581978,10.1941432953 --2.79437875748,1.75628232956,10.1839447021 --2.83534646034,1.76229763031,10.2075386047 --2.86531686783,1.76131129265,10.1901273727 --2.89828634262,1.76132535934,10.1827144623 --2.93825387955,1.76634061337,10.1993017197 --2.97022414207,1.76635444164,10.1898946762 --3.00519299507,1.76836872101,10.1894845963 --3.02717614174,1.7713766098,10.2032756805 --3.06014633179,1.7723903656,10.1988763809 --3.0951154232,1.77440464497,10.1964607239 --3.13208413124,1.77741909027,10.2030553818 --3.16605329514,1.77743327618,10.1966400146 --3.20102262497,1.77944731712,10.195230484 --3.22400617599,1.78445506096,10.2150382996 --3.254976511,1.78346848488,10.2006292343 --3.29194569588,1.78648281097,10.2052221298 --3.32591462135,1.78649687767,10.1978054047 --3.36588287354,1.79151153564,10.2113990784 --3.39585375786,1.79052472115,10.1939916611 --3.4358215332,1.7945394516,10.2055807114 --3.44980740547,1.79354584217,10.1943798065 --3.48577666283,1.79555988312,10.1939697266 --3.52574419975,1.79957461357,10.2035541534 --3.55871462822,1.80058813095,10.1951503754 --3.59368419647,1.80260169506,10.1927471161 --3.63065290451,1.80461597443,10.1923303604 --3.66562247276,1.80562961102,10.1899271011 --3.68460702896,1.80763673782,10.1917228699 --3.72057628632,1.80965042114,10.1903152466 --3.76054477692,1.81366479397,10.2009134293 --3.79051566124,1.81267762184,10.1825046539 --3.82448577881,1.81369125843,10.1740922928 --3.86445379257,1.81770551205,10.1816825867 --3.88343811035,1.81871259212,10.1824760437 --3.91540884972,1.81872558594,10.1700716019 --3.95537734032,1.82273972034,10.1776638031 --3.98834753036,1.82275295258,10.1662530899 --4.02231788635,1.82376623154,10.1588497162 --4.05828714371,1.82577967644,10.1564464569 --4.09225749969,1.8267929554,10.1470336914 --4.11124229431,1.82879960537,10.1498394012 --4.14921140671,1.83181345463,10.1504306793 --4.18018245697,1.83082604408,10.134021759 --4.21415233612,1.83183932304,10.1236076355 --4.25512075424,1.83585333824,10.1322040558 --4.28409290314,1.83486545086,10.1128034592 --4.32006216049,1.83587884903,10.1073923111 --4.34504508972,1.83988666534,10.1201839447 --4.37701654434,1.84089910984,10.1077842712 --4.41198682785,1.84191203117,10.1013813019 --4.44495725632,1.84192490578,10.0889720917 --4.4789276123,1.84293758869,10.0795660019 --4.51689720154,1.84595108032,10.0781574249 --4.53488206863,1.84695756435,10.0759563446 --4.56885242462,1.84797036648,10.0645427704 --4.60382318497,1.84898304939,10.0591478348 --4.63879299164,1.84999620914,10.0487298965 --4.67376375198,1.85200881958,10.0413265228 --4.71673202515,1.85702264309,10.0509252548 --4.76569843292,1.86403727531,10.0715169907 --4.78468322754,1.86504387856,10.0703144073 --4.82265281677,1.86705684662,10.0679101944 --4.84862565994,1.86506831646,10.0394992828 --4.87359952927,1.86307930946,10.0121040344 --4.88757658005,1.85608911514,9.96069908142 --4.90255260468,1.84909904003,9.91129016876 --4.90653181076,1.83810734749,9.84088420868 --4.90452241898,1.83111107349,9.79767894745 --4.9384932518,1.83212351799,9.78727054596 --4.97046470642,1.83313548565,9.77286148071 --5.00643587112,1.83514797688,9.76746082306 --5.04040670395,1.83616018295,9.75805854797 --5.07237863541,1.83617210388,9.74365139008 --5.09636116028,1.84017932415,9.75044155121 --5.12833356857,1.84019100666,9.73804569244 --5.16530370712,1.8422036171,9.73163318634 --5.19627666473,1.84321498871,9.71723747253 --5.23224639893,1.84422755241,9.70882511139 --5.25921964645,1.84323859215,9.68441486359 --5.29519081116,1.84525084496,9.67801475525 --5.31517553329,1.84725725651,9.67781162262 --5.34514760971,1.84726858139,9.65940570831 --5.37811946869,1.84828019142,9.64700317383 --5.41009187698,1.84829163551,9.63360595703 --5.43706512451,1.84730279446,9.60919570923 --5.47103691101,1.84831440449,9.59879684448 --5.50700807571,1.85032641888,9.59139442444 --5.52699279785,1.85233271122,9.58918190002 --5.55796527863,1.8523440361,9.57277870178 --5.59393644333,1.85435581207,9.56537914276 --5.62091016769,1.85336637497,9.54197502136 --5.65788030624,1.85537862778,9.53356075287 --5.68285512924,1.85438895226,9.50715827942 --5.70483970642,1.8563952446,9.50995922089 --5.73281288147,1.8554059267,9.48855686188 --5.76978397369,1.8584177494,9.48115062714 --5.79675769806,1.8574283123,9.45774745941 --5.8347287178,1.85944008827,9.45234489441 --5.86670160294,1.86045122147,9.43694019318 --5.90167331696,1.8624625206,9.42653846741 --5.91565990448,1.86246776581,9.41533470154 --5.94963169098,1.863478899,9.40293121338 --5.97660636902,1.86248922348,9.38053417206 --6.01757621765,1.86650121212,9.37812519073 --6.04455041885,1.8655115366,9.35472202301 --6.08052206039,1.86752271652,9.3453207016 --6.1074962616,1.866533041,9.3209104538 --6.12148332596,1.86653792858,9.31171989441 --6.1504573822,1.866548419,9.29030990601 --6.18942832947,1.86955988407,9.284907341 --6.21040391922,1.86656939983,9.251496315 --6.23237991333,1.86457872391,9.22210121155 --6.26735162735,1.86658966541,9.21069908142 --6.28733778,1.86759543419,9.2084980011 --6.31131267548,1.86660504341,9.18008899689 --6.34328603745,1.86761546135,9.1646900177 --6.36626195908,1.86562490463,9.13629055023 --6.40323352814,1.86763584614,9.12688541412 --6.43920564651,1.87064671516,9.11547660828 --6.46418046951,1.86965620518,9.09007835388 --6.47916793823,1.86966133118,9.07987213135 --6.52413749695,1.8736730814,9.08146858215 --6.54311466217,1.87168169022,9.04807186127 --6.57208871841,1.87169158459,9.02666282654 --6.60906076431,1.87370228767,9.01726341248 --6.63503599167,1.87271165848,8.99286174774 --6.65401315689,1.87072038651,8.95845603943 --6.68699550629,1.87572717667,8.97325801849 --6.70497274399,1.87273573875,8.93785381317 --6.73994588852,1.874745965,8.92545413971 --6.77191925049,1.87575590611,8.90804672241 --6.79689502716,1.87476503849,8.88164043427 --6.82786989212,1.87577462196,8.86525058746 --6.86584234238,1.87878513336,8.8558473587 --6.86683273315,1.87478840351,8.82764148712 --6.88980865479,1.87379729748,8.79923915863 --6.92878103256,1.87680768967,8.79083442688 --6.94575881958,1.87381601334,8.75442695618 --6.9747338295,1.87382519245,8.73402786255 --7.01570558548,1.87783563137,8.72862911224 --7.02069568634,1.87483930588,8.70642757416 --7.0516705513,1.87684857845,8.68903255463 --7.08564376831,1.87785828114,8.67362594604 --7.10962057114,1.87686693668,8.64622020721 --7.11959981918,1.87187421322,8.60181236267 --7.07359409332,1.85187602043,8.49140644073 --7.18954801559,1.87689328194,8.57602119446 --5.40698671341,1.37972450256,6.41758584976 --5.36997747421,1.36372792721,6.33217668533 --5.3459649086,1.35173296928,6.26175689697 --5.35592603683,1.34374809265,6.19294786453 --5.35590791702,1.33875501156,6.15354776382 --5.39287996292,1.34276592731,6.15513324738 --5.39986944199,1.34276998043,6.14393758774 --5.25888538361,1.29876410961,5.94250297546 --5.32984972,1.31277763844,5.98511075974 --5.29983997345,1.29978191853,5.91371059418 --5.31381750107,1.29879033566,5.89029550552 --5.31179952621,1.29279720783,5.84988594055 --5.31378173828,1.28880441189,5.81549072266 --5.29977560043,1.28280675411,5.78027391434 --5.29775762558,1.27781367302,5.74086713791 --5.30073833466,1.27282118797,5.70645236969 --5.27672672272,1.26282584667,5.64505672455 --5.28170728683,1.25883352757,5.61364507675 --5.29368638992,1.25784134865,5.59124994278 --5.28367948532,1.25284409523,5.56203842163 --5.29765748978,1.25185239315,5.54062843323 --5.30863666534,1.24986040592,5.5162191391 --5.3156170845,1.24686801434,5.48781013489 --5.32859611511,1.24587619305,5.46640968323 --5.34357404709,1.24488425255,5.44700813293 --5.34755516052,1.24189162254,5.41559553146 --5.32655191422,1.23489332199,5.37739753723 --5.3435292244,1.23490166664,5.35999202728 --5.34950971603,1.23190903664,5.33158588409 --5.34049415588,1.22491526604,5.28817653656 --5.33947658539,1.22092223167,5.25276470184 --5.3544549942,1.21993029118,5.23436641693 --5.34144020081,1.21293616295,5.18795824051 --5.355427742,1.21394062042,5.18475484848 --5.38240337372,1.21694982052,5.17734766006 --5.40837907791,1.21895873547,5.16894102097 --5.42335796356,1.21896660328,5.15054273605 --5.43733644485,1.21797466278,5.13013029099 --5.43232059479,1.21298110485,5.09272813797 --5.46029567719,1.21599018574,5.08531284332 --5.4712843895,1.21599447727,5.07910966873 --5.49126243591,1.21700251102,5.06571435928 --5.5132393837,1.21901094913,5.05330944061 --5.53521633148,1.22001934052,5.04090499878 --5.55319452286,1.22102749348,5.02449703217 --5.58217048645,1.22403621674,5.01809072495 --5.60614681244,1.22604489326,5.00667953491 --5.62213563919,1.22804892063,5.00649881363 --5.65211057663,1.23105788231,5.00008630753 --5.67308807373,1.23206591606,4.98668718338 --5.70306396484,1.23507463932,4.9802775383 --5.73803853989,1.24008357525,4.97887849808 --5.76601457596,1.2430921793,4.97046947479 --5.78100347519,1.24409639835,4.9682803154 --5.80398035049,1.24610435963,4.95587778091 --5.83495616913,1.25011301041,4.94946622849 --5.86893129349,1.2541217804,4.94606351852 --5.90490627289,1.25813043118,4.94466686249 --5.93188333511,1.26113855839,4.93526649475 --5.9708571434,1.26614761353,4.93485641479 --5.99184417725,1.27015197277,4.93666219711 --6.03881645203,1.27716135979,4.94326305389 --6.07279205322,1.28116977215,4.93886232376 --6.10476827621,1.28517794609,4.93245887756 --6.13774394989,1.28818619251,4.9270606041 --6.18371725082,1.29519534111,4.93166017532 --6.2146935463,1.29920327663,4.92426204681 --6.23867988586,1.30220782757,4.92706155777 --6.27365589142,1.30721592903,4.92266511917 --6.31163024902,1.31222438812,4.91925477982 --6.34460735321,1.31623220444,4.91285848618 --6.37858295441,1.32024025917,4.90645456314 --6.41655778885,1.32524847984,4.90305233002 --6.45653343201,1.3302564621,4.90165948868 --6.4695224762,1.33126008511,4.89546108246 --6.51049661636,1.33726847172,4.89305019379 --6.54947280884,1.34227621555,4.89066171646 --6.58344888687,1.34628403187,4.88325881958 --6.62842321396,1.35329222679,4.88385820389 --5.52261829376,1.10224533081,3.99983763695 --5.53360700607,1.10324907303,3.99464154243 --5.3976187706,1.07024824619,3.8682179451 --6.79831552505,1.37532639503,4.86106967926 --6.82529306412,1.37733340263,4.84665870667 --6.88726425171,1.38734197617,4.85826730728 --6.90924406052,1.38934862614,4.84086704254 --6.94722032547,1.39435589314,4.83446645737 --6.99220323563,1.40236079693,4.84926843643 --7.02018165588,1.4043674469,4.83587169647 --7.06315755844,1.41037476063,4.83247423172 --7.11613130569,1.41838240623,4.83608293533 --7.14410972595,1.42138898373,4.82168102264 --7.18608570099,1.42739605904,4.81728839874 --7.22906970978,1.43440055847,4.830098629 --7.25604915619,1.43740689754,4.8146982193 --7.29602527618,1.44241380692,4.80729341507 --7.35799789429,1.45242154598,4.81490039825 --7.39597511292,1.45742809772,4.80650568008 --7.42795372009,1.46043431759,4.79411172867 --7.47992801666,1.46844148636,4.79371118546 --7.51391363144,1.47444522381,4.79851198196 --7.55389118195,1.47945153713,4.79112434387 --7.60886573792,1.48745858669,4.79172325134 --7.64584350586,1.49246478081,4.78132820129 --7.69281959534,1.49847126007,4.77693414688 --7.7557926178,1.50847840309,4.78153419495 --7.79277086258,1.51348435879,4.77013587952 --7.81875896454,1.51748752594,4.76994943619 --7.88573122025,1.52749443054,4.77655601501 --7.90471315384,1.52849960327,4.7531504631 --8.00266551971,1.54251182079,4.74336242676 --8.14762496948,1.5695207119,4.79599523544 --8.15460968018,1.56752514839,4.76559972763 --8.1805973053,1.57152807713,4.76340198517 --8.18558216095,1.56953251362,4.7309961319 --8.24055767059,1.57753837109,4.72759819031 --8.25054168701,1.5765427351,4.69819545746 --8.28952121735,1.58154797554,4.68580150604 --8.32350063324,1.58555305004,4.67040777206 --8.35348129272,1.5885579586,4.65200662613 --8.3954668045,1.59556090832,4.65882110596 --8.41344928741,1.596565485,4.63341712952 --8.43243217468,1.59657001495,4.60800790787 --8.4574136734,1.59857439995,4.58761978149 --9.66719341278,1.84160602093,5.21852779388 --9.71417236328,1.84661006927,5.20413541794 --9.70616722107,1.84361124039,5.17993307114 --9.74014854431,1.84761488438,5.15853977203 --9.75013446808,1.84561812878,5.1231303215 --9.77911663055,1.84862160683,5.09873390198 --9.79210186005,1.84762454033,5.06633901596 --9.82408428192,1.85062801838,5.04293966293 --9.82807159424,1.84863090515,5.00553941727 --9.84106349945,1.84963238239,4.99233961105 --9.83905029297,1.8456350565,4.95193815231 --8.02433300018,1.4816095829,3.98604631424 --8.02531909943,1.47861373425,3.95363235474 --8.02530479431,1.4766176939,3.92223548889 --8.02729034424,1.47462165356,3.89082503319 --8.02227783203,1.47062563896,3.85641789436 --8.01127243042,1.46762740612,3.83521366119 --8.01325798035,1.46563148499,3.80481243134 --8.01624298096,1.46363544464,3.77440452576 --8.00923061371,1.45963931084,3.73899054527 --8.00321865082,1.45564317703,3.70559453964 --8.00520420074,1.45364713669,3.67518854141 --7.9951915741,1.44965100288,3.63877344131 --7.9981842041,1.44865298271,3.62457060814 --8.01516819,1.45065701008,3.6011660099 --8.00015640259,1.4446606636,3.56376338005 --7.99014472961,1.4406645298,3.52835536003 --8.00712871552,1.44166839123,3.5049495697 --7.99511623383,1.43767225742,3.46853637695 --8.05509471893,1.44667613506,3.46515417099 --8.111079216,1.45667815208,3.47395849228 --8.15705966949,1.46268200874,3.46356987953 --8.21303844452,1.47168564796,3.45718288422 --8.29101371765,1.48468911648,3.45979952812 --8.32799530029,1.48969268799,3.44440579414 --8.3879737854,1.49869608879,3.43801140785 --8.45595169067,1.50969934464,3.43563199043 --8.49593925476,1.51670086384,3.43643975258 --8.55991744995,1.52670395374,3.43105053902 --8.63789463043,1.539706707,3.4316740036 --8.64388084412,1.53870987892,3.40126132965 --10.3016433716,1.853703022,4.03935337067 --10.3256292343,1.85570454597,4.01095724106 --10.3276176453,1.85370635986,3.97355246544 --10.3396110535,1.85470700264,3.95935487747 --10.3695955276,1.85770845413,3.93295860291 --10.3695850372,1.8557100296,3.89556121826 --10.3835725784,1.85571146011,3.86316299438 --10.4145584106,1.85971271992,3.83676505089 --10.419547081,1.85771417618,3.80035829544 --10.4285354614,1.85771560669,3.76595759392 --10.4625263214,1.86271584034,3.75976705551 --10.4485177994,1.85771739483,3.71736502647 --10.4625053406,1.85771870613,3.68395709991 --10.4984912872,1.86271941662,3.65956735611 --10.4904813766,1.85872101784,3.61916255951 --10.5004701614,1.85872209072,3.58475828171 --10.5244626999,1.86172235012,3.57456564903 --10.5174541473,1.85872364044,3.53516602516 --10.5404405594,1.86072444916,3.50476050377 --10.5514287949,1.86072540283,3.47136378288 --10.5534191132,1.85872650146,3.43496441841 --10.565407753,1.85872745514,3.40156412125 --10.600394249,1.86372768879,3.37617516518 --10.5983896255,1.86172831059,3.35596370697 --10.607378006,1.86172914505,3.32156276703 --10.6273670197,1.86372959614,3.29117035866 --10.6363563538,1.86273026466,3.25676965714 --10.6473455429,1.86273086071,3.22337341309 --10.6803321838,1.86673092842,3.19597530365 --10.6793231964,1.86473166943,3.15857291222 --10.6983165741,1.8677315712,3.14537262917 --10.7043066025,1.86673223972,3.1109817028 --10.7132959366,1.86673271656,3.07557034492 --10.7272863388,1.86673295498,3.04317760468 --10.7392749786,1.86773324013,3.0097796917 --10.7472658157,1.86673367023,2.97437167168 --10.7772531509,1.8707331419,2.94597840309 --10.7782497406,1.87073349953,2.92777729034 --10.7942390442,1.87173342705,2.89538049698 --10.8112287521,1.87273323536,2.86298155785 --10.8242177963,1.87373328209,2.82958269119 --10.8332090378,1.8737334013,2.7951836586 --10.829199791,1.87073397636,2.75677466393 --10.8561897278,1.87373328209,2.72738409042 --10.8531856537,1.87273347378,2.70818185806 --10.8601760864,1.87273347378,2.67277669907 --10.8701667786,1.87273335457,2.63938641548 --10.8661594391,1.87073373795,2.60097455978 --10.8881483078,1.87273299694,2.5695772171 --10.90213871,1.87373256683,2.53617763519 --10.8991355896,1.87273275852,2.51697349548 --10.9031267166,1.87173271179,2.48157548904 --10.908118248,1.87073254585,2.44617438316 --10.9081106186,1.86973261833,2.40977311134 --10.9221010208,1.87073194981,2.37637376785 --10.9200935364,1.86873197556,2.33896541595 --10.9260845184,1.86873161793,2.30356097221 --10.9360761642,1.86873102188,2.27017068863 --10.9420719147,1.86873066425,2.25296807289 --10.9550638199,1.87072980404,2.21957159042 --10.9680547714,1.8717290163,2.1851644516 --10.9910459518,1.87372756004,2.15377187729 --11.0250349045,1.8787252903,2.12438106537 --11.0330276489,1.87872457504,2.08897519112 --11.0420198441,1.8797236681,2.05457806587 --11.0320158005,1.87672412395,2.03437328339 --11.0540075302,1.8797223568,2.00197482109 --11.0699996948,1.88172090054,1.96857702732 --11.0869913101,1.88271927834,1.9351786375 --11.0869846344,1.88171887398,1.89877593517 --11.1079759598,1.88471698761,1.8663828373 --11.0969734192,1.88171732426,1.84617733955 --11.10496521,1.88271605968,1.81178331375 --11.1209573746,1.88471448421,1.77737689018 --11.1309499741,1.8847130537,1.74298071861 --11.1449432373,1.88671135902,1.70857858658 --11.1489362717,1.88571023941,1.67318069935 --11.1469297409,1.88470959663,1.63677978516 --11.1669254303,1.88770771027,1.62158322334 --11.186917305,1.88970541954,1.58818602562 --11.1759119034,1.88770520687,1.54977476597 --11.1819057465,1.88770377636,1.51437413692 --11.2068986893,1.89070093632,1.48198330402 --11.1938934326,1.88770079613,1.44357311726 --11.212884903,1.88969838619,1.41017973423 --11.2208824158,1.89169716835,1.39297938347 --11.2318754196,1.89269518852,1.35757410526 --11.2248697281,1.8896945715,1.32117795944 --11.2468633652,1.89369153976,1.28778338432 --11.2398576736,1.89169085026,1.25037515163 --11.2618513107,1.89468765259,1.21597111225 --11.2688455582,1.89468574524,1.18057155609 --11.2688426971,1.89468502998,1.16236937046 --11.2788362503,1.89568269253,1.1279784441 --11.282831192,1.89568090439,1.09157061577 --11.2768259048,1.89367997646,1.05517101288 --11.2868204117,1.89467763901,1.01976931095 --11.2868146896,1.89367592335,0.983364522457 --11.2898101807,1.893674016,0.946957111359 --11.2778072357,1.89167428017,0.927751362324 --11.2948026657,1.89367115498,0.893356800079 --11.2787971497,1.89067089558,0.855949878693 --11.2837915421,1.8906686306,0.819540560246 --11.2887868881,1.89166641235,0.784142494202 --11.2897825241,1.89066457748,0.748746931553 --11.2777776718,1.88766384125,0.711334824562 --11.2927751541,1.89066147804,0.69413536787 --11.2817707062,1.8876606226,0.657733380795 --11.2897663116,1.88865792751,0.622334063053 --11.2727613449,1.88565766811,0.584921240807 --11.2757568359,1.88565528393,0.548512101173 --11.2777528763,1.88565301895,0.513114631176 --11.2857475281,1.88665020466,0.477715671062 --11.2747459412,1.88465034962,0.458502709866 --11.2747411728,1.88464820385,0.423105239868 --11.270737648,1.88264632225,0.386697351933 --11.2747335434,1.88364386559,0.351298928261 --11.2707290649,1.88264191151,0.314890116453 --11.2817249298,1.8846385479,0.279491573572 --11.277721405,1.88263654709,0.243082806468 --11.2757196426,1.88263559341,0.224877998233 --11.2717151642,1.88163387775,0.189479753375 --11.2767114639,1.88263070583,0.153070405126 --11.2737083435,1.88162875175,0.117671906948 --11.2847042084,1.88362503052,0.0822751447558 --11.2737007141,1.88162374496,0.0458635613322 --11.2756996155,1.88162219524,0.0276591069996 --11.2746953964,1.88161981106,-0.00773970177397 --11.2766914368,1.88161695004,-0.0441490113735 --11.2656888962,1.87961566448,-0.0795510932803 --11.2716846466,1.88061213493,-0.115959301591 --11.2756824493,1.88160896301,-0.151356592774 --11.2696790695,1.88060688972,-0.18776923418 --11.2736778259,1.88060498238,-0.204960972071 --11.2736749649,1.88060212135,-0.241371080279 --11.26567173,1.87960040569,-0.27677410841 --11.2756690979,1.88159608841,-0.313178956509 --11.267665863,1.87959432602,-0.348582148552 --11.2646627426,1.87959170341,-0.383983075619 --11.2656602859,1.87958848476,-0.420392692089 --11.2756595612,1.88158559799,-0.438590973616 --11.2686567307,1.88058340549,-0.473994553089 --11.269654274,1.88058006763,-0.510403811932 --11.2626514435,1.87957799435,-0.545808017254 --11.2736501694,1.88157320023,-0.582208931446 --11.2766475677,1.88256955147,-0.617604732513 --11.2706451416,1.88156700134,-0.654019594193 --11.2686443329,1.88156569004,-0.671214938164 --11.2786426544,1.88356089592,-0.707614898682 --11.2706403732,1.88255858421,-0.743020772934 --11.2736387253,1.88355469704,-0.77942699194 --11.2716360092,1.8835515976,-0.814826905727 --11.2876367569,1.88654565811,-0.85222953558 --11.275633812,1.88454389572,-0.887640118599 --11.2856330872,1.88654053211,-0.905832827091 --11.2916326523,1.88853597641,-0.942233979702 --11.2856302261,1.88753306866,-0.9786490798 --11.2986297607,1.89052736759,-1.01504039764 --11.2976284027,1.8905236721,-1.05144882202 --11.295627594,1.89052021503,-1.08684718609 --11.3066272736,1.89351463318,-1.12425041199 --11.2926263809,1.89151477814,-1.14146196842 --11.3016262054,1.89350938797,-1.17785561085 --11.3226261139,1.89750218391,-1.21625351906 --11.3076238632,1.89550030231,-1.25167000294 --11.3056230545,1.89549648762,-1.28706717491 --11.3276252747,1.90048885345,-1.32546055317 --11.3186235428,1.89948606491,-1.36086809635 --11.3206233978,1.89948356152,-1.38007807732 --11.3486251831,1.90547454357,-1.41946935654 --11.3306236267,1.90247321129,-1.45388042927 --11.3326244354,1.90346848965,-1.49028015137 --11.3656272888,1.91045844555,-1.53066945076 --11.3456249237,1.90745735168,-1.56508469582 --11.3516263962,1.9094517231,-1.60248672962 --11.3766279221,1.91444516182,-1.62367451191 --11.3506259918,1.91044485569,-1.6570905447 --11.3636274338,1.91343784332,-1.69548857212 --11.3896303177,1.91942858696,-1.73588228226 --11.3836307526,1.91842472553,-1.77128183842 --11.3996324539,1.92241704464,-1.81068134308 --11.4126348495,1.92541229725,-1.83087587357 --11.4136352539,1.92640697956,-1.8682820797 --11.4196376801,1.92840075493,-1.90668833256 --11.4536418915,1.93538951874,-1.9490776062 --11.444642067,1.93538594246,-1.98448109627 --11.4566450119,1.93837833405,-2.02388191223 --11.4816484451,1.94336843491,-2.06527423859 --11.4806499481,1.94436585903,-2.08347296715 --11.4926528931,1.94735825062,-2.12287044525 --11.5196580887,1.95334756374,-2.16526460648 --11.5166597366,1.95334243774,-2.20267248154 --11.5336637497,1.95833361149,-2.24306535721 --11.5526676178,1.96232414246,-2.2844619751 --11.544670105,1.96231985092,-2.3208694458 --11.5546712875,1.96431481838,-2.34207105637 --11.5726766586,1.96930539608,-2.383466959 --11.5626783371,1.96830153465,-2.41886758804 --11.559679985,1.96929585934,-2.45728254318 --11.5596828461,1.9702899456,-2.49467873573 --11.5666866302,1.9732824564,-2.53407764435 --11.5796918869,1.97627353668,-2.57548069954 --11.6116991043,1.98326051235,-2.62087345123 --11.6187019348,1.98625600338,-2.64106750488 --11.6457099915,1.99224388599,-2.68545937538 --11.6727170944,1.99823176861,-2.72984910011 --11.6727209091,2.00022506714,-2.76925945282 --11.6707239151,2.00121879578,-2.80766439438 --11.6857309341,2.00520896912,-2.85006165504 --11.677731514,2.00420713425,-2.86726284027 --11.6707344055,2.00420165062,-2.90467000008 --11.6917419434,2.01019024849,-2.94906830788 --11.6827449799,2.0101852417,-2.98547029495 --11.6677474976,2.00918149948,-3.02189016342 --11.701757431,2.01616692543,-3.06927585602 --11.68475914,2.01516342163,-3.10469102859 --11.6877622604,2.01615905762,-3.12488889694 --11.7167720795,2.02314543724,-3.17127513885 --11.7037744522,2.02314090729,-3.20768713951 --11.707780838,2.0251326561,-3.2480866909 --11.7157869339,2.02812337875,-3.29049301147 --11.7207937241,2.03111457825,-3.33088755608 --11.731801033,2.03510427475,-3.37429213524 --11.7518081665,2.0390958786,-3.3994820118 --11.7548151016,2.04208707809,-3.44089007378 --11.7638216019,2.04507732391,-3.48328709602 --11.7878332138,2.05206346512,-3.53068351746 --11.7888393402,2.05405521393,-3.57108449936 --11.7978467941,2.05704498291,-3.61347699165 --11.8098554611,2.06103396416,-3.65787863731 --11.8158607483,2.06302809715,-3.68007850647 --11.7988643646,2.06202411652,-3.71548819542 --11.8028717041,2.06501460075,-3.75789499283 --11.810880661,2.06900405884,-3.80129647255 --11.8048858643,2.0699968338,-3.84070658684 --11.8048934937,2.07198858261,-3.88110470772 --11.8109025955,2.07497835159,-3.92451000214 --11.8069057465,2.07497501373,-3.94371271133 --11.8289175034,2.08196043968,-3.99210762978 --11.8209238052,2.08195376396,-4.03051185608 --11.8139305115,2.08294630051,-4.06992197037 --11.8249406815,2.08793449402,-4.11532354355 --11.832950592,2.09092330933,-4.15972471237 --11.8239564896,2.09191656113,-4.19813108444 --11.8479661942,2.09790539742,-4.22732305527 --11.8469753265,2.09989619255,-4.26872587204 --11.864988327,2.1058819294,-4.31712293625 --11.8790006638,2.11086893082,-4.36351394653 --11.8750085831,2.11186027527,-4.40492486954 --11.8620138168,2.11185407639,-4.4423327446 --11.8620233536,2.1148443222,-4.4847369194 --11.8660297394,2.1168384552,-4.50794219971 --11.8640384674,2.11882901192,-4.54934310913 --11.8560466766,2.11982154846,-4.58874893188 --11.8620576859,2.12380957603,-4.63415431976 --11.8500642776,2.12380290031,-4.67256546021 --11.8530759811,2.12679171562,-4.7169713974 --11.8370819092,2.12678599358,-4.75337982178 --11.8220834732,2.12578487396,-4.7695941925 --11.8380975723,2.13076996803,-4.81899166107 --11.849111557,2.1357562542,-4.86638879776 --11.8401203156,2.13674855232,-4.90579462051 --11.8491334915,2.1417350769,-4.95319747925 --11.8361406326,2.14172816277,-4.99160957336 --11.8501558304,2.14771318436,-5.04100751877 --11.8701677322,2.15270185471,-5.07120037079 --11.8471727371,2.15169763565,-5.10561656952 --11.8451833725,2.15368723869,-5.14902448654 --11.8481960297,2.15667533875,-5.19341897964 --11.8412065506,2.15866613388,-5.23482894897 --11.8222131729,2.15866041183,-5.27124595642 --11.8452253342,2.16364789009,-5.30343770981 --11.820230484,2.16264414787,-5.33685350418 --11.7982368469,2.16163921356,-5.3722743988 --11.8202562332,2.16862082481,-5.42666864395 --11.7952613831,2.16661715508,-5.46008443832 --11.7852716446,2.16860842705,-5.50049543381 --11.8072919846,2.17558979988,-5.55488491058 --11.7772884369,2.17159318924,-5.56410598755 --11.764298439,2.17258548737,-5.60352087021 --11.7393026352,2.17058157921,-5.63693761826 --11.7353153229,2.17357063293,-5.68034553528 --11.722325325,2.17356300354,-5.71875047684 --11.7173376083,2.17655229568,-5.76216220856 --11.6963453293,2.17554712296,-5.79757785797 --11.6913499832,2.17654252052,-5.8177819252 --11.6863622665,2.17853164673,-5.86119222641 --11.6563673019,2.17652916908,-5.89261579514 --11.6483793259,2.17851924896,-5.93503141403 --11.6393909454,2.18050932884,-5.9764418602 --11.6053934097,2.17650842667,-6.00485992432 --11.598405838,2.17949819565,-6.04726886749 --11.5984134674,2.18049168587,-6.07047319412 --11.5744190216,2.17948722839,-6.10388708115 --11.542424202,2.17648506165,-6.13431549072 --11.5654468536,2.18546438217,-6.19170284271 --11.5184459686,2.17946743965,-6.21413755417 --11.5104589462,2.18145704269,-6.25654888153 --11.5164766312,2.18644189835,-6.30594825745 --11.4964771271,2.1844420433,-6.31916618347 --11.5084972382,2.19042444229,-6.3715596199 --11.5065135956,2.19441151619,-6.41797161102 --11.4925251007,2.19540309906,-6.45738458633 --11.484539032,2.19739222527,-6.49979162216 --11.494559288,2.20337462425,-6.55319738388 --11.4785699844,2.20436668396,-6.591609478 --11.4875822067,2.20835661888,-6.61980295181 --11.4635896683,2.20735120773,-6.65422344208 --11.4435997009,2.20734453201,-6.69063949585 --11.4566230774,2.21432518959,-6.7460398674 --11.5386743546,2.23528003693,-6.84039497375 --11.6247291565,2.2572324276,-6.93976354599 --11.6977777481,2.27618956566,-7.0301194191 --11.7538108826,2.29016041756,-7.0882973671 --11.7748403549,2.29813694954,-7.14968442917 --11.7478485107,2.29713177681,-7.18410634995 --11.7258586884,2.29712462425,-7.22152662277 --11.6788597107,2.29212713242,-7.24396085739 --11.6488666534,2.2901237011,-7.27537727356 --11.5998659134,2.28512692451,-7.2968173027 --11.5568571091,2.27813625336,-7.29503822327 --11.5298652649,2.27713108063,-7.32946586609 --11.5108785629,2.27812290192,-7.36788082123 --11.4618759155,2.27212667465,-7.38731002808 --11.4278821945,2.27012443542,-7.41673851013 --11.3918867111,2.26712298393,-7.44516992569 --11.3618946075,2.26611924171,-7.47659349442 --11.3428964615,2.26411914825,-7.48980760574 --11.3129024506,2.2621152401,-7.52123117447 --11.2639007568,2.25711965561,-7.53966093063 --11.2279062271,2.25411844254,-7.56708955765 --11.2069168091,2.25411081314,-7.60451173782 --11.1589164734,2.2491145134,-7.62394809723 --11.1359157562,2.24711632729,-7.63315677643 --11.105922699,2.24511265755,-7.66458559036 --11.0679264069,2.24211239815,-7.69001436234 --11.0269289017,2.23811340332,-7.71344614029 --10.9989366531,2.23710894585,-7.74486494064 --10.9589385986,2.23411011696,-7.76829338074 --10.9259443283,2.23210787773,-7.79672002792 --10.9039449692,2.23010873795,-7.80794334412 --10.8739519119,2.22810554504,-7.83736085892 --10.8339538574,2.22510647774,-7.86079263687 --10.8009595871,2.22310447693,-7.88821458817 --10.7529573441,2.21710896492,-7.90565109253 --10.716960907,2.2151081562,-7.93208599091 --10.697974205,2.21609973907,-7.96950101852 --10.6679697037,2.21210479736,-7.9737238884 --10.6349754333,2.21010279655,-8.00114917755 --10.5979795456,2.20710253716,-8.02557754517 --10.5619831085,2.20510220528,-8.05100917816 --10.5309896469,2.20309925079,-8.07943153381 --10.4969940186,2.20109772682,-8.1058588028 --10.4559955597,2.19709992409,-8.12628555298 --10.4399986267,2.19709849358,-8.14050197601 --10.3959980011,2.192101717,-8.15994167328 --10.3670063019,2.19109797478,-8.18936252594 --10.3220043182,2.18710207939,-8.20679664612 --10.3140239716,2.19108819962,-8.25220584869 --10.2640199661,2.18509459496,-8.26665115356 --10.227022171,2.18209505081,-8.28907394409 --10.2160291672,2.18309164047,-8.30628108978 --10.176030159,2.18009305,-8.32771778107 --10.1450366974,2.17809081078,-8.35514163971 --10.1120424271,2.17608880997,-8.38157081604 --10.0590353012,2.17009711266,-8.39201450348 --10.0150337219,2.16610145569,-8.4084444046 --9.98904323578,2.16609597206,-8.44087505341 --9.97204589844,2.1650955677,-8.45308685303 --9.93004512787,2.16109871864,-8.47051429749 --9.92807102203,2.16708111763,-8.52293205261 --9.88607025146,2.16308450699,-8.54036045074 --9.86007976532,2.16307926178,-8.57178401947 --9.82808589935,2.16107726097,-8.59821224213 --9.78108119965,2.15608334541,-8.61164855957 --9.74707221985,2.15209197998,-8.60886955261 --9.71607971191,2.15108919144,-8.63630104065 --9.68708705902,2.15008592606,-8.66472625732 --9.65309143066,2.14808487892,-8.68915748596 --9.64011096954,2.15107274055,-8.73157310486 --9.59410667419,2.1470785141,-8.7450094223 --9.56411552429,2.14607548714,-8.77344322205 --9.54811763763,2.14507460594,-8.78565216064 --9.51011943817,2.14307641983,-8.80507850647 --9.47912597656,2.14107394218,-8.83150577545 --9.45613861084,2.14306712151,-8.86593341827 --9.42014217377,2.14006733894,-8.88836860657 --9.37513828278,2.13607311249,-8.90079784393 --9.34214305878,2.13407182693,-8.92522716522 --9.32514572144,2.1340713501,-8.93744564056 --9.29815578461,2.13406705856,-8.96686840057 --9.25915622711,2.13106894493,-8.98630809784 --9.2181558609,2.12707304955,-9.00173377991 --9.19516849518,2.12906622887,-9.03515720367 --9.18018722534,2.13205456734,-9.07657623291 --9.15818500519,2.13005709648,-9.08379745483 --9.13419818878,2.13105034828,-9.11722755432 --9.11821556091,2.13303947449,-9.15663909912 --9.08322048187,2.13203954697,-9.17907333374 --9.04922485352,2.13003873825,-9.20250701904 --9.02323532104,2.13103342056,-9.23292922974 --8.97523021698,2.12604141235,-9.24237251282 --8.93022537231,2.12204766273,-9.25380897522 --8.82615852356,2.09910082817,-9.17707443237 --8.90325164795,2.12503218651,-9.31244373322 --8.8672542572,2.12303352356,-9.33186817169 --8.84927177429,2.12602305412,-9.37129211426 --8.80727100372,2.1230275631,-9.38573074341 --8.77427577972,2.12202620506,-9.40916061401 --8.77429199219,2.12501573563,-9.43735980988 --8.73829555511,2.12301635742,-9.45880031586 --8.70830345154,2.12301325798,-9.48522853851 --8.67831230164,2.12301039696,-9.51165676117 --8.6443157196,2.1210103035,-9.53308200836 --8.60831928253,2.11901116371,-9.55351734161 --8.58733558655,2.12200212479,-9.58994197845 --8.56433296204,2.11900615692,-9.59416007996 --8.52733516693,2.11700749397,-9.61359786987 --8.51836204529,2.12299108505,-9.66200637817 --8.47535896301,2.11899662018,-9.67444610596 --8.43936252594,2.11699748039,-9.69488430023 --8.42638683319,2.12198281288,-9.74030303955 --8.38938808441,2.11998462677,-9.75873565674 --8.37539291382,2.119982481,-9.77294921875 --8.3434009552,2.11898088455,-9.79738140106 --8.30940532684,2.11798024178,-9.81981754303 --8.28341770172,2.11897468567,-9.85024166107 --8.25142478943,2.11897325516,-9.87366867065 --8.21743011475,2.11797261238,-9.8961057663 --8.18243312836,2.1159734726,-9.91553115845 --8.17444515228,2.11796665192,-9.93774700165 --8.13444423676,2.11597084999,-9.95218276978 --8.1104593277,2.11696338654,-9.98560905457 --8.07946777344,2.11696076393,-10.0110416412 --8.0444726944,2.11596131325,-10.0314760208 --8.01648235321,2.11695671082,-10.0599021912 --7.99049663544,2.11795043945,-10.0913314819 --7.97650194168,2.11794829369,-10.1055440903 --7.94951438904,2.118942976,-10.1359758377 --7.91952419281,2.11993956566,-10.1624069214 --7.88552951813,2.11893939972,-10.183839798 --7.86054372787,2.1199324131,-10.2162647247 --7.83656024933,2.12292432785,-10.2506942749 --7.8175611496,2.12192559242,-10.2589111328 --7.78456830978,2.12092423439,-10.2823495865 --7.77259683609,2.12690711021,-10.3317670822 --7.73259687424,2.12391114235,-10.3462085724 --7.6935968399,2.12191486359,-10.3606424332 --7.6766204834,2.12590146065,-10.4040632248 --7.64362812042,2.12590003014,-10.4275007248 --7.61163663864,2.12589788437,-10.4519357681 --7.60164785385,2.12789201736,-10.4721488953 --7.57065629959,2.12788963318,-10.4965744019 --7.53165626526,2.12589335442,-10.51101017 --7.50967645645,2.12888288498,-10.5494403839 --7.48168992996,2.12987732887,-10.5798749924 --7.4436917305,2.12888050079,-10.5953102112 --7.43670654297,2.13087153435,-10.6205234528 --7.40271186829,2.13087153435,-10.640953064 --7.37172174454,2.13086867332,-10.6663837433 --7.34774065018,2.13385939598,-10.7028169632 --7.31074285507,2.13186192513,-10.7192487717 --7.28776359558,2.13585138321,-10.757683754 --7.26177978516,2.13784408569,-10.7901105881 --7.25479507446,2.13983535767,-10.815320015 --7.22080183029,2.13983464241,-10.8367538452 --7.19782161713,2.14282464981,-10.8741788864 --7.15782165527,2.14082884789,-10.8876218796 --7.1248292923,2.14082765579,-10.9100522995 --7.0938410759,2.14182424545,-10.9364862442 --7.06986093521,2.14481425285,-10.9739198685 --7.04785823822,2.14281845093,-10.9771404266 --7.01787042618,2.14381432533,-11.0045700073 --6.98888492584,2.14580845833,-11.0350084305 --6.95288848877,2.14480996132,-11.052438736 --6.94192790985,2.15278720856,-11.111869812 --6.92195367813,2.1567735672,-11.1552944183 --6.88095188141,2.1547794342,-11.1657304764 --6.86195230484,2.15378093719,-11.1729459763 --6.8249578476,2.15278196335,-11.1923961639 --6.77394151688,2.14679765701,-11.1858358383 --6.73294019699,2.14480304718,-11.1972808838 --6.71797323227,2.15178465843,-11.2486982346 --6.67697238922,2.14978981018,-11.2601442337 --6.57285308838,2.11987376213,-11.1284189224 --6.52283668518,2.1138894558,-11.1218605042 --6.46480846405,2.10591292381,-11.1023101807 --6.40778112411,2.09793567657,-11.0837593079 --6.36477518082,2.09494447708,-11.0892047882 --6.31075191498,2.08796453476,-11.0756568909 --6.27074813843,2.0849711895,-11.0840921402 --6.26176357269,2.08796310425,-11.1083078384 --6.21875667572,2.08497238159,-11.1127519608 --6.16673612595,2.07899045944,-11.1022062302 --6.11070823669,2.07101392746,-11.0826568604 --6.07470989227,2.06901717186,-11.0970878601 --6.02068376541,2.06203866005,-11.080537796 --5.97166585922,2.05705571175,-11.0719823837 --5.9376411438,2.05007433891,-11.0502090454 --5.88361549377,2.0430958271,-11.0336666107 --5.84060525894,2.03910684586,-11.0351085663 --5.81762742996,2.04309654236,-11.0725345612 --5.80667066574,2.05207180977,-11.1349658966 --5.7796869278,2.05406570435,-11.1653928757 --5.74469089508,2.05406737328,-11.1828346252 --5.72569036484,2.05307006836,-11.1880540848 --5.69970989227,2.05706167221,-11.2224903107 --5.67272758484,2.05905437469,-11.2549247742 --5.64173793793,2.06105184555,-11.2793607712 --5.61275291443,2.06304645538,-11.3087997437 --5.58076190948,2.06404542923,-11.3302297592 --5.53474617004,2.05906009674,-11.3246717453 --5.52175664902,2.06105566025,-11.3428936005 --5.49377346039,2.06404900551,-11.374329567 --5.453769207,2.0610563755,-11.3817739487 --5.4137635231,2.05906462669,-11.3872108459 --5.37676477432,2.05806875229,-11.4006557465 --5.3427696228,2.05806994438,-11.4180879593 --5.30476951599,2.05707526207,-11.4295339584 --5.28877401352,2.05807447433,-11.4407510757 --5.21069669724,2.04012989998,-11.3662166595 --5.17269515991,2.03813552856,-11.3766622543 --5.16575193405,2.05010294914,-11.4520816803 --5.13676691055,2.05209779739,-11.480512619 --5.0977640152,2.05110478401,-11.4889593124 --5.08477497101,2.05309987068,-11.5071763992 --5.05879735947,2.05709028244,-11.5436115265 --5.01578712463,2.05310201645,-11.5440635681 --4.97878599167,2.05210709572,-11.5544977188 --4.9457950592,2.0531065464,-11.5759382248 --4.90478754044,2.0511162281,-11.5793848038 --4.86878919601,2.0511200428,-11.5928239822 --4.84577989578,2.04812860489,-11.5880460739 --4.80477237701,2.04613828659,-11.5914955139 --4.76877403259,2.04514217377,-11.6049346924 --4.73578310013,2.04614114761,-11.626376152 --4.68976306915,2.04215908051,-11.6158227921 --4.65476846695,2.04216074944,-11.63326931 --4.62077331543,2.04216241837,-11.6497001648 --4.59776258469,2.04017186165,-11.6439237595 --4.55875825882,2.038179636,-11.6503677368 --4.52276134491,2.03818297386,-11.6648139954 --4.48275232315,2.03619360924,-11.6662511826 --4.43973827362,2.03220748901,-11.6627006531 --4.40875148773,2.03420424461,-11.6881380081 --4.36573696136,2.03121852875,-11.6835861206 --4.35074567795,2.03221559525,-11.69880867 --4.31274318695,2.03122258186,-11.7072534561 --4.2707285881,2.02823662758,-11.7026939392 --4.2317237854,2.02624464035,-11.7091445923 --4.19873380661,2.02824378014,-11.7305870056 --4.15571498871,2.02326059341,-11.7210206985 --4.11771202087,2.02226758003,-11.729470253 --4.09871196747,2.02227067947,-11.7346992493 --4.05769872665,2.01928400993,-11.731136322 --4.01668787003,2.0162961483,-11.7305870056 --3.98068809509,2.01630115509,-11.7420272827 --3.94168114662,2.01431083679,-11.7454710007 --3.90267419815,2.01332044601,-11.748916626 --3.86567282677,2.01232671738,-11.7583618164 --3.84366130829,2.00933623314,-11.7515821457 --3.80465435982,2.00834608078,-11.7550296783 --3.77066040039,2.00934743881,-11.7724704742 --3.7306497097,2.00635957718,-11.7719163895 --3.69264531136,2.00536751747,-11.7783641815 --3.65764808655,2.00637125969,-11.7918024063 --3.63563656807,2.00338101387,-11.7850265503 --3.59462285042,2.00039482117,-11.7814760208 --3.56163287163,2.00239419937,-11.8029203415 --3.52161955833,1.99940776825,-11.7993602753 --3.48160982132,1.9974193573,-11.7998142242 --3.44861888885,1.99941909313,-11.8202543259 --3.40760350227,1.99643409252,-11.814702034 --3.36959505081,1.9944447279,-11.8161382675 --3.35460615158,1.99644064903,-11.833363533 --3.31359004974,1.99345624447,-11.8268089294 --3.27759075165,1.99346137047,-11.8382568359 --3.24259233475,1.993465662,-11.8506946564 --3.19856667519,1.98848700523,-11.8341464996 --3.15855407715,1.98650038242,-11.8315982819 --3.14255976677,1.98749959469,-11.8428153992 --3.10254645348,1.98551344872,-11.8392648697 --3.06654644012,1.98551917076,-11.8497104645 --3.02653098106,1.98253405094,-11.8441553116 --2.98852324486,1.9805444479,-11.8466014862 --2.95051383972,1.97955572605,-11.8470430374 --2.91652035713,1.98055744171,-11.864484787 --2.89249849319,1.97657358646,-11.8467140198 --2.85549354553,1.97558224201,-11.8521595001 --2.82049822807,1.97658514977,-11.867609024 --2.78048014641,1.97360169888,-11.8590517044 --2.74347376823,1.97261142731,-11.8624925613 --2.70747447014,1.97261667252,-11.8739433289 --2.66745638847,1.96963334084,-11.8653888702 --2.64744567871,1.9676425457,-11.8596086502 --2.612449646,1.96864593029,-11.8740558624 --2.57042455673,1.96466696262,-11.8585109711 --2.53341889381,1.96367609501,-11.8629570007 --2.50043177605,1.96667444706,-11.8864040375 --2.45940375328,1.96169674397,-11.8678417206 --2.42039036751,1.9597107172,-11.8642940521 --2.4023911953,1.9597132206,-11.8705215454 --2.3633723259,1.95673036575,-11.8609619141 --2.32737159729,1.95773684978,-11.8704118729 --2.29137158394,1.95774281025,-11.8808631897 --2.25134682655,1.95376336575,-11.8653030396 --2.21434020996,1.9527733326,-11.8687515259 --2.17833924294,1.95277988911,-11.8782014847 --2.15832781792,1.95178973675,-11.8714256287 --2.12131738663,1.94980180264,-11.8708667755 --2.08933925629,1.95479512215,-11.9033184052 --2.05635142326,1.95779407024,-11.9257593155 --2.02537894249,1.96278393269,-11.9642076492 --1.995413661,1.96976983547,-12.0096559525 --1.96242904663,1.97376692295,-12.0350980759 --1.94342255592,1.97277402878,-12.0333204269 --1.9074229002,1.97277998924,-12.0437688828 --1.86840581894,1.97079634666,-12.0362186432 --1.83542501926,1.97479140759,-12.0656661987 --1.80043172836,1.97679388523,-12.0821123123 --1.76141250134,1.97381138802,-12.0725593567 --1.72239327431,1.9708288908,-12.0630083084 --1.70641052723,1.97482228279,-12.0852375031 --1.66940045357,1.97383439541,-12.0846776962 --1.63239717484,1.97384285927,-12.0911312103 --1.59639978409,1.97484791279,-12.1035814285 --1.55737864971,1.97186660767,-12.0920295715 --1.52238547802,1.97386908531,-12.1084747314 --1.50438964367,1.97487008572,-12.1177034378 --1.46838867664,1.97587716579,-12.1261482239 --1.43037450314,1.97389185429,-12.1215963364 --1.39337015152,1.97390091419,-12.1270475388 --1.35838294029,1.97690033913,-12.1494989395 --1.32036781311,1.97491562366,-12.1439466476 --1.28336274624,1.97492527962,-12.148396492 --1.26334321499,1.97193968296,-12.1336183548 --1.22633719444,1.97194993496,-12.1370687485 --1.18932819366,1.97196173668,-12.1375150681 --1.15333294868,1.97296583652,-12.1519651413 --1.11531794071,1.97198116779,-12.1464166641 --1.07831192017,1.97199141979,-12.1498670578 --1.04130589962,1.972001791,-12.1533174515 --1.02229332924,1.97001230717,-12.1455383301 --0.986299335957,1.97201573849,-12.1609897614 --0.949297308922,1.97302389145,-12.1684446335 --0.900365650654,1.98599565029,-12.2501134872 --0.863361954689,1.98700475693,-12.255563736 --0.825351774693,1.98601770401,-12.2550201416 --0.807362377644,1.98801529408,-12.2702493668 --0.770347654819,1.98703050613,-12.2646894455 --0.733345925808,1.9880386591,-12.2721414566 --0.695338904858,1.98804986477,-12.274600029 --0.658332109451,1.98806083202,-12.2770471573 --0.620314955711,1.98607766628,-12.2694997787 --0.584326505661,1.9890781641,-12.2899465561 --0.565321087837,1.98908495903,-12.2891750336 --0.527305841446,1.98710072041,-12.2836294174 --0.490302234888,1.98811006546,-12.2890796661 --0.453299582005,1.98911881447,-12.2955284119 --0.416287720203,1.98813271523,-12.292974472 --0.378278762102,1.9881452322,-12.2934331894 --0.340252488852,1.98516714573,-12.2768850327 --0.322262406349,1.98716521263,-12.2911081314 --0.285252720118,1.98717796803,-12.2905550003 --0.247227102518,1.98319959641,-12.2750082016 --0.210228666663,1.98520624638,-12.2854604721 --0.172206401825,1.98322618008,-12.2729167938 --0.135194435716,1.98224008083,-12.2703647614 --0.117192156613,1.98224496841,-12.2725830078 --0.0791490450501,1.9762762785,-12.2400379181 --0.0421424582601,1.97728741169,-12.2424888611 --0.00513563118875,1.97729873657,-12.2449388504 -0.0140854949132,1.96166050434,-11.364115715 -0.0510758273304,1.95864462852,-11.346496582 -0.0880600512028,1.95462524891,-11.3228807449 -0.106058239937,1.95361924171,-11.3170661926 -0.1430465132,1.94960224628,-11.297451973 -0.180073007941,1.95260608196,-11.314827919 -0.217091321945,1.95460546017,-11.3242063522 -0.254107683897,1.9566038847,-11.3315830231 -0.291131794453,1.95860660076,-11.3469572067 -0.328151971102,1.96060705185,-11.358332634 -0.347165822983,1.96260917187,-11.3675222397 -0.384177863598,1.96360516548,-11.3708992004 -0.421169489622,1.96059012413,-11.3542871475 -0.459194898605,1.96359336376,-11.3706674576 -0.495180279016,1.95957517624,-11.3480491638 -0.532193303108,1.96057188511,-11.3524255753 -0.569208502769,1.96256959438,-11.3587989807 -0.588212132454,1.96256625652,-11.3579950333 -0.624217629433,1.96155929565,-11.3553657532 -0.65714430809,1.94750988483,-11.2747631073 -0.691108644009,1.94048082829,-11.2311477661 -0.723051667213,1.92944049835,-11.1665325165 -0.755998909473,1.9184025526,-11.1059274673 -0.792006134987,1.91839647293,-11.104306221 -0.809002578259,1.91738963127,-11.0964918137 -0.845007836819,1.91738247871,-11.092871666 -0.877970635891,1.9093528986,-11.0472631454 -0.90993142128,1.90132248402,-10.9996490479 -0.945934057236,1.90131378174,-10.9930362701 -0.980938136578,1.90030646324,-10.9884109497 -0.997925758362,1.89729487896,-10.9716110229 -1.0319122076,1.89427793026,-10.9489955902 -1.06488859653,1.8892557621,-10.916384697 -1.09888672829,1.88724541664,-10.9057598114 -1.13488864899,1.88723647594,-10.8981523514 -1.16686296463,1.8812135458,-10.8635387421 -1.2028772831,1.88221156597,-10.8689155579 -1.21886622906,1.88020086288,-10.8531084061 -1.25184679031,1.87518119812,-10.8245010376 -1.28584444523,1.87417054176,-10.8128814697 -1.31883394718,1.87115573883,-10.793264389 -1.3528277874,1.8691431284,-10.7776527405 -1.38581383228,1.8661262989,-10.7540426254 -1.41880536079,1.86311268806,-10.7364253998 -1.43177354336,1.85709154606,-10.6996250153 -1.4687962532,1.86009383202,-10.7130031586 -1.50077831745,1.85607528687,-10.6853933334 -1.53176116943,1.85205733776,-10.6587753296 -1.5677703619,1.85305261612,-10.658164978 -1.59774827957,1.84803235531,-10.6265468597 -1.63073933125,1.84501850605,-10.6079397202 -1.64673447609,1.84401154518,-10.5981311798 -1.67670989037,1.83898985386,-10.5635223389 -1.71172070503,1.83998632431,-10.5649013519 -1.74370622635,1.83596968651,-10.5402975082 -1.77167761326,1.82994639874,-10.5016813278 -1.80769252777,1.83194494247,-10.507062912 -1.84169280529,1.83093595505,-10.4974546432 -1.85467231274,1.82692110538,-10.4716510773 -1.88968062401,1.82791626453,-10.4700365067 -1.91966152191,1.82389760017,-10.4404287338 -1.95165848732,1.82188749313,-10.4278078079 -1.98365116119,1.8198748827,-10.4101991653 -2.01765275002,1.81986665726,-10.4015903473 -2.04562878609,1.81484591961,-10.3669786453 -2.06263279915,1.81484353542,-10.3661680222 -2.0976421833,1.81583940983,-10.3655529022 -2.12561893463,1.81081926823,-10.3319425583 -2.15962338448,1.81081271172,-10.3263301849 -2.19463014603,1.8118070364,-10.3227233887 -2.22261142731,1.8077892065,-10.2931060791 -2.23961353302,1.80778598785,-10.2903013229 -2.27060341835,1.8047722578,-10.2696962357 -2.30059242249,1.80175828934,-10.2480840683 -2.33359503746,1.80175101757,-10.2404680252 -2.36659502983,1.80174231529,-10.2298603058 -2.39658689499,1.79972994328,-10.2112417221 -2.42858481407,1.7987203598,-10.1986303329 -2.44558429718,1.79771578312,-10.1928339005 -2.47457242012,1.79470157623,-10.1702184677 -2.50255346298,1.79068362713,-10.1396169662 -2.53856897354,1.79368269444,-10.1449975967 -2.56554675102,1.78866350651,-10.1113958359 -2.59353232384,1.78564810753,-10.0857830048 -2.62854290009,1.78664493561,-10.0861692429 -2.64353871346,1.78563868999,-10.0763654709 -2.67353200912,1.78362727165,-10.0587520599 -2.70452570915,1.78261566162,-10.0411500931 -2.71846246719,1.76957726479,-9.96455287933 -2.75447630882,1.77157557011,-9.96794223785 -2.79149460793,1.77457618713,-9.9763250351 -2.81948232651,1.77156221867,-9.95271396637 -2.83146715164,1.76855063438,-9.93092060089 -2.868486166,1.77155172825,-9.94029808044 -2.89847922325,1.77054011822,-9.92169475555 -2.93349194527,1.7725379467,-9.9240732193 -2.95746564865,1.76651751995,-9.88547515869 -2.98846507072,1.76650929451,-9.87385940552 -3.01344227791,1.76149022579,-9.83826541901 -3.02844190598,1.76148617268,-9.83245277405 -3.05141353607,1.75546455383,-9.79086112976 -3.08040785789,1.75345420837,-9.77424526215 -3.11140608788,1.75344526768,-9.76064109802 -3.14039921761,1.75143408775,-9.74203395844 -3.16939234734,1.74942290783,-9.72342777252 -3.18439126015,1.74941849709,-9.71662139893 -3.2133846283,1.74740755558,-9.69801616669 -3.25541543961,1.75341403484,-9.71939659119 -3.27538347244,1.74639129639,-9.67380142212 -3.30538153648,1.74638271332,-9.66018867493 -3.33136916161,1.74336922169,-9.63557624817 -3.35835623741,1.74035537243,-9.60998153687 -3.37235307693,1.7393501997,-9.60117340088 -3.4013478756,1.73833990097,-9.58356952667 -3.43335056305,1.73833358288,-9.57496070862 -3.46034145355,1.7363216877,-9.55335235596 -3.48933768272,1.73531234264,-9.5377407074 -3.51231837273,1.73129582405,-9.50513744354 -3.54131412506,1.73028635979,-9.48853206635 -3.58530855179,1.72827255726,-9.46512413025 -3.6072871685,1.72425496578,-9.42952728271 -3.63628268242,1.72324562073,-9.41292572021 -3.65525627136,1.71722614765,-9.37232303619 -3.68224740028,1.71521472931,-9.3507232666 -3.71926546097,1.71921539307,-9.35809898376 -3.74027848244,1.72121763229,-9.36629390717 -3.76727080345,1.72020673752,-9.34568977356 -3.79326033592,1.71719455719,-9.32209014893 -3.82326054573,1.71718752384,-9.31047725677 -3.85927414894,1.72018611431,-9.31286239624 -3.89027500153,1.72017908096,-9.30126094818 -3.92027544975,1.72017204762,-9.28964710236 -3.93828034401,1.72117042542,-9.28884983063 -3.96828007698,1.72116303444,-9.27624130249 -4.0022892952,1.72315979004,-9.27362728119 -4.03329086304,1.72315323353,-9.26301956177 -4.06429243088,1.72414660454,-9.25241184235 -4.09429216385,1.72413921356,-9.23980236053 -4.1282992363,1.72513520718,-9.23519802094 -4.14329862595,1.72513139248,-9.22839546204 -4.17229700089,1.72512328625,-9.21378612518 -4.20129489899,1.72411525249,-9.199177742 -4.22828865051,1.7231054306,-9.17957401276 -4.26430130005,1.72610366344,-9.18095588684 -4.28928947449,1.72309148312,-9.15536308289 -4.30428934097,1.72308766842,-9.14856147766 -4.34230518341,1.72708725929,-9.15294837952 -4.37130308151,1.72607934475,-9.13833904266 -4.40130376816,1.72707271576,-9.12672519684 -4.43130350113,1.72706532478,-9.11312198639 -4.46230459213,1.72705876827,-9.10151767731 -4.4913020134,1.72705054283,-9.08591556549 -4.51131057739,1.7290507555,-9.08911132812 -4.53229379654,1.72503662109,-9.057513237 -4.56229496002,1.72603011131,-9.0458984375 -4.5973033905,1.7280267477,-9.04229164124 -4.62830543518,1.72802066803,-9.03168296814 -4.65730333328,1.72801268101,-9.01607990265 -4.69030809402,1.72900772095,-9.0084733963 -4.69929838181,1.72699999809,-8.99067211151 -4.73831415176,1.73099958897,-8.99505901337 -4.76731157303,1.73099172115,-8.97945594788 -4.79831314087,1.73198544979,-8.96785068512 -4.8202996254,1.72897291183,-8.93925189972 -4.85430669785,1.7309691906,-8.93463611603 -4.87929821014,1.72895848751,-8.91104030609 -4.90431451797,1.7329621315,-8.92322826385 -4.94433116913,1.73696208,-8.92861175537 -4.96531581879,1.733948946,-8.89801692963 -4.98329734802,1.72993445396,-8.86341762543 -5.0142993927,1.73092830181,-8.851811409 -5.0432972908,1.73092067242,-8.83620929718 -5.06931447983,1.73492455482,-8.84939575195 -5.10532331467,1.73692131042,-8.84578990936 -5.13532400131,1.73791503906,-8.8331785202 -5.15731191635,1.73590326309,-8.80557823181 -5.19432210922,1.73890030384,-8.80297470093 -5.22131729126,1.73789191246,-8.78437042236 -5.26133203506,1.74189126492,-8.78775596619 -5.27232599258,1.74088513851,-8.77296447754 -5.3063325882,1.74288129807,-8.76734542847 -5.3303232193,1.7408708334,-8.74275016785 -5.36232566833,1.74186491966,-8.73114967346 -5.39432859421,1.74285972118,-8.72153663635 -5.41932201385,1.74185049534,-8.69993209839 -5.45532989502,1.74484670162,-8.69433116913 -5.47032976151,1.74484348297,-8.68752670288 -5.49732494354,1.74383485317,-8.66792964935 -5.53633785248,1.74783360958,-8.66930961609 -5.56333398819,1.74782550335,-8.65070438385 -5.59833955765,1.74982106686,-8.64310455322 -5.62633752823,1.74981367588,-8.62649536133 -5.66034173965,1.75180864334,-8.61689662933 -5.68135023117,1.7538087368,-8.62008285522 -5.70434093475,1.75279843807,-8.5944852829 -5.71831941605,1.74778354168,-8.55489826202 -5.76033496857,1.75278329849,-8.55928039551 -5.79634189606,1.75477921963,-8.55267906189 -5.82634162903,1.75577270985,-8.53807353973 -5.85936498642,1.76177847385,-8.55825328827 -5.866335392,1.7547608614,-8.50966453552 -5.90334367752,1.7577573061,-8.50406265259 -5.9303393364,1.75774919987,-8.48446369171 -5.95533323288,1.75674045086,-8.46286010742 -5.98733568192,1.75773501396,-8.45125198364 -6.01533269882,1.75772738457,-8.43265533447 -6.04835414886,1.76373231411,-8.45084095001 -6.07334852219,1.76372373104,-8.42923545837 -6.10034418106,1.76371586323,-8.40963554382 -6.14335870743,1.76771485806,-8.41202735901 -6.16234588623,1.76570379734,-8.38242340088 -6.18333387375,1.76369285583,-8.35284137726 -6.23335790634,1.77069532871,-8.36621379852 -6.23834657669,1.76768803596,-8.34541511536 -6.26133728027,1.76667833328,-8.31982135773 -6.31136035919,1.77368056774,-8.33219718933 -6.32934617996,1.77066886425,-8.29960918427 -6.36134767532,1.77166330814,-8.28700351715 -6.40235996246,1.77666139603,-8.28638744354 -6.42134666443,1.77365028858,-8.25480270386 -6.43634653091,1.77464699745,-8.24700069427 -6.48436594009,1.78064787388,-8.25537872314 -6.50435400009,1.77863740921,-8.22578811646 -6.54036045074,1.78163337708,-8.21817588806 -6.59438514709,1.78863596916,-8.23255634308 -6.62638616562,1.79062986374,-8.21795749664 -6.6513800621,1.78962182999,-8.19635105133 -6.67839241028,1.79362285137,-8.20254516602 -6.70038318634,1.7926132679,-8.17595005035 -6.72837972641,1.79260587692,-8.1563539505 -6.77039194107,1.79760408401,-8.15573310852 -6.80739736557,1.79959976673,-8.14712905884 -6.85841798782,1.8066008091,-8.15650653839 -6.90243148804,1.81159925461,-8.15688991547 -6.89340591431,1.80558717251,-8.11811637878 -6.91940069199,1.80557906628,-8.09552288055 -6.96341371536,1.81057751179,-8.09590435028 -6.80222558975,1.75850701332,-7.8504652977 -6.73913526535,1.73347020149,-7.72394514084 -6.76913642883,1.73546493053,-7.70933771133 -6.76611948013,1.73145627975,-7.68055200577 -6.77610111237,1.7264444828,-7.6419672966 -6.79409074783,1.72443509102,-7.61238002777 -6.79406404495,1.71842038631,-7.56280183792 -6.80805063248,1.71541035175,-7.53020763397 -6.83204603195,1.71440315247,-7.50761842728 -6.83502292633,1.70939016342,-7.46303081512 -6.83500909805,1.70538258553,-7.4372549057 -6.86401081085,1.7073777914,-7.42264270782 -6.86898994446,1.70236504078,-7.37906932831 -6.88798141479,1.70035707951,-7.35247421265 -6.9009680748,1.69734716415,-7.31888771057 -6.91395568848,1.69533777237,-7.28629350662 -6.92894411087,1.69232857227,-7.25470972061 -6.93393611908,1.69032359123,-7.23691415787 -6.94592285156,1.68731367588,-7.20233249664 -6.967918396,1.68730700016,-7.17973184586 -6.9879117012,1.68629944324,-7.15315055847 -6.99989891052,1.68329036236,-7.12055444717 -7.01789093018,1.68228244781,-7.09296607971 -7.02788829803,1.68127918243,-7.08116292953 -7.03787326813,1.67826914787,-7.04458808899 -7.06387233734,1.67826378345,-7.0259885788 -7.08486747742,1.67825710773,-7.00239181519 -7.09285211563,1.67424702644,-6.96481275558 -7.10183811188,1.67123770714,-6.92922544479 -7.12783670425,1.67123222351,-6.9096364975 -7.11982011795,1.66722452641,-6.87984800339 -7.13881444931,1.66621780396,-6.85425615311 -7.16781616211,1.66721320152,-6.83865642548 -7.17480039597,1.66320371628,-6.80107593536 -7.17978429794,1.65919387341,-6.76248979568 -7.20378255844,1.66018819809,-6.74090433121 -7.2227768898,1.65918171406,-6.71630573273 -7.21075820923,1.65317392349,-6.68352174759 -7.23275518417,1.65316808224,-6.66093063354 -7.24474477768,1.65116012096,-6.62934207916 -7.26073694229,1.64915311337,-6.6007604599 -7.27673006058,1.64814627171,-6.57316875458 -7.28371667862,1.64513778687,-6.53758049011 -7.29870843887,1.64313066006,-6.50800275803 -7.30870676041,1.64312791824,-6.49719524384 -7.31269168854,1.63911879063,-6.45861530304 -7.32568264008,1.63711166382,-6.42803287506 -7.3466796875,1.6371062994,-6.40543794632 -7.34265947342,1.63109588623,-6.35986661911 -7.36065387726,1.63008999825,-6.33427858353 -7.37664842606,1.62908387184,-6.30768442154 -7.37563896179,1.62607896328,-6.28589963913 -7.37562227249,1.62107002735,-6.24531793594 -7.39762067795,1.6220651865,-6.22372436523 -7.4096121788,1.61905837059,-6.19314193726 -7.41159725189,1.61505007744,-6.15456056595 -7.43359565735,1.61604523659,-6.13296842575 -7.42858457565,1.61204004288,-6.10818767548 -7.45358514786,1.61303591728,-6.08958911896 -7.46157455444,1.61002886295,-6.05600976944 -7.46756315231,1.60702168941,-6.02142572403 -7.48255777359,1.60601603985,-5.99483156204 -7.49955368042,1.60501074791,-5.96924352646 -7.50754356384,1.60300385952,-5.93566799164 -7.50053167343,1.59899890423,-5.90988922119 -7.52453184128,1.59999477863,-5.89029455185 -7.52551841736,1.59598743916,-5.85271024704 -7.54051351547,1.5949819088,-5.82513046265 -7.55350732803,1.59297657013,-5.79753637314 -7.56149816513,1.59097027779,-5.76495742798 -7.57749414444,1.58996534348,-5.73936605453 -7.57148361206,1.58696091175,-5.71558094025 -7.59348392487,1.58695697784,-5.69498348236 -7.59347057343,1.58294987679,-5.65641117096 -7.61547040939,1.58394598961,-5.63581418991 -7.62346172333,1.58094000816,-5.6032409668 -7.63245439529,1.57893455029,-5.57265520096 -7.65045213699,1.57893037796,-5.54906082153 -7.65344762802,1.577927351,-5.5322728157 -7.6654419899,1.57592225075,-5.50368976593 -7.68243932724,1.57591795921,-5.47909975052 -7.69843673706,1.57591366768,-5.45450258255 -7.70242643356,1.57290780544,-5.41992759705 -7.71842384338,1.57190358639,-5.39533185959 -7.71341514587,1.56889986992,-5.37255477905 -7.72441005707,1.56789517403,-5.34396743774 -7.74040699005,1.56689095497,-5.3193731308 -7.74739933014,1.56488573551,-5.28680276871 -7.75639343262,1.5628811121,-5.25721502304 -7.77239084244,1.56287693977,-5.2316327095 -7.77638244629,1.559871912,-5.19904375076 -7.77937841415,1.55886936188,-5.18226289749 -7.80238008499,1.55986618996,-5.16266441345 -7.80336999893,1.55686080456,-5.1270904541 -7.81436491013,1.55485653877,-5.09850978851 -7.83236408234,1.55485320091,-5.0759100914 -7.82935333252,1.55084776878,-5.0383348465 -7.84134960175,1.54984378815,-5.01075172424 -7.84834814072,1.5498418808,-4.99795532227 -7.85133981705,1.54683721066,-4.96437978745 -7.86133527756,1.54583323002,-4.935795784 -7.88333654404,1.54683029652,-4.91520261765 -7.87432336807,1.54182481766,-4.87462854385 -7.89232254028,1.54182171822,-4.85104370117 -7.9063205719,1.54181826115,-4.82545423508 -7.90131425858,1.53881561756,-4.80467224121 -7.91531181335,1.53781235218,-4.77908420563 -7.9333114624,1.53880918026,-4.75549983978 -7.93530416489,1.53580522537,-4.7229142189 -7.94329929352,1.53380143642,-4.69333457947 -7.96229982376,1.53479874134,-4.67074489594 -7.95829391479,1.53179633617,-4.65096235275 -7.95528507233,1.52879214287,-4.61538362503 -7.97228479385,1.52878928185,-4.59179401398 -7.96527385712,1.52378499508,-4.55322790146 -7.97427034378,1.52278184891,-4.52464818954 -7.98726892471,1.52277898788,-4.49905776978 -7.98726177216,1.51877522469,-4.46548175812 -7.98925876617,1.51777362823,-4.44969463348 -8.01126194,1.51977133751,-4.42910289764 -7.99624824524,1.51376700401,-4.38753080368 -8.00124359131,1.51176393032,-4.35695362091 -8.0222454071,1.51276183128,-4.33635663986 -8.01123523712,1.50775802135,-4.29679107666 -8.02223300934,1.50675547123,-4.27020549774 -8.02623081207,1.50675404072,-4.25542163849 -8.02322387695,1.50275075436,-4.22084951401 -8.03022098541,1.50174820423,-4.19226551056 -8.04922294617,1.50274610519,-4.17066860199 -8.04221439362,1.49874305725,-4.13409996033 -8.04921150208,1.49674069881,-4.10551834106 -8.07021427155,1.49873876572,-4.08492136002 -8.05920696259,1.49473714828,-4.06313800812 -8.07620811462,1.49573504925,-4.03955459595 -8.0852060318,1.49473297596,-4.01197481155 -8.08920288086,1.49273049831,-3.98239016533 -8.08919811249,1.48972821236,-3.94982147217 -8.1092004776,1.49172651768,-3.92823123932 -8.10119533539,1.48872506618,-3.90844535828 -8.11319446564,1.48772323132,-3.8828599453 -8.13519763947,1.48972165585,-3.86226820946 -8.12819099426,1.48571944237,-3.82768845558 -8.13819026947,1.48571753502,-3.80011773109 -8.1451883316,1.48471581936,-3.77253031731 -8.15618801117,1.48371398449,-3.74595379829 -8.15518665314,1.48271310329,-3.73016047478 -8.17118740082,1.48271155357,-3.70657372475 -8.13016986847,1.47270905972,-3.65601944923 -8.15517425537,1.47470784187,-3.63643217087 -8.17617797852,1.47670662403,-3.61583423615 -8.16917228699,1.47270488739,-3.58126616478 -8.17517185211,1.47270417213,-3.56847548485 -8.18917369843,1.47370290756,-3.54389166832 -8.18616867065,1.47070145607,-3.51230883598 -8.19316864014,1.46970009804,-3.4847278595 -8.20516872406,1.46969890594,-3.45914745331 -8.20416641235,1.46669781208,-3.42757868767 -8.19015884399,1.46269643307,-3.39100861549 -8.17215156555,1.457695961,-3.36822724342 -8.07511997223,1.43669474125,-3.29571199417 -8.18615055084,1.45569396019,-3.31406140327 -8.21715831757,1.45969295502,-3.29746079445 -8.22315788269,1.45869207382,-3.26889324188 -8.11212348938,1.43569171429,-3.19238185883 -8.06510734558,1.42369127274,-3.14283919334 -7.95207357407,1.40169167519,-3.0811226368 -7.93906879425,1.39669156075,-3.04754376411 -7.99308300018,1.40569078922,-3.03994441032 -8.02009010315,1.40869021416,-3.02234435081 -7.95707130432,1.39469075203,-2.96781158447 -7.94006633759,1.38869082928,-2.9322476387 -7.86404466629,1.37269186974,-2.87371945381 -7.87604761124,1.37369179726,-2.86491465569 -7.83203554153,1.36369264126,-2.81936907768 -7.84804010391,1.36469268799,-2.79777884483 -7.88504981995,1.37069225311,-2.78417468071 -7.84103822708,1.35969340801,-2.73962402344 -7.83403635025,1.35669398308,-2.70905375481 -7.73701190948,1.33769619465,-2.65932130814 -7.69600200653,1.32869780064,-2.61677098274 -7.65499210358,1.3186994791,-2.57422637939 -7.65299320221,1.31670022011,-2.54664969444 -7.63598966599,1.31170153618,-2.514077425 -7.64399337769,1.31170225143,-2.49049043655 -7.60498523712,1.30270445347,-2.44993972778 -7.53997039795,1.28970682621,-2.41418743134 -7.52096796036,1.28470861912,-2.38063383102 -7.57198190689,1.2927082777,-2.37202477455 -7.43795204163,1.26571381092,-2.30052685738 -7.45895910263,1.26871454716,-2.281935215 -7.44095802307,1.26371669769,-2.25036692619 -7.48997116089,1.27171647549,-2.24076128006 -7.45296430588,1.26371860504,-2.21599197388 -7.35394430161,1.24372386932,-2.15847325325 -7.34994697571,1.24172580242,-2.13190031052 -7.3629527092,1.24272704124,-2.11130833626 -7.36895704269,1.24272871017,-2.08773303032 -7.30394649506,1.22873330116,-2.04318380356 -7.34695863724,1.23573338985,-2.03157997131 -7.27194452286,1.22073769569,-1.9958435297 -7.24294281006,1.2147411108,-1.96228671074 -7.21994113922,1.2087444067,-1.93072712421 -7.24395036697,1.21174550056,-1.91412365437 -7.22795057297,1.2077485323,-1.88456463814 -7.20795059204,1.20275175571,-1.85499095917 -7.19194984436,1.19975376129,-1.83821320534 -7.17395019531,1.19475698471,-1.80963599682 -7.14394950867,1.18876111507,-1.77707922459 -7.11694812775,1.1817650795,-1.74552237988 -7.11295223236,1.18076789379,-1.72094285488 -7.09295320511,1.17577159405,-1.69236850739 -7.13496589661,1.18177199364,-1.67977023125 -7.08895969391,1.17277598381,-1.65600442886 -7.13497304916,1.18077623844,-1.64440190792 -7.12297582626,1.1767796278,-1.61782968044 -7.10397720337,1.17278373241,-1.58926677704 -7.03397035599,1.15879070759,-1.54872214794 -6.98196697235,1.14779698849,-1.51218450069 -6.99697494507,1.1497989893,-1.49358558655 -6.9589715004,1.14280295372,-1.47281980515 -6.97998094559,1.14580476284,-1.45522642136 -6.96598434448,1.14180898666,-1.4286648035 -6.97299098969,1.14181172848,-1.40807306767 -6.95399427414,1.13781630993,-1.38051462173 -6.95700025558,1.13781940937,-1.35892784595 -6.89999723434,1.12582659721,-1.32338690758 -6.92400455475,1.12982678413,-1.31758248806 -6.9020075798,1.12483179569,-1.29002285004 -6.89701318741,1.12383568287,-1.26645028591 -6.87501621246,1.11884069443,-1.23987746239 -6.89102506638,1.12084317207,-1.22128510475 -6.85302591324,1.11284959316,-1.19073879719 -6.87103176117,1.11585009098,-1.1839287281 -6.89604234695,1.11985206604,-1.16634523869 -6.92005252838,1.12285387516,-1.14875638485 -6.85705041885,1.1108622551,-1.11519765854 -6.86705827713,1.11186552048,-1.09462332726 -6.86506509781,1.11086952686,-1.07205021381 -6.95008325577,1.12586653233,-1.06641101837 -6.87107658386,1.11087477207,-1.04067099094 -6.82807826996,1.10288214684,-1.01111531258 -6.85808897018,1.10688376427,-0.994522333145 -6.8500957489,1.10488843918,-0.970955252647 -6.83410072327,1.10189366341,-0.94736802578 -6.76809978485,1.08890330791,-0.914823949337 -6.8391160965,1.1009016037,-0.904219686985 -6.81011676788,1.09590613842,-0.888451397419 -6.79812288284,1.09291112423,-0.865862429142 -6.7921295166,1.09091603756,-0.843289911747 -6.77913618088,1.087921381,-0.81972104311 -8.84636592865,1.45774400234,-1.10202896595 -6.76415061951,1.08393144608,-0.774575710297 -6.82816505432,1.09493017197,-0.761969447136 -6.78116369247,1.08693647385,-0.74519443512 -6.81317520142,1.09193789959,-0.728591620922 -6.74217605591,1.07794892788,-0.697063624859 -6.72718286514,1.07495474815,-0.674481928349 -6.72419118881,1.073959589,-0.652906477451 -8.89240074158,1.460760355,-0.89818239212 -6.70320177078,1.06996846199,-0.618552744389 -6.72721242905,1.0739710331,-0.599970340729 -6.71421957016,1.07097685337,-0.577398836613 -6.72622919083,1.0729804039,-0.55781263113 -6.7232375145,1.07198512554,-0.537220478058 -6.72524642944,1.07198989391,-0.515656411648 -6.73525571823,1.07299363613,-0.496065437794 -6.75226163864,1.07599437237,-0.487267613411 -6.81127500534,1.08599340916,-0.471665412188 -6.7622795105,1.07700288296,-0.446105748415 -6.83329391479,1.0890007019,-0.431492239237 -6.76229715347,1.0760127306,-0.403949767351 -6.70030212402,1.06502401829,-0.37740701437 -6.6853055954,1.06202805042,-0.365627557039 -6.70631599426,1.06503081322,-0.347028702497 -6.70632505417,1.0650357008,-0.326445043087 -6.79634046555,1.08103144169,-0.311830759048 -6.71734428406,1.06604480743,-0.28528881073 -6.76235628128,1.07404506207,-0.267684221268 -6.70336198807,1.06305646896,-0.243130460382 -6.86437654495,1.09204185009,-0.242273539305 -6.7853808403,1.07705521584,-0.216725453734 -6.79139041901,1.07805967331,-0.196142092347 -6.78839969635,1.07706522942,-0.174572825432 -6.87241315842,1.09206116199,-0.15794980526 -6.79041910172,1.07707548141,-0.132419556379 -6.89243268967,1.09506905079,-0.116773948073 -7.06944656372,1.1270519495,-0.112911701202 -6.9424495697,1.10407137871,-0.086389310658 -6.84145498276,1.08608818054,-0.0608681924641 -6.84846448898,1.08709263802,-0.0402799621224 -6.82747268677,1.0831001997,-0.018707441166 -6.91848611832,1.09909510612,-8.44052483444e-05 -6.99549436569,1.113088727,0.00874066911638 -6.98050308228,1.11009573936,0.0303187128156 -9.04058361053,1.47485768795,0.0129242269322 -6.9575214386,1.10610926151,0.0744514912367 -6.62952041626,1.04715359211,0.0998769178987 -6.66153144836,1.05315518379,0.119481928647 -6.6265411377,1.04716527462,0.14102819562 -6.63954687119,1.04916632175,0.150830864906 -6.68355798721,1.0571668148,0.171426400542 -6.78357124329,1.07516026497,0.192055001855 -6.78758096695,1.07516527176,0.212642431259 -6.68558931351,1.05718362331,0.233165577054 -6.61459827423,1.04519808292,0.252717345953 -6.61260890961,1.04420411587,0.273290783167 -6.6086139679,1.04420745373,0.283085495234 -6.61062479019,1.04421305656,0.30366179347 -6.63163614273,1.04821634293,0.324255526066 -9.15867710114,1.49590146542,0.409035176039 -6.71765899658,1.0632174015,0.368435353041 -6.69066905975,1.05922663212,0.388008147478 -6.66067934036,1.05323636532,0.407573908567 -6.6196846962,1.04624462128,0.416345208883 -6.6486954689,1.05124688148,0.437936723232 -6.68270635605,1.05824828148,0.459538698196 -6.77271795273,1.07424259186,0.484160631895 -6.82672834396,1.08324146271,0.507762670517 -6.75273942947,1.07025718689,0.525302290916 -6.65374565125,1.05327343941,0.53103518486 -6.61975669861,1.04728400707,0.549600303173 -6.65176725388,1.05328571796,0.57120937109 -6.56677913666,1.03830325603,0.586744070053 -6.59479045868,1.04330587387,0.609326779842 -6.67580080032,1.05830097198,0.634949803352 -6.62481307983,1.04931414127,0.652494549751 -6.61681842804,1.04831814766,0.661298334599 -6.59783029556,1.04532718658,0.680858135223 -6.67084121704,1.05832350254,0.707463204861 -6.5988535881,1.04533970356,0.722012996674 -6.5628657341,1.03935098648,0.739572107792 -6.56187677383,1.03935718536,0.759164869785 -6.74588537216,1.07333815098,0.796820580959 -6.77089071274,1.07733774185,0.809621691704 -6.53990697861,1.03637647629,0.808100521564 -6.55891799927,1.04038023949,0.830681085587 -6.58792972565,1.04638278484,0.854269444942 -6.52594232559,1.03539776802,0.867828190327 -6.51995515823,1.03440511227,0.887406527996 -6.48096179962,1.02741396427,0.893179893494 -9.08689689636,1.49304771423,1.21391987801 -9.09190559387,1.49505221844,1.24250650406 -9.04491519928,1.48706424236,1.26506519318 -6.95299434662,1.11337220669,1.03270280361 -6.82501077652,1.09139716625,1.03822433949 -6.48503494263,1.03145313263,1.01564705372 -6.46404123306,1.02745938301,1.02243971825 -6.47705364227,1.03046441078,1.0450129509 -6.54606342316,1.04346096516,1.07462716103 -6.4560790062,1.02748072147,1.08217287064 -6.48009061813,1.03248417377,1.1067456007 -6.44010448456,1.02549695969,1.12130534649 -6.45111656189,1.02850210667,1.14289653301 -6.47712135315,1.03350150585,1.15670394897 -6.45813512802,1.03051114082,1.17427265644 -6.46814775467,1.03251671791,1.19684350491 -6.45816040039,1.03152489662,1.21542322636 -6.4681725502,1.03353023529,1.23701643944 -6.4201874733,1.02554440498,1.2495714426 -6.34520435333,1.01256275177,1.2571169138 -6.41720724106,1.02655529976,1.27993166447 -6.48721599579,1.03955161572,1.31254303455 -6.45623016357,1.03456306458,1.32711839676 -6.43924379349,1.03257274628,1.34468746185 -6.43525743484,1.03258037567,1.36426866055 -6.46326875687,1.03758335114,1.39084410667 -6.43827629089,1.03359043598,1.39563822746 -6.45328807831,1.03759515285,1.41922163963 -6.4493021965,1.03760313988,1.43978452682 -6.44731473923,1.03761029243,1.45937621593 -6.44932794571,1.0386172533,1.4809461832 -6.44534111023,1.0386248827,1.50052952766 -6.38535881042,1.02864170074,1.50907409191 -6.42536258698,1.03663897514,1.52787971497 -6.46337270737,1.04364001751,1.55648028851 -6.61837482452,1.07262253761,1.6111266613 -6.44939994812,1.04265642166,1.5946418047 -6.45741319656,1.04566264153,1.6182063818 -6.43042850494,1.04067420959,1.63277745247 -6.44143438339,1.04367601871,1.64557504654 -6.44844722748,1.04568207264,1.66815626621 -6.44746017456,1.04668951035,1.68873786926 -6.44647359848,1.04669690132,1.70931982994 -6.47048568726,1.05270051956,1.73689484596 -6.45450019836,1.04971015453,1.75347924232 -6.44751358032,1.0497187376,1.7730512619 -6.43352174759,1.04772460461,1.77983999252 -6.36154127121,1.03574371338,1.7823933363 -6.55853843689,1.07271909714,1.85503637791 -6.46755981445,1.05674147606,1.85258221626 -6.44457578659,1.05375266075,1.86814510822 -6.41859102249,1.04976415634,1.88172757626 -6.48359966278,1.06276106834,1.9213193655 -6.4756064415,1.06176590919,1.92912018299 -6.45862150192,1.05977618694,1.94569611549 -6.44363689423,1.05778622627,1.96326267719 -6.47564792633,1.06478846073,1.9938532114 -6.43566560745,1.05880272388,2.00440740585 -6.44867801666,1.06180787086,2.02900457382 -6.39369678497,1.05282461643,2.03455877304 -6.40070343018,1.05482721329,2.04735088348 -6.4287147522,1.06083011627,2.07694602013 -6.41073036194,1.05884087086,2.09351015091 -6.41774368286,1.06184732914,2.11709475517 -6.42675685883,1.06385338306,2.14167451859 -6.43976926804,1.06785869598,2.16726279259 -6.41377878189,1.06386697292,2.17004108429 -6.40779352188,1.0638756752,2.18962287903 -6.40680789948,1.06488358974,2.21119904518 -6.41382169724,1.06689023972,2.2357711792 -6.43683338165,1.07289397717,2.26535630226 -6.35785627365,1.05891525745,2.26090931892 -6.36386966705,1.06192195415,2.28449511528 -6.4708647728,1.08190727234,2.33132839203 -6.46987962723,1.0829154253,2.35389447212 -6.4218993187,1.07593142986,2.35945916176 -6.40591526031,1.07394194603,2.37603259087 -6.37593317032,1.06995499134,2.38760137558 -6.36394882202,1.06896483898,2.40518116951 -6.36996269226,1.07097172737,2.42975664139 -6.37496900558,1.07297468185,2.44254994392 -6.39198160172,1.07697975636,2.47113180161 -6.41599369049,1.08298361301,2.50271177292 -6.39601039886,1.08099472523,2.51729273796 -6.41302251816,1.08499968052,2.54588222504 -6.40503787994,1.08500897884,2.56545805931 -6.39404678345,1.08401501179,2.57323122025 -6.3940615654,1.08502304554,2.59581017494 -6.40107488632,1.08802950382,2.62040615082 -6.54707193375,1.11801195145,2.70102310181 -6.66407108307,1.14099907875,2.77064204216 -6.49110794067,1.11003768444,2.72516512871 -6.4131321907,1.09705936909,2.71672177315 -6.41613960266,1.0980629921,2.72951078415 -6.41415452957,1.09907138348,2.75208282471 -6.42716741562,1.10307717323,2.78066372871 -8.40291690826,1.48373126984,3.6249499321 -6.7091588974,1.16104269028,2.94492578506 -6.46420717239,1.11509490013,2.86640810966 -6.42721939087,1.10910534859,2.86218953133 -6.43723297119,1.11211168766,2.88977408409 -6.39225435257,1.10512804985,2.89432907104 -6.44326257706,1.11712694168,2.93992638588 -6.52426528931,1.13412034512,2.99854421616 -6.51428127289,1.13413023949,3.01812028885 -6.4363079071,1.12115263939,3.00766706467 -6.54030036926,1.14213788509,3.06648778915 -6.50532054901,1.1371524334,3.07505249977 -6.55032920837,1.14715242386,3.11964917183 -6.48135375977,1.13617312908,3.11220765114 -6.58635377884,1.15816235542,3.18581080437 -6.49538230896,1.14218699932,3.16736984253 -6.55338811874,1.15518450737,3.21897149086 -6.63438415527,1.1721739769,3.26978635788 -6.45042657852,1.13821589947,3.20729994774 -6.41344738007,1.13323104382,3.21386837959 -6.41346263885,1.1342394352,3.23844432831 -6.3944811821,1.13325130939,3.25401091576 -6.42849063873,1.14125323296,3.29461169243 -6.3975110054,1.13726723194,3.30417585373 -6.39251947403,1.13727235794,3.31396436691 -6.41853094101,1.14427602291,3.35155439377 -6.37455272675,1.1372923851,3.35411882401 -6.39656496048,1.14429664612,3.38971185684 -6.45557165146,1.15829443932,3.44628787041 -6.44858789444,1.15830421448,3.46786499023 -6.44359636307,1.15830922127,3.4776570797 -6.4956035614,1.17130804062,3.53025269508 -6.35664081573,1.14534211159,3.48179721832 -6.4066491127,1.15734148026,3.53437829018 -6.3706703186,1.1523566246,3.53995490074 -6.35268878937,1.1513684988,3.555529356 -6.33870649338,1.15037953854,3.57310676575 -6.35771131516,1.15538012981,3.59590673447 -6.34672880173,1.15539073944,3.61548066139 -6.36974048615,1.16239511967,3.65406274796 -6.3777551651,1.16640222073,3.68463873863 -6.33577823639,1.16041874886,3.68719959259 -6.33979320526,1.16342651844,3.71478772163 -6.33081054688,1.16343677044,3.73536705971 -6.33681726456,1.16543996334,3.75215244293 -6.33383369446,1.16744935513,3.77672600746 -6.42283439636,1.18844091892,3.85433745384 -6.52883195877,1.21242940426,3.94295048714 -6.37887382507,1.18446683884,3.88246917725 -6.33689641953,1.17748320103,3.88305187225 -6.33491277695,1.17949223518,3.9086265564 -6.3379201889,1.18149590492,3.92342209816 -6.37592983246,1.19249761105,3.9739985466 -6.32395458221,1.18351602554,3.96857261658 -6.35196638107,1.19251966476,4.01315116882 -6.3249874115,1.18953359127,4.02371931076 -6.33600091934,1.19353997707,4.05730628967 -6.33200979233,1.1945451498,4.06809949875 -6.32402706146,1.19555556774,4.09067058563 -6.29404878616,1.19156980515,4.09825229645 -6.36905097961,1.20956432819,4.17384576797 -6.42105817795,1.22356331348,4.23543310165 -6.31409358978,1.20359253883,4.19398593903 -6.32110071182,1.20659565926,4.21277141571 -6.39510345459,1.22559046745,4.28936576843 -6.37212371826,1.22260344028,4.30194616318 -6.34614515305,1.22061753273,4.31351041794 -6.36115789413,1.22662317753,4.35110330582 -6.5141453743,1.26160264015,4.48272037506 -6.47916841507,1.25761818886,4.48828983307 -6.38719415665,1.23864066601,4.44104480743 -6.3112244606,1.225664258,4.41760873795 -6.28724622726,1.22367787361,4.43017482758 -6.31925630569,1.23368048668,4.48076629639 -6.30227565765,1.2326925993,4.49734830856 -6.34628391266,1.24469316006,4.557929039 -6.33430242538,1.24570441246,4.57850885391 -6.29031944275,1.23771750927,4.56228256226 -6.31833028793,1.24672091007,4.61087846756 -7.17517900467,1.43656229973,5.25669002533 -7.15119981766,1.43557596207,5.2732591629 -7.03023958206,1.41160845757,5.21880483627 -7.12823629379,1.43759834766,5.324406147 -6.63335037231,1.33170413971,4.99285173416 -7.12126207352,1.4406131506,5.3707652092 -6.63137578964,1.33671808243,5.03921699524 -6.51941490173,1.31474936008,4.9877576828 -6.37745952606,1.2867859602,4.91131019592 -6.34348297119,1.28280186653,4.9168753624 -6.35449790955,1.28880882263,4.95645475388 -6.38150024414,1.29580783844,4.9922580719 -6.31053113937,1.28383100033,4.96881914139 -6.29955101013,1.28484249115,4.99238300323 -6.28856992722,1.28585374355,5.01496124268 -6.30558300018,1.29285955429,5.05954790115 -6.31959676743,1.29986584187,5.1021323204 -6.2776222229,1.29388332367,5.10069847107 -6.3896074295,1.32086586952,5.20651292801 -6.29864406586,1.30389308929,5.16606426239 -6.2586684227,1.29891014099,5.16563558578 -6.32967042923,1.31790518761,5.25523900986 -6.36867904663,1.33090662956,5.31982946396 -6.40768861771,1.34390842915,5.38640213013 -6.30872583389,1.32493710518,5.33696269989 -6.28473949432,1.32094657421,5.3337430954 -6.35874128342,1.34194111824,5.42933559418 -6.26677799225,1.32496857643,5.38489580154 -6.36877250671,1.35195744038,5.50450563431 -6.32979774475,1.34697437286,5.50507640839 -6.30482053757,1.34498894215,5.51863574982 -6.280834198,1.34199798107,5.51343774796 -6.26485443115,1.34201061726,5.53400754929 -6.27187013626,1.34701859951,5.5745844841 -6.26288938522,1.35002970695,5.6011595726 -6.31989431381,1.36702764034,5.68575763702 -6.39189577103,1.38802266121,5.78534936905 -6.59986686707,1.44199037552,6.00797557831 -6.58887863159,1.44199728966,6.0167593956 -6.43193006516,1.40903806686,5.91130304337 -6.37595939636,1.40005874634,5.89686584473 -6.43896245956,1.41905534267,5.99046564102 -6.41498470306,1.41806948185,6.00503969193 -6.29202985764,1.39310371876,5.92857885361 -6.3600320816,1.41409945488,6.02817869186 -6.35804080963,1.41510462761,6.04496526718 -6.2350859642,1.3901386261,5.96552085876 -6.32508277893,1.41613006592,6.0881152153 -6.29610681534,1.41414535046,6.09768819809 -6.28412723541,1.41615736485,6.12425661087 -6.26314926147,1.41517090797,6.14083862305 -6.26215791702,1.41717576981,6.15862894058 -6.24817895889,1.41818833351,6.18319940567 -6.23219966888,1.41920077801,6.20478200912 -6.22222042084,1.42221260071,6.23434305191 -6.20024204254,1.42122638226,6.24992609024 -6.18926239014,1.42323827744,6.27750015259 -6.17628288269,1.42425012589,6.30208539963 -6.16029500961,1.4232583046,6.30586481094 -6.14131736755,1.42327177525,6.32543754578 -6.13533639908,1.42628240585,6.35801696777 -6.10436153412,1.42429840565,6.36558437347 -6.08638334274,1.42431163788,6.3861579895 -6.08240270615,1.42832219601,6.42173099518 -6.06841421127,1.42732977867,6.42652082443 -6.04743719101,1.42734360695,6.44409370422 -6.04645490646,1.43235349655,6.48267316818 -6.01947927475,1.43036866188,6.49424219131 -6.00350141525,1.431381464,6.51682043076 -5.99252176285,1.43339347839,6.54539442062 -5.96654510498,1.4324079752,6.55598402023 -5.96155548096,1.4334141016,6.57176208496 -5.95157623291,1.43642580509,6.60133934021 -5.92560052872,1.43444085121,6.61390829086 -5.90662288666,1.43545436859,6.63348579407 -5.89964199066,1.43846535683,6.66607046127 -5.87566614151,1.43848025799,6.68163204193 -5.85168981552,1.43749463558,6.69521331787 -5.85969686508,1.44149792194,6.725004673 -5.83672046661,1.44151234627,6.74057817459 -5.81574440002,1.44152653217,6.75914525986 -5.80976295471,1.4455370903,6.79273843765 -5.77978849411,1.4435530901,6.80030965805 -5.76181173325,1.44456672668,6.82287311554 -5.74983263016,1.44657886028,6.85045814514 -5.73184585571,1.44458723068,6.85024690628 -5.71586847305,1.44560050964,6.87481546402 -5.70389032364,1.44861292839,6.90438365936 -5.67491531372,1.44662857056,6.9119644165 -5.65993738174,1.44864153862,6.9375371933 -5.6499581337,1.45165324211,6.9681224823 -5.63896989822,1.45166039467,6.97690677643 -5.62399196625,1.45367312431,7.00149106979 -5.60901403427,1.45568621159,7.02805805206 -5.59003734589,1.45569992065,7.04863500595 -5.56906080246,1.4567142725,7.06720685959 -3.45560193062,0.857151508331,4.43349456787 -3.43262648582,0.855165719986,4.4310874939 -3.43263697624,0.857171058655,4.44586420059 -3.41266179085,0.8551851511,4.44843864441 -3.40668225288,0.857196092606,4.46802902222 -5.46019029617,1.45979082584,7.17587566376 -5.44621276855,1.46280348301,7.20345258713 -5.41423940659,1.45982027054,7.20802021027 -5.41424846649,1.46282482147,7.22982215881 -5.39327287674,1.46383929253,7.24938821793 -5.37129640579,1.46385359764,7.26596879959 -5.34532213211,1.46286904812,7.27853679657 -5.33534383774,1.46688115597,7.31211423874 -5.31336784363,1.46689558029,7.32968711853 -5.29239177704,1.46690964699,7.34727287292 -5.28340387344,1.46791648865,7.35905790329 -5.2644276619,1.46893060207,7.38162469864 -5.24445152283,1.46994459629,7.40120649338 -5.22047615051,1.46995937824,7.41479110718 -5.20149993896,1.47097337246,7.43735980988 -5.18152427673,1.47198748589,7.45793437958 -5.16054868698,1.47300195694,7.47750520706 -5.1475610733,1.47200942039,7.48230218887 -5.12658548355,1.47302353382,7.50088214874 -5.10860919952,1.47503745556,7.52445745468 -5.09163331985,1.47705101967,7.55002975464 -5.06465911865,1.47606658936,7.56060314178 -5.04568338394,1.47708070278,7.58317708969 -5.02570724487,1.47809457779,7.6027636528 -5.01671934128,1.47910165787,7.61554479599 -4.99574375153,1.4801158905,7.63412809372 -4.97576856613,1.48113024235,7.65669155121 -4.9537935257,1.48214483261,7.67427158356 -4.93381786346,1.48315882683,7.69485235214 -4.91284227371,1.48417329788,7.71442937851 -4.90485429764,1.48518025875,7.7292098999 -4.88187980652,1.48619496822,7.74578666687 -4.86290407181,1.48820912838,7.76935911179 -4.83992862701,1.48822379112,7.7849445343 -4.81695413589,1.48823857307,7.80152225494 -4.79797887802,1.49025261402,7.82509660721 -4.77800321579,1.49126672745,7.84667491913 -4.77001571655,1.49327361584,7.86145925522 -4.74504137039,1.49328887463,7.87503623962 -4.72606611252,1.49530303478,7.89960670471 -4.69909238815,1.49431848526,7.90918827057 -4.67811775208,1.49533307552,7.92976427078 -4.65314388275,1.49534845352,7.94433450699 -4.63616704941,1.49836182594,7.96992588043 -4.62518072128,1.49836933613,7.98070430756 -4.60620546341,1.50038349628,8.00527954102 -4.58523035049,1.50239789486,8.02585887909 -4.56225585938,1.50341284275,8.04343509674 -4.53828239441,1.50342786312,8.0590133667 -4.5193066597,1.50544178486,8.08259868622 -4.5103187561,1.50644874573,8.09638404846 -4.48234558105,1.50546467304,8.10496139526 -4.46637010574,1.50947833061,8.13653182983 -4.4423956871,1.50949311256,8.1511182785 -4.42442035675,1.51250720024,8.17869377136 -4.40244626999,1.51352202892,8.19926643372 -4.37847232819,1.51453709602,8.21584129333 -4.36748552322,1.51554453373,8.22563171387 -4.34551095963,1.51655936241,8.24620628357 -4.32553625107,1.51857352257,8.26978778839 -4.29856348038,1.5185893774,8.28135967255 -4.2795882225,1.52060341835,8.30694198608 -4.25661420822,1.52161824703,8.32452583313 -4.23963928223,1.52563214302,8.35709095001 -4.23565006256,1.52963805199,8.38088417053 -4.21667575836,1.53265225887,8.40845870972 -4.19570064545,1.53466665745,8.43104171753 -4.16272974014,1.5316838026,8.43061542511 -4.16874742508,1.54469275475,8.50820064545 -3.7728767395,1.39478266239,7.76274204254 -3.67191457748,1.35880804062,7.58452892303 -3.62594723701,1.349827528,7.54910564423 -3.59297633171,1.34584462643,7.54068040848 -3.55500650406,1.33986222744,7.5192694664 -3.5270345211,1.33787822723,7.52084350586 -3.49206471443,1.33289575577,7.50741672516 -3.46109318733,1.32991206646,7.50099849701 -3.44410777092,1.32692050934,7.49379348755 -3.41113758087,1.3239376545,7.48436307907 -3.38516545296,1.3229534626,7.48993396759 -3.35619354248,1.31996953487,7.4875125885 -3.32822132111,1.31798529625,7.48609828949 -3.29824995995,1.31500148773,7.48067951202 -3.26627898216,1.31101810932,7.47026157379 -3.2542924881,1.31102573872,7.47504663467 -3.23031973839,1.3110408783,7.4836230278 -3.19834899902,1.3070577383,7.47320175171 -3.16737794876,1.30307412148,7.46477937698 -3.14640426636,1.30408871174,7.47936153412 -3.11243414879,1.29910588264,7.46393585205 -3.07846355438,1.29412269592,7.44552707672 -3.0714764595,1.29712963104,7.46330404282 -3.04150533676,1.29414582253,7.45588445663 -3.01353311539,1.29116165638,7.45246887207 -2.98656129837,1.28917729855,7.45204925537 -2.95958924294,1.28819298744,7.45162820816 -2.93661665916,1.28820812702,7.46220159531 -2.92063093185,1.286216259,7.45399999619 -2.9046561718,1.28922998905,7.48257350922 -2.87068653107,1.28424715996,7.4641494751 -2.8467130661,1.28326189518,7.46874189377 -2.81574249268,1.28027832508,7.45731925964 -2.78677129745,1.27729463577,7.45089626312 -2.7617995739,1.27630996704,7.45547056198 -2.75281190872,1.2773168087,7.46526956558 -2.72584033012,1.27533245087,7.46384620667 -2.70286726952,1.27534735203,7.47242879868 -2.67689585686,1.27436316013,7.47499752045 -2.64692473412,1.27137935162,7.46358156204 -2.62795066833,1.27339327335,7.48316478729 -2.60796642303,1.26840233803,7.46295642853 -2.58999204636,1.27141618729,7.48553943634 -2.56202149391,1.2694324255,7.48210716248 -2.54004764557,1.26944684982,7.49169874191 -2.51307630539,1.26846253872,7.48927497864 -2.49210309982,1.26947724819,7.50485038757 -2.46813035011,1.26849198341,7.50844240189 -2.45614480972,1.26949977875,7.5132226944 -2.43717026711,1.27151358128,7.53181600571 -2.41519761086,1.27252840996,7.54538869858 -2.39122533798,1.27254366875,7.5519657135 -2.37525033951,1.27655684948,7.58155488968 -2.35727620125,1.28057074547,7.60713529587 -2.3383026123,1.28258490562,7.62971591949 -2.33231472969,1.28659129143,7.65350198746 -2.31334090233,1.2896052599,7.67608642578 -2.29936623573,1.29661858082,7.71865653992 -2.2933883667,1.30762994289,7.78524637222 -2.2794137001,1.31464326382,7.82981681824 -2.27443623543,1.32665479183,7.90539312363 -2.25346255302,1.32966899872,7.92298412323 -2.25447320938,1.33867430687,7.97576570511 -2.25449347496,1.35468423367,8.06935787201 -2.26251292229,1.37669348717,8.19992446899 -2.25153684616,1.38770616055,8.26150131226 -2.23656225204,1.39471948147,8.30808353424 -2.19359493256,1.38273775578,8.24767684937 -2.22759580612,1.41473662853,8.4304599762 -2.23661470413,1.44074559212,8.57602977753 -2.23863506317,1.46175563335,8.69560813904 -2.23665618896,1.47876620293,8.79919815063 -2.42664361,1.66175091267,9.81233978271 -2.40167212486,1.6667662859,9.84491443634 -2.38768601418,1.66677379608,9.84971904755 -2.35871601105,1.66879010201,9.86828804016 -2.3277451992,1.66780638695,9.87187767029 -2.29677534103,1.66782271862,9.87845802307 -2.26580548286,1.66883921623,9.88703346252 -2.23583555222,1.66985559464,9.89960861206 -2.22184991837,1.67086350918,9.90840244293 -2.19287919998,1.67187929153,9.92298698425 -2.16090941429,1.6708958149,9.92357254028 -2.13493847847,1.67591142654,9.95714378357 -2.10696721077,1.67892694473,9.97673034668 -2.0779967308,1.68094313145,9.99430942535 -2.05202531815,1.68595850468,10.026889801 -2.05403518677,1.70096325874,10.1166820526 -2.02906394005,1.70797860622,10.1602525711 -2.00209283829,1.71199429035,10.1908340454 -1.97612142563,1.71800947189,10.2254209518 -1.94315218925,1.71702623367,10.2260026932 -1.91218245029,1.71804249287,10.2385807037 -1.88121259212,1.71905887127,10.250161171 -1.85822951794,1.71206831932,10.2119579315 -1.82126176357,1.70708572865,10.1925325394 -1.7892922163,1.70710217953,10.1961174011 -1.75632286072,1.7061188221,10.1937017441 -1.72235405445,1.70413565636,10.1882810593 -1.69038450718,1.70315206051,10.1918640137 -1.65841495991,1.70316839218,10.1964464188 -1.64243042469,1.70317673683,10.1992359161 -1.61046111584,1.70419323444,10.2058143616 -1.57849144936,1.70320951939,10.2083997726 -1.54352247715,1.69922626019,10.1889896393 -1.51355290413,1.70224237442,10.2115621567 -1.47858428955,1.69925940037,10.1941461563 -1.46259975433,1.69926762581,10.1979341507 -1.43063032627,1.69928395748,10.2005186081 -1.39566195011,1.69530081749,10.1850967407 -1.36269283295,1.69431746006,10.180680275 -1.33072292805,1.69233334064,10.1772727966 -1.29775381088,1.69134998322,10.1728553772 -1.26478517056,1.69036662579,10.1724300385 -1.24980008602,1.69137454033,10.180223465 -1.21683132648,1.69039106369,10.1778020859 -1.18386209011,1.68840754032,10.1713857651 -1.15289247036,1.69042348862,10.1819696426 -1.1199233532,1.68843984604,10.1735553741 -1.08795404434,1.68845617771,10.1771364212 -1.0719691515,1.687464118,10.1749324799 -1.03800094128,1.68548095226,10.1635065079 -1.00603115559,1.68349695206,10.1590976715 -0.974062383175,1.68451321125,10.1676721573 -0.94209253788,1.68252921104,10.1602659225 -0.910123229027,1.6825453043,10.1608505249 -0.879153549671,1.68456125259,10.1724348068 -0.862169444561,1.68256962299,10.166220665 -0.832199394703,1.68658542633,10.1878089905 -0.799230933189,1.68560183048,10.1863822937 -0.766262054443,1.6836181879,10.1759653091 -0.735291898251,1.68363380432,10.1785593033 -0.703323245049,1.68565011024,10.1921319962 -0.671353638172,1.68466603756,10.1857233047 -0.654369115829,1.68067419529,10.167517662 -0.62340015173,1.68569028378,10.1960916519 -0.589431285858,1.67870664597,10.1586790085 -0.559461534023,1.68572223186,10.1952619553 -0.525492966175,1.67873871326,10.1588468552 -0.49352362752,1.67775464058,10.1564302444 -0.462553709745,1.67877018452,10.163022995 -0.445569872856,1.67777860165,10.1558055878 -0.413600385189,1.67479431629,10.1433954239 -0.381631344557,1.67581045628,10.1479759216 -0.350661545992,1.67782604694,10.1605672836 -0.317693114281,1.67584240437,10.1491422653 -0.285723775625,1.67385816574,10.1377286911 -0.270738512278,1.67586576939,10.1515283585 -0.237770080566,1.67288208008,10.1351041794 -0.206799969077,1.67289745808,10.1307010651 -0.174831047654,1.67491340637,10.1452789307 -0.142861768603,1.67192924023,10.1248664856 -0.110892698169,1.67194509506,10.1254482269 -0.0789236724377,1.67296087742,10.1330299377 -0.0629391074181,1.67196893692,10.1268224716 -0.0319690927863,1.67398416996,10.1364164352 --0.0159841384739,1.67800807953,9.75278377533 --0.0469533726573,1.67602372169,9.74436283112 --0.0769235491753,1.67403900623,9.73195552826 --0.107892908156,1.67705464363,9.7485370636 --0.137862771749,1.67006981373,9.70812320709 --0.168832346797,1.6760853529,9.74071025848 --0.184816449881,1.67609345913,9.7384929657 --0.214786678553,1.6761084795,9.73708629608 --0.245755970478,1.67612409592,9.7386674881 --0.275726169348,1.67613911629,9.73526096344 --0.306695282459,1.67515468597,9.72783851624 --0.336665213108,1.67316997051,9.71442508698 --0.367634683847,1.67418539524,9.72301006317 --0.381620198488,1.6701925993,9.70080947876 --0.413589119911,1.67520833015,9.72438812256 --0.442559063435,1.66822338104,9.68297195435 --0.474528580904,1.67523872852,9.72056293488 --0.50449860096,1.67425382137,9.71315288544 --0.534468531609,1.67326891422,9.70273971558 --0.550452649593,1.67327690125,9.70352363586 --0.581422150135,1.67429220676,9.7081079483 --0.611392259598,1.67430710793,9.70370006561 --0.642361700535,1.67432248592,9.70528316498 --0.673331260681,1.67633759975,9.70986938477 --0.703301250935,1.67535257339,9.70345973969 --0.735270380974,1.67836797237,9.71704292297 --0.750255405903,1.67837548256,9.7138376236 --0.778225660324,1.67139017582,9.67541980743 --0.809195518494,1.67340517044,9.68401145935 --0.841165006161,1.67742049694,9.70260238647 --0.872134745121,1.67943549156,9.70719242096 --0.903103768826,1.67845082283,9.70076942444 --0.9340736866,1.68046569824,9.70636081696 --0.950058341026,1.68147337437,9.71315479279 --0.981027841568,1.68248844147,9.7117395401 --1.01299738884,1.68550348282,9.72533035278 --1.04296731949,1.68451833725,9.71591663361 --1.07393693924,1.68553328514,9.71650505066 --1.1069060564,1.68954861164,9.73409175873 --1.13787543774,1.68956375122,9.72967338562 --1.15286064148,1.68957090378,9.72947406769 --1.18582975864,1.69358611107,9.74506092072 --1.21579957008,1.69160091877,9.73364543915 --1.24676966667,1.69361555576,9.73724079132 --1.2787386179,1.69463086128,9.73982334137 --1.30970871449,1.69564557076,9.74141693115 --1.32669270039,1.69765341282,9.7472038269 --1.35666263103,1.69566810131,9.73678874969 --1.38963162899,1.69868314266,9.74737453461 --1.41960191727,1.69869756699,9.74096870422 --1.45457029343,1.70371305943,9.76455497742 --1.48254108429,1.70072734356,9.74214363098 --1.51650977135,1.70474255085,9.7567281723 --1.53049504757,1.70274960995,9.74652481079 --1.56746327877,1.71076524258,9.78211593628 --1.60143232346,1.71478021145,9.797706604 --1.63040280342,1.71279454231,9.7822971344 --1.66437184811,1.71680951118,9.79688835144 --1.69534146786,1.71682417393,9.79047298431 --1.72931051254,1.71983921528,9.804063797 --1.74529516697,1.72084665298,9.80385684967 --1.77926397324,1.72386169434,9.81344223022 --1.8142323494,1.72787690163,9.82802677155 --1.84620201588,1.7288916111,9.82761573792 --1.87317347527,1.72590517998,9.80421352386 --1.90814208984,1.72992026806,9.81880092621 --1.92112779617,1.72692704201,9.80259418488 --1.95709609985,1.73194229603,9.8211812973 --1.99006581306,1.73395693302,9.82777786255 --2.01903581619,1.73197102547,9.80936145782 --2.05400490761,1.73598599434,9.82395458221 --2.08697414398,1.73800075054,9.8245382309 --2.11794400215,1.73801493645,9.81913089752 --2.13392925262,1.73902201653,9.8199300766 --2.16989779472,1.74303710461,9.83551979065 --2.19786834717,1.7400509119,9.81310367584 --2.23183751106,1.74306559563,9.81969356537 --2.26580691338,1.74608016014,9.82728862762 --2.29577684402,1.744094491,9.81186676025 --2.32774686813,1.74610853195,9.81146430969 --2.34972977638,1.75111663342,9.83425712585 --2.37870049477,1.74913060665,9.81684207916 --2.41266989708,1.75214493275,9.82444190979 --2.44463968277,1.75215923786,9.8200302124 --2.47660946846,1.75317335129,9.81461524963 --2.50857949257,1.75418746471,9.81321334839 --2.52756333351,1.75619506836,9.82100296021 --2.5565340519,1.7552087307,9.80459117889 --2.59150338173,1.758223176,9.81318569183 --2.62747192383,1.76223802567,9.82176971436 --2.65444350243,1.75925123692,9.80036640167 --2.68041539192,1.75626420975,9.7739572525 --2.72438168526,1.76528012753,9.81254768372 --2.73236894608,1.76028573513,9.78134346008 --2.77433562279,1.76730155945,9.80992698669 --2.80230712891,1.76531481743,9.79152107239 --2.83927559853,1.76932942867,9.80311107635 --2.86924600601,1.7683429718,9.78969764709 --2.90721487999,1.77335751057,9.80729961395 --2.93518590927,1.77237081528,9.78788948059 --2.96016836166,1.77737915516,9.81368160248 --2.9891397953,1.77739226818,9.80028152466 --3.0261080265,1.7804069519,9.80886745453 --3.05607891083,1.78042030334,9.79646110535 --3.09504723549,1.78543496132,9.81305503845 --3.12201833725,1.78244817257,9.78763580322 --3.14700102806,1.78845620155,9.81243133545 --3.17497253418,1.78746914864,9.79503059387 --3.21194148064,1.79048347473,9.80362415314 --3.2499101162,1.79549789429,9.8152179718 --3.28287959099,1.79551184177,9.80779838562 --3.31684970856,1.79752540588,9.80839824677 --3.35081958771,1.7995390892,9.80699253082 --3.37080335617,1.80154657364,9.81278038025 --3.40977168083,1.80656099319,9.82537460327 --3.43774342537,1.80557382107,9.80697059631 --3.47371268272,1.80858778954,9.81056499481 --3.51068162918,1.811601758,9.816157341 --3.54165220261,1.81161510944,9.80274009705 --3.57662200928,1.81362879276,9.80434131622 --3.59660577774,1.81563615799,9.80912971497 --3.62957644463,1.81764936447,9.80472946167 --3.66154694557,1.8176625967,9.79532051086 --3.69551682472,1.8196760416,9.79191398621 --3.7314863205,1.82168984413,9.79350662231 --3.76345682144,1.82270300388,9.7830953598 --3.78144168854,1.82370984554,9.78389263153 --3.8134124279,1.82472276688,9.77548980713 --3.85238099098,1.82873690128,9.78307914734 --3.88235235214,1.82874965668,9.76867294312 --3.91732239723,1.83076298237,9.7672700882 --3.95229196548,1.83277654648,9.76285362244 --3.98726201057,1.83478975296,9.76145172119 --4.00124835968,1.8337957859,9.75325584412 --4.03821754456,1.83680939674,9.75484752655 --4.0701880455,1.83782231808,9.74343490601 --4.10615825653,1.83983576298,9.74302959442 --4.1411280632,1.84184896946,9.73962211609 --4.17009973526,1.8408613205,9.72121143341 --4.20507001877,1.84387433529,9.71881103516 --4.22605419159,1.8458814621,9.7246055603 --4.25902462006,1.84689426422,9.71619987488 --4.28899669647,1.84690666199,9.70079231262 --4.31396961212,1.84491825104,9.67539024353 --4.35593795776,1.84993219376,9.68698501587 --4.37991142273,1.84694361687,9.65857982635 --4.41189193726,1.85395205021,9.68737316132 --4.4328660965,1.84996330738,9.65095901489 --4.47483539581,1.85497689247,9.66356468201 --4.50280761719,1.85398864746,9.64416027069 --4.54377603531,1.85800242424,9.65074825287 --4.56575012207,1.85501348972,9.6183423996 --4.6107172966,1.86102759838,9.63293075562 --4.62570381165,1.86103355885,9.6257314682 --4.66467380524,1.86504662037,9.6303358078 --4.71064090729,1.87206077576,9.64692974091 --4.73661422729,1.87007212639,9.62352752686 --4.7765827179,1.87308561802,9.62511062622 --4.76756572723,1.85709238052,9.53070068359 --4.84152603149,1.87510991096,9.60330295563 --4.83651733398,1.86711323261,9.55509662628 --4.845495224,1.85812211037,9.49869441986 --4.85847187042,1.85113191605,9.44827842712 --4.87344789505,1.84514176846,9.40387058258 --4.89342308044,1.84115219116,9.36946487427 --4.93339300156,1.84516525269,9.37305736542 --4.9453792572,1.84417068958,9.35985565186 --4.9653544426,1.8411809206,9.32645320892 --5.02331924438,1.85219609737,9.36405181885 --5.05629110336,1.85320794582,9.35464954376 --5.08926200867,1.8542201519,9.34323692322 --5.13423061371,1.86123335361,9.35583686829 --5.14920711517,1.85524308681,9.31242847443 --5.16519355774,1.85624885559,9.3072309494 --5.20816230774,1.86126184464,9.31482601166 --5.22513818741,1.85627162457,9.27541732788 --5.2551112175,1.85628306866,9.26001358032 --5.3000793457,1.86229622364,9.27061080933 --5.32105445862,1.85930645466,9.23819923401 --5.34602832794,1.85731720924,9.21379470825 --5.3770108223,1.8643245697,9.23460102081 --5.39598608017,1.86033463478,9.19818496704 --5.43195676804,1.86234652996,9.19278240204 --5.46792840958,1.86535835266,9.18738079071 --5.48990345001,1.86236846447,9.15797615051 --5.51687669754,1.86137914658,9.13656806946 --5.55285835266,1.8693870306,9.16538143158 --5.57383346558,1.86639690399,9.13397312164 --5.60980463028,1.86940872669,9.12757015228 --5.6237821579,1.86441791058,9.08415603638 --5.65875339508,1.86642932892,9.07574939728 --5.69272565842,1.86844062805,9.06735515594 --5.71070194244,1.86445009708,9.03094291687 --5.73768520355,1.86845707893,9.04174041748 --5.7756562233,1.87246870995,9.03834056854 --5.79863166809,1.87047851086,9.01194190979 --5.81960725784,1.86748814583,8.98153495789 --5.87057495117,1.87550127506,8.99713134766 --5.88155317307,1.86950969696,8.95172691345 --5.91852474213,1.87252104282,8.9463262558 --5.92751312256,1.87052583694,8.92811775208 --5.94548988342,1.86753487587,8.89472007751 --5.9884595871,1.87254703045,8.89630794525 --6.00943565369,1.86955630779,8.86791324615 --6.03241109848,1.86856603622,8.84050559998 --6.07937955856,1.87457835674,8.84809780121 --6.11535215378,1.87758922577,8.84170627594 --6.12234067917,1.87459361553,8.82049560547 --6.15431404114,1.8766040802,8.80709457397 --6.19728422165,1.88061594963,8.80869197845 --6.20326471329,1.87362349033,8.75829029083 --6.24123668671,1.87763440609,8.7528886795 --6.27720832825,1.8796453476,8.7434797287 --6.28419733047,1.87764954567,8.72428035736 --6.30717325211,1.87665879726,8.69787788391 --6.35414266586,1.88267076015,8.70447826385 --6.35812330246,1.8746778965,8.65207386017 --6.3950958252,1.87768864632,8.64467144012 --6.42706918716,1.87969887257,8.63026809692 --6.45604324341,1.87970876694,8.61085796356 --6.45603466034,1.87571203709,8.5836648941 --6.48700857162,1.87672197819,8.56725692749 --6.52398109436,1.8797326088,8.55885124207 --6.53196048737,1.87374019623,8.51244354248 --6.56893348694,1.87775051594,8.50605201721 --6.60690546036,1.88076102734,8.49864673615 --6.62288379669,1.87776935101,8.46324157715 --6.64486885071,1.87977480888,8.46404457092 --6.67284393311,1.88078415394,8.44464492798 --6.69781923294,1.87979340553,8.41922855377 --6.73279285431,1.88180327415,8.40883255005 --6.75576925278,1.88081216812,8.38242816925 --6.77174758911,1.87782001495,8.34903430939 --6.81371927261,1.88283073902,8.34562778473 --6.82270812988,1.88183486462,8.32942485809 --6.83468723297,1.87684237957,8.29002094269 --6.88965559006,1.88585424423,8.30262088776 --6.96361923218,1.89886772633,8.33822822571 --5.37699127197,1.4317240715,6.36743497849 --5.36397600174,1.42272973061,6.3110294342 --5.32997560501,1.409730196,6.24981689453 --5.34791517258,1.39775359631,6.14858341217 --5.36789274216,1.39776229858,6.13319206238 --5.35487699509,1.38876855373,6.07676410675 --5.35785770416,1.38377583027,6.04136228561 --5.3498506546,1.37877881527,6.0121512413 --5.34783315659,1.37378549576,5.97175073624 --5.34781455994,1.36779272556,5.93233442307 --5.33679819107,1.35979890823,5.88091564178 --5.35177612305,1.35880732536,5.85950946808 --5.34076118469,1.35081338882,5.81010580063 --5.34074258804,1.34582066536,5.77168798447 --5.29574394226,1.33082020283,5.70347166061 --5.22774219513,1.3068215847,5.5920419693 --5.30470466614,1.3228354454,5.63864374161 --5.28669118881,1.31284081936,5.58323574066 --5.2746758461,1.30484700203,5.5338177681 --5.27165842056,1.29985368252,5.49541425705 --5.26564121246,1.29286026955,5.45299768448 --5.26563215256,1.29086375237,5.43579816818 --5.26461410522,1.28587079048,5.39938640594 --5.26759576797,1.28187811375,5.36798191071 --5.27657556534,1.27988576889,5.34257507324 --5.2805557251,1.27589333057,5.31115531921 --5.29053497314,1.27490115166,5.28674507141 --5.29351711273,1.27090835571,5.2563457489 --5.30350494385,1.27091264725,5.24913978577 --5.31348466873,1.26992046833,5.22472763062 --5.32246446609,1.26792812347,5.20032548904 --5.34244155884,1.26793682575,5.18591403961 --5.36841821671,1.27094566822,5.17851781845 --5.38639640808,1.27095377445,5.16311979294 --5.3963842392,1.27195835114,5.15490198135 --5.40036535263,1.26796543598,5.12549543381 --5.42434263229,1.27097404003,5.11610078812 --5.43132305145,1.26798129082,5.08969449997 --5.45729923248,1.27099013329,5.08128929138 --5.47527694702,1.27099835873,5.06487941742 --5.49525499344,1.2720066309,5.05148410797 --5.51224184036,1.27401137352,5.05027532578 --5.52522182465,1.27401900291,5.02987337112 --5.54319953918,1.27402710915,5.013463974 --5.59517049789,1.28303730488,5.02907371521 --5.59515333176,1.2790440321,4.99666929245 --5.62312889099,1.28205275536,4.98926401138 --5.6491060257,1.28406107426,4.98087072372 --5.68308925629,1.29106676579,4.99466848373 --5.77305221558,1.30907964706,5.04227972031 --5.88301038742,1.33209347725,5.10790967941 --5.98897027969,1.35510694981,5.1685333252 --6.03594303131,1.36211645603,5.17613935471 --6.07691669464,1.36812567711,5.17773771286 --6.11189222336,1.37313401699,5.17535305023 --6.1178817749,1.37213778496,5.16213321686 --6.13586091995,1.37214517593,5.14372968674 --6.13984298706,1.37015151978,5.11433410645 --6.12682819366,1.3621571064,5.0689125061 --6.01683473587,1.33215653896,4.94246912003 --6.04281234741,1.33416438103,4.9320731163 --6.07678794861,1.33917272091,4.92767238617 --6.10577297211,1.34417760372,4.93547773361 --6.14874696732,1.35018658638,4.93807888031 --6.17872333527,1.3541945219,4.92967605591 --6.22369670868,1.36020338535,4.93327617645 --6.2616724968,1.36621165276,4.93188714981 --6.29364871979,1.37021970749,4.92448425293 --6.32262563705,1.37322735786,4.91508769989 --6.35061120987,1.37823200226,4.92089080811 --6.39258623123,1.38424038887,4.92149829865 --6.42356348038,1.38724792004,4.91310119629 --6.45953941345,1.39225590229,4.90870857239 --6.49751472473,1.39726400375,4.90429973602 --6.53449058533,1.40227162838,4.90091609955 --6.55547809601,1.40527582169,4.89970779419 --6.61144971848,1.41528451443,4.90931463242 --5.52063512802,1.15524029732,4.01913833618 --5.52861595154,1.15424716473,3.99773287773 --5.54459619522,1.15425443649,3.98233056068 --5.55757665634,1.15426135063,3.96493077278 --6.80932044983,1.44032597542,4.87513637543 --6.85529518127,1.4473336935,4.87574481964 --6.88827228546,1.45134079456,4.86634635925 --6.92024993896,1.45534789562,4.85594701767 --6.96622467041,1.4623554945,4.85555267334 --6.99920225143,1.46636259556,4.84514904022 --7.03517961502,1.47136962414,4.83775901794 --7.07216405869,1.47737395763,4.84656000137 --7.12613773346,1.48638164997,4.8511724472 --7.1581158638,1.48938834667,4.83977508545 --7.19509315491,1.49439525604,4.83137512207 --7.2330698967,1.49940216541,4.82398176193 --7.28104496002,1.50740921497,4.82258415222 --7.32702112198,1.51341617107,4.82120609283 --7.36100673676,1.51942014694,4.82701063156 --7.40898180008,1.52742731571,4.82461071014 --7.45295858383,1.53343391418,4.82022094727 --7.49393558502,1.53944039345,4.81383323669 --7.53091335297,1.54344677925,4.80343103409 --7.57288980484,1.54945325851,4.79704141617 --7.62986373901,1.5584603548,4.79863882065 --7.65885066986,1.56346380711,4.80044698715 --7.70082855225,1.56947004795,4.79305362701 --7.74280548096,1.5754762888,4.78566360474 --7.80477952957,1.58548307419,4.79027462006 --7.83675813675,1.58848881721,4.77587985992 --7.88473510742,1.59649503231,4.77149105072 --7.92672014236,1.60349857807,4.78030204773 --8.05068302155,1.62650716305,4.82193279266 --8.09066104889,1.63251268864,4.81154251099 --8.1236410141,1.63651823997,4.79614400864 --8.12362575531,1.6325224638,4.76073646545 --8.17960166931,1.64152848721,4.75934934616 --8.2095823288,1.64453363419,4.74195241928 --8.23457050323,1.64853644371,4.73875236511 --8.26655006409,1.65254151821,4.72235631943 --8.29053211212,1.65354633331,4.7009563446 --8.31851291656,1.65655112267,4.68256616592 --8.34449386597,1.65855586529,4.66216659546 --8.3984708786,1.66756141186,4.65777730942 --8.4424495697,1.6735663414,4.64738416672 --8.42944431305,1.66956806183,4.62217521667 --8.45642566681,1.67157268524,4.60177469254 --9.24028015137,1.83459424973,5.0056347847 --9.2972574234,1.84359884262,4.9992518425 --9.33623790741,1.84760296345,4.98185539246 --9.34022426605,1.84560632706,4.94545078278 --9.3662071228,1.8476099968,4.92105293274 --9.36020183563,1.84461140633,4.89885091782 --9.3971824646,1.84961521626,4.88045835495 --9.39816856384,1.84661841393,4.84305763245 --9.40415477753,1.8436217308,4.80663967133 --9.45013427734,1.85062551498,4.79325580597 --8.00133991241,1.54261004925,3.96794748306 --8.00633239746,1.54261207581,3.95475006104 --8.00331783295,1.53961610794,3.92033290863 --7.99530506134,1.53462016582,3.88391900063 --8.00428962708,1.533624053,3.85752797127 --7.98727846146,1.52762818336,3.81610107422 --7.99426412582,1.52663207054,3.78870725632 --7.99924945831,1.52563607693,3.759298563 --7.97724580765,1.51963794231,3.73309183121 --7.98023080826,1.51764202118,3.70267987251 --7.99221611023,1.51764595509,3.67727899551 --7.97620391846,1.51164984703,3.63785982132 --7.97019147873,1.50865364075,3.60445785522 --7.98317623138,1.50865757465,3.58006238937 --7.96516466141,1.5026614666,3.53963470459 --7.97015762329,1.50266325474,3.5274450779 --7.97114372253,1.50066721439,3.49703741074 --7.98612737656,1.5006711483,3.47262859344 --8.04210567474,1.50967514515,3.46724104881 --8.11608219147,1.5226790905,3.4698638916 --8.16006183624,1.52968275547,3.45847320557 --8.21804141998,1.53868627548,3.45308876038 --8.2830247879,1.55068814754,3.46590733528 --8.3180065155,1.55569159985,3.45052361488 --8.3889837265,1.56769502163,3.44913482666 --8.44696331024,1.5766980648,3.4427549839 --8.49494361877,1.58470129967,3.43136572838 --8.54892349243,1.59270441532,3.42197585106 --8.62690639496,1.60770559311,3.43880319595 --8.66388988495,1.61270856857,3.42241621017 --9.90471076965,1.85870420933,3.9004535675 --9.93369579315,1.86170613766,3.87606453896 --9.93668460846,1.85970807076,3.84066224098 --9.95467090607,1.86070990562,3.81126451492 --9.99265480042,1.86571156979,3.78987526894 --9.97565078735,1.86171281338,3.7646651268 --10.0036363602,1.86471426487,3.73927307129 --10.0216236115,1.86571609974,3.70886611938 --10.0406103134,1.86671769619,3.68047785759 --10.0515975952,1.86671948433,3.64706540108 --10.0755844116,1.86972093582,3.62068128586 --10.0785732269,1.86772251129,3.58426618576 --10.0715684891,1.86472344398,3.56406831741 --10.1075525284,1.86972475052,3.54067373276 --10.0985431671,1.86572647095,3.50126886368 --10.1395282745,1.87172746658,3.47988057137 --10.1235198975,1.86572933197,3.43746638298 --10.1525058746,1.86973047256,3.41207885742 --10.1414966583,1.86573207378,3.37166643143 --10.14149189,1.863732934,3.35346293449 --10.1744775772,1.86873376369,3.32907390594 --10.169467926,1.86573529243,3.29066085815 --10.1814556122,1.86573648453,3.25926756859 --10.2114419937,1.86973726749,3.23286914825 --10.2104330063,1.86673855782,3.19646382332 --10.2194213867,1.86673974991,3.16305804253 --10.220416069,1.86574029922,3.14586138725 --10.255402565,1.87074065208,3.12147212029 --10.2463932037,1.8667422533,3.08205723763 --10.2793798447,1.87174248695,3.05666565895 --10.2723703384,1.86774373055,3.01926589012 --10.2973585129,1.87074422836,2.99086713791 --10.2963533401,1.86974489689,2.97266459465 --10.2703466415,1.86274671555,2.92925286293 --10.3123321533,1.86974656582,2.9058599472 --10.3243217468,1.86974716187,2.87345695496 --10.3433103561,1.87174749374,2.84406757355 --10.3293027878,1.86674892902,2.80364990234 --10.3752889633,1.87374818325,2.7812628746 --10.3742799759,1.87174916267,2.74586415291 --10.4022722244,1.87674856186,2.73566961288 --10.3882646561,1.87174987793,2.69626116753 --10.4252519608,1.87774920464,2.67087078094 --10.423242569,1.87575006485,2.63446259499 --10.4412326813,1.8777500391,2.6040687561 --10.4402236938,1.87575078011,2.56866836548 --10.4542131424,1.87675082684,2.53626298904 --10.422211647,1.86975252628,2.51004600525 --10.473197937,1.87775087357,2.48766040802 --10.4701890945,1.87575161457,2.45226383209 --10.4871797562,1.8777513504,2.42086315155 --10.4841718674,1.87475204468,2.38445448875 --10.5151596069,1.87975108624,2.35706686974 --10.5111560822,1.8777513504,2.33785676956 --10.5271463394,1.87975108624,2.30646014214 --10.5231380463,1.87775158882,2.27005243301 --10.5361289978,1.87875127792,2.23866319656 --10.5611190796,1.88175034523,2.2082593441 --10.5571107864,1.87975084782,2.1718506813 --10.587100029,1.88374936581,2.143460989 --10.5810966492,1.88174986839,2.12526512146 --10.6120862961,1.8867483139,2.09586334229 --10.5980787277,1.88274908066,2.05745172501 --10.6300697327,1.88674747944,2.02906179428 --10.6230621338,1.88474798203,1.99265778065 --10.6450519562,1.88774657249,1.96226620674 --10.6400442123,1.88574683666,1.92585766315 --10.6590394974,1.88774561882,1.91165924072 --10.6810312271,1.89074420929,1.88126993179 --10.7050218582,1.89474272728,1.85087811947 --10.7190132141,1.89574158192,1.81747078896 --10.7170066833,1.89474153519,1.78206825256 --10.7249975204,1.89474070072,1.74867165089 --10.7179908752,1.89174091816,1.71226525307 --10.7379865646,1.89573931694,1.69806945324 --10.7339801788,1.89373922348,1.66266930103 --10.7459716797,1.89473807812,1.62926638126 --10.7569646835,1.89573681355,1.59586572647 --10.7409582138,1.8917375803,1.55845892429 --10.7779493332,1.89773452282,1.52906692028 --10.7639427185,1.89373493195,1.4916561842 --10.7919378281,1.89873254299,1.4784655571 --10.7829313278,1.89573264122,1.44205880165 --10.809923172,1.89973008633,1.41066193581 --10.8069171906,1.89872956276,1.37525820732 --10.8289089203,1.90172708035,1.3428580761 --10.8199033737,1.89972710609,1.30746126175 --10.8428955078,1.90272450447,1.27506160736 --10.8228940964,1.89872562885,1.25485157967 --10.8318872452,1.89972412586,1.22044467926 --10.8518800735,1.90272164345,1.18804967403 --10.8438739777,1.89972126484,1.15264999866 --10.847867012,1.89972007275,1.11824905872 --10.8778600693,1.9047164917,1.08685827255 --10.8718547821,1.9027159214,1.05044412613 --10.867852211,1.90171575546,1.03223752975 --10.8968448639,1.90671217442,1.00085043907 --10.9148387909,1.90970945358,0.967450857162 --10.906832695,1.90670895576,0.932049810886 --10.8958282471,1.90470862389,0.89563792944 --10.9268217087,1.909704566,0.863242149353 --10.9198160172,1.9077038765,0.82783895731 --10.9358129501,1.9107016325,0.81164175272 --10.9208068848,1.90670180321,0.775231540203 --10.9358024597,1.90969896317,0.741837322712 --10.9187965393,1.90569901466,0.705426454544 --10.9337911606,1.9076962471,0.672033190727 --10.9597864151,1.91169214249,0.638635694981 --10.9417829514,1.90869307518,0.619421958923 --10.9437789917,1.90869128704,0.58502393961 --10.9737730026,1.91368663311,0.551627337933 --10.9657678604,1.91168582439,0.516221940517 --10.9627628326,1.91068434715,0.48081433773 --10.9977588654,1.91667914391,0.448431700468 --10.9827537537,1.9136787653,0.412015616894 --11.0087509155,1.91867518425,0.395823806524 --10.9967470169,1.91567456722,0.360418379307 --11.019742012,1.91967022419,0.327030897141 --10.9937372208,1.91467106342,0.290614128113 --11.0157337189,1.91866660118,0.25621637702 --11.0127286911,1.91766500473,0.220808848739 --11.0277252197,1.91966128349,0.186413228512 --11.0537233353,1.92465734482,0.170228168368 --11.0547180176,1.92465507984,0.134821817279 --11.0617141724,1.92565202713,0.0994162485003 --11.0547103882,1.92465054989,0.064008705318 --11.0777072906,1.92864561081,0.0296182911843 --11.065703392,1.92664468288,-0.00579045014456 --11.0766992569,1.92764103413,-0.0411935038865 --11.0686979294,1.92664074898,-0.0583931431174 --11.0846948624,1.92963635921,-0.0937941670418 --11.0756912231,1.92763495445,-0.129203081131 --11.0996875763,1.93162953854,-0.163587734103 --11.0816841125,1.92862915993,-0.199000924826 --11.0896816254,1.9306255579,-0.234403088689 --11.1126785278,1.93462002277,-0.269796699286 --11.0796756744,1.92862272263,-0.288022488356 --11.1066732407,1.93361663818,-0.323412925005 --11.121670723,1.93661189079,-0.35880869627 --11.0976667404,1.93161225319,-0.393216729164 --11.0886640549,1.93061065674,-0.428628176451 --11.1236629486,1.93760311604,-0.465020030737 --11.1106595993,1.93460190296,-0.499422192574 --11.1146583557,1.93559992313,-0.517627179623 --11.0996551514,1.93359875679,-0.55304390192 --11.1476545334,1.94258928299,-0.589419364929 --11.1266517639,1.93858897686,-0.623829305172 --11.1176490784,1.93758714199,-0.659241318703 --11.1376466751,1.94158113003,-0.695637524128 --11.1596460342,1.94557487965,-0.732029974461 --11.1546449661,1.94457387924,-0.749230325222 --11.1646432877,1.94656908512,-0.785633444786 --11.1726417542,1.94856464863,-0.822037935257 --11.1686401367,1.94856178761,-0.857443869114 --11.1926393509,1.9535548687,-0.893828809261 --11.1906375885,1.95355165005,-0.929231464863 --11.1916360855,1.95354783535,-0.96564167738 --11.2086362839,1.95754337311,-0.984837710857 --11.2156352997,1.95853865147,-1.02123916149 --11.1976327896,1.95553767681,-1.05565047264 --11.2106323242,1.95853197575,-1.09204351902 --11.2136316299,1.95952761173,-1.12844932079 --11.2066297531,1.95952486992,-1.16385793686 --11.2186307907,1.96152091026,-1.18305671215 --11.1806268692,1.95552313328,-1.21547710896 --11.1966266632,1.95851659775,-1.25287437439 --11.1896257401,1.95851385593,-1.2872723341 --11.1956253052,1.95950865746,-1.32468354702 --11.1986246109,1.96150410175,-1.36007666588 --11.217625618,1.9654968977,-1.39847636223 --11.2006244659,1.96249759197,-1.414686203 --11.1536197662,1.95450103283,-1.44611895084 --11.1786222458,1.95949268341,-1.4845072031 --11.1636199951,1.95749092102,-1.51892018318 --11.1766214371,1.96148431301,-1.55631661415 --11.2236251831,1.9704720974,-1.59769332409 --11.203622818,1.96747100353,-1.63110339642 --11.2266263962,1.97246479988,-1.65229654312 --11.2356271744,1.97445869446,-1.68969535828 --11.2056236267,1.970459342,-1.72211515903 --11.1736211777,1.96546018124,-1.75454044342 --11.2096252441,1.97244918346,-1.79592859745 --11.1756219864,1.96745049953,-1.82734870911 --11.1936254501,1.97144258022,-1.86573815346 --11.1806240082,1.97044014931,-1.90014874935 --11.1916255951,1.97243559361,-1.9203492403 --11.1836261749,1.97243213654,-1.95576000214 --11.1976280212,1.97542464733,-1.99415457249 --11.1746273041,1.97242391109,-2.02656579018 --11.1636266708,1.97142088413,-2.06198382378 --11.1886310577,1.97741115093,-2.10237288475 --11.1836309433,1.97640955448,-2.11957454681 --11.1776304245,1.97640562057,-2.15498018265 --11.18663311,1.979398489,-2.19338226318 --11.155632019,1.97539925575,-2.22480511665 --11.1836366653,1.98138856888,-2.26619172096 --11.1876382828,1.98338234425,-2.30359339714 --11.1926412582,1.9853758812,-2.3409910202 --11.1776399612,1.98337602615,-2.35720777512 --11.2166481018,1.99236273766,-2.40159273148 --11.1946468353,1.98936152458,-2.43400502205 --11.2066507339,1.99235343933,-2.47340345383 --11.2156534195,1.99534595013,-2.51179766655 --11.2276582718,1.99933767319,-2.55220460892 --11.2396621704,2.00332927704,-2.59159898758 --11.2606668472,2.00732183456,-2.6147916317 --11.2566690445,2.00831699371,-2.65119624138 --11.2626724243,2.0113093853,-2.68959403038 --11.2546749115,2.01130485535,-2.7260093689 --11.2646789551,2.0142967701,-2.76540446281 --11.2566814423,2.01429224014,-2.8008081913 --11.2826890945,2.02028012276,-2.84520721436 --11.2726888657,2.01927924156,-2.86141061783 --11.2606906891,2.01927542686,-2.89682602882 --11.2636947632,2.02126836777,-2.9352273941 --11.266699791,2.02326130867,-2.97362780571 --11.2767047882,2.02725243568,-3.01402711868 --11.2627058029,2.02624893188,-3.04843735695 --11.2687110901,2.02824091911,-3.0878367424 --11.262711525,2.02823901176,-3.10503864288 --11.2957220078,2.03622460365,-3.15243411064 --11.2827243805,2.03522062302,-3.18683958054 --11.303732872,2.04120898247,-3.23123884201 --11.3127393723,2.04519987106,-3.27163362503 --11.2707366943,2.03920245171,-3.29906249046 --11.2917451859,2.04419016838,-3.3434574604 --11.311750412,2.04918217659,-3.36764264107 --11.3127565384,2.05117464066,-3.40705084801 --11.3047599792,2.05216908455,-3.44345855713 --11.3287696838,2.05815601349,-3.48884677887 --11.3067722321,2.05615353584,-3.52227139473 --11.3347826004,2.06313943863,-3.56865262985 --11.3297872543,2.06413316727,-3.60605740547 --11.3277902603,2.06512975693,-3.62526273727 --11.3498001099,2.07111668587,-3.6706507206 --11.3448047638,2.07210993767,-3.70906376839 --11.367816925,2.07909607887,-3.75545477867 --11.346818924,2.07709336281,-3.78887414932 --11.3958358765,2.08907294273,-3.84324598312 --11.3618345261,2.08407354355,-3.87267255783 --11.3838434219,2.09006357193,-3.89986586571 --11.3688459396,2.08905935287,-3.93427157402 --11.3868579865,2.09504628181,-3.98067235947 --11.3888654709,2.09803748131,-4.0210723877 --11.3838710785,2.09903025627,-4.05947828293 --11.3498706818,2.09503078461,-4.08789777756 --11.3768844604,2.10201501846,-4.13728713989 --11.3948926926,2.10700583458,-4.16347837448 --11.394900322,2.10999703407,-4.20489263535 --11.3679027557,2.10699558258,-4.23530435562 --11.4199228287,2.11897230148,-4.2946844101 --11.4279327393,2.12296104431,-4.3380818367 --11.4059362411,2.12195801735,-4.37150239944 --11.4199438095,2.1259496212,-4.39669370651 --11.3989477158,2.12394618988,-4.43010950089 --11.4289636612,2.13192844391,-4.48250007629 --11.4259719849,2.13491988182,-4.52290868759 --11.428981781,2.1379096508,-4.56531047821 --11.4189882278,2.1389029026,-4.60271787643 --11.4500055313,2.14688444138,-4.65610456467 --11.421002388,2.14288806915,-4.66531801224 --11.4380168915,2.14887309074,-4.71371459961 --11.4350252151,2.15086436272,-4.7541179657 --11.4210319519,2.15085840225,-4.79052972794 --11.4210414886,2.15384840965,-4.83293819427 --11.4320554733,2.15883493423,-4.87933540344 --11.4010572433,2.15583395958,-4.90976476669 --11.414065361,2.15982508659,-4.93595790863 --11.3900690079,2.15782189369,-4.96837520599 --11.3900794983,2.16081142426,-5.01078033447 --11.3820886612,2.16280388832,-5.04918289185 --11.3720970154,2.16379618645,-5.08759403229 --11.3881120682,2.16978096962,-5.13698863983 --11.3651170731,2.16777706146,-5.17041110992 --11.3521194458,2.16677570343,-5.18662500381 --11.3621330261,2.17176198959,-5.23301649094 --11.3491411209,2.17275524139,-5.27042961121 --11.3261461258,2.17175126076,-5.30385255814 --11.3121528625,2.17174482346,-5.34026145935 --11.3001613617,2.17273783684,-5.37766933441 --11.2891693115,2.17373013496,-5.4160823822 --11.2691698074,2.17073106766,-5.42829322815 --11.2291688919,2.16673278809,-5.45372629166 --11.2251796722,2.16872286797,-5.49513292313 --11.2321939468,2.17370939255,-5.54153156281 --11.2262048721,2.17569994926,-5.58294630051 --11.2112131119,2.17569327354,-5.61935901642 --11.1902189255,2.17568898201,-5.65277385712 --11.184223175,2.17568492889,-5.67198181152 --11.1792345047,2.17867517471,-5.7133898735 --11.1562404633,2.17667102814,-5.74580574036 --11.1592540741,2.18065834045,-5.79120874405 --11.1522655487,2.18364882469,-5.83161592484 --11.1452770233,2.18563914299,-5.87303113937 --11.1182813644,2.18363642693,-5.90344905853 --11.1082849503,2.18363380432,-5.92065858841 --11.095293045,2.18462634087,-5.95806837082 --11.0963087082,2.18861365318,-6.00347614288 --11.0923213959,2.19160270691,-6.04588222504 --11.0603237152,2.18860173225,-6.0743098259 --11.0563373566,2.19159054756,-6.11671495438 --11.0353441238,2.19058537483,-6.15113830566 --11.0233469009,2.1905837059,-6.16633987427 --10.9923496246,2.18758225441,-6.19476366043 --11.0133733749,2.19556212425,-6.25115680695 --11.0013837814,2.19755315781,-6.2905755043 --11.0054016113,2.20253896713,-6.33797693253 --11.0724439621,2.22050118446,-6.42034006119 --11.1124763489,2.23247313499,-6.48872280121 --11.1635055542,2.24544739723,-6.53989076614 --11.2545585632,2.26939940453,-6.63824653625 --11.2485742569,2.272387743,-6.68165302277 --11.2235803604,2.27138352394,-6.71406793594 --11.2526102066,2.28135824203,-6.77845859528 --11.2356214523,2.28235054016,-6.81587123871 --11.2166223526,2.28035068512,-6.8290886879 --11.1786241531,2.27635073662,-6.8545165062 --11.1356248856,2.2723531723,-6.87694835663 --11.0966253281,2.26835393906,-6.90137624741 --11.0826377869,2.26934480667,-6.94079017639 --11.0496425629,2.26734352112,-6.96921920776 --11.0156459808,2.26434230804,-6.99664640427 --11.0096530914,2.26533722878,-7.01685237885 --10.9716539383,2.26133799553,-7.04127836227 --10.9406585693,2.2593357563,-7.06969881058 --10.9286727905,2.26132559776,-7.11111831665 --10.8856725693,2.25632810593,-7.13255119324 --10.8456726074,2.25232934952,-7.15598535538 --10.8146781921,2.25032758713,-7.18340063095 --10.7896766663,2.24732995033,-7.19262742996 --10.7416734695,2.2423350811,-7.21006298065 --10.7216835022,2.2423286438,-7.2444729805 --10.6846857071,2.23932909966,-7.26890325546 --10.6416845322,2.23433208466,-7.2893371582 --10.6176929474,2.23432707787,-7.32175731659 --10.5776929855,2.23032855988,-7.34419202805 --10.5666980743,2.23032593727,-7.36039590836 --10.5347013474,2.22732424736,-7.38782453537 --10.487698555,2.22232913971,-7.40526437759 --10.456703186,2.2203271389,-7.43268918991 --10.4327125549,2.22032213211,-7.46511173248 --10.3977146149,2.21732187271,-7.48953819275 --10.3547143936,2.21232533455,-7.50897502899 --10.3487205505,2.21432042122,-7.52817392349 --10.3147239685,2.2113199234,-7.55360364914 --10.2737236023,2.20732235909,-7.57403945923 --10.2427282333,2.20532083511,-7.60046052933 --10.2137336731,2.20431804657,-7.62888669968 --10.1777362823,2.20131826401,-7.65231704712 --10.1497430801,2.20031547546,-7.68073749542 --10.1207380295,2.19632077217,-7.68496465683 --10.0817375183,2.19232273102,-7.7053937912 --10.0517435074,2.19132041931,-7.73282146454 --10.0397577286,2.19331002235,-7.77323484421 --9.98575019836,2.18631911278,-7.78267765045 --9.94975185394,2.18331980705,-7.8051071167 --9.94477176666,2.18830609322,-7.85051441193 --9.89575386047,2.17932152748,-7.83774518967 --9.8717622757,2.17931652069,-7.86916780472 --9.83676528931,2.17631673813,-7.89260149002 --9.80176734924,2.17431712151,-7.91502857208 --9.77377414703,2.17331409454,-7.94345617294 --9.73377323151,2.16931724548,-7.96188688278 --9.70477962494,2.16831445694,-7.98931455612 --9.690782547,2.16831302643,-8.00352954865 --9.64077568054,2.1623210907,-8.01396942139 --9.57976150513,2.15333509445,-8.01440906525 --9.56577682495,2.15532517433,-8.05383014679 --9.52077198029,2.15033102036,-8.06726360321 --9.49778175354,2.15132546425,-8.09868526459 --9.50481033325,2.15830469131,-8.15508937836 --9.4828081131,2.15630722046,-8.16331577301 --9.44680976868,2.15330886841,-8.18273448944 --9.41581439972,2.15230751038,-8.20816612244 --9.38481903076,2.15030646324,-8.23259067535 --9.30879402161,2.13832831383,-8.22005367279 --9.290807724,2.14032053947,-8.25547122955 --9.27080631256,2.13832235336,-8.26368618011 --9.23881053925,2.13632202148,-8.28711414337 --9.22382545471,2.1393122673,-8.32553291321 --9.21684551239,2.14329814911,-8.37094593048 --9.17484283447,2.13930296898,-8.38537788391 --9.14885139465,2.13929891586,-8.41480827332 --9.10284614563,2.13430571556,-8.42624950409 --9.06984901428,2.13230586052,-8.44867992401 --9.06185626984,2.13330149651,-8.46688461304 --9.02585697174,2.13130307198,-8.48631477356 --8.99686336517,2.13030076027,-8.51274681091 --8.96586799622,2.12929987907,-8.53617191315 --8.92686653137,2.12530326843,-8.55260467529 --8.89587116241,2.12430214882,-8.57703781128 --8.88787937164,2.12529754639,-8.59524250031 --8.8428735733,2.12130475044,-8.60567855835 --8.81688117981,2.12130093575,-8.6341047287 --8.79088973999,2.12129688263,-8.66253089905 --8.75088787079,2.11730122566,-8.67796993256 --8.72089195251,2.11629986763,-8.7023973465 --8.72992801666,2.12527537346,-8.76379680634 --8.68390655518,2.11729288101,-8.74602985382 --8.65591335297,2.11729025841,-8.77245807648 --8.6269197464,2.11628818512,-8.79788780212 --8.57190608978,2.1093018055,-8.79733085632 --8.54891586304,2.11029601097,-8.82875823975 --8.53893852234,2.1142821312,-8.87317562103 --8.47992038727,2.10629868507,-8.86761951447 --8.50095272064,2.115275383,-8.9168176651 --8.46995639801,2.11427497864,-8.9392414093 --8.43795967102,2.11227488518,-8.96066665649 --8.42097759247,2.11526489258,-8.99909496307 --8.37997341156,2.1112704277,-9.01152896881 --8.33096313477,2.1062810421,-9.01597213745 --8.30597305298,2.10627627373,-9.04540061951 --8.2869720459,2.10527801514,-9.05261421204 --8.26198196411,2.1062734127,-9.08204174042 --8.22698307037,2.10327553749,-9.09946632385 --8.21900844574,2.10925960541,-9.14789009094 --8.21603775024,2.11524057388,-9.20029735565 --8.18804454803,2.11523795128,-9.2257194519 --8.16505718231,2.11723136902,-9.25815010071 --8.12003421783,2.1092505455,-9.23738574982 --8.11706447601,2.11523079872,-9.29079627991 --8.0890712738,2.1152279377,-9.31722640991 --8.04906845093,2.11223316193,-9.32966041565 --8.0280828476,2.11422538757,-9.3640871048 --7.99308538437,2.11322712898,-9.38252258301 --7.95406675339,2.10624241829,-9.36775684357 --7.92307186127,2.10524153709,-9.39018726349 --7.92310571671,2.11321973801,-9.44759273529 --7.86708784103,2.10523581505,-9.44204425812 --7.83208942413,2.10323810577,-9.45947551727 --7.83512735367,2.11321306229,-9.52188587189 --7.78111028671,2.10522842407,-9.51733112335 --7.74611186981,2.1032307148,-9.53476333618 --7.736120224,2.10522603989,-9.55297851562 --7.70512533188,2.10422563553,-9.57440280914 --7.67112731934,2.10322713852,-9.59283447266 --7.64413690567,2.1032230854,-9.62026500702 --7.61514472961,2.10322093964,-9.64469242096 --7.58415079117,2.10321974754,-9.66813182831 --7.57315778732,2.10421609879,-9.68434143066 --7.563185215,2.11019968987,-9.73276042938 --7.51317119598,2.10421299934,-9.73120307922 --7.48117589951,2.10321259499,-9.75263786316 --7.45518732071,2.10420799255,-9.78106498718 --7.42619562149,2.10520529747,-9.80650043488 --7.40120697021,2.1062002182,-9.83592510223 --7.40823411942,2.11318230629,-9.87612724304 --7.36522769928,2.10919070244,-9.88256454468 --7.33022928238,2.10719275475,-9.89999961853 --7.30123710632,2.10719037056,-9.92442798615 --7.27024316788,2.10718917847,-9.94686126709 --7.26327610016,2.11416912079,-10.0012788773 --7.21025848389,2.10718536377,-9.99472904205 --7.20126867294,2.1091799736,-10.0139360428 --7.18729400635,2.11416506767,-10.0593585968 --7.13928127289,2.10917782784,-10.0588026047 --7.13331604004,2.117156744,-10.1142120361 --7.11033248901,2.11914873123,-10.1486444473 --7.05430984497,2.11116814613,-10.1360912323 --7.04133844376,2.11715173721,-10.1845188141 --7.02934598923,2.11814832687,-10.2007322311 --6.99034261703,2.11515402794,-10.2111654282 --6.97436666489,2.1201403141,-10.2545852661 --6.92335128784,2.11415553093,-10.250041008 --6.89536094666,2.11515188217,-10.2764701843 --6.89039993286,2.12312865257,-10.3358812332 --6.87440299988,2.12312817574,-10.3471021652 --6.82538843155,2.11814212799,-10.343547821 --6.81341934204,2.12412428856,-10.3939676285 --6.76340246201,2.1181397438,-10.3884134293 --6.75343704224,2.12511944771,-10.4428348541 --6.70241880417,2.11913633347,-10.4352798462 --6.67342948914,2.12013268471,-10.4617166519 --6.66644334793,2.12312483788,-10.4849233627 --6.63645219803,2.12312245369,-10.509355545 --6.60746335983,2.12511873245,-10.5357923508 --6.56946134567,2.12212371826,-10.5472278595 --6.53546476364,2.12212538719,-10.5646591187 --6.51048088074,2.12411832809,-10.5970907211 --6.47648429871,2.12311983109,-10.614522934 --6.4574842453,2.12312173843,-10.6217508316 --6.4345035553,2.12611246109,-10.6581830978 --6.39549970627,2.12311911583,-10.6666135788 --6.36751317978,2.12511372566,-10.6960554123 --6.33551883698,2.12511396408,-10.7154798508 --6.30452871323,2.12611174583,-10.7399234772 --6.27653980255,2.12710762024,-10.7663469315 --6.24852705002,2.12311863899,-10.7585802078 --6.24157094955,2.13309288025,-10.8220005035 --6.19355487823,2.12710809708,-10.8164453506 --6.18259143829,2.13508677483,-10.8718566895 --6.13557863235,2.13010025024,-10.8703155518 --6.09156751633,2.12611174583,-10.870757103 --6.058573246,2.12611222267,-10.8901920319 --6.02855587006,2.12112593651,-10.8764181137 --5.97953748703,2.11514234543,-10.8688707352 --5.93652772903,2.1121532917,-10.8703126907 --5.89351701736,2.10816478729,-10.8707513809 --5.85551452637,2.1061706543,-10.881193161 --5.84355306625,2.11414909363,-10.9376125336 --5.82157611847,2.11813759804,-10.9770431519 --5.81459522247,2.12212705612,-11.0052604675 --5.7655749321,2.11614513397,-10.9947042465 --5.72456741333,2.1131541729,-10.9991464615 --5.67254304886,2.10617518425,-10.9835987091 --5.63253641129,2.10318374634,-10.9890384674 --5.58652019501,2.09819865227,-10.9834852219 --5.56952190399,2.09819960594,-10.9917039871 --5.55055189133,2.10418438911,-11.0381355286 --5.49752378464,2.09720754623,-11.0185861588 --5.46753311157,2.09820532799,-11.042016983 --5.42953157425,2.09621119499,-11.0524654388 --5.3835144043,2.09122681618,-11.0459127426 --5.34350585938,2.08823680878,-11.0483455658 --5.34253740311,2.09521794319,-11.0905637741 --5.29651975632,2.09023427963,-11.0830097198 --5.26152086258,2.08923792839,-11.0964441299 --5.22752523422,2.0892393589,-11.1138868332 --5.18050575256,2.08425688744,-11.1043386459 --5.14249992371,2.08226513863,-11.1097688675 --5.12052631378,2.08725261688,-11.1511993408 --5.08649587631,2.07927393913,-11.1244344711 --5.06051588058,2.0832657814,-11.1588745117 --5.03052663803,2.08526349068,-11.182305336 --4.97849607468,2.07728815079,-11.1607608795 --4.94850683212,2.07928514481,-11.1851968765 --4.9175157547,2.08028435707,-11.2066278458 --4.8734998703,2.075299263,-11.2010755539 --4.8575053215,2.07629799843,-11.2133045197 --4.8144903183,2.07231235504,-11.2087478638 --4.77949094772,2.07131671906,-11.2211837769 --4.74349021912,2.07132172585,-11.232626915 --4.71650791168,2.07431483269,-11.2640590668 --4.66447305679,2.06634187698,-11.2375087738 --4.63448619843,2.06833839417,-11.2639522552 --4.615483284,2.06734275818,-11.266169548 --4.5774769783,2.06535100937,-11.2716093063 --4.53947257996,2.06335878372,-11.2790584564 --4.50647735596,2.06436038017,-11.2954921722 --4.45945167542,2.05838179588,-11.2789392471 --4.432472229,2.06237339973,-11.3133840561 --4.3934636116,2.05938339233,-11.3158254623 --4.37546300888,2.05938625336,-11.3210468292 --4.32943964005,2.05340623856,-11.3075008392 --4.30747079849,2.05939102173,-11.35293293 --4.25843858719,2.05241632462,-11.3293819427 --4.22544336319,2.0534183979,-11.3458166122 --4.18743848801,2.05142641068,-11.352268219 --4.17043876648,2.05142855644,-11.3584833145 --4.12942409515,2.04744267464,-11.3539237976 --4.100440979,2.05143713951,-11.3833675385 --4.05641841888,2.04645609856,-11.3708124161 --4.02242231369,2.04645872116,-11.386256218 --3.98641991615,2.04546499252,-11.395699501 --3.94540452957,2.04247975349,-11.3901424408 --3.90138316154,2.0374982357,-11.3785972595 --3.89240407944,2.04148745537,-11.4068069458 --3.84938359261,2.03750538826,-11.3962564468 --3.81438446045,2.03750991821,-11.4087018967 --3.78038668633,2.03751349449,-11.4221391678 --3.74037361145,2.03452658653,-11.4195871353 --3.69434380531,2.02755045891,-11.3990392685 --3.68336105347,2.03154206276,-11.4232540131 --3.64836215973,2.03154659271,-11.4357013702 --3.61135411263,2.02955627441,-11.4381351471 --3.5783598423,2.03055810928,-11.4555768967 --3.52932167053,2.02258706093,-11.4260396957 --3.50234436989,2.02757811546,-11.4614753723 --3.46634078026,2.02658510208,-11.4689178467 --3.44332385063,2.02359843254,-11.4561405182 --3.39929580688,2.01762104034,-11.4375886917 --3.37532925606,2.02460575104,-11.4840259552 --3.32829165459,2.01663374901,-11.4554777145 --3.29629898071,2.01863455772,-11.4739131927 --3.25628423691,2.01564908028,-11.4693660736 --3.22228527069,2.01565337181,-11.4818048477 --3.20328187943,2.01465821266,-11.4840345383 --3.16727805138,2.01466608047,-11.4904785156 --3.12424898148,2.0086889267,-11.4709224701 --3.09225893021,2.01068806648,-11.4923667908 --3.05725669861,2.0106947422,-11.5008058548 --3.01623535156,2.00671339035,-11.4892559052 --2.9782230854,2.00372576714,-11.4877004623 --2.9642355442,2.00672125816,-11.5059223175 --2.9212038517,2.00074577332,-11.4833641052 --2.88720774651,2.00174880028,-11.4988155365 --2.84718823433,1.99776601791,-11.4892635345 --2.81319069862,1.99877011776,-11.5027093887 --2.77316951752,1.99478828907,-11.491153717 --2.74017310143,1.99579155445,-11.5055904388 --2.72217178345,1.99579513073,-11.5098180771 --2.68114471436,1.99081683159,-11.4922609329 --2.64815211296,1.99281799793,-11.5107088089 --2.61314868927,1.99182534218,-11.5181493759 --2.57111859322,1.98684895039,-11.4976015091 --2.53812408447,1.98785126209,-11.5140428543 --2.50211977959,1.98785948753,-11.5204963684 --2.4801003933,1.98387384415,-11.5057229996 --2.44509720802,1.98388135433,-11.5131664276 --2.40808582306,1.982894063,-11.5116128922 --2.36906337738,1.97891283035,-11.4990558624 --2.33607172966,1.98091363907,-11.5185060501 --2.30307841301,1.98291540146,-11.535949707 --2.27008414268,1.98391759396,-11.5523920059 --2.2601172924,1.99090087414,-11.5916061401 --2.22411227226,1.99090957642,-11.5970573425 --2.19513773918,1.99590027332,-11.6334943771 --2.15913271904,1.99590909481,-11.6389436722 --2.12312602997,1.99491882324,-11.6423883438 --2.09013390541,1.99691998959,-11.6608314514 --2.07313609123,1.99792182446,-11.668053627 --2.03311157227,1.99394226074,-11.65350914 --1.99710094929,1.99195420742,-11.6529464722 --1.96109342575,1.99196457863,-11.6553926468 --1.92709934711,1.99396717548,-11.6718425751 --1.89310336113,1.99497067928,-11.6862869263 --1.85508775711,1.99298596382,-11.6807403564 --1.84010076523,1.99598145485,-11.6989603043 --1.80208396912,1.9929972887,-11.6924123764 --1.76808738708,1.99500131607,-11.7058544159 --1.73207807541,1.99401295185,-11.7062969208 --1.69305431843,1.99003279209,-11.6927509308 --1.66006553173,1.99303245544,-11.7141952515 --1.62405514717,1.99204456806,-11.713637352 --1.61008179188,1.99703216553,-11.7458639145 --1.57507956028,1.99803984165,-11.7533073425 --1.53504896164,1.99306380749,-11.7327651978 --1.49513733387,2.01102209091,-11.8364229202 --1.4591357708,2.01102948189,-11.844877243 --1.42212331295,2.01004314423,-11.8423261642 --1.405128479,2.01104307175,-11.8525495529 --1.36609613895,2.00606822968,-11.8299951553 --1.32807779312,2.00408530235,-11.8214502335 --1.29711139202,2.01107239723,-11.8648910522 --1.25908696651,2.00709271431,-11.8503379822 --1.22005748749,2.00311613083,-11.8307924271 --1.1870752573,2.00711250305,-11.8582344055 --1.16806459427,2.00612187386,-11.8524608612 --1.13206315041,2.00712943077,-11.860915184 --1.09402990341,2.00215482712,-11.8373556137 --1.06004345417,2.00515365601,-11.8608026505 --1.02000176907,1.99918413162,-11.8292617798 --0.987025678158,2.00417709351,-11.8627071381 --0.948997080326,2.00019979477,-11.8441572189 --0.933015704155,2.00419259071,-11.8673791885 --0.894988059998,2.00021505356,-11.8498325348 --0.859982967377,2.0002245903,-11.8542699814 --0.822962582111,1.99824285507,-11.8437194824 --0.784927785397,1.99326908588,-11.8191690445 --0.749942660332,1.99726760387,-11.843626976 --0.729905545712,1.99129188061,-11.8118486404 --0.693893134594,1.99030554295,-11.8092956543 --0.654835522175,1.98034453392,-11.7627458572 --0.620865881443,1.98733448982,-11.8022022247 --0.583823084831,1.98136520386,-11.7696428299 --0.548839092255,1.9853631258,-11.7950983047 --0.511807262897,1.98138785362,-11.7735481262 --0.495837420225,1.98737442493,-11.8077707291 --0.459832012653,1.98738443851,-11.8122234344 --0.422789901495,1.98141479492,-11.780670166 --0.387808293104,1.98641169071,-11.8081235886 --0.3528021276,1.98642194271,-11.8115644455 --0.317821651697,1.99141824245,-11.8400154114 --0.280787676573,1.98744416237,-11.8164691925 --0.263820022345,1.99342989922,-11.8526964188 --0.227787226439,1.98945498466,-11.8301401138 --0.191808655858,1.99445056915,-11.8606004715 --0.155788108706,1.99246895313,-11.8500480652 --0.119772672653,1.99148464203,-11.8444976807 --0.083760201931,1.99049866199,-11.8419494629 --0.0477571189404,1.99150776863,-11.8484020233 --0.0297775119543,1.99650037289,-11.872631073 -0.00628159055486,1.98753976822,-11.8250770569 -0.0227025877684,1.97643792629,-10.9722118378 -0.058676559478,1.96941351891,-10.9385995865 -0.0946797952056,1.9684047699,-10.9329853058 -0.129630282521,1.95836770535,-10.8763713837 -0.164604604244,1.95234358311,-10.8427562714 -0.181594625115,1.94933331013,-10.8289432526 -0.216588765383,1.94732010365,-10.8143253326 -0.25158983469,1.94531071186,-10.8067054749 -0.286586016417,1.94329857826,-10.7940893173 -0.320544183254,1.93426597118,-10.7444791794 -0.354498356581,1.92423141003,-10.6908750534 -0.372516661882,1.92723619938,-10.7040643692 -0.404454290867,1.91419303417,-10.6344518661 -0.438436359167,1.90917360783,-10.607840538 -0.473462313414,1.91217780113,-10.6242160797 -0.507448613644,1.90816056728,-10.6016044617 -0.542462646961,1.91015827656,-10.6059865952 -0.577476561069,1.9111559391,-10.6103687286 -0.593460798264,1.90714287758,-10.5905590057 -0.627454280853,1.90412974358,-10.5749464035 -0.661458015442,1.90412211418,-10.5693264008 -0.695451557636,1.90110898018,-10.5537157059 -0.728447020054,1.89909720421,-10.5400924683 -0.762440681458,1.89608418941,-10.5244836807 -0.794424116611,1.8920661211,-10.4988641739 -0.811417996883,1.89005804062,-10.4880638123 -0.846436977386,1.89205861092,-10.4974431992 -0.877406597137,1.88603305817,-10.4578294754 -0.911413490772,1.88602733612,-10.4552116394 -0.945416331291,1.88501954079,-10.448597908 -0.978406310081,1.88200473785,-10.4289903641 -1.01140105724,1.87899267673,-10.4143762589 -1.02739417553,1.87798428535,-10.4025697708 -1.0593829155,1.87396931648,-10.3819551468 -1.0923858881,1.87396168709,-10.375333786 -1.12639212608,1.87395560741,-10.3717193604 -1.15736997128,1.86793494225,-10.3401117325 -1.1913779974,1.86792993546,-10.3384962082 -1.22437441349,1.86691880226,-10.3248872757 -1.23734641075,1.86089980602,-10.2920827866 -1.26934063435,1.85888779163,-10.276468277 -1.30435872078,1.86088812351,-10.2848501205 -1.33433496952,1.8548668623,-10.2512435913 -1.36733734608,1.85485899448,-10.2436285019 -1.40235543251,1.85685932636,-10.2520103455 -1.43233776093,1.85184133053,-10.2243976593 -1.44732892513,1.84983241558,-10.2105922699 -1.48133456707,1.8498262167,-10.2059850693 -1.51031494141,1.84580743313,-10.1763677597 -1.54231154919,1.84379684925,-10.1627569199 -1.57531297207,1.84278869629,-10.1541481018 -1.605296731,1.83877158165,-10.1275415421 -1.62029206753,1.8377648592,-10.1177310944 -1.65530633926,1.83876335621,-10.1221208572 -1.68227744102,1.83273994923,-10.0825099945 -1.71326911449,1.82972705364,-10.0639038086 -1.74728524685,1.83172667027,-10.0702781677 -1.77626645565,1.82770848274,-10.0406742096 -1.80726122856,1.82569718361,-10.025062561 -1.82527136803,1.82669794559,-10.0302562714 -1.85124051571,1.81967401505,-9.98865032196 -1.88324165344,1.81966590881,-9.97903823853 -1.91624820232,1.8196606636,-9.97542572021 -1.94623935223,1.81764769554,-9.95581531525 -1.97321760654,1.81162846088,-9.92320632935 -2.00722932816,1.81362581253,-9.9245929718 -2.02122092247,1.81161749363,-9.91078948975 -2.04920434952,1.80760085583,-9.88318157196 -2.08422017097,1.80960011482,-9.88857078552 -2.11119961739,1.80458176136,-9.85696411133 -2.14320087433,1.80357384682,-9.84735870361 -2.17621088028,1.805570364,-9.84673976898 -2.20419454575,1.80155396461,-9.81913852692 -2.21919393539,1.80054962635,-9.81332683563 -2.25119590759,1.80054247379,-9.80471992493 -2.2771756649,1.79552435875,-9.77311134338 -2.30717206001,1.79451453686,-9.75849914551 -2.34118247032,1.79551100731,-9.75789356232 -2.36816716194,1.7914955616,-9.73128414154 -2.39615392685,1.78848099709,-9.70668315887 -2.41014885902,1.78647446632,-9.69587802887 -2.44416356087,1.78947365284,-9.70025634766 -2.45408058167,1.77142524719,-9.60268115997 -2.47805690765,1.76640594006,-9.5670747757 -2.51206946373,1.76840376854,-9.5684671402 -2.54407453537,1.76839840412,-9.56285762787 -2.56007838249,1.76939630508,-9.56104946136 -2.59108185768,1.7693901062,-9.5534362793 -2.62007594109,1.7673791647,-9.53583335876 -2.66713929176,1.77940189838,-9.59118747711 -2.69613170624,1.77739012241,-9.57159042358 -2.72713565826,1.77738440037,-9.56497097015 -2.75111174583,1.77136516571,-9.52837848663 -2.75908637047,1.76634883881,-9.49558830261 -2.78507375717,1.76333522797,-9.47097969055 -2.79701375961,1.7502989769,-9.39639377594 -2.82500910759,1.7492890358,-9.3797826767 -2.85500979424,1.74828183651,-9.36917304993 -2.88801860809,1.74927818775,-9.36656856537 -2.91200137138,1.74526262283,-9.33696174622 -2.92599987984,1.74525797367,-9.32915592194 -2.95700359344,1.74525213242,-9.32154750824 -3.00505781174,1.75626981258,-9.36692523956 -3.02904248238,1.75225520134,-9.33931350708 -3.06405735016,1.75425469875,-9.34370136261 -3.08302402496,1.74723148346,-9.29611587524 -3.10600709915,1.74321627617,-9.26650428772 -3.12602066994,1.74621868134,-9.27470207214 -3.15201234818,1.7442073822,-9.25409030914 -3.17499399185,1.73919141293,-9.22249126434 -3.20499444008,1.73918402195,-9.21088981628 -3.23198771477,1.73717343807,-9.19128704071 -3.25797939301,1.73516237736,-9.17067909241 -3.28397059441,1.73315095901,-9.14907550812 -3.29696702957,1.73214566708,-9.1392698288 -3.32496380806,1.73013687134,-9.12366580963 -3.35296058655,1.72912812233,-9.10806179047 -3.36291027069,1.71809780598,-9.04148197174 -3.38890361786,1.71708750725,-9.02187633514 -3.4249227047,1.72008907795,-9.03025722504 -3.46792197227,1.72007799149,-9.01084804535 -3.50093269348,1.72107565403,-9.01023387909 -3.53193736076,1.72207057476,-9.00263023376 -3.65416431427,1.77016627789,-9.23690605164 -3.62502193451,1.74009442329,-9.06937789917 -3.63898587227,1.73207104206,-9.0177898407 -3.64396429062,1.72705769539,-8.98799419403 -3.67897939682,1.73005771637,-8.99237442017 -3.70096230507,1.72604262829,-8.96078491211 -3.72595334053,1.72403144836,-8.93818473816 -3.75395298004,1.7230246067,-8.92557144165 -3.78896689415,1.72602367401,-8.92796039581 -3.81596326828,1.72501504421,-8.91135406494 -3.83096408844,1.72501182556,-8.9055557251 -3.85795974731,1.72400283813,-8.88795566559 -3.88896512985,1.72499835491,-8.88134384155 -3.9159617424,1.72398984432,-8.86473941803 -3.94696736336,1.72498548031,-8.85812759399 -3.97396326065,1.72397661209,-8.84052944183 -4.00496864319,1.72497236729,-8.8339176178 -4.02297687531,1.72697234154,-8.83610916138 -4.04897117615,1.72496318817,-8.81750488281 -4.08198165894,1.72796094418,-8.8158864975 -4.1079750061,1.72595095634,-8.79529476166 -4.13697528839,1.72594428062,-8.78269290924 -4.16898298264,1.72794091702,-8.77807807922 -4.21000671387,1.73294436932,-8.79146194458 -4.21498918533,1.72893345356,-8.76566410065 -4.25000286102,1.73193240166,-8.76704883575 -4.27900218964,1.73192536831,-8.75345039368 -4.31000757217,1.73292088509,-8.74584007263 -4.34602165222,1.73592054844,-8.74922084808 -4.37602376938,1.73691427708,-8.7376203537 -4.38301086426,1.73390555382,-8.71682071686 -4.41201066971,1.73389863968,-8.70322227478 -4.44301509857,1.73489379883,-8.69461631775 -4.4730181694,1.73588860035,-8.68500518799 -4.5010175705,1.73588144779,-8.67040061951 -4.52801465988,1.73487365246,-8.65379810333 -4.55901861191,1.73586881161,-8.6451921463 -4.572016716,1.73586475849,-8.63638877869 -4.6000161171,1.73585772514,-8.62178421021 -4.62801456451,1.73485040665,-8.60618782043 -4.65801715851,1.73584496975,-8.59558200836 -4.69002389908,1.73784136772,-8.58996582031 -4.72002649307,1.73783588409,-8.57935905457 -4.75403499603,1.74083268642,-8.57475662231 -4.76402854919,1.73882675171,-8.56095314026 -4.78902244568,1.73781788349,-8.5403547287 -4.82002639771,1.73881280422,-8.53075122833 -4.86305046082,1.74481618404,-8.54412937164 -4.89004802704,1.74480867386,-8.52752590179 -4.91103601456,1.74179720879,-8.49993133545 -4.93803358078,1.74178981781,-8.48332881927 -4.96204948425,1.74579322338,-8.49451255798 -4.99906158447,1.74879169464,-8.49490451813 -5.0290646553,1.74978661537,-8.48429298401 -5.0500535965,1.74777567387,-8.45769309998 -5.10008525848,1.75578176975,-8.47907924652 -5.13108921051,1.75677716732,-8.47046279907 -5.13006639481,1.75176465511,-8.43668079376 -5.16407346725,1.75376117229,-8.4310760498 -5.19107246399,1.75375437737,-8.41546535492 -5.21706819534,1.7527462244,-8.39587306976 -5.2490735054,1.75474214554,-8.38825893402 -5.27907514572,1.75573635101,-8.37565898895 -5.30106592178,1.75372648239,-8.35105895996 -5.32407855988,1.75672829151,-8.35824775696 -5.3500752449,1.75672054291,-8.33964729309 -5.40010499954,1.76472604275,-8.36002159119 -5.41808986664,1.76071405411,-8.32842922211 -5.45009469986,1.7627093792,-8.31882572174 -5.48009586334,1.76370382309,-8.30622291565 -5.49808168411,1.76069176197,-8.27463340759 -5.4960603714,1.75568056107,-8.24284076691 -5.53807830811,1.76068139076,-8.24922561646 -5.58710575104,1.76768577099,-8.2665977478 -5.59908437729,1.76267135143,-8.22700691223 -5.6110625267,1.75765669346,-8.18642616272 -5.64607048035,1.76065349579,-8.18082141876 -5.67807531357,1.76164901257,-8.17121601105 -5.69908380508,1.76464939117,-8.17440414429 -5.72908496857,1.76564371586,-8.16080665588 -5.75808620453,1.76663804054,-8.14719867706 -5.79109191895,1.76863408089,-8.13859367371 -5.81108093262,1.76662385464,-8.11100006104 -5.83507585526,1.7656160593,-8.09039497375 -5.88009548187,1.77161705494,-8.09778594971 -5.92513370514,1.78162848949,-8.13594150543 -5.92609930038,1.77360975742,-8.08037185669 -5.94608926773,1.77159965038,-8.05278015137 -5.97509050369,1.77259421349,-8.0391702652 -5.99708175659,1.77058506012,-8.01358318329 -6.03309059143,1.77358198166,-8.00797939301 -6.06909990311,1.77757966518,-8.00435733795 -6.07809305191,1.77557420731,-7.98856830597 -6.11410188675,1.77857148647,-7.98395395279 -6.15010976791,1.78156816959,-7.97735357285 -6.16909885406,1.77955818176,-7.94876194 -6.20310497284,1.78255474567,-7.9411482811 -6.24411916733,1.78655397892,-7.94253063202 -6.25311279297,1.78554856777,-7.92674064636 -6.28011083603,1.78554201126,-7.9091386795 -6.3251285553,1.79154241085,-7.91452312469 -6.36213779449,1.79553973675,-7.90990877151 -6.38713359833,1.79453229904,-7.88930988312 -6.42013788223,1.79752790928,-7.87870502472 -6.4361243248,1.79451715946,-7.84611797333 -6.46714162827,1.79952037334,-7.8593006134 -6.50915527344,1.80451917648,-7.85968780518 -6.54215955734,1.8065148592,-7.84907960892 -6.59318208694,1.81451690197,-7.86045598984 -6.62718629837,1.81651246548,-7.8498544693 -6.64017009735,1.81250095367,-7.81426429749 -6.67217254639,1.81449580193,-7.80066728592 -6.68417024612,1.81449246407,-7.79085731506 -6.6400976181,1.79446136951,-7.68533182144 -6.46089363098,1.73538601398,-7.41992330551 -6.49890375137,1.73938405514,-7.41631269455 -6.50188064575,1.73337054253,-7.37073755264 -6.52988147736,1.73436546326,-7.35513734818 -6.5258641243,1.72935688496,-7.32536077499 -6.51983356476,1.72134113312,-7.27078676224 -6.54683351517,1.72133588791,-7.25418806076 -6.55381536484,1.71732449532,-7.21460676193 -6.56379985809,1.71331417561,-7.17902040482 -6.57578659058,1.71030449867,-7.14543581009 -6.59477996826,1.70829701424,-7.11984586716 -6.59977245331,1.70729207993,-7.10205459595 -6.62777423859,1.7082875967,-7.08744907379 -6.62975263596,1.70227539539,-7.04386806488 -6.64374160767,1.70026659966,-7.01228904724 -6.65272665024,1.69625663757,-6.97571229935 -6.68172979355,1.6972527504,-6.96309900284 -6.70372676849,1.6972464323,-6.94051361084 -6.6967086792,1.69223821163,-6.90973758698 -6.72070789337,1.69223296642,-6.89113426208 -6.73069524765,1.68922412395,-6.85754394531 -6.75969839096,1.6912201643,-6.84393978119 -6.75567293167,1.68420732021,-6.79437541962 -6.77666950226,1.68320119381,-6.77178525925 -6.80667352676,1.68519759178,-6.75918054581 -6.80666303635,1.68319201469,-6.73739051819 -6.81164646149,1.67818188667,-6.69781923294 -6.83464479446,1.67817676067,-6.67821931839 -6.84463310242,1.67516815662,-6.64463806152 -6.85261917114,1.67115926743,-6.60906028748 -6.87862062454,1.67215490341,-6.59245920181 -6.88360500336,1.66814565659,-6.55487585068 -6.88459587097,1.66514062881,-6.53409194946 -6.90859603882,1.66613602638,-6.51549291611 -6.90757656097,1.66012537479,-6.4719209671 -6.94258499146,1.66412329674,-6.46431064606 -6.94056463242,1.65811288357,-6.41974306107 -6.96656656265,1.65910899639,-6.40413284302 -6.95354795456,1.65310120583,-6.37036037445 -6.96453762054,1.65109372139,-6.33878087997 -6.9825334549,1.65008795261,-6.31419324875 -6.98651885986,1.64507937431,-6.27661657333 -7.00351476669,1.6450740099,-6.25301122665 -7.01350450516,1.64206659794,-6.22043800354 -7.0274977684,1.6400604248,-6.19285011292 -7.02749013901,1.63805603981,-6.17305707932 -7.04248332977,1.63604986668,-6.1454782486 -7.03546237946,1.6290396452,-6.09890890121 -7.08147907257,1.63604009151,-6.10128641129 -7.07846069336,1.63003087044,-6.05772304535 -7.08044672012,1.6260226965,-6.02014160156 -7.09143877029,1.62401652336,-5.99055433273 -7.09943675995,1.62301397324,-5.97875165939 -7.10742712021,1.62000739574,-5.94617271423 -7.11841964722,1.6180011034,-5.91658830643 -7.13941860199,1.61899673939,-5.89500427246 -7.14740943909,1.61599040031,-5.86341762543 -7.15439939499,1.61298382282,-5.83083486557 -7.17039632797,1.61197900772,-5.80624246597 -7.16538524628,1.60797429085,-5.78246212006 -7.18338251114,1.60796964169,-5.75887727737 -7.19337558746,1.60596394539,-5.72929048538 -7.20436954498,1.60395860672,-5.70070314407 -7.21436166763,1.60195279121,-5.670129776 -7.23536205292,1.60294902325,-5.65052700043 -7.23735713959,1.60094594955,-5.63373279572 -7.23534202576,1.59593844414,-5.59317445755 -7.26434755325,1.5979360342,-5.57957172394 -7.2613325119,1.5929287672,-5.53999662399 -7.27933120728,1.5929248333,-5.51740455627 -7.28832435608,1.59091961384,-5.48781824112 -7.29931879044,1.5889146328,-5.45923852921 -7.29831218719,1.58691132069,-5.44044685364 -7.32931900024,1.5899091959,-5.42784738541 -7.3223028183,1.58390200138,-5.38528347015 -7.34030151367,1.58389818668,-5.36269378662 -7.35629987717,1.58389425278,-5.3390994072 -7.35528755188,1.57888805866,-5.30153131485 -7.37228631973,1.57888448238,-5.2789349556 -7.38628816605,1.5798830986,-5.27113962173 -7.39228105545,1.57787823677,-5.24054908752 -7.39427185059,1.57387280464,-5.20597457886 -7.43228149414,1.57887160778,-5.19738054276 -7.43627357483,1.57586669922,-5.16578817368 -7.44526815414,1.57386231422,-5.1372013092 -7.46927118301,1.57585954666,-5.1186132431 -7.45825958252,1.57085561752,-5.09283590317 -7.47325801849,1.57085204124,-5.06824970245 -7.49025726318,1.57084870338,-5.04565572739 -7.49324941635,1.56784379482,-5.01208543777 -7.50824737549,1.56684029102,-4.98750066757 -7.52624750137,1.56783735752,-4.96590232849 -7.50823354721,1.56183302402,-4.93612766266 -7.50522232056,1.55782794952,-4.89955282211 -7.53923130035,1.56182646751,-4.88795661926 -7.53822135925,1.55782175064,-4.85238742828 -7.55722236633,1.55781912804,-4.83178758621 -7.5652179718,1.55581533909,-4.80320215225 -7.56320810318,1.55181074142,-4.76763010025 -7.56820631027,1.55180895329,-4.7538394928 -7.58320569992,1.55180597305,-4.73024702072 -7.58419752121,1.54780185223,-4.69667577744 -7.59819698334,1.54779887199,-4.67208957672 -7.61419630051,1.54779613018,-4.64850521088 -7.61318826675,1.54379200935,-4.61492300034 -7.62218475342,1.54278886318,-4.58635187149 -7.62818384171,1.54278731346,-4.57355833054 -7.63117837906,1.53978383541,-4.54297065735 -7.64517736435,1.53978121281,-4.51838684082 -7.67118215561,1.54177939892,-4.50178813934 -7.66016960144,1.53577506542,-4.46122980118 -7.67016744614,1.53477215767,-4.43464422226 -7.6841673851,1.53476977348,-4.411049366 -7.67215824127,1.53076708317,-4.38628435135 -7.68115568161,1.52976441383,-4.35969400406 -7.6961555481,1.52976214886,-4.33610773087 -7.69314861298,1.52575874329,-4.30252552032 -7.69614315033,1.5237557888,-4.27096033096 -7.70914268494,1.52275359631,-4.24637508392 -7.70413827896,1.52075183392,-4.22758817673 -7.71513652802,1.51974952221,-4.20200252533 -7.73213863373,1.52074766159,-4.18040561676 -7.71712684631,1.51474416256,-4.13984107971 -7.72712516785,1.51374185085,-4.1132645607 -7.73312234879,1.51173949242,-4.08468723297 -7.74312162399,1.51073741913,-4.05909872055 -7.73311471939,1.50773584843,-4.03732347488 -7.75511837006,1.50973427296,-4.01773500443 -7.75111246109,1.50573170185,-3.98416185379 -7.75711011887,1.50372970104,-3.95657587051 -7.77911376953,1.50572836399,-3.93797397614 -7.7671046257,1.50072562695,-3.89941906929 -7.78210830688,1.50272500515,-3.89162397385 -7.78410482407,1.49972319603,-3.86204123497 -7.78910255432,1.49872124195,-3.83346509933 -7.80210351944,1.49871981144,-3.80987286568 -7.81110239029,1.49771809578,-3.78329634666 -7.81109857559,1.49471628666,-3.7527179718 -7.82610034943,1.49571490288,-3.73012566566 -7.82709884644,1.49471414089,-3.7153365612 -7.82909631729,1.49171257019,-3.68575978279 -7.83109331131,1.48971092701,-3.65618395805 -7.85009670258,1.49170982838,-3.63558888435 -7.84809303284,1.48870825768,-3.60401773453 -7.85709238052,1.48770689964,-3.57744526863 -7.86709260941,1.48770570755,-3.55285143852 -7.86108970642,1.48470509052,-3.53407907486 -7.86708831787,1.4837038517,-3.50749015808 -7.88109064102,1.48370277882,-3.48390746117 -7.88208818436,1.48170173168,-3.45433163643 -7.89408969879,1.48170077801,-3.43073773384 -7.91609430313,1.48369991779,-3.41114544868 -7.90108728409,1.47869873047,-3.37359142303 -7.88007879257,1.47369813919,-3.34980845451 -7.88407802582,1.47169721127,-3.32124137878 -7.87907457352,1.46869635582,-3.28966641426 -7.87006998062,1.46469557285,-3.25708460808 -7.89907693863,1.46769499779,-3.24049043655 -7.92808437347,1.47169446945,-3.22389435768 -7.93208456039,1.47169411182,-3.21110153198 -7.94508695602,1.47169351578,-3.18751549721 -7.94508552551,1.46969294548,-3.15794372559 -7.95008563995,1.46869242191,-3.13037157059 -7.9610877037,1.46869194508,-3.10578942299 -7.93507862091,1.46169185638,-3.0662252903 -7.91107034683,1.45469164848,-3.02766132355 -7.91607141495,1.45469141006,-3.01487660408 -7.92307281494,1.45369124413,-2.98929142952 -7.89506387711,1.44569146633,-2.94874215126 -7.83204555511,1.43169212341,-2.8952050209 -7.81203985214,1.42569255829,-2.85864830017 -7.79503536224,1.41969299316,-2.82408070564 -7.73701953888,1.40669417381,-2.77354311943 -7.73101806641,1.40469443798,-2.7567679882 -7.72301626205,1.40169501305,-2.72619533539 -7.69400882721,1.39369606972,-2.68763875961 -7.7330198288,1.39969587326,-2.67503619194 -7.67200469971,1.38569772243,-2.62450575829 -7.61999225616,1.37369966507,-2.57796621323 -7.61599206924,1.37070059776,-2.55038094521 -7.6009888649,1.36670148373,-2.53061676025 -7.54797697067,1.35470366478,-2.48507022858 -7.50296735764,1.34470593929,-2.44252300262 -7.48396444321,1.33870768547,-2.40896844864 -7.48996782303,1.33870875835,-2.38538098335 -7.51397562027,1.34170937538,-2.36680221558 -7.4989733696,1.33771038055,-2.34901666641 -7.44796323776,1.32671332359,-2.30547475815 -7.41695833206,1.31871592999,-2.26892280579 -7.38695335388,1.3117184639,-2.23336386681 -7.3909573555,1.31071996689,-2.20879197121 -7.34094905853,1.29972338676,-2.16724348068 -7.33595085144,1.29672539234,-2.13968253136 -7.35795688629,1.30072546005,-2.13486862183 -7.33195400238,1.29372823238,-2.10131049156 -7.33395767212,1.29273021221,-2.0767352581 -7.33696174622,1.29273200035,-2.05314850807 -7.25794839859,1.2757371664,-2.00362563133 -7.24094820023,1.27074015141,-1.97307240963 -7.25695562363,1.27274167538,-1.95348334312 -7.33197259903,1.28673923016,-1.96463119984 -7.39598941803,1.29773843288,-1.95901107788 -7.40099382401,1.2967402935,-1.93543314934 -7.22796297073,1.26275098324,-1.85997319221 -7.16095399857,1.24875664711,-1.81545722485 -7.17696142197,1.24975836277,-1.79685533047 -7.10995292664,1.23576438427,-1.75333440304 -7.0829501152,1.22976708412,-1.73356997967 -7.09195709229,1.23076927662,-1.71297705173 -7.07195806503,1.22577309608,-1.6834218502 -7.07796382904,1.22577548027,-1.66183531284 -7.05896520615,1.22077941895,-1.63327121735 -7.01796293259,1.21178472042,-1.59872817993 -7.01696538925,1.21078622341,-1.58693897724 -7.00896930695,1.20878958702,-1.56235492229 -6.98096990585,1.2017942667,-1.53180193901 -6.95797109604,1.19679868221,-1.50323605537 -6.95197582245,1.19480228424,-1.47866654396 -6.93197822571,1.18980669975,-1.45109987259 -6.94098567963,1.1908094883,-1.43051731586 -6.91898488998,1.1858124733,-1.41374588013 -6.9069890976,1.18281662464,-1.38817846775 -6.90199422836,1.18082034588,-1.36460185051 -6.90000009537,1.17982387543,-1.34103727341 -6.88900470734,1.17682802677,-1.31646025181 -6.93801784515,1.18482804298,-1.30583536625 -6.89501810074,1.17583465576,-1.27329683304 -6.85001468658,1.16683971882,-1.25155174732 -6.83501911163,1.16284430027,-1.22696852684 -6.83802604675,1.16284775734,-1.20539116859 -6.82703113556,1.15985226631,-1.18082475662 -6.82703733444,1.15885591507,-1.15923905373 -6.86604976654,1.16585695744,-1.14464533329 -6.817050457,1.15586435795,-1.11309456825 -6.81705379486,1.15486621857,-1.1023029089 -6.84406423569,1.15986800194,-1.08570671082 -6.83507013321,1.15687263012,-1.06213355064 -6.81607484818,1.15287804604,-1.0365704298 -6.86208772659,1.16087841988,-1.02296853065 -6.87009572983,1.16088175774,-1.0023881197 -6.79308986664,1.14588999748,-0.977648615837 -6.79209709167,1.1458940506,-0.95606648922 -6.74409866333,1.13590216637,-0.926512420177 -6.78611135483,1.14290297031,-0.911913156509 -6.85612726212,1.1559009552,-0.902284860611 -6.85313415527,1.1539055109,-0.879715561867 -6.83013916016,1.14891171455,-0.854155480862 -6.83914375305,1.1509128809,-0.845349311829 -6.76114320755,1.13592422009,-0.81083625555 -6.80515575409,1.1429246664,-0.796228766441 -6.75215816498,1.13293385506,-0.766687810421 -6.7261633873,1.12694048882,-0.742116391659 -6.77917671204,1.13694000244,-0.728503704071 -6.72417545319,1.12594735622,-0.709756314754 -6.68317937851,1.11795556545,-0.683199346066 -6.6811876297,1.11696052551,-0.661628365517 -6.68419647217,1.11696481705,-0.641048133373 -6.68320417404,1.11596941948,-0.620460271835 -6.6992149353,1.11897265911,-0.600884258747 -6.70222330093,1.11897706985,-0.580303311348 -6.69922780991,1.11797964573,-0.569514870644 -6.70423698425,1.11798393726,-0.548937618732 -6.70024442673,1.11698889732,-0.528345227242 -6.68325185776,1.11399555206,-0.504792332649 -6.73826551437,1.12399470806,-0.490172594786 -6.7772769928,1.12999558449,-0.473563224077 -6.79528713226,1.1329985857,-0.453979045153 -6.70028400421,1.11601054668,-0.434242844582 -6.6462893486,1.10502111912,-0.4077077806 -6.64629840851,1.10502612591,-0.387127161026 -6.64430761337,1.10403132439,-0.366544544697 -6.6573176384,1.10603499413,-0.346959263086 -6.6923289299,1.11203634739,-0.329356104136 -6.70133399963,1.11403787136,-0.319563984871 -6.6933426857,1.11204385757,-0.297993242741 -6.65334939957,1.10405313969,-0.274434685707 -6.64535856247,1.10205924511,-0.252868354321 -6.64136743546,1.10106480122,-0.232286304235 -6.64837741852,1.1020693779,-0.211712926626 -6.6713886261,1.1060718298,-0.19310939312 -6.79739999771,1.13006067276,-0.190248712897 -6.80040931702,1.13006532192,-0.169662877917 -6.67241239548,1.10608494282,-0.141170024872 -6.74442577362,1.11908209324,-0.124542452395 -6.73143482208,1.11708891392,-0.102973207831 -6.68144226074,1.10710000992,-0.079434171319 -6.76845550537,1.12309527397,-0.0627968534827 -6.7804608345,1.12509655952,-0.052997071296 -6.80547142029,1.13009893894,-0.0333953984082 -8.5055475235,1.44390547276,-0.0737741813064 -6.78349018097,1.12511229515,0.0097401086241 -6.77549982071,1.12411868572,0.0313060469925 -6.76850891113,1.12212491035,0.0518904328346 -6.96352529526,1.15810716152,0.0685824975371 -6.84352636337,1.13612401485,0.0813102796674 -6.88353776932,1.14412462711,0.101909123361 -6.66154098511,1.10215711594,0.126355245709 -6.63655090332,1.09816598892,0.147904366255 -6.59956073761,1.09117615223,0.168465197086 -6.58957052231,1.08918321133,0.18903440237 -6.59357595444,1.09018540382,0.198833405972 -6.59558677673,1.09019088745,0.219408139586 -6.57959699631,1.08719885349,0.23997169733 -6.58960723877,1.08920323849,0.259571909904 -6.59861850739,1.09120798111,0.280152320862 -6.58862924576,1.08921515942,0.300718098879 -6.58863973618,1.08922111988,0.321291565895 -6.59064483643,1.08922374249,0.331090211868 -6.59565591812,1.09022891521,0.351668804884 -6.5996670723,1.09123444557,0.372247099876 -6.61467790604,1.09423840046,0.392838150263 -6.57668876648,1.08724939823,0.412389308214 -6.58369970322,1.08925449848,0.432971209288 -6.58671045303,1.08925998211,0.45256882906 -6.56471586227,1.08526587486,0.462336719036 -6.56372737885,1.08527219296,0.482907921076 -6.64573860168,1.1012673378,0.506539106369 -6.66474962234,1.10427093506,0.528125405312 -6.64376068115,1.10127985477,0.547692000866 -6.57377195358,1.08829534054,0.564236164093 -6.58077764511,1.08929753304,0.575024545193 -6.62278842926,1.09729802608,0.597631216049 -6.59280014038,1.09230828285,0.61619502306 -6.57181167603,1.08831739426,0.635751545429 -6.56982326508,1.08832371235,0.655342280865 -6.56083488464,1.08733129501,0.674919188023 -6.53984689713,1.08334064484,0.694470226765 -6.54285240173,1.08434331417,0.704273104668 -6.55886363983,1.08734738827,0.725860238075 -6.55687570572,1.0873541832,0.74643021822 -6.59888648987,1.09535443783,0.770039141178 -6.56189870834,1.08936619759,0.787591159344 -6.54591083527,1.08637475967,0.806168496609 -6.56992197037,1.09137773514,0.828761518002 -6.55292844772,1.0883834362,0.837537646294 -6.42794418335,1.0654078722,0.846036553383 -6.41995573044,1.06441545486,0.864624083042 -6.43696737289,1.06841945648,0.886217057705 -6.42897987366,1.06642735004,0.905783832073 -6.46199083328,1.07342910767,0.929384529591 -6.45800304413,1.07343626022,0.948964357376 -6.41701078415,1.06544566154,0.954721689224 -6.39102363586,1.06145608425,0.971294462681 -6.41403484344,1.06645941734,0.993891060352 -6.43304681778,1.07046329975,1.01647830009 -6.44405841827,1.07246828079,1.03806328773 -6.44807100296,1.0734744072,1.05864775181 -6.44607686996,1.07347810268,1.06843745708 -6.43808984756,1.07248616219,1.0880035162 -6.45010185242,1.07549107075,1.10959601402 -6.42811584473,1.07250118256,1.12715446949 -6.4401268959,1.0745061636,1.14874839783 -6.44513988495,1.07651245594,1.17031955719 -6.45615148544,1.07851743698,1.19191324711 -6.43715906143,1.07552397251,1.19968187809 -6.44717073441,1.0785292387,1.22127342224 -6.45518350601,1.08053481579,1.24285888672 -6.43819665909,1.07754421234,1.26043021679 -6.44320964813,1.07955062389,1.28200531006 -6.42022323608,1.0755610466,1.29857087135 -6.42422962189,1.07656395435,1.30936455727 -6.43424129486,1.07956922054,1.33096122742 -6.41525602341,1.07657933235,1.34852004051 -6.41326856613,1.07658648491,1.36810815334 -6.46627807617,1.08758544922,1.39870905876 -6.4192943573,1.07959973812,1.4102678299 -6.4193072319,1.08060669899,1.43084597588 -6.42531347275,1.08160948753,1.44263124466 -6.41532754898,1.08061814308,1.46120595932 -6.35134458542,1.06963539124,1.46875584126 -6.42635250092,1.08463060856,1.50437521935 -6.39736795425,1.07964229584,1.51894116402 -6.41437959671,1.0836468935,1.54352080822 -6.46938848495,1.09464502335,1.57514476776 -6.42339897156,1.0866560936,1.5759062767 -6.42241239548,1.08666348457,1.59648382664 -6.46642208099,1.09666359425,1.62708449364 -6.46543502808,1.09667098522,1.64766597748 -6.51844453812,1.10766983032,1.6812620163 -6.467461586,1.09868502617,1.68983101845 -6.4204788208,1.09070003033,1.70037555695 -6.45448350906,1.09769833088,1.71917653084 -6.45149612427,1.09870588779,1.73876917362 -6.43151187897,1.09571659565,1.75533115864 -6.40952730179,1.09272754192,1.77090036869 -6.43553829193,1.09773075581,1.79849076271 -6.41855335236,1.09574067593,1.81506621838 -6.41356086731,1.0957454443,1.82484340668 -6.4225730896,1.09775114059,1.84744346142 -6.4495844841,1.10475420952,1.87602937222 -6.40060281754,1.09576976299,1.88457906246 -6.39461708069,1.09577822685,1.90415501595 -6.38763093948,1.09578669071,1.92274463177 -6.37964582443,1.0947958231,1.9423084259 -6.41364955902,1.10179376602,1.96211886406 -6.41666316986,1.10380089283,1.9846919775 -6.40567779541,1.10281002522,2.00227928162 -6.39969205856,1.10281860828,2.02185726166 -6.39770698547,1.10382664204,2.04342126846 -6.40371990204,1.10583305359,2.06601548195 -6.39373445511,1.10484242439,2.08458900452 -6.41473913193,1.10984253883,2.10139322281 -6.4357509613,1.11484646797,2.12898945808 -6.39376974106,1.10786151886,2.13853549957 -6.42878055573,1.115863204,2.17112851143 -6.4677901268,1.1248639822,2.20473408699 -6.45380496979,1.12287414074,2.22230553627 -6.38981962204,1.11188900471,2.21306204796 -6.27684593201,1.09091615677,2.19858527184 -6.31385660172,1.09891760349,2.23217916489 -6.41185951233,1.11990845203,2.2858080864 -6.40887403488,1.120916605,2.30639338493 -6.43588495255,1.12691938877,2.33699417114 -6.47389507294,1.13592076302,2.37258076668 -6.46790266037,1.13492560387,2.38137340546 -6.47291612625,1.13793230057,2.40496397018 -6.43193531036,1.13094747066,2.41351604462 -6.3769569397,1.1219650507,2.41705942154 -6.41996526718,1.13096511364,2.45367360115 -6.42197990417,1.13297283649,2.47724461555 -6.36399459839,1.12298715115,2.46799898148 -6.3590092659,1.12299561501,2.48759174347 -6.33702659607,1.12000751495,2.50215411186 -6.28904724121,1.11202394962,2.50670957565 -6.35705327988,1.12701976299,2.55431985855 -6.34806871414,1.12702918053,2.5729033947 -6.36208152771,1.13103473186,2.60049271584 -6.38208580017,1.13603508472,2.61929416656 -6.40209817886,1.1410394907,2.64987921715 -6.42011022568,1.14604413509,2.67947053909 -6.41912555695,1.14805233479,2.70204854012 -6.50612831116,1.1670447588,2.75966596603 -6.44715070724,1.15706324577,2.75922036171 -6.56514930725,1.1820499897,2.82985854149 -6.61015033722,1.19104576111,2.85967373848 -6.58516836166,1.18805813789,2.87324237823 -6.5891828537,1.19106554985,2.89882206917 -6.53120613098,1.18108439445,2.89936041832 -6.48522663116,1.1731004715,2.90293335915 -6.49423980713,1.17710709572,2.93051481247 -6.51825141907,1.18311059475,2.96411275864 -6.61824512482,1.20409667492,3.01993250847 -6.60626077652,1.20410680771,3.03851532936 -6.55328369141,1.19512474537,3.04006385803 -6.55929756165,1.19813156128,3.06665039062 -6.50132131577,1.18815040588,3.06520247459 -6.54432964325,1.1991508007,3.10879850388 -6.54433727264,1.20015478134,3.12059497833 -6.50135850906,1.19317066669,3.12516021729 -6.45138072968,1.18418824673,3.12671470642 -6.50938749313,1.19818592072,3.17830991745 -6.47540712357,1.19319999218,3.18589258194 -6.45842504501,1.19221150875,3.20246267319 -6.4734377861,1.19721710682,3.23404812813 -6.53643608093,1.21120965481,3.27685570717 -6.49845695496,1.20522499084,3.28341960907 -6.48647356033,1.20423531532,3.30200076103 -6.50848579407,1.21123957634,3.3375890255 -6.39251899719,1.18926978111,3.30610942841 -6.37153816223,1.18728220463,3.32067370415 -6.37955141068,1.19128870964,3.34827399254 -6.37655973434,1.1912933588,3.35906338692 -6.42356777191,1.20329296589,3.40766096115 -6.44857883453,1.21029675007,3.44525337219 -6.41060066223,1.20431220531,3.45081877708 -6.37362194061,1.19932770729,3.45737361908 -6.37563705444,1.20233571529,3.48296236992 -6.36465454102,1.20234620571,3.50253415108 -6.47964286804,1.2273286581,3.57537770271 -6.5666437149,1.2473205328,3.6469976902 -6.35769510269,1.20636892319,3.56247091293 -6.38370609283,1.21337234974,3.60107445717 -6.35372638702,1.20938658714,3.61063671112 -6.30974960327,1.20240354538,3.61219644547 -6.33675289154,1.2094026804,3.63999319077 -6.33276939392,1.21141171455,3.66258454323 -6.32178688049,1.21142232418,3.68215894699 -6.34679794312,1.21842622757,3.72175145149 -6.35481262207,1.22243320942,3.75233221054 -6.37082529068,1.2284386158,3.78692746162 -6.35583639145,1.22644615173,3.79269099236 -6.34085512161,1.22645759583,3.81026434898 -6.34186983109,1.22846579552,3.83586359024 -6.34388542175,1.23147392273,3.86344265938 -6.35689926147,1.23648035526,3.89801979065 -6.33891820908,1.23549234867,3.91359758377 -6.33493518829,1.23750185966,3.93816995621 -6.35793876648,1.24350166321,3.96497392654 -6.30896377563,1.23551988602,3.96252965927 -6.32697629929,1.24252510071,4.00011777878 -6.33199119568,1.24553275108,4.02970552444 -6.31601047516,1.24454462528,4.04727315903 -6.35601902008,1.25654566288,4.09887361526 -6.34303760529,1.25655698776,4.11844301224 -6.34704494476,1.25856041908,4.13424062729 -6.35905885696,1.26356697083,4.16981744766 -6.31308364868,1.25658476353,4.16837644577 -6.3041009903,1.25759518147,4.1899561882 -6.31411552429,1.26260185242,4.22354745865 -6.33112859726,1.26860737801,4.26213741302 -6.33614349365,1.27261531353,4.29371404648 -6.3991394043,1.28860723972,4.34853696823 -6.40215492249,1.29161548615,4.37911605835 -6.36817741394,1.28763091564,4.38468837738 -6.35119771957,1.28664314747,4.40225601196 -6.349214077,1.28865253925,4.42983007431 -6.35522937775,1.29366016388,4.46241521835 -6.36423587799,1.29666292667,4.48320531845 -6.33825731277,1.2946767807,4.49378347397 -6.3262758255,1.29468798637,4.51436090469 -6.35428619385,1.30369138718,4.56295013428 -6.32530879974,1.30070614815,4.57251119614 -6.42730474472,1.32669484615,4.67313718796 -6.73326015472,1.39964318275,4.91884613037 -6.4553232193,1.33870267868,4.73752355576 -6.58031463623,1.36968684196,4.85715150833 -6.8242816925,1.42864716053,5.06283569336 -6.7783074379,1.42166543007,5.06239032745 -6.57736444473,1.37971413136,4.94789552689 -6.5893778801,1.38572049141,4.98748779297 -6.48041677475,1.36375141144,4.93902015686 -6.4524307251,1.35976135731,4.93380022049 -6.44844818115,1.36177134514,4.96237277985 -6.40647315979,1.35578870773,4.96193933487 -6.37649583817,1.35280370712,4.9705080986 -6.3645157814,1.35281527042,4.9930768013 -6.54449462891,1.39878833294,5.16173171997 -6.58949327469,1.4107837677,5.2125377655 -6.46053647995,1.38481867313,5.14507389069 -6.4665517807,1.38982641697,5.18166017532 -6.43957424164,1.38684093952,5.19322538376 -6.35960817337,1.3718662262,5.16277265549 -6.29963779449,1.36188733578,5.14733076096 -6.28865623474,1.36289846897,5.16991567612 -6.4766254425,1.40886569023,5.33775949478 -6.53662919998,1.42786288261,5.41936159134 -6.56463956833,1.43786609173,5.47496128082 -6.46067857742,1.41689622402,5.42449712753 -6.36271619797,1.39792501926,5.37704706192 -6.35973405838,1.4009346962,5.40762901306 -6.40674066544,1.41593444347,5.48022556305 -6.39175271988,1.41494226456,5.48500537872 -6.34677886963,1.40796029568,5.48057508469 -6.34479618073,1.41196990013,5.51216125488 -6.34281349182,1.41497969627,5.54473686218 -6.30183982849,1.40899729729,5.54429578781 -6.27586269379,1.40701174736,5.5558681488 -6.28886842728,1.41301393509,5.58465671539 -6.27088880539,1.41202652454,5.6022439003 -6.25191068649,1.41203987598,5.62080764771 -6.28791952133,1.42504179478,5.68640851974 -6.28793668747,1.42905092239,5.72099256516 -6.26995801926,1.42906403542,5.74056005478 -6.26897478104,1.43307352066,5.7741484642 -6.24698877335,1.43008255959,5.77193164825 -6.23800754547,1.43209385872,5.79950475693 -6.23302602768,1.43610417843,5.83008718491 -6.19705200195,1.43112099171,5.83364439011 -6.19506978989,1.43513083458,5.86722707748 -6.18109035492,1.43614327908,5.89079475403 -6.16510248184,1.43415105343,5.89358234406 -6.13712644577,1.43216621876,5.90315580368 -6.14314222336,1.43817436695,5.94473981857 -6.10516786575,1.43319141865,5.94431495667 -6.09518766403,1.43520283699,5.97089385986 -6.08520746231,1.43721437454,5.99846315384 -6.06422996521,1.4372279644,6.01404523849 -6.05724048615,1.43723416328,6.02583026886 -6.05025911331,1.44024503231,6.05541276932 -6.0232834816,1.43826007843,6.06598329544 -6.0043053627,1.43827354908,6.08455371857 -6.00032377243,1.442283988,6.11812925339 -5.97734737396,1.44129824638,6.13269948959 -5.9583697319,1.44131183624,6.15127086639 -5.96337652206,1.44531524181,6.17407512665 -5.94839763641,1.44632792473,6.19664955139 -5.92242193222,1.44434273243,6.20821857452 -5.92343902588,1.44935202599,6.2468047142 -5.89346408844,1.44636797905,6.25437021255 -5.88348436356,1.44937944412,6.28195095062 -5.86250734329,1.44939339161,6.29852390289 -5.85651779175,1.45039963722,6.31230306625 -5.8415389061,1.45141208172,6.33389186859 -5.83155918121,1.45342373848,6.36246585846 -5.80058479309,1.45043969154,6.36803865433 -5.78760576248,1.45245206356,6.39361047745 -5.77862596512,1.45546364784,6.42318725586 -5.76163911819,1.45347189903,6.42397642136 -5.75165939331,1.45648360252,6.45255422592 -5.74567890167,1.46049463749,6.48612880707 -5.71370458603,1.45751094818,6.49069786072 -5.69572687149,1.45752394199,6.50928688049 -5.68574762344,1.4605358839,6.53885793686 -5.65977239609,1.45855116844,6.55042409897 -5.64878416061,1.45855808258,6.55722093582 -5.64680242538,1.4635682106,6.59579849243 -5.62082672119,1.46258318424,6.60637569427 -5.61384677887,1.46559429169,6.63895750046 -5.59187030792,1.4656085968,6.65453147888 -5.56189632416,1.46262454987,6.66109895706 -5.56290483475,1.46662926674,6.68289136887 -5.53892946243,1.46564388275,6.69547128677 -5.51495409012,1.4646589756,6.71003055573 -5.51097345352,1.46966946125,6.74661540985 -5.49599504471,1.47068214417,6.77019739151 -5.48301649094,1.47369468212,6.7967748642 -5.46304035187,1.47370874882,6.81534576416 -5.4470539093,1.47271692753,6.81713104248 -5.43407487869,1.47472918034,6.84272003174 -3.46259903908,0.900148391724,4.43757295609 -3.44462227821,0.899161458015,4.44117212296 -3.42964601517,0.898174762726,4.45073843002 -3.41666889191,0.899187445641,4.4623131752 -5.31320714951,1.47380840778,6.92937803268 -3.40869045258,0.900198996067,4.47989606857 -5.30322885513,1.4768204689,6.96095228195 -5.29125022888,1.47983276844,6.98953151703 -5.27027416229,1.47984683514,7.00611257553 -5.25329685211,1.48186004162,7.0276966095 -5.23332071304,1.48187434673,7.04726266861 -5.20934581757,1.48188912868,7.05984306335 -5.193359375,1.47989749908,7.06162452698 -5.17738199234,1.48191058636,7.08520460129 -5.15540647507,1.4819252491,7.10177373886 -5.13243103027,1.48193967342,7.11535739899 -5.11145544052,1.48195409775,7.1329293251 -5.09647798538,1.4839669466,7.15751600266 -5.08848953247,1.48497366905,7.17029857635 -5.06951332092,1.48598766327,7.19087123871 -5.05153751373,1.48800134659,7.21244859695 -5.03156137466,1.48901534081,7.23102760315 -5.01858329773,1.49102795124,7.25960826874 -4.99460887909,1.49104297161,7.27318143845 -4.97163438797,1.49105787277,7.28874969482 -4.97064304352,1.49406290054,7.310546875 -4.95366716385,1.49607646465,7.33412408829 -4.92769289017,1.49509191513,7.34469747543 -4.90671730042,1.49610614777,7.36227607727 -4.88874101639,1.49711978436,7.38385868073 -4.86476612091,1.49713480473,7.39743280411 -4.84279155731,1.49714946747,7.41400766373 -4.83780193329,1.49915540218,7.43080186844 -4.81782627106,1.50116956234,7.45037841797 -4.79985046387,1.50218355656,7.47394752502 -4.77487611771,1.50219845772,7.48453474045 -4.75889968872,1.50421190262,7.51110744476 -4.74192380905,1.50622546673,7.53568458557 -4.73093605042,1.50723290443,7.54446935654 -4.71096086502,1.50824713707,7.56404972076 -4.69098567963,1.50926136971,7.58462285995 -4.67001008987,1.51027560234,7.602206707 -4.65603256226,1.51328861713,7.63178777695 -4.626060009,1.51130473614,7.63536596298 -4.60608530045,1.51331925392,7.65693378448 -4.60409593582,1.51632475853,7.68072032928 -4.57912158966,1.51633989811,7.69230175018 -4.55214881897,1.51535570621,7.70187234879 -4.53617238998,1.51836919785,7.72944879532 -4.50520038605,1.51538562775,7.73102712631 -4.48622465134,1.51739966869,7.75360393524 -4.4642496109,1.51841425896,7.77018690109 -4.45926094055,1.52042031288,7.78897857666 -4.4432849884,1.52343380451,7.81755256653 -4.42530870438,1.52644753456,7.84113883972 -4.40133571625,1.52646291256,7.85670566559 -4.38535881042,1.52947604656,7.88429069519 -4.36938285828,1.53248953819,7.91286993027 -4.35539627075,1.53149735928,7.91566467285 -4.33242225647,1.53251230717,7.93223953247 -4.31744670868,1.53652596474,7.9648065567 -4.29447174072,1.53754043579,7.97939777374 -4.27949571609,1.54155397415,8.011967659 -4.25852108002,1.54256820679,8.03155231476 -4.24854373932,1.54858076572,8.07412242889 -4.23055887222,1.54658949375,8.06991291046 -4.2125825882,1.54960310459,8.09450435638 -4.20060586929,1.55461609364,8.13407421112 -4.17563247681,1.55463123322,8.14665794373 -4.16765451431,1.56164324284,8.19423103333 -4.15667724609,1.56765568256,8.23481655121 -4.1556968689,1.57766580582,8.29441070557 -4.15570688248,1.58267104626,8.32719612122 -4.14972829819,1.5916826725,8.38077163696 -4.12575483322,1.59169757366,8.39635753632 -4.04979610443,1.57172358036,8.30891704559 -3.99283194542,1.55874538422,8.25748825073 -3.86488771439,1.51478171349,8.0590429306 -3.82891821861,1.51079964638,8.04960823059 -3.82292938232,1.51380574703,8.06741046906 -3.77696275711,1.50482559204,8.0369720459 -3.7619869709,1.50883889198,8.06955242157 -3.73301529884,1.50785505772,8.07312774658 -3.71503996849,1.51086878777,8.09871578217 -3.7310552597,1.52887582779,8.19930458069 -3.70407319069,1.52288651466,8.1750831604 -3.6221165657,1.49791359901,8.06264400482 -3.52916312218,1.46694278717,7.92320728302 -3.3662302494,1.40498661995,7.62674045563 -3.31726455688,1.3930066824,7.57931804657 -3.24630475044,1.37103152275,7.48188352585 -3.22433114052,1.37204611301,7.49446487427 -3.20234799385,1.36705577374,7.47624731064 -3.1693778038,1.36307287216,7.4638209343 -3.14540410042,1.36208772659,7.47040843964 -3.11843252182,1.36110377312,7.47198152542 -3.08746194839,1.3571202755,7.46355485916 -3.05949020386,1.3551363945,7.46212911606 -3.04550433159,1.35414421558,7.46091890335 -3.02153110504,1.35315918922,7.46650934219 -2.99855828285,1.35417413712,7.47708463669 -2.96958684921,1.3511903286,7.47166442871 -2.94061589241,1.3482067585,7.46823120117 -2.92064166069,1.35022079945,7.48382139206 -2.88967061043,1.34623718262,7.47240304947 -2.87568497658,1.34524524212,7.4711894989 -2.85371208191,1.34526002407,7.48376607895 -2.82474064827,1.34227609634,7.47734594345 -2.80076766014,1.34229111671,7.48392629623 -2.77379631996,1.3403069973,7.48350000381 -2.74782395363,1.33932244778,7.48408317566 -2.71685361862,1.33533895016,7.47166109085 -2.71186518669,1.33834517002,7.49444913864 -2.68289470673,1.33536148071,7.48802280426 -2.66292047501,1.33737552166,7.50460863113 -2.63494920731,1.33539152145,7.50018453598 -2.60897731781,1.33340704441,7.50076389313 -2.5870039463,1.33442151546,7.51135158539 -2.56603074074,1.33543610573,7.52692842484 -2.54204821587,1.32944619656,7.49571275711 -2.52807283401,1.33445930481,7.53129291534 -2.51009845734,1.33747315407,7.55487680435 -2.48512601852,1.33648836613,7.55746030807 -2.45515561104,1.33350467682,7.54603672028 -2.34032249451,1.35759401321,7.71533250809 -2.32634735107,1.3636071682,7.75591373444 -2.31136202812,1.36161541939,7.75069904327 -2.31438183784,1.37962508202,7.84928369522 -2.30840444565,1.39163649082,7.91886901855 -2.27643442154,1.38665306568,7.90045022964 -2.26445841789,1.3956656456,7.9510345459 -2.24448490143,1.39867985249,7.97461748123 -2.26348924637,1.41968107224,8.08742141724 -2.26450967789,1.4376912117,8.1890039444 -2.25653243065,1.44970297813,8.25859165192 -2.24455666542,1.45971560478,8.31617546082 -2.2435772419,1.47672605515,8.41376781464 -2.40254974365,1.60970437527,9.11339664459 -2.46155238152,1.67270278931,9.45000553131 -2.45056581497,1.67571008205,9.46679973602 -2.4205956459,1.67572641373,9.47437477112 -2.39562320709,1.67874133587,9.49796199799 -2.3646531105,1.67775785923,9.49954414368 -2.33968162537,1.68177318573,9.52811813354 -2.30771183968,1.67978990078,9.52669525146 -2.27774167061,1.67980611324,9.53327465057 -2.26875424385,1.6848129034,9.56007099152 -2.24378228188,1.68782806396,9.58565807343 -2.21281242371,1.68784463406,9.59023284912 -2.18384218216,1.68886077404,9.60280799866 -2.15587067604,1.68987619877,9.61440181732 -2.13189888,1.69589138031,9.6499786377 -2.10392737389,1.69690680504,9.66356754303 -2.0939412117,1.70191407204,9.69235229492 -2.07696723938,1.71392786503,9.76193237305 -2.05499410629,1.72094225883,9.80652046204 -2.03102254868,1.7279573679,9.84709644318 -2.00205183029,1.72897326946,9.86068153381 -1.97608017921,1.73298847675,9.88926792145 -1.95809590816,1.73099708557,9.87905883789 -1.92912530899,1.73301291466,9.89364337921 -1.88515973091,1.72103202343,9.8362121582 -1.85418975353,1.72004818916,9.83979606628 -1.81722152233,1.71406567097,9.81038093567 -1.78825104237,1.71608150005,9.82496261597 -1.75228285789,1.71009874344,9.80254173279 -1.73529851437,1.70910727978,9.79633045197 -1.7053283453,1.70912325382,9.80491256714 -1.67535817623,1.7101392746,9.81349658966 -1.64538836479,1.71215558052,9.82607078552 -1.61241877079,1.70817184448,9.81366062164 -1.58144950867,1.7091884613,9.82223129272 -1.56146597862,1.70419728756,9.79502391815 -1.53349483013,1.70621275902,9.81261444092 -1.5005261898,1.70422959328,9.80718612671 -1.47255539894,1.70724499226,9.8277721405 -1.43758654594,1.7012617588,9.80036067963 -1.4076167345,1.70327782631,9.8119392395 -1.37364828587,1.69929480553,9.79651355743 -1.35966289043,1.70130252838,9.80830478668 -1.32569420338,1.69731926918,9.78888607025 -1.29872298241,1.70133447647,9.81747436523 -1.26275491714,1.69435155392,9.78105640411 -1.23478400707,1.6973669529,9.80364227295 -1.20381450653,1.69738304615,9.80522441864 -1.1728451252,1.69739925861,9.81080055237 -1.15486097336,1.69340777397,9.78859424591 -1.12589049339,1.69642341137,9.80517959595 -1.09192180634,1.6904399395,9.77876281738 -1.0639513731,1.69545543194,9.80734539032 -1.03298187256,1.69547152519,9.80992412567 -1.00101220608,1.69248759747,9.79751300812 -0.971042275429,1.69350349903,9.80609798431 -0.95505797863,1.69351172447,9.80688095093 -0.924088001251,1.69152748585,9.8004732132 -0.892119050026,1.69054377079,9.79504871368 -0.863148808479,1.69355940819,9.81663322449 -0.833179116249,1.696575284,9.83221244812 -0.798210799694,1.68659198284,9.78379535675 -0.784225165844,1.68859946728,9.79459476471 -0.754255115986,1.69061517715,9.80418014526 -0.72428548336,1.69263088703,9.81976127625 -0.6933157444,1.69164681435,9.81634712219 -0.661346614361,1.68966293335,9.80392742157 -0.628378093243,1.68467926979,9.78050327301 -0.598407745361,1.684694767,9.78209686279 -0.582423448563,1.68370294571,9.77888298035 -0.551453590393,1.68171870708,9.76847076416 -0.521484076977,1.68573439121,9.78905010223 -0.490514397621,1.68375015259,9.78263568878 -0.459545135498,1.68476605415,9.78521537781 -0.429574966431,1.68578147888,9.79180622101 -0.398605614901,1.68579733372,9.79338645935 -0.382621049881,1.68280529976,9.78017711639 -0.352651029825,1.68482077122,9.79276561737 -0.321681410074,1.68283653259,9.78135204315 -0.290712058544,1.68285226822,9.77993297577 -0.259742617607,1.68186807632,9.77451610565 -0.230772033334,1.68988323212,9.81810951233 -0.198803246021,1.68489921093,9.79268550873 -0.183818519115,1.6909070015,9.82647514343 -0.151849374175,1.67892289162,9.7610578537 -0.120879925787,1.67493855953,9.74164104462 -0.0909097120166,1.67595386505,9.74323368073 -0.0599404275417,1.67396962643,9.7338142395 -0.0299702137709,1.67398476601,9.73340702057 -0.0139861227944,1.67799293995,9.75618934631 --0.0239754468203,1.679012537,9.31665992737 --0.0529457889497,1.6800276041,9.31824874878 --0.0679304301739,1.67903542519,9.31403541565 --0.0969006940722,1.67705059052,9.30562400818 --0.125870838761,1.67406570911,9.28820896149 --0.154841214418,1.67608070374,9.29579925537 --0.184810429811,1.67509627342,9.29037189484 --0.212781533599,1.6731108427,9.2779712677 --0.242751136422,1.67712640762,9.29655170441 --0.257735699415,1.6761341095,9.29233646393 --0.285706728697,1.67314875126,9.27693367004 --0.315676063299,1.6741642952,9.27950954437 --0.34464648366,1.67517912388,9.28410053253 --0.373616486788,1.67319417,9.27268314362 --0.403586387634,1.67720937729,9.2922706604 --0.432556420565,1.67622447014,9.28285312653 --0.446541875601,1.67523169518,9.27665138245 --0.47551214695,1.67524659634,9.2742395401 --0.505481541157,1.67626202106,9.27581596375 --0.53345233202,1.67327654362,9.26241016388 --0.56242275238,1.67429149151,9.26199913025 --0.592392265797,1.67530655861,9.26758003235 --0.605378091335,1.67131376266,9.24737644196 --0.635348021984,1.67432880402,9.26096630096 --0.664318025112,1.67334365845,9.25254821777 --0.692288577557,1.67135834694,9.23613548279 --0.721258938313,1.67137312889,9.23672580719 --0.755227208138,1.68238902092,9.28730392456 --0.781198740005,1.67640304565,9.25289726257 --0.796183466911,1.67641067505,9.25368785858 --0.825153589249,1.676425457,9.24827289581 --0.85512316227,1.67644047737,9.24985218048 --0.88409358263,1.67745518684,9.24844264984 --0.916062712669,1.68247056007,9.27202606201 --0.944033265114,1.68048501015,9.25761318207 --0.960018217564,1.6834924221,9.27341175079 --0.98898857832,1.68350708485,9.27000236511 --1.01895844936,1.68552184105,9.27358818054 --1.04992794991,1.68753707409,9.28417205811 --1.07789874077,1.68655133247,9.27276325226 --1.10886847973,1.68956625462,9.28435134888 --1.13783848286,1.68858098984,9.27593326569 --1.1548230648,1.69258856773,9.29573154449 --1.18379318714,1.69260323048,9.28831672668 --1.21576201916,1.69561851025,9.29889202118 --1.24573266506,1.69763290882,9.30649185181 --1.27570211887,1.69764780998,9.30206871033 --1.30667197704,1.70066261292,9.31165981293 --1.33764147758,1.7016774416,9.31624221802 --1.35162711143,1.70168447495,9.31204223633 --1.3815972805,1.70269906521,9.31363296509 --1.41156697273,1.70371365547,9.31021404266 --1.44353628159,1.70672869682,9.32079696655 --1.47050738335,1.70374262333,9.30238819122 --1.50147771835,1.70675706863,9.31298732758 --1.53344666958,1.70877218246,9.31956481934 --1.55043113232,1.71177971363,9.33035850525 --1.58240067959,1.71479451656,9.34094715118 --1.61037135124,1.71280872822,9.32753658295 --1.64434039593,1.71882379055,9.34912586212 --1.67331087589,1.71783792973,9.34171581268 --1.70328104496,1.71885228157,9.33930397034 --1.72126531601,1.72285997868,9.35409832001 --1.75123500824,1.72287452221,9.34767723083 --1.78220498562,1.72388899326,9.35126972198 --1.81017577648,1.72290289402,9.33785820007 --1.84314501286,1.72591769695,9.34944629669 --1.87411510944,1.72793209553,9.35203742981 --1.9040851593,1.72894644737,9.34762382507 --1.92007029057,1.72995352745,9.35242271423 --1.95103991032,1.7309679985,9.35200786591 --1.98201024532,1.73298215866,9.35460281372 --2.01198029518,1.7339963913,9.35019111633 --2.04295063019,1.73501062393,9.35078048706 --2.07392024994,1.73602509499,9.34936618805 --2.107888937,1.74003994465,9.35994720459 --2.11987543106,1.7380464077,9.34674930573 --2.15084528923,1.73906064034,9.34533500671 --2.1838145256,1.74207532406,9.35192012787 --2.21378517151,1.74208927155,9.34851455688 --2.2457549572,1.74510335922,9.35210514069 --2.27772474289,1.74711787701,9.35469341278 --2.30769515038,1.74713170528,9.35028648376 --2.32367968559,1.74813902378,9.34807014465 --2.35465049744,1.7501527071,9.35067462921 --2.38562059402,1.75116682053,9.34826087952 --2.42258834839,1.75618195534,9.3668422699 --2.45155906677,1.75619566441,9.35643196106 --2.48053050041,1.75620913506,9.34903049469 --2.49951386452,1.75821685791,9.35781478882 --2.53048419952,1.75923085213,9.3554058075 --2.56145429611,1.76124477386,9.35199356079 --2.59242463112,1.76225864887,9.34958648682 --2.62739372253,1.76627314091,9.36017417908 --2.6563642025,1.76528680325,9.34876155853 --2.68733525276,1.76730036736,9.34836292267 --2.70531916618,1.76930773258,9.35315132141 --2.73628973961,1.77032160759,9.3497428894 --2.76526069641,1.77033483982,9.3403377533 --2.79823040962,1.77234911919,9.34091949463 --2.82920074463,1.77336263657,9.33751392365 --2.86217069626,1.7753765583,9.34110927582 --2.89314103127,1.77639019489,9.3356962204 --2.91212487221,1.77939772606,9.34348678589 --2.94409489632,1.78041160107,9.34107398987 --2.97406625748,1.78142476082,9.33567619324 --3.00703573227,1.78343868256,9.33526039124 --3.03500747681,1.78245174885,9.32185459137 --3.07097625732,1.78646600246,9.33144378662 --3.0869615078,1.78747284412,9.33023834229 --3.1169321537,1.78848612309,9.32183074951 --3.15490078926,1.79350066185,9.33641910553 --3.18487215042,1.79351377487,9.33001995087 --3.21684193611,1.79452741146,9.3246011734 --3.25181174278,1.79854130745,9.33119773865 --3.28278255463,1.7995544672,9.32579231262 --3.297768116,1.79956114292,9.32058525085 --3.33673596382,1.80457568169,9.33517074585 --3.36570763588,1.80458843708,9.32476997375 --3.39867758751,1.8066021204,9.32235717773 --3.43264770508,1.80961573124,9.32394981384 --3.46261835098,1.80962884426,9.3125333786 --3.49758815765,1.8126424551,9.31813430786 --3.51657271385,1.81564950943,9.32393169403 --3.54654383659,1.81566250324,9.31352138519 --3.57751488686,1.81667554379,9.3061132431 --3.60848546028,1.81668865681,9.29770088196 --3.64245533943,1.81970214844,9.297290802 --3.67642569542,1.82171547413,9.29788684845 --3.71039581299,1.82472872734,9.2984828949 --3.72438144684,1.82373511791,9.28927230835 --3.75535273552,1.82474792004,9.28186702728 --3.78532409668,1.82576072216,9.27145957947 --3.82029414177,1.82877397537,9.27405738831 --3.85226464272,1.82978701591,9.2666425705 --3.88723444939,1.83280050755,9.2672328949 --3.89822149277,1.83080613613,9.253033638 --3.93419098854,1.83381962776,9.2556219101 --3.97016072273,1.83783304691,9.25821304321 --3.997133255,1.83684504032,9.24181461334 --4.03210306168,1.83885836601,9.24140357971 --4.06707334518,1.84187161922,9.24099445343 --4.09404611588,1.84088337421,9.22459602356 --4.10603237152,1.83988940716,9.21038341522 --4.14300203323,1.8439027071,9.21497821808 --4.17397356033,1.8449151516,9.20657539368 --4.20594453812,1.84592783451,9.19816207886 --4.24291467667,1.84994101524,9.20276069641 --4.27188587189,1.84895324707,9.18734741211 --4.30385732651,1.8509657383,9.17994117737 --4.32684087753,1.85497307777,9.19073581696 --4.34781599045,1.85098385811,9.16133785248 --4.38678455353,1.85599720478,9.16792964935 --4.42375421524,1.85901033878,9.16951847076 --4.44872760773,1.85702180862,9.14711284637 --4.4866976738,1.86203491688,9.15170955658 --4.50068378448,1.86104083061,9.14249992371 --4.53165531158,1.86205291748,9.13309955597 --4.56762599945,1.86506581306,9.13269329071 --4.59759759903,1.86607778072,9.11928272247 --4.62856960297,1.86708974838,9.10988330841 --4.67253780365,1.87310349941,9.12447738647 --4.7115073204,1.87811648846,9.12907218933 --4.72549343109,1.87712228298,9.11986446381 --4.76546287537,1.88213539124,9.12646198273 --4.80043363571,1.88414776325,9.12205314636 --4.81541013718,1.87915766239,9.07964134216 --4.81739044189,1.86816561222,9.01624679565 --4.8413643837,1.86617648602,8.9918384552 --4.83834552765,1.85318410397,8.91742610931 --4.84933328629,1.85218942165,8.90422439575 --4.8793053627,1.85320091248,8.89181900024 --4.90327978134,1.85121178627,8.86941814423 --4.93225193024,1.85222327709,8.85501003265 --4.96722316742,1.85423541069,8.85160636902 --5.00419378281,1.85824775696,8.85119915009 --5.01618051529,1.85725319386,8.83899307251 --5.05515050888,1.86126577854,8.8415851593 --5.06812810898,1.8552750349,8.80018424988 --5.10409879684,1.85928726196,8.79677200317 --5.13207244873,1.85929811001,8.78237819672 --5.16104507446,1.85930943489,8.76696777344 --5.18701887131,1.85932016373,8.74756336212 --5.21600151062,1.86432754993,8.76435947418 --5.23397731781,1.86133718491,8.73195838928 --5.2659497261,1.86234867573,8.72255516052 --5.29992103577,1.86536037922,8.71514415741 --5.32389593124,1.86337065697,8.69274234772 --5.34886980057,1.86238133907,8.67033004761 --5.39083957672,1.8683937788,8.6769285202 --5.39083051682,1.86339735985,8.64672851562 --5.42980051041,1.86740958691,8.64732170105 --5.44577789307,1.86341881752,8.61191654205 --5.47675037384,1.8644298315,8.60051345825 --5.50272464752,1.86444032192,8.58111000061 --5.54069566727,1.86845219135,8.57970333099 --5.54768466949,1.86545658112,8.56150627136 --5.58465576172,1.86946821213,8.55809783936 --5.60263204575,1.86647748947,8.52669620514 --5.6446018219,1.87148976326,8.53028488159 --5.66257858276,1.86849915981,8.4988822937 --5.70254945755,1.87251079082,8.50048065186 --5.72252559662,1.87052035332,8.47207736969 --5.74551010132,1.87352645397,8.47788238525 --5.76048707962,1.86953532696,8.44147396088 --5.7984585762,1.87354683876,8.43906879425 --5.82443284988,1.87355697155,8.41865921021 --5.85540628433,1.8745675087,8.40625572205 --5.87638235092,1.87257695198,8.37985515594 --5.90835571289,1.87458753586,8.36845016479 --5.91334533691,1.87159144878,8.34825515747 --5.9533162117,1.87660300732,8.34784889221 --5.97229290009,1.87361228466,8.31743812561 --6.01026391983,1.87762343884,8.3140335083 --6.03024053574,1.87563252449,8.28663349152 --6.07221126556,1.88064396381,8.2882270813 --6.07720088959,1.87864804268,8.2670211792 --6.11017417908,1.88065838814,8.25762557983 --6.13414907455,1.87966787815,8.23421573639 --6.16412401199,1.88167786598,8.22082042694 --6.18809938431,1.88068723679,8.19841766357 --6.22407150269,1.8836979866,8.19100952148 --6.23904943466,1.87970626354,8.15660572052 --6.26303434372,1.88371229172,8.16039943695 --6.29100894928,1.88472187519,8.1440038681 --6.31498527527,1.88373112679,8.12160110474 --6.33496189117,1.8817397356,8.09420013428 --6.36293697357,1.88274943829,8.07679653168 --6.38491296768,1.88175833225,8.05138874054 --6.4138879776,1.88276791573,8.03599262238 --6.42187643051,1.88177204132,8.01878261566 --6.45585012436,1.88378214836,8.00938510895 --6.47982645035,1.88379120827,7.98698234558 --6.5058016777,1.88380038738,7.96657657623 --6.52377939224,1.88180875778,7.93616676331 --6.55675363541,1.88381850719,7.92577362061 --6.55974388123,1.88082206249,7.90357017517 --6.57772111893,1.87883043289,7.87315940857 --6.58970069885,1.87483799458,7.83675670624 --5.35399150848,1.49572563171,6.31820774078 --5.33897638321,1.48473131657,6.25879192352 --5.32396221161,1.47473692894,6.20139122009 --5.31294631958,1.46574318409,6.14797830582 --5.30893802643,1.46174633503,6.1227684021 --5.30392074585,1.45475304127,6.07736063004 --5.29390525818,1.44575917721,6.02695608139 --5.29888534546,1.4417668581,5.99354791641 --5.28387117386,1.43177247047,5.93814277649 --5.29085111618,1.42778015137,5.90773677826 --5.2838344574,1.4207867384,5.86132383347 --5.30881929398,1.42479264736,5.87012195587 --5.2968044281,1.4167984724,5.81972122192 --5.29478645325,1.41080546379,5.77930641174 --5.30776453018,1.40881383419,5.7558965683 --5.30374717712,1.40282046795,5.71448850632 --5.30173015594,1.39682734013,5.67608737946 --5.3017206192,1.39383101463,5.65687417984 --5.30970096588,1.39183855057,5.63048410416 --5.42865371704,1.41985607147,5.72008228302 --5.24567985535,1.36284697056,5.49066305161 --5.25366020203,1.36085486412,5.46325063705 --5.24564361572,1.35386109352,5.41984367371 --5.24362564087,1.34786808491,5.38243055344 --5.245616436,1.34587180614,5.367228508 --5.24059963226,1.33987832069,5.32782363892 --5.25357866287,1.3388863802,5.30641317368 --5.25855875015,1.3358938694,5.27700233459 --5.25954055786,1.33090090752,5.24460220337 --5.2755188942,1.33090925217,5.22618865967 --5.28949737549,1.32991743088,5.20678710938 --5.28748941422,1.32792067528,5.18859004974 --5.30846595764,1.32892930508,5.17517662048 --5.31244707108,1.32493662834,5.14577054977 --5.33142471313,1.32594490051,5.13136863708 --5.36339902878,1.32995450497,5.12896156311 --5.3633813858,1.32596135139,5.09555006027 --5.377368927,1.32696592808,5.09234666824 --5.39034843445,1.32697355747,5.07295417786 --5.41932439804,1.32998263836,5.06754970551 --5.43730163574,1.32999098301,5.05113744736 --5.45328044891,1.32999897003,5.03373575211 --5.47225856781,1.33100712299,5.01832437515 --5.50123405457,1.3350161314,5.01292514801 --5.51822137833,1.33702075481,5.01171636581 --5.52120256424,1.33302772045,4.98231363297 --5.55617761612,1.33803701401,4.98191261292 --5.57015705109,1.3380446434,4.96251058578 --5.63412475586,1.35005569458,4.98811769485 --5.69709300995,1.3630669117,5.01171684265 --5.71307182312,1.36307454109,4.99331235886 --5.72006177902,1.36207830906,4.98310852051 --5.75203704834,1.36608719826,4.97870540619 --5.77101516724,1.36709499359,4.96229410172 --5.79699230194,1.37010324001,4.952896595 --5.83796596527,1.37611234188,4.9565038681 --5.86894178391,1.38012087345,4.95009469986 --5.91791439056,1.38913059235,4.9596991539 --6.03387975693,1.4161413908,5.04151105881 --6.10984611511,1.43115270138,5.07211208344 --6.15881872177,1.43916201591,5.08072376251 --6.16779947281,1.43816888332,5.05431175232 --6.16578292847,1.43317484856,5.0199098587 --6.1487698555,1.42518007755,4.97249507904 --6.12776613235,1.41718173027,4.93929290771 --6.14974355698,1.41918945312,4.92388105392 --6.20071601868,1.42819869518,4.93248176575 --6.22369432449,1.43020617962,4.91908836365 --6.26166915894,1.43521475792,4.91567468643 --6.29364585876,1.43922245502,4.90928411484 --6.35761499405,1.4512321949,4.92688703537 --6.3636059761,1.45023560524,4.9156908989 --6.41357851028,1.45924448967,4.92128515244 --6.43755674362,1.46125173569,4.90688085556 --6.48353099823,1.46826016903,4.91049480438 --6.49851083755,1.46826708317,4.88807821274 --6.56248140335,1.48027646542,4.90368032455 --6.56346464157,1.47628223896,4.87228441238 --6.62244415283,1.48828828335,4.90009021759 --6.65542125702,1.49329578876,4.89168930054 --5.50863981247,1.21324050426,4.00707912445 --5.52961826324,1.21424806118,3.9946668148 --5.54459810257,1.21525537968,3.97825956345 --5.54558134079,1.21226155758,3.95286870003 --6.84130191803,1.51933348179,4.86269378662 --6.86428976059,1.52233755589,4.86249303818 --6.90626478195,1.52834498882,4.85909175873 --6.93724298477,1.53235197067,4.84870147705 --7.00421333313,1.54436063766,4.86230278015 --7.02019405365,1.54436683655,4.83989715576 --7.05017232895,1.54837346077,4.8274974823 --7.10915327072,1.56037890911,4.85231256485 --7.13313245773,1.56238532066,4.83490610123 --7.17110919952,1.56739223003,4.82750844955 --7.23708057404,1.57940030098,4.83911895752 --7.25906085968,1.58040654659,4.81971073151 --7.31403493881,1.59041392803,4.82331991196 --7.33201599121,1.59041976929,4.80192184448 --7.39099693298,1.60242486,4.82372522354 --7.42297554016,1.60643112659,4.81133079529 --7.48094844818,1.61643850803,4.81493091583 --7.50592851639,1.61844432354,4.79753494263 --7.55090522766,1.62545096874,4.79314470291 --7.59288167953,1.63145744801,4.78574466705 --7.63785839081,1.638463974,4.78034877777 --7.68084287643,1.64646804333,4.7901506424 --7.72481918335,1.65247440338,4.78375673294 --7.76279735565,1.6584802866,4.77336072922 --7.8167719841,1.66648697853,4.77196025848 --7.85175132751,1.67149269581,4.75956773758 --7.9357213974,1.6875,4.77718830109 --8.03668880463,1.70650780201,4.80380392075 --8.07467460632,1.71351134777,4.80961322784 --8.12065029144,1.72051727772,4.80120706558 --8.15761566162,1.7215269804,4.75341081619 --8.1955947876,1.72653234005,4.74101781845 --8.21057701111,1.72653698921,4.714615345 --8.23455905914,1.72854185104,4.69321250916 --8.26254653931,1.7335447073,4.69201755524 --8.29252719879,1.73654961586,4.67462491989 --8.32450771332,1.74055457115,4.65722084045 --8.37048530579,1.74755990505,4.64782190323 --8.39946651459,1.7505645752,4.62942886353 --8.44644451141,1.75756967068,4.62104129791 --8.48443126678,1.76457262039,4.62383985519 --8.98433208466,1.87158823013,4.86556720734 --9.0153131485,1.87459242344,4.84516906738 --9.01330089569,1.87159585953,4.80676364899 --9.02428531647,1.86959958076,4.77535915375 --9.01327419281,1.86460256577,4.73295783997 --9.01326084137,1.86060619354,4.69554710388 --9.01425361633,1.85960781574,4.67734098434 --9.00424194336,1.85361111164,4.63594055176 --9.01822662354,1.85361468792,4.60653734207 --9.0102148056,1.84861791134,4.56613302231 --9.02119922638,1.84762144089,4.53472328186 --8.95519733429,1.83062374592,4.46530675888 --7.99933719635,1.619612813,3.94464969635 --7.99533033371,1.61761474609,3.92644357681 --7.99431705475,1.61461865902,3.8940384388 --7.98930358887,1.61062276363,3.85963010788 --7.99128961563,1.60862672329,3.82922935486 --7.98627614975,1.60463058949,3.79481816292 --7.98026323318,1.60063457489,3.76041126251 --7.98624849319,1.59963858128,3.73200845718 --7.98124217987,1.59664058685,3.71380257607 --7.97522974014,1.59364449978,3.67939138412 --7.9702167511,1.58964836597,3.64598560333 --7.97820186615,1.58865237236,3.61858057976 --7.96519041061,1.58365619183,3.58217930794 --7.96417665482,1.58065998554,3.55077171326 --7.95816373825,1.57666385174,3.51736545563 --7.96715593338,1.57766580582,3.50616550446 --7.95914316177,1.57366967201,3.47175502777 --7.98812580109,1.57767355442,3.45435905457 --8.03510475159,1.58467757702,3.44395685196 --8.1020822525,1.59668147564,3.44357991219 --8.16406059265,1.60768520832,3.43918275833 --8.22203826904,1.61768877506,3.43379974365 --8.27402496338,1.62669062614,3.44061136246 --8.33600234985,1.6376940012,3.43521475792 --8.3799829483,1.64469742775,3.42282652855 --8.43796157837,1.65470063686,3.41543412209 --8.5039396286,1.6657037735,3.41104459763 --8.56392002106,1.67670667171,3.40466451645 --8.6199054718,1.68670809269,3.41147542 --9.06983280182,1.77870869637,3.56219911575 --9.43277263641,1.85170924664,3.67490267754 --9.44875812531,1.85271155834,3.64650344849 --9.46574401855,1.85371387005,3.61810064316 --9.47273159027,1.8527162075,3.58569407463 --9.49271774292,1.85471820831,3.5593020916 --9.50071048737,1.85471940041,3.54510331154 --9.51369762421,1.85572147369,3.51570653915 --9.51868534088,1.85372376442,3.48229646683 --9.53467178345,1.8547257185,3.45389890671 --9.54965877533,1.85572779179,3.42449450493 --9.56864547729,1.85672974586,3.397097826 --9.57263278961,1.8557318449,3.3636906147 --9.5886259079,1.85773265362,3.35249638557 --9.60161304474,1.85873448849,3.32310080528 --9.62759876251,1.8617361784,3.29770255089 --9.6345872879,1.86073803902,3.26529574394 --9.63557624817,1.85873997211,3.23189973831 --9.65356349945,1.8607416153,3.20349764824 --9.66055107117,1.8597433567,3.17109036446 --9.6645450592,1.85874438286,3.15488481522 --9.6815328598,1.86074578762,3.1264872551 --9.69052028656,1.86074745655,3.09508419037 --9.69850921631,1.85974907875,3.06368470192 --9.7054977417,1.85875070095,3.03228878975 --9.72448539734,1.8607519865,3.00388550758 --9.73647403717,1.86175346375,2.97348380089 --9.75746631622,1.86475372314,2.96329069138 --9.7654542923,1.86475515366,2.93189191818 --9.77344322205,1.86375665665,2.8994808197 --9.76643371582,1.86075842381,2.86408424377 --9.79841995239,1.86475896835,2.83968853951 --9.81340789795,1.8667601347,2.80927824974 --9.79140472412,1.86076152325,2.78607368469 --9.81939315796,1.86476206779,2.76068162918 --9.82138252258,1.86376357079,2.72727704048 --9.8373708725,1.86476445198,2.69787669182 --9.8433599472,1.86376571655,2.6654715538 --9.87434673309,1.8687659502,2.64108610153 --9.8833360672,1.86876690388,2.60867238045 --9.90032958984,1.87176692486,2.59748840332 --9.91131877899,1.87176775932,2.5660815239 --9.91830921173,1.87176883221,2.53367424011 --9.93229866028,1.87276935577,2.50428342819 --9.93828773499,1.87177026272,2.47187924385 --9.94627761841,1.87177109718,2.44048142433 --9.96026706696,1.87277150154,2.41007900238 --9.96826076508,1.87377178669,2.39487552643 --9.96125221252,1.87077307701,2.35947012901 --9.99223995209,1.87577271461,2.33307123184 --9.99623012543,1.87477362156,2.30067253113 --10.0052213669,1.8747740984,2.26927304268 --9.99821281433,1.87177538872,2.2338654995 --10.0361995697,1.8777743578,2.20846557617 --10.0301961899,1.8757750988,2.19026184082 --10.0321865082,1.87477588654,2.15786767006 --10.0521764755,1.87777554989,2.1284661293 --10.0441675186,1.87477684021,2.09305882454 --10.0781564713,1.87977576256,2.06666231155 --10.0961465836,1.8827753067,2.03726792336 --10.0861387253,1.87877655029,2.00186467171 --10.0931339264,1.87977659702,1.98666584492 --10.127122879,1.88477528095,1.95926213264 --10.1241140366,1.88277590275,1.92586684227 --10.1401042938,1.88477551937,1.89546740055 --10.1560955048,1.88677501678,1.86506867409 --10.1400871277,1.88277637959,1.82764995098 --10.1710777283,1.88677501678,1.80025851727 --10.1890726089,1.89077401161,1.7870644331 --10.197063446,1.8907738924,1.75465917587 --10.1940565109,1.88877427578,1.72126269341 --10.2270460129,1.89377248287,1.6928602457 --10.2360372543,1.89477217197,1.66146636009 --10.23802948,1.89377212524,1.62806081772 --10.2650194168,1.89877045155,1.59866058826 --10.2660160065,1.89777052402,1.58246433735 --10.2830076218,1.89976942539,1.55207085609 --10.3059978485,1.90376782417,1.52166831493 --10.2939910889,1.89976871014,1.48626184464 --10.3129825592,1.90276730061,1.45586705208 --10.3179750443,1.90276682377,1.42245781422 --10.341966629,1.90676498413,1.39306950569 --10.3309631348,1.90376567841,1.37385439873 --10.34395504,1.90576446056,1.34245848656 --10.3519477844,1.90676367283,1.31005775928 --10.3509407043,1.90476346016,1.27665734291 --10.3789319992,1.90976107121,1.24625575542 --10.3539266586,1.90376257896,1.20984864235 --10.3639221191,1.90576159954,1.19364094734 --10.3719148636,1.90676057339,1.16124105453 --10.395907402,1.90975832939,1.13084793091 --10.3979005814,1.90975761414,1.09744358063 --10.413892746,1.91175580025,1.06604874134 --10.4258861542,1.91375422478,1.03364658356 --10.4268798828,1.912753582,1.00024390221 --10.4528751373,1.91775107384,0.986048519611 --10.4558677673,1.91775012016,0.952644586563 --10.4538621902,1.9167495966,0.919244945049 --10.4628553391,1.91774809361,0.886847853661 --10.430850029,1.91075003147,0.84942317009 --10.4498434067,1.91374754906,0.818029999733 --10.4708366394,1.91774487495,0.786636471748 --10.4758338928,1.91774404049,0.770438313484 --10.4658269882,1.91574394703,0.73501843214 --10.4708213806,1.91574251652,0.70262503624 --10.4848146439,1.917740345,0.670226514339 --10.4818086624,1.91673958302,0.635813653469 --10.509803772,1.92173576355,0.604421377182 --10.5157976151,1.92273414135,0.571016788483 --10.5207948685,1.92373299599,0.554819822311 --10.5137891769,1.9217325449,0.520408987999 --10.5157833099,1.92173111439,0.487006247044 --10.5237779617,1.92272913456,0.454613804817 --10.5417718887,1.9257260561,0.421206772327 --10.5527667999,1.92772352695,0.388814777136 --10.5427618027,1.92572319508,0.354403555393 --10.5477581024,1.92572200298,0.338208079338 --10.547753334,1.92572057247,0.303794384003 --10.5567483902,1.92671811581,0.270391911268 --10.5567436218,1.92671656609,0.236990436912 --10.5637388229,1.92771434784,0.203588783741 --10.5527334213,1.92571401596,0.170187279582 --10.5747318268,1.92971074581,0.153993099928 --10.5687265396,1.9287096262,0.119579412043 --10.5787210464,1.92970693111,0.0861793607473 --10.589717865,1.93170392513,0.0527799427509 --10.5827131271,1.93070304394,0.0193778369576 --10.5887079239,1.93170034885,-0.015033941716 --10.563703537,1.92670154572,-0.048441324383 --10.5996990204,1.93369531631,-0.0818322896957 --10.6156978607,1.93669247627,-0.099033407867 --10.6256933212,1.93868935108,-0.132429674268 --10.6256895065,1.93868732452,-0.165829181671 --10.6316862106,1.93968451023,-0.200238108635 --10.6316814423,1.93968248367,-0.233637392521 --10.6496782303,1.94267809391,-0.268039315939 --10.6456747055,1.94267642498,-0.30144032836 --10.6506729126,1.94367468357,-0.318642854691 --10.6606683731,1.94567108154,-0.353047311306 --10.6716661453,1.94766736031,-0.386438161135 --10.67466259,1.94866466522,-0.420845866203 --10.6916589737,1.95165991783,-0.455242872238 --10.6886558533,1.95165789127,-0.489654123783 --10.7046546936,1.95465445518,-0.506845891476 --10.6796503067,1.94965529442,-0.540262639523 --10.6906480789,1.95265138149,-0.574662446976 --10.694644928,1.95364820957,-0.609067440033 --10.7056417465,1.9556440115,-0.643465280533 --10.696639061,1.95364260674,-0.676869809628 --10.7026367188,1.95563900471,-0.711271941662 --10.6936349869,1.95363891125,-0.728484988213 --10.7096328735,1.95763385296,-0.762875974178 --10.7136297226,1.95863044262,-0.797278702259 --10.6926259995,1.95463049412,-0.830697834492 --10.7096252441,1.95862519741,-0.866097331047 --10.6976222992,1.95662391186,-0.899506926537 --10.6916189194,1.95562195778,-0.932909607887 --10.6886177063,1.95562076569,-0.950117230415 --10.6866149902,1.95561814308,-0.983515143394 --10.6856126785,1.95561516285,-1.01792359352 --10.6796102524,1.95561301708,-1.05132722855 --10.6906089783,1.95760810375,-1.08673012257 --10.7016077042,1.96060311794,-1.12213230133 --10.710606575,1.96259844303,-1.15753626823 --10.7166061401,1.96459579468,-1.17472994328 --10.7116041183,1.96359324455,-1.20914244652 --10.7236032486,1.96658802032,-1.2445397377 --10.712600708,1.96558618546,-1.27795028687 --10.7175998688,1.96658205986,-1.3123459816 --10.7135982513,1.96657907963,-1.34675681591 --10.7215976715,1.96957409382,-1.38215851784 --10.7215967178,1.96957230568,-1.39936006069 --10.7395973206,1.97356569767,-1.43575406075 --10.7235946655,1.97156465054,-1.46917402744 --10.7275934219,1.97256016731,-1.50356864929 --10.7275934219,1.97355639935,-1.53797078133 --10.7135906219,1.97155499458,-1.57138812542 --10.7115898132,1.97255134583,-1.60579407215 --10.7185907364,1.97454810143,-1.6239926815 --10.7435922623,1.97953975201,-1.6623891592 --10.7375907898,1.97953689098,-1.69579005241 --10.7325897217,1.97953367233,-1.7302005291 --10.7105875015,1.97553348541,-1.76161253452 --10.7305898666,1.98052573204,-1.80001544952 --10.7315893173,1.98252129555,-1.83441257477 --10.7465906143,1.98551642895,-1.85461294651 --10.7315883636,1.98351490498,-1.88702178001 --10.7555913925,1.98950612545,-1.92541062832 --10.7265892029,1.98450708389,-1.95582938194 --10.7495918274,1.99049830437,-1.99522984028 --10.744591713,1.99049472809,-2.02963829041 --10.7575931549,1.99448776245,-2.06703710556 --10.7415914536,1.99148857594,-2.0812394619 --10.7525930405,1.99448180199,-2.11864185333 --10.7465934753,1.99447822571,-2.15305185318 --10.7835988998,2.0034661293,-2.19544267654 --10.7846002579,2.00446105003,-2.23084402084 --10.7645988464,2.00246024132,-2.2622551918 --10.7615995407,2.00245833397,-2.27945947647 --10.7686014175,2.00445199013,-2.31686687469 --10.7586011887,2.00444889069,-2.35027456284 --10.7636032104,2.00644302368,-2.38667488098 --10.7626037598,2.00743794441,-2.42208003998 --10.7666063309,2.00943207741,-2.45848178864 --10.7596073151,2.00942826271,-2.49289178848 --10.7716093063,2.0124232769,-2.51308560371 --10.7586097717,2.01142048836,-2.54650139809 --10.7686128616,2.01541304588,-2.58490610123 --10.7816171646,2.01940488815,-2.62329983711 --10.7976207733,2.02339601517,-2.66269445419 --10.8036251068,2.02638912201,-2.70009565353 --10.7916250229,2.02538609505,-2.73350667953 --10.8026275635,2.02838087082,-2.75470972061 --10.8026304245,2.03037500381,-2.79111647606 --10.8036336899,2.03236913681,-2.82751941681 --10.8186397552,2.03635978699,-2.86792087555 --10.8106403351,2.03635573387,-2.90232872963 --10.7966413498,2.03535294533,-2.93473434448 --10.7936429977,2.03634738922,-2.97114825249 --10.7816429138,2.03534722328,-2.98635697365 --10.802649498,2.04133653641,-3.02774500847 --10.7846498489,2.03933429718,-3.06016397476 --10.7876548767,2.0413274765,-3.09756660461 --10.7896585464,2.04332065582,-3.13497185707 --10.8016643524,2.04831171036,-3.17436361313 --10.7936658859,2.04830694199,-3.20978045464 --10.8176727295,2.05429816246,-3.23497152328 --10.8096752167,2.05429363251,-3.26937627792 --10.8156805038,2.05728530884,-3.30878472328 --10.8096828461,2.05828022957,-3.34419226646 --10.8016862869,2.0582754612,-3.37859606743 --10.7976894379,2.05926966667,-3.41500639915 --10.7906923294,2.06026434898,-3.45041704178 --10.8147001266,2.06625533104,-3.4756000042 --10.8117036819,2.06724882126,-3.51301550865 --10.8067083359,2.06924319267,-3.54841685295 --10.8287172318,2.07523059845,-3.59281039238 --10.8117189407,2.07422780991,-3.62623500824 --10.8187265396,2.07721853256,-3.66563010216 --10.8337345123,2.08320760727,-3.70802474022 --10.8297367096,2.08320474625,-3.72623467445 --10.8267421722,2.08519816399,-3.76364541054 --10.8337488174,2.08818888664,-3.8040471077 --10.8157510757,2.08718633652,-3.83545327187 --10.8227586746,2.09117674828,-3.87686395645 --10.835767746,2.09616541862,-3.91925907135 --10.8177700043,2.09416270256,-3.9516749382 --10.8347768784,2.09915399551,-3.97687029839 --10.8427848816,2.10314393044,-4.01827192307 --10.8187866211,2.1011428833,-4.04768133163 --10.8317956924,2.10613083839,-4.09209156036 --10.8408050537,2.11012077332,-4.13348531723 --10.8468141556,2.11411070824,-4.17489099503 --10.8308124542,2.11211109161,-4.18809700012 --10.8428230286,2.11709952354,-4.23149585724 --10.8288269043,2.11609482765,-4.26591348648 --10.8318347931,2.12008571625,-4.30631828308 --10.8318433762,2.12307715416,-4.34572505951 --10.8248491287,2.12407064438,-4.38213062286 --10.8208560944,2.12606310844,-4.42054367065 --10.8108568192,2.12506175041,-4.43574428558 --10.8198671341,2.12905025482,-4.47914886475 --10.8058719635,2.12904548645,-4.5135641098 --10.8068809509,2.13203620911,-4.55397224426 --10.7878837585,2.13103318214,-4.58538007736 --10.7778892517,2.13202691078,-4.62179708481 --10.7658939362,2.13202166557,-4.65620279312 --10.7739009857,2.13501477242,-4.67940092087 --10.7439002991,2.13201451302,-4.70682048798 --10.7619161606,2.13899970055,-4.75522518158 --10.7249135971,2.13400173187,-4.77964878082 --10.7249221802,2.13699245453,-4.82005691528 --10.7229318619,2.13998365402,-4.85946321487 --10.7209405899,2.14197468758,-4.89886856079 --10.7139482498,2.14396739006,-4.9362783432 --10.7219552994,2.14696002007,-4.96048069 --10.7059593201,2.14695525169,-4.99389314651 --10.6779613495,2.14395427704,-5.022315979 --10.682972908,2.14794301987,-5.06471395493 --10.665977478,2.14793848991,-5.09813165665 --10.6579856873,2.1499311924,-5.13554334641 --10.6519880295,2.14992833138,-5.15274429321 --10.6419963837,2.15092134476,-5.18915605545 --10.6189985275,2.14991879463,-5.21957540512 --10.6090068817,2.15091180801,-5.25598669052 --10.5970134735,2.15090560913,-5.29139757156 --10.5470075607,2.14391183853,-5.30883169174 --10.5490188599,2.14790081978,-5.35123920441 --10.5530261993,2.15089416504,-5.37444591522 --10.5420341492,2.15188741684,-5.40985155106 --10.5440454483,2.15587663651,-5.45225524902 --10.5360546112,2.15786838531,-5.49067306519 --10.5300645828,2.15985989571,-5.52907943726 --10.5380792618,2.16484594345,-5.57548570633 --10.5340890884,2.16783666611,-5.61488866806 --10.5320949554,2.16883182526,-5.6350941658 --10.5191030502,2.16982555389,-5.67050647736 --10.5141134262,2.17281627655,-5.70991325378 --10.5111246109,2.17580604553,-5.75132656097 --10.4971323013,2.17679953575,-5.78674268723 --10.4761381149,2.17579579353,-5.81816005707 --10.4761505127,2.17978453636,-5.86056375504 --10.486161232,2.18377494812,-5.88776636124 --10.524189949,2.19574999809,-5.95014095306 --10.6142377853,2.21970486641,-6.04350757599 --10.6962852478,2.24166297913,-6.13186407089 --10.7723293304,2.26262235641,-6.21822929382 --10.7463340759,2.26061940193,-6.24865198135 --10.7463493347,2.26460671425,-6.29406404495 --10.7213478088,2.26160979271,-6.30228042603 --10.7013549805,2.26160478592,-6.33468770981 --10.6763601303,2.2606010437,-6.36611557007 --10.6323575974,2.25460529327,-6.38554430008 --10.6043615341,2.25260305405,-6.41396379471 --10.593372345,2.25459432602,-6.45338392258 --10.5453681946,2.24759984016,-6.46981287003 --10.5253677368,2.2456009388,-6.48103237152 --10.4993724823,2.24459815025,-6.51045131683 --10.4603719711,2.23960042,-6.53187704086 --10.4163675308,2.23460483551,-6.55030679703 --10.3923749924,2.23360085487,-6.58173513412 --10.371380806,2.23359632492,-6.61314582825 --10.3543901443,2.2335896492,-6.64856719971 --10.3333892822,2.23159170151,-6.65777826309 --10.3063926697,2.22958922386,-6.68619966507 --10.2743959427,2.22658872604,-6.71162462234 --10.2393960953,2.22358965874,-6.7350525856 --10.2073984146,2.22058916092,-6.76047992706 --10.1914081573,2.22258234024,-6.79589748383 --10.1444034576,2.21558833122,-6.81133174896 --10.1244020462,2.21358966827,-6.82155036926 --10.0894031525,2.21059083939,-6.84397411346 --10.0714120865,2.21158456802,-6.87839698792 --10.0384130478,2.20758485794,-6.90181779861 --10.0134181976,2.20758152008,-6.93124198914 --9.97341632843,2.20258522034,-6.94966602325 --9.94241905212,2.20058441162,-6.9750957489 --9.92742061615,2.19958424568,-6.98730278015 --9.89642333984,2.19658350945,-7.0127325058 --9.86542510986,2.19458293915,-7.03715515137 --9.83442783356,2.19258236885,-7.06258773804 --9.82644271851,2.19557189941,-7.10299825668 --9.77443408966,2.18858098984,-7.11243152618 --9.77244186401,2.19057440758,-7.13464164734 --9.71743202209,2.18258500099,-7.14208078384 --9.67642879486,2.17758893967,-7.15951442719 --9.65043354034,2.17658638954,-7.1869354248 --9.62343883514,2.17558431625,-7.21436357498 --9.61145114899,2.17757511139,-7.25177526474 --9.55644035339,2.16958618164,-7.2582154274 --9.57345962524,2.17657089233,-7.29441404343 --9.5024394989,2.165589571,-7.28785514832 --9.47744560242,2.16458630562,-7.31628131866 --9.47946643829,2.16957092285,-7.36368083954 --9.41644954681,2.16058588028,-7.36312532425 --9.40946578979,2.16357398033,-7.40554475784 --9.37346553802,2.16057634354,-7.42497301102 --9.36347007751,2.16057348251,-7.4411854744 --9.30545520782,2.15258693695,-7.44261932373 --9.2914686203,2.15457820892,-7.48004627228 --9.25246620178,2.15058207512,-7.49647426605 --9.22346878052,2.1485812664,-7.52089881897 --9.20247745514,2.14957642555,-7.55131721497 --9.16747665405,2.14657855034,-7.57074451447 --9.15247821808,2.14557814598,-7.5829615593 --9.14449501038,2.14956665039,-7.62437677383 --9.11249637604,2.14656710625,-7.64680862427 --9.04547595978,2.13558554649,-7.63924884796 --9.02948760986,2.13757777214,-7.67467403412 --8.97347354889,2.12959098816,-7.67611312866 --8.93947410583,2.12659287453,-7.69553995132 --8.94548892975,2.13158178329,-7.72474384308 --8.90148258209,2.12558865547,-7.73617982864 --8.86448001862,2.12259221077,-7.75260734558 --8.85749721527,2.12657999992,-7.7950220108 --8.81249046326,2.12158751488,-7.80546236038 --8.78349399567,2.11958694458,-7.82888793945 --8.78952026367,2.12756752968,-7.88229131699 --8.7845287323,2.12956213951,-7.90250062943 --8.7575340271,2.12856006622,-7.92792701721 --8.71152496338,2.12256836891,-7.9363617897 --8.67652416229,2.11957144737,-7.95378684998 --8.63752174377,2.11557602882,-7.96821975708 --8.61853218079,2.11756944656,-8.00165176392 --8.58152961731,2.1145734787,-8.01707935333 --8.55452251434,2.1105799675,-8.0172996521 --8.55354595184,2.116563797,-8.06571006775 --8.51354122162,2.1125690937,-8.07914733887 --8.48054122925,2.10957121849,-8.09756851196 --8.46255397797,2.11156368256,-8.13199996948 --8.41854572296,2.1065723896,-8.13942432404 --8.39255142212,2.10657000542,-8.16484832764 --8.384557724,2.1075656414,-8.18306446075 --8.35055732727,2.10456776619,-8.20149803162 --8.33257007599,2.10656094551,-8.23492050171 --8.30257225037,2.10556077957,-8.25634670258 --8.26156711578,2.10156726837,-8.26778507233 --8.24557971954,2.1035592556,-8.30219841003 --8.23960113525,2.10854482651,-8.347615242 --8.19858264923,2.10156035423,-8.33284473419 --8.17358970642,2.10155749321,-8.35927009583 --8.14259243011,2.09955811501,-8.37969875336 --8.10959243774,2.09756016731,-8.3981294632 --8.07659339905,2.09556174278,-8.41656112671 --8.04959774017,2.09556007385,-8.44098949432 --8.03660106659,2.09555864334,-8.45420646667 --8.01260852814,2.09555530548,-8.48062515259 --7.9936208725,2.0975484848,-8.5140542984 --7.95461559296,2.09355473518,-8.52447795868 --7.9316239357,2.09455037117,-8.55290317535 --7.90863323212,2.09554600716,-8.58132839203 --7.87363195419,2.09254908562,-8.59776496887 --7.84662294388,2.08855700493,-8.59498310089 --7.83364057541,2.09254622459,-8.63440513611 --7.79964017868,2.09054899216,-8.65083503723 --7.7566318512,2.08555746078,-8.65827655792 --7.74665260315,2.09054470062,-8.70069503784 --7.71365261078,2.08854675293,-8.71812534332 --7.69266366959,2.0895409584,-8.74854850769 --7.67666387558,2.08854198456,-8.75776290894 --7.6406621933,2.08654618263,-8.77219963074 --7.61667060852,2.08754229546,-8.7996263504 --7.59167766571,2.08753943443,-8.82504653931 --7.55967855453,2.08554077148,-8.84347820282 --7.53568792343,2.08653712273,-8.87090492249 --7.51069641113,2.08753323555,-8.89834022522 --7.49369525909,2.08653521538,-8.90555095673 --7.46369886398,2.08553528786,-8.92598152161 --7.4487156868,2.08852529526,-8.96339797974 --7.41471529007,2.08752799034,-8.97983551025 --7.38972425461,2.08752441406,-9.00727081299 --7.36573266983,2.08852052689,-9.03368854523 --7.32772874832,2.08552622795,-9.04512786865 --7.31172895432,2.08452749252,-9.05333805084 --7.2817325592,2.08452773094,-9.0737695694 --7.25774240494,2.08552312851,-9.10220336914 --7.22774505615,2.08452391624,-9.12162780762 --7.19975090027,2.08452248573,-9.14506244659 --7.16474962234,2.08252596855,-9.15949821472 --7.14376163483,2.08452010155,-9.18991661072 --7.1267619133,2.08352160454,-9.198138237 --7.09676456451,2.08252191544,-9.21756362915 --7.07177400589,2.08351826668,-9.24499797821 --7.0457816124,2.08451557159,-9.26942157745 --7.01578521729,2.08351588249,-9.28985500336 --6.96977186203,2.07752847672,-9.28929519653 --6.96079778671,2.08451223373,-9.33671474457 --6.94279670715,2.08251452446,-9.34293365479 --6.89778423309,2.07752680779,-9.34337425232 --6.89181423187,2.08450818062,-9.39478969574 --6.84079456329,2.07752490044,-9.38723564148 --6.81780576706,2.07951998711,-9.41565704346 --6.79081392288,2.07951712608,-9.44109725952 --6.76982688904,2.08251094818,-9.47151184082 --6.75482940674,2.08251047134,-9.48273563385 --6.72383213043,2.08151173592,-9.50116729736 --6.7028465271,2.08450460434,-9.53359413147 --6.67785596848,2.08550071716,-9.56002044678 --6.64185380936,2.08250546455,-9.57246112823 --6.62287092209,2.08649682999,-9.60788631439 --6.59387636185,2.08649611473,-9.62931728363 --6.57988023758,2.08649492264,-9.64153862 --6.55188655853,2.08749341965,-9.66396713257 --6.5178861618,2.08549690247,-9.67840194702 --6.47687673569,2.08150672913,-9.68183708191 --6.44688129425,2.08150672913,-9.70227336884 --6.42289304733,2.0835018158,-9.73070049286 --6.41590547562,2.0854947567,-9.75291442871 --6.38290596008,2.08449745178,-9.76834869385 --6.35491275787,2.08549594879,-9.79077720642 --6.32091188431,2.08350014687,-9.80420875549 --6.28991508484,2.08350110054,-9.82264232635 --6.26893138885,2.08649325371,-9.85606861115 --6.2349319458,2.08549594879,-9.87151432037 --6.18691205978,2.07851290703,-9.86295413971 --6.17391729355,2.0795109272,-9.87617015839 --6.17396211624,2.09048366547,-9.94258403778 --6.14496803284,2.09048295021,-9.96401500702 --6.1169757843,2.09148073196,-9.98744869232 --6.10200214386,2.09646654129,-10.0318746567 --6.06099224091,2.09347701073,-10.0343141556 --6.04699659348,2.09347581863,-10.0465326309 --6.02300977707,2.09546995163,-10.0759601593 --5.98199987411,2.09248042107,-10.0784006119 --5.95000267029,2.09148192406,-10.0958385468 --5.90598773956,2.08649539948,-10.0932836533 --5.89501953125,2.09347724915,-10.1436977386 --5.86402463913,2.09347772598,-10.1631374359 --5.83400535583,2.08849239349,-10.1483650208 --5.81402444839,2.09248280525,-10.1837835312 --5.77101135254,2.08749580383,-10.1822271347 --5.75604009628,2.09447979927,-10.2296609879 --5.70301055908,2.08550333977,-10.2091035843 --5.69004297256,2.09248495102,-10.2605361938 --5.64302158356,2.08650350571,-10.2489700317 --5.630027771,2.08750104904,-10.2631893158 --5.59702920914,2.08650374413,-10.278629303 --5.57104158401,2.08849906921,-10.3060626984 --5.53603982925,2.08750414848,-10.3175010681 --5.49803256989,2.08451271057,-10.3229389191 --5.47304725647,2.08750677109,-10.3533773422 --5.43804502487,2.08551216125,-10.3638114929 --5.42605257034,2.08750891685,-10.3790254593 --5.4000658989,2.08950376511,-10.4074611664 --5.3650636673,2.08850932121,-10.4178953171 --5.32805728912,2.08551716805,-10.424331665 --5.30607795715,2.09050774574,-10.4607667923 --5.26406431198,2.08552026749,-10.4592151642 --5.23407125473,2.08652019501,-10.4796495438 --5.22508382797,2.08951354027,-10.4998559952 --5.20009899139,2.09250736237,-10.5302886963 --5.17110729218,2.09350609779,-10.5527229309 --5.14512205124,2.09650039673,-10.5821590424 --5.11412763596,2.09650087357,-10.6015977859 --5.08513641357,2.09849905968,-10.6240310669 --5.06613254547,2.09650373459,-10.626250267 --5.03714227676,2.09850144386,-10.6496868134 --5.00514507294,2.09850335121,-10.6661214828 --4.96814060211,2.09651088715,-10.6735658646 --4.93013381958,2.09451937675,-10.6790122986 --4.9111623764,2.1005051136,-10.7234430313 --4.86313486099,2.09352731705,-10.7048826218 --4.8381524086,2.09651994705,-10.7373189926 --4.80512142181,2.08854198456,-10.7095499039 --4.7931637764,2.09851861,-10.7689723969 --4.75816202164,2.09752416611,-10.7794113159 --4.72015476227,2.09553313255,-10.7838563919 --4.6781373024,2.09054875374,-10.7772941589 --4.6341176033,2.08556580544,-10.767742157 --4.62112474442,2.08656334877,-10.781955719 --4.58111333847,2.08357524872,-10.7814035416 --4.54911661148,2.08357739449,-10.7978410721 --4.50609731674,2.07859373093,-10.7892875671 --4.47309923172,2.07859706879,-10.8037281036 --4.43609285355,2.07660531998,-10.809173584 --4.40409708023,2.07760739326,-10.8256130219 --4.37807607651,2.07262277603,-10.8088331223 --4.3490858078,2.07462072372,-10.8322696686 --4.30706787109,2.06963682175,-10.824716568 --4.27607297897,2.07063817978,-10.8421506882 --4.24407720566,2.07163953781,-10.8595943451 --4.21007537842,2.07064557076,-10.8690271378 --4.16705513,2.06566286087,-10.8594808578 --4.1550655365,2.06765842438,-10.8766946793 --4.1210641861,2.06666374207,-10.8871307373 --4.08906793594,2.06766581535,-10.9035730362 --4.05005455017,2.06467890739,-10.9010133743 --4.01705694199,2.06468200684,-10.9154577255 --3.97904610634,2.06269335747,-10.9159021378 --3.94805216789,2.06369423866,-10.9343395233 --3.92503738403,2.05970573425,-10.9245681763 --3.8950445652,2.06170582771,-10.9439992905 --3.85703444481,2.05871677399,-10.9454488754 --3.82704257965,2.06071639061,-10.965883255 --3.7920396328,2.05972290039,-10.9743270874 --3.75302457809,2.05673694611,-10.9697685242 --3.73301625252,2.05474472046,-10.9669933319 --3.69901490211,2.05475020409,-10.977435112 --3.65999960899,2.05076432228,-10.9728784561 --3.63000774384,2.05276370049,-10.9933128357 --3.5879843235,2.04778337479,-10.9797592163 --3.5569922924,2.04978299141,-11.0002059937 --3.51998019218,2.04679536819,-10.9986400604 --3.50398230553,2.04679632187,-11.0068616867 --3.4699819088,2.04680132866,-11.0183105469 --3.43497610092,2.04580974579,-11.0237483978 --3.39495635033,2.04182696342,-11.0141925812 --3.35894775391,2.03983688354,-11.0166339874 --3.33096599579,2.04383063316,-11.0480833054 --3.2929494381,2.04084587097,-11.0415172577 --3.27494764328,2.03984928131,-11.0457487106 --3.23993968964,2.03885912895,-11.0481796265 --3.19992136955,2.03487563133,-11.0406360626 --3.16892695427,2.03687667847,-11.0580720901 --3.12990808487,2.03289341927,-11.0495157242 --3.09991765022,2.03489255905,-11.0709524155 --3.05889368057,2.02991199493,-11.0574054718 --3.04289460182,2.03091430664,-11.063621521 --3.00487732887,2.02692937851,-11.0570631027 --2.97087550163,2.02693557739,-11.0665092468 --2.93586874008,2.02594470978,-11.0709524155 --2.89885663986,2.0239572525,-11.069401741 --2.8588309288,2.01897788048,-11.0538425446 --2.83084917068,2.02297186852,-11.0842838287 --2.80682301521,2.01799058914,-11.0625114441 --2.7748260498,2.0189936161,-11.0769510269 --2.73981881142,2.01800322533,-11.0803937912 --2.70882558823,2.02000403404,-11.0988321304 --2.65876317024,2.00704693794,-11.0452919006 --2.63178300858,2.01204013824,-11.0767211914 --2.59577322006,2.01005101204,-11.0781726837 --2.5807788372,2.01205062866,-11.089392662 --2.54777979851,2.01205515862,-11.1018390656 --2.52783131599,2.02302932739,-11.1662693024 --2.4908156395,2.02104401588,-11.1607131958 --2.44978404045,2.01506853104,-11.1391639709 --2.42481923103,2.02305269241,-11.1866054535 --2.40179181099,2.01707172394,-11.1638298035 --2.37080192566,2.02007102966,-11.1852731705 --2.33679771423,2.02007889748,-11.1917152405 --2.29978322983,2.01709294319,-11.1881685257 --2.26276445389,2.01410961151,-11.1796092987 --2.23177647591,2.01710796356,-11.2030572891 --2.20078420639,2.0201086998,-11.2214918137 --2.17775654793,2.01412796974,-11.198723793 --2.15078639984,2.02111577988,-11.2401628494 --2.11175680161,2.01613879204,-11.2206058502 --2.07574176788,2.01315307617,-11.2160482407 --2.04375314713,2.017152071,-11.2385034561 --2.00773620605,2.01416754723,-11.2319421768 --1.97675144672,2.01816439629,-11.258392334 --1.95974743366,2.01716923714,-11.2596082687 --1.92574524879,2.01817655563,-11.2680568695 --1.88872253895,2.01419520378,-11.2554960251 --1.85774075985,2.01819062233,-11.2849502563 --1.82172107697,2.01520752907,-11.275384903 --1.78872776031,2.01820969582,-11.2928390503 --1.7517067194,2.01422739029,-11.282286644 --1.73470377922,2.01423192024,-11.2845058441 --1.6966739893,2.00925517082,-11.2649497986 --1.66669857502,2.01524686813,-11.3003988266 --1.62967479229,2.01126623154,-11.2868432999 --1.59667563438,2.01227164268,-11.2982854843 --1.56066071987,2.01028609276,-11.2937355042 --1.52665567398,2.01029491425,-11.2991781235 --1.50764071941,2.00830674171,-11.2894039154 --1.47665762901,2.01230287552,-11.3168458939 --1.43963479996,2.00932192802,-11.3042984009 --1.40562701225,2.00933241844,-11.3067369461 --1.37061977386,2.0083425045,-11.3101902008 --1.33661198616,2.00835299492,-11.3126296997 --1.29958879948,2.0043721199,-11.3000841141 --1.28459918499,2.00736927986,-11.3152999878 --1.2485858202,2.0053832531,-11.3127574921 --1.21457898617,2.00539326668,-11.3161993027 --1.18158531189,2.00839591026,-11.3326463699 --1.14455723763,2.00441789627,-11.3150978088 --1.11155760288,2.00542378426,-11.3255367279 --1.09354460239,2.00343418121,-11.3177585602 --1.0595395565,2.0034430027,-11.3232030869 --1.02351748943,2.00046181679,-11.3116531372 --0.990527927876,2.00446224213,-11.3321046829 --0.954501748085,2.00048327446,-11.3165502548 --0.921507060528,2.00248646736,-11.3319950104 --0.886494159698,2.0015001297,-11.3294439316 --0.852486431599,2.00151085854,-11.3318872452 --0.83447521925,1.99952030182,-11.3261137009 --0.80148178339,2.0025229454,-11.3425569534 --0.764448285103,1.99754822254,-11.3200149536 --0.731460869312,2.00154781342,-11.342464447 --0.698465406895,2.00355148315,-11.3569040298 --0.663452446461,2.00256514549,-11.3543558121 --0.644407808781,1.99459326267,-11.3155698776 --0.610422432423,1.9995919466,-11.3400316238 --0.576418578625,1.99960052967,-11.3464784622 --0.542408943176,1.99961233139,-11.3469200134 --0.507380783558,1.99563443661,-11.3293628693 --0.472354620695,1.99265551567,-11.3138093948 --0.436317741871,1.98668265343,-11.2882633209 --0.419298797846,1.98469626904,-11.2744779587 --0.383244514465,1.97573292255,-11.2319259644 --0.350271731615,1.98272454739,-11.2683792114 --0.315224826336,1.97575700283,-11.2328214645 --0.281213790178,1.97476959229,-11.2322683334 --0.247190698981,1.97278904915,-11.2197113037 --0.213215649128,1.97878217697,-11.2541723251 --0.196207553148,1.97778987885,-11.2513952255 --0.162199959159,1.97880101204,-11.2538433075 --0.128212794662,1.98280072212,-11.2762975693 --0.094202041626,1.98281335831,-11.2757444382 --0.0602066069841,1.98481762409,-11.2901935577 --0.0262134578079,1.98782086372,-11.3066425323 -0.00780444964767,1.9868376255,-11.2990875244 -0.00519545888528,1.97815406322,-10.4650392532 -0.0402294993401,1.9831622839,-10.4884252548 -0.074216209352,1.97814536095,-10.4668083191 -0.108211643994,1.97613298893,-10.4531898499 -0.142231732607,1.97813403606,-10.4635677338 -0.176234126091,1.97612571716,-10.456949234 -0.21023774147,1.97511780262,-10.4513320923 -0.227220088243,1.97110342979,-10.4295301437 -0.262257814407,1.97611391544,-10.456911087 -0.294209867716,1.96607851982,-10.4012928009 -0.328220695257,1.96607470512,-10.402674675 -0.361190646887,1.95904898643,-10.3640651703 -0.392140746117,1.94801282883,-10.3064479828 -0.424111664295,1.9409879446,-10.2688341141 -0.441107571125,1.93898069859,-10.2600336075 -0.473081856966,1.93295764923,-10.2254209518 -0.505072176456,1.92894327641,-10.2068004608 -0.537052690983,1.92392349243,-10.178188324 -0.571071147919,1.92592382431,-10.1865730286 -0.602039337158,1.91789782047,-10.1459617615 -0.634027063847,1.91388201714,-10.1243495941 -0.650035142899,1.91488182545,-10.1275320053 -0.685059845448,1.91788542271,-10.1419219971 -0.716041445732,1.91286671162,-10.1143064499 -0.749051809311,1.91386282444,-10.1146869659 -0.782051026821,1.91185319424,-10.1040792465 -0.81405299902,1.91084516048,-10.0964574814 -0.828028738499,1.90582787991,-10.067650795 -0.860026836395,1.90381789207,-10.0560359955 -0.891013860703,1.89980220795,-10.0334224701 -0.924018263817,1.89879524708,-10.0278139114 -0.95500934124,1.89578175545,-10.0091972351 -0.985994696617,1.89176499844,-9.9845905304 -1.01900815964,1.89276301861,-9.98797130585 -1.03399837017,1.89075350761,-9.97316741943 -1.06499159336,1.88774108887,-9.95655250549 -1.09598481655,1.88472890854,-9.9399394989 -1.12798547745,1.88372027874,-9.93032836914 -1.15696668625,1.87870192528,-9.9017124176 -1.19198954105,1.88170468807,-9.914103508 -1.22197902203,1.8786906004,-9.8934879303 -1.2359662056,1.87567961216,-9.87568187714 -1.26796793938,1.87467169762,-9.86707305908 -1.29896819592,1.87266337872,-9.85745429993 -1.3147367239,1.82553207874,-9.61008548737 -1.34372365475,1.82151687145,-9.58647918701 -1.37271845341,1.81950604916,-9.57085990906 -1.39275097847,1.82551825047,-9.59804916382 -1.41670715809,1.81548762321,-9.54344654083 -1.4477083683,1.81447970867,-9.53384113312 -1.48274409771,1.820489645,-9.55921363831 -1.51978468895,1.82650184631,-9.58959674835 -1.54173326492,1.81546759605,-9.52699565887 -1.56971955299,1.81145226955,-9.50238800049 -1.58371317387,1.80944502354,-9.4905834198 -1.61371147633,1.80843579769,-9.47797679901 -1.64471769333,1.80843067169,-9.47336387634 -1.67371559143,1.80642175674,-9.46074485779 -1.70572412014,1.80741763115,-9.45814037323 -1.73371243477,1.80340361595,-9.43553543091 -1.76170670986,1.80139279366,-9.4189157486 -1.77771139145,1.80139100552,-9.41811275482 -1.8067060709,1.79938018322,-9.40150642395 -1.83670735359,1.79837286472,-9.39189720154 -1.86570763588,1.79736506939,-9.38127708435 -1.89570724964,1.79635679722,-9.36967372894 -1.92269587517,1.79334318638,-9.34706306458 -1.93669259548,1.7913377285,-9.33825874329 -1.96769821644,1.79133236408,-9.33265113831 -1.99368214607,1.78731667995,-9.30504608154 -2.02167773247,1.78530657291,-9.28943252563 -2.05268335342,1.78530132771,-9.28382873535 -2.0816822052,1.78429293633,-9.27121925354 -2.11570429802,1.78829586506,-9.28259944916 -2.13171172142,1.78929579258,-9.28478813171 -2.15368151665,1.78227305412,-9.24218559265 -2.16661429405,1.76723265648,-9.16159439087 -2.19862508774,1.7682300806,-9.16099071503 -2.22863149643,1.76822566986,-9.15637397766 -2.25662660599,1.76621556282,-9.13977146149 -2.28562760353,1.76620841026,-9.12916278839 -2.30163526535,1.76720821857,-9.13135147095 -2.32963204384,1.76519930363,-9.11674404144 -2.37067937851,1.77421450615,-9.15411949158 -2.39967775345,1.77320587635,-9.14052009583 -2.41763997078,1.76418042183,-9.08991622925 -2.44864964485,1.76517748833,-9.08830165863 -2.47664690018,1.76416862011,-9.07369613647 -2.48863601685,1.76115942001,-9.05590724945 -2.50559663773,1.75213325024,-9.00330638885 -2.53460073471,1.75212776661,-8.99569129944 -2.56259799004,1.75011909008,-8.98109054565 -2.59260320663,1.75111413002,-8.97448444366 -2.6206035614,1.75010693073,-8.96287250519 -2.64458942413,1.74609303474,-8.93627071381 -2.65959358215,1.74709117413,-8.93446159363 -2.69862747192,1.75309979916,-8.95784950256 -2.72662758827,1.75209259987,-8.94623851776 -2.74760437012,1.74707436562,-8.90964126587 -2.78363108635,1.75207972527,-8.92601680756 -2.80761837959,1.74806654453,-8.90041542053 -2.82161855698,1.74806308746,-8.89460945129 -2.84560585022,1.74404978752,-8.86900997162 -2.87862157822,1.74705004692,-8.8733959198 -2.90361118317,1.74403774738,-8.84980106354 -2.93361830711,1.74503397942,-8.84518718719 -2.94858050346,1.73600924015,-8.79259777069 -2.98059391975,1.73800861835,-8.79498004913 -3.00462341309,1.7440186739,-8.82016277313 -3.02059006691,1.73599636555,-8.7725687027 -3.04157066345,1.73098003864,-8.73897743225 -3.0565366745,1.72295761108,-8.69038105011 -3.08654499054,1.72495448589,-8.68676662445 -3.1055226326,1.71893715858,-8.65017032623 -3.14254808426,1.72394180298,-8.66455745697 -3.16356801987,1.72794759274,-8.67974376678 -3.20360040665,1.73395550251,-8.70212650299 -3.2305996418,1.73394811153,-8.68851947784 -3.24857497215,1.72792983055,-8.64892864227 -3.27657747269,1.72792434692,-8.63931655884 -3.30858874321,1.72892248631,-8.63871002197 -3.32055020332,1.71989810467,-8.5841255188 -3.33755993843,1.7218991518,-8.58831119537 -3.38160157204,1.73091125488,-8.62068462372 -3.40358734131,1.72689783573,-8.59209537506 -3.43660140038,1.72989749908,-8.59448242188 -3.47061657906,1.73289740086,-8.59787559509 -3.48859572411,1.72788131237,-8.56227588654 -3.52361416817,1.73088288307,-8.56966018677 -3.54663515091,1.73588895798,-8.58585262299 -3.55358862877,1.72486138344,-8.52227115631 -3.58359646797,1.72585809231,-8.51765727997 -3.6136033535,1.72685456276,-8.51204776764 -3.65363121033,1.73286032677,-8.5294342041 -3.67562174797,1.73084938526,-8.50582504272 -3.70863318443,1.73284780979,-8.50522327423 -3.72163295746,1.73284447193,-8.49841594696 -3.73961257935,1.72782886028,-8.46282672882 -3.77162408829,1.72982728481,-8.46221160889 -3.8096473217,1.73483097553,-8.47459506989 -3.82562422752,1.72881424427,-8.43600273132 -3.86464858055,1.73381829262,-8.4493894577 -3.87363958359,1.7318110466,-8.43259143829 -3.90565061569,1.73380959034,-8.43197536469 -3.9346549511,1.73480498791,-8.42336750031 -3.95864796638,1.73279523849,-8.40177536011 -3.98665142059,1.73379027843,-8.39216136932 -4.02367019653,1.73779201508,-8.39955329895 -4.04966783524,1.73678421974,-8.3829574585 -4.07268667221,1.74078917503,-8.3971414566 -4.08566045761,1.7347714901,-8.35454845428 -4.11065578461,1.73376309872,-8.33595275879 -4.15368747711,1.74077022076,-8.35732555389 -4.16666126251,1.73375272751,-8.31473731995 -4.19165897369,1.73374521732,-8.2981300354 -4.22366809845,1.73574280739,-8.29452514648 -4.23566436768,1.7347381115,-8.28373241425 -4.26767492294,1.73673641682,-8.28211402893 -4.29467535019,1.73673021793,-8.26851177216 -4.32668399811,1.73872733116,-8.26391029358 -4.35468578339,1.73872184753,-8.25230693817 -4.38669586182,1.74171984196,-8.2496919632 -4.41069173813,1.74071192741,-8.23108673096 -4.42869949341,1.74171209335,-8.23327922821 -4.45770263672,1.74270713329,-8.22268009186 -4.48570489883,1.7437016964,-8.2110748291 -4.51170349121,1.74269509315,-8.19547462463 -4.54371261597,1.74469268322,-8.19186210632 -4.57772397995,1.74769103527,-8.19025802612 -4.59871530533,1.74568104744,-8.16565990448 -4.61371803284,1.74667906761,-8.16185569763 -4.64873075485,1.74967825413,-8.16224765778 -4.67573165894,1.74967265129,-8.14963722229 -4.70273160934,1.74966645241,-8.1350402832 -4.72372293472,1.747656703,-8.11044311523 -4.74972248077,1.74765050411,-8.09583473206 -4.77373838425,1.75165390968,-8.10702705383 -4.80474472046,1.75265026093,-8.09942531586 -4.83274698257,1.75364506245,-8.08781719208 -4.86275148392,1.75464081764,-8.07821750641 -4.88875102997,1.75463473797,-8.06360816956 -4.91474914551,1.75462758541,-8.04601955414 -4.94175052643,1.75462222099,-8.0334072113 -4.96476459503,1.75862503052,-8.04259490967 -4.98675823212,1.7576161623,-8.01999759674 -5.02176952362,1.76061475277,-8.01839351654 -5.04676675797,1.75960767269,-8.00079345703 -5.07476902008,1.76060283184,-7.9891834259 -5.10377120972,1.76159751415,-7.97659063339 -5.14078617096,1.76559746265,-7.97897434235 -5.15278482437,1.76559400558,-7.97016906738 -5.17577886581,1.76358580589,-7.94857645035 -5.20978927612,1.76658391953,-7.94596338272 -5.22577476501,1.76357221603,-7.91337776184 -5.26479101181,1.76757276058,-7.91776371002 -5.28678512573,1.76656460762,-7.89616107941 -5.31378555298,1.76655888557,-7.88156080246 -5.32778644562,1.7675563097,-7.87476110458 -5.35678958893,1.76855158806,-7.86315822601 -5.38078546524,1.76754426956,-7.843562603 -5.41679859161,1.77154350281,-7.8439412117 -5.44279766083,1.77153730392,-7.82734298706 -5.46979761124,1.77153134346,-7.81174850464 -5.50981426239,1.77653193474,-7.81613445282 -5.49778270721,1.76851713657,-7.77135753632 -5.53179121017,1.77151441574,-7.76575756073 -5.55879211426,1.77150928974,-7.75214719772 -5.59180116653,1.77450668812,-7.74653625488 -5.61880064011,1.77450096607,-7.73093986511 -5.64680194855,1.77549552917,-7.71634674072 -5.68081092834,1.77849328518,-7.71173477173 -5.69581317902,1.77949142456,-7.70692777634 -5.72781944275,1.78148782253,-7.69832611084 -5.765832901,1.78648722172,-7.69871234894 -5.78882789612,1.7854796648,-7.67712068558 -5.81282520294,1.78447306156,-7.65851640701 -5.84383010864,1.78646910191,-7.6479177475 -5.85582923889,1.78646600246,-7.63911104202 -5.88783502579,1.78946256638,-7.63050460815 -5.91583538055,1.78945696354,-7.6149148941 -5.93783140182,1.78944993019,-7.59430599213 -5.97083806992,1.79144704342,-7.58669996262 -5.99883890152,1.79244148731,-7.57110977173 -6.03885316849,1.79744100571,-7.57249641418 -6.05385541916,1.79843902588,-7.56669330597 -6.10688400269,1.80744361877,-7.58506441116 -6.13388299942,1.8074375391,-7.56747627258 -6.16588830948,1.80943393707,-7.55787038803 -6.17486953735,1.80542171001,-7.51928281784 -6.2108798027,1.80841994286,-7.51566505432 -6.25289535522,1.81441986561,-7.51805257797 -6.27490377426,1.8174200058,-7.52024650574 -6.29289388657,1.81441092491,-7.49166345596 -6.33090543747,1.81940937042,-7.48905086517 -6.33888626099,1.81439733505,-7.44946622849 -6.37689733505,1.81839573383,-7.44685268402 -6.34083461761,1.80036878586,-7.35430860519 -6.21268224716,1.75431156158,-7.15284204483 -6.2186756134,1.75230658054,-7.13605213165 -6.2356672287,1.75029873848,-7.1094584465 -6.24865531921,1.74728953838,-7.07787227631 -6.26064252853,1.74328017235,-7.04528713226 -6.27963733673,1.74227333069,-7.02168893814 -6.27460861206,1.73425865173,-6.96912336349 -6.28660869598,1.73425626755,-6.96131372452 -6.28758621216,1.72824394703,-6.91673707962 -6.30658149719,1.72723734379,-6.89314317703 -6.31456613541,1.72222757339,-6.85755586624 -6.34557199478,1.72522437572,-6.8469581604 -6.3325381279,1.71420836449,-6.78739595413 -6.36554574966,1.7172062397,-6.7797908783 -6.36053085327,1.71319878101,-6.7520070076 -6.37852573395,1.7121925354,-6.72840881348 -6.38050603867,1.70618152618,-6.68682909012 -6.40851020813,1.70817780495,-6.67323303223 -6.40848970413,1.701166749,-6.63064813614 -6.43649291992,1.70316290855,-6.61606121063 -6.43847513199,1.69815278053,-6.57646942139 -6.45247650146,1.6981511116,-6.5696721077 -6.45946264267,1.6941421032,-6.53409194946 -6.48046112061,1.69413685799,-6.51349878311 -6.48744726181,1.69012796879,-6.47792100906 -6.51244878769,1.69112408161,-6.46231746674 -6.5254406929,1.68911707401,-6.43372869492 -6.53843259811,1.68711006641,-6.40514183044 -6.53241872787,1.68210351467,-6.37835693359 -6.55741977692,1.68309962749,-6.36176395416 -6.57341480255,1.68209338188,-6.33617734909 -6.58940982819,1.68108773232,-6.3115811348 -6.59839868546,1.677079916,-6.27900218964 -6.61639547348,1.67607474327,-6.25640630722 -6.60838031769,1.67106807232,-6.22763061523 -6.64439153671,1.67606711388,-6.22301673889 -6.64637565613,1.67105817795,-6.18443870544 -6.65936899185,1.6690518856,-6.15685033798 -6.68236970901,1.67004799843,-6.13925075531 -6.69436216354,1.66704165936,-6.11066484451 -6.6963467598,1.66203308105,-6.07209396362 -6.71135091782,1.66403210163,-6.06728410721 -6.73134946823,1.66402757168,-6.04668951035 -6.73333454132,1.6590192318,-6.00812196732 -6.73532056808,1.65401136875,-5.97153568268 -6.76232433319,1.65600836277,-5.95694255829 -6.74829959869,1.6479973793,-5.90537452698 -6.77730512619,1.64999496937,-5.89277887344 -6.77329492569,1.6459903717,-5.87098169327 -6.79129314423,1.64598572254,-5.84839439392 -6.79327964783,1.64097833633,-5.81181669235 -6.81528091431,1.64197468758,-5.79322385788 -6.8082613945,1.6349657774,-5.74865674973 -6.83726787567,1.63796365261,-5.73704910278 -6.83825492859,1.63295650482,-5.70046901703 -6.83924818039,1.63095271587,-5.68168926239 -6.84423875809,1.6279463768,-5.64910316467 -6.87324476242,1.62994456291,-5.63749551773 -6.85321807861,1.62093389034,-5.58293771744 -6.88922929764,1.62493312359,-5.57633590698 -6.89622116089,1.62192738056,-5.54574918747 -6.9042134285,1.61892187595,-5.51517343521 -6.90420722961,1.61691856384,-5.49737882614 -6.92720985413,1.61791551113,-5.47978639603 -6.91719102859,1.61090743542,-5.43521690369 -6.94519662857,1.61390542984,-5.42162227631 -6.95018815994,1.61089980602,-5.39003658295 -6.96818780899,1.61089634895,-5.36844825745 -6.96017122269,1.60388886929,-5.32588100433 -6.97917699814,1.60688889027,-5.3240685463 -6.97116088867,1.5998814106,-5.28150510788 -7.00416994095,1.60388052464,-5.27289390564 -7.01416492462,1.60187590122,-5.24432182312 -7.0141544342,1.59787011147,-5.20973682404 -7.01314353943,1.59386432171,-5.17316865921 -7.04915904999,1.59986650944,-5.18434333801 -7.02713632584,1.59085810184,-5.13277864456 -7.05514240265,1.59385633469,-5.11918306351 -7.05813360214,1.58985126019,-5.0866060257 -7.08013677597,1.59084892273,-5.06900787354 -7.08713054657,1.58884453773,-5.03942918777 -7.09612607956,1.58684051037,-5.01184415817 -7.09011793137,1.58383727074,-4.99006271362 -7.10811853409,1.58383440971,-4.9694685936 -7.11111116409,1.58082973957,-4.93689775467 -7.1271109581,1.58082687855,-4.91530036926 -7.13710689545,1.57882332802,-4.88871574402 -7.15310716629,1.57882034779,-4.86613035202 -7.15710067749,1.57581627369,-4.83554840088 -7.17410516739,1.5778157711,-4.83074808121 -7.18410205841,1.5768122673,-4.80416488647 -7.18409395218,1.57280790806,-4.77059030533 -7.18408584595,1.56880366802,-4.73800468445 -7.1990852356,1.56880104542,-4.71541404724 -7.2070813179,1.5667976141,-4.68783187866 -7.21308040619,1.56679606438,-4.67504405975 -7.23008203506,1.56679368019,-4.65444517136 -7.22507143021,1.56178927422,-4.61787652969 -7.2220621109,1.55778515339,-4.58330011368 -7.25407075882,1.56178414822,-4.57170438766 -7.25706529617,1.55878067017,-4.54112577438 -7.27106523514,1.55877828598,-4.51853084564 -7.27206230164,1.55677652359,-4.50274515152 -7.26705312729,1.55277252197,-4.46717262268 -7.30006217957,1.55677175522,-4.45656871796 -7.28905057907,1.55076742172,-4.4170050621 -7.28204059601,1.54576361179,-4.38043546677 -7.32005167007,1.5507632494,-4.37282896042 -7.32905006409,1.54976069927,-4.34723758698 -7.30803728104,1.54375755787,-4.31846094131 -7.33804512024,1.54675662518,-4.30487108231 -7.34003973007,1.54375374317,-4.27528238297 -7.33303117752,1.5397503376,-4.2387213707 -7.36704063416,1.54374969006,-4.22811937332 -7.36603450775,1.54074692726,-4.19653844833 -7.37703418732,1.53974473476,-4.17195272446 -7.36902809143,1.53674280643,-4.15117549896 -7.36702156067,1.53274023533,-4.11959123611 -7.39102745056,1.53473901749,-4.10299491882 -7.39802503586,1.53373682499,-4.07542276382 -7.4000210762,1.53073441982,-4.04584407806 -7.41402244568,1.5307328701,-4.02325582504 -7.40301322937,1.52573001385,-3.98668169975 -7.41201448441,1.52572929859,-3.97589564323 -7.42301511765,1.52572762966,-3.95230150223 -7.42301034927,1.52272558212,-3.92172694206 -7.43100976944,1.52172386646,-3.89614057541 -7.44401073456,1.52172243595,-3.87256169319 -7.44700813293,1.51872062683,-3.84398365021 -7.43600177765,1.51571917534,-3.8231985569 -7.44400119781,1.51371777058,-3.79761528969 -7.44799947739,1.51271617413,-3.77003216743 -7.45899963379,1.51171481609,-3.74545645714 -7.47700309753,1.51271390915,-3.72585844994 -7.46999740601,1.50871193409,-3.69228816032 -7.46699333191,1.50571036339,-3.66071844101 -7.48499822617,1.50771033764,-3.65590929985 -7.48199415207,1.50470876694,-3.62434148788 -7.4829916954,1.50270736217,-3.59575891495 -7.50999879837,1.50570678711,-3.58016347885 -7.50199317932,1.5017054081,-3.54659438133 -7.50399112701,1.49870419502,-3.51900720596 -7.52999782562,1.50170373917,-3.50241804123 -7.52299404144,1.49970304966,-3.48463010788 -7.53299570084,1.49870216846,-3.46005296707 -7.55400037766,1.50070154667,-3.44145894051 -7.54999685287,1.4977004528,-3.40989351273 -7.54999446869,1.49469971657,-3.38229775429 -7.57400131226,1.4976991415,-3.36470723152 -7.56599664688,1.49369835854,-3.3321352005 -7.56299448013,1.49169790745,-3.31634879112 -7.58099889755,1.49369740486,-3.29576444626 -7.59100055695,1.49269688129,-3.27118945122 -7.58199596405,1.48869621754,-3.23960185051 -7.5969991684,1.48969590664,-3.21702861786 -7.5999994278,1.48769533634,-3.19044232368 -7.601998806,1.4866951704,-3.17764520645 -7.62000370026,1.48869478703,-3.15705990791 -7.61800193787,1.48569440842,-3.12748980522 -7.60899782181,1.4816942215,-3.09590959549 -7.65401124954,1.48869395256,-3.08730340004 -7.63400411606,1.48269379139,-3.04975032806 -7.62800168991,1.47869372368,-3.01917695999 -7.6640124321,1.48569345474,-3.02036619186 -7.65400838852,1.48169350624,-2.98878526688 -7.6660118103,1.48169338703,-2.96521043777 -7.66200971603,1.47869348526,-2.93563604355 -7.62299823761,1.46869397163,-2.89208030701 -7.64700508118,1.47169387341,-2.87448382378 -7.62799978256,1.46569430828,-2.83892345428 -7.63100099564,1.46469438076,-2.82613682747 -7.65700817108,1.46869444847,-2.80953454971 -7.64700555801,1.4646948576,-2.77796626091 -7.62900066376,1.4586956501,-2.74340367317 -7.59199142456,1.44869673252,-2.70283532143 -7.6089963913,1.4506970644,-2.68126320839 -7.58699178696,1.44469809532,-2.64668750763 -7.5559835434,1.43669903278,-2.62191295624 -7.54498195648,1.43270003796,-2.59035348892 -7.54898405075,1.43170082569,-2.56478023529 -7.55398654938,1.43070161343,-2.54019713402 -7.51997947693,1.42170333862,-2.50163626671 -7.50797748566,1.41770470142,-2.47106480598 -7.53098392487,1.42170464993,-2.46625947952 -7.49897813797,1.41370654106,-2.42870092392 -7.49597883224,1.41070795059,-2.40113162994 -7.49498081207,1.40970921516,-2.37455701828 -7.43996953964,1.39671218395,-2.33000826836 -7.43897104263,1.39471364021,-2.3044230938 -7.42697095871,1.39071547985,-2.27386641502 -7.43397378922,1.39071595669,-2.26406264305 -7.41597175598,1.38571810722,-2.2324962616 -7.38096666336,1.37672102451,-2.19495010376 -7.35896396637,1.37072336674,-2.16337180138 -7.3359618187,1.3647261858,-2.13080835342 -7.31796121597,1.35972869396,-2.09925508499 -7.30396127701,1.35573101044,-2.07067322731 -7.29095983505,1.35173261166,-2.05389738083 -7.30396604538,1.35273396969,-2.03330922127 -7.31497192383,1.35373568535,-2.01172757149 -7.2879691124,1.34673893452,-1.97916066647 -7.20995664597,1.3297444582,-1.9316239357 -7.22996473312,1.33274579048,-1.91303730011 -7.32198762894,1.34974372387,-1.91540634632 -7.24597406387,1.33374857903,-1.88067042828 -7.16396141052,1.31575489044,-1.83313727379 -7.1369600296,1.30875861645,-1.80157446861 -7.11996126175,1.30476200581,-1.77300584316 -7.0999622345,1.29876554012,-1.74344527721 -7.11396932602,1.30076754093,-1.72385466099 -7.10897064209,1.29876899719,-1.71106183529 -7.11397647858,1.29877150059,-1.68848633766 -7.09697771072,1.29377520084,-1.65992724895 -7.06697750092,1.28677964211,-1.62935352325 -7.05698013306,1.28378307819,-1.60377502441 -7.07298851013,1.28578519821,-1.58419454098 -7.04598903656,1.2797896862,-1.55364084244 -7.01298618317,1.27179312706,-1.53387057781 -6.99698829651,1.26779723167,-1.50729465485 -6.98899269104,1.26480078697,-1.48271548748 -6.95099163055,1.2568063736,-1.4501696825 -6.97700166702,1.26080787182,-1.43357682228 -6.95600414276,1.25581252575,-1.40600907803 -6.92800283432,1.24981606007,-1.38823544979 -6.91500663757,1.24582016468,-1.36266577244 -6.9170126915,1.24482345581,-1.3410782814 -6.91401863098,1.24382710457,-1.31751000881 -6.91702508926,1.24283027649,-1.29592692852 -6.8870267868,1.23683583736,-1.26736044884 -6.88403272629,1.23483967781,-1.24477815628 -6.86303281784,1.22984290123,-1.22900593281 -6.85303783417,1.2268474102,-1.20444011688 -6.83604240417,1.22285223007,-1.17887222767 -6.84805059433,1.22485506535,-1.15928673744 -6.88706254959,1.23185586929,-1.14567291737 -6.87806797028,1.22886037827,-1.12111353874 -6.89907741547,1.23186254501,-1.10351490974 -6.89808130264,1.23186469078,-1.09173643589 -6.86108350754,1.22387123108,-1.06317210197 -6.90209579468,1.23087191582,-1.04857373238 -6.92710590363,1.23487389088,-1.03098213673 -6.90811061859,1.22987926006,-1.00541746616 -6.93512058258,1.23488104343,-0.988810002804 -6.92512607574,1.23188579082,-0.965233981609 -6.93313074112,1.23388707638,-0.955442667007 -6.94613981247,1.23489022255,-0.934870660305 -6.91914367676,1.22889637947,-0.909291863441 -6.87014532089,1.21890461445,-0.879738330841 -6.98216581345,1.23989915848,-0.875102758408 -6.90816497803,1.2249096632,-0.841569662094 -6.79715633392,1.20292150974,-0.813844621181 -6.78716278076,1.19992661476,-0.791265070438 -6.81317329407,1.20492863655,-0.773670732975 -6.78117799759,1.19793605804,-0.747121453285 -6.76718425751,1.19494152069,-0.724537074566 -6.8221988678,1.20494115353,-0.709942281246 -6.7852025032,1.19694876671,-0.684370100498 -6.73720216751,1.1879554987,-0.667604804039 -6.72120857239,1.18396174908,-0.644043028355 -6.74321937561,1.18796432018,-0.625456929207 -6.77123022079,1.19196617603,-0.607860147953 -6.71323299408,1.18097627163,-0.580304563046 -6.70624065399,1.17898154259,-0.558725595474 -6.72825145721,1.1829842329,-0.54013633728 -6.7832608223,1.19298124313,-0.535323381424 -6.7272644043,1.18199157715,-0.507783770561 -6.66326761246,1.16900265217,-0.480239599943 -6.68527889252,1.17300534248,-0.461649268866 -6.68328666687,1.17201030254,-0.441063076258 -6.67129516602,1.16901636124,-0.419483959675 -6.70130634308,1.17501842976,-0.400899797678 -6.71931219101,1.17801904678,-0.392100334167 -6.72132110596,1.17802369595,-0.371517926455 -6.73133134842,1.18002772331,-0.350944191217 -6.67833662033,1.16903817654,-0.326383262873 -6.64834308624,1.16304636002,-0.303811728954 -6.69135570526,1.17104685307,-0.286212474108 -6.72136211395,1.17704629898,-0.277418345213 -6.70136976242,1.17205345631,-0.255838125944 -6.68737840652,1.16905999184,-0.234264850616 -6.71238946915,1.17406260967,-0.214681327343 -6.77040243149,1.18506145477,-0.197076559067 -6.83841562271,1.19805920124,-0.179470419884 -6.91842889786,1.21305537224,-0.16284276545 -7.03043937683,1.23504555225,-0.157990843058 -7.08245134354,1.24504482746,-0.138391181827 -7.04845905304,1.23805356026,-0.114833578467 -7.18047428131,1.26304388046,-0.0981912910938 -8.17852973938,1.45593488216,-0.112113498151 -6.92748117447,1.21408295631,-0.0451634153724 -6.90048885345,1.20809113979,-0.0235857702792 -6.98149728775,1.22408461571,-0.0147663196549 -6.95850515366,1.21909236908,0.00681188423187 -6.74350690842,1.17812275887,0.0332828462124 -6.87352132797,1.20311307907,0.0519177354872 -6.69752550125,1.16913938522,0.0764024555683 -6.69953536987,1.16914463043,0.0969830602407 -6.68654489517,1.16615176201,0.117559745908 -6.70855045319,1.17015182972,0.127366110682 -6.76556253433,1.18115067482,0.1479678303 -6.70057058334,1.16916394234,0.168524578214 -6.71458148956,1.17216789722,0.189111813903 -6.80259418488,1.18916296959,0.210721567273 -6.75760316849,1.18017411232,0.231280475855 -6.65160608292,1.15919005871,0.241014122963 -6.65161657333,1.15919578075,0.261591434479 -6.67062759399,1.16319930553,0.28218343854 -6.67663764954,1.16420423985,0.302766919136 -6.57664680481,1.14522266388,0.321297138929 -6.60965776443,1.15122425556,0.341901302338 -6.58566904068,1.14723348618,0.36245188117 -6.57667398453,1.14523756504,0.372239202261 -6.6396856308,1.15823531151,0.393862128258 -6.70769739151,1.17123270035,0.417458295822 -6.61270713806,1.15325081348,0.434002965689 -6.60971784592,1.15225720406,0.454574346542 -6.61072921753,1.15326321125,0.475151270628 -6.76074075699,1.18224954605,0.502799034119 -6.64074611664,1.15926837921,0.507527947426 -6.62275695801,1.15527689457,0.527098238468 -6.61376810074,1.1542840004,0.546680927277 -6.5577788353,1.14329743385,0.563246011734 -6.5487909317,1.14230501652,0.583803534508 -6.558801651,1.14430975914,0.604393601418 -6.54581356049,1.14231789112,0.623963236809 -6.56481838226,1.14531826973,0.634774625301 -6.54783058167,1.14232695103,0.654335916042 -6.54284191132,1.14233374596,0.673919379711 -6.53685379028,1.1413410902,0.694479763508 -6.51986598969,1.1383497715,0.713057041168 -6.46987771988,1.12836277485,0.728621184826 -6.46088409424,1.12736749649,0.738395810127 -6.45089578629,1.12537515163,0.756982147694 -6.46890735626,1.12937903404,0.778571903706 -6.47491931915,1.13138484955,0.800135314465 -6.42793178558,1.12239778042,0.814711391926 -6.35194540024,1.10741508007,0.827248811722 -6.39495706558,1.11641561985,0.851841568947 -6.39196300507,1.11641943455,0.86162674427 -6.37597513199,1.11342799664,0.879210472107 -6.39498758316,1.11743223667,0.90178668499 -6.44999742508,1.12843060493,0.927406489849 -6.44701004028,1.1284378767,0.947967946529 -6.38502407074,1.1164535284,0.960518181324 -6.36003112793,1.11246049404,0.967298448086 -6.43504142761,1.12745642662,0.996908605099 -6.44505214691,1.12946128845,1.01750993729 -6.30606985092,1.10348832607,1.01902782917 -6.25308418274,1.09350287914,1.03158211708 -6.33209371567,1.1094981432,1.06219863892 -6.37510538101,1.11849868298,1.08878600597 -6.36011171341,1.11550438404,1.09656989574 -6.43312120438,1.13050031662,1.12718641758 -6.49813127518,1.14349770546,1.15778446198 -6.44314575195,1.13351249695,1.16934740543 -6.46515798569,1.13851630688,1.19392037392 -6.75615644455,1.19647943974,1.26162290573 -6.63317489624,1.17250454426,1.26215851307 -6.45918941498,1.13853442669,1.24386823177 -6.57019662857,1.16152453423,1.28348922729 -6.58420801163,1.16452896595,1.3060874939 -6.4792265892,1.14555203915,1.30861866474 -6.53223657608,1.15655088425,1.33921039104 -6.61724424362,1.17354464531,1.37483966351 -6.63325023651,1.1775457859,1.38863015175 -6.47827148438,1.14757668972,1.38113367558 -6.47828435898,1.1485837698,1.40171444416 -6.44629859924,1.14259541035,1.41529810429 -6.42831325531,1.13960540295,1.43285930157 -6.42032670975,1.13861405849,1.45242297649 -6.44133853912,1.14361774921,1.47701644897 -6.43734550476,1.14362204075,1.48679888248 -6.4603562355,1.14862525463,1.51140522957 -6.5063662529,1.15862512589,1.54200232029 -6.57537555695,1.17362165451,1.57859492302 -6.53639125824,1.16663491726,1.59115993977 -6.50240659714,1.16064739227,1.60472464561 -6.50841903687,1.16265332699,1.62632191181 -6.47342777252,1.15666258335,1.62909352779 -6.47244167328,1.15667021275,1.65065574646 -6.51345157623,1.16567099094,1.68125152588 -6.46346855164,1.15668594837,1.68982505798 -6.50647878647,1.16668641567,1.72141742706 -6.63448238373,1.19267308712,1.77404415607 -6.55350208282,1.177693367,1.77559244633 -6.46351575851,1.16071176529,1.76433742046 -6.43153142929,1.15472412109,1.77691376209 -6.4475440979,1.15972900391,1.80249130726 -6.43255901337,1.15773892403,1.82005882263 -6.49056720734,1.16973650455,1.85567557812 -6.44758462906,1.16275119781,1.86622619629 -6.37759780884,1.14876639843,1.85799121857 -6.34261465073,1.1427795887,1.86955702305 -6.3636264801,1.14878368378,1.89614737034 -6.40763616562,1.15878391266,1.92973780632 -6.39065170288,1.15579426289,1.94630861282 -6.33167076111,1.14581167698,1.95086359978 -6.32068538666,1.14382088184,1.96844530106 -6.34769010544,1.15082037449,1.9872367382 -6.34570455551,1.1508282423,2.00781583786 -6.40071296692,1.16282653809,2.04541444778 -6.42072486877,1.16883087158,2.07299900055 -6.39674091339,1.16484224796,2.08658266068 -6.43675136566,1.17384338379,2.1211616993 -6.43676567078,1.17585098743,2.14274334908 -6.44877099991,1.17885255814,2.15655303001 -6.40478944778,1.17086780071,2.16510367393 -6.47679615021,1.18686330318,2.20971083641 -6.54380321503,1.20185947418,2.25331473351 -6.56081533432,1.20686411858,2.28090429306 -6.51583433151,1.19887948036,2.28846645355 -6.45484781265,1.18689370155,2.27923679352 -6.41186666489,1.17990899086,2.28778386116 -6.4298787117,1.18491363525,2.31537866592 -6.42689323425,1.18492209911,2.33694696426 -6.41290903091,1.18393194675,2.35353469849 -6.44691944122,1.19193410873,2.38811445236 -6.45093345642,1.19494116306,2.4116973877 -6.42994308472,1.19094872475,2.41547870636 -6.41995859146,1.18995821476,2.4340569973 -6.41097354889,1.18996751308,2.4526424408 -6.3959903717,1.18897819519,2.47020316124 -6.42000150681,1.19498169422,2.50080156326 -6.42601537704,1.19798839092,2.52538537979 -6.42203092575,1.1979970932,2.54695343971 -6.44203567505,1.20299756527,2.56575059891 -6.35406064987,1.18702113628,2.55529236794 -6.41906738281,1.20201766491,2.6028907299 -6.50507116318,1.22101032734,2.6585085392 -6.54308128357,1.23101174831,2.69708967209 -6.54209566116,1.23201978207,2.71967387199 -6.6001033783,1.24601757526,2.76627063751 -6.62510681152,1.25201702118,2.7880692482 -6.59512519836,1.24703025818,2.79963827133 -6.57014322281,1.24404263496,2.81320714951 -6.55615949631,1.24305319786,2.83078670502 -6.53017711639,1.23906564713,2.84336185455 -6.54319047928,1.24407148361,2.87293624878 -6.56919431686,1.25007092953,2.89573478699 -6.56420993805,1.25107979774,2.91731500626 -6.54822683334,1.24909090996,2.93487977982 -6.47825098038,1.23611164093,2.92843699455 -6.47126674652,1.23712086678,2.94901561737 -6.46628236771,1.23812997341,2.9705927372 -6.49929285049,1.24613213539,3.00918006897 -6.49630117416,1.24713683128,3.01996636391 -6.47431898117,1.24414908886,3.03453087807 -6.47633361816,1.24615681171,3.05911612511 -6.44535255432,1.24217045307,3.06869149208 -6.47236394882,1.24917376041,3.10527706146 -6.51637268066,1.26117408276,3.14987134933 -6.43839120865,1.24519228935,3.12563705444 -6.42440843582,1.24420309067,3.14321208 -6.44642019272,1.25120735168,3.17779922485 -6.5254240036,1.27020120621,3.24039530754 -6.53743743896,1.27420735359,3.27097678185 -6.52545404434,1.2742177248,3.28955984116 -6.50547266006,1.27222979069,3.30512475967 -6.46348667145,1.2642416954,3.29690146446 -6.46550130844,1.26624953747,3.32248425484 -6.43952083588,1.26326286793,3.33504366875 -6.40654087067,1.25827717781,3.3426232338 -6.43155241013,1.26628100872,3.38020825386 -6.38657522202,1.25829792023,3.38276314735 -6.40758705139,1.26530230045,3.41835045815 -6.4015955925,1.26530742645,3.42714834213 -6.39261245728,1.26531755924,3.4477212429 -6.44661951065,1.2793160677,3.50131416321 -6.44463539124,1.28132498264,3.52588868141 -6.39065980911,1.27134346962,3.52245330811 -6.40267276764,1.27634966373,3.55403923988 -6.48467588425,1.29734301567,3.62463116646 -6.39369773865,1.27836406231,3.58740520477 -6.36571836472,1.27437794209,3.59797048569 -6.36673355103,1.27738595009,3.62355852127 -6.35075235367,1.27639782429,3.64111948013 -6.33976984024,1.27640855312,3.66069412231 -6.36778068542,1.28441178799,3.70228004456 -6.3687877655,1.28641569614,3.71508169174 -6.33680963516,1.28143060207,3.72363781929 -6.36182069778,1.28943419456,3.76323533058 -6.35383796692,1.29044425488,3.7848110199 -6.35285425186,1.29245316982,3.81039047241 -6.35087060928,1.29546225071,3.8359618187 -6.34288740158,1.2954723835,3.85753917694 -6.33689641953,1.29547786713,3.8673248291 -6.37090682983,1.30648005009,3.91391706467 -6.41791439056,1.3194797039,3.96851539612 -6.40193367004,1.31849181652,3.98707056046 -6.39395046234,1.31950187683,4.00865650177 -6.35497283936,1.31351780891,4.01123332977 -6.35898923874,1.31752610207,4.04179763794 -6.3959903717,1.32752346992,4.07859420776 -6.35601329803,1.3205395937,4.08017396927 -6.30003976822,1.31055927277,4.07273006439 -6.31105327606,1.31656563282,4.106320858 -6.34306430817,1.32656860352,4.15489673615 -6.32208395004,1.32458126545,4.16847801208 -6.34408807755,1.33058142662,4.1962761879 -6.34110498428,1.33359098434,4.22284412384 -6.35911798477,1.34059631824,4.26242923737 -6.40512561798,1.35459625721,4.32101774216 -6.40414190292,1.35660517216,4.34859848022 -6.43115329742,1.36660897732,4.39518451691 -6.42417049408,1.36761891842,4.41876840591 -6.42417907715,1.36962342262,4.433552742 -6.39919948578,1.36663711071,4.44512987137 -6.37922000885,1.36564993858,4.46069908142 -6.37023735046,1.36666059494,4.48327827454 -6.38125181198,1.37166726589,4.51986122131 -6.38526773453,1.37667560577,4.55243301392 -6.41027116776,1.38367509842,4.58423471451 -6.49427080154,1.40666759014,4.67283821106 -6.4652929306,1.4036822319,4.68240833282 -6.4363155365,1.40069711208,4.69296312332 -6.40333795547,1.39571225643,4.69854450226 -6.36536216736,1.38972878456,4.70111274719 -6.35737943649,1.39173913002,4.72469854355 -6.40737819672,1.40473389626,4.77649784088 -6.38739919662,1.40374696255,4.7930598259 -6.39141511917,1.40875530243,4.82663822174 -6.40042972565,1.41476261616,4.86421585083 -6.39044761658,1.41577339172,4.88680267334 -6.38846492767,1.41878283024,4.91637849808 -6.36948537827,1.41779577732,4.9329533577 -6.37749242783,1.42179870605,4.95474290848 -6.35651302338,1.41981208324,4.97031068802 -6.35552978516,1.42382097244,4.99990177155 -6.3305516243,1.42083513737,5.01246643066 -6.29357624054,1.41585159302,5.01503562927 -6.29559230804,1.4198602438,5.04762077332 -6.3086066246,1.42786705494,5.09019374847 -6.27762174606,1.42187786102,5.0819683075 -6.26664066315,1.42288911343,5.1045498848 -6.28465366364,1.43089473248,5.15113019943 -6.25667667389,1.42790961266,5.16069984436 -6.24069690704,1.427921772,5.17928123474 -6.23271512985,1.4299325943,5.20485925674 -6.20073032379,1.42394351959,5.19464159012 -6.21474504471,1.43195021152,5.23921442032 -6.20376348495,1.43296146393,5.26180028915 -6.16878843307,1.42797768116,5.26536607742 -6.17080497742,1.43298661709,5.29994249344 -6.15482521057,1.43299889565,5.31852531433 -6.13484716415,1.43201243877,5.3350892067 -6.13585519791,1.43401670456,5.35188531876 -6.12887382507,1.43702721596,5.37846803665 -6.09889745712,1.43304276466,5.38603401184 -6.09691524506,1.43705248833,5.41761112213 -6.08793401718,1.43906354904,5.44318675995 -6.05895757675,1.43607878685,5.45076179504 -6.0439786911,1.43609118462,5.47133207321 -6.0369887352,1.4370970726,5.4811296463 -6.03400707245,1.44010746479,5.5136885643 -6.01002979279,1.43912148476,5.52526950836 -5.9920501709,1.43813419342,5.54185581207 -5.9950671196,1.44314324856,5.57942581177 -5.97908830643,1.44415581226,5.59900045395 -5.95611047745,1.4421697855,5.61157941818 -5.96011924744,1.44617402554,5.63335895538 -5.94214010239,1.4451867342,5.64994716644 -5.90816545486,1.44120335579,5.65350723267 -5.91718053818,1.44821083546,5.69609546661 -5.89520311356,1.447224617,5.70967340469 -5.88322353363,1.44823658466,5.73324871063 -5.87823438644,1.45024251938,5.74702453613 -5.85925626755,1.44925582409,5.76360225677 -5.84327697754,1.450268507,5.78317928314 -5.84029579163,1.45427858829,5.81575679779 -5.81731796265,1.45229279995,5.82833480835 -5.79334211349,1.45130741596,5.84090042114 -5.79834938049,1.45431101322,5.86369132996 -5.78037166595,1.45432412624,5.88127040863 -5.76039409637,1.45433795452,5.89783716202 -5.74941444397,1.45634973049,5.92241811752 -5.73343610764,1.45736265182,5.94298744202 -5.71945667267,1.45837497711,5.9645690918 -5.70347881317,1.45938801765,5.98513889313 -5.69348955154,1.45839452744,5.99193906784 -5.67651128769,1.45940756798,6.01051998138 -5.67752981186,1.46441733837,6.05008172989 -5.6485543251,1.46143257618,6.05566501617 -5.62257862091,1.45944786072,6.06622743607 -5.62259674072,1.465457201,6.10281515121 -5.60161924362,1.46447110176,6.11739397049 -5.58763217926,1.46347904205,6.12216806412 -5.58664989471,1.46848869324,6.15775918961 -5.55167627335,1.46350538731,6.15733146667 -5.54769563675,1.46851623058,6.19189929962 -5.51972055435,1.46553146839,6.1984796524 -5.48974609375,1.46254742146,6.20404434204 -5.49876213074,1.47055506706,6.25163555145 -5.4777765274,1.46756446362,6.2484087944 -5.4767947197,1.47257447243,6.28598833084 -5.44981956482,1.47058951855,6.29356813431 -5.43284225464,1.47160279751,6.31314373016 -5.40786647797,1.46961784363,6.3237156868 -5.39788627625,1.47262918949,6.35030508041 -5.39789628983,1.47563445568,6.37108373642 -5.3669219017,1.47265028954,6.37366390228 -5.3709397316,1.47965967655,6.41923284531 -5.34096574783,1.47667562962,6.42380475998 -5.32798719406,1.47868776321,6.44739294052 -5.30501127243,1.47770249844,6.460958004 -5.27903604507,1.47571754456,6.46953678131 -5.29304122925,1.48271942139,6.50633430481 -5.25306987762,1.47673738003,6.49791002274 -5.25608825684,1.48374688625,6.54347991943 -5.23411226273,1.48376142979,6.55804872513 -5.21513557434,1.48377490044,6.57463598251 -5.18416166306,1.48079109192,6.57720994949 -3.44060778618,0.943153083324,4.41056489944 -3.43561816216,0.94315880537,4.41736459732 -3.41164469719,0.940174162388,4.41592073441 -3.40766525269,0.943184912205,4.43850183487 -3.39668726921,0.944197058678,4.45208358765 -5.09128808975,1.48686468601,6.68987607956 -5.08530807495,1.49187576771,6.72445726395 -5.06732225418,1.48988461494,6.72323465347 -5.05234479904,1.4918974638,6.74581813812 -5.01737213135,1.4869145155,6.74239253998 -5.01639127731,1.49392473698,6.78496694565 -4.98741722107,1.49094033241,6.78855133057 -4.97843885422,1.49495220184,6.82013034821 -4.94846534729,1.49196839333,6.82370042801 -4.95547294617,1.49797201157,6.85549068451 -4.9165019989,1.49199020863,6.84705543518 -4.91851997375,1.49999964237,6.89364242554 -4.89054632187,1.49701523781,6.89921951294 -4.86457204819,1.49603056908,6.90779399872 -4.86259126663,1.50204086304,6.94938135147 -4.83761692047,1.5010560751,6.95995140076 -4.82063102722,1.4990645647,6.95873594284 -4.81265211105,1.50407636166,6.99331283569 -4.78867769241,1.5030913353,7.0048866272 -4.76670217514,1.50310599804,7.01946020126 -4.75772380829,1.50711762905,7.05204582214 -4.71575403214,1.50013625622,7.03662061691 -4.71376371384,1.50314176083,7.05740785599 -4.70878505707,1.50915300846,7.09797906876 -4.68081092834,1.50716865063,7.10256195068 -4.65883541107,1.50718295574,7.11614561081 -4.64985799789,1.51219522953,7.1517124176 -4.6268825531,1.51220989227,7.16429233551 -4.60090827942,1.51022517681,7.171875 -4.61391496658,1.51922762394,7.21666479111 -4.57994365692,1.51524484158,7.21323490143 -4.55696868896,1.51525974274,7.22680664062 -4.55498838425,1.52227008343,7.27239322662 -4.52201652527,1.51828682423,7.26897382736 -4.49404335022,1.51630270481,7.27454614639 -4.50904941559,1.52630507946,7.32532644272 -4.47507810593,1.52232205868,7.32090091705 -4.44710493088,1.52033782005,7.32548093796 -4.44412469864,1.52734851837,7.37106513977 -4.41715145111,1.52636420727,7.37764310837 -4.38817882538,1.52438020706,7.38121747971 -4.38419914246,1.53139126301,7.4267950058 -4.36421442032,1.52840054035,7.41957950592 -4.34523916245,1.52941453457,7.44015407562 -4.33926010132,1.53642582893,7.48174190521 -4.3092880249,1.53344213963,7.48331832886 -4.29231214523,1.53645586967,7.50789260864 -4.28533363342,1.54246759415,7.55046510696 -4.27135705948,1.54648065567,7.58004570007 -4.26736783981,1.54948663712,7.60083150864 -4.260389328,1.55549800396,7.64241933823 -4.23241710663,1.55451416969,7.64898681641 -4.20844221115,1.55452895164,7.6595788002 -4.20246362686,1.56154036522,7.70515680313 -4.17849063873,1.56155586243,7.71972084045 -4.17551088333,1.57056641579,7.77030897141 -4.17552042007,1.5745716095,7.79909944534 -4.15654563904,1.57758593559,7.82267045975 -4.13057279587,1.57660126686,7.83125448227 -4.12859344482,1.58661210537,7.88782453537 -4.1246137619,1.59462296963,7.93841457367 -4.13463115692,1.60963141918,8.01898956299 -4.13664007187,1.61563611031,8.05278396606 -4.10666894913,1.61365270615,8.05735015869 -4.09469127655,1.61866509914,8.09394073486 -4.07571649551,1.62167906761,8.11851978302 -4.04574489594,1.61969554424,8.12209320068 -4.03476810455,1.6257083416,8.16466236115 -4.00779533386,1.62572407722,8.17324447632 -4.00080728531,1.6277307272,8.19202613831 -3.9758336544,1.62774574757,8.2036151886 -3.93086600304,1.61976516247,8.17519187927 -3.88589835167,1.61078441143,8.14577198029 -3.84292984009,1.60280334949,8.12034797668 -3.79596352577,1.5928235054,8.08791160583 -3.77697873116,1.58983242512,8.07970142365 -3.75300502777,1.59084737301,8.09228897095 -3.7380297184,1.59586083889,8.12686157227 -3.71505618095,1.59687578678,8.14343929291 -3.71407651901,1.6078864336,8.20901679993 -3.73309135437,1.62889277935,8.31860351562 -3.70911836624,1.62990808487,8.3351764679 -3.70712900162,1.63591372967,8.36596488953 -3.67715740204,1.63392996788,8.36754703522 -3.65918254852,1.63694393635,8.39712619781 -3.62621164322,1.63396084309,8.39170837402 -3.60623788834,1.63697552681,8.41927433014 -3.57626628876,1.63599169254,8.42085552216 -3.55529260635,1.63800632954,8.44443225861 -3.53930687904,1.63701462746,8.44222640991 -3.52133226395,1.64102852345,8.47280693054 -3.49136066437,1.63904488087,8.47438716888 -3.4693877697,1.64205992222,8.49795436859 -3.44341516495,1.64207530022,8.50853919983 -3.42144179344,1.64409017563,8.53111362457 -3.39147043228,1.64210653305,8.53269481659 -3.38048386574,1.64411377907,8.54348468781 -3.24554204941,1.58615100384,8.27705955505 -2.91765427589,1.42522633076,7.50862789154 -2.89867997169,1.4272403717,7.52920532227 -2.86171102524,1.42025816441,7.50278282166 -2.84073734283,1.42127239704,7.51637077332 -2.82675075531,1.41928017139,7.51316928864 -2.79877972603,1.4172962904,7.51074075699 -2.77780580521,1.41831052303,7.52432918549 -2.75483298302,1.4183255434,7.53490352631 -2.72886157036,1.41734135151,7.53747701645 -2.69389152527,1.41035819054,7.51206541061 -2.65992188454,1.40437543392,7.49064397812 -2.65293383598,1.4073818922,7.50743675232 -2.63196063042,1.4093965292,7.52301311493 -2.61298656464,1.41141057014,7.54359483719 -2.59401249886,1.41442465782,7.56417751312 -2.55804395676,1.4074422121,7.53675031662 -2.51707553864,1.39646041393,7.49034166336 -2.49610257149,1.3974750042,7.5059170723 -2.33635592461,1.4496101141,7.83171749115 -2.32038164139,1.45562386513,7.86928892136 -2.29341053963,1.4536396265,7.86886548996 -2.28242349625,1.45464646816,7.87367010117 -2.26544904709,1.45966017246,7.90724992752 -2.25347352028,1.4686729908,7.95883131027 -2.25949287415,1.49168229103,8.07740688324 -2.24751782417,1.50169539452,8.13497543335 -2.24553847313,1.51870572567,8.22456932068 -2.23056387901,1.52671909332,8.27115058899 -2.26456451416,1.56171774864,8.45093727112 -2.39354920387,1.68070375919,9.0524969101 -2.37057638168,1.68471848965,9.07808494568 -2.34060573578,1.68273460865,9.07767009735 -2.31763386726,1.68774974346,9.10923957825 -2.28566384315,1.68476617336,9.10082435608 -2.28067588806,1.69277250767,9.14260959625 -2.25070548058,1.69178855419,9.14319324493 -2.22173452377,1.69080460072,9.14777565002 -2.1967625618,1.69381976128,9.16835975647 -2.16979146004,1.69583547115,9.18393421173 -2.14282035828,1.69685101509,9.19751644135 -2.1168487072,1.69986641407,9.21609687805 -2.1178586483,1.7128713131,9.2858915329 -2.0998852253,1.72288537025,9.34346675873 -2.07791256905,1.72989988327,9.38204860687 -2.0569396019,1.73691439629,9.42663002014 -2.02097129822,1.73193180561,9.40420627594 -1.99500012398,1.73494720459,9.42778301239 -1.96602928638,1.73496294022,9.43337345123 -1.95104444027,1.73497128487,9.43815517426 -1.91307651997,1.72698891163,9.40173816681 -1.88110649586,1.72400522232,9.39132785797 -1.84713745117,1.71902215481,9.37390804291 -1.81816697121,1.72003793716,9.38148880005 -1.78819680214,1.7190541029,9.38406944275 -1.75722646713,1.7170702219,9.37765789032 -1.7422413826,1.71707832813,9.37844944 -1.71427094936,1.71909403801,9.39302635193 -1.68130147457,1.71411061287,9.37661075592 -1.64933216572,1.7121270895,9.36818981171 -1.62336051464,1.71514213085,9.38977718353 -1.59139108658,1.71215867996,9.3793592453 -1.57740604877,1.71416664124,9.38914203644 -1.54743564129,1.71318244934,9.38772964478 -1.51646602154,1.71119880676,9.38331031799 -1.48449647427,1.70821511745,9.37189006805 -1.45552623272,1.70823097229,9.3794708252 -1.42355620861,1.70424723625,9.36206245422 -1.395586133,1.70726287365,9.37963485718 -1.38060116768,1.70627105236,9.38042449951 -1.3476318121,1.7012873888,9.35701179504 -1.31866121292,1.70130300522,9.36059951782 -1.2906910181,1.70431888103,9.37817382812 -1.25872170925,1.700335145,9.36375427246 -1.22875154018,1.69935107231,9.36133861542 -1.21476578712,1.6993585825,9.36313915253 -1.18279671669,1.6963750124,9.34871673584 -1.15482640266,1.6993906498,9.36629390717 -1.12485635281,1.69740641117,9.36287879944 -1.09488630295,1.69642233849,9.36046123505 -1.06591629982,1.69743800163,9.3690404892 -1.03694593906,1.69845366478,9.37462425232 -1.02096092701,1.69546163082,9.36042118073 -0.991990447044,1.69547712803,9.36301040649 -0.966020047665,1.70349264145,9.40857982635 -0.933050453663,1.69550871849,9.36817264557 -0.907079577446,1.70252382755,9.40975189209 -0.875109791756,1.69653975964,9.37834453583 -0.843140661716,1.69155609608,9.35592269897 -0.830155134201,1.69556355476,9.37571430206 -0.800185680389,1.69557952881,9.37828922272 -0.773214757442,1.70059466362,9.40787506104 -0.74224460125,1.69561028481,9.38246822357 -0.712275028229,1.69462621212,9.38204669952 -0.68230509758,1.69264185429,9.37463188171 -0.652335464954,1.69265770912,9.37420940399 -0.637350201607,1.69066536427,9.36300849915 -0.607380628586,1.68968129158,9.36258602142 -0.57841026783,1.6906965971,9.36617279053 -0.550439536572,1.69371175766,9.38476276398 -0.518470585346,1.68672800064,9.34933948517 -0.489500552416,1.6887434721,9.35992145538 -0.475515127182,1.68975102901,9.36871814728 -0.445545405149,1.6887665987,9.3612985611 -0.416574954987,1.68878185749,9.36288833618 -0.38660505414,1.68579745293,9.34747409821 -0.356635272503,1.68281304836,9.33305740356 -0.326665461063,1.67882859707,9.31564044952 -0.297695428133,1.68184411526,9.32822322845 -0.28470954299,1.6888512373,9.36802196503 -0.254740148783,1.68986701965,9.369597435 -0.224770396948,1.68588256836,9.3511800766 -0.195799857378,1.68389773369,9.34277248383 -0.165830299258,1.68091332912,9.32735157013 -0.136860057712,1.68392848969,9.33893871307 -0.121875263751,1.68093633652,9.32572937012 -0.0929049029946,1.6809514761,9.32331752777 -0.0639346167445,1.68296658993,9.33490562439 -0.0339652188122,1.67898225784,9.31748199463 -0.00499488413334,1.67899739742,9.31507015228 --0.00299679301679,1.67200171947,8.74895477295 --0.0309668798,1.67301678658,8.75553226471 --0.0579379871488,1.67103147507,8.74612426758 --0.0859079882503,1.67004668713,8.73670005798 --0.112879179418,1.67106127739,8.74429416656 --0.126864045858,1.66806900501,8.72807884216 --0.15383516252,1.66908359528,8.72967243195 --0.180806189775,1.66809821129,8.72426223755 --0.208776429296,1.67011320591,8.73484325409 --0.236746400595,1.66912841797,8.73041915894 --0.263717353344,1.66814303398,8.72300815582 --0.290688306093,1.6671577692,8.71559715271 --0.30567330122,1.67516517639,8.75439071655 --0.33264374733,1.67018008232,8.72797012329 --0.359614610672,1.66819477081,8.71855735779 --0.385585606098,1.66120922565,8.68314170837 --0.412556618452,1.66122376919,8.68173217773 --0.440526783466,1.66323876381,8.68531227112 --0.453512519598,1.66124594212,8.67710876465 --0.48048377037,1.66226017475,8.68070316315 --0.508453667164,1.66227531433,8.677277565 --0.535424768925,1.66228973866,8.6768693924 --0.562395632267,1.66130435467,8.67145729065 --0.589366674423,1.66231870651,8.67104911804 --0.617337048054,1.66333353519,8.67663192749 --0.632321715355,1.66634118557,8.68841934204 --0.659292817116,1.66635560989,8.68601036072 --0.686263203621,1.66437029839,8.67358970642 --0.717232823372,1.6733853817,8.71617603302 --0.74120503664,1.66739916801,8.68077278137 --0.769175648689,1.6694136858,8.68736076355 --0.798146009445,1.67342841625,8.70394802094 --0.811130821705,1.66943585873,8.68472766876 --0.839101672173,1.6714502573,8.69332122803 --0.866072237492,1.6704647541,8.68290233612 --0.894043028355,1.67247927189,8.68949317932 --0.921014010906,1.67149353027,8.68408203125 --0.949984133244,1.67450833321,8.69466590881 --0.977955162525,1.6775226593,8.70226287842 --0.991940259933,1.67752993107,8.70105171204 --1.0199110508,1.67854428291,8.70464324951 --1.05088019371,1.68355941772,8.72521972656 --1.07785153389,1.68357348442,8.72281646729 --1.10682141781,1.68558824062,8.72639369965 --1.13379275799,1.68560230732,8.72298908234 --1.14877772331,1.68760967255,8.73078346252 --1.17774772644,1.68962442875,8.73436260223 --1.20571827888,1.68963873386,8.73395061493 --1.23368895054,1.69065308571,8.73353862762 --1.26066029072,1.6906671524,8.72913265228 --1.29063022137,1.69368171692,8.74071884155 --1.31960070133,1.69669604301,8.74730873108 --1.33058738708,1.69370245934,8.73010921478 --1.36155700684,1.69771742821,8.74669456482 --1.38852787018,1.69673144817,8.73828125 --1.41849792004,1.70074605942,8.74886989594 --1.4464687109,1.70076024532,8.74745941162 --1.47543907166,1.70277452469,8.75004482269 --1.50540935993,1.70578896999,8.76063537598 --1.52039396763,1.70679628849,8.76142120361 --1.55236363411,1.71181106567,8.7820110321 --1.5813344717,1.71482515335,8.78760814667 --1.60930526257,1.71483922005,8.78419685364 --1.6402746439,1.71785402298,8.79277515411 --1.66824567318,1.7188680172,8.79036712646 --1.69521653652,1.71688187122,8.77894973755 --1.71120142937,1.71988928318,8.78774547577 --1.74017226696,1.72190320492,8.79134178162 --1.76914250851,1.72291743755,8.78992462158 --1.79411435127,1.71993088722,8.77151584625 --1.82708418369,1.72594535351,8.79511451721 --1.8520553112,1.7229591608,8.77169036865 --1.86704027653,1.72396636009,8.77348327637 --1.89801096916,1.72798025608,8.78708457947 --1.92598164082,1.72799432278,8.78067016602 --1.95395278931,1.72900807858,8.77726364136 --1.98392271996,1.73002231121,8.77884483337 --2.01189398766,1.7310359478,8.77544021606 --2.03986477852,1.73104977608,8.76902580261 --2.05884861946,1.73505747318,8.78681755066 --2.08582019806,1.73507094383,8.77941513062 --2.11678981781,1.73808526993,8.78399562836 --2.14176225662,1.7360984087,8.76759052277 --2.17473173141,1.74111282825,8.78318405151 --2.20370268822,1.74212658405,8.78177547455 --2.23167347908,1.74214029312,8.77436065674 --2.24865794182,1.74514746666,8.78315544128 --2.27362990379,1.74216079712,8.76474380493 --2.30459976196,1.7451748848,8.76832675934 --2.33357071877,1.74618852139,8.76692008972 --2.36454105377,1.74920248985,8.77151012421 --2.39351153374,1.75021612644,8.76809883118 --2.40749788284,1.75022268295,8.76790523529 --2.43646788597,1.75123655796,8.76148223877 --2.46843862534,1.75525033474,8.77208328247 --2.4954097271,1.75426375866,8.76067066193 --2.52837920189,1.75827801228,8.76925373077 --2.55135250092,1.75529038906,8.74785518646 --2.58232283592,1.7573043108,8.75044345856 --2.59930753708,1.76031136513,8.75723934174 --2.62827801704,1.76032495499,8.75081920624 --2.65524935722,1.76033818722,8.73940658569 --2.68621969223,1.76235198975,8.74199867249 --2.71819067001,1.76636552811,8.75060176849 --2.74616217613,1.76637876034,8.7431936264 --2.77513289452,1.76739215851,8.73778057098 --2.79111790657,1.76839900017,8.74057865143 --2.82408738136,1.77241313457,8.74615955353 --2.85105967522,1.77242600918,8.73675823212 --2.88103055954,1.77343928814,8.7353515625 --2.91400003433,1.77745342255,8.73993206024 --2.93997240067,1.77646589279,8.72753238678 --2.97094273567,1.7784794569,8.72711849213 --2.98492860794,1.7784858942,8.72391891479 --3.01589918137,1.78049945831,8.72350692749 --3.04986929893,1.78551328182,8.73310279846 --3.07983970642,1.78652656078,8.72868728638 --3.10481214523,1.78453910351,8.71127700806 --3.13778233528,1.78755271435,8.71586608887 --3.15276765823,1.78855919838,8.71466445923 --3.18473887444,1.79157245159,8.71926879883 --3.21470952034,1.79358577728,8.71385192871 --3.2426815033,1.79359853268,8.70544624329 --3.27365207672,1.79561173916,8.70403766632 --3.30962109566,1.80062580109,8.71462345123 --3.33459424973,1.79963779449,8.69922447205 --3.35957694054,1.80564582348,8.72302055359 --3.38155007362,1.80265772343,8.69660663605 --3.41651988029,1.806671381,8.70419597626 --3.44349217415,1.80668377876,8.69279193878 --3.47446298599,1.80869686604,8.69038391113 --3.49943590164,1.80770885944,8.67398071289 --3.5384042263,1.81372320652,8.6895647049 --3.55439019203,1.81472945213,8.69137191772 --3.57836294174,1.81274151802,8.67096138 --3.61233329773,1.81675481796,8.67555618286 --3.6473031044,1.82076823711,8.68114376068 --3.67127609253,1.81878018379,8.66073417664 --3.70224738121,1.82079303265,8.6573266983 --3.72223210335,1.82479977608,8.66813373566 --3.74720430374,1.82281196117,8.6487159729 --3.77817583084,1.82482457161,8.64531135559 --3.81014657021,1.82683753967,8.64390468597 --3.83911824226,1.82784986496,8.63449287415 --3.86909008026,1.82986223698,8.62909126282 --3.90505957603,1.83387577534,8.63467788696 --3.91704630852,1.83288156986,8.62447357178 --3.94501900673,1.83389365673,8.61507511139 --3.97798967361,1.83590650558,8.61366176605 --4.00996112823,1.83891892433,8.61326789856 --4.03893327713,1.83993136883,8.60285377502 --4.07390356064,1.84294426441,8.60644817352 --4.09587717056,1.84095549583,8.58203983307 --4.11286258698,1.84296178818,8.5828371048 --4.1468334198,1.84597468376,8.58342933655 --4.17480564117,1.84598660469,8.57202339172 --4.19877958298,1.84499800205,8.55261993408 --4.23774862289,1.85001146793,8.56220722198 --4.26572084427,1.85102331638,8.54979705811 --4.28570604324,1.85402977467,8.55760574341 --4.31867694855,1.85704231262,8.55519771576 --4.34464979172,1.8560539484,8.53778266907 --4.37662124634,1.858066082,8.53438091278 --4.41359138489,1.86307907104,8.53897190094 --4.43656539917,1.86109006405,8.51756858826 --4.47053670883,1.8641024828,8.5171661377 --4.48752212524,1.86610853672,8.51696491241 --4.50849676132,1.86311936378,8.4905538559 --4.54146814346,1.86613154411,8.48815250397 --4.58243751526,1.8721446991,8.49974727631 --4.61041021347,1.87315618992,8.48834991455 --4.64438152313,1.87616848946,8.48493385315 --4.67635393143,1.87818038464,8.4805355072 --4.68834018707,1.87718594074,8.46932601929 --4.72331190109,1.88119804859,8.46992778778 --4.76628017426,1.88821136951,8.48352241516 --4.77025985718,1.8782197237,8.42711162567 --4.77323913574,1.8682281971,8.36869430542 --4.78221750259,1.8612370491,8.32228469849 --4.77720928192,1.85424029827,8.28408718109 --4.80818128586,1.85525202751,8.27567386627 --4.83715391159,1.85626327991,8.26527023315 --4.86412715912,1.85727441311,8.25086307526 --4.88710212708,1.8562848568,8.23046112061 --4.91707468033,1.85729634762,8.22105503082 --4.93705034256,1.85530638695,8.19565200806 --4.95403623581,1.85631227493,8.19445037842 --4.97801017761,1.85632288456,8.17504310608 --5.00598335266,1.85633397102,8.16163158417 --5.03395700455,1.85734498501,8.14922809601 --5.06093025208,1.85835576057,8.13482284546 --5.08490514755,1.85736620426,8.1164226532 --5.11787748337,1.86037755013,8.11202144623 --5.13686275482,1.86238372326,8.11281394958 --5.16283655167,1.86239433289,8.09640598297 --5.19280958176,1.86440527439,8.08700466156 --5.21678495407,1.86441552639,8.06860542297 --5.24875736237,1.86642670631,8.06119728088 --5.27673053741,1.86743748188,8.04779052734 --5.28571891785,1.86644208431,8.0345954895 --5.31469249725,1.86745297909,8.02218532562 --5.34366559982,1.86846387386,8.00977611542 --5.36864042282,1.86847412586,7.99237394333 --5.39761352539,1.86948478222,7.97996520996 --5.42958641052,1.87249577045,7.97256183624 --5.45656061172,1.87250602245,7.9581618309 --5.47154760361,1.8735114336,7.95296001434 --5.49552249908,1.87352144718,7.93355512619 --5.51249933243,1.87053060532,7.90414953232 --5.54947042465,1.87454199791,7.90274047852 --5.57544517517,1.8745521307,7.88633728027 --5.60341978073,1.87656235695,7.8729352951 --5.62939453125,1.87657237053,7.85653209686 --5.64737987518,1.87857794762,7.8553314209 --5.66835546494,1.8765873909,7.83092069626 --5.6913318634,1.87659692764,7.81152677536 --5.72030496597,1.87760746479,7.79710817337 --5.74528074265,1.87861704826,7.78071641922 --5.76925611496,1.8776267767,7.76030445099 --5.78624248505,1.87963199615,7.75810909271 --5.80421924591,1.87664103508,7.72969675064 --5.84019184113,1.88065195084,7.72629356384 --5.86216783524,1.88066112995,7.70489501953 --5.88414335251,1.87967050076,7.68248796463 --5.91511774063,1.88168048859,7.67309141159 --5.94009304047,1.88169026375,7.65367746353 --5.94808197021,1.88069450855,7.63948059082 --5.98305463791,1.88470482826,7.63508605957 --6.00902938843,1.88471460342,7.61667060852 --6.02900695801,1.88372337818,7.59327554703 --6.06098031998,1.88573360443,7.58286523819 --6.08795547485,1.88674294949,7.56746530533 --6.11393070221,1.88775253296,7.55005884171 --6.13391685486,1.89075779915,7.55086374283 --6.1538939476,1.88876652718,7.52646112442 --6.18486785889,1.89177656174,7.51404762268 --6.20684432983,1.89078533649,7.49264955521 --6.23082065582,1.89079427719,7.47324895859 --6.2457985878,1.88780260086,7.44183635712 --6.2047996521,1.87080204487,7.36862754822 --6.22177791595,1.86881029606,7.34122419357 --5.38696193695,1.59473907948,6.29760789871 --5.34995269775,1.57674276829,6.2131934166 --5.35093307495,1.5707501173,6.17277288437 --5.3039264679,1.54975295067,6.07835912704 --5.28491258621,1.53775823116,6.0169467926 --5.25990915298,1.52675974369,5.96772813797 --5.26388978958,1.52176737785,5.93331766129 --5.25787305832,1.51477384567,5.88790607452 --5.24885654449,1.50578045845,5.83848428726 --5.2428393364,1.49778711796,5.79407596588 --5.23882198334,1.4907938242,5.75267267227 --5.23880386353,1.48580098152,5.71526145935 --5.22679710388,1.47880339622,5.68305015564 --5.22577905655,1.47281062603,5.6446352005 --5.22776031494,1.46781802177,5.61022567749 --5.24373865128,1.46782636642,5.59182596207 --5.24471950531,1.46283364296,5.55641317368 --5.23170423508,1.45383965969,5.50599527359 --5.22569656372,1.4488427639,5.48178958893 --5.23167657852,1.44585037231,5.45237779617 --5.24165678024,1.44385826588,5.42797422409 --5.22964143753,1.43486428261,5.38056564331 --5.23562192917,1.43087184429,5.35215950012 --5.23560333252,1.42587900162,5.31674051285 --5.24558210373,1.42388701439,5.29232978821 --5.24157476425,1.42088997364,5.27213668823 --5.25055408478,1.41789782047,5.24672365189 --5.2625336647,1.41690576077,5.22532176971 --5.26751422882,1.41291320324,5.19590568542 --5.28249263763,1.41292142868,5.17750263214 --5.29747104645,1.41292953491,5.15909910202 --5.31244945526,1.41193771362,5.1406955719 --5.32143783569,1.41194212437,5.13147592545 --5.35041332245,1.41595113277,5.12707901001 --5.34939622879,1.41095781326,5.0936794281 --5.37137269974,1.412966609,5.08126688004 --5.40834712982,1.4189760685,5.08487939835 --5.41532707214,1.41598367691,5.05745840073 --5.42130851746,1.41299080849,5.03105974197 --5.4412946701,1.41599583626,5.0328502655 --5.44427680969,1.41300272942,5.00344800949 --5.46125507355,1.41301071644,4.98704576492 --5.50422763824,1.42102062702,4.99464941025 --5.59119081497,1.44003367424,5.04225969315 --5.57417631149,1.43103909492,4.99384641647 --5.59516334534,1.43504405022,4.99664592743 --5.61214208603,1.43505179882,4.98025035858 --5.63611888885,1.43706023693,4.96884012222 --5.68209123611,1.44606995583,4.97743988037 --5.70406913757,1.44707798958,4.96504306793 --5.74804162979,1.45508778095,4.97063398361 --5.80400371552,1.46410107613,4.97204780579 --5.86995458603,1.47311842442,4.96424770355 --5.89693164825,1.47612667084,4.95484495163 --5.90891170502,1.47513377666,4.93243837357 --5.94888591766,1.48114275932,4.93404054642 --5.96986484528,1.48315036297,4.91964197159 --6.01884555817,1.49415671825,4.94444799423 --6.1547999382,1.52617132664,5.02608108521 --6.16578054428,1.52517807484,5.00268363953 --6.14576721191,1.51518321037,4.95225954056 --6.15074968338,1.51218962669,4.92385625839 --6.18972396851,1.51819825172,4.92245101929 --6.21870136261,1.52220606804,4.91406059265 --6.26668310165,1.53221201897,4.93586158752 --6.31765556335,1.54222095013,4.9444732666 --6.33463525772,1.54222798347,4.92506933212 --6.36861181259,1.54723584652,4.91967725754 --6.40758705139,1.55324399471,4.91727685928 --6.44856119156,1.55925238132,4.91587305069 --6.48554611206,1.56725728512,4.92868471146 --6.51052427292,1.56926453114,4.91528749466 --6.54050111771,1.57327210903,4.90488195419 --6.57147884369,1.57727956772,4.89548158646 --6.61645364761,1.58528769016,4.89709186554 --6.64043188095,1.58729469776,4.88168478012 --5.49464178085,1.28824222088,3.98590278625 --5.49763298035,1.28824555874,3.97470259666 --5.42862939835,1.26724863052,3.89627361298 --5.53159141541,1.29026019573,3.94488620758 --6.83332014084,1.61833000183,4.87590789795 --6.8682975769,1.62333714962,4.86851549149 --6.91027355194,1.63034451008,4.86612606049 --6.93225240707,1.63135123253,4.84771490097 --6.95624017715,1.63535499573,4.84852170944 --7.00821399689,1.645362854,4.85212850571 --7.03719234467,1.64836966991,4.83872413635 --7.08416795731,1.65637695789,4.83934354782 --7.12714338303,1.66338431835,4.83493804932 --7.16512060165,1.66839110851,4.82855224609 --7.21109580994,1.67639839649,4.82615280151 --7.25907945633,1.68640291691,4.84297227859 --7.29305696487,1.69040977955,4.83156633377 --7.35403013229,1.70241737366,4.839179039 --8.14886474609,1.89545476437,5.34101581573 --8.19984149933,1.90346121788,5.33863544464 --8.22882175446,1.90646696091,5.31922578812 --8.24580287933,1.90647208691,5.2928237915 --8.26779174805,1.90947520733,5.28862762451 --8.27977466583,1.90847992897,5.25922822952 --8.29775619507,1.90848493576,5.23383045197 --8.32573699951,1.91149032116,5.21443128586 --8.33971977234,1.9104950428,5.18602895737 --8.35770225525,1.91149997711,5.16063213348 --8.36769390106,1.91150248051,5.14843273163 --8.31468772888,1.89450502396,5.07699966431 --8.05372047424,1.82750046253,4.87751483917 --8.03470897675,1.81950438023,4.83010053635 --8.05469036102,1.82050931454,4.80770683289 --8.08067131042,1.82251465321,4.78729534149 --8.10565280914,1.82551980019,4.76790380478 --8.16262054443,1.83352792263,4.74931001663 --8.18460178375,1.83453285694,4.72690677643 --8.22658061981,1.84153831005,4.71651220322 --8.24556350708,1.84254288673,4.69311952591 --8.2705450058,1.84454774857,4.67272281647 --8.30752372742,1.8495528698,4.65832042694 --8.32651424408,1.85255539417,4.6521282196 --8.65143108368,1.92257153988,4.7664141655 --8.67141437531,1.92357563972,4.74202156067 --8.68839740753,1.92357981205,4.71562480927 --8.71037960052,1.92558419704,4.69122028351 --8.73136234283,1.92658817768,4.66682291031 --8.72835636139,1.92459011078,4.64661359787 --8.75533771515,1.92659425735,4.62521505356 --8.77332210541,1.92759823799,4.5998249054 --8.78330612183,1.92660200596,4.5684132576 --8.79229164124,1.92560577393,4.53801822662 --8.81227493286,1.92660963535,4.51261663437 --8.82325935364,1.92561352253,4.4822101593 --8.82725334167,1.92461514473,4.46701478958 --8.82623958588,1.92161870003,4.4306063652 --8.01235389709,1.72961008549,3.97391915321 --7.98634386063,1.72161376476,3.92850494385 --7.97833108902,1.71661782265,3.89209079742 --7.97531795502,1.71262180805,3.85868287086 --7.97530412674,1.70962572098,3.82728099823 --7.97329711914,1.70762777328,3.81007218361 --7.97328329086,1.70563185215,3.77866816521 --7.96626996994,1.70063579082,3.74325299263 --7.96925640106,1.69863975048,3.71385407448 --7.97124195099,1.69664371014,3.68344712257 --7.96722841263,1.69264769554,3.65003538132 --7.96222257614,1.69064962864,3.63182711601 --7.95121049881,1.68465352058,3.59541463852 --7.96419477463,1.68565750122,3.57101750374 --7.94918394089,1.67966127396,3.53361153603 --7.9571685791,1.67866516113,3.50620269775 --7.93315839767,1.67066895962,3.46479082108 --7.95914077759,1.67367291451,3.44538378716 --8.01412582397,1.68467497826,3.4552025795 --8.07010555267,1.69467890263,3.44981789589 --8.11408519745,1.70268261433,3.43842482567 --8.17906284332,1.71468627453,3.43603897095 --8.24604034424,1.72668993473,3.43466114998 --8.43500232697,1.76669311523,3.48532056808 --8.52397632599,1.78369629383,3.49194860458 --8.75293922424,1.83369743824,3.57382559776 --8.75692558289,1.83270049095,3.5424182415 --8.74891471863,1.82770359516,3.50600647926 --8.7479019165,1.82470655441,3.47360897064 --8.75188922882,1.82370972633,3.44219875336 --8.76687431335,1.82471251488,3.41579818726 --8.77386188507,1.82371556759,3.38639783859 --8.78485298157,1.82471692562,3.37419390678 --8.79184055328,1.82371985912,3.34479379654 --8.85382080078,1.83472204208,3.33741545677 --8.90480136871,1.84372448921,3.32502937317 --8.91978740692,1.84472703934,3.29762148857 --8.92277526855,1.8427298069,3.26621747017 --8.92276382446,1.84073257446,3.23381376266 --8.90975856781,1.83673405647,3.2126057148 --8.93874359131,1.84073638916,3.19121170044 --8.95073032379,1.84073889256,3.16381716728 --8.96871566772,1.84274125099,3.13740968704 --8.9737033844,1.84174382687,3.10700750351 --8.98768997192,1.84274613857,3.07960486412 --8.99468326569,1.84274733067,3.06539750099 --9.0046710968,1.84274971485,3.03699970245 --9.01265907288,1.84275209904,3.00759720802 --9.02264499664,1.8427542448,2.97919893265 --9.02663326263,1.84075677395,2.94778728485 --9.05661869049,1.84575843811,2.92639803886 --9.06460666656,1.84476065636,2.89699625969 --9.07660007477,1.84676170349,2.88479542732 --9.07558822632,1.84476387501,2.85239005089 --9.09257507324,1.84576582909,2.82599139214 --9.10856246948,1.84776771069,2.79959702492 --9.12754917145,1.84976947308,2.7731924057 --9.1325378418,1.84877157211,2.74278903008 --9.14152526855,1.84877359867,2.71338391304 --9.15351867676,1.85077428818,2.70118546486 --9.15950584412,1.8497761488,2.67077851295 --9.17949390411,1.85177779198,2.64538550377 --9.17448329926,1.84877991676,2.61197900772 --9.1874704361,1.84978151321,2.58357262611 --9.19545936584,1.84978330135,2.55417108536 --9.22144603729,1.85378444195,2.53078532219 --9.21244239807,1.85078573227,2.51157093048 --9.22443008423,1.85178732872,2.48316907883 --9.23041915894,1.85078895092,2.45377445221 --9.23340797424,1.84979069233,2.42236328125 --9.23939704895,1.84979224205,2.39296841621 --9.2683839798,1.85379314423,2.36856460571 --9.27637290955,1.85379457474,2.33916378021 --9.28036689758,1.85379528999,2.32395720482 --9.30835437775,1.85879588127,2.30057263374 --9.32434272766,1.85979676247,2.27317476273 --9.3223323822,1.85779857635,2.24076628685 --9.33932113647,1.85979950428,2.21336627007 --9.34631061554,1.85980081558,2.18295669556 --9.35429954529,1.85980200768,2.15355753899 --9.37129306793,1.86280190945,2.1423664093 --9.38528251648,1.86480283737,2.11396384239 --9.37227344513,1.8598048687,2.07854557037 --9.38226318359,1.8608058691,2.05015397072 --9.39925193787,1.8628064394,2.02275729179 --9.4112405777,1.86380732059,1.99334847927 --9.42822933197,1.86580777168,1.96595323086 --9.44822406769,1.86980736256,1.95475888252 --9.44221401215,1.86680901051,1.92134523392 --9.45620346069,1.86880946159,1.89294624329 --9.45619392395,1.86781060696,1.8615424633 --9.48018360138,1.87081050873,1.83514642715 --9.50417232513,1.87481045723,1.80875194073 --9.51416301727,1.87581086159,1.77935183048 --9.49615859985,1.87081241608,1.76014590263 --9.52314853668,1.87581193447,1.73374640942 --9.52913856506,1.87581253052,1.70334291458 --9.54812812805,1.87781238556,1.67595052719 --9.57311820984,1.88181185722,1.64854681492 --9.57110977173,1.88081288338,1.61714792252 --9.57210445404,1.87981331348,1.60093784332 --9.59709453583,1.88381242752,1.57454955578 --9.61208438873,1.88581228256,1.54615628719 --9.60407733917,1.88381361961,1.51274251938 --9.61506748199,1.88481366634,1.4833445549 --9.64105701447,1.88881254196,1.45594584942 --9.63704872131,1.88681352139,1.42353701591 --9.6410446167,1.88781344891,1.40833461285 --9.65603542328,1.88981318474,1.37994456291 --9.65502643585,1.88781368732,1.34753000736 --9.68301677704,1.89281237125,1.32114577293 --9.6780090332,1.89081311226,1.28873765469 --9.68200111389,1.89081323147,1.25732791424 --9.69999217987,1.89381241798,1.22893619537 --9.70798778534,1.89481198788,1.21372926235 --9.71697902679,1.89581167698,1.18332612514 --9.72497081757,1.89681136608,1.15292477608 --9.7249622345,1.89581167698,1.12152159214 --9.73295497894,1.89681136608,1.09112036228 --9.75194644928,1.89981007576,1.06273198128 --9.75793838501,1.90080964565,1.03132140636 --9.76993370056,1.90280890465,1.01712501049 --9.76992607117,1.90180897713,0.985722243786 --9.79091835022,1.90480732918,0.956321954727 --9.80990982056,1.90880572796,0.926924824715 --9.81090354919,1.90780568123,0.895521879196 --9.81289577484,1.90780544281,0.864117503166 --9.82988834381,1.91080379486,0.834725022316 --9.83288478851,1.91080343723,0.818514823914 --9.82887649536,1.9088037014,0.787116408348 --9.84286975861,1.91180229187,0.75671505928 --9.84586238861,1.91180181503,0.725310504436 --9.85285568237,1.9128010273,0.69390296936 --9.85184955597,1.91180074215,0.662501513958 --9.86484527588,1.9137994051,0.647297978401 --9.84783840179,1.90980064869,0.614893972874 --9.86783123016,1.91379833221,0.584491789341 --9.86282444,1.91179847717,0.553092420101 --9.87081718445,1.91279733181,0.521685540676 --9.88081073761,1.91479587555,0.491291105747 --9.88280391693,1.91479504108,0.45887491107 --9.88879871368,1.91579389572,0.428483068943 --9.8817949295,1.9137942791,0.412278115749 --9.88578891754,1.91479337215,0.380873918533 --9.90078258514,1.91679120064,0.349467068911 --9.91477680206,1.91978907585,0.319074183702 --9.89676952362,1.91579020023,0.286663204432 --9.89976406097,1.91578912735,0.255260139704 --9.89875793457,1.91578841209,0.222844481468 --9.91975498199,1.9197858572,0.208660453558 --9.94574928284,1.92478203773,0.177256941795 --9.96074295044,1.92777955532,0.146868541837 --9.96773719788,1.92877781391,0.115468300879 --9.95273208618,1.92577850819,0.0830540508032 --9.9757270813,1.92977488041,0.0516556613147 --9.97172451019,1.9297747612,0.0354484133422 --9.97471809387,1.92977333069,0.0040487581864 --9.97871303558,1.9307718277,-0.0273507144302 --9.97370815277,1.92977118492,-0.059765022248 --9.98770236969,1.93176829815,-0.0911610499024 --9.98969745636,1.93276691437,-0.122560374439 --9.98469161987,1.93176615238,-0.154974937439 --9.99269008636,1.93276453018,-0.171178027987 --9.99068450928,1.9327634573,-0.202578678727 --9.98267936707,1.93076312542,-0.233982160687 --9.98567485809,1.9317612648,-0.266393691301 --9.97966957092,1.93076062202,-0.297797054052 --9.96566390991,1.92776095867,-0.329205602407 --9.99066066742,1.93275618553,-0.361603051424 --10.0066585541,1.9357534647,-0.377798557281 --10.0256547928,1.93974924088,-0.410196989775 --10.0166501999,1.93874883652,-0.44160208106 --10.0026445389,1.93574905396,-0.473011523485 --10.026640892,1.94074416161,-0.505403399467 --10.0176362991,1.93974351883,-0.537822246552 --10.0346326828,1.94273948669,-0.570217609406 --10.014629364,1.93874120712,-0.585428595543 --10.0246257782,1.94173800945,-0.617830097675 --10.0236225128,1.94173634052,-0.649228870869 --10.0106172562,1.93873620033,-0.680640041828 --10.0306148529,1.9437315464,-0.714042007923 --10.0186109543,1.94173109531,-0.745452880859 --10.0216064453,1.94172859192,-0.777859389782 --10.0186052322,1.94172811508,-0.793055295944 --10.0186014175,1.94172596931,-0.825465321541 --10.0315980911,1.94572198391,-0.857858896255 --10.0575962067,1.95071589947,-0.892259120941 --10.0825948715,1.95670986176,-0.925646007061 --10.0705909729,1.95470941067,-0.957056879997 --10.0775880814,1.95670592785,-0.990466654301 --10.0705862045,1.95570588112,-1.00566756725 --10.0705823898,1.95570337772,-1.03807425499 --10.0755796432,1.95770013332,-1.07047331333 --10.0685768127,1.95669865608,-1.10289061069 --10.0675735474,1.95669639111,-1.1342856884 --10.0785713196,1.95969200134,-1.16768622398 --10.0635671616,1.95769178867,-1.19910466671 --10.0625658035,1.95769059658,-1.21530926228 --10.07056427,1.95968663692,-1.24770069122 --10.0675611496,1.95968437195,-1.28011131287 --10.0615577698,1.95968258381,-1.31252741814 --10.0705566406,1.96167826653,-1.34592795372 --10.0745544434,1.96367490292,-1.37832474709 --10.074552536,1.96367192268,-1.41072833538 --10.0785512924,1.96566975117,-1.42793512344 --10.0785493851,1.96566677094,-1.46033811569 --10.0725469589,1.96566486359,-1.491740942 --10.0785455704,1.96766078472,-1.52514386177 --10.0795440674,1.96865737438,-1.5585565567 --10.07954216,1.96965420246,-1.59095859528 --10.0895423889,1.97265088558,-1.60815012455 --10.0885400772,1.97264778614,-1.6415656805 --10.0875377655,1.97364473343,-1.67396879196 --10.0675354004,1.97064507008,-1.70337808132 --10.0745344162,1.97264039516,-1.73778736591 --10.0485305786,1.96864175797,-1.76620018482 --10.0645303726,1.97263538837,-1.80159938335 --10.0855321884,1.97762978077,-1.82078528404 --10.0885314941,1.9796257019,-1.85418915749 --10.0795297623,1.97862386703,-1.88559770584 --10.0875291824,1.98161876202,-1.92000031471 --10.0915298462,1.98361420631,-1.95441234112 --10.1015300751,1.98660862446,-1.98880755901 --10.1035299301,1.98860442638,-2.02221083641 --10.0935277939,1.98660445213,-2.03742313385 --10.099527359,1.98859941959,-2.07182693481 --10.097527504,1.98959589005,-2.1042277813 --10.0895261765,1.98959350586,-2.13563299179 --10.0915260315,1.99058914185,-2.17004609108 --10.0945262909,1.99258446693,-2.20344376564 --10.0905256271,1.99358129501,-2.23584914207 --10.0815248489,1.99258100986,-2.25106024742 --10.0975265503,1.9965736866,-2.28745436668 --10.0975265503,1.99856936932,-2.32085895538 --10.0695228577,1.9935708046,-2.3492872715 --10.1105298996,2.00355815887,-2.3906621933 --10.113530159,2.00555300713,-2.42506718636 --10.1085309982,2.00654959679,-2.45747280121 --10.112531662,2.00754642487,-2.47567868233 --10.1135320663,2.00954174995,-2.51008868217 --10.11353302,2.01153707504,-2.54348897934 --10.1005325317,2.00953531265,-2.57490706444 --10.1065340042,2.01252937317,-2.60929894447 --10.1025342941,2.01352548599,-2.64271140099 --10.0935344696,2.01352262497,-2.67411637306 --10.1005363464,2.01551866531,-2.69332146645 --10.1065378189,2.01851248741,-2.72872209549 --10.1045389175,2.0195081234,-2.76212596893 --10.1165428162,2.02350020409,-2.79952740669 --10.1335477829,2.02949142456,-2.83792161942 --10.1345500946,2.03148603439,-2.87333583832 --10.1325511932,2.03248143196,-2.90673613548 --10.1295518875,2.03247952461,-2.92293739319 --10.1455574036,2.03747010231,-2.96234178543 --10.1615619659,2.04346132278,-3.00073242188 --10.149561882,2.04245877266,-3.03214383125 --10.1445636749,2.04345440865,-3.06555247307 --10.1505680084,2.04644751549,-3.10195374489 --10.1545715332,2.04944086075,-3.13836193085 --10.1685752869,2.05343461037,-3.15955400467 --10.1805801392,2.0574259758,-3.19795203209 --10.1695814133,2.05742287636,-3.229357481 --10.171585083,2.05941653252,-3.26576924324 --10.1805896759,2.06340837479,-3.30316400528 --10.1895952225,2.06740021706,-3.34156894684 --10.1955986023,2.07039570808,-3.3607647419 --10.2196063995,2.07738351822,-3.40416359901 --10.2056074142,2.07638096809,-3.43557810783 --10.2086114883,2.07937383652,-3.47197985649 --10.2246189117,2.08536362648,-3.51237201691 --10.2016181946,2.08236312866,-3.54078936577 --10.1946210861,2.08335828781,-3.5752081871 --10.2046251297,2.08635258675,-3.5953938961 --10.2126312256,2.09034395218,-3.63480424881 --10.2036333084,2.09033966064,-3.66720724106 --10.2056388855,2.09333252907,-3.7046186924 --10.198641777,2.09432792664,-3.73802351952 --10.1766414642,2.09132695198,-3.76643776894 --10.1816482544,2.09531879425,-3.80484557152 --10.2136583328,2.10330653191,-3.83402919769 --10.1396446228,2.08931970596,-3.84447550774 --10.1686573029,2.09830498695,-3.89086270332 --10.1666622162,2.10029816628,-3.92727637291 --10.1806707382,2.10628724098,-3.96867156029 --10.1816778183,2.10927987099,-4.0060801506 --10.1806821823,2.11127305031,-4.0424861908 --10.1636838913,2.11027050018,-4.07290029526 --10.1826915741,2.1152613163,-4.09808826447 --10.1726951599,2.11625671387,-4.13150167465 --10.1586971283,2.11525321007,-4.16291189194 --10.1697072983,2.12124252319,-4.20431232452 --10.1627111435,2.12223696709,-4.23872041702 --10.1467132568,2.12123394012,-4.27013969421 --10.1427154541,2.12223100662,-4.28734636307 --10.1317195892,2.12222671509,-4.31975221634 --10.103717804,2.11922693253,-4.3461766243 --10.1127271652,2.12421655655,-4.38758182526 --10.0977296829,2.12321281433,-4.41899585724 --10.0727300644,2.12021279335,-4.44540643692 --10.0767383575,2.12420344353,-4.48481225967 --10.0687398911,2.1242017746,-4.50102758408 --10.0387372971,2.12020301819,-4.52544355392 --10.032743454,2.12219643593,-4.56085634232 --10.044754982,2.12818455696,-4.60324954987 --10.043762207,2.13017678261,-4.64065504074 --10.0237646103,2.12917423248,-4.67108440399 --10.0157690048,2.13016867638,-4.70448303223 --10.0047702789,2.1301677227,-4.71970367432 --10.0057783127,2.13315916061,-4.75709676743 --9.98578071594,2.13215661049,-4.78651571274 --9.97278404236,2.13215184212,-4.81994056702 --9.94478321075,2.12915229797,-4.84435129166 --9.94479179382,2.13214373589,-4.88275814056 --9.93179702759,2.13213896751,-4.91517162323 --9.9488067627,2.1381289959,-4.94337558746 --9.92880916595,2.13712668419,-4.97178506851 --9.9318189621,2.14111661911,-5.01219272614 --9.92382526398,2.14211010933,-5.04760837555 --9.90882873535,2.14210581779,-5.07902050018 --9.91183948517,2.14609575272,-5.11841440201 --9.90884780884,2.14908742905,-5.15683078766 --9.90785312653,2.15108299255,-5.17603635788 --9.9118642807,2.15507245064,-5.21643161774 --9.89986991882,2.15606713295,-5.24984502792 --9.88187408447,2.15606379509,-5.28026294708 --9.87488174438,2.15805625916,-5.31667804718 --9.87989425659,2.1630449295,-5.3590836525 --9.89690971375,2.17002892494,-5.40747880936 --9.98995018005,2.19299125671,-5.4756269455 --10.0599880219,2.21395635605,-5.55198717117 --10.0539979935,2.21594810486,-5.58939409256 --10.0670137405,2.22293281555,-5.637799263 --10.0790309906,2.22991776466,-5.6851978302 --10.0380277634,2.22392177582,-5.70463037491 --9.99802398682,2.21892571449,-5.72405862808 --9.99302768707,2.21992206573,-5.74226856232 --9.96702957153,2.21792078018,-5.76868438721 --9.94703388214,2.2169175148,-5.79910421371 --9.9140329361,2.21291899681,-5.82152414322 --9.88603401184,2.2109181881,-5.8479552269 --9.85103321075,2.20692038536,-5.86938047409 --9.82703495026,2.20491862297,-5.89679765701 --9.81003475189,2.20291948318,-5.90801334381 --9.78703784943,2.20191693306,-5.93643569946 --9.77204418182,2.20291161537,-5.96985721588 --9.74104499817,2.19991254807,-5.99227237701 --9.72405052185,2.19990777969,-6.0246963501 --9.69605255127,2.19790744781,-6.04911375046 --9.67505645752,2.19690442085,-6.07853507996 --9.65905570984,2.19490480423,-6.08974695206 --9.62505435944,2.1909070015,-6.11117506027 --9.5870513916,2.18691062927,-6.12960195541 --9.55004882812,2.18191385269,-6.14903354645 --9.53205299377,2.18190979958,-6.17944860458 --9.50805664062,2.18090772629,-6.20687389374 --9.49405670166,2.17990779877,-6.21908521652 --9.48206520081,2.18090081215,-6.2534995079 --9.43505764008,2.17490839958,-6.26593494415 --9.4140625,2.1739051342,-6.2953619957 --9.38206195831,2.17090678215,-6.31678628922 --9.34005641937,2.16491246223,-6.3312125206 --9.33106613159,2.16790437698,-6.36762714386 --9.31606674194,2.16690468788,-6.37984848022 --9.274061203,2.16091036797,-6.39427804947 --9.25006389618,2.15990877151,-6.42070007324 --9.22706794739,2.15890622139,-6.44812488556 --9.19506645203,2.15590834618,-6.46854639053 --9.1640663147,2.15290951729,-6.48997163773 --9.15907859802,2.15689945221,-6.52938556671 --9.12006664276,2.14891028404,-6.5236082077 --9.08906555176,2.14591145515,-6.54503583908 --9.08207798004,2.14990234375,-6.58345413208 --9.04907608032,2.14590454102,-6.60287857056 --9.01007270813,2.1419095993,-6.61830949783 --8.99207782745,2.14190506935,-6.64873170853 --8.95607471466,2.13790869713,-6.66616201401 --8.94607830048,2.1379070282,-6.68037080765 --8.92608261108,2.13790345192,-6.7087893486 --8.88207530975,2.13191080093,-6.72022533417 --8.86007881165,2.13190841675,-6.74664068222 --8.83508205414,2.12990736961,-6.77206945419 --8.79207515717,2.12491440773,-6.78350305557 --8.77007865906,2.12391161919,-6.81092977524 --8.75708007812,2.12391161919,-6.82213449478 --8.7200756073,2.11991596222,-6.83857345581 --8.7060842514,2.12090969086,-6.87098646164 --8.67608451843,2.11891078949,-6.8914103508 --8.64608383179,2.11591219902,-6.9118347168 --8.62809085846,2.11690759659,-6.94226026535 --8.60409450531,2.11590576172,-6.96768569946 --8.57708740234,2.11191248894,-6.96790027618 --8.54308509827,2.10891580582,-6.98533201218 --8.52809333801,2.10990977287,-7.01775312424 --8.50109481812,2.10890960693,-7.04017686844 --8.46308898926,2.10391521454,-7.05360555649 --8.43709087372,2.10291433334,-7.0770316124 --8.41209506989,2.10191321373,-7.10146045685 --8.38708877563,2.09791922569,-7.10267400742 --8.38210391998,2.10290789604,-7.14308834076 --8.33709430695,2.09691691399,-7.15153408051 --8.31409835815,2.0959148407,-7.17695617676 --8.27909374237,2.09291887283,-7.19238710403 --8.25609779358,2.09191727638,-7.21680116653 --8.23910522461,2.09291195869,-7.24722146988 --8.21109771729,2.08891940117,-7.24644804001 --8.1861000061,2.08791851997,-7.26987075806 --8.15810203552,2.08691906929,-7.29130172729 --8.13910865784,2.08691501617,-7.31972074509 --8.1131105423,2.08591461182,-7.34214448929 --8.07310295105,2.08092164993,-7.35257959366 --8.06111526489,2.0839138031,-7.3869934082 --8.03810977936,2.08091878891,-7.39021921158 --8.00510692596,2.07792210579,-7.40665149689 --7.98611354828,2.07891798019,-7.43507146835 --7.95511245728,2.0759203434,-7.45249605179 --7.92911481857,2.07591986656,-7.47492361069 --7.91712665558,2.07791209221,-7.50933599472 --7.89712333679,2.07591557503,-7.5145573616 --7.86712217331,2.07391762733,-7.53298473358 --7.8371219635,2.07191944122,-7.55141305923 --7.8111243248,2.07091903687,-7.57384204865 --7.78812932968,2.07091665268,-7.59927129745 --7.76813602448,2.07191300392,-7.62669181824 --7.74414014816,2.07191157341,-7.65011262894 --7.729139328,2.07091259956,-7.65932750702 --7.69613647461,2.06791615486,-7.67475986481 --7.66913795471,2.06691646576,-7.69518232346 --7.65414953232,2.06890940666,-7.72860956192 --7.62414836884,2.06691145897,-7.74603366852 --7.581138134,2.06192135811,-7.75147342682 --7.58516407013,2.06990289688,-7.80288219452 --7.57116413116,2.06890368462,-7.81208944321 --7.53215694427,2.06391096115,-7.82152843475 --7.50315713882,2.06291246414,-7.8399553299 --7.48716831207,2.06490588188,-7.87238121033 --7.44715881348,2.05991435051,-7.87880754471 --7.42016124725,2.05991435051,-7.90024280548 --7.40217018127,2.06090950966,-7.92966175079 --7.39117336273,2.06190776825,-7.94287729263 --7.35216569901,2.0569152832,-7.95131492615 --7.32917118073,2.05791354179,-7.97573852539 --7.31318187714,2.0599064827,-8.00816345215 --7.28818511963,2.05990576744,-8.02958011627 --7.26118707657,2.05890631676,-8.05000782013 --7.22618293762,2.05591154099,-8.06244659424 --7.21818828583,2.05690836906,-8.07765007019 --7.19519329071,2.05690598488,-8.10207271576 --7.16219043732,2.05491018295,-8.11651039124 --7.13919639587,2.05490803719,-8.14093494415 --7.10919570923,2.05391025543,-8.15836906433 --7.08219766617,2.05291056633,-8.17779064178 --7.06621026993,2.05590319633,-8.21122074127 --7.04620504379,2.05290794373,-8.21343421936 --7.01820611954,2.05190896988,-8.23286628723 --6.98320150375,2.04891467094,-8.24430274963 --6.97121715546,2.05290484428,-8.28071689606 --6.93721294403,2.04990983009,-8.29315280914 --6.91421937943,2.05090737343,-8.31858539581 --6.89723110199,2.05390119553,-8.34899806976 --6.86621522903,2.04791331291,-8.33922767639 --6.84622478485,2.04990839958,-8.36765480042 --6.82923603058,2.05190229416,-8.39806747437 --6.79823541641,2.04990506172,-8.41450786591 --6.76423072815,2.04791045189,-8.42594051361 --6.73222827911,2.04591464996,-8.43936920166 --6.70623159409,2.04591393471,-8.46080112457 --6.70524549484,2.0489051342,-8.4860086441 --6.67324256897,2.04690909386,-8.49943828583 --6.6512503624,2.04790568352,-8.52586841583 --6.62024879456,2.04690909386,-8.54029655457 --6.60426235199,2.04990124702,-8.57371807098 --6.57225990295,2.0479054451,-8.58714962006 --6.53625392914,2.04491209984,-8.59659194946 --6.52725982666,2.04590892792,-8.61180210114 --6.50026273727,2.04590940475,-8.63122940063 --6.47126293182,2.04491138458,-8.64866256714 --6.45527744293,2.04790329933,-8.68208122253 --6.42027139664,2.04490971565,-8.69151687622 --6.39027166367,2.04391217232,-8.70795345306 --6.38828516006,2.04790377617,-8.73215579987 --6.35528182983,2.04590845108,-8.74459457397 --6.32928562164,2.04590797424,-8.76501846313 --6.30328989029,2.04590749741,-8.78645133972 --6.27028608322,2.04391241074,-8.79788398743 --6.2422876358,2.04291367531,-8.81631565094 --6.21629238129,2.04391288757,-8.83774852753 --6.19129753113,2.0439119339,-8.8591709137 --6.17629718781,2.04391312599,-8.86739063263 --6.15030193329,2.04391241074,-8.88882350922 --6.1142950058,2.04092025757,-8.89626216888 --6.09530735016,2.04391360283,-8.92668533325 --6.07231473923,2.04491114616,-8.95110702515 --6.03630685806,2.04091906548,-8.95754051208 --6.0273141861,2.04291534424,-8.97375297546 --6.00332117081,2.04391264915,-8.99818515778 --5.97131872177,2.04291725159,-9.01062011719 --5.94332027435,2.04191875458,-9.0280456543 --5.92233228683,2.04491329193,-9.0574798584 --5.8883266449,2.04191946983,-9.06691646576 --5.86032915115,2.04192042351,-9.0853509903 --5.84933423996,2.04291844368,-9.0985622406 --5.81833267212,2.04192233086,-9.11199474335 --5.79133701324,2.04192209244,-9.13243103027 --5.77034854889,2.04491710663,-9.16085624695 --5.73534154892,2.04192447662,-9.16829299927 --5.71635532379,2.04491758347,-9.19971561432 --5.68635511398,2.04392051697,-9.21414470673 --5.67035388947,2.04392266273,-9.22036457062 --5.63434648514,2.0409309864,-9.2268075943 --5.62136936188,2.04591798782,-9.26822757721 --5.58135652542,2.04192996025,-9.26867675781 --5.5613694191,2.04492402077,-9.29809474945 --5.53837823868,2.04692029953,-9.32351779938 --5.50437402725,2.04492640495,-9.33396720886 --5.48737096786,2.04393005371,-9.33717918396 --5.46337938309,2.04492735863,-9.3616065979 --5.43237876892,2.04393053055,-9.37604904175 --5.41139173508,2.04692482948,-9.40547466278 --5.3823928833,2.04692721367,-9.42090129852 --5.34438180923,2.04293775558,-9.42334747314 --5.31638526917,2.04393839836,-9.44178295135 --5.30038309097,2.04294109344,-9.44699764252 --5.27338838577,2.04394078255,-9.46743392944 --5.24338769913,2.0429444313,-9.48085975647 --5.21639251709,2.04394388199,-9.5012960434 --5.18539190292,2.04294776917,-9.51473426819 --5.15038299561,2.03995656967,-9.51916313171 --5.13638544083,2.03995656967,-9.52938747406 --5.11339759827,2.0429520607,-9.55681991577 --5.07838916779,2.03996038437,-9.56225776672 --5.05339765549,2.04195833206,-9.58568763733 --5.01939201355,2.03996491432,-9.5941324234 --4.99440002441,2.04096341133,-9.6165561676 --4.95939207077,2.03897166252,-9.6219959259 --4.9313955307,2.03897237778,-9.64043140411 --4.91539382935,2.03897547722,-9.64464378357 --4.89541101456,2.04296731949,-9.67807292938 --4.85439300537,2.03798246384,-9.67252063751 --4.83340835571,2.04097557068,-9.70394802094 --4.79739952087,2.03898501396,-9.70739173889 --4.77140617371,2.03998398781,-9.72881984711 --4.75039577484,2.03699231148,-9.72404098511 --4.72139787674,2.03699421883,-9.7404756546 --4.69540548325,2.03899288177,-9.7629108429 --4.66941356659,2.0409913063,-9.78534412384 --4.63440513611,2.03800010681,-9.78978347778 --4.60440635681,2.03800272942,-9.80522632599 --4.57440567017,2.03800678253,-9.81765174866 --4.5624127388,2.03900384903,-9.83287811279 --4.53040885925,2.03800964355,-9.84231090546 --4.49940776825,2.03801393509,-9.85474967957 --4.46940755844,2.03701782227,-9.86717510223 --4.4354019165,2.03602528572,-9.87462425232 --4.40740585327,2.0370259285,-9.89305782318 --4.37640380859,2.03603100777,-9.90348720551 --4.36140537262,2.03603172302,-9.91271591187 --4.33541345596,2.03803014755,-9.93514728546 --4.30341053009,2.03703594208,-9.94458293915 --4.2744140625,2.03803730011,-9.96202373505 --4.24641799927,2.03903841972,-9.97945213318 --4.21541595459,2.03804326057,-9.99088668823 --4.18842458725,2.0400416851,-10.0133275986 --4.17643117905,2.04203915596,-10.0275449753 --4.14442873001,2.04104471207,-10.0379867554 --4.11543035507,2.04104733467,-10.0524110794 --4.08543205261,2.0420498848,-10.0678529739 --4.05743741989,2.04305052757,-10.0862846375 --4.03144931793,2.04604673386,-10.1127309799 --4.01243925095,2.04405498505,-10.1079406738 --3.97943615913,2.04306125641,-10.117389679 --3.95545077324,2.04605555534,-10.1468238831 --3.92444992065,2.04606032372,-10.1582574844 --3.89445114136,2.04606318474,-10.1726942062 --3.86645746231,2.0480632782,-10.1921291351 --3.83445620537,2.04806852341,-10.2035751343 --3.81544685364,2.04607605934,-10.1997928619 --3.78444647789,2.04608035088,-10.2122325897 --3.7564535141,2.04708003998,-10.232670784 --3.72645449638,2.04808354378,-10.2461023331 --3.69846057892,2.0490834713,-10.2655353546 --3.66044473648,2.04609799385,-10.2609863281 --3.62944436073,2.04610204697,-10.2734270096 --3.61745285988,2.04809904099,-10.2886419296 --3.58544993401,2.04710483551,-10.298081398 --3.56146669388,2.05109858513,-10.3285093307 --3.52445149422,2.04811239243,-10.3249559402 --3.5024766922,2.0541009903,-10.3643960953 --3.47247958183,2.05510354042,-10.3798351288 --3.44047522545,2.05411052704,-10.3872652054 --3.4284863472,2.05710554123,-10.4054889679 --3.39648342133,2.05611157417,-10.4149274826 --3.36147427559,2.05412197113,-10.4173765182 --3.33749318123,2.05911445618,-10.4498062134 --3.31451511383,2.06410527229,-10.4852333069 --3.27248620987,2.05812764168,-10.4666872025 --3.24248862267,2.05913043022,-10.4811201096 --3.22648787498,2.05913329124,-10.4863414764 --3.19147825241,2.05714344978,-10.4887914658 --3.16649699211,2.06213665009,-10.5202255249 --3.12747359276,2.05715537071,-10.5076704025 --3.0944674015,2.05616378784,-10.5131082535 --3.05945801735,2.05417442322,-10.5155601501 --3.02845597267,2.05417990685,-10.5249872208 --3.01045012474,2.05318570137,-10.5252170563 --2.98246049881,2.05618405342,-10.5476531982 --2.94845271111,2.0541934967,-10.5521011353 --2.91645073891,2.05419945717,-10.5615415573 --2.88444662094,2.05420660973,-10.5689744949 --2.85746073723,2.05820250511,-10.595410347 --2.8424654007,2.0592019558,-10.6066398621 --2.81246829033,2.06020498276,-10.6210718155 --2.78247451782,2.06220602989,-10.6395149231 --2.74144148827,2.05523061752,-10.6169643402 --2.70743346214,2.05424046516,-10.6204109192 --2.67543053627,2.05424714088,-10.6288490295 --2.63941383362,2.05126190186,-10.6232938766 --2.61939883232,2.04827332497,-10.6135196686 --2.58338117599,2.04528880119,-10.6069631577 --2.54736185074,2.04130530357,-10.5984020233 --2.51435565948,2.04031348228,-10.6038455963 --2.48335576057,2.04131865501,-10.6152830124 --2.4523601532,2.04332089424,-10.631734848 --2.42035460472,2.04232907295,-10.6371660233 --2.40435647964,2.04333043098,-10.64539814 --2.37134790421,2.04234051704,-10.6478347778 --2.33633303642,2.03935408592,-10.64427948 --2.30633878708,2.04135584831,-10.6617202759 --2.27031850815,2.03837275505,-10.6521625519 --2.2363088131,2.03738355637,-10.6536121368 --2.20530867577,2.03738856316,-10.6650485992 --2.18629574776,2.03539919853,-10.6572771072 --2.15228366852,2.033411026,-10.6567201614 --2.12228870392,2.03541326523,-10.673157692 --2.09028697014,2.03641939163,-10.6826028824 --2.05627512932,2.03443145752,-10.6820487976 --2.02527832985,2.03643488884,-10.6964931488 --1.98925292492,2.03145480156,-10.681930542 --1.97526609898,2.03544998169,-10.7011632919 --1.9412497282,2.03246450424,-10.6955976486 --1.90522813797,2.02948236465,-10.6850481033 --1.87222123146,2.02849173546,-10.6894960403 --1.84323072433,2.03149151802,-10.7099266052 --1.80720794201,2.02750992775,-10.6983776093 --1.77520620823,2.02851629257,-10.707824707 --1.76021182537,2.03051567078,-10.7190485001 --1.72619342804,2.02753162384,-10.7114830017 --1.69519591331,2.02953577042,-10.7249250412 --1.66319596767,2.03054094315,-10.7363739014 --1.62716758251,2.02556276321,-10.7188167572 --1.59617006779,2.02756667137,-10.732257843 --1.58117461205,2.02856683731,-10.7424783707 --1.54716479778,2.02757811546,-10.7439346313 --1.51515746117,2.02758765221,-10.7473678589 --1.48315596581,2.02859425545,-10.756814003 --1.44914221764,2.02660751343,-10.7542629242 --1.41613566875,2.02661705017,-10.7587127686 --1.38513731956,2.02862167358,-10.771150589 --1.35011577606,2.025639534,-10.7606010437 --1.33511865139,2.02664065361,-10.7688159943 --1.3031219244,2.02864456177,-10.7832689285 --1.26708638668,2.02267026901,-10.7587118149 --1.23508024216,2.02267956734,-10.7631492615 --1.2040886879,2.02568030357,-10.7825965881 --1.17007112503,2.02369594574,-10.7760438919 --1.1520537138,2.02070879936,-10.7642679214 --1.12004840374,2.02071738243,-10.7697076797 --1.08603179455,2.01873278618,-10.7641592026 --1.05201518536,2.01674818993,-10.7586097717 --1.02001368999,2.01775455475,-10.7680559158 --0.98699259758,2.01577234268,-10.7574892044 --0.952973723412,2.01278877258,-10.7499389648 --0.936969637871,2.01279401779,-10.7511587143 --0.903960168362,2.01280522346,-10.7526082993 --0.867917120457,2.00583553314,-10.7210597992 --0.835914731026,2.00684261322,-10.7295064926 --0.799861311913,1.99687850475,-10.6879501343 --0.766841769218,1.99489533901,-10.6793928146 --0.733824133873,1.99291110039,-10.6728382111 --0.716805577278,1.98992431164,-10.6600589752 --0.68277567625,1.98594713211,-10.6415090561 --0.649756908417,1.98396360874,-10.6339559555 --0.615720570087,1.97798967361,-10.6094036102 --0.583704173565,1.97700488567,-10.6038417816 --0.550683140755,1.97402250767,-10.5942907333 --0.516630470753,1.96505749226,-10.5537309647 --0.500618219376,1.96406745911,-10.5469484329 --0.468622624874,1.96607100964,-10.5624065399 --0.435575336218,1.95910322666,-10.5268421173 --0.40255010128,1.95612323284,-10.5132951736 --0.370540440083,1.95613467693,-10.5147438049 --0.33850723505,1.95115888119,-10.493180275 --0.307513147593,1.95416176319,-10.5096244812 --0.289459943771,1.94419407845,-10.4638538361 --0.25741648674,1.93822395802,-10.4322910309 --0.194391980767,1.93724954128,-10.4301805496 --0.162342846394,1.92928242683,-10.3936214447 --0.130330950022,1.92929518223,-10.393075943 --0.0993129760027,1.92731106281,-10.3865146637 --0.0832909718156,1.92432618141,-10.3707389832 --0.0512518212199,1.91835379601,-10.3441896439 --0.0202577337623,1.92135667801,-10.3606357574 --0.0107910837978,1.90560722351,-9.49391365051 -0.0201091617346,1.88354420662,-9.38831233978 -0.0522628612816,1.91161811352,-9.52568435669 -0.0832382440567,1.90459573269,-9.49207401276 -0.0982291400433,1.90258622169,-9.47826290131 -0.129231542349,1.90057861805,-9.47064876556 -0.160232022405,1.89856982231,-9.46103572845 -0.191237688065,1.89756381512,-9.45642280579 -0.222259968519,1.90056681633,-9.46780109406 -0.252241641283,1.89454829693,-9.44018650055 -0.267228364944,1.89053678513,-9.42238140106 -0.298236310482,1.89053201675,-9.41976928711 -0.329240173101,1.88952517509,-9.41315937042 -0.360241860151,1.88751709461,-9.40455055237 -0.391257852316,1.88851690292,-9.40993404388 -0.421249389648,1.8855035305,-9.39132022858 -0.451248884201,1.88349461555,-9.38070392609 -0.467253565788,1.883492589,-9.37990379333 -0.496240615845,1.87847721577,-9.35728549957 -0.527251839638,1.87947428226,-9.35767364502 -0.557247459888,1.87646341324,-9.34306335449 -0.587246179581,1.87445402145,-9.33145046234 -0.617250978947,1.87344813347,-9.32583332062 -0.646236419678,1.86843192577,-9.30122375488 -0.661238908768,1.86842894554,-9.29841518402 -0.693256318569,1.8694293499,-9.30481243134 -0.722254931927,1.86742031574,-9.29319000244 -0.753069579601,1.82731044292,-9.09482002258 -0.782071709633,1.82630324364,-9.08620452881 -0.811072766781,1.82429563999,-9.07659053802 -0.825061440468,1.82128536701,-9.05979347229 -0.854060649872,1.81927680969,-9.04818439484 -0.885090172291,1.82428395748,-9.06655883789 -0.912067115307,1.81726384163,-9.03295612335 -0.941070437431,1.8162573576,-9.02534389496 -0.971078932285,1.8162535429,-9.0227355957 -1.00008320808,1.81524777412,-9.01612186432 -1.01408088207,1.81424248219,-9.00831508636 -1.04307770729,1.81223237514,-8.99371623993 -1.07208192348,1.81122660637,-8.98710250854 -1.10008025169,1.80921781063,-8.97448921204 -1.13009560108,1.81021785736,-8.97887039185 -1.15708208084,1.80620276928,-8.95426654816 -1.18507957458,1.8041934967,-8.94065570831 -1.20108783245,1.80519342422,-8.94285964966 -1.22908806801,1.80318582058,-8.93224525452 -1.25809371471,1.80318069458,-8.92663288116 -1.28508245945,1.79916703701,-8.90403079987 -1.3120777607,1.79615700245,-8.88841629028 -1.34208869934,1.79715466499,-8.88780879974 -1.35508346558,1.79514801502,-8.87700176239 -1.38207697868,1.792137146,-8.85939311981 -1.41108381748,1.79213273525,-8.85478305817 -1.43807756901,1.78912186623,-8.83717536926 -1.46809220314,1.79112148285,-8.84055995941 -1.49609029293,1.78911268711,-8.82695865631 -1.52308428288,1.78610193729,-8.8093547821 -1.53708899021,1.78710067272,-8.80853939056 -1.56508708,1.78509175777,-8.79493999481 -1.59308993816,1.78408575058,-8.78632831573 -1.6220985651,1.78408253193,-8.78371524811 -1.64909374714,1.78207230568,-8.76711177826 -1.67609262466,1.78006434441,-8.75449943542 -1.70208573341,1.77705335617,-8.73589134216 -1.71608686447,1.77705013752,-8.73108768463 -1.7440880537,1.77604317665,-8.72048568726 -1.77510583401,1.7780444622,-8.72687339783 -1.85308754444,1.77001321316,-8.67305374146 -1.88209581375,1.77100980282,-8.66944599152 -1.8981076479,1.77301192284,-8.6756362915 -1.91606664658,1.76198458672,-8.62203884125 -1.94909155369,1.76598930359,-8.63543128967 -1.97810339928,1.76798784733,-8.63581085205 -2.00108361244,1.76197075844,-8.60321903229 -2.03109836578,1.7639708519,-8.60660266876 -2.05608916283,1.7609590292,-8.5850019455 -2.06707954407,1.75795078278,-8.56920051575 -2.0970928669,1.75994992256,-8.57059001923 -2.12108325958,1.75593829155,-8.54898071289 -2.14808297157,1.75493085384,-8.53637981415 -2.17508530617,1.75392496586,-8.52676868439 -2.20007753372,1.75191390514,-8.5061712265 -2.21910238266,1.75592267513,-8.52634906769 -2.24208784103,1.75190830231,-8.49875259399 -2.2710981369,1.75290632248,-8.49713897705 -2.29207658768,1.74688887596,-8.4625453949 -2.32610487938,1.75189554691,-8.47992610931 -2.34507632256,1.74487471581,-8.43733978271 -2.34699177742,1.72482740879,-8.33675956726 -2.39009690285,1.74787390232,-8.43992137909 -2.41208148003,1.74285960197,-8.41132450104 -2.44008874893,1.74385619164,-8.40671062469 -2.46709132195,1.74285066128,-8.39710426331 -2.49509811401,1.7438467741,-8.39149570465 -2.52009487152,1.74183857441,-8.37588787079 -2.54609489441,1.74083185196,-8.36328220367 -2.55508136749,1.73682188988,-8.34248924255 -2.58308815956,1.73781824112,-8.33687973022 -2.61310148239,1.73981773853,-8.33826828003 -2.6370947361,1.73680782318,-8.3186674118 -2.6610891819,1.7347984314,-8.30006504059 -2.70012927055,1.74281036854,-8.32944488525 -2.71810483932,1.73579227924,-8.29085350037 -2.73411536217,1.73779404163,-8.2960395813 -2.75911140442,1.7357852459,-8.27844524384 -2.7911298275,1.73978686333,-8.28483390808 -2.80810451508,1.73276865482,-8.24524021149 -2.83611369133,1.73376643658,-8.24261760712 -2.86010861397,1.73175740242,-8.2240190506 -2.88610839844,1.73075044155,-8.21042346954 -2.90312170982,1.73375356197,-8.21860599518 -2.93012595177,1.73374891281,-8.2099981308 -2.95913314819,1.73374545574,-8.20440387726 -2.98714065552,1.73474264145,-8.19979000092 -3.00913047791,1.73173117638,-8.17519760132 -3.04716515541,1.7387406826,-8.19956684113 -3.07918071747,1.74174118042,-8.20296287537 -3.07313299179,1.72971630096,-8.14518070221 -3.09913516045,1.72971093655,-8.13457107544 -3.12814331055,1.73070800304,-8.12997150421 -3.15214204788,1.72970116138,-8.11535739899 -3.18215227127,1.73169922829,-8.1127576828 -3.21116185188,1.73269736767,-8.11014556885 -3.22115540504,1.73069107533,-8.09634780884 -3.25216913223,1.73369085789,-8.09773921967 -3.2871928215,1.73769521713,-8.11012172699 -3.30818247795,1.7346842289,-8.08552455902 -3.33418512344,1.7346791029,-8.07491493225 -3.36018681526,1.73467361927,-8.06331157684 -3.39621162415,1.73967826366,-8.07669639587 -3.40720796585,1.73867344856,-8.06589698792 -3.43320894241,1.73766756058,-8.0532989502 -3.46021342278,1.73866331577,-8.04469108582 -3.48621511459,1.73765790462,-8.03308773041 -3.51221776009,1.73765289783,-8.02247810364 -3.53220701218,1.7346419096,-7.99688100815 -3.56422114372,1.73764181137,-7.99827718735 -3.5822327137,1.73964381218,-8.00446891785 -3.60222196579,1.73663294315,-7.97887277603 -3.6302292347,1.73763012886,-7.97325849533 -3.66023945808,1.73962831497,-7.97065162659 -3.68624091148,1.73962271214,-7.95805454254 -3.71124172211,1.7396171093,-7.94544410706 -3.74025011063,1.74061465263,-7.9408364296 -3.75124692917,1.73961007595,-7.93003988266 -3.77724909782,1.73960494995,-7.91843700409 -3.80124759674,1.7385982275,-7.9028339386 -3.82424354553,1.73759043217,-7.88423776627 -3.85625743866,1.73959040642,-7.88562822342 -3.88727021217,1.74259006977,-7.88601064682 -3.91126728058,1.74158263206,-7.86842012405 -3.9222650528,1.74057865143,-7.85862016678 -3.95027136803,1.74157547951,-7.85200929642 -3.97927880287,1.74357235432,-7.84541034698 -4.00027275085,1.74156403542,-7.82480335236 -4.0292801857,1.74256145954,-7.81919813156 -4.052277565,1.74155426025,-7.80159759521 -4.06427669525,1.7415510416,-7.79379653931 -4.08627128601,1.73954248428,-7.77221107483 -4.11227416992,1.73953807354,-7.76160240173 -4.15129995346,1.74554300308,-7.77598142624 -4.18030691147,1.7475399971,-7.76937961578 -4.1962928772,1.74352860451,-7.739777565 -4.22529935837,1.74452531338,-7.73218202591 -4.24731636047,1.74852955341,-7.74436473846 -4.28433704376,1.75353217125,-7.75275373459 -4.30232572556,1.75052165985,-7.72516298294 -4.33333730698,1.75352096558,-7.72454023361 -4.36034011841,1.7535161972,-7.71294641495 -4.38634300232,1.75351166725,-7.70134019852 -4.41935634613,1.75751137733,-7.70173120499 -4.43235778809,1.75750911236,-7.69592857361 -4.45936059952,1.7575044632,-7.68433332443 -4.48736619949,1.75950098038,-7.67572784424 -4.5143699646,1.75949668884,-7.66512441635 -4.54538011551,1.76249504089,-7.66151714325 -4.57338523865,1.76349163055,-7.65291023254 -4.59237718582,1.76148247719,-7.62831449509 -4.61539363861,1.76548659801,-7.64049482346 -4.64339828491,1.76648271084,-7.63089418411 -4.66639614105,1.76547622681,-7.6132941246 -4.68538808823,1.76346731186,-7.58870029449 -4.71940231323,1.76746737957,-7.59008646011 -4.74840831757,1.76846444607,-7.5824804306 -4.77240753174,1.76845836639,-7.56588506699 -4.79442119598,1.7724609375,-7.57407665253 -4.81341362,1.77045249939,-7.55047655106 -4.8354101181,1.76844549179,-7.53088140488 -4.86541748047,1.77044284344,-7.52427768707 -4.89342260361,1.77243924141,-7.51467323303 -4.9274353981,1.77543878555,-7.514067173 -4.95744276047,1.7774361372,-7.50746107101 -4.96043014526,1.77442836761,-7.48467350006 -4.98643302917,1.77442407608,-7.47306108475 -5.01343584061,1.77541971207,-7.46046733856 -5.04043912888,1.77641546726,-7.44886493683 -5.06443881989,1.77640998363,-7.4332613945 -5.09544706345,1.77840793133,-7.42765569687 -5.11045122147,1.7804068327,-7.42484664917 -5.1344499588,1.77940070629,-7.40725803375 -5.16746091843,1.78239965439,-7.40464830399 -5.18545341492,1.78039133549,-7.38004970551 -5.21245622635,1.78138697147,-7.36745357513 -5.24847126007,1.78638756275,-7.36983346939 -5.26646280289,1.78337872028,-7.34325218201 -5.27846288681,1.78337609768,-7.33544969559 -5.29745674133,1.78236865997,-7.31284666061 -5.34047985077,1.78837203979,-7.32422590256 -5.36648082733,1.78936672211,-7.30864048004 -5.38547468185,1.78735947609,-7.28603839874 -5.41247797012,1.78835558891,-7.27443122864 -5.44048213959,1.79035139084,-7.26184225082 -5.45548582077,1.79135048389,-7.25902938843 -5.48549175262,1.79334723949,-7.24943590164 -5.50849103928,1.79334187508,-7.23282623291 -5.54150104523,1.79634022713,-7.22822141647 -5.57751369476,1.800339818,-7.22761249542 -5.60251426697,1.80033481121,-7.2120141983 -5.61750411987,1.79832589626,-7.18342161179 -5.64552211761,1.80332970619,-7.19660520554 -5.6735253334,1.8043255806,-7.18401145935 -5.7025308609,1.80732250214,-7.17440128326 -5.72953414917,1.80831861496,-7.16179609299 -5.76154184341,1.81131613255,-7.15419816971 -5.78854465485,1.81231200695,-7.14159202576 -5.79754209518,1.81130850315,-7.12979030609 -5.83355379105,1.81530737877,-7.12718772888 -5.86055612564,1.81630325317,-7.11358880997 -5.89456653595,1.82030165195,-7.10898065567 -5.93057823181,1.82430064678,-7.10637331009 -5.95157384872,1.82329404354,-7.08478212357 -5.97557401657,1.82328903675,-7.06817674637 -5.99057722092,1.82528758049,-7.06337308884 -6.00656843185,1.82227945328,-7.03578519821 -6.02456188202,1.82127225399,-7.01119184494 -5.87638902664,1.76520824432,-6.78476428986 -5.87436437607,1.75719499588,-6.73719263077 -5.8853521347,1.75418627262,-6.70560789108 -5.90534973145,1.75318062305,-6.68501377106 -5.90934276581,1.75117611885,-6.66821622849 -5.92233371735,1.74816834927,-6.63962745667 -5.92831754684,1.74315822124,-6.60205364227 -5.93730449677,1.73914933205,-6.56847476959 -5.94829463959,1.73614156246,-6.53887891769 -5.95828294754,1.73213326931,-6.50729465485 -5.97327661514,1.73012638092,-6.48071336746 -5.9712638855,1.72612023354,-6.45692968369 -5.98826026917,1.72511446476,-6.43433141708 -6.00225257874,1.72210764885,-6.40675354004 -6.01424407959,1.72010028362,-6.37816619873 -6.02723693848,1.71709382534,-6.35156965256 -6.04823637009,1.7170894146,-6.33297586441 -6.05323123932,1.71608543396,-6.3171877861 -6.06322145462,1.71207821369,-6.28759479523 -6.08221960068,1.71207332611,-6.26700115204 -6.09221029282,1.70906591415,-6.23641967773 -6.11020708084,1.70806086063,-6.21482801437 -6.1242017746,1.70605492592,-6.1892375946 -6.1331911087,1.70204734802,-6.15766096115 -6.13618469238,1.70004343987,-6.14086771011 -6.1581864357,1.7010396719,-6.12327671051 -6.16317272186,1.69603157043,-6.08869409561 -6.17316484451,1.69402515888,-6.06009960175 -6.19116258621,1.69302010536,-6.03752374649 -6.20715904236,1.69101524353,-6.01492786407 -6.21314764023,1.68700766563,-5.98135042191 -6.22314739227,1.68700563908,-5.97155761719 -6.23013734818,1.68399870396,-5.93997049332 -6.25213909149,1.68499529362,-5.92337179184 -6.27213954926,1.68499159813,-5.90477514267 -6.28213167191,1.68198525906,-5.87520027161 -6.28611898422,1.67697787285,-5.84062194824 -6.30912256241,1.67897510529,-5.82601165771 -6.30311059952,1.67396962643,-5.80122804642 -6.31810712814,1.67296504974,-5.77763986588 -6.34311151505,1.67496240139,-5.76305007935 -6.34209632874,1.6689542532,-5.72447395325 -6.3510890007,1.66594862938,-5.69588565826 -6.36908817291,1.66594481468,-5.67529582977 -6.38008260727,1.66393959522,-5.64870643616 -6.38107633591,1.66093611717,-5.63091945648 -6.39707422256,1.66093194485,-5.60833454132 -6.39505958557,1.65492427349,-5.5697593689 -6.40405273438,1.65191876888,-5.54117774963 -6.42105197906,1.65191495419,-5.51959371567 -6.43204689026,1.64991021156,-5.4930100441 -6.43503665924,1.64590406418,-5.46042108536 -6.44703912735,1.64590299129,-5.45361709595 -6.45202970505,1.64289712906,-5.4210486412 -6.45802211761,1.63989186287,-5.391456604 -6.47302055359,1.63888800144,-5.36886930466 -6.47901248932,1.63588261604,-5.33829164505 -6.49401140213,1.63487899303,-5.31570577621 -6.49500608444,1.63287615776,-5.29891681671 -6.4969959259,1.62787020206,-5.26534128189 -6.51299571991,1.6278668642,-5.24375391006 -6.52899503708,1.62786352634,-5.22216749191 -6.53198623657,1.62385833263,-5.19058132172 -6.54098129272,1.62185394764,-5.16300392151 -6.55898284912,1.62185132504,-5.14440107346 -6.55597543716,1.61884796619,-5.12461709976 -6.56497097015,1.61684393883,-5.09803009033 -6.58497333527,1.61784136295,-5.0794467926 -6.58496379852,1.61283612251,-5.0458650589 -6.59495973587,1.61083221436,-5.0192899704 -6.61096000671,1.61082947254,-4.99869632721 -6.61095094681,1.60682439804,-4.9651184082 -6.61294746399,1.60482215881,-4.95032405853 -6.62794685364,1.60481929779,-4.9287352562 -6.63394117355,1.60181522369,-4.89916563034 -6.63893556595,1.59881126881,-4.87057638168 -6.662940979,1.60080969334,-4.85598182678 -6.66493368149,1.59680533409,-4.82440519333 -6.66693067551,1.5958032608,-4.80961322784 -6.68293094635,1.59580087662,-4.78902339935 -6.69092798233,1.59379756451,-4.76243925095 -6.69192028046,1.58979308605,-4.72987174988 -6.70692062378,1.58979082108,-4.70927476883 -6.71391630173,1.58678746223,-4.6816983223 -6.72391462326,1.58578455448,-4.6571097374 -6.72391080856,1.58378255367,-4.64131736755 -6.73991203308,1.58378040791,-4.62073040009 -6.75091075897,1.58277761936,-4.5961523056 -6.75990819931,1.58077478409,-4.57057094574 -6.77290821075,1.58077251911,-4.54897165298 -6.78190660477,1.57876980305,-4.52339172363 -6.78890323639,1.57676684856,-4.4968085289 -6.78489780426,1.57376468182,-4.47802591324 -6.79689741135,1.57376253605,-4.45543384552 -6.81690168381,1.57476103306,-4.43784332275 -6.82189750671,1.57175803185,-4.40927314758 -6.82689380646,1.56975519657,-4.38168954849 -6.83489179611,1.56775283813,-4.35610628128 -6.84489059448,1.56675052643,-4.3325138092 -6.85389232635,1.5677498579,-4.32272338867 -6.85888910294,1.56474721432,-4.29514408112 -6.85788297653,1.56174409389,-4.26357030869 -6.87388563156,1.56174266338,-4.24397516251 -6.87888240814,1.55974018574,-4.21639871597 -6.88588047028,1.55773806572,-4.19081258774 -6.88987731934,1.55573570728,-4.16323041916 -6.89687824249,1.55573499203,-4.15243864059 -6.90587711334,1.55373299122,-4.12785673141 -6.91687774658,1.55373132229,-4.10427713394 -6.91887378693,1.55072903633,-4.07569646835 -6.92087030411,1.54772686958,-4.04711675644 -6.94087505341,1.54972589016,-4.02952671051 -6.93286895752,1.54572427273,-4.00974369049 -6.9348654747,1.54272210598,-3.98116707802 -6.94586610794,1.54272079468,-3.9585776329 -6.95286560059,1.5407191515,-3.93299984932 -6.96986913681,1.54171812534,-3.91341519356 -6.96586370468,1.53771591187,-3.8818385601 -6.98386764526,1.53871500492,-3.8632478714 -6.97886323929,1.53571391106,-3.84546613693 -6.98686361313,1.53471255302,-3.82088518143 -7.00086593628,1.53471159935,-3.80029249191 -6.9998626709,1.53170979023,-3.77071619034 -7.01286458969,1.53170895576,-3.74913144112 -7.02886819839,1.53270816803,-3.72953987122 -7.02286243439,1.52870631218,-3.69697237015 -7.02586269379,1.52770578861,-3.68418359756 -7.03486299515,1.52670478821,-3.66059923172 -7.04186344147,1.52570366859,-3.63601517677 -7.04786300659,1.52370274067,-3.61043930054 -7.06286668777,1.52470219135,-3.59084129333 -7.05786180496,1.52070069313,-3.55927467346 -7.06786394119,1.52069997787,-3.53668546677 -7.06686258316,1.51869952679,-3.52189993858 -7.07386302948,1.5176987648,-3.49731945992 -7.0808634758,1.51669800282,-3.47273993492 -7.09586715698,1.51669764519,-3.45314335823 -7.09686565399,1.51469683647,-3.42556667328 -7.10486745834,1.5136963129,-3.40198087692 -7.11487007141,1.51469624043,-3.39219975471 -7.1138677597,1.51169550419,-3.36461162567 -7.11986875534,1.51069498062,-3.34002828598 -7.13487291336,1.51169478893,-3.31944656372 -7.12686872482,1.50669407845,-3.28787446022 -7.14187240601,1.50769388676,-3.2672932148 -7.15587615967,1.50869369507,-3.24670505524 -7.14587259293,1.50469338894,-3.22792625427 -7.1618771553,1.50669324398,-3.2083363533 -7.16587781906,1.50469303131,-3.18275856972 -7.1678776741,1.50269269943,-3.15716814995 -7.17888069153,1.50269269943,-3.13459157944 -7.18588256836,1.50169277191,-3.11100459099 -7.18888282776,1.49969267845,-3.08542299271 -7.19088363647,1.49969267845,-3.07263541222 -7.21589136124,1.50269281864,-3.05704116821 -7.20288705826,1.4976927042,-3.02348232269 -7.20988893509,1.49669289589,-2.99989748001 -7.22189235687,1.49669313431,-2.97831344604 -7.22289323807,1.49469339848,-2.95173859596 -7.2258939743,1.49369359016,-2.92714548111 -7.24489974976,1.49669373035,-2.92135548592 -7.2368979454,1.49269402027,-2.89177417755 -7.2509021759,1.49369430542,-2.87118697166 -7.2659072876,1.49469470978,-2.8506052494 -7.24990320206,1.48869526386,-2.81704258919 -7.26390790939,1.48969578743,-2.79645562172 -7.27891206741,1.49169588089,-2.78965401649 -7.26490879059,1.48669660091,-2.7570912838 -7.26390981674,1.48469722271,-2.73051214218 -7.2929186821,1.48869752884,-2.71591711044 -7.28791809082,1.48569834232,-2.68833136559 -7.28791904449,1.48369908333,-2.66175985336 -7.30292463303,1.48469984531,-2.64117836952 -7.29692363739,1.48270022869,-2.6253991127 -7.31092882156,1.48370087147,-2.60579609871 -7.3219332695,1.48370170593,-2.58322358131 -7.31093168259,1.47970283031,-2.55265855789 -7.32493686676,1.4807035923,-2.53207135201 -7.33894205093,1.4817044735,-2.51148319244 -7.32594013214,1.47770571709,-2.4809114933 -7.33594369888,1.47870612144,-2.4721095562 -7.31694078445,1.47270774841,-2.43855786324 -7.32294416428,1.47170889378,-2.4159617424 -7.29293870926,1.46371102333,-2.3784224987 -7.32094717026,1.46771156788,-2.36381173134 -7.31994962692,1.46571302414,-2.33724665642 -7.32495307922,1.46571433544,-2.31366348267 -7.36196327209,1.4727139473,-2.31384921074 -7.32195615768,1.46171677113,-2.27430319786 -7.35396575928,1.46771717072,-2.26069068909 -7.36397123337,1.46771848202,-2.23811626434 -7.34396886826,1.46172082424,-2.20556092262 -7.23594713211,1.43672633171,-2.14504933357 -7.29896259308,1.44972491264,-2.15322041512 -7.30696725845,1.44972646236,-2.13064050674 -7.27496337891,1.44072961807,-2.09508943558 -7.28596878052,1.4417309761,-2.07449221611 -7.26896858215,1.43673372269,-2.04393315315 -7.23396444321,1.42773723602,-2.00837826729 -7.26297426224,1.43273806572,-1.99278128147 -7.25697469711,1.43073940277,-1.97899067402 -7.25497770309,1.42874157429,-1.95342195034 -7.28398752213,1.43274247646,-1.93782198429 -7.24598360062,1.42374646664,-1.90128266811 -7.20998001099,1.41375052929,-1.86672353745 -7.24399089813,1.41975128651,-1.85212779045 -7.30800533295,1.4327493906,-1.8582983017 -7.22399330139,1.41375589371,-1.80977976322 -7.16798639297,1.40076124668,-1.77023351192 -7.18799448013,1.40376281738,-1.75164711475 -7.09798192978,1.38277029991,-1.70312798023 -7.15899848938,1.39476966858,-1.69551968575 -7.08398866653,1.37677657604,-1.65198707581 -7.15100383759,1.39077413082,-1.65815246105 -7.0999994278,1.37877988815,-1.62061738968 -7.04499483109,1.36578595638,-1.5830732584 -7.13201522827,1.38278377056,-1.58243262768 -7.06200790405,1.36679089069,-1.54090774059 -7.05801200867,1.36479413509,-1.51732158661 -7.0220117569,1.3567994833,-1.48477721214 -7.0170135498,1.35480129719,-1.4719928503 -7.02002000809,1.35480427742,-1.44941914082 -7.02402544022,1.35380733013,-1.42783153057 -6.98302459717,1.34381318092,-1.39528131485 -6.97702980042,1.34181702137,-1.37071537971 -6.94603061676,1.33382236958,-1.34115445614 -6.98704338074,1.34182310104,-1.32755434513 -6.93603849411,1.33082830906,-1.30479967594 -6.92004203796,1.32583284378,-1.27922487259 -6.89604473114,1.31983804703,-1.25166225433 -6.85104465485,1.3098449707,-1.21912610531 -6.87805509567,1.31484663486,-1.2025333643 -6.84205675125,1.30585300922,-1.17297828197 -6.84306001663,1.30585479736,-1.16218829155 -6.87607145309,1.31185591221,-1.14757478237 -6.84607362747,1.30486214161,-1.11902594566 -6.87908506393,1.31086337566,-1.10342824459 -6.84108734131,1.30187022686,-1.07387900352 -6.85209512711,1.30287325382,-1.05428981781 -6.86810445786,1.30587589741,-1.03569495678 -6.90511274338,1.31287491322,-1.03089439869 -6.85311317444,1.30088317394,-0.999352395535 -6.87612342834,1.304885149,-0.981756448746 -6.84112644196,1.29689204693,-0.95419293642 -6.89714050293,1.30789148808,-0.941587150097 -6.89514732361,1.30689561367,-0.919997870922 -6.90615606308,1.30889892578,-0.899422466755 -6.82515001297,1.2909078598,-0.875678002834 -6.76615095139,1.27891719341,-0.844146966934 -6.79316186905,1.28291928768,-0.826559841633 -6.87717866898,1.29991590977,-0.818909585476 -6.87718629837,1.29892003536,-0.797329008579 -6.85919189453,1.29492604733,-0.772766590118 -6.85419893265,1.29293096066,-0.7501963377 -6.80119800568,1.28193807602,-0.731449186802 -6.84921073914,1.29093801975,-0.716838121414 -6.92222595215,1.30593574047,-0.705213487148 -6.90723276138,1.30194139481,-0.681641757488 -6.86123609543,1.29195010662,-0.654091060162 -6.83324098587,1.28595733643,-0.629520952702 -6.75123786926,1.26796758175,-0.607799589634 -6.74524593353,1.26697266102,-0.586219072342 -6.7362537384,1.26397836208,-0.563654482365 -6.71726036072,1.25998485088,-0.541074573994 -6.80727624893,1.27798080444,-0.529453754425 -6.77528190613,1.27098858356,-0.504892110825 -6.72628688812,1.25999844074,-0.478349238634 -6.78229570389,1.27199494839,-0.474508315325 -6.77830410004,1.27000021935,-0.45293328166 -6.73430919647,1.26100945473,-0.427385002375 -6.72831726074,1.2590149641,-0.405811309814 -6.73032712936,1.25901997089,-0.384248048067 -6.75933790207,1.26502168179,-0.366636276245 -6.77234792709,1.26702547073,-0.34606346488 -6.77335214615,1.2670276165,-0.336260974407 -6.7143573761,1.25503909588,-0.309734255075 -6.74036836624,1.26004135609,-0.291135072708 -6.72037649155,1.25504863262,-0.268572688103 -6.76838779449,1.26504826546,-0.251948207617 -6.92640686035,1.29703617096,-0.24128049612 -6.83741092682,1.27905082703,-0.21474327147 -6.87541770935,1.286049366,-0.205943062901 -6.83542490005,1.27805888653,-0.182386502624 -6.92543840408,1.29605388641,-0.166745126247 -6.84844398499,1.28006756306,-0.141213193536 -6.79245042801,1.26807928085,-0.116679541767 -6.86746311188,1.2830760479,-0.0990588441491 -6.83446645737,1.27708232403,-0.0872825160623 -6.89847898483,1.28908014297,-0.0686698406935 -7.10449743271,1.33206152916,-0.0559574514627 -6.87049627304,1.28309392929,-0.0255201701075 -6.83650493622,1.27610313892,-0.00296635855921 -6.76251125336,1.26111733913,0.0205635074526 -6.57951498032,1.22314465046,0.0470176525414 -6.53851795197,1.21515226364,0.0577908568084 -6.66353273392,1.24014306068,0.0754397138953 -6.54253911972,1.21516299248,0.0979524329305 -6.51954889297,1.21117150784,0.118517003953 -6.5615606308,1.21917212009,0.138120025396 -6.73757600784,1.25515639782,0.156801253557 -6.85758924484,1.28014707565,0.176458418369 -6.93359565735,1.29514038563,0.18629977107 -6.95560646057,1.30014324188,0.207886725664 -6.95561647415,1.30014884472,0.229462847114 -6.81462287903,1.27117192745,0.249964371324 -6.87863492966,1.28416955471,0.271578490734 -6.90564537048,1.29017186165,0.29317137599 -6.72965288162,1.2542001009,0.312634050846 -6.62965679169,1.23321568966,0.321366131306 -6.60366678238,1.22822475433,0.340937644243 -6.61067771912,1.22922980785,0.361519098282 -7.55069828033,1.42211401463,0.403674930334 -6.65269994736,1.2382363081,0.403696894646 -6.60171079636,1.22824907303,0.423233509064 -6.64371585846,1.23724639416,0.434062719345 -6.60372686386,1.22925782204,0.453608363867 -6.64273786545,1.2372585535,0.475216120481 -6.80174875259,1.2702434063,0.501898169518 -6.84976053238,1.28024303913,0.525496482849 -6.85077047348,1.28024876118,0.54608809948 -6.7457818985,1.2592689991,0.562591552734 -6.65178823471,1.24028480053,0.568320572376 -6.53479957581,1.21630656719,0.581841170788 -6.69981002808,1.25029063225,0.612502157688 -7.67881345749,1.45116281509,0.692672491074 -7.66582298279,1.44917023182,0.715250134468 -6.42784690857,1.19534647465,0.656080126762 -6.43885231018,1.19734811783,0.666874468327 -6.58486175537,1.22733438015,0.697538197041 -6.633872509,1.23833358288,0.721156895161 -6.59088468552,1.22934615612,0.738702714443 -6.61889600754,1.23534846306,0.761301398277 -6.70090579987,1.25334322453,0.788927137852 -6.64791822433,1.2423568964,0.804486572742 -6.53792619705,1.22037577629,0.805205643177 -6.50493907928,1.21338701248,0.822758853436 -6.47695159912,1.20839750767,0.840321004391 -6.54896211624,1.22339379787,0.867936313152 -6.55297374725,1.22539961338,0.88852250576 -6.47298717499,1.20941758156,0.900063455105 -6.49799871445,1.21442043781,0.922663509846 -6.58300209045,1.23241150379,0.942496478558 -6.67401123047,1.25140464306,0.973133683205 -6.39903259277,1.19545161724,0.962538599968 -6.33004713058,1.18146848679,0.974081099033 -6.5780506134,1.23343861103,1.02479755878 -6.61506128311,1.24143958092,1.04941165447 -6.55307006836,1.22945225239,1.05215907097 -6.54708194733,1.22845971584,1.07173836231 -6.43909883499,1.20648276806,1.07824516296 -6.52710723877,1.22547602654,1.10988938808 -6.53611898422,1.22748148441,1.13147771358 -6.54113149643,1.22948753834,1.15305387974 -6.54414367676,1.23049390316,1.17462396622 -6.55214881897,1.23249590397,1.18543231487 -6.54916191101,1.23250329494,1.20600247383 -6.52617549896,1.22851371765,1.22355949879 -6.55718660355,1.23551595211,1.24915504456 -6.65119409561,1.25650811195,1.28479385376 -6.71920251846,1.27050435543,1.31642389297 -6.65721845627,1.25852096081,1.32795548439 -6.59222841263,1.24553418159,1.32672393322 -6.49424648285,1.2255563736,1.33123719692 -6.5302567482,1.23455762863,1.35784459114 -6.47927236557,1.22457253933,1.36939680576 -6.61627721786,1.25355803967,1.41505265236 -6.57329273224,1.24557197094,1.42859947681 -6.54030752182,1.23958408833,1.44316411018 -6.50431632996,1.23259329796,1.44693005085 -6.49632978439,1.23160171509,1.46649861336 -6.47834396362,1.22861170769,1.48406171799 -6.46635723114,1.22762048244,1.50165045261 -6.53536558151,1.24261653423,1.53627216816 -6.48338270187,1.23263204098,1.54681670666 -6.53538560867,1.24362742901,1.56862473488 -6.60539340973,1.25962328911,1.60424816608 -6.61640548706,1.2626285553,1.62783527374 -6.70341205597,1.28162169456,1.6684576273 -6.64142942429,1.26963877678,1.67601084709 -6.58344697952,1.25865542889,1.68455696106 -6.55346298218,1.25366735458,1.69911921024 -6.49947357178,1.24268007278,1.69786894321 -6.47748851776,1.23869073391,1.71344482899 -6.44650411606,1.23370301723,1.72701132298 -6.48351430893,1.24270415306,1.75661683083 -6.4685292244,1.24071395397,1.77418744564 -6.44654464722,1.23672521114,1.79073882103 -6.37156438828,1.22174465656,1.79229402542 -6.41756772995,1.23174095154,1.81509315968 -6.38858366013,1.22675323486,1.82865941525 -6.34460115433,1.21876788139,1.83821713924 -6.33061599731,1.21677744389,1.85480248928 -6.38162469864,1.22877645493,1.88940560818 -6.38963842392,1.23178267479,1.91298294067 -6.39864397049,1.23378479481,1.92578172684 -6.41565608978,1.23878931999,1.95137560368 -6.39467144012,1.23580050468,1.96694266796 -6.3536901474,1.22781527042,1.97748541832 -6.41869735718,1.24381172657,2.01709961891 -6.45470809937,1.25281310081,2.04870152473 -6.45472192764,1.25382065773,2.07028150558 -6.44072961807,1.25082683563,2.07706260681 -6.40574741364,1.24484050274,2.08861804008 -6.40776062012,1.24684751034,2.11020946503 -6.38477706909,1.24285912514,2.1247780323 -6.38179159164,1.24386715889,2.14535713196 -6.45079803467,1.25986289978,2.18797802925 -6.50980615616,1.27386057377,2.22858262062 -6.47281694412,1.26687073708,2.22834658623 -6.42583608627,1.25788640976,2.23491120338 -6.42784976959,1.25989377499,2.25749063492 -6.46685934067,1.26989471912,2.29209065437 -6.48187255859,1.27489995956,2.31966757774 -6.4718875885,1.27390944958,2.33824801445 -6.46490240097,1.27391827106,2.35782957077 -6.4799079895,1.27791965008,2.37461543083 -6.46592330933,1.2759295702,2.39120602608 -6.4459400177,1.2729408741,2.40677332878 -6.4549536705,1.27694714069,2.43235468864 -6.44996833801,1.27795577049,2.45293307304 -6.43298435211,1.27496671677,2.46950054169 -6.4459900856,1.2789683342,2.4852976799 -6.49399852753,1.29096758366,2.5249042511 -6.37802743912,1.26699602604,2.50542593002 -6.50902557373,1.29798066616,2.57606744766 -6.4460477829,1.28599989414,2.57561516762 -6.53205108643,1.30599224567,2.63024187088 -6.45107603073,1.2900146246,2.62277984619 -6.44508457184,1.2900198698,2.63255476952 -6.43809986115,1.29002892971,2.65214133263 -6.43911409378,1.29203689098,2.67571568489 -6.52411746979,1.31202936172,2.73134565353 -6.53613090515,1.31703543663,2.75992107391 -6.48415231705,1.30705273151,2.76247787476 -6.55115032196,1.32304430008,2.80031061172 -6.54616546631,1.32305324078,2.82188653946 -6.56317806244,1.32905817032,2.85247278214 -6.53519678116,1.32507145405,2.86503267288 -6.68918943405,1.36105132103,2.95169949532 -6.57022094727,1.33608114719,2.92720556259 -6.5742354393,1.33908843994,2.95278763771 -6.51525068283,1.32710325718,2.93955349922 -6.51726531982,1.32911086082,2.9641354084 -6.49428272247,1.32612299919,2.97771120071 -6.55528926849,1.34212005138,3.02831554413 -6.46231746674,1.32314527035,3.01184892654 -6.48332977295,1.33014976978,3.04543113708 -6.44834899902,1.32416415215,3.0530090332 -6.45935487747,1.32716619968,3.0698056221 -6.49836397171,1.33816719055,3.11140441895 -6.5463719368,1.35116648674,3.15799856186 -6.56838417053,1.35817074776,3.19258856773 -6.50740814209,1.34719026089,3.18913769722 -6.49142551422,1.34520125389,3.20571756363 -6.47244310379,1.34321308136,3.22128868103 -6.45845317841,1.34121978283,3.22706961632 -6.44947004318,1.34122991562,3.24763894081 -6.434486866,1.34024083614,3.2642250061 -6.43850135803,1.34324836731,3.29080510139 -6.52850294113,1.36623990536,3.3594250679 -6.42353439331,1.34426784515,3.33295512199 -6.438539505,1.34926915169,3.35275149345 -6.41455841064,1.34528195858,3.36532568932 -6.43357086182,1.35228681564,3.3999106884 -6.37059688568,1.34030723572,3.39345479012 -6.47759532928,1.36729550362,3.4730784893 -6.53160142899,1.38229358196,3.52568984032 -6.54361486435,1.38729953766,3.55727887154 -6.54362249374,1.38830375671,3.57007002831 -6.49664545059,1.38032126427,3.57162284851 -6.47166490555,1.37733435631,3.58419036865 -6.44768428802,1.37434720993,3.59676527977 -6.42470359802,1.37136030197,3.61033153534 -6.42371940613,1.37336874008,3.6349196434 -6.37174367905,1.36438715458,3.63247561455 -6.41374397278,1.37538337708,3.66828250885 -6.44275522232,1.38438642025,3.70987820625 -6.42577409744,1.38339841366,3.72743582726 -6.40779209137,1.38141024113,3.74301528931 -6.45180034637,1.39441037178,3.79361772537 -6.42981958389,1.39242291451,3.80719351768 -6.42682790756,1.39342796803,3.81897735596 -6.39684963226,1.38844239712,3.82853889465 -6.4478559494,1.40344107151,3.88414406776 -6.4398727417,1.40445113182,3.90572786331 -6.41489315033,1.4014647007,3.91829037666 -6.42590713501,1.40647125244,3.95186948776 -6.4309220314,1.41047883034,3.98145604134 -6.42693042755,1.41148388386,3.99224948883 -6.42994594574,1.41449189186,4.02083492279 -6.43096208572,1.41750061512,4.04940271378 -6.4119811058,1.41651284695,4.06497716904 -6.42599439621,1.42251884937,4.10056781769 -6.41101264954,1.42153012753,4.1181511879 -6.40802145004,1.42253541946,4.1309261322 -6.39004087448,1.42154765129,4.14749526978 -6.37705993652,1.42155897617,4.16706800461 -6.36307811737,1.42157042027,4.18564558029 -6.363093853,1.42457914352,4.21322727203 -6.32911634445,1.41959452629,4.21879959106 -6.26914310455,1.40761470795,4.20736169815 -6.33014011383,1.42360746861,4.26116991043 -6.33315563202,1.42761564255,4.29075622559 -6.31817531586,1.42762744427,4.3093252182 -6.30719327927,1.42763841152,4.32990455627 -6.28721380234,1.4266513586,4.34546709061 -6.27923154831,1.42766177654,4.36804771423 -6.26225090027,1.42667376995,4.38462495804 -6.2722568512,1.43067622185,4.40542125702 -6.25327777863,1.42968928814,4.42197799683 -6.24629545212,1.43169951439,4.4455575943 -6.23131418228,1.43071115017,4.46314144135 -6.20933485031,1.42872452736,4.47670936584 -6.20435190201,1.43073415756,4.50129652023 -6.1853723526,1.42974710464,4.51686620712 -6.18638086319,1.43175148964,4.53264713287 -6.16640138626,1.43076443672,4.54722070694 -6.16641759872,1.43377327919,4.57580566406 -6.14943790436,1.43278563023,4.59238290787 -6.13545751572,1.43279767036,4.61194849014 -6.12947511673,1.4348077774,4.63652992249 -6.11448669434,1.43281543255,4.64031171799 -6.10650444031,1.43482577801,4.66290044785 -6.09352397919,1.43483769894,4.68346357346 -6.07454442978,1.43385028839,4.69804620743 -6.0655632019,1.43486118317,4.72062540054 -6.06158065796,1.43787109852,4.74720430374 -6.03260421753,1.43488621712,4.75576019287 -6.02561378479,1.43489193916,4.76455783844 -6.01863193512,1.43690252304,4.78913211823 -6.00265264511,1.43591499329,4.80670547485 -5.98767232895,1.43592727184,4.82527542114 -5.98369026184,1.43893694878,4.85185909271 -5.96571063995,1.43794977665,4.86743783951 -5.94673156738,1.43696248531,4.88201808929 -5.94474124908,1.43896794319,4.89679002762 -5.93176031113,1.43897926807,4.91538381577 -5.91478157043,1.43899226189,4.93294620514 -5.91179895401,1.44200193882,4.96053218842 -5.88882112503,1.44001603127,4.97309350967 -5.87884044647,1.44102704525,4.99468183517 -5.87085914612,1.44303810596,5.01925373077 -5.85087203979,1.44004666805,5.01803684235 -5.84189081192,1.44105756283,5.04062414169 -5.83690929413,1.4440677166,5.06720638275 -5.81393146515,1.44208168983,5.07877922058 -5.80295133591,1.44309353828,5.10134553909 -5.79697036743,1.44610416889,5.12791824341 -5.77898263931,1.44311237335,5.12770748138 -5.76900243759,1.44512367249,5.1502866745 -5.7620215416,1.44713437557,5.17586326599 -5.74504232407,1.44714713097,5.19244003296 -5.72106552124,1.44516146183,5.20301198959 -5.71708393097,1.44817173481,5.23158693314 -5.71109342575,1.44917726517,5.24138641357 -5.68911600113,1.4471912384,5.25395536423 -5.67813634872,1.44920301437,5.27652645111 -5.668156147,1.45021438599,5.29911088943 -5.6541762352,1.45122671127,5.31868600845 -5.64119672775,1.45223867893,5.33926105499 -5.62721776962,1.45325112343,5.35883712769 -5.61922836304,1.45325744152,5.36762571335 -5.61524772644,1.45626783371,5.39719772339 -5.59626913071,1.45528101921,5.41177749634 -5.5832901001,1.45729315281,5.43235492706 -5.57131052017,1.45830500126,5.45393323898 -5.55433177948,1.45831787586,5.47051239014 -5.54835128784,1.46132898331,5.49907875061 -5.54735994339,1.46333360672,5.51388072968 -5.53638029099,1.46534526348,5.5364613533 -5.5144033432,1.46335947514,5.54902982712 -5.49642515182,1.46337258816,5.5646109581 -5.48744535446,1.46538412571,5.59018135071 -5.47046709061,1.46539700031,5.60676288605 -5.45848798752,1.46740913391,5.62933444977 -5.44849920273,1.46741580963,5.63612508774 -5.43252134323,1.46742880344,5.65469551086 -5.42154169083,1.46944081783,5.67826890945 -5.39856529236,1.46845495701,5.68884754181 -5.38758611679,1.47046685219,5.71242284775 -5.3756070137,1.47147905827,5.73499774933 -5.37061691284,1.47248470783,5.74679231644 -5.35363864899,1.47249758244,5.76337623596 -5.34066057205,1.47451031208,5.78594017029 -5.32468175888,1.47452306747,5.80352592468 -5.30370521545,1.47453713417,5.81709384918 -5.29472589493,1.47654855251,5.84267663956 -5.27874708176,1.47756123543,5.86026287079 -5.26975870132,1.47756803036,5.86904335022 -5.25378131866,1.4785810709,5.88761854172 -5.23480367661,1.47759449482,5.90220117569 -5.21782588959,1.47860777378,5.91977548599 -5.20884656906,1.48061931133,5.946352005 -5.18487071991,1.47963404655,5.95592689514 -5.16989326477,1.48064696789,5.97649431229 -5.1679019928,1.48265194893,5.99129915237 -5.14592647552,1.48166668415,6.00485467911 -5.12994909286,1.48267960548,6.02343273163 -5.11597013474,1.48369193077,6.0430264473 -5.1009926796,1.48470497131,6.06359672546 -5.08801412582,1.48671746254,6.08617258072 -5.07802581787,1.48672437668,6.09296369553 -5.06104898453,1.48773789406,6.11153078079 -5.04707098007,1.48875057697,6.13310575485 -5.03109312057,1.48976325989,6.15069818497 -5.01311635971,1.49077701569,6.16826486588 -5.00213718414,1.49278903008,6.19284915924 -4.98216104507,1.49280297756,6.20742225647 -4.97917127609,1.49480855465,6.22321128845 -4.95519542694,1.49282312393,6.2317943573 -3.43960094452,1.00514805317,4.39479351044 -3.41662621498,1.00216269493,4.39336919785 -3.40664815903,1.00317466259,4.40795183182 -3.33868527412,0.985198616982,4.34950828552 -3.38469266891,1.00419890881,4.43511247635 -4.87231969833,1.50089454651,6.34546279907 -4.85734224319,1.50290751457,6.36604356766 -4.83536672592,1.50192189217,6.37762260437 -4.81139087677,1.50093650818,6.38620471954 -4.80541181564,1.50594782829,6.41977739334 -4.71945238113,1.48297548294,6.34733247757 -4.68647098541,1.47498762608,6.32510089874 -4.76347017288,1.50798153877,6.46771144867 -4.7374958992,1.5059967041,6.47428560257 -4.71651983261,1.50601089001,6.4868683815 -4.69554376602,1.5060249567,6.49945068359 -4.68656539917,1.51003706455,6.53002119064 -4.6645898819,1.50905120373,6.54060983658 -4.66060066223,1.51105737686,6.5573887825 -4.63862514496,1.51007175446,6.56896781921 -4.615650177,1.51008653641,6.57954311371 -4.48370409012,1.47012388706,6.43707942963 -4.58069753647,1.51211357117,6.61570072174 -4.56771993637,1.51412642002,6.64127159119 -4.56473016739,1.51713168621,6.65707778931 -4.54075527191,1.51614677906,6.66664886475 -4.519780159,1.51616120338,6.6802239418 -4.50780248642,1.51917350292,6.706802845 -4.48382806778,1.51818871498,6.71637439728 -4.46985054016,1.52020132542,6.73896455765 -4.44887542725,1.52021563053,6.75254058838 -4.43588876724,1.51922345161,6.75632143021 -4.41991233826,1.52123701572,6.77789449692 -4.40693473816,1.52424943447,6.80248403549 -4.38296079636,1.52326476574,6.81304645538 -4.37098264694,1.52627718449,6.83963394165 -4.33201265335,1.52029514313,6.8252081871 -4.17207479477,1.46733820438,6.62174654007 -4.14909029007,1.46234810352,6.60852861404 -4.13311481476,1.46436154842,6.62909984589 -4.29908895493,1.53633713722,6.93674039841 -4.3051071167,1.54734623432,6.99531269073 -4.2901301384,1.54935920238,7.01790332794 -4.26915550232,1.54937362671,7.03247928619 -4.244181633,1.54838883877,7.04005765915 -4.23719358444,1.55039548874,7.05384016037 -4.22221708298,1.55340874195,7.07841730118 -4.20923995972,1.55642151833,7.10599899292 -4.20525979996,1.56343209743,7.14759397507 -4.19428253174,1.56844460964,7.18016719818 -4.2052989006,1.58145236969,7.24875926971 -4.20031023026,1.58445882797,7.26753616333 -4.18933200836,1.5884706974,7.29813337326 -4.188352108,1.59748113155,7.34871339798 -4.17337560654,1.60049438477,7.37529230118 -4.13740539551,1.59551215172,7.36585998535 -4.14242315292,1.60752117634,7.42744731903 -4.12444782257,1.60953474045,7.44803476334 -4.11545991898,1.61054193974,7.45981740952 -4.10548257828,1.61655414104,7.49639558792 -4.08950662613,1.61956751347,7.52197647095 -4.06553316116,1.61858272552,7.5335521698 -4.04155921936,1.6185978651,7.54512786865 -4.02158403397,1.62061190605,7.56271505356 -4.00359916687,1.61762094498,7.55849266052 -4.00461816788,1.62863075733,7.61608123779 -3.98264431953,1.6296454668,7.6316576004 -3.95667147636,1.6286611557,7.640229702 -3.94269442558,1.6326738596,7.66882562637 -3.91972064972,1.63268887997,7.68339729309 -3.89474725723,1.63270413876,7.69297647476 -3.88675999641,1.63471102715,7.70775842667 -3.86378598213,1.63472592831,7.72133827209 -3.84281110764,1.63574028015,7.73792505264 -3.82183718681,1.63775491714,7.75649929047 -3.79786372185,1.63776993752,7.76807928085 -3.77489042282,1.63878524303,7.78364658356 -3.75391626358,1.63979971409,7.80222225189 -3.74692726135,1.64180588722,7.81602954865 -3.72395420074,1.64282095432,7.83159828186 -3.70297980309,1.6448353529,7.84918308258 -3.67800712585,1.64485096931,7.86075115204 -3.65203428268,1.643866539,7.86833143234 -3.6280605793,1.64388144016,7.87892055511 -3.60808634758,1.64589583874,7.90049505234 -3.59410047531,1.64590370655,7.90228366852 -3.56612849236,1.64391994476,7.90685462952 -3.54815340042,1.64693367481,7.93144035339 -3.52517986298,1.6479486227,7.94601869583 -3.50220608711,1.64896333218,7.95960426331 -3.47823381424,1.6499787569,7.97417020798 -3.46824645996,1.65098595619,7.98495960236 -3.43927502632,1.6490021944,7.98653459549 -3.41630125046,1.65001690388,8.00012111664 -3.39432764053,1.65103173256,8.01769828796 -3.36535620689,1.64904808998,8.01927185059 -3.34438204765,1.65106236935,8.03785800934 -3.32040858269,1.65207743645,8.04944324493 -3.3074233532,1.65208542347,8.05522251129 -3.27745199203,1.64910185337,8.05379676819 -3.25347876549,1.65011680126,8.06538200378 -3.22950601578,1.65013206005,8.078956604 -3.20653247833,1.65114676952,8.09254550934 -3.18256020546,1.65216219425,8.10711479187 -3.15858674049,1.65317702293,8.11870193481 -3.14260172844,1.65118563175,8.11648273468 -3.12362766266,1.65519976616,8.14206409454 -3.10165429115,1.65721452236,8.1606426239 -3.07268285751,1.65523052216,8.16022396088 -3.04970955849,1.65624547005,8.17580413818 -3.02273750305,1.65526115894,8.18038654327 -3.01275086403,1.65726840496,8.19317245483 -2.98777842522,1.65728378296,8.20375156403 -2.96380591393,1.659299016,8.21832561493 -2.93983316422,1.65931403637,8.23091125488 -2.91586017609,1.6613291502,8.24449062347 -2.89488649368,1.66334342957,8.26507949829 -2.86591553688,1.66135966778,8.26565265656 -2.85492897034,1.663367033,8.27544307709 -2.83195638657,1.66538226604,8.29401493073 -2.80898332596,1.66639685631,8.30960178375 -2.781011343,1.66541266441,8.31019020081 -2.75803899765,1.66742777824,8.3297586441 -2.73406624794,1.66844272614,8.34334182739 -2.70909428596,1.66945827007,8.3559179306 -2.6991071701,1.67146527767,8.36871051788 -2.67613387108,1.67347991467,8.38430213928 -2.64816331863,1.6724960804,8.38887119293 -2.62419056892,1.67351102829,8.40245819092 -2.5932199955,1.6705275774,8.39503669739 -2.41929292679,1.56857323647,7.92956161499 -2.3983092308,1.56258237362,7.90435314178 -2.37133741379,1.56059789658,7.90194272995 -2.3413670063,1.55661416054,7.89251661301 -2.31539511681,1.55562961102,7.89410114288 -2.28742384911,1.55364537239,7.88968086243 -2.26245212555,1.55366075039,7.89625740051 -2.25147604942,1.56367337704,7.95183563232 -2.26348257065,1.58167588711,8.03963756561 -2.2525062561,1.59268820286,8.09522724152 -2.24053049088,1.60270094872,8.15080547333 -2.23955154419,1.62171149254,8.24639320374 -2.29155564308,1.68171095848,8.53600502014 -2.265583992,1.68272650242,8.54558467865 -2.24461102486,1.68774092197,8.57416629791 -2.23362469673,1.6897482872,8.58695602417 -2.21065235138,1.69276309013,8.60853672028 -2.1836810112,1.69277870655,8.61511611938 -2.16370725632,1.69879293442,8.64870071411 -2.14273405075,1.70280718803,8.67728996277 -2.12775945663,1.71382057667,8.73486614227 -2.10978555679,1.72183442116,8.77944946289 -2.10479736328,1.72984039783,8.81924057007 -2.08282446861,1.7348549366,8.8478269577 -2.04985523224,1.72987186909,8.83339977264 -2.02288389206,1.73088741302,8.84098434448 -1.99891126156,1.73290216923,8.86057472229 -1.96994054317,1.73191809654,8.86015796661 -1.94495904446,1.72292840481,8.8169336319 -1.91698813438,1.72194421291,8.82051563263 -1.88701784611,1.71996021271,8.81509685516 -1.85904693604,1.71897602081,8.8186788559 -1.83107578754,1.71899163723,8.82026576996 -1.80110573769,1.71700787544,8.8158416748 -1.77413475513,1.71702337265,8.8244228363 -1.76014947891,1.71703135967,8.82720947266 -1.72917926311,1.71304738522,8.8137960434 -1.70220828056,1.71406304836,8.82237625122 -1.67723631859,1.7170779705,8.83896446228 -1.64526712894,1.71309459209,8.82453536987 -1.61729586124,1.71110999584,8.82312774658 -1.60231113434,1.71111822128,8.82191181183 -1.57234060764,1.70713400841,8.81050014496 -1.54337012768,1.70614993572,8.80708312988 -1.51439988613,1.70416581631,8.80366420746 -1.48443031311,1.70218205452,8.79923248291 -1.45645928383,1.70119762421,8.79881954193 -1.42948794365,1.701212883,8.80340862274 -1.41450333595,1.70122098923,8.80119228363 -1.38553309441,1.69923698902,8.79777145386 -1.35656285286,1.69725263119,8.7933511734 -1.326592803,1.69426882267,8.78193092346 -1.29962170124,1.69428408146,8.78751754761 -1.27365028858,1.69629919529,8.80110168457 -1.24468028545,1.6953150034,8.79668045044 -1.22969484329,1.69232285023,8.78747653961 -1.20272433758,1.6943384409,8.79805183411 -1.17675304413,1.69635355473,8.81263637543 -1.14678275585,1.69236922264,8.79522418976 -1.11981225014,1.69438481331,8.8058013916 -1.09084177017,1.69140040874,8.79738521576 -1.06487059593,1.69441556931,8.81396770477 -1.05088508129,1.69342303276,8.80976581573 -1.02091526985,1.69043910503,8.79634189606 -0.994943976402,1.69245409966,8.81092834473 -0.965973317623,1.68846952915,8.79651832581 -0.938002765179,1.68848502636,8.79510307312 -0.909032940865,1.68650090694,8.78967666626 -0.896046876907,1.68650817871,8.7924785614 -0.867077052593,1.68552398682,8.78705215454 -0.839106440544,1.68453931808,8.78363609314 -0.812135636806,1.68555450439,8.79221916199 -0.785164475441,1.68556952477,8.79580974579 -0.756194829941,1.68458533287,8.79038238525 -0.729223430157,1.68360030651,8.78997707367 -0.715238392353,1.68460810184,8.79276275635 -0.688267946243,1.68662345409,8.80834007263 -0.66029727459,1.68563866615,8.80192756653 -0.631326854229,1.68065416813,8.7805147171 -0.603356420994,1.67966938019,8.77809619904 -0.576385617256,1.68168461323,8.78768062592 -0.56240016222,1.67969202995,8.7804775238 -0.533430218697,1.6767077446,8.76405525208 -0.50645929575,1.67772269249,8.77064228058 -0.478488892317,1.67673814297,8.76622390747 -0.451518326998,1.67975318432,8.78280448914 -0.423548042774,1.6787686348,8.78038406372 -0.396577090025,1.68078351021,8.78897190094 -0.382591813803,1.67879116535,8.78376483917 -0.355620652437,1.67980587482,8.78635692596 -0.326651036739,1.67582166195,8.76892948151 -0.299680024385,1.67683649063,8.77551937103 -0.272708922625,1.67785131931,8.78011035919 -0.244738638401,1.67686665058,8.77469062805 -0.216768398881,1.67588186264,8.76927089691 -0.202783331275,1.67588949203,8.76905918121 -0.175812244415,1.67690432072,8.7746515274 -0.147842019796,1.67491936684,8.76723098755 -0.120870731771,1.67293417454,8.75782489777 -0.092900633812,1.67294943333,8.75540351868 -0.0659294649959,1.67296409607,8.7529964447 -0.0379593521357,1.66997933388,8.74157428741 -0.0239743478596,1.67198705673,8.7513628006 --0.00699231401086,1.68400394917,8.42289066315 --0.0329637601972,1.68401837349,8.42048168182 --0.059934142977,1.68503332138,8.4260597229 --0.0729197636247,1.68204069138,8.40985393524 --0.0988911688328,1.68205523491,8.40744590759 --0.12586158514,1.68307006359,8.41402339935 --0.151832953095,1.6820846796,8.40961456299 --0.178803220391,1.68209969997,8.4041891098 --0.204774603248,1.68111407757,8.40178012848 --0.23174521327,1.6841288805,8.41436290741 --0.243731498718,1.67913579941,8.39016437531 --0.26970282197,1.67915022373,8.38675403595 --0.29667326808,1.68016505241,8.39133262634 --0.322644621134,1.67917943001,8.38792324066 --0.348615735769,1.67819392681,8.37850952148 --0.375586211681,1.67920875549,8.38308906555 --0.401557385921,1.67822313309,8.37567615509 --0.414542973042,1.67723047733,8.37246990204 --0.441513746977,1.68024504185,8.38305568695 --0.467485129833,1.68025934696,8.38064575195 --0.494455814362,1.68227410316,8.38723087311 --0.520426928997,1.68028831482,8.37881565094 --0.548397243023,1.68530321121,8.39839744568 --0.560383021832,1.68131029606,8.37819004059 --0.587354183197,1.68432474136,8.39078140259 --0.614324510098,1.68433940411,8.38835811615 --0.64129537344,1.68635392189,8.3939447403 --0.668266355991,1.68836832047,8.40153408051 --0.695237100124,1.68938291073,8.40511989594 --0.72420758009,1.69639754295,8.43570995331 --0.739192247391,1.70040524006,8.44949817657 --0.764163792133,1.69641923904,8.43108654022 --0.791134536266,1.6974337101,8.43167114258 --0.818105518818,1.69844806194,8.43525981903 --0.843077123165,1.69546210766,8.41884994507 --0.871047139168,1.69747686386,8.42342567444 --0.89701873064,1.69749093056,8.42001914978 --0.911004066467,1.69949817657,8.42581272125 --0.940973520279,1.70451319218,8.44839096069 --0.965945422649,1.7025270462,8.43498420715 --0.992915928364,1.70254147053,8.43156433105 --1.01888716221,1.70155549049,8.42415237427 --1.04685807228,1.70556986332,8.43574523926 --1.07382893562,1.70558416843,8.43433094025 --1.08681499958,1.70559108257,8.43413162231 --1.11378550529,1.7056055069,8.42971038818 --1.14075648785,1.70661950111,8.43030071259 --1.1687271595,1.70963382721,8.4378900528 --1.19569790363,1.70964825153,8.43346977234 --1.2226691246,1.71066224575,8.4350643158 --1.23665440083,1.71166944504,8.43685531616 --1.26462507248,1.71368384361,8.44244289398 --1.29059636593,1.71269774437,8.43403053284 --1.31956660748,1.7167121172,8.44461631775 --1.34553790092,1.71572613716,8.4362039566 --1.37350893021,1.71774017811,8.44279766083 --1.39947998524,1.71675407887,8.43238067627 --1.41546487808,1.72076153755,8.44717597961 --1.4454344511,1.72377634048,8.45775222778 --1.47040629387,1.72178971767,8.4453458786 --1.49837696552,1.72380399704,8.44793319702 --1.52534854412,1.72481763363,8.44853115082 --1.55431854725,1.7268320322,8.45311069489 --1.583288908,1.72984647751,8.45869350433 --1.59527468681,1.72785317898,8.44848537445 --1.62424564362,1.73186719418,8.45808124542 --1.6522166729,1.73288118839,8.46067333221 --1.68118703365,1.73589539528,8.46625995636 --1.70815825462,1.73590922356,8.46285057068 --1.73512887955,1.73592329025,8.45542907715 --1.7481148243,1.73592996597,8.45222759247 --1.7770857811,1.73894393444,8.45982265472 --1.80405688286,1.73895764351,8.45541095734 --1.83402705193,1.74297189713,8.46399688721 --1.86199736595,1.74298596382,8.46057605743 --1.88996875286,1.74499964714,8.4631729126 --1.91893911362,1.74701392651,8.46475505829 --1.93292462826,1.74802064896,8.46555328369 --1.96589434147,1.75403523445,8.48714447021 --1.99486458302,1.7560492754,8.48772525787 --2.02383542061,1.75806319714,8.49131774902 --2.04580783844,1.75307607651,8.46290016174 --2.07777810097,1.75809013844,8.48150157928 --2.0997505188,1.75410306454,8.45308208466 --2.11573576927,1.75611019135,8.46087932587 --2.14270663261,1.75612390041,8.45346355438 --2.17367744446,1.76113772392,8.46606254578 --2.20164823532,1.76115143299,8.46264839172 --2.22761964798,1.76116478443,8.45123100281 --2.2565908432,1.76317834854,8.45483016968 --2.28756046295,1.76619267464,8.46040725708 --2.29754734039,1.76419878006,8.44520568848 --2.3265182972,1.76621234417,8.44679832458 --2.355489254,1.76822590828,8.44839096069 --2.38645911217,1.77123999596,8.45397281647 --2.41243100166,1.77025318146,8.44456577301 --2.43940210342,1.77026665211,8.43614864349 --2.456387043,1.77327370644,8.44494438171 --2.48035931587,1.77128648758,8.42753314972 --2.51233005524,1.77630019188,8.44013404846 --2.54230070114,1.7783138752,8.44272327423 --2.5692718029,1.77832710743,8.43430709839 --2.59924244881,1.78134083748,8.43689823151 --2.62621426582,1.78135383129,8.4304933548 --2.64019942284,1.78136062622,8.42627811432 --2.67216944695,1.78537464142,8.43386554718 --2.701141119,1.78738772869,8.43446540833 --2.72511363029,1.78540039062,8.41805744171 --2.75308489799,1.78641355038,8.41264533997 --2.78605508804,1.79142725468,8.4242401123 --2.81302642822,1.7914403677,8.4148235321 --2.82601284981,1.79144668579,8.41062545776 --2.86298108101,1.79846143723,8.43020629883 --2.88695406914,1.79647374153,8.41380023956 --2.91892433167,1.8004873991,8.42039299011 --2.94089722633,1.79649960995,8.39597511292 --2.96786904335,1.79751241207,8.38857078552 --2.98385429382,1.79851925373,8.39136600494 --3.01182579994,1.79953217506,8.38495349884 --3.04479598999,1.80354583263,8.39354610443 --3.07376742363,1.8055588007,8.39114189148 --3.10773730278,1.81057262421,8.40072917938 --3.13370919228,1.80958521366,8.38831710815 --3.15868186951,1.8085975647,8.37491130829 --3.17766594887,1.81260478497,8.38370037079 --3.20963668823,1.81561803818,8.38829517365 --3.23760843277,1.8166308403,8.38188743591 --3.26258111,1.81564307213,8.36747932434 --3.29555130005,1.81965649128,8.37306785583 --3.32152366638,1.81966888905,8.36166286469 --3.35549402237,1.82468223572,8.37126159668 --3.37247920036,1.8266890049,8.37505722046 --3.40544891357,1.82970249653,8.37763595581 --3.43042230606,1.82971441746,8.36524009705 --3.46239280701,1.83272767067,8.36682796478 --3.49436306953,1.83474087715,8.36741161346 --3.51433753967,1.83175218105,8.34201049805 --3.52932310104,1.83275854588,8.339802742 --3.55729556084,1.83377099037,8.33340072632 --3.59026575089,1.8377841711,8.33598613739 --3.62523579597,1.84179759026,8.34458065033 --3.64321064949,1.83780860901,8.31316947937 --3.67318201065,1.83982133865,8.30976295471 --3.71115136147,1.84583485126,8.3243560791 --3.71614027023,1.84183967113,8.30115795135 --3.74411201477,1.84285211563,8.2917432785 --3.77508354187,1.84486484528,8.29033660889 --3.80105614662,1.8448767662,8.27692604065 --3.84002518654,1.85089039803,8.2925195694 --3.8639986515,1.85090196133,8.27611732483 --3.89297056198,1.85191440582,8.26870536804 --3.91495394707,1.85592150688,8.28049659729 --3.93692803383,1.85393285751,8.25909042358 --3.96689987183,1.85594511032,8.25468444824 --4.00287008286,1.86095809937,8.26328372955 --4.02784347534,1.85996985435,8.24687004089 --4.05881500244,1.86298215389,8.24346160889 --4.07080125809,1.86198794842,8.23526000977 --4.10277318954,1.86500024796,8.23485851288 --4.12774658203,1.86501181126,8.21945095062 --4.15771818161,1.86702406406,8.21303939819 --4.18269109726,1.86603546143,8.19763183594 --4.2156624794,1.86904788017,8.19822788239 --4.24563455582,1.87106013298,8.19081115723 --4.26461982727,1.87406647205,8.19661426544 --4.29159212112,1.87407815456,8.18420410156 --4.31456613541,1.87308931351,8.16479682922 --4.34953737259,1.87710177898,8.16839313507 --4.37251091003,1.87611281872,8.14898681641 --4.40748262405,1.88012528419,8.1525850296 --4.42945671082,1.87913608551,8.13117694855 --4.44844198227,1.88214242458,8.1359796524 --4.48341226578,1.88515508175,8.13656044006 --4.50538682938,1.88416576385,8.11515331268 --4.53535938263,1.88617730141,8.10975646973 --4.56533145905,1.8881893158,8.10134124756 --4.59130525589,1.88820028305,8.08794021606 --4.62428665161,1.89720821381,8.11674308777 --4.65925741196,1.90122067928,8.11733341217 --4.68423175812,1.90123152733,8.10193252563 --4.71220445633,1.90124285221,8.09052562714 --4.74017715454,1.90225422382,8.07811069489 --4.77115011215,1.9052656889,8.07271003723 --4.79612350464,1.90427660942,8.05529689789 --4.78111839294,1.89327847958,8.00310707092 --4.79409503937,1.88828802109,7.96569013596 --4.80407381058,1.88129687309,7.92528486252 --4.8290476799,1.88130772114,7.90887403488 --4.8490228653,1.87931776047,7.88547086716 --4.87599658966,1.88032877445,7.87306547165 --4.90097045898,1.88033950329,7.85665416718 --4.91295814514,1.88034462929,7.84946203232 --4.94593048096,1.88335609436,7.84706068039 --4.96490573883,1.88136613369,7.82064628601 --4.99287939072,1.88237714767,7.80923748016 --5.02285194397,1.88438808918,7.80183649063 --5.05682420731,1.88839972019,7.80043506622 --5.06581258774,1.88740444183,7.78723287582 --5.09378623962,1.88841533661,7.775826931 --5.12075948715,1.88942599297,7.76241731644 --5.14873313904,1.89043676853,7.75101232529 --5.17470693588,1.89044737816,7.73559999466 --5.2006816864,1.89145767689,7.7222032547 --5.22865581512,1.89346826077,7.71079969406 --5.24264287949,1.89347350597,7.70560216904 --5.27161598206,1.89548432827,7.69418764114 --5.30358886719,1.8984951973,7.68878793716 --5.32756376266,1.8985054493,7.67037677765 --5.34953927994,1.89751517773,7.64997243881 --5.37751340866,1.89852559566,7.6385717392 --5.40348768234,1.89953577518,7.62316226959 --5.41047668457,1.89754009247,7.60796499252 --5.4424495697,1.90055096149,7.60156059265 --5.46442508698,1.89956057072,7.58115625381 --5.49139976501,1.90057098866,7.56674432755 --5.51837396622,1.90158116817,7.55334186554 --5.54334878922,1.90259099007,7.53693628311 --5.55233716965,1.9015955925,7.52373170853 --5.58031177521,1.90260565281,7.51233482361 --5.60228681564,1.90161526203,7.49092197418 --5.62426376343,1.90162467957,7.47152519226 --5.65423679352,1.90363502502,7.46111679077 --5.6732134819,1.90164411068,7.43671131134 --5.70418739319,1.90465450287,7.42730093002 --5.71917438507,1.90565943718,7.42310523987 --5.75114774704,1.90866982937,7.41570234299 --5.77112436295,1.90767896175,7.39229488373 --5.80009937286,1.90968871117,7.38190031052 --5.82507419586,1.90969836712,7.36449050903 --5.85304927826,1.91170823574,7.35209083557 --5.88102388382,1.91371798515,7.33868360519 --5.89800977707,1.91472315788,7.33547830582 --5.92698478699,1.9167330265,7.32407903671 --5.95495986938,1.9187425375,7.31168222427 --5.97993516922,1.91975212097,7.29326581955 --6.01290893555,1.92276203632,7.28687047958 --6.03588533401,1.92277109623,7.26746702194 --6.05087280273,1.92377591133,7.26226902008 --6.07284879684,1.92378497124,7.24085855484 --6.09782457352,1.92379426956,7.2224445343 --6.1198015213,1.92380297184,7.20305204391 --6.14677619934,1.9248124361,7.18764305115 --6.16575431824,1.92382073402,7.16424655914 --6.20572566986,1.92983150482,7.16283082962 --6.05975341797,1.87782084942,6.97161817551 --5.77280521393,1.7768008709,6.59617519379 --5.63382148743,1.72479474545,6.39475297928 --5.40086078644,1.64277994633,6.08932590485 --5.39084434509,1.63278627396,6.03790950775 --5.37583017349,1.6217918396,5.98250484467 --5.37981128693,1.61679923534,5.94809532166 --5.3808016777,1.61380290985,5.92989063263 --5.37878417969,1.60780978203,5.88948345184 --5.35277223587,1.5928145647,5.82307386398 --5.35475349426,1.58782172203,5.78766584396 --5.32374286652,1.57182586193,5.71726036072 --5.31972503662,1.5648329258,5.6748380661 --5.33070468903,1.56284046173,5.65144729614 --5.30870103836,1.55384230614,5.60923480988 --5.30968236923,1.54784941673,5.57382392883 --5.31866264343,1.54585707188,5.54842853546 --5.30964660645,1.53686332703,5.50301742554 --5.30862808228,1.53087043762,5.46559858322 --5.32160711288,1.52987837791,5.44419670105 --5.30760145187,1.52288079262,5.4119887352 --5.3095831871,1.51788794994,5.37958574295 --5.31956291199,1.5158957243,5.35517978668 --5.3245434761,1.51190304756,5.32577323914 --5.32252597809,1.50690984726,5.28936386108 --5.35450029373,1.51091957092,5.28695726395 --5.35148334503,1.50492608547,5.2505569458 --5.3464756012,1.50092923641,5.22834873199 --5.35745477676,1.49893689156,5.20594835281 --5.36043596268,1.49494421482,5.17453145981 --5.37641477585,1.49495220184,5.15713167191 --5.39839220047,1.49696063995,5.14573478699 --5.40537214279,1.49396836758,5.11831665039 --5.43534803391,1.49797725677,5.1149263382 --5.44833564758,1.49898195267,5.10971212387 --5.4543170929,1.49598896503,5.08331727982 --5.46929502487,1.49599695206,5.06390380859 --5.52826452255,1.50900816917,5.08650827408 --5.52324819565,1.50201439857,5.04910230637 --5.57421827316,1.51202499866,5.06269407272 --5.61419200897,1.52003443241,5.06730222702 --5.62318086624,1.52003872395,5.05808734894 --5.64315891266,1.5210467577,5.04368638992 --5.67213487625,1.52505540848,5.03728628159 --5.67111778259,1.52006185055,5.00388097763 --5.73208665848,1.53307282925,5.0254817009 --5.76906108856,1.53808200359,5.0250749588 --5.78404951096,1.54108607769,5.02288532257 --5.79502916336,1.53909361362,4.99846363068 --5.83300352097,1.54510271549,4.99906396866 --5.86697864532,1.55011153221,4.99565982819 --5.92394924164,1.56212174892,5.01226568222 --5.92193222046,1.55712795258,4.97785902023 --5.95790719986,1.56213676929,4.97545289993 --5.9908914566,1.56914198399,4.98725795746 --6.03486442566,1.57715117931,4.9918627739 --6.05484294891,1.57815885544,4.97545480728 --6.10481548309,1.58816826344,4.98405408859 --6.16478538513,1.60017824173,5.00065660477 --6.25474977493,1.62118983269,5.04227638245 --6.24173545837,1.6131953001,4.997859478 --6.22772979736,1.6061975956,4.96964979172 --6.3026971817,1.62320816517,4.99725627899 --6.33667325974,1.62821614742,4.99186134338 --6.36665010452,1.63222396374,4.98245763779 --6.42062234879,1.64223325253,4.99206113815 --6.4436006546,1.64424049854,4.97665452957 --6.47657728195,1.64824831486,4.96925401688 --6.49456501007,1.65125226974,4.96705913544 --6.53254032135,1.65726041794,4.96265172958 --6.56751680374,1.66226828098,4.95625114441 --6.60449314117,1.66827583313,4.95185899734 --6.64746761322,1.67528426647,4.95045137405 --6.68444395065,1.68129169941,4.9460644722 --6.72541904449,1.68829965591,4.94265699387 --6.71441364288,1.68330180645,4.91845989227 --5.55963087082,1.37024664879,4.02984046936 --5.56961154938,1.36925375462,4.00943040848 --5.58759069443,1.37126100063,3.99502372742 --5.60357093811,1.37126815319,3.97962427139 --7.66214370728,1.913377285,5.4366106987 --7.69612932205,1.92038154602,5.44241380692 --7.72710752487,1.92338788509,5.42700958252 --7.74108934402,1.92239356041,5.40061473846 --7.75307178497,1.9213988781,5.37221240997 --7.77205324173,1.92140471935,5.34881305695 --7.79403305054,1.92341065407,5.32640171051 --7.81601333618,1.92441642284,5.30500221252 --7.82400417328,1.92441916466,5.29280853271 --7.84498548508,1.92542493343,5.27040576935 --7.86496639252,1.92543065548,5.24700021744 --7.88494729996,1.92643618584,5.22359418869 --7.90792751312,1.92844176292,5.20320081711 --7.92690896988,1.92844724655,5.17879295349 --7.93989181519,1.92845249176,5.15139341354 --7.94988250732,1.92845511436,5.14019727707 --7.97886180878,1.93146085739,5.12279605865 --7.99584341049,1.93146622181,5.09739160538 --8.01582527161,1.93247163296,5.07398891449 --8.0348072052,1.93347668648,5.05059289932 --8.05478858948,1.93448197842,5.02719116211 --8.06077289581,1.93148672581,4.99478387833 --8.08076095581,1.93448960781,4.98958730698 --8.1027431488,1.93649482727,4.96718358994 --8.12272453308,1.9375,4.9437828064 --8.13170909882,1.93550467491,4.913377285 --8.15268993378,1.93650960922,4.89098119736 --8.16667366028,1.9365144968,4.86357593536 --8.18165588379,1.93651926517,4.83717489243 --8.19464683533,1.93752169609,4.8279838562 --8.20862960815,1.93752646446,4.80057859421 --8.22061347961,1.93653106689,4.77217435837 --8.25459289551,1.94153630733,4.75677585602 --8.26657581329,1.94054079056,4.72837257385 --8.28355884552,1.94054543972,4.7029709816 --8.30054187775,1.9415500164,4.67756986618 --8.30053520203,1.9395519495,4.6603717804 --8.32751750946,1.94255673885,4.64097595215 --8.33450126648,1.94056117535,4.60855722427 --8.36448192596,1.94356584549,4.59116840363 --8.37946510315,1.94357025623,4.56476926804 --8.39544868469,1.94457447529,4.53836345673 --8.37944412231,1.93857610226,4.51215744019 --8.40542602539,1.94158065319,4.49176025391 --8.43240737915,1.94458520412,4.47135734558 --8.42039585114,1.93858861923,4.43095827103 --8.08143806458,1.85258579254,4.21446037292 --8.01743412018,1.83358871937,4.14703416824 --8.03241825104,1.83359313011,4.12263727188 --8.07240486145,1.84159588814,4.12744665146 --8.13438034058,1.85360097885,4.12705755234 --8.14036560059,1.85160517693,4.09664583206 --8.14535045624,1.84960913658,4.06623983383 --8.13033866882,1.84261286259,4.02582979202 --8.16932010651,1.84961736202,4.01344013214 --8.15130805969,1.8416210413,3.97203278542 --8.18929481506,1.84962356091,3.97382831573 --8.18828105927,1.8456274271,3.9414305687 --8.17127132416,1.83863115311,3.90001296997 --8.16025829315,1.83363485336,3.86260724068 --8.16224479675,1.83063864708,3.83221197128 --8.1552324295,1.82664227486,3.7968044281 --8.15921878815,1.82364630699,3.76639533043 --8.13921356201,1.81764805317,3.7401766777 --8.1451997757,1.81665182114,3.711779356 --8.13618850708,1.81165552139,3.67637681961 --8.14817237854,1.81165933609,3.64996910095 --8.13716030121,1.80566310883,3.61356210709 --8.14214611053,1.80466687679,3.58415365219 --8.13613414764,1.80067062378,3.5497405529 --8.15712451935,1.8036724329,3.54455637932 --8.21010303497,1.81367635727,3.53615474701 --8.25908279419,1.8226801157,3.5267663002 --8.31406211853,1.83268368244,3.51937508583 --8.37004089355,1.84268724918,3.51198291779 --8.35503005981,1.83669066429,3.47356963158 --8.39401817322,1.84469234943,3.47538876534 --8.40400409698,1.84469568729,3.44798564911 --8.42098903656,1.84569907188,3.42358541489 --8.43397426605,1.84570240974,3.39718008041 --8.45595836639,1.84870564938,3.37478089333 --8.46294498444,1.8477088213,3.34638094902 --8.48292922974,1.8497120142,3.3229804039 --8.49192237854,1.85071361065,3.31077885628 --8.50290775299,1.85071671009,3.28337192535 --8.51889228821,1.85171985626,3.2579665184 --8.52987861633,1.85172283649,3.23157310486 --8.54186439514,1.85272574425,3.20517468452 --8.5508518219,1.85172891617,3.17676496506 --8.56483745575,1.85273182392,3.1503572464 --8.56983089447,1.85273325443,3.13716292381 --8.5878162384,1.8547359705,3.11276340485 --8.60180187225,1.85573887825,3.08635687828 --8.60078907013,1.8527418375,3.05495357513 --8.62877368927,1.85674440861,3.03456258774 --8.6317615509,1.8557472229,3.00415372849 --8.6397485733,1.85475003719,2.97574877739 --8.64974117279,1.85575127602,2.96354579926 --8.67772674561,1.86075353622,2.94315838814 --8.6937122345,1.86175620556,2.91674590111 --8.69369983673,1.85975885391,2.88634943962 --8.7166852951,1.86276113987,2.86294722557 --8.7276725769,1.86276364326,2.83554387093 --8.7316608429,1.86176633835,2.80614304543 --8.77165031433,1.86976671219,2.80395102501 --8.75663948059,1.86376965046,2.76753640175 --8.76962661743,1.86477184296,2.74113893509 --8.79161262512,1.8677740097,2.71673202515 --8.78960132599,1.86577653885,2.68532848358 --8.79758930206,1.86577880383,2.65793800354 --8.82957363129,1.87078046799,2.63653445244 --8.82756900787,1.86878180504,2.62032961845 --8.8445558548,1.87078368664,2.59493231773 --8.86954116821,1.87478542328,2.57153224945 --8.8485326767,1.86778831482,2.53411793709 --8.86551952362,1.86979019642,2.50872159004 --8.89150619507,1.87379169464,2.48532009125 --8.88649559021,1.87079405785,2.45291113853 --8.90148925781,1.87379467487,2.44272398949 --8.92147541046,1.87579619884,2.41732001305 --8.91046524048,1.87179887295,2.3829035759 --8.9334526062,1.87480020523,2.35951662064 --8.96343803406,1.87980127335,2.33712100983 --8.96642780304,1.87880325317,2.30670976639 --8.96841621399,1.87780511379,2.27630186081 --8.99240875244,1.88180530071,2.26811647415 --8.98939800262,1.87980747223,2.23569774628 --8.99438762665,1.87880921364,2.20730686188 --9.03437328339,1.88680946827,2.18691277504 --9.02036380768,1.88181197643,2.15250086784 --9.03335285187,1.88281321526,2.12509894371 --9.05034637451,1.88581347466,2.11390018463 --9.04033660889,1.88181579113,2.08048725128 --9.04232597351,1.88081741333,2.05109143257 --9.06931400299,1.88581800461,2.02668976784 --9.07130336761,1.88381969929,1.99628102779 --9.08529186249,1.88582062721,1.96989166737 --9.10527992249,1.88882136345,1.94348669052 --9.10827541351,1.8888220787,1.92929005623 --9.1112651825,1.88782346249,1.89887845516 --9.14025211334,1.89282369614,1.87549197674 --9.12824344635,1.88882577419,1.84207928181 --9.14923286438,1.89182627201,1.81567525864 --9.1752204895,1.89682638645,1.79027307034 --9.15421199799,1.89082896709,1.75586748123 --9.19120502472,1.89782762527,1.74868249893 --9.18619537354,1.89582920074,1.71727740765 --9.19418621063,1.89583015442,1.68786787987 --9.2011756897,1.89683115482,1.65846049786 --9.20716571808,1.8968321085,1.63006925583 --9.21115589142,1.89583313465,1.5996556282 --9.22014522552,1.89683377743,1.57125771046 --9.22114086151,1.89683437347,1.5560529232 --9.23213100433,1.89783489704,1.52765119076 --9.25712013245,1.90183448792,1.50124824047 --9.25411128998,1.89983582497,1.47084951401 --9.26710224152,1.90183603764,1.44244527817 --9.27209186554,1.90183675289,1.41304385662 --9.28708267212,1.90383672714,1.38565063477 --9.299077034,1.90583634377,1.37143909931 --9.30006885529,1.90483736992,1.34204590321 --9.30705928802,1.90583765507,1.31264150143 --9.31905078888,1.90783786774,1.28424215317 --9.32904052734,1.90883791447,1.25483345985 --9.33003234863,1.9078387022,1.22442662716 --9.33802700043,1.90883851051,1.21022462845 --9.35801792145,1.91283786297,1.18282794952 --9.35600948334,1.91083860397,1.15242624283 --9.37799930573,1.91483771801,1.12502849102 --9.37199211121,1.91283881664,1.09361898899 --9.39398288727,1.91683769226,1.06622314453 --9.40497398376,1.91783750057,1.03681719303 --9.41696548462,1.91983699799,1.00842380524 --9.40296173096,1.91683840752,0.991212487221 --9.42595291138,1.92083716393,0.963819205761 --9.42994403839,1.92083728313,0.93340998888 --9.42893695831,1.91983771324,0.903006374836 --9.43292808533,1.91983771324,0.872597038746 --9.43792057037,1.92083775997,0.843199849129 --9.4469127655,1.92183721066,0.813799083233 --9.46990776062,1.92583537102,0.800600707531 --9.48490047455,1.92883419991,0.772208988667 --9.47789287567,1.92683506012,0.740798056126 --9.49488449097,1.9298337698,0.711392462254 --9.5068769455,1.93183279037,0.681992173195 --9.50187015533,1.92983341217,0.651592552662 --9.51086521149,1.93183255196,0.636383652687 --9.50985908508,1.93083274364,0.605980694294 --9.50585079193,1.92983317375,0.575579285622 --9.51484298706,1.93083226681,0.54516929388 --9.52283668518,1.93183135986,0.515774011612 --9.52282905579,1.93183135986,0.485369831324 --9.53082275391,1.93283045292,0.454961657524 --9.53181838989,1.93283033371,0.439759194851 --9.53581142426,1.93382966518,0.409353166819 --9.54080486298,1.93382894993,0.379960775375 --9.54479885101,1.93482840061,0.34955522418 --9.54479122162,1.93382799625,0.318137913942 --9.54978466034,1.93482720852,0.288745850325 --9.55377864838,1.93582653999,0.258340775967 --9.5597743988,1.93682563305,0.24313762784 --9.56776809692,1.93782436848,0.212732702494 --9.57476139069,1.9388231039,0.182328402996 --9.56375598907,1.93682384491,0.151925563812 --9.578748703,1.93982172012,0.121521241963 --9.58774280548,1.94182014465,0.0911179333925 --9.58473682404,1.94081997871,0.0607146695256 --9.58473396301,1.94081962109,0.0455130077899 --9.59672832489,1.94281756878,0.0151113178581 --9.59772109985,1.94281685352,-0.0152913900092 --9.60171604156,1.94381570816,-0.0456935167313 --9.608710289,1.94481396675,-0.0771078020334 --9.60270404816,1.94381403923,-0.107512243092 --9.61469841003,1.94681167603,-0.137911051512 --9.62069511414,1.94781053066,-0.153109937906 --9.62068939209,1.94780957699,-0.183512017131 --9.61268424988,1.94580972195,-0.214931055903 --9.620677948,1.94780766964,-0.245329588652 --9.63667392731,1.95080471039,-0.275722920895 --9.62666797638,1.94880497456,-0.30613014102 --9.61966228485,1.94780468941,-0.337549835443 --9.64166069031,1.95180130005,-0.352736443281 --9.65865516663,1.9557980299,-0.384139299393 --9.65165042877,1.95479774475,-0.41454488039 --9.65164470673,1.95479643345,-0.444945394993 --9.67164134979,1.95979249477,-0.476343154907 --9.67063617706,1.95979130268,-0.507756948471 --9.66463088989,1.95779085159,-0.538161695004 --9.66962909698,1.95978939533,-0.553357183933 --9.6706237793,1.95978784561,-0.584768950939 --9.6616191864,1.95778775215,-0.615177333355 --9.67561531067,1.96178424358,-0.646575808525 --9.6756105423,1.96178269386,-0.677987992764 --9.68260669708,1.96378016472,-0.709392249584 --9.67260074615,1.96177995205,-0.739802360535 --9.68959999084,1.96577680111,-0.755994737148 --9.68159580231,1.96477615833,-0.786402642727 --9.68059158325,1.96477460861,-0.816802084446 --9.68058681488,1.96477293968,-0.848213255405 --9.67258262634,1.96377241611,-0.878622114658 --9.66857814789,1.96277117729,-0.909025669098 --9.6635761261,1.96277093887,-0.924232125282 --9.67457294464,1.96476733685,-0.956640303135 --9.6665687561,1.96376681328,-0.986036777496 --9.67156505585,1.96576404572,-1.01845324039 --9.67856216431,1.96776092052,-1.04985249043 --9.68355846405,1.96975815296,-1.08125436306 --9.68455505371,1.97075593472,-1.11266219616 --9.68755340576,1.97075438499,-1.12785494328 --9.69055080414,1.97275173664,-1.15925884247 --9.69154644012,1.97274947166,-1.19066548347 --9.69554424286,1.97474646568,-1.22307980061 --9.69654083252,1.97574412823,-1.25448584557 --9.69153690338,1.97574257851,-1.28488993645 --9.69353485107,1.97674000263,-1.31629347801 --9.69753360748,1.9777380228,-1.3324958086 --9.6965303421,1.97773575783,-1.36390447617 --9.692527771,1.97773396969,-1.39430618286 --9.70452594757,1.98172950745,-1.427713871 --9.70052337646,1.98172771931,-1.45811498165 --9.68651866913,1.97972738743,-1.48752498627 --9.68251514435,1.97972548008,-1.5189396143 --9.70551681519,1.98472011089,-1.5371234417 --9.71151542664,1.98671650887,-1.5695271492 --9.70151138306,1.98571538925,-1.59994125366 --9.70851039886,1.98871135712,-1.63234186172 --9.715508461,1.99070715904,-1.66575407982 --9.70750617981,1.98970580101,-1.69515025616 --9.7005033493,1.98970413208,-1.72657036781 --9.70750331879,1.99170136452,-1.7437735796 --9.71050071716,1.9936978817,-1.77516806126 --9.7275018692,1.99769163132,-1.80956399441 --9.71649932861,1.99669063091,-1.83998060226 --9.70749664307,1.99568903446,-1.87039196491 --9.70449447632,1.9966865778,-1.90180063248 --9.70049285889,1.9966840744,-1.93321156502 --9.70949268341,1.99868071079,-1.95040583611 --9.71549224854,2.00167608261,-1.98381400108 --9.7294921875,2.00567007065,-2.01821112633 --9.70848846436,2.00267076492,-2.04561805725 --9.70648765564,2.00366783142,-2.07803463936 --9.72748947144,2.00966024399,-2.11342120171 --9.71148586273,2.00665974617,-2.14283943176 --9.70848560333,2.00665855408,-2.15804028511 --9.71748542786,2.01065301895,-2.19244766235 --9.70248317719,2.00865268707,-2.22186398506 --9.70948410034,2.01164722443,-2.25526285172 --9.7254858017,2.01664042473,-2.29065775871 --9.68647861481,2.00964474678,-2.31508803368 --9.69147968292,2.01163959503,-2.34849143028 --9.71848392487,2.01863217354,-2.37068247795 --9.70848178864,2.01763010025,-2.40109539032 --9.70348072052,2.01762747765,-2.43149161339 --9.71348285675,2.02162098885,-2.46690011024 --9.71748352051,2.02461624146,-2.5003027916 --9.70448207855,2.0226149559,-2.52971291542 --9.73748779297,2.03060555458,-2.55389976501 --9.7224855423,2.02960467339,-2.58331632614 --9.71848487854,2.03060102463,-2.61573195457 --9.73448848724,2.03559350967,-2.65212488174 --9.71348571777,2.03259372711,-2.67953848839 --9.71248531342,2.0335893631,-2.71295404434 --9.71248626709,2.03558492661,-2.74535346031 --9.70448589325,2.03458452225,-2.759557724 --9.71748924255,2.03957700729,-2.79595685005 --9.73249340057,2.04456877708,-2.83335900307 --9.70548915863,2.04057025909,-2.85978460312 --9.70249080658,2.04156637192,-2.89219284058 --9.73149681091,2.04955482483,-2.93358612061 --9.69849205017,2.04455757141,-2.95700025558 --9.72049713135,2.05054998398,-2.98019623756 --9.72149944305,2.05254483223,-3.01359796524 --9.70149707794,2.04954457283,-3.04202246666 --9.71750164032,2.0555357933,-3.07941126823 --9.73450756073,2.06152653694,-3.11881828308 --9.72350788116,2.06052398682,-3.14922952652 --9.71650886536,2.06152057648,-3.18063688278 --9.72151184082,2.06451416016,-3.21604132652 --9.70750999451,2.06251478195,-3.22824668884 --9.7225151062,2.06750559807,-3.26664376259 --9.73552131653,2.07249689102,-3.30504727364 --9.72752189636,2.07349348068,-3.33645653725 --9.7295255661,2.07548737526,-3.37186908722 --9.75053310394,2.08247637749,-3.4122569561 --9.73453140259,2.08047747612,-3.42447185516 --9.74353599548,2.08446955681,-3.46187472343 --9.74754047394,2.08746290207,-3.49727487564 --9.73054027557,2.0864610672,-3.52669763565 --9.74954795837,2.09345030785,-3.56708717346 --9.76655673981,2.09943962097,-3.60849499702 --9.75755691528,2.09943580627,-3.63990306854 --9.75655937195,2.10043311119,-3.65710830688 --9.76156520844,2.10442566872,-3.6935095787 --9.76456832886,2.10741877556,-3.72890686989 --9.754570961,2.10741496086,-3.76132941246 --9.75857639313,2.11140751839,-3.79773211479 --9.75458049774,2.1124022007,-3.83113670349 --9.75058269501,2.11439657211,-3.86555290222 --9.76859092712,2.1193883419,-3.88974452019 --9.7715959549,2.12338066101,-3.92614793777 --9.76760005951,2.12437534332,-3.96056079865 --9.75260066986,2.12437295914,-3.98997044563 --9.75460720062,2.12736558914,-4.02637577057 --9.74360847473,2.12736177444,-4.0577878952 --9.71860694885,2.12436199188,-4.08421325684 --9.71260738373,2.12436032295,-4.09941673279 --9.69260787964,2.1223590374,-4.12682914734 --9.70061588287,2.12734985352,-4.16623592377 --9.70062255859,2.13034248352,-4.20264816284 --9.68862438202,2.13033914566,-4.23305368423 --9.68662929535,2.13233232498,-4.26846313477 --9.67463207245,2.13232851028,-4.29987955093 --9.6716337204,2.13332605362,-4.31607723236 --9.66763973236,2.13531947136,-4.35149621964 --9.64563846588,2.13331913948,-4.3779091835 --9.6456451416,2.13631129265,-4.41431617737 --9.64265060425,2.13930463791,-4.44972801208 --9.62065029144,2.13730406761,-4.47614145279 --9.6216583252,2.14029598236,-4.51355266571 --9.60465526581,2.13729763031,-4.52375936508 --9.61766719818,2.14428567886,-4.56615877151 --9.59666728973,2.14228439331,-4.59357833862 --9.58667182922,2.14327979088,-4.62599277496 --9.59068012238,2.14727067947,-4.66439390182 --9.58268547058,2.14826512337,-4.69780683517 --9.57569026947,2.15025949478,-4.7312130928 --9.58069515228,2.1532535553,-4.75241756439 --9.57870292664,2.1562461853,-4.78882694244 --9.56270503998,2.1552426815,-4.81925058365 --9.56071281433,2.15823507309,-4.85565853119 --9.52670860291,2.15423822403,-4.87607765198 --9.51771450043,2.15523266792,-4.90949344635 --9.50871944427,2.15622735023,-4.94189786911 --9.50472259521,2.15722441673,-4.95910835266 --9.50573062897,2.16121530533,-4.99751806259 --9.49973773956,2.16320872307,-5.03192424774 --9.55076503754,2.17918229103,-5.09631156921 --9.64280796051,2.2051410675,-5.18167114258 --9.6708278656,2.21512174606,-5.23506641388 --9.67984104156,2.22110939026,-5.27846622467 --9.67184352875,2.22110748291,-5.29367256165 --9.65084648132,2.22010564804,-5.32108449936 --9.59383487701,2.21011638641,-5.33052682877 --9.60184860229,2.21610379219,-5.37393093109 --9.5688457489,2.21210622787,-5.39535570145 --9.53884410858,2.20810747147,-5.41777276993 --9.52184200287,2.2061085701,-5.42899513245 --9.50684738159,2.20710420609,-5.46041488647 --9.48184776306,2.20510363579,-5.48583507538 --9.46385192871,2.20410037041,-5.51525306702 --9.42684745789,2.1991045475,-5.53367757797 --9.40384864807,2.19710326195,-5.5600976944 --9.383852005,2.19710087776,-5.58751010895 --9.37885475159,2.19709777832,-5.60472011566 --9.35885810852,2.19709539413,-5.63213253021 --9.32485485077,2.19209814072,-5.65256357193 --9.31486225128,2.19409203529,-5.68597364426 --9.2808599472,2.1900947094,-5.70640707016 --9.27486801147,2.19308686256,-5.74282121658 --9.23286151886,2.18709301949,-5.75724840164 --9.2258644104,2.1870906353,-5.77245092392 --9.20186519623,2.18508958817,-5.79787254333 --9.17986774445,2.18408799171,-5.82429170609 --9.14486408234,2.18009138107,-5.84372806549 --9.13086986542,2.1810863018,-5.87514448166 --9.09886837006,2.17708897591,-5.89456224442 --9.06386470795,2.17309260368,-5.91299200058 --9.05986881256,2.17408871651,-5.93120574951 --9.02586555481,2.17009210587,-5.94962978363 --8.99486351013,2.16609406471,-5.9700551033 --8.98687171936,2.16908669472,-6.00446224213 --8.94886684418,2.16409158707,-6.0208978653 --8.90986061096,2.15809726715,-6.03532171249 --8.90186977386,2.16108989716,-6.06972885132 --8.87086105347,2.15509748459,-6.06995344162 --8.85486602783,2.15609359741,-6.0993680954 --8.82986736298,2.15409302711,-6.12379646301 --8.80987071991,2.15409040451,-6.15122032166 --8.78787326813,2.15308880806,-6.17663764954 --8.76087284088,2.15108942986,-6.19906282425 --8.72186660767,2.14509534836,-6.21248674393 --8.70686626434,2.14409589767,-6.22371101379 --8.69187164307,2.14509153366,-6.25311946869 --8.66387081146,2.14209246635,-6.27454471588 --8.63487052917,2.14009428024,-6.29496860504 --8.61087226868,2.13909316063,-6.31939554214 --8.57786846161,2.13509678841,-6.33682155609 --8.54786586761,2.13209867477,-6.35624599457 --8.54086971283,2.13309621811,-6.37246227264 --8.50586509705,2.12910056114,-6.3878865242 --8.48386859894,2.12809896469,-6.41331100464 --8.46487236023,2.12809634209,-6.43972253799 --8.42486476898,2.12210273743,-6.45215892792 --8.40386772156,2.12210083008,-6.47757768631 --8.39387702942,2.12409377098,-6.51199769974 --8.35586357117,2.11710572243,-6.50422286987 --8.33286571503,2.1161043644,-6.52864837646 --8.32887840271,2.12009453773,-6.56706047058 --8.27986526489,2.11210608482,-6.57048797607 --8.2598695755,2.11210346222,-6.59691047668 --8.24787807465,2.1140973568,-6.62932729721 --8.21487426758,2.11110091209,-6.64575767517 --8.19186782837,2.1071062088,-6.6489777565 --8.17887592316,2.10910010338,-6.68039226532 --8.14187049866,2.10510587692,-6.69382953644 --8.11587047577,2.10310649872,-6.71424436569 --8.09687519073,2.10310339928,-6.74167060852 --8.06587219238,2.10010623932,-6.75909948349 --8.06187725067,2.10210204124,-6.7773103714 --8.04588413239,2.10309743881,-6.80673027039 --8.00287342072,2.09710693359,-6.81315612793 --7.98387908936,2.09810376167,-6.84058332443 --7.96988725662,2.09909820557,-6.87099599838 --7.92187356949,2.09211015701,-6.87343072891 --7.90287828445,2.09210729599,-6.89984893799 --7.89388084412,2.09310531616,-6.91406345367 --7.8588757515,2.08911061287,-6.92749547958 --7.84588432312,2.09110450745,-6.95890951157 --7.81588220596,2.08810710907,-6.9763379097 --7.78588008881,2.08610987663,-6.99376726151 --7.76488399506,2.08610773087,-7.01919460297 --7.74088573456,2.08510732651,-7.04161977768 --7.71887969971,2.08211255074,-7.04383611679 --7.69688272476,2.08211088181,-7.06826353073 --7.67888879776,2.08210706711,-7.09568309784 --7.64688539505,2.07911109924,-7.11111593246 --7.62188625336,2.07811141014,-7.1315331459 --7.59588670731,2.07711195946,-7.15196037292 --7.56988716125,2.07611274719,-7.17238807678 --7.55588674545,2.07511377335,-7.18160152435 --7.53989458084,2.0771086216,-7.21102237701 --7.51289367676,2.07511043549,-7.22944116592 --7.49389982224,2.07610702515,-7.25586128235 --7.4588932991,2.07211279869,-7.26829957962 --7.44090032578,2.07310891151,-7.29571962357 --7.41890382767,2.07310700417,-7.32014942169 --7.40390205383,2.07210898399,-7.32735586166 --7.38891124725,2.07410335541,-7.3577747345 --7.36291217804,2.07310390472,-7.37820529938 --7.33491039276,2.07110619545,-7.39562797546 --7.31091356277,2.07110548019,-7.41805887222 --7.29992580414,2.07409739494,-7.45247507095 --7.27993154526,2.07509422302,-7.47890377045 --7.27593851089,2.07708907127,-7.49710607529 --7.25994777679,2.07908368111,-7.52753210068 --7.23995304108,2.0800807476,-7.55295085907 --7.22296142578,2.08207583427,-7.58237552643 --7.19896411896,2.08107542992,-7.60379600525 --7.16896152496,2.07907867432,-7.61922168732 --7.14396429062,2.07907819748,-7.64166212082 --7.10994672775,2.07209205627,-7.62887859344 --7.08394765854,2.07109284401,-7.64830350876 --7.05995035172,2.07009220123,-7.66972637177 --7.03094911575,2.0690946579,-7.68716430664 --6.98893642426,2.06310558319,-7.68959951401 --6.97294521332,2.06510019302,-7.71901464462 --6.94394397736,2.06310272217,-7.73544597626 --6.93494844437,2.06410074234,-7.74965906143 --6.90694713593,2.06310248375,-7.76708936691 --6.87894630432,2.06110501289,-7.78351163864 --6.85895299911,2.06210160255,-7.80994033813 --6.8339548111,2.06210184097,-7.83036804199 --6.80695486069,2.06110358238,-7.84778928757 --6.78696155548,2.06210017204,-7.87421798706 --6.77095985413,2.06110239029,-7.88144159317 --6.74596118927,2.06010246277,-7.90086078644 --6.71595859528,2.05810642242,-7.91528892517 --6.69596529007,2.05910277367,-7.94171714783 --6.66896629333,2.05910420418,-7.96014976501 --6.64897251129,2.06010103226,-7.98556900024 --6.62796592712,2.05710697174,-7.98578739166 --6.61297750473,2.060100317,-8.01720523834 --6.58597803116,2.05910158157,-8.03563785553 --6.55397367477,2.05610656738,-8.04807281494 --6.53197908401,2.05710411072,-8.07250499725 --6.50698137283,2.05710458755,-8.09192657471 --6.47497653961,2.0541100502,-8.10335540771 --6.45898771286,2.05710315704,-8.13478088379 --6.44999313354,2.05910038948,-8.1500005722 --6.4149851799,2.05510854721,-8.1564207077 --6.39499235153,2.05610466003,-8.18284702301 --6.37500095367,2.05810070038,-8.21028137207 --6.34399700165,2.05610537529,-8.22271060944 --6.31399440765,2.05410909653,-8.23714542389 --6.30299758911,2.05510807037,-8.24835395813 --6.27099275589,2.0521132946,-8.25978755951 --6.24699640274,2.05311250687,-8.28121566772 --6.23100805283,2.05610609055,-8.31162929535 --6.19099521637,2.05111765862,-8.31307220459 --6.16800022125,2.05111575127,-8.33650493622 --6.14900922775,2.05311131477,-8.36392688751 --6.13400840759,2.0531129837,-8.37114620209 --6.1040058136,2.05111718178,-8.38457775116 --6.08301305771,2.05311369896,-8.41000461578 --6.05100774765,2.05011940002,-8.42043495178 --6.02300786972,2.04912161827,-8.4368686676 --6.00301647186,2.05111789703,-8.46329212189 --5.972012043,2.04912281036,-8.4747209549 --5.95701122284,2.04812479019,-8.48194122314 --5.93601942062,2.05012130737,-8.50736808777 --5.90201187134,2.04712867737,-8.51480197906 --5.87301015854,2.04613208771,-8.5292339325 --5.85402011871,2.04812717438,-8.55765914917 --5.82201528549,2.04613280296,-8.56809520721 --5.79301404953,2.04513597488,-8.58252811432 --5.78702354431,2.04813051224,-8.60173797607 --5.75201463699,2.04413890839,-8.60717201233 --5.71900844574,2.04214596748,-8.61560630798 --5.70302248001,2.04513788223,-8.64903354645 --5.67201852798,2.0431432724,-8.65946102142 --5.64802312851,2.04414224625,-8.68089008331 --5.62302732468,2.04514169693,-8.70232963562 --5.60402059555,2.04314780235,-8.70154190063 --5.57001256943,2.04015564919,-8.70797634125 --5.54902076721,2.04215240479,-8.73339939117 --5.52302312851,2.04215312004,-8.75183010101 --5.48901557922,2.03916096687,-8.75826740265 --5.46802520752,2.04115700722,-8.78570461273 --5.44801616669,2.03816413879,-8.78291511536 --5.42101812363,2.03816556931,-8.80035114288 --5.40202999115,2.04115986824,-8.82977867126 --5.37803554535,2.04315829277,-8.85221290588 --5.34102249146,2.03816986084,-8.8526468277 --5.32003164291,2.0401661396,-8.87806797028 --5.29403448105,2.0411670208,-8.89649868011 --5.27004051208,2.04216527939,-8.91893291473 --5.26304960251,2.04516029358,-8.93713855743 --5.22403526306,2.04017305374,-8.93558597565 --5.2000412941,2.04117155075,-8.95802021027 --5.17504501343,2.04217147827,-8.97744464874 --5.14504289627,2.04117584229,-8.98988246918 --5.1110329628,2.03818488121,-8.99431610107 --5.10003852844,2.03918290138,-9.0075340271 --5.07404136658,2.04018354416,-9.02596473694 --5.04503917694,2.03918766975,-9.03839111328 --5.01904344559,2.04018735886,-9.05883598328 --4.98803901672,2.03819346428,-9.06826686859 --4.96304321289,2.0391933918,-9.08769226074 --4.93404150009,2.03819704056,-9.10112762451 --4.9270529747,2.04119086266,-9.12134075165 --4.88503170013,2.03520822525,-9.111784935 --4.8600358963,2.03620791435,-9.13121032715 --4.83303785324,2.03620934486,-9.14864730835 --4.80403709412,2.03621315956,-9.16208362579 --4.78004407883,2.03821158409,-9.18451499939 --4.7530465126,2.03821277618,-9.20195102692 --4.7310333252,2.03422284126,-9.19416999817 --4.70303344727,2.03422546387,-9.20960712433 --4.67703723907,2.03522610664,-9.22803783417 --4.65104055405,2.03622674942,-9.24646949768 --4.61903429031,2.03423428535,-9.2529001236 --4.58903121948,2.03323912621,-9.26433849335 --4.564037323,2.03523826599,-9.28577518463 --4.54903507233,2.03424119949,-9.28998470306 --4.5190320015,2.03324604034,-9.30142211914 --4.49303627014,2.03424620628,-9.32085800171 --4.45602178574,2.03025913239,-9.31830215454 --4.43202972412,2.03225708008,-9.34173679352 --4.40503120422,2.03225922585,-9.35716152191 --4.39002943039,2.03226184845,-9.3623790741 --4.35802316666,2.03026914597,-9.36982059479 --4.33002376556,2.03027200699,-9.38425254822 --4.30703449249,2.03326821327,-9.41069030762 --4.27803325653,2.03327226639,-9.42312431335 --4.24001407623,2.02828812599,-9.415558815 --4.21401786804,2.02928853035,-9.43398857117 --4.20001983643,2.03028893471,-9.44321632385 --4.17101812363,2.02929353714,-9.45464515686 --4.14301919937,2.03029608727,-9.47008323669 --4.11602210999,2.03029727936,-9.48751926422 --4.0870218277,2.03030109406,-9.50095939636 --4.05601596832,2.02930808067,-9.50839328766 --4.0220041275,2.02631902695,-9.50882720947 --4.00900745392,2.02731871605,-9.51904678345 --3.97900342941,2.02632474899,-9.52847862244 --3.95100426674,2.02732753754,-9.54291343689 --3.92501020432,2.02832722664,-9.56335163116 --3.89400601387,2.02733325958,-9.57279682159 --3.86299967766,2.02634072304,-9.57922840118 --3.83199429512,2.02534794807,-9.58666419983 --3.8220038414,2.02734327316,-9.60388088226 --3.79701137543,2.03034210205,-9.62531089783 --3.76199841499,2.027354002,-9.62475776672 --3.7370057106,2.02935290337,-9.64618682861 --3.70499825478,2.02736115456,-9.65162754059 --3.68101000786,2.03035736084,-9.67806720734 --3.64599394798,2.02737116814,-9.67349815369 --3.63299798965,2.02837061882,-9.68472003937 --3.60199189186,2.02737784386,-9.69115447998 --3.57199001312,2.02738285065,-9.70259857178 --3.54599571228,2.02838301659,-9.7220287323 --3.51198387146,2.0263941288,-9.72247409821 --3.48398590088,2.02739644051,-9.73791217804 --3.45698904991,2.02839827538,-9.75434112549 --3.44198846817,2.02840065956,-9.76056575775 --3.41399168968,2.02940249443,-9.77700710297 --3.38198113441,2.02741265297,-9.7784318924 --3.35398507118,2.02841424942,-9.79587841034 --3.32699084282,2.03041434288,-9.81531906128 --3.29598402977,2.02942252159,-9.82075023651 --3.28098273277,2.0294251442,-9.82597064972 --3.2539896965,2.03142499924,-9.84641456604 --3.21997380257,2.02843880653,-9.84184360504 --3.19197869301,2.03043961525,-9.86029338837 --3.16698861122,2.03243732452,-9.88372135162 --3.13498067856,2.03144621849,-9.88816356659 --3.10798716545,2.03344631195,-9.90760135651 --3.09900403023,2.03843808174,-9.93182086945 --3.06699585915,2.03644704819,-9.93626213074 --3.04000234604,2.03844714165,-9.95569801331 --3.01902627945,2.04543662071,-9.9931268692 --2.99002766609,2.04543972015,-10.0075674057 --2.95801925659,2.04444909096,-10.0110044479 --2.93203139305,2.04844617844,-10.0364484787 --2.9110121727,2.04345965385,-10.0226736069 --2.88201236725,2.04446387291,-10.0351066589 --2.85602378845,2.04846119881,-10.059545517 --2.82100582123,2.04447627068,-10.052986145 --2.79100584984,2.04548096657,-10.0654306412 --2.76100444794,2.04548573494,-10.0768737793 --2.73200654984,2.0464887619,-10.0913124084 --2.71600031853,2.04549479485,-10.0905227661 --2.68800783157,2.04849481583,-10.1109714508 --2.652987957,2.04451084137,-10.1024093628 --2.62800431252,2.04850554466,-10.1318464279 --2.59700059891,2.04851222038,-10.1402902603 --2.56298279762,2.04552745819,-10.1337242126 --2.53398489952,2.04653048515,-10.1481628418 --2.52500915527,2.05251836777,-10.1793880463 --2.49300146103,2.05152750015,-10.1838321686 --2.46099424362,2.05153656006,-10.1882762909 --2.44002580643,2.05952191353,-10.2327032089 --2.40601038933,2.05653548241,-10.2291469574 --2.3780195713,2.05953478813,-10.2505912781 --2.34500741959,2.0575466156,-10.2500324249 --2.32598924637,2.05355978012,-10.2372484207 --2.29498505592,2.05356693268,-10.2446899414 --2.26297950745,2.05357503891,-10.2511415482 --2.22896003723,2.05059123039,-10.2425756454 --2.19192814827,2.04361462593,-10.2220163345 --2.1779999733,2.0615773201,-10.3074550629 --2.17606067657,2.07554388046,-10.3756780624 --2.16916847229,2.10048484802,-10.4981155396 --2.09812283516,2.0925219059,-10.4739952087 --2.0621008873,2.08853983879,-10.4634475708 --2.04416036606,2.1025094986,-10.5358810425 --2.00914096832,2.09952616692,-10.5273256302 --1.96708571911,2.08756375313,-10.4827728271 --1.97520697117,2.11549520493,-10.6119937897 --1.89595746994,2.06164646149,-10.3694429398 --1.89812660217,2.09955239296,-10.5528726578 --1.8240634203,2.08759951591,-10.5117664337 --1.79808843136,2.09459018707,-10.5482025146 --1.76315546036,2.1115591526,-10.6328668594 --1.70499908924,2.07765483856,-10.4863166809 --1.64985525608,2.04774332047,-10.352766037 --1.61281371117,2.03977274895,-10.3222074509 --1.57174420357,2.02581787109,-10.2636461258 --1.54174435139,2.02782297134,-10.2750883102 --1.52271795273,2.0228407383,-10.2543077469 --1.48768293858,2.01586604118,-10.2307462692 --1.45567262173,2.0148768425,-10.2321968079 --1.41963255405,2.00790500641,-10.2036428452 --1.38660871983,2.0049238205,-10.1910820007 --1.35559880733,2.00393486023,-10.192522049 --1.3225736618,1.99995434284,-10.1789617538 --1.30455124378,1.99596977234,-10.1621837616 --1.2735439539,1.99597907066,-10.1666316986 --1.23850166798,1.98800826073,-10.1360721588 --1.20749056339,1.98701989651,-10.13651371 --1.17647767067,1.98603236675,-10.1349525452 --1.14244318008,1.98005723953,-10.1123981476 --1.11042404175,1.97807335854,-10.1048440933 --1.09541749954,1.9770796299,-10.104057312 --1.06138503551,1.97210347652,-10.0835123062 --1.03137505054,1.97111415863,-10.0849456787 --1.00036489964,1.9711253643,-10.0863933563 --0.967329382896,1.96515059471,-10.062833786 --0.936309456825,1.96316707134,-10.054268837 --0.907319188118,1.9661668539,-10.075717926 --0.889289200306,1.96118664742,-10.0519456863 --0.859283089638,1.96119534969,-10.057387352 --0.828266978264,1.96020972729,-10.0528306961 --0.796234548092,1.95523333549,-10.0322685242 --0.765218198299,1.95324790478,-10.0277137756 --0.736225247383,1.95624935627,-10.0461578369 --0.703180551529,1.94927990437,-10.0136022568 --0.688177883625,1.94928395748,-10.0168247223 --0.657148599625,1.94530570507,-9.99925804138 --0.626138031483,1.94431722164,-10.0007133484 --0.597132325172,1.94532561302,-10.0061435699 --0.564073085785,1.93536400795,-9.95958328247 --0.532037854195,1.92938899994,-9.93703269958 --0.50305223465,1.93438673019,-9.96248340607 --0.489056169987,1.93638730049,-9.97169685364 --0.458035618067,1.93440425396,-9.96314716339 --0.428020447493,1.93341827393,-9.95958614349 --0.398014396429,1.93442726135,-9.96503257751 --0.367994844913,1.93144357204,-9.95747089386 --0.33696809411,1.92846393585,-9.94291973114 --0.321965664625,1.92946815491,-9.946144104 --0.291947245598,1.92748391628,-9.93958377838 --0.261924624443,1.9245018959,-9.92902183533 --0.231927827001,1.92750597,-9.94347381592 --0.201913490891,1.92651963234,-9.94091796875 --0.171891048551,1.92453753948,-9.93035888672 --0.14187887311,1.92455005646,-9.92980480194 --0.126862704754,1.92156171799,-9.92002391815 --0.096835963428,1.91858208179,-9.90546607971 --0.066814340651,1.91659963131,-9.89591121674 --0.0378326252103,1.92259550095,-9.92434978485 --0.00780455349013,1.91861665249,-9.9087934494 --0.000215809282963,1.90636217594,-9.06205558777 -0.0297744441777,1.90134811401,-9.04244709015 -0.0437631681561,1.89833784103,-9.02663230896 -0.0737683698535,1.89733183384,-9.02102375031 -0.103783942759,1.89833140373,-9.02541351318 -0.144637033343,1.86423993111,-8.86900234222 -0.173642262816,1.86323440075,-8.8633890152 -0.202644333243,1.86122703552,-8.85477733612 -0.216635420918,1.85821807384,-8.84097003937 -0.246660605073,1.86122298241,-8.85436153412 -0.274647086859,1.85620737076,-8.8307466507 -0.303657501936,1.85620450974,-8.83013343811 -0.332653731108,1.85319411755,-8.81552886963 -0.361666381359,1.85419237614,-8.81691455841 -0.389672368765,1.85318756104,-8.81229114532 -0.40467736125,1.85318589211,-8.81149196625 -0.432665139437,1.84817123413,-8.7888841629 -0.461677849293,1.84916949272,-8.79027080536 -0.491709828377,1.85317838192,-8.81065273285 -0.519699931145,1.84916472435,-8.79004573822 -0.547695100307,1.84615397453,-8.77443599701 -0.5767146945,1.84815633297,-8.78281497955 -0.589698076248,1.84414350986,-8.76101207733 -0.618711471558,1.84414255619,-8.76339817047 -0.645698666573,1.84012770653,-8.73978614807 -0.674700379372,1.8381203413,-8.73018741608 -0.701690554619,1.83410716057,-8.70957565308 -0.731721520424,1.83911538124,-8.72895526886 -0.745718300343,1.83710968494,-8.72015476227 -0.771695375443,1.83008980751,-8.68655014038 -0.801724255085,1.83409690857,-8.7039308548 -0.829723894596,1.83208870888,-8.69232368469 -0.857728421688,1.83108317852,-8.68571090698 -0.885730266571,1.83007609844,-8.67610359192 -0.912726640701,1.82706654072,-8.66149139404 -0.927740514278,1.82906973362,-8.66967964172 -0.954738080502,1.82706081867,-8.65606689453 -0.983745038509,1.8260563612,-8.6514673233 -1.01074743271,1.82504999638,-8.64284610748 -1.03975760937,1.82604718208,-8.64124011993 -1.06574702263,1.82103419304,-8.61963272095 -1.09274578094,1.81902587414,-8.60702133179 -1.10775208473,1.8200250864,-8.60722351074 -1.13475096226,1.81801664829,-8.59461402893 -1.162758708,1.81801307201,-8.59099960327 -1.18875336647,1.81500291824,-8.57438659668 -1.21575140953,1.81299412251,-8.56078052521 -1.24375545979,1.81198859215,-8.55317783356 -1.27176344395,1.81198501587,-8.54956531525 -1.28576743603,1.81198334694,-8.54776000977 -1.31176018715,1.80797219276,-8.52915477753 -1.33775627613,1.80596268177,-8.51354503632 -1.36777722836,1.80896580219,-8.52293014526 -1.39075255394,1.80194592476,-8.48633098602 -1.41976940632,1.80394697189,-8.49171352386 -1.44476127625,1.7999355793,-8.47210216522 -1.45775949955,1.79893100262,-8.46430015564 -1.48777663708,1.80093204975,-8.46969509125 -1.5147818327,1.80092728138,-8.46307945251 -1.54077637196,1.79791712761,-8.44548034668 -1.56979298592,1.79991829395,-8.45086097717 -1.59679460526,1.7989115715,-8.44025707245 -1.63277697563,1.79189217091,-8.40484714508 -1.6567646265,1.78787875175,-8.38024616241 -1.68477201462,1.78787505627,-8.37564277649 -1.70876169205,1.78386282921,-8.35303783417 -1.7357686758,1.78385925293,-8.34842205048 -1.76478135586,1.7858581543,-8.34881687164 -1.77677571774,1.78385186195,-8.33701705933 -1.80076920986,1.78084158897,-8.31840419769 -1.83279800415,1.78584873676,-8.33578681946 -1.85477995872,1.77983272076,-8.30518627167 -1.88078057766,1.77882611752,-8.29358005524 -1.90878903866,1.77882313728,-8.28997516632 -1.93278264999,1.77581310272,-8.27136611938 -1.94678604603,1.77581119537,-8.26856708527 -1.96877038479,1.7707965374,-8.23996734619 -1.99477481842,1.77079188824,-8.23235034943 -2.02278232574,1.77078866959,-8.2277507782 -2.05179595947,1.772788167,-8.22914218903 -2.07378220558,1.76777470112,-8.20254135132 -2.09978604317,1.76776957512,-8.19392871857 -2.11479330063,1.76876974106,-8.19512939453 -2.13778614998,1.76575958729,-8.17551803589 -2.16178131104,1.76275038719,-8.15791416168 -2.19480776787,1.76775598526,-8.17230987549 -2.22081303596,1.76775205135,-8.16569137573 -2.24580955505,1.76574349403,-8.14909744263 -2.27482318878,1.76774311066,-8.15048885345 -2.28381276131,1.76473498344,-8.13367843628 -2.30981492996,1.76372933388,-8.12307739258 -2.3388273716,1.76472842693,-8.12347126007 -2.36182165146,1.76271915436,-8.10486221313 -2.39083266258,1.76371765137,-8.10326480865 -2.4188439846,1.7647163868,-8.10264778137 -2.44083309174,1.76170444489,-8.07805347443 -2.44681429863,1.75669252872,-8.05224704742 -2.48184466362,1.76269996166,-8.07064247131 -2.50684714317,1.76169478893,-8.06102466583 -2.53285121918,1.76169013977,-8.05241680145 -2.56286525726,1.76369011402,-8.05381774902 -2.58485770226,1.76068019867,-8.03320980072 -2.59785842896,1.75967717171,-8.02741241455 -2.62285995483,1.75967133045,-8.01580429077 -2.64785933495,1.75766468048,-8.00220775604 -2.67386364937,1.75766015053,-7.9936003685 -2.70287585258,1.7596591711,-7.99299573898 -2.72186017036,1.75464558601,-7.96339464188 -2.74886798859,1.75564301014,-7.95878219604 -2.76487898827,1.75764489174,-7.96397304535 -2.78787493706,1.75563669205,-7.94637060165 -2.81187200546,1.75362873077,-7.92977714539 -2.83988213539,1.75462710857,-7.92716789246 -2.87591362,1.76163518429,-7.94754886627 -2.89590287209,1.75762414932,-7.9229426384 -2.9259159565,1.75962364674,-7.92334270477 -2.93691396713,1.75961959362,-7.91453552246 -2.97093749046,1.76362395287,-7.92593193054 -2.98691701889,1.75760865211,-7.8913269043 -3.01492476463,1.75860583782,-7.88573122025 -3.04293394089,1.75960361958,-7.88212490082 -3.07996726036,1.76761257648,-7.90449523926 -3.10095787048,1.76360213757,-7.88090324402 -3.11396074295,1.76460027695,-7.87709522247 -3.14397382736,1.76659989357,-7.87749099731 -3.16897559166,1.76559460163,-7.8658862114 -3.19698405266,1.76759207249,-7.86128139496 -3.22198581696,1.76658678055,-7.84967756271 -3.25199961662,1.76958692074,-7.85106420517 -3.28000664711,1.77058374882,-7.84446954727 -3.2930085659,1.77058148384,-7.83966779709 -3.32603001595,1.77458524704,-7.85004091263 -3.34802484512,1.77257680893,-7.83044195175 -3.38104367256,1.77657878399,-7.83683538437 -3.41105651855,1.77857863903,-7.83722400665 -3.43305134773,1.77657008171,-7.81762552261 -3.44605326653,1.77656793594,-7.81282377243 -3.48308110237,1.78357410431,-7.82920455933 -3.50707864761,1.7815669775,-7.81261491776 -3.54811477661,1.7905766964,-7.83798837662 -3.57512116432,1.79157364368,-7.83137512207 -3.58208417892,1.78055143356,-7.77680158615 -3.60608386993,1.78054523468,-7.76220035553 -3.62109017372,1.78154504299,-7.76239204407 -3.6511015892,1.78354418278,-7.76078701019 -3.67109370232,1.78053486347,-7.73818635941 -3.69709682465,1.78053033352,-7.72758626938 -3.72109627724,1.78052389622,-7.71199274063 -3.74108910561,1.77751517296,-7.69038772583 -3.7751095295,1.78251802921,-7.69876718521 -3.77708983421,1.77650678158,-7.66998052597 -3.80810308456,1.77950656414,-7.67037296295 -3.83009958267,1.77849924564,-7.65177536011 -3.85610365868,1.77849531174,-7.64217042923 -3.88110589981,1.77849054337,-7.63056468964 -3.90911316872,1.77948772907,-7.62396383286 -3.9351170063,1.78048348427,-7.61336421967 -3.93509578705,1.77447164059,-7.58257389069 -3.96510720253,1.77647078037,-7.58096456528 -3.98710370064,1.77546370029,-7.56236982346 -4.01811599731,1.77846324444,-7.5617647171 -4.04412126541,1.77845990658,-7.55315113068 -4.08214569092,1.78446424007,-7.56554031372 -4.09512710571,1.77945077419,-7.52995347977 -4.12215232849,1.78545856476,-7.55114078522 -4.13713884354,1.78144741058,-7.52153778076 -4.15913677216,1.78044080734,-7.50393724442 -4.18814468384,1.78243863583,-7.4983382225 -4.2141494751,1.78343498707,-7.48872995377 -4.23814964294,1.78242945671,-7.47413349152 -4.26415300369,1.78342521191,-7.46253967285 -4.27715539932,1.78342342377,-7.45773553848 -4.30215835571,1.78341913223,-7.44612932205 -4.3281621933,1.78441512585,-7.43552780151 -4.35616922379,1.78541266918,-7.42892074585 -4.3851776123,1.7884105444,-7.4233174324 -4.41218233109,1.78840708733,-7.41371917725 -4.42818975449,1.79040706158,-7.41391277313 -4.45419359207,1.79140329361,-7.40330886841 -4.47619199753,1.79039728642,-7.38670253754 -4.50820350647,1.79339635372,-7.38410949707 -4.54121828079,1.79739665985,-7.38549757004 -4.57022619247,1.79939460754,-7.37988901138 -4.59122371674,1.79838812351,-7.36128520966 -4.5912065506,1.79337882996,-7.33449411392 -4.61921310425,1.79437601566,-7.32688951492 -4.64020967484,1.79336929321,-7.30729484558 -4.67722845078,1.79837107658,-7.31269407272 -4.7012295723,1.79836642742,-7.29908752441 -4.73123931885,1.80136489868,-7.29448032379 -4.75523948669,1.80135989189,-7.27988100052 -4.77324867249,1.8033605814,-7.2820763588 -4.79424476624,1.80235385895,-7.26248168945 -4.83526945114,1.80935811996,-7.2748632431 -4.8542637825,1.80735075474,-7.25326108932 -4.8892788887,1.81135129929,-7.25465869904 -4.91127634048,1.81034505367,-7.23606681824 -4.93728017807,1.8113411665,-7.2244644165 -4.95028209686,1.81233918667,-7.2186627388 -4.97328233719,1.81233406067,-7.2030582428 -4.99828386307,1.81232964993,-7.18946075439 -5.01727867126,1.81032264233,-7.16786003113 -5.04328203201,1.81131863594,-7.15526533127 -5.06427955627,1.81031250954,-7.13666391373 -5.07928419113,1.81231164932,-7.13385915756 -5.10528707504,1.81230759621,-7.12126398087 -5.14030122757,1.81730782986,-7.12165975571 -5.17030954361,1.81930577755,-7.11505699158 -5.19030618668,1.81829929352,-7.09446048737 -5.21931314468,1.82029688358,-7.08685398102 -5.24431562424,1.82129299641,-7.07424449921 -5.25931930542,1.82229173183,-7.0704460144 -5.27230739594,1.81828224659,-7.03985834122 -5.30932426453,1.82328343391,-7.04324388504 -5.32331323624,1.82027423382,-7.01365947723 -5.34330940247,1.81926810741,-6.99306488037 -5.37431907654,1.82226634026,-6.98745918274 -5.39932060242,1.82226228714,-6.97385787964 -5.42433595657,1.82726502419,-6.98305225372 -5.44833660126,1.82726037502,-6.96745634079 -5.47133636475,1.82725548744,-6.95085763931 -5.49734020233,1.82925188541,-6.9382557869 -5.53235387802,1.83325171471,-6.93764400482 -5.54934644699,1.83124411106,-6.91206073761 -5.57935428619,1.83324193954,-6.90445613861 -5.59836292267,1.83624267578,-6.90664148331 -5.62436580658,1.8372387886,-6.89304637909 -5.6563744545,1.84023714066,-6.88744211197 -5.67737340927,1.84023177624,-6.8688378334 -5.71338653564,1.84523165226,-6.86822795868 -5.75640678406,1.85123360157,-6.87462615967 -5.75639486313,1.84822702408,-6.85183668137 -5.78139638901,1.84822285175,-6.83723640442 -5.80339574814,1.84821784496,-6.81963300705 -5.82239151001,1.84721159935,-6.79704380035 -5.84439086914,1.84720671177,-6.77944040298 -5.84336662292,1.83919370174,-6.73287010193 -5.70220470428,1.78513431549,-6.52041435242 -5.70519733429,1.78212952614,-6.5026216507 -5.7191901207,1.78012263775,-6.47603416443 -5.73418331146,1.77811598778,-6.45044898987 -5.75518321991,1.77811157703,-6.4328494072 -5.75616407394,1.7711006403,-6.39127588272 -5.76415205002,1.76709222794,-6.35868930817 -5.78515195847,1.76708805561,-6.34109258652 -5.77613401413,1.7600799799,-6.31030893326 -5.78512334824,1.75707232952,-6.27971696854 -5.80612325668,1.75706791878,-6.26113271713 -5.81110906601,1.75105929375,-6.22654294968 -5.83010816574,1.75105476379,-6.20694875717 -5.84410238266,1.74904870987,-6.18136405945 -5.85008955002,1.7440404892,-6.14777898788 -5.85608577728,1.74303722382,-6.13398742676 -5.87908887863,1.7440341711,-6.1193857193 -5.88107299805,1.73802483082,-6.08081483841 -5.88906240463,1.73401772976,-6.05022478104 -5.91106462479,1.73501455784,-6.03462457657 -5.9130487442,1.72900545597,-5.99605941772 -5.92704486847,1.72800028324,-5.97246170044 -5.93304157257,1.72599744797,-5.95966386795 -5.94703769684,1.72499203682,-5.93507862091 -5.95002412796,1.71998429298,-5.90048742294 -5.97502851486,1.72098183632,-5.88689899445 -5.97701454163,1.71597361565,-5.85032272339 -5.98800849915,1.71296799183,-5.8237323761 -6.01201200485,1.71496534348,-5.80914497375 -6.00299787521,1.70895934105,-5.78235006332 -6.02900362015,1.71095740795,-5.77075052261 -6.04199886322,1.70895218849,-5.74517250061 -6.04198503494,1.70394444466,-5.7085852623 -6.05197811127,1.70093858242,-5.68001270294 -6.07197999954,1.7009357214,-5.66340875626 -6.06997108459,1.69793128967,-5.64262485504 -6.08296728134,1.69592678547,-5.61902999878 -6.10597133636,1.6969243288,-5.6044344902 -6.10595798492,1.6919169426,-5.56785678864 -6.11595153809,1.68891179562,-5.54027938843 -6.13995695114,1.69090986252,-5.52767133713 -6.14594841003,1.68690371513,-5.49610137939 -6.14694309235,1.68490076065,-5.48029661179 -6.17094802856,1.68689870834,-5.46670055389 -6.16693210602,1.67989087105,-5.42613935471 -6.1759262085,1.67788612843,-5.39954614639 -6.20093250275,1.67988443375,-5.38694858551 -6.20392274857,1.67587852478,-5.354367733 -6.21792078018,1.67387473583,-5.33177995682 -6.2179145813,1.67187142372,-5.31399440765 -6.21790313721,1.66686522961,-5.27941226959 -6.22789907455,1.66486096382,-5.25382328033 -6.24590015411,1.6648581028,-5.23424196243 -6.25089263916,1.66085314751,-5.20465421677 -6.26389074326,1.65984964371,-5.18206071854 -6.27589321136,1.66084861755,-5.17427539825 -6.27488183975,1.65584266186,-5.13969326019 -6.27687311172,1.65183746815,-5.10810518265 -6.28987121582,1.64983403683,-5.08452796936 -6.30687236786,1.64983141422,-5.06493997574 -6.31186580658,1.64682674408,-5.03536081314 -6.32486438751,1.64582371712,-5.01375961304 -6.32185792923,1.64282059669,-4.99398088455 -6.33785867691,1.6428180933,-4.97438526154 -6.34985685349,1.64181482792,-4.95080184937 -6.35284948349,1.63781023026,-4.92022180557 -6.36284685135,1.63580679893,-4.89563369751 -6.37084293365,1.6338031292,-4.86905288696 -6.38684368134,1.63380086422,-4.84945964813 -6.39484453201,1.63379967213,-4.83966302872 -6.40484189987,1.63179647923,-4.81507778168 -6.4098367691,1.62879264355,-4.78649759293 -6.41483163834,1.62578892708,-4.75890636444 -6.42683076859,1.62478625774,-4.73532915115 -6.438829422,1.6237834692,-4.71273994446 -6.45583200455,1.62378156185,-4.69414567947 -6.44982481003,1.62077867985,-4.67336416245 -6.46882772446,1.62077701092,-4.65577602386 -6.47782564163,1.61977422237,-4.63118696213 -6.48882436752,1.61777150631,-4.60760450363 -6.49482107162,1.61576843262,-4.58101606369 -6.50882148743,1.61476624012,-4.55943584442 -6.5178194046,1.61376357079,-4.53484964371 -6.52381944656,1.61276245117,-4.52405118942 -6.5248131752,1.60975897312,-4.49347448349 -6.52480649948,1.60575544834,-4.462890625 -6.53880786896,1.60475337505,-4.44131326675 -6.54980754852,1.60475122929,-4.41872215271 -6.56480979919,1.60474956036,-4.39912700653 -6.55980348587,1.60074734688,-4.37935447693 -6.56780195236,1.59974503517,-4.35476541519 -6.58180332184,1.59974336624,-4.33417606354 -6.59480428696,1.59874165058,-4.31259250641 -6.59880113602,1.595739007,-4.28501224518 -6.60980081558,1.59473705292,-4.26242494583 -6.61379766464,1.59273469448,-4.23583316803 -6.61479520798,1.59073328972,-4.22105026245 -6.61779212952,1.58773076534,-4.19247913361 -6.63279438019,1.58872961998,-4.17387342453 -6.63779211044,1.58572733402,-4.14630794525 -6.6497926712,1.5857257843,-4.12471914291 -6.65078878403,1.58172345161,-4.09613609314 -6.66579151154,1.58272230625,-4.07654476166 -6.66078662872,1.57972061634,-4.05875730515 -6.66478443146,1.57671868801,-4.03217458725 -6.67678594589,1.5767172575,-4.00960206985 -6.68178367615,1.57471561432,-3.98401474953 -6.6917848587,1.57371425629,-3.96142745018 -6.69678354263,1.5717124939,-3.93584179878 -6.70478343964,1.57071125507,-3.9122531414 -6.70378065109,1.56771016121,-3.89647626877 -6.7117805481,1.56670880318,-3.87288880348 -6.71677970886,1.56470727921,-3.84730672836 -6.73778533936,1.56670689583,-3.83072400093 -6.7457857132,1.56570577621,-3.80713844299 -6.74478244781,1.5627040863,-3.77855348587 -6.74978303909,1.56170344353,-3.76676988602 -6.75878381729,1.56070256233,-3.74417901039 -6.76978588104,1.56070172787,-3.72258973122 -6.77078342438,1.55770039558,-3.69501042366 -6.77978420258,1.55669939518,-3.67143630981 -6.78878593445,1.55569863319,-3.64884757996 -6.798787117,1.55569791794,-3.6272521019 -6.79978656769,1.55469727516,-3.61346817017 -6.82079267502,1.5566971302,-3.5968837738 -6.81978988647,1.55269598961,-3.5683093071 -6.83279323578,1.5536955595,-3.54870796204 -6.8467965126,1.55369508266,-3.5281291008 -6.84479427338,1.55069410801,-3.49954986572 -6.85479640961,1.54969358444,-3.47795677185 -6.8698015213,1.55269384384,-3.47215938568 -6.86979961395,1.5496929884,-3.44359731674 -6.86679649353,1.54569208622,-3.41501498222 -6.88880395889,1.5486921072,-3.3994204998 -6.87979888916,1.54369115829,-3.36784148216 -6.88980150223,1.54269099236,-3.34526610374 -6.90780687332,1.54469096661,-3.32767176628 -6.89480161667,1.53969037533,-3.30690002441 -6.90580415726,1.53969025612,-3.28630208969 -6.92080926895,1.54069030285,-3.26671695709 -6.91880702972,1.53768980503,-3.23913455009 -6.91980743408,1.53568959236,-3.21255922318 -6.94481515884,1.53868985176,-3.19796729088 -6.93781232834,1.53568971157,-3.18118214607 -6.93981266022,1.5336894989,-3.15560030937 -6.95781850815,1.53568983078,-3.13702058792 -6.94681453705,1.53068935871,-3.10544466972 -6.94581365585,1.52768945694,-3.07787680626 -6.96682071686,1.52968990803,-3.06128692627 -6.95581674576,1.52468979359,-3.03070044518 -6.96782112122,1.52669000626,-3.02290701866 -6.97782421112,1.52669024467,-3.00132107735 -6.97382354736,1.52369046211,-2.97275328636 -6.97582435608,1.52069079876,-2.94717955589 -6.99983263016,1.52469134331,-2.93257498741 -6.9848279953,1.51869153976,-2.90000247955 -6.99983358383,1.51969218254,-2.8804192543 -7.0068359375,1.52069234848,-2.87062382698 -7.00083494186,1.51669287682,-2.84204959869 -7.01383972168,1.51769351959,-2.82146930695 -7.03484678268,1.51969408989,-2.804874897 -7.02984619141,1.51669466496,-2.77729344368 -7.03684902191,1.51569533348,-2.75470781326 -7.04485273361,1.51569604874,-2.73212838173 -7.03685092926,1.51269650459,-2.71535420418 -7.04685497284,1.51269733906,-2.69377160072 -7.06686258316,1.51569795609,-2.67618465424 -7.06286239624,1.51269900799,-2.64959907532 -7.06286382675,1.5106998682,-2.62402224541 -7.07386875153,1.51070070267,-2.60343003273 -7.07086801529,1.50870120525,-2.58964109421 -7.0818734169,1.50970220566,-2.56806492805 -7.09287834167,1.50970315933,-2.54648923874 -7.09087944031,1.50770437717,-2.52090406418 -7.10088396072,1.50770545006,-2.49932265282 -7.1078877449,1.50770652294,-2.47674059868 -7.10388851166,1.50470781326,-2.45016336441 -7.11289215088,1.50570821762,-2.44136214256 -7.1198964119,1.50570940971,-2.41878080368 -7.12289905548,1.50371086597,-2.39421153069 -7.12190103531,1.50171232224,-2.3696205616 -7.13590717316,1.50271332264,-2.34904503822 -7.13791036606,1.50171482563,-2.3254544735 -7.1109046936,1.49471640587,-2.30269432068 -7.10190486908,1.49071824551,-2.2751159668 -7.15792179108,1.5017182827,-2.26951003075 -7.13691902161,1.49472057819,-2.23793649673 -7.14492416382,1.49472212791,-2.21536374092 -7.16693210602,1.4987231493,-2.19876098633 -7.17093610764,1.4977247715,-2.17518424988 -7.16593647003,1.49572587013,-2.1613945961 -7.16794013977,1.49472773075,-2.13682579994 -7.17494440079,1.49472928047,-2.11523127556 -7.17894887924,1.49373114109,-2.09165644646 -7.1789522171,1.49173307419,-2.06707954407 -7.18395662308,1.49173498154,-2.04449319839 -7.200963974,1.49373626709,-2.02491259575 -7.14195251465,1.47973966599,-1.99514663219 -7.15095853806,1.47974145412,-1.97356545925 -7.14896154404,1.47774386406,-1.94800198078 -7.17597103119,1.48274493217,-1.93239974976 -7.19297838211,1.48474657536,-1.9128190279 -7.16897726059,1.47774982452,-1.88224411011 -7.15897941589,1.47375273705,-1.85468280315 -7.19798946381,1.481752038,-1.85387063026 -7.19499254227,1.47975456715,-1.82928800583 -7.18899536133,1.47675728798,-1.8037109375 -7.16999673843,1.47176086903,-1.77414941788 -7.18100261688,1.4727627039,-1.7535598278 -7.17900705338,1.47076547146,-1.72898590565 -7.15800523758,1.46576797962,-1.71121287346 -7.13400506973,1.45877206326,-1.68065726757 -7.166015625,1.46477282047,-1.66604912281 -7.1000084877,1.44877934456,-1.62550604343 -7.15002202988,1.45777928829,-1.6148982048 -7.13702487946,1.45378303528,-1.58734083176 -7.14203071594,1.45378553867,-1.56574833393 -7.14503383636,1.45378684998,-1.55495417118 -7.10703229904,1.44479215145,-1.52141308784 -7.09703588486,1.44079577923,-1.49583911896 -7.05703401566,1.4308013916,-1.46328163147 -7.05103874207,1.42880487442,-1.43870925903 -7.02403974533,1.42180967331,-1.41013491154 -7.02904653549,1.42181265354,-1.3885512352 -7.02204799652,1.41881477833,-1.37478065491 -6.98904848099,1.41082036495,-1.34521055222 -6.97305250168,1.40582478046,-1.31864893436 -6.91104841232,1.39183247089,-1.28309810162 -6.93505859375,1.39583432674,-1.26551270485 -7.01007604599,1.41083264351,-1.25889062881 -6.98407840729,1.40483796597,-1.2313195467 -6.9230723381,1.39084410667,-1.20756566525 -6.89307403564,1.38285005093,-1.17900907993 -6.94908905029,1.3948495388,-1.16839039326 -6.91509103775,1.38585579395,-1.13884329796 -6.94910240173,1.39285707474,-1.123244524 -6.93510723114,1.3888617754,-1.09866833687 -6.8951048851,1.37986683846,-1.07990539074 -6.84610509872,1.36787450314,-1.04836475849 -6.9321231842,1.38587152958,-1.04272437096 -6.96113443375,1.39087319374,-1.02514159679 -6.92913722992,1.38287973404,-0.997578203678 -6.93414497375,1.38388311863,-0.976985394955 -6.9231505394,1.37988817692,-0.952426612377 -6.92515420914,1.37989008427,-0.941638767719 -6.91315984726,1.37689507008,-0.918060541153 -6.91316699982,1.37589895725,-0.896475970745 -6.93917751312,1.38090085983,-0.878878831863 -6.91618204117,1.37490701675,-0.853315293789 -6.92319059372,1.37591063976,-0.831747710705 -6.9091963768,1.37191617489,-0.808170974255 -6.88919830322,1.36791992188,-0.794392287731 -6.93521118164,1.37692022324,-0.778796374798 -6.96922206879,1.38392138481,-0.762189209461 -6.93922662735,1.37692844868,-0.735638201237 -6.89422988892,1.36593687534,-0.708080887794 -6.87723588943,1.36194288731,-0.684506475925 -6.91724777222,1.36994361877,-0.667907357216 -6.83924388885,1.35295307636,-0.647164702415 -6.88425636292,1.36195337772,-0.631554543972 -6.87726402283,1.35995852947,-0.608983576298 -6.83926820755,1.35096669197,-0.583419680595 -6.81827449799,1.34597325325,-0.559849560261 -6.79728126526,1.34097993374,-0.536282241344 -6.80428600311,1.3419816494,-0.526487886906 -6.77229166031,1.33498942852,-0.501926720142 -6.73729753494,1.32699763775,-0.477365493774 -6.782310009,1.33599805832,-0.460762709379 -6.77831792831,1.3350032568,-0.439187765121 -6.78032684326,1.33500802517,-0.417621195316 -6.833340168,1.34600758553,-0.401017785072 -6.87134695053,1.35400593281,-0.394197791815 -6.82635259628,1.34301555157,-0.368652522564 -6.78535842896,1.33402478695,-0.344097226858 -6.80436897278,1.33802771568,-0.324508219957 -6.77137565613,1.33003616333,-0.300947725773 -6.77038431168,1.33004117012,-0.280359864235 -6.80339574814,1.33704280853,-0.261760592461 -6.74539661407,1.32405161858,-0.24700987339 -6.74940633774,1.32505619526,-0.226427853107 -6.8284201622,1.34105265141,-0.21079672873 -6.75142478943,1.32506620884,-0.185259431601 -6.75343418121,1.32507133484,-0.163695633411 -6.78544521332,1.33107292652,-0.145086973906 -6.75345277786,1.32408177853,-0.122526600957 -6.76145792007,1.32608342171,-0.112727507949 -6.7744679451,1.32808721066,-0.0921470746398 -6.77147817612,1.3280929327,-0.070580303669 -6.81748962402,1.33709287643,-0.051965188235 -6.77949714661,1.32910263538,-0.0294112470001 -6.77550697327,1.32810854912,-0.00784516707063 -6.76851081848,1.32611191273,0.00195755180903 -6.79652261734,1.33211421967,0.0225425679237 -6.79553222656,1.33211958408,0.0431289151311 -6.82254314423,1.33812177181,0.0637187808752 -6.61654472351,1.29315185547,0.0881879255176 -6.57955408096,1.28516173363,0.108754046261 -6.64456653595,1.29915952682,0.128366991878 -6.77557563782,1.32714676857,0.138210177422 -6.74458503723,1.3201559782,0.158782362938 -6.73659563065,1.31916284561,0.180341929197 -6.72060489655,1.3151704073,0.200915768743 -6.78361701965,1.32916820049,0.221534475684 -6.82862854004,1.33816838264,0.243129119277 -6.82263326645,1.3371720314,0.253909289837 -6.80064296722,1.33318042755,0.274480819702 -7.19166183472,1.41713726521,0.302244871855 -6.74166202545,1.32019901276,0.314622372389 -6.70467233658,1.31220960617,0.335170984268 -6.66268205643,1.30322086811,0.354730069637 -6.65069198608,1.30122816563,0.374315828085 -6.71269893646,1.3142234087,0.387121528387 -6.76071023941,1.32522308826,0.409718066454 -6.74472045898,1.32123088837,0.429302871227 -6.77573156357,1.32823288441,0.45188587904 -6.68874120712,1.30925011635,0.46843546629 -6.73675298691,1.32024991512,0.49202272296 -6.78276395798,1.33024966717,0.514632880688 -6.78576946259,1.3312523365,0.525420606136 -6.81977987289,1.33825385571,0.548019587994 -6.83279132843,1.34125828743,0.570589661598 -6.8198018074,1.33926582336,0.590177476406 -6.90281295776,1.35726082325,0.61679071188 -6.90082359314,1.35726726055,0.638361811638 -6.7658290863,1.32828819752,0.639101922512 -6.74684095383,1.32429718971,0.659652411938 -6.52685308456,1.27733302116,0.663149118423 -6.56486415863,1.2863342762,0.686737179756 -6.63087511063,1.30033147335,0.712348043919 -6.7478852272,1.32632172108,0.742976605892 -6.77789640427,1.33332383633,0.766568720341 -6.75190210342,1.32733035088,0.77435451746 -6.766913414,1.33133471012,0.796935796738 -6.74792528152,1.32734370232,0.816498875618 -6.76293611526,1.33134794235,0.839082241058 -6.68594932556,1.31536495686,0.851639389992 -6.65396165848,1.30837583542,0.869201600552 -6.75697135925,1.33136796951,0.901811897755 -6.75197696686,1.33037173748,0.911602795124 -6.75798845291,1.33237731457,0.933187425137 -6.73200130463,1.32738757133,0.951744914055 -6.73301267624,1.32839369774,0.972335398197 -6.69602489471,1.32040548325,0.988896727562 -6.62903881073,1.30642175674,1.00144541264 -6.60405158997,1.30143201351,1.01901233196 -6.62605714798,1.30643200874,1.03181970119 -6.62906885147,1.30743825436,1.05339157581 -6.60708189011,1.30344808102,1.07096505165 -6.61509418488,1.30645382404,1.09353327751 -6.5991063118,1.30346250534,1.11112344265 -6.59411907196,1.30247008801,1.13168895245 -6.63912296295,1.31246674061,1.14850234985 -6.66113471985,1.31847023964,1.17308402061 -6.65614700317,1.3174778223,1.19365358353 -6.63216018677,1.31348800659,1.21023499966 -6.66317129135,1.32049024105,1.23681426048 -6.65018415451,1.31849884987,1.25539445877 -6.67419528961,1.32450199127,1.27999293804 -6.67420148849,1.32550537586,1.2907782793 -6.66721439362,1.32451355457,1.31134188175 -6.66522693634,1.32452058792,1.33192431927 -6.64624023438,1.32153022289,1.34949910641 -6.60225534439,1.31254398823,1.36305093765 -6.59426832199,1.31155216694,1.38262569904 -6.62527942657,1.31955432892,1.40922307968 -6.58928728104,1.3115632534,1.41299629211 -6.5873003006,1.31257045269,1.43357598782 -6.63531017303,1.32357013226,1.46417284012 -6.62732362747,1.32257831097,1.48374962807 -6.61533641815,1.32058703899,1.50232791901 -6.6173491478,1.32259380817,1.52390909195 -6.56335926056,1.3106058836,1.52366876602 -6.57237100601,1.31361150742,1.54625964165 -6.59138298035,1.31861567497,1.571839571 -6.61939477921,1.32561838627,1.59942531586 -6.60640859604,1.32462763786,1.61799752712 -6.64441823959,1.33362865448,1.64759755135 -6.67442989349,1.34163105488,1.67618405819 -6.62643957138,1.33064222336,1.67595434189 -6.69944763184,1.34863781929,1.71456098557 -6.67746162415,1.34464848042,1.7311309576 -6.60748004913,1.33066678047,1.73568975925 -6.60049438477,1.32967543602,1.75625145435 -6.59450769424,1.32968342304,1.77583742142 -6.61551904678,1.33568716049,1.80242872238 -6.58852767944,1.32969522476,1.80621254444 -6.38055753708,1.28473651409,1.77569317818 -6.46856451035,1.3057295084,1.81930696964 -6.42358160019,1.29674434662,1.82886719704 -6.40159606934,1.29275500774,1.84345245361 -6.42960834503,1.30075824261,1.87302327156 -6.46961832047,1.31075894833,1.90462744236 -6.43862724304,1.30476748943,1.90641379356 -6.4826374054,1.31576776505,1.94000756741 -6.50864934921,1.3227711916,1.96958112717 -6.51966142654,1.32577681541,1.99416732788 -6.53667402267,1.33078145981,2.02075266838 -6.45969438553,1.3158018589,2.02030110359 -6.47769975662,1.31980252266,2.03610181808 -6.4827132225,1.32280933857,2.05967450142 -6.46372842789,1.31982004642,2.07525539398 -6.4427447319,1.31583106518,2.09082221985 -6.4407582283,1.31683886051,2.11140966415 -6.46477031708,1.32384264469,2.14098882675 -6.38179206848,1.30686414242,2.13654375076 -6.34480333328,1.2988743782,2.13630771637 -6.47880363464,1.33085918427,2.19994425774 -6.40482521057,1.31587958336,2.19849014282 -6.49682998657,1.33787167072,2.25010323524 -6.51684188843,1.3438757658,2.27869153023 -6.54385280609,1.35087859631,2.3092918396 -6.55685853958,1.35488045216,2.32508111 -6.5818696022,1.36188364029,2.35567450523 -6.53788900375,1.35389924049,2.36422038078 -6.50990581512,1.34891164303,2.37679457664 -6.55291509628,1.35991215706,2.41438508034 -6.55392932892,1.36191952229,2.43697190285 -6.5459446907,1.36192893982,2.45753526688 -6.51895475388,1.35693752766,2.45931410789 -6.47897338867,1.34895205498,2.46689152718 -6.46198987961,1.34696292877,2.48346114159 -6.4330072403,1.34197568893,2.4950363636 -6.4240231514,1.34198522568,2.5146048069 -6.39604139328,1.33699822426,2.52716445923 -6.43804979324,1.34799849987,2.56477165222 -6.52404689789,1.36898732185,2.60859394073 -6.50306415558,1.3659992218,2.62415480614 -6.60506629944,1.39098918438,2.68676638603 -6.59308242798,1.38999903202,2.7053437233 -6.53310346603,1.37801754475,2.7049062252 -6.58311223984,1.39101684093,2.74849462509 -6.57612800598,1.39202582836,2.76907348633 -6.59613227844,1.39702630043,2.78887033463 -6.53015518188,1.38404595852,2.78543114662 -6.5661649704,1.39404773712,2.82401633263 -6.58917713165,1.40205156803,2.8575963974 -6.71017551422,1.43203783035,2.93122959137 -6.53021383286,1.39207804203,2.87974619865 -6.55521821976,1.39907777309,2.90253782272 -6.55923223495,1.40208494663,2.92811775208 -6.54124975204,1.39909648895,2.94468379021 -6.52026700974,1.39710819721,2.95925974846 -6.50428390503,1.39511907101,2.97583889961 -6.51629734039,1.40012514591,3.00541567802 -6.54330825806,1.40812826157,3.0410118103 -6.4763250351,1.39414477348,3.02376794815 -6.46234226227,1.39215540886,3.04134392738 -6.46735620499,1.39616274834,3.06791949272 -6.49036836624,1.40316677094,3.10250663757 -6.47538518906,1.40217745304,3.11909365654 -6.44440460205,1.39719152451,3.12964916229 -6.45441818237,1.40219783783,3.15823745728 -6.46642398834,1.40519976616,3.17603087425 -6.42144584656,1.39721643925,3.17958593369 -6.42446041107,1.40022420883,3.20516848564 -6.45647096634,1.41022646427,3.24476289749 -6.52747535706,1.42922186852,3.30435824394 -6.47249889374,1.41824018955,3.30192518234 -6.45850849152,1.41624701023,3.30770516396 -6.4715218544,1.42225277424,3.33829975128 -6.41554546356,1.41127169132,3.33584928513 -6.41656112671,1.41327989101,3.36142349243 -6.46756839752,1.42827880383,3.41202259064 -6.47558307648,1.4332857132,3.44159889221 -6.51059293747,1.44428777695,3.48518538475 -6.51060009003,1.44529163837,3.49698996544 -6.34464120865,1.40733087063,3.4355199337 -6.4736366272,1.44131553173,3.52912783623 -6.35467100143,1.41534614563,3.49166679382 -6.38068199158,1.42334961891,3.53026175499 -6.44168806076,1.44134688377,3.58885383606 -6.44369602203,1.44335067272,3.60264587402 -6.44771051407,1.44635868073,3.63121533394 -6.43872785568,1.44736874104,3.65179681778 -6.43074464798,1.44837880135,3.67337155342 -6.41476249695,1.44639015198,3.68995285034 -6.39378166199,1.44440281391,3.70451951027 -6.38579893112,1.44541299343,3.72609424591 -6.3748087883,1.44441926479,3.73288011551 -6.36182641983,1.44343030453,3.75145554543 -6.35584306717,1.44444000721,3.77403354645 -6.365858078,1.45044696331,3.80660581589 -6.35687446594,1.45045721531,3.8271894455 -6.34789228439,1.45146763325,3.84875774384 -6.34490823746,1.45347642899,3.8723526001 -6.33091878891,1.45148348808,3.87713980675 -6.33193445206,1.45449209213,3.90471148491 -6.33694934845,1.45949983597,3.93429279327 -6.30997037888,1.45551383495,3.94485974312 -6.30298757553,1.45652377605,3.96743440628 -6.30000400543,1.45853304863,3.99201798439 -6.26902532578,1.45454764366,3.99958920479 -6.2800321579,1.45855021477,4.02037382126 -6.2770485878,1.46055960655,4.04594421387 -6.25306892395,1.45757293701,4.05752086639 -6.2440867424,1.45858359337,4.07909345627 -6.25010156631,1.46359109879,4.10968017578 -6.22912168503,1.46160376072,4.12325572968 -6.21213293076,1.45861160755,4.12603759766 -6.21714830399,1.46261942387,4.15661668777 -6.19316911697,1.45963287354,4.16819047928 -6.19218540192,1.46264195442,4.19477176666 -6.18420314789,1.46465241909,4.21734285355 -6.15822410583,1.46066617966,4.22692346573 -6.14324426651,1.460678339,4.24548196793 -6.14825105667,1.46368169785,4.26227903366 -6.13027095795,1.46269416809,4.27785158157 -6.1092915535,1.45970714092,4.29142141342 -6.10730838776,1.46271657944,4.31799793243 -6.08632850647,1.46072936058,4.33058214188 -6.0793466568,1.46273994446,4.35415124893 -6.07436418533,1.46474981308,4.37872743607 -6.05937576294,1.46275746822,4.38250827789 -6.04639434814,1.46276891232,4.40108776093 -6.04141139984,1.46477854252,4.42468070984 -6.01743364334,1.46279239655,4.4362449646 -6.00645208359,1.46280372143,4.45681715012 -6.01746702194,1.46981060505,4.49339723587 -5.98149108887,1.46382701397,4.49595928192 -5.97650003433,1.46383225918,4.5057592392 -5.97851705551,1.46784102917,4.53633069992 -5.95353841782,1.46585488319,4.54591035843 -5.93955802917,1.46586692333,4.56448030472 -5.93657541275,1.46787667274,4.5910577774 -5.9135966301,1.46589004993,4.60164308548 -5.91260576248,1.46789479256,4.61543083191 -5.90562438965,1.46990561485,4.63999462128 -5.89364385605,1.46991705894,4.65957403183 -5.87466478348,1.46893012524,4.67414569855 -5.86368322372,1.46994113922,4.69373703003 -5.84770393372,1.46895384789,4.71129989624 -5.84471321106,1.47095882893,4.7230963707 -5.83373212814,1.47097015381,4.74367427826 -5.81475353241,1.4699832201,4.75824451447 -5.80577278137,1.47199428082,4.78081846237 -5.79079294205,1.47200644016,4.79839324951 -5.77381372452,1.47101902962,4.81397294998 -5.76283359528,1.47203075886,4.8355383873 -5.75684309006,1.47303652763,4.84532976151 -5.7348651886,1.47105014324,4.85690546036 -5.72788333893,1.47306060791,4.88049125671 -5.715903759,1.47407257557,4.90106058121 -5.69592523575,1.47208583355,4.91463136673 -5.6779460907,1.47109866142,4.92921209335 -5.67596483231,1.4751086235,4.95877838135 -5.66697454453,1.4751149416,4.96557569504 -5.64699649811,1.47412848473,4.97914600372 -5.63101768494,1.47314095497,4.99572324753 -5.62603569031,1.47615110874,5.02131128311 -5.61005735397,1.47616398335,5.03887605667 -5.59207820892,1.47517681122,5.05345582962 -5.57509946823,1.4751894474,5.06903457642 -5.57410907745,1.47719478607,5.08480882645 -5.55912923813,1.47720682621,5.10139846802 -5.54615020752,1.47821891308,5.12097358704 -5.53417062759,1.47923123837,5.14253520966 -5.52119159698,1.48024320602,5.16211128235 -5.50021362305,1.47825670242,5.17369365692 -5.50222206116,1.48126113415,5.19148206711 -5.48624324799,1.48127377033,5.20806121826 -5.47426366806,1.48228561878,5.22863769531 -5.45528554916,1.48129916191,5.24320554733 -5.43830680847,1.48131167889,5.25779867172 -5.43032693863,1.48432314396,5.28336238861 -5.41534805298,1.48433566093,5.30094146729 -5.412358284,1.48634111881,5.31472444534 -5.39637947083,1.486353755,5.33130502701 -5.38140058517,1.48636627197,5.34888553619 -5.37342071533,1.48937773705,5.37445402145 -5.3594417572,1.4893900156,5.39303541183 -5.34146404266,1.48940336704,5.40860414505 -5.3344836235,1.49241423607,5.4341878891 -5.32849407196,1.49342024326,5.44497394562 -5.31351518631,1.49343276024,5.46255636215 -5.29653739929,1.49344599247,5.4791264534 -5.28655815125,1.49545764923,5.50270080566 -5.26558017731,1.49447143078,5.51428079605 -5.2556014061,1.49648320675,5.53785610199 -5.25660991669,1.49948775768,5.55564880371 -5.23663234711,1.49850130081,5.56823015213 -5.22365379333,1.50051355362,5.58880567551 -5.20767593384,1.50052654743,5.6063785553 -5.19369792938,1.50153946877,5.62694168091 -5.17971897125,1.50255179405,5.64552974701 -5.16174173355,1.5025652647,5.66110134125 -5.1517534256,1.50257217884,5.66788578033 -5.14077377319,1.50458407402,5.6904668808 -5.12479639053,1.50459706783,5.70804214478 -5.10981845856,1.50560975075,5.72661828995 -5.09883880615,1.50762164593,5.7492017746 -5.08086156845,1.50763511658,5.76477479935 -5.06588363647,1.50864779949,5.78335285187 -5.05889511108,1.50965440273,5.79413175583 -5.04891586304,1.5116661787,5.81870794296 -5.02993869781,1.51167964935,5.83229207993 -5.0179605484,1.51369190216,5.85486650467 -4.99498414993,1.51170647144,5.86444282532 -4.98300552368,1.51371872425,5.88701820374 -4.97501707077,1.51472520828,5.89580821991 -4.95803976059,1.51473844051,5.91238546371 -4.94306135178,1.51575124264,5.93096733093 -4.92708444595,1.51676440239,5.94953680038 -4.9151058197,1.5187766552,5.97211647034 -4.89912843704,1.51978969574,5.9896979332 -4.89214897156,1.52380108833,6.01926994324 -4.87316322327,1.52081000805,6.01505470276 -4.86418390274,1.52382159233,6.04163408279 -4.85620450974,1.52683293819,6.06921815872 -4.82623004913,1.52384889126,6.06979608536 -4.81325244904,1.5258616209,6.0923666954 -4.80927276611,1.53087234497,6.12594413757 -3.48160481453,1.07414531708,4.46356582642 -3.46362900734,1.07315897942,4.46913766861 -3.45864963531,1.07616996765,4.49071884155 -3.43067574501,1.07118535042,4.48230552673 -3.41869878769,1.07219803333,4.49587249756 -4.72239780426,1.53694438934,6.22862625122 -4.69642353058,1.5349599123,6.23519134521 -4.68043661118,1.53196787834,6.23298931122 -4.39052772522,1.43603694439,5.88851451874 -4.37055253983,1.43505108356,5.90008497238 -4.23660469055,1.39308798313,5.75665616989 -4.48956108093,1.49204695225,6.13726520538 -4.46758508682,1.4900611639,6.14585256577 -4.51959180832,1.51606094837,6.25842523575 -4.57858705521,1.54205393791,6.36022186279 -4.55261182785,1.5390689373,6.36381483078 -4.54063415527,1.54208147526,6.38938379288 -4.52265787125,1.54309523106,6.4059586525 -4.50068283081,1.54210972786,6.41653728485 -4.34774065018,1.49215066433,6.2401008606 -4.25578308105,1.46517932415,6.14867353439 -4.22580051422,1.45719051361,6.12645149231 -4.20882463455,1.4582041502,6.14302062988 -4.29582214355,1.49819672108,6.31061077118 -4.40281391144,1.54718494415,6.50920820236 -4.39283514023,1.55019688606,6.53679561615 -4.38185834885,1.55420958996,6.56536102295 -4.37486982346,1.55621612072,6.57714653015 -4.36988973618,1.561226964,6.61273431778 -4.3249206543,1.55224597454,6.58831501007 -4.32094192505,1.55825722218,6.62788152695 -4.30096626282,1.55827128887,6.64146280289 -4.27899074554,1.5582857132,6.65204334259 -4.25501728058,1.55730092525,6.66061353683 -4.27901983261,1.57030081749,6.7194185257 -4.26404380798,1.57331430912,6.74298381805 -4.26606225967,1.58232390881,6.79157066345 -4.16510820389,1.55035448074,6.67713880539 -3.20337581635,1.16755819321,5.17764520645 -3.18340063095,1.16657221317,5.18023204803 -4.25013542175,1.60636281967,6.93208742142 -4.22516107559,1.60437774658,6.93767881393 -4.21218442917,1.60839080811,6.96624326706 -3.1234869957,1.16462016106,5.20874452591 -4.20922470093,1.62541174889,7.05840921402 -4.16525554657,1.61643075943,7.03398513794 -4.1672744751,1.62644064426,7.08756065369 -4.17728185654,1.63444364071,7.12935447693 -4.17730093002,1.64445364475,7.17894268036 -4.15632677078,1.64546835423,7.1955075264 -4.1403503418,1.64748156071,7.21809434891 -4.12037563324,1.64849603176,7.23566675186 -4.09940099716,1.64951050282,7.25124120712 -4.08542442322,1.65352356434,7.27882003784 -4.07943582535,1.65552973747,7.29361629486 -4.05446243286,1.65454518795,7.3031835556 -4.0344877243,1.65555953979,7.32075834274 -4.01351308823,1.65657413006,7.33633565903 -3.98753929138,1.65558922291,7.34092712402 -3.97056412697,1.65860319138,7.3654923439 -3.94758963585,1.65761780739,7.37608003616 -3.93460321426,1.6576256752,7.37986421585 -3.9126291275,1.65764033794,7.39344358444 -3.8896548748,1.65765523911,7.40502405167 -3.86468172073,1.65667068958,7.41359758377 -3.84270739555,1.65768527985,7.4271774292 -3.81973338127,1.6577000618,7.43875741959 -3.80974650383,1.6587074995,7.44854021072 -3.78777194023,1.65872192383,7.46112728119 -3.76579856873,1.65973687172,7.47669363022 -3.74082493782,1.65875220299,7.48427438736 -3.7208507061,1.66076648235,7.50284862518 -3.69387793541,1.65878224373,7.5064291954 -3.67590284348,1.66079604626,7.52801179886 -3.66291618347,1.66080367565,7.53080177307 -3.64294147491,1.6618180275,7.54838514328 -3.61596918106,1.6608338356,7.55295753479 -3.59599518776,1.66284823418,7.57252788544 -3.57402157784,1.66386306286,7.58710384369 -3.54704904556,1.66187882423,7.59068250656 -3.5250749588,1.6628934145,7.60426616669 -3.51708674431,1.66390001774,7.61706113815 -3.49411320686,1.66491508484,7.6296377182 -3.47113990784,1.66493010521,7.64221429825 -3.45016622543,1.6669447422,7.65978765488 -3.42619299889,1.66695976257,7.66936969757 -3.40821790695,1.66997373104,7.69294929504 -3.39423203468,1.66898167133,7.69373750687 -3.36825942993,1.66799712181,7.69931650162 -3.34928512573,1.6710113287,7.72188949585 -3.32531189919,1.67102634907,7.73147296906 -3.30433821678,1.67204105854,7.74905061722 -3.27936530113,1.67205631733,7.7566318512 -3.25839161873,1.67407083511,7.77421045303 -3.24640488625,1.6740783453,7.77900218964 -3.2224316597,1.67409336567,7.78858661652 -3.20045876503,1.67510843277,7.80615186691 -3.177485466,1.67612326145,7.81873369217 -3.1545124054,1.67713832855,7.83230924606 -3.12953948975,1.67715358734,7.83989143372 -3.10656619072,1.67716836929,7.85247373581 -3.09857869148,1.68017530441,7.86826133728 -3.0776052475,1.6821898222,7.88683986664 -3.05563139915,1.68320417404,7.90142774582 -3.02665996552,1.68122053146,7.90000247955 -3.00668621063,1.68423485756,7.92158079147 -2.98171377182,1.68425023556,7.93015861511 -2.96972727776,1.68425774574,7.93495225906 -2.94775414467,1.68627250195,7.95252561569 -2.92178201675,1.68528807163,7.95810461044 -2.90480685234,1.69030165672,7.98669433594 -2.87783527374,1.6883174181,7.99027061462 -2.85586214066,1.6903321743,8.00784683228 -2.83388900757,1.69334697723,8.0254240036 -2.82190299034,1.69335472584,8.03220844269 -2.79892992973,1.69436943531,8.04579257965 -2.77995586395,1.69838368893,8.07237052917 -2.75098419189,1.69539952278,8.06795883179 -2.7270116806,1.69641458988,8.07953929901 -2.70803761482,1.70042872429,8.10612010956 -2.67406845093,1.69544613361,8.0906867981 -2.66808009148,1.699452281,8.11348438263 -2.64510726929,1.7014670372,8.1280670166 -2.6141371727,1.697483778,8.11964130402 -2.59116387367,1.69849848747,8.13322925568 -2.57019114494,1.70251321793,8.15779590607 -2.54321885109,1.70052862167,8.15739154816 -2.51624751091,1.7005443573,8.16096782684 -2.5102596283,1.70555078983,8.18775272369 -2.47828960419,1.7005674839,8.17433261871 -2.45131826401,1.69958329201,8.17790794373 -2.4273455143,1.70059812069,8.18849658966 -2.37738084793,1.68261837959,8.113073349 -2.34940910339,1.67963397503,8.10965919495 -2.33242464066,1.67664265633,8.09944438934 -2.29945516586,1.67065954208,8.08002185822 -2.28048110008,1.6756734848,8.10760879517 -2.26450681686,1.68368709087,8.15018081665 -2.25253129005,1.69469976425,8.20576381683 -2.24355459213,1.70871210098,8.2743434906 -2.22458076477,1.7137260437,8.30592632294 -2.21159482002,1.7137336731,8.30871868134 -2.18662285805,1.71474885941,8.3192987442 -2.17164802551,1.72376215458,8.36788082123 -2.15367436409,1.73177623749,8.40845394135 -2.13470077515,1.73779022694,8.44303798676 -2.10972833633,1.73880517483,8.45262718201 -2.09874248505,1.74081277847,8.46740818024 -2.08276772499,1.75082612038,8.51499462128 -2.05879569054,1.752841115,8.53257465363 -2.03082466125,1.7518569231,8.53315544128 -2.00285387039,1.750872612,8.53373622894 -1.97488260269,1.74888837337,8.53331947327 -1.93791425228,1.73890590668,8.49390029907 -1.92392897606,1.7389138937,8.49468803406 -1.89895713329,1.74092900753,8.50726985931 -1.86898684502,1.73694515228,8.49784946442 -1.84201598167,1.73696088791,8.50342559814 -1.81704378128,1.73797571659,8.51401424408 -1.7860738039,1.73399209976,8.49859523773 -1.76010239124,1.73500740528,8.50717544556 -1.74811637402,1.73601484299,8.51596736908 -1.72114539146,1.7360304594,8.52054595947 -1.69217431545,1.73304605484,8.51013851166 -1.66320443153,1.73106229305,8.50770664215 -1.63523292542,1.72807765007,8.50129985809 -1.60726261139,1.72809350491,8.50187301636 -1.58029127121,1.72710895538,8.50246047974 -1.56530642509,1.72511696815,8.49724578857 -1.53933501244,1.72613227367,8.50482940674 -1.51136374474,1.72314763069,8.49842071533 -1.48239326477,1.72016346455,8.48900222778 -1.45542263985,1.72017908096,8.49357700348 -1.42845118046,1.72019433975,8.49316501617 -1.41546559334,1.72020196915,8.49695777893 -1.38649559021,1.71721804142,8.48953151703 -1.35952460766,1.71723353863,8.49211025238 -1.33155345917,1.71524882317,8.48370170593 -1.30758178234,1.71826374531,8.50528144836 -1.27761185169,1.71427977085,8.4878616333 -1.25164020061,1.71429479122,8.49245071411 -1.2406539917,1.71730196476,8.51024246216 -1.21168398857,1.71531772614,8.49981975555 -1.18471252918,1.71333301067,8.49740886688 -1.15874147415,1.71534824371,8.50698852539 -1.1317704916,1.71436357498,8.5075712204 -1.10480010509,1.71537911892,8.5131444931 -1.09181439877,1.7153866291,8.51593780518 -1.06384348869,1.71240198612,8.50552749634 -1.03687286377,1.71241748333,8.50910377502 -1.01090097427,1.71243226528,8.51169776917 -0.983930766582,1.71344780922,8.51826953888 -0.957959473133,1.71446287632,8.5268535614 -0.931988298893,1.71547782421,8.53543758392 -0.918002605438,1.71348547935,8.52623748779 -0.890032470226,1.71250116825,8.5228099823 -0.864060938358,1.71251606941,8.52740192413 -0.838089466095,1.71353089809,8.53398990631 -0.809119522572,1.70954668522,8.51656723022 -0.781149029732,1.70756196976,8.50614929199 -0.755177497864,1.70757687092,8.51073932648 -0.742192327976,1.70958459377,8.52152442932 -0.715221583843,1.70959985256,8.52110671997 -0.687250554562,1.7046148777,8.49969959259 -0.660279929638,1.7046302557,8.50127792358 -0.63430917263,1.70764529705,8.51885414124 -0.606338441372,1.7026604414,8.49844264984 -0.580366849899,1.70367527008,8.50203418732 -0.567381739616,1.70568287373,8.5148191452 -0.540410757065,1.70469796658,8.50940608978 -0.514439582825,1.70671284199,8.5209903717 -0.486469328403,1.70372819901,8.50656890869 -0.460498094559,1.70574295521,8.51715660095 -0.432527542114,1.69975829124,8.4927406311 -0.418542146683,1.69676578045,8.47553634644 -0.391571134329,1.69378077984,8.46312332153 -0.365600079298,1.69679570198,8.47770786285 -0.338629066944,1.69281053543,8.46229553223 -0.311658740044,1.69382572174,8.4668712616 -0.285687237978,1.69484043121,8.46946430206 -0.258716464043,1.6918554306,8.45804786682 -0.244731768966,1.69186329842,8.45683002472 -0.218760251999,1.69187784195,8.45842266083 -0.191789418459,1.68689274788,8.43700790405 -0.164819195867,1.68890798092,8.4475812912 -0.138847574592,1.68792235851,8.43917655945 -0.111877128482,1.68693757057,8.43375492096 -0.0988914072514,1.68694484234,8.4355506897 -0.072919934988,1.68695938587,8.43714332581 -0.0459495335817,1.68697440624,8.432721138 -0.0199780426919,1.68498873711,8.42531394958 --0.022974004969,1.67901325226,8.08962440491 --0.0489446781576,1.68202805519,8.10120105743 --0.0739164277911,1.68104231358,8.09679317474 --0.0988881215453,1.68005657196,8.08938407898 --0.1118735075,1.68106400967,8.09517383575 --0.137844160199,1.68207883835,8.0967502594 --0.162815898657,1.68109309673,8.09334182739 --0.187787503004,1.6791074276,8.08493232727 --0.212759003043,1.67712175846,8.07251930237 --0.238729730248,1.67813646793,8.07709693909 --0.263701438904,1.67815065384,8.07568836212 --0.276686757803,1.67815804482,8.07447624207 --0.302657395601,1.6791728735,8.07505226135 --0.327628821135,1.67618715763,8.06463813782 --0.352600902319,1.6792011261,8.07423782349 --0.378571778536,1.68021571636,8.07881832123 --0.404542714357,1.68223035336,8.08540153503 --0.429514169693,1.6802444458,8.07598781586 --0.441500127316,1.6782515049,8.06478214264 --0.467471063137,1.68026602268,8.07036495209 --0.494441866875,1.68628060818,8.09395027161 --0.518413722515,1.68129467964,8.07253932953 --0.544385075569,1.68430900574,8.08212757111 --0.570355772972,1.68432354927,8.08170604706 --0.596326947212,1.68633782864,8.0872926712 --0.60931289196,1.68834483624,8.0960931778 --0.635283946991,1.68935918808,8.09967803955 --0.662254869938,1.69437372684,8.11626529694 --0.678229033947,1.66938626766,8.00185203552 --0.712198078632,1.69240188599,8.10344409943 --0.741168260574,1.70041668415,8.13802814484 --0.754153549671,1.70042395592,8.13481616974 --0.776126384735,1.69343721867,8.1004114151 --0.803097426891,1.69745159149,8.11500167847 --0.831067621708,1.70146632195,8.13158130646 --0.856039464474,1.70148015022,8.12717437744 --0.881010890007,1.69949424267,8.11775970459 --0.90798163414,1.70250868797,8.12634372711 --0.921967029572,1.70551586151,8.13613891602 --0.947938501835,1.70652985573,8.13873100281 --0.971910059452,1.70354378223,8.11931324005 --0.997881352901,1.70355784893,8.11990070343 --1.02485191822,1.70557236671,8.12448120117 --1.05082321167,1.70658636093,8.12406826019 --1.0757945776,1.7056003809,8.11465263367 --1.08978056908,1.70860719681,8.12845993042 --1.11675143242,1.71062147617,8.13404560089 --1.14172267914,1.70963549614,8.12262535095 --1.1686937809,1.71164953709,8.13021659851 --1.19566464424,1.71366393566,8.13379955292 --1.22063612938,1.712677598,8.12538719177 --1.23362183571,1.71368467808,8.12518215179 --1.26059293747,1.71569871902,8.13077163696 --1.28656411171,1.71571266651,8.12835788727 --1.31353521347,1.71772670746,8.1319437027 --1.33950674534,1.71874046326,8.13253879547 --1.36447787285,1.71675431728,8.12011528015 --1.39344847202,1.72176861763,8.13670730591 --1.40643453598,1.72277545929,8.13850879669 --1.43240582943,1.7237893343,8.13509464264 --1.46037638187,1.72580349445,8.14167785645 --1.48634803295,1.72681713104,8.14027023315 --1.51331877708,1.72783124447,8.14085388184 --1.53929042816,1.72884500027,8.13844490051 --1.56426250935,1.72885835171,8.13304233551 --1.57924699783,1.72986578941,8.13782501221 --1.6012198925,1.72687864304,8.11541748047 --1.6331897974,1.73389327526,8.14401245117 --1.65516197681,1.72990643978,8.11759090424 --1.6791343689,1.72791969776,8.10618591309 --1.71310377121,1.73793447018,8.14278125763 --1.73507630825,1.73394751549,8.11936759949 --1.74906182289,1.73495435715,8.12216186523 --1.78003180027,1.74096882343,8.14074993134 --1.80600333214,1.74098241329,8.13633918762 --1.83297395706,1.74199640751,8.1329164505 --1.86194455624,1.74501025677,8.14150524139 --1.88991618156,1.74802386761,8.14910697937 --1.90390098095,1.74903106689,8.14688777924 --1.92887341976,1.74904417992,8.14048671722 --1.95784413815,1.75205814838,8.14807605743 --1.98481535912,1.75307166576,8.14666461945 --2.0117866993,1.75408518314,8.14625740051 --2.03875756264,1.75509881973,8.14283943176 --2.06373000145,1.75511193275,8.13543605804 --2.08171463013,1.76011919975,8.15323448181 --2.10568666458,1.75813233852,8.13882064819 --2.13365793228,1.76114594936,8.14141273499 --2.15962910652,1.76115942001,8.13399600983 --2.18859982491,1.76317322254,8.13757801056 --2.21557164192,1.76518654823,8.13818073273 --2.24254250526,1.76520013809,8.13275814056 --2.25752830505,1.76720690727,8.13855934143 --2.2844991684,1.76822030544,8.134141922 --2.31546974182,1.77323424816,8.14573383331 --2.33744287491,1.77024674416,8.12632846832 --2.3634147644,1.7712597847,8.12092208862 --2.39038610458,1.77127313614,8.11650753021 --2.40437173843,1.7722799778,8.11630058289 --2.43434286118,1.77629339695,8.12489891052 --2.46431326866,1.779307127,8.13048553467 --2.48728632927,1.77731966972,8.11508178711 --2.51725673676,1.78133332729,8.11966609955 --2.54822731018,1.78534710407,8.1292591095 --2.57119941711,1.78235983849,8.10983657837 --2.5861852169,1.78436636925,8.11464214325 --2.61715531349,1.78838014603,8.12122440338 --2.64212822914,1.78839278221,8.11282539368 --2.66510105133,1.78640520573,8.09641647339 --2.69907045364,1.79241943359,8.11200332642 --2.72304344177,1.79143178463,8.09959888458 --2.75301361084,1.79444551468,8.10117721558 --2.76799917221,1.79545211792,8.10397720337 --2.79397130013,1.79646480083,8.09657001495 --2.82094311714,1.79747784138,8.09115886688 --2.85291385651,1.80149114132,8.10175704956 --2.87788653374,1.80150365829,8.09135055542 --2.90085887909,1.79951632023,8.07192707062 --2.91884374619,1.80352318287,8.08373260498 --2.94681549072,1.80453598499,8.08132553101 --2.97378706932,1.80554902554,8.07390785217 --3.00575780869,1.80956244469,8.08250331879 --3.0317299366,1.81057500839,8.07409572601 --3.05570292473,1.80958712101,8.06068897247 --3.08567404747,1.81260025501,8.06328392029 --3.0996594429,1.81260681152,8.06007194519 --3.12663173676,1.81361949444,8.05366230011 --3.1586022377,1.81763267517,8.06125926971 --3.18257498741,1.81664502621,8.04584312439 --3.21454596519,1.82165813446,8.05344295502 --3.23751926422,1.81967008114,8.0370349884 --3.26449084282,1.82068276405,8.02861690521 --3.28447532654,1.82468986511,8.04141426086 --3.3154463768,1.82770287991,8.04500961304 --3.3364200592,1.82571446896,8.02360153198 --3.37238955498,1.8317283392,8.03718852997 --3.39836263657,1.83274018764,8.02979278564 --3.4233353138,1.83175241947,8.01738166809 --3.44132018089,1.83475911617,8.02417755127 --3.47129154205,1.83777189255,8.02377033234 --3.50026345253,1.83978450298,8.02136516571 --3.52123737335,1.83779597282,7.99895143509 --3.55220842361,1.84080886841,8.00054454803 --3.58217978477,1.84282147884,7.99913406372 --3.60915255547,1.84483361244,7.99273538589 --3.62013912201,1.84283947945,7.98152065277 --3.6481115818,1.84485173225,7.97712135315 --3.6790831089,1.84786427021,7.9777135849 --3.70705533028,1.84987652302,7.97230958939 --3.73302769661,1.84988856316,7.96089458466 --3.75900053978,1.84990048409,7.95048809052 --3.78997182846,1.85291302204,7.95007753372 --3.80495762825,1.85491931438,7.94887256622 --3.83393001556,1.85693144798,7.94547080994 --3.8539044857,1.85394251347,7.92206096649 --3.88687539101,1.85795521736,7.92565345764 --3.91184854507,1.85796678066,7.91324853897 --3.93782138824,1.85897862911,7.9018368721 --3.9578063488,1.8619852066,7.91164159775 --3.98877811432,1.86499750614,7.91123819351 --4.01675033569,1.86700963974,7.90282249451 --4.0407242775,1.86602091789,7.88841915131 --4.06769657135,1.86703264713,7.87901067734 --4.0976691246,1.87004482746,7.87560415268 --4.12264204025,1.87005627155,7.86219549179 --4.1376285553,1.87106215954,7.8609957695 --4.16260147095,1.87107348442,7.84758710861 --4.19557285309,1.8750859499,7.84917974472 --4.22154664993,1.87609708309,7.83978652954 --4.2455201149,1.87510848045,7.82337188721 --4.27549266815,1.87812042236,7.81896305084 --4.30246591568,1.87913179398,7.80955934525 --4.32245063782,1.88213837147,7.81635570526 --4.34442472458,1.88114905357,7.79795265198 --4.37639665604,1.88516128063,7.79654359818 --4.40037059784,1.88417220116,7.78113746643 --4.42934370041,1.8861836195,7.77573919296 --4.4543170929,1.88619482517,7.76132774353 --4.47530174255,1.89020144939,7.76912403107 --4.50227451324,1.89121294022,7.75771045685 --4.52824831009,1.8922239542,7.74630880356 --4.5562210083,1.89323532581,7.73689842224 --4.59219264984,1.89924740791,7.74249887466 --4.62816381454,1.90425956249,7.74810218811 --4.65413713455,1.90427064896,7.73468971252 --4.66412496567,1.90327584743,7.72348737717 --4.69009828568,1.90428686142,7.71007490158 --4.71007442474,1.90229690075,7.68867635727 --4.72205162048,1.89730620384,7.65326833725 --4.7450261116,1.89631676674,7.63586187363 --4.75300455093,1.88932538033,7.59445381165 --4.76998090744,1.88633525372,7.56704092026 --4.77896881104,1.88534021378,7.55483961105 --4.80694198608,1.88735127449,7.54543161392 --4.82691717148,1.88536143303,7.52301979065 --4.85189151764,1.88537192345,7.50961732864 --4.87486696243,1.88538217545,7.49321508408 --4.89884138107,1.88539266586,7.47780942917 --4.91382789612,1.88739824295,7.47460603714 --4.94480085373,1.8904093504,7.4702038765 --4.97177505493,1.89142000675,7.4598031044 --5.0007481575,1.89343094826,7.45139503479 --5.01672506332,1.8904402256,7.4239897728 --5.04169940948,1.89145076275,7.40958118439 --5.0726723671,1.89446163177,7.40417528152 --5.08865880966,1.89546716213,7.40297937393 --5.1106338501,1.89547741413,7.38255882263 --5.13860797882,1.89748775959,7.37416601181 --5.16558218002,1.89849817753,7.36276102066 --5.19355583191,1.90050876141,7.35235357285 --5.22352933884,1.90251946449,7.34494829178 --5.25350284576,1.90553021431,7.33754396439 --5.26948976517,1.90753543377,7.33635139465 --5.29446411133,1.90754568577,7.31993150711 --5.32543754578,1.91055631638,7.31453466415 --5.35541152954,1.91356682777,7.30713415146 --5.37638711929,1.91257631779,7.28672790527 --5.41235923767,1.91758751869,7.28631973267 --5.41734886169,1.91559147835,7.27012872696 --5.44632291794,1.91760194302,7.25971651077 --5.46929836273,1.91761159897,7.24231386185 --5.49627304077,1.91862165928,7.22990846634 --5.52224779129,1.91963160038,7.21650648117 --5.54222393036,1.91864085197,7.19409418106 --5.57019901276,1.9206507206,7.18369674683 --5.58518600464,1.92265582085,7.17949581146 --5.61416006088,1.9246660471,7.16908884048 --5.62713813782,1.92067444324,7.13868379593 --5.65411281586,1.92268431187,7.12527322769 --5.68908643723,1.92669475079,7.12388086319 --5.70006465912,1.92270290852,7.09047031403 --5.72404098511,1.92271232605,7.07406711578 --5.74602603912,1.92671811581,7.07786273956 --5.76200437546,1.92472660542,7.05246734619 --5.78597974777,1.92573595047,7.0350561142 --5.81295490265,1.92674553394,7.02265691757 --5.82693338394,1.92375385761,6.99324607849 --5.84790992737,1.92376279831,6.97283983231 --5.88688278198,1.92977333069,6.97544956207 --5.88687324524,1.92577672005,6.95224142075 --5.90684986115,1.92478573322,6.92982769012 --5.9428229332,1.92979598045,6.92742681503 --5.94480466843,1.92280292511,6.88502120972 --5.96778059006,1.92281198502,6.86661195755 --6.01875066757,1.93282330036,6.8822221756 --5.86777734756,1.87781310081,6.68397521973 --5.80377435684,1.84881412983,6.5665473938 --5.80575609207,1.84282112122,6.52714729309 --5.82173442841,1.84082949162,6.50273942947 --5.85670804977,1.84583950043,6.50033950806 --5.88868236542,1.84984910488,6.49393606186 --5.91265869141,1.85085809231,6.47853040695 --5.89265441895,1.84085977077,6.43532133102 --5.51172542572,1.70683336258,5.97181177139 --5.33174943924,1.6418248415,5.73535585403 --5.31573486328,1.62983047962,5.68094444275 --5.32871389389,1.62883865833,5.65854167938 --5.32569599152,1.62184548378,5.61812496185 --5.33967494965,1.61985373497,5.59671878815 --5.33666610718,1.61585700512,5.57551431656 --5.37162160873,1.61587393284,5.54070663452 --5.36160564423,1.6068803072,5.49328184128 --5.30859994888,1.58488297462,5.40286111832 --5.32357788086,1.58389115334,5.383456707 --5.4235367775,1.6099063158,5.45106887817 --5.36954021454,1.58990550041,5.37784719467 --5.32753229141,1.5719088316,5.30144023895 --5.34750938416,1.57191753387,5.28703212738 --5.34149217606,1.56492424011,5.24560689926 --5.36047029495,1.56593251228,5.23120927811 --5.36845064163,1.56294000149,5.20580863953 --5.37543964386,1.5629440546,5.19560241699 --5.39141798019,1.56195235252,5.17719173431 --5.40939569473,1.56296062469,5.16078138351 --5.42437505722,1.56196856499,5.14238214493 --5.44235277176,1.56297683716,5.12597227097 --5.45733213425,1.56198477745,5.10757255554 --5.47330999374,1.56199288368,5.08916139603 --5.49529647827,1.56699776649,5.09396791458 --5.52127313614,1.57000648975,5.08556747437 --5.56224632263,1.57701611519,5.09117174149 --5.58322381973,1.5790245533,5.07675743103 --5.59320402145,1.57703197002,5.05335521698 --5.62417936325,1.58104074001,5.04895401001 --5.66814374924,1.58705377579,5.04035949707 --5.70711803436,1.59406304359,5.04296255112 --5.7250957489,1.59507107735,5.02554941177 --5.78904771805,1.60408830643,5.01775836945 --5.81502437592,1.60709667206,5.00734996796 --5.87499427795,1.62010705471,5.02796649933 --5.8809838295,1.61911094189,5.01575136185 --5.90596103668,1.62211894989,5.0043463707 --5.95393419266,1.63212835789,5.01396274567 --5.96591377258,1.6301356554,4.99054813385 --6.05386066437,1.64715397358,4.99975585938 --6.0658416748,1.64516079426,4.97735643387 --6.09582710266,1.65216588974,4.98616075516 --6.23778009415,1.68918085098,5.07179260254 --6.24376153946,1.68618750572,5.04237508774 --6.2477440834,1.6821937561,5.01297569275 --6.28771877289,1.68920218945,5.01257944107 --6.32769393921,1.69621062279,5.01218652725 --6.337682724,1.69621431828,5.00297737122 --6.39465427399,1.70822381973,5.01558446884 --6.46062421799,1.72223353386,5.035197258 --7.10147809982,1.90027570724,5.51298570633 --7.17544651031,1.91628551483,5.53459644318 --7.20742368698,1.92029297352,5.52219057083 --7.23440217972,1.92329967022,5.5067949295 --7.24639177322,1.92430317402,5.4975938797 --7.26237201691,1.92330932617,5.47319126129 --7.27835273743,1.92331564426,5.44878816605 --7.31233072281,1.92832267284,5.43839359283 --7.31931304932,1.92532849312,5.40698671341 --5.55964326859,1.42924356461,4.04302597046 --5.56062555313,1.42525029182,4.01560974121 --5.58061313629,1.42925429344,4.01742124557 --5.6095905304,1.43426215649,4.01101636887 --7.39922618866,1.92635607719,5.30317831039 --7.41820669174,1.92636227608,5.28077411652 --7.43918657303,1.92736840248,5.26037740707 --7.45616769791,1.92737448215,5.23596715927 --7.46714925766,1.92638015747,5.20755815506 --7.48513841629,1.92838358879,5.20235872269 --7.49212169647,1.92638885975,5.17195796967 --7.51210212708,1.92639482021,5.15055894852 --7.53608226776,1.92940092087,5.13216304779 --7.54906463623,1.92840647697,5.10576105118 --7.56604528427,1.92841219902,5.08135128021 --7.58202695847,1.92841792107,5.05694913864 --7.587018013,1.92742061615,5.0427479744 --7.6079993248,1.92842638493,5.02134227753 --7.62398052216,1.92843198776,4.99694061279 --7.64996051788,1.93143785,4.97954463959 --7.65294456482,1.92744290829,4.9461350441 --7.67492580414,1.92944860458,4.92573547363 --7.69490671158,1.93045425415,4.90332746506 --7.7038974762,1.93045699596,4.89213085175 --7.72087955475,1.93146216869,4.86873435974 --7.72886276245,1.92946720123,4.83933210373 --7.745844841,1.92947268486,4.81492328644 --7.77282476425,1.93247830868,4.79752492905 --7.78680753708,1.93248343468,4.77212667465 --7.79979753494,1.93348610401,4.76292610168 --7.80978059769,1.93249118328,4.73452091217 --7.83376169205,1.93449652195,4.71512269974 --7.84674501419,1.9335013628,4.68871974945 --7.86472702026,1.93450653553,4.6653175354 --7.87670993805,1.93351149559,4.63790941238 --7.9066901207,1.93751680851,4.62252044678 --7.91968011856,1.93951952457,4.61230993271 --7.92766427994,1.93752419949,4.58290576935 --7.94764614105,1.9385291338,4.56050348282 --7.95563030243,1.93753385544,4.53109836578 --7.99560880661,1.94353938103,4.52070713043 --7.92160701752,1.9205416441,4.44428348541 --7.67563390732,1.85353970528,4.26879739761 --7.62663507462,1.83954060078,4.22458028793 --7.64561653137,1.84054589272,4.20216608047 --7.66759872437,1.84355092049,4.18276929855 --7.69357967377,1.84655594826,4.16537237167 --7.73255872726,1.85256123543,4.15497779846 --7.74254274368,1.85156595707,4.12857723236 --7.74052858353,1.84757018089,4.09516716003 --7.74552059174,1.84757244587,4.08196592331 --7.76150369644,1.84857726097,4.05856180191 --7.78148555756,1.85058200359,4.03715801239 --7.78947019577,1.84858644009,4.00975656509 --7.79545497894,1.84659087658,3.98135447502 --7.81743764877,1.84959542751,3.96095132828 --7.83142089844,1.84959983826,3.93654870987 --7.84041213989,1.85060214996,3.9253475666 --7.82340049744,1.84260606766,3.88493561745 --7.83438444138,1.84261059761,3.85852503777 --7.87436485291,1.84961509705,3.84814023972 --7.88734865189,1.84961950779,3.8227314949 --7.89733314514,1.84862375259,3.7963283062 --7.90532493591,1.84962582588,3.78513407707 --7.91031074524,1.84762990475,3.75673556328 --7.92429447174,1.84763407707,3.73233366013 --7.93527841568,1.8476382494,3.7059237957 --7.94726324081,1.84764242172,3.68052077293 --7.97624540329,1.85164666176,3.66312170029 --7.98822975159,1.85165071487,3.63771986961 --7.93123102188,1.8366522789,3.59448862076 --7.94821453094,1.83765625954,3.57209396362 --7.99319458008,1.84566032887,3.56270885468 --8.0241765976,1.85066449642,3.5453016758 --8.03916168213,1.85166835785,3.52190899849 --8.04414749146,1.84967207909,3.49249410629 --8.04113388062,1.8466758728,3.46109676361 --7.99713230133,1.83367776871,3.42486405373 --8.03511428833,1.84068155289,3.41147375107 --8.05609798431,1.84368526936,3.39108633995 --8.06408405304,1.84268891811,3.36367845535 --8.09106731415,1.84669268131,3.34427332878 --8.11804962158,1.85069620609,3.32588362694 --8.09703922272,1.84269976616,3.2864716053 --8.12502861023,1.84770154953,3.28327989578 --8.15601158142,1.85270512104,3.26487135887 --8.14899921417,1.84870874882,3.23146271706 --8.16498470306,1.8497120142,3.20806717873 --8.19296741486,1.85371530056,3.18967747688 --8.19095516205,1.85071885586,3.15826821327 --8.20493984222,1.85172224045,3.13285708427 --8.22293186188,1.85472357273,3.12567043304 --8.22391891479,1.85272705555,3.09525799751 --8.22690582275,1.85073041916,3.06584835052 --8.26288795471,1.85673344135,3.049451828 --8.27787303925,1.85873663425,3.02505159378 --8.27486228943,1.85573971272,2.9946577549 --8.30484580994,1.86074268818,2.97525382042 --8.29883956909,1.85774433613,2.95805072784 --8.3138256073,1.85874736309,2.93365192413 --8.34580898285,1.86374998093,2.91525554657 --8.34279727936,1.8607531786,2.88384652138 --8.35178375244,1.86075615883,2.85744905472 --8.37776851654,1.86475872993,2.83604264259 --8.37775611877,1.86276173592,2.80664587021 --8.3867483139,1.86376321316,2.79444098473 --8.39973545074,1.86476588249,2.76904010773 --8.40472221375,1.86376881599,2.74063396454 --8.4137096405,1.86377155781,2.71423721313 --8.4396944046,1.8677738905,2.69283628464 --8.44268131256,1.866776824,2.66342449188 --8.4556684494,1.86677932739,2.63802552223 --8.48165988922,1.87278008461,2.63183379173 --8.47764873505,1.86978304386,2.60042405128 --8.48463630676,1.86878561974,2.57302331924 --8.51762104034,1.87478756905,2.55362725258 --8.50360965729,1.86979067326,2.51921463013 --8.50659751892,1.8677932024,2.4898018837 --8.54358959198,1.87579345703,2.48762822151 --8.52557849884,1.86979663372,2.45221495628 --8.54556560516,1.87279868126,2.42780518532 --8.5665512085,1.87580060959,2.40440678596 --8.57453918457,1.87580299377,2.37700295448 --8.59152603149,1.87780487537,2.35260748863 --8.5975151062,1.87680721283,2.32521176338 --8.60350799561,1.87780809402,2.31200957298 --8.60949611664,1.87681055069,2.2835996151 --8.64148235321,1.88281166553,2.26320838928 --8.63047218323,1.87881457806,2.22978925705 --8.64945888519,1.88081622124,2.20539021492 --8.67544555664,1.88581752777,2.1829957962 --8.66043567657,1.88082039356,2.14958810806 --8.68242835999,1.88482069969,2.14038944244 --8.70141601562,1.88682210445,2.11599373817 --8.70440483093,1.88682413101,2.08759450912 --8.71739292145,1.88782572746,2.06119179726 --8.73538017273,1.89082717896,2.03578710556 --8.73437023163,1.88882935047,2.00638699532 --8.74935722351,1.89083075523,1.97997903824 --8.74835300446,1.8898319006,1.96477329731 --8.77434062958,1.89383256435,1.94238901138 --8.77532958984,1.89283466339,1.91298246384 --8.78331851959,1.89283633232,1.8845692873 --8.80330562592,1.89583706856,1.86017751694 --8.81729412079,1.89783835411,1.83377611637 --8.81628417969,1.89584028721,1.80336117744 --8.82827854156,1.89784061909,1.79217493534 --8.84226799011,1.89984166622,1.76577484608 --8.85025596619,1.90084302425,1.73736345768 --8.85824584961,1.90084433556,1.70996642113 --8.86723518372,1.90184557438,1.68256676197 --8.86922454834,1.90084707737,1.65315711498 --8.88621902466,1.90384697914,1.64196145535 --8.89320850372,1.90384829044,1.61355388165 --8.90119838715,1.90484941006,1.58615791798 --8.90418720245,1.90385079384,1.55674612522 --8.91417694092,1.90485179424,1.52934575081 --8.91316795349,1.90385329723,1.49994277954 --8.92415714264,1.90485417843,1.47254061699 --8.93514728546,1.90685486794,1.44513905048 --8.94014167786,1.90685534477,1.43093264103 --8.95613098145,1.90985572338,1.40453541279 --8.97612190247,1.91285574436,1.37914502621 --8.98711109161,1.91385626793,1.35174632072 --8.99610137939,1.91485691071,1.32333779335 --8.99509239197,1.91385829449,1.29393470287 --8.99908256531,1.91385924816,1.26452195644 --9.00107765198,1.913859725,1.25032246113 --9.00006961823,1.91286098957,1.22091853619 --8.99705982208,1.91086232662,1.19050359726 --9.01605033875,1.91386198997,1.16512072086 --9.03004074097,1.91686213017,1.13771915436 --9.03203105927,1.91586303711,1.10831010342 --9.021027565,1.91286444664,1.09210348129 --9.03301811218,1.9148645401,1.06369197369 --9.0400094986,1.91586482525,1.03630280495 --9.05200004578,1.91686499119,1.00789284706 --9.05599117279,1.91686558723,0.9794947505 --9.06498146057,1.91886568069,0.951089680195 --9.07597351074,1.92086577415,0.922682583332 --9.0819683075,1.92086565495,0.909492909908 --9.09095954895,1.9228656292,0.88108921051 --9.09295082092,1.92186617851,0.851680755615 --9.09994220734,1.92286634445,0.823280274868 --9.09893512726,1.92186713219,0.793875038624 --9.10792636871,1.92386698723,0.765472650528 --9.10691738129,1.92286777496,0.736067175865 --9.12991333008,1.92686593533,0.72387611866 --9.13090515137,1.92686641216,0.694469094276 --9.13889694214,1.92786633968,0.665055811405 --9.14788913727,1.92986595631,0.6366558671 --9.15988063812,1.9318652153,0.608254313469 --9.15987300873,1.93086576462,0.578848898411 --9.15686511993,1.92986631393,0.549445152283 --9.16386127472,1.93086588383,0.535244345665 --9.16985416412,1.93186557293,0.506848454475 --9.17984485626,1.93386495113,0.477436482906 --9.17983818054,1.93386518955,0.448030799627 --9.17983055115,1.93286550045,0.418625146151 --9.19182300568,1.93486452103,0.390227615833 --9.19681549072,1.93586421013,0.360819846392 --9.20981216431,1.9388628006,0.347632735968 --9.19980430603,1.93586409092,0.317217499018 --9.20879745483,1.9378631115,0.288822978735 --9.21078968048,1.93786299229,0.259417146444 --9.21778297424,1.93886220455,0.230010256171 --9.2117767334,1.93786287308,0.200606018305 --9.21676921844,1.93786227703,0.1712000072 --9.20876598358,1.93686306477,0.155990988016 --9.20675849915,1.93586325645,0.126585364342 --9.24975204468,1.94485831261,0.0981923937798 --9.24474525452,1.94385874271,0.0687880218029 --9.23673820496,1.94185936451,0.039382994175 --9.24673175812,1.94385802746,0.00997920054942 --9.2497253418,1.94385743141,-0.0194247215986 --9.25172233582,1.9448568821,-0.0346337333322 --9.2457151413,1.9438573122,-0.0640395954251 --9.24270915985,1.94285726547,-0.0934450253844 --9.24070358276,1.94185709953,-0.122850380838 --9.26269721985,1.94685399532,-0.152247563004 --9.256690979,1.94585430622,-0.181654110551 --9.25068378448,1.94385457039,-0.211060911417 --9.26068115234,1.94685292244,-0.226265698671 --9.26867580414,1.94785141945,-0.255665510893 --9.26966953278,1.94885075092,-0.285068929195 --9.26766395569,1.94785034657,-0.3144736588 --9.25765705109,1.94585096836,-0.343883931637 --9.27265167236,1.94984817505,-0.374291837215 --9.2706489563,1.94884824753,-0.388487875462 --9.28564357758,1.95284545422,-0.418894082308 --9.27163791656,1.94984650612,-0.447294235229 --9.28563213348,1.95284378529,-0.477699607611 --9.28662776947,1.95384275913,-0.507101595402 --9.29162216187,1.95484113693,-0.537513256073 --9.2826166153,1.9528414011,-0.566924273968 --9.30961513519,1.95883727074,-0.582105457783 --9.29660892487,1.95683789253,-0.611520528793 --9.31460475922,1.96083438396,-0.641916513443 --9.31159877777,1.96083366871,-0.671320974827 --9.30859470367,1.95983290672,-0.701739013195 --9.30658912659,1.95983207226,-0.7311424613 --9.31258487701,1.96182990074,-0.761549592018 --9.32158279419,1.96382808685,-0.776745080948 --9.30457687378,1.96082925797,-0.805154085159 --9.30957221985,1.96182715893,-0.835561454296 --9.30756759644,1.96182620525,-0.864964485168 --9.30756282806,1.96282482147,-0.895378649235 --9.32355880737,1.96682107449,-0.925768196583 --9.30955410004,1.96382164955,-0.95518887043 --9.32755374908,1.96781814098,-0.971380889416 --9.31554794312,1.96581852436,-0.99978518486 --9.32454395294,1.96881556511,-1.03119671345 --9.32754039764,1.96981346607,-1.06058990955 --9.32553672791,1.96981203556,-1.0910050869 --9.32953262329,1.97180986404,-1.12140965462 --9.32952880859,1.9718080759,-1.15080690384 --9.33552646637,1.97380626202,-1.16701495647 --9.34552383423,1.97680282593,-1.19740653038 --9.33351898193,1.97480285168,-1.22682583332 --9.33751487732,1.97680044174,-1.25722801685 --9.3285112381,1.97479987144,-1.28664207458 --9.325507164,1.97479844093,-1.3160443306 --9.32150268555,1.97479724884,-1.34544861317 --9.31250095367,1.97379779816,-1.35965919495 --9.32949924469,1.97779273987,-1.39205884933 --9.34349727631,1.98178827763,-1.42446362972 --9.32449150085,1.97878944874,-1.45187354088 --9.32748985291,1.98078680038,-1.48227488995 --9.34748744965,1.98578107357,-1.51567614079 --9.31948184967,1.98078370094,-1.54209542274 --9.32748126984,1.9827811718,-1.55829334259 --9.34047985077,1.98677659035,-1.59069526196 --9.32647514343,1.98377668858,-1.61910879612 --9.32747364044,1.98577404022,-1.64951264858 --9.33847141266,1.98876965046,-1.68191671371 --9.31646633148,1.98477113247,-1.70832526684 --9.3124628067,1.98476934433,-1.73874127865 --9.33246517181,1.9907643795,-1.75693082809 --9.31045913696,1.98676609993,-1.78334105015 --9.31745815277,1.98876202106,-1.81575298309 --9.33945846558,1.99475514889,-1.85014867783 --9.3264541626,1.99375486374,-1.87856161594 --9.31545162201,1.99175429344,-1.90696907043 --9.34145355225,1.99874782562,-1.92716169357 --9.32044887543,1.99474918842,-1.953571558 --9.32644748688,1.99774491787,-1.98598206043 --9.32644557953,1.99874210358,-2.01638317108 --9.30044078827,1.99374437332,-2.04179692268 --9.30243873596,1.99574100971,-2.07320523262 --9.28643512726,1.99374127388,-2.1006166935 --9.3004360199,1.99773681164,-2.11881256104 --9.31443691254,2.00173091888,-2.15322041512 --9.31543636322,2.00372743607,-2.18361592293 --9.30143260956,2.00172710419,-2.21203422546 --9.30543231964,2.00372314453,-2.2434322834 --9.31943321228,2.00871706009,-2.27783536911 --9.30743026733,2.00771594048,-2.30624675751 --9.31543159485,2.0107126236,-2.32344412804 --9.33043193817,2.01470589638,-2.35783982277 --9.30442714691,2.01070809364,-2.38326072693 --9.3184299469,2.01570153236,-2.41867184639 --9.32442951202,2.01869678497,-2.45107030869 --9.30442523956,2.01569747925,-2.47748422623 --9.31042671204,2.01869249344,-2.51089477539 --9.31442642212,2.02068758011,-2.54329848289 --9.30342483521,2.01968836784,-2.55549693108 --9.30542469025,2.02168393135,-2.5879073143 --9.32242774963,2.02767634392,-2.62431168556 --9.31342697144,2.02667450905,-2.65271043777 --9.32042789459,2.03066897392,-2.68712472916 --9.33343029022,2.03466176987,-2.72151374817 --9.31342697144,2.03066468239,-2.73172211647 --9.31042671204,2.03266119957,-2.76313567162 --9.33143138885,2.03865218163,-2.80052852631 --9.31342887878,2.03665208817,-2.82794952393 --9.33343315125,2.04364299774,-2.86534357071 --9.32943344116,2.04463982582,-2.89574480057 --9.32043266296,2.04463744164,-2.92616677284 --9.31443119049,2.04363679886,-2.94037103653 --9.33643722534,2.05062699318,-2.97876358032 --9.31643295288,2.04762721062,-3.00518035889 --9.31143379211,2.0486240387,-3.03558421135 --9.31143474579,2.05061936378,-3.06799125671 --9.32343864441,2.05561184883,-3.10439562798 --9.31743907928,2.05660843849,-3.13480234146 --9.3134393692,2.05660700798,-3.15000987053 --9.32144260406,2.06060028076,-3.18541622162 --9.31144237518,2.06059789658,-3.2148270607 --9.31344509125,2.06359243393,-3.24823379517 --9.32244873047,2.06758522987,-3.28363180161 --9.31844997406,2.0685813427,-3.31503868103 --9.31945228577,2.07157588005,-3.34844684601 --9.32045459747,2.07257294655,-3.36565423012 --9.31845664978,2.07456851006,-3.39704990387 --9.31945896149,2.07756280899,-3.43045592308 --9.31645965576,2.07855844498,-3.4628674984 --9.3154630661,2.08055305481,-3.496281147 --9.31146430969,2.08254885674,-3.52768397331 --9.30946731567,2.08454394341,-3.56008887291 --9.31747055054,2.0875389576,-3.58029603958 --9.30847167969,2.08753585815,-3.61070919037 --9.30147361755,2.0885322094,-3.64111280441 --9.31548023224,2.09452271461,-3.67950820923 --9.3114824295,2.09651780128,-3.71191954613 --9.29348087311,2.09451699257,-3.73934054375 --9.28748321533,2.09551286697,-3.7707490921 --9.28748607635,2.09750986099,-3.78795647621 --9.28948974609,2.10050320625,-3.82235908508 --9.28549194336,2.1014983654,-3.85476756096 --9.27049255371,2.10049676895,-3.88217306137 --9.2604932785,2.10149359703,-3.91258907318 --9.26549911499,2.10548567772,-3.94899702072 --9.26250267029,2.10748052597,-3.98241019249 --9.26450538635,2.10947656631,-3.99960374832 --9.25750827789,2.11047267914,-4.03101348877 --9.25551223755,2.11246657372,-4.06441926956 --9.25751781464,2.11645936966,-4.09982633591 --9.24752044678,2.1164560318,-4.13023853302 --9.25152587891,2.12044835091,-4.16664457321 --9.22652435303,2.11744904518,-4.19106912613 --9.23953056335,2.12244153023,-4.21426916122 --9.23853492737,2.1244354248,-4.2476644516 --9.23253917694,2.12643027306,-4.28007650375 --9.22554206848,2.12742567062,-4.31249284744 --9.21654510498,2.12842154503,-4.34289646149 --9.22655487061,2.13441133499,-4.38330793381 --9.21655750275,2.1354072094,-4.41371679306 --9.2135591507,2.13640451431,-4.42992067337 --9.21156406403,2.13839817047,-4.46432828903 --9.2055683136,2.14039301872,-4.49673557281 --9.17656517029,2.13639473915,-4.51916265488 --9.18257331848,2.14138555527,-4.5575671196 --9.19158363342,2.14737534523,-4.59696388245 --9.19758892059,2.15036940575,-4.61816978455 --9.20059776306,2.15436077118,-4.65557670593 --9.19460201263,2.15635538101,-4.68797969818 --9.19961071014,2.16134572029,-4.72638320923 --9.21362304688,2.16733312607,-4.76978635788 --9.2746515274,2.18630456924,-4.83616018295 --9.34068393707,2.20627403259,-4.90553045273 --9.32168006897,2.2032763958,-4.91373538971 --9.33869552612,2.2112622261,-4.95913124084 --9.3146944046,2.20926213264,-4.98455524445 --9.26868724823,2.20126914978,-4.99899482727 --9.24668693542,2.19926857948,-5.02440881729 --9.21968460083,2.19626951218,-5.04783296585 --9.18167972565,2.19127416611,-5.06526184082 --9.16067504883,2.18727755547,-5.07247304916 --9.15568351746,2.19027066231,-5.10789251328 --9.13568401337,2.18826913834,-5.13430833817 --9.11668491364,2.18726730347,-5.16172933578 --9.09268474579,2.18526697159,-5.18615007401 --9.08068943024,2.18626284599,-5.21655893326 --9.06169033051,2.18526077271,-5.24398088455 --8.99167728424,2.17427325249,-5.26163291931 --9.00469207764,2.18125963211,-5.30603027344 --8.98569393158,2.18025755882,-5.33345365524 --8.95269012451,2.1762611866,-5.35187387466 --8.92868900299,2.17426085472,-5.37629985809 --8.91769504547,2.17525601387,-5.40771436691 --8.89869213104,2.17225837708,-5.41593170166 --8.87969303131,2.17125678062,-5.44234704971 --8.85169124603,2.16825819016,-5.46377038956 --8.82368850708,2.1652598381,-5.48519468307 --8.79868793488,2.1632604599,-5.50761032104 --8.79069519043,2.16525411606,-5.54102611542 --8.75168895721,2.16025996208,-5.5564661026 --8.74368953705,2.16025853157,-5.5696644783 --8.72069072723,2.15825796127,-5.59408950806 --8.68668556213,2.15426206589,-5.6115193367 --8.65468215942,2.15026545525,-5.62994670868 --8.64768981934,2.15225839615,-5.66436576843 --8.61168289185,2.14726376534,-5.6787815094 --8.5846824646,2.14426517487,-5.70020771027 --8.59068965912,2.14825773239,-5.7234120369 --8.55368423462,2.14326334,-5.73783779144 --8.54168987274,2.14425826073,-5.76926183701 --8.51968955994,2.14325785637,-5.79267406464 --8.49068832397,2.14025974274,-5.81310796738 --8.44867801666,2.13426756859,-5.82353496552 --8.44769001007,2.13825821877,-5.86093950272 --8.41267871857,2.13126778603,-5.85817575455 --8.39768314362,2.13226413727,-5.88659143448 --8.38068580627,2.13226127625,-5.91401195526 --8.34167861938,2.12626791,-5.92644357681 --8.31767845154,2.12426829338,-5.94886684418 --8.29467868805,2.12326812744,-5.97128248215 --8.26767635345,2.12126970291,-5.99170923233 --8.24967384338,2.11827254295,-5.99892663956 --8.22367286682,2.11627340317,-6.0203576088 --8.20767688751,2.11727046967,-6.04777288437 --8.17166996002,2.11227607727,-6.06120061874 --8.14766979218,2.11027669907,-6.0826177597 --8.12266921997,2.10827732086,-6.10404396057 --8.1076669693,2.10727882385,-6.11326217651 --8.09367275238,2.10827469826,-6.14167261124 --8.05966663361,2.10427975655,-6.15610074997 --8.04267120361,2.10427689552,-6.18352556229 --8.01566886902,2.10227847099,-6.2029504776 --7.98666572571,2.09928131104,-6.22037172318 --7.96966934204,2.09927821159,-6.24779748917 --7.95066547394,2.09728193283,-6.25301074982 --7.92666530609,2.09528207779,-6.27544355392 --7.90866851807,2.09527993202,-6.30085802078 --7.87666416168,2.09228396416,-6.31628799438 --7.85966777802,2.09228110313,-6.34270429611 --7.83066511154,2.09028363228,-6.36114215851 --7.81366872787,2.09028124809,-6.38654851913 --7.78565883636,2.08528923988,-6.38477087021 --7.76766252518,2.08528661728,-6.41119718552 --7.75266838074,2.08728265762,-6.43961858749 --7.71666097641,2.0822892189,-6.45104837418 --7.69766378403,2.08228731155,-6.47546386719 --7.66565895081,2.07829165459,-6.49090194702 --7.64365911484,2.07729125023,-6.51231384277 --7.6346616745,2.07829022408,-6.5255279541 --7.61366319656,2.07728886604,-6.54895162582 --7.57465362549,2.07229733467,-6.55738544464 --7.57166671753,2.07728719711,-6.59479045868 --7.53265762329,2.07129573822,-6.60322570801 --7.51666259766,2.07229185104,-6.63064622879 --7.4896607399,2.07029390335,-6.64907646179 --7.47665977478,2.0692949295,-6.65828704834 --7.45466136932,2.06929445267,-6.68071269989 --7.43066120148,2.06729483604,-6.70113611221 --7.41066360474,2.06729340553,-6.72455358505 --7.37365484238,2.06330108643,-6.73398971558 --7.36666679382,2.06729245186,-6.76940631866 --7.33165931702,2.06229925156,-6.77983522415 --7.32166051865,2.06229829788,-6.79204940796 --7.29966259003,2.06229782104,-6.81447696686 --7.27466154099,2.06029868126,-6.83390331268 --7.25966835022,2.06229448318,-6.86232423782 --7.22966337204,2.05929875374,-6.87574005127 --7.21166849136,2.06029582024,-6.90216970444 --7.18666791916,2.05929732323,-6.92058753967 --7.17266702652,2.0582985878,-6.9298119545 --7.15767383575,2.06029391289,-6.95823192596 --7.13167238235,2.05829596519,-6.97565031052 --7.11167573929,2.05829429626,-7.00007963181 --7.08667516708,2.05729532242,-7.01849985123 --7.07068157196,2.05929112434,-7.04692840576 --7.0496840477,2.05929017067,-7.06934785843 --7.02667617798,2.05529713631,-7.06856536865 --7.01068210602,2.05729293823,-7.09598445892 --6.98768377304,2.05629277229,-7.11741495132 --6.96768760681,2.0572912693,-7.14083480835 --6.94668960571,2.05729007721,-7.16325473785 --6.93470048904,2.06028318405,-7.19567966461 --6.90469551086,2.05728769302,-7.20910406113 --6.9007024765,2.05928301811,-7.22731494904 --6.87970590591,2.06028151512,-7.2507443428 --6.84769964218,2.05628705025,-7.2621717453 --6.82770395279,2.05728507042,-7.28660106659 --6.81071043015,2.05828142166,-7.31301784515 --6.78170681,2.0562851429,-7.32744503021 --6.77471113205,2.0572822094,-7.34265613556 --6.75071287155,2.05728244781,-7.36308860779 --6.72371053696,2.0552854538,-7.37850570679 --6.7037153244,2.05628323555,-7.40293455124 --6.67571258545,2.05428624153,-7.41937255859 --6.64470720291,2.05129146576,-7.43079614639 --6.61970710754,2.05029273033,-7.44922304153 --6.58269643784,2.04630184174,-7.45465755463 --6.59772062302,2.0542845726,-7.49385499954 --6.55470561981,2.04829740524,-7.49329948425 --6.53170633316,2.04729747772,-7.51271438599 --6.51171064377,2.04829573631,-7.53613471985 --6.47670269012,2.04430317879,-7.54457902908 --6.46171188354,2.04729771614,-7.57400083542 --6.4547162056,2.04829502106,-7.58820056915 --6.40569448471,2.04031252861,-7.5796456337 --6.38670015335,2.04130983353,-7.60507392883 --6.37671470642,2.04530072212,-7.64049291611 --6.3427066803,2.0423078537,-7.64893245697 --6.31470346451,2.04031133652,-7.66336011887 --6.30371665955,2.04430317879,-7.69677019119 --6.28270959854,2.04130959511,-7.69699954987 --6.25370502472,2.0393140316,-7.70942211151 --6.24271869659,2.04330539703,-7.74383926392 --6.19770050049,2.03632044792,-7.73929071426 --6.18471193314,2.03931355476,-7.77070331573 --6.16872119904,2.04230809212,-7.80013084412 --6.13271045685,2.03731751442,-7.80456399918 --6.12171220779,2.0383169651,-7.81578063965 --6.10271835327,2.03931427002,-7.84019804001 --6.0717124939,2.03731989861,-7.85062980652 --6.0477142334,2.03732037544,-7.87005996704 --6.03372621536,2.04031348228,-7.90147972107 --5.99671363831,2.03532409668,-7.90391254425 --5.97171449661,2.03532528877,-7.92234659195 --5.96171760559,2.03632378578,-7.93456077576 --5.93071174622,2.03332972527,-7.94499588013 --5.91372013092,2.03632497787,-7.97241449356 --5.88972234726,2.03632545471,-7.99184560776 --5.85971736908,2.03433060646,-8.0032787323 --5.83672046661,2.03433036804,-8.02370643616 --5.81572580338,2.03532838821,-8.04713630676 --5.7887096405,2.03034067154,-8.03635692596 --5.76571178436,2.03034067154,-8.05577754974 --5.75172567368,2.03433275223,-8.08920860291 --5.71671485901,2.03034257889,-8.09263801575 --5.68871212006,2.02934598923,-8.1070766449 --5.67072057724,2.03134250641,-8.13248729706 --5.65271425247,2.02934765816,-8.13370513916 --5.6207075119,2.02635407448,-8.14315128326 --5.5977101326,2.027354002,-8.16257286072 --5.56970739365,2.02535796165,-8.17600536346 --5.54771232605,2.02735638618,-8.19843864441 --5.52671766281,2.02835488319,-8.22085952759 --5.49370908737,2.02536296844,-8.22729682922 --5.47071123123,2.02536296844,-8.24671840668 --5.44669818878,2.0213727951,-8.23994922638 --5.42470312119,2.02237153053,-8.26238250732 --5.40170574188,2.02337193489,-8.2807970047 --5.37570571899,2.02237415314,-8.29723167419 --5.34870481491,2.02237677574,-8.3126707077 --5.3287115097,2.0243742466,-8.33608722687 --5.31571245193,2.02437472343,-8.34531116486 --5.28770875931,2.02237915993,-8.35773944855 --5.26070737839,2.02238225937,-8.37217235565 --5.2327041626,2.02038645744,-8.38460159302 --5.20870637894,2.0213868618,-8.40302753448 --5.17669868469,2.01839470863,-8.41046905518 --5.14969730377,2.01839780807,-8.42490291595 --5.14470863342,2.02139139175,-8.44511222839 --5.10669183731,2.01640510559,-8.4415473938 --5.08569812775,2.01740264893,-8.46497440338 --5.05569267273,2.01640892029,-8.47440910339 --5.04070806503,2.02040052414,-8.50783348083 --5.01470851898,2.02040266991,-8.52427005768 --4.98169851303,2.01741147041,-8.5287065506 --4.97170257568,2.01841020584,-8.54091644287 --4.94370031357,2.0174138546,-8.55435657501 --4.91769981384,2.01741671562,-8.56877994537 --4.88769340515,2.01542329788,-8.57721042633 --4.86970567703,2.01941752434,-8.60663890839 --4.83769702911,2.01642584801,-8.61207389832 --4.81169748306,2.01642775536,-8.62851047516 --4.79369020462,2.01443386078,-8.62773036957 --4.76869106293,2.01443552971,-8.64415550232 --4.74369335175,2.01543688774,-8.66158771515 --4.72270154953,2.01743340492,-8.68702316284 --4.69169425964,2.01544117928,-8.69345664978 --4.66469287872,2.01544475555,-8.7068862915 --4.65069103241,2.01444673538,-8.71310424805 --4.62268781662,2.01345133781,-8.72453403473 --4.59769058228,2.01445221901,-8.74297237396 --4.57269239426,2.01545405388,-8.75939750671 --4.53767824173,2.01146554947,-8.75883865356 --4.51167821884,2.01146793365,-8.77427101135 --4.48968553543,2.01346611977,-8.7966966629 --4.4746837616,2.01346874237,-8.80292892456 --4.44467735291,2.01147556305,-8.81035995483 --4.42268419266,2.01347374916,-8.83278465271 --4.39167642593,2.01148152351,-8.83922386169 --4.36768007278,2.01248168945,-8.85865497589 --4.33967828751,2.01248574257,-8.87109375 --4.30967140198,2.0104932785,-8.87752056122 --4.29667234421,2.01049375534,-8.88674545288 --4.27067327499,2.01149606705,-8.90217876434 --4.23766136169,2.0085067749,-8.90361595154 --4.21166229248,2.00850915909,-8.91904735565 --4.18265628815,2.00751519203,-8.92747688293 --4.15265083313,2.00652194023,-8.93591880798 --4.133664608,2.01051592827,-8.96534442902 --4.11465454102,2.00752401352,-8.96157073975 --4.08765363693,2.00752735138,-8.97500419617 --4.05864715576,2.006534338,-8.98242855072 --4.0326499939,2.00753569603,-8.99987316132 --4.00865459442,2.00853562355,-9.01930236816 --3.97564101219,2.00554728508,-9.01873397827 --3.94964289665,2.00654911995,-9.03517341614 --3.94165301323,2.00954389572,-9.05338287354 --3.90663743019,2.00555706024,-9.05083084106 --3.8826406002,2.00655794144,-9.06824874878 --3.8536362648,2.00556373596,-9.07768630981 --3.82563447952,2.0055680275,-9.09012889862 --3.79963636398,2.00656986237,-9.10656642914 --3.76762485504,2.0035803318,-9.10800170898 --3.75663042068,2.00557851791,-9.12122058868 --3.73063158989,2.0065805912,-9.13665390015 --3.69862031937,2.00359106064,-9.13809013367 --3.67161870003,2.00359511375,-9.15051937103 --3.64963030815,2.00759100914,-9.17695713043 --3.61360955238,2.00260734558,-9.16839504242 --3.60662388802,2.00660014153,-9.19060707092 --3.57762050629,2.00660562515,-9.20105266571 --3.55062007904,2.00660896301,-9.21448612213 --3.52061128616,2.00461745262,-9.21891498566 --3.49962592125,2.00961184502,-9.24835014343 --3.46260166168,2.0036303997,-9.23578739166 --3.43760681152,2.00563073158,-9.25522518158 --3.42861795425,2.00862526894,-9.27444458008 --3.39861130714,2.00763273239,-9.28088378906 --3.36559700966,2.00464510918,-9.27932548523 --3.34561300278,2.0096385479,-9.30974769592 --3.31159687042,2.00565218925,-9.30619430542 --3.28559803963,2.00665473938,-9.32061862946 --3.26160645485,2.00965309143,-9.3430557251 --3.24058866501,2.00566601753,-9.33128643036 --3.21258592606,2.00567126274,-9.34172058105 --3.19260382652,2.01066327095,-9.37414646149 --3.15758419037,2.00667929649,-9.36659145355 --3.12857913971,2.00568580627,-9.3750295639 --3.10458874702,2.00868368149,-9.3984670639 --3.07558226585,2.00769090652,-9.40489673615 --3.06258559227,2.00969099998,-9.41512203217 --3.03759169579,2.01169085503,-9.43455410004 --3.00156807899,2.00670909882,-9.42300033569 --2.97757673264,2.00970745087,-9.44543075562 --2.94957518578,2.00971221924,-9.45686912537 --2.92257547379,2.01071548462,-9.47030067444 --2.89557743073,2.01171803474,-9.4857416153 --2.87856864929,2.0107254982,-9.48296546936 --2.85758638382,2.01571846008,-9.51438999176 --2.82858276367,2.01572442055,-9.52383136749 --2.80459547043,2.01972055435,-9.55027389526 --2.76756548882,2.0127427578,-9.53171253204 --2.73153853416,2.00776290894,-9.5161523819 --2.70554351807,2.00976371765,-9.53458976746 --2.69054102898,2.00976729393,-9.53881645203 --2.65952849388,2.00777864456,-9.53824901581 --2.63855004311,2.0137693882,-9.57368183136 --2.6015188694,2.0067923069,-9.55412483215 --2.572514534,2.00679898262,-9.56256484985 --2.54953217506,2.01179218292,-9.59400749207 --2.53252077103,2.00980114937,-9.58822536469 --2.49849915504,2.005818367,-9.57866859436 --2.47551608086,2.01081204414,-9.60910511017 --2.44450426102,2.00882339478,-9.60954380035 --2.41650247574,2.0098285675,-9.61997795105 --2.38649439812,2.00883746147,-9.62441730499 --2.35849308968,2.00984215736,-9.6358537674 --2.33149766922,2.01184344292,-9.65329647064 --2.31850242615,2.01384305954,-9.66452026367 --2.28949570656,2.01285099983,-9.66994857788 --2.25848388672,2.01086235046,-9.67038917542 --2.23349547386,2.01485943794,-9.6948261261 --2.19947218895,2.01087784767,-9.68327140808 --2.16946697235,2.01088523865,-9.69072246552 --2.15948176384,2.01487851143,-9.71193408966 --2.12846899033,2.0128903389,-9.71137237549 --2.09444475174,2.00890922546,-9.69881725311 --2.0694565773,2.01290655136,-9.7232503891 --2.03643774986,2.00992202759,-9.71670150757 --2.0034134388,2.0049405098,-9.70413589478 --1.97340655327,2.00494909286,-9.70958328247 --1.95538711548,2.00096273422,-9.69580078125 --1.92336940765,1.99797749519,-9.69024467468 --1.8943656683,1.99898433685,-9.69868850708 --1.85933220387,1.99200832844,-9.67713165283 --1.83133161068,1.99401319027,-9.68856906891 --1.80433571339,1.99601519108,-9.70500659943 --1.76729130745,1.98704564571,-9.67245388031 --1.75328874588,1.9870493412,-9.67566490173 --1.72629666328,1.9910492897,-9.69611358643 --1.6922659874,1.98507165909,-9.6775598526 --1.66125047207,1.98308539391,-9.6740026474 --1.63425171375,1.98408901691,-9.68743038177 --1.6032371521,1.98310208321,-9.68487739563 --1.57020783424,1.97812378407,-9.66731834412 --1.55922675133,1.98311519623,-9.69254112244 --1.52418410778,1.97414433956,-9.66198062897 --1.49216151237,1.97116208076,-9.65142631531 --1.46315479279,1.97117054462,-9.65686702728 --1.43213427067,1.96818697453,-9.64830589294 --1.40111374855,1.96520352364,-9.63974475861 --1.37110376358,1.96421408653,-9.64219474792 --1.35408496857,1.96122729778,-9.62941837311 --1.32507550716,1.96123743057,-9.63185596466 --1.29505884647,1.95825147629,-9.62729167938 --1.26403713226,1.95526862144,-9.61773395538 --1.23100423813,1.95029234886,-9.59718608856 --1.20401072502,1.95329344273,-9.61562633514 --1.1729850769,1.94931292534,-9.60206413269 --1.15595829487,1.94433057308,-9.58127880096 --1.12695527077,1.94533705711,-9.59073257446 --1.0969376564,1.94335198402,-9.58517360687 --1.06893122196,1.94336032867,-9.5906047821 --1.03992342949,1.943369627,-9.59504890442 --1.00687539577,1.93440151215,-9.55948638916 --0.979887008667,1.93939995766,-9.5829334259 --0.966892421246,1.94139933586,-9.59414863586 --0.933850169182,1.93442821503,-9.56459999084 --0.906852841377,1.93643152714,-9.57903289795 --0.876838028431,1.93544495106,-9.5764837265 --0.847827255726,1.93445587158,-9.57792472839 --0.818812727928,1.93346905708,-9.57536220551 --0.802796661854,1.93148088455,-9.56559181213 --0.774791121483,1.93148875237,-9.57202529907 --0.744768202305,1.92850661278,-9.56146907806 --0.716774880886,1.932508111,-9.57991886139 --0.686743974686,1.9275302887,-9.5613527298 --0.657740175724,1.9285377264,-9.56980609894 --0.629728972912,1.92854893208,-9.57023429871 --0.614719986916,1.92755651474,-9.56746006012 --0.585702240467,1.92557144165,-9.56189727783 --0.556690692902,1.92558324337,-9.56234169006 --0.526670634747,1.92359972,-9.55479335785 --0.499694883823,1.93059146404,-9.59023952484 --0.471686899662,1.93160116673,-9.59367179871 --0.442684233189,1.93260788918,-9.60312175751 --0.427657902241,1.92762494087,-9.58333587646 --0.396607041359,1.91965842247,-9.54578208923 --0.367585062981,1.91667568684,-9.53622055054 --0.318413257599,1.88377809525,-9.38787841797 --0.290418833494,1.88678026199,-9.40532779694 --0.262410402298,1.8877903223,-9.4087677002 --0.247374325991,1.88081264496,-9.37998580933 --0.218344718218,1.87683415413,-9.36343288422 --0.190323770046,1.87485086918,-9.35486888885 --0.162312060595,1.87486255169,-9.35530948639 --0.13430967927,1.87686932087,-9.36475372314 --0.106291607022,1.87488436699,-9.35919284821 --0.0782944485545,1.87788832188,-9.3736371994 --0.0642792358994,1.87589931488,-9.3648557663 --0.035246361047,1.8719227314,-9.34530830383 --0.0072229783982,1.86894071102,-9.33474826813 --0.00280384672806,1.85503530502,-8.48306655884 -0.0252161342651,1.85603785515,-8.49145317078 -0.0532175526023,1.8540302515,-8.48184299469 -0.0812232196331,1.85302507877,-8.47623348236 -0.0952207669616,1.8510196209,-8.46842956543 -0.122223846614,1.84901332855,-8.46080684662 -0.150230571628,1.84800875187,-8.45619869232 -0.178238525987,1.84800469875,-8.45258903503 -0.206255525351,1.84900557995,-8.45797634125 -0.23425501585,1.84599709511,-8.44637298584 -0.247246190906,1.84298861027,-8.43256187439 -0.275261282921,1.84398853779,-8.43595027924 -0.303263992071,1.84198176861,-8.42734718323 -0.330278664827,1.84298181534,-8.43072128296 -0.358285546303,1.84197735786,-8.42611598969 -0.385277867317,1.83796536922,-8.40750789642 -0.413302302361,1.84197020531,-8.4198884964 -0.426283419132,1.83595621586,-8.39609146118 -0.454290390015,1.8349519968,-8.39148807526 -0.481304138899,1.83595144749,-8.39386367798 -0.510323703289,1.83795368671,-8.40126228333 -0.536312997341,1.83394026756,-8.37964820862 -0.565339446068,1.83694624901,-8.39404010773 -0.591331720352,1.83293449879,-8.37542533875 -0.605334877968,1.8329321146,-8.37262535095 -0.630317032337,1.82691514492,-8.34401130676 -0.659340560436,1.82991957664,-8.35540390015 -0.686342358589,1.82791268826,-8.34579753876 -0.713342368603,1.8259049654,-8.33419322968 -0.741358458996,1.82690572739,-8.33858108521 -0.767356216908,1.82489693165,-8.32496643066 -0.778330624104,1.81787979603,-8.29416751862 -0.808372080326,1.82489383221,-8.32354640961 -0.838403820992,1.82990241051,-8.34293746948 -0.861373007298,1.82087898254,-8.30132865906 -0.88635879755,1.81586420536,-8.27572441101 -0.913365781307,1.81486034393,-8.27111434937 -0.941375255585,1.81485748291,-8.26851463318 -0.953366100788,1.81184911728,-8.25371074677 -0.980379104614,1.81284832954,-8.2550907135 -1.00939679146,1.81484985352,-8.26049137115 -1.03438782692,1.81083774567,-8.23988437653 -1.06139683723,1.81083500385,-8.23727226257 -1.08639192581,1.80782520771,-8.22065925598 -1.10241508484,1.81183338165,-8.23785114288 -1.12740838528,1.80882251263,-8.2192440033 -1.15139365196,1.80380761623,-8.19264125824 -1.18142199516,1.80781459808,-8.20903110504 -1.2054091692,1.80280089378,-8.18442630768 -1.23141336441,1.80179595947,-8.17681407928 -1.25842165947,1.80179286003,-8.17320537567 -1.27041506767,1.79978573322,-8.16040611267 -1.29843223095,1.8017873764,-8.16579151154 -1.32342410088,1.79777574539,-8.14519786835 -1.34942650795,1.79676985741,-8.13559150696 -1.37543082237,1.7957649231,-8.12798023224 -1.42341578007,1.78874337673,-8.08876800537 -1.43742036819,1.78874194622,-8.08697223663 -1.4644317627,1.78974056244,-8.08635902405 -1.48842799664,1.78673195839,-8.07074546814 -1.51040542126,1.77971327305,-8.03516197205 -1.54445815086,1.79073274136,-8.07652664185 -1.5654361248,1.78371477127,-8.04192733765 -1.59043216705,1.78070569038,-8.02533435822 -1.60343801975,1.78070545197,-8.02551937103 -1.62843799591,1.77969837189,-8.01291561127 -1.65243208408,1.77668833733,-7.99431657791 -1.68044745922,1.77768921852,-7.99770593643 -1.70042467117,1.77067124844,-7.96210765839 -1.7314542532,1.77667868137,-7.97949409485 -1.75243735313,1.77066385746,-7.9498925209 -1.7604162693,1.76465010643,-7.92210102081 -1.78843104839,1.76665043831,-7.92449426651 -1.81544554234,1.7686508894,-7.92687273026 -1.83843767643,1.76464033127,-7.90627479553 -1.86344158649,1.7646355629,-7.89766359329 -1.8954719305,1.76964354515,-7.916056633 -1.91545200348,1.76362717152,-7.88246440887 -1.92845714092,1.76362645626,-7.88165330887 -1.9574764967,1.76662909985,-7.88904094696 -1.98348343372,1.7666258812,-7.88343381882 -2.01049518585,1.76762497425,-7.88282108307 -2.03449273109,1.76561713219,-7.86722373962 -2.05748820305,1.76360833645,-7.84962081909 -2.0694861412,1.76160395145,-7.84082746506 -2.09750318527,1.76460587978,-7.84620428085 -2.11949324608,1.76059448719,-7.82261419296 -2.14449810982,1.76059043407,-7.81500148773 -2.17351508141,1.76259183884,-7.81939649582 -2.19550871849,1.75958240032,-7.79979228973 -2.22051310539,1.75957798958,-7.79118490219 -2.22950363159,1.75657045841,-7.77538013458 -2.25751519203,1.75756931305,-7.77378606796 -2.28051352501,1.75556230545,-7.75917816162 -2.30852890015,1.75756335258,-7.76256132126 -2.33654069901,1.75956213474,-7.76096582413 -2.36254954338,1.76056015491,-7.75735092163 -2.38956046104,1.76155900955,-7.75574111938 -2.40155887604,1.76055490971,-7.74695110321 -2.42255163193,1.75754535198,-7.72634267807 -2.45457696915,1.76155078411,-7.73973369598 -2.47556829453,1.75854051113,-7.71713685989 -2.50057435036,1.75853729248,-7.710521698 -2.52357077599,1.75652909279,-7.69293069839 -2.54957985878,1.75752723217,-7.68931531906 -2.55857181549,1.75452053547,-7.67451477051 -2.58558034897,1.75551819801,-7.66991853714 -2.60757732391,1.75351059437,-7.65331220627 -2.63258290291,1.75350701809,-7.6457028389 -2.665610075,1.75851356983,-7.66108942032 -2.69663000107,1.76251649857,-7.66848564148 -2.71662044525,1.75850605965,-7.64488744736 -2.72260475159,1.75449562073,-7.62109518051 -2.74961638451,1.75549519062,-7.62047719955 -2.7706091404,1.75248575211,-7.59888601303 -2.80664396286,1.76049554348,-7.62226438522 -2.83565878868,1.76249623299,-7.62465620041 -2.85865807533,1.76148986816,-7.61005449295 -2.87867999077,1.76649653912,-7.62624406815 -2.89065146446,1.75747799873,-7.58265018463 -2.92066836357,1.76047968864,-7.58704280853 -2.94166398048,1.75847172737,-7.56843805313 -2.96767091751,1.75946879387,-7.56183576584 -2.99568223953,1.76046800613,-7.56023263931 -3.02269268036,1.76246678829,-7.55762052536 -3.03569555283,1.76246511936,-7.55382156372 -3.06571173668,1.76546645164,-7.55721521378 -3.08670759201,1.76345860958,-7.53861236572 -3.11171317101,1.76445531845,-7.53100061417 -3.14172792435,1.76645576954,-7.53240394592 -3.16573023796,1.76645100117,-7.52080154419 -3.18973398209,1.76644694805,-7.51118755341 -3.21676898003,1.77445960045,-7.54236793518 -3.23576021194,1.77144992352,-7.51876974106 -3.26377105713,1.77344882488,-7.51616573334 -3.28977632523,1.77344536781,-7.50757169724 -3.31377887726,1.77344059944,-7.49596834183 -3.34579920769,1.7774438858,-7.50434875488 -3.36879897118,1.77643787861,-7.48975086212 -3.3757891655,1.77343082428,-7.47195720673 -3.40279793739,1.77442896366,-7.46735048294 -3.42880487442,1.77542626858,-7.46074295044 -3.44679379463,1.77141571045,-7.43415641785 -3.47981548309,1.77641940117,-7.44353866577 -3.50381875038,1.77641522884,-7.43292951584 -3.52681875229,1.77540957928,-7.41833305359 -3.54182553291,1.77740967274,-7.41853189468 -3.56482553482,1.77640390396,-7.40393543243 -3.59383869171,1.77840423584,-7.40431976318 -3.61683964729,1.77839899063,-7.39071655273 -3.64685320854,1.7803992033,-7.39111232758 -3.66684770584,1.77839136124,-7.37051773071 -3.69085121155,1.77838730812,-7.35990810394 -3.71086716652,1.78239119053,-7.37010240555 -3.72685527802,1.77838075161,-7.34250450134 -3.75987458229,1.78338336945,-7.34889411926 -3.77886748314,1.78037488461,-7.32630205154 -3.80487394333,1.7813719511,-7.31869745255 -3.83087968826,1.78236889839,-7.31009912491 -3.84488463402,1.78336834908,-7.30829524994 -3.8638792038,1.7803606987,-7.28769159317 -3.8868792057,1.78035509586,-7.27210378647 -3.9178943634,1.78335607052,-7.27449131012 -3.94390153885,1.78435373306,-7.26787757874 -3.97090935707,1.78635156155,-7.26127576828 -3.98689723015,1.78234112263,-7.23269367218 -3.99990224838,1.78334057331,-7.2308754921 -4.03692579269,1.78934490681,-7.24226903915 -4.06393384933,1.79034304619,-7.23665857315 -4.08793640137,1.79033863544,-7.22406101227 -4.1099357605,1.79033315182,-7.20845985413 -4.13393831253,1.79032886028,-7.19586277008 -4.15994358063,1.79032552242,-7.18626880646 -4.16593599319,1.78832006454,-7.17046642303 -4.18893718719,1.78831541538,-7.15686416626 -4.21995210648,1.79131615162,-7.15824842453 -4.2449555397,1.79231214523,-7.14665603638 -4.27596950531,1.79531252384,-7.14704561234 -4.29696750641,1.79430651665,-7.12944841385 -4.31996917725,1.79430198669,-7.11584568024 -4.34098434448,1.79830539227,-7.1250371933 -4.36298370361,1.79730021954,-7.10943746567 -4.39900398254,1.80330300331,-7.11682844162 -4.43602609634,1.80930662155,-7.12621355057 -4.46203184128,1.81030380726,-7.11760520935 -4.47802209854,1.80729484558,-7.09101772308 -4.48501682281,1.80529022217,-7.07721614838 -4.51402616501,1.80728852749,-7.07162094116 -4.53802919388,1.807284832,-7.06001186371 -4.56503677368,1.80928266048,-7.05240631104 -4.60706377029,1.81728804111,-7.06779384613 -4.61905002594,1.81227755547,-7.03620195389 -4.64605665207,1.81427538395,-7.02859449387 -4.66506767273,1.81727683544,-7.03279066086 -4.6870675087,1.81727194786,-7.0171880722 -4.70706415176,1.81526565552,-6.99759578705 -4.7330698967,1.81726276875,-6.98799085617 -4.77209234238,1.8232665062,-6.99837303162 -4.78107404709,1.8172544241,-6.96080112457 -4.81408882141,1.82125520706,-6.96218538284 -4.83309936523,1.82425677776,-6.96637678146 -4.84909105301,1.82124841213,-6.93979644775 -4.87509679794,1.82324552536,-6.93018913269 -4.89509439468,1.82223987579,-6.91158866882 -4.92009830475,1.82323646545,-6.89998674393 -4.94710493088,1.824234128,-6.89138221741 -4.97110700607,1.8252300024,-6.877784729 -4.99612379074,1.83023369312,-6.88898038864 -5.01512098312,1.82922792435,-6.86937665939 -5.0331158638,1.82722103596,-6.84678792953 -5.06713008881,1.83122158051,-6.84718227386 -5.08812952042,1.83121669292,-6.83057546616 -5.11313343048,1.83221316338,-6.81797933578 -5.12713670731,1.83321177959,-6.81318473816 -5.15414237976,1.83420920372,-6.80358362198 -5.17714452744,1.83520531654,-6.7899723053 -5.20615291595,1.83720374107,-6.78336620331 -5.22715091705,1.83719813824,-6.76378583908 -5.24614906311,1.83619272709,-6.74517393112 -5.2681479454,1.83518743515,-6.72659683228 -5.28916025162,1.83918952942,-6.73277902603 -5.32417535782,1.84419035912,-6.73416280746 -5.34317159653,1.84318423271,-6.71257829666 -5.37217950821,1.84518253803,-6.7059674263 -5.39418029785,1.84517800808,-6.6893696785 -5.41618061066,1.84517347813,-6.67277240753 -5.45720100403,1.85217607021,-6.68016052246 -5.45919084549,1.84917020798,-6.65937900543 -5.48519611359,1.85116744041,-6.64876794815 -5.533223629,1.86017239094,-6.66415309906 -5.55121946335,1.85816633701,-6.64255666733 -5.56220817566,1.85415792465,-6.61196994781 -5.59121656418,1.85715615749,-6.60436105728 -5.61321640015,1.85715150833,-6.58677053452 -5.62121343613,1.85614824295,-6.57497167587 -5.6422123909,1.85614335537,-6.55638122559 -5.64319229126,1.849132061,-6.51479673386 -5.50603342056,1.79307353497,-6.30437421799 -5.51902627945,1.79006707668,-6.27877950668 -5.52601385117,1.78605854511,-6.24519920349 -5.53800535202,1.78305160999,-6.21761608124 -5.54800605774,1.78304982185,-6.20980787277 -5.55699539185,1.77904224396,-6.17922401428 -5.56898784637,1.77603542805,-6.15164422989 -5.5849852562,1.77403044701,-6.13004732132 -5.58396482468,1.7670198679,-6.08748292923 -5.58995246887,1.76201164722,-6.05390357971 -5.61696052551,1.76501059532,-6.0462846756 -5.59993600845,1.75600039959,-6.00651884079 -5.61893606186,1.75499641895,-5.98792934418 -5.63493299484,1.75399160385,-5.96633911133 -5.63391542435,1.74698197842,-5.92576646805 -5.64791107178,1.74497687817,-5.90217828751 -5.66390895844,1.74397230148,-5.88059091568 -5.65389156342,1.73696482182,-5.84981775284 -5.66888904572,1.73596036434,-5.82822179794 -5.68388652802,1.73495590687,-5.80662584305 -5.68987607956,1.72994887829,-5.77504348755 -5.69886827469,1.72694277763,-5.74646234512 -5.71186447144,1.7249379158,-5.72287034988 -5.72486019135,1.72293293476,-5.69829034805 -5.72585344315,1.71992909908,-5.68050289154 -5.74185228348,1.71992516518,-5.65991210938 -5.74884414673,1.71591901779,-5.63032627106 -5.76183986664,1.71391451359,-5.60673856735 -5.78284406662,1.71491205692,-5.59213542938 -5.78883504868,1.71090590954,-5.56155395508 -5.79782819748,1.70790052414,-5.53397226334 -5.80682849884,1.70789897442,-5.52517271042 -5.80881690979,1.70289206505,-5.49059867859 -5.82081270218,1.69988751411,-5.46601772308 -5.83881378174,1.69988441467,-5.44743156433 -5.84680747986,1.69687926769,-5.41984462738 -5.85680294037,1.69487464428,-5.3942565918 -5.86980628967,1.69587397575,-5.38846492767 -5.87579917908,1.69286870956,-5.35987091064 -5.89079809189,1.69186532497,-5.33927869797 -5.90279531479,1.68986129761,-5.3156914711 -5.91779470444,1.68885803223,-5.2951002121 -5.92578840256,1.68585324287,-5.2675204277 -5.93478393555,1.68284869194,-5.24094104767 -5.94178342819,1.68284702301,-5.23014688492 -5.94777679443,1.67984211445,-5.20156145096 -5.96077489853,1.67783856392,-5.17897748947 -5.96776914597,1.67483401299,-5.15139293671 -5.98276853561,1.67383098602,-5.13080644608 -5.98876285553,1.6708265543,-5.10321426392 -5.99775838852,1.66882228851,-5.0766415596 -6.00275707245,1.66782057285,-5.06484222412 -6.01275396347,1.66581678391,-5.03926897049 -6.0267534256,1.66481387615,-5.01867580414 -6.03274774551,1.66180968285,-4.99108839035 -6.04374551773,1.65980637074,-4.96750354767 -6.05974721909,1.65980398655,-4.94890642166 -6.06774282455,1.65680015087,-4.92233085632 -6.06673765182,1.65479755402,-4.90553712845 -6.07573413849,1.65279400349,-4.87996006012 -6.0937371254,1.65279209614,-4.86237239838 -6.10673713684,1.65178954601,-4.84177303314 -6.10972976685,1.64778518677,-4.81120347977 -6.12573194504,1.64778316021,-4.79260969162 -6.13472890854,1.64577972889,-4.76703739166 -6.13272380829,1.64277744293,-4.75023937225 -6.14472341537,1.64177465439,-4.72765922546 -6.15071964264,1.63977134228,-4.70107269287 -6.16271829605,1.63776874542,-4.67849445343 -6.17371749878,1.6367661953,-4.65590620041 -6.18771839142,1.6357640028,-4.63532209396 -6.18771505356,1.6337621212,-4.62052202225 -6.20471811295,1.63476037979,-4.60194015503 -6.20771217346,1.63075685501,-4.57335805893 -6.22171354294,1.63075482845,-4.55277490616 -6.22771024704,1.62775182724,-4.5261964798 -6.24271249771,1.62775015831,-4.50759792328 -6.24971008301,1.62574744225,-4.48201704025 -6.25571012497,1.62574648857,-4.47122335434 -6.26570940018,1.62374424934,-4.44863176346 -6.27170658112,1.62174153328,-4.42205762863 -6.28670835495,1.62173998356,-4.40247392654 -6.3007106781,1.62173855305,-4.38386678696 -6.30170536041,1.61773514748,-4.3533039093 -6.32271099091,1.61973452568,-4.33870744705 -6.32370853424,1.61773300171,-4.32392454147 -6.32970619202,1.61573076248,-4.2993273735 -6.32870006561,1.6107275486,-4.26776504517 -6.34470319748,1.61172652245,-4.25016498566 -6.3497004509,1.60872411728,-4.22359037399 -6.36370277405,1.60872280598,-4.20399999619 -6.36669921875,1.60572040081,-4.17642259598 -6.36669683456,1.60371899605,-4.16163539886 -6.37469673157,1.60271716118,-4.13804864883 -6.37869358063,1.59971499443,-4.11146974564 -6.3906955719,1.59971380234,-4.0908780098 -6.40269708633,1.59871256351,-4.07028722763 -6.40669488907,1.59571063519,-4.04371118546 -6.4086933136,1.59470951557,-4.02993059158 -6.41569280624,1.5927079916,-4.00634002686 -6.42169189453,1.59070634842,-3.98076987267 -6.43669509888,1.59170567989,-3.96217799187 -6.43669128418,1.58770346642,-3.93360114098 -6.44369125366,1.58570218086,-3.91001343727 -6.45369243622,1.58570110798,-3.88743782043 -6.45469141006,1.58370029926,-3.87463784218 -6.47169542313,1.58469974995,-3.85705018044 -6.4726934433,1.58169817924,-3.82947206497 -6.47769212723,1.57969665527,-3.80390024185 -6.48669338226,1.57869589329,-3.78230381012 -6.4876909256,1.57569432259,-3.75472950935 -6.5006942749,1.57569372654,-3.73513889313 -6.50869607925,1.57569360733,-3.72535657883 -6.50769329071,1.57269215584,-3.69776773453 -6.51569414139,1.57169115543,-3.67419576645 -6.53469991684,1.57269120216,-3.6585958004 -6.53369760513,1.56968986988,-3.63002562523 -6.55370378494,1.57168996334,-3.61541795731 -6.56170511246,1.57068932056,-3.59184765816 -6.55370044708,1.56668829918,-3.57405614853 -6.56770467758,1.56768798828,-3.55447506905 -6.58471012115,1.56868803501,-3.53688812256 -6.58370733261,1.56568706036,-3.50930833817 -6.5917096138,1.56468653679,-3.48672556877 -6.62071943283,1.56868720055,-3.476126194 -6.59971046448,1.56168568134,-3.4503595829 -6.60371017456,1.55968523026,-3.42577767372 -6.63072013855,1.5636857748,-3.41417622566 -6.62371587753,1.5586848259,-3.38360214233 -6.62171363831,1.55568420887,-3.35503768921 -6.64872360229,1.55968475342,-3.34343457222 -6.6397190094,1.55468392372,-3.31186485291 -6.6497220993,1.55568420887,-3.30406737328 -6.66772842407,1.55768442154,-3.28747105598 -6.66572713852,1.55368387699,-3.25989603996 -6.67472982407,1.5536839962,-3.23831033707 -6.68373298645,1.55268406868,-3.21672534943 -6.67773008347,1.54868364334,-3.18715500832 -6.68473243713,1.54768383503,-3.16457223892 -6.69773721695,1.54968416691,-3.1577796936 -6.6957359314,1.54668402672,-3.13119482994 -6.69473552704,1.54368400574,-3.10363483429 -6.71574306488,1.54568469524,-3.08902788162 -6.7067399025,1.54168450832,-3.05845952034 -6.71874427795,1.54168498516,-3.03886771202 -6.72774744034,1.54168534279,-3.0163025856 -6.72574710846,1.53968548775,-3.00251412392 -6.72874832153,1.53768587112,-2.97892355919 -6.74975633621,1.54068660736,-2.96333026886 -6.75275754929,1.53868699074,-2.93875670433 -6.74175453186,1.53368723392,-2.90818428993 -6.75876140594,1.53568804264,-2.8905954361 -6.75275945663,1.53268826008,-2.87481546402 -6.7577624321,1.53168880939,-2.85222625732 -6.77476835251,1.53268969059,-2.83463692665 -6.76976823807,1.52969026566,-2.8070628643 -6.77276992798,1.52769100666,-2.7824947834 -6.78377485275,1.52869176865,-2.76289772987 -6.77877473831,1.52469265461,-2.73532795906 -6.78877878189,1.52569305897,-2.72752642632 -6.80078363419,1.52669394016,-2.70695304871 -6.80778694153,1.52569484711,-2.68536376953 -6.80778837204,1.52369582653,-2.66077947617 -6.8137922287,1.52269697189,-2.63820147514 -6.81579494476,1.52169799805,-2.61363148689 -6.81479549408,1.51969850063,-2.60084295273 -6.8217997551,1.51969969273,-2.5792555809 -6.83080387115,1.51970076561,-2.55768108368 -6.83980846405,1.5197019577,-2.53708982468 -6.83781003952,1.51670324802,-2.51151537895 -6.85181617737,1.51870429516,-2.49292135239 -6.85682010651,1.51770567894,-2.46935677528 -6.85882139206,1.51670634747,-2.45855498314 -6.8568239212,1.51470780373,-2.43298339844 -6.86882972717,1.51570904255,-2.4133939743 -6.88083553314,1.51571035385,-2.39380431175 -6.87483644485,1.51271212101,-2.36624574661 -6.88284111023,1.51271355152,-2.34565019608 -6.88384389877,1.51071512699,-2.32108306885 -6.88984727859,1.51171588898,-2.31128811836 -6.89785194397,1.51171731949,-2.28971004486 -6.89985513687,1.50971901417,-2.26711583138 -6.90085935593,1.50872075558,-2.2425506115 -6.91786623001,1.51072216034,-2.22495388985 -6.92387104034,1.50972390175,-2.20238280296 -6.92987585068,1.50972568989,-2.18079400063 -6.92787694931,1.50872659683,-2.16800737381 -6.93388175964,1.50772845745,-2.14641976357 -6.93588542938,1.50673031807,-2.12284564972 -6.94089031219,1.50573217869,-2.10125303268 -6.94989585876,1.50673401356,-2.07968139648 -6.94989967346,1.50473618507,-2.05609846115 -6.94990110397,1.50373721123,-2.04430747032 -6.96290826797,1.50573885441,-2.02472114563 -6.96491193771,1.50374102592,-2.00114965439 -6.97191762924,1.50374305248,-1.97956848145 -6.97492265701,1.50274515152,-1.95698523521 -6.95592212677,1.49674832821,-1.92741906643 -6.97593069077,1.49974989891,-1.90983128548 -6.97293233871,1.49875128269,-1.89704537392 -6.97093582153,1.49675381184,-1.8724758625 -6.96093845367,1.49275672436,-1.8459059 -6.98394727707,1.49675834179,-1.82931244373 -6.97895050049,1.49376106262,-1.80473172665 -6.98795700073,1.49476325512,-1.78414404392 -6.98596143723,1.49276578426,-1.76056075096 -6.99496555328,1.49376678467,-1.75077795982 -7.00297164917,1.49476909637,-1.73018550873 -7.01497888565,1.49577116966,-1.70961022377 -7.00198125839,1.49177467823,-1.68303477764 -7.00998735428,1.49177706242,-1.66146087646 -7.00699186325,1.4897800684,-1.63787662983 -7.02199983597,1.49178218842,-1.61829555035 -6.99499702454,1.48478519917,-1.59952569008 -7.00100326538,1.48478782177,-1.57794475555 -6.97600412369,1.47779214382,-1.54838478565 -7.01401662827,1.4857929945,-1.5347867012 -7.02702379227,1.48679530621,-1.51519668102 -6.962018013,1.47080230713,-1.47665190697 -7.03103256226,1.48579955101,-1.48182368279 -7.03303861618,1.48580265045,-1.45924532413 -7.01204013824,1.47880709171,-1.4316740036 -6.96203804016,1.46681380272,-1.39614546299 -7.01805257797,1.4788132906,-1.38652920723 -7.03706169128,1.48181533813,-1.3679407835 -6.98505926132,1.46882224083,-1.3333966732 -6.99706411362,1.47082304955,-1.32460272312 -6.92305850983,1.45283162594,-1.28606510162 -6.95706987381,1.45883285999,-1.2704757452 -6.99808216095,1.46783339977,-1.25686883926 -6.86506843567,1.43584656715,-1.20637643337 -6.79306459427,1.4188555479,-1.16885447502 -6.87608337402,1.43685305119,-1.16421663761 -6.92809391022,1.44785094261,-1.16438066959 -6.97610712051,1.45785105228,-1.1517701149 -6.81809186935,1.42086708546,-1.09731626511 -6.87210607529,1.4318665266,-1.08668756485 -6.94112253189,1.44686496258,-1.07805931568 -6.93912887573,1.44586896896,-1.05548286438 -6.91813278198,1.43987464905,-1.02892923355 -6.93813896179,1.44387507439,-1.02113473415 -6.94214677811,1.44387853146,-1.0005389452 -6.92215108871,1.43888413906,-0.974973082542 -6.92615842819,1.43888783455,-0.953397393227 -6.92216539383,1.43689215183,-0.930820226669 -6.89716959,1.43089842796,-0.904266893864 -6.89717340469,1.42990040779,-0.893475413322 -6.89217996597,1.42890501022,-0.870898902416 -6.85018253326,1.41791296005,-0.84235060215 -6.90919685364,1.43091201782,-0.829735517502 -6.85819864273,1.41892063618,-0.80019068718 -6.85820627213,1.41792500019,-0.77861148119 -6.89521837234,1.42592608929,-0.762015998363 -6.9142241478,1.42892634869,-0.754208624363 -6.91223144531,1.42793095112,-0.731641948223 -6.85723352432,1.41494035721,-0.703085422516 -6.84024000168,1.41094648838,-0.678532481194 -6.85824966431,1.41394913197,-0.659932672977 -6.80525255203,1.40195870399,-0.63139384985 -6.80226039886,1.39996361732,-0.609815478325 -6.78226280212,1.39596772194,-0.597032546997 -6.80027246475,1.39897072315,-0.577452898026 -6.82828378677,1.40497255325,-0.559848606586 -6.82429122925,1.40297758579,-0.538268864155 -6.78229665756,1.39298653603,-0.511729538441 -6.78830528259,1.39399063587,-0.491148561239 -6.70130681992,1.37400436401,-0.460632503033 -6.76031589508,1.38700067997,-0.456793963909 -6.78632640839,1.39200282097,-0.438201278448 -6.75133275986,1.38401126862,-0.413646668196 -6.7303404808,1.37901854515,-0.390093743801 -6.76635169983,1.38701975346,-0.372490346432 -6.76436042786,1.38602471352,-0.35190102458 -6.77136516571,1.38702642918,-0.342105180025 -6.77137422562,1.38703155518,-0.320537537336 -6.76338291168,1.38503742218,-0.298962801695 -6.78239345551,1.38904035091,-0.27937322855 -6.80540370941,1.39304304123,-0.259784966707 -6.76741027832,1.38505220413,-0.236227169633 -6.78142023087,1.38705563545,-0.216631263494 -6.76642417908,1.38405990601,-0.204857543111 -6.81243610382,1.39405977726,-0.187239944935 -6.70643949509,1.37007701397,-0.15973341465 -6.73045015335,1.3750795126,-0.140143290162 -6.75146055222,1.37908232212,-0.120549172163 -6.76447105408,1.38208627701,-0.099969394505 -6.76647567749,1.38208854198,-0.0901677981019 -6.76148509979,1.38109445572,-0.0686011984944 -6.78249549866,1.38509738445,-0.0490011498332 -6.7515039444,1.3791064024,-0.0264504346997 -6.7665143013,1.38211011887,-0.00586784817278 -6.65551948547,1.35712862015,0.0186388734728 -6.62452888489,1.35013771057,0.0401952117682 -6.67953538895,1.36213386059,0.0480372197926 -6.72954702377,1.37313330173,0.0676430314779 -6.68055534363,1.36214482784,0.0891955941916 -6.65756511688,1.35715329647,0.110748745501 -6.62257385254,1.34916305542,0.13131518662 -6.78558921814,1.38514876366,0.149992629886 -6.71259689331,1.36916327477,0.171525925398 -6.71860265732,1.37016558647,0.182309195399 -6.72661304474,1.37217020988,0.202894866467 -6.73462295532,1.3741748333,0.22348152101 -6.73063373566,1.37318086624,0.244061157107 -6.70864295959,1.36818933487,0.264627367258 -6.77565479279,1.38318681717,0.286240577698 -6.76565980911,1.38119077682,0.29603484273 -6.84467220306,1.39918661118,0.318648487329 -6.7336807251,1.37420666218,0.338153749704 -6.71569013596,1.37021458149,0.357738167048 -6.69570064545,1.36522316933,0.378298193216 -6.68171167374,1.36223089695,0.398862749338 -6.7117228508,1.36923289299,0.420457810163 -6.72672843933,1.37323391438,0.431256890297 -6.69273853302,1.36524438858,0.450815677643 -6.71974945068,1.37224674225,0.472412437201 -6.72476053238,1.37325191498,0.493001461029 -6.70077085495,1.36826109886,0.512569010258 -6.6897816658,1.36526870728,0.533133268356 -6.73579263687,1.37626850605,0.555746972561 -6.76379823685,1.38226771355,0.567553937435 -6.78980970383,1.38927030563,0.590143322945 -6.81282043457,1.3942732811,0.612730562687 -6.97083044052,1.42925775051,0.643403530121 -6.80384206772,1.39228665829,0.653891265392 -7.12185049057,1.46424913406,0.69665145874 -6.8338637352,1.40029478073,0.69806843996 -6.7828707695,1.38930499554,0.70581138134 -6.72288179398,1.37531960011,0.722354054451 -6.85089159012,1.40530788898,0.753012835979 -6.80890321732,1.39631986618,0.770572602749 -6.73691606522,1.38033640385,0.786099612713 -6.73892736435,1.38134217262,0.806690037251 -6.72993278503,1.37934672832,0.816471815109 -6.74994421005,1.38435018063,0.839066028595 -6.76295518875,1.38735473156,0.861645698547 -6.7529668808,1.3853623867,0.881228387356 -6.70197963715,1.37537634373,0.8977637887 -6.70999097824,1.37738156319,0.919350206852 -6.74300193787,1.38538324833,0.943946480751 -6.77000761032,1.39138257504,0.957745313644 -6.74501943588,1.38639247417,0.975324392319 -6.75003099442,1.38839828968,0.996907830238 -6.74204301834,1.38640594482,1.01747369766 -6.73505496979,1.3854136467,1.03804206848 -6.73106718063,1.38542079926,1.05861914158 -6.63708209991,1.36544120312,1.0671530962 -6.67008686066,1.37243962288,1.08195948601 -6.67309951782,1.37444579601,1.10353553295 -6.63211297989,1.36545872688,1.1190867424 -6.65012359619,1.3704624176,1.14169168472 -6.5951385498,1.35847747326,1.15522921085 -6.63814878464,1.36947762966,1.18184220791 -6.63815498352,1.36948108673,1.19262504578 -6.68016576767,1.37948155403,1.2202218771 -6.67617797852,1.37948894501,1.24079668522 -6.6401925087,1.37250125408,1.25635266304 -6.62520551682,1.36951029301,1.27492344379 -6.63721656799,1.37251520157,1.29751634598 -6.60523080826,1.36652696133,1.31307995319 -6.61323690414,1.36852908134,1.32487463951 -6.60924959183,1.36853671074,1.34544634819 -6.59026288986,1.36554658413,1.36301696301 -6.56727695465,1.36055696011,1.37958872318 -6.57928943634,1.36456215382,1.40316534042 -6.59230136871,1.36856710911,1.42674803734 -6.60731267929,1.37257170677,1.45034110546 -6.59631919861,1.37057673931,1.45813798904 -6.57833385468,1.36758685112,1.47668874264 -6.59334564209,1.37159132957,1.50028455257 -6.73934841156,1.405575037,1.54995703697 -6.60237073898,1.37560403347,1.54444754124 -6.57738447189,1.37061500549,1.56002271175 -6.60339593887,1.377617836,1.58661699295 -6.61640167236,1.38161945343,1.60040581226 -6.57541751862,1.37263309956,1.61296224594 -6.6304268837,1.3866314888,1.64656436443 -6.6064414978,1.38264238834,1.66214168072 -6.60045528412,1.38165068626,1.68270742893 -6.60146808624,1.38265764713,1.70428848267 -6.65247058868,1.395652771,1.72611749172 -6.61848640442,1.38866579533,1.74066209793 -6.50350856781,1.36369180679,1.73517692089 -6.48752307892,1.36070156097,1.7517632246 -6.52953290939,1.3717019558,1.78336107731 -6.57054281235,1.38270258904,1.81495952606 -6.56355667114,1.38171088696,1.83453881741 -6.56456279755,1.38271439075,1.84533345699 -6.57457590103,1.38572025299,1.86990880966 -6.50059604645,1.37073981762,1.87244915962 -6.48561048508,1.36874973774,1.8900192976 -6.53761911392,1.38174819946,1.92463684082 -6.54463195801,1.38475453854,1.94821822643 -6.48364448547,1.37076866627,1.94296848774 -6.52165460587,1.3807696104,1.97457289696 -6.57566308975,1.39476788044,2.01118016243 -6.57067728043,1.39477622509,2.03175497055 -6.55069303513,1.39178717136,2.04831767082 -6.49471187592,1.37980413437,2.05387306213 -6.47772693634,1.37781453133,2.07044792175 -6.35474586487,1.3498390913,2.04517841339 -6.3767580986,1.35584318638,2.07375407219 -6.40976858139,1.36584496498,2.1043639183 -6.42978048325,1.37184906006,2.13195419312 -6.39979743958,1.3658618927,2.14451742172 -6.48880243301,1.3878544569,2.19413304329 -6.46681833267,1.38486564159,2.20871138573 -6.4638261795,1.38487029076,2.2194852829 -6.51483440399,1.39786887169,2.25710082054 -6.53884553909,1.40487229824,2.28669786453 -6.43287134171,1.38189852238,2.2752122879 -6.40088891983,1.37591195107,2.28677415848 -6.51789045334,1.40489923954,2.34741401672 -6.50990533829,1.40490829945,2.36699175835 -6.54890775681,1.41490519047,2.39081025124 -6.53192424774,1.41291618347,2.40836691856 -6.55893468857,1.41991901398,2.43996357918 -6.48495721817,1.40493965149,2.43651485443 -6.5149679184,1.41294205189,2.46911644936 -6.46298885345,1.40295910835,2.47366428375 -6.4739947319,1.40696132183,2.48944807053 -6.5549993515,1.42695486546,2.54106879234 -6.55301332474,1.42896282673,2.56265807152 -6.47203779221,1.41098511219,2.55619239807 -6.50304889679,1.41998755932,2.59078025818 -6.52306032181,1.42699170113,2.62038350105 -6.50107717514,1.42300343513,2.63495469093 -6.57007598877,1.44099509716,2.67277503014 -6.5820889473,1.44600081444,2.70036530495 -6.57910346985,1.44700932503,2.72293663025 -6.54412221909,1.44002354145,2.7325026989 -6.51814031601,1.43603622913,2.74606156349 -6.55714988708,1.44703722,2.7846634388 -6.56816291809,1.45204305649,2.81225419044 -6.57216978073,1.4540463686,2.82603907585 -6.54918718338,1.45005834103,2.83962035179 -6.54420280457,1.45106756687,2.862180233 -6.51922035217,1.44707989693,2.874761343 -6.54123258591,1.45508420467,2.90833806992 -6.51425075531,1.45009720325,2.9209022522 -6.51725769043,1.45210063457,2.93369960785 -6.5002746582,1.45011174679,2.95027065277 -6.50528860092,1.45311880112,2.97585892677 -6.49630498886,1.45312869549,2.99642419815 -6.48732089996,1.45313835144,3.01600670815 -6.45034122467,1.44715332985,3.02356982231 -6.43935728073,1.44616341591,3.04215145111 -6.4493637085,1.45016586781,3.05893945694 -6.47037553787,1.45717012882,3.09252643585 -6.46239185333,1.45717990398,3.11310100555 -6.44940900803,1.45719063282,3.13166880608 -6.44942378998,1.45919859409,3.15525865555 -6.41644430161,1.45321309566,3.16481137276 -6.40445280075,1.4512193203,3.17060756683 -6.39746904373,1.45222878456,3.19118976593 -6.39648485184,1.45423746109,3.21575522423 -6.32351016998,1.43825912476,3.20431423187 -6.38251638412,1.45525658131,3.25692176819 -6.3565363884,1.45126986504,3.26947546005 -6.28056335449,1.43529236317,3.25602960587 -6.32656383514,1.44728791714,3.29083943367 -6.32357931137,1.44929683208,3.31342339516 -6.32559490204,1.45230484009,3.33900213242 -6.33860874176,1.45831096172,3.37057971954 -6.33862400055,1.46031939983,3.39516091347 -6.32964086533,1.46132957935,3.41572976112 -6.32865619659,1.46333801746,3.43932080269 -6.31766605377,1.46234428883,3.44610476494 -6.31268215179,1.4633538723,3.46867704391 -6.31669664383,1.46736133099,3.49526643753 -6.28171825409,1.46037662029,3.50182890892 -6.27973413467,1.46338534355,3.5254137516 -6.289747715,1.4683920145,3.55599570274 -6.2617688179,1.46340608597,3.56655359268 -6.26477575302,1.46640956402,3.58035182953 -6.26779079437,1.46941745281,3.60693764687 -6.24880933762,1.4674295187,3.62151312828 -6.23082828522,1.4654417038,3.63708043098 -6.2268447876,1.46745085716,3.65966725349 -6.20986366272,1.46646296978,3.676227808 -6.20987176895,1.46746730804,3.68901634216 -6.20688819885,1.46947646141,3.71259832382 -6.17890882492,1.46549057961,3.72216415405 -6.17592525482,1.46749973297,3.74574661255 -6.17794132233,1.47050821781,3.77331495285 -6.14996194839,1.46652197838,3.78189373016 -6.14197921753,1.4675321579,3.80247712135 -6.15598487854,1.47253406048,3.82426357269 -6.13000535965,1.46854758263,3.83384442329 -6.11802387238,1.46855890751,3.85340428352 -6.12603855133,1.4735660553,3.88399100304 -6.11105728149,1.4735776186,3.90056967735 -6.08907747269,1.47059059143,3.91314005852 -6.08709430695,1.47360002995,3.93870806694 -6.07810354233,1.47260594368,3.94550538063 -6.06012296677,1.47061812878,3.96008348465 -6.06113862991,1.47362673283,3.98666858673 -6.03216123581,1.46964132786,3.99522614479 -6.02617835999,1.47165131569,4.0178027153 -6.02619457245,1.47465991974,4.04339599609 -6.00021600723,1.47067427635,4.05395078659 -5.99922466278,1.47267889977,4.06673717499 -5.99324226379,1.47368907928,4.08931589127 -5.97426176071,1.47270143032,4.10289669037 -5.96827936172,1.47371149063,4.12547588348 -5.96729660034,1.47772073746,4.1520485878 -5.94531726837,1.4747338295,4.16362714767 -5.94232559204,1.47573876381,4.17442560196 -5.93534374237,1.47774922848,4.19699668884 -5.91436481476,1.47476255894,4.21055364609 -5.90638256073,1.47677278519,4.23114585876 -5.89740133286,1.47778356075,4.25172662735 -5.88442087173,1.47779524326,4.27029466629 -5.86843156815,1.47480273247,4.27208757401 -5.86644935608,1.4778124094,4.29865598679 -5.84946918488,1.47682487965,4.31422472 -5.83948802948,1.47783565521,4.33381128311 -5.83150625229,1.47884631157,4.35539102554 -5.81052732468,1.47685956955,4.36795949936 -5.79654693604,1.47687149048,4.38553190231 -5.80155420303,1.47987484932,4.40233373642 -5.77957630157,1.47788870335,4.41489028931 -5.78159236908,1.48189711571,4.44348144531 -5.76661252975,1.48190915585,4.46005821228 -5.75063228607,1.48092150688,4.47563838959 -5.73965215683,1.4819329977,4.4962015152 -5.72767114639,1.4819444418,4.51478338242 -5.72068119049,1.48195040226,4.52357006073 -5.70870065689,1.48296189308,4.54215192795 -5.69572067261,1.48297381401,4.56072282791 -5.67874145508,1.48198652267,4.57629013062 -5.6697602272,1.48399734497,4.59687900543 -5.65977954865,1.48500883579,4.6184425354 -5.64080095291,1.48402190208,4.63201522827 -5.64780807495,1.48802471161,4.65082406998 -5.63382768631,1.48803675175,4.66839885712 -5.61184978485,1.48505055904,4.67996406555 -5.60186958313,1.48706185818,4.70054388046 -5.59088897705,1.48807322979,4.72012662888 -5.57490968704,1.48708593845,4.73669147491 -5.5689201355,1.48809182644,4.74647760391 -5.54794168472,1.48610532284,4.75805234909 -5.54296016693,1.48811542988,4.78263807297 -5.52198171616,1.48712909222,4.79421281815 -5.51500082016,1.4891397953,4.81779003143 -5.49602222443,1.4881529808,4.83136034012 -5.49104166031,1.4911634922,4.85693597794 -5.47905302048,1.48917067051,4.8617181778 -5.46607303619,1.49018239975,4.87930679321 -5.45109367371,1.49019467831,4.89588499069 -5.43911409378,1.49120664597,4.91545915604 -5.42913389206,1.492218256,4.93703079224 -5.40515708923,1.49023234844,4.94560670853 -5.39917564392,1.49224305153,4.97018814087 -5.39018630981,1.49224948883,4.97697925568 -5.37820720673,1.49326121807,4.99655580521 -5.36622810364,1.49427354336,5.01711845398 -5.35124826431,1.49428594112,5.03369760513 -5.3382692337,1.49529790878,5.05227565765 -5.31929111481,1.49431121349,5.06485795975 -5.31530094147,1.49531662464,5.07664585114 -5.30432128906,1.49632847309,5.09722328186 -5.29434156418,1.49833989143,5.11880207062 -5.27236413956,1.49635398388,5.12937164307 -5.25838518143,1.49736630917,5.14695167542 -5.24940538406,1.4993776083,5.16953086853 -5.23242664337,1.49839043617,5.18411302567 -5.23243618011,1.50139558315,5.2008895874 -5.21945714951,1.50240767002,5.21947145462 -5.19648075104,1.50042200089,5.22904062271 -5.18750047684,1.50243330002,5.25162315369 -5.17952013016,1.50544428825,5.27520751953 -5.16154289246,1.50445783138,5.28977680206 -5.14256572723,1.50347137451,5.30334568024 -5.14557361603,1.50747549534,5.32214212418 -5.12759542465,1.50648856163,5.33572435379 -5.11261749268,1.50750148296,5.35329580307 -5.10563755035,1.51051259041,5.37887334824 -5.08266115189,1.50852668285,5.38745212555 -5.072681427,1.51053845882,5.41002893448 -5.06669235229,1.51154458523,5.42081022263 -5.05271339417,1.51155686378,5.43839693069 -5.03473615646,1.51157033443,5.45296812057 -5.02475690842,1.5135819912,5.47554731369 -5.00378036499,1.51259601116,5.48612737656 -4.99080133438,1.51360821724,5.50570392609 -4.98682069778,1.5186188221,5.53528165817 -4.97883176804,1.5186252594,5.54307508469 -4.96685266495,1.51963734627,5.56365633011 -4.95387411118,1.52164959908,5.58323669434 -4.92989873886,1.51866447926,5.59179925919 -4.91492080688,1.51967740059,5.60937690735 -4.9079413414,1.52368843555,5.63595676422 -4.88995504379,1.52069735527,5.63373327255 -4.88297510147,1.52370834351,5.66031455994 -4.87499523163,1.52671945095,5.68490791321 -4.85001993179,1.52473449707,5.69147968292 -4.84004116058,1.52674627304,5.71505784988 -4.83006191254,1.52975809574,5.73863840103 -4.81108522415,1.52877175808,5.7522110939 -4.80909538269,1.53177726269,5.76799726486 -4.79411745071,1.53279006481,5.78558015823 -4.77114152908,1.53080463409,5.79415512085 -4.76416254044,1.53481602669,5.82272386551 -4.75918197632,1.53882682323,5.85231208801 -4.72720861435,1.5348430872,5.84988546371 -4.71323013306,1.5358556509,5.86847257614 -4.7182393074,1.54085993767,5.89424991608 -4.68926525116,1.53687548637,5.89482975006 -4.68228530884,1.54088664055,5.92241716385 -3.48860692978,1.12314462662,4.47454023361 -3.46263313293,1.1191599369,4.47010946274 -3.44465756416,1.11717379093,4.47567987442 -3.45767378807,1.12718105316,4.52026748657 -3.44168686867,1.12418889999,4.51306724548 -4.58941173553,1.54396009445,6.0110912323 -4.58043336868,1.54797184467,6.03766918182 -4.45548439026,1.50900769234,5.91420412064 -4.4844956398,1.5260117054,5.98979473114 -4.52450418472,1.54801309109,6.07940292358 -4.52151441574,1.55001866817,6.09518909454 -4.50653743744,1.55203163624,6.11377096176 -4.48856115341,1.55204534531,6.12934207916 -4.42159748077,1.5340692997,6.07889795303 -4.44561052322,1.55007433891,6.15048837662 -4.44063091278,1.55608522892,6.18307161331 -4.39866018295,1.54710364342,6.16464710236 -4.41566514969,1.55710494518,6.20744943619 -4.37769460678,1.55012309551,6.19600868225 -4.26774215698,1.51515591145,6.08255672455 -4.28075790405,1.52716302872,6.14014625549 -4.29277420044,1.53917074203,6.19772672653 -4.33878135681,1.56517100334,6.3033285141 -4.28180599213,1.54618775845,6.24210500717 -4.30981731415,1.56519174576,6.32270383835 -4.29884004593,1.56820428371,6.34927368164 -4.2668671608,1.56322073936,6.34385251999 -4.25488996506,1.56623339653,6.36842918396 -4.23791360855,1.5672467947,6.38501167297 -4.2479300499,1.57925486565,6.44259500504 -4.26793384552,1.59125554562,6.49339723587 -4.25095796585,1.59326899052,6.51097726822 -3.90706920624,1.46235072613,6.03543615341 -3.67115163803,1.37440955639,5.71594429016 -3.79113864899,1.43039441109,5.93757677078 -4.22104310989,1.61331546307,6.64130163193 -4.21806335449,1.62132608891,6.68188142776 -4.2110748291,1.62233233452,6.69267940521 -4.18110227585,1.61934888363,6.69224262238 -4.15312957764,1.61636471748,6.69381523132 -4.15414857864,1.6253746748,6.74139690399 -4.17216253281,1.6413807869,6.81500005722 -4.16418457031,1.64639258385,6.8495759964 -4.13821125031,1.64540815353,6.85514688492 -4.13622093201,1.64841353893,6.87494373322 -4.12224388123,1.6514261961,6.89853286743 -4.10526895523,1.65344011784,6.92009735107 -4.08429384232,1.65345442295,6.93268108368 -4.06231880188,1.65346908569,6.94425916672 -4.03834486008,1.65248394012,6.95184183121 -4.03535556793,1.65648972988,6.9716296196 -4.01038217545,1.65450513363,6.97919750214 -3.99140691757,1.65651917458,6.99577856064 -3.96843290329,1.65553414822,7.00635051727 -3.95245623589,1.65754723549,7.02694320679 -3.92748260498,1.65656256676,7.03351926804 -3.91450643539,1.66057574749,7.06308364868 -3.90551877022,1.66158258915,7.07187891006 -3.88554382324,1.66259670258,7.08745574951 -2.97683548927,1.26280546188,5.53831863403 -3.81562185287,1.66064155102,7.11519289017 -3.79464745522,1.66165602207,7.12877225876 -3.77767205238,1.66366970539,7.15034818649 -3.7676846981,1.66467690468,7.15813779831 -3.74371051788,1.66369187832,7.16571998596 -3.72173643112,1.66370642185,7.17730093002 -3.69976258278,1.66372132301,7.18987417221 -3.6767885685,1.66373610497,7.19945573807 -3.66181254387,1.66674935818,7.22503566742 -3.64282798767,1.6637583971,7.21581935883 -3.62285351753,1.66477286816,7.23239326477 -3.60487818718,1.66678667068,7.25197553635 -3.58290433884,1.66780138016,7.26455020905 -3.56192970276,1.66781556606,7.27714014053 -3.53595733643,1.66683149338,7.28270626068 -3.51698231697,1.66884541512,7.30029010773 -3.50699472427,1.66885232925,7.3070898056 -3.48502111435,1.66986715794,7.31966543198 -3.46404719353,1.67088186741,7.33523511887 -3.44707226753,1.67389571667,7.35880994797 -3.42209887505,1.67291069031,7.36339759827 -3.39712619781,1.67192625999,7.36997127533 -3.37815093994,1.67394006252,7.38755941391 -3.3671643734,1.67394757271,7.39434480667 -3.34619045258,1.67496228218,7.40991783142 -3.32621574402,1.67697632313,7.42550611496 -3.30424261093,1.67699122429,7.43907833099 -3.28426814079,1.67900538445,7.45566177368 -3.25629615784,1.67702138424,7.45523691177 -3.24430990219,1.67702913284,7.46002101898 -3.22233605385,1.67704367638,7.47160720825 -3.20236229897,1.67905807495,7.49017858505 -3.17439007759,1.67707407475,7.488758564 -3.15641498566,1.67908763885,7.50934839249 -3.13544082642,1.68110203743,7.52393245697 -3.11246800423,1.68111717701,7.53550481796 -3.09948134422,1.68012487888,7.53630018234 -3.08050775528,1.68313908577,7.55787181854 -3.06153321266,1.68615317345,7.57845115662 -3.03656053543,1.68516850471,7.58403205872 -3.0125875473,1.68418347836,7.59161520004 -2.9936132431,1.68719780445,7.61319160461 -2.96864056587,1.68721306324,7.61877155304 -2.95565485954,1.68622076511,7.62056064606 -2.93668031693,1.68923485279,7.64114427567 -2.9127073288,1.68924999237,7.64972257614 -2.89073419571,1.69026470184,7.66330289841 -2.87076044083,1.69327914715,7.68288040161 -2.84378862381,1.69129490852,7.6844534874 -2.82381415367,1.69330906868,7.70204353333 -2.81682682037,1.6973156929,7.72082853317 -2.78985476494,1.69433116913,7.72041273117 -2.76688170433,1.69534623623,7.73199176788 -2.75090670586,1.70135951042,7.76257610321 -2.72193598747,1.69837594032,7.75914525986 -2.69896268845,1.69839072227,7.76973056793 -2.69097495079,1.70139729977,7.78452730179 -2.66400384903,1.70041334629,7.78709459305 -2.64103055,1.70042788982,7.79668617249 -2.62305593491,1.70444178581,7.82326793671 -2.59708404541,1.70445728302,7.8268456459 -2.57411170006,1.70547235012,7.84041833878 -2.55713677406,1.710485816,7.86900997162 -2.5381526947,1.70549499989,7.85379076004 -2.51518034935,1.70750999451,7.86736536026 -2.49620628357,1.7115240097,7.89095306396 -2.46623539925,1.70754015446,7.88153219223 -2.44326305389,1.70855522156,7.89510774612 -2.4202902317,1.70956993103,7.90768909454 -2.40930318832,1.71057724953,7.91448497772 -2.38233160973,1.70859277248,7.91307020187 -2.35735988617,1.70860826969,7.92163944244 -2.33338689804,1.70862305164,7.9282336235 -2.3084154129,1.70963847637,7.93680381775 -2.29044055939,1.71465206146,7.96439790726 -2.26247048378,1.71266829967,7.96396160126 -2.25348258018,1.71467483044,7.97676467896 -2.23250961304,1.71768939495,7.99834156036 -2.20653796196,1.71770477295,8.00092411041 -2.1975607872,1.73071670532,8.0635175705 -2.1885843277,1.74472904205,8.13209152222 -2.16361236572,1.74474430084,8.14066982269 -2.14863729477,1.7537573576,8.18525791168 -2.13765072823,1.75476455688,8.1940536499 -2.10967993736,1.7537804842,8.19262886047 -2.08370828629,1.75279581547,8.19720935822 -2.05973625183,1.75481104851,8.21078777313 -2.03276467323,1.75382637978,8.21037387848 -2.00479388237,1.75184237957,8.20894622803 -1.96982455254,1.74185931683,8.17353725433 -1.95384013653,1.73986792564,8.16631507874 -1.92886793613,1.73988282681,8.17190551758 -1.90589559078,1.74289762974,8.18948459625 -1.87492525578,1.73691380024,8.17007064819 -1.84895443916,1.73792946339,8.17763805389 -1.82698118687,1.74094378948,8.19622993469 -1.81099641323,1.73795211315,8.18501853943 -1.78602457047,1.73796713352,8.19260120392 -1.75805354118,1.73498284817,8.18618583679 -1.73108291626,1.73499858379,8.18775749207 -1.70111238956,1.73001468182,8.17134094238 -1.67614078522,1.73102986813,8.17991924286 -1.64916932583,1.72804510593,8.17550945282 -1.63518452644,1.72805333138,8.17628574371 -1.61121225357,1.72906816006,8.18687534332 -1.5792427063,1.72208464146,8.16045093536 -1.55527055264,1.72409939766,8.1710395813 -1.52729988098,1.7211151123,8.16361808777 -1.50132846832,1.72113037109,8.16619873047 -1.4893424511,1.7221378088,8.17199134827 -1.46337139606,1.72215330601,8.17656707764 -1.43739974499,1.72116827965,8.17615509033 -1.41142785549,1.71918332577,8.17474746704 -1.38645684719,1.72119867802,8.18631839752 -1.35948574543,1.71921408176,8.18289852142 -1.33551394939,1.7222288847,8.19648265839 -1.32252812386,1.72123646736,8.19627666473 -1.2945574522,1.7182520628,8.18585681915 -1.26858627796,1.71826732159,8.18843650818 -1.24361455441,1.71828222275,8.19502258301 -1.21864271164,1.71929705143,8.2006111145 -1.1936712265,1.72031199932,8.21019077301 -1.16570055485,1.71732771397,8.19777297974 -1.15371441841,1.71833491325,8.20356845856 -1.12474429607,1.71335077286,8.18514537811 -1.09877336025,1.71336603165,8.1887216568 -1.0718023777,1.71138131618,8.18130588531 -1.04782998562,1.71239590645,8.19189929962 -1.02085971832,1.71241152287,8.19146823883 -0.995887696743,1.71242618561,8.19406318665 -0.980903089046,1.70843422413,8.18184566498 -0.958930075169,1.71444833279,8.209441185 -0.928960502148,1.70746421814,8.17901515961 -0.902989029884,1.70547926426,8.17560386658 -0.877018511295,1.70649468899,8.18217372894 -0.852046430111,1.70650923252,8.18476676941 -0.838061571121,1.70551717281,8.17955112457 -0.81308978796,1.70553183556,8.18414020538 -0.787118792534,1.70554697514,8.18572044373 -0.761147797108,1.70556199551,8.18630027771 -0.734176754951,1.70157718658,8.17088794708 -0.709205091,1.70259189606,8.1784734726 -0.683233737946,1.70160675049,8.17206287384 -0.670248389244,1.70161437988,8.17484855652 -0.644277095795,1.70062923431,8.17043495178 -0.618306040764,1.69964432716,8.16801834106 -0.592335045338,1.6986593008,8.16759777069 -0.567363381386,1.69967401028,8.17318725586 -0.540392875671,1.69668924809,8.16076469421 -0.527407586575,1.697696805,8.16355037689 -0.501436114311,1.69471156597,8.15314102173 -0.475465267897,1.69472658634,8.151720047 -0.450493633747,1.69574117661,8.15930843353 -0.42452275753,1.69575619698,8.1578874588 -0.398551464081,1.69277095795,8.14747428894 -0.37258040905,1.69078576565,8.14005756378 -0.359594702721,1.68879318237,8.13085365295 -0.334623157978,1.69080781937,8.14143943787 -0.30865240097,1.69082272053,8.1420173645 -0.282681375742,1.68883764744,8.1326007843 -0.257709354162,1.68785190582,8.12719631195 -0.231738850474,1.68886709213,8.13576889038 -0.205767661333,1.68488168716,8.11435604095 -0.193781480193,1.68788874149,8.12815475464 -0.167810678482,1.68690371513,8.12373352051 -0.142838835716,1.68591809273,8.12232685089 -0.116867974401,1.6829328537,8.10890674591 -0.0908972546458,1.68194782734,8.10248374939 -0.0659254789352,1.68196225166,8.10207653046 -0.0409537367523,1.6829764843,8.10866737366 -0.0279684066772,1.68298399448,8.10845565796 -0.00199774210341,1.68199884892,8.10203266144 --0.0129848783836,1.67800760269,7.77477931976 --0.0369569957256,1.68002176285,7.78237199783 --0.0619278810918,1.67803645134,7.77394723892 --0.0858998894691,1.67605066299,7.76553821564 --0.0978860482574,1.67905759811,7.77733612061 --0.122856803238,1.67607235909,7.76290845871 --0.146828696132,1.67408657074,7.75249767303 --0.170800954103,1.67610049248,7.76309299469 --0.195771828294,1.67611515522,7.76166820526 --0.219743713737,1.67412924767,7.75325679779 --0.231730028987,1.67713618279,7.76405858994 --0.256700754166,1.6761507988,7.75663042068 --0.280672580004,1.67416501045,7.74821805954 --0.305644035339,1.67817926407,7.76380395889 --0.328616589308,1.67419302464,7.74340009689 --0.35358774662,1.67520737648,7.74998092651 --0.378559052944,1.67822182178,7.75756311417 --0.390544652939,1.67522895336,7.74735164642 --0.414516925812,1.6772428751,7.75094795227 --0.439488530159,1.68025696278,7.76353693008 --0.463460028172,1.67727124691,7.75011825562 --0.488431215286,1.67828559875,7.75369977951 --0.513402819633,1.68129968643,7.76328802109 --0.537374377251,1.67931389809,7.75187063217 --0.550359725952,1.6813211441,7.75865936279 --0.574331820011,1.68133497238,7.75625133514 --0.598303735256,1.68034887314,7.75184202194 --0.622275352478,1.67836296558,7.74142360687 --0.648246645927,1.68337726593,7.76101303101 --0.673218309879,1.6863912344,7.7676024437 --0.687202990055,1.68839883804,7.77838373184 --0.713174641132,1.6944129467,7.79898023605 --0.73714607954,1.69242703915,7.78656005859 --0.762117624283,1.69344103336,7.78914737701 --0.788088560104,1.69645535946,7.79872941971 --0.812060832977,1.69646906853,7.79532432556 --0.839031040668,1.69948375225,7.80789804459 --0.849018096924,1.69649016857,7.79070091248 --0.87498909235,1.69850432873,7.799284935 --0.898961126804,1.6985180378,7.79387617111 --0.926931619644,1.70453262329,7.81846046448 --0.948904037476,1.69954609871,7.79304599762 --0.975874960423,1.70456039906,7.80963373184 --1.00084650517,1.70557439327,7.80922031403 --1.01283216476,1.70358133316,7.8020067215 --1.03680443764,1.70359480381,7.7986035347 --1.06377518177,1.70760929585,7.81018447876 --1.08774697781,1.70662283897,7.80277347565 --1.11271858215,1.70763683319,7.80236148834 --1.1386898756,1.70965075493,7.80794811249 --1.16266143322,1.70766460896,7.79652690887 --1.17464780807,1.7086712122,7.79632949829 --1.20161867142,1.71168541908,7.8079161644 --1.22459113598,1.71069872379,7.79550886154 --1.25156152248,1.71271312237,7.80108213425 --1.27653324604,1.71372687817,7.80067300797 --1.30150520802,1.71474039555,7.80126714706 --1.31249165535,1.71274697781,7.79206323624 --1.34046196938,1.71676135063,7.80464267731 --1.36443448067,1.71677458286,7.80024003983 --1.38940572739,1.71678853035,7.79481887817 --1.41637635231,1.71980261803,7.80140066147 --1.4393491745,1.71881580353,7.79099798203 --1.46532058716,1.72082960606,7.79358482361 --1.48230481148,1.72583723068,7.81437444687 --1.50427782536,1.7228500843,7.79796934128 --1.53124856949,1.72586417198,7.80355215073 --1.56121850014,1.73187863827,7.82313299179 --1.58019268513,1.72589099407,7.7937335968 --1.60816287994,1.72890532017,7.80130958557 --1.63613390923,1.73291921616,7.81290054321 --1.64612078667,1.73092544079,7.80069971085 --1.6710921526,1.73093903065,7.79528188705 --1.70106232166,1.73695325851,7.81386804581 --1.72103655338,1.73296558857,7.79147195816 --1.75000679493,1.73697972298,7.80405521393 --1.77697789669,1.73899364471,7.80764007568 --1.78696477413,1.73699975014,7.79543733597 --1.81393539906,1.73901379108,7.7970161438 --1.83990728855,1.74102711678,7.79861068726 --1.86587846279,1.74204087257,7.79619169235 --1.8908509016,1.74305379391,7.79479265213 --1.92282044888,1.75006830692,7.81737661362 --1.9417937994,1.74408090115,7.78595638275 --1.95577943325,1.74608755112,7.79075574875 --1.98375058174,1.74910128117,7.79834699631 --2.00472402573,1.74611377716,7.77894115448 --2.03169488907,1.74812746048,7.77952194214 --2.06166529655,1.7531414032,7.7931098938 --2.08163952827,1.74915361404,7.77170991898 --2.11660814285,1.75816833973,7.8022942543 --2.12859416008,1.75817489624,7.79708623886 --2.14756822586,1.75318694115,7.77067995071 --2.17653822899,1.75720107555,7.77625465393 --2.20750904083,1.76321482658,7.79385328293 --2.22548294067,1.75722694397,7.76243782043 --2.25045490265,1.75724005699,7.75602436066 --2.27343797684,1.76624810696,7.78982210159 --2.29441094398,1.76326048374,7.76940822601 --2.3193833828,1.76327335835,7.76400089264 --2.3493540287,1.76828706264,7.77459096909 --2.37132668495,1.76629972458,7.75717449188 --2.39729881287,1.76731276512,7.75476694107 --2.42626976967,1.77132618427,7.76236200333 --2.43625688553,1.76933217049,7.752161026 --2.46722698212,1.7743461132,7.76274204254 --2.49819755554,1.7793598175,7.77533483505 --2.51617217064,1.77437138557,7.7479300499 --2.54214382172,1.77538454533,7.74351596832 --2.57111501694,1.77939772606,7.75011253357 --2.59608721733,1.77941060066,7.74169492722 --2.60807347298,1.77941691875,7.73648881912 --2.63704442978,1.78243029118,7.74107789993 --2.66101741791,1.78244268894,7.73267650604 --2.6869893074,1.78345549107,7.7272605896 --2.71695971489,1.78646910191,7.73284339905 --2.74093270302,1.78648138046,7.72444295883 --2.75791740417,1.79048860073,7.73223209381 --2.78189015388,1.78950095177,7.72182226181 --2.8078622818,1.79051363468,7.71741437912 --2.83583378792,1.79352664948,7.71800470352 --2.86380529404,1.79553973675,7.71759080887 --2.88877797127,1.79655194283,7.71118879318 --2.91874861717,1.79956543446,7.71476984024 --2.92673659325,1.79757082462,7.70057439804 --2.95670795441,1.80058395863,7.70616769791 --2.9816801548,1.80159640312,7.6977558136 --3.00965189934,1.80360925198,7.69734668732 --3.03362417221,1.80362176895,7.68492841721 --3.06459522247,1.80763494968,7.69151735306 --3.08756899834,1.80664670467,7.68011951447 --3.10655283928,1.81065392494,7.69090843201 --3.13252568245,1.81266617775,7.68650913239 --3.15949749947,1.81367897987,7.68108987808 --3.18247103691,1.81369078159,7.6686873436 --3.21344232559,1.81770372391,7.67528438568 --3.23941445351,1.8187161684,7.66786909103 --3.25440001488,1.81972253323,7.66966724396 --3.2863702774,1.82373595238,7.67524719238 --3.31334280968,1.82574820518,7.67184448242 --3.33431696892,1.82375979424,7.65343523026 --3.35928964615,1.82477176189,7.64402484894 --3.38926076889,1.82778465748,7.64561319351 --3.41723299026,1.8297970295,7.6432056427 --3.43121886253,1.83080327511,7.64200210571 --3.46019053459,1.83381593227,7.64058828354 --3.49016261101,1.83782827854,7.64419364929 --3.51013636589,1.83483970165,7.62177276611 --3.53411006927,1.83485150337,7.61036634445 --3.56608080864,1.83886432648,7.61595964432 --3.58805465698,1.83787584305,7.59954977036 --3.60504055023,1.84088206291,7.60635995865 --3.63501191139,1.84389472008,7.60594463348 --3.65898561478,1.84390628338,7.59454059601 --3.68695735931,1.8459186554,7.58912134171 --3.70893168449,1.84492993355,7.57371854782 --3.74590134621,1.85194325447,7.58831262589 --3.75388884544,1.84994864464,7.57310199738 --3.77886199951,1.84996032715,7.56269264221 --3.79983663559,1.84897124767,7.54528999329 --3.82980871201,1.85198354721,7.54488182068 --3.86078023911,1.85599589348,7.54647493362 --3.88475370407,1.85600733757,7.53406715393 --3.91572523117,1.85901975632,7.53465604782 --3.92471313477,1.8580249548,7.52345752716 --3.94868683815,1.85803627968,7.5110502243 --3.98365712166,1.86304914951,7.51863765717 --4.00463151932,1.86206018925,7.50022935867 --4.02660608292,1.86107110977,7.48382043839 --4.05757761002,1.86508333683,7.48441505432 --4.08755016327,1.86809527874,7.48300933838 --4.09753751755,1.86710059643,7.47280502319 --4.12051153183,1.86611163616,7.45839834213 --4.14848423004,1.86912333965,7.45299196243 --4.17845678329,1.87213516235,7.45159006119 --4.20742893219,1.87414705753,7.44617271423 --4.22940397263,1.87415766716,7.43077373505 --4.25038814545,1.8781645298,7.43956661224 --4.27236270905,1.8771750927,7.42416810989 --4.29833602905,1.87818646431,7.41375494003 --4.3243098259,1.8791975975,7.40434980392 --4.35428237915,1.8822094202,7.40093946457 --4.38125562668,1.88422060013,7.3935379982 --4.40522956848,1.88423132896,7.38113832474 --4.42121553421,1.88623738289,7.37992525101 --4.44818925858,1.88824856281,7.37252569199 --4.48515939713,1.89426088333,7.38011646271 --4.50913381577,1.89427173138,7.36671113968 --4.54810428619,1.90128433704,7.37730312347 --4.57707643509,1.90329575539,7.37089109421 --4.60704994202,1.90730702877,7.36749124527 --4.61203861237,1.90331172943,7.34827947617 --4.63601303101,1.90432226658,7.33487653732 --4.64999055862,1.90033173561,7.30547142029 --4.67596435547,1.90134251118,7.29506635666 --4.67794466019,1.89235031605,7.24766397476 --4.69192123413,1.8883600235,7.21724557877 --4.69890975952,1.8863645792,7.20304393768 --4.722884655,1.88737511635,7.18963813782 --4.73986101151,1.88438463211,7.16623735428 --4.76083612442,1.88439488411,7.14782714844 --4.78781032562,1.88540577888,7.13841772079 --4.80878639221,1.88541555405,7.1220240593 --4.83376073837,1.88642597198,7.10961484909 --4.84674787521,1.88743138313,7.10441303253 --4.87971973419,1.89144289494,7.10299921036 --4.89569616318,1.88845229149,7.07759189606 --4.92267036438,1.89046287537,7.0681848526 --4.96164131165,1.89747464657,7.07678699493 --4.97861814499,1.89448416233,7.05237579346 --5.00359296799,1.89649426937,7.0409784317 --5.02957677841,1.90250086784,7.05377674103 --5.0385556221,1.89650952816,7.01836633682 --5.07352781296,1.90152072906,7.01996326447 --5.1094994545,1.9075319767,7.02255964279 --5.12347745895,1.90354084969,6.99515771866 --5.14945173264,1.90555119514,6.98274326324 --5.18342447281,1.90956223011,6.98234081268 --5.19641160965,1.91056740284,6.97613430023 --5.22038698196,1.91157722473,6.96273708344 --5.25535964966,1.91658818722,6.96333551407 --5.26133966446,1.91059613228,6.92492723465 --5.28831338882,1.91260635853,6.91351366043 --5.32528543472,1.91761732101,6.91711902618 --5.32627534866,1.91362130642,6.89390087128 --5.35025119781,1.91463088989,6.88050556183 --5.38722372055,1.92064189911,6.88310527802 --5.39720249176,1.91665029526,6.84969091415 --5.42117834091,1.91765964031,6.83629655838 --5.45315170288,1.92067027092,6.83088541031 --5.46213102341,1.91667830944,6.79747962952 --5.47411870956,1.91668307781,6.79027795792 --5.50809192657,1.92169368267,6.78787279129 --5.52007055283,1.9177018404,6.75846862793 --5.54604578018,1.91971158981,6.74606275558 --5.58101844788,1.92472207546,6.74465894699 --5.59199714661,1.9207303524,6.71324539185 --5.61897277832,1.9227398634,6.70284938812 --5.63895845413,1.925745368,6.70464468002 --5.64693832397,1.9217530489,6.67124414444 --5.67191410065,1.92276227474,6.65784311295 --5.69289112091,1.92277121544,6.63943862915 --5.70387029648,1.91877937317,6.60903072357 --5.72784614563,1.91978859901,6.59362125397 --5.76681804657,1.92679917812,6.59622192383 --5.76480960846,1.92180252075,6.57201242447 --5.78878593445,1.92281138897,6.55761432648 --5.81776094437,1.92582094669,6.54821109772 --5.82973957062,1.92282903194,6.51879835129 --5.85571575165,1.92483818531,6.50639915466 --5.87569284439,1.92484676838,6.4869966507 --5.88368177414,1.92385089397,6.47479295731 --5.91065788269,1.92585992813,6.46339416504 --5.89464378357,1.91286528111,6.40398168564 --5.91462087631,1.91287386417,6.38457727432 --5.94359588623,1.91588330269,6.37416696548 --5.96657276154,1.9168920517,6.35776090622 --5.9065694809,1.88989329338,6.25335073471 --5.98154258728,1.91190326214,6.31315755844 --5.91854047775,1.88390433788,6.20675039291 --5.98050737381,1.8979164362,6.23134374619 --6.00948286057,1.90092551708,6.22194385529 --5.97847270966,1.88392961025,6.14952993393 --5.38759326935,1.68088650703,5.50004434586 --5.39957284927,1.67889428139,5.47764635086 --6.05241107941,1.89295208454,6.12752771378 --5.3695526123,1.66090226173,5.39402723312 --5.33854198456,1.64490652084,5.32862329483 --5.35452032089,1.64391481876,5.31021642685 --5.33950614929,1.63392066956,5.26080369949 --5.34648656845,1.63092792034,5.23440361023 --5.3564658165,1.6289358139,5.20999097824 --5.3704533577,1.62994039059,5.20678758621 --5.39443016052,1.63294923306,5.1963801384 --5.38941383362,1.62595546246,5.15898370743 --5.39539432526,1.62196302414,5.13056564331 --5.41537237167,1.62397134304,5.11716794968 --5.44334793091,1.62698018551,5.11076402664 --5.44133043289,1.62098705769,5.07535028458 --5.4623169899,1.6259919405,5.07915449142 --5.51628684998,1.63800275326,5.09675312042 --5.53026628494,1.63701069355,5.07634162903 --5.53024864197,1.63201725483,5.04393959045 --5.56522321701,1.63802659512,5.0435385704 --5.56620502472,1.63303351402,5.01112318039 --5.62316608429,1.64304757118,5.01452732086 --5.70413064957,1.66305983067,5.05513620377 --5.7011141777,1.65806615353,5.01972961426 --5.7220916748,1.6590744257,5.00532007217 --5.7410697937,1.66008234024,4.98890829086 --5.7770447731,1.66609120369,4.9885134697 --5.8040304184,1.67209625244,4.99631977081 --5.84000492096,1.67810535431,4.99390506744 --5.86198282242,1.68011331558,4.98050403595 --5.88795995712,1.68312144279,4.97009897232 --5.92593479156,1.69013023376,4.97070741653 --6.02187919617,1.70914924145,4.98590087891 --5.90589618683,1.67214488983,4.87268352509 --6.03884983063,1.70715999603,4.95028400421 --6.72068834305,1.90720927715,5.48300552368 --6.76066350937,1.91421771049,5.47960233688 --6.77864265442,1.91422462463,5.45819807053 --6.79562234879,1.91423141956,5.43579149246 --6.81760168076,1.91523838043,5.41839694977 --6.8265914917,1.9152418375,5.40718889236 --6.84257125854,1.91524863243,5.38378047943 --6.86754989624,1.91725587845,5.36838340759 --6.88752937317,1.91826272011,5.34797382355 --6.90650892258,1.91826939583,5.32757329941 --6.92448949814,1.91927611828,5.30616998672 --6.94146966934,1.91928255558,5.28477621078 --6.95745849609,1.92128622532,5.27957725525 --6.97343873978,1.92129266262,5.25616979599 --6.99341821671,1.92229950428,5.23576164246 --6.99940109253,1.91830515862,5.20535850525 --7.0213804245,1.9203119278,5.18695735931 --7.04036045074,1.92131853104,5.16554641724 --5.51965045929,1.47724342346,4.00488376617 --5.54263782501,1.48224771023,4.00869131088 --5.55261850357,1.48225474358,3.98827934265 --7.11228990555,1.9253411293,5.09714269638 --7.13427019119,1.92734754086,5.07874488831 --7.14425230026,1.92535340786,5.05133962631 --7.15923309326,1.92435956001,5.02692937851 --7.17822170258,1.92736303806,5.02373552322 --7.19620275497,1.92836904526,5.00233602524 --7.20918416977,1.9273750782,4.97693014145 --7.22916460037,1.92838120461,4.95652675629 --7.24714565277,1.9293872118,4.93512821198 --7.26612615585,1.9303933382,4.91372156143 --7.27910804749,1.92939901352,4.88831520081 --7.2880988121,1.92940187454,4.87812280655 --7.30907869339,1.93140804768,4.85771274567 --7.32406044006,1.93141376972,4.83431434631 --7.327044487,1.92741906643,4.80190229416 --7.35002470016,1.92942488194,4.78451395035 --7.37100553513,1.93143081665,4.76410531998 --7.38298749924,1.93043649197,4.73769426346 --7.38697957993,1.92943894863,4.72450399399 --7.38596439362,1.92444396019,4.69009399414 --7.41394376755,1.92844986916,4.67469358444 --7.42592668533,1.92745530605,4.6492934227 --7.4509062767,1.9304612875,4.63088083267 --7.45888996124,1.92846632004,4.60348653793 --7.47387170792,1.92847180367,4.57907581329 --7.49086141586,1.93147468567,4.57388591766 --7.50384378433,1.93048012257,4.54847812653 --7.50582838058,1.92748498917,4.5160651207 --7.44682407379,1.90748775005,4.44765233994 --7.27983856201,1.85748696327,4.31421422958 --7.24182987213,1.84349095821,4.25878858566 --7.23581600189,1.83849561214,4.22438812256 --7.252805233,1.84149861336,4.21818065643 --7.27278661728,1.84350407124,4.19877958298 --7.27777099609,1.84050893784,4.17138671875 --7.30275154114,1.84351456165,4.15498828888 --7.3237323761,1.84552013874,4.13456821442 --7.33871507645,1.84652531147,4.11216688156 --7.34470701218,1.84652781487,4.10097742081 --7.35469007492,1.84553277493,4.07557296753 --7.37167263031,1.84653794765,4.05417060852 --7.37465715408,1.84354269505,4.02476358414 --7.39263916016,1.84454786777,4.00335359573 --7.40162277222,1.84355282784,3.97795605659 --7.40260791779,1.84055745602,3.94754719734 --7.41459846497,1.84256005287,3.93834161758 --7.41558361053,1.83956456184,3.90894460678 --7.4295668602,1.83956956863,3.88553714752 --7.4405503273,1.83957433701,3.86113643646 --7.45953273773,1.84057927132,3.84073472023 --7.47451591492,1.84158408642,3.81833410263 --7.49549770355,1.84358906746,3.79791975021 --7.4874920845,1.8395909071,3.7797305584 --7.49947547913,1.83959567547,3.75532317162 --7.51845836639,1.8416005373,3.73492336273 --7.53244161606,1.84260511398,3.71151661873 --7.55542373657,1.8446097374,3.69311881065 --7.54841041565,1.83961415291,3.65870094299 --7.56539344788,1.84161877632,3.63730168343 --7.56938552856,1.84062099457,3.6240978241 --7.61736440659,1.85062563419,3.6187183857 --7.6053519249,1.84362995625,3.58230280876 --7.62533473969,1.84663438797,3.56190037727 --7.64031887054,1.84763860703,3.53950309753 --7.64330387115,1.84464299679,3.51008534431 --7.66028785706,1.84664738178,3.48868942261 --7.68827676773,1.8526494503,3.48750185966 --7.67526435852,1.84565365314,3.45108580589 --7.6882481575,1.84665799141,3.42667365074 --7.71023130417,1.84866213799,3.40727710724 --7.6872215271,1.84066593647,3.36787509918 --7.69720554352,1.83967006207,3.34246635437 --7.73418664932,1.84667432308,3.3290643692 --7.7311797142,1.84467625618,3.3128592968 --7.74016523361,1.84368026257,3.28745746613 --7.75614929199,1.84568428993,3.26505637169 --7.75613546371,1.84268820286,3.2356505394 --7.76512098312,1.84269201756,3.21024823189 --7.80610179901,1.84969592094,3.1978456974 --7.79608917236,1.84469985962,3.16443943977 --7.81208133698,1.84770166874,3.1572508812 --7.84306335449,1.85270547867,3.13983917236 --7.83805084229,1.84870922565,3.1094455719 --7.84103679657,1.84771299362,3.08103442192 --7.87301921844,1.85271656513,3.06463456154 --7.88000488281,1.85172021389,3.03823041916 --7.89698982239,1.85372376442,3.0158290863 --7.92397975922,1.85872542858,3.01162934303 --7.91496753693,1.85472905636,2.97922563553 --7.9269528389,1.85473251343,2.95482349396 --7.94593715668,1.85773599148,2.93241381645 --7.9519238472,1.85673952103,2.9060151577 --7.96690893173,1.85774278641,2.88261294365 --7.97890090942,1.85974442959,2.87241053581 --7.97188901901,1.85574805737,2.84100556374 --7.99087381363,1.85775125027,2.81859850883 --8.00286006927,1.85875439644,2.79521226883 --8.01284599304,1.85875785351,2.7687933445 --8.02183246613,1.85876107216,2.74339365959 --8.04681587219,1.86276388168,2.72400307655 --8.03681087494,1.85876572132,2.70579433441 --8.04379844666,1.85876893997,2.67938971519 --8.07478141785,1.86377167702,2.660987854 --8.06877040863,1.8607749939,2.63058662415 --8.08675575256,1.86277782917,2.60818958282 --8.1047410965,1.86478066444,2.58477902412 --8.10672855377,1.86278390884,2.55636882782 --8.1157207489,1.8647851944,2.54517102242 --8.13570690155,1.86778783798,2.52276754379 --8.14169406891,1.86679089069,2.49636864662 --8.16167926788,1.86979341507,2.47396683693 --8.17366600037,1.8707960844,2.44957137108 --8.18865203857,1.87179875374,2.4251639843 --8.19863986969,1.87280142307,2.3997631073 --8.20463275909,1.87280261517,2.38756632805 --8.20962047577,1.87180554867,2.36015796661 --8.21660709381,1.87180817127,2.33375525475 --8.23559379578,1.87481057644,2.31034803391 --8.24758052826,1.87581288815,2.28595495224 --8.25356769562,1.87581562996,2.25854253769 --8.2475566864,1.87181866169,2.22813296318 --8.25355052948,1.8728197813,2.21593642235 --8.27553653717,1.87682187557,2.19353508949 --8.29252433777,1.87882387638,2.17013955116 --8.29251194,1.87682652473,2.14173483849 --8.28850078583,1.87382948399,2.1113152504 --8.30648803711,1.87683141232,2.08791708946 --8.32947921753,1.88083183765,2.07971954346 --8.33646774292,1.88083410263,2.05331873894 --8.34445571899,1.88183641434,2.02691435814 --8.36144351959,1.88383805752,2.00352334976 --8.37543106079,1.88584005833,1.9781140089 --8.38041973114,1.8858423233,1.95070636272 --8.38640785217,1.88584446907,1.92430973053 --8.39539527893,1.88584649563,1.89790356159 --8.41738891602,1.89084661007,1.88870286942 --8.42937660217,1.89184844494,1.86330294609 --8.43736457825,1.89185035229,1.83690154552 --8.45135307312,1.89385199547,1.8114964962 --8.45934104919,1.89485394955,1.78509545326 --8.47933006287,1.89785504341,1.76170313358 --8.48331832886,1.89685702324,1.73430049419 --8.49231243134,1.89885759354,1.72210049629 --8.49630069733,1.89785969257,1.69368326664 --8.50728988647,1.89986109734,1.66828978062 --8.52427864075,1.90186226368,1.6428809166 --8.52126789093,1.89986455441,1.61448276043 --8.53425598145,1.90186583996,1.58807075024 --8.53325176239,1.90086686611,1.57387018204 --8.5522403717,1.90386772156,1.54947268963 --8.538230896,1.89987051487,1.51805746555 --8.54522037506,1.89987194538,1.49166166782 --8.57120800018,1.90487229824,1.4682636261 --8.58419704437,1.90687334538,1.44185483456 --8.59118652344,1.90687465668,1.41546070576 --8.58618164062,1.90487599373,1.40025413036 --8.58117103577,1.90287804604,1.37084305286 --8.58616161346,1.90287947655,1.34343826771 --8.60015106201,1.90488028526,1.31804311275 --8.60914039612,1.90588128567,1.29063045979 --8.63112926483,1.9098815918,1.26623511314 --8.63311958313,1.90988302231,1.23883771896 --8.65511322021,1.91388225555,1.22763395309 --8.63810443878,1.90888500214,1.19723045826 --8.65809440613,1.91288518906,1.17182791233 --8.64508533478,1.90888762474,1.14141476154 --8.65507507324,1.90988838673,1.11501717567 --8.66206550598,1.91088926792,1.08761048317 --8.67205619812,1.91288995743,1.06121373177 --8.68205070496,1.91388988495,1.04800736904 --8.68404102325,1.91389107704,1.01959550381 --8.68603229523,1.91389226913,0.992198050022 --8.69702243805,1.9148927927,0.965801477432 --8.71801185608,1.91889238358,0.939390718937 --8.7080039978,1.91589438915,0.909982264042 --8.71899414062,1.91789472103,0.883587062359 --8.72498893738,1.91889476776,0.870389103889 --8.73697948456,1.92089498043,0.842979252338 --8.73097133636,1.9188965559,0.814578533173 --8.74196243286,1.92089676857,0.78717058897 --8.75095272064,1.92189705372,0.759765982628 --8.75894451141,1.92289745808,0.732362926006 --8.74693584442,1.91989946365,0.702952802181 --8.74193191528,1.9189003706,0.68875336647 --8.75492286682,1.92090022564,0.661345183849 --8.77091407776,1.92389953136,0.634949624538 --8.78290557861,1.92589950562,0.607544481754 --8.79889678955,1.92889869213,0.581151247025 --8.80788803101,1.93089878559,0.552735745907 --8.80787944794,1.92989945412,0.525342702866 --8.81687545776,1.93189895153,0.511131942272 --8.83286762238,1.93489813805,0.484742134809 --8.82685852051,1.9328994751,0.455324500799 --8.83685112,1.93489909172,0.427925348282 --8.83484268188,1.93389987946,0.399519234896 --8.84183502197,1.93589985371,0.372122377157 --8.84982681274,1.9368994236,0.34371137619 --8.8508234024,1.93689966202,0.329507350922 --8.84981441498,1.93690025806,0.301100432873 --8.84780693054,1.93590092659,0.272693783045 --8.85879993439,1.93790018559,0.245297387242 --8.86179161072,1.93790030479,0.216889470816 --8.85778427124,1.93690109253,0.188483029604 --8.85678005219,1.93690133095,0.174279376864 --8.85377311707,1.93590199947,0.145872190595 --8.85876655579,1.93690168858,0.11746378988 --8.85975837708,1.93690192699,0.0890559703112 --8.85675048828,1.93590247631,0.0606482252479 --8.87474441528,1.93990063667,0.0332555472851 --8.88073635101,1.94090008736,0.00484891142696 --8.87373256683,1.93890094757,-0.00935529451817 --8.87572574615,1.93990087509,-0.0377625375986 --8.88271903992,1.94090008736,-0.0661682859063 --8.87471199036,1.93890106678,-0.0945773497224 --8.88670539856,1.94189965725,-0.12298130244 --8.8816986084,1.94090032578,-0.15139003098 --8.88969135284,1.94189918041,-0.178779318929 --8.8966884613,1.9438983202,-0.192979931831 --8.89168167114,1.94289886951,-0.221388787031 --8.89467430115,1.9438983202,-0.249794080853 --8.9006690979,1.94489729404,-0.278197228909 --8.90066242218,1.94489717484,-0.306603491306 --8.89765548706,1.94489729404,-0.335011899471 --8.90564918518,1.94589602947,-0.36442694068 --8.91064548492,1.94789516926,-0.378626555204 --8.89663887024,1.944896698,-0.40602850914 --8.89963340759,1.94589591026,-0.434432446957 --8.92262744904,1.95089244843,-0.463833212852 --8.91362094879,1.94889318943,-0.49224627018 --8.92061519623,1.95089173317,-0.520645022392 --8.90660858154,1.9478931427,-0.54906386137 --8.91760730743,1.95089137554,-0.563255488873 --8.90859985352,1.94889211655,-0.591669917107 --8.92459583282,1.95288920403,-0.621071875095 --8.9055891037,1.94889128208,-0.648483812809 --8.91358280182,1.95088946819,-0.677893698215 --8.90857696533,1.94988942146,-0.705290079117 --8.91057109833,1.95088851452,-0.734706699848 --8.9255695343,1.95488584042,-0.749903738499 --8.93756484985,1.957883358,-0.779305517673 --8.94155979156,1.95888197422,-0.80770277977 --8.91855335236,1.95388448238,-0.835124492645 --8.92054748535,1.95488321781,-0.863525092602 --8.9195432663,1.95588243008,-0.891930162907 --8.90253639221,1.9518840313,-0.919345796108 --8.90453338623,1.95288324356,-0.933544576168 --8.95553207397,1.96487438679,-0.966935217381 --8.9465265274,1.96387469769,-0.995351672173 --8.93052101135,1.95987606049,-1.02175199986 --8.94751739502,1.96487224102,-1.05215191841 --8.93351173401,1.96187317371,-1.07956409454 --8.93650627136,1.96387159824,-1.10897397995 --8.96350669861,1.96986651421,-1.12616562843 --8.94550132751,1.96686816216,-1.1535859108 --8.94049549103,1.96586763859,-1.18199574947 --8.95849323273,1.97086334229,-1.21238744259 --8.93448638916,1.96586585045,-1.23880779743 --8.94048309326,1.96886348724,-1.26820909977 --8.95648193359,1.97285997868,-1.28440260887 --8.9354763031,1.96886205673,-1.31081867218 --8.9384727478,1.9698599577,-1.3402248621 --8.94946956635,1.97385656834,-1.370626688 --8.93446350098,1.97085750103,-1.39804494381 --8.94046020508,1.97285473347,-1.42744278908 --8.96545886993,1.97984862328,-1.45983624458 --8.97745800018,1.98284566402,-1.47603321075 --8.96745300293,1.98184561729,-1.50445330143 --8.97645187378,1.984842062,-1.53485405445 --8.94944477081,1.97884511948,-1.56027567387 --8.93943977356,1.97784507275,-1.58768320084 --8.96443939209,1.98483848572,-1.62108254433 --8.92643165588,1.9768435955,-1.64450907707 --8.92843055725,1.97784221172,-1.65870118141 --8.93342781067,1.97983920574,-1.6891105175 --8.92742347717,1.97983837128,-1.7175219059 --8.92041969299,1.9788377285,-1.74492192268 --8.93841934204,1.98483204842,-1.77732014656 --8.91041183472,1.97883534431,-1.80173945427 --8.9014081955,1.97883474827,-1.83016049862 --8.92140865326,1.98382866383,-1.86254918575 --8.92440795898,1.98582684994,-1.87876427174 --8.91340255737,1.98382687569,-1.90516233444 --8.92740154266,1.98882162571,-1.93756639957 --8.92039871216,1.98782062531,-1.9659794569 --8.93239784241,1.99281573296,-1.99737346172 --8.9373960495,1.99481225014,-2.02878832817 --8.92139339447,1.99181425571,-2.03999423981 --8.91739082336,1.9928123951,-2.06941127777 --8.9363899231,1.99780583382,-2.10280513763 --8.91138458252,1.99380838871,-2.12722349167 --8.92238426208,1.99780333042,-2.15962910652 --8.93038368225,2.00079894066,-2.19102978706 --8.92038059235,1.99979841709,-2.2184381485 --8.92438030243,2.00179600716,-2.23464488983 --8.9293794632,2.00479197502,-2.26504039764 --8.91537570953,2.00279211998,-2.29246306419 --8.92637634277,2.00678682327,-2.32486271858 --8.92537403107,2.00778412819,-2.35426449776 --8.93337440491,2.0117790699,-2.38667297363 --8.93437290192,2.0137758255,-2.41707921028 --8.93437290192,2.01477432251,-2.43228411674 --8.92737007141,2.01477265358,-2.46069335938 --8.93037033081,2.01676893234,-2.4910902977 --8.93036937714,2.01876568794,-2.5214984417 --8.9293680191,2.01976251602,-2.55190992355 --8.9163646698,2.01876211166,-2.57932877541 --8.93536758423,2.02475404739,-2.61472558975 --8.93336772919,2.0247528553,-2.62892270088 --8.92936515808,2.02575039864,-2.65833091736 --8.94836902618,2.03274226189,-2.69473695755 --8.92336368561,2.02874469757,-2.71815156937 --8.93836688995,2.03373718262,-2.75355792046 --8.93236541748,2.03373503685,-2.78195881844 --8.91636180878,2.03273510933,-2.80837702751 --8.92536354065,2.03573107719,-2.82657837868 --8.92836475372,2.03872656822,-2.85797977448 --8.92936515808,2.04072237015,-2.88938832283 --8.92636489868,2.04171919823,-2.91980099678 --8.92936515808,2.04471421242,-2.95119953156 --8.93036651611,2.04671001434,-2.98260569572 --8.93236732483,2.04970526695,-3.01501989365 --8.93936920166,2.05270147324,-3.03322529793 --8.92836856842,2.0517001152,-3.06063246727 --8.93837165833,2.05669331551,-3.09503316879 --8.93537139893,2.05768966675,-3.12544107437 --8.92937088013,2.05868697166,-3.1548500061 --8.93137359619,2.06168198586,-3.18725943565 --8.94237709045,2.0666744709,-3.22266292572 --8.92537307739,2.06267666817,-3.23287558556 --8.92837619781,2.06667137146,-3.26527810097 --8.94238090515,2.07166314125,-3.30167651176 --8.93138027191,2.07166147232,-3.33009409904 --8.92737960815,2.07265758514,-3.36050224304 --8.92238044739,2.07465434074,-3.39091515541 --8.92238235474,2.07664942741,-3.42231464386 --8.92638492584,2.07864570618,-3.44052577019 --8.92338657379,2.0806415081,-3.47092676163 --8.91338539124,2.08063936234,-3.49933767319 --8.91738986969,2.08463335037,-3.53375244141 --8.91439151764,2.08562898636,-3.56516361237 --8.90939235687,2.08762526512,-3.59557294846 --8.90439414978,2.08862137794,-3.62598109245 --8.91039657593,2.09161710739,-3.64417791367 --8.90839862823,2.09361219406,-3.67558169365 --8.90139961243,2.09460902214,-3.70599913597 --8.910405159,2.09960079193,-3.74240469933 --8.90140628815,2.09959793091,-3.77080655098 --8.89740848541,2.10159373283,-3.80221819878 --8.90941333771,2.10658717155,-3.82442808151 --8.89341259003,2.10458636284,-3.84982967377 --8.88341331482,2.10558342934,-3.8792488575 --8.89542102814,2.11157417297,-3.91765546799 --8.88241958618,2.1105723381,-3.9450647831 --8.87242221832,2.1115694046,-3.97448277473 --8.89243125916,2.11955714226,-4.01587581635 --8.88343048096,2.11855697632,-4.02908802032 --8.87143135071,2.11855459213,-4.05750370026 --8.87343597412,2.12154793739,-4.09191083908 --8.86743927002,2.1235435009,-4.12231492996 --8.87644672394,2.12853455544,-4.15971517563 --8.87244987488,2.13152933121,-4.19213008881 --8.84844684601,2.12753081322,-4.21454191208 --8.84344768524,2.12852907181,-4.22975492477 --8.88646697998,2.14250874519,-4.2831401825 --8.85946273804,2.13851094246,-4.30455732346 --8.83946228027,2.13651061058,-4.32998180389 --8.85647201538,2.14449858665,-4.37238454819 --8.82746887207,2.14050126076,-4.39280366898 --8.83747768402,2.14649105072,-4.43221092224 --8.90150165558,2.16446661949,-4.47937631607 --8.90550994873,2.16845798492,-4.51679086685 --8.93052482605,2.1784427166,-4.56317901611 --8.98555088043,2.19641685486,-4.6255645752 --8.95454597473,2.19142007828,-4.64497947693 --8.92654323578,2.18842196465,-4.66741275787 --8.933552742,2.19341230392,-4.70581150055 --8.87953662872,2.18142676353,-4.69704961777 --8.84252929688,2.17543196678,-4.71347379684 --8.83753395081,2.1774263382,-4.74587965012 --8.79552555084,2.17043328285,-4.76031589508 --8.76952362061,2.1674349308,-4.78173208237 --8.76752948761,2.17042803764,-4.81614208221 --8.72852230072,2.16443395615,-4.83157539368 --8.72152328491,2.16443276405,-4.84578514099 --8.71252632141,2.16542816162,-4.87619495392 --8.68552398682,2.16243004799,-4.89762115479 --8.67352676392,2.16342687607,-4.92602777481 --8.65852832794,2.16342449188,-4.95344305038 --8.62452316284,2.15842866898,-4.97087335587 --8.60852432251,2.15742683411,-4.99728488922 --8.62653541565,2.16441607475,-5.02548408508 --8.58952903748,2.15842175484,-5.04091358185 --8.57753181458,2.15941786766,-5.07033252716 --8.56753540039,2.16041398048,-5.09973621368 --8.52852725983,2.15442013741,-5.11417293549 --8.50352573395,2.15142154694,-5.1355919838 --8.48752784729,2.15141916275,-5.16301774979 --8.4545173645,2.14542770386,-5.16123199463 --8.44252109528,2.14542412758,-5.19065237045 --8.4245223999,2.14542293549,-5.21505832672 --8.40151977539,2.14342331886,-5.23849058151 --8.36151123047,2.13643050194,-5.24991083145 --8.35551738739,2.13942456245,-5.28232192993 --8.32951545715,2.1364262104,-5.30375576019 --8.31051158905,2.1334297657,-5.3099656105 --8.29051113129,2.13242888451,-5.33439064026 --8.26050662994,2.12843251228,-5.351811409 --8.23950576782,2.12643241882,-5.37422180176 --8.24251747131,2.13242220879,-5.41364336014 --8.1935043335,2.12343358994,-5.41907596588 --8.18350410461,2.12243318558,-5.43128967285 --8.17250728607,2.1244289875,-5.46070432663 --8.14150333405,2.12043309212,-5.4771270752 --8.11349868774,2.11743593216,-5.49555063248 --8.10750579834,2.1194293499,-5.52795982361 --8.07950210571,2.11643218994,-5.5463848114 --8.04949855804,2.11243581772,-5.56381511688 --8.05550575256,2.1174287796,-5.58601617813 --8.02250003815,2.11243367195,-5.60144901276 --8.00149917603,2.11143398285,-5.62285470963 --7.97949838638,2.10943388939,-5.64527988434 --7.9414896965,2.1034412384,-5.65671300888 --7.91648769379,2.10144281387,-5.67714262009 --7.90349149704,2.10243940353,-5.70455217361 --7.8834862709,2.09944343567,-5.70876264572 --7.87249135971,2.10143899918,-5.73918962479 --7.83948469162,2.09644412994,-5.75260972977 --7.82048559189,2.09644293785,-5.77703714371 --7.78447771072,2.09044981003,-5.78846311569 --7.77148199081,2.09244608879,-5.81688547134 --7.74847984314,2.09044718742,-5.83629226685 --7.72347259521,2.0854537487,-5.83751678467 --7.71347856522,2.08844876289,-5.86793613434 --7.68647527695,2.0854511261,-5.88636779785 --7.6644744873,2.08445191383,-5.90677976608 --7.63546943665,2.08045530319,-5.92320871353 --7.62147331238,2.08145213127,-5.95062875748 --7.59847259521,2.08045291901,-5.97105121613 --7.58647155762,2.07945370674,-5.98126649857 --7.55946779251,2.0764567852,-5.9976811409 --7.53646707535,2.07545733452,-6.01911640167 --7.52447223663,2.07745289803,-6.04752969742 --7.49146509171,2.07245898247,-6.0599565506 --7.47446775436,2.07345700264,-6.08437204361 --7.45146608353,2.07145810127,-6.10479736328 --7.4304599762,2.0684633255,-6.1070098877 --7.406457901,2.06646466255,-6.12643527985 --7.38745927811,2.06646370888,-6.14985942841 --7.36145687103,2.06446623802,-6.16728258133 --7.33845567703,2.06246709824,-6.18771123886 --7.33646774292,2.06745743752,-6.22411775589 --7.28744983673,2.05847167969,-6.22356367111 --7.28345441818,2.06046843529,-6.23876237869 --7.26845788956,2.06146550179,-6.26518201828 --7.23545074463,2.05747151375,-6.27661037445 --7.21044874191,2.05547380447,-6.29504013062 --7.20045566559,2.05746793747,-6.32545518875 --7.16944932938,2.05447340012,-6.33787870407 --7.14644813538,2.05247449875,-6.35730028152 --7.14845657349,2.05646777153,-6.37850475311 --7.10143947601,2.04748153687,-6.3779463768 --7.08444261551,2.04847931862,-6.40337610245 --7.067445755,2.04947757721,-6.42678451538 --7.04044246674,2.04748058319,-6.44321680069 --7.0274477005,2.0484764576,-6.47062730789 --7.00344610214,2.04747796059,-6.48905229568 --6.98944425583,2.046479702,-6.49727392197 --6.97244739532,2.04747772217,-6.52169322968 --6.95244884491,2.04747700691,-6.54412031174 --6.92744684219,2.04547929764,-6.56154584885 --6.89944124222,2.04248356819,-6.57496070862 --6.8854470253,2.04447937012,-6.60238075256 --6.86944389343,2.0424823761,-6.60860347748 --6.85244703293,2.04348015785,-6.63302230835 --6.83144807816,2.04348039627,-6.6534409523 --6.79944038391,2.03948640823,-6.66487884521 --6.78144311905,2.0394847393,-6.68829774857 --6.7734541893,2.04347705841,-6.72171640396 --6.73344087601,2.03748774529,-6.72515726089 --6.71544313431,2.03848648071,-6.74756622314 --6.71645307541,2.04147958755,-6.76977872849 --6.67343664169,2.03449249268,-6.76921463013 --6.661444664,2.03748703003,-6.79863214493 --6.64945220947,2.03948187828,-6.82804822922 --6.61344194412,2.03449034691,-6.83448505402 --6.60044908524,2.03748559952,-6.86290216446 --6.59145069122,2.03748488426,-6.87410640717 --6.56344604492,2.03548908234,-6.88854074478 --6.54545021057,2.03648686409,-6.91297006607 --6.53145647049,2.03848266602,-6.94038534164 --6.50245094299,2.03548741341,-6.95281267166 --6.47945022583,2.03448843956,-6.97123527527 --6.45645046234,2.03448939323,-6.99066877365 --6.43944549561,2.03249359131,-6.99388074875 --6.41544437408,2.03149557114,-7.01130580902 --6.40445423126,2.03448867798,-7.04272603989 --6.36443901062,2.02850103378,-7.04316043854 --6.35445022583,2.03249335289,-7.07658910751 --6.34246015549,2.03548741341,-7.10700941086 --6.31645679474,2.03349065781,-7.12142801285 --6.2924451828,2.02949953079,-7.11664295197 --6.27645111084,2.03049588203,-7.14306783676 --6.2564535141,2.03149533272,-7.16448974609 --6.23445463181,2.03149557114,-7.184923172 --6.21946144104,2.03349137306,-7.21133518219 --6.18044710159,2.02750301361,-7.21277856827 --6.15244245529,2.02550768852,-7.22520446777 --6.15045070648,2.02850174904,-7.24541521072 --6.11944389343,2.02550816536,-7.25484752655 --6.10244846344,2.02650547028,-7.2792634964 --6.08145046234,2.02750515938,-7.29968690872 --6.05344581604,2.02450966835,-7.31211471558 --6.02243804932,2.02151632309,-7.32155036926 --6.01545381546,2.02750611305,-7.3589720726 --5.99244308472,2.0235145092,-7.35519742966 --5.9684419632,2.02251672745,-7.37161874771 --5.9614572525,2.02750658989,-7.4080286026 --5.92744684219,2.02351546288,-7.4134645462 --5.89643955231,2.0205218792,-7.42290401459 --5.88144731522,2.02351737022,-7.45032215118 --5.85843515396,2.01852679253,-7.44453430176 --5.83843898773,2.01952552795,-7.46696519852 --5.81343650818,2.01852822304,-7.48239183426 --5.78242921829,2.0155351162,-7.49082565308 --5.76143169403,2.01653432846,-7.51225996017 --5.74043321609,2.01653432846,-7.53167581558 --5.71342945099,2.01553893089,-7.54410076141 --5.6894288063,2.01454043388,-7.56153392792 --5.6804318428,2.01553916931,-7.57374668121 --5.64441823959,2.01055002213,-7.57518291473 --5.63443231583,2.01554131508,-7.60960006714 --5.60342407227,2.01254868507,-7.61703109741 --5.58342838287,2.01354694366,-7.64047002792 --5.5544219017,2.01155281067,-7.64989566803 --5.54542541504,2.01255178452,-7.66210794449 --5.51641893387,2.01055717468,-7.6725435257 --5.50042724609,2.01255321503,-7.69895935059 --5.47442388535,2.01155662537,-7.71238517761 --5.4494228363,2.01055908203,-7.72882413864 --5.42141771317,2.00956463814,-7.73925018311 --5.39641523361,2.00856757164,-7.75367307663 --5.38641786575,2.00956630707,-7.76589679718 --5.35741138458,2.00657248497,-7.77532672882 --5.33040761948,2.00557684898,-7.78775930405 --5.30440425873,2.00458073616,-7.80017995834 --5.28040409088,2.00458240509,-7.81761693954 --5.25840568542,2.00458288193,-7.83603811264 --5.23040056229,2.00258851051,-7.84646749496 --5.21739912033,2.00259017944,-7.85368680954 --5.19139623642,2.0015938282,-7.86711740494 --5.16739606857,2.00159573555,-7.8835477829 --5.13838911057,1.99960231781,-7.89197587967 --5.11438846588,1.99960422516,-7.9084072113 --5.0913901329,1.99960505962,-7.92684078217 --5.06939172745,2.00060558319,-7.94526290894 --5.0493812561,1.99661362171,-7.94148302078 --5.03239011765,1.99960958958,-7.96790552139 --5.00438499451,1.99861454964,-7.97934770584 --4.97237300873,1.99462449551,-7.9817700386 --4.95237922668,1.99662232399,-8.00520610809 --4.9363899231,2.00061702728,-8.03363037109 --4.91537714005,1.99662673473,-8.02684402466 --4.89638376236,1.99862384796,-8.05127334595 --4.87038087845,1.99762785435,-8.06369972229 --4.84237575531,1.99663341045,-8.07413673401 --4.81537151337,1.99463820457,-8.08556938171 --4.79237318039,1.99563896656,-8.10400295258 --4.75935935974,1.99164998531,-8.10443115234 --4.75036430359,1.99264788628,-8.11764621735 --4.72135734558,1.99165463448,-8.1260843277 --4.70436668396,1.99465024471,-8.15250110626 --4.67636108398,1.99265575409,-8.16294002533 --4.64034366608,1.98766982555,-8.1583738327 --4.62034988403,1.98966753483,-8.18180656433 --4.59935474396,1.9916665554,-8.20323753357 --4.58535194397,1.99066960812,-8.2074508667 --4.55934906006,1.99067366123,-8.21988105774 --4.53735256195,1.99167335033,-8.24031639099 --4.51535606384,1.99267315865,-8.25974464417 --4.48234176636,1.98868489265,-8.25917434692 --4.46334934235,1.99168181419,-8.28359889984 --4.43434286118,1.98968839645,-8.29204082489 --4.42334508896,1.99068820477,-8.30225849152 --4.39533805847,1.98869502544,-8.30968093872 --4.37634754181,1.99269104004,-8.33611774445 --4.34533643723,1.98970043659,-8.33955287933 --4.32834863663,1.99269497395,-8.36797523499 --4.29934024811,1.99170255661,-8.37440490723 --4.27534198761,1.99270379543,-8.39184474945 --4.26334190369,1.99270510674,-8.39905452728 --4.23433446884,1.99071228504,-8.40649223328 --4.2083325386,1.99071586132,-8.41993141174 --4.18132829666,1.9897210598,-8.43036365509 --4.15432310104,1.98872685432,-8.43978977203 --4.12631750107,1.98773312569,-8.44822406769 --4.1013174057,1.98773562908,-8.46366405487 --4.09232282639,1.98973345757,-8.47687244415 --4.06131029129,1.98674380779,-8.47830200195 --4.03931617737,1.98874282837,-8.49973964691 --4.01732063293,1.99074208736,-8.52016925812 --3.99231982231,1.99074494839,-8.53460216522 --3.96130847931,1.98775494099,-8.53704071045 --3.9493086338,1.98775625229,-8.54425048828 --3.93032073975,1.99275112152,-8.5726890564 --3.89830589294,1.98876321316,-8.57111740112 --3.86529064178,1.98477554321,-8.56956005096 --3.84830522537,1.98976886272,-8.59998226166 --3.81528997421,1.98578131199,-8.59842777252 --3.79329442978,1.98778104782,-8.6178483963 --3.78329992294,1.98977899551,-8.631067276 --3.7472782135,1.98379564285,-8.62251377106 --3.7222776413,1.98479878902,-8.63594055176 --3.70429158211,1.98879241943,-8.66637229919 --3.66826796532,1.98281025887,-8.65480327606 --3.64226603508,1.98281443119,-8.66723918915 --3.61926960945,1.98481476307,-8.68566799164 --3.60326385498,1.98382008076,-8.68689918518 --3.57425451279,1.98182880878,-8.69132995605 --3.55526661873,1.9858237505,-8.71875286102 --3.52325248718,1.98283565044,-8.71819877625 --3.50226092339,1.98583316803,-8.7416267395 --3.47425508499,1.98483967781,-8.75006771088 --3.4372279644,1.97885990143,-8.73450183868 --3.43224620819,1.98385000229,-8.76172447205 --3.40824818611,1.98485147953,-8.77815341949 --3.37422704697,1.97986769676,-8.76958656311 --3.34722208977,1.97987389565,-8.77801609039 --3.3262321949,1.98287045956,-8.80345153809 --3.29822611809,1.9828774929,-8.81088924408 --3.26621079445,1.97888994217,-8.80933570862 --3.26223158836,1.98487842083,-8.8385477066 --3.23221993446,1.982888937,-8.83998203278 --3.21423864365,1.98888027668,-8.87441825867 --3.17520308495,1.97990548611,-8.8498468399 --3.13917708397,1.97392499447,-8.83629322052 --3.12019252777,1.97891843319,-8.86672306061 --3.0961959362,1.98091948032,-8.88415527344 --3.08319425583,1.98092198372,-8.88936805725 --3.05017495155,1.97693729401,-8.88280963898 --3.03420066833,1.98492455482,-8.92424583435 --2.99716925621,1.9779471159,-8.9046831131 --2.96816039085,1.97595596313,-8.90912437439 --2.94115614891,1.97596180439,-8.91856098175 --2.92213869095,1.97197437286,-8.90678024292 --2.89713835716,1.97297751904,-8.92020702362 --2.87113785744,1.97398126125,-8.93364906311 --2.84112548828,1.97199237347,-8.93408870697 --2.81211400032,1.97000253201,-8.9355173111 --2.78812003136,1.97300231457,-8.95596313477 --2.75710201263,1.96901655197,-8.95039176941 --2.73310828209,1.97201633453,-8.97083568573 --2.72010755539,1.97201836109,-8.97705364227 --2.68808746338,1.9680339098,-8.96949005127 --2.65807414055,1.96604561806,-8.9689283371 --2.63407874107,1.96804618835,-8.98736286163 --2.60607028008,1.9670548439,-8.99179458618 --2.57505297661,1.96406888962,-8.98723316193 --2.56506204605,1.9670650959,-9.00345039368 --2.53504776955,1.965077281,-9.00188732147 --2.50704073906,1.96408510208,-9.00833034515 --2.48003602028,1.96409142017,-9.01676464081 --2.45102548599,1.96310138702,-9.01920604706 --2.42201566696,1.96111094952,-9.02265167236 --2.39902448654,1.96510922909,-9.04508495331 --2.38401651382,1.96411597729,-9.04330158234 --2.3540019989,1.96112823486,-9.04174137115 --2.33301687241,1.96612286568,-9.0701675415 --2.30400633812,1.96513295174,-9.07260990143 --2.27499580383,1.9641430378,-9.07505226135 --2.24999690056,1.96514582634,-9.08948040009 --2.22199058533,1.96515357494,-9.09592342377 --2.20999288559,1.96615386009,-9.10513782501 --2.18299031258,1.96715939045,-9.11558055878 --2.15297603607,1.96517169476,-9.11402511597 --2.126973629,1.96617686749,-9.12445354462 --2.10097575188,1.96817958355,-9.13989925385 --2.07396960258,1.96818697453,-9.14632701874 --2.04696893692,1.96919155121,-9.15877628326 --2.03597545624,1.97118937969,-9.1719865799 --2.00093817711,1.96421563625,-9.14642715454 --1.97795367241,1.96921026707,-9.17587280273 --1.95094954967,1.97021663189,-9.18430805206 --1.91791975498,1.96423828602,-9.16674900055 --1.89192008972,1.96524190903,-9.18018627167 --1.86290514469,1.96325469017,-9.17761707306 --1.84689235687,1.96126437187,-9.17083835602 --1.81486523151,1.95628428459,-9.15628051758 --1.79288649559,1.96327590942,-9.19072055817 --1.75884687901,1.95530307293,-9.16315555573 --1.73385334015,1.95830345154,-9.18259525299 --1.7048419714,1.95731413364,-9.18404102325 --1.673817873,1.95333242416,-9.17248249054 --1.66081690788,1.95333504677,-9.17769622803 --1.63280785084,1.9533444643,-9.18113517761 --1.59977173805,1.94636964798,-9.1575756073 --1.57377266884,1.94837331772,-9.17101383209 --1.54576158524,1.94738376141,-9.17244815826 --1.51473534107,1.94240319729,-9.15888977051 --1.48773026466,1.94341039658,-9.1663274765 --1.47171795368,1.94141983986,-9.16055965424 --1.44169378281,1.93743777275,-9.14899539948 --1.41669976711,1.9404386282,-9.16742897034 --1.3866776228,1.93745577335,-9.15787124634 --1.35665154457,1.93247497082,-9.14430522919 --1.33065271378,1.93547868729,-9.15774250031 --1.31564700603,1.93448412418,-9.15897846222 --1.28461205959,1.92850852013,-9.13640975952 --1.25861299038,1.93051230907,-9.14984703064 --1.23160719872,1.93152022362,-9.1562833786 --1.20158576965,1.92853689194,-9.14773464203 --1.17356967926,1.92655038834,-9.14416599274 --1.14656472206,1.92755758762,-9.15160560608 --1.13155424595,1.92556583881,-9.14783287048 --1.10354208946,1.92457711697,-9.14827346802 --1.07552993298,1.92358863354,-9.14871501923 --1.04852092266,1.92359805107,-9.15214633942 --1.02050602436,1.92261111736,-9.14958286285 --0.99249202013,1.92162370682,-9.148021698 --0.963476479053,1.91963708401,-9.14547538757 --0.950477719307,1.92163872719,-9.15269374847 --0.922461628914,1.9196523428,-9.14912891388 --0.895457565784,1.92065918446,-9.15757083893 --0.835248410702,1.87678360939,-8.97022247314 --0.809243500233,1.87779092789,-8.97765445709 --0.782237052917,1.87779915333,-8.98409938812 --0.769237041473,1.87880134583,-8.99031925201 --0.742221057415,1.87781488895,-8.98675060272 --0.714201629162,1.87583053112,-8.9801940918 --0.687191426754,1.87584078312,-8.98263645172 --0.660185158253,1.87684893608,-8.98908233643 --0.634179472923,1.87785685062,-8.99551105499 --0.606158733368,1.8748729229,-8.98795604706 --0.592145383358,1.87288272381,-8.98117542267 --0.564123928547,1.87089955807,-8.97262096405 --0.537112772465,1.87091052532,-8.97406196594 --0.510090470314,1.86792743206,-8.9644908905 --0.482069790363,1.86594367027,-8.95694065094 --0.455059558153,1.86595416069,-8.95938396454 --0.429054766893,1.8669615984,-8.96681594849 --0.415037184954,1.86397361755,-8.95603466034 --0.388030052185,1.86498248577,-8.96148109436 --0.361015707254,1.86399519444,-8.95992088318 --0.33399656415,1.86301076412,-8.95335865021 --0.306973040104,1.86002850533,-8.94279384613 --0.279957652092,1.85904181004,-8.94023513794 --0.266978412867,1.86503303051,-8.96646595001 --0.23893687129,1.85806071758,-8.93890857697 --0.211915388703,1.85607743263,-8.93034744263 --0.185907706618,1.85708653927,-8.9347782135 --0.158890068531,1.85510110855,-8.93021965027 --0.131879985332,1.85611176491,-8.93266677856 --0.104862563312,1.85512638092,-8.92811012268 --0.0918544307351,1.85413324833,-8.92632293701 --0.0648411512375,1.8541456461,-8.92576885223 --0.037824653089,1.85315978527,-8.92221450806 --0.0118021499366,1.85017681122,-8.91264152527 --0.00923335179687,1.83479559422,-8.05799674988 -0.0167659595609,1.831787467,-8.04637908936 -0.0448257699609,1.84181141853,-8.09177780151 -0.0578109771013,1.8377995491,-8.07197189331 -0.0838103294373,1.83479142189,-8.06035518646 -0.110842607915,1.83980071545,-8.07974243164 -0.137850791216,1.83879709244,-8.07613754272 -0.163844108582,1.83478593826,-8.05852413177 -0.189851909876,1.83378231525,-8.05490589142 -0.217893451452,1.83979666233,-8.08329963684 -0.229872465134,1.83478164673,-8.05748939514 -0.25687661767,1.83277595043,-8.04988956451 -0.281861513853,1.82676041126,-8.0242729187 -0.307858347893,1.82375097275,-8.00966453552 -0.334869921207,1.82374930382,-8.00906085968 -0.359858244658,1.81873559952,-7.98644781113 -0.386871725321,1.81873512268,-7.98784542084 -0.399887114763,1.8217394352,-7.99702787399 -0.426900625229,1.82173895836,-7.99842405319 -0.453915268183,1.82273888588,-8.00081920624 -0.478915959597,1.82073187828,-7.99019765854 -0.505927562714,1.82073032856,-7.98959684372 -0.531931638718,1.81872498989,-7.98198843002 -0.545949220657,1.82173037529,-7.99318122864 -0.570941984653,1.81771910191,-7.97457170486 -0.596944272518,1.81571280956,-7.96496772766 -0.623966872692,1.81871724129,-7.97535181046 -0.64794844389,1.81170034409,-7.94574642181 -0.673962652683,1.81270039082,-7.94812726974 -0.698953986168,1.80868840218,-7.92752695084 -0.710942864418,1.80467891693,-7.9107298851 -0.736953318119,1.80467700958,-7.90911865234 -0.763975024223,1.80768096447,-7.91850376129 -0.789981424809,1.80667710304,-7.9128985405 -0.815994799137,1.80767667294,-7.91428184509 -0.844020783901,1.81168282032,-7.92767238617 -0.867002546787,1.80466628075,-7.89806604385 -0.88101708889,1.80766999722,-7.90625762939 -0.906015396118,1.80466198921,-7.89265346527 -0.931012928486,1.80165362358,-7.87805271149 -0.95702445507,1.8026522398,-7.87743902206 -0.984041929245,1.80365419388,-7.8828291893 -1.00803160667,1.79964160919,-7.86023139954 -1.03605628014,1.8026471138,-7.87262153625 -1.04705119133,1.80064117908,-7.86180686951 -1.06903147697,1.79362416267,-7.83020305634 -1.09604454041,1.79462349415,-7.83060407639 -1.12306332588,1.79762601852,-7.83698987961 -1.14605474472,1.79361474514,-7.81638002396 -1.17004847527,1.78960454464,-7.79778194427 -1.19706702232,1.79160714149,-7.80416917801 -1.20806217194,1.78960120678,-7.79335927963 -1.25605487823,1.78358376026,-7.76115703583 -1.2780444622,1.77957177162,-7.73854541779 -1.30405259132,1.77956879139,-7.73394680023 -1.33308207989,1.78357696533,-7.75133323669 -1.35406601429,1.77856206894,-7.72272539139 -1.3731033802,1.785577178,-7.75392198563 -1.39106941223,1.7755535841,-7.70732355118 -1.41305851936,1.77154135704,-7.68372154236 -1.4400755167,1.77354311943,-7.68811368942 -1.46809637547,1.77654659748,-7.69650697708 -1.48707592487,1.76953017712,-7.66389131546 -1.50108551979,1.77053153515,-7.66709184647 -1.52709746361,1.77153074741,-7.66648244858 -1.54808449745,1.76651787758,-7.64087867737 -1.57409489155,1.76751625538,-7.63827753067 -1.60010492802,1.76751458645,-7.6356754303 -1.62109422684,1.76350283623,-7.61206912994 -1.64710795879,1.76450312138,-7.61345481873 -1.66011178493,1.76450157166,-7.61065912247 -1.68311178684,1.7624951601,-7.59804773331 -1.70510530472,1.75948548317,-7.57844686508 -1.73312699795,1.76248967648,-7.5878329277 -1.75612533092,1.76048243046,-7.57323074341 -1.78012788296,1.75947713852,-7.56262922287 -1.81116127968,1.76548695564,-7.58401346207 -1.8221590519,1.76448261738,-7.57521009445 -1.84415340424,1.76047360897,-7.55661010742 -1.86916089058,1.76047074795,-7.55100536346 -1.89215946198,1.75846374035,-7.53640604019 -1.91716682911,1.75846087933,-7.53080177307 -1.94217598438,1.75945901871,-7.5271897316 -1.96316695213,1.75544834137,-7.50459527969 -1.97617518902,1.75644922256,-7.50678014755 -2.00318956375,1.75844979286,-7.50817775726 -2.02217626572,1.75343728065,-7.48157262802 -2.04517436028,1.75143003464,-7.46598243713 -2.06416153908,1.74641776085,-7.43938159943 -2.09318518639,1.75042295456,-7.45076608658 -2.1181936264,1.75042080879,-7.44615936279 -2.13320589066,1.75242352486,-7.45235586166 -2.15620684624,1.75141775608,-7.43975448608 -2.18221735954,1.75241661072,-7.43715286255 -2.20822954178,1.75341618061,-7.43654251099 -2.23123049736,1.75241053104,-7.42394208908 -2.2572426796,1.75341022015,-7.42333078384 -2.27325963974,1.75741529465,-7.43451499939 -2.29124355316,1.75140154362,-7.40392684937 -2.31625294685,1.75240004063,-7.40031433105 -2.34025740623,1.7513961792,-7.39171218872 -2.36526441574,1.75139331818,-7.38511419296 -2.3902721405,1.75239098072,-7.37951087952 -2.41427946091,1.75238847733,-7.37389373779 -2.41825771332,1.74637544155,-7.3441028595 -2.44627308846,1.74837660789,-7.34650468826 -2.47429132462,1.75137901306,-7.35189008713 -2.49328351021,1.74836969376,-7.33028173447 -2.52129983902,1.75137138367,-7.3336763382 -2.55132031441,1.75437474251,-7.3410782814 -2.57933664322,1.75737631321,-7.34446954727 -2.59835982323,1.76238429546,-7.36265039444 -2.61534452438,1.75737118721,-7.33206224442 -2.63333415985,1.75336062908,-7.30745983124 -2.66235256195,1.75636315346,-7.31285333633 -2.68735933304,1.75636053085,-7.3062543869 -2.71236872673,1.75735926628,-7.30263900757 -2.73637390137,1.75735580921,-7.29403591156 -2.74336314201,1.75434792042,-7.27524375916 -2.76837182045,1.75534617901,-7.27063369751 -2.78836488724,1.75133728981,-7.24904870987 -2.81437730789,1.75333726406,-7.24843025208 -2.84439587593,1.75733983517,-7.25383281708 -2.86940479279,1.75833821297,-7.24922132492 -2.90944910049,1.76835238934,-7.28259897232 -2.91042423248,1.76133835316,-7.24881458282 -2.94144630432,1.76534259319,-7.25820398331 -2.95743274689,1.76033091545,-7.22960662842 -2.98143720627,1.76032733917,-7.22000932693 -3.00243592262,1.75932109356,-7.20440626144 -3.03446054459,1.76432657242,-7.21678781509 -3.05646061897,1.76332092285,-7.20219278336 -3.07147073746,1.76532280445,-7.20638036728 -3.09647727013,1.76531994343,-7.19878482819 -3.11647343636,1.76331281662,-7.18018722534 -3.14248347282,1.76531171799,-7.1765794754 -3.16648960114,1.76530897617,-7.1689696312 -3.19049406052,1.76530539989,-7.15937232971 -3.20951128006,1.76931011677,-7.17056751251 -3.22750401497,1.76630139351,-7.14797019958 -3.25251197815,1.76729953289,-7.14236021042 -3.28052425385,1.76929926872,-7.14076519012 -3.30252504349,1.76829433441,-7.12716531754 -3.32753252983,1.76929211617,-7.12056064606 -3.34953355789,1.76828718185,-7.10696172714 -3.35953378677,1.76828467846,-7.10014820099 -3.38353848457,1.7682813406,-7.09055042267 -3.41656136513,1.77328586578,-7.10093927383 -3.43455457687,1.77027750015,-7.07834720612 -3.45855998993,1.77027463913,-7.06974172592 -3.48356676102,1.77127206326,-7.06214284897 -3.51158046722,1.77427268028,-7.06252813339 -3.52057743073,1.77326881886,-7.05172920227 -3.54558324814,1.77326607704,-7.04313707352 -3.57559990883,1.77726769447,-7.04652643204 -3.59459662437,1.77526116371,-7.02792263031 -3.61860227585,1.7752584219,-7.0193157196 -3.64961981773,1.77926051617,-7.02370882034 -3.65959978104,1.77324688435,-6.98612260818 -3.67360520363,1.77424645424,-6.98432826996 -3.69360351562,1.77224075794,-6.96772623062 -3.71660685539,1.77223694324,-6.95612812042 -3.7315967083,1.76822769642,-6.92953443527 -3.75660347939,1.76922535896,-6.92193412781 -3.78361487389,1.77122497559,-6.91932249069 -3.81164431572,1.77923464775,-6.94450950623 -3.83865475655,1.78223383427,-6.94090223312 -3.8566493988,1.77922642231,-6.91931200027 -3.86663079262,1.77321374416,-6.88273239136 -3.90065407753,1.77921843529,-6.89410209656 -3.91965079308,1.77721202374,-6.87451219559 -3.94565868378,1.77821028233,-6.86791372299 -3.95866322517,1.77920949459,-6.86511039734 -3.98867821693,1.78321063519,-6.86650037766 -4.01268291473,1.78320753574,-6.85590553284 -4.03969335556,1.78520679474,-6.85229444504 -4.06369781494,1.78620374203,-6.84169864655 -4.08670091629,1.78619992733,-6.82910585403 -4.10870313644,1.78619611263,-6.81650018692 -4.11970472336,1.78619432449,-6.81069326401 -4.15172147751,1.79019582272,-6.81309509277 -4.16070413589,1.78418433666,-6.77850008011 -4.18971681595,1.78718411922,-6.77590322495 -4.21572542191,1.78818285465,-6.77029132843 -4.24373579025,1.7911823988,-6.76668739319 -4.26573753357,1.79117798805,-6.75209760666 -4.28475046158,1.79418075085,-6.75928401947 -4.3037481308,1.79317510128,-6.74068832397 -4.32274675369,1.79216969013,-6.72308492661 -4.3517575264,1.79416918755,-6.71949195862 -4.38577699661,1.80017209053,-6.72587442398 -4.41078281403,1.80116927624,-6.71528673172 -4.41477537155,1.79816424847,-6.69947576523 -4.44779157639,1.80216574669,-6.70187711716 -4.47079563141,1.80316257477,-6.6902718544 -4.49580144882,1.80415999889,-6.68067455292 -4.51680278778,1.80415582657,-6.6660695076 -4.54681491852,1.80715572834,-6.66347265244 -4.56681394577,1.80615079403,-6.64588165283 -4.57781553268,1.80614888668,-6.63908147812 -4.60582542419,1.8091480732,-6.63447475433 -4.62982988358,1.81014537811,-6.62387132645 -4.65884065628,1.8121445179,-6.61927604675 -4.67884111404,1.81214022636,-6.60366630554 -4.69783878326,1.81113469601,-6.58408117294 -4.72785139084,1.81413495541,-6.58246898651 -4.74085521698,1.81513404846,-6.5786652565 -4.76085424423,1.81412923336,-6.5610742569 -4.78686141968,1.81612730026,-6.55247402191 -4.80285644531,1.81412088871,-6.52988100052 -4.82686090469,1.81511795521,-6.51828384399 -4.86087799072,1.82011950016,-6.52067756653 -4.87687253952,1.81711316109,-6.49808549881 -4.8868727684,1.81711113453,-6.49028110504 -4.9198884964,1.82211232185,-6.49166870117 -4.94088888168,1.8211081028,-6.47508049011 -4.99392747879,1.83411753178,-6.50344944 -5.02293729782,1.83711659908,-6.49784946442 -5.02791976929,1.83010578156,-6.46026849747 -5.04791927338,1.8301012516,-6.44267606735 -5.07193517685,1.8351047039,-6.45286417007 -5.093937397,1.83510100842,-6.43826580048 -5.13095569611,1.84110319614,-6.44266080856 -5.1529583931,1.84209990501,-6.42905139923 -5.17896461487,1.84409749508,-6.41845941544 -5.19395875931,1.84109127522,-6.39486646652 -5.23097705841,1.84709334373,-6.39925479889 -5.23597145081,1.84508895874,-6.38346815109 -5.26798343658,1.84908902645,-6.38086509705 -5.28998613358,1.84908556938,-6.36626434326 -5.3109869957,1.84908175468,-6.35066175461 -5.33098649979,1.84907710552,-6.33207654953 -5.37601327896,1.85808193684,-6.34644842148 -5.38300991058,1.85707879066,-6.3336558342 -5.40000629425,1.85507321358,-6.31206607819 -5.43001651764,1.85807240009,-6.30646371841 -5.4329996109,1.85206258297,-6.26887702942 -5.39093828201,1.83003759384,-6.17733335495 -5.29982805252,1.78899669647,-6.02783918381 -5.29780864716,1.78198623657,-5.98625564575 -5.3028049469,1.77998292446,-5.97246074677 -5.32881212234,1.7819814682,-5.96286725998 -5.32479047775,1.77397036552,-5.91829824448 -5.33778572083,1.77096498013,-5.89470481873 -5.35478544235,1.76996123791,-5.87610530853 -5.33174657822,1.75594460964,-5.81055307388 -5.33873653412,1.75093770027,-5.77997255325 -5.35073947906,1.75193679333,-5.7741765976 -5.35372638702,1.74592912197,-5.74058532715 -5.36271905899,1.74292302132,-5.7129983902 -5.38071966171,1.74191963673,-5.69441699982 -5.37970352173,1.7359110117,-5.65682935715 -5.40270900726,1.73690915108,-5.6442399025 -5.39669704437,1.73190355301,-5.62044095993 -5.39868354797,1.72589576244,-5.58487176895 -5.40767717361,1.72289037704,-5.55828285217 -5.4286813736,1.72388839722,-5.54468297958 -5.42966794968,1.71788072586,-5.50910806656 -5.44466686249,1.71687710285,-5.48852205276 -5.46066713333,1.71587383747,-5.46992492676 -5.45565605164,1.71086859703,-5.44614696503 -5.46665239334,1.70886433125,-5.42255306244 -5.47664737701,1.70585954189,-5.39697217941 -5.48864459991,1.70485544205,-5.37437915802 -5.49763870239,1.70085048676,-5.34780168533 -5.52064561844,1.70284950733,-5.33719205856 -5.52163410187,1.69784295559,-5.30360937119 -5.52563095093,1.69584023952,-5.28883457184 -5.5426325798,1.69583785534,-5.27222967148 -5.55162811279,1.69283330441,-5.24664497375 -5.574634552,1.69483220577,-5.23504781723 -5.57862615585,1.69082665443,-5.20446920395 -5.59162473679,1.68882334232,-5.18288326263 -5.6076259613,1.68882071972,-5.16429424286 -5.60762023926,1.6858175993,-5.14750289917 -5.61361408234,1.68181288242,-5.11991596222 -5.6276140213,1.68180990219,-5.0993309021 -5.63460826874,1.67780554295,-5.07274484634 -5.6446056366,1.67580199242,-5.04915475845 -5.66761207581,1.67780089378,-5.03657054901 -5.67660951614,1.67579734325,-5.01297092438 -5.6756029129,1.6717941761,-4.99518823624 -5.69560813904,1.67379295826,-4.98158311844 -5.71261072159,1.67379081249,-4.96399688721 -5.7146024704,1.66878592968,-4.93341398239 -5.72660160065,1.66778314114,-4.91182565689 -5.73559904099,1.66577970982,-4.88724422455 -5.74159812927,1.66477823257,-4.87645053864 -5.74559211731,1.66077399254,-4.84786939621 -5.7565908432,1.65877103806,-4.8252863884 -5.76358699799,1.65676748753,-4.79970026016 -5.77958917618,1.65676569939,-4.78210735321 -5.7965927124,1.65676414967,-4.76551151276 -5.79558324814,1.65175914764,-4.73194885254 -5.79457902908,1.64875674248,-4.71614980698 -5.81458425522,1.64975583553,-4.70156097412 -5.82558345795,1.64875328541,-4.6799697876 -5.82957839966,1.64474976063,-4.65238618851 -5.84458017349,1.64474797249,-4.63379859924 -5.84857559204,1.64174437523,-4.6062169075 -5.85757398605,1.63974177837,-4.58263540268 -5.86957836151,1.64074170589,-4.57782840729 -5.87757587433,1.63873898983,-4.55325078964 -5.87756919861,1.63473510742,-4.5226726532 -5.89757490158,1.6357344389,-4.5090713501 -5.90957546234,1.63473260403,-4.48848295212 -5.91557264328,1.63172972202,-4.46290254593 -5.9395813942,1.63472962379,-4.4513130188 -5.93157291412,1.63072669506,-4.43052196503 -5.93757009506,1.62772405148,-4.40494394302 -5.96157884598,1.63072395325,-4.39335441589 -5.96857690811,1.62772166729,-4.36976051331 -5.96757030487,1.62371826172,-4.33918428421 -5.98557567596,1.62471759319,-4.32359027863 -5.98957443237,1.62371647358,-4.31179952621 -5.98956918716,1.61971342564,-4.28222322464 -6.01457834244,1.62271368504,-4.27261400223 -6.01357221603,1.61771047115,-4.24204444885 -6.0345788002,1.61971032619,-4.22845172882 -6.04257822037,1.61770832539,-4.20487308502 -6.04357385635,1.61470592022,-4.17728424072 -6.04957485199,1.61370515823,-4.16650152206 -6.07258319855,1.61670529842,-4.15489816666 -6.065574646,1.61070179939,-4.12132167816 -6.07157325745,1.608700037,-4.09674215317 -6.09958410263,1.61270058155,-4.08814334869 -6.09757852554,1.60769808292,-4.05856180191 -6.10857963562,1.60669696331,-4.0369887352 -6.11458110809,1.60669648647,-4.02817773819 -6.10957431793,1.60169374943,-3.99561524391 -6.11757516861,1.6006923914,-3.97303032875 -6.13457965851,1.60169196129,-3.95644307137 -6.12357091904,1.59468889236,-3.92185878754 -6.14657878876,1.59768915176,-3.90926861763 -6.15958213806,1.59768843651,-3.88968849182 -6.15057611465,1.59268677235,-3.86990427971 -6.14657068253,1.58868467808,-3.84031772614 -6.17758321762,1.59368574619,-3.83272576332 -6.16957616806,1.58768332005,-3.8001499176 -6.17557573318,1.58568227291,-3.77656888962 -6.19558286667,1.58768236637,-3.76197981834 -6.1865773201,1.58368098736,-3.74318671227 -6.19757986069,1.58268046379,-3.72260785103 -6.21558618546,1.58368051052,-3.70701551437 -6.2035779953,1.57767820358,-3.67244410515 -6.21858263016,1.5786781311,-3.65485596657 -6.23658895493,1.57967817783,-3.63926386833 -6.23158454895,1.57467675209,-3.60968351364 -6.23258399963,1.57367634773,-3.59689378738 -6.2505903244,1.57467651367,-3.58031749725 -6.24558639526,1.57067525387,-3.55074071884 -6.25758981705,1.57067513466,-3.532143116 -6.27459573746,1.57167518139,-3.51555776596 -6.27359390259,1.56867444515,-3.48798823357 -6.27859449387,1.56667387486,-3.46539378166 -6.29059934616,1.56867432594,-3.45959186554 -6.28859758377,1.56467354298,-3.43201732635 -6.29359817505,1.5626732111,-3.40844082832 -6.31360578537,1.56567370892,-3.39384865761 -6.3206076622,1.56367361546,-3.37127399445 -6.32460832596,1.56167328358,-3.34867477417 -6.34361553192,1.56367397308,-3.33308911324 -6.32860898972,1.55867302418,-3.31131649017 -6.33661174774,1.55767297745,-3.28973674774 -6.35261774063,1.55867350101,-3.27314257622 -6.34861564636,1.55467307568,-3.24556159973 -6.35061597824,1.55267298222,-3.22098278999 -6.37362527847,1.55567383766,-3.20838093758 -6.37462568283,1.55467379093,-3.19559979439 -6.37662601471,1.55167388916,-3.171022892 -6.38262844086,1.55067420006,-3.14844608307 -6.39163160324,1.55067455769,-3.12786126137 -6.39463329315,1.54867470264,-3.10427856445 -6.41264009476,1.55067551136,-3.08868312836 -6.40563774109,1.54567551613,-3.06010556221 -6.40363740921,1.54367554188,-3.04632115364 -6.42264509201,1.54667639732,-3.03073310852 -6.41964483261,1.54267668724,-3.00415706635 -6.41964530945,1.53967702389,-2.97957253456 -6.42764902115,1.53967773914,-2.95898342133 -6.42864990234,1.53767824173,-2.93440842628 -6.43965435028,1.5386787653,-2.92760896683 -6.4496588707,1.53867948055,-2.90703558922 -6.4536614418,1.53768026829,-2.88445091248 -6.45166158676,1.53368091583,-2.85887384415 -6.47166967392,1.53668189049,-2.84427404404 -6.46967029572,1.53368258476,-2.81869792938 -6.47867488861,1.53368353844,-2.79811882973 -6.48367738724,1.53368401527,-2.7883245945 -6.47967767715,1.52968490124,-2.76175379753 -6.49268388748,1.53068590164,-2.74317026138 -6.4986872673,1.529687047,-2.72158765793 -6.50969266891,1.53068804741,-2.70298957825 -6.51569652557,1.52968919277,-2.68140745163 -6.52670192719,1.52969038486,-2.66182661057 -6.50769662857,1.52369081974,-2.6410548687 -6.5207028389,1.52469205856,-2.62247157097 -6.52270555496,1.52369320393,-2.5998814106 -6.53071022034,1.52369451523,-2.57929849625 -6.53271341324,1.52169585228,-2.55670976639 -6.54672002792,1.52269721031,-2.53813314438 -6.54672241211,1.52069854736,-2.51454949379 -6.54572343826,1.51869928837,-2.50176906586 -6.55772924423,1.51970076561,-2.48317885399 -6.56273365021,1.51870214939,-2.46159482002 -6.56973838806,1.5187035799,-2.44100689888 -6.58174467087,1.51970517635,-2.42143368721 -6.57974720001,1.5167068243,-2.39685869217 -6.57274675369,1.51470768452,-2.38305974007 -6.5847530365,1.51470923424,-2.36348748207 -6.59675884247,1.51571071148,-2.34489679337 -6.60076332092,1.5147125721,-2.32330942154 -6.60576820374,1.51471424103,-2.30172801018 -6.60076999664,1.51071619987,-2.27615761757 -6.61077642441,1.51171791553,-2.25657248497 -6.61477851868,1.51171875,-2.24677419662 -6.61878347397,1.51072061062,-2.2242064476 -6.62078714371,1.50972259045,-2.20260953903 -6.63579463959,1.51072430611,-2.18403625488 -6.637799263,1.50972628593,-2.16244029999 -6.64380455017,1.50972831249,-2.14086747169 -6.66281270981,1.51172995567,-2.12428021431 -6.64381027222,1.50673151016,-2.10649394989 -6.6588177681,1.50873339176,-2.08791947365 -6.66482305527,1.5077354908,-2.06732988358 -6.66082620621,1.504737854,-2.04275727272 -6.67183303833,1.50573980808,-2.02317786217 -6.68384027481,1.50774180889,-2.00458478928 -6.67084121704,1.50274455547,-1.97702038288 -6.68384647369,1.50474536419,-1.97021651268 -6.68485116959,1.50374782085,-1.9476377964 -6.68785572052,1.50275015831,-1.92605209351 -6.67485761642,1.49775326252,-1.89849352837 -6.70686912537,1.50375461578,-1.88589453697 -6.69887208939,1.50075745583,-1.86130833626 -6.69687414169,1.49875891209,-1.8485352993 -6.70488071442,1.49976122379,-1.82894015312 -6.70288515091,1.49676406384,-1.80536925793 -6.70689058304,1.49676668644,-1.78379130363 -6.70989656448,1.49576926231,-1.76220929623 -6.71390199661,1.49577188492,-1.74063205719 -6.72390937805,1.4957742691,-1.72104716301 -6.73291349411,1.49777531624,-1.71225452423 -6.71491479874,1.49177920818,-1.68468618393 -6.72592258453,1.49278140068,-1.6660875082 -6.75493335724,1.49878299236,-1.6514954567 -6.72893333435,1.49078726768,-1.62193250656 -6.73294019699,1.49079024792,-1.60035765171 -6.76695203781,1.49679160118,-1.58676552773 -6.74094963074,1.49079442024,-1.56898593903 -6.74695634842,1.49079728127,-1.54840147495 -6.76996660233,1.49479925632,-1.53181433678 -6.74896860123,1.48780345917,-1.50424695015 -6.76197624207,1.48980605602,-1.4856544733 -6.77698516846,1.49180841446,-1.46706926823 -6.75898742676,1.48681282997,-1.4405002594 -6.77099275589,1.48881363869,-1.43269741535 -6.79400253296,1.49281573296,-1.41512346268 -6.78600692749,1.48981964588,-1.39154028893 -6.7810125351,1.48782324791,-1.36796998978 -6.80102205276,1.4918255806,-1.3503818512 -6.7800245285,1.48483037949,-1.32381033897 -6.77102613449,1.48183274269,-1.31102180481 -6.79503679276,1.48683464527,-1.29442822933 -6.79004240036,1.48483860493,-1.27086150646 -6.72603845596,1.467846632,-1.2353168726 -6.75904989243,1.47484791279,-1.22071671486 -6.75205612183,1.47285223007,-1.19714796543 -6.78506755829,1.47885358334,-1.18254351616 -6.8050737381,1.48285388947,-1.17574203014 -6.77507591248,1.47485995293,-1.14719355106 -6.78308391571,1.4758630991,-1.12759923935 -6.79909324646,1.47886574268,-1.10901033878 -6.81110191345,1.48086869717,-1.08942687511 -6.82110977173,1.48187196255,-1.06885552406 -6.83411836624,1.48387479782,-1.05025434494 -6.8251209259,1.48187744617,-1.03747451305 -6.81912708282,1.47888183594,-1.01489460468 -6.83813667297,1.48288428783,-0.996309161186 -6.74413156509,1.45989584923,-0.958774745464 -6.77114295959,1.46489787102,-0.941195368767 -6.84415960312,1.48189616203,-0.931580603123 -6.77415752411,1.46390593052,-0.899030566216 -6.75115919113,1.45891010761,-0.884260356426 -6.83917713165,1.47790682316,-0.876636207104 -6.80017995834,1.46791434288,-0.849077284336 -6.79218673706,1.46591925621,-0.826500594616 -6.7941942215,1.46492338181,-0.804929673672 -6.76819896698,1.45893001556,-0.780352950096 -6.77520370483,1.45993149281,-0.770562529564 -6.82321691513,1.46993160248,-0.755957901478 -6.76621866226,1.45594120026,-0.72641569376 -6.79422950745,1.46194314957,-0.70882332325 -6.79923820496,1.4629471302,-0.68823993206 -6.78424453735,1.45895290375,-0.665656387806 -6.7892537117,1.45895719528,-0.644093394279 -6.7832570076,1.45695984364,-0.633296072483 -6.76426315308,1.4519661665,-0.609728872776 -6.74326944351,1.44697272778,-0.58616065979 -6.70327425003,1.43698132038,-0.560602545738 -6.72928476334,1.44198358059,-0.542020261288 -6.75129556656,1.44698619843,-0.523428499699 -6.72529745102,1.44099104404,-0.51064324379 -6.74830770493,1.44499349594,-0.492052018642 -6.70631313324,1.43500256538,-0.466502964497 -6.7393245697,1.44200408459,-0.448904365301 -6.67932844162,1.42801511288,-0.42235776782 -6.68733739853,1.4290189743,-0.402765542269 -6.64834356308,1.42002809048,-0.378215372562 -6.70035219193,1.43102526665,-0.372396856546 -6.67635917664,1.42603266239,-0.349826514721 -6.68836927414,1.42803657055,-0.329257667065 -6.71338033676,1.43303894997,-0.310660541058 -6.70338869095,1.43104505539,-0.289087593555 -6.70639801025,1.43104982376,-0.26850771904 -6.70640707016,1.43105494976,-0.247925043106 -6.70141124725,1.42905795574,-0.237140119076 -6.70242071152,1.42906296253,-0.216558814049 -6.65542697906,1.41807341576,-0.19300621748 -6.67743825912,1.42307627201,-0.173420280218 -6.65344619751,1.41708409786,-0.151847615838 -6.67045688629,1.42108750343,-0.132257014513 -6.66346073151,1.41909086704,-0.121474348009 -6.64647006989,1.41509819031,-0.0999091267586 -6.67448091507,1.42110049725,-0.0803202465177 -6.67549085617,1.42110574245,-0.0597412101924 -6.6825003624,1.42211008072,-0.0401434004307 -6.69651126862,1.42611408234,-0.0195653047413 -6.67852067947,1.4211217165,0.00199601217173 -6.67452478409,1.42012465,0.0117957741022 -6.67753505707,1.42112994194,0.0323748700321 -6.65654420853,1.41613805294,0.0539319440722 -6.66055440903,1.41714298725,0.0745102390647 -6.65756464005,1.4161490202,0.0950873866677 -6.68257522583,1.42215144634,0.114692017436 -6.67158508301,1.41915822029,0.135267347097 -6.57458639145,1.39617276192,0.146011024714 -6.66359996796,1.41716790199,0.166621476412 -6.66561079025,1.41717326641,0.187200248241 -6.68362140656,1.42217671871,0.207788467407 -6.63263034821,1.41018891335,0.228336155415 -6.64064121246,1.41219365597,0.248917609453 -6.67765235901,1.42019474506,0.269521296024 -6.67765760422,1.42019748688,0.27932074666 -6.6806678772,1.42120289803,0.299902141094 -6.68267869949,1.4222086668,0.32146307826 -6.68868923187,1.42321372032,0.342047929764 -6.68969964981,1.42321944237,0.362628519535 -6.67171049118,1.41922748089,0.382208973169 -6.67571544647,1.42023003101,0.392992764711 -6.65372610092,1.41523873806,0.412566065788 -6.63873720169,1.41224682331,0.433125376701 -6.63974809647,1.4132527113,0.453703761101 -6.63775777817,1.41225874424,0.473298102617 -6.6427693367,1.41326439381,0.494862049818 -6.6477804184,1.41526973248,0.51544713974 -6.65278577805,1.41627192497,0.525253653526 -6.66179704666,1.41827690601,0.546826004982 -6.65280818939,1.41728401184,0.566410601139 -6.67081975937,1.42128801346,0.588979542255 -6.65783071518,1.41829586029,0.608556509018 -6.65684127808,1.41830217838,0.629133939743 -6.65885305405,1.41930794716,0.649717152119 -6.615858078,1.40931677818,0.656494736671 -6.6428694725,1.41631948948,0.67908513546 -6.64988088608,1.41832482815,0.700658380985 -6.62689256668,1.41333425045,0.719229698181 -6.65990400314,1.4213360548,0.742819309235 -6.6659154892,1.42334163189,0.764393389225 -6.65892076492,1.42234539986,0.773198306561 -6.64393234253,1.41835403442,0.792764246464 -6.65594387054,1.42235851288,0.814353227615 -6.63195610046,1.41736841202,0.832915902138 -6.6439666748,1.42037308216,0.854505896568 -6.66297864914,1.4253770113,0.87807571888 -6.63599061966,1.41938722134,0.895647108555 -6.62699651718,1.41739153862,0.904443621635 -6.63400840759,1.4193969965,0.926023304462 -6.60902118683,1.41440737247,0.944575130939 -6.61203289032,1.41541337967,0.965163707733 -6.63904380798,1.42241585255,0.988762915134 -6.60905694962,1.41642701626,1.00631654263 -6.62606811523,1.42043101788,1.02890896797 -6.59907484055,1.41443824768,1.03568744659 -6.59108686447,1.41344606876,1.05526340008 -6.62509870529,1.42244768143,1.08085286617 -6.58211183548,1.41246068478,1.09541606903 -6.55012512207,1.40547227859,1.11197090149 -6.53513813019,1.40348124504,1.13053965569 -6.56914901733,1.41148293018,1.15613532066 -6.53515625,1.40449118614,1.16091799736 -6.54316806793,1.40649664402,1.1825054884 -6.56717967987,1.41350007057,1.20709228516 -6.54819297791,1.4095095396,1.22466480732 -6.56020545959,1.41351497173,1.24823117256 -6.62021493912,1.42751264572,1.27884113789 -6.58822250366,1.42052078247,1.28362202644 -6.58423519135,1.42052841187,1.30419170856 -6.5962471962,1.42453324795,1.32678437233 -6.54726219177,1.4135478735,1.33933401108 -6.5102763176,1.40556025505,1.35290694237 -6.52028894424,1.40856575966,1.3754901886 -6.50330209732,1.40557527542,1.3930618763 -6.55530595779,1.41857099533,1.4138635397 -6.53931951523,1.41558027267,1.43144071102 -6.52433300018,1.41358959675,1.44902086258 -6.58134269714,1.42758774757,1.48161840439 -6.5983543396,1.43259215355,1.50620412827 -6.5693693161,1.42660391331,1.52176308632 -6.57837486267,1.42960572243,1.5335688591 -6.60138654709,1.43560945988,1.56014657021 -6.57340192795,1.43062102795,1.5757073164 -6.58441352844,1.43362641335,1.59929120541 -6.59742546082,1.43763124943,1.6228864193 -6.58543920517,1.43664038181,1.64146173 -6.5194568634,1.4216581583,1.64800691605 -6.50946474075,1.41966342926,1.65678203106 -6.54547452927,1.42966461182,1.68539428711 -6.53448915482,1.42767393589,1.70495092869 -6.60749721527,1.44666945934,1.74356412888 -6.52651596069,1.42868959904,1.74511480331 -6.5635266304,1.4386909008,1.77570605278 -6.44354915619,1.41071772575,1.76723408699 -6.42955684662,1.40872359276,1.7740226984 -6.46056699753,1.41672587395,1.80262172222 -6.49857807159,1.42772710323,1.83420538902 -6.52159023285,1.43373084068,1.86178970337 -6.49760484695,1.42974185944,1.87636971474 -6.47662067413,1.4257529974,1.89292526245 -6.48663282394,1.42975854874,1.91651880741 -6.50663757324,1.43475902081,1.93232393265 -6.50065279007,1.43476760387,1.9528875351 -6.45766973495,1.42578220367,1.96244847775 -6.5176782608,1.4417797327,2.00104951859 -6.51769161224,1.44278717041,2.02263092995 -6.50070714951,1.44079744816,2.03920793533 -6.54970979691,1.45279312134,2.06500482559 -6.53672409058,1.45080268383,2.0825881958 -6.49474239349,1.44281733036,2.09214663506 -6.50175523758,1.44582366943,2.11573529243 -6.44577407837,1.43384063244,2.12029576302 -6.45578765869,1.43784677982,2.14586448669 -6.37380886078,1.41886806488,2.14142298698 -6.38881444931,1.42386949062,2.15721297264 -6.43282461166,1.43586957455,2.19280982018 -6.38584327698,1.4258852005,2.19937372208 -6.42785310745,1.43788588047,2.23496484756 -6.41386842728,1.43589603901,2.25253367424 -6.4258813858,1.44090163708,2.27812314034 -6.36190223694,1.42692041397,2.27867746353 -6.42690229416,1.44291305542,2.31149172783 -6.4589138031,1.45291543007,2.34507155418 -6.47192668915,1.45792102814,2.37165760994 -6.45994138718,1.45593059063,2.3892428875 -6.45095729828,1.45594012737,2.40881109238 -6.46197032928,1.45994615555,2.43538808823 -6.42698144913,1.45295608044,2.43416380882 -6.38199996948,1.44297158718,2.43973660469 -6.38201475143,1.44497966766,2.4623093605 -6.34903335571,1.43899333477,2.47286868095 -6.31405162811,1.43200719357,2.48144769669 -6.37605953217,1.44900429249,2.52704501152 -6.36307525635,1.44801449776,2.54461812973 -6.31808757782,1.43702626228,2.53839731216 -6.39809322357,1.45902037621,2.59199404716 -6.37711048126,1.45603203773,2.60656428337 -6.37112569809,1.45604121685,2.62713575363 -6.35514163971,1.45405173302,2.6427230835 -6.32316064835,1.44806563854,2.65327882767 -6.35716438293,1.45806372166,2.67808198929 -6.35717868805,1.46007156372,2.70066428185 -6.34319496155,1.45808196068,2.71724796295 -6.33721065521,1.45909106731,2.73782086372 -6.33822536469,1.4610991478,2.76139450073 -6.33524036407,1.4621077776,2.78297400475 -6.32825660706,1.46311736107,2.80354046822 -6.3242650032,1.46312212944,2.81332874298 -6.31228113174,1.4621322155,2.83090925217 -6.30229711533,1.46114206314,2.84948754311 -6.31031084061,1.46514892578,2.87606859207 -6.28532981873,1.46116161346,2.88863229752 -6.28234481812,1.4631704092,2.91021442413 -6.29335832596,1.46817648411,2.93780636787 -6.27236890793,1.46418452263,2.94057869911 -6.2583861351,1.462195158,2.95715904236 -6.26340007782,1.46620249748,2.98273921013 -6.23741912842,1.46121549606,2.99430632591 -6.23743438721,1.46422386169,3.01788067818 -6.2444486618,1.46823096275,3.04446339607 -6.21346855164,1.46224474907,3.05303764343 -6.2184753418,1.4652479887,3.06683373451 -6.21749067307,1.46725666523,3.09040236473 -6.19050979614,1.46226990223,3.10097289085 -6.18652629852,1.4642790556,3.12255072594 -6.19154024124,1.46728634834,3.14813899994 -6.1715593338,1.46529865265,3.16269874573 -6.16556787491,1.46430397034,3.17148756981 -6.16958284378,1.46831166744,3.19706964493 -6.14460134506,1.46432435513,3.20765209198 -6.13761854172,1.46533429623,3.22822237015 -6.14263343811,1.4683419466,3.25479912758 -6.11665296555,1.46435511112,3.26536941528 -6.11766862869,1.46736359596,3.289945364 -6.11967611313,1.4693672657,3.30273938179 -6.0936961174,1.46538078785,3.31330728531 -6.09271192551,1.46738946438,3.33688378334 -6.09672641754,1.47039711475,3.36247444153 -6.0747461319,1.46740984917,3.37504315376 -6.0587644577,1.46642136574,3.39061617851 -6.06977891922,1.47142803669,3.42119121552 -6.04179143906,1.46543765068,3.41797327995 -6.03480863571,1.46644747257,3.43854689598 -6.03982305527,1.47045516968,3.46513557434 -6.01784276962,1.4674680233,3.47769999504 -6.01385879517,1.46947717667,3.49928736687 -6.01487493515,1.47248589993,3.52485728264 -5.9888958931,1.46849942207,3.53443074226 -5.98890352249,1.46950352192,3.54622817039 -5.99491834641,1.47451126575,3.5748000145 -5.97393846512,1.47152400017,3.58737134933 -5.95695734024,1.46953594685,3.60194802284 -5.96097230911,1.47454369068,3.62853693962 -5.93999242783,1.47155642509,3.64110612869 -5.93800115585,1.47256147861,3.65288543701 -5.9370174408,1.47457015514,3.67647576332 -5.91403770447,1.4715834856,3.68803930283 -5.9040555954,1.47259414196,3.70662069321 -5.90807104111,1.47660219669,3.73419880867 -5.87709283829,1.47061681747,3.73977565765 -5.88310003281,1.47462022305,3.75655817986 -5.8761177063,1.47563040257,3.77713918686 -5.85813760757,1.47364294529,3.79170227051 -5.85215473175,1.47465252876,3.81229424477 -5.84817218781,1.47766244411,3.83585953712 -5.83019161224,1.47567474842,3.84943819046 -5.82820892334,1.47868418694,3.87401008606 -5.82721710205,1.47968864441,3.88580465317 -5.80123853683,1.47570264339,3.89437699318 -5.80425453186,1.47971093655,3.92195677757 -5.79327344894,1.47972202301,3.94053030014 -5.77229404449,1.47773504257,3.95210671425 -5.76831054688,1.47974455357,3.97469305992 -5.76232910156,1.48175489902,3.99725842476 -5.75033950806,1.4797617197,4.00204515457 -5.74135780334,1.48077249527,4.02162599564 -5.73537540436,1.4827824831,4.04320859909 -5.71639633179,1.48079550266,4.05677318573 -5.69741630554,1.47880804539,4.0693526268 -5.70143222809,1.48381626606,4.09793901443 -5.68745183945,1.48282802105,4.11451196671 -5.67246389389,1.48083591461,4.11827802658 -5.68147850037,1.48684287071,4.14987754822 -5.65850019455,1.48385667801,4.16044187546 -5.64351987839,1.48286855221,4.1760187149 -5.63153886795,1.48387992382,4.19359922409 -5.61555957794,1.48289239407,4.20916461945 -5.61456823349,1.48389697075,4.22096586227 -5.60658597946,1.4849075079,4.2415471077 -5.59160661697,1.48491990566,4.25810813904 -5.58062505722,1.48493087292,4.27570104599 -5.57764387131,1.48894095421,4.30126619339 -5.55866479874,1.48695385456,4.31384181976 -5.54568386078,1.48696541786,4.33042669296 -5.54169416428,1.48797118664,4.34219551086 -5.53471231461,1.48898172379,4.36377716064 -5.51273393631,1.48699510098,4.37336111069 -5.50775194168,1.48900532722,4.39693689346 -5.48577451706,1.48701906204,4.40750408173 -5.4857916832,1.49102830887,4.43508243561 -5.48180913925,1.49403810501,4.45867300034 -5.45482349396,1.48804819584,4.45144844055 -5.45384120941,1.49105763435,4.47803163528 -5.44286060333,1.49206900597,4.4966135025 -5.42588186264,1.49108183384,4.51118087769 -5.40590381622,1.48909521103,4.52275466919 -5.40592098236,1.49410438538,4.55034065247 -5.39293241501,1.4921118021,4.55411958694 -5.37695360184,1.49112451077,4.56968402863 -5.37497138977,1.4951338768,4.59527683258 -5.34899425507,1.49114847183,4.60184764862 -5.34701251984,1.4951581955,4.62842798233 -5.32703447342,1.49317169189,4.64000034332 -5.31005525589,1.49218440056,4.65358066559 -5.30906438828,1.4941893816,4.66736459732 -5.3030834198,1.49720001221,4.69094181061 -5.27810668945,1.49421465397,4.69850635529 -5.26812648773,1.49522578716,4.71809005737 -5.26014614105,1.49723684788,4.73967170715 -5.23916816711,1.49525046349,4.75024318695 -5.22918796539,1.4962618351,4.76982879639 -5.2291970253,1.49826657772,4.78461503983 -5.2082195282,1.49728035927,4.79518651962 -5.19823980331,1.4982919693,4.81575870514 -5.19325828552,1.50130236149,4.84034109116 -5.1742811203,1.50031578541,4.85290956497 -5.15230321884,1.49832952023,4.86149406433 -5.15231227875,1.50033426285,4.87628412247 -5.13033485413,1.49834799767,4.88486766815 -5.12735414505,1.502358675,4.91342449188 -5.11437416077,1.50237047672,4.93001699448 -5.09039783478,1.49938499928,4.93758583069 -5.07342004776,1.4993981123,4.95215177536 -5.07443761826,1.50440728664,4.98273992538 -5.05645084381,1.50141572952,4.98052549362 -5.05246973038,1.50442612171,5.00710296631 -5.05048847198,1.50943613052,5.03568267822 -5.02251291275,1.50545144081,5.039249897 -5.00653409958,1.50446403027,5.05284357071 -5.00755262375,1.51047372818,5.08541345596 -4.99056577682,1.50748193264,5.08419561386 -4.9765868187,1.50749433041,5.10077667236 -4.96960639954,1.51050531864,5.12436151505 -4.95662784576,1.51151764393,5.1429309845 -4.94164943695,1.51253020763,5.15851354599 -4.9436674118,1.51753950119,5.19209432602 -4.91269302368,1.51255548,5.19166660309 -4.90170478821,1.51256263256,5.19644832611 -4.90472221375,1.51857149601,5.23103427887 -4.87874746323,1.51558685303,5.23659515381 -4.86176967621,1.51459991932,5.25017690659 -4.86378765106,1.52160918713,5.28475379944 -4.84381055832,1.51962292194,5.29533338547 -4.81883430481,1.5166374445,5.29991817474 -4.82684230804,1.52264106274,5.32569932938 -4.80386638641,1.5206553936,5.33327436447 -4.79288721085,1.52166736126,5.35385322571 -4.784907341,1.52467858791,5.37743759155 -4.76093244553,1.52269363403,5.3849978447 -4.75095319748,1.52470529079,5.40658044815 -4.74397277832,1.52771615982,5.43116998672 -4.72598648071,1.52472484112,5.42795038223 -4.71100902557,1.52573776245,5.44452619553 -4.70502948761,1.52974903584,5.47209501266 -4.68105316162,1.52676343918,5.47767734528 -4.67407369614,1.53077471256,5.50325870514 -4.65609693527,1.52978801727,5.51584148407 -4.65010786057,1.5307943821,5.52662181854 -4.64012908936,1.5338062048,5.54919958115 -4.62215137482,1.53281962872,5.56178283691 -4.60317564011,1.53283345699,5.57435131073 -4.58719825745,1.53284657001,5.58992815018 -4.58421754837,1.53785681725,5.62051582336 -4.55924224854,1.53587174416,5.62509250641 -4.55425310135,1.53687775135,5.63687801361 -4.5452747345,1.53988957405,5.66145277023 -4.50230312347,1.53090810776,5.64303350449 -4.49132537842,1.53292012215,5.66461324692 -4.47734737396,1.53393292427,5.68318557739 -4.46536970139,1.5359454155,5.70376491547 -3.45562291145,1.16215395927,4.44042730331 -3.4326479435,1.15816855431,4.43900489807 -3.41867136955,1.15818154812,4.44957447052 -3.42368841171,1.16518986225,4.48218393326 -3.39671492577,1.16020536423,4.47575569153 -4.40348958969,1.5500125885,5.82444524765 -4.32052946091,1.52503955364,5.75300312042 -4.36452817917,1.5460357666,5.82979726791 -4.37554454803,1.55704331398,5.88138341904 -4.32357692719,1.54406404495,5.84994935989 -4.27760744095,1.53308331966,5.82552194595 -4.24063491821,1.52510035038,5.81111526489 -4.26164960861,1.54110622406,5.87769460678 -4.28966236115,1.5591108799,5.95526695251 -4.03773450851,1.46316671371,5.62602806091 -4.23370504379,1.54813718796,5.93562746048 -4.23972225189,1.55714559555,5.98122310638 -4.24773979187,1.56815445423,6.03279018402 -4.23776197433,1.57216668129,6.058365345 -4.1917924881,1.56018555164,6.03095436096 -4.19181203842,1.56819581985,6.07152414322 -4.20581817627,1.57819795609,6.11132001877 -4.22683191299,1.59420371056,6.18190431595 -4.23584985733,1.60621213913,6.23648023605 -4.20787572861,1.60222768784,6.23606204987 -4.18490171432,1.60124266148,6.2446269989 -4.17392396927,1.60425508022,6.27020168304 -4.16593503952,1.60526156425,6.27800178528 -4.12196540833,1.59428048134,6.2535777092 -4.11998605728,1.60229122639,6.29315137863 -4.11300706863,1.60730242729,6.32374048233 -4.10602855682,1.61231410503,6.35631322861 -3.97708129883,1.56635034084,6.19987487793 -4.07907438278,1.61833977699,6.40047216415 -4.08008480072,1.62334501743,6.42524814606 -3.31929826736,1.30250823498,5.26876497269 -4.09112071991,1.645362854,6.53041315079 -3.18937087059,1.25955426693,5.13193273544 -4.05216932297,1.64539074898,6.55657958984 -4.03319454193,1.64640510082,6.57214784622 -4.00921964645,1.64441978931,6.57773256302 -4.00323104858,1.64642620087,6.59052371979 -3.96226167679,1.63744461536,6.56909608841 -3.96628022194,1.64845395088,6.62167644501 -3.95330381393,1.6524668932,6.64724731445 -3.93132925034,1.65148162842,6.65682649612 -3.91535258293,1.65349471569,6.67541646957 -3.9093644619,1.65550124645,6.69019317627 -3.8883895874,1.65551578999,6.70177030563 -3.86541485786,1.65453016758,6.70836114883 -3.85143923759,1.65754365921,6.73392295837 -3.83346366882,1.65955746174,6.75050354004 -3.81048989296,1.65857243538,6.75907659531 -3.79351425171,1.66058599949,6.77765607834 -3.00173163414,1.28975021839,5.38739538193 -3.76954984665,1.66360616684,6.80802822113 -3.75057458878,1.66462004185,6.82261323929 -3.7295999527,1.66463446617,6.83419322968 -2.97581863403,1.30979597569,5.49772500992 -2.95884370804,1.30980968475,5.50729894638 -3.66767668724,1.66667795181,6.87291526794 -3.6656870842,1.67068326473,6.89371347427 -3.64071369171,1.66869854927,6.89829015732 -3.61973953247,1.66871321201,6.91086292267 -3.60076498985,1.67072737217,6.92743444443 -3.5697927475,1.66574370861,6.91902065277 -3.5588157177,1.67075622082,6.95059776306 -3.54882836342,1.6717633009,6.95738840103 -3.52785372734,1.67177760601,6.96797847748 -3.50987911224,1.67379176617,6.98754501343 -3.488904953,1.6738063097,7.00011968613 -3.47092962265,1.67581999302,7.01770305634 -3.44595694542,1.6748354435,7.02227783203 -3.42998099327,1.67684876919,7.04386281967 -3.41499519348,1.67585706711,7.04164505005 -3.39801979065,1.67787063122,7.06123113632 -3.38204455376,1.68088424206,7.08480453491 -3.35507202148,1.67889988422,7.08438444138 -3.33509731293,1.67991411686,7.09797048569 -3.32312059402,1.68492674828,7.12955093384 -3.29514861107,1.68194270134,7.12712860107 -3.28416228294,1.68195033073,7.13390684128 -3.26818656921,1.68596363068,7.15649271011 -3.23721551895,1.68098032475,7.14806461334 -3.21524167061,1.68099486828,7.15764856339 -3.20326519012,1.68700754642,7.19022989273 -3.17229413986,1.68202412128,7.18080615997 -3.1503200531,1.68203866482,7.19039106369 -3.14533209801,1.68604516983,7.21116828918 -3.11835980415,1.68306076527,7.20975017548 -3.08938789368,1.67907679081,7.203332901 -3.07841110229,1.68608915806,7.23891687393 -3.05243897438,1.68410491943,7.24148607254 -3.02946519852,1.68411958218,7.24807596207 -3.0234773159,1.68712604046,7.26586198807 -2.99050664902,1.68114280701,7.24944400787 -2.97653126717,1.68615603447,7.28002023697 -2.96055603027,1.69016969204,7.30559921265 -2.93058538437,1.68618607521,7.29816818237 -2.90861177444,1.68620085716,7.30874824524 -2.88863778114,1.68821513653,7.32432937622 -2.87665081024,1.68722236156,7.32513189316 -2.85867643356,1.69023633003,7.34670877457 -2.83770275116,1.69225084782,7.36028814316 -2.81073045731,1.68926644325,7.35786962509 -2.78575873375,1.68828213215,7.36244010925 -2.77378177643,1.6952944994,7.39803218842 -2.75479745865,1.69030356407,7.38281822205 -2.73682355881,1.69431746006,7.40539360046 -2.7158498764,1.69533193111,7.41897630692 -2.68787837029,1.69234800339,7.41455125809 -2.6679046154,1.69436216354,7.43113231659 -2.64993023872,1.69837617874,7.45371246338 -2.62395834923,1.69639158249,7.45428991318 -2.61297106743,1.69639873505,7.45809078217 -2.59399700165,1.69941282272,7.47866868973 -2.56802582741,1.69842875004,7.48123407364 -2.54305315018,1.69644379616,7.48282146454 -2.52607870102,1.70145750046,7.50940132141 -2.49810743332,1.69847357273,7.50397729874 -2.47513437271,1.69848835468,7.51255846024 -2.46714711189,1.70149505138,7.52735042572 -2.43817567825,1.69651091099,7.51693487167 -2.42020153999,1.70052480698,7.54051923752 -2.40522646904,1.7075381279,7.57509756088 -2.37925481796,1.70555377007,7.57567358017 -2.35528254509,1.70556890965,7.58225107193 -2.33630847931,1.70958280563,7.6038351059 -2.32232308388,1.70859098434,7.60161876678 -2.30234932899,1.7106051445,7.62020301819 -2.27937650681,1.71161985397,7.62878894806 -2.25640416145,1.71263480186,7.63936471939 -2.23243165016,1.71264982224,7.64594364166 -2.20945858955,1.71266460419,7.65453004837 -2.19947218895,1.714671731,7.66531705856 -2.18249773979,1.72068536282,7.69589996338 -2.18451857567,1.74369561672,7.79747247696 -2.17154335976,1.753708601,7.84604930878 -2.14557099342,1.75172376633,7.84464073181 -2.12359809875,1.75373840332,7.86022186279 -2.09662652016,1.75175392628,7.85680532455 -2.08664035797,1.75476133823,7.87158298492 -2.06566691399,1.75677549839,7.88917398453 -2.0346968174,1.75179207325,7.8717508316 -2.00272703171,1.74480867386,7.84932947159 -1.97175657749,1.73882484436,7.82891321182 -1.94378578663,1.73584067822,7.82149076462 -1.93179905415,1.73484790325,7.82229328156 -1.90382838249,1.73186385632,7.814868927 -1.87985658646,1.73287892342,7.82444190979 -1.85488474369,1.73289418221,7.82802200317 -1.83191204071,1.73390889168,7.83860826492 -1.80494046211,1.73092412949,7.83119726181 -1.77796936035,1.72793984413,7.82677364349 -1.76898229122,1.73194670677,7.8425693512 -1.74101173878,1.7279624939,7.83414316177 -1.71703922749,1.72797727585,7.83973121643 -1.69206738472,1.72799241543,7.84231424332 -1.66409635544,1.72400808334,7.82989931107 -1.64012479782,1.72502315044,7.84047031403 -1.61515271664,1.72403812408,7.84105825424 -1.60216724873,1.7240459919,7.84184265137 -1.57519602776,1.72106134892,7.8334274292 -1.55422270298,1.72407543659,7.85301828384 -1.52725160122,1.72209095955,7.84559869766 -1.50128078461,1.72110652924,7.8461689949 -1.47830820084,1.7221211195,7.856757164 -1.45433580875,1.72313570976,7.86234521866 -1.43735158443,1.71714425087,7.84013223648 -1.41537904739,1.72015869617,7.8587141037 -1.38740849495,1.7161744833,7.8452911377 -1.36543548107,1.71918880939,7.86088228226 -1.33746469021,1.71420443058,7.84546327591 -1.31349289417,1.71521914005,7.85304450989 -1.29950761795,1.71322703362,7.84583282471 -1.27553570271,1.71424198151,7.85341405869 -1.24956464767,1.71225726604,7.8489947319 -1.22559261322,1.71327197552,7.85657691956 -1.20162057877,1.7142868042,7.86316156387 -1.17564940453,1.71230196953,7.85774326324 -1.14967811108,1.71031701565,7.85132694244 -1.13769233227,1.71032452583,7.85611581802 -1.11272001266,1.70933926105,7.85171031952 -1.08574926853,1.70535457134,7.83928871155 -1.06277668476,1.70736885071,7.84988069534 -1.03780519962,1.70638394356,7.85046243668 -1.01283371449,1.70539879799,7.850045681 -1.00184798241,1.70940625668,7.86682605743 -0.974876761436,1.70442152023,7.84841394424 -0.950904607773,1.70543599129,7.85300350189 -0.92593318224,1.70445096493,7.85358381271 -0.899962186813,1.70246613026,7.84616327286 -0.875990211964,1.70348072052,7.85274887085 -0.850018918514,1.70049571991,7.84133434296 -0.839032828808,1.70350301266,7.85612297058 -0.813061773777,1.70051801205,7.8467040062 -0.789089620113,1.70053255558,7.85029506683 -0.763118267059,1.69754743576,7.8368806839 -0.738147497177,1.69856262207,7.84245157242 -0.715174794197,1.70057678223,7.85404729843 -0.688204467297,1.69659233093,7.83661937714 -0.676218748093,1.69759964943,7.84340763092 -0.651247024536,1.69561433792,7.83699655533 -0.626275599003,1.69462919235,7.83457803726 -0.602303206921,1.69464349747,7.83417415619 -0.577332019806,1.6936583519,7.83375358582 -0.552360534668,1.69267296791,7.82933759689 -0.52738904953,1.69068777561,7.82292318344 -0.515402913094,1.69069492817,7.8237195015 -0.490431785583,1.69070971012,7.82329750061 -0.465460181236,1.68772435188,7.81388473511 -0.440489292145,1.68873941898,7.81745815277 -0.416516780853,1.68775343895,7.81205701828 -0.391545623541,1.68676841259,7.80963611603 -0.378560513258,1.68577599525,7.80541944504 -0.354588478804,1.6867903471,7.81000947952 -0.330616295338,1.68680465221,7.81060218811 -0.305645287037,1.68681943417,7.81117916107 -0.280674099922,1.68483412266,7.80675840378 -0.256701976061,1.68584835529,7.80835056305 -0.231730774045,1.68386316299,7.80093097687 -0.219744622707,1.68287014961,7.79772949219 -0.195772722363,1.68588447571,7.80931758881 -0.170801430941,1.68189918995,7.79389953613 -0.145830571651,1.68391394615,7.80147314072 -0.12185819447,1.67992794514,7.78407096863 -0.0968874022365,1.68294286728,7.7976436615 -0.0729151666164,1.67995691299,7.78623867035 -0.0609291121364,1.67996406555,7.78603506088 -0.0359581783414,1.68097877502,7.78961038589 -0.0119860516861,1.6799929142,7.78320360184 --0.00299643562175,1.6880017519,7.55194759369 --0.0269679278135,1.68901622295,7.55352783203 --0.0509394034743,1.68803060055,7.55110836029 --0.0739119797945,1.68604445457,7.53870391846 --0.0978835448623,1.68805873394,7.54828643799 --0.121854744852,1.68307328224,7.52786111832 --0.133840575814,1.68508040905,7.53465270996 --0.156813323498,1.68709421158,7.54025268555 --0.180784553289,1.68410861492,7.52882814407 --0.204755961895,1.68412303925,7.52640676498 --0.228727862239,1.68813705444,7.54299545288 --0.251700222492,1.68615102768,7.53158712387 --0.263685643673,1.68315827847,7.52137136459 --0.28765758872,1.68717241287,7.53596115112 --0.310629725456,1.68418633938,7.5205488205 --0.333602070808,1.68220019341,7.51214075089 --0.358573198318,1.68721461296,7.5317196846 --0.382545053959,1.68922865391,7.53930807114 --0.405516654253,1.68424284458,7.51488447189 --0.417503148317,1.68724954128,7.52968978882 --0.440475404263,1.68626332283,7.5202794075 --0.465446174145,1.68827784061,7.52785158157 --0.488418668509,1.68729162216,7.52344703674 --0.512390553951,1.6893055439,7.52803468704 --0.536361992359,1.6893197298,7.52561426163 --0.561333417892,1.69333386421,7.54120063782 --0.571320056915,1.68734061718,7.51699542999 --0.597291111946,1.69435489178,7.54358005524 --0.621262788773,1.6953690052,7.54316473007 --0.645235240459,1.69838261604,7.55176258087 --0.669206380844,1.6963968277,7.54433727264 --0.694177985191,1.7004109621,7.55692529678 --0.719149708748,1.7044249773,7.56951570511 --0.729136645794,1.7004314661,7.55331707001 --0.756107032299,1.70744609833,7.57689332962 --0.77807945013,1.70245957375,7.55748224258 --0.803051233292,1.70647346973,7.56807231903 --0.828022420406,1.70748770237,7.57265281677 --0.850994825363,1.70750117302,7.56524515152 --0.861980855465,1.70450806618,7.55403518677 --0.886952936649,1.70852172375,7.56663274765 --0.911923825741,1.70953607559,7.56720733643 --0.936895668507,1.71254992485,7.57579898834 --0.959868133068,1.71156334877,7.56839179993 --0.982840120792,1.70957696438,7.55697488785 --1.00981092453,1.71459126472,7.57655954361 --1.01979756355,1.71159780025,7.56135559082 --1.04376971722,1.71261143684,7.56194925308 --1.07074010372,1.71662580967,7.57552337646 --1.09471225739,1.71763944626,7.57511663437 --1.11668491364,1.71465265751,7.55970621109 --1.14165592194,1.71566689014,7.55928230286 --1.16662836075,1.71968019009,7.56888532639 --1.17861390114,1.71868729591,7.56467199326 --1.20258617401,1.71970069408,7.56426620483 --1.22655820847,1.71971428394,7.56085252762 --1.25252938271,1.72272825241,7.56943941116 --1.27450191975,1.72074151039,7.55402708054 --1.30247282982,1.72675561905,7.57461595535 --1.31345844269,1.72376263142,7.56239652634 --1.33643114567,1.72377574444,7.5559926033 --1.3644015789,1.72879004478,7.57257413864 --1.38837361336,1.72880351543,7.56916332245 --1.41234588623,1.7298167944,7.56675624847 --1.43931674957,1.7338309288,7.57734012604 --1.45929038525,1.72884356976,7.554936409 --1.47327589989,1.73185050488,7.56373262405 --1.50024735928,1.73586428165,7.5763258934 --1.52221989632,1.73387742043,7.56091070175 --1.54719090462,1.73489129543,7.55748558044 --1.57416212559,1.73790502548,7.56807518005 --1.59613502026,1.73591804504,7.55466604233 --1.62310647964,1.74093163013,7.56626224518 --1.63609206676,1.74193871021,7.56705093384 --1.65806460381,1.73895168304,7.55263805389 --1.68303668499,1.74096488953,7.55423355103 --1.71200728416,1.74697911739,7.5708193779 --1.7349793911,1.74499225616,7.55940151215 --1.75895154476,1.7450054884,7.55398893356 --1.77693641186,1.75201284885,7.57979393005 --1.79990828037,1.75102615356,7.56737232208 --1.81888246536,1.7470382452,7.54397201538 --1.85085260868,1.75505256653,7.57256555557 --1.86882591248,1.74906504154,7.53914022446 --1.89879631996,1.75507903099,7.55772972107 --1.92276835442,1.75509226322,7.55131578445 --1.93675410748,1.75709915161,7.55711364746 --1.96072661877,1.75711202621,7.55270862579 --1.98769783974,1.76012551785,7.55729389191 --2.00867128372,1.75813794136,7.54189109802 --2.03764152527,1.76215207577,7.55146694183 --2.06161403656,1.76316487789,7.54706382751 --2.08758568764,1.76417827606,7.54765176773 --2.09657263756,1.76218438148,7.53244018555 --2.12454414368,1.76619780064,7.54203653336 --2.15051627159,1.7682107687,7.54463481903 --2.17048978806,1.76522314548,7.52422380447 --2.20245909691,1.77123749256,7.54280185699 --2.22143316269,1.7672495842,7.51939249039 --2.23841810226,1.77225673199,7.53419303894 --2.26239061356,1.77226960659,7.5267791748 --2.28636288643,1.77228236198,7.5203704834 --2.31433391571,1.77629578114,7.52595663071 --2.33930635452,1.77730870247,7.52254724503 --2.36127948761,1.7763210535,7.51014232635 --2.38725161552,1.77833402157,7.50973320007 --2.40423607826,1.78134131432,7.5205206871 --2.42720890045,1.78135383129,7.51111507416 --2.45218157768,1.78236651421,7.50871419907 --2.47915315628,1.78537976742,7.50929737091 --2.50212621689,1.78439211845,7.49989175797 --2.53009700775,1.78740561008,7.50247192383 --2.55506968498,1.78841805458,7.49906778336 --2.56805586815,1.78942453861,7.49886655807 --2.59802651405,1.79443800449,7.50845575333 --2.61899971962,1.79245018959,7.4910402298 --2.64197325706,1.79246234894,7.48264169693 --2.67194366455,1.7964758873,7.49022388458 --2.69591641426,1.79648828506,7.48281669617 --2.70790290833,1.79649460316,7.47861051559 --2.73587417603,1.79950773716,7.48019313812 --2.76184654236,1.8015203476,7.4787902832 --2.78881859779,1.80353319645,7.4793844223 --2.81678986549,1.80654609203,7.48096990585 --2.84176230431,1.80755877495,7.47455644608 --2.86873483658,1.8105713129,7.4761595726 --2.87972092628,1.80957746506,7.46794652939 --2.90869283676,1.81259036064,7.47354459763 --2.92866659164,1.8106020689,7.45413160324 --2.95064043999,1.8096139431,7.44172954559 --2.97861194611,1.81262683868,7.44231510162 --3.00958347321,1.81763982773,7.45291662216 --3.03155636787,1.81665194035,7.43749761581 --3.04754185677,1.81965851784,7.44329547882 --3.072514534,1.81967079639,7.43688678741 --3.09848642349,1.82168340683,7.43146944046 --3.12845826149,1.82569611073,7.43806886673 --3.15143108368,1.82570827007,7.42565441132 --3.17940402031,1.82872056961,7.42826032639 --3.19338965416,1.82972681522,7.42805433273 --3.21836185455,1.83073914051,7.41963672638 --3.24333548546,1.83175110817,7.41423845291 --3.27130723,1.83376383781,7.41282272339 --3.29827952385,1.83677613735,7.41041612625 --3.32325220108,1.83778810501,7.40300703049 --3.35022449493,1.83980059624,7.39959526062 --3.35721230507,1.83680582047,7.38338899612 --3.38918352127,1.8418186903,7.39198493958 --3.41515612602,1.84283077717,7.38657665253 --3.43513083458,1.84184193611,7.36917543411 --3.46210336685,1.84385406971,7.36576652527 --3.49807310104,1.85086762905,7.3803524971 --3.51804757118,1.84887874126,7.36194467545 --3.52603554726,1.84688401222,7.34974813461 --3.55900645256,1.85289680958,7.35833978653 --3.58098053932,1.85190832615,7.34393072128 --3.60395407677,1.85191977024,7.33152103424 --3.63192605972,1.85393202305,7.32911062241 --3.66289782524,1.85794448853,7.33270168304 --3.66888642311,1.85494947433,7.31650400162 --3.69086027145,1.85496079922,7.30209541321 --3.72683024406,1.86197388172,7.31468248367 --3.74680519104,1.85998475552,7.29728126526 --3.76977920532,1.8599960804,7.28487348557 --3.80075120926,1.86400830746,7.28847026825 --3.83272242546,1.86902081966,7.29306268692 --3.83271241188,1.86302495003,7.26485872269 --3.86968255043,1.87003815174,7.27844905853 --3.8886578083,1.86804878712,7.2590470314 --3.91862940788,1.87106096745,7.25762653351 --3.94560313225,1.87407243252,7.25423336029 --3.95957899094,1.86908257008,7.22381734848 --3.99854850769,1.87709569931,7.2404127121 --4.0045375824,1.87510037422,7.22521734238 --4.03251075745,1.87711215019,7.22080612183 --4.05848360062,1.87812376022,7.21239185333 --4.08545732498,1.88113498688,7.20799636841 --4.10943031311,1.88114631176,7.19558000565 --4.13540363312,1.8831577301,7.18817567825 --4.150390625,1.88416349888,7.18797445297 --4.17836380005,1.88717484474,7.18457555771 --4.20333719254,1.88818621635,7.17416381836 --4.23330926895,1.89119791985,7.17275619507 --4.2592830658,1.89320898056,7.16535615921 --4.28725576401,1.89622056484,7.15994596481 --4.30423164368,1.89323067665,7.1355304718 --4.31921815872,1.89523637295,7.13533210754 --4.3501906395,1.89824819565,7.13492441177 --4.37016630173,1.89725828171,7.11752605438 --4.39513969421,1.8982694149,7.10610961914 --4.4321103096,1.90528166294,7.11570835114 --4.45208644867,1.904291749,7.09830999374 --4.48205900192,1.90730333328,7.09489679337 --4.49604558945,1.90930879116,7.0926990509 --4.52501916885,1.9113202095,7.08829259872 --4.55699062347,1.91633176804,7.08788156509 --4.59096288681,1.92134356499,7.09147977829 --4.60693979263,1.91835308075,7.06707715988 --4.62891435623,1.91836333275,7.05167150497 --4.6558880806,1.92037427425,7.04326200485 --4.65887784958,1.91637861729,7.02305603027 --4.66985607147,1.91138756275,6.99165391922 --4.6898317337,1.9103975296,6.97324800491 --4.69781064987,1.90440607071,6.93683815002 --4.71078777313,1.90041542053,6.90742349625 --4.75075817108,1.90842759609,6.91902208328 --4.74874925613,1.90343129635,6.89181232452 --4.76672554016,1.90144097805,6.87141084671 --4.80069828033,1.90645229816,6.87401008606 --4.81867408752,1.90446186066,6.85260057449 --4.82265377045,1.89746999741,6.8111872673 --4.86562347412,1.90648245811,6.82578372955 --4.88360023499,1.90449178219,6.8053817749 --4.89758729935,1.90649712086,6.80218076706 --4.92556190491,1.90950751305,6.79578018188 --4.94553756714,1.9085174799,6.77636241913 --4.97151231766,1.91052770615,6.76696109772 --5.00048589706,1.91353821754,6.76155996323 --5.01646280289,1.91054737568,6.73815584183 --5.03643894196,1.91055703163,6.71974658966 --5.06942129135,1.91956424713,6.74154615402 --5.08239936829,1.91657304764,6.71414136887 --5.10237550735,1.91558229923,6.69674301147 --5.1453461647,1.9245942831,6.70833587646 --5.14832639694,1.91760194302,6.66792869568 --5.17929983139,1.92061257362,6.66351985931 --5.21827173233,1.92762374878,6.67011976242 --5.22426128387,1.92562806606,6.65591812134 --5.24123859406,1.92463707924,6.63451910019 --5.2772102356,1.93064808846,6.63510227203 --5.28418970108,1.92465627193,6.59968900681 --5.30616569519,1.92466568947,6.58428764343 --5.34213924408,1.93167626858,6.5868935585 --5.34212970734,1.92667996883,6.56468391418 --5.37010478973,1.92968976498,6.55728960037 --5.38708209991,1.92869865894,6.53488063812 --5.40006017685,1.9247071743,6.50746917725 --5.43503332138,1.93071758747,6.50807237625 --5.46700716019,1.93472790718,6.50366449356 --5.47498655319,1.93073558807,6.47126102448 --5.48197555542,1.92873990536,6.45805358887 --5.48395633698,1.92174744606,6.41763830185 --5.49793481827,1.91975581646,6.39223098755 --5.5239109993,1.92176520824,6.38183355331 --5.52389240265,1.9147721529,6.3404250145 --5.55086755753,1.91678190231,6.33001661301 --5.57084465027,1.91679060459,6.31261825562 --5.57883310318,1.91579496861,6.30040645599 --5.57381677628,1.90680134296,6.25500822067 --5.55080366135,1.89080631733,6.18758583069 --5.60477256775,1.9038182497,6.20818662643 --5.5957570076,1.8938242197,6.15878486633 --5.62573194504,1.89783382416,6.15238285065 --5.64870786667,1.89784288406,6.136967659 --5.65569734573,1.89784693718,6.12476444244 --5.67067575455,1.89585506916,6.10236644745 --5.69365167618,1.8968641758,6.08695173264 --5.71362924576,1.89787268639,6.06955003738 --5.73460674286,1.89788126945,6.05314826965 --5.76158237457,1.90089035034,6.04274320602 --5.77556180954,1.8988982439,6.01934528351 --5.78655004501,1.89890265465,6.01113939285 --5.81352567673,1.90191173553,6.00073623657 --5.83950233459,1.90392053127,5.98933506012 --5.87847518921,1.91093051434,5.99093198776 --5.90345144272,1.91293919086,5.97853326797 --5.95042324066,1.92294967175,5.98813486099 --5.96041202545,1.92295372486,5.978931427 --5.98638820648,1.92496263981,5.96652555466 --6.00536632538,1.92497074604,5.94712018967 --6.0173459053,1.92297828197,5.92071294785 --6.04432249069,1.92598676682,5.91032028198 --6.06230020523,1.92499494553,5.88890361786 --6.01029443741,1.90199756622,5.7994799614 --5.7523431778,1.81198096275,5.52720975876 --5.63335132599,1.76597869396,5.37476444244 --5.98525619507,1.8780118227,5.68245649338 --6.10721111298,1.91202771664,5.76307535172 --6.13818740845,1.91703641415,5.75567626953 --5.64127826691,1.74600625038,5.24412584305 --5.56727743149,1.71600747108,5.14070463181 --5.57626628876,1.71601176262,5.13149023056 --5.57224988937,1.71001803875,5.0950884819 --5.59322690964,1.71102631092,5.08067464828 --5.5832118988,1.70303225517,5.03927326202 --5.61918640137,1.70904135704,5.03987789154 --5.66115999222,1.71705091,5.04548072815 --5.70613241196,1.72706079483,5.05307912827 --5.71312189102,1.72606468201,5.04287624359 --5.73509979248,1.72807276249,5.02946949005 --5.76007699966,1.73108100891,5.01906871796 --5.79905128479,1.73809027672,5.02066707611 --5.83002710342,1.74309885502,5.01526784897 --5.85900354385,1.74710714817,5.00786685944 --5.88797998428,1.75211548805,5.00046777725 --5.92096471786,1.75912082195,5.01327943802 --5.95493984222,1.76512956619,5.00886869431 --5.97691869736,1.76713728905,4.99547433853 --6.03588867188,1.78014743328,5.0120716095 --6.04986858368,1.78015446663,4.99167585373 --6.46776437759,1.90618693829,5.31037902832 --6.53973293304,1.92319726944,5.33599424362 --6.56371927261,1.92820191383,5.33779001236 --6.57769966125,1.92720866203,5.31438827515 --6.59567975998,1.92721557617,5.29499530792 --6.60966014862,1.92622220516,5.27159309387 --6.62663984299,1.92622923851,5.25018644333 --6.64661884308,1.9272364378,5.23077535629 --6.66060829163,1.92923998833,5.2255859375 --6.66958999634,1.92724633217,5.19818210602 --6.68356990814,1.92625296116,5.17376708984 --6.70654916763,1.92826008797,5.15736532211 --6.72252941132,1.92826664448,5.13596773148 --6.74250888824,1.92927360535,5.11655807495 --6.75448989868,1.9272800684,5.0911488533 --6.76048088074,1.92728304863,5.07996225357 --6.78745937347,1.93029022217,5.06656265259 --6.81843662262,1.93429756165,5.0551533699 --5.53567123413,1.54423689842,4.04834508896 --5.54265260696,1.5422437191,4.02593708038 --5.5816283226,1.55025219917,4.02754068375 --5.59760808945,1.55125916004,4.01214122772 --6.86835384369,1.92832517624,4.94033813477 --6.90133142471,1.93333232403,4.93094015121 --6.91931152344,1.93333888054,4.90952682495 --6.93929195404,1.93534529209,4.89113330841 --6.95527219772,1.93535161018,4.86872577667 --6.96925401688,1.93435764313,4.84532260895 --6.98923397064,1.93636405468,4.82591772079 --7.00222396851,1.93736732006,4.8187212944 --7.01320505142,1.9363732338,4.79230690002 --7.03118610382,1.93737947941,4.77190732956 --7.04216861725,1.9353852272,4.74650526047 --7.06214904785,1.93739140034,4.72710180283 --7.06413269043,1.93339669704,4.69569826126 --7.0891122818,1.93640315533,4.67929172516 --7.10610103607,1.93940639496,4.67510175705 --7.11808300018,1.93841218948,4.64969015121 --7.13406515121,1.93841791153,4.62829637527 --7.15704488754,1.94042408466,4.61089658737 --7.1480307579,1.93342888355,4.57147693634 --7.08502626419,1.9114317894,4.49704313278 --6.95204305649,1.87142932415,4.39480829239 --6.88803863525,1.84943223,4.32137584686 --6.87902450562,1.8424372673,4.28395748138 --6.888007164,1.84144282341,4.25956201553 --6.91198682785,1.84344911575,4.24315071106 --6.92696905136,1.84445464611,4.2227602005 --6.94894933701,1.84646070004,4.2053527832 --6.97993612289,1.85346436501,4.20915651321 --7.00191736221,1.85647010803,4.1927652359 --6.99890184402,1.85147535801,4.15934610367 --7.02088212967,1.85348117352,4.14194297791 --7.02786540985,1.85148644447,4.1155371666 --7.04084825516,1.8514919281,4.09313774109 --7.05583095551,1.85249733925,4.07173538208 --7.05182361603,1.84949958324,4.05453634262 --7.07180500031,1.85150527954,4.03613615036 --7.07978820801,1.8495105505,4.00972080231 --7.09777021408,1.85151600838,3.99032354355 --7.10975265503,1.85052132607,3.96691823006 --7.10573816299,1.84652614594,3.9345099926 --7.11272192001,1.84453117847,3.90809965134 --7.13071155548,1.84853410721,3.90390896797 --7.16069173813,1.85253965855,3.89050626755 --7.16467571259,1.85054457188,3.86310482025 --7.17365932465,1.84954965115,3.83769345284 --7.19464111328,1.85155510902,3.81929063797 --7.20062541962,1.84955990314,3.79288721085 --7.19761037827,1.84556460381,3.76147842407 --7.22559928894,1.85156750679,3.76229023933 --7.22558450699,1.84857213497,3.73288679123 --7.24956560135,1.85157740116,3.71547889709 --7.27554702759,1.85558247566,3.70008587837 --7.2755317688,1.85258722305,3.66966748238 --7.28951454163,1.85259211063,3.64726209641 --7.32049560547,1.85759711266,3.63386535645 --7.31248998642,1.85459923744,3.61566829681 --7.33147192001,1.85660421848,3.59525752068 --7.3514547348,1.85860896111,3.57686901093 --7.35743951797,1.85661351681,3.55046319962 --7.34842586517,1.85161805153,3.51604485512 --7.37440776825,1.8556227684,3.49964475632 --7.37439346313,1.85262703896,3.47124886513 --7.39838266373,1.85662961006,3.46804785728 --7.42336463928,1.86063432693,3.45064353943 --7.41135215759,1.8546384573,3.41624045372 --7.42133617401,1.85464286804,3.39183473587 --7.4413189888,1.85664761066,3.37142133713 --7.46030235291,1.85865199566,3.35203003883 --7.46828746796,1.85765624046,3.32662343979 --7.48427772522,1.86065852642,3.31942272186 --7.47226524353,1.85466265678,3.28501272202 --7.49824810028,1.85866701603,3.26862192154 --7.51823091507,1.86167132854,3.24821257591 --7.50921869278,1.85667550564,3.21580910683 --7.52520179749,1.85767972469,3.19339561462 --7.53719377518,1.85968160629,3.18520832062 --7.55117797852,1.86068582535,3.16280794144 --7.5691614151,1.86268997192,3.14139866829 --7.58514547348,1.86369395256,3.12000203133 --7.55713558197,1.85369825363,3.07857489586 --7.5821185112,1.85770201683,3.06118273735 --7.60210227966,1.86070609093,3.04077768326 --7.59909582138,1.85770797729,3.02557778358 --7.58908367157,1.85271203518,2.99317002296 --7.61706590652,1.85771584511,2.97576379776 --7.63505077362,1.85971951485,2.95537185669 --7.64303588867,1.85972344875,2.92996358871 --7.6530213356,1.85972726345,2.90555858612 --7.6680059433,1.86073100567,2.88315582275 --7.68499708176,1.86373269558,2.87596106529 --7.6909828186,1.86373651028,2.84954953194 --7.70096874237,1.86374020576,2.82514548302 --7.73495149612,1.86974346638,2.8107612133 --7.74093723297,1.86874711514,2.7843503952 --7.75192308426,1.86975073814,2.75994253159 --7.78290605545,1.87475395203,2.74354958534 --7.78889894485,1.87575554848,2.73235845566 --7.78888607025,1.87275910378,2.70394921303 --7.79287242889,1.87176275253,2.67653369904 --7.81385707855,1.87476599216,2.65613603592 --7.8228430748,1.87476933002,2.63173985481 --7.84082841873,1.87777245045,2.60932946205 --7.86281299591,1.88077557087,2.58893036842 --7.86280727386,1.87977719307,2.57573962212 --7.87479257584,1.88078033924,2.55133032799 --7.89977741241,1.88478326797,2.53193449974 --7.89576530457,1.88178670406,2.50252699852 --7.90775108337,1.88278973103,2.47811889648 --7.91273832321,1.88179302216,2.45171332359 --7.91873121262,1.88179457188,2.43950939178 --7.92471837997,1.88179755211,2.41411352158 --7.92670536041,1.87980079651,2.3867058754 --7.92969274521,1.87880396843,2.35929322243 --7.95167827606,1.88280642033,2.33890151978 --7.97066450119,1.88480913639,2.31750965118 --7.97365140915,1.8838121891,2.29009699821 --7.99363803864,1.88681471348,2.26870250702 --8.00563049316,1.88881587982,2.25749015808 --8.01261806488,1.88881874084,2.23209118843 --8.01860427856,1.88882160187,2.20568132401 --8.02559185028,1.88882434368,2.18028211594 --8.03857898712,1.88982689381,2.15688943863 --8.04056739807,1.8888297081,2.12948036194 --8.05655384064,1.89083206654,2.10607647896 --8.03454875946,1.88483440876,2.0858631134 --8.04353713989,1.88483703136,2.0604557991 --8.06352329254,1.8878390789,2.0380525589 --8.06051158905,1.88584196568,2.01066040993 --8.07849884033,1.88884413242,1.9872508049 --8.0944852829,1.89084625244,1.96384966373 --8.10047912598,1.89184749126,1.95164883137 --8.11046695709,1.89184975624,1.92725527287 --8.12045478821,1.89285206795,1.90184676647 --8.12544250488,1.89285457134,1.87544071674 --8.15442848206,1.8988558054,1.85504376888 --8.15641784668,1.89785850048,1.82763373852 --8.16540527344,1.89786064625,1.80223047733 --8.17139911652,1.89886152744,1.79003155231 --8.17038822174,1.89686405659,1.76263058186 --8.20337486267,1.90386509895,1.74222719669 --8.21436214447,1.90486693382,1.71783447266 --8.2263507843,1.90586876869,1.69242441654 --8.22633934021,1.90487122536,1.66502058506 --8.24132728577,1.90687286854,1.6406172514 --8.25232124329,1.90887331963,1.62942075729 --8.25231075287,1.90787577629,1.6020168066 --8.25529956818,1.90687775612,1.57561898232 --8.26828765869,1.9088793993,1.55020833015 --8.26627731323,1.90688169003,1.52280914783 --8.27726554871,1.90888333321,1.49740433693 --8.28825473785,1.90988492966,1.47200036049 --8.29424858093,1.91088557243,1.45980477333 --8.31323719025,1.9138866663,1.43539655209 --8.3312253952,1.91788768768,1.4120067358 --8.33621406555,1.91788947582,1.38459026814 --8.35320281982,1.91989040375,1.36019027233 --8.35319328308,1.91889238358,1.33278608322 --8.36818218231,1.92189335823,1.30839192867 --8.37417602539,1.92289400101,1.2951836586 --8.37516593933,1.92189586163,1.26777720451 --8.37315654755,1.91989791393,1.2403768301 --8.37014579773,1.91889989376,1.21196269989 --8.39813518524,1.92389976978,1.18957424164 --8.39012432098,1.92090237141,1.16015541553 --8.3911151886,1.91990399361,1.13274776936 --8.38111019135,1.91790568829,1.11754143238 --8.40310001373,1.921905756,1.09415316582 --8.41608905792,1.9239064455,1.06875324249 --8.43007850647,1.92590713501,1.0433524847 --8.43006896973,1.92590880394,1.01594662666 --8.44505882263,1.92790925503,0.99054557085 --8.45804977417,1.93090987206,0.965148508549 --8.46204471588,1.93091034889,0.95194709301 --8.4670343399,1.9319113493,0.924533784389 --8.47702503204,1.93291211128,0.898128509521 --8.48001480103,1.93291330338,0.871733903885 --8.49100589752,1.93491387367,0.845327854156 --8.48599624634,1.93291568756,0.816914618015 --8.50898647308,1.93791508675,0.792523384094 --8.51398181915,1.93891525269,0.779321908951 --8.51497268677,1.93791663647,0.751916110516 --8.52396392822,1.93991708755,0.725515186787 --8.5229549408,1.93891835213,0.698111534119 --8.54094409943,1.94191801548,0.671701550484 --8.53593540192,1.93991971016,0.644302427769 --8.53893089294,1.94091999531,0.63008916378 --8.54392242432,1.94092071056,0.603694438934 --8.55591392517,1.94392073154,0.577292919159 --8.5429058075,1.93992292881,0.54787003994 --8.54489707947,1.93992376328,0.521477818489 --8.55288696289,1.94092416763,0.494065910578 --8.55087947845,1.939925313,0.466662049294 --8.56587505341,1.94392430782,0.45447063446 --8.5738658905,1.94492447376,0.427060246468 --8.58685779572,1.94792413712,0.400662124157 --8.58684921265,1.94692492485,0.373257786036 --8.61184024811,1.95292329788,0.346854746342 --8.60383319855,1.95092487335,0.319454908371 --8.6098241806,1.95192492008,0.292048186064 --8.60882091522,1.9509254694,0.277839273214 --8.61581325531,1.95292544365,0.250432431698 --8.62480449677,1.95392525196,0.224040880799 --8.61479663849,1.95192682743,0.195624768734 --8.61378860474,1.95092761517,0.168220877647 --8.61278057098,1.95092833042,0.140816509724 --8.62177276611,1.95292782784,0.113410867751 --8.60876941681,1.94892966747,0.0992027819157 --8.63276100159,1.95492744446,0.0728115439415 --8.63375377655,1.95492780209,0.0443927757442 --8.63174629211,1.95392847061,0.0169889256358 --8.62673854828,1.95292949677,-0.0104156425223 --8.62173080444,1.95193040371,-0.0378207415342 --8.62172317505,1.95193076134,-0.0662403553724 --8.63572025299,1.9549292326,-0.0794321075082 --8.6417131424,1.9559289217,-0.106834433973 --8.66170597076,1.96092677116,-0.134232059121 --8.65469837189,1.9589278698,-0.161637306213 --8.65669155121,1.95992779732,-0.189039826393 --8.65268421173,1.95892846584,-0.217459633946 --8.65967750549,1.96092772484,-0.244859501719 --8.64467334747,1.95692956448,-0.258061230183 --8.65566730499,1.95992827415,-0.286473631859 --8.68066120148,1.96592521667,-0.313861221075 --8.67665481567,1.96492564678,-0.34126573801 --8.67764663696,1.96492552757,-0.369681864977 --8.68364143372,1.96692478657,-0.397079378366 --8.66463375092,1.96192705631,-0.424496233463 --8.67863082886,1.96592521667,-0.438693404198 --8.68762397766,1.96792376041,-0.467102020979 --8.66861724854,1.9639261961,-0.493506193161 --8.66261100769,1.96192669868,-0.520913898945 --8.68060493469,1.96692419052,-0.549312770367 --8.66759872437,1.96392571926,-0.57672804594 --8.66659164429,1.96392548084,-0.605145871639 --8.67558860779,1.96692407131,-0.619344174862 --8.67258262634,1.96592414379,-0.646748900414 --8.6635761261,1.96392500401,-0.674161314964 --8.67557048798,1.96792280674,-0.702562630177 --8.67156505585,1.96692299843,-0.72996878624 --8.67755889893,1.96892166138,-0.75837635994 --8.67855644226,1.96892118454,-0.771567702293 --8.67555046082,1.96892118454,-0.798972606659 --8.69054508209,1.97291827202,-0.828380167484 --8.69054031372,1.9739177227,-0.855779826641 --8.675532341,1.96991920471,-0.883202791214 --8.67452812195,1.9709187746,-0.910604536533 --8.68452262878,1.97391653061,-0.939002215862 --8.6775188446,1.97191727161,-0.953220963478 --8.67851448059,1.97291624546,-0.980618476868 --8.68950939178,1.97591364384,-1.01002717018 --8.65850162506,1.96891784668,-1.03443837166 --8.67149829865,1.97291481495,-1.06384289265 --8.67849349976,1.97491276264,-1.09224259853 --8.67148780823,1.97491288185,-1.11965489388 --8.68748664856,1.97890985012,-1.13585853577 --8.69648170471,1.98190736771,-1.16425204277 --8.6734752655,1.97691011429,-1.18966758251 --8.67847061157,1.97890818119,-1.2190836668 --8.69246768951,1.98290467262,-1.24847900867 --8.67146110535,1.97890710831,-1.27389276028 --8.67645740509,1.980905056,-1.30229258537 --8.6924533844,1.98490107059,-1.33269512653 --8.67144966125,1.98090410233,-1.34390580654 --8.67344474792,1.98190248013,-1.37231135368 --8.68644142151,1.98589885235,-1.40271890163 --8.67743682861,1.98489904404,-1.42912125587 --8.66743183136,1.98289942741,-1.45654118061 --8.68342971802,1.9878950119,-1.48693823814 --8.65642356873,1.98189926147,-1.49715459347 --8.6774225235,1.98789393902,-1.52855181694 --8.69742107391,1.99388873577,-1.55994927883 --8.69141578674,1.99388825893,-1.58735787868 --8.689412117,1.99388694763,-1.61576974392 --8.69640922546,1.99688398838,-1.64517068863 --8.69240570068,1.99688303471,-1.6725730896 --8.67640113831,1.99388515949,-1.68479347229 --8.68539905548,1.9968817234,-1.71418690681 --8.68039512634,1.99688088894,-1.74159240723 --8.68339252472,1.99887835979,-1.77100241184 --8.68038845062,1.99887704849,-1.79941558838 --8.67138385773,1.99787688255,-1.82581877708 --8.67037963867,1.99887514114,-1.85422563553 --8.66937923431,1.99987435341,-1.86843085289 --8.65437316895,1.9968752861,-1.89485371113 --8.66037082672,1.99987208843,-1.92425179482 --8.68037128448,2.00586605072,-1.95664513111 --8.67336750031,2.00586533546,-1.98405563831 --8.65736198425,2.00286626816,-2.00946831703 --8.66536045074,2.00686240196,-2.03987073898 --8.67035961151,2.00886011124,-2.05608201027 --8.67635917664,2.01085662842,-2.08547472954 --8.68335723877,2.01485276222,-2.11587762833 --8.67735385895,2.01485157013,-2.14429736137 --8.680352211,2.01684856415,-2.17369842529 --8.67834949493,2.0178463459,-2.20210313797 --8.67934703827,2.01984381676,-2.23151040077 --8.6733455658,2.01884388924,-2.24471712112 --8.66834259033,2.01884222031,-2.2731320858 --8.65833854675,2.01784157753,-2.29953813553 --8.64733505249,2.01684141159,-2.32594871521 --8.65833473206,2.0218360424,-2.3583574295 --8.66333389282,2.02383232117,-2.38875985146 --8.65933227539,2.02483034134,-2.41716957092 --8.6603307724,2.02582883835,-2.43136239052 --8.66032981873,2.02782583237,-2.46178340912 --8.65732860565,2.02882361412,-2.4901881218 --8.66332817078,2.03181934357,-2.52058267593 --8.66032600403,2.0328168869,-2.55000019073 --8.64932250977,2.03181648254,-2.57640957832 --8.64332103729,2.03281474113,-2.60482597351 --8.63631916046,2.03181481361,-2.61702299118 --8.6413192749,2.03481030464,-2.64843297005 --8.66032123566,2.04180288315,-2.6828212738 --8.65832042694,2.04279994965,-2.71223139763 --8.64131736755,2.04080033302,-2.73765301704 --8.65031814575,2.0447947979,-2.77005410194 --8.63831520081,2.04379439354,-2.79646730423 --8.63831520081,2.04479265213,-2.81167411804 --8.64831733704,2.04978680611,-2.84406781197 --8.63231277466,2.04778695107,-2.86948561668 --8.63331317902,2.04978322983,-2.89989233017 --8.63831424713,2.05277848244,-2.93129253387 --8.6283121109,2.05277705193,-2.9587097168 --8.6283121109,2.05477356911,-2.98911881447 --8.63931465149,2.05876874924,-3.00731062889 --8.63231277466,2.05876660347,-3.03572511673 --8.62731266022,2.0597641468,-3.06412982941 --8.63131427765,2.0637588501,-3.09654378891 --8.6403169632,2.06775259972,-3.12994432449 --8.62931537628,2.06775140762,-3.15635061264 --8.6473197937,2.07274460793,-3.17754173279 --8.63231658936,2.07174444199,-3.20396733284 --8.64132118225,2.07673788071,-3.23736381531 --8.6503238678,2.08073091507,-3.27177190781 --8.6413230896,2.08072924614,-3.29917860031 --8.63132190704,2.08072757721,-3.32659077644 --8.64532661438,2.08671927452,-3.36299538612 --8.64032554626,2.08671832085,-3.37619423866 --8.63632678986,2.08871507645,-3.40560007095 --8.64433002472,2.09270811081,-3.44000601768 --8.63632965088,2.09370565414,-3.46841859818 --8.64033317566,2.0976998806,-3.50183105469 --8.64533615112,2.1006937027,-3.53422307968 --8.63133430481,2.0996928215,-3.56064081192 --8.65334129333,2.1066839695,-3.5848326683 --8.64834308624,2.1086807251,-3.61423826218 --8.63934230804,2.10867834091,-3.64265298843 --8.63934421539,2.11167311668,-3.67506837845 --8.63534641266,2.11366891861,-3.70547986031 --8.62334537506,2.1136674881,-3.73188495636 --8.62434864044,2.11666202545,-3.76429200172 --8.63735389709,2.12065577507,-3.78548717499 --8.62435340881,2.12065410614,-3.81290984154 --8.62335586548,2.12364888191,-3.8443133831 --8.63936424255,2.13063883781,-3.88371801376 --8.62436294556,2.1296377182,-3.90912532806 --8.62036514282,2.13163352013,-3.93953108788 --8.61936855316,2.13362812996,-3.97194337845 --8.61136817932,2.13362789154,-3.9851565361 --8.61737442017,2.13862013817,-4.02056312561 --8.62037754059,2.14161348343,-4.05396127701 --8.61538124084,2.14360928535,-4.08436918259 --8.59237766266,2.14061045647,-4.10779953003 --8.60838794708,2.14859938622,-4.14719009399 --8.58538341522,2.14560079575,-4.16960811615 --8.6113948822,2.1545894146,-4.19779586792 --8.64741134644,2.16657185555,-4.24717950821 --8.67542552948,2.17755627632,-4.29357194901 --8.67943191528,2.18254828453,-4.32998943329 --8.67743587494,2.18454265594,-4.36239290237 --8.63442707062,2.17655038834,-4.37582397461 --8.6164264679,2.17554950714,-4.40124511719 --8.60142421722,2.17355132103,-4.41045236588 --8.58442306519,2.17255043983,-4.43586730957 --8.56242084503,2.16955089569,-4.45929145813 --8.55342292786,2.17054748535,-4.48870420456 --8.51541519165,2.16455364227,-4.5041384697 --8.49341201782,2.16155457497,-4.52655267715 --8.48641586304,2.16355013847,-4.5569653511 --8.46140956879,2.15855526924,-4.56118202209 --8.45241260529,2.160551548,-4.59059667587 --8.43741226196,2.15954971313,-4.61701440811 --8.41140937805,2.15655231476,-4.63743543625 --8.40641307831,2.15854692459,-4.6688451767 --8.38941287994,2.1575460434,-4.69426584244 --8.35940742493,2.15354967117,-4.71269273758 --8.34740638733,2.15255022049,-4.7228975296 --8.34541225433,2.15554380417,-4.75631046295 --8.31540679932,2.15154743195,-4.77473974228 --8.28940296173,2.14754986763,-4.79516601562 --8.27840518951,2.14854669571,-4.82257032394 --8.26140594482,2.1475455761,-4.84799337387 --8.24540138245,2.14554786682,-4.85620546341 --8.23740577698,2.14754343033,-4.88662433624 --8.19739627838,2.14055109024,-4.89804840088 --8.20040512085,2.14554238319,-4.9344587326 --8.17640209198,2.14254403114,-4.95487499237 --8.1574010849,2.1415438652,-4.9782910347 --8.11138916016,2.13355398178,-4.98673152924 --8.12439823151,2.13854503632,-5.01193189621 --8.08138751984,2.1305539608,-5.02136421204 --8.06138515472,2.12955403328,-5.04377937317 --8.04638767242,2.12955212593,-5.07020425797 --8.02738666534,2.12855195999,-5.09362459183 --7.99738121033,2.12455606461,-5.11004686356 --8.0003900528,2.12954688072,-5.14645147324 --7.97638320923,2.12455272675,-5.14967346191 --7.94137525558,2.11955857277,-5.1631026268 --7.92937755585,2.11955571175,-5.1905169487 --7.91037750244,2.11955523491,-5.21394062042 --7.87436914444,2.11356186867,-5.22636938095 --7.86937475204,2.11655592918,-5.25777626038 --7.83236551285,2.1105632782,-5.26920461655 --7.83537149429,2.11355781555,-5.28941583633 --7.81036806107,2.11056041718,-5.30783128738 --7.79937124252,2.11255645752,-5.33625030518 --7.76036119461,2.10556459427,-5.34668779373 --7.75036525726,2.10756063461,-5.37509965897 --7.72536182404,2.10456299782,-5.3935174942 --7.70536088943,2.10356283188,-5.41594219208 --7.69135856628,2.10156488419,-5.4241528511 --7.66335344315,2.09856820107,-5.44158697128 --7.6453537941,2.09856748581,-5.46500825882 --7.63135623932,2.09856534004,-5.49041843414 --7.60034942627,2.09457039833,-5.50484609604 --7.57934761047,2.09257102013,-5.52525854111 --7.56434965134,2.09356880188,-5.55067873001 --7.53834056854,2.08857607841,-5.55090379715 --7.5243434906,2.08957338333,-5.57732725143 --7.50534248352,2.08857345581,-5.59873628616 --7.48134040833,2.08657503128,-5.6191778183 --7.4683432579,2.08757257462,-5.64458084106 --7.43233346939,2.08157992363,-5.65501499176 --7.41233253479,2.08057999611,-5.67643499374 --7.40033149719,2.07958078384,-5.68665742874 --7.39433908463,2.08357453346,-5.71806716919 --7.35832881927,2.07758235931,-5.72749423981 --7.34833431244,2.07957792282,-5.75590515137 --7.31332445145,2.07458543777,-5.76633834839 --7.30232954025,2.07658100128,-5.79475784302 --7.25831508636,2.06859278679,-5.7981967926 --7.2683262825,2.07358312607,-5.82439947128 --7.21830844879,2.06459784508,-5.82284021378 --7.22432279587,2.07158565521,-5.86323881149 --7.20232057571,2.06958699226,-5.8826584816 --7.17231464386,2.06559205055,-5.89608669281 --7.15031242371,2.06459331512,-5.9155087471 --7.12831068039,2.06359434128,-5.93493080139 --7.11330795288,2.06159710884,-5.94215202332 --7.08930444717,2.05959916115,-5.95957231522 --7.07831001282,2.06159496307,-5.98799133301 --7.04730272293,2.0576004982,-6.0004234314 --7.02430009842,2.05660247803,-6.01884698868 --7.01230478287,2.05759859085,-6.04626369476 --6.99029684067,2.05360484123,-6.04647779465 --6.96729469299,2.05260682106,-6.06490325928 --6.95630025864,2.05460238457,-6.09332132339 --6.93429899216,2.05360341072,-6.11274814606 --6.89928817749,2.04861164093,-6.12118291855 --6.89930105209,2.05360150337,-6.157579422 --6.84627914429,2.04361891747,-6.1510310173 --6.84429073334,2.048609972,-6.18643569946 --6.8332901001,2.0476102829,-6.19665575027 --6.80328273773,2.04361605644,-6.20807743073 --6.78928661346,2.04561328888,-6.23349285126 --6.76828622818,2.04461336136,-6.25493431091 --6.74828577042,2.04461359978,-6.27535581589 --6.71327543259,2.03962230682,-6.28278970718 --6.70827865601,2.04061961174,-6.29699277878 --6.68127346039,2.03762388229,-6.31041145325 --6.64726352692,2.03363180161,-6.3188495636 --6.65628433228,2.04261612892,-6.36525201797 --6.6182718277,2.03662633896,-6.36968994141 --6.58926439285,2.03263187408,-6.38111114502 --6.58727788925,2.03862190247,-6.41852807999 --6.56626987457,2.03462791443,-6.41874837875 --6.547270298,2.03462791443,-6.4391617775 --6.53227472305,2.03662514687,-6.46458625793 --6.49225950241,2.02963662148,-6.46703195572 --6.47426176071,2.0296356678,-6.48945665359 --6.47327613831,2.03662514687,-6.52685785294 --6.44126701355,2.03163218498,-6.53629493713 --6.42426156998,2.02963638306,-6.53950977325 --6.41326856613,2.03263139725,-6.56792163849 --6.38526296616,2.02963638306,-6.58034992218 --6.37627220154,2.03362965584,-6.61177062988 --6.34826612473,2.03063464165,-6.62419939041 --6.32826662064,2.03063488007,-6.64462471008 --6.30026054382,2.02763962746,-6.65705537796 --6.29426431656,2.02963733673,-6.67126607895 --6.28227138519,2.03163266182,-6.69968557358 --6.24926137924,2.02764081955,-6.70611143112 --6.23426580429,2.02963781357,-6.73153352737 --6.20625925064,2.0266430378,-6.74295711517 --6.18726110458,2.02664256096,-6.76438236237 --6.16526031494,2.02664375305,-6.78281116486 --6.14324998856,2.02265167236,-6.78002786636 --6.1372628212,2.02764248848,-6.81544876099 --6.10925674438,2.02464771271,-6.82687473297 --6.07924890518,2.02165436745,-6.83630514145 --6.07226085663,2.02564620972,-6.86971473694 --6.04425477982,2.02365112305,-6.88215303421 --6.01323699951,2.01566505432,-6.86937761307 --6.00524806976,2.02065706253,-6.90279769897 --5.98725128174,2.02165555954,-6.92522192001 --5.95524120331,2.01766395569,-6.93165016174 --5.94024753571,2.01966047287,-6.95807933807 --5.91724491119,2.01866292953,-6.97349309921 --5.89124011993,2.01666688919,-6.9869222641 --5.87624645233,2.01966333389,-7.01335096359 --5.85823917389,2.01666903496,-7.01356124878 --5.83924198151,2.01766777039,-7.03599691391 --5.81123495102,2.01467370987,-7.04541301727 --5.78623151779,2.01367735863,-7.05984306335 --5.76823472977,2.0146753788,-7.08327674866 --5.74222993851,2.01268005371,-7.09569978714 --5.73423290253,2.01367855072,-7.10790967941 --5.70922899246,2.0126824379,-7.12133169174 --5.68622779846,2.01168394089,-7.13876771927 --5.66622924805,2.01268434525,-7.15818738937 --5.63922405243,2.01068878174,-7.17062473297 --5.61321926117,2.00869345665,-7.18305063248 --5.59422111511,2.00969290733,-7.20346784592 --5.59323167801,2.0136859417,-7.2246761322 --5.56022024155,2.00969552994,-7.2291135788 --5.54222345352,2.01069378853,-7.25153636932 --5.51021337509,2.00670218468,-7.25798225403 --5.48020410538,2.00371003151,-7.26440525055 --5.4702167511,2.00870203972,-7.29783153534 --5.44020748138,2.00470972061,-7.3042550087 --5.43121004105,2.00570869446,-7.31647586823 --5.39919805527,2.00171804428,-7.31989860535 --5.37919998169,2.00271773338,-7.34032821655 --5.35920238495,2.00371742249,-7.36075782776 --5.32919311523,2.00072526932,-7.36718559265 --5.30018472672,1.99773240089,-7.37461137772 --5.28819608688,2.00172567368,-7.40603923798 --5.28019952774,2.00272369385,-7.41925525665 --5.24918889999,1.99973261356,-7.42368125916 --5.23219490051,2.00172972679,-7.44810724258 --5.20218515396,1.99873769283,-7.45453929901 --5.18318843842,1.99973666668,-7.4759645462 --5.16419267654,2.00173544884,-7.4973897934 --5.14318084717,1.99774384499,-7.49362182617 --5.12017917633,1.99674665928,-7.50803661346 --5.10218429565,1.99874448776,-7.53146600723 --5.08519029617,2.00174188614,-7.55488204956 --5.05117607117,1.99675309658,-7.55632638931 --5.0291762352,1.99675428867,-7.57375526428 --5.01017999649,1.99875307083,-7.59517908096 --4.99617624283,1.99775636196,-7.59939432144 --4.97417736053,1.99775719643,-7.61783027649 --4.95718336105,2.0007545948,-7.64124488831 --4.92416954041,1.99576544762,-7.64268112183 --4.89916658401,1.9957691431,-7.65611600876 --4.87516403198,1.99477267265,-7.66953754425 --4.84915924072,1.99377739429,-7.68096971512 --4.83715820312,1.99377894402,-7.68818473816 --4.81115341187,1.99178373814,-7.69961643219 --4.78514957428,1.99078810215,-7.71205759048 --4.75814247131,1.98879444599,-7.72048044205 --4.73814582825,1.9907938242,-7.7409081459 --4.71013879776,1.98880052567,-7.74934434891 --4.69014215469,1.98979985714,-7.76977109909 --4.6731338501,1.98780608177,-7.76899003983 --4.652135849,1.98880660534,-7.78741407394 --4.62513017654,1.98781216145,-7.7978553772 --4.60513305664,1.98881196976,-7.81727361679 --4.56911420822,1.98282623291,-7.81271791458 --4.55813026428,1.98881721497,-7.84713315964 --4.53312778473,1.98882091045,-7.86057186127 --4.52513122559,1.98981904984,-7.87277317047 --4.49211645126,1.98583090305,-7.87221193314 --4.47512578964,1.98882687092,-7.89864253998 --4.45012235641,1.98883104324,-7.91107416153 --4.42311573029,1.98683738708,-7.9195022583 --4.40011453629,1.98683965206,-7.93492937088 --4.38512659073,1.9908336401,-7.96435308456 --4.36611509323,1.98784220219,-7.95957517624 --4.34211397171,1.98784518242,-7.97400856018 --4.31110191345,1.98485517502,-7.97644901276 --4.29511213303,1.98885035515,-8.0038690567 --4.26910734177,1.98785555363,-8.01430130005 --4.24310255051,1.98686087132,-8.02473258972 --4.22409105301,1.98286950588,-8.01995849609 --4.20509672165,1.98586750031,-8.0423822403 --4.17809009552,1.98387396336,-8.0508146286 --4.15108394623,1.98288023472,-8.05924701691 --4.13409328461,1.98687601089,-8.08567047119 --4.09907436371,1.98189091682,-8.08011627197 --4.08308649063,1.98588490486,-8.10954475403 --4.06707811356,1.98289144039,-8.10775470734 --4.04407835007,1.98389327526,-8.12418937683 --4.0170712471,1.98290002346,-8.13161754608 --3.99908065796,1.98589634895,-8.15704345703 --3.96706557274,1.98190832138,-8.15648651123 --3.94106030464,1.98191392422,-8.16591644287 --3.91505599022,1.98091924191,-8.17635250092 --3.9060614109,1.98291671276,-8.190574646 --3.8750462532,1.97892868519,-8.1890001297 --3.86006116867,1.98392140865,-8.22042179108 --3.82604265213,1.97993564606,-8.21587181091 --3.80905461311,1.98393034935,-8.24429988861 --3.78405046463,1.9829351902,-8.25472164154 --3.75203514099,1.9799476862,-8.25316619873 --3.74103665352,1.98094797134,-8.26238250732 --3.7260518074,1.9859405756,-8.29379844666 --3.68501830101,1.97696459293,-8.27224445343 --3.67003464699,1.98195636272,-8.30567169189 --3.64603352547,1.9829595089,-8.31910037994 --3.62103104591,1.98296368122,-8.33153533936 --3.58901453018,1.97897660732,-8.32897853851 --3.59104299545,1.98795986176,-8.36718654633 --3.54199123383,1.97399556637,-8.32563495636 --3.5290119648,1.98098468781,-8.36305236816 --3.50401043892,1.98098826408,-8.37649536133 --3.4800093174,1.98199164867,-8.3899230957 --3.44999599457,1.97900271416,-8.39035987854 --3.43000459671,1.98199975491,-8.41479492188 --3.40497589111,1.97501921654,-8.39101696014 --3.37897109985,1.97402501106,-8.40045166016 --3.36799931526,1.98300969601,-8.44587898254 --3.32595920563,1.97303771973,-8.41732501984 --3.2979490757,1.97104692459,-8.42075443268 --3.28697776794,1.98003149033,-8.46617603302 --3.26996564865,1.97704052925,-8.46039199829 --3.23794698715,1.97305488586,-8.45483112335 --3.21394681931,1.97405791283,-8.46926498413 --3.17791938782,1.9670778513,-8.45471382141 --3.15592241287,1.96907866001,-8.4721364975 --3.13192224503,1.97008144855,-8.48657131195 --3.09990429878,1.96609580517,-8.48201942444 --3.07991218567,1.96909368038,-8.50443935394 --3.06089687347,1.96610474586,-8.49567317963 --3.02987885475,1.96211850643,-8.4911108017 --3.00888490677,1.96511769295,-8.51153373718 --2.97987246513,1.96212816238,-8.5129737854 --2.94985771179,1.96014046669,-8.51141548157 --2.92786169052,1.96214079857,-8.52984142303 --2.91485977173,1.96214354038,-8.53506374359 --2.88384103775,1.9581580162,-8.52950000763 --2.86184597015,1.96115791798,-8.54893112183 --2.83483934402,1.9601650238,-8.55637454987 --2.8008108139,1.95418584347,-8.53980541229 --2.76979184151,1.95020031929,-8.53424739838 --2.7578253746,1.96018278599,-8.58367443085 --2.73980760574,1.95619523525,-8.57188892365 --2.7077870369,1.95221102238,-8.56433773041 --2.68779754639,1.95620751381,-8.58976554871 --2.65577363968,1.95122528076,-8.57819652557 --2.6317756176,1.95322728157,-8.59464073181 --2.6017563343,1.94924211502,-8.58806800842 --2.5687315464,1.94426047802,-8.5765209198 --2.56475567818,1.95124733448,-8.60873126984 --2.5357401371,1.94825994968,-8.60616397858 --2.50471878052,1.94427621365,-8.59760189056 --2.4827272892,1.94727408886,-8.62104606628 --2.46073293686,1.95027387142,-8.64047145844 --2.42670273781,1.94429564476,-8.62291812897 --2.40270423889,1.9462980032,-8.6383562088 --2.38970088959,1.94630169868,-8.6415719986 --2.36168861389,1.94431221485,-8.64301109314 --2.33768868446,1.94531548023,-8.65643978119 --2.312687397,1.94731974602,-8.66888046265 --2.28266763687,1.94333481789,-8.66231822968 --2.26167821884,1.94733178616,-8.68674659729 --2.23868298531,1.95033240318,-8.70517921448 --2.2186563015,1.94435024261,-8.68440532684 --2.19265031815,1.94435727596,-8.69184017181 --2.16965675354,1.94735682011,-8.71228122711 --2.14063835144,1.94437122345,-8.70671081543 --2.11664295197,1.9473720789,-8.72515869141 --2.09264230728,1.94837594032,-8.73758125305 --2.06262159348,1.94439172745,-8.73002052307 --2.05263066292,1.94738793373,-8.74623775482 --2.02863550186,1.95038890839,-8.76468276978 --2.00062036514,1.94840145111,-8.76211166382 --1.96959471703,1.94342017174,-8.74955177307 --1.9476082325,1.94841587543,-8.77699661255 --1.91557633877,1.94243836403,-8.7574300766 --1.89459300041,1.94843220711,-8.78786754608 --1.88058650494,1.94743776321,-8.78808879852 --1.8505641222,1.94345474243,-8.7785282135 --1.82556152344,1.94446003437,-8.7889585495 --1.80056011677,1.94646465778,-8.8003911972 --1.76953244209,1.94048452377,-8.78583240509 --1.74352943897,1.94149017334,-8.79627895355 --1.72952330112,1.94149577618,-8.79650211334 --1.69949960709,1.93751335144,-8.78594493866 --1.67750930786,1.9415115118,-8.80836391449 --1.64748847485,1.93852758408,-8.8008184433 --1.61746203899,1.93354678154,-8.78725528717 --1.59246230125,1.93555045128,-8.80069446564 --1.56545257568,1.93455994129,-8.80413532257 --1.55244851112,1.93456435204,-8.80634975433 --1.5244320631,1.93257784843,-8.80278778076 --1.49440646172,1.928596735,-8.79023170471 --1.47141420841,1.93259608746,-8.81065940857 --1.44037973881,1.92561995983,-8.78909683228 --1.4143768549,1.9266256094,-8.79954433441 --1.3893764019,1.92862987518,-8.8119802475 --1.37234818935,1.92264807224,-8.79019546509 --1.34835481644,1.92664837837,-8.80963420868 --1.32033538818,1.92366349697,-8.80306911469 --1.25617182255,1.88776361942,-8.65975093842 --1.23720633984,1.89774763584,-8.70718002319 --1.20515668392,1.8877800703,-8.67061710358 --1.19114637375,1.8867880106,-8.66683959961 --1.16412973404,1.88480162621,-8.66327571869 --1.13812112808,1.8848105669,-8.66771602631 --1.11110651493,1.88382303715,-8.66615867615 --1.08711278439,1.88682353497,-8.68559741974 --1.05707216263,1.87985086441,-8.65803527832 --1.03106343746,1.87985992432,-8.66247653961 --1.01805615425,1.87886595726,-8.6616897583 --0.993052959442,1.88087201118,-8.67112445831 --0.965033948421,1.87888717651,-8.66557979584 --0.938014149666,1.87590253353,-8.65901565552 --0.910994529724,1.87391769886,-8.65245342255 --0.884984970093,1.87392735481,-8.65589332581 --0.861997127533,1.87892472744,-8.68032169342 --0.845965087414,1.87194478512,-8.65554428101 --0.818943560123,1.86996126175,-8.64698123932 --0.792934894562,1.86997044086,-8.65142440796 --0.766930341721,1.87197756767,-8.65987491608 --0.740910887718,1.86899256706,-8.65329933167 --0.714900314808,1.86900281906,-8.65573978424 --0.701902925968,1.87100374699,-8.66497135162 --0.675887584686,1.87001669407,-8.66240406036 --0.64885866642,1.86503708363,-8.64683532715 --0.622850179672,1.86604630947,-8.65127944946 --0.596839666367,1.86605656147,-8.65371990204 --0.570833086967,1.86706483364,-8.66016674042 --0.544810533524,1.86408162117,-8.65059280396 --0.531809329987,1.86508476734,-8.65581893921 --0.505798757076,1.86509513855,-8.65826034546 --0.478773742914,1.8621134758,-8.64670372009 --0.452750146389,1.85913097858,-8.6361322403 --0.426751703024,1.86213493347,-8.65058708191 --0.40174254775,1.86214435101,-8.65401363373 --0.375737279654,1.86415207386,-8.66145992279 --0.360696554184,1.85617673397,-8.62868595123 --0.335691452026,1.85718417168,-8.63611602783 --0.309676796198,1.85619676113,-8.63455677032 --0.28366330266,1.85620892048,-8.63399791718 --0.257641345263,1.85322570801,-8.62543392181 --0.232651814818,1.85822474957,-8.64787387848 --0.205629587173,1.85624170303,-8.63932704926 --0.193626001477,1.8572460413,-8.64153289795 --0.166601523757,1.85426425934,-8.63098716736 --0.141598746181,1.85627043247,-8.640417099 --0.114551410079,1.84830117226,-8.60786437988 --0.089562125504,1.8533000946,-8.63029956818 --0.0635212287307,1.84632694721,-8.60373401642 --0.0375211946666,1.84933197498,-8.61618232727 --0.0245242957026,1.8513327837,-8.62540721893 -0.000464496086352,1.85733175278,-8.64783763885 -0.00150608585682,1.83964323997,-7.7891626358 -0.0274934601039,1.83362865448,-7.76556062698 -0.0534883588552,1.82961821556,-7.74895906448 -0.078524440527,1.83463013172,-7.77233171463 -0.0915142968297,1.83162069321,-7.75653409958 -0.116483829916,1.82159686089,-7.71592950821 -0.142527684569,1.82861280441,-7.74631357193 -0.168534293771,1.82760846615,-7.74071121216 -0.193511500955,1.81958889961,-7.70711088181 -0.219550028443,1.82560181618,-7.73249292374 -0.245561793447,1.82560050488,-7.73188924789 -0.256537437439,1.81858420372,-7.70307683945 -0.283575356007,1.82459664345,-7.72747135162 -0.308578491211,1.82259082794,-7.71885919571 -0.33356243372,1.81657481194,-7.69126367569 -0.359593510628,1.82058393955,-7.70964670181 -0.384606987238,1.82158374786,-7.71102666855 -0.409596174955,1.8165705204,-7.68843078613 -0.422606647015,1.81757235527,-7.69262552261 -0.44761094451,1.81556737423,-7.68501710892 -0.473628968,1.81756937504,-7.69040822983 -0.498631387949,1.81556344032,-7.68080282211 -0.523636698723,1.81355905533,-7.67419433594 -0.548643171787,1.8125551939,-7.66858434677 -0.572644293308,1.81054878235,-7.65796661377 -0.585651934147,1.8115490675,-7.65916395187 -0.611666977406,1.81254947186,-7.66156053543 -0.635657191277,1.80753719807,-7.63995981216 -0.660662651062,1.80553305149,-7.63335514069 -0.686690688133,1.81054055691,-7.64873123169 -0.709671854973,1.80352365971,-7.61813306808 -0.735687851906,1.80452477932,-7.62152767181 -0.74870121479,1.80652832985,-7.62871551514 -0.771683573723,1.79951202869,-7.59912109375 -0.798715770245,1.8055216074,-7.61850261688 -0.823721706867,1.80451750755,-7.61189937592 -0.84670996666,1.7985047102,-7.58829832077 -0.872733831406,1.80251002312,-7.59967756271 -0.894711434841,1.79449141026,-7.56508541107 -0.910747170448,1.80150640011,-7.5942735672 -0.934748828411,1.79950022697,-7.58366537094 -0.956731557846,1.7934845686,-7.55406665802 -0.983761489391,1.79849302769,-7.57144641876 -1.00675523281,1.7944829464,-7.55284261703 -1.03075492382,1.79147613049,-7.54024219513 -1.04577958584,1.79648518562,-7.55843162537 -1.06978344917,1.79548037052,-7.54982185364 -1.09781169891,1.79948759079,-7.56521654129 -1.16075718403,1.77944016457,-7.47342061996 -1.18878936768,1.78544962406,-7.49280405045 -1.19978487492,1.78344404697,-7.48200273514 -1.22177946568,1.77943480015,-7.46439218521 -1.24779295921,1.78043484688,-7.46479463577 -1.27079474926,1.77842926979,-7.45418119431 -1.29680728912,1.77942872047,-7.45358657837 -1.31578624249,1.77241182327,-7.4199795723 -1.34381353855,1.77741873264,-7.43437147141 -1.3538069725,1.77441227436,-7.42156553268 -1.3788163662,1.77441036701,-7.4179649353 -1.40382838249,1.7754099369,-7.41735506058 -1.42682766914,1.77240312099,-7.40375518799 -1.45183813572,1.77340173721,-7.4011516571 -1.4758450985,1.77239882946,-7.39554262161 -1.49884581566,1.77139258385,-7.3829407692 -1.50884211063,1.76938784122,-7.37312889099 -1.53284740448,1.76838409901,-7.36552762985 -1.55685555935,1.76838183403,-7.3609161377 -1.58186590672,1.76838052273,-7.35831403732 -1.60587406158,1.76837825775,-7.35370254517 -1.63088274002,1.76837599277,-7.34910678864 -1.66091668606,1.77538621426,-7.37049245834 -1.66488492489,1.76636767387,-7.33169746399 -1.69089913368,1.76736831665,-7.33309555054 -1.71490502357,1.76736474037,-7.32549524307 -1.73590052128,1.76435649395,-7.30788850784 -1.76291882992,1.76635909081,-7.31328582764 -1.78291225433,1.76335000992,-7.29367208481 -1.7969212532,1.76435101032,-7.29588079453 -1.82294011116,1.76735413074,-7.302257061 -1.84292840958,1.76234221458,-7.27667045593 -1.86995005608,1.76534676552,-7.28604888916 -1.88893568516,1.76033353806,-7.25746202469 -1.91595411301,1.76333630085,-7.26285552979 -1.94393455982,1.7553178072,-7.22246265411 -1.97396683693,1.7613273859,-7.24283742905 -1.99697077274,1.76032316685,-7.23323488235 -2.01997303963,1.75931811333,-7.22164106369 -2.04197621346,1.75831389427,-7.21202373505 -2.06798887253,1.75931382179,-7.21142721176 -2.08998918533,1.75730800629,-7.19782876968 -2.10400152206,1.76031088829,-7.20401525497 -2.1239964962,1.75730276108,-7.18541002274 -2.14800357819,1.75730001926,-7.17881059647 -2.17100691795,1.75629556179,-7.16821479797 -2.19501519203,1.75629377365,-7.16360664368 -2.22102975845,1.75829482079,-7.16499853134 -2.24202728271,1.75628769398,-7.14840221405 -2.2600505352,1.76129543781,-7.1655921936 -2.28807115555,1.76429951191,-7.17397737503 -2.31709456444,1.76930451393,-7.18436574936 -2.33508300781,1.76429343224,-7.15877008438 -2.36009454727,1.76529312134,-7.15715885162 -2.38309884071,1.76528930664,-7.14755821228 -2.4071059227,1.76528680325,-7.1409573555 -2.41409659386,1.76227962971,-7.12415266037 -2.44612550735,1.76828718185,-7.14054918289 -2.47414469719,1.77129030228,-7.14693784714 -2.49815249443,1.77128815651,-7.14133024216 -2.67118835449,1.76926231384,-7.07331228256 -2.69218707085,1.76725614071,-7.05771827698 -2.70720028877,1.77025949955,-7.06489992142 -2.72819924355,1.76825344563,-7.04930639267 -2.75320863724,1.76925194263,-7.04470682144 -2.77220487595,1.76724505424,-7.02709674835 -2.8042318821,1.77225160599,-7.0414853096 -2.83024382591,1.77425146103,-7.0398812294 -2.85324907303,1.77424836159,-7.03127527237 -2.86826086044,1.77725088596,-7.03646469116 -2.88625240326,1.77324175835,-7.01287794113 -2.90625095367,1.77123570442,-6.99727201462 -2.92724943161,1.76922953129,-6.98068809509 -2.96128177643,1.7772384882,-7.00105905533 -2.98428559303,1.77623474598,-6.99046516418 -3.00428533554,1.77522933483,-6.97585391998 -3.01328134537,1.77322494984,-6.96406316757 -3.04430437088,1.77822971344,-6.97444963455 -3.0723195076,1.7812308073,-6.97584962845 -3.09632611275,1.78122842312,-6.96825027466 -3.11632418633,1.77922236919,-6.95165252686 -3.13933062553,1.78021991253,-6.94403886795 -3.16233539581,1.78021681309,-6.93443822861 -3.18135285378,1.78422152996,-6.94563770294 -3.198346138,1.78121352196,-6.9240322113 -3.21934556961,1.77920806408,-6.9084444046 -3.24435520172,1.78120696545,-6.90383768082 -3.26435494423,1.7792018652,-6.88922929764 -3.28735995293,1.77919876575,-6.87962961197 -3.30737996101,1.78520476818,-6.8938164711 -3.32837939262,1.78319942951,-6.87822914124 -3.35439062119,1.78519904613,-6.87562131882 -3.37639451027,1.78519558907,-6.86501264572 -3.40941810608,1.7912003994,-6.87540817261 -3.4244081974,1.78619122505,-6.84980916977 -3.44841575623,1.78718936443,-6.84319972992 -3.45841479301,1.78618645668,-6.83440685272 -3.48943448067,1.79118967056,-6.84079933167 -3.5014193058,1.78517830372,-6.80920553207 -3.52141785622,1.78417241573,-6.79162168503 -3.55243873596,1.78917634487,-6.79999685287 -3.57444143295,1.78817236423,-6.78740358353 -3.59243774414,1.78616583347,-6.76780796051 -3.60945057869,1.78916883469,-6.77499198914 -3.63045144081,1.788164258,-6.76040029526 -3.65545988083,1.79016268253,-6.7538022995 -3.68447518349,1.79316401482,-6.75519704819 -3.70146965981,1.79015684128,-6.73360443115 -3.72247195244,1.79015302658,-6.72099685669 -3.75048470497,1.79215323925,-6.71940040588 -3.76248931885,1.79315292835,-6.71758174896 -3.77147006989,1.78614020348,-6.68000841141 -3.82252144814,1.80115604401,-6.72138118744 -3.8385155201,1.79814898968,-6.69977664948 -3.85651159286,1.79614245892,-6.67919254303 -3.88752985001,1.80014526844,-6.68457460403 -3.90153646469,1.8021453619,-6.68377304077 -3.92754626274,1.80414450169,-6.67916679382 -3.94554305077,1.80213844776,-6.6595749855 -3.97455739975,1.80513942242,-6.65996694565 -3.99756169319,1.80513656139,-6.64936828613 -4.02657604218,1.80913734436,-6.6487660408 -4.03856372833,1.80412769318,-6.61917877197 -4.05357170105,1.8061286211,-6.62037134171 -4.07156896591,1.80412256718,-6.60078144073 -4.09157037735,1.80411875248,-6.58716821671 -4.13360261917,1.81312680244,-6.60755681992 -4.14759397507,1.80911886692,-6.58196544647 -4.1645898819,1.80711233616,-6.56038093567 -4.19460535049,1.8111140728,-6.56276082993 -4.20360422134,1.81011116505,-6.5529665947 -4.22861146927,1.81210947037,-6.54536581039 -4.24460697174,1.80910313129,-6.52376937866 -4.26761198044,1.81010043621,-6.5131688118 -4.29562330246,1.81210017204,-6.50957155228 -4.32864236832,1.81810295582,-6.51495790482 -4.33462429047,1.81109166145,-6.47836637497 -4.35163402557,1.81409323215,-6.48156070709 -4.38264989853,1.81809461117,-6.48295450211 -4.398645401,1.81608843803,-6.46135950089 -4.42565488815,1.81808757782,-6.45576334 -4.45466804504,1.82108807564,-6.45415496826 -4.46565628052,1.81707906723,-6.423579216 -4.51369380951,1.82808899879,-6.45094680786 -4.52469587326,1.82908761501,-6.44514131546 -4.52867603302,1.82107567787,-6.40556192398 -4.55268192291,1.82207322121,-6.39496994019 -4.58569908142,1.82707536221,-6.39836072922 -4.60469913483,1.82607102394,-6.38176012039 -4.62870502472,1.82806897163,-6.37215614319 -4.64770460129,1.82706439495,-6.35456514359 -4.66371297836,1.82906532288,-6.35575675964 -4.68771886826,1.83106327057,-6.3461523056 -4.70972251892,1.83106029034,-6.33355140686 -4.72571802139,1.82905435562,-6.3109703064 -4.75072526932,1.83105266094,-6.30236816406 -4.7817401886,1.83505368233,-6.30275249481 -4.77972602844,1.83004653454,-6.27796936035 -4.83476877213,1.84405767918,-6.31033802032 -4.86978626251,1.84905970097,-6.31373786926 -4.87276792526,1.84204924107,-6.27614355087 -4.90678453445,1.84705066681,-6.27754831314 -4.92378234863,1.8460457325,-6.25795030594 -4.94478464127,1.84604227543,-6.24335289001 -4.9487786293,1.84403812885,-6.22755861282 -4.97678852081,1.84703743458,-6.22195672989 -5.00980424881,1.85203886032,-6.22334432602 -5.03080606461,1.85203528404,-6.20775461197 -5.07383298874,1.86104047298,-6.22212791443 -5.08982896805,1.85903513432,-6.20053815842 -5.11483573914,1.86103332043,-6.19093465805 -5.13684892654,1.86503601074,-6.19812393188 -5.1518445015,1.86303007603,-6.17454242706 -5.17885351181,1.86602914333,-6.16793012619 -5.19985532761,1.86602568626,-6.15233802795 -5.22486162186,1.86802363396,-6.14174222946 -5.24486303329,1.86802017689,-6.12613773346 -5.26387262344,1.87102127075,-6.12833786011 -5.29188108444,1.87402021885,-6.12074327469 -5.29987049103,1.86901259422,-6.09015512466 -5.24779891968,1.84198462963,-5.98663473129 -5.13066482544,1.79093551636,-5.80618095398 -5.12464189529,1.78092420101,-5.7606086731 -5.13463544846,1.77791857719,-5.73501300812 -5.12962150574,1.77191221714,-5.70923900604 -5.13961553574,1.7689063549,-5.68265724182 -5.16262102127,1.77090466022,-5.67106533051 -5.16861104965,1.76589787006,-5.64048290253 -5.17260026932,1.76089084148,-5.60888957977 -5.1926035881,1.7608884573,-5.59429740906 -5.20259809494,1.75788331032,-5.56871080399 -5.19758558273,1.75287747383,-5.54393529892 -5.20657968521,1.74987232685,-5.5183391571 -5.21457242966,1.74586653709,-5.49075603485 -5.22756958008,1.74386239052,-5.46817588806 -5.23856544495,1.74085760117,-5.44359636307 -5.24555826187,1.73685216904,-5.41600608826 -5.25054931641,1.73284590244,-5.38542842865 -5.25154352188,1.72984266281,-5.36962890625 -5.26654338837,1.72883939743,-5.35004281998 -5.27053356171,1.72383320332,-5.31847000122 -5.28753566742,1.72383069992,-5.30187320709 -5.29352807999,1.71982526779,-5.27329158783 -5.31853723526,1.72182524204,-5.26568174362 -5.3165230751,1.71481764317,-5.22811746597 -5.32352304459,1.71481609344,-5.21832036972 -5.33452033997,1.71281218529,-5.19474124908 -5.35052156448,1.71180975437,-5.1771478653 -5.36051845551,1.70980572701,-5.15355873108 -5.36451005936,1.70480024815,-5.12298822403 -5.38951921463,1.70780026913,-5.11537694931 -5.38951396942,1.7047971487,-5.09858798981 -5.40251350403,1.70379424095,-5.07799959183 -5.4155125618,1.70179116726,-5.05741214752 -5.4305138588,1.70178866386,-5.03882265091 -5.43750858307,1.69878447056,-5.01224327087 -5.4585146904,1.6997834444,-4.99964809418 -5.46450901031,1.69577908516,-4.97207164764 -5.46850728989,1.69477725029,-4.96026992798 -5.493516922,1.69777715206,-4.95166873932 -5.48650121689,1.68976998329,-4.91111469269 -5.50250387192,1.68976819515,-4.89451503754 -5.514503479,1.68776547909,-4.87392234802 -5.5235004425,1.68576228619,-4.85033464432 -5.54150485992,1.6867607832,-4.8347454071 -5.5455031395,1.68475902081,-4.82195997238 -5.54849624634,1.68075478077,-4.79337358475 -5.56850194931,1.68175375462,-4.77978086472 -5.58150291443,1.68075168133,-4.7601890564 -5.57548999786,1.67374575138,-4.72361278534 -5.59749746323,1.67574524879,-4.71102952957 -5.60749578476,1.67374241352,-4.6884469986 -5.60549068451,1.67073988914,-4.6706662178 -5.61348819733,1.66873693466,-4.64707660675 -5.63749742508,1.67173695564,-4.63747406006 -5.63548803329,1.66573250294,-4.6048989296 -5.64048433304,1.66272926331,-4.57930707932 -5.67549991608,1.6687309742,-4.57771492004 -5.65648365021,1.65972578526,-4.54594612122 -5.67749071121,1.66172540188,-4.53433847427 -5.6804857254,1.65872204304,-4.50675535202 -5.69348716736,1.65772032738,-4.48618555069 -5.70348739624,1.65571820736,-4.46558427811 -5.72449445724,1.6577180624,-4.45298957825 -5.72248649597,1.65271413326,-4.42141389847 -5.72448444366,1.65071249008,-4.40763139725 -5.75149536133,1.65471327305,-4.40003013611 -5.74748659134,1.64870917797,-4.36745166779 -5.7504825592,1.64570629597,-4.33987808228 -5.77549219131,1.64870667458,-4.33028364182 -5.77648735046,1.64470374584,-4.30170583725 -5.78648710251,1.64270198345,-4.28012418747 -5.80149412155,1.64570248127,-4.27732372284 -5.79248285294,1.63869833946,-4.24174547195 -5.81549167633,1.64069855213,-4.23114299774 -5.83049535751,1.64069771767,-4.21355724335 -5.82748889923,1.63569438457,-4.18198871613 -5.84249258041,1.63669371605,-4.16538906097 -5.86349964142,1.6386936903,-4.1518073082 -5.84948921204,1.63169074059,-4.12801504135 -5.86549377441,1.63269007206,-4.11044120789 -5.88349962234,1.63368988037,-4.09682893753 -5.88849830627,1.63168799877,-4.07126092911 -5.89749860764,1.62968671322,-4.04967594147 -5.92050790787,1.63268709183,-4.03808403015 -5.91750383377,1.62968564034,-4.02229070663 -5.91249704361,1.62468278408,-3.99071598053 -5.93850708008,1.62768340111,-3.98112368584 -5.92849826813,1.62068021297,-3.94556283951 -5.9465045929,1.62268018723,-3.93096542358 -5.97051334381,1.62568080425,-3.92036604881 -5.96350622177,1.6196782589,-3.88779473305 -5.97250986099,1.62067818642,-3.88098835945 -5.98751401901,1.62067782879,-3.86340689659 -5.98450946808,1.61667585373,-3.83383274078 -6.00051498413,1.61767566204,-3.81724572182 -6.00751543045,1.61567473412,-3.79466462135 -6.01151418686,1.61267352104,-3.77107048035 -6.0165143013,1.61067247391,-3.74650216103 -6.02251625061,1.6106723547,-3.73769807816 -6.01951217651,1.60567057133,-3.70813322067 -6.03851938248,1.60767090321,-3.69354510307 -6.05252361298,1.60867083073,-3.67595553398 -6.05051994324,1.60366952419,-3.64837312698 -6.05452013016,1.60166859627,-3.62380075455 -6.06852483749,1.602668643,-3.60621237755 -6.07252597809,1.60166847706,-3.59640645981 -6.07552528381,1.59866762161,-3.57084345818 -6.09053087234,1.59966778755,-3.55424880981 -6.09253025055,1.59666705132,-3.5296626091 -6.09953212738,1.59566664696,-3.50807476044 -6.12154054642,1.5986675024,-3.49548006058 -6.11453676224,1.59466648102,-3.47770357132 -6.12253856659,1.59366643429,-3.45612645149 -6.14054584503,1.59566688538,-3.44152665138 -6.13754367828,1.59166610241,-3.41394877434 -6.13754272461,1.58866560459,-3.38738298416 -6.15755033493,1.5906662941,-3.37378501892 -6.15554857254,1.58666574955,-3.34720373154 -6.15754938126,1.58566570282,-3.33541584015 -6.16555213928,1.58466565609,-3.31482625008 -6.17255449295,1.58366584778,-3.29226112366 -6.17955684662,1.58266592026,-3.27166414261 -6.19256210327,1.58266639709,-3.25308632851 -6.18355846405,1.57766580582,-3.22251772881 -6.19756412506,1.57966649532,-3.21771907806 -6.20856809616,1.57966685295,-3.19912481308 -6.20456647873,1.57566678524,-3.1715528965 -6.21156930923,1.57466709614,-3.14997553825 -6.22357463837,1.57566773891,-3.13237404823 -6.22657585144,1.57266795635,-3.10879778862 -6.22957754135,1.57066833973,-3.0852227211 -6.24558401108,1.57366907597,-3.08142089844 -6.24758529663,1.57166934013,-3.0578379631 -6.25058698654,1.56966984272,-3.03426408768 -6.2595911026,1.56967043877,-3.01467251778 -6.26459360123,1.56767106056,-2.99210000038 -6.27159738541,1.56667172909,-2.97151017189 -6.27960109711,1.56667244434,-2.95092844963 -6.27660036087,1.56367278099,-2.93714189529 -6.29460859299,1.56667375565,-2.92155480385 -6.29961109161,1.56467449665,-2.89996767044 -6.29461097717,1.5606751442,-2.87240552902 -6.31261825562,1.56267619133,-2.85780096054 -6.31061887741,1.55967700481,-2.83223009109 -6.31462240219,1.55867791176,-2.80965471268 -6.31762361526,1.55767834187,-2.79984951019 -6.32262706757,1.55667936802,-2.77728295326 -6.33163166046,1.5566804409,-2.75769543648 -6.33763551712,1.55568158627,-2.73710298538 -6.34363985062,1.55468261242,-2.71552824974 -6.34264135361,1.55168366432,-2.69095468521 -6.34764385223,1.55168437958,-2.68116521835 -6.36165094376,1.55368554592,-2.6645629406 -6.36765480042,1.5526869297,-2.64298963547 -6.36265516281,1.54868805408,-2.6164252758 -6.37866258621,1.55068945885,-2.60081982613 -6.37666463852,1.54769074917,-2.57624363899 -6.37666702271,1.54569220543,-2.55266547203 -6.39167308807,1.54869282246,-2.54687643051 -6.38867473602,1.54469430447,-2.52229619026 -6.40568256378,1.54769587517,-2.50571346283 -6.4096865654,1.54569733143,-2.48413014412 -6.40368747711,1.54169893265,-2.45854973793 -6.41569375992,1.5427005291,-2.43996834755 -6.42369890213,1.54270207882,-2.4203774929 -6.42270040512,1.54170298576,-2.40760207176 -6.4237036705,1.53970468044,-2.38501882553 -6.43571043015,1.5407063961,-2.36643743515 -6.43871450424,1.5397080183,-2.34485054016 -6.45072126389,1.54070985317,-2.32626891136 -6.45672607422,1.53971159458,-2.30568408966 -6.45072793961,1.53571367264,-2.2801129818 -6.45773172379,1.53671443462,-2.27131962776 -6.46073627472,1.53571641445,-2.24973511696 -6.46874189377,1.5357183218,-2.23014616966 -6.46874570847,1.5337202549,-2.20658040047 -6.48775482178,1.53672206402,-2.19098687172 -6.49376010895,1.53572416306,-2.17040395737 -6.4897608757,1.53472518921,-2.15761518478 -6.50076770782,1.53472709656,-2.13902688026 -6.50477266312,1.53472924232,-2.11745023727 -6.49377393723,1.5297318697,-2.09087777138 -6.50478076935,1.53073382378,-2.07228946686 -6.50878620148,1.52973616123,-2.05071520805 -6.51779222488,1.529738307,-2.03113341331 -6.53779935837,1.53473877907,-2.0273206234 -6.5177989006,1.52774190903,-1.99775731564 -6.52880620956,1.527744174,-1.97818732262 -6.54681491852,1.53074586391,-1.96258151531 -6.53081560135,1.52574908733,-1.93402731419 -6.5458240509,1.52775120735,-1.916441679 -6.55583095551,1.52775347233,-1.89784681797 -6.52782726288,1.52075576782,-1.87708520889 -6.54583597183,1.52275788784,-1.86049687862 -6.55984401703,1.52476000786,-1.84290468693 -6.54784631729,1.5207631588,-1.8173251152 -6.55985403061,1.52176558971,-1.79874110222 -6.57186174393,1.52276790142,-1.78015637398 -6.55586338043,1.51777160168,-1.75259816647 -6.56486797333,1.51877248287,-1.74479305744 -6.59087896347,1.52377426624,-1.73020231724 -6.57688093185,1.51877784729,-1.70363855362 -6.57588577271,1.51678097248,-1.68106520176 -6.59789609909,1.52078282833,-1.66645216942 -6.58889961243,1.51778638363,-1.6418787241 -6.58490180969,1.51578807831,-1.62910461426 -6.60191059113,1.51879048347,-1.61152267456 -6.59691524506,1.51579391956,-1.58795213699 -6.60992336273,1.51779639721,-1.57035076618 -6.61593008041,1.51779925823,-1.5497739315 -6.61193561554,1.51480269432,-1.52719116211 -6.61494207382,1.51480591297,-1.50562059879 -6.61794567108,1.51480734348,-1.49582314491 -6.60994958878,1.5118111372,-1.47224402428 -6.62295818329,1.51381373405,-1.4536601305 -6.64396858215,1.5168159008,-1.43707072735 -6.62097024918,1.50982069969,-1.40950858593 -6.62997770309,1.51082360744,-1.38992643356 -6.65398836136,1.51582562923,-1.37432706356 -6.62598705292,1.50782930851,-1.35655975342 -6.63499450684,1.50883221626,-1.33697748184 -6.65100383759,1.51183474064,-1.31938326359 -6.64100885391,1.50783920288,-1.29482376575 -6.65701818466,1.51084160805,-1.27722847462 -6.67102718353,1.51384437084,-1.25864326954 -6.65103054047,1.50684952736,-1.23208892345 -6.67003679276,1.51184999943,-1.22627186775 -6.66604280472,1.50885403156,-1.20369946957 -6.65904855728,1.50685846806,-1.18013656139 -6.65505456924,1.50486242771,-1.15854680538 -6.68506622314,1.5108641386,-1.14295625687 -6.66206979752,1.50386977196,-1.1164008379 -6.66607379913,1.50487148762,-1.1066069603 -6.68808412552,1.5088737011,-1.09000611305 -6.67508935928,1.50487875938,-1.06544804573 -6.6790971756,1.50488245487,-1.04486680031 -6.68610525131,1.50588583946,-1.02527534962 -6.68511247635,1.50389003754,-1.00369870663 -6.68111944199,1.50189459324,-0.981133341789 -6.68312311172,1.50189638138,-0.971333384514 -6.6941318512,1.50389957428,-0.951753020287 -6.70414113998,1.5059030056,-0.932168900967 -6.70014762878,1.50390744209,-0.910585463047 -6.68215322495,1.49891328812,-0.886024296284 -6.66115808487,1.49291920662,-0.861458301544 -6.69916677475,1.50091826916,-0.856653749943 -6.7001748085,1.50092244148,-0.836065649986 -6.71118402481,1.50292575359,-0.816482663155 -6.69919013977,1.49893116951,-0.793903112411 -6.73120164871,1.50593268871,-0.777309477329 -6.68220376968,1.49294149876,-0.748765289783 -6.70621490479,1.4989439249,-0.731171309948 -6.67121553421,1.4899494648,-0.715409338474 -6.67222309113,1.4889537096,-0.694825410843 -6.67723226547,1.48995792866,-0.674249589443 -6.68224096298,1.48996210098,-0.653673827648 -6.67924880981,1.48896682262,-0.633082032204 -6.66025543213,1.4839733839,-0.609520375729 -6.64626216888,1.47897934914,-0.58695101738 -6.71427297592,1.49597501755,-0.585112214088 -6.72928285599,1.49897837639,-0.565531492233 -6.72529125214,1.49698352814,-0.543957412243 -6.74130105972,1.49998676777,-0.524376392365 -6.73830890656,1.49899160862,-0.503784239292 -6.7463183403,1.49999570847,-0.483209103346 -6.74332284927,1.49999845028,-0.472420752048 -6.74933195114,1.5000026226,-0.451842308044 -6.72033786774,1.49301028252,-0.428276330233 -6.65234136581,1.47602236271,-0.400744527578 -6.72835588455,1.49401938915,-0.387116104364 -6.71436405182,1.49002599716,-0.364554852247 -6.68337059021,1.48203420639,-0.340997189283 -6.68037509918,1.48103702068,-0.330213040113 -6.72338724136,1.49103736877,-0.31359437108 -6.74039745331,1.49504065514,-0.294006109238 -6.74940776825,1.49704480171,-0.273428916931 -6.7514166832,1.49704957008,-0.252845406532 -6.72142362595,1.48905789852,-0.230277970433 -6.72843313217,1.49106228352,-0.20969940722 -6.70843696594,1.48606705666,-0.19792458415 -6.68244457245,1.47907531261,-0.175367191434 -6.69345474243,1.48107922077,-0.155772835016 -6.70946502686,1.48508286476,-0.135199248791 -6.72247505188,1.48808646202,-0.115602828562 -6.74248552322,1.49308943748,-0.0960072278976 -6.73049497604,1.48909628391,-0.0744405314326 -6.73250007629,1.49009883404,-0.0636594295502 -6.71250867844,1.4851064682,-0.0420928858221 -6.6735162735,1.47511613369,-0.0205266214907 -6.71152830124,1.48411726952,-0.000930237467401 -6.7125377655,1.48412263393,0.0196509212255 -6.71854829788,1.48612737656,0.0402326323092 -6.70555257797,1.48213171959,0.051012005657 -6.71756315231,1.4851359129,0.0715945214033 -6.71257257462,1.48414182663,0.0921748802066 -6.72458314896,1.48614597321,0.112758912146 -6.66759109497,1.47315847874,0.134301736951 -6.69360208511,1.47916102409,0.154890134931 -6.71361303329,1.48416423798,0.175479128957 -6.7166185379,1.48516666889,0.185281127691 -6.70162773132,1.48117399216,0.205853909254 -6.69163799286,1.47918093204,0.226428121328 -6.70564889908,1.48218524456,0.247997060418 -6.70365953445,1.48119115829,0.268575936556 -6.68766927719,1.47819888592,0.289143770933 -6.73968029022,1.49019801617,0.309767723083 -6.69468450546,1.47920656204,0.319528967142 -6.73169612885,1.48820769787,0.341124147177 -6.73270654678,1.48921346664,0.361707627773 -6.72871685028,1.48821973801,0.382285684347 -6.71872758865,1.48622691631,0.402856647968 -6.72973823547,1.48823153973,0.424431353807 -6.61074256897,1.46025013924,0.431146174669 -6.61375379562,1.4612557888,0.451725244522 -6.67476511002,1.47625374794,0.474343448877 -6.68177556992,1.47825860977,0.494932740927 -6.67878675461,1.47726523876,0.515508055687 -6.6667971611,1.47427272797,0.535089373589 -6.67880868912,1.47827720642,0.556667983532 -6.66281414032,1.47428250313,0.566441833973 -6.6908249855,1.48128473759,0.588048458099 -6.70083618164,1.48428952694,0.609627187252 -6.70784711838,1.48629486561,0.631201863289 -6.69885826111,1.48430204391,0.650787293911 -6.68186950684,1.48031055927,0.670356333256 -6.68388032913,1.48131644726,0.690941631794 -6.68888616562,1.48231887817,0.701732397079 -6.69289779663,1.48432469368,0.72330302 -6.67390918732,1.47933375835,0.742864191532 -6.67792081833,1.48133933544,0.763454735279 -6.65693187714,1.47634851933,0.782028615475 -6.66294336319,1.47835409641,0.803603649139 -6.61795568466,1.46836674213,0.820156812668 -6.60596227646,1.46537184715,0.829926908016 -6.69097232819,1.48636615276,0.858557939529 -6.69698286057,1.48837137222,0.879157066345 -6.67499542236,1.48338103294,0.897723793983 -6.67100763321,1.48338806629,0.918296635151 -6.69601821899,1.48939096928,0.941888689995 -6.67102527618,1.48439788818,0.949662089348 -6.67103672028,1.48440432549,0.970245778561 -6.69004774094,1.48940813541,0.993825376034 -6.64806079865,1.48042070866,1.00938653946 -6.63207387924,1.477429986,1.02894163132 -6.63208580017,1.47743654251,1.04952430725 -6.61909770966,1.4754447937,1.06810641289 -6.61010408401,1.47344958782,1.07787907124 -6.61711597443,1.47545516491,1.09946405888 -6.60412836075,1.47346365452,1.11804413795 -6.57114219666,1.46647548676,1.13459539413 -6.59815311432,1.47347819805,1.15918922424 -6.53816795349,1.4594938755,1.17074203491 -6.56717300415,1.46649289131,1.1855442524 -6.59618425369,1.47449553013,1.21113049984 -6.60119581223,1.47650110722,1.23173260689 -6.59620857239,1.47650885582,1.25229883194 -6.59422111511,1.47651600838,1.27287602425 -6.57323503494,1.47252619267,1.29044044018 -6.59324598312,1.4785296917,1.31404292583 -6.59925222397,1.47953236103,1.32582938671 -6.59326457977,1.47954010963,1.34541201591 -6.58627843857,1.47854828835,1.36597037315 -6.59229040146,1.48055410385,1.38756167889 -6.5783033371,1.47856330872,1.4061306715 -6.58031654358,1.47957015038,1.42770636082 -6.5783290863,1.48057734966,1.44828569889 -6.53633785248,1.47058749199,1.45104658604 -6.48635339737,1.45960235596,1.46161091328 -6.53636312485,1.47260141373,1.49221849442 -6.48237991333,1.46061718464,1.50275957584 -6.53738880157,1.47461545467,1.5343773365 -6.55740070343,1.48061943054,1.55995929241 -6.55141401291,1.48062741756,1.57954072952 -6.55142068863,1.48063099384,1.59032571316 -6.54643392563,1.48063874245,1.60991168022 -6.5064496994,1.47265255451,1.62246632576 -6.52046203613,1.47665762901,1.64704465866 -6.50847625732,1.47466683388,1.66561448574 -6.47849082947,1.46867859364,1.67919111252 -6.5204949379,1.4796756506,1.69999146461 -6.53050756454,1.48368120193,1.72357535362 -6.50852203369,1.47969198227,1.73915231228 -6.5165348053,1.48269808292,1.76272749901 -6.45355272293,1.46771562099,1.76828050613 -6.43356800079,1.46472644806,1.78484165668 -6.43958091736,1.4667327404,1.80742406845 -6.45358657837,1.47173404694,1.82122719288 -6.45859956741,1.4737405777,1.84380698204 -6.46461248398,1.47674691677,1.86639392376 -6.47962474823,1.48175191879,1.89197432995 -6.46464014053,1.47976195812,1.90954267979 -6.46465301514,1.4807690382,1.93013739586 -6.46466684341,1.48177659512,1.95171356201 -6.46067380905,1.48178100586,1.96149802208 -6.45868778229,1.48278880119,1.98208272457 -6.45870161057,1.4837962389,2.00366044044 -6.45271635056,1.48380506039,2.02422213554 -6.43173217773,1.47981619835,2.03978943825 -6.43574476242,1.48282265663,2.06139230728 -6.40775489807,1.47683167458,2.06514453888 -6.3777718544,1.4708442688,2.07770967484 -6.39078426361,1.47484946251,2.10230994225 -6.35480165482,1.4678632021,2.11287212372 -6.33381795883,1.46387469769,2.12842988968 -6.35183000565,1.46987915039,2.15502619743 -6.29484987259,1.45789659023,2.15857887268 -6.36285018921,1.47488856316,2.19040822983 -6.34486627579,1.47289967537,2.20696592331 -6.33288145065,1.47090935707,2.22454214096 -6.31789731979,1.46891963482,2.24111700058 -6.35690736771,1.4799207449,2.27571296692 -6.35192251205,1.4809294939,2.29628133774 -6.35092926025,1.4809333086,2.30608510971 -6.35194349289,1.48294115067,2.32865715027 -6.34095859528,1.48195064068,2.34624195099 -6.33197498322,1.48196029663,2.36580204964 -6.32698917389,1.48196876049,2.38539004326 -6.31500482559,1.48097860813,2.40296626091 -6.31101989746,1.48198723793,2.4235432148 -6.30402851105,1.48099255562,2.43232369423 -6.29304361343,1.48000228405,2.44990611076 -6.29505825043,1.48201012611,2.47347044945 -6.28607416153,1.48201954365,2.49204897881 -6.26809024811,1.47903037071,2.50663518906 -6.27110481262,1.48203802109,2.53020882607 -6.27511882782,1.48504531384,2.55379152298 -6.25512886047,1.480052948,2.55756568909 -6.24214458466,1.47906303406,2.57415032387 -6.25015878677,1.48306977749,2.59972763062 -6.23017597198,1.48008143902,2.61429476738 -6.22819137573,1.4810898304,2.63587093353 -6.22320699692,1.48209893703,2.65644264221 -6.20522403717,1.48011016846,2.67102336884 -6.21223020554,1.48211276531,2.68481969833 -6.22224378586,1.48711919785,2.71140122414 -6.18726348877,1.48013341427,2.71897363663 -6.18427848816,1.48114216328,2.7405436039 -6.19429254532,1.48614871502,2.7671289444 -6.1713104248,1.48216080666,2.77970218658 -6.1713180542,1.48316514492,2.79148221016 -6.17133331299,1.48617339134,2.81406140327 -6.14735174179,1.48118567467,2.82564210892 -6.14436721802,1.48319458961,2.84721493721 -6.14438247681,1.48520278931,2.86979532242 -6.12839984894,1.48321402073,2.88536834717 -6.11541652679,1.48222446442,2.90194773674 -6.11742448807,1.48422849178,2.91472887993 -6.10744094849,1.48323845863,2.93231582642 -6.10245656967,1.48424756527,2.95289182663 -6.10247182846,1.48725581169,2.97547626495 -6.08948993683,1.48626685143,2.99303746223 -6.08450555801,1.48727607727,3.01361489296 -6.0825214386,1.48828470707,3.03520178795 -6.06053256989,1.48429322243,3.03696918488 -6.05954837799,1.48630189896,3.0595471859 -6.05956315994,1.48831009865,3.08213543892 -6.03258323669,1.4843236208,3.09269356728 -6.03259849548,1.4863319397,3.11528229713 -6.03161430359,1.48834049702,3.1378633976 -6.01163339615,1.48635292053,3.15142941475 -6.00664186478,1.48635792732,3.16022276878 -6.00465774536,1.48736679554,3.1827955246 -5.98767614365,1.48637855053,3.19737005234 -5.97469377518,1.48538935184,3.21394610405 -5.98070859909,1.48939681053,3.24052619934 -5.96072721481,1.48640906811,3.25310611725 -5.95573711395,1.48641443253,3.26288175583 -5.95975208282,1.49042224884,3.28846287727 -5.94277095795,1.48843407631,3.30303549767 -5.92778873444,1.48744547367,3.31860923767 -5.93380355835,1.49145281315,3.34519553185 -5.91682243347,1.48946464062,3.35976696014 -5.9098315239,1.48847019672,3.36755824089 -5.91184711456,1.49247837067,3.39214348793 -5.89986515045,1.49148952961,3.40971159935 -5.88488340378,1.49050056934,3.4243016243 -5.8828997612,1.49250996113,3.44786643982 -5.87191820145,1.49252068996,3.46544456482 -5.84993743896,1.48953354359,3.47701430321 -5.84594678879,1.48953866959,3.48680114746 -5.84796190262,1.49354696274,3.51139211655 -5.83498096466,1.49255847931,3.52894973755 -5.83099794388,1.49456787109,3.550532341 -5.8160161972,1.49357926846,3.56512069702 -5.80503463745,1.4935901165,3.58269906044 -5.79205369949,1.49260163307,3.60025620461 -5.78906202316,1.49360644817,3.61005473137 -5.78107976913,1.4946167469,3.6296312809 -5.78209543228,1.49762523174,3.65421915054 -5.76211547852,1.49463796616,3.6667869091 -5.74313545227,1.49265038967,3.67936396599 -5.74515151978,1.49665927887,3.70593166351 -5.73017120361,1.49567103386,3.72150111198 -5.72118091583,1.49467682838,3.72730302811 -5.71819782257,1.49668669701,3.75086903572 -5.71521520615,1.49969601631,3.77345299721 -5.69723510742,1.49770843983,3.78702282906 -5.68225431442,1.49672019482,3.80160808563 -5.67427206039,1.49773049355,3.82118797302 -5.67528009415,1.49973464012,3.83398413658 -5.66829872131,1.50074541569,3.85554337502 -5.64531946182,1.49775862694,3.86512136459 -5.64033651352,1.49976849556,3.88670349121 -5.63435506821,1.50177884102,3.90827512741 -5.61337518692,1.49879181385,3.91885733604 -5.60639333725,1.49980211258,3.93943452835 -5.60040283203,1.49980783463,3.94821929932 -5.59242200851,1.50181877613,3.96878623962 -5.58443927765,1.50182890892,3.98738598824 -5.57145929337,1.50184082985,4.00494480133 -5.554479599,1.50085306168,4.01852178574 -5.54249954224,1.50086462498,4.03609132767 -5.53851652145,1.50287437439,4.05867528915 -5.5355257988,1.50387954712,4.06946372986 -5.51854610443,1.50289201736,4.08303976059 -5.51956272125,1.50690090656,4.10962104797 -5.49958372116,1.50491392612,4.12119340897 -5.49660158157,1.50792360306,4.14477729797 -5.48562049866,1.50793468952,4.16236114502 -5.47563123703,1.50694167614,4.16913127899 -5.46165132523,1.50695359707,4.18471050262 -5.45566940308,1.50896382332,4.2062921524 -5.44268941879,1.50897550583,4.22286891937 -5.42171096802,1.5059889555,4.23344182968 -5.41372966766,1.50799977779,4.25401639938 -5.40074968338,1.50801157951,4.27059221268 -5.39975881577,1.50901651382,4.28337812424 -5.38377857208,1.50902867317,4.29696464539 -5.37679767609,1.51003944874,4.3185377121 -5.36581707001,1.51105058193,4.33612442017 -5.36283493042,1.51406049728,4.36070299149 -5.33285903931,1.50907588005,4.36426782608 -5.32387781143,1.51008689404,4.38384914398 -5.33088541031,1.51509034634,4.403632164 -5.30790805817,1.51210415363,4.41220617294 -5.29492807388,1.51211607456,4.42878341675 -5.29794454575,1.51712477207,4.45836782455 -5.27396774292,1.51413881779,4.46594285965 -5.2539896965,1.5121524334,4.47750663757 -5.26399564743,1.51715457439,4.49831914902 -5.2360200882,1.51317000389,4.50387048721 -5.23503684998,1.51617920399,4.52946901321 -5.2190580368,1.51619184017,4.54403972626 -5.20507907867,1.51620423794,4.56060600281 -5.18709993362,1.51521706581,4.57219409943 -5.20111560822,1.52322363853,4.61277198792 -5.17013120651,1.51623487473,4.60054445267 -5.16514921188,1.51924490929,4.62314081192 -5.15217018127,1.51925718784,4.64070653915 -5.12619400024,1.51627194881,4.646276474 -5.12121248245,1.51828217506,4.66986036301 -5.11223220825,1.52029359341,4.69043636322 -5.09924411774,1.51830089092,4.69322013855 -5.09626293182,1.52231097221,4.71880483627 -5.0862827301,1.52332234383,4.73838376999 -5.06030654907,1.52033734322,4.7439494133 -5.05332565308,1.52234792709,4.76554107666 -5.04834461212,1.5253585577,4.79011678696 -5.0193696022,1.5213739872,4.79268312454 -5.01337957382,1.52137994766,4.80147361755 -5.0183968544,1.5283882618,4.83506059647 -4.98942136765,1.52340388298,4.83762454987 -4.98144102097,1.5254150629,4.85920572281 -4.98645830154,1.53242373466,4.89378499985 -4.95848274231,1.52843880653,4.89636039734 -4.93950510025,1.52645230293,4.90793228149 -4.94651222229,1.53145539761,4.92873764038 -4.91753673553,1.52647089958,4.93030929565 -4.90355825424,1.52748346329,4.94688129425 -4.90357637405,1.53249299526,4.97646903992 -4.88159990311,1.53050708771,4.98504018784 -4.86962080002,1.53151917458,5.00361347198 -4.86164093018,1.53353023529,5.02520275116 -4.84665393829,1.53153836727,5.02597904205 -4.83867311478,1.53354930878,5.0475692749 -4.82769489288,1.53556168079,5.06813240051 -4.8057179451,1.53357553482,5.07571458817 -4.79773855209,1.5365871191,5.0992808342 -4.78675937653,1.53759872913,5.11787176132 -4.77377176285,1.53560626507,5.11966085434 -4.76179265976,1.53761827946,5.13823843002 -4.76081180573,1.54262828827,5.16881561279 -4.73283624649,1.53764367104,5.17038965225 -4.71885824203,1.53865635395,5.18696594238 -4.71387767792,1.5426671505,5.2135424614 -4.69390106201,1.54168069363,5.22312545776 -4.69191122055,1.54368638992,5.23790216446 -4.6799325943,1.54469835758,5.25648403168 -4.65995550156,1.54371213913,5.26606702805 -4.64997673035,1.54572403431,5.28764009476 -4.63499879837,1.54673671722,5.30321836472 -4.61802101135,1.54574978352,5.31580543518 -4.61803150177,1.54975509644,5.33357810974 -4.60205316544,1.54976785183,5.34716796875 -4.58007764816,1.54778242111,5.35573291779 -4.57009840012,1.54979395866,5.37632322311 -4.55112218857,1.54880774021,5.38789415359 -4.53614377975,1.54982054234,5.4034743309 -4.52816438675,1.5528318882,5.42705965042 -4.51417779922,1.55083978176,5.42784023285 -4.50319862366,1.55285155773,5.44743108749 -4.4922208786,1.55486392975,5.468998909 -4.47424411774,1.55487751961,5.48157310486 -4.45326805115,1.55289161205,5.49015045166 -4.44528913498,1.55690300465,5.51472902298 -4.4283118248,1.55691635609,5.52830648422 -4.43032073975,1.56092095375,5.5480966568 -4.40334653854,1.55693638325,5.54966831207 -4.40336513519,1.56394636631,5.58425235748 -4.39538574219,1.56695747375,5.60784912109 -3.47163915634,1.21915972233,4.48605489731 -3.45866179466,1.21917235851,4.49763345718 -3.44768381119,1.22018444538,4.51122093201 -3.44169521332,1.22019076347,4.51800537109 -4.32348966599,1.57001698017,5.6769361496 -4.29051685333,1.56403386593,5.67050409317 -4.28053808212,1.5660456419,5.69308710098 -4.29155397415,1.57805299759,5.74268484116 -4.27957630157,1.58006536961,5.76326465607 -4.24759483337,1.57107746601,5.74102592468 -4.2136220932,1.56509423256,5.73160600662 -4.0376868248,1.50114071369,5.53312158585 -4.12068367004,1.54113304615,5.6787519455 -4.10970640182,1.54414558411,5.70131921768 -4.08473205566,1.54116070271,5.70389318466 -3.97277998924,1.50319385529,5.58644008636 -4.01877784729,1.5251891613,5.66725492477 -4.05778741837,1.54819118977,5.75884199142 -4.13578510284,1.58718454838,5.90347003937 -4.14480304718,1.59919309616,5.95603942871 -4.14682149887,1.60720264912,5.9976234436 -4.11084985733,1.60021972656,5.98420810699 -4.10087203979,1.60423195362,6.00977993011 -4.09088420868,1.60323882103,6.01457309723 -3.96493625641,1.55827498436,5.87111759186 -4.09192228317,1.62025856972,6.0947470665 -4.11093664169,1.63626480103,6.16333246231 -4.09995889664,1.63927698135,6.18791151047 -4.06098842621,1.63129496574,6.1704864502 -3.84805417061,1.54334425926,5.87320232391 -4.04002285004,1.63431441784,6.20085287094 -3.71912789345,1.50339138508,5.75731563568 -3.82911801338,1.55937838554,5.9629445076 -3.89212012291,1.59437501431,6.09856081009 -3.90613675117,1.60938262939,6.16313123703 -3.21934008598,1.31353545189,5.13547039032 -3.21135210991,1.31354212761,5.14025974274 -3.90918374062,1.63240671158,6.27110815048 -3.87521243095,1.62542378902,6.25968360901 -3.86923360825,1.63143503666,6.29326200485 -3.88324928284,1.64744222164,6.35885095596 -3.82728433609,1.63046419621,6.31340360641 -3.83230209351,1.64247298241,6.3639998436 -3.85830497742,1.65847277641,6.42879724503 -3.84332847595,1.66048586369,6.4483795166 -3.82235336304,1.6605001688,6.4579615593 -3.78238391876,1.65051853657,6.43653059006 -3.78240346909,1.66052854061,6.48111963272 -3.76642727852,1.6625418663,6.49969816208 -3.76743745804,1.66754698753,6.52547979355 -3.74546265602,1.66656148434,6.53306484222 -3.04767394066,1.34371674061,5.37739562988 -3.04669380188,1.35072684288,5.41298913956 -3.06470894814,1.36773335934,5.48357582092 -3.6765601635,1.67261624336,6.6003780365 -3.65158653259,1.67063140869,6.60296010971 -3.01677203178,1.36576867104,5.49751567841 -3.00579500198,1.36778092384,5.51710128784 -3.61064696312,1.67566502094,6.64891195297 -3.58467435837,1.67368090153,6.65147733688 -3.56469917297,1.67369484901,6.66206884384 -3.55272269249,1.67770767212,6.69063568115 -3.53074884415,1.67772233486,6.69921350479 -3.52176070213,1.67772901058,6.70601272583 -3.50978374481,1.68274176121,6.73359251022 -3.48381066322,1.67975723743,6.73417282104 -3.46083712578,1.67877221107,6.74174261093 -3.44586157799,1.68278551102,6.76431846619 -3.42488670349,1.68279981613,6.77390432358 -3.40491223335,1.68281412125,6.78648233414 -3.40692210197,1.68981909752,6.81726837158 -3.37794995308,1.68583512306,6.81184673309 -3.36097431183,1.68784868717,6.82943487167 -3.343998909,1.68986225128,6.84801578522 -3.31602716446,1.68687844276,6.84558391571 -3.29805159569,1.68789207935,6.86117315292 -3.29606246948,1.69289779663,6.88495731354 -3.27109003067,1.69091320038,6.88852787018 -3.25111508369,1.6919271946,6.90011692047 -3.23813843727,1.69693994522,6.92670631409 -3.20716738701,1.69095659256,6.91727685928 -3.19119215012,1.69497025013,6.93984937668 -3.17421650887,1.69698357582,6.95744419098 -3.15723180771,1.69399237633,6.95022201538 -3.13925719261,1.69600641727,6.96879434586 -3.12028264999,1.69802045822,6.98338031769 -3.09730887413,1.69703507423,6.988966465 -3.07633519173,1.69804990292,7.00153541565 -3.05536079407,1.69806420803,7.01112508774 -3.03937578201,1.69507265091,7.00490808487 -3.02340006828,1.69808602333,7.02649593353 -3.00842475891,1.70209932327,7.05207300186 -2.98045325279,1.69911551476,7.04863977432 -2.96147799492,1.70012927055,7.06223583221 -2.9465034008,1.70514285564,7.08980369568 -2.91953086853,1.70215821266,7.08539199829 -2.90854406357,1.70216572285,7.0901799202 -2.89656805992,1.70817840099,7.12375974655 -2.86759662628,1.70419454575,7.11633396149 -2.84462356567,1.70420944691,7.12291383743 -2.83264684677,1.71022212505,7.15649843216 -2.79967665672,1.70323908329,7.13807535172 -2.78270173073,1.70625257492,7.15965795517 -2.77071523666,1.70626008511,7.16144895554 -2.75474023819,1.71027362347,7.18603038788 -2.73176693916,1.71028852463,7.1926112175 -2.70979380608,1.71030330658,7.20218896866 -2.68382191658,1.70831894875,7.20176315308 -2.666847229,1.71233248711,7.22434520721 -2.64187479019,1.71034789085,7.22592258453 -2.63188791275,1.71135509014,7.23371076584 -2.61091375351,1.71236920357,7.24330663681 -2.59393930435,1.71638309956,7.26788043976 -2.57196617126,1.7163977623,7.27746105194 -2.54699397087,1.71541309357,7.2790389061 -2.52502083778,1.71542775631,7.28861904144 -2.51103496552,1.71343576908,7.28540563583 -2.48906207085,1.71445035934,7.29498624802 -2.46908831596,1.71646487713,7.31156158447 -2.44111728668,1.71248078346,7.30413770676 -2.42714095116,1.71949338913,7.3347363472 -2.40716743469,1.7215077877,7.35131406784 -2.38319516182,1.72052299976,7.35688591003 -2.36920952797,1.71953094006,7.35267543793 -2.3482363224,1.72054541111,7.36525917053 -2.32826256752,1.72255957127,7.3818397522 -2.30728912354,1.72457408905,7.39541959763 -2.29031395912,1.72858738899,7.4190158844 -2.26534247398,1.72760295868,7.42258262634 -2.25635528564,1.72960972786,7.43337869644 -2.23838090897,1.73362362385,7.45696210861 -2.21640825272,1.73563826084,7.46853971481 -2.19443511963,1.73665297031,7.47912311554 -2.18845701218,1.75066411495,7.54271793365 -2.17148256302,1.75667774677,7.57229804993 -2.15150952339,1.7606921196,7.5928735733 -2.14452147484,1.76369845867,7.61167144775 -2.11854982376,1.76171398163,7.6102514267 -2.09257864952,1.76072955132,7.6108212471 -2.06560707092,1.75774514675,7.60540151596 -2.03663659096,1.7537612915,7.59297847748 -2.00766539574,1.74777722359,7.57856178284 -1.97669553757,1.74179375172,7.55813550949 -1.96770775318,1.74380028248,7.56794309616 -1.94373571873,1.74381530285,7.57351970673 -1.92176318169,1.74583005905,7.58709573746 -1.89579117298,1.74284517765,7.58168506622 -1.87181949615,1.74286055565,7.5892534256 -1.84684753418,1.7418756485,7.5888376236 -1.81887662411,1.73789143562,7.57741498947 -1.80589103699,1.73689925671,7.57620191574 -1.78491711617,1.73891317844,7.58879995346 -1.75794637203,1.73592889309,7.58237218857 -1.733974576,1.73594403267,7.58794736862 -1.71200108528,1.7369582653,7.59654474258 -1.68602979183,1.73497366905,7.59312009811 -1.67304432392,1.73398149014,7.59190607071 -1.64907264709,1.73399662971,7.59748029709 -1.6241004467,1.73201155663,7.59407138824 -1.60112810135,1.73302614689,7.60265207291 -1.57915520668,1.73504066467,7.61523675919 -1.55218398571,1.73105609417,7.60382032394 -1.52621257305,1.72807133198,7.59740209579 -1.51722538471,1.73207807541,7.61219930649 -1.49025464058,1.72809374332,7.60377025604 -1.46528279781,1.72710883617,7.60035705566 -1.44231057167,1.72812354565,7.6099357605 -1.41733932495,1.72713887691,7.61050891876 -1.39336681366,1.72615337372,7.61010217667 -1.38238084316,1.72816085815,7.6198849678 -1.35740876198,1.72617566586,7.61447620392 -1.33343660831,1.72519040108,7.61606264114 -1.31046509743,1.7272053957,7.62963104248 -1.28049480915,1.71922135353,7.59721279144 -1.25752258301,1.72023594379,7.60579538345 -1.23454999924,1.72025036812,7.61138629913 -1.22156453133,1.71925806999,7.60717535019 -1.19759237766,1.71927285194,7.60875988007 -1.17262101173,1.71728789806,7.60633802414 -1.1486492157,1.71730279922,7.60991716385 -1.12667644024,1.7203168869,7.62250804901 -1.09970545769,1.71433246136,7.60508823395 -1.07573401928,1.71534729004,7.60966444016 -1.06274783611,1.71235466003,7.59946537018 -1.0377767086,1.71136975288,7.59704065323 -1.01380491257,1.71138453484,7.59962081909 -0.989832937717,1.71039915085,7.60020589828 -0.965860784054,1.70941388607,7.5987944603 -0.941889286041,1.71042871475,7.6033706665 -0.916917920113,1.70844364166,7.59794998169 -0.907930612564,1.71345019341,7.61875200272 -0.880959868431,1.70646560192,7.59633111954 -0.856988072395,1.70648038387,7.59791278839 -0.834016263485,1.70949494839,7.61049079895 -0.810043632984,1.70650923252,7.60308980942 -0.785072505474,1.70552420616,7.59766674042 -0.773086965084,1.70653176308,7.60245037079 -0.748115241528,1.70254647732,7.59003829956 -0.724143862724,1.703561306,7.59461355209 -0.701171636581,1.70557570457,7.60419940948 -0.676199555397,1.70059013367,7.58579397202 -0.653227984905,1.70460486412,7.60336828232 -0.628256618977,1.7016197443,7.59294891357 -0.616270720959,1.70062696934,7.59274101257 -0.592298865318,1.69964158535,7.59032678604 -0.568327069283,1.69965612888,7.58891153336 -0.545354425907,1.69967031479,7.59250688553 -0.520383179188,1.69668507576,7.58008670807 -0.497410982847,1.69969940186,7.5916724205 -0.473439127207,1.69871389866,7.58825826645 -0.460453867912,1.69572138786,7.57704353333 -0.436482459307,1.69573616982,7.58062124252 -0.412510454655,1.69375050068,7.57321023941 -0.388538688421,1.69276499748,7.56879472733 -0.365566521883,1.69577920437,7.58238172531 -0.34159475565,1.69479382038,7.57796669006 -0.317622959614,1.69280815125,7.57255172729 -0.305637031794,1.6928153038,7.56834554672 -0.281665831804,1.69483017921,7.57891893387 -0.257693707943,1.69084429741,7.5615105629 -0.234721377492,1.69285845757,7.57410144806 -0.209750577807,1.68887341022,7.55667304993 -0.186777964234,1.68988740444,7.55926990509 -0.174792230129,1.68989467621,7.56105899811 -0.150820687413,1.68990910053,7.55864048004 -0.1268491745,1.68892347813,7.55722045898 -0.103876575828,1.69093739986,7.56481695175 -0.0799049139023,1.68695187569,7.54939985275 -0.0559334941208,1.68896627426,7.55697917938 -0.0319619961083,1.68898081779,7.55655956268 -0.0199762135744,1.68598794937,7.54235029221 --0.0109864305705,1.67400681973,7.17879772186 --0.0329592376947,1.67102062702,7.16639184952 --0.0559309087694,1.67403483391,7.17596960068 --0.0669171586633,1.66904175282,7.1557636261 --0.0888900980353,1.67205548286,7.16736078262 --0.111861467361,1.66806983948,7.15093231201 --0.133834421635,1.67008340359,7.15953016281 --0.156805843115,1.66809773445,7.15110254288 --0.179777920246,1.67411184311,7.17168855667 --0.200751110911,1.66512513161,7.13728475571 --0.212736845016,1.67113244534,7.15807533264 --0.234709560871,1.67014598846,7.15366792679 --0.257680982351,1.66916036606,7.14824104309 --0.279653936625,1.67017388344,7.15083837509 --0.302625507116,1.67018806934,7.1494140625 --0.325597494841,1.67220211029,7.15799856186 --0.347569674253,1.6692160368,7.14258098602 --0.358556300402,1.67022264004,7.14638233185 --0.38052880764,1.66823625565,7.1389708519 --0.402501165867,1.66625010967,7.12955713272 --0.425473213196,1.66926395893,7.1371421814 --0.44844481349,1.66927814484,7.13571882248 --0.471417069435,1.67229199409,7.14530801773 --0.494388759136,1.67230606079,7.14488601685 --0.504375398159,1.66831254959,7.12868213654 --0.527347564697,1.67132639885,7.13627099991 --0.550319552422,1.67234027386,7.13985490799 --0.573291599751,1.67435419559,7.14343929291 --0.596264243126,1.67736768723,7.15503692627 --0.618236660957,1.67638123035,7.14662313461 --0.630221843719,1.67638862133,7.14540243149 --0.655193805695,1.68440246582,7.17599821091 --0.678166270256,1.68641614914,7.18159008026 --0.702137768269,1.68943023682,7.19017124176 --0.725109398365,1.68844413757,7.18574762344 --0.747081875801,1.6874576807,7.17733430862 --0.771053493023,1.69047176838,7.18591737747 --0.78004103899,1.68647766113,7.17072534561 --0.8030128479,1.68649160862,7.16830539703 --0.82798409462,1.69150567055,7.18388652802 --0.849956929684,1.69151902199,7.17948150635 --0.869930207729,1.68653202057,7.1570725441 --0.895900666714,1.69154655933,7.17464351654 --0.907887041569,1.69455325603,7.18244552612 --0.929859220982,1.69256687164,7.17202711105 --0.952831983566,1.69458019733,7.17662525177 --0.976803183556,1.69559419155,7.17819976807 --1.00077557564,1.69860768318,7.18879652023 --1.02074873447,1.69462072849,7.16738510132 --1.04571974277,1.69763493538,7.17495822906 --1.05970489979,1.70164203644,7.19075012207 --1.07967877388,1.69865465164,7.17535352707 --1.1026507616,1.69866836071,7.17193460464 --1.12962138653,1.70568275452,7.19251155853 --1.14959514141,1.70269536972,7.17711353302 --1.17356657982,1.70370912552,7.17869234085 --1.19853794575,1.70672309399,7.18627262115 --1.20852482319,1.70572948456,7.17807102203 --1.23249661922,1.70774304867,7.18165779114 --1.25446951389,1.70675611496,7.17525005341 --1.27744209766,1.70776951313,7.17484283447 --1.3024135828,1.71078324318,7.18242692947 --1.32438623905,1.7107963562,7.1750164032 --1.34835803509,1.71180987358,7.17660045624 --1.36034405231,1.71281671524,7.17839574814 --1.38131713867,1.71082961559,7.16598558426 --1.40628910065,1.71384310722,7.17457675934 --1.42926061153,1.71385681629,7.16714906693 --1.45423257351,1.71687018871,7.17574310303 --1.47320616245,1.71288275719,7.15333127975 --1.48919117451,1.71889007092,7.17412757874 --1.51016378403,1.71590316296,7.15970945358 --1.5361354351,1.72091674805,7.17130041122 --1.56110703945,1.72293031216,7.17588424683 --1.58507931232,1.72494351864,7.17747497559 --1.60505270958,1.72195613384,7.16106653214 --1.63102424145,1.72596979141,7.17065429688 --1.64500963688,1.72897672653,7.17944812775 --1.66698217392,1.72798979282,7.17003202438 --1.68895494938,1.72800266743,7.16161966324 --1.71192741394,1.72801566124,7.15821075439 --1.7348998785,1.72902882099,7.1537976265 --1.76087141037,1.73204231262,7.16138410568 --1.78484392166,1.73405539989,7.16298103333 --1.79682946205,1.73406219482,7.15976238251 --1.82380056381,1.73807585239,7.17034816742 --1.848772645,1.74108910561,7.17393875122 --1.86974596977,1.73910164833,7.16253232956 --1.89371871948,1.74111461639,7.16312837601 --1.9156910181,1.74012744427,7.15270900726 --1.94066286087,1.74214088917,7.15429401398 --1.95264935493,1.74314713478,7.1550951004 --1.97662162781,1.74516010284,7.15368413925 --1.99559545517,1.7411724329,7.13427305222 --2.02456617355,1.74718630314,7.14985895157 --2.04853868484,1.74819910526,7.14844989777 --2.07351088524,1.75121212006,7.15104436874 --2.08349728584,1.7492184639,7.14183235168 --2.1094686985,1.75223183632,7.14541578293 --2.13044190407,1.75124418736,7.13300418854 --2.15541410446,1.75325727463,7.13359117508 --2.18038630486,1.75527024269,7.13518381119 --2.20335912704,1.75628292561,7.1297750473 --2.22533226013,1.75529527664,7.12136745453 --2.24331688881,1.76130259037,7.1391620636 --2.26329016685,1.75931489468,7.12274694443 --2.28926229477,1.76232802868,7.12633705139 --2.30423736572,1.7563393116,7.09592914581 --2.33420777321,1.76235306263,7.11051368713 --2.3591799736,1.76336586475,7.11010169983 --2.38715195656,1.76837897301,7.12070178986 --2.39613842964,1.76638519764,7.10748243332 --2.42311048508,1.77039813995,7.11407899857 --2.44308423996,1.76841020584,7.09866809845 --2.47105574608,1.77242338657,7.10726118088 --2.49602842331,1.77443599701,7.10685443878 --2.51400184631,1.77044808865,7.08342933655 --2.53098726273,1.77545487881,7.09723424911 --2.55795931816,1.77946770191,7.10182523727 --2.58293151855,1.78048038483,7.10041570663 --2.60390496254,1.77949249744,7.08700037003 --2.63787484169,1.78850626945,7.11059617996 --2.6488506794,1.77951717377,7.0691742897 --2.67682290077,1.78352999687,7.07677268982 --2.68281126022,1.7805352211,7.05957317352 --2.71578121185,1.78754901886,7.07816076279 --2.73375535011,1.78456068039,7.05674409866 --2.76472640038,1.79057383537,7.0713429451 --2.78270053864,1.78758561611,7.04891967773 --2.80867314339,1.79059803486,7.05051898956 --2.82864665985,1.78860986233,7.03410053253 --2.84963083267,1.79561722279,7.05490207672 --2.86360692978,1.78962790966,7.02549552917 --2.89457798004,1.79564106464,7.03809022903 --2.92554879189,1.80165421963,7.04968070984 --2.94852161407,1.80166649818,7.04026222229 --2.97749328613,1.80567932129,7.04685497284 --2.98947000504,1.79968965054,7.01344966888 --3.00845432281,1.80469679832,7.02623987198 --3.02942848206,1.8037083149,7.0148396492 --3.05340123177,1.80472052097,7.00842618942 --3.06737732887,1.79973113537,6.98001909256 --3.10634589195,1.81074535847,7.00760602951 --3.12532043457,1.8087567091,6.99019670486 --3.14730381966,1.81476414204,7.00798225403 --3.1632797718,1.81177484989,6.9855837822 --3.19824957848,1.81878840923,7.00317335129 --3.21422481537,1.81479918957,6.9787607193 --3.24719572067,1.82181239128,6.99235630035 --3.26517033577,1.81882357597,6.97194099426 --3.29114317894,1.82183563709,6.96953201294 --3.29813170433,1.81984055042,6.95733976364 --3.33410096169,1.8278542757,6.97391796112 --3.35807418823,1.82886624336,6.96650600433 --3.38304781914,1.82987773418,6.96310806274 --3.40602135658,1.83088946342,6.95369768143 --3.42799496651,1.83090090752,6.94228744507 --3.45096850395,1.83091259003,6.93287754059 --3.46395468712,1.83191871643,6.93066883087 --3.49492669106,1.83793103695,6.93826723099 --3.5079035759,1.8329410553,6.90986442566 --3.53387618065,1.83495306969,6.90544891357 --3.56084871292,1.8379650116,6.90404176712 --3.59282016754,1.84397757053,6.91263914108 --3.59880852699,1.84098267555,6.89642858505 --3.62078261375,1.84099388123,6.88502073288 --3.64775562286,1.84400570393,6.88361787796 --3.66773033142,1.84301662445,6.86820888519 --3.69370293617,1.84502863884,6.86279058456 --3.71667718887,1.84603965282,6.85439300537 --3.7446501255,1.84905147552,6.85398674011 --3.75363779068,1.848056674,6.84478521347 --3.78061008453,1.8500688076,6.8403635025 --3.79858565331,1.84807920456,6.82195949554 --3.82655858994,1.85209095478,6.82155656815 --3.85453104973,1.85510277748,6.82014703751 --3.8715069294,1.85311293602,6.799741745 --3.89947986603,1.85612475872,6.79833364487 --3.92646217346,1.86413240433,6.81912136078 --3.93444037437,1.85714161396,6.78271245956 --3.96241378784,1.86115300655,6.78231525421 --3.98338866234,1.86116373539,6.76891088486 --4.01036119461,1.86317527294,6.76449728012 --4.03033685684,1.86318564415,6.75009870529 --4.05631971359,1.87019312382,6.76788473129 --4.06329870224,1.86320185661,6.73148393631 --4.09327125549,1.86721372604,6.73207330704 --4.12624311447,1.87322568893,6.73867321014 --4.14521837234,1.8712362051,6.72025632858 --4.17519044876,1.87624776363,6.72084999084 --4.20616292953,1.88025963306,6.72244024277 --4.20515346527,1.87526345253,6.69723796844 --4.23812532425,1.88027536869,6.70182847977 --4.26009988785,1.88028597832,6.68942308426 --4.29107284546,1.88529753685,6.69101762772 --4.30105161667,1.88030648232,6.66061878204 --4.33802223206,1.88731873035,6.67121315002 --4.3499994278,1.88332819939,6.64179468155 --4.36798524857,1.88633406162,6.6465959549 --4.39995718002,1.89134597778,6.64818239212 --4.4259314537,1.89435660839,6.64178037643 --4.45290517807,1.8963675499,6.63637447357 --4.47887945175,1.89837825298,6.62997436523 --4.50185394287,1.89938855171,6.61857032776 --4.52383852005,1.90439510345,6.62736034393 --4.54281377792,1.90340518951,6.60894680023 --4.56278944016,1.90341520309,6.59253787994 --4.59476232529,1.90842652321,6.59413576126 --4.60973930359,1.90543580055,6.57072925568 --4.60572195053,1.89544296265,6.52132892609 --4.62769699097,1.89545309544,6.50791978836 --4.62668800354,1.89045679569,6.48471879959 --4.64066505432,1.88746607304,6.4603099823 --4.66563987732,1.8894764185,6.45190811157 --4.68361663818,1.88848602772,6.4335026741 --4.71358919144,1.89249706268,6.43008422852 --4.72556781769,1.88950574398,6.40469026566 --4.74354457855,1.8885153532,6.38628435135 --4.76652860641,1.89352166653,6.39507436752 --4.78850460052,1.89453160763,6.38166618347 --4.80048274994,1.89054048061,6.35526037216 --4.82245826721,1.8915501833,6.34286165237 --4.85343170166,1.89656102657,6.34145593643 --4.86740970612,1.89356982708,6.31805276871 --4.88339614868,1.89657533169,6.31784915924 --4.90637111664,1.897585392,6.30443000793 --4.92134904861,1.89559423923,6.28303289413 --4.9593205452,1.90260565281,6.28962373734 --4.97929668427,1.90261518955,6.27321434021 --5.0042719841,1.90462493896,6.26381206512 --5.01625013351,1.90163350105,6.23841285706 --5.02523899078,1.90063810349,6.2292098999 --5.06321048737,1.90864944458,6.23479890823 --5.07718849182,1.90565812588,6.21139431 --5.10516309738,1.90966808796,6.20498847961 --5.12014055252,1.9076769352,6.18258047104 --5.15211439133,1.91268730164,6.18117856979 --5.15609455109,1.90569519997,6.14476203918 --5.18207931519,1.91270112991,6.15656805038 --5.20105600357,1.91271018982,6.13916254044 --5.20803642273,1.9077180624,6.10775756836 --5.18402338028,1.89072310925,6.03934192657 --5.19200325012,1.88573110104,6.0099401474 --5.21297979355,1.88674008846,5.9955368042 --5.24296331406,1.89474666119,6.01033163071 --5.26194047928,1.89475548267,5.99393320084 --5.30091238022,1.90176653862,5.99851799011 --5.32488822937,1.9037758112,5.98711442947 --5.34986448288,1.90678501129,5.97772169113 --5.380838871,1.91079497337,5.97331190109 --5.38681936264,1.90580248833,5.94191026688 --5.41480302811,1.91280865669,5.95269775391 --5.41178607941,1.90481543541,5.91129350662 --5.42076587677,1.9008231163,5.88389587402 --5.4537396431,1.90683317184,5.88148784637 --5.46771764755,1.90484142303,5.85807466507 --5.5046916008,1.91185164452,5.86067724228 --5.52366876602,1.91186022758,5.84327220917 --5.53565692902,1.91286468506,5.8370680809 --5.55263471603,1.91187310219,5.81766462326 --5.57761144638,1.91388189793,5.80726861954 --5.58159208298,1.90888917446,5.77385902405 --5.59357118607,1.90689718723,5.74844455719 --5.62554597855,1.91190683842,5.74403572083 --5.62853717804,1.90991020203,5.72984600067 --5.65551233292,1.91291952133,5.71942901611 --5.67249011993,1.91192770004,5.70002508163 --5.68746948242,1.91093552113,5.67963218689 --5.71244573593,1.91394424438,5.66822814941 --5.74442052841,1.91795372963,5.66281509399 --5.74340295792,1.91196036339,5.62540817261 --5.76438951492,1.91596531868,5.62820911407 --5.78836631775,1.917973876,5.6158080101 --5.81034326553,1.91898238659,5.60039520264 --5.81832408905,1.91598951817,5.57299947739 --5.83730268478,1.9159976244,5.55559682846 --5.86627864838,1.9200065136,5.54718923569 --5.86626052856,1.91401314735,5.51077461243 --5.88424777985,1.9170178175,5.51057958603 --5.91722297668,1.92302668095,5.50617742538 --5.90020942688,1.91103196144,5.45476770401 --5.73722791672,1.84902644157,5.26733064651 --5.5202589035,1.76901698112,5.0328950882 --5.51624250412,1.76302325726,4.99749803543 --5.52723073959,1.76402759552,4.99028253555 --5.52321434021,1.75703382492,4.95488214493 --5.5381937027,1.75704157352,4.93647909164 --5.60816001892,1.77505338192,4.96707868576 --5.62813854218,1.77606141567,4.95267391205 --5.68410873413,1.79007184505,4.97027635574 --5.63309335709,1.76407837868,4.87665367126 --5.74605178833,1.79709255695,4.94427204132 --5.78102684021,1.80310153961,4.94186353683 --5.82000112534,1.81111061573,4.94346523285 --5.86597394943,1.82112014294,4.95005846024 --5.88195323944,1.82112765312,4.93165874481 --5.89693260193,1.82113492489,4.91225624084 --5.94691324234,1.83414149284,4.93805742264 --6.21682214737,1.91217148304,5.09828710556 --6.25879573822,1.92018043995,5.09887933731 --6.26877737045,1.918186903,5.07448577881 --6.29775381088,1.92219495773,5.06407499313 --6.29573774338,1.91620099545,5.02866315842 --6.30472755432,1.91720438004,5.02047586441 --6.32870578766,1.91921198368,5.00606679916 --6.34168624878,1.91821885109,4.9826540947 --6.35766601562,1.91822576523,4.96224927902 --6.36264848709,1.91523194313,4.93385124207 --6.39662456512,1.92123997211,4.92744779587 --6.39561653137,1.91824281216,4.91024398804 --6.42259407043,1.92125046253,4.89783477783 --6.43357563019,1.92025709152,4.87342834473 --6.44755601883,1.9192636013,4.85203075409 --6.45853757858,1.91827011108,4.82762289047 --6.49851322174,1.92627799511,4.82623386383 --6.47350168228,1.91328251362,4.77482032776 --6.50048780441,1.91928696632,4.77861881256 --6.50147104263,1.91429281235,4.74721384048 --5.49565553665,1.597245574,3.9726421833 --5.5086350441,1.59725284576,3.95422434807 --5.50861883163,1.59325921535,3.92782688141 --6.53040027618,1.90531730652,4.64059257507 --6.59137153625,1.91932618618,4.6521897316 --6.58636474609,1.91532862186,4.63298940659 --6.61334323883,1.91933572292,4.62058925629 --6.60932826996,1.91334104538,4.58618402481 --6.64830446243,1.92034876347,4.58178186417 --6.6432890892,1.91435408592,4.54637050629 --6.66426897049,1.91636049747,4.5299744606 --6.67924976349,1.91636681557,4.50856637955 --6.52127170563,1.86636257172,4.38433170319 --6.41827583313,1.83136343956,4.28390979767 --6.41825914383,1.82736933231,4.25349712372 --6.42724132538,1.82537531853,4.23009681702 --6.42622566223,1.82138085365,4.19969034195 --6.46520233154,1.82938814163,4.19629526138 --6.49118900299,1.83439207077,4.19809007645 --6.51816797256,1.83839893341,4.18568277359 --6.5331492424,1.83940494061,4.16628646851 --6.54013156891,1.83741080761,4.14087724686 --6.54411506653,1.83441662788,4.11346626282 --6.557097435,1.83442246914,4.09307289124 --6.57707738876,1.83642888069,4.07566070557 --6.57406949997,1.83343160152,4.0584487915 --6.56505584717,1.82743668556,4.02404785156 --6.57203865051,1.82544231415,3.9996483326 --6.58602046967,1.82544827461,3.97924494743 --6.60900020599,1.82845461369,3.96383595467 --6.62998151779,1.83146047592,3.94844460487 --6.62996530533,1.82746589184,3.91903233528 --6.65595293045,1.83246958256,3.9198281765 --6.66493558884,1.83147501945,3.89642596245 --6.68591594696,1.83448112011,3.88002300262 --6.69689893723,1.83348679543,3.85761833191 --6.70088291168,1.83149206638,3.83121323586 --6.71386480331,1.83149778843,3.80980563164 --6.7258477211,1.83150327206,3.78840637207 --6.75083494186,1.83650660515,3.78820443153 --6.74082183838,1.83051156998,3.75379538536 --6.73780632019,1.82651662827,3.72338533401 --6.77078580856,1.83152258396,3.71399211884 --6.77876901627,1.83152806759,3.68958067894 --6.80275011063,1.8345335722,3.67518877983 --6.81173276901,1.8335391283,3.65076994896 --6.82972192764,1.83654201031,3.64657211304 --6.82770729065,1.8325470686,3.61716556549 --6.85768795013,1.83855271339,3.6057741642 --6.84767341614,1.83155751228,3.57135462761 --6.87465429306,1.83656299114,3.55795884132 --6.8826379776,1.83556807041,3.53456163406 --6.9086265564,1.84157109261,3.53436660767 --6.90861129761,1.83757603168,3.50595664978 --6.88759946823,1.8285806179,3.46653866768 --6.91758012772,1.83358609676,3.45413947105 --6.94056129456,1.83759129047,3.43773436546 --6.94154644012,1.83459615707,3.4103281498 --6.96952772141,1.83960127831,3.39693331718 --6.96652030945,1.83660364151,3.38173317909 --6.99550151825,1.84160888195,3.36833310127 --7.00848436356,1.84261393547,3.3459148407 --7.01746797562,1.84161889553,3.32251024246 --7.02945184708,1.84262347221,3.30111408234 --7.03343677521,1.84062826633,3.27571415901 --7.04941987991,1.84163320065,3.25530552864 --7.06540966034,1.8446354866,3.24910616875 --7.06039571762,1.84064018726,3.21869254112 --7.06338167191,1.83864474297,3.19329762459 --7.07436561584,1.83864951134,3.17089343071 --7.08934879303,1.83965408802,3.15049242973 --7.10933113098,1.84265887737,3.1310737133 --7.13531303406,1.84666359425,3.1156771183 --7.12730741501,1.84366571903,3.09847378731 --7.15528917313,1.84867024422,3.08408093452 --7.16027402878,1.84667479992,3.05867242813 --7.18425655365,1.85067915916,3.04227757454 --7.19324064255,1.84968364239,3.01785874367 --7.21522378922,1.85368800163,3.00046372414 --7.20921039581,1.84869229794,2.97106337547 --7.23220062256,1.85369455814,2.96686005592 --7.23218631744,1.85169887543,2.93945169449 --7.23317241669,1.84870314598,2.91305136681 --7.2411570549,1.84870743752,2.88863754272 --7.26813983917,1.85371148586,2.87324690819 --7.28112411499,1.85471570492,2.8508348465 --7.27111148834,1.8487200737,2.81942224503 --7.29210233688,1.85372185707,2.81523728371 --7.29808712006,1.85272610188,2.7898209095 --7.30907201767,1.85273003578,2.76742100716 --7.3340549469,1.85773396492,2.75001764297 --7.352039814,1.85973775387,2.73062515259 --7.35002613068,1.85674202442,2.70220851898 --7.36001825333,1.85874390602,2.69301462173 --7.37100315094,1.85874783993,2.66960144043 --7.37798881531,1.85875165462,2.64621019363 --7.39797258377,1.86175560951,2.62579417229 --7.39895915985,1.85975933075,2.59938955307 --7.4259428978,1.86476278305,2.58299899101 --7.43792819977,1.86476647854,2.56059789658 --7.42992210388,1.86176872253,2.54337859154 --7.44390726089,1.86377227306,2.52198195457 --7.47389030457,1.86877560616,2.50558066368 --7.46187925339,1.86377954483,2.47518014908 --7.47386407852,1.86478304863,2.45277953148 --7.48584938049,1.86578667164,2.42936396599 --7.51583337784,1.87178981304,2.4129679203 --7.50182819366,1.86679196358,2.39475917816 --7.50781488419,1.86579549313,2.3703584671 --7.51780080795,1.86679899693,2.34695363045 --7.53278589249,1.86880218983,2.32555603981 --7.56077051163,1.87380504608,2.3081600666 --7.56075763702,1.87180876732,2.28074216843 --7.56674432755,1.87181210518,2.2563419342 --7.58373594284,1.87481343746,2.24813961983 --7.58572292328,1.8738168478,2.22274279594 --7.58871030807,1.87282013893,2.19734048843 --7.61169481277,1.87682306767,2.17692708969 --7.61668205261,1.87582623959,2.15253210068 --7.6256685257,1.87682950497,2.12811923027 --7.64765405655,1.88083207607,2.10872912407 --7.63464927673,1.8758341074,2.09151983261 --7.63063669205,1.8728376627,2.06310009956 --7.64662313461,1.87584042549,2.04170489311 --7.67460823059,1.88084280491,2.02330827713 --7.68659448624,1.88184559345,1.99990081787 --7.69358158112,1.88184857368,1.97549831867 --7.69857501984,1.88284993172,1.96329081059 --7.7095618248,1.88385283947,1.93988835812 --7.71554946899,1.88385570049,1.91549003124 --7.72753620148,1.88485836983,1.89208447933 --7.74152326584,1.88686084747,1.86968755722 --7.75350999832,1.88886344433,1.84628307819 --7.758497715,1.88786625862,1.82087385654 --7.77849006653,1.89286696911,1.8126758337 --7.75848007202,1.88587081432,1.78126275539 --7.77946615219,1.88987290859,1.75985896587 --7.78345441818,1.88887560368,1.73445308208 --7.79144191742,1.88987827301,1.71004891396 --7.80042982101,1.89088058472,1.68665730953 --7.82141637802,1.89488244057,1.66525757313 --7.83940935135,1.89888298512,1.65605711937 --7.82239866257,1.89288675785,1.62564218044 --7.84938526154,1.89788818359,1.6052416563 --7.85637378693,1.8988904953,1.58084309101 --7.87136077881,1.9008923769,1.55743587017 --7.87734889984,1.90089476109,1.53202545643 --7.86533880234,1.89689815044,1.50362157822 --7.87733221054,1.89889872074,1.49342882633 --7.88032054901,1.89890134335,1.46701109409 --7.88530921936,1.89890348911,1.44261884689 --7.89429759979,1.89890563488,1.41821575165 --7.92228460312,1.90490663052,1.39680767059 --7.90827465057,1.89990997314,1.36840546131 --7.93226146698,1.90491104126,1.34599483013 --7.94425582886,1.90791153908,1.33580589294 --7.93324565887,1.90391457081,1.3073939085 --7.94023370743,1.90391659737,1.28198230267 --7.9622220993,1.90891754627,1.25958096981 --7.96021127701,1.90692007542,1.23317658901 --7.96720075607,1.90792191029,1.2087816 --7.9711894989,1.90792405605,1.18236231804 --7.98318386078,1.90992426872,1.17217731476 --7.9771733284,1.90792703629,1.14476513863 --8.00116157532,1.91292750835,1.12236511707 --7.99315166473,1.9099303484,1.09495687485 --8.01014041901,1.91293132305,1.07155823708 --8.02812957764,1.91593205929,1.04815912247 --8.02611923218,1.91493439674,1.02073776722 --8.01611423492,1.9119361639,1.00653660297 --8.05310249329,1.91993546486,0.986150145531 --8.0390920639,1.91593849659,0.957735300064 --8.04608154297,1.91693997383,0.932328224182 --8.07107162476,1.92193996906,0.90993732214 --8.08406066895,1.92494094372,0.884521663189 --8.07405090332,1.92094373703,0.857113540173 --8.07904529572,1.92194414139,0.84491622448 --8.08403587341,1.92294561863,0.819514274597 --8.09102535248,1.92394685745,0.794109642506 --8.1020154953,1.92594778538,0.768699526787 --8.10500526428,1.9259493351,0.743301451206 --8.09799575806,1.9229516983,0.7158857584 --8.1269903183,1.92994999886,0.705689072609 --8.11198139191,1.92595303059,0.678283512592 --8.1279706955,1.92895317078,0.653885364532 --8.12896156311,1.9289547205,0.627474665642 --8.12195301056,1.92595696449,0.601073086262 --8.12594223022,1.92695820332,0.574658215046 --8.15193271637,1.93195736408,0.551268577576 --8.11992931366,1.92396104336,0.535048902035 --8.12591934204,1.92496204376,0.509647965431 --8.14990997314,1.93096137047,0.485246628523 --8.13590049744,1.92696404457,0.457832962275 --8.15989112854,1.93196320534,0.433434456587 --8.15188217163,1.92996525764,0.407030582428 --8.13587379456,1.92496824265,0.379615813494 --8.14286899567,1.9269682169,0.367421030998 --8.17985916138,1.93496584892,0.34301841259 --8.1698513031,1.93196809292,0.316614806652 --8.16684246063,1.93196964264,0.290205955505 --8.17483329773,1.93297016621,0.263791888952 --8.18582439423,1.93497014046,0.238392919302 --8.17881584167,1.93297207355,0.211985781789 --8.19481182098,1.93697082996,0.199790820479 --8.2018032074,1.93897128105,0.173379078507 --8.17779445648,1.93197488785,0.14697599411 --8.17178630829,1.93097662926,0.120566412807 --8.18377780914,1.93297636509,0.0941538438201 --8.20076942444,1.93697547913,0.0687574893236 --8.20276165009,1.93797624111,0.0423474870622 --8.20575618744,1.93797636032,0.0291427746415 --8.20274829865,1.93697762489,0.00273312744685 --8.21273994446,1.93997728825,-0.0226602852345 --8.2267332077,1.94297659397,-0.0490677133203 --8.21172428131,1.93897902966,-0.0754790753126 --8.21771621704,1.94097924232,-0.101887345314 --8.23171234131,1.943977952,-0.114072516561 --8.22170543671,1.94197976589,-0.140484273434 --8.22369670868,1.94198024273,-0.166892498732 --8.23968982697,1.94597899914,-0.193294972181 --8.22768115997,1.94298112392,-0.219708651304 --8.2236738205,1.94198226929,-0.246119454503 --8.24566650391,1.94798004627,-0.272516310215 --8.24265861511,1.94698095322,-0.29892590642 --8.22965431213,1.94398295879,-0.312138199806 --8.25164794922,1.94898056984,-0.33853161335 --8.24164009094,1.94698226452,-0.36494654417 --8.25063228607,1.94898164272,-0.391347318888 --8.24862575531,1.94898223877,-0.417756527662 --8.25361824036,1.94998192787,-0.444159477949 --8.239610672,1.94698405266,-0.469564110041 --8.26760864258,1.95398056507,-0.483756840229 --8.24160003662,1.94798433781,-0.509173810482 --8.26259422302,1.95298171043,-0.536574721336 --8.27858734131,1.95797967911,-0.563979208469 --8.25557994843,1.95198297501,-0.589395582676 --8.24557209015,1.94998455048,-0.614798605442 --8.23456859589,1.94798624516,-0.628015816212 --8.23156070709,1.94698679447,-0.654426932335 --8.24155521393,1.94998550415,-0.680821061134 --8.22854804993,1.94698739052,-0.706230163574 --8.23054122925,1.94798719883,-0.733650326729 --8.24853515625,1.95298457146,-0.761046350002 --8.24252891541,1.95198535919,-0.787461459637 --8.24552536011,1.95298492908,-0.800659894943 --8.2415189743,1.95198535919,-0.82707208395 --8.25951385498,1.9569824934,-0.85446369648 --8.24750709534,1.95498418808,-0.87987357378 --8.24149990082,1.95398497581,-0.906289279461 --8.24749469757,1.95598375797,-0.932683765888 --8.24648761749,1.95598363876,-0.960105836391 --8.23548412323,1.95398533344,-0.972313463688 --8.25247955322,1.95898234844,-0.99970126152 --8.2524728775,1.95898199081,-1.02712059021 --8.25946903229,1.96198034286,-1.0545258522 --8.24646186829,1.95898211002,-1.07892477512 --8.25745582581,1.96297979355,-1.10733604431 --8.24945068359,1.96098065376,-1.13274049759 --8.26344871521,1.96497797966,-1.1479421854 --8.26344299316,1.96597754955,-1.17434418201 --8.26043701172,1.96597743034,-1.20075285435 --8.25743103027,1.96597731113,-1.22716140747 --8.25842666626,1.9669765234,-1.25457584858 --8.26442146301,1.96897470951,-1.2819776535 --8.27241706848,1.97197258472,-1.31038892269 --8.26941394806,1.97197282314,-1.32258105278 --8.25440788269,1.9689745903,-1.34800374508 --8.26940345764,1.97397112846,-1.37639558315 --8.26839923859,1.97397041321,-1.40381240845 --8.25039196014,1.9709726572,-1.42822933197 --8.25238704681,1.97197139263,-1.45563828945 --8.247382164,1.97197139263,-1.48103582859 --8.25438022614,1.97396957874,-1.49624598026 --8.27137756348,1.97996532917,-1.52564144135 --8.26137256622,1.97796618938,-1.5510519743 --8.24236488342,1.97396862507,-1.57547473907 --8.24536037445,1.97596693039,-1.60287857056 --8.23735523224,1.97496724129,-1.62828481197 --8.2443523407,1.97796475887,-1.65669047832 --8.24735069275,1.97996354103,-1.67089474201 --8.25834751129,1.98296010494,-1.70030081272 --8.24834156036,1.98196077347,-1.72571277618 --8.25433921814,1.98495817184,-1.75411844254 --8.25033378601,1.9849575758,-1.78052592278 --8.2393283844,1.98295843601,-1.80492651463 --8.24032497406,1.98495674133,-1.83233225346 --8.23132133484,1.98295772076,-1.84454488754 --8.2323179245,1.98495602608,-1.87195026875 --8.25531768799,1.99194991589,-1.90435254574 --8.23931121826,1.98895144463,-1.92877113819 --8.23930835724,1.99094986916,-1.95617806911 --8.23530387878,1.99094891548,-1.98258399963 --8.24630355835,1.99494588375,-1.99878406525 --8.23529911041,1.99294626713,-2.02420020103 --8.22929382324,1.99294579029,-2.0506131649 --8.22129058838,1.99294567108,-2.07601904869 --8.24429130554,1.99993908405,-2.10840916634 --8.24428749084,2.00093698502,-2.13682699203 --8.22228050232,1.99793982506,-2.15924263 --8.23128032684,1.99993693829,-2.1754450798 --8.24328041077,2.00493216515,-2.20584368706 --8.23927688599,2.00593113899,-2.23224616051 --8.23127269745,2.00493049622,-2.25866484642 --8.23927116394,2.00892686844,-2.28907632828 --8.23526859283,2.00992536545,-2.31547808647 --8.2212638855,2.00792622566,-2.33989262581 --8.23226451874,2.01192259789,-2.35709667206 --8.21325874329,2.00792479515,-2.3795030117 --8.21725654602,2.01092147827,-2.40891361237 --8.2272567749,2.01591682434,-2.43931126595 --8.21325206757,2.01391768456,-2.46372652054 --8.2112493515,2.01491546631,-2.492146492 --8.21724796295,2.01791167259,-2.52154421806 --8.21224594116,2.01791143417,-2.53374290466 --8.21824645996,2.02090740204,-2.56415367126 --8.22724628448,2.02590274811,-2.59556388855 --8.21224117279,2.02390360832,-2.61896920204 --8.2292432785,2.02989673615,-2.65236830711 --8.22724151611,2.03189444542,-2.68078374863 --8.21223735809,2.02989530563,-2.70520329475 --8.22323894501,2.03289103508,-2.72239565849 --8.22023677826,2.03488874435,-2.7508149147 --8.22323703766,2.03788495064,-2.78021788597 --8.22523593903,2.03988170624,-2.80962467194 --8.20923233032,2.03788256645,-2.83303499222 --8.20522975922,2.03888058662,-2.86044287682 --8.21723175049,2.04487419128,-2.89385437965 --8.22423267365,2.0478708744,-2.91004681587 --8.21523094177,2.04786992073,-2.93646383286 --8.22323226929,2.05186462402,-2.96786355972 --8.23523521423,2.05685806274,-3.00126886368 --8.22123146057,2.05585837364,-3.02568221092 --8.24723720551,2.06484794617,-3.0640809536 --8.22923278809,2.0628490448,-3.08750081062 --8.22223091125,2.0618493557,-3.09970712662 --8.24123573303,2.06884074211,-3.13509607315 --8.2342338562,2.06983876228,-3.1625123024 --8.22423171997,2.06983757019,-3.18893098831 --8.23223400116,2.07383155823,-3.2213332653 --8.22923374176,2.07582879066,-3.24973988533 --8.23423576355,2.07982325554,-3.28215646744 --8.23223590851,2.08082199097,-3.295347929 --8.21823310852,2.07982182503,-3.32077360153 --8.22723579407,2.08381533623,-3.35316419601 --8.24824237823,2.09280538559,-3.39156746864 --8.23123931885,2.09080600739,-3.4149813652 --8.23724269867,2.09480023384,-3.44738507271 --8.25224685669,2.09979367256,-3.46858453751 --8.24924755096,2.10179018974,-3.49799752235 --8.23524570465,2.10078954697,-3.52342009544 --8.23724746704,2.10478496552,-3.55381631851 --8.23424816132,2.10678124428,-3.58322715759 --8.22224617004,2.10578036308,-3.60863757133 --8.24325466156,2.11476922035,-3.64905047417 --8.24525547028,2.11676621437,-3.66525363922 --8.22025108337,2.11276912689,-3.68567490578 --8.25226211548,2.12475466728,-3.73006820679 --8.23225879669,2.12175583839,-3.75248527527 --8.2432641983,2.12774777412,-3.78788352013 --8.2462682724,2.13174176216,-3.82028961182 --8.22926616669,2.13074207306,-3.84370136261 --8.22026443481,2.12974214554,-3.85591721535 --8.22626972198,2.1337351799,-3.89032864571 --8.22027015686,2.1357319355,-3.91873645782 --8.23727893829,2.14372158051,-3.95712709427 --8.25728797913,2.15170955658,-3.99853467941 --8.24028682709,2.15070986748,-4.02194452286 --8.21228027344,2.14671301842,-4.04137468338 --8.20228099823,2.14671087265,-4.0687918663 --8.19828128815,2.14770960808,-4.08198738098 --8.17527675629,2.14471149445,-4.10341262817 --8.16027545929,2.14371109009,-4.12782478333 --8.14427375793,2.14271044731,-4.15224409103 --8.09926223755,2.13271975517,-4.16267824173 --8.09726524353,2.13571500778,-4.19308185577 --8.07826042175,2.13271832466,-4.2003030777 --8.06125831604,2.13171863556,-4.22371864319 --8.05225944519,2.13271570206,-4.25113105774 --8.03225708008,2.13071680069,-4.27355575562 --8.00725078583,2.12671947479,-4.29297685623 --8.01725959778,2.13271021843,-4.32937145233 --7.9822511673,2.12671637535,-4.34380054474 --7.96724796295,2.1247189045,-4.35201120377 --7.96125030518,2.12671494484,-4.38142871857 --7.94124698639,2.12471604347,-4.40284347534 --7.93825054169,2.12771105766,-4.43426370621 --7.91724729538,2.12471246719,-4.45467329025 --7.89324235916,2.1217148304,-4.47409296036 --7.87824201584,2.12171411514,-4.49851179123 --7.88224601746,2.12470960617,-4.51671266556 --7.86824607849,2.12470841408,-4.54213619232 --7.83623790741,2.11871385574,-4.55655479431 --7.83324193954,2.1217083931,-4.58797216415 --7.81423950195,2.12070941925,-4.60938405991 --7.80924320221,2.12270450592,-4.63980293274 --7.77223348618,2.11571192741,-4.6512260437 --7.75622987747,2.11371469498,-4.65843868256 --7.74122905731,2.1137137413,-4.68285989761 --7.73723316193,2.11570882797,-4.71327066422 --7.70622587204,2.11171412468,-4.72769069672 --7.69622707367,2.11271119118,-4.75511074066 --7.66121816635,2.10671782494,-4.76753950119 --7.64921855927,2.10671591759,-4.79295063019 --7.63521575928,2.10471820831,-4.8011636734 --7.61321210861,2.1027200222,-4.82058048248 --7.59821224213,2.10271883011,-4.84500408173 --7.57620811462,2.09972071648,-4.86442184448 --7.5542049408,2.09872245789,-4.88485383987 --7.54520750046,2.09971928596,-4.91125392914 --7.51119804382,2.09372591972,-4.92368507385 --7.50319766998,2.0937256813,-4.93590211868 --7.49019861221,2.09472417831,-4.96031093597 --7.46119165421,2.08972859383,-4.97574138641 --7.45419549942,2.09272456169,-5.00415086746 --7.42018604279,2.08673143387,-5.01557588577 --7.40518569946,2.08673048019,-5.03899049759 --7.38618373871,2.08573102951,-5.06142711639 --7.38418626785,2.08672833443,-5.07561779022 --7.36118268967,2.08473086357,-5.09403991699 --7.33717823029,2.08273339272,-5.11247205734 --7.3221783638,2.08273243904,-5.135887146 --7.28316640854,2.07474184036,-5.14331579208 --7.2741689682,2.07673811913,-5.17072916031 --7.25416660309,2.0757393837,-5.19115352631 --7.23115873337,2.07074546814,-5.19237041473 --7.22716474533,2.0747396946,-5.22378826141 --7.20416069031,2.07174229622,-5.24120378494 --7.16614866257,2.06575131416,-5.24863386154 --7.16415596008,2.06974458694,-5.28104448318 --7.13114690781,2.06475138664,-5.29248046875 --7.11914825439,2.0657491684,-5.31688404083 --7.11915254593,2.06774520874,-5.33409166336 --7.08714389801,2.06275177002,-5.34552097321 --7.06814193726,2.06175255775,-5.36594057083 --7.05014038086,2.06175279617,-5.38736486435 --7.03113889694,2.06075334549,-5.40778541565 --7.00713443756,2.05775618553,-5.4252166748 --6.99413156509,2.05675840378,-5.43242454529 --6.98613643646,2.0587542057,-5.46083831787 --6.93511629105,2.04876995087,-5.45727729797 --6.93512535095,2.05276155472,-5.49168729782 --6.91112041473,2.0507645607,-5.50811052322 --6.89011764526,2.04876661301,-5.52652978897 --6.87311697006,2.04876637459,-5.54794692993 --6.85611200333,2.04677033424,-5.5521607399 --6.84511518478,2.04876732826,-5.57857990265 --6.81310558319,2.04377412796,-5.58901309967 --6.78709983826,2.04077839851,-5.60343742371 --6.77710342407,2.0427749157,-5.62984657288 --6.76610708237,2.04477119446,-5.6572766304 --6.72909402847,2.03778100014,-5.66270542145 --6.71609163284,2.03678321838,-5.66991901398 --6.70109224319,2.03678226471,-5.69233083725 --6.67208433151,2.03278779984,-5.70476579666 --6.64908027649,2.03179073334,-5.72118902206 --6.63508176804,2.03178906441,-5.74460268021 --6.60907554626,2.0297935009,-5.75802278519 --6.59607839584,2.03079104424,-5.78344917297 --6.58407592773,2.02979278564,-5.79166698456 --6.56407403946,2.02879405022,-5.81008434296 --6.53206396103,2.02380156517,-5.81851053238 --6.50905942917,2.02180480957,-5.8339266777 --6.48505496979,2.01980805397,-5.85036468506 --6.46305131912,2.01881051064,-5.86678361893 --6.44905328751,2.01980876923,-5.89019823074 --6.43104696274,2.01681351662,-5.89342451096 --6.42105197906,2.01880979538,-5.91983127594 --6.40905570984,2.02080655098,-5.94625854492 --6.37704467773,2.01581454277,-5.95368289948 --6.35003805161,2.01381969452,-5.96611166 --6.34004306793,2.01581549644,-5.99352884293 --6.30703210831,2.01082372665,-6.00096750259 --6.30903959274,2.01481795311,-6.0201625824 --6.29604291916,2.01581549644,-6.04558801651 --6.27203798294,2.01481890678,-6.06000995636 --6.24703216553,2.01182317734,-6.07343196869 --6.2250289917,2.010825634,-6.08985614777 --6.20402669907,2.00982761383,-6.10728025436 --6.17601823807,2.00583386421,-6.11770439148 --6.17802667618,2.00982761383,-6.13790655136 --6.14801740646,2.00583457947,-6.14734268188 --6.13001680374,2.0058350563,-6.16675758362 --6.11802196503,2.00883150101,-6.19318246841 --6.10402441025,2.00982904434,-6.21760702133 --6.07601642609,2.00683546066,-6.22702360153 --6.06802463531,2.0108294487,-6.25744628906 --6.05001735687,2.00783467293,-6.25967311859 --6.02301073074,2.00484013557,-6.27110290527 --6.01601934433,2.00883388519,-6.30151176453 --5.98300743103,2.00384283066,-6.30694580078 --5.96800994873,2.00484108925,-6.3303694725 --5.94800806046,2.00484251976,-6.34778642654 --5.92600488663,2.00384497643,-6.36421585083 --5.91500377655,2.002846241,-6.37243032455 --5.89099836349,2.00085020065,-6.38585138321 --5.86599302292,1.99885439873,-6.39928436279 --5.84999513626,1.99985349178,-6.42069864273 --5.83299589157,2.00085282326,-6.44212388992 --5.81299448013,2.00085425377,-6.45954227448 --5.78998279572,1.99586319923,-6.45476198196 --5.76898097992,1.99586498737,-6.47219276428 --5.75198221207,1.99686431885,-6.49361944199 --5.71997022629,1.99187362194,-6.49804496765 --5.71197938919,1.99586713314,-6.52845811844 --5.68697404861,1.99387145042,-6.54189586639 --5.65896511078,1.99087846279,-6.54930830002 --5.65296840668,1.99187624454,-6.56352758408 --5.64297628403,1.99587070942,-6.59295129776 --5.61697006226,1.99387598038,-6.60438251495 --5.58195447922,1.98788750172,-6.60481071472 --5.56895971298,1.98988413811,-6.63022899628 --5.53995037079,1.98689174652,-6.6376581192 --5.52495384216,1.988889575,-6.66107988358 --5.50994873047,1.98689365387,-6.66429662704 --5.48494243622,1.98489844799,-6.67571973801 --5.46994638443,1.98689639568,-6.69914054871 --5.44994592667,1.98689746857,-6.71757316589 --5.42694234848,1.9859007597,-6.73200273514 --5.4009346962,1.98290657997,-6.74141979218 --5.38694000244,1.9859033823,-6.76684761047 --5.37393712997,1.98490619659,-6.7720618248 --5.34692811966,1.98191285133,-6.78048324585 --5.32492637634,1.98191523552,-6.79692268372 --5.3059258461,1.98191583157,-6.8153424263 --5.28992938995,1.98391413689,-6.83776473999 --5.26292133331,1.98092079163,-6.84618854523 --5.23991727829,1.97992408276,-6.86062145233 --5.23191928864,1.98092317581,-6.87183237076 --5.21392059326,1.98192322254,-6.89124917984 --5.18591165543,1.97893023491,-6.8996887207 --5.16491031647,1.97893214226,-6.91611623764 --5.13790225983,1.97693884373,-6.92454433441 --5.11389684677,1.9749430418,-6.9369726181 --5.10290575027,1.97893762589,-6.96538543701 --5.08890151978,1.97794103622,-6.96960687637 --5.06890106201,1.97794234753,-6.98703145981 --5.03989076614,1.9749506712,-6.99245977402 --5.02089166641,1.97595095634,-7.01189041138 --4.99388360977,1.97295761108,-7.02032232285 --4.97688627243,1.97495639324,-7.04174566269 --4.94887685776,1.97196424007,-7.04817390442 --4.93887662888,1.97196471691,-7.05739116669 --4.91487169266,1.97096931934,-7.06881380081 --4.88886451721,1.96897530556,-7.07824516296 --4.87086629868,1.96997475624,-7.09867191315 --4.84986543655,1.96997666359,-7.11510133743 --4.83186769485,1.971976161,-7.13552761078 --4.80385780334,1.96898424625,-7.14095115662 --4.79085445404,1.96798706055,-7.1461725235 --4.76584768295,1.96599245071,-7.15660238266 --4.75085401535,1.96898949146,-7.18102359772 --4.72584867477,1.96799445152,-7.19246339798 --4.70584774017,1.96799600124,-7.20887947083 --4.67783784866,1.96600413322,-7.21430778503 --4.65183019638,1.96401059628,-7.22273540497 --4.64483499527,1.96600818634,-7.23695611954 --4.62483453751,1.96600961685,-7.25337314606 --4.59382104874,1.96201992035,-7.255818367 --4.57482194901,1.96302044392,-7.2742395401 --4.54781293869,1.96102797985,-7.28066682816 --4.5328207016,1.96402406693,-7.30710124969 --4.51681232452,1.96203005314,-7.30631542206 --4.49481010437,1.96203303337,-7.32074356079 --4.47681331635,1.96403241158,-7.34116697311 --4.453810215,1.96303594112,-7.35459947586 --4.42880344391,1.96204161644,-7.36402702332 --4.40680170059,1.96204447746,-7.37845516205 --4.36276817322,1.95106816292,-7.35789871216 --4.35078001022,1.95606160164,-7.38832187653 --4.3608083725,1.96604335308,-7.42851495743 --4.32879304886,1.9620552063,-7.42795991898 --4.30378627777,1.9600610733,-7.43738889694 --4.28278541565,1.96106314659,-7.45281124115 --4.25277233124,1.95707333088,-7.45525550842 --4.23878145218,1.96106886864,-7.48166799545 --4.23379039764,1.96506357193,-7.50089406967 --4.18675088882,1.95209157467,-7.47233247757 --4.1707572937,1.95508897305,-7.4957485199 --4.15476465225,1.95908546448,-7.52118015289 --4.1277551651,1.95609354973,-7.52660942078 --4.11276388168,1.9600892067,-7.55303287506 --4.08675670624,1.95909583569,-7.56147241592 --4.06573915482,1.95310807228,-7.54968166351 --4.0347237587,1.94912004471,-7.54912519455 --4.02774572372,1.95710730553,-7.58954000473 --3.99973487854,1.95511615276,-7.59397935867 --3.97072148323,1.95112657547,-7.59541082382 --3.95573067665,1.95512211323,-7.62183046341 --3.92972302437,1.95412921906,-7.62926530838 --3.91471576691,1.95213472843,-7.62948560715 --3.89171242714,1.95213866234,-7.64191532135 --3.86870932579,1.95214259624,-7.65434551239 --3.84570598602,1.95214664936,-7.66677474976 --3.82971525192,1.95614254475,-7.69320487976 --3.79669475555,1.95015764236,-7.68664169312 --3.77168726921,1.94916439056,-7.69406509399 --3.75267291069,1.94517457485,-7.68628931046 --3.72566199303,1.94318366051,-7.6897149086 --3.70265984535,1.94318687916,-7.70416116714 --3.68566703796,1.94718420506,-7.72758245468 --3.65464925766,1.94219756126,-7.7240190506 --3.62663650513,1.93920779228,-7.72544765472 --3.60162949562,1.93821418285,-7.73388195038 --3.58862447739,1.93721830845,-7.73609256744 --3.5686275959,1.9392182827,-7.75552988052 --3.54863023758,1.941218853,-7.77395915985 --3.52462482452,1.94122445583,-7.78338575363 --3.48559093475,1.93224823475,-7.76182699203 --3.46659517288,1.93424749374,-7.78225517273 --3.44858026505,1.93025803566,-7.77346849442 --3.43159031868,1.93425357342,-7.80091333389 --3.40658164024,1.93326127529,-7.80633068085 --3.38357925415,1.93326497078,-7.81977081299 --3.35957407951,1.93327057362,-7.82920026779 --3.33055853844,1.93028259277,-7.82763385773 --3.31256556511,1.93328011036,-7.85106372833 --3.28455114365,1.93029141426,-7.85048961639 --3.26954388618,1.92929720879,-7.85072231293 --3.25756263733,1.93528747559,-7.88613510132 --3.21852731705,1.92631232738,-7.86359167099 --3.19652557373,1.92731547356,-7.87701749802 --3.18053793907,1.93230998516,-7.90544509888 --3.16054034233,1.93431067467,-7.92286396027 --3.15154528618,1.93630886078,-7.93608570099 --1.98918628693,1.91065585613,-8.2362909317 --1.97019886971,1.91565155983,-8.26271343231 --1.93615722656,1.90667951107,-8.23416042328 --1.91014432907,1.9056905508,-8.23459434509 --1.881118536,1.90070903301,-8.22202777863 --1.86710965633,1.89971578121,-8.2202539444 --1.84511137009,1.90171802044,-8.23568153381 --1.82311499119,1.90471923351,-8.25311470032 --1.79609775543,1.90173256397,-8.24955177307 --1.76907992363,1.899746418,-8.24498748779 --1.74608123302,1.90174901485,-8.26042938232 --1.72006893158,1.90075969696,-8.26187038422 --1.70505273342,1.89777088165,-8.2520866394 --1.6820524931,1.89977431297,-8.2655210495 --1.65403103828,1.89579033852,-8.25796508789 --1.63203406334,1.89879190922,-8.27439308167 --1.607026577,1.89879977703,-8.28083610535 --1.58101081848,1.89681231976,-8.27826499939 --1.56599354744,1.8938242197,-8.26748275757 --1.53696632385,1.88884353638,-8.25392913818 --1.51095032692,1.88685619831,-8.25136184692 --1.48593652248,1.88486754894,-8.25078487396 --1.46092820168,1.8848760128,-8.25622749329 --1.43692672253,1.8868803978,-8.26867485046 --1.41392409801,1.88888549805,-8.27909851074 --1.39991402626,1.88689303398,-8.27632808685 --1.37590551376,1.88690149784,-8.28075027466 --1.35290837288,1.88990354538,-8.29719161987 --1.32890701294,1.89190804958,-8.30963611603 --1.30389630795,1.89191794395,-8.31206989288 --1.27586829662,1.88693773746,-8.29750728607 --1.253875494,1.89093732834,-8.31793880463 --1.23684167862,1.88295841217,-8.2911567688 --1.2158588171,1.88995242119,-8.32159805298 --1.18883669376,1.88696885109,-8.31303882599 --1.16483485699,1.88897371292,-8.32447910309 --1.13881409168,1.88598930836,-8.31690597534 --1.11280250549,1.88499975204,-8.31935787201 --1.0867818594,1.88301539421,-8.31178760529 --1.07276535034,1.88002669811,-8.30200576782 --1.04976773262,1.88302922249,-8.31743907928 --1.02374851704,1.88004374504,-8.31187438965 --0.999750435352,1.88304674625,-8.3273229599 --0.973730623722,1.88106191158,-8.32075786591 --0.947710514069,1.87807714939,-8.31419277191 --0.922699689865,1.87808728218,-8.31663131714 --0.910700082779,1.87908887863,-8.32385444641 --0.884680211544,1.87710416317,-8.31729125977 --0.856640636921,1.86913025379,-8.29172706604 --0.833646178246,1.87313127518,-8.31016254425 --0.807627916336,1.87114560604,-8.30560684204 --0.781598031521,1.86616623402,-8.28903007507 --0.758609592915,1.872164011,-8.31347560883 --0.745599985123,1.87117147446,-8.31069660187 --0.720587909222,1.87018215656,-8.31213474274 --0.695571243763,1.86919558048,-8.30856609344 --0.670558273792,1.86820697784,-8.30900382996 --0.644539833069,1.86622142792,-8.30445194244 --0.621544778347,1.87022280693,-8.32188034058 --0.606509506702,1.86324465275,-8.29410266876 --0.582503020763,1.86425232887,-8.30053329468 --0.557490170002,1.86426365376,-8.30097293854 --0.532475233078,1.86327624321,-8.29940986633 --0.506443738937,1.85829794407,-8.28184509277 --0.482460379601,1.86529326439,-8.31130313873 --0.457438319921,1.86230957508,-8.30273246765 --0.432415276766,1.85932636261,-8.29316234589 --0.421445906162,1.86831200123,-8.32939434052 --0.394393563271,1.85834503174,-8.29183101654 --0.370387136936,1.85935282707,-8.29826068878 --0.344352483749,1.85437631607,-8.27770137787 --0.320349156857,1.8563824892,-8.28713417053 --0.294309049845,1.84940886497,-8.26157474518 --0.28230881691,1.85041117668,-8.26779174805 --0.2572876513,1.84842717648,-8.26023006439 --0.232282862067,1.85043442249,-8.26867961884 --0.208271369338,1.85044503212,-8.27010726929 --0.183266654611,1.85245227814,-8.27855587006 --0.158242240548,1.84947001934,-8.267993927 --0.134242221713,1.85247457027,-8.28042602539 --0.121205374599,1.84549689293,-8.2516450882 --0.0962171107531,1.85049521923,-8.27609920502 --0.0721827596426,1.84551823139,-8.25551986694 --0.0471761338413,1.8475266695,-8.261967659 --0.0221589095891,1.84654057026,-8.25841140747 -0.00184318819083,1.84854638577,-8.26884174347 -0.00111728999764,1.82742357254,-7.40018033981 -0.0131183853373,1.82642054558,-7.39537239075 -0.0381450876594,1.82942736149,-7.40876722336 -0.0631948709488,1.83844649792,-7.44415378571 -0.0871707499027,1.82942652702,-7.40954637527 -0.112185060978,1.83042657375,-7.41094303131 -0.136185154319,1.82741940022,-7.39933013916 -0.160197734833,1.82741904259,-7.39971208572 -0.173205539584,1.82741940022,-7.40091896057 -0.197213992476,1.82641685009,-7.39730358124 -0.221219569445,1.82541251183,-7.39068984985 -0.247260987759,1.83242714405,-7.41808509827 -0.270244330168,1.82541131973,-7.39047193527 -0.29525026679,1.82340717316,-7.3838763237 -0.32027181983,1.82641124725,-7.39226722717 -0.331261336803,1.82240223885,-7.37645673752 -0.355253666639,1.81739103794,-7.35685873032 -0.378246814013,1.81338059902,-7.33824586868 -0.404278874397,1.818390131,-7.35664367676 -0.426264226437,1.8113758564,-7.33102464676 -0.452292203903,1.81538319588,-7.34542560577 -0.475279420614,1.80936956406,-7.32082462311 -0.487292855978,1.8113732338,-7.32800865173 -0.511294841766,1.80936729908,-7.31740760803 -0.536322176456,1.81337451935,-7.3317899704 -0.561339378357,1.81437659264,-7.33618545532 -0.585346281528,1.81337320805,-7.33057832718 -0.608339905739,1.80936312675,-7.31197500229 -0.632344841957,1.80735862255,-7.30437326431 -0.643340110779,1.80535280704,-7.29356718063 -0.666342735291,1.80334758759,-7.28395366669 -0.691358089447,1.80434846878,-7.28635263443 -0.714360773563,1.80234324932,-7.27674007416 -0.737357795238,1.79933488369,-7.26113891602 -0.759352326393,1.79532551765,-7.24352741241 -0.771355807781,1.7943239212,-7.24072742462 -0.794358670712,1.79231882095,-7.23111820221 -0.821391761303,1.7983288765,-7.25051641464 -0.843390285969,1.79532170296,-7.23689985275 -0.867396652699,1.79431807995,-7.23030185699 -0.890400528908,1.79231357574,-7.22169303894 -0.915418863297,1.79431629181,-7.22708559036 -0.927420675755,1.79331386089,-7.2222905159 -0.949418544769,1.79030632973,-7.20767974854 -0.972419857979,1.78830039501,-7.19607925415 -0.997441112995,1.79130470753,-7.20446443558 -1.018430233,1.78629267216,-7.18086242676 -1.04243957996,1.78629088402,-7.17726039886 -1.06645178795,1.7862906456,-7.17665195465 -1.07744944096,1.7842861414,-7.16785335541 -1.10045480728,1.78328239918,-7.16024684906 -1.12345921993,1.78227818012,-7.15164279938 -1.145388484,1.76023352146,-7.062251091 -1.1683986187,1.76023244858,-7.05963611603 -1.19040000439,1.7582269907,-7.04803133011 -1.20039391518,1.75522077084,-7.03523349762 -1.22440373898,1.75521922112,-7.03163957596 -1.24841725826,1.75621962547,-7.03203296661 -1.26941478252,1.75421226025,-7.01642560959 -1.29242229462,1.75320982933,-7.01082229614 -1.3144248724,1.7512049675,-7.00021886826 -1.3384411335,1.75320696831,-7.00360202789 -1.34944200516,1.75220441818,-6.99780225754 -1.37043976784,1.74919712543,-6.98220062256 -1.39244151115,1.74719190598,-6.97060251236 -1.4184678793,1.75219881535,-6.98398303986 -1.43946218491,1.74818968773,-6.96439743042 -1.46247172356,1.74818837643,-6.96078872681 -1.48749279976,1.75119292736,-6.96916913986 -1.49648296833,1.74718511105,-6.95237874985 -1.51949167252,1.74718332291,-6.94777345657 -1.54149484634,1.74617874622,-6.93717479706 -1.56249642372,1.74417376518,-6.92556476593 -1.58550524712,1.74417209625,-6.92096042633 -1.61152505875,1.74717569351,-6.92736196518 -1.61851108074,1.74216604233,-6.90655994415 -1.64252650738,1.74416768551,-6.90894412994 -1.6675413847,1.74516904354,-6.91034841537 -1.69054937363,1.74516701698,-6.90474796295 -1.7115521431,1.74416255951,-6.89413642883 -1.73456263542,1.74416184425,-6.89152383804 -1.75757074356,1.7441598177,-6.88592433929 -1.76455545425,1.73914957047,-6.86313819885 -1.78957307339,1.74115228653,-6.86752796173 -1.81760239601,1.74716055393,-6.88391208649 -1.84161269665,1.74815940857,-6.88031864166 -1.8606095314,1.74515247345,-6.86370420456 -1.8785982132,1.73914134502,-6.83811616898 -1.91064035892,1.74915552139,-6.8674993515 -1.92967152596,1.7561674118,-6.89268922806 -1.94364917278,1.74815130234,-6.85608911514 -1.96063530445,1.74213898182,-6.82750272751 -1.9856518507,1.74414122105,-6.83089208603 -2.00364518166,1.74013268948,-6.81028604507 -2.02966403961,1.7431358099,-6.81568145752 -2.0526714325,1.74313366413,-6.80908727646 -2.06568050385,1.74513506889,-6.8112859726 -2.08969497681,1.74713647366,-6.81266689301 -2.11270475388,1.74713551998,-6.80905723572 -2.13972640038,1.75113999844,-6.81744813919 -2.15872144699,1.74813210964,-6.79785680771 -2.17972373962,1.74612772465,-6.78625679016 -2.20875048637,1.75213456154,-6.79965019226 -2.22878026962,1.75914561749,-6.82384061813 -2.24677491188,1.75513780117,-6.8042345047 -3.40715956688,1.77904820442,-6.45752859116 -3.43617796898,1.78405106068,-6.46192169189 -3.44215488434,1.77503681183,-6.42034721375 -3.45815038681,1.77203035355,-6.39975214005 -3.48015666008,1.7720284462,-6.39114904404 -3.4871532917,1.77102470398,-6.37934970856 -3.52017784119,1.77703022957,-6.39074230194 -3.54218387604,1.77702832222,-6.38213825226 -3.5581805706,1.7750223875,-6.3625369072 -3.58319115639,1.77702200413,-6.35794210434 -3.61020493507,1.78002309799,-6.35734272003 -3.63020777702,1.7790197134,-6.34474182129 -3.64521789551,1.78202152252,-6.34793281555 -3.65720677376,1.77701258659,-6.3193526268 -3.68021559715,1.77801191807,-6.31373643875 -3.70622777939,1.78101217747,-6.31113624573 -3.72923493385,1.78201055527,-6.30254364014 -3.75023984909,1.78200805187,-6.29194021225 -3.77625274658,1.78500878811,-6.29032850266 -3.7932639122,1.78801107407,-6.2945356369 -3.8002474308,1.78100001812,-6.25994348526 -3.83627462387,1.78800654411,-6.27433109283 -3.84926724434,1.78499925137,-6.24973678589 -3.88228917122,1.79000353813,-6.25813245773 -3.89227676392,1.78499436378,-6.22755098343 -3.90628480911,1.78699541092,-6.22873973846 -3.93129467964,1.78899478912,-6.22314548492 -3.95830845833,1.7919960022,-6.22253274918 -3.98231720924,1.79399502277,-6.21593141556 -3.99631166458,1.79098880291,-6.19333744049 -4.02432584763,1.79398989677,-6.19273662567 -4.03731918335,1.79098331928,-6.16913890839 -4.05332899094,1.79298484325,-6.17134237289 -4.06231689453,1.78797590733,-6.14075660706 -4.09734106064,1.79498076439,-6.1511464119 -4.11133575439,1.79197466373,-6.12855625153 -4.13834810257,1.79497528076,-6.1259560585 -4.16235685349,1.79697442055,-6.11935138702 -4.18135929108,1.79597139359,-6.10574531555 -4.19035959244,1.79596924782,-6.0969543457 -4.21136331558,1.79596662521,-6.08436584473 -4.23136711121,1.7959638834,-6.07176351547 -4.26238489151,1.80096650124,-6.07515478134 -4.27037239075,1.79495763779,-6.04357481003 -4.29938697815,1.79895925522,-6.04396677017 -4.3243970871,1.80195891857,-6.03836202621 -4.32638883591,1.79795396328,-6.02056646347 -4.34338855743,1.79694974422,-6.00297307968 -4.372402668,1.80095112324,-6.00237178802 -4.38539743423,1.79794514179,-5.97878456116 -4.41541337967,1.80194699764,-5.98017501831 -4.43942213058,1.80394613743,-5.97257423401 -4.45642185211,1.80294215679,-5.95498085022 -4.46642303467,1.80294060707,-5.94719409943 -4.48342323303,1.80193686485,-5.93059206009 -4.50743198395,1.80393600464,-5.92298936844 -4.52843666077,1.80393385887,-5.91138887405 -4.54944086075,1.80493164062,-5.89879751205 -4.57244825363,1.80593025684,-5.88920164108 -4.589448452,1.80492663383,-5.87259912491 -4.60045099258,1.80492568016,-5.86680555344 -4.6214556694,1.80592358112,-5.8542137146 -4.64346218109,1.80692207813,-5.84460306168 -4.67047357559,1.80992233753,-5.84000396729 -4.68647241592,1.80891811848,-5.82042074203 -4.71748828888,1.81392002106,-5.82180738449 -4.7104716301,1.80691218376,-5.79302597046 -4.73848390579,1.80991280079,-5.78942680359 -4.76048994064,1.81191146374,-5.77981424332 -4.80552005768,1.8219178915,-5.79621315002 -4.81851673126,1.81991314888,-5.77461290359 -4.84953212738,1.82391476631,-5.77500343323 -4.87654209137,1.82691442966,-5.76841688156 -4.88454198837,1.82691264153,-5.75961399078 -4.92656898499,1.83591806889,-5.77299594879 -4.93255710602,1.83091056347,-5.74141693115 -4.96157026291,1.83491134644,-5.73880767822 -4.97856998444,1.83390772343,-5.72022438049 -4.99757242203,1.8339048624,-5.70463323593 -4.91747665405,1.7948693037,-5.57212018967 -4.83338594437,1.75883746147,-5.45538759232 -4.79132986069,1.73581552505,-5.36984348297 -4.80332708359,1.73381137848,-5.3472661972 -4.81432437897,1.73080730438,-5.32566595078 -4.83032512665,1.72980427742,-5.30709457397 -4.84332513809,1.72880125046,-5.28848552704 -4.8533205986,1.72579693794,-5.26489925385 -4.86132192612,1.7247954607,-5.25610876083 -4.8633108139,1.71978878975,-5.22352933884 -4.89232492447,1.72379052639,-5.22192287445 -4.88930892944,1.71578240395,-5.1833562851 -4.89730405807,1.71277785301,-5.15876150131 -4.90529918671,1.70877337456,-5.13318157196 -4.90729522705,1.70677053928,-5.11839103699 -4.91629123688,1.70376646519,-5.0948009491 -4.92929124832,1.70276355743,-5.07521295547 -4.94529342651,1.70176148415,-5.0586271286 -4.94328069687,1.69475471973,-5.02403926849 -4.96428823471,1.69675421715,-5.01344203949 -4.97828912735,1.69575178623,-4.99485731125 -4.98028564453,1.69274914265,-4.98007202148 -4.99628829956,1.69274747372,-4.96447563171 -5.00328397751,1.68974351883,-4.93988132477 -5.01628446579,1.68774092197,-4.92029953003 -5.02528238297,1.68573760986,-4.89770746231 -5.04328727722,1.6867364645,-4.88411140442 -5.04627990723,1.68173158169,-4.85453748703 -5.06429004669,1.6847332716,-4.85673379898 -5.06127738953,1.67772698402,-4.82116651535 -5.08228492737,1.67972695827,-4.81155633926 -5.09028244019,1.67672359943,-4.78797054291 -5.10228252411,1.67572128773,-4.76838159561 -5.11128091812,1.67271828651,-4.74579668045 -5.13529109955,1.67571890354,-4.73819589615 -5.12828111649,1.67071473598,-4.71541690826 -5.14228343964,1.67071306705,-4.69782829285 -5.1542840004,1.66871082783,-4.67824316025 -5.16528463364,1.66770875454,-4.65864562988 -5.17928695679,1.66670703888,-4.64105844498 -5.19629192352,1.66770625114,-4.62646627426 -5.18628025055,1.66070187092,-4.60168743134 -5.20028305054,1.66070044041,-4.5841012001 -5.21528673172,1.66069924831,-4.5685005188 -5.22028255463,1.65669596195,-4.5429186821 -5.23528671265,1.65669488907,-4.52731847763 -5.24528646469,1.65469276905,-4.50574302673 -5.25128364563,1.65268993378,-4.48116207123 -5.26929330826,1.65569138527,-4.48236083984 -5.26828575134,1.65068721771,-4.45178318024 -5.27428293228,1.64768481255,-4.42819166183 -5.29128837585,1.6476842165,-4.41360378265 -5.30128908157,1.64668238163,-4.39301729202 -5.30828762054,1.64368009567,-4.37042665482 -5.32529306412,1.64467966557,-4.35583877563 -5.3132815361,1.63767576218,-4.33105754852 -5.32628440857,1.63767468929,-4.31346702576 -5.34529161453,1.63867461681,-4.30087423325 -5.35529279709,1.63767313957,-4.28029298782 -5.35328578949,1.63266956806,-4.24971961975 -5.38129901886,1.63667118549,-4.2451133728 -5.38729810715,1.63466918468,-4.22251749039 -5.39029693604,1.63266813755,-4.20974206924 -5.41030454636,1.63466846943,-4.19814538956 -5.41130018234,1.6306656599,-4.17056846619 -5.42530441284,1.63066494465,-4.1539773941 -5.43430519104,1.6286636591,-4.1333899498 -5.43630170822,1.62466144562,-4.10779905319 -5.45430898666,1.62666153908,-4.09420919418 -5.45530700684,1.62466037273,-4.08141469955 -5.46630954742,1.62365937233,-4.06183719635 -5.4693069458,1.620657444,-4.03626155853 -5.50232315063,1.62665975094,-4.03564119339 -5.49331378937,1.61965620518,-4.00107097626 -5.50831890106,1.61965596676,-3.98449397087 -5.52332401276,1.62065577507,-3.96890115738 -5.52232122421,1.617654562,-3.95510363579 -5.52932214737,1.61565351486,-3.93351650238 -5.54232597351,1.61565315723,-3.91593313217 -5.55232858658,1.61465251446,-3.89634871483 -5.56233072281,1.61365187168,-3.87774944305 -5.57933759689,1.61465203762,-3.86217904091 -5.58433914185,1.6146517992,-3.85238695145 -5.5733294487,1.60664880276,-3.81879854202 -5.58833503723,1.60764873028,-3.80222344398 -5.60434150696,1.60864901543,-3.78762722015 -5.60133695602,1.60364711285,-3.7590508461 -5.62434720993,1.60664820671,-3.74945020676 -5.62934684753,1.60464727879,-3.72686481476 -5.62734508514,1.60264635086,-3.71208095551 -5.64235067368,1.60264658928,-3.69649100304 -5.64134788513,1.59864532948,-3.66990971565 -5.65235185623,1.59864521027,-3.65132665634 -5.67336082458,1.60064613819,-3.63973450661 -5.67435932159,1.59764504433,-3.61416101456 -5.68136119843,1.59564471245,-3.59357023239 -5.69436693192,1.59764540195,-3.5897667408 -5.69336509705,1.59364438057,-3.56319212914 -5.70336866379,1.59364438057,-3.54460072517 -5.72037553787,1.59464502335,-3.53001475334 -5.72237539291,1.59164452553,-3.50642514229 -5.73838186264,1.5926450491,-3.4908452034 -5.74538516998,1.59364533424,-3.48304486275 -5.73938083649,1.58764410019,-3.45347690582 -5.74638319016,1.58664417267,-3.43289089203 -5.76239013672,1.58764481544,-3.41829490662 -5.76639127731,1.58564460278,-3.39571356773 -5.76338911057,1.58164393902,-3.36814832687 -5.77739524841,1.58264458179,-3.35254979134 -5.77639436722,1.58064436913,-3.33975672722 -5.78940010071,1.58064496517,-3.32316565514 -5.79740333557,1.57964527607,-3.30259299278 -5.80240535736,1.57764542103,-3.28100967407 -5.81541156769,1.57864618301,-3.26441860199 -5.81140899658,1.57364583015,-3.23783588409 -5.82441520691,1.57464647293,-3.22026228905 -5.83441972733,1.57564711571,-3.2144575119 -5.84442424774,1.57564783096,-3.19587230682 -5.83842182159,1.5706474781,-3.16730952263 -5.84342432022,1.56964790821,-3.14671373367 -5.86343336105,1.57164919376,-3.13411998749 -5.86843633652,1.57064974308,-3.11254167557 -5.86443471909,1.56564986706,-3.08596920967 -5.8824429512,1.56965076923,-3.0851495266 -5.87944221497,1.56565105915,-3.05858755112 -5.8884472847,1.56565189362,-3.03999638557 -5.88844823837,1.56265234947,-3.01641201973 -5.88944959641,1.55965292454,-2.9928381443 -5.91646146774,1.5646545887,-2.9832508564 -5.91646289825,1.56165516376,-2.95966887474 -5.91446256638,1.55965542793,-2.94687843323 -5.92146682739,1.55865645409,-2.92728972435 -5.92246818542,1.55565726757,-2.90371990204 -5.9304728508,1.55565822124,-2.88512301445 -5.93247509003,1.55365908146,-2.86254572868 -5.94348144531,1.55366027355,-2.84495806694 -5.94548273087,1.55266094208,-2.83416986465 -5.94648551941,1.5506619215,-2.81158638 -5.96949577332,1.5536634922,-2.7999932766 -5.97449970245,1.55266475677,-2.77842617035 -5.96849918365,1.54866552353,-2.75284004211 -5.98250627518,1.54966700077,-2.73724198341 -5.97150468826,1.54366791248,-2.7076895237 -5.97450733185,1.54366862774,-2.69789385796 -5.99551677704,1.54667031765,-2.6852991581 -5.98451519012,1.54067146778,-2.65673303604 -5.98851919174,1.53967285156,-2.63614535332 -5.99552440643,1.53867423534,-2.61656427383 -6.01153230667,1.54067599773,-2.60196399689 -6.00953435898,1.53767740726,-2.57838463783 -6.01753854752,1.53867816925,-2.57059335709 -6.01253986359,1.53567969799,-2.54601049423 -6.02554750443,1.53668141365,-2.5284409523 -6.03555345535,1.53668308258,-2.51084804535 -6.03955793381,1.53568482399,-2.4902639389 -6.02955770493,1.53068637848,-2.46368455887 -6.05456924438,1.53468835354,-2.45209550858 -6.04956912994,1.53268921375,-2.43831586838 -6.05657482147,1.53169107437,-2.41873812675 -6.06858205795,1.53269290924,-2.40214204788 -6.06958580017,1.53069472313,-2.38055706024 -6.0765914917,1.53069663048,-2.36097979546 -6.0865983963,1.53069853783,-2.34338760376 -6.07959794998,1.52769970894,-2.32861638069 -6.08560371399,1.52770161629,-2.31001400948 -6.09561014175,1.52770364285,-2.29144096375 -6.09861516953,1.52670562267,-2.27085518837 -6.10462093353,1.52570772171,-2.25127291679 -6.11562824249,1.526709795,-2.23368763924 -6.13163709641,1.52871179581,-2.21809887886 -6.12463712692,1.52571296692,-2.20431423187 -6.13164329529,1.5257152319,-2.18473887444 -6.13564825058,1.52471745014,-2.16514348984 -6.13865375519,1.5237197876,-2.14357972145 -6.14966106415,1.5247220993,-2.12599372864 -6.14066314697,1.52072453499,-2.10140872002 -6.15667200089,1.52272677422,-2.08581805229 -6.15867471695,1.52172791958,-2.07504057884 -6.16268014908,1.52073025703,-2.05544710159 -6.16468572617,1.51973295212,-2.03387975693 -6.18069458008,1.52173507214,-2.01828718185 -6.17669868469,1.5197378397,-1.99570155144 -6.17270231247,1.51674056053,-1.97213685513 -6.18571043015,1.51774299145,-1.9555439949 -6.17771100998,1.51474452019,-1.94176411629 -6.1997218132,1.51874661446,-1.92816793919 -6.20272779465,1.51774942875,-1.90759038925 -6.18572854996,1.51175272465,-1.88002896309 -6.20673894882,1.51575481892,-1.86642456055 -6.22474861145,1.51875722408,-1.85083937645 -6.2017455101,1.51175940037,-1.83305382729 -6.20875263214,1.51176214218,-1.81348288059 -6.21676015854,1.511764884,-1.79489839077 -6.20676326752,1.50776827335,-1.77032840252 -6.21477079391,1.50777113438,-1.75174450874 -6.24178266525,1.51377308369,-1.73914825916 -6.23978805542,1.51177620888,-1.71756637096 -6.24379205704,1.5117777586,-1.70778357983 -6.24579763412,1.51078057289,-1.68818545341 -6.2498049736,1.50978386402,-1.66761827469 -6.25381135941,1.50978684425,-1.64803147316 -6.25081682205,1.50679016113,-1.62644815445 -6.25982475281,1.5077931881,-1.607868433 -6.25482940674,1.50479674339,-1.5852959156 -6.2708363533,1.50879764557,-1.57949531078 -6.26384067535,1.50480139256,-1.55691385269 -6.27084875107,1.50580441952,-1.53734374046 -6.26885461807,1.50380790234,-1.51674950123 -6.2838640213,1.50581073761,-1.49917888641 -6.26486682892,1.4998152256,-1.47360336781 -6.2838768959,1.50381779671,-1.45801138878 -6.28087902069,1.5018196106,-1.44721603394 -6.27688550949,1.49982368946,-1.42465519905 -6.28389358521,1.49982690811,-1.40606641769 -6.29090166092,1.50083005428,-1.38747704029 -6.28990840912,1.49883389473,-1.36591207981 -6.29891633987,1.4998370409,-1.34831166267 -6.28791809082,1.49683964252,-1.33454358578 -6.29692649841,1.49784266949,-1.31694340706 -6.30893564224,1.49984586239,-1.29935538769 -6.3119430542,1.49884963036,-1.27878916264 -6.30394887924,1.49585402012,-1.25621795654 -6.31995868683,1.49885690212,-1.23962497711 -6.31496524811,1.49586105347,-1.21804761887 -6.32497024536,1.49786233902,-1.21024847031 -6.32197713852,1.4958666563,-1.18867981434 -6.32298469543,1.4948707819,-1.16810727119 -6.32499217987,1.4948745966,-1.14851868153 -6.33900213242,1.49687767029,-1.13093483448 -6.33600902557,1.49488186836,-1.11034810543 -6.33001184464,1.49288439751,-1.09856915474 -6.33201932907,1.49288833141,-1.07898151875 -6.35002994537,1.49589121342,-1.06238973141 -6.34603691101,1.49389576912,-1.04082167149 -6.350045681,1.49389970303,-1.02124118805 -6.35805416107,1.49490344524,-1.00265359879 -6.34106016159,1.48990905285,-0.979085743427 -6.36006641388,1.49390971661,-0.972289741039 -6.35407352448,1.49191462994,-0.950718164444 -6.35408115387,1.49091875553,-0.931125879288 -6.36509084702,1.49292230606,-0.912546873093 -6.34409618378,1.48692846298,-0.888973891735 -6.35910606384,1.48893165588,-0.871386647224 -6.36611509323,1.48993575573,-0.851815700531 -6.36011838913,1.48793840408,-0.841023743153 -6.36212730408,1.48794269562,-0.821438908577 -6.36713600159,1.48794686794,-0.801862537861 -6.37614583969,1.4899507761,-0.783275604248 -6.36415290833,1.48595643044,-0.76071625948 -6.37616252899,1.48795986176,-0.743116438389 -6.36616945267,1.48496556282,-0.721543729305 -6.38517618179,1.48896622658,-0.713754415512 -6.37818384171,1.48697149754,-0.693169057369 -6.37919282913,1.48697638512,-0.672603309155 -6.38920307159,1.48798012733,-0.654017031193 -6.40621328354,1.49198329449,-0.636424005032 -6.41622304916,1.49398708344,-0.617835104465 -6.37322282791,1.48299360275,-0.60207504034 -6.39723396301,1.48799610138,-0.585474848747 -6.40724420547,1.49000012875,-0.566885769367 -6.4112534523,1.49000453949,-0.547305166721 -6.41226243973,1.49000954628,-0.526739418507 -6.42427253723,1.49201333523,-0.508152008057 -6.39527893066,1.48502099514,-0.485576570034 -6.40828466415,1.48702228069,-0.476784586906 -6.4022936821,1.4860278368,-0.456208497286 -6.41630363464,1.48803150654,-0.437623232603 -6.41631317139,1.48803675175,-0.41705685854 -6.42232275009,1.48904109001,-0.398458003998 -6.39733028412,1.48204886913,-0.375900059938 -6.40934038162,1.48505270481,-0.357309579849 -6.40734577179,1.48405563831,-0.346535176039 -6.43435716629,1.49005806446,-0.328940331936 -6.44036722183,1.49106264114,-0.309360295534 -6.42837524414,1.48806905746,-0.2887814641 -6.43538570404,1.48907363415,-0.269202560186 -6.42539453506,1.48707997799,-0.248627707362 -6.43140459061,1.48708462715,-0.229047819972 -6.43340921402,1.48808705807,-0.219256475568 -6.44641971588,1.49109089375,-0.20065997541 -6.43842887878,1.48809707165,-0.180089116096 -6.43343877792,1.4871032238,-0.159520953894 -6.43244838715,1.48710870743,-0.139935150743 -6.42445802689,1.48411512375,-0.119367212057 -6.42446279526,1.48411774635,-0.109575003386 -6.4454741478,1.48912084103,-0.0909785702825 -6.43248319626,1.48612785339,-0.0704093277454 -6.42149353027,1.48313474655,-0.0498425886035 -6.43450450897,1.48613882065,-0.0302617065609 -6.44451475143,1.48814332485,-0.0106788566336 -6.43952417374,1.4871493578,0.00890663079917 -6.44152975082,1.4871519804,0.0186986979097 -6.45454072952,1.49015617371,0.0382834672928 -6.40954875946,1.47916698456,0.0588448494673 -6.3965587616,1.47517430782,0.0794044807553 -6.38756847382,1.47318100929,0.0989843830466 -6.43458175659,1.48518145084,0.118578016758 -6.44259214401,1.48718619347,0.138164654374 -6.4385972023,1.4861894846,0.147955417633 -6.43360710144,1.48419582844,0.167537257075 -6.44661808014,1.48720002174,0.187127411366 -6.43862915039,1.48620700836,0.207687139511 -6.43563985825,1.48521316051,0.227269366384 -6.45265054703,1.4892168045,0.246864899993 -6.4406619072,1.48622441292,0.267420202494 -6.42666625977,1.48322916031,0.27720156312 -6.44467735291,1.4872328043,0.296800106764 -6.4246878624,1.48224127293,0.316366523504 -6.43169879913,1.48424625397,0.335956841707 -6.43371009827,1.48525226116,0.356522142887 -6.43072128296,1.48425865173,0.376102864742 -6.41372585297,1.48026359081,0.384896427393 -6.44173812866,1.48726642132,0.406471312046 -6.40674781799,1.47827661037,0.424053430557 -6.36675882339,1.46928811073,0.442604064941 -6.39677047729,1.47629022598,0.463205039501 -6.41778230667,1.48229396343,0.484776377678 -6.41079330444,1.48030078411,0.503370165825 -6.42579889297,1.48430192471,0.514164328575 -6.40781116486,1.48031067848,0.533719718456 -6.42382192612,1.48431491852,0.55430918932 -6.41483402252,1.48232245445,0.57387804985 -6.39984464645,1.47933065891,0.592455983162 -6.39085626602,1.47733795643,0.611043334007 -6.41886806488,1.48434078693,0.633618056774 -6.39687395096,1.47934675217,0.641408801079 -6.40188550949,1.48035252094,0.661981642246 -6.40789747238,1.48235821724,0.68255764246 -6.39490890503,1.47936630249,0.701134979725 -6.37592077255,1.47537505627,0.718718409538 -6.39293241501,1.48037934303,0.740298986435 -6.38394451141,1.4783872366,0.75986212492 -6.38295078278,1.47839057446,0.769651710987 -6.38896179199,1.48039603233,0.789250671864 -6.39297389984,1.48140215874,0.80982452631 -6.3659863472,1.47541248798,0.827381670475 -6.38099765778,1.47941684723,0.847984373569 -6.37301015854,1.47842466831,0.867547810078 -6.37001657486,1.47742855549,0.877331793308 -6.36202907562,1.47643613815,0.895914971828 -6.35404062271,1.4744437933,0.91449713707 -6.34805297852,1.47345149517,0.934063792229 -6.34806537628,1.47445809841,0.953648090363 -6.338078022,1.4724663496,0.972222685814 -6.34508991241,1.47447192669,0.992808043957 -6.33609676361,1.4724766016,1.00159275532 -6.34110832214,1.47448265553,1.02217268944 -6.34012174606,1.47548985481,1.04273414612 -6.34713363647,1.47749555111,1.06332230568 -6.33514595032,1.4755038023,1.08090913296 -6.33015918732,1.47451162338,1.10047757626 -6.32516527176,1.47351562977,1.10927355289 -6.32217788696,1.47352302074,1.12884879112 -6.32819080353,1.47652924061,1.15041553974 -6.32320356369,1.47553658485,1.1690043211 -6.31721687317,1.47454476357,1.18856859207 -6.28723049164,1.46855604649,1.20314407349 -6.29724311829,1.47156155109,1.22472703457 -6.31024932861,1.47556316853,1.23750948906 -6.29026222229,1.47157287598,1.25309979916 -6.27927589417,1.46958184242,1.27166247368 -6.29128789902,1.47258687019,1.29325687885 -6.27830171585,1.47059583664,1.31083142757 -6.27631521225,1.47160363197,1.33138978481 -6.27432823181,1.47161102295,1.35096871853 -6.27133464813,1.47161483765,1.35977041721 -6.2743473053,1.47262144089,1.38035106659 -6.25936174393,1.47063100338,1.3979139328 -6.27637386322,1.47563564777,1.42149710655 -6.25738811493,1.47164559364,1.43708181381 -6.26740074158,1.47465133667,1.45965600014 -6.24040842056,1.4686589241,1.46344733238 -6.25942134857,1.47466337681,1.48802423477 -6.23943567276,1.47067368031,1.50360047817 -6.2414484024,1.47168064117,1.52417957783 -6.23646259308,1.47168886662,1.54374539852 -6.2404756546,1.47369539738,1.56433594227 -6.21149110794,1.46770739555,1.57790291309 -6.22249698639,1.47170937061,1.59069311619 -6.2175116539,1.47171771526,1.61025869846 -6.2175245285,1.47172474861,1.62985014915 -6.2105383873,1.47173333168,1.64842581749 -6.22455120087,1.47673845291,1.67201197147 -6.19956684113,1.47175002098,1.68657207489 -6.20257997513,1.47275686264,1.70716106892 -6.19958734512,1.47276127338,1.71694135666 -6.18160247803,1.4697715044,1.73251605034 -6.19161558151,1.47377729416,1.75510501862 -6.18862915039,1.47378528118,1.77468252182 -6.16864490509,1.47079622746,1.79024350643 -6.16365909576,1.4708044529,1.80882918835 -6.16567325592,1.4718118906,1.8303951025 -6.15968036652,1.47181642056,1.83819806576 -6.16969347,1.47482252121,1.86177253723 -6.1547088623,1.47283267975,1.87833952904 -6.15172243118,1.47284042835,1.89693796635 -6.14773702621,1.47384881973,1.91651070118 -6.13875246048,1.47285819054,1.93507230282 -6.14175891876,1.47386133671,1.94586980343 -6.14277267456,1.47586870193,1.96645450592 -6.12778902054,1.47387909889,1.98301827908 -6.12080383301,1.47288811207,2.00159215927 -6.1168179512,1.47389614582,2.02018547058 -6.12383174896,1.47690308094,2.04375123978 -6.11284732819,1.47591233253,2.06033945084 -6.11885356903,1.47791552544,2.07311987877 -6.09786987305,1.4739266634,2.08670020103 -6.08988523483,1.47393596172,2.1052672863 -6.09289979935,1.47594320774,2.12684941292 -6.08291482925,1.47495281696,2.14442276955 -6.06793117523,1.47296321392,2.16000080109 -6.0819439888,1.47796869278,2.18558239937 -6.06395339966,1.47397577763,2.19035673141 -6.05996751785,1.4749840498,2.20895195007 -6.05698299408,1.4759926796,2.22951459885 -6.04699850082,1.47500216961,2.24610638618 -6.02901506424,1.47201311588,2.26067900658 -6.04602813721,1.47801840305,2.28825092316 -6.03003740311,1.475025177,2.29303455353 -6.01405334473,1.47203564644,2.30761957169 -6.02906703949,1.47804117203,2.33420085907 -6.01008415222,1.47505271435,2.34876298904 -5.99010133743,1.47206413746,2.36233568192 -6.01211357117,1.47906839848,2.39191627502 -5.97313261032,1.47108304501,2.39749717712 -5.97114038467,1.47108733654,2.40728545189 -5.9841542244,1.47609341145,2.43385887146 -5.95517253876,1.47110641003,2.44343495369 -5.95518779755,1.47211480141,2.46500468254 -5.96920108795,1.47812044621,2.49159097672 -5.95121765137,1.47513151169,2.50517392159 -5.93523454666,1.47314250469,2.51975226402 -5.94024133682,1.47514569759,2.53254055977 -5.91626024246,1.47115802765,2.54411053658 -5.91627550125,1.47316646576,2.56568384171 -5.91529083252,1.47517514229,2.58724951744 -5.89530849457,1.47218668461,2.5998301506 -5.90532255173,1.47619307041,2.62541270256 -5.89933872223,1.47720241547,2.64399600029 -5.88334846497,1.4732093811,2.64778208733 -5.87536478043,1.47321927547,2.66634774208 -5.88237857819,1.4772258997,2.68994736671 -5.86539697647,1.47523748875,2.70451211929 -5.85341405869,1.47424805164,2.72108125687 -5.85742902756,1.47725582123,2.7446577549 -5.84143829346,1.47426247597,2.74745845795 -5.83345556259,1.47427248955,2.76602435112 -5.83547067642,1.47728049755,2.78860425949 -5.82748699188,1.4772901535,2.80619001389 -5.81050491333,1.47430193424,2.82075047493 -5.81951951981,1.47930848598,2.84634017944 -5.78754043579,1.47332322598,2.8538942337 -5.78954696655,1.47432661057,2.8647043705 -5.80656099319,1.4823321104,2.89527726173 -5.77558040619,1.47534608841,2.90185594559 -5.7665977478,1.4753562212,2.91943240166 -5.78261089325,1.48236167431,2.94902038574 -5.76163053513,1.47937440872,2.96157765388 -5.75563907623,1.47837972641,2.96937036514 -5.75165605545,1.48038911819,2.98993968964 -5.73567390442,1.47840046883,3.0035238266 -5.71969270706,1.47641205788,3.01808810234 -5.72770690918,1.48141884804,3.04368233681 -5.70172691345,1.47643256187,3.05324101448 -5.697742939,1.47744166851,3.0728302002 -5.71074914932,1.48244357109,3.09062576294 -5.69076871872,1.47945606709,3.10318636894 -5.67778682709,1.47846722603,3.11876058578 -5.67780256271,1.48147547245,3.14035487175 -5.65782165527,1.47848784924,3.15193152428 -5.65483903885,1.48049736023,3.17349672318 -5.65185499191,1.48250639439,3.19408106804 -5.63386678696,1.4785143137,3.19585943222 -5.62288427353,1.4775249958,3.21243405342 -5.6279001236,1.48253285885,3.23801136017 -5.62391614914,1.48354208469,3.25760579109 -5.61693429947,1.48455238342,3.27716946602 -5.6069521904,1.48456311226,3.29473829269 -5.588971138,1.48257493973,3.30633044243 -5.58897972107,1.48357951641,3.31811356544 -5.58599662781,1.4855889082,3.33968472481 -5.56901597977,1.48360085487,3.35226869583 -5.55703449249,1.48361206055,3.36883401871 -5.55705070496,1.48662078381,3.39142155647 -5.54007053375,1.4846329689,3.40498590469 -5.53707838058,1.48463761806,3.41379237175 -5.53309631348,1.4866476059,3.43535590172 -5.52111434937,1.48665857315,3.45093917847 -5.50913333893,1.48566949368,3.4665222168 -5.50815010071,1.48867893219,3.49008560181 -5.49816846848,1.48868954182,3.50667357445 -5.48218774796,1.48770141602,3.52024745941 -5.47719717026,1.48770689964,3.5290324688 -5.46821498871,1.48771750927,3.54661393166 -5.45523452759,1.48772907257,3.56218552589 -5.44125366211,1.48674070835,3.57676267624 -5.43927097321,1.48875010014,3.5993373394 -5.42329120636,1.48776221275,3.6129090786 -5.42830657959,1.49177014828,3.6394970417 -5.41331720352,1.48877739906,3.64128828049 -5.39933681488,1.48878908157,3.65586543083 -5.38935565948,1.48880004883,3.67343640327 -5.39137268066,1.49280881882,3.69901108742 -5.36439418793,1.48782289028,3.70458960533 -5.3594121933,1.48983287811,3.72516918182 -5.36142015457,1.49183726311,3.73895263672 -5.34544086456,1.49084949493,3.75252223015 -5.33745908737,1.49186015129,3.7711019516 -5.33547639847,1.49486935139,3.7936861515 -5.30749893188,1.48988425732,3.79924631119 -5.31251525879,1.49489223957,3.82683181763 -5.29753494263,1.49390423298,3.84041261673 -5.30254268646,1.49690783024,3.85620355606 -5.29056215286,1.49691951275,3.8727710247 -5.2775812149,1.49693095684,3.88736009598 -5.2536034584,1.49294471741,3.89492988586 -5.2566204071,1.49795365334,3.922498703 -5.24563884735,1.49796450138,3.93809556961 -5.23465013504,1.49597144127,3.94287514687 -5.2236700058,1.49698317051,3.96043872833 -5.22768688202,1.50199139118,3.98802518845 -5.20770740509,1.49900436401,3.99760866165 -5.19272756577,1.49801635742,4.01118850708 -5.19574451447,1.50302505493,4.03876638412 -5.15976953506,1.49604165554,4.0373249054 -5.17077589035,1.50104403496,4.05812120438 -5.16479444504,1.50305438042,4.0787024498 -5.14581632614,1.50106775761,4.0902633667 -5.13683509827,1.50207853317,4.10785531998 -5.12885475159,1.50408947468,4.12742805481 -5.10687637329,1.50110328197,4.13599681854 -5.10789394379,1.50511240959,4.1625752449 -5.11390113831,1.50911557674,4.17938089371 -5.08492469788,1.50413060188,4.18195390701 -5.09394073486,1.51113831997,4.21552944183 -5.06096458435,1.5041539669,4.21411085129 -5.05698394775,1.5071644783,4.23767662048 -5.04400348663,1.50717616081,4.25226640701 -5.02902460098,1.50618875027,4.26683044434 -5.01803588867,1.50519549847,4.27061986923 -5.02005386353,1.51020479202,4.29919099808 -4.99607658386,1.50621902943,4.30575895309 -4.99209499359,1.50922906399,4.32834529877 -4.99811172485,1.51623725891,4.3599281311 -4.96313667297,1.50825357437,4.35650157928 -4.96214532852,1.5102584362,4.3683013916 -4.9501657486,1.51127028465,4.38487529755 -4.93918657303,1.51228201389,4.4024477005 -4.92420816422,1.51129472256,4.41701126099 -4.92022657394,1.51430475712,4.43960428238 -4.91224575043,1.51631557941,4.45918893814 -4.89526796341,1.51532876492,4.47175693512 -4.89127779007,1.51633453369,4.48253393173 -4.87529850006,1.51534688473,4.49413061142 -4.86132049561,1.5153594017,4.50969362259 -4.85334014893,1.51737034321,4.52928113937 -4.8393611908,1.51738262177,4.54386043549 -4.81138467789,1.51239776611,4.54543638229 -4.81240320206,1.51840734482,4.57500267029 -4.81241226196,1.52041220665,4.58879423141 -4.8014330864,1.52142381668,4.60637235641 -4.78845405579,1.52243602276,4.62195205688 -4.77347564697,1.521448493,4.63553237915 -4.75449848175,1.52046215534,4.64610004425 -4.75551652908,1.52547168732,4.67567491531 -4.73853826523,1.52448451519,4.68725681305 -4.73454809189,1.52548992634,4.69705438614 -4.71257162094,1.52350413799,4.70462179184 -4.69959306717,1.52351653576,4.72118806839 -4.68261528015,1.52252960205,4.73276853561 -4.67063617706,1.52354156971,4.74935007095 -4.65765714645,1.52355372906,4.76493120193 -4.66166543961,1.52755761147,4.78273248672 -4.64768695831,1.52857017517,4.7983007431 -4.64270734787,1.5315810442,4.82287359238 -4.61973047256,1.52859520912,4.82845163345 -4.60875177383,1.53060746193,4.84702253342 -4.59077453613,1.52962064743,4.85760307312 -4.59278297424,1.53262507915,4.87439441681 -4.57380628586,1.5316388607,4.88496017456 -4.56182718277,1.53265082836,4.90154600143 -4.53885126114,1.5296652317,4.90712022781 -4.53287124634,1.53267610073,4.93069934845 -4.51489400864,1.53168940544,4.94127893448 -4.5139131546,1.53769958019,4.97085285187 -4.4999256134,1.53470718861,4.97064304352 -4.48994636536,1.53671896458,4.99022054672 -4.46697044373,1.5337331295,4.99480581284 -4.46598958969,1.53974318504,5.02438592911 -4.44101428986,1.53575825691,5.02795314789 -4.43203496933,1.53876984119,5.04853534698 -4.42305612564,1.54078161716,5.070104599 -4.41406726837,1.54078817368,5.07490158081 -4.40008926392,1.54080057144,5.08948850632 -4.3881111145,1.54181301594,5.10805416107 -4.37113380432,1.54182612896,5.11963605881 -4.35415649414,1.54083943367,5.13121700287 -4.35017728806,1.54585051537,5.1597776413 -4.3361992836,1.54686284065,5.17436695099 -4.32921028137,1.54686915874,5.18215560913 -4.30823421478,1.54488348961,5.1897277832 -4.29225683212,1.54489636421,5.20231246948 -4.27228069305,1.54391050339,5.21088552475 -4.26530122757,1.54692149162,5.23447036743 -4.2453250885,1.5459356308,5.2430434227 -4.2343378067,1.54494297504,5.24682044983 -4.216360569,1.54395627975,5.25641155243 -4.20938158035,1.54796767235,5.28098678589 -4.17940807343,1.54198384285,5.27755069733 -4.15643262863,1.53999829292,5.28113698959 -3.40864992142,1.25016868114,4.39521598816 -3.41265869141,1.25417280197,4.41400718689 -3.38068652153,1.24718952179,4.4015712738 -3.38870382309,1.25619769096,4.43915987015 -4.11454820633,1.55906152725,5.4128203392 -4.0825753212,1.55307793617,5.40539503098 -4.07059764862,1.55509030819,5.42397403717 -4.08361434937,1.56809782982,5.47654771805 -4.05563020706,1.55910849571,5.45633840561 -4.01266002655,1.54812693596,5.43292140961 -4.01067972183,1.55513739586,5.46549654007 -3.84673905373,1.49218034744,5.27706480026 -3.81376767159,1.48619747162,5.26762008667 -3.98774433136,1.5671724081,5.54122114182 -3.98575377464,1.56917750835,5.55502700806 -4.02376413345,1.59317994118,5.64460325241 -4.00078868866,1.59119439125,5.64819049835 -3.9988090992,1.59720504284,5.68276357651 -3.74789047241,1.49626553059,5.36331987381 -3.72591543198,1.49328017235,5.36689758301 -3.74892950058,1.51128566265,5.4354763031 -3.77893209457,1.52828478813,5.4972615242 -3.92991423607,1.6022644043,5.75285768509 -3.92693376541,1.60827469826,5.78544855118 -3.86596941948,1.59029746056,5.73501014709 -3.70003008842,1.52334094048,5.52657699585 -3.70304942131,1.53235042095,5.56815338135 -3.87202644348,1.61632633209,5.85875654221 -3.86503767967,1.61733281612,5.86754798889 -3.85206079483,1.62034547329,5.88712692261 -3.83708405495,1.62135851383,5.90370607376 -3.78011798859,1.60338008404,5.85528516769 -3.57618975639,1.51843166351,5.57983398438 -3.6831817627,1.57541978359,5.78343629837 -3.25030136108,1.37851202488,5.12519264221 -3.46226835251,1.48548007011,5.49576950073 -3.35831451416,1.44451117516,5.36833953857 -3.60827040672,1.57047069073,5.8039484024 -3.72526049614,1.63445734978,6.03253650665 -3.72228097916,1.6414681673,6.06911754608 -3.71130394936,1.64548051357,6.09369134903 -3.69931602478,1.64348769188,6.09349679947 -3.69233798981,1.64949941635,6.12506914139 -3.68435978889,1.65551126003,6.15464735031 -3.65538716316,1.65052723885,6.14922523499 -3.62641453743,1.64554333687,6.14380025864 -3.60244059563,1.64255821705,6.14637851715 -3.58945417404,1.64156615734,6.1461648941 -3.57047867775,1.64157998562,6.15674781799 -3.08962249756,1.41068649292,5.36830615997 -3.43455410004,1.59262788296,6.00888967514 -3.54154634476,1.65661656857,6.23948001862 -3.52557015419,1.65762984753,6.25605916977 -3.06970858574,1.43473160267,5.48961257935 -3.29466032982,1.55469167233,5.91141366959 -3.4426419735,1.64067220688,6.22100114822 -3.46765518188,1.66267728806,6.31158494949 -3.44968008995,1.66369116306,6.3251619339 -3.4347038269,1.66670441628,6.34374475479 -3.422727108,1.67071700096,6.36832523346 -3.39775395393,1.66773235798,6.36989450455 -3.38276791573,1.66474044323,6.3646903038 -3.36179351807,1.66475498676,6.37326383591 -3.34681749344,1.66676807404,6.39184904099 -3.3258433342,1.66678273678,6.40042209625 -3.30686855316,1.66679668427,6.41200304031 -3.28389501572,1.66581165791,6.41657686234 -3.2759168148,1.67182338238,6.44916296005 -3.25893115997,1.66783177853,6.43995523453 -3.24095606804,1.66884565353,6.45353651047 -3.22897982597,1.67385840416,6.48011112213 -3.2010076046,1.6698744297,6.47468423843 -3.18603181839,1.67288756371,6.49426794052 -3.17105603218,1.67490100861,6.51484441757 -3.162068367,1.67590773106,6.52163648605 -3.14609265327,1.67792105675,6.53922271729 -3.12811779976,1.67993509769,6.55380058289 -3.10514450073,1.6779500246,6.55837440491 -3.08317041397,1.67696464062,6.56395673752 -3.0691947937,1.68097782135,6.58753156662 -3.04222226143,1.67699337006,6.58211612701 -3.04023361206,1.68299925327,6.60688781738 -3.02025866508,1.68301320076,6.61548089981 -3.00228476524,1.68502759933,6.63204669952 -2.97631192207,1.68104290962,6.62863016129 -2.96333527565,1.68605554104,6.65322160721 -2.94436144829,1.68706989288,6.66778755188 -2.93437361717,1.68707680702,6.67158842087 -2.9193983078,1.69108998775,6.69317150116 -2.89542508125,1.68910515308,6.69474983215 -2.87845015526,1.69111871719,6.71233034134 -2.85747694969,1.69213366508,6.72289466858 -2.83650231361,1.69114780426,6.72948741913 -2.81752848625,1.6921620369,6.74306440353 -2.80954051018,1.69416868687,6.75285768509 -2.79956436157,1.70218122005,6.78942775726 -2.76759338379,1.69419777393,6.77100944519 -2.7456202507,1.69421255589,6.77758550644 -2.7266459465,1.69522666931,6.79116487503 -2.70667147636,1.69624066353,6.80075502396 -2.6866979599,1.69725525379,6.81332540512 -2.68570780754,1.70326042175,6.84012699127 -2.65773630142,1.69927632809,6.83170223236 -2.63476371765,1.69829142094,6.83627557755 -2.61678862572,1.70030510426,6.85186195374 -2.59581542015,1.700319767,6.86143684387 -2.57384181023,1.70033431053,6.86702013016 -2.55886626244,1.70434737206,6.89060926437 -2.5408821106,1.69935631752,6.87638902664 -2.52490735054,1.70336985588,6.89896917343 -2.50393342972,1.70438420773,6.9075512886 -2.47896146774,1.70139956474,6.90612697601 -2.45998740196,1.7034137249,6.9207072258 -2.44501209259,1.70842695236,6.94629049301 -2.43402576447,1.70843434334,6.95007705688 -2.40705347061,1.70444977283,6.94066524506 -2.39007878304,1.70746350288,6.96124649048 -2.36310768127,1.70447933674,6.95481491089 -2.34513354301,1.70749330521,6.97339248657 -2.32515978813,1.70850753784,6.98497724533 -2.30418634415,1.7095220089,6.994556427 -2.29619884491,1.71152877808,7.00635004044 -2.26322889328,1.70254552364,6.97892951965 -2.24225521088,1.70255982876,6.98751354218 -2.23627758026,1.71557128429,7.04309940338 -2.22830057144,1.72758316994,7.09467840195 -2.21532511711,1.73559617996,7.13125658035 -2.18735432625,1.73061215878,7.1208281517 -2.19136309624,1.74361634254,7.17162942886 -2.17238926888,1.74663043022,7.18921089172 -2.14841675758,1.74464547634,7.19079017639 -2.13544154167,1.75365841389,7.23036527634 -2.10047221184,1.74267554283,7.19394683838 -2.0854973793,1.74968886375,7.22553062439 -2.07251095772,1.74769628048,7.22132730484 -2.03954148293,1.73871326447,7.19190216064 -2.00457239151,1.72673046589,7.15348148346 -1.98459863663,1.72874462605,7.1670665741 -1.95662772655,1.72376048565,7.15364170074 -1.93465459347,1.72377490997,7.15923023224 -1.91468167305,1.72678935528,7.175801754 -1.90069544315,1.72379696369,7.16560411453 -1.87772345543,1.72381198406,7.17117500305 -1.85575079918,1.7238266468,7.17875432968 -1.83177757263,1.72184121609,7.17435216904 -1.80580663681,1.71885693073,7.16891908646 -1.78483307362,1.71987092495,7.17751073837 -1.76585972309,1.72388517857,7.19808673859 -1.75187444687,1.72089314461,7.19087076187 -1.727902174,1.71890795231,7.18845796585 -1.70692849159,1.71992206573,7.19705057144 -1.68495607376,1.72093677521,7.20562648773 -1.65998399258,1.7179517746,7.19921064377 -1.63901090622,1.71996605396,7.20979595184 -1.6240260601,1.7159743309,7.19757938385 -1.60005402565,1.71398925781,7.19615888596 -1.57808089256,1.71400356293,7.20075035095 -1.55310928822,1.71201884747,7.19532632828 -1.53213655949,1.71403324604,7.20790481567 -1.50816392899,1.7110478878,7.20249795914 -1.48619163036,1.71206259727,7.21107387543 -1.47620487213,1.71406948566,7.2188668251 -1.44923365116,1.70908498764,7.20144844055 -1.43126034737,1.71509885788,7.2310218811 -1.40728795528,1.71211361885,7.22561216354 -1.37931716442,1.70612931252,7.20219230652 -1.36134326458,1.71114289761,7.22977638245 -1.33537232876,1.70815837383,7.21834897995 -1.32538509369,1.70916509628,7.22315406799 -1.30141377449,1.70818030834,7.22372198105 -1.27944123745,1.7091947794,7.23130369186 -1.25346922874,1.7032096386,7.2118973732 -1.23349618912,1.70722365379,7.23048019409 -1.20652484894,1.70023906231,7.20706510544 -1.18755173683,1.70625305176,7.2336435318 -1.1735663414,1.70226073265,7.21943330765 -1.15159332752,1.70227491856,7.22302627563 -1.12762153149,1.70028984547,7.21860551834 -1.10664892197,1.70330405235,7.23318576813 -1.08367717266,1.70331895351,7.23775863647 -1.05770504475,1.69633376598,7.21235656738 -1.04971790314,1.70234024525,7.23614931107 -1.022747159,1.69435584545,7.21072673798 -1.00077426434,1.69536995888,7.21531581879 -0.977802455425,1.69538462162,7.21789216995 -0.954830646515,1.69539940357,7.22046899796 -0.930858254433,1.69141387939,7.20806217194 -0.910885512829,1.69742786884,7.2336397171 -0.894900798798,1.68843603134,7.19743108749 -0.873928129673,1.69145023823,7.21401166916 -0.850956141949,1.69146490097,7.21459150314 -0.828983724117,1.69247913361,7.22217464447 -0.806010901928,1.69049322605,7.21477127075 -0.784039080143,1.69350790977,7.22834396362 -0.770053327084,1.68551540375,7.20014333725 -0.749080657959,1.68952953815,7.21772623062 -0.726108551025,1.68854391575,7.21630954742 -0.703136026859,1.68655824661,7.20990085602 -0.680164396763,1.68757283688,7.21347475052 -0.65819221735,1.68958735466,7.22505283356 -0.635219454765,1.68660140038,7.21465015411 -0.623233497143,1.68460857868,7.20644378662 -0.601261079311,1.68662285805,7.21502780914 -0.576289772987,1.67963767052,7.18960762024 -0.555316865444,1.68365156651,7.20819568634 -0.532344758511,1.6826659441,7.20378017426 -0.5093729496,1.6816804409,7.20335912704 -0.48540148139,1.67769515514,7.18893718719 -0.475414872169,1.6827019453,7.20673179626 -0.451443225145,1.67771649361,7.18831300735 -0.429470479488,1.6777305603,7.19190454483 -0.407498449087,1.68274486065,7.20948219299 -0.384525984526,1.67875897884,7.19507455826 -0.360554456711,1.67277359962,7.17265367508 -0.339581400156,1.67878735065,7.19624662399 -0.327595502138,1.6747944355,7.18103885651 -0.305623412132,1.67980873585,7.20161724091 -0.282650917768,1.67482280731,7.18021059036 -0.259679287672,1.67483723164,7.18078660965 -0.236707687378,1.67485165596,7.18136262894 -0.214735254645,1.67786574364,7.19694852829 -0.203748330474,1.67387247086,7.17975568771 -0.180777013302,1.67688703537,7.1933259964 -0.157804965973,1.67290115356,7.17391061783 -0.135832369328,1.67591512203,7.18750047684 -0.113859459758,1.6759288311,7.18609619141 -0.0908878743649,1.67694330215,7.1916718483 -0.0679161250591,1.67395758629,7.18025112152 -0.0569296255708,1.67196452618,7.17204999924 -0.0349568687379,1.67697823048,7.18964338303 -0.011985170655,1.6699924469,7.16222143173 --0.0109859704971,1.66700708866,6.8667883873 --0.0319592505693,1.67002046108,6.87938594818 --0.0539313256741,1.67303454876,6.89096546173 --0.0749044939876,1.67004811764,6.87856054306 --0.0968764796853,1.67006218433,6.87813854218 --0.118848398328,1.66907632351,6.87371492386 --0.12883554399,1.66808271408,6.86752080917 --0.150807738304,1.67109668255,6.87810325623 --0.17277982831,1.67211079597,6.88068246841 --0.19375257194,1.6671243906,6.86026954651 --0.215724736452,1.66913831234,6.8668513298 --0.236697927117,1.66815161705,6.86444711685 --0.247683957219,1.66915869713,6.86523675919 --0.269656836987,1.67517220974,6.8878326416 --0.29062885046,1.66718626022,6.85540533066 --0.312600851059,1.66720020771,6.85598421097 --0.334573626518,1.6722137928,6.87157678604 --0.355546504259,1.67022716999,6.86216640472 --0.376519322395,1.6682407856,6.85275554657 --0.387505441904,1.66824769974,6.85454654694 --0.409477263689,1.66826164722,6.8511223793 --0.43144968152,1.67027533054,6.85670757294 --0.453422605991,1.6742888689,6.87030506134 --0.473395586014,1.66830217838,6.84489059448 --0.495368123055,1.67031574249,6.85147953033 --0.506354093552,1.67032277584,6.85026788712 --0.528326153755,1.67033660412,6.84984779358 --0.550299227238,1.67435002327,6.86144638062 --0.573271036148,1.67736399174,6.87302684784 --0.594244062901,1.67637729645,6.86661815643 --0.616216003895,1.67639100552,6.86419677734 --0.63918787241,1.67940497398,6.87377786636 --0.650174915791,1.68241143227,6.88358736038 --0.672146975994,1.68242514133,6.8811674118 --0.695119142532,1.6864387989,6.89175367355 --0.716091632843,1.68345224857,6.8803358078 --0.7370647192,1.6834654808,6.87492895126 --0.760036468506,1.68547940254,6.88050699234 --0.782008707523,1.6854929924,6.87909030914 --0.793995678425,1.69049954414,6.89690351486 --0.815967202187,1.6895134449,6.88847208023 --0.83693999052,1.68752682209,6.88005924225 --0.857913613319,1.68853962421,6.87866258621 --0.880885243416,1.68955349922,6.88123750687 --0.901857554913,1.68756699562,6.86981725693 --0.924829959869,1.69058060646,6.87840795517 --0.938815355301,1.69658768177,6.90020227432 --0.957789242268,1.69260036945,6.88079833984 --0.97876149416,1.69061398506,6.86837387085 --1.00373315811,1.69662761688,6.88896369934 --1.02670562267,1.69964110851,6.89555454254 --1.04667890072,1.69665408134,6.88214588165 --1.05866515636,1.69966077805,6.88994550705 --1.08163702488,1.70067453384,6.89152431488 --1.10360968113,1.7016876936,6.89011287689 --1.12658190727,1.7037011385,6.89369916916 --1.14855408669,1.70371460915,6.88927984238 --1.16852760315,1.70172739029,6.8778758049 --1.19150018692,1.70374059677,6.88347005844 --1.20648550987,1.71074783802,6.9062666893 --1.22645866871,1.70776081085,6.89185333252 --1.24843049049,1.70677435398,6.88442516327 --1.27440237999,1.71378803253,6.906021595 --1.29437565804,1.71180081367,6.89261054993 --1.3153488636,1.71081364155,6.88620471954 --1.33632099628,1.70882689953,6.87377786636 --1.34930706024,1.71283376217,6.88457870483 --1.37427866459,1.71684741974,6.89516210556 --1.39125323296,1.71085953712,6.86976003647 --1.4162248373,1.71487319469,6.88034486771 --1.43919742107,1.71688628197,6.8829369545 --1.46116948128,1.71689963341,6.87551021576 --1.48514163494,1.71991300583,6.8821015358 --1.50012719631,1.72591996193,6.90090417862 --1.52309930325,1.72693324089,6.8994846344 --1.54107344151,1.72194552422,6.87907934189 --1.56304681301,1.72295832634,6.87767791748 --1.58601868153,1.72497165203,6.87525463104 --1.61198985577,1.72898542881,6.88683652878 --1.62197649479,1.72799170017,6.88063144684 --1.64294981956,1.72800433636,6.87322425842 --1.66892123222,1.73201787472,6.88480997086 --1.69089400768,1.73303079605,6.88039922714 --1.71086728573,1.73104357719,6.86698389053 --1.7348395586,1.73305666447,6.87057304382 --1.75981152058,1.7370698452,6.87816333771 --1.76879858971,1.73507595062,6.86795806885 --1.79577088356,1.74108922482,6.88656568527 --1.81374418736,1.73710167408,6.86313915253 --1.83471739292,1.73611438274,6.85472869873 --1.85968959332,1.74012732506,6.86232376099 --1.88266217709,1.7411403656,6.860912323 --1.90263533592,1.73915290833,6.84749603271 --1.91862046719,1.7441599369,6.86329269409 --1.94059336185,1.74517261982,6.85788059235 --1.95656847954,1.74018418789,6.83347892761 --1.98653864861,1.74719834328,6.85405778885 --2.00951123238,1.7482111454,6.85164499283 --2.03148412704,1.74922382832,6.84623432159 --2.04447054863,1.75123023987,6.85203886032 --2.06944227219,1.75424349308,6.85461902618 --2.08641695976,1.75025510788,6.83321237564 --2.1153883934,1.75726866722,6.85180902481 --2.13636112213,1.75628113747,6.84139156342 --2.15733504295,1.75629329681,6.83399009705 --2.18130755424,1.75830614567,6.83458089828 --2.19929146767,1.76331365108,6.85136413574 --2.21726584435,1.76032543182,6.83295440674 --2.23823928833,1.76033771038,6.82454824448 --2.26321148872,1.76335060596,6.8271355629 --2.28418469429,1.762362957,6.81772470474 --2.30715799332,1.76437544823,6.81531906128 --2.33013033867,1.76538813114,6.81090307236 --2.34411668777,1.76839435101,6.81871080399 --2.36508965492,1.76740694046,6.80728816986 --2.38706302643,1.76741921902,6.80087804794 --2.41503477097,1.77343225479,6.81247472763 --2.43400835991,1.77044439316,6.79605722427 --2.45998072624,1.77445709705,6.80064821243 --2.48595285416,1.77746987343,6.80524015427 --2.49793887138,1.77847623825,6.80403232574 --2.51891279221,1.77848827839,6.79462385178 --2.53988599777,1.77750051022,6.78420877457 --2.56385874748,1.77951288223,6.7828001976 --2.58383321762,1.77952444553,6.77240276337 --2.60580611229,1.7795368433,6.7639837265 --2.61979198456,1.78154325485,6.76878213882 --2.65076327324,1.7895565033,6.7853770256 --2.66973781586,1.78756809235,6.77097129822 --2.69570970535,1.79058086872,6.77356052399 --2.71968269348,1.79259312153,6.77115106583 --2.73565769196,1.7886043787,6.74773454666 --2.76462888718,1.79361748695,6.75732421875 --2.77861499786,1.79662382603,6.7611207962 --2.79958868027,1.79563570023,6.75070953369 --2.82456207275,1.79864776134,6.75231456757 --2.84953474998,1.80166006088,6.7519068718 --2.86950850487,1.80067181587,6.73849153519 --2.89148235321,1.80068361759,6.73108577728 --2.92145323753,1.80669665337,6.74066972733 --2.92944121361,1.80470216274,6.73046970367 --2.95541405678,1.80771446228,6.73206424713 --2.97238850594,1.80472564697,6.71164798737 --2.99636125565,1.80673778057,6.70723342896 --3.02633357048,1.81275045872,6.71883821487 --3.044308424,1.81076169014,6.70142745972 --3.05629491806,1.81176745892,6.70022821426 --3.07926821709,1.81277942657,6.69381713867 --3.10224127769,1.81379151344,6.68639945984 --3.12921380997,1.81680381298,6.68899250031 --3.15318751335,1.81881558895,6.68559026718 --3.17716026306,1.82082760334,6.68017339706 --3.19613552094,1.81983852386,6.66677618027 --3.20512294769,1.81884419918,6.65756654739 --3.238093853,1.82585716248,6.67216157913 --3.25506901741,1.82286798954,6.65275001526 --3.27804231644,1.82387983799,6.64533615112 --3.30701398849,1.8288923502,6.64992237091 --3.32398986816,1.82690286636,6.63252592087 --3.35096240044,1.82991492748,6.63311386108 --3.36894702911,1.83392179012,6.64190578461 --3.38592290878,1.8319324255,6.62350177765 --3.40589761734,1.83194351196,6.61109781265 --3.43586969376,1.83695578575,6.61769151688 --3.45284438133,1.83396673203,6.59727048874 --3.47781825066,1.83697831631,6.59487104416 --3.49580359459,1.8409845829,6.60467720032 --3.51677799225,1.84099578857,6.5932674408 --3.53475260735,1.83900678158,6.57484674454 --3.56572413445,1.84501934052,6.5814332962 --3.58769917488,1.84602999687,6.57404279709 --3.60667419434,1.8450409174,6.55863237381 --3.63364672661,1.84805285931,6.55721712112 --3.63663554192,1.84405755997,6.53700494766 --3.66260933876,1.84706902504,6.53560590744 --3.69458079338,1.85308122635,6.54420232773 --3.70655798912,1.84809100628,6.51679468155 --3.73253154755,1.85210251808,6.51438951492 --3.76050400734,1.85511445999,6.51397323608 --3.77747964859,1.85312473774,6.49556732178 --3.79046654701,1.85513055325,6.49436616898 --3.81744003296,1.8581417799,6.49396753311 --3.84341311455,1.86115348339,6.48955011368 --3.86238861084,1.86016392708,6.47514915466 --3.88736224174,1.86217522621,6.46973896027 --3.90533804893,1.86118543148,6.45333528519 --3.93032193184,1.86919236183,6.47213888168 --3.9502966404,1.86820316315,6.45772457123 --3.96427369118,1.86521291733,6.43431711197 --3.99024677277,1.86822426319,6.42990493774 --4.01622104645,1.87123513222,6.42751216888 --4.03819561005,1.87124598026,6.41609668732 --4.0661687851,1.87525737286,6.41569519043 --4.07615566254,1.87526273727,6.40747976303 --4.1011300087,1.87727367878,6.40207767487 --4.13110303879,1.88228523731,6.40366983414 --4.14607954025,1.87929487228,6.38226413727 --4.16805458069,1.88030540943,6.37186098099 --4.19502782822,1.88331663609,6.36845254898 --4.21700334549,1.88432693481,6.35805034637 --4.22599077225,1.88433206081,6.34884023666 --4.24996614456,1.88634240627,6.34244823456 --4.27693939209,1.88935363293,6.33803367615 --4.29691505432,1.88936388493,6.32362365723 --4.31689071655,1.88937389851,6.31022310257 --4.34186506271,1.89138484001,6.30281066895 --4.35385227203,1.89239001274,6.29860639572 --4.37782716751,1.8944003582,6.29120922089 --4.40280103683,1.89641129971,6.28278923035 --4.43477392197,1.90142250061,6.28639030457 --4.46074819565,1.90443301201,6.2809882164 --4.48772239685,1.90744376183,6.27658319473 --4.50669813156,1.9074536562,6.26017141342 --4.51868581772,1.90845882893,6.25597047806 --4.53466272354,1.90646827221,6.23656988144 --4.55363845825,1.90647804737,6.22015762329 --4.5726146698,1.90548789501,6.20374488831 --4.58259296417,1.90149664879,6.17634344101 --4.59956932068,1.90050625801,6.15692663193 --4.6155462265,1.89851558208,6.13752317429 --4.61653757095,1.89551925659,6.11932897568 --4.63051509857,1.89252841473,6.09692001343 --4.6574883461,1.89553916454,6.09049987793 --4.67446565628,1.89454829693,6.0731010437 --4.69844055176,1.89655864239,6.06369161606 --4.71341848373,1.89556741714,6.04429864883 --4.72440624237,1.89557242393,6.03809165955 --4.73938322067,1.8935816288,6.01667785645 --4.76035928726,1.89459109306,6.00427770615 --4.76933813095,1.89059984684,5.97485733032 --4.79231405258,1.89260947704,5.96546220779 --4.81528997421,1.89361929893,5.95505809784 --4.83426618576,1.89362883568,5.93864202499 --4.85225200653,1.89763426781,5.94144105911 --4.88422584534,1.90264463425,5.94304895401 --4.89420557022,1.89965295792,5.91664505005 --4.91918039322,1.90166294575,5.90823936462 --4.9431552887,1.90367281437,5.89782571793 --4.96413230896,1.90468192101,5.88542938232 --4.98810768127,1.90669178963,5.87501811981 --4.99709606171,1.90669631958,5.8668179512 --5.011074543,1.90470480919,5.84541416168 --5.036049366,1.90771460533,5.83600187302 --5.05302762985,1.9067234993,5.81860351562 --5.07200431824,1.90673267841,5.80219125748 --5.08898115158,1.9067414999,5.78378152847 --5.10496854782,1.90874660015,5.78358268738 --5.11794710159,1.90675497055,5.76117944717 --5.14392232895,1.90976452827,5.75276899338 --5.15690088272,1.90777289867,5.73036432266 --5.17587804794,1.90778195858,5.71395301819 --5.19085645676,1.90679037571,5.6945567131 --5.21183252335,1.90779948235,5.68014240265 --5.22082185745,1.90780377388,5.67194318771 --5.24379825592,1.90981268883,5.66155004501 --5.26777410507,1.91282212734,5.65013504028 --5.28775167465,1.91383087635,5.63573455811 --5.30173015594,1.91183924675,5.61432790756 --5.31470870972,1.90984725952,5.5919213295 --5.34268426895,1.91385686398,5.58551692963 --5.35767126083,1.9158616066,5.58331537247 --5.36665153503,1.91286933422,5.55691003799 --5.39162731171,1.91587853432,5.54649782181 --5.40760612488,1.91488659382,5.52810049057 --5.42158460617,1.91389489174,5.50669240952 --5.44156169891,1.91490352154,5.49128293991 --5.45155096054,1.91490769386,5.48408412933 --5.4725279808,1.91591644287,5.46967554092 --5.49950361252,1.91992557049,5.46126747131 --5.51648187637,1.91993367672,5.44387102127 --5.5284614563,1.91794145107,5.42046165466 --5.55343818665,1.92095017433,5.41106748581 --5.56241798401,1.91795766354,5.38465690613 --5.57940578461,1.92096233368,5.38446187973 --5.60138225555,1.92197108269,5.37004470825 --5.60736370087,1.91797816753,5.34164333344 --5.63234043121,1.92098677158,5.33123970032 --5.65631771088,1.92399537563,5.31983709335 --5.66629695892,1.92100286484,5.29442453384 --5.6892747879,1.92301130295,5.28202199936 --5.70126342773,1.92501544952,5.27682733536 --5.71624183655,1.92402338982,5.25540685654 --5.73122119904,1.92303097248,5.23600959778 --5.75519895554,1.92603933811,5.22461032867 --5.67119884491,1.89004015923,5.11216878891 --5.61319351196,1.86404263973,5.02574539185 --5.61917448044,1.86004984379,4.99833631516 --5.62016534805,1.8580532074,4.98313474655 --5.64214324951,1.8600615263,4.96972179413 --5.6911149025,1.87107145786,4.98132658005 --5.6950969696,1.86707818508,4.95292615891 --5.75006818771,1.88108849525,4.96953439713 --5.78304338455,1.88709712029,4.96613502502 --5.76803827286,1.87909936905,4.93692970276 --5.80701255798,1.88710844517,4.9385304451 --5.87298154831,1.90411937237,4.9631357193 --5.93595075607,1.92012989521,4.98474311829 --5.96592760086,1.92513799667,4.97835063934 --5.98490619659,1.9261456728,4.96093654633 --5.99188756943,1.92315232754,4.93453407288 --6.00187683105,1.92415630817,4.92632865906 --6.03085374832,1.92816436291,4.91792583466 --6.03783512115,1.92517113686,4.89152240753 --6.05481433868,1.92617833614,4.87311697006 --6.07479333878,1.92718577385,4.85771989822 --6.08377504349,1.92519247532,4.833319664 --6.09075641632,1.92219924927,4.80590105057 --6.11174345016,1.92720365524,4.80670022964 --6.11672592163,1.92320990562,4.7793006897 --6.13070583344,1.92321705818,4.75788736343 --6.15668344498,1.92622470856,4.74648332596 --6.16266584396,1.92323100567,4.72008466721 --6.17964553833,1.92423808575,4.70168066025 --6.20362377167,1.92724561691,4.6882724762 --6.20461559296,1.92524850368,4.67407941818 --6.21959590912,1.92525553703,4.65366840363 --6.23757553101,1.92626237869,4.63626861572 --6.23555898666,1.9202684164,4.60285282135 --6.25853776932,1.92327547073,4.58945655823 --5.49666786194,1.67024302483,3.98480176926 --5.48666095734,1.66424572468,3.96359324455 --5.50963973999,1.66825330257,3.95318579674 --5.62060117722,1.6992650032,4.00882339478 --6.02650737762,1.82629108429,4.27954292297 --6.04848623276,1.82929837704,4.26512622833 --6.05546855927,1.82730460167,4.24173212051 --6.08344602585,1.83131194115,4.23232889175 --6.09043645859,1.83131539822,4.22211885452 --6.10041809082,1.83032178879,4.20072317123 --6.10739994049,1.82832813263,4.17631435394 --6.1293797493,1.83133494854,4.16291570663 --6.1313624382,1.82734119892,4.13449764252 --6.13834476471,1.82534730434,4.11110067368 --6.1713218689,1.83135461807,4.10469818115 --6.16431522369,1.82735729218,4.08549261093 --6.16029977798,1.82236301899,4.05408477783 --6.17528009415,1.82236969471,4.03466749191 --6.19326066971,1.82437622547,4.01826572418 --6.19324445724,1.82038211823,3.98985934258 --6.21722364426,1.82338881493,3.97746014595 --6.22020673752,1.82039475441,3.95105338097 --6.2311964035,1.82239806652,3.94384884834 --6.24117898941,1.82140398026,3.92244958878 --6.2491607666,1.81941020489,3.89903855324 --6.25514364243,1.8174161911,3.87463116646 --6.28412246704,1.82242286205,3.86523413658 --6.28310680389,1.81842851639,3.83683037758 --6.28709030151,1.81643414497,3.81142449379 --6.29008102417,1.81543719769,3.79921936989 --6.30406236649,1.81544339657,3.77981138229 --6.32804250717,1.81944978237,3.76640415192 --6.35002231598,1.82245612144,3.75200128555 --6.35700511932,1.82046198845,3.72859716415 --6.33099412918,1.80946671963,3.68518161774 --6.35098266602,1.8134701252,3.68297600746 --6.40195798874,1.82547712326,3.68659281731 --6.40794086456,1.82348287106,3.66218185425 --6.41492414474,1.82148838043,3.63877654076 --6.43690490723,1.82449448109,3.62437868118 --6.45688581467,1.82750058174,3.6079685688 --6.46686840057,1.82650613785,3.58656835556 --6.47885894775,1.82850909233,3.58037757874 --6.4858417511,1.82751476765,3.55595684052 --6.48582601547,1.82352018356,3.52854824066 --6.50180864334,1.82552564144,3.51115822792 --6.51878976822,1.82653141022,3.49274563789 --6.5057759285,1.81953644753,3.4583337307 --6.54775476456,1.82854259014,3.45494747162 --6.55374526978,1.82854533195,3.44474697113 --6.56772851944,1.8295507431,3.425344944 --6.58271026611,1.83055639267,3.40593528748 --6.59369325638,1.8305618763,3.38452744484 --6.60867500305,1.83156728745,3.36511850357 --6.63165616989,1.83557283878,3.35072469711 --6.64363956451,1.83557808399,3.33032512665 --6.65563011169,1.83758080006,3.3231253624 --6.64961576462,1.83258581161,3.29271054268 --6.65160036087,1.83059084415,3.26730966568 --6.66458320618,1.83059620857,3.2469022274 --6.68656492233,1.83460140228,3.23150444031 --6.70754671097,1.83760666847,3.21510004997 --6.72552871704,1.83961200714,3.19668841362 --6.73052072525,1.83961439133,3.18649697304 --6.74450302124,1.84061968327,3.16608452797 --6.76348543167,1.84262466431,3.14868283272 --6.7654709816,1.84062957764,3.12328052521 --6.791451931,1.84463465214,3.10887694359 --6.79943656921,1.84463953972,3.08647799492 --6.80042123795,1.84164452553,3.06006598473 --6.81241226196,1.84364688396,3.05287241936 --6.82139635086,1.84365177155,3.03046607971 --6.84337854385,1.84665668011,3.01406359673 --6.85536193848,1.847661376,2.99265313148 --6.86134672165,1.84666621685,2.96925234795 --6.8793296814,1.84867095947,2.95084834099 --6.87932252884,1.84767317772,2.93764448166 --6.90130472183,1.85167789459,2.92124629021 --6.9002904892,1.84768247604,2.89484500885 --6.92527294159,1.85268700123,2.87944412231 --6.9312582016,1.85169160366,2.85604333878 --6.93924236298,1.85169625282,2.83262896538 --6.97022390366,1.85770070553,2.81922507286 --6.96421766281,1.85470294952,2.80402708054 --6.9712023735,1.85370743275,2.78061962128 --6.98218727112,1.85471177101,2.75921821594 --6.98817157745,1.85371637344,2.734801054 --6.99515724182,1.85272061825,2.71240878105 --7.01813983917,1.85672485828,2.69601368904 --7.04212236404,1.86072921753,2.67859840393 --7.04811525345,1.86173129082,2.66840362549 --7.05709981918,1.86173558235,2.64600110054 --7.05808591843,1.85973966122,2.62059783936 --7.0690703392,1.85974407196,2.59818315506 --7.09505367279,1.86474788189,2.58279275894 --7.09803962708,1.86375212669,2.55839323997 --7.09802532196,1.86075639725,2.5319788456 --7.11101722717,1.86375832558,2.52377700806 --7.1180024147,1.86276245117,2.50037026405 --7.12098884583,1.86176657677,2.47596955299 --7.12897396088,1.86177062988,2.45255661011 --7.14095878601,1.86277449131,2.43115377426 --7.15794324875,1.86477816105,2.41175675392 --7.16392946243,1.86478209496,2.38835525513 --7.17392110825,1.86578416824,2.37814116478 --7.18290662766,1.86678802967,2.35573983192 --7.20389080048,1.86979162693,2.33734035492 --7.20587778091,1.8687953949,2.31294417381 --7.20686388016,1.86679947376,2.28652048111 --7.21784973145,1.86780297756,2.2651257515 --7.23084163666,1.86980473995,2.25693082809 --7.2368273735,1.86980855465,2.23251390457 --7.24081373215,1.86881232262,2.20810651779 --7.25679922104,1.87081551552,2.18872070312 --7.26078557968,1.86981940269,2.16431355476 --7.26777172089,1.86982297897,2.14090752602 --7.2897567749,1.87382602692,2.12251114845 --7.29175043106,1.87382781506,2.11030769348 --7.3137345314,1.87783098221,2.0908973217 --7.32572078705,1.87883424759,2.06950235367 --7.34070634842,1.8808375597,2.04809427261 --7.33269453049,1.8768414259,2.02069306374 --7.35068035126,1.87984442711,2.0002887249 --7.36866521835,1.88284730911,1.97988533974 --7.36965942383,1.88284909725,1.96768629551 --7.37664604187,1.8828523159,1.94428300858 --7.38663196564,1.88385570049,1.92086696625 --7.39561891556,1.88385879993,1.89847195148 --7.39460611343,1.88186240196,1.87205338478 --7.41159248352,1.88486516476,1.85165810585 --7.40658044815,1.88186872005,1.82525515556 --7.42657232285,1.88686954975,1.81806063652 --7.44955825806,1.89087200165,1.79866051674 --7.45054578781,1.88987541199,1.773250103 --7.46053218842,1.89087820053,1.74983716011 --7.48651790619,1.89588034153,1.73144567013 --7.47750711441,1.89188396931,1.70404016972 --7.48349428177,1.89188706875,1.67962682247 --7.49548768997,1.8948880434,1.67043614388 --7.47747612,1.88789212704,1.64001178741 --7.49346351624,1.89089441299,1.61962747574 --7.51844882965,1.89589643478,1.59921312332 --7.52343702316,1.8958991766,1.57582044601 --7.51942539215,1.89390254021,1.54940903187 --7.54041242599,1.89790463448,1.52901160717 --7.54440593719,1.89790594578,1.51680243015 --7.56139326096,1.90090799332,1.49540388584 --7.56838130951,1.90191066265,1.47200572491 --7.56236934662,1.89891397953,1.44458329678 --7.56935739517,1.89891648293,1.42118513584 --7.59134435654,1.90391814709,1.40079033375 --7.57333421707,1.89792215824,1.3713696003 --7.58532714844,1.89992284775,1.36117005348 --7.60731458664,1.9049243927,1.34077811241 --7.60830307007,1.90392708778,1.31536567211 --7.59529256821,1.89893066883,1.28795945644 --7.61528015137,1.90293228626,1.2665592432 --7.58926963806,1.89493668079,1.23613655567 --7.62025690079,1.90193748474,1.21674108505 --7.64324998856,1.90793740749,1.20854949951 --7.63623952866,1.90494048595,1.18214082718 --7.64622783661,1.90594232082,1.15873777866 --7.66221570969,1.90894389153,1.13633704185 --7.67020463943,1.90994596481,1.11294031143 --7.67819309235,1.91094791889,1.08852767944 --7.68518781662,1.91294884682,1.0773307085 --7.68417644501,1.91095125675,1.05192291737 --7.69316530228,1.91295313835,1.02852499485 --7.70115423203,1.91395509243,1.00411343575 --7.69714355469,1.91195774078,0.978711247444 --7.70413255692,1.91295969486,0.95430213213 --7.72912073135,1.91896009445,0.932906746864 --7.72911500931,1.91796147823,0.919693589211 --7.72810459137,1.91696381569,0.894284963608 --7.74309396744,1.91996490955,0.871895492077 --7.74408340454,1.91996705532,0.846483111382 --7.75207281113,1.92096877098,0.822074830532 --7.7720618248,1.92496931553,0.79967969656 --7.75805187225,1.92097270489,0.772259771824 --7.77104663849,1.92397248745,0.762074410915 --7.77903604507,1.9249740839,0.73766797781 --7.78202533722,1.92497599125,0.712253153324 --7.79901504517,1.92897641659,0.689867138863 --7.7920050621,1.92597925663,0.663450777531 --7.80199432373,1.92798030376,0.639043152332 --7.80498456955,1.92798197269,0.61464548111 --7.80797958374,1.92898261547,0.602444589138 --7.80996990204,1.92898440361,0.57703179121 --7.8199596405,1.93098556995,0.55262607336 --7.81694984436,1.92898762226,0.527219355106 --7.82693958282,1.9309886694,0.502814590931 --7.82693004608,1.93099045753,0.477404147387 --7.82892084122,1.93099200726,0.453008145094 --7.83391571045,1.93199241161,0.440806418657 --7.84690570831,1.93499290943,0.416400969028 --7.84389638901,1.93299496174,0.390993595123 --7.85088682175,1.93499588966,0.366594135761 --7.850877285,1.93399751186,0.341184109449 --7.84286832809,1.93200004101,0.315778881311 --7.84786272049,1.93300044537,0.302562087774 --7.83685398102,1.93000304699,0.277157664299 --7.84684467316,1.93200361729,0.25275734067 --7.86283588409,1.93600356579,0.228354945779 --7.86682605743,1.93600463867,0.202942997217 --7.87381696701,1.93800532818,0.17854629457 --7.8688082695,1.93600738049,0.153137907386 --7.87579917908,1.93800806999,0.127725407481 --7.8817949295,1.93900799751,0.115527190268 --7.88278579712,1.93900918961,0.0901170298457 --7.88377714157,1.9390103817,0.0657232627273 --7.88076782227,1.93801212311,0.0403134636581 --7.88875961304,1.9400125742,0.0149028925225 --7.87975025177,1.93801486492,-0.0105074075982 --7.8747420311,1.93601667881,-0.0359181128442 --7.87473773956,1.93601727486,-0.0481153316796 --7.88172912598,1.93801772594,-0.0735251903534 --7.88372039795,1.93801856041,-0.0989351943135 --7.88971233368,1.9400190115,-0.123327836394 --7.88370370865,1.93802082539,-0.148739770055 --7.88669490814,1.93902146816,-0.174149274826 --7.88069057465,1.93702280521,-0.186348453164 --7.88468265533,1.93802332878,-0.21175737679 --7.88967466354,1.94002377987,-0.23716558516 --7.89166641235,1.94002449512,-0.26257455349 --7.89565849304,1.94102489948,-0.287982225418 --7.90865087509,1.94502413273,-0.31338378787 --7.8886423111,1.94002759457,-0.337790638208 --7.89863824844,1.94202673435,-0.350996434689 --7.89963054657,1.94302749634,-0.376405477524 --7.90362262726,1.94402778149,-0.401811599731 --7.8946146965,1.94202971458,-0.426212489605 --7.89560699463,1.94203031063,-0.451621085405 --7.8985991478,1.94303071499,-0.477027654648 --7.89659166336,1.94303166866,-0.502439081669 --7.9015879631,1.94403135777,-0.515646517277 --7.90458011627,1.9450315237,-0.541052103043 --7.90357303619,1.94503223896,-0.565445661545 --7.90256547928,1.94503295422,-0.59085559845 --7.90055751801,1.94503378868,-0.616266787052 --7.9075512886,1.94703328609,-0.641666054726 --7.89854288101,1.94503509998,-0.667086541653 --7.91854047775,1.95103251934,-0.680271029472 --7.91553354263,1.95003330708,-0.705682516098 --7.90352535248,1.94803547859,-0.731108129025 --7.90051794052,1.94703626633,-0.755504131317 --7.91251182556,1.95103490353,-0.781908988953 --7.91050481796,1.95103549957,-0.807319223881 --7.9164981842,1.95303487778,-0.83271586895 --7.91149425507,1.95203566551,-0.845935940742 --7.92248821259,1.95503425598,-0.872338831425 --7.91248035431,1.95303595066,-0.896746814251 --7.92647504807,1.9570338726,-0.923142492771 --7.92046833038,1.95603501797,-0.94855928421 --7.92346191406,1.95803463459,-0.973958671093 --7.91945457458,1.95703530312,-0.999371469021 --7.91045045853,1.95503675938,-1.01158452034 --7.92144536972,1.95903503895,-1.03798258305 --7.9124379158,1.957036376,-1.06239020824 --7.923432827,1.96103465557,-1.08878648281 --7.92042684555,1.9610350132,-1.11419701576 --7.91041946411,1.95903658867,-1.13860762119 --7.92041444778,1.9620347023,-1.16601967812 --7.92141151428,1.9630343914,-1.17821085453 --7.90440320969,1.95903718472,-1.20263910294 --7.9143986702,1.96303522587,-1.22903358936 --7.92739439011,1.96703267097,-1.25643503666 --7.92738819122,1.96803224087,-1.28285253048 --7.91438102722,1.96503424644,-1.30625605583 --7.93037700653,1.97003102303,-1.33466231823 --7.93237400055,1.97103047371,-1.34786510468 --7.92636823654,1.97103106976,-1.37226593494 --7.94036436081,1.97602808475,-1.40067434311 --7.92735767365,1.97302985191,-1.42407858372 --7.92535161972,1.97302961349,-1.45049953461 --7.93234729767,1.97702789307,-1.47689390182 --7.92934465408,1.97602808475,-1.48909378052 --7.92633867264,1.97702801228,-1.51551735401 --7.92833375931,1.97802686691,-1.54192471504 --7.93232917786,1.98002529144,-1.56832540035 --7.92532348633,1.98002588749,-1.59272885323 --7.91331672668,1.97802746296,-1.61714875698 --7.91131162643,1.97802698612,-1.64255201817 --7.90930891037,1.97802698612,-1.6557649374 --7.91730546951,1.98202455044,-1.68316626549 --7.90929985046,1.98102521896,-1.70757341385 --7.91029500961,1.9820240736,-1.73398113251 --7.90929031372,1.98302316666,-1.76039540768 --7.91928672791,1.98702025414,-1.78880155087 --7.91128158569,1.98602080345,-1.8132083416 --7.90827894211,1.98602080345,-1.8254083395 --7.90927505493,1.9880194664,-1.85181391239 --7.90827035904,1.98901855946,-1.87822628021 --7.90426540375,1.98901820183,-1.90363371372 --7.8932595253,1.98801910877,-1.9280526638 --7.88625431061,1.98701941967,-1.95245611668 --7.89825248718,1.9920156002,-1.9818636179 --7.89925050735,1.99301469326,-1.99506294727 --7.88224411011,1.99001693726,-2.01747488976 --7.87823963165,1.99001634121,-2.04288172722 --7.87623548508,1.99101543427,-2.0692961216 --7.87623214722,1.993013978,-2.09570193291 --7.87422800064,1.99401283264,-2.12211537361 --7.88722658157,1.99900853634,-2.15151119232 --7.89722681046,2.00200557709,-2.16771626472 --7.87721967697,1.99900829792,-2.18912816048 --7.87921667099,2.0010061264,-2.21653747559 --7.895216465,2.00700092316,-2.24693083763 --7.88321113586,2.00500178337,-2.27135419846 --7.88420820236,2.00699973106,-2.2977502346 --7.87420368195,2.00600028038,-2.32216501236 --7.87820243835,2.00799822807,-2.33737707138 --7.88320064545,2.01099538803,-2.36476874352 --7.89319992065,2.01599097252,-2.3951818943 --7.88219547272,2.01499152184,-2.41858506203 --7.88319301605,2.01698923111,-2.44599246979 --7.89819335938,2.02298378944,-2.47739291191 --7.88018703461,2.01998591423,-2.49981427193 --7.87818527222,2.01998519897,-2.51302146912 --7.89318609238,2.02597951889,-2.54441809654 --7.88418245316,2.02597928047,-2.56882619858 --7.89218187332,2.02997493744,-2.59923958778 --7.9051823616,2.03496932983,-2.63064098358 --7.88617610931,2.03197193146,-2.65205311775 --7.8861746788,2.03396916389,-2.67945885658 --7.89717626572,2.03896546364,-2.69665765762 --7.87416934967,2.03396844864,-2.71707606316 --7.89417266846,2.04196095467,-2.75148034096 --7.89517116547,2.04495787621,-2.77887821198 --7.87816572189,2.04195976257,-2.80129575729 --7.88116502762,2.04495596886,-2.83071136475 --7.90116930008,2.05194973946,-2.85090065002 --7.88916492462,2.05094981194,-2.87532091141 --7.88616275787,2.05194807053,-2.90172147751 --7.89316368103,2.05594325066,-2.93212580681 --7.88816165924,2.05694150925,-2.95853614807 --7.88315963745,2.05793976784,-2.98494625092 --7.90216398239,2.06593179703,-3.01933813095 --7.88315868378,2.0619354248,-3.02756237984 --7.89215993881,2.06692957878,-3.05896449089 --7.90716362,2.07292246819,-3.09235930443 --7.88515758514,2.06992530823,-3.11277675629 --7.88215637207,2.07092261314,-3.14018630981 --7.89315891266,2.0769162178,-3.17258572578 --7.89115858078,2.07891345024,-3.20100188255 --7.89515972137,2.08091044426,-3.2172088623 --7.90716314316,2.08690357208,-3.25061202049 --7.89315891266,2.0859041214,-3.273011446 --7.90516281128,2.09189724922,-3.30641174316 --7.90416288376,2.09389352798,-3.33583164215 --7.89616155624,2.09489250183,-3.36123657227 --7.90116357803,2.09888696671,-3.39264655113 --7.90516519547,2.10288214684,-3.42304706573 --7.92517137527,2.10987401009,-3.4462480545 --7.93217420578,2.11486816406,-3.47764086723 --7.92017221451,2.1138677597,-3.50205254555 --7.90616893768,2.11286783218,-3.52647733688 --7.90817117691,2.11686301231,-3.55688500404 --7.9141740799,2.12085723877,-3.5892932415 --7.90817308426,2.12085676193,-3.60149884224 --7.91217565536,2.12485122681,-3.63290429115 --7.93018293381,2.13284134865,-3.6703004837 --7.92418289185,2.1348388195,-3.697712183 --7.91718244553,2.13583636284,-3.72512984276 --7.90318012238,2.13483643532,-3.74853825569 --7.87917423248,2.13083934784,-3.76795840263 --7.86817216873,2.12984037399,-3.77816939354 --7.85416889191,2.12884044647,-3.8015794754 --7.81115722656,2.11984944344,-3.81302118301 --7.80015563965,2.11984848976,-3.83742690086 --7.78015136719,2.11685013771,-3.85885262489 --7.75614595413,2.11385321617,-3.87828040123 --7.73814201355,2.11185455322,-3.89969444275 --7.74214410782,2.11485075951,-3.91690015793 --7.72013950348,2.11185336113,-3.9363155365 --7.70313644409,2.10985398293,-3.95873785019 --7.68513250351,2.10785531998,-3.98015403748 --7.66412782669,2.10585737228,-4.00057888031 --7.6511259079,2.10485696793,-4.02398777008 --7.63712310791,2.10485672951,-4.04740476608 --7.62311983109,2.10185909271,-4.05561637878 --7.59511232376,2.09686350822,-4.0720410347 --7.59011363983,2.09986019135,-4.10046100616 --7.56910896301,2.09686231613,-4.11987638474 --7.56110906601,2.0978603363,-4.14629077911 --7.54810762405,2.09785962105,-4.16970205307 --7.52810335159,2.09486150742,-4.19012498856 --7.52510356903,2.09586000443,-4.20332479477 --7.50710058212,2.094861269,-4.22474765778 --7.48309421539,2.09086418152,-4.24317646027 --7.48009681702,2.09386014938,-4.27157878876 --7.47109699249,2.09485793114,-4.29800033569 --7.45509433746,2.09385848045,-4.31940889359 --7.45409822464,2.09785342216,-4.34982013702 --7.44309568405,2.09585475922,-4.35902786255 --7.43309545517,2.09685254097,-4.38545608521 --7.4140920639,2.09485435486,-4.40486240387 --7.39408826828,2.09285593033,-4.42529058456 --7.37608480453,2.0918571949,-4.44570350647 --7.3610830307,2.09085702896,-4.46811914444 --7.34908246994,2.09185600281,-4.49253749847 --7.33107662201,2.087859869,-4.49775123596 --7.31407403946,2.08686041832,-4.51917171478 --7.30907678604,2.0898566246,-4.54758548737 --7.28907299042,2.08785843849,-4.5670042038 --7.27907323837,2.08885645866,-4.59241867065 --7.24206161499,2.08186483383,-4.60185003281 --7.21505451202,2.07786941528,-4.61727809906 --7.21805858612,2.08086514473,-4.63447761536 --7.20305681229,2.07986521721,-4.65689611435 --7.17905092239,2.07686853409,-4.6743273735 --7.16004753113,2.07587003708,-4.69374227524 --7.15004825592,2.07686781883,-4.71915817261 --7.1220407486,2.07287311554,-4.73358678818 --7.09903526306,2.069876194,-4.75 --7.09603691101,2.07087397575,-4.76522302628 --7.06302642822,2.06488180161,-4.77463436127 --7.05202722549,2.06587982178,-4.80005979538 --7.04202795029,2.06787729263,-4.82547712326 --7.01502084732,2.06388235092,-4.83990335464 --6.99901914597,2.06288266182,-4.86132192612 --6.98701620102,2.06188440323,-4.869535923 --6.96100902557,2.05788874626,-4.88395595551 --6.94500684738,2.05788898468,-4.90537643433 --6.93500852585,2.05888700485,-4.93079376221 --6.91300344467,2.05688977242,-4.94720506668 --6.88399505615,2.05189585686,-4.95963096619 --6.8799996376,2.05589056015,-4.99005699158 --6.85799121857,2.05089664459,-4.99127674103 --6.84699201584,2.0518951416,-5.01467752457 --6.83199119568,2.05189490318,-5.03710365295 --6.79898023605,2.04690241814,-5.04653406143 --6.78598022461,2.04690122604,-5.06995391846 --6.77598190308,2.04889917374,-5.09435844421 --6.74097013474,2.04290771484,-5.10279989243 --6.73497009277,2.04290676117,-5.11501169205 --6.72797393799,2.04590296745,-5.14242506027 --6.69596338272,2.03991055489,-5.1518535614 --6.67495918274,2.03891301155,-5.16927719116 --6.67096471786,2.04190778732,-5.19868564606 --6.63495159149,2.03491711617,-5.20511960983 --6.61494779587,2.03391909599,-5.22354745865 --6.61795377731,2.0379140377,-5.24174594879 --6.58394145966,2.03092265129,-5.24917602539 --6.56493854523,2.0299243927,-5.26759576797 --6.55394029617,2.03192210197,-5.29302310944 --6.51992845535,2.02593111992,-5.29944610596 --6.50993061066,2.02792835236,-5.32486248016 --6.49593019485,2.02792739868,-5.34728288651 --6.46991872787,2.02193641663,-5.343501091 --6.46492433548,2.02593135834,-5.37291574478 --6.44391965866,2.02393388748,-5.38933420181 --6.41991424561,2.02193760872,-5.40477228165 --6.39990997314,2.01994013786,-5.42118167877 --6.38390874863,2.01994037628,-5.44159889221 --6.35389900208,2.01594758034,-5.45102882385 --6.34990119934,2.01694536209,-5.46524477005 --6.33690214157,2.01794409752,-5.48765516281 --6.30288934708,2.01195335388,-5.49409341812 --6.28288602829,2.01095557213,-5.51151895523 --6.27388954163,2.01395201683,-5.53793621063 --6.23587417603,2.00596380234,-5.53936052322 --6.22287511826,2.00796222687,-5.56278562546 --6.21987771988,2.0089597702,-5.57698917389 --6.18786621094,2.00396823883,-5.58442592621 --6.1698641777,2.00396943092,-5.60284471512 --6.15486335754,2.00396895409,-5.62426614761 --6.12885570526,2.00097441673,-5.6356883049 --6.10484981537,1.99897897243,-5.64911460876 --6.09385251999,2.00097608566,-5.67454051971 --6.0768456459,1.99798107147,-5.67675542831 --6.05584144592,1.99598407745,-5.69217348099 --6.04984760284,1.99997866154,-5.72159051895 --6.01883649826,1.99498713017,-5.72801446915 --6.00183486938,1.99498772621,-5.7474360466 --5.98983716965,1.99698543549,-5.77186012268 --5.96583127975,1.99498987198,-5.78529071808 --5.95282745361,1.99299275875,-5.79049968719 --5.94183015823,1.9949901104,-5.81491184235 --5.90881681442,1.98999977112,-5.81934213638 --5.89381742477,1.9909992218,-5.84076547623 --5.87781667709,1.9909992218,-5.86118793488 --5.85481119156,1.98900330067,-5.87461042404 --5.84280824661,1.9880053997,-5.88183355331 --5.82880926132,1.98900449276,-5.90324497223 --5.80680418015,1.9880079031,-5.91766881943 --5.78179740906,1.98501300812,-5.93010568619 --5.75979232788,1.98401653767,-5.9445309639 --5.74479293823,1.98501574993,-5.96595430374 --5.72478961945,1.98401844501,-5.98136806488 --5.71979141235,1.98501646519,-5.99457836151 --5.69378328323,1.98202252388,-6.00500679016 --5.66977739334,1.98002719879,-6.01743602753 --5.65477800369,1.98102653027,-6.03885889053 --5.63577508926,1.98102843761,-6.0552740097 --5.61577224731,1.98003041744,-6.07271194458 --5.59276676178,1.97803485394,-6.08513069153 --5.56775188446,1.97204554081,-6.07734775543 --5.55175256729,1.97304534912,-6.0977730751 --5.54175758362,1.9760414362,-6.12419080734 --5.51374769211,1.97204875946,-6.13262891769 --5.49974966049,1.97404754162,-6.15403938293 --5.48274898529,1.97504782677,-6.17346525192 --5.45473861694,1.97105550766,-6.18089437485 --5.44573783875,1.9710559845,-6.19010782242 --5.43274068832,1.97305381298,-6.21352767944 --5.40573167801,1.97006070614,-6.2219581604 --5.38572883606,1.96906304359,-6.2383890152 --5.36772727966,1.9690643549,-6.25580501556 --5.3427195549,1.96707034111,-6.26522397995 --5.32772111893,1.96806931496,-6.28664588928 --5.31671857834,1.9680711031,-6.29386425018 --5.29271173477,1.96607613564,-6.30529260635 --5.27370977402,1.96607780457,-6.32272291183 --5.25670957565,1.9660782814,-6.34113788605 --5.23570632935,1.96608114243,-6.35657262802 --5.20769500732,1.96208906174,-6.36300230026 --5.19569969177,1.96508610249,-6.3874168396 --5.17669010162,1.96109342575,-6.38564395905 --5.16069030762,1.96209323406,-6.40505695343 --5.12867593765,1.95710396767,-6.40750074387 --5.11167669296,1.95810413361,-6.42692708969 --5.09467554092,1.9591050148,-6.44433259964 --5.0766749382,1.95910596848,-6.46276140213 --5.05467033386,1.95810961723,-6.47619152069 --5.04567050934,1.9591101408,-6.48540592194 --5.02867031097,1.96011018753,-6.50483179092 --5.00065946579,1.95611870289,-6.5102596283 --4.97765302658,1.95512342453,-6.52168369293 --4.95865106583,1.95512521267,-6.53810596466 --4.93764734268,1.95412838459,-6.55253458023 --4.91163873672,1.95213508606,-6.56096982956 --4.91164779663,1.95612895489,-6.58117485046 --4.88463783264,1.95313668251,-6.58760452271 --4.87264347076,1.95613312721,-6.61302280426 --4.85864782333,1.95813071728,-6.63644647598 --4.83163738251,1.95513856411,-6.6428771019 --4.80462741852,1.95214641094,-6.64930915833 --4.78862905502,1.95414614677,-6.6687207222 --4.77462291718,1.95215010643,-6.67194461823 --4.75862503052,1.95414960384,-6.69236516953 --4.73662090302,1.9531532526,-6.70579957962 --4.71461582184,1.9521573782,-6.71822404861 --4.69261074066,1.95116150379,-6.73064899445 --4.68462324142,1.95715379715,-6.76307487488 --4.66360902786,1.95216417313,-6.75529050827 --4.65361785889,1.956158638,-6.78370285034 --4.63061285019,1.95516300201,-6.79614210129 --4.59759521484,1.9501761198,-6.79357910156 --4.57458877563,1.94818127155,-6.80400037766 --4.55959272385,1.95117950439,-6.82642412186 --4.52557325363,1.94519364834,-6.82186031342 --4.51057720184,1.94719147682,-6.84529256821 --4.50858592987,1.95118618011,-6.86349201202 --4.47456645966,1.94520044327,-6.85893106461 --4.44955825806,1.94320702553,-6.86736536026 --4.43255901337,1.94420731068,-6.88577890396 --4.4055480957,1.94121563435,-6.8912153244 --4.39355659485,1.9452111721,-6.91763067245 --4.38355636597,1.94621181488,-6.92685890198 --4.35654497147,1.94322049618,-6.93128728867 --4.33954572678,1.94422078133,-6.94969940186 --4.32254886627,1.9462198019,-6.97113895416 --4.29754018784,1.94422674179,-6.97856712341 --4.27753829956,1.94522893429,-6.9939956665 --4.25653505325,1.94523227215,-7.00742053986 --4.24753522873,1.94523251057,-7.01663303375 --4.22853469849,1.94623410702,-7.03305530548 --4.20252513885,1.944242239,-7.03848314285 --4.16750240326,1.93725824356,-7.03092861176 --4.14649915695,1.93726158142,-7.04435491562 --4.13350725174,1.9412573576,-7.07077693939 --4.1084985733,1.93926429749,-7.07820987701 --4.09749698639,1.93926632404,-7.08442640305 --4.07749557495,1.94026863575,-7.09985589981 --4.05048274994,1.93727779388,-7.10328531265 --4.02947950363,1.93728148937,-7.11570358276 --4.01248311996,1.93928039074,-7.1371383667 --3.97846055031,1.93329679966,-7.1285738945 --3.9614636898,1.93529605865,-7.14900064468 --3.95246434212,1.93629622459,-7.15821266174 --3.91944265366,1.93031191826,-7.15064525604 --3.89844036102,1.93031489849,-7.16508150101 --3.87743711472,1.93031823635,-7.17851018906 --3.84942293167,1.92732906342,-7.17893743515 --3.83042311668,1.92833018303,-7.19636917114 --3.81142377853,1.93033123016,-7.21379995346 --3.79140686989,1.92534315586,-7.20301675797 --3.77140498161,1.92534577847,-7.21743869781 --3.7504029274,1.92634880543,-7.23187637329 --3.724391222,1.92335784435,-7.23530197144 --3.70138549805,1.92336308956,-7.24573898315 --3.67737793922,1.92236948013,-7.25417518616 --3.6643717289,1.92037427425,-7.25538492203 --3.64136624336,1.92037951946,-7.26582288742 --3.61835932732,1.91938555241,-7.27424478531 --3.59535288811,1.91839122772,-7.28367519379 --3.56733822823,1.91540229321,-7.28411388397 --3.55034279823,1.91840112209,-7.30554437637 --3.52232599258,1.91441333294,-7.30296182632 --3.50132346153,1.9144166708,-7.31639289856 --3.48931980133,1.91441988945,-7.32061290741 --3.46531224251,1.91342639923,-7.32905387878 --3.43429017067,1.90744233131,-7.32047700882 --3.4132874012,1.90744566917,-7.33390903473 --3.39629220963,1.91044437885,-7.35533714294 --3.3782954216,1.91344416142,-7.37476587296 --3.36929655075,1.91444420815,-7.3839764595 --3.34228348732,1.91145420074,-7.38642168045 --2.19293785095,1.89477825165,-7.77782964706 --2.17090034485,1.88480222225,-7.74604845047 --2.14688968658,1.88381123543,-7.74947786331 --2.11786437035,1.87882936001,-7.73792123795 --2.09686470032,1.88083171844,-7.75335788727 --2.07586455345,1.88283443451,-7.76778936386 --2.05285692215,1.88284182549,-7.77421712875 --2.02583813667,1.8798558712,-7.76966333389 --2.01684212685,1.88185477257,-7.78087091446 --1.99484169483,1.88385784626,-7.79531812668 --1.96480727196,1.8768812418,-7.77374076843 --1.94180107117,1.8768876791,-7.78217887878 --1.92481839657,1.88388025761,-7.81461906433 --1.89679312706,1.87889814377,-7.80305480957 --1.8867944479,1.88089895248,-7.8112654686 --1.86579608917,1.88290071487,-7.82770204544 --1.83877301216,1.87891721725,-7.81813192368 --1.81576538086,1.87892460823,-7.82456064224 --1.78874635696,1.87593901157,-7.82001447678 --1.76071918011,1.87095808983,-7.8064494133 --1.74072253704,1.87395882607,-7.82387256622 --1.73373746872,1.87895154953,-7.84608459473 --1.70671403408,1.87496840954,-7.83652067184 --1.68069636822,1.87298190594,-7.83296442032 --1.66271221638,1.8789755106,-7.86339998245 --1.63669121265,1.87599110603,-7.85582876205 --1.61167645454,1.87400269508,-7.85526704788 --1.58967399597,1.8760073185,-7.86669874191 --1.57566201687,1.87401592731,-7.86192798615 --1.55164968967,1.87302625179,-7.86335849762 --1.52965056896,1.87502896786,-7.87880325317 --1.50362658501,1.87104594707,-7.86822605133 --1.48062372208,1.87305104733,-7.87967443466 --1.45761620998,1.8730584383,-7.88610506058 --1.43259823322,1.87107229233,-7.88153362274 --1.42159736156,1.87207424641,-7.88775014877 --1.4016058445,1.87607252598,-7.91018009186 --1.37357544899,1.87109363079,-7.89362430573 --1.35057079792,1.87209951878,-7.90306472778 --1.32656109333,1.87210845947,-7.90750694275 --1.30355012417,1.87111794949,-7.90992450714 --1.27953886986,1.87112796307,-7.91236066818 --1.26854360104,1.87312698364,-7.92459392548 --1.24352443218,1.87114143372,-7.91902446747 --1.22152495384,1.8731443882,-7.9334602356 --1.19348669052,1.86616969109,-7.90889072418 --1.16746497154,1.86318576336,-7.90133714676 --1.14546191692,1.86419069767,-7.91176176071 --1.12145328522,1.86519932747,-7.91720867157 --1.10844063759,1.86320829391,-7.91142749786 --1.08442902565,1.86221837997,-7.91386651993 --1.06041669846,1.8622289896,-7.91530370712 --1.03640520573,1.86123895645,-7.91774272919 --1.01642048359,1.86823403835,-7.94617557526 --0.992404282093,1.86624658108,-7.94360160828 --0.979391396046,1.86425566673,-7.93782234192 --0.955379188061,1.86426639557,-7.93926000595 --0.932371079922,1.8642745018,-7.94468832016 --0.905340909958,1.85929524899,-7.92914247513 --0.880318522453,1.85631155968,-7.92057752609 --0.858322560787,1.86031317711,-7.93801498413 --0.833296298981,1.85633146763,-7.92544317245 --0.80928760767,1.85634016991,-7.93089103699 --0.799293577671,1.85933864117,-7.9430975914 --0.773263692856,1.85435914993,-7.92754030228 --0.7502566576,1.85536682606,-7.9339723587 --0.727253615856,1.85737240314,-7.94441127777 --0.702229082584,1.85438990593,-7.93384838104 --0.678217709064,1.85440027714,-7.9362912178 --0.667216479778,1.85540282726,-7.94150161743 --0.642196655273,1.85341787338,-7.93594932556 --0.618180155754,1.85143077374,-7.93338441849 --0.595178365707,1.85443580151,-7.94482374191 --0.571154892445,1.8504525423,-7.93524885178 --0.547141671181,1.8504639864,-7.93568992615 --0.522115707397,1.84648227692,-7.92413282394 --0.510108053684,1.8464884758,-7.92335271835 --0.487097173929,1.84649837017,-7.92577934265 --0.464095205069,1.84850358963,-7.93721675873 --0.438055604696,1.84152936935,-7.91266584396 --0.416059374809,1.84553134441,-7.92909097672 --0.391033440828,1.84254992008,-7.91754007339 --0.367009848356,1.83956682682,-7.90797328949 --0.356011778116,1.84156775475,-7.91618490219 --0.333013981581,1.84457063675,-7.93162488937 --0.307984769344,1.84059095383,-7.91707372665 --0.284970998764,1.84060263634,-7.91649913788 --0.261973291636,1.84360551834,-7.93193674088 --0.236928492785,1.83563411236,-7.90237808228 --0.213930130005,1.83963751793,-7.91681528091 --0.201923429966,1.83964335918,-7.91703796387 --0.177887186408,1.83366715908,-7.89547014236 --0.153881981969,1.83567452431,-7.90392112732 --0.130870059133,1.83568513393,-7.90534973145 --0.10685441643,1.83469796181,-7.90379524231 --0.0838321894407,1.83271431923,-7.89521980286 --0.0598145164549,1.83172821999,-7.89166641235 --0.0478055514395,1.83073532581,-7.88988876343 --0.0247990321368,1.83274316788,-7.89631986618 --0.00078554591164,1.8327549696,-7.89676713943 --0.00425220839679,1.81221699715,-7.034116745 -0.0197539571673,1.81021308899,-7.02752065659 -0.0427766144276,1.81321823597,-7.03690338135 -0.0657716691494,1.80820870399,-7.02029418945 -0.0778025463223,1.81422162056,-7.04348707199 -0.101810969412,1.81321883202,-7.03889083862 -0.124806381762,1.80920946598,-7.02228355408 -0.147828698158,1.81121456623,-7.03166484833 -0.171836212277,1.81021130085,-7.02607059479 -0.193829059601,1.80520093441,-7.00745201111 -0.217849001288,1.80720436573,-7.01385116577 -0.229860886931,1.80820715427,-7.0190486908 -0.252857595682,1.80419850349,-7.00344753265 -0.275871872902,1.80519926548,-7.00483322144 -0.298881858587,1.80419778824,-7.00222301483 -0.321881860495,1.80119097233,-6.98962211609 -0.344889998436,1.8001884222,-6.98501443863 -0.356898963451,1.80118966103,-6.98721456528 -0.379903107882,1.7991849184,-6.97861194611 -0.402911305428,1.7981826067,-6.97400522232 -0.425930589437,1.80018615723,-6.98038625717 -0.448934823275,1.79818153381,-6.97178554535 -0.472960472107,1.80118834972,-6.98417425156 -0.4959628582,1.79918265343,-6.97357654572 -0.506958186626,1.79617702961,-6.96277761459 -0.528964042664,1.79517364502,-6.956158638 -0.551969349384,1.79316973686,-6.94855976105 -0.575989127159,1.79517328739,-6.95495605469 -0.599000513554,1.79517257214,-6.95334672928 -0.621002554893,1.79316723347,-6.94273662567 -0.644013941288,1.79316651821,-6.94112825394 -0.655015408993,1.7921640873,-6.93632364273 -0.678026795387,1.79216349125,-6.934715271 -0.700024008751,1.78815555573,-6.91911745071 -0.726958751678,1.76711237431,-6.83574008942 -0.74896222353,1.7651078701,-6.82613706589 -0.770970344543,1.76410579681,-6.82152462006 -0.781970381737,1.76310253143,-6.8147277832 -0.804988801479,1.76510572433,-6.82011127472 -0.826992332935,1.76310122013,-6.81051015854 -0.851016938686,1.7661075592,-6.82189655304 -0.872012376785,1.76209902763,-6.8042974472 -0.894018888474,1.76109600067,-6.79769134521 -0.917029798031,1.76109516621,-6.7950925827 -0.928031623363,1.76009309292,-6.79029369354 -0.949033915997,1.75808823109,-6.77968168259 -0.971038877964,1.75708436966,-6.77108240128 -0.995057821274,1.75908768177,-6.77648019791 -1.01606023312,1.75708281994,-6.7658700943 -1.03806316853,1.75507819653,-6.7552781105 -1.06107878685,1.75607991219,-6.75766658783 -1.07409930229,1.76008737087,-6.77184963226 -1.09207904339,1.7520711422,-6.73825645447 -1.1140857935,1.75106847286,-6.73165512085 -1.13609182835,1.7500654459,-6.72405719757 -1.15910494328,1.75106573105,-6.72345495224 -1.18212044239,1.75206768513,-6.72584295273 -1.19413208961,1.7540705204,-6.73103237152 -1.21513128281,1.75106394291,-6.71644067764 -1.23512983322,1.74805748463,-6.7018327713 -1.25814211369,1.74905753136,-6.70023345947 -1.28014981747,1.74805545807,-6.6946310997 -1.30316281319,1.74905598164,-6.69402837753 -1.3251709938,1.74905395508,-6.68842601776 -1.33517074585,1.7470511198,-6.68162250519 -1.35718142986,1.74805057049,-6.67900943756 -1.37818181515,1.74504482746,-6.66542053223 -1.40019500256,1.74604582787,-6.66579723358 -1.42220044136,1.74504256248,-6.65720701218 -1.44320464134,1.74403882027,-6.64760494232 -1.46722340584,1.74604213238,-6.6529955864 -1.4762185812,1.74403703213,-6.64119672775 -1.49722266197,1.74203336239,-6.63159561157 -1.51923167706,1.74203205109,-6.62699174881 -1.54324877262,1.74403452873,-6.63038921356 -1.5652577877,1.74403321743,-6.62578487396 -1.58727025986,1.74503386021,-6.62516403198 -1.6072665453,1.74202609062,-6.60658550262 -1.6202801466,1.74402987957,-6.61377668381 -1.64329493046,1.74603152275,-6.61516332626 -1.66430020332,1.74502849579,-6.60655975342 -1.68630921841,1.7450273037,-6.60195541382 -1.70631051064,1.74302232265,-6.58935403824 -1.73032677174,1.74502456188,-6.59175157547 -1.74932420254,1.74201786518,-6.57515287399 -1.76233613491,1.74402070045,-6.58034992218 -1.7853499651,1.74502193928,-6.58073949814 -1.80434608459,1.74201440811,-6.56215143204 -1.82735991478,1.74301552773,-6.562541008 -1.84535384178,1.73900723457,-6.54194784164 -1.87338685989,1.74601757526,-6.5623216629 -1.89241993427,1.75403046608,-6.5895075798 -3.01982665062,1.76595294476,-6.24821424484 -3.03381848335,1.7609449625,-6.2236289978 -3.05783057213,1.76294565201,-6.22102928162 -3.07683348656,1.76194214821,-6.20843029022 -3.09884238243,1.76294159889,-6.20282268524 -3.11884665489,1.76293873787,-6.19123125076 -3.12985086441,1.76293838024,-6.18842744827 -3.1468501091,1.76093351841,-6.17183017731 -3.16785621643,1.76093149185,-6.16223907471 -3.19086790085,1.76293206215,-6.15962171555 -3.21187376976,1.7629301548,-6.15003013611 -3.23789024353,1.76693248749,-6.15241622925 -3.25889611244,1.76693058014,-6.14282417297 -3.27691268921,1.77093505859,-6.15301799774 -3.28890395164,1.76692712307,-6.12742042542 -3.31091094017,1.76692557335,-6.11883544922 -3.32991480827,1.76692295074,-6.10722923279 -3.35693264008,1.77092599869,-6.11160898209 -3.37593460083,1.76992237568,-6.09702825546 -3.3979575634,1.77592945099,-6.11421775818 -3.41595935822,1.77492618561,-6.10061216354 -3.43496203423,1.77392280102,-6.08702230453 -3.45296382904,1.77291953564,-6.07341814041 -3.47797656059,1.77592015266,-6.07082223892 -3.49497699738,1.7739161253,-6.05522108078 -3.52499771118,1.77992022038,-6.06161928177 -3.529992342,1.77691602707,-6.04781961441 -3.55400371552,1.77891635895,-6.04421615601 -3.57400870323,1.77891421318,-6.03361463547 -3.60202670097,1.78391706944,-6.0370054245 -3.61602139473,1.77991080284,-6.01442337036 -3.64203548431,1.78291237354,-6.01381969452 -3.66103959084,1.78290987015,-6.00221157074 -3.66903829575,1.78190732002,-5.99242258072 -3.6910469532,1.7829066515,-5.98581361771 -3.70904874802,1.78190326691,-5.97121858597 -3.73506236076,1.78490447998,-5.96962118149 -3.75907301903,1.78690457344,-5.96502065659 -3.78007936478,1.78790307045,-5.95542287827 -3.80709505081,1.79190516472,-5.95680809021 -3.80407857895,1.78489685059,-5.93002128601 -3.83209490776,1.78889906406,-5.93142032623 -3.85910964012,1.7929006815,-5.9308218956 -3.87711238861,1.79189801216,-5.91820812225 -3.89811849594,1.79289627075,-5.90761804581 -3.92112755775,1.79389572144,-5.9010181427 -3.94714045525,1.79689657688,-5.89842176437 -3.94813084602,1.79289114475,-5.87962198257 -3.97514533997,1.79689264297,-5.87901878357 -3.99114465714,1.79488861561,-5.86142539978 -4.0071439743,1.79288434982,-5.84284257889 -4.02314376831,1.7918806076,-5.82624101639 -4.0511598587,1.79588258266,-5.82663965225 -4.076171875,1.7988833189,-5.8240237236 -4.08717536926,1.79888272285,-5.81923007965 -4.09616565704,1.79387521744,-5.79065132141 -4.11617088318,1.79487359524,-5.78004550934 -4.14719009399,1.79987692833,-5.78444099426 -4.15818357468,1.79587054253,-5.75886249542 -4.18920326233,1.80187404156,-5.76424455643 -4.20220899582,1.80287444592,-5.76244688034 -4.21620702744,1.80086994171,-5.74284887314 -4.24622344971,1.80587232113,-5.74425506592 -4.26723003387,1.80687093735,-5.73465013504 -4.28523254395,1.80586826801,-5.72005605698 -4.30223417282,1.80486500263,-5.70346879959 -4.32624435425,1.80786526203,-5.69885110855 -4.34125328064,1.80986654758,-5.70004606247 -4.36225938797,1.8108651638,-5.68945026398 -4.38426589966,1.81186378002,-5.67886686325 -4.40026664734,1.81086051464,-5.66226625443 -4.41626691818,1.80985701084,-5.64467668533 -4.44227933884,1.8128579855,-5.64206075668 -4.45727825165,1.81085395813,-5.62247991562 -4.46427679062,1.80985164642,-5.6116938591 -4.48928880692,1.81285238266,-5.6080737114 -4.50428819656,1.81184864044,-5.58948230743 -4.53330373764,1.81585073471,-5.58987045288 -4.55631113052,1.81784975529,-5.58028650284 -4.57531547546,1.81784784794,-5.56768226624 -4.59632158279,1.81884670258,-5.55708217621 -4.60532331467,1.81884539127,-5.54929018021 -4.62332630157,1.81884276867,-5.53370523453 -4.6543431282,1.8238452673,-5.53609037399 -4.66734027863,1.8218408823,-5.51450681686 -4.68434286118,1.82083833218,-5.49890947342 -4.70534849167,1.82183682919,-5.48731899261 -4.70834350586,1.81983363628,-5.4725279808 -4.73936080933,1.82483613491,-5.47490739822 -4.75235891342,1.82283222675,-5.45431470871 -4.77136278152,1.82283008099,-5.43973207474 -4.79937601089,1.82683122158,-5.43712615967 -4.74730920792,1.79880571365,-5.33860301971 -4.68222999573,1.76477634907,-5.22510147095 -4.61715984344,1.73575127125,-5.13038253784 -4.61414384842,1.72774326801,-5.0928068161 -4.63515138626,1.72874307632,-5.08321094513 -4.64214611053,1.72473835945,-5.05762481689 -4.65814971924,1.72473669052,-5.04302406311 -4.67014932632,1.72273349762,-5.02244520187 -4.6841506958,1.72173142433,-5.00584363937 -4.69315290451,1.72173070908,-4.99806308746 -4.69814682007,1.71772587299,-4.97146892548 -4.69413137436,1.70871841908,-4.93389749527 -4.70412969589,1.70671522617,-4.91231060028 -4.71412754059,1.70371198654,-4.89072418213 -4.73013210297,1.70371055603,-4.87612867355 -4.73812818527,1.70070683956,-4.85155677795 -4.74412870407,1.69970560074,-4.8427529335 -4.75012397766,1.69570147991,-4.81618309021 -4.76212453842,1.69469916821,-4.79758930206 -4.77312421799,1.69269669056,-4.77799606323 -4.78412437439,1.6906940937,-4.757417202 -4.7941236496,1.68869149685,-4.73682546616 -4.79812192917,1.68668973446,-4.72503805161 -4.81312561035,1.68668842316,-4.70944643021 -4.81912183762,1.68268501759,-4.68485927582 -4.82912158966,1.68068253994,-4.66427183151 -4.8451256752,1.68068158627,-4.64968156815 -4.85912895203,1.68068015575,-4.63309240341 -4.87213087082,1.6796785593,-4.61550474167 -4.87613010406,1.67767703533,-4.60372018814 -4.88012552261,1.67367339134,-4.57812786102 -4.89412879944,1.67367219925,-4.56154060364 -4.91914081573,1.67667353153,-4.5559425354 -4.92113447189,1.67166948318,-4.52736949921 -4.92512989044,1.66766619682,-4.50178194046 -4.94513845444,1.6696665287,-4.49217510223 -4.94013118744,1.66566336155,-4.47239160538 -4.96013879776,1.66666340828,-4.46081352234 -4.97714471817,1.66766321659,-4.44821071625 -4.97713804245,1.66265928745,-4.41863489151 -4.99514484406,1.66365909576,-4.40604496002 -5.00814819336,1.66265809536,-4.38944959641 -5.01014280319,1.65865468979,-4.36187458038 -5.01314210892,1.65665352345,-4.35008430481 -5.02614545822,1.65665256977,-4.33349084854 -5.04115009308,1.65665197372,-4.31790781021 -5.04414606094,1.65164911747,-4.29232215881 -5.06115245819,1.65264904499,-4.27873516083 -5.06114673615,1.64764583111,-4.25114440918 -5.08315658569,1.65064656734,-4.24156045914 -5.09416151047,1.65164709091,-4.2377538681 -5.09315538406,1.64664375782,-4.20818328857 -5.11016225815,1.64764380455,-4.19459676743 -5.1211643219,1.64664280415,-4.17699718475 -5.12015867233,1.64163970947,-4.148416996 -5.13716554642,1.64263987541,-4.13483142853 -5.15617370605,1.64364027977,-4.12323951721 -5.14916610718,1.63963782787,-4.10345554352 -5.1601691246,1.63863694668,-4.0848736763 -5.1801776886,1.64063763618,-4.07427835464 -5.18017339706,1.63563513756,-4.04768800735 -5.1941781044,1.63563477993,-4.0311126709 -5.20818281174,1.63563466072,-4.01552200317 -5.20517921448,1.63263309002,-3.99973154068 -5.21418094635,1.63163220882,-3.98014426231 -5.24019384384,1.63563382626,-3.97355651855 -5.23518705368,1.62963092327,-3.94297623634 -5.24719047546,1.62863063812,-3.92638015747 -5.26219654083,1.62963068485,-3.91080212593 -5.2721991539,1.62863016129,-3.89221358299 -5.27519989014,1.62762963772,-3.88240456581 -5.28620290756,1.62662923336,-3.86284399033 -5.291203022,1.6236281395,-3.84124660492 -5.30620861053,1.62462830544,-3.82567000389 -5.33122110367,1.62862992287,-3.81906437874 -5.31821012497,1.61962664127,-3.78250288963 -5.32921409607,1.61962640285,-3.76491332054 -5.33721733093,1.61962676048,-3.7581152916 -5.34021711349,1.61662554741,-3.73453259468 -5.35622358322,1.61762607098,-3.72093629837 -5.37022924423,1.61862647533,-3.70534873009 -5.36522436142,1.61262440681,-3.67577672005 -5.38623380661,1.61562561989,-3.66518712044 -5.39523839951,1.61662614346,-3.65938329697 -5.39523649216,1.61262488365,-3.63380503654 -5.40624046326,1.61162507534,-3.61621880531 -5.42424869537,1.61362600327,-3.6036272049 -5.42424678802,1.60962498188,-3.57805228233 -5.43024873734,1.60762453079,-3.55647850037 -5.44825696945,1.60962569714,-3.54487013817 -5.44325351715,1.60662472248,-3.52809643745 -5.45525884628,1.60662508011,-3.51150631905 -5.46226119995,1.60462498665,-3.4919128418 -5.47226572037,1.60462522507,-3.47333455086 -5.48627185822,1.60462594032,-3.45774960518 -5.49327421188,1.6036260128,-3.4381570816 -5.50127744675,1.60262620449,-3.41857600212 -5.50127744675,1.60062599182,-3.40579414368 -5.51528358459,1.60162675381,-3.39119267464 -5.5142827034,1.59762620926,-3.36562085152 -5.52428674698,1.59662675858,-3.34802913666 -5.52928924561,1.59462678432,-3.3264541626 -5.54229545593,1.59562766552,-3.31085944176 -5.55129957199,1.59462821484,-3.29227542877 -5.55129957199,1.59262812138,-3.27949762344 -5.56030368805,1.5916287899,-3.26189732552 -5.56330490112,1.58962881565,-3.23932242393 -5.57431030273,1.58962965012,-3.22174286842 -5.58231449127,1.58863031864,-3.20315098763 -5.58631658554,1.58663070202,-3.18157172203 -5.60532617569,1.58863210678,-3.1699681282 -5.59332084656,1.58363139629,-3.14921450615 -5.61533117294,1.5866330862,-3.13960528374 -5.62133455276,1.58563363552,-3.11902999878 -5.62333631516,1.58263409138,-3.09743452072 -5.63534212112,1.58363521099,-3.08084869385 -5.64934921265,1.5846363306,-3.06526446342 -5.64134645462,1.58063614368,-3.04848694801 -5.64734983444,1.5786370039,-3.02791547775 -5.66035652161,1.57963812351,-3.01330447197 -5.65735673904,1.57563865185,-2.98773694038 -5.6713643074,1.57663989067,-2.97215390205 -5.6763677597,1.57564091682,-2.9515748024 -5.6863732338,1.57564210892,-2.93398952484 -5.67837095261,1.57164204121,-2.91820168495 -5.69337844849,1.57264363766,-2.90360975266 -5.68737745285,1.5686442852,-2.87703990936 -5.69738388062,1.5686455965,-2.86043834686 -5.7003865242,1.56664657593,-2.83886361122 -5.71539497375,1.56764817238,-2.82427191734 -5.71039485931,1.56364905834,-2.79771661758 -5.72840261459,1.56765019894,-2.79689693451 -5.71940135956,1.56165099144,-2.76932668686 -5.72740697861,1.56165242195,-2.75074505806 -5.74841737747,1.56465423107,-2.73915052414 -5.74241781235,1.56065535545,-2.71357417107 -5.74542093277,1.55865681171,-2.69200539589 -5.75942850113,1.55965840816,-2.67740368843 -5.75242757797,1.55665898323,-2.66163825989 -5.75443077087,1.55466032028,-2.64104437828 -5.77044010162,1.55666220188,-2.62645983696 -5.7744436264,1.55466377735,-2.60588407516 -5.77444696426,1.55266535282,-2.5842936039 -5.77645111084,1.5506670475,-2.56272149086 -5.7744512558,1.5486676693,-2.55092906952 -5.78645896912,1.54966962337,-2.53434824944 -5.7984662056,1.55067145824,-2.51874780655 -5.80247116089,1.54867315292,-2.49817562103 -5.80247449875,1.54667508602,-2.47560882568 -5.8174829483,1.54867696762,-2.46101403236 -5.82148790359,1.54667890072,-2.44142460823 -5.81648826599,1.54467988014,-2.42764949799 -5.83749866486,1.54768192768,-2.4160451889 -5.84550476074,1.54768395424,-2.39746880531 -5.83850622177,1.54368579388,-2.3728890419 -5.84651279449,1.54368782043,-2.35431408882 -5.8425154686,1.5396900177,-2.33074164391 -5.85452318192,1.54069209099,-2.31514143944 -5.87053012848,1.54469311237,-2.31134033203 -5.85953044891,1.53869521618,-2.28477454185 -5.87453985214,1.54069757462,-2.26919603348 -5.89254951477,1.54369962215,-2.25560045242 -5.8825507164,1.53870201111,-2.23002672195 -5.88555574417,1.53770422935,-2.21043539047 -5.90356588364,1.54070663452,-2.19585824013 -5.89856624603,1.53770780563,-2.18307352066 -5.90457296371,1.53771018982,-2.16448545456 -5.91458034515,1.53771257401,-2.14690732956 -5.90758323669,1.53371500969,-2.12332439423 -5.92059183121,1.53571748734,-2.10674834251 -5.938601017,1.53871965408,-2.09314799309 -5.92259931564,1.53272116184,-2.07636809349 -5.93160629272,1.53372359276,-2.05878329277 -5.95261764526,1.53772592545,-2.04618239403 -5.93361711502,1.52972900867,-2.0176217556 -5.9436249733,1.53073143959,-2.00004410744 -5.96763658524,1.53573381901,-1.98844146729 -5.95763874054,1.5307366848,-1.96386742592 -5.96564388275,1.53173792362,-1.95607852936 -5.97065067291,1.53174078465,-1.93650627136 -5.96965551376,1.52874350548,-1.91591572762 -5.96766042709,1.52674651146,-1.89433908463 -5.97766828537,1.5277493,-1.87676072121 -5.98267507553,1.5267521143,-1.85817086697 -5.97467899323,1.52275538445,-1.83459889889 -5.99268627167,1.52675628662,-1.83079135418 -5.99369239807,1.52575933933,-1.81021654606 -5.98969697952,1.52276277542,-1.7876521349 -6.00070524216,1.52376544476,-1.77105987072 -6.00371170044,1.52276849747,-1.75147914886 -6.00071763992,1.52077174187,-1.72990310192 -6.01472663879,1.52277457714,-1.71430778503 -6.01572990417,1.52177619934,-1.70353519917 -6.01673603058,1.52077937126,-1.68394398689 -6.02774477005,1.52178227901,-1.66735041142 -6.01874923706,1.517786026,-1.64378404617 -6.03275871277,1.51978898048,-1.62720727921 -6.04576778412,1.52179169655,-1.61160349846 -6.02976751328,1.51679420471,-1.59583926201 -6.03777551651,1.51779735088,-1.57824862003 -6.04878425598,1.51880013943,-1.56165397167 -6.04779100418,1.51680397987,-1.54009616375 -6.04179620743,1.51380777359,-1.51851284504 -6.05480575562,1.51581072807,-1.50192821026 -6.04681062698,1.51281487942,-1.47935676575 -6.05381536484,1.51381623745,-1.4715565443 -6.06082391739,1.51381969452,-1.45298147202 -6.06283092499,1.51282334328,-1.43340146542 -6.06783914566,1.51282680035,-1.41481626034 -6.08184862137,1.51582980156,-1.39823365211 -6.07085323334,1.51083409786,-1.37565338612 -6.06985664368,1.50983631611,-1.36487519741 -6.07786560059,1.51083958149,-1.34728419781 -6.08087348938,1.51084327698,-1.32771074772 -6.0788807869,1.50884747505,-1.30713534355 -6.09689044952,1.51185011864,-1.29252779484 -6.08989667892,1.5088545084,-1.27095115185 -6.10290670395,1.51085782051,-1.25338160992 -6.09390878677,1.50786054134,-1.24159061909 -6.10191726685,1.50886392593,-1.22399878502 -6.10092496872,1.50786817074,-1.2034304142 -6.10193252563,1.50687217712,-1.18385052681 -6.10094022751,1.50487661362,-1.16328394413 -6.11094999313,1.50688004494,-1.14569985867 -6.10895681381,1.50488436222,-1.12610900402 -6.11696195602,1.50688576698,-1.11830770969 -6.12097072601,1.50688993931,-1.09874081612 -6.13298034668,1.50889325142,-1.08214199543 -6.121986866,1.50489842892,-1.05958068371 -6.12399530411,1.50390267372,-1.04000711441 -6.12800359726,1.50390672684,-1.02142000198 -6.13001155853,1.50391077995,-1.00282561779 -6.13401699066,1.50391280651,-0.993049919605 -6.13402509689,1.50291728973,-0.973469793797 -6.13803386688,1.50292134285,-0.954882919788 -6.14904356003,1.5049251318,-0.937298476696 -6.15705347061,1.50592899323,-0.918724298477 -6.15406084061,1.50493371487,-0.899134635925 -6.15206480026,1.50393605232,-0.889338731766 -6.15607404709,1.50394046307,-0.869772732258 -6.15908288956,1.5039447546,-0.851182460785 -6.15709161758,1.50194978714,-0.830619573593 -6.16009998322,1.50195407867,-0.812029659748 -6.16710948944,1.50295817852,-0.793451428413 -6.16711854935,1.50196301937,-0.773874163628 -6.17012310028,1.50296485424,-0.765072584152 -6.16813182831,1.50097000599,-0.744511663914 -6.16714048386,1.49997496605,-0.724932551384 -6.1811504364,1.50297832489,-0.708329379559 -6.18416023254,1.50298309326,-0.688760519028 -6.18116855621,1.50198817253,-0.669176697731 -6.17817735672,1.49999332428,-0.649594008923 -6.18918323517,1.50299477577,-0.640810966492 -6.1811914444,1.50000059605,-0.620238244534 -6.18520069122,1.500005126,-0.601651310921 -6.18220949173,1.49901032448,-0.582070052624 -6.19021987915,1.50001466274,-0.563491523266 -6.20022964478,1.5020185709,-0.545894980431 -6.18323707581,1.4970253706,-0.524329423904 -6.19624328613,1.50002682209,-0.515546619892 -6.19525289536,1.49903202057,-0.495970904827 -6.19726276398,1.49903678894,-0.477379620075 -6.2012720108,1.50004160404,-0.458791702986 -6.2052822113,1.50004649162,-0.439225107431 -6.19929122925,1.49805212021,-0.4196421206 -6.20029592514,1.49805474281,-0.409857332706 -6.20830631256,1.50005924702,-0.391275286674 -6.2083158493,1.49906432629,-0.372681170702 -6.21432638168,1.5000692606,-0.353116750717 -6.21633625031,1.50007414818,-0.334525227547 -6.20834541321,1.49808049202,-0.313963830471 -6.21335554123,1.49908530712,-0.295376360416 -6.22936153412,1.50308609009,-0.287565797567 -6.20636987686,1.49609410763,-0.266010940075 -6.21538066864,1.49809849262,-0.247427344322 -6.22239112854,1.50010323524,-0.228840708733 -6.2124004364,1.49710965157,-0.209259942174 -6.20441055298,1.4941163063,-0.188703924417 -6.22642183304,1.50011944771,-0.171106889844 -6.22342681885,1.49912238121,-0.161318898201 -6.22043657303,1.49812829494,-0.141745507717 -6.22044658661,1.49713385105,-0.123153150082 -6.21945714951,1.4971395731,-0.103581547737 -6.22046756744,1.49714529514,-0.0840112343431 -6.22647809982,1.49815011024,-0.0654214844108 -6.2214884758,1.49715638161,-0.0458487607539 -6.22849369049,1.49815821648,-0.0370442159474 -6.21950387955,1.49616503716,-0.0174711383879 -6.21451425552,1.49417150021,0.00209972355515 -6.21852493286,1.49517667294,0.0206907335669 -6.21753549576,1.4951826334,0.040260899812 -6.2215461731,1.49618780613,0.0588524825871 -6.21755170822,1.49519133568,0.0686372593045 -6.22456264496,1.4961963892,0.0882078632712 -6.20557260513,1.49120461941,0.107774041593 -6.21358346939,1.49320936203,0.126366689801 -6.22159481049,1.49521458149,0.145938843489 -6.20960521698,1.49222171307,0.164525389671 -6.21361637115,1.49322724342,0.184096381068 -6.22362279892,1.49622917175,0.193886294961 -6.19863271713,1.48923802376,0.212463259697 -6.20464420319,1.49124348164,0.232035577297 -6.22365522385,1.49624693394,0.250639379025 -6.20766639709,1.49225521088,0.270197033882 -6.20167684555,1.49026191235,0.288782417774 -6.21168899536,1.49326682091,0.308360248804 -6.21469449997,1.49426960945,0.318147808313 -6.19870519638,1.49027776718,0.336722791195 -6.20671701431,1.49228298664,0.356299936771 -6.19872808456,1.49029004574,0.374881505966 -6.19973945618,1.49029636383,0.394451320171 -6.19475078583,1.48930299282,0.413035422564 -6.190762043,1.48830962181,0.431620210409 -6.18476819992,1.48731374741,0.441396296024 -6.19878005981,1.49131822586,0.460984677076 -6.19879102707,1.49132430553,0.479575335979 -6.1878027916,1.48833239079,0.499127149582 -6.19481420517,1.49033761024,0.517728924751 -6.19182634354,1.49034452438,0.537293195724 -6.18883180618,1.48934793472,0.54609400034 -6.19584369659,1.4913533926,0.565675795078 -6.18285560608,1.48836159706,0.58424270153 -6.18786764145,1.49036753178,0.603821575642 -6.1858792305,1.49037408829,0.622408688068 -6.18089151382,1.48938155174,0.641967892647 -6.17190361023,1.4873893261,0.660539567471 -6.18690919876,1.49139010906,0.670356690884 -6.17592096329,1.48839831352,0.688923597336 -6.17593336105,1.48940503597,0.708493411541 -6.16894578934,1.48741257191,0.727068006992 -6.15895795822,1.48542046547,0.744656324387 -6.15396976471,1.48442769051,0.763234436512 -6.15097618103,1.48443162441,0.773011445999 -6.1589884758,1.48643696308,0.792601287365 -6.17000055313,1.490442276,0.813179194927 -6.1450138092,1.48445248604,0.829745948315 -6.16402482986,1.48945629597,0.850347161293 -6.14903783798,1.48646509647,0.867918133736 -6.14805030823,1.48647224903,0.887485384941 -6.15105628967,1.48747515678,0.897279560566 -6.14706897736,1.48748242855,0.915859878063 -6.13508176804,1.48449099064,0.933436334133 -6.12909460068,1.48349869251,0.952009141445 -6.1301074028,1.48450553417,0.971582770348 -6.13411998749,1.48651170731,0.991166889668 -6.13313293457,1.48651885986,1.01073479652 -6.1321387291,1.48652219772,1.01953864098 -6.11815214157,1.48353135586,1.03710472584 -6.12616491318,1.48653709888,1.05768287182 -6.12017822266,1.48554515839,1.07625472546 -6.12119007111,1.48655164242,1.09485197067 -6.11820363998,1.48655927181,1.11441338062 -6.1152100563,1.48656308651,1.12320995331 -6.10822343826,1.48557138443,1.14177727699 -6.09923696518,1.48357963562,1.15935754776 -6.09624958038,1.4835870266,1.17793953419 -6.09326267242,1.48359453678,1.19652152061 -6.10527515411,1.48759996891,1.21810114384 -6.09028911591,1.48460924625,1.23467695713 -6.08929586411,1.48461306095,1.24445950985 -6.08930921555,1.48562037945,1.26403343678 -6.08432292938,1.48562824726,1.28260755539 -6.06933689117,1.48263776302,1.29917991161 -6.07734966278,1.48564362526,1.31976830959 -6.06936311722,1.48465192318,1.33734977245 -6.06237745285,1.48366045952,1.35591375828 -6.05638360977,1.48266482353,1.36371600628 -6.06239700317,1.48467111588,1.38429772854 -6.05641078949,1.48467946053,1.40286636353 -6.05442428589,1.4846868515,1.42145371437 -6.06443691254,1.48869264126,1.44303667545 -6.04545164108,1.48470306396,1.45860481262 -6.0424656868,1.48471081257,1.47718763351 -6.03147315979,1.48271632195,1.48496294022 -6.03148698807,1.48372375965,1.50453972816 -6.03650045395,1.48573040962,1.52512180805 -6.03051424026,1.48573851585,1.54271090031 -6.02952814102,1.48674619198,1.56228411198 -6.0295419693,1.48775362968,1.58186304569 -6.02354955673,1.48675847054,1.59064149857 -6.01456403732,1.48576748371,1.60821390152 -6.01257753372,1.48577511311,1.62680315971 -6.00959157944,1.48678290844,1.64538753033 -6.01460552216,1.48878991604,1.66695427895 -5.99662065506,1.48580026627,1.68153750896 -5.9996342659,1.48780727386,1.70211482048 -6.00264120102,1.48881053925,1.7129021883 -6.00165557861,1.48981845379,1.73247861862 -5.99466991425,1.48982703686,1.75006175041 -5.98268508911,1.48783671856,1.76663517952 -5.97769927979,1.48784518242,1.78520870209 -5.97171449661,1.48785400391,1.80377602577 -5.98172712326,1.49185955524,1.82538032532 -5.96073627472,1.48686718941,1.83014571667 -5.95875120163,1.48787534237,1.8497171402 -5.96276473999,1.48988223076,1.87030637264 -5.94677972794,1.48689234257,1.88489282131 -5.94479465485,1.48790061474,1.90446507931 -5.946808815,1.48990797997,1.92504346371 -5.93881702423,1.48891329765,1.93282556534 -5.92983198166,1.48792243004,1.94941425323 -5.93684625626,1.49092924595,1.97198605537 -5.92786073685,1.48993825912,1.98857498169 -5.91087770462,1.48694932461,2.00412940979 -5.91789102554,1.49095571041,2.02572464943 -5.90290737152,1.48796629906,2.04129123688 -5.90391397476,1.48896980286,2.05109262466 -5.90092897415,1.48997843266,2.07066106796 -5.88794469833,1.48798847198,2.08624053001 -5.87796163559,1.48699831963,2.10379958153 -5.88297557831,1.49000537395,2.12538504601 -5.86999177933,1.48801541328,2.14096331596 -5.86100721359,1.48802518845,2.15852928162 -5.86901378632,1.49102783203,2.17132306099 -5.85403013229,1.48803818226,2.18590521812 -5.84604597092,1.48804759979,2.20347857475 -5.83706235886,1.48705732822,2.22104334831 -5.82707834244,1.48606717587,2.23762083054 -5.82409334183,1.48707544804,2.25621128082 -5.83110713959,1.49108219147,2.27879905701 -5.80511760712,1.48509085178,2.27957582474 -5.80813217163,1.48709845543,2.30115294456 -5.8121471405,1.49010574818,2.32273983955 -5.79416465759,1.48711740971,2.33729290962 -5.78218078613,1.48612761497,2.35287308693 -5.78219604492,1.48813581467,2.37344932556 -5.77020454407,1.48514163494,2.37825059891 -5.76122140884,1.48515164852,2.39581370354 -5.76723575592,1.48815870285,2.41840028763 -5.75025272369,1.48616981506,2.43197798729 -5.75226831436,1.48817777634,2.45355296135 -5.74728441238,1.48918688297,2.47213053703 -5.72930192947,1.4861985445,2.48569703102 -5.71831130981,1.48420453072,2.49148273468 -5.72832536697,1.48921096325,2.51606941223 -5.71634197235,1.48722136021,2.53164625168 -5.69735956192,1.48423302174,2.5442211628 -5.70437431335,1.4882401228,2.5678050518 -5.68939208984,1.48625123501,2.58237433434 -5.67740106583,1.48425734043,2.58716821671 -5.69841337204,1.49226176739,2.61676120758 -5.67943286896,1.48927390575,2.63031387329 -5.66844940186,1.48828423023,2.64589810371 -5.66246509552,1.48829340935,2.66348814964 -5.65648174286,1.48930299282,2.68205904961 -5.6405005455,1.48731458187,2.69661593437 -5.64750671387,1.49031722546,2.70942544937 -5.63052511215,1.48732888699,2.72299194336 -5.62454175949,1.48833858967,2.74156308174 -5.6285572052,1.49134624004,2.76415085793 -5.60957574844,1.48835837841,2.77671647072 -5.60359191895,1.48936760426,2.79430770874 -5.59660959244,1.48937761784,2.81287026405 -5.59961652756,1.49138140678,2.82466602325 -5.58263492584,1.48939275742,2.83724880219 -5.58065128326,1.49140179157,2.85782194138 -5.57066869736,1.49041223526,2.87439441681 -5.56368589401,1.49142205715,2.8919775486 -5.55870199203,1.49243140221,2.91056132317 -5.54672002792,1.49144232273,2.92613339424 -5.54172945023,1.49144780636,2.93490982056 -5.54174566269,1.49345636368,2.95648741722 -5.52476406097,1.49146807194,2.96906590462 -5.51578140259,1.49147832394,2.98564839363 -5.51179838181,1.49248766899,3.00522494316 -5.50281572342,1.49249792099,3.02180790901 -5.49982452393,1.49350309372,3.03158640862 -5.49784135818,1.49551200867,3.05216646194 -5.47986030579,1.49252426624,3.0647315979 -5.47087812424,1.49253451824,3.08131456375 -5.46489524841,1.49354445934,3.09989142418 -5.4529132843,1.49255514145,3.11448049545 -5.44293165207,1.49256587029,3.13105273247 -5.44993877411,1.49656891823,3.14584589005 -5.43895721436,1.49557995796,3.16240811348 -5.43297386169,1.49658954144,3.18000602722 -5.42699098587,1.49759936333,3.19858527184 -5.40901088715,1.49561190605,3.21114587784 -5.40802764893,1.497620821,3.23272490501 -5.39604663849,1.49763202667,3.24829530716 -5.39505434036,1.49863648415,3.25809860229 -5.38007354736,1.49664819241,3.27167201042 -5.3780913353,1.49965751171,3.29324293137 -5.36710929871,1.49866843224,3.30882406235 -5.35212898254,1.49768018723,3.3223965168 -5.35214471817,1.50068879128,3.34399223328 -5.34215497971,1.49869537354,3.34976792336 -5.33217382431,1.49870622158,3.36634230614 -5.33019018173,1.50171530247,3.38693547249 -5.31520986557,1.49972701073,3.40050697327 -5.30422878265,1.49973833561,3.41706967354 -5.30424547195,1.50274729729,3.43965196609 -5.28226613998,1.49976027012,3.44823169708 -5.27827501297,1.49976551533,3.45702171326 -5.2862906456,1.50577294827,3.48461008072 -5.26231241226,1.50178694725,3.49316453934 -5.25832939148,1.50379645824,3.51275706291 -5.24834871292,1.5038074255,3.52933287621 -5.24036741257,1.50481820107,3.54789710045 -5.2283782959,1.50282502174,3.55168128014 -5.22939395905,1.50583350658,3.5742828846 -5.20841550827,1.50284671783,3.58385062218 -5.20743274689,1.50585603714,3.60642981529 -5.1914525032,1.50486814976,3.61900424957 -5.18447113037,1.5058786869,3.63758230209 -5.16949129105,1.50489079952,3.65115046501 -5.16750001907,1.50589549541,3.66094946861 -5.15751981735,1.50590693951,3.67850923538 -5.14953804016,1.50691759586,3.6960940361 -5.14555597305,1.50892734528,3.71667695045 -5.13257551193,1.50893902779,3.73125267029 -5.11259651184,1.50595211983,3.74082636833 -5.12061214447,1.51195979118,3.77040696144 -5.11362218857,1.51196575165,3.77719759941 -5.09064435959,1.50797939301,3.78476667404 -5.09066152573,1.51198852062,3.80835294724 -5.07268190384,1.51000118256,3.81893324852 -5.06370162964,1.51101207733,3.8365085125 -5.05872011185,1.51302242279,3.85708475113 -5.03474187851,1.50903642178,3.86365389824 -5.03975009918,1.51204013824,3.87944602966 -5.03076934814,1.51305103302,3.89702272415 -5.01079130173,1.51106441021,3.90659141541 -5.00980901718,1.51407384872,3.93017220497 -5.00582647324,1.51708364487,3.95076584816 -4.98884725571,1.51509642601,3.96233940125 -4.98285722733,1.51510226727,3.9701256752 -4.97687673569,1.51711297035,3.99069452286 -4.95889806747,1.5151257515,4.00127077103 -4.95391654968,1.51813590527,4.02185440063 -4.94093608856,1.51714754105,4.03544712067 -4.93095636368,1.51815903187,4.05301427841 -4.91397762299,1.51717185974,4.06458616257 -4.92298460007,1.52217483521,4.08437871933 -4.89400815964,1.51618981361,4.08595132828 -4.88302850723,1.51720166206,4.10252189636 -4.89004468918,1.52320933342,4.13311100006 -4.86406755447,1.51922392845,4.1366891861 -4.85208845139,1.51923573017,4.15226316452 -4.85410547256,1.52424454689,4.17885351181 -4.83811759949,1.52125263214,4.17863178253 -4.82913732529,1.52226376534,4.19621610641 -4.82215690613,1.52427446842,4.21579694748 -4.80617856979,1.5232872963,4.22836494446 -4.79719829559,1.52429878712,4.24693489075 -4.78621864319,1.52531015873,4.26252508163 -4.77423906326,1.52532207966,4.27810192108 -4.77124786377,1.52632713318,4.28790044785 -4.75626993179,1.52633976936,4.30146694183 -4.74729013443,1.52735126019,4.32003927231 -4.73431110382,1.52736330032,4.33461856842 -4.73232936859,1.53137326241,4.35919904709 -4.70635271072,1.52738785744,4.36177921295 -4.71436071396,1.53239107132,4.38256692886 -4.70638036728,1.53440225124,4.40214204788 -4.67940473557,1.5294175148,4.40470600128 -4.67542314529,1.53242731094,4.42630815506 -4.66944360733,1.53643846512,4.44886827469 -4.64246702194,1.5304530859,4.44945955276 -4.64347600937,1.53445780277,4.46424484253 -4.63149690628,1.5344697237,4.47982501984 -4.61051988602,1.53148365021,4.48739528656 -4.60254001617,1.53449487686,4.50697422028 -4.59855937958,1.53750538826,4.53055238724 -4.57958126068,1.53551864624,4.53913593292 -4.56960201263,1.53753018379,4.55671739578 -4.55661487579,1.53553783894,4.55849456787 -4.54963445663,1.53754878044,4.57907629013 -4.53265714645,1.53656208515,4.59064388275 -4.52467679977,1.53857290745,4.60924196243 -4.50470018387,1.53658676147,4.61780834198 -4.48772239685,1.53560018539,4.62937450409 -4.48973989487,1.54160916805,4.65896463394 -4.46875476837,1.53661859035,4.65273427963 -4.4657740593,1.54062879086,4.67732381821 -4.45279502869,1.54164087772,4.69190835953 -4.4338183403,1.53965473175,4.70147323608 -4.42083978653,1.54066693783,4.71605730057 -4.41385936737,1.54267776012,4.73664808273 -4.39588260651,1.54169130325,4.74721336365 -4.38989305496,1.54269742966,4.75500631332 -4.37791490555,1.54370975494,4.77157926559 -4.3679356575,1.54472112656,4.78916883469 -4.35295820236,1.54473412037,4.8027381897 -4.34097909927,1.54574608803,4.8183259964 -4.31800317764,1.54276061058,4.82289743423 -4.32001256943,1.54676508904,4.83969068527 -4.30603456497,1.54677784443,4.85426235199 -4.28705787659,1.54579150677,4.86283874512 -4.27208042145,1.54580450058,4.87640857697 -4.26809978485,1.54981482029,4.90100049973 -4.24512386322,1.54682910442,4.90458250046 -4.22814750671,1.54584264755,4.91614866257 -4.22315835953,1.54684865475,4.92593193054 -4.20918083191,1.54786157608,4.94050502777 -4.19520282745,1.54787397385,4.95409202576 -4.1782245636,1.54688692093,4.96368455887 -4.16324853897,1.5479003191,4.97824192047 -4.14927101135,1.54791307449,4.99281597137 -4.13329267502,1.54792582989,5.00341081619 -4.12630414963,1.5479323864,5.0111913681 -4.1153254509,1.54994428158,5.02877426147 -4.10534763336,1.55195629597,5.04834794998 -4.08637094498,1.55096995831,5.05593490601 -4.07039451599,1.55098319054,5.06850385666 -4.0564160347,1.55099570751,5.08209276199 -4.04942750931,1.55200219154,5.08987426758 -4.02745294571,1.54901707172,5.09543609619 -3.62357234955,1.38811039925,4.62487840652 -3.41964387894,1.30916321278,4.40035820007 -3.41466426849,1.31317389011,4.42094802856 -3.40868496895,1.31618499756,4.44053602219 -3.38870954514,1.31319904327,4.44310712814 -3.94457817078,1.55108809471,5.16613006592 -3.94159793854,1.55609858036,5.19471311569 -3.9196228981,1.55411314964,5.1992855072 -3.90264630318,1.55312657356,5.20986413956 -3.88766884804,1.55413937569,5.22245168686 -3.88468933105,1.55914998055,5.25202846527 -3.87071180344,1.56016278267,5.26660966873 -3.88771724701,1.57116436958,5.30640268326 -3.73177647591,1.51020658016,5.1309299469 -3.79178023338,1.54420411587,5.24453735352 -3.84578561783,1.57420265675,5.35114526749 -3.82980918884,1.57521593571,5.3637213707 -3.77284312248,1.55723750591,5.3192896843 -3.74386048317,1.54824888706,5.297062397 -3.73388266563,1.55126094818,5.31763887405 -3.6899125576,1.5382797718,5.28922080994 -3.667937994,1.53629434109,5.29279327393 -3.67095732689,1.54530394077,5.33236646652 -3.64498281479,1.54031896591,5.32895326614 -3.63400554657,1.54333150387,5.34852600098 -3.62001919746,1.54033946991,5.34630632401 -3.59304499626,1.53535473347,5.34089565277 -3.48009443283,1.49138844013,5.21143007278 -3.57908797264,1.5443778038,5.39105463028 -3.59310340881,1.55838465691,5.44665288925 -3.59712266922,1.56839418411,5.49022102356 -3.44917106628,1.50342977047,5.28596973419 -3.39320588112,1.48445165157,5.23752307892 -3.57717657089,1.57942330837,5.55117988586 -3.46422624588,1.53345680237,5.41572284698 -3.44225168228,1.53147149086,5.41829776764 -3.33729910851,1.48950314522,5.29184675217 -3.38730478287,1.52050256729,5.40446138382 -3.55227041245,1.60447311401,5.6803188324 -3.60927510262,1.64047133923,5.80892038345 -3.59229898453,1.64148497581,5.82149839401 -3.57732272148,1.64249801636,5.83707952499 -3.53335428238,1.63051736355,5.8066444397 -3.50938057899,1.62753248215,5.8082151413 -3.52439618111,1.64353954792,5.87280416489 -3.39044213295,1.58157229424,5.67355012894 -3.38946247101,1.58958280087,5.71212482452 -3.44846534729,1.62858009338,5.84775161743 -3.22154664993,1.52263736725,5.50925207138 -3.46050143242,1.65259766579,5.94992542267 -3.44052743912,1.65261232853,5.95948648453 -3.11563587189,1.49469017982,5.4469461441 -3.41956233978,1.65563166142,5.98586463928 -3.39958739281,1.65464568138,5.99344539642 -3.3936085701,1.66165697575,6.02503490448 -3.37363409996,1.66167140007,6.03360795975 -3.35465931892,1.66168558598,6.04417800903 -3.3406829834,1.66369855404,6.06275844574 -3.32669687271,1.6617064476,6.05954742432 -3.30872130394,1.66172039509,6.07112598419 -3.28874659538,1.66173446178,6.07870769501 -3.27277088165,1.66274797916,6.09428358078 -3.2527961731,1.66276216507,6.1018652916 -3.23282194138,1.66177654266,6.11043739319 -3.21284723282,1.66179072857,6.11801862717 -3.21085762978,1.6657961607,6.13681173325 -3.18988370895,1.66481077671,6.14338541031 -3.16790890694,1.66282510757,6.14597654343 -3.15693259239,1.66783773899,6.17254543304 -3.13395833969,1.66485238075,6.17313718796 -3.1179831028,1.66686606407,6.18970870972 -3.10999536514,1.66787266731,6.19750022888 -3.09002065659,1.66788685322,6.2050819397 -3.07304549217,1.66890072823,6.21965551376 -3.06206822395,1.6739127636,6.24424934387 -3.04009437561,1.6719275713,6.24882268906 -3.02211976051,1.67294156551,6.26139831543 -3.00314450264,1.67295527458,6.26998996735 -2.99515771866,1.67496240139,6.27976608276 -2.974183321,1.67397677898,6.28534841537 -2.95420885086,1.67299091816,6.2929315567 -2.94223237038,1.67800343037,6.31751537323 -2.92325782776,1.67801761627,6.32809209824 -2.90528249741,1.67903137207,6.33967924118 -2.88730859756,1.68104565144,6.35424232483 -2.88131952286,1.68305146694,6.36504936218 -2.85634732246,1.68006718159,6.36361694336 -2.83937239647,1.68208098412,6.37919092178 -2.82939529419,1.68809306622,6.4087805748 -2.80442285538,1.68510842323,6.40635538101 -2.79144597054,1.68912088871,6.42894935608 -2.77147269249,1.68913555145,6.43951272964 -2.76748299599,1.69314110279,6.45532083511 -2.74251055717,1.69015657902,6.45289421082 -2.72353601456,1.6901705265,6.46347570419 -2.7055618763,1.69218444824,6.47705316544 -2.68258905411,1.69019961357,6.47962379456 -2.66461443901,1.69221353531,6.49320173264 -2.65362691879,1.69122040272,6.49300670624 -2.6366519928,1.69323420525,6.50858879089 -2.61767840385,1.69424843788,6.52115774155 -2.5967040062,1.69326269627,6.52574872971 -2.57673025131,1.69427704811,6.53532218933 -2.55875563622,1.69529080391,6.54791069031 -2.53878188133,1.69630515575,6.55748462677 -2.52679562569,1.69531285763,6.55727005005 -2.50682139397,1.69532692432,6.56485795975 -2.48784732819,1.69634103775,6.57643651962 -2.46887278557,1.69735491276,6.58702278137 -2.4488992691,1.69736933708,6.59659767151 -2.43292450905,1.70138275623,6.61617898941 -2.41195058823,1.70039725304,6.62176370621 -2.40496301651,1.70340383053,6.63455343246 -2.38299012184,1.70241868496,6.64012050629 -2.36701440811,1.70543181896,6.65771865845 -2.34504175186,1.70544660091,6.66229295731 -2.32706713676,1.70746040344,6.67687559128 -2.3050942421,1.70647501945,6.6804561615 -2.29510736465,1.70648217201,6.68524503708 -2.27613353729,1.70849633217,6.69782400131 -2.26315736771,1.71450889111,6.72641468048 -2.25218081474,1.72252130508,6.76200199127 -2.2312078476,1.72353601456,6.77057361603 -2.21623301506,1.72854924202,6.79615354538 -2.19525957108,1.72856378555,6.80373191833 -2.18527293205,1.72957086563,6.80951881409 -2.17629480362,1.73858237267,6.85012531281 -2.16231989861,1.74559557438,6.88070297241 -2.14134716988,1.74661040306,6.89126873016 -2.11437535286,1.74162590504,6.87885475159 -2.09240245819,1.74064052105,6.88343524933 -2.07142877579,1.74165487289,6.89101791382 -2.04744672775,1.72966492176,6.85179710388 -2.02247428894,1.72668004036,6.84438514709 -1.99950170517,1.72469484806,6.84496498108 -1.97852838039,1.72570931911,6.85254383087 -1.95555579662,1.72372424603,6.85312318802 -1.93158352375,1.72073912621,6.84970474243 -1.92159700394,1.72274625301,6.85549259186 -1.89862394333,1.71976089478,6.85408067703 -1.87565135956,1.71877574921,6.85366296768 -1.85467875004,1.71979033947,6.86323213577 -1.83170616627,1.71780514717,6.86281347275 -1.80973339081,1.71781980991,6.86639308929 -1.78875946999,1.71683382988,6.86999130249 -1.77477443218,1.71484196186,6.86276865005 -1.75480103493,1.71585607529,6.87335157394 -1.73582684994,1.71786975861,6.88594436646 -1.70885622501,1.71288573742,6.87250995636 -1.68688344955,1.71290028095,6.87509250641 -1.66990864277,1.71691358089,6.89568710327 -1.6459363699,1.71392846107,6.89026927948 -1.6339507103,1.71293604374,6.88905286789 -1.61497676373,1.71595001221,6.9036397934 -1.58900558949,1.71096551418,6.89121294022 -1.5680321455,1.71097958088,6.89580488205 -1.54905879498,1.71499359608,6.91338014603 -1.52408671379,1.71000850201,6.90096902847 -1.50311374664,1.71102297306,6.90854883194 -1.49112784863,1.71003043652,6.90533876419 -1.46815550327,1.70804524422,6.90391778946 -1.4451829195,1.7060598135,6.90050363541 -1.42620921135,1.70907366276,6.9160900116 -1.40023779869,1.70408904552,6.89966869354 -1.38126432896,1.70710277557,6.91625213623 -1.37127768993,1.70810985565,6.92204475403 -1.3443069458,1.70212554932,6.90161561966 -1.32233405113,1.7011398077,6.90120601654 -1.30336070061,1.7051538229,6.9197845459 -1.27938854694,1.70116865635,6.91036891937 -1.25441741943,1.69718384743,6.89893960953 -1.23444378376,1.69919776917,6.90853214264 -1.22145855427,1.69620549679,6.90031480789 -1.20148491859,1.69821941853,6.9109044075 -1.17751312256,1.69523429871,6.9014840126 -1.15554094315,1.69524884224,6.90505838394 -1.13356781006,1.69326293468,6.90165472031 -1.11359453201,1.69627702236,6.91423892975 -1.09860992432,1.69028520584,6.89302015305 -1.07763719559,1.69129943848,6.90060091019 -1.05866312981,1.69431304932,6.91619634628 -1.03269279003,1.68832850456,6.89676046371 -1.01271927357,1.69034230709,6.90735292435 -0.993745625019,1.69535601139,6.92693996429 -0.968773782253,1.68837082386,6.90452766418 -0.957788050175,1.68937826157,6.90830898285 -0.936815321445,1.69039237499,6.91589164734 -0.913843214512,1.68840706348,6.90947246552 -0.891870081425,1.68642103672,6.90406799316 -0.870897293091,1.68743515015,6.91165113449 -0.846926212311,1.68445014954,6.90121984482 -0.824953556061,1.68346440792,6.89880657196 -0.815966546535,1.68647122383,6.91360187531 -0.792994439602,1.68348562717,6.9041852951 -0.773020982742,1.68649935722,6.91777563095 -0.75104868412,1.68651378155,6.91835594177 -0.727077305317,1.68152868748,6.90293073654 -0.705104768276,1.68054282665,6.90051603317 -0.685131728649,1.68455660343,6.91810083389 -0.675144851208,1.68656349182,6.92389965057 -0.650174021721,1.67957854271,6.89846944809 -0.630200088024,1.68159210682,6.90807056427 -0.608227908611,1.6806063652,6.90765142441 -0.586255788803,1.68062067032,6.90922832489 -0.564283251762,1.67963480949,6.90481519699 -0.552297830582,1.67764234543,6.89759731293 -0.532324194908,1.68065583706,6.91119432449 -0.510351717472,1.67966997623,6.90777826309 -0.48837941885,1.67868423462,6.90536117554 -0.466407001019,1.67669844627,6.90094661713 -0.444435030222,1.67771279812,6.90352201462 -0.422462791204,1.6767270565,6.90110349655 -0.411476194859,1.67373394966,6.89190292358 -0.390503823757,1.67874801159,6.90948152542 -0.36853146553,1.67676222324,6.90506505966 -0.347558408976,1.67877590656,6.91165685654 -0.32558581233,1.67578983307,6.90024614334 -0.30361366272,1.67480409145,6.89882564545 -0.292627513409,1.67381119728,6.89561748505 -0.271654725075,1.67782497406,6.9092040062 -0.249682232738,1.67483901978,6.89779138565 -0.227710455656,1.67685341835,6.90636396408 -0.205738052726,1.67386746407,6.89494895935 -0.183765992522,1.67288160324,6.89352798462 -0.162792876363,1.67489516735,6.90112161636 -0.151806756854,1.67390227318,6.89691257477 -0.129834741354,1.67391645908,6.89749097824 -0.108861491084,1.67492997646,6.90108728409 -0.0868891105056,1.66794395447,6.87367248535 -0.0649173334241,1.67295825481,6.89324617386 -0.0439439900219,1.67097175121,6.88484430313 -0.0219720136374,1.67298591137,6.89042139053 -0.0109859900549,1.66999292374,6.87921142578 --0.00798957142979,1.6890052557,6.66884183884 --0.0289622172713,1.69001913071,6.67342567444 --0.0499349944293,1.69503283501,6.69101333618 --0.0599219053984,1.69303929806,6.6808142662 --0.0808945223689,1.69205307961,6.67639827728 --0.101866997778,1.68806684017,6.66397953033 --0.122839830816,1.69208061695,6.67456769943 --0.143812313676,1.68909430504,6.66614961624 --0.164784938097,1.68910801411,6.66473388672 --0.185757860541,1.69212162495,6.67432355881 --0.195744246244,1.68712842464,6.65411472321 --0.215717971325,1.68514144421,6.64771461487 --0.237690210342,1.69315540791,6.67329740524 --0.257662713528,1.68316912651,6.6348733902 --0.279634714127,1.68718314171,6.65145158768 --0.300607383251,1.68819665909,6.65203714371 --0.321580380201,1.6902102232,6.65862846375 --0.332566231489,1.69121730328,6.66141462326 --0.352539420128,1.68723058701,6.64600419998 --0.372513204813,1.68724370003,6.64260578156 --0.393485695124,1.68625724316,6.63918733597 --0.414458274841,1.68627083302,6.63777112961 --0.434431523085,1.68428421021,6.62636184692 --0.456403553486,1.68729805946,6.63594007492 --0.467389464378,1.68830502033,6.63872718811 --0.487363249063,1.68731808662,6.63532876968 --0.508335769176,1.68733167648,6.63291168213 --0.531307518482,1.69334554672,6.65248966217 --0.55028116703,1.6883585453,6.63108253479 --0.57125389576,1.68837201595,6.63066864014 --0.584239125252,1.69537949562,6.65445423126 --0.603212654591,1.6903924942,6.63304424286 --0.626184225082,1.69540643692,6.64761972427 --0.64715731144,1.69641971588,6.64921283722 --0.67012912035,1.70043373108,6.66379165649 --0.691102027893,1.70144689083,6.66338205338 --0.714074015617,1.70646071434,6.67796468735 --0.723060905933,1.70246720314,6.66376018524 --0.744034290314,1.7044801712,6.66635799408 --0.76500660181,1.70349371433,6.65993595123 --0.786978662014,1.70450747013,6.66251468658 --0.807951509953,1.70452082157,6.6601023674 --0.828924417496,1.70553410053,6.65869235992 --0.849897682667,1.70654702187,6.65928697586 --0.860883176327,1.7055542469,6.65606594086 --0.883855819702,1.71056759357,6.67166185379 --0.904828190804,1.70958101749,6.66524028778 --0.927800476551,1.71459460258,6.6768283844 --0.946774065495,1.71060740948,6.66041851044 --0.967746496201,1.7096208334,6.65499925613 --0.991718828678,1.71663427353,6.67459344864 --1.00070548058,1.71264076233,6.66138362885 --1.02067840099,1.7106539011,6.64996623993 --1.04365062714,1.71466732025,6.65955352783 --1.06462419033,1.71568024158,6.66015386581 --1.08659672737,1.71769356728,6.66173839569 --1.10656952858,1.71570670605,6.6503200531 --1.1175558567,1.71671319008,6.65211582184 --1.13952803612,1.71772670746,6.65169477463 --1.15950131416,1.71573972702,6.6422829628 --1.18447291851,1.72175335884,6.66086959839 --1.2034471035,1.71976578236,6.64946985245 --1.2274184227,1.72377979755,6.65804433823 --1.25039088726,1.72679293156,6.66563558578 --1.25637853146,1.71979880333,6.63842535019 --1.28334975243,1.72881281376,6.66601419449 --1.30332279205,1.72782564163,6.65559911728 --1.32529568672,1.72883880138,6.65719032288 --1.34526908398,1.72785151005,6.64878225327 --1.37024044991,1.73286521435,6.66136074066 --1.38921439648,1.73087775707,6.64895629883 --1.40519917011,1.73788499832,6.67274951935 --1.41817450523,1.72789669037,6.63033819199 --1.44414627552,1.73391032219,6.64993000031 --1.4661192894,1.73592329025,6.65052175522 --1.48509263992,1.73293578625,6.63610744476 --1.50806438923,1.73494935036,6.63668107986 --1.5200510025,1.73795568943,6.64348602295 --1.54102349281,1.73696875572,6.63606405258 --1.5619969368,1.73798143864,6.63265943527 --1.58396995068,1.73899424076,6.63325357437 --1.61294007301,1.74800860882,6.65782690048 --1.6329138279,1.74702107906,6.65042495728 --1.65188717842,1.74403369427,6.63500452042 --1.65787529945,1.74003911018,6.61580562592 --1.68884527683,1.75105345249,6.64939117432 --1.7088187933,1.75006592274,6.63997983932 --1.73279118538,1.75307905674,6.6465716362 --1.74376761913,1.74309003353,6.60416650772 --1.77773666382,1.75610482693,6.64675188065 --1.79571020603,1.75311720371,6.62732839584 --1.80269765854,1.74912309647,6.611120224 --1.83066868782,1.75613677502,6.63070774078 --1.85364198685,1.75914943218,6.634308815 --1.86861717701,1.75316095352,6.60790205002 --1.90058660507,1.76417541504,6.63848018646 --1.91956019402,1.76218783855,6.62406206131 --1.93453526497,1.75619935989,6.59765291214 --1.95152032375,1.76320636272,6.61845636368 --1.97149372101,1.76221895218,6.60804080963 --1.99246692657,1.76223134995,6.60162830353 --2.01743865013,1.76524460316,6.6072101593 --2.03941202164,1.76625704765,6.60480308533 --2.06138539314,1.76826941967,6.60340261459 --2.07137131691,1.76727592945,6.59618377686 --2.09734392166,1.77228879929,6.60778522491 --2.11231923103,1.76730024815,6.58237457275 --2.13729071617,1.77031350136,6.58594989777 --2.1622633934,1.77432620525,6.59355115891 --2.18623495102,1.77633929253,6.59312391281 --2.19921135902,1.77035009861,6.56472682953 --2.22219467163,1.78135812283,6.59852075577 --2.23816895485,1.7763698101,6.57510042191 --2.26714015007,1.78338325024,6.59169054031 --2.28611397743,1.78239536285,6.57827663422 --2.30808734894,1.78340768814,6.57386445999 --2.32806110382,1.78241968155,6.56445741653 --2.35103440285,1.78443205357,6.56405353546 --2.36002087593,1.78343808651,6.55483913422 --2.38799262047,1.78845119476,6.56743097305 --2.40996599197,1.78946340084,6.56302213669 --2.4319396019,1.79147553444,6.55961942673 --2.45091366768,1.78948748112,6.54620504379 --2.48088502884,1.79750072956,6.56380176544 --2.48687267303,1.79350626469,6.54658651352 --2.50884604454,1.79451835155,6.54218006134 --2.53481817245,1.79853129387,6.54676389694 --2.55579209328,1.79854309559,6.54036283493 --2.57976460457,1.80155551434,6.53995037079 --2.59973812103,1.80056750774,6.52853250504 --2.62071228027,1.80057942867,6.52112483978 --2.63169884682,1.80158531666,6.51892280579 --2.66566872597,1.81059920788,6.54250907898 --2.67764568329,1.80560958385,6.51411056519 --2.70061802864,1.80662202835,6.50868415833 --2.73358869553,1.81563556194,6.53028011322 --2.74956393242,1.8116465807,6.50986814499 --2.77653646469,1.8166590929,6.51747083664 --2.78952240944,1.81866550446,6.51825904846 --2.80749726295,1.81667685509,6.50284910202 --2.83246922493,1.81968927383,6.50242996216 --2.8564426899,1.82170140743,6.50202894211 --2.8774163723,1.82171320915,6.49261236191 --2.90338921547,1.82572543621,6.49620962143 --2.91137671471,1.82473087311,6.48600196838 --2.93534946442,1.82674312592,6.48358917236 --2.95532417297,1.82675457001,6.47318315506 --2.98429536819,1.83176743984,6.48076486588 --2.99527287483,1.82577729225,6.45237064362 --3.02024531364,1.828789711,6.4509510994 --3.04621815681,1.83180177212,6.45354795456 --3.05520582199,1.83180725574,6.44634628296 --3.07817935944,1.83281898499,6.44193840027 --3.10515189171,1.83783125877,6.44552946091 --3.12512564659,1.83684289455,6.43310976028 --3.15009856224,1.83985507488,6.43169641495 --3.17607164383,1.84286689758,6.43329143524 --3.19404649734,1.84187805653,6.41788101196 --3.20503377914,1.84188377857,6.41467952728 --3.23100662231,1.84589552879,6.4162774086 --3.24498319626,1.8419059515,6.3938741684 --3.27795362473,1.84991908073,6.40645122528 --3.29692864418,1.84893000126,6.39404964447 --3.317902565,1.84894144535,6.38363265991 --3.33788728714,1.85494828224,6.39743041992 --3.35386323929,1.8529586792,6.37902736664 --3.37483739853,1.85296988487,6.36961984634 --3.40580868721,1.85898268223,6.37719726562 --3.41878604889,1.85499250889,6.35480737686 --3.44675827026,1.86000466347,6.3573923111 --3.46873235703,1.86101591587,6.34897994995 --3.48271822929,1.863022089,6.34976959229 --3.49969410896,1.86103248596,6.33336687088 --3.52266788483,1.8630437851,6.32695674896 --3.54764151573,1.86505544186,6.32455062866 --3.57061553001,1.86706662178,6.31814289093 --3.59158992767,1.86707770824,6.30773067474 --3.61456394196,1.86908888817,6.30132341385 --3.62555122375,1.87009453773,6.29711866379 --3.64652657509,1.87110507488,6.28872537613 --3.66850066185,1.87211632729,6.27930831909 --3.69047498703,1.87312734127,6.27090072632 --3.71044969559,1.87313818932,6.25848770142 --3.73542332649,1.87514948845,6.25508022308 --3.74341130257,1.87415456772,6.24587726593 --3.77138400078,1.87816643715,6.24646234512 --3.7873609066,1.87717628479,6.22906589508 --3.81233453751,1.88018751144,6.22566127777 --3.84130692482,1.88419926167,6.2272439003 --3.86228203773,1.88521003723,6.216837883 --3.87625837326,1.88221991062,6.19442415237 --3.89324402809,1.88522613049,6.19921684265 --3.91521954536,1.88723659515,6.19182443619 --3.94019317627,1.88924765587,6.1874165535 --3.96216797829,1.89125847816,6.17800617218 --3.98614192009,1.89326941967,6.17159557343 --4.00111913681,1.89127910137,6.15219497681 --4.02509307861,1.89329016209,6.14477539062 --4.03807973862,1.89429557323,6.14357566833 --4.05905532837,1.89530599117,6.13317298889 --4.08202934265,1.89731681347,6.12476110458 --4.10400485992,1.89832735062,6.11535406113 --4.12597990036,1.89933753014,6.10695791245 --4.149954319,1.90234839916,6.09954309464 --4.15494298935,1.89935290813,6.08634376526 --4.1759185791,1.90036332607,6.07493305206 --4.1998925209,1.90237402916,6.06751966476 --4.22086811066,1.90338420868,6.05712032318 --4.24084377289,1.90439426899,6.04471540451 --4.26481866837,1.90640497208,6.0373044014 --4.28379440308,1.90641498566,6.02289438248 --4.30178022385,1.90942084789,6.02768993378 --4.32775449753,1.91343152523,6.0232834816 --4.33673286438,1.9084404707,5.99487352371 --4.35970783234,1.91045069695,5.98646879196 --4.39268016815,1.916462183,5.99105834961 --4.40065908432,1.91147089005,5.96165037155 --4.43163204193,1.91748178005,5.9642496109 --4.45661592484,1.92448854446,5.97703742981 --4.46959447861,1.92149746418,5.95564174652 --4.49656820297,1.92550802231,5.95122861862 --4.50754642487,1.9215170145,5.9258184433 --4.53052186966,1.92352700233,5.91741991043 --4.5574965477,1.92753732204,5.91402006149 --4.55848693848,1.92354118824,5.89581775665 --4.57146501541,1.92055022717,5.8734087944 --4.58344268799,1.91755926609,5.84899139404 --4.60041952133,1.91756856441,5.83259010315 --4.60539913177,1.91057670116,5.80017948151 --4.62737464905,1.91258656979,5.7897734642 --4.65035057068,1.91459643841,5.78036642075 --4.65933895111,1.91460096836,5.77316951752 --4.67531633377,1.91361033916,5.75475883484 --4.70229101181,1.91762053967,5.75035381317 --4.72426700592,1.91863012314,5.73995065689 --4.74524259567,1.91963982582,5.72754001617 --4.74822378159,1.91364753246,5.69413661957 --4.77519798279,1.91765773296,5.68872356415 --4.77818775177,1.9146617651,5.67351770401 --4.80716276169,1.91967189312,5.672123909 --4.81914043427,1.91668057442,5.64870977402 --4.83411884308,1.91568922997,5.63031148911 --4.85709476471,1.91769874096,5.62090921402 --4.87807035446,1.91870844364,5.60748910904 --4.8820605278,1.9167124033,5.59428977966 --4.90103769302,1.91772150993,5.57988452911 --4.92401313782,1.91973114014,5.5694732666 --4.93999147415,1.91873979568,5.55207300186 --4.95496940613,1.91774833202,5.53367376328 --4.98094463348,1.92075812817,5.52625989914 --4.99592208862,1.91976690292,5.50684976578 --5.00091171265,1.91877090931,5.49464702606 --5.02688741684,1.92178046703,5.48824691772 --5.04386520386,1.92178940773,5.47083330154 --5.06484174728,1.92279839516,5.45842838287 --5.08781766891,1.92580759525,5.44802236557 --5.10779476166,1.92681658268,5.43461942673 --5.12877225876,1.9278254509,5.42221593857 --5.13876056671,1.92883002758,5.41500902176 --5.15373849869,1.92783844471,5.39559841156 --5.17071676254,1.92784690857,5.37919855118 --5.20069169998,1.93285632133,5.37680435181 --5.21167039871,1.92986476421,5.35238409042 --5.23164796829,1.9308732748,5.3389840126 --5.2566242218,1.93388235569,5.33058309555 --5.26361370087,1.93388652802,5.32037782669 --5.27659225464,1.93189466,5.29896783829 --5.30156898499,1.93590354919,5.29056882858 --5.31554746628,1.93391180038,5.27015829086 --5.33652496338,1.93592023849,5.25776052475 --5.35750198364,1.93792891502,5.24435138702 --5.35749292374,1.9339325428,5.2271437645 --5.37447166443,1.93394064903,5.21074581146 --5.40244674683,1.93894994259,5.20332813263 --5.41542673111,1.93795752525,5.18394088745 --5.42840576172,1.93596553802,5.1625289917 --5.45738124847,1.94097471237,5.15611457825 --5.46836090088,1.93898236752,5.13371372223 --5.47035217285,1.93698585033,5.11951637268 --5.49832773209,1.94099485874,5.11210346222 --5.51330709457,1.94000267982,5.09370565414 --5.53628444672,1.94301116467,5.08230304718 --5.55826187134,1.94501948357,5.06990003586 --5.57324075699,1.94402730465,5.05049037933 --5.58422040939,1.94203495979,5.02707529068 --5.59920835495,1.94503927231,5.02487897873 --5.60518932343,1.94104635715,4.9974694252 --5.62016820908,1.94105410576,4.978058815 --5.62714958191,1.93806111813,4.95266103745 --5.65912485123,1.94307017326,4.94825077057 --5.67710399628,1.94407773018,4.93285799026 --5.70508003235,1.94908642769,4.92444372177 --5.71606969833,1.95009040833,4.91824531555 --5.72305011749,1.9470975399,4.8918337822 --5.74402856827,1.94910538197,4.87843513489 --5.76600646973,1.95111334324,4.86502695084 --5.76498937607,1.94511973858,4.83262300491 --5.79496622086,1.95012807846,4.827231884 --5.79395771027,1.94713127613,4.81002140045 --5.80493783951,1.94513845444,4.78761529922 --5.8269162178,1.94814634323,4.77420806885 --5.82989788055,1.94315302372,4.74479532242 --5.85387611389,1.94716084003,4.73339366913 --5.86885595322,1.94716799259,4.71499633789 --5.84684324265,1.93317306042,4.66558074951 --5.88882637024,1.94517874718,4.68438768387 --5.75483703613,1.89417684078,4.54596424103 --5.8717956543,1.92919039726,4.60856580734 --5.8177895546,1.90519344807,4.53515148163 --5.85176563263,1.91220188141,4.53174972534 --5.71277666092,1.85920000076,4.39231681824 --5.70076227188,1.85020565987,4.35391187668 --5.69875383377,1.84720873833,4.33770704269 --5.7037358284,1.84421539307,4.31229877472 --5.72671413422,1.84722304344,4.30089426041 --5.73569583893,1.84522974491,4.27949905396 --5.74167776108,1.84323644638,4.25509119034 --5.74765920639,1.84024310112,4.23068284988 --5.77563619614,1.84525096416,4.22227144241 --5.51467943192,1.75424015522,4.01402902603 --5.52566051483,1.75424718857,3.99462008476 --5.54763936996,1.75725448132,3.98422670364 --5.61260938644,1.77426445484,4.00382137299 --5.81755208969,1.83928120136,4.12444162369 --5.82153463364,1.83528769016,4.09903526306 --5.83451557159,1.83529436588,4.08063697815 --5.83050727844,1.83229732513,4.06342840195 --5.84048891068,1.83130395412,4.0420165062 --5.8434715271,1.82831025124,4.01661586761 --5.86445093155,1.83031737804,4.00320959091 --5.8754324913,1.83032381535,3.98381614685 --5.89541196823,1.83233094215,3.96940588951 --5.89640331268,1.83033406734,3.9562022686 --5.9123840332,1.83134067059,3.93980360031 --5.92836380005,1.83234763145,3.92238998413 --5.93334627151,1.83035385609,3.89798116684 --5.93333005905,1.82635974884,3.87057518959 --5.9523100853,1.82836663723,3.8561770916 --5.97129011154,1.83037340641,3.84076476097 --5.97028207779,1.82837641239,3.82656288147 --5.9842634201,1.82838273048,3.80916953087 --5.99024581909,1.82638883591,3.78576231003 --6.00422716141,1.82739531994,3.76735377312 --6.02520608902,1.82940220833,3.75293922424 --6.02219104767,1.82440781593,3.72454047203 --6.04217100143,1.82741439342,3.71013641357 --6.03516387939,1.82341718674,3.69192647934 --6.04914522171,1.82342362404,3.67351794243 --6.06112623215,1.82342982292,3.65411257744 --6.07310819626,1.8234360218,3.63470745087 --6.08409070969,1.82344210148,3.61531162262 --6.0930724144,1.82244813442,3.59390306473 --6.09605646133,1.82045388222,3.56950259209 --6.10904598236,1.82245731354,3.56329011917 --6.12502717972,1.82346343994,3.54689526558 --6.14000844955,1.82446944714,3.529494524 --6.14999055862,1.82447552681,3.50807642937 --6.16797208786,1.82648158073,3.49268102646 --6.17795372009,1.82648766041,3.47126317024 --6.19593524933,1.82849371433,3.45586872101 --6.20492553711,1.82949674129,3.44766426086 --6.21090888977,1.82750236988,3.42526602745 --6.22988986969,1.83050847054,3.40986442566 --6.2368721962,1.82851433754,3.38644146919 --6.25285482407,1.83052003384,3.37005114555 --6.26183748245,1.82952582836,3.34864234924 --6.270819664,1.82953155041,3.3272330761 --6.25981378555,1.82353413105,3.30802464485 --6.26679754257,1.82253944874,3.28663086891 --6.30277585983,1.83054566383,3.28023338318 --6.3107585907,1.82955133915,3.2578163147 --6.33973884583,1.83555734158,3.24741744995 --6.35872030258,1.8385630846,3.23100686073 --6.3697104454,1.83956587315,3.22380614281 --6.37969398499,1.83957135677,3.2034060955 --6.39867544174,1.84257698059,3.18699789047 --6.40765810013,1.8415825367,3.16559076309 --6.43863868713,1.84858810902,3.15620112419 --6.42662477493,1.84159326553,3.12378334999 --6.45360612869,1.84659862518,3.11239600182 --6.44659900665,1.84260129929,3.09517765045 --6.46958065033,1.84660673141,3.08077430725 --6.46156644821,1.84161174297,3.05136919022 --6.49054718018,1.84661722183,3.03997015953 --6.50752925873,1.84962236881,3.02256727219 --6.53351020813,1.85362780094,3.00916266441 --6.55249261856,1.85663306713,2.99276351929 --6.55748414993,1.85663568974,2.98154950142 --6.56546831131,1.8556406498,2.96015191078 --6.57345151901,1.85564577579,2.93773794174 --6.58943510056,1.85765063763,2.92034673691 --6.60641717911,1.85965585709,2.90193319321 --6.6313996315,1.8646607399,2.88854432106 --6.637383461,1.86366581917,2.86512970924 --6.64937496185,1.8656681776,2.85793209076 --6.64636087418,1.86167299747,2.83153128624 --6.67134237289,1.86667788029,2.81713032722 --6.69332456589,1.87068271637,2.80071949959 --6.70730829239,1.87168753147,2.78131580353 --6.70829296112,1.86869239807,2.75590276718 --6.7192773819,1.86969709396,2.73550319672 --6.74326705933,1.87569928169,2.73331069946 --6.75025177002,1.87470400333,2.71090650558 --6.75423622131,1.87370872498,2.68648886681 --6.77321958542,1.87671327591,2.66908788681 --6.78720331192,1.87771773338,2.64968752861 --6.78418970108,1.87472236156,2.6232817173 --6.80117988586,1.87772452831,2.61707544327 --6.80616521835,1.87672924995,2.59366750717 --6.82014942169,1.87873351574,2.57426857948 --6.82313489914,1.87673795223,2.55087256432 --6.84211826324,1.87974238396,2.53245997429 --6.84910297394,1.8797467947,2.51005578041 --6.85008955002,1.87775111198,2.48565483093 --6.87707948685,1.88475310802,2.48345971107 --6.86906576157,1.87975764275,2.45504641533 --6.88504981995,1.88176178932,2.43563866615 --6.8980345726,1.8837659359,2.41523241997 --6.9150185585,1.88576996326,2.3968372345 --6.92200422287,1.88577413559,2.37443375587 --6.93698835373,1.88777828217,2.35401821136 --6.93498182297,1.88578033447,2.34183096886 --6.94296741486,1.8857845068,2.31942224503 --6.96495103836,1.88978838921,2.30201864243 --6.94893932343,1.8837928772,2.27160906792 --6.97692251205,1.88879644871,2.25620770454 --6.98490762711,1.88880050182,2.23379945755 --6.98089408875,1.88580477238,2.20738840103 --7.00288534164,1.89080631733,2.20218896866 --7.01387071609,1.89281010628,2.18179869652 --7.01385688782,1.88981425762,2.15638279915 --7.04384088516,1.89681756496,2.14097905159 --7.05382680893,1.89782130718,2.11957931519 --7.05081319809,1.89482545853,2.09316134453 --7.05879926682,1.89482903481,2.07177138329 --7.07379102707,1.89783072472,2.06356406212 --7.06977844238,1.89483463764,2.03816652298 --7.08376407623,1.89683818817,2.01776480675 --7.10574817657,1.90084135532,1.99935913086 --7.10473537445,1.89884531498,1.97394621372 --7.11172151566,1.89884889126,1.95154547691 --7.12970685959,1.90185213089,1.93214464188 --7.12170124054,1.89885425568,1.91693007946 --7.12468767166,1.89785802364,1.89353072643 --7.14767313004,1.90286099911,1.8751257658 --7.14766025543,1.90086460114,1.8507232666 --7.16764545441,1.90486764908,1.83131718636 --7.16663265228,1.90287148952,1.80590176582 --7.17261981964,1.90287482738,1.78350627422 --7.18661212921,1.90587592125,1.77531301975 --7.19859838486,1.90787923336,1.75289332867 --7.18558692932,1.90188324451,1.72549259663 --7.19357347488,1.9028865099,1.70308887959 --7.21455907822,1.906889081,1.68368458748 --7.21254682541,1.90489280224,1.65827095509 --7.23153305054,1.90889537334,1.63887631893 --7.22852659225,1.90689730644,1.62566864491 --7.22451496124,1.90490090847,1.6002613306 --7.24550104141,1.90890336037,1.58086121082 --7.25248813629,1.9089063406,1.55846381187 --7.26347446442,1.91090917587,1.53605175018 --7.24846363068,1.90491330624,1.50864863396 --7.25445699692,1.90591466427,1.49744081497 --7.26144456863,1.90691757202,1.47504281998 --7.27643108368,1.90892016888,1.45363485813 --7.28141880035,1.90892314911,1.4302277565 --7.27840662003,1.90692663193,1.40481317043 --7.29339361191,1.90992903709,1.38340675831 --7.30538129807,1.91193151474,1.36201143265 --7.3063750267,1.91093301773,1.34980452061 --7.30936288834,1.91093599796,1.32640397549 --7.32135009766,1.91293859482,1.30399274826 --7.33933734894,1.91694045067,1.28359830379 --7.3323264122,1.91294395924,1.25819444656 --7.35531282425,1.91894567013,1.23778688908 --7.3523015976,1.91694879532,1.21338760853 --7.35429573059,1.91695022583,1.20117783546 --7.36428356171,1.91795253754,1.17877566814 --7.36927175522,1.91795516014,1.15537071228 --7.39425849915,1.9239565134,1.13496375084 --7.39024782181,1.9219596386,1.11056637764 --7.39223623276,1.92096245289,1.08615291119 --7.41322374344,1.92596375942,1.06575989723 --7.40421867371,1.92296588421,1.05154407024 --7.41720676422,1.92596781254,1.02913796902 --7.42919492722,1.92796969414,1.00673556328 --7.44218301773,1.92997145653,0.984331727028 --7.44717168808,1.93097388744,0.960929572582 --7.45916032791,1.93297553062,0.938529610634 --7.45814943314,1.93197822571,0.914123892784 --7.46014356613,1.9319794178,0.901915729046 --7.47313213348,1.93398106098,0.879515230656 --7.48212099075,1.93598306179,0.85610640049 --7.48510980606,1.93598520756,0.832709908485 --7.49809837341,1.93898677826,0.809294521809 --7.49908733368,1.93798923492,0.784885287285 --7.49908208847,1.93799042702,0.772681295872 --7.49807167053,1.93699288368,0.748274981976 --7.51406097412,1.93999409676,0.725873887539 --7.50005054474,1.93499755859,0.700471997261 --7.52403879166,1.94099807739,0.678059399128 --7.528028965,1.94199991226,0.654662311077 --7.52501821518,1.94000244141,0.630258858204 --7.54900741577,1.94600272179,0.607850730419 --7.54400253296,1.94400429726,0.595654129982 --7.53499221802,1.94100725651,0.570241212845 --7.55498170853,1.94600772858,0.547841370106 --7.55897092819,1.94600951672,0.523428916931 --7.5709605217,1.94901061058,0.50002425909 --7.57695055008,1.95001208782,0.47662743926 --7.58694076538,1.95201313496,0.453226804733 --7.58393526077,1.95101463795,0.440009474754 --7.57592582703,1.94901740551,0.415609866381 --7.58991575241,1.95201802254,0.392206430435 --7.59490585327,1.95301949978,0.367794841528 --7.60789585114,1.95602023602,0.344394296408 --7.61388587952,1.95702147484,0.319983303547 --7.60288143158,1.95402359962,0.307787954807 --7.61987161636,1.95802366734,0.284386515617 --7.60986185074,1.95502662659,0.258969247341 --7.60985183716,1.95402848721,0.234562307596 --7.62984275818,1.96002805233,0.211161762476 --7.62583351135,1.95803034306,0.186757415533 --7.63082361221,1.95903158188,0.16234883666 --7.62281894684,1.95703315735,0.150148406625 --7.62480974197,1.95703458786,0.125740870833 --7.61579990387,1.9540374279,0.10031927377 --7.63379096985,1.95903706551,0.0769249126315 --7.62478208542,1.95603966713,0.0525196306407 --7.62377262115,1.95604133606,0.028112296015 --7.62876367569,1.95704233646,0.00370470620692 --7.63275909424,1.95804262161,-0.00849894806743 --7.63474988937,1.95904397964,-0.0329060889781 --7.63374090195,1.95804560184,-0.057313028723 --7.631731987,1.95804727077,-0.0817206203938 --7.62272262573,1.95504975319,-0.106129579246 --7.63471412659,1.95804977417,-0.130534231663 --7.63470554352,1.95805108547,-0.154941409826 --7.61970090866,1.95405364037,-0.167150110006 --7.62369155884,1.95505452156,-0.191556543112 --7.62868309021,1.95605528355,-0.215962007642 --7.63667488098,1.95905554295,-0.240365758538 --7.62866592407,1.95605778694,-0.264777064323 --7.628657341,1.95605909824,-0.289184570312 --7.61864900589,1.95406162739,-0.313598871231 --7.62764453888,1.95606100559,-0.32579651475 --7.61763572693,1.95406353474,-0.350211650133 --7.61762714386,1.95406472683,-0.374619603157 --7.61861944199,1.9540656805,-0.399026572704 --7.61261081696,1.95306754112,-0.423440009356 --7.61960268021,1.95506763458,-0.447841316462 --7.63259506226,1.95906698704,-0.473252773285 --7.61859035492,1.95506930351,-0.484453767538 --7.62458276749,1.95706951618,-0.508854806423 --7.63157510757,1.95906960964,-0.534270763397 --7.62656641006,1.95807123184,-0.558683514595 --7.62355852127,1.95807254314,-0.58207732439 --7.62655067444,1.95907306671,-0.607497155666 --7.63054275513,1.96007323265,-0.631898164749 --7.63753986359,1.96207261086,-0.644091486931 --7.63853216171,1.96307325363,-0.669512867928 --7.64652490616,1.96507287025,-0.693906247616 --7.62751626968,1.96107637882,-0.717324078083 --7.62950849533,1.96207678318,-0.741726756096 --7.63250160217,1.96307706833,-0.767144203186 --7.64349460602,1.96607601643,-0.792547225952 --7.6484913826,1.96807551384,-0.804740965366 --7.63748311996,1.96507775784,-0.828147768974 --7.63747549057,1.96607840061,-0.85356926918 --7.65446996689,1.97107625008,-0.878957986832 --7.64646244049,1.97007799149,-0.903376996517 --7.64045476913,1.96907937527,-0.927792429924 --7.65645217896,1.97307705879,-0.940978229046 --7.6564450264,1.97407746315,-0.966397583485 --7.64943790436,1.97307896614,-0.989798128605 --7.66043186188,1.97607755661,-1.01620972157 --7.65842485428,1.97607815266,-1.04061567783 --7.65341758728,1.97607922554,-1.06502878666 --7.66441249847,1.98007762432,-1.09042108059 --7.65340805054,1.9770796299,-1.10163068771 --7.65440130234,1.97807955742,-1.12704586983 --7.6593952179,1.98007881641,-1.15245068073 --7.66538953781,1.98307788372,-1.1778523922 --7.67038393021,1.98507714272,-1.20325541496 --7.66937685013,1.98507738113,-1.2286734581 --7.65836954117,1.98307931423,-1.25208497047 --7.66636753082,1.9860779047,-1.26527941227 --7.65736055374,1.98407948017,-1.28868579865 --7.66535520554,1.98707795143,-1.31509482861 --7.65434741974,1.98507976532,-1.33850741386 --7.66034221649,1.98807859421,-1.36492085457 --7.65833616257,1.98807871342,-1.3893238306 --7.65132951736,1.98707985878,-1.41374194622 --7.67032909393,1.99307620525,-1.42893207073 --7.65232086182,1.98907935619,-1.45135056973 --7.66231632233,1.99307703972,-1.4777482748 --7.65831041336,1.99307751656,-1.50215625763 --7.64830350876,1.99207913876,-1.52556777 --7.64429759979,1.99207949638,-1.54997622967 --7.65529298782,1.99607682228,-1.57738351822 --7.649289608,1.99507784843,-1.58960092068 --7.64928436279,1.99607729912,-1.61399495602 --7.64827871323,1.99707698822,-1.6394084692 --7.6472735405,1.99807655811,-1.66482174397 --7.62926578522,1.99407958984,-1.68623006344 --7.63426160812,1.9970780611,-1.71263802052 --7.63525629044,1.99807715416,-1.73804306984 --7.63325357437,1.99807715416,-1.75024664402 --7.62424755096,1.99707829952,-1.77467250824 --7.64224529266,2.00407385826,-1.80306100845 --7.63123893738,2.00207543373,-1.82647776604 --7.62823343277,2.00307512283,-1.85189652443 --7.63422966003,2.00607323647,-1.87829530239 --7.63122463226,2.00607275963,-1.90371274948 --7.62522172928,2.00507354736,-1.91491532326 --7.63621902466,2.01007032394,-1.94230806828 --7.61821174622,2.00607323647,-1.96372187138 --7.62720870972,2.01007008553,-1.99213707447 --7.6352057457,2.01406741142,-2.01953887939 --7.64820384979,2.01906347275,-2.04894995689 --7.64019823074,2.01906394958,-2.07235383987 --7.64519739151,2.0210621357,-2.08655643463 --7.63519144058,2.02006316185,-2.10996890068 --7.64118862152,2.02306056023,-2.13737440109 --7.63818454742,2.02406001091,-2.16278743744 --7.63217973709,2.02406001091,-2.18719768524 --7.6471786499,2.0300552845,-2.21659088135 --7.6401758194,2.02905607224,-2.2277982235 --7.61916828156,2.02505922318,-2.24821400642 --7.62716627121,2.02905607224,-2.27662181854 --7.6411652565,2.03505110741,-2.30703091621 --7.635160923,2.03505086899,-2.33143901825 --7.62415552139,2.03305196762,-2.35485553741 --7.64215564728,2.04004597664,-2.38625669479 --7.62015008926,2.03505039215,-2.39347529411 --7.62114715576,2.03704833984,-2.41987991333 --7.63214635849,2.04204416275,-2.44928050041 --7.62714242935,2.04304337502,-2.47469782829 --7.62013816833,2.04304337502,-2.49910950661 --7.64113998413,2.05103611946,-2.5315015316 --7.63113546371,2.05003666878,-2.55491161346 --7.64113616943,2.05403327942,-2.57110857964 --7.64413452148,2.05703020096,-2.59952759743 --7.65013313293,2.06102657318,-2.62792921066 --7.63112688065,2.0580291748,-2.64935564995 --7.64612817764,2.0640232563,-2.68075346947 --7.62512111664,2.06002664566,-2.70016050339 --7.63812255859,2.06602096558,-2.73156642914 --7.63912057877,2.06901836395,-2.75897550583 --7.63111782074,2.06801915169,-2.77018880844 --7.6201133728,2.06601977348,-2.793602705 --7.6321144104,2.0720140934,-2.82399392128 --7.63511323929,2.07501101494,-2.85240387917 --7.62610960007,2.07501077652,-2.87682080269 --7.63311004639,2.08000612259,-2.90622115135 --7.64311170578,2.08400201797,-2.92443609238 --7.62910699844,2.08200335503,-2.94685006142 --7.63910865784,2.08699774742,-2.97724461555 --7.64310836792,2.09099364281,-3.0066576004 --7.63010406494,2.08999466896,-3.02906560898 --7.64010572433,2.09498906136,-3.06047081947 --7.65110826492,2.10098266602,-3.09288263321 --7.64510631561,2.10098290443,-3.10408329964 --7.65010643005,2.1049785614,-3.13449931145 --7.6351017952,2.10297966003,-3.15691804886 --7.64410448074,2.10797429085,-3.18730759621 --7.65810775757,2.11496686935,-3.22172307968 --7.65110588074,2.11596560478,-3.2461206913 --7.64510393143,2.11696386337,-3.27254080772 --7.64410352707,2.11796283722,-3.28573822975 --7.63210010529,2.11696267128,-3.31016635895 --7.63910245895,2.12195730209,-3.34056091309 --7.65610742569,2.12994861603,-3.3759624958 --7.66411066055,2.13494277,-3.40837550163 --7.66511106491,2.13793897629,-3.43677425385 --7.65510845184,2.13793826103,-3.461186409 --7.64410591125,2.1369395256,-3.47140336037 --7.61809873581,2.1319437027,-3.48882102966 --7.61309766769,2.13394165039,-3.51624417305 --7.59809398651,2.13194227219,-3.53764748573 --7.57008552551,2.12694716454,-3.55406785011 --7.55408143997,2.12494826317,-3.57649445534 --7.51506996155,2.1169564724,-3.58792185783 --7.51206922531,2.11695551872,-3.60113048553 --7.49606513977,2.11595678329,-3.62254548073 --7.47806024551,2.11395859718,-3.6429605484 --7.47506093979,2.1159555912,-3.67037081718 --7.46005725861,2.11495637894,-3.69279432297 --7.43705034256,2.1109597683,-3.71121788025 --7.42704868317,2.11095905304,-3.73462057114 --7.43005037308,2.11395573616,-3.75082874298 --7.40804433823,2.11095929146,-3.76924705505 --7.39904212952,2.11095809937,-3.79365682602 --7.38303852081,2.10895895958,-3.81507515907 --7.3710360527,2.10895872116,-3.83849310875 --7.35703277588,2.10795927048,-3.86091208458 --7.34202957153,2.10695981979,-3.88232445717 --7.32802534103,2.10496258736,-3.88953018188 --7.31102085114,2.10296392441,-3.91095900536 --7.30502080917,2.10496163368,-3.93636083603 --7.2740111351,2.0989677906,-3.95079898834 --7.26100873947,2.09796786308,-3.97321248055 --7.26101112366,2.10196328163,-4.00262403488 --7.24100589752,2.09996581078,-4.02103662491 --7.23200368881,2.09796690941,-4.03124856949 --7.21800088882,2.09796714783,-4.05265712738 --7.19599437714,2.09497022629,-4.07108688354 --7.19199562073,2.09696698189,-4.09850025177 --7.18199443817,2.09796595573,-4.12190485001 --7.15098524094,2.09197235107,-4.13533973694 --7.14098358154,2.09297132492,-4.15874528885 --7.13098144531,2.09197235107,-4.16896772385 --7.11397695541,2.08997392654,-4.18837451935 --7.09497213364,2.08797597885,-4.20779895782 --7.08197021484,2.08797597885,-4.23021602631 --7.06096458435,2.08497881889,-4.24864435196 --7.05096340179,2.08597755432,-4.27205038071 --7.0439620018,2.08597755432,-4.28326368332 --7.01195192337,2.07998466492,-4.2946896553 --7.0159573555,2.08497834206,-4.32608795166 --7.00095415115,2.08397865295,-4.34750890732 --6.96994447708,2.07898545265,-4.3599448204 --6.96394538879,2.08098268509,-4.38534450531 --6.95194387436,2.08098196983,-4.40876817703 --6.93894004822,2.07898449898,-4.41597938538 --6.92493772507,2.0789847374,-4.43739366531 --6.90793418884,2.07698607445,-4.4578204155 --6.90293598175,2.07998251915,-4.48523759842 --6.87692832947,2.07598757744,-4.49864959717 --6.86492681503,2.07598686218,-4.52207326889 --6.83891868591,2.07199215889,-4.53548765182 --6.82691574097,2.0709939003,-4.5437078476 --6.81991672516,2.07299137115,-4.56911420822 --6.79991197586,2.07099366188,-4.58754444122 --6.78691005707,2.07099342346,-4.6089515686 --6.77590990067,2.07199239731,-4.63338088989 --6.7428984642,2.06500053406,-4.64179754257 --6.73890161514,2.06899619102,-4.67021656036 --6.72089481354,2.06500101089,-4.67342710495 --6.7008895874,2.06300354004,-4.69084692001 --6.68488693237,2.06200456619,-4.71127080917 --6.66788339615,2.06100583076,-4.73069047928 --6.64387655258,2.05801010132,-4.74511098862 --6.63187599182,2.059009552,-4.7675242424 --6.61787414551,2.059009552,-4.78894329071 --6.60787153244,2.05801081657,-4.79714822769 --6.58486509323,2.05501484871,-4.81257534027 --6.57086324692,2.05501484871,-4.83399486542 --6.5568614006,2.05501484871,-4.8554148674 --6.52785205841,2.05002140999,-4.86583614349 --6.53085947037,2.05601382256,-4.89924764633 --6.50084924698,2.05102086067,-4.90968132019 --6.48384284973,2.04802536964,-4.91289186478 --6.47384357452,2.04902362823,-4.937312603 --6.44683504105,2.04502940178,-4.94873285294 --6.43983745575,2.0480260849,-4.9751496315 --6.421833992,2.04702806473,-4.99357223511 --6.38681983948,2.04003787041,-4.99899816513 --6.37682104111,2.04103565216,-5.02341890335 --6.37082099915,2.04203534126,-5.03462696075 --6.3348069191,2.03504562378,-5.03905439377 --6.3468208313,2.04403305054,-5.0804681778 --6.30180120468,2.03304815292,-5.07688808441 --6.28179645538,2.03205084801,-5.0933098793 --6.27179718018,2.03304886818,-5.11773061752 --6.25479412079,2.03305029869,-5.13614749908 --6.23678731918,2.0290555954,-5.13836574554 --6.2237868309,2.03005456924,-5.16079187393 --6.20578289032,2.02905678749,-5.17820739746 --6.18077516556,2.02606201172,-5.19063425064 --6.16777467728,2.02706122398,-5.21204805374 --6.13976478577,2.02206778526,-5.22248315811 --6.11875915527,2.0200715065,-5.23689508438 --6.10575532913,2.01907444,-5.24311590195 --6.10676383972,2.02506637573,-5.27653074265 --6.07975435257,2.02007317543,-5.2859454155 --6.05474615097,2.01707863808,-5.29837846756 --6.04774999619,2.02007484436,-5.32479000092 --6.01873970032,2.01608252525,-5.33321809769 --5.9957280159,2.01009058952,-5.33043861389 --5.99673748016,2.01608252525,-5.36384868622 --5.95972156525,2.0090944767,-5.36528205872 --5.94071722031,2.00809669495,-5.38170289993 --5.92671632767,2.00809669495,-5.40211725235 --5.90270900726,2.00610184669,-5.41454601288 --5.88970899582,2.00710105896,-5.43596172333 --5.88170814514,2.00710129738,-5.44618034363 --5.8627038002,2.00610375404,-5.46260261536 --5.84069776535,2.00410795212,-5.47602319717 --5.8296995163,2.00610613823,-5.49944019318 --5.79768562317,2.00011563301,-5.50386619568 --5.79169130325,2.00411081314,-5.53228664398 --5.7696852684,2.00211501122,-5.54570913315 --5.75868177414,2.00011730194,-5.55191421509 --5.73867750168,1.99911987782,-5.56835126877 --5.72267532349,1.99912083149,-5.58676481247 --5.69966888428,1.99712538719,-5.60020160675 --5.67365932465,1.99413216114,-5.60861444473 --5.66966676712,1.99812591076,-5.63903141022 --5.63965463638,1.99413454533,-5.64546918869 --5.62564897537,1.99213862419,-5.64867639542 --5.61465120316,1.99413645267,-5.67209243774 --5.59664773941,1.99313819408,-5.6895198822 --5.57264089584,1.99114358425,-5.70094871521 --5.56164264679,1.99314165115,-5.72335195541 --5.53763437271,1.99014699459,-5.73478126526 --5.52463579178,1.99214589596,-5.75720882416 --5.51263237,1.99114835262,-5.76343011856 --5.49062538147,1.98815310001,-5.77483654022 --5.47762680054,1.99015176296,-5.79726314545 --5.46162557602,1.99115264416,-5.81567907333 --5.44762659073,1.992151618,-5.83811712265 --5.4256196022,1.99015629292,-5.84952545166 --5.40961885452,1.99115669727,-5.868953228 --5.38860750198,1.9861651659,-5.86517333984 --5.37660932541,1.98816335201,-5.88758563995 --5.35760593414,1.98716580868,-5.90401601791 --5.33159637451,1.98417270184,-5.91244411469 --5.32360219955,1.98816800117,-5.93986225128 --5.30059480667,1.98617315292,-5.95128726959 --5.27858877182,1.98417758942,-5.96371126175 --5.26458311081,1.98218178749,-5.96692848206 --5.24958324432,1.98318171501,-5.98634338379 --5.23158073425,1.98318338394,-6.00377464294 --5.201567173,1.97819316387,-6.00720214844 --5.19157218933,1.98218977451,-6.03262090683 --5.16756391525,1.97919547558,-6.04305171967 --5.14455652237,1.97720086575,-6.05347013474 --5.14456367493,1.98119568825,-6.0716753006 --5.12055587769,1.97820115089,-6.08311891556 --5.09354496002,1.97520911694,-6.08954715729 --5.08254861832,1.97720658779,-6.11295318604 --5.05753946304,1.97521317005,-6.12137889862 --5.03153038025,1.97222030163,-6.12981939316 --5.02453804016,1.97621440887,-6.1592373848 --5.00452566147,1.97222340107,-6.15344142914 --4.98752450943,1.97222459316,-6.1708612442 --4.97152376175,1.9732247591,-6.19028949738 --4.94751644135,1.97123062611,-6.20072746277 --4.93451881409,1.97322916985,-6.22213602066 --4.92652702332,1.97822344303,-6.25156354904 --4.90351200104,1.97223424911,-6.2437915802 --4.88650989532,1.97323560715,-6.26020050049 --4.86250257492,1.97124147415,-6.27064037323 --4.83849382401,1.96824789047,-6.27905988693 --4.82649803162,1.97124505043,-6.30348539352 --4.81650447845,1.97524082661,-6.3299036026 --4.79349708557,1.97324621677,-6.34033155441 --4.76848840714,1.97125303745,-6.3487663269 --4.76449203491,1.97325050831,-6.36196088791 --4.73347616196,1.96726202965,-6.3623957634 --4.72148084641,1.97125911713,-6.38681936264 --4.69947528839,1.97026348114,-6.39925575256 --4.67146205902,1.96527326107,-6.40167379379 --4.65946674347,1.96927034855,-6.42609500885 --4.66147851944,1.97426235676,-6.44930648804 --4.62845945358,1.96727597713,-6.44573402405 --4.61846733093,1.97227120399,-6.47315645218 --4.58344650269,1.96528613567,-6.46759557724 --4.54942655563,1.95830047131,-6.46303367615 --4.53242588043,1.95930159092,-6.48045396805 --4.51742744446,1.96130084991,-6.50087547302 --4.50241994858,1.9593064785,-6.5010933876 --4.48642110825,1.96030640602,-6.52051830292 --4.46841907501,1.96130847931,-6.53593254089 --4.44641304016,1.96031320095,-6.54736423492 --4.42640972137,1.96031630039,-6.56179714203 --4.40440320969,1.95932114124,-6.57322978973 --4.37939310074,1.95632874966,-6.57965755463 --4.36538553238,1.95433402061,-6.57986402512 --4.34938669205,1.95533394814,-6.59928846359 --4.31937074661,1.95134580135,-6.59872341156 --4.2953619957,1.94935274124,-6.60614919662 --4.28036355972,1.95135188103,-6.62656879425 --4.25134897232,1.94636273384,-6.62801170349 --4.23635149002,1.94936192036,-6.64843130112 --4.22634935379,1.9493637085,-6.65463972092 --4.20133876801,1.94637143612,-6.66107320786 --4.18433952332,1.94837200642,-6.67950248718 --4.16233301163,1.94637715816,-6.68992996216 --4.13732242584,1.94438517094,-6.69535684586 --4.12132406235,1.94638502598,-6.71477985382 --4.10132026672,1.94638836384,-6.72820663452 --4.07729959488,1.93940281868,-6.7134308815 --4.06330394745,1.94240045547,-6.73686122894 --4.04029655457,1.94140684605,-6.74528837204 --4.01828956604,1.94041228294,-6.75470972061 --4.00629758835,1.94440805912,-6.78113508224 --3.97728061676,1.93942010403,-6.77956342697 --3.96026921272,1.93642830849,-6.77578926086 --3.94026565552,1.93643176556,-6.78921842575 --3.92126345634,1.93743431568,-6.80364131927 --3.89825487137,1.93544101715,-6.81106233597 --3.87023997307,1.93145179749,-6.81250810623 --3.85624480247,1.93444955349,-6.83492469788 --3.83223485947,1.93245744705,-6.84034538269 --3.80622315407,1.9304664135,-6.844789505 --3.7982237339,1.93146646023,-6.85399580002 --3.7792224884,1.9324682951,-6.87043619156 --3.74920344353,1.92748212814,-6.86586618423 --3.73120236397,1.92848408222,-6.88128328323 --3.70018100739,1.92249906063,-6.87471437454 --3.69119620323,1.92949032784,-6.90915298462 --3.66917419434,1.92250549793,-6.89235591888 --3.65417861938,1.92550361156,-6.91478538513 --3.63217258453,1.92450881004,-6.92522239685 --3.61016535759,1.92351484299,-6.93364334106 --3.58815908432,1.92352020741,-6.94408178329 --3.56414842606,1.9215285778,-6.94850206375 --3.53913736343,1.91953718662,-6.95293903351 --3.52212285995,1.91554713249,-6.94514703751 --3.51213669777,1.92153942585,-6.97757577896 --3.48512101173,1.91755080223,-6.97700500488 --3.46111154556,1.9165583849,-6.98344516754 --3.43910479546,1.91556417942,-6.99287700653 --3.41709685326,1.91457056999,-7.00029373169 --3.38907957077,1.91058337688,-6.99772787094 --3.3790781498,1.9105848074,-7.00494861603 --3.36007642746,1.91158735752,-7.0193734169 --3.34107446671,1.91259002686,-7.03379774094 --3.31606197357,1.91059970856,-7.03622579575 --3.29305362701,1.90960657597,-7.04366111755 --3.26804208755,1.9076154232,-7.04810667038 --3.25004148483,1.90861725807,-7.06352233887 --3.23803591728,1.90762150288,-7.06573724747 --3.22203993797,1.91062045097,-7.08615779877 --3.19302034378,1.90663456917,-7.08160257339 --3.17301678658,1.90663826466,-7.09402751923 --3.15201258659,1.90764284134,-7.10546302795 --3.13701963425,1.91163980961,-7.12989473343 --3.12000417709,1.90765047073,-7.12111186981 --3.10200548172,1.90965139866,-7.13854074478 --3.07899641991,1.90865886211,-7.1449713707 --3.05498480797,1.90666770935,-7.14839696884 --3.03397917747,1.90667307377,-7.15781736374 --3.01097011566,1.90568053722,-7.164249897 --2.98595762253,1.90268993378,-7.16769361496 --2.97495365143,1.90269339085,-7.1709022522 --1.75154161453,1.89506840706,-7.57869005203 --1.71547615528,1.87910962105,-7.52611446381 --1.69045650959,1.87612402439,-7.52054643631 --1.6824669838,1.88011932373,-7.53876972198 --1.65644490719,1.87613511086,-7.53121185303 --1.63945889473,1.88312971592,-7.55964136124 --1.61845600605,1.88413417339,-7.57107019424 --1.59343540668,1.88114917278,-7.56450033188 --1.56942307949,1.88015925884,-7.56694889069 --1.54942703247,1.8841599226,-7.58538722992 --1.53540587425,1.87917351723,-7.57058620453 --1.51741945744,1.8851685524,-7.59902524948 --1.49240076542,1.88318264484,-7.59446620941 --1.46838581562,1.88119423389,-7.59390354156 --1.44637727737,1.88120210171,-7.59932804108 --1.42537903786,1.88420414925,-7.61577367783 --1.40934956074,1.87722277641,-7.59298563004 --1.38734209538,1.87823021412,-7.5994143486 --1.3673479557,1.88222980499,-7.61985445023 --1.34132313728,1.87824738026,-7.60929727554 --1.3193154335,1.87825477123,-7.61572504044 --1.29530060291,1.87726652622,-7.61516714096 --1.26725816727,1.86829400063,-7.58659219742 --1.24726438522,1.8722935915,-7.60703039169 --1.23626244068,1.87329638004,-7.61225128174 --1.21224367619,1.87031018734,-7.60768270493 --1.1922494173,1.87531018257,-7.62711524963 --1.16722357273,1.87032794952,-7.61554479599 --1.14924585819,1.87931859493,-7.65198850632 --1.12120211124,1.8703469038,-7.62242269516 --1.11221063137,1.87434363365,-7.63763475418 --1.08618056774,1.86836409569,-7.62207508087 --1.06316518784,1.86737596989,-7.62050104141 --1.04418742657,1.87636709213,-7.65695667267 --1.01512670517,1.86240458488,-7.61037302017 --0.996145248413,1.87039744854,-7.6428155899 --0.973134577274,1.87040698528,-7.64625501633 --0.960117638111,1.86741828918,-7.6364736557 --0.937100291252,1.86543142796,-7.63289690018 --0.915098488331,1.86743581295,-7.64534044266 --0.891075015068,1.86445248127,-7.63576889038 --0.869069576263,1.86545908451,-7.6442027092 --0.847068965435,1.8684630394,-7.65764760971 --0.823048114777,1.865478158,-7.65108442307 --0.811040222645,1.86548447609,-7.65030908585 --0.789030075073,1.8654936552,-7.65373134613 --0.764002919197,1.86151242256,-7.64117717743 --0.741995692253,1.86252009869,-7.64760637283 --0.718987882137,1.86352813244,-7.65405368805 --0.695969462395,1.86154186726,-7.6494808197 --0.673962295055,1.86254954338,-7.65590906143 --0.662962496281,1.86355125904,-7.66313028336 --0.637927293777,1.85757446289,-7.64256715775 --0.615929067135,1.86157727242,-7.65801239014 --0.592913329601,1.85958957672,-7.6564450264 --0.569897770882,1.85860204697,-7.65487957001 --0.545868873596,1.854621768,-7.64031410217 --0.522853255272,1.85363423824,-7.63875007629 --0.510833144188,1.84964704514,-7.6259598732 --0.48884087801,1.85464668274,-7.64741039276 --0.465826451778,1.85465848446,-7.64684915543 --0.443819344044,1.85566616058,-7.65327692032 --0.4197871387,1.85068786144,-7.63571357727 --0.39677849412,1.85169649124,-7.64116001129 --0.373756617308,1.8487123251,-7.63359117508 --0.361740291119,1.84572315216,-7.62481117249 --0.33973222971,1.84673130512,-7.63023948669 --0.316719591618,1.84674227238,-7.6316819191 --0.293694734573,1.84375989437,-7.62111377716 --0.271686702967,1.84476804733,-7.62654161453 --0.24867400527,1.84477901459,-7.62798500061 --0.225657224655,1.8437923193,-7.62542581558 --0.215685322881,1.8527790308,-7.65864229202 --0.191651552916,1.84780156612,-7.64008998871 --0.168621182442,1.84282195568,-7.62452220917 --0.14660616219,1.84283411503,-7.62294578552 --0.123581014574,1.83985185623,-7.61238384247 --0.100577585399,1.84185791016,-7.62283229828 --0.0895668789744,1.84086573124,-7.61904287338 --0.0665435940027,1.83788239956,-7.61048412323 --0.0445304661989,1.83789348602,-7.61090946198 --0.0215115528554,1.83690798283,-7.60635328293 -0.00150639947969,1.83592200279,-7.60279798508 --0.00350340665318,1.82507193089,-6.77713298798 -0.0195039063692,1.82306885719,-6.77153396606 -0.0305285062641,1.82807862759,-6.78872108459 -0.0525152757764,1.82106494904,-6.76411104202 -0.075520709157,1.81906092167,-6.75651454926 -0.0975319594145,1.81906020641,-6.75489902496 -0.120548941195,1.8200622797,-6.75829839706 -0.143574178219,1.82306885719,-6.76969337463 -0.165564522147,1.81705713272,-6.74808931351 -0.176575258374,1.81805956364,-6.75227928162 -0.199590280652,1.81906068325,-6.75367927551 -0.221589028835,1.81505334377,-6.74007415771 -0.252551287413,1.80002391338,-6.68566226959 -0.273537546396,1.79301035404,-6.6600561142 -0.295548141003,1.79300940037,-6.6574473381 -0.306546777487,1.791005373,-6.64965009689 -0.327533334494,1.78399181366,-6.62404918671 -0.351579636335,1.79300940037,-6.65544080734 -0.372576445341,1.78900134563,-6.63983058929 -0.394582897425,1.78699839115,-6.63322925568 -0.416589647532,1.78599536419,-6.6266283989 -0.437593460083,1.78299129009,-6.6180138588 -0.448597460985,1.78298997879,-6.61521291733 -0.471619814634,1.78599512577,-6.62361001968 -0.492619693279,1.78198885918,-6.61100244522 -0.514633536339,1.78298974037,-6.61139297485 -0.537650763988,1.78399217129,-6.61479663849 -0.557636618614,1.77697861195,-6.58819675446 -0.580661892891,1.78098523617,-6.59958744049 -0.589648008347,1.77597510815,-6.57978248596 -0.611657738686,1.77497398853,-6.57618188858 -0.635690152645,1.77998435497,-6.59457588196 -0.656699538231,1.77998316288,-6.59095621109 -0.675679385662,1.77096664906,-6.55836009979 -0.70071542263,1.77797877789,-6.5797624588 -0.710713088512,1.77597439289,-6.57095909119 -0.732724070549,1.77597379684,-6.56835651398 -0.753729522228,1.77397060394,-6.56074810028 -0.775745093822,1.77497267723,-6.56313562393 -0.796748816967,1.77296853065,-6.55353212357 -0.819769978523,1.77597296238,-6.56092453003 -0.840768873692,1.77196633816,-6.54633522034 -0.849766075611,1.76996219158,-6.53751707077 -0.869760155678,1.76595294476,-6.51792383194 -0.894798278809,1.77296638489,-6.54230833054 -0.915802180767,1.77096223831,-6.53270816803 -0.935800850391,1.76795578003,-6.51810407639 -0.959827959538,1.77196347713,-6.53149604797 -0.981840729713,1.77196407318,-6.53088998795 -0.990832686424,1.76895701885,-6.51609230042 -1.01384890079,1.76995921135,-6.51849555969 -1.03284645081,1.76695215702,-6.50288057327 -1.05586099625,1.76795339584,-6.50328969955 -1.07888090611,1.76995754242,-6.50968027115 -1.09888184071,1.76795220375,-6.49707603455 -1.11787843704,1.76394486427,-6.48046779633 -1.12988972664,1.76594746113,-6.48466825485 -1.15089678764,1.76494526863,-6.47806453705 -1.17089962959,1.76294100285,-6.46745681763 -1.19291162491,1.76294124126,-6.46585559845 -1.2159307003,1.76594483852,-6.47124576569 -1.23593008518,1.76293885708,-6.45665359497 -1.25693619251,1.76093614101,-6.44905614853 -1.26693916321,1.76093482971,-6.44524765015 -1.28794717789,1.75993323326,-6.43964290619 -1.31096708775,1.76293742657,-6.44602870941 -1.33297586441,1.76293587685,-6.44044065475 -1.35197734833,1.75993132591,-6.42882394791 -1.37398779392,1.75993072987,-6.42523002625 -1.38700568676,1.76393663883,-6.43641662598 -1.4039914608,1.75692403316,-6.40783309937 -1.43002355099,1.76393401623,-6.42621994019 -1.45002579689,1.7609295845,-6.4146232605 -1.46802198887,1.75792241096,-6.39701604843 -1.4890294075,1.75692045689,-6.39041757584 -1.51204657555,1.75892329216,-6.39381122589 -1.52204966545,1.75892210007,-6.39000511169 -1.54205143452,1.75691747665,-6.37741518021 -1.56808149815,1.76292645931,-6.39380264282 -1.58708333969,1.7599221468,-6.38219118118 -1.60507822037,1.75591421127,-6.36259937286 -1.62708902359,1.75691378117,-6.3590054512 -1.6400667429,1.7478979826,-6.32240819931 -1.65709900856,1.75591087341,-6.34858512878 -1.68011522293,1.75791335106,-6.35098028183 -1.69811189175,1.75390648842,-6.33338403702 -1.7221313715,1.7569103241,-6.33878135681 -1.74414288998,1.75791049004,-6.33618164062 -1.75912988186,1.75189912319,-6.30858516693 -1.7891715765,1.76091337204,-6.33696937561 -1.79616308212,1.75690686703,-6.32117366791 -1.81717014313,1.75690484047,-6.31358194351 -1.83416748047,1.75389862061,-6.29696798325 -1.86320316792,1.76091015339,-6.31935882568 -1.88521397114,1.7619099617,-6.31576347351 -1.89819550514,1.75389623642,-6.2821726799 -1.92823493481,1.76290953159,-6.30855417252 -1.93422305584,1.75790143013,-6.28876781464 -1.95824205875,1.7609051466,-6.2941570282 -1.9832650423,1.76591062546,-6.30353975296 -1.99624693394,1.7578972578,-6.26995611191 -2.02628517151,1.76690983772,-6.29533338547 -2.04629015923,1.76590704918,-6.28573560715 -2.06027650833,1.75889587402,-6.25714540482 -3.20874810219,1.78785192966,-5.92090559006 -3.22474765778,1.78584766388,-5.90430831909 -3.2367401123,1.78084027767,-5.87972021103 -3.24273681641,1.77883696556,-5.86792230606 -3.26374554634,1.77983641624,-5.86131811142 -3.29076337814,1.7838395834,-5.86471843719 -3.3137755394,1.78584063053,-5.86210870743 -3.33678722382,1.78784120083,-5.85850667953 -3.35579180717,1.78783893585,-5.84691381454 -3.37479710579,1.7878370285,-5.83631277084 -3.38079357147,1.7858338356,-5.82451677322 -3.40680980682,1.78883612156,-5.82591438293 -3.42581439018,1.78883397579,-5.81432199478 -3.44782423973,1.78983402252,-5.80872058868 -3.45481014252,1.78282439709,-5.77613925934 -3.48984003067,1.79183220863,-5.79253196716 -3.50083327293,1.78782582283,-5.76892948151 -3.52285528183,1.7938324213,-5.78511714935 -3.53685188293,1.79082727432,-5.76453351974 -3.56086468697,1.79382824898,-5.76193141937 -3.59188747406,1.79983329773,-5.77032899857 -3.60187959671,1.79582643509,-5.74473333359 -3.61788034439,1.79382288456,-5.72913408279 -3.63489365578,1.79782617092,-5.73533391953 -3.65790462494,1.7998265028,-5.73073291779 -3.6688978672,1.795820117,-5.70614624023 -3.69891905785,1.80082464218,-5.71353149414 -3.71692252159,1.80082213879,-5.69994211197 -3.73592782021,1.80082046986,-5.68933820724 -3.7579369545,1.80182027817,-5.68273973465 -3.77294707298,1.80482208729,-5.68494415283 -3.78394150734,1.80081653595,-5.6623415947 -3.80995631218,1.80481827259,-5.66174030304 -3.82695865631,1.80381548405,-5.64714622498 -3.85097050667,1.80681633949,-5.64354419708 -3.88098978996,1.811819911,-5.6479473114 -3.88597607613,1.80481088161,-5.61437225342 -3.90799570084,1.81081664562,-5.62855195999 -3.92299556732,1.8098129034,-5.61095952988 -3.94400334358,1.81081211567,-5.60236167908 -3.96200680733,1.80980980396,-5.58877277374 -3.96999835968,1.80480325222,-5.56217479706 -3.99601197243,1.80880463123,-5.55958652496 -4.03604412079,1.81881320477,-5.57995605469 -4.0260219574,1.80980300903,-5.54518318176 -4.06104755402,1.8178088665,-5.55657291412 -4.07304430008,1.81480431557,-5.5359711647 -4.10206127167,1.8198069334,-5.53737783432 -4.11706209183,1.8178037405,-5.52077674866 -4.1400718689,1.81980383396,-5.5141825676 -4.14506864548,1.81780087948,-5.50139522552 -4.16207122803,1.81779849529,-5.4868016243 -4.18908691406,1.82180058956,-5.48718643188 -4.2110953331,1.82280015945,-5.47859764099 -4.22108983994,1.81979489326,-5.4550037384 -4.25210905075,1.82479846478,-5.45939779282 -4.27712154388,1.82879948616,-5.4557929039 -4.28011655807,1.82579600811,-5.44100236893 -4.29711961746,1.8247936964,-5.42640829086 -4.31111860275,1.82279002666,-5.40682840347 -4.33713197708,1.82679128647,-5.40422487259 -4.36014175415,1.82879161835,-5.39762401581 -4.38215065002,1.83079135418,-5.39001941681 -4.39915370941,1.83078920841,-5.37542438507 -4.40615367889,1.82978737354,-5.36563539505 -4.42015314102,1.82778406143,-5.34704589844 -4.45117139816,1.83378732204,-5.35043668747 -4.47117805481,1.83478629589,-5.33983659744 -4.4971909523,1.8387876749,-5.33722448349 -4.51619625092,1.83878624439,-5.32463312149 -4.53219842911,1.83778357506,-5.30804777145 -4.54320192337,1.83878338337,-5.30325460434 -4.56120634079,1.83878159523,-5.28966093063 -4.57520627975,1.83677852154,-5.2710723877 -4.59721565247,1.83977842331,-5.26346158981 -4.62522935867,1.84377992153,-5.2608704567 -4.63022089005,1.83877408504,-5.23228120804 -4.64823198318,1.84277629852,-5.2364730835 -4.67124128342,1.84477615356,-5.2278842926 -4.6171746254,1.81475126743,-5.13034820557 -4.57111692429,1.78872942924,-5.04280853271 -4.51304864883,1.75770461559,-4.94326734543 -4.49501991272,1.74369251728,-4.88970470428 -4.47899341583,1.72968113422,-4.83815050125 -4.48098993301,1.72667884827,-4.82435846329 -4.494992733,1.72667717934,-4.80876016617 -4.4989862442,1.72167253494,-4.78118038177 -4.51499080658,1.72167158127,-4.76758480072 -4.52899360657,1.72067010403,-4.75198793411 -4.53599023819,1.71666657925,-4.72840166092 -4.56200456619,1.72166860104,-4.7257976532 -4.56500244141,1.71966660023,-4.7130112648 -4.56699419022,1.71366178989,-4.68343925476 -4.58099746704,1.71266043186,-4.66784477234 -4.58999729156,1.71065783501,-4.64725017548 -4.61300849915,1.71365916729,-4.64164400101 -4.62100601196,1.71065616608,-4.61906385422 -4.62900447845,1.70765328407,-4.59648513794 -4.63200283051,1.70565164089,-4.58468961716 -4.64600658417,1.70465052128,-4.5690984726 -4.64699888229,1.69964599609,-4.53952503204 -4.66500616074,1.70064604282,-4.52793359756 -4.67500638962,1.69864404202,-4.50834560394 -4.67800140381,1.6936403513,-4.48176288605 -4.69700956345,1.69464063644,-4.47117185593 -4.69600486755,1.69163835049,-4.45636892319 -4.70600557327,1.68963634968,-4.43579864502 -4.72000980377,1.68963575363,-4.4221830368 -4.73001098633,1.68763399124,-4.40161418915 -4.74901914597,1.68963432312,-4.39102220535 -4.75401592255,1.6856316328,-4.36743211746 -4.77102327347,1.68663167953,-4.35582828522 -4.76901817322,1.68262934685,-4.33904695511 -4.77801847458,1.68062758446,-4.31846904755 -4.78802013397,1.67962610722,-4.29987573624 -4.80002307892,1.67862522602,-4.28327989578 -4.80702209473,1.67562329769,-4.26169347763 -4.82302904129,1.67662322521,-4.24810695648 -4.81902265549,1.67162072659,-4.23032045364 -4.84703874588,1.67762327194,-4.22871208191 -4.84903383255,1.67262041569,-4.20213794708 -4.86303901672,1.67262005806,-4.18655586243 -4.87003850937,1.66961836815,-4.16595888138 -4.88704586029,1.67061877251,-4.15337133408 -4.88904237747,1.66661608219,-4.12778711319 -4.90805339813,1.67061841488,-4.13098430634 -4.91605424881,1.66861689091,-4.11040210724 -4.91404771805,1.6626137495,-4.08083152771 -4.93105506897,1.66461420059,-4.06922864914 -4.94606113434,1.6646143198,-4.054646492 -4.9510602951,1.66161262989,-4.03206110001 -4.96006250381,1.65961170197,-4.01346588135 -4.97807264328,1.66461372375,-4.01565933228 -4.98307180405,1.66061222553,-3.99307632446 -4.99107265472,1.65861105919,-3.97250056267 -5.00607919693,1.65961122513,-3.95791888237 -5.01408100128,1.65761053562,-3.93931341171 -5.02508449554,1.65661001205,-3.92172980309 -5.02808475494,1.65560948849,-3.91093921661 -5.04208993912,1.6556096077,-3.89536118507 -5.05309438705,1.65560936928,-3.87876296043 -5.05909490585,1.65260839462,-3.857183218 -5.06909751892,1.65160799026,-3.83958959579 -5.08710622787,1.65360891819,-3.82799768448 -5.09210634232,1.65060782433,-3.80640816689 -5.09810876846,1.65060782433,-3.79762387276 -5.11411571503,1.65160858631,-3.78502321243 -5.12411975861,1.65060830116,-3.76644682884 -5.12311649323,1.64560651779,-3.73987030983 -5.14012432098,1.64760756493,-3.72826504707 -5.14812660217,1.64560711384,-3.70868349075 -5.155128479,1.64360666275,-3.68810749054 -5.15812921524,1.64260649681,-3.67830562592 -5.17013454437,1.64260673523,-3.66172337532 -5.17413425446,1.63960599899,-3.63914704323 -5.19114255905,1.64060688019,-3.62655830383 -5.20114660263,1.6406069994,-3.60995316505 -5.20714855194,1.63860678673,-3.58936929703 -5.21615219116,1.63760685921,-3.57078742981 -5.22415590286,1.63760733604,-3.56399536133 -5.22715568542,1.63460671902,-3.54141235352 -5.23115730286,1.63260638714,-3.51982522011 -5.26017189026,1.63760888577,-3.51622033119 -5.26617383957,1.6356086731,-3.49563980103 -5.26717329025,1.63260805607,-3.47107124329 -5.27517700195,1.63160824776,-3.45248126984 -5.26917314529,1.62660729885,-3.43570280075 -5.29818820953,1.63260984421,-3.43209266663 -5.30018806458,1.6296094656,-3.40852236748 -5.30218887329,1.6266092062,-3.38593649864 -5.30919218063,1.62460947037,-3.36635565758 -5.32520008087,1.62661063671,-3.3537530899 -5.31819629669,1.62260973454,-3.33696889877 -5.33420419693,1.62361109257,-3.32338404655 -5.33720541,1.62161111832,-3.30179619789 -5.34721088409,1.62061178684,-3.28421592712 -5.35621500015,1.6206125021,-3.2666246891 -5.37222290039,1.62161386013,-3.25303888321 -5.36321878433,1.61461305618,-3.22346711159 -5.36521959305,1.61361324787,-3.21268105507 -5.38422966003,1.61661481857,-3.20207476616 -5.38322973251,1.61261487007,-3.17750358582 -5.39123392105,1.61161565781,-3.15892243385 -5.41324567795,1.61561751366,-3.15031075478 -5.40624284744,1.60961735249,-3.12175154686 -5.41824913025,1.6106184721,-3.10615968704 -5.42425203323,1.61061906815,-3.09836363792 -5.43125629425,1.60961997509,-3.07977414131 -5.43826055527,1.6076208353,-3.06020331383 -5.44226360321,1.60562157631,-3.03962016106 -5.44626665115,1.60362243652,-3.01903796196 -5.46927833557,1.60762441158,-3.01043128967 -5.46627855301,1.60362482071,-2.9858520031 -5.46527862549,1.60162520409,-2.97307729721 -5.47828578949,1.60262656212,-2.95847821236 -5.48929214478,1.60262787342,-2.94189548492 -5.47728824615,1.59562802315,-2.9123237133 -5.50730371475,1.60263049603,-2.90672683716 -5.51530838013,1.60163187981,-2.88913321495 -5.50430440903,1.59663176537,-2.87135624886 -5.50030517578,1.59263241291,-2.84677672386 -5.51831483841,1.59463429451,-2.83418989182 -5.51631593704,1.59163534641,-2.8106136322 -5.5193195343,1.58963656425,-2.79003119469 -5.53032588959,1.58963811398,-2.77443265915 -5.54333353043,1.59063994884,-2.75885272026 -5.54133415222,1.58864045143,-2.74705719948 -5.55234146118,1.58964204788,-2.73047685623 -5.54333972931,1.5836430788,-2.70389842987 -5.54434347153,1.58064448833,-2.68232107162 -5.57235717773,1.58664691448,-2.67472934723 -5.56235551834,1.5806479454,-2.64814639091 -5.57836484909,1.58264994621,-2.63455629349 -5.58136749268,1.58265078068,-2.62477207184 -5.5703663826,1.57665193081,-2.59720373154 -5.59637928009,1.58165442944,-2.5886080265 -5.58837938309,1.57665574551,-2.56303119659 -5.60338830948,1.57865786552,-2.54943108559 -5.6113948822,1.57765972614,-2.53086447716 -5.61840057373,1.57766163349,-2.51326990128 -5.59939527512,1.57066214085,-2.49348807335 -5.62040615082,1.5736644268,-2.48190140724 -5.6294131279,1.57366645336,-2.46432518959 -5.62541532516,1.57066822052,-2.44173431396 -5.62541913986,1.56767010689,-2.42016029358 -5.64743041992,1.57167232037,-2.4095594883 -5.64143037796,1.56867337227,-2.39578056335 -5.64243459702,1.56667542458,-2.37519717216 -5.65944480896,1.56967771053,-2.36161112785 -5.65244626999,1.56467974186,-2.3370411396 -5.66445446014,1.56568205357,-2.32145261765 -5.68246412277,1.56868433952,-2.30885338783 -5.66646337509,1.56168651581,-2.28029251099 -5.68046998978,1.56468760967,-2.2764840126 -5.69748020172,1.56769001484,-2.26289510727 -5.69648456573,1.56469237804,-2.24131989479 -5.70949316025,1.56669473648,-2.22573757172 -5.71049785614,1.56369721889,-2.20516014099 -5.70950222015,1.56169950962,-2.1845676899 -5.71850967407,1.56170201302,-2.16699409485 -5.72051239014,1.5617030859,-2.15818786621 -5.72151756287,1.55970573425,-2.13761305809 -5.73052549362,1.55970835686,-2.12003993988 -5.73453092575,1.55871093273,-2.10144901276 -5.73253583908,1.55671346188,-2.07987356186 -5.75454711914,1.56071603298,-2.06827664375 -5.75655269623,1.55871868134,-2.04869174957 -5.74955368042,1.55572021008,-2.03492164612 -5.75155925751,1.55472290516,-2.01533818245 -5.75856637955,1.55472552776,-1.99775111675 -5.76557397842,1.55472826958,-1.98016417027 -5.76357889175,1.55173122883,-1.95859467983 -5.78859138489,1.55673360825,-1.94799268246 -5.77559041977,1.55173528194,-1.93320560455 -5.77859640121,1.55073833466,-1.91363203526 -5.78960561752,1.5517411232,-1.89705300331 -5.77960824966,1.54774439335,-1.87347316742 -5.78961706161,1.54874718189,-1.85688769817 -5.8056268692,1.55074989796,-1.84230101109 -5.80163192749,1.54775321484,-1.82072377205 -5.80663585663,1.54875445366,-1.81292033195 -5.80364131927,1.54575788975,-1.79135155678 -5.81364965439,1.5467607975,-1.77476537228 -5.82165813446,1.54776382446,-1.7571862936 -5.82966566086,1.5477668047,-1.74058663845 -5.82167053223,1.54377043247,-1.71703052521 -5.8336763382,1.54677176476,-1.71122920513 -5.82868146896,1.54277527332,-1.68965256214 -5.82768726349,1.54077863693,-1.67006039619 -5.84469795227,1.54478144646,-1.65547418594 -5.84670448303,1.54278492928,-1.63590097427 -5.84171056747,1.53978860378,-1.61432802677 -5.85371923447,1.54179155827,-1.59873151779 -5.85272264481,1.5407936573,-1.58795440197 -5.858730793,1.54079687595,-1.57036423683 -5.85273599625,1.53780078888,-1.54878878593 -5.86274528503,1.53880381584,-1.5322009325 -5.86075210571,1.5368077755,-1.51162922382 -5.86575937271,1.53681111336,-1.49403429031 -5.88477039337,1.53981411457,-1.47945344448 -5.8717713356,1.53581666946,-1.46567595005 -5.86977815628,1.5338203907,-1.44608581066 -5.88678884506,1.53682351112,-1.43051338196 -5.88079452515,1.53382754326,-1.40992391109 -5.88780355453,1.53483116627,-1.39234006405 -5.90081357956,1.53683447838,-1.37576556206 -5.89081811905,1.53183877468,-1.35417985916 -5.90082454681,1.53484046459,-1.34639918804 -5.90583229065,1.53484404087,-1.32880485058 -5.90483951569,1.53284811974,-1.30922365189 -5.91184854507,1.53385162354,-1.291639328 -5.90885591507,1.5308560133,-1.27107095718 -5.91886520386,1.53285956383,-1.25447952747 -5.92387008667,1.53386127949,-1.24569416046 -5.91887664795,1.53086578846,-1.22511792183 -5.92688655853,1.53186953068,-1.20753800869 -5.93389511108,1.53187334538,-1.18995332718 -5.94190454483,1.53387701511,-1.17237222195 -5.92690992355,1.52788233757,-1.14979803562 -5.92991828918,1.52788639069,-1.13121771812 -5.94292449951,1.53088760376,-1.12442302704 -5.95093345642,1.53189134598,-1.10782051086 -5.95194196701,1.53089570999,-1.08825266361 -5.95595121384,1.53089988232,-1.06967616081 -5.94295692444,1.52590513229,-1.04809629917 -5.94896602631,1.52690911293,-1.03050732613 -5.96397686005,1.52991271019,-1.0139311552 -5.95898008347,1.52791535854,-1.00314867496 -5.9529876709,1.52492010593,-0.98355692625 -5.98000049591,1.5309227705,-0.968980669975 -5.97200727463,1.52792799473,-0.948403537273 -5.97701644897,1.52893209457,-0.930809557438 -5.98302650452,1.52893638611,-0.912240684032 -5.97303390503,1.52594172955,-0.891659498215 -5.98603963852,1.52894294262,-0.884855210781 -5.9940495491,1.52994704247,-0.867270946503 -5.97805595398,1.52495324612,-0.844715774059 -5.99106645584,1.52695691586,-0.828126311302 -5.99207544327,1.52696156502,-0.809540867805 -5.99408483505,1.52596616745,-0.790959358215 -5.99408912659,1.52596855164,-0.781176149845 -6.00409889221,1.52797245979,-0.764574825764 -5.99210691452,1.52397847176,-0.743017554283 -5.98811531067,1.52098369598,-0.723441839218 -6.00612688065,1.52598702908,-0.707840323448 -6.00513553619,1.52499222755,-0.68827277422 -5.99414396286,1.52099812031,-0.667701303959 -6.02615213394,1.52899777889,-0.662893891335 -6.00615930557,1.52300465107,-0.641321599483 -6.00316810608,1.52100992203,-0.621750950813 -6.02117919922,1.52601313591,-0.606143653393 -6.00318670273,1.52002000809,-0.584581792355 -6.0241985321,1.52502334118,-0.568001568317 -6.01920795441,1.52302896976,-0.548427402973 -6.01621198654,1.52203178406,-0.538639545441 -6.02822256088,1.52503561974,-0.522036790848 -6.03823280334,1.52703988552,-0.504450619221 -6.03124189377,1.5240457058,-0.484874069691 -6.02625131607,1.5220515728,-0.465302318335 -6.04326295853,1.526055336,-0.447727888823 -6.02227067947,1.5200625658,-0.427150458097 -6.03927755356,1.52406358719,-0.41935557127 -6.04128742218,1.52406871319,-0.400775194168 -6.02929592133,1.52007520199,-0.381194621325 -6.02530574799,1.51908111572,-0.361627787352 -6.04631757736,1.52408432961,-0.345032513142 -6.03132629395,1.51909148693,-0.324472635984 -6.0303311348,1.51909410954,-0.31566914916 -6.04934310913,1.52409768105,-0.298089742661 -6.03135108948,1.51810503006,-0.278507292271 -6.04036283493,1.52010977268,-0.259936273098 -6.04437303543,1.5211148262,-0.241358742118 -6.04738330841,1.52111983299,-0.223758071661 -6.03739261627,1.51812660694,-0.204188734293 -6.03739833832,1.51812958717,-0.194409191608 -6.03740882874,1.51813519001,-0.175828188658 -6.04241943359,1.51914024353,-0.157251313329 -6.04343032837,1.51914584637,-0.138671085238 -6.03444004059,1.5161523819,-0.120084576309 -6.03945112228,1.51715767384,-0.101507380605 -6.04646205902,1.51916265488,-0.0829304978251 -6.04346656799,1.51816570759,-0.0741277337074 -6.04547786713,1.51817131042,-0.0555482506752 -6.04848861694,1.51917672157,-0.0369687005877 -6.04749917984,1.51818275452,-0.0183880887926 -6.04051017761,1.51618945599,0.00117155292537 -6.04652166367,1.51819479465,0.0197507292032 -6.03953170776,1.51620137691,0.0383312515914 -6.03453636169,1.51420474052,0.0471320785582 -6.04254770279,1.51620972157,0.0657115653157 -6.04255867004,1.51621568203,0.0842912718654 -6.03156900406,1.51322305202,0.102868959308 -6.04958152771,1.51822698116,0.121452264488 -6.04359197617,1.51623356342,0.140030309558 -6.03459787369,1.5142377615,0.149806007743 -6.04260921478,1.51624286175,0.168388277292 -6.02861976624,1.51225066185,0.186960890889 -6.03263139725,1.51325643063,0.205541610718 -6.03864240646,1.51526176929,0.224124252796 -6.03465414047,1.51426839828,0.242700725794 -6.04066562653,1.51527380943,0.261284053326 -6.03267097473,1.51327776909,0.270078539848 -6.02468204498,1.5112849474,0.288650542498 -6.04769468307,1.51728844643,0.308228075504 -6.03170490265,1.51329660416,0.325814276934 -6.01971673965,1.51030445099,0.344380438328 -6.02872848511,1.51330947876,0.362968981266 -6.01673364639,1.50931406021,0.371755242348 -6.02474594116,1.51231968403,0.391321241856 -6.03175783157,1.5143250227,0.409909129143 -6.0227689743,1.51233232021,0.427498281002 -6.02578115463,1.51333868504,0.447059214115 -6.02579307556,1.51334512234,0.465638279915 -6.01680469513,1.51035249233,0.4832251966 -6.01681089401,1.51035583019,0.493003427982 -6.02182292938,1.51236152649,0.511590719223 -6.01083421707,1.50936937332,0.529172837734 -6.02684688568,1.51437366009,0.54875856638 -6.02585840225,1.51438033581,0.5673366189 -6.01887083054,1.51338803768,0.585903048515 -6.00988292694,1.5103956461,0.603486418724 -6.01488924026,1.51239824295,0.613275408745 -6.00390100479,1.5094063282,0.630853712559 -6.01091337204,1.51241207123,0.650426328182 -6.00892591476,1.51241910458,0.669001698494 -6.00793790817,1.51242554188,0.686601281166 -5.99995040894,1.51043355465,0.70516204834 -6.01295661926,1.51443517208,0.715950548649 -6.00196933746,1.51144337654,0.733525693417 -5.99798107147,1.51045048237,0.751117527485 -6.001994133,1.51245677471,0.770686388016 -5.9930062294,1.51046478748,0.788264751434 -5.99701833725,1.51247084141,0.806856334209 -5.99803161621,1.51347780228,0.826418101788 -5.9920372963,1.51148164272,0.8342243433 -5.99305057526,1.51248860359,0.853786230087 -5.97606372833,1.50849795341,0.870360374451 -5.98007535934,1.50950396061,0.888953089714 -5.98308897018,1.51151061058,0.908521652222 -5.97310161591,1.50951898098,0.926093101501 -5.97111415863,1.50952589512,0.943689763546 -5.97712087631,1.51152873039,0.954467356205 -5.96713447571,1.50953722,0.972037434578 -5.9651465416,1.50954413414,0.989634156227 -5.95516014099,1.50755274296,1.00720274448 -5.95617294312,1.50855958462,1.02578794956 -5.95918560028,1.50956618786,1.04535877705 -5.95419931412,1.50957381725,1.06294476986 -5.9492058754,1.50857830048,1.07172822952 -5.95421886444,1.51058459282,1.09130787849 -5.95523166656,1.51159131527,1.10989499092 -5.94124555588,1.50860071182,1.12646698952 -5.94725799561,1.51060676575,1.14605236053 -5.93327188492,1.50761604309,1.16262257099 -5.94127845764,1.51061844826,1.17341458797 -5.92429304123,1.50662839413,1.18997097015 -5.91730642319,1.50563681126,1.20754647255 -5.92231988907,1.50764322281,1.2271296978 -5.91633319855,1.50765132904,1.24470949173 -5.91934633255,1.5086581707,1.26428520679 -5.91535997391,1.5086659193,1.28187394142 -5.91536712646,1.50966954231,1.29165565968 -5.91238021851,1.5096770525,1.30924904346 -5.89939451218,1.50668644905,1.32581710815 -5.90740776062,1.50969266891,1.34639692307 -5.89742183685,1.50870144367,1.36297869682 -5.88843584061,1.50671041012,1.38054227829 -5.89244937897,1.5087171793,1.40012657642 -5.88845682144,1.50872147083,1.40891098976 -5.88847017288,1.50972867012,1.42749798298 -5.90548276901,1.51573348045,1.450086236 -5.88249874115,1.50974476337,1.46464216709 -5.88051176071,1.51075220108,1.48224163055 -5.87952613831,1.51175999641,1.50180327892 -5.8685336113,1.50876557827,1.50859260559 -5.87554740906,1.51277184486,1.52917647362 -5.87256145477,1.5127799511,1.54774963856 -5.87457513809,1.5147870779,1.56732952595 -5.85859012604,1.51079702377,1.58191621304 -5.85960435867,1.51280450821,1.60149085522 -5.84961938858,1.51081371307,1.61806726456 -5.85662603378,1.51381659508,1.62984979153 -5.85263967514,1.5138245821,1.64743959904 -5.85365390778,1.51583206654,1.6670165062 -5.8376698494,1.51284253597,1.68257784843 -5.83668422699,1.5138502121,1.70116424561 -5.82769870758,1.51285922527,1.71774506569 -5.82671356201,1.51386737823,1.73731064796 -5.82972002029,1.5148704052,1.74711537361 -5.8197350502,1.51387989521,1.76368963718 -5.80475139618,1.51089024544,1.77925252914 -5.82076406479,1.51689517498,1.80284285545 -5.79078102112,1.50990784168,1.81341421604 -5.79679536819,1.51291489601,1.83498418331 -5.79580926895,1.51392269135,1.8535733223 -5.78581762314,1.51192820072,1.86035788059 -5.78383255005,1.51293635368,1.87894058228 -5.78184747696,1.51394486427,1.89850234985 -5.77686214447,1.51395344734,1.91608655453 -5.77487707138,1.51496148109,1.93467056751 -5.77289152145,1.51596963406,1.95325481892 -5.76490020752,1.51497507095,1.9610298872 -5.75691509247,1.51398420334,1.97761416435 -5.75493049622,1.51499271393,1.99717783928 -5.73494720459,1.51100385189,2.00975966454 -5.7379617691,1.51401138306,2.03033876419 -5.74297618866,1.51701855659,2.05191254616 -5.72299289703,1.51302981377,2.06449174881 -5.72200012207,1.51303374767,2.07329511642 -5.71701574326,1.51404297352,2.09185886383 -5.72003078461,1.51605033875,2.11244130135 -5.69404792786,1.51006281376,2.12301278114 -5.69706249237,1.51307034492,2.14359617233 -5.69607782364,1.51507866383,2.16317033768 -5.67908763885,1.51008558273,2.16695427895 -5.68110227585,1.51309347153,2.18753123283 -5.67011833191,1.51110339165,2.20311045647 -5.6541352272,1.50911414623,2.21669077873 -5.66414928436,1.51412069798,2.24027132988 -5.65916585922,1.51412987709,2.25883603096 -5.64518213272,1.51214039326,2.27341079712 -5.6331911087,1.50914645195,2.27820801735 -5.62820720673,1.5101556778,2.29677248001 -5.64322090149,1.51616132259,2.3223593235 -5.6182384491,1.51117360592,2.33194327354 -5.60825586319,1.51018381119,2.34850716591 -5.6192688942,1.51518988609,2.37210583687 -5.61028575897,1.51519978046,2.38867926598 -5.58929634094,1.50920772552,2.39045667648 -5.60131072998,1.51521408558,2.41602635384 -5.58532810211,1.513225317,2.42959952354 -5.57334470749,1.51123559475,2.44418621063 -5.56536102295,1.5112452507,2.46076703072 -5.57237625122,1.51525247097,2.48433852196 -5.54439496994,1.50926566124,2.49192380905 -5.54040336609,1.50927066803,2.50070357323 -5.54541873932,1.51327824593,2.5232796669 -5.54543399811,1.51528632641,2.54287290573 -5.52045297623,1.50929939747,2.5524392128 -5.52646827698,1.51430690289,2.5760076046 -5.51148605347,1.51131808758,2.58958363533 -5.50149488449,1.50932371616,2.59438848495 -5.5055103302,1.51333153248,2.61696076393 -5.49452781677,1.51234209538,2.63253331184 -5.49854373932,1.5163500309,2.65510797501 -5.48356151581,1.51436126232,2.66868257523 -5.47657823563,1.51437079906,2.68527317047 -5.4805932045,1.51737844944,2.70785093307 -5.46960353851,1.5153850317,2.71362352371 -5.46162033081,1.51539492607,2.73020482063 -5.4516377449,1.51540529728,2.74578666687 -5.45065402985,1.51741409302,2.76635813713 -5.44067144394,1.51642453671,2.78193974495 -5.43368864059,1.5174343586,2.7995121479 -5.41670751572,1.51444625854,2.81208205223 -5.41471529007,1.51545071602,2.82088303566 -5.41973114014,1.51945853233,2.84445953369 -5.41674804688,1.52046775818,2.86403417587 -5.40576601028,1.52047848701,2.87960624695 -5.38078546524,1.5154914856,2.88718914986 -5.3987994194,1.52349698544,2.91776823997 -5.38280916214,1.51950418949,2.91956162453 -5.37782669067,1.52051377296,2.93813729286 -5.35984563828,1.51852583885,2.94971227646 -5.34986305237,1.51753628254,2.9652929306 -5.34388113022,1.51854646206,2.98385834694 -5.34189748764,1.5205552578,3.00344777107 -5.33291530609,1.52056586742,3.02002072334 -5.32392501831,1.51957201958,3.02580666542 -5.32594156265,1.52258038521,3.04838323593 -5.31196022034,1.52159178257,3.0619597435 -5.31597614288,1.5255998373,3.08554172516 -5.29999542236,1.52361166477,3.09811520576 -5.29101324081,1.5236222744,3.11468887329 -5.29002141953,1.52462673187,3.12448620796 -5.28403902054,1.52563679218,3.14305567741 -5.27805614471,1.52664661407,3.16064500809 -5.27807378769,1.52965581417,3.18320775032 -5.27409076691,1.53166508675,3.20180225372 -5.26110982895,1.53067648411,3.21637058258 -5.24412918091,1.52868855,3.22794890404 -5.23913955688,1.52869427204,3.23672151566 -5.21116018295,1.52270829678,3.24130296707 -5.20517730713,1.52371811867,3.25889325142 -5.1981959343,1.52472889423,3.27745366096 -5.18921375275,1.52473914623,3.29304695129 -5.17923212051,1.52474987507,3.30862903595 -5.18224906921,1.52875852585,3.33319735527 -5.15726232529,1.52276790142,3.3289744854 -5.15527963638,1.52577710152,3.34955859184 -5.15229606628,1.52778637409,3.36915040016 -5.14031600952,1.52679824829,3.38470864296 -5.12833547592,1.52680945396,3.3992857933 -5.12735271454,1.52981865406,3.42086696625 -5.11037254333,1.52783095837,3.43243813515 -5.11537981033,1.53083431721,3.44624185562 -5.10839891434,1.53184509277,3.46480727196 -5.0944185257,1.53085684776,3.4783782959 -5.07743835449,1.52886903286,3.488966465 -5.07345628738,1.53087902069,3.50953316689 -5.05647659302,1.52889120579,3.52012014389 -5.05448484421,1.5298961401,3.52991318703 -5.05650281906,1.5339050293,3.55448508263 -5.03952217102,1.53191721439,3.56507158279 -5.02354335785,1.52992975712,3.57763338089 -5.02256059647,1.53293883801,3.59922456741 -5.00458192825,1.53095197678,3.61077857018 -4.98460245132,1.5279648304,3.61935925484 -4.99460935593,1.53296756744,3.63814806938 -4.98062896729,1.53197932243,3.65073490143 -4.97564744949,1.53398942947,3.67031359673 -4.96166753769,1.53300154209,3.68388223648 -4.94568824768,1.53201389313,3.69545984268 -4.93570804596,1.53202521801,3.71202707291 -4.9377245903,1.5370336771,3.73563027382 -4.93173456192,1.53703963757,3.74341034889 -4.91075658798,1.53305315971,3.75197339058 -4.92077207565,1.54106032848,3.78256368637 -4.89479398727,1.53607451916,3.78614664078 -4.90081071854,1.54208278656,3.81472206116 -4.88483190536,1.54009521008,3.8262989521 -4.86885213852,1.53910756111,3.83787488937 -4.86486196518,1.53911304474,3.84666490555 -4.85588169098,1.54012441635,3.86423230171 -4.84090280533,1.53913664818,3.87680411339 -4.83492183685,1.54114723206,3.89637875557 -4.82794046402,1.54315769672,3.91397476196 -4.80996179581,1.54117071629,3.9245390892 -4.8029718399,1.54017663002,3.93034005165 -4.80398988724,1.54518592358,3.95591211319 -4.78501081467,1.54219889641,3.96449565887 -4.76903295517,1.54121184349,3.9770526886 -4.76805067062,1.54522109032,3.9996509552 -4.75707054138,1.54523265362,4.01522779465 -4.75508069992,1.5472381115,4.0269985199 -4.74010133743,1.54625022411,4.03858661652 -4.71912288666,1.54326367378,4.04517269135 -4.71714162827,1.54727363586,4.06874465942 -4.71616029739,1.55128347874,4.09331655502 -4.69618225098,1.5482968092,4.10089874268 -4.6902012825,1.55030727386,4.12048339844 -4.68921136856,1.55231261253,4.13325595856 -4.66623353958,1.54932641983,4.13784265518 -4.66825151443,1.55433571339,4.16541433334 -4.65127325058,1.55234861374,4.175989151 -4.63529491425,1.5513613224,4.18756151199 -4.62631416321,1.55237233639,4.2041554451 -4.61633443832,1.55338382721,4.22073459625 -4.60534572601,1.55239069462,4.22352552414 -4.61036396027,1.55939972401,4.25508499146 -4.58938598633,1.55541300774,4.26068019867 -4.57240772247,1.55442607403,4.27125358582 -4.56742715836,1.55743670464,4.29282951355 -4.5504488945,1.55544936657,4.30241823196 -4.53547048569,1.55546212196,4.31498861313 -4.5284819603,1.55546879768,4.32275772095 -4.531498909,1.5614773035,4.35036277771 -4.51252126694,1.55949056149,4.35893678665 -4.49754333496,1.55850338936,4.37150764465 -4.4935631752,1.5625140667,4.39507389069 -4.47158670425,1.55952811241,4.40064811707 -4.46359634399,1.55853438377,4.40544843674 -4.45461702347,1.5605455637,4.42303371429 -4.43763971329,1.55955910683,4.43458938599 -4.43165922165,1.5615695715,4.45419025421 -4.41668081284,1.56158232689,4.46676158905 -4.4017033577,1.56059515476,4.47933244705 -4.40072250366,1.56560516357,4.50590705872 -4.38773393631,1.56361234188,4.50570631027 -4.38175392151,1.56662333012,4.52728128433 -4.36277627945,1.5646365881,4.53486633301 -4.34979820251,1.56464898586,4.5494389534 -4.33282136917,1.56366240978,4.56000852585 -4.32284212112,1.56567418575,4.57758426666 -4.30886411667,1.56568682194,4.5911564827 -4.30187511444,1.56569314003,4.59794235229 -4.28789663315,1.5657055378,4.6105298996 -4.27691745758,1.56671726704,4.62612056732 -4.26094007492,1.56573033333,4.6376914978 -4.24396324158,1.56474363804,4.64826011658 -4.23098516464,1.56575620174,4.66283416748 -4.22399568558,1.56576216221,4.66863489151 -4.2070183754,1.56477558613,4.67920351028 -4.20703744888,1.57078540325,4.70778512955 -4.17506408691,1.56380176544,4.70135688782 -4.17108392715,1.56781232357,4.72593307495 -4.16610336304,1.57182300091,4.748524189 -4.14912605286,1.5708360672,4.75810718536 -4.13913822174,1.56984305382,4.76188850403 -4.12915992737,1.57185530663,4.78045749664 -4.10418462753,1.56687009335,4.78103590012 -4.10120391846,1.57188034058,4.80662202835 -4.08322811127,1.57089412212,4.81618785858 -4.06725025177,1.57090699673,4.82677173615 -4.05527162552,1.57191932201,4.84235239029 -4.04828262329,1.57192540169,4.84815406799 -4.03530502319,1.5729380846,4.86371898651 -4.02032804489,1.57295107841,4.8762922287 -4.00735044479,1.57396364212,4.89087152481 -3.99037337303,1.57297682762,4.90045309067 -3.97739553452,1.57398939133,4.91503238678 -3.97640514374,1.57599449158,4.92882633209 -3.94743156433,1.57101035118,4.92439603806 -3.93445444107,1.57202327251,4.93996238708 -3.92647528648,1.57503461838,4.96054649353 -3.91549658775,1.57604658604,4.97713518143 -3.90551900864,1.57905876637,4.99670171738 -3.47364020348,1.39615535736,4.47724676132 -3.44965577126,1.38816535473,4.46102905273 -3.43467903137,1.38817822933,4.46961116791 -3.43469882011,1.39418828487,4.49818515778 -3.78663420677,1.55712735653,4.98480558395 -3.81864500046,1.57813060284,5.05740261078 -3.80266880989,1.57814395428,5.0689740181 -3.7946805954,1.57815063,5.07475996017 -3.78370308876,1.58016312122,5.09332799911 -3.77172493935,1.58217537403,5.10891771317 -3.74975013733,1.57918989658,5.11248874664 -3.73877215385,1.58120203018,5.13007164001 -3.72179555893,1.58121538162,5.13965177536 -3.71981573105,1.587225914,5.17022943497 -3.72882318497,1.59522902966,5.19902420044 -3.6988503933,1.58824527264,5.19159269333 -3.67487621307,1.58526039124,5.19216442108 -3.45394873619,1.48831439018,4.91274547577 -3.45296907425,1.49532485008,4.94431209564 -3.47298383713,1.51233077049,5.00489711761 -3.66495633125,1.61030220985,5.3134970665 -3.6469707489,1.60631096363,5.3052816391 -3.60300111771,1.59332966805,5.27586221695 -3.57602763176,1.58734536171,5.27143573761 -3.56704950333,1.59135723114,5.2930150032 -3.54507470131,1.58837175369,5.29559183121 -3.51010346413,1.58038902283,5.27916145325 -3.54211473465,1.6033924818,5.36175203323 -3.53612613678,1.60439884663,5.37054157257 -3.492156744,1.59141755104,5.33912467957 -3.47518110275,1.59143137932,5.34969472885 -3.47720074654,1.60044121742,5.38926887512 -3.39424037933,1.56646764278,5.29585599899 -3.4192545414,1.58747303486,5.37142944336 -3.40726709366,1.58548033237,5.37022590637 -3.38629245758,1.58349466324,5.37380218506 -3.27134203911,1.53352832794,5.22935676575 -3.43332099915,1.62550592422,5.52395057678 -3.4183447361,1.62651896477,5.53753137589 -3.41136598587,1.63153040409,5.56411361694 -3.32140874863,1.59355866909,5.45568656921 -3.43538999557,1.6575409174,5.66148328781 -3.44140815735,1.66954982281,5.71007108688 -3.39743947983,1.65556895733,5.67763853073 -3.36446738243,1.64758551121,5.66122579575 -3.26851177216,1.60561490059,5.53880310059 -3.3065226078,1.635617733,5.64337444305 -3.28253817558,1.62762725353,5.62117624283 -3.35553956032,1.67562294006,5.78675556183 -3.33656477928,1.67563700676,5.79533147812 -3.3235874176,1.67764949799,5.81292247772 -3.30961155891,1.68066287041,5.8314871788 -3.28763771057,1.6786775589,5.83506059647 -3.26766300201,1.67769181728,5.8416390419 -3.25867509842,1.67769861221,5.84643125534 -3.24369859695,1.67971169949,5.86101961136 -3.23272204399,1.68372428417,5.88459157944 -3.21174740791,1.68173861504,5.88917207718 -3.19477176666,1.68275213242,5.90075588226 -3.17879652977,1.683765769,5.91532897949 -3.15982103348,1.68377959728,5.92291545868 -3.15283346176,1.68478631973,5.93269681931 -3.13685750961,1.68579959869,5.94628095627 -3.12088155746,1.68781292439,5.95986557007 -3.100908041,1.68682765961,5.96842575073 -3.08593082428,1.68884027004,5.98202943802 -3.06595683098,1.68785476685,5.98959875107 -3.04898166656,1.68986845016,6.00217676163 -3.03699493408,1.68787610531,6.00196170807 -3.02401852608,1.69088864326,6.02154827118 -3.0080435276,1.69290244579,6.03711795807 -2.99106812477,1.69391608238,6.04969787598 -2.96809434891,1.69193100929,6.05027627945 -2.94911956787,1.69094479084,6.05786418915 -2.93713355064,1.68995273113,6.05863904953 -2.93115496635,1.69796395302,6.0932264328 -2.9111802578,1.69697797298,6.09881496429 -2.89720416069,1.69999098778,6.11739969254 -2.87823033333,1.70100533962,6.12796354294 -2.86725306511,1.70501756668,6.15255451202 -2.8432803154,1.70303297043,6.15212202072 -2.83529186249,1.70303928852,6.15792751312 -2.81531763077,1.70305359364,6.16450786591 -2.79434418678,1.70206820965,6.17007780075 -2.77836894989,1.70408165455,6.18565702438 -2.75839519501,1.70409607887,6.19322919846 -2.74241995811,1.70610952377,6.2088098526 -2.72544407845,1.70712292194,6.22040510178 -2.71145868301,1.7041311264,6.21618175507 -2.69548296928,1.70614433289,6.23077201843 -2.67550945282,1.70615899563,6.23933696747 -2.65153622627,1.70317399502,6.23592233658 -2.63556098938,1.70518732071,6.25150537491 -2.6175866127,1.70620119572,6.26308393478 -2.60959839821,1.70720767975,6.2698841095 -2.59262418747,1.7092217207,6.2854514122 -2.57065057755,1.70823633671,6.28703355789 -2.54867744446,1.7062510252,6.28960704803 -2.53270244598,1.70926463604,6.30618715286 -2.51872611046,1.71327733994,6.32578325272 -2.49275374413,1.70829284191,6.31736326218 -2.48776555061,1.7122989893,6.33414793015 -2.47079133987,1.71431291103,6.34972000122 -2.44981718063,1.71332716942,6.35231161118 -2.43284249306,1.71534073353,6.3668923378 -2.41686749458,1.71835422516,6.38447141647 -2.39789319038,1.71836829185,6.39405202866 -2.38391852379,1.72438156605,6.41862201691 -2.37793040276,1.72738802433,6.43340969086 -2.35395693779,1.72340261936,6.42700862885 -2.33598303795,1.72541677952,6.44157600403 -2.32000780106,1.72843015194,6.45916128159 -2.29703474045,1.72644507885,6.45774364471 -2.28705906868,1.73545753956,6.49531126022 -2.29106783867,1.74646186829,6.53810787201 -2.27409338951,1.74947559834,6.55468845367 -2.25411987305,1.74948990345,6.56326580048 -2.24514293671,1.75950193405,6.60384559631 -2.22616958618,1.76151621342,6.6164188385 -2.20519566536,1.7605304718,6.62100553513 -2.19022035599,1.76554358006,6.64359283447 -2.17823386192,1.76355099678,6.6413860321 -2.15226197243,1.75956654549,6.63196468353 -2.13228869438,1.76058089733,6.64153909683 -2.11831307411,1.76559376717,6.66812515259 -2.08434319496,1.75361073017,6.63171052933 -2.05837154388,1.74962615967,6.62128829956 -2.03439903259,1.74664127827,6.6168680191 -2.02341246605,1.7456485033,6.61765813828 -2.0014398098,1.74466335773,6.62023305893 -1.9804662466,1.74367749691,6.62382125854 -1.95549428463,1.74069285393,6.61639499664 -1.93951940536,1.74470627308,6.63698196411 -1.9125483036,1.73872196674,6.62255477905 -1.89257466793,1.73973619938,6.63013839722 -1.8815882206,1.73874342442,6.63092708588 -1.86061429977,1.73775744438,6.63252401352 -1.83664214611,1.73477244377,6.62710046768 -1.81666839123,1.7357865572,6.6336889267 -1.79469585419,1.73480117321,6.6352648735 -1.77372300625,1.73481571674,6.64083957672 -1.76173639297,1.73182308674,6.63563871384 -1.74176251888,1.73283708096,6.64222717285 -1.72078990936,1.73285162449,6.64780139923 -1.70181679726,1.73586595058,6.6623711586 -1.67684412003,1.72988069057,6.64796543121 -1.65587091446,1.72989499569,6.65154933929 -1.63789772987,1.73390924931,6.67111539841 -1.62491166592,1.73091673851,6.66191101074 -1.60393869877,1.73093116283,6.66649055481 -1.58396542072,1.73194539547,6.6750702858 -1.56199204922,1.72995948792,6.67166614532 -1.54001951218,1.72897422314,6.67224407196 -1.52104628086,1.73098826408,6.68681716919 -1.5100594759,1.72999536991,6.68461704254 -1.48708677292,1.72701001167,6.67820453644 -1.46511459351,1.72702467442,6.67977666855 -1.44114232063,1.72203958035,6.66935968399 -1.42316854,1.72605323792,6.68694210052 -1.40119600296,1.72506773472,6.68652153015 -1.38022279739,1.72508192062,6.6891078949 -1.36723685265,1.72108960152,6.67790222168 -1.34626364708,1.72010362148,6.67949104309 -1.32629048824,1.72211790085,6.68906927109 -1.30331802368,1.71913254261,6.6816534996 -1.28434443474,1.72114622593,6.69424009323 -1.26137280464,1.71916127205,6.6908082962 -1.23839950562,1.71517539024,6.6784081459 -1.22941303253,1.71818244457,6.6901922226 -1.20744073391,1.71719717979,6.68976783752 -1.18546819687,1.71521151066,6.6873497963 -1.16449511051,1.71522557735,6.68893718719 -1.141523242,1.71224045753,6.68251180649 -1.12154972553,1.71325433254,6.68910121918 -1.10157680511,1.7152684927,6.69967889786 -1.08659172058,1.7072763443,6.67347049713 -1.069617033,1.71328961849,6.69706535339 -1.04964387417,1.71530354023,6.70564985275 -1.02667152882,1.71131813526,6.69523382187 -1.00369989872,1.70833301544,6.68880414963 -0.98572576046,1.71334636211,6.70839691162 -0.969740569592,1.70235419273,6.66919612885 -0.950767934322,1.70736837387,6.69076347351 -0.929794490337,1.70638227463,6.68835926056 -0.909822225571,1.70939671993,6.70392656326 -0.888849139214,1.70941066742,6.70451450348 -0.866876602173,1.70742499828,6.69909858704 -0.844903945923,1.70443928242,6.69168615341 -0.834916889668,1.70444595814,6.69248819351 -0.812945187092,1.70446074009,6.69305515289 -0.79397124052,1.7074739933,6.70665073395 -0.771998882294,1.70548844337,6.70123195648 -0.751026451588,1.70650267601,6.70680761337 -0.729053795338,1.70351684093,6.69739627838 -0.718068003654,1.70352423191,6.69817876816 -0.698094189167,1.70353770256,6.70177841187 -0.675122261047,1.69855225086,6.68635654449 -0.654149889946,1.69956660271,6.69193220139 -0.633176445961,1.69758021832,6.68553066254 -0.612204432487,1.6995947361,6.69509983063 -0.592230975628,1.70160830021,6.7026925087 -0.581244587898,1.69961535931,6.69548845291 -0.560271680355,1.69862926006,6.6950750351 -0.538299441338,1.69664359093,6.68665504456 -0.517327368259,1.69865787029,6.69522714615 -0.496353805065,1.69567143917,6.6848282814 -0.475381433964,1.69668567181,6.69040584564 -0.454408437014,1.69569945335,6.68699550629 -0.443422496319,1.69470667839,6.68378257751 -0.423449128866,1.6967202425,6.69437360764 -0.400477826595,1.69173502922,6.67594146729 -0.380504012108,1.69274830818,6.67854261398 -0.359531342983,1.69276225567,6.67912626266 -0.338559567928,1.6967767477,6.69769191742 -0.317586481571,1.69479048252,6.69028425217 -0.306600481272,1.69279754162,6.68307352066 -0.285627990961,1.69381153584,6.6876540184 -0.264654874802,1.69182527065,6.67824602127 -0.243682324886,1.69183921814,6.68082857132 -0.222709655762,1.69185316563,6.68041276932 -0.202736124396,1.69586646557,6.69500827789 -0.191750079393,1.69287359715,6.68279743195 -0.170777529478,1.69388759136,6.68737983704 -0.14980468154,1.69190132618,6.67996788025 -0.128832042217,1.69191515446,6.68155145645 -0.107859358191,1.69192898273,6.67913675308 -0.0868867635727,1.69294285774,6.68372011185 -0.0659141540527,1.69395673275,6.68930387497 -0.05492849648,1.69496393204,6.69308567047 -0.0339557155967,1.6909776926,6.67667293549 -0.0129830949008,1.69499158859,6.69025659561 --0.00798927713186,1.6810053587,6.42983531952 --0.0289610847831,1.67801952362,6.42040348053 --0.0489342026412,1.67703318596,6.41399097443 --0.0689075812697,1.68304646015,6.43458414078 --0.0888804420829,1.67606008053,6.4091668129 --0.10885373503,1.67807340622,6.41775846481 --0.118840284646,1.67808020115,6.41555213928 --0.13881342113,1.6780936718,6.41414022446 --0.15978513658,1.67710781097,6.40970659256 --0.179758250713,1.67612123489,6.40729379654 --0.199731558561,1.67813456059,6.41188573837 --0.219704553485,1.67714810371,6.40647125244 --0.229690909386,1.67515480518,6.40026187897 --0.249664187431,1.67616820335,6.40285253525 --0.269637107849,1.67518162727,6.39643621445 --0.289610087872,1.6741951704,6.39302253723 --0.30958339572,1.67520844936,6.39561414719 --0.330555289984,1.67622244358,6.39618349075 --0.350528419018,1.67623579502,6.39477157593 --0.359515935183,1.67424201965,6.38757896423 --0.380488455296,1.6772557497,6.39816093445 --0.400461524725,1.67726910114,6.39574813843 --0.420433789492,1.6732827425,6.38131904602 --0.440406680107,1.67329609394,6.3769030571 --0.459380686283,1.67130899429,6.3695025444 --0.480353295803,1.67532253265,6.37908601761 --0.490339994431,1.67532908916,6.3798828125 --0.510312616825,1.67334258556,6.37246131897 --0.530286192894,1.67535567284,6.37605810165 --0.550259172916,1.67536902428,6.37264299393 --0.571232140064,1.6783823967,6.38323354721 --0.592204272747,1.6793961525,6.38480806351 --0.613176882267,1.68240964413,6.39039134979 --0.623163461685,1.68241620064,6.38918542862 --0.644136488438,1.68542945385,6.39877843857 --0.664109885693,1.68544256687,6.39736938477 --0.685082137585,1.68645620346,6.39894771576 --0.705055594444,1.687469244,6.39854192734 --0.726028621197,1.69048249722,6.4051322937 --0.735015273094,1.68648898602,6.39292192459 --0.755988299847,1.68950223923,6.39951324463 --0.77896052599,1.69651579857,6.42110157013 --0.797933757305,1.69352889061,6.40668392181 --0.818906247616,1.69454240799,6.4082660675 --0.839878737926,1.69555580616,6.40884590149 --0.858852744102,1.69456851482,6.40144491196 --0.869839191437,1.69657504559,6.40824222565 --0.893811047077,1.70458889008,6.43182659149 --0.908785641193,1.69360113144,6.39141321182 --0.931757569313,1.69861483574,6.40599489212 --0.951730847359,1.69862771034,6.4025850296 --0.973702967167,1.70164132118,6.40816307068 --0.996676027775,1.7086545229,6.42776536942 --1.00566244125,1.70566105843,6.41655158997 --1.02163636684,1.69767355919,6.38413143158 --1.04360949993,1.70168662071,6.39573001862 --1.06558227539,1.70469987392,6.40331840515 --1.08555531502,1.70471286774,6.39790344238 --1.10552799702,1.70372605324,6.39048194885 --1.12251281738,1.71573352814,6.43028211594 --1.15846085548,1.7087584734,6.39946460724 --1.17943322659,1.70977187157,6.39704179764 --1.20040643215,1.7107847929,6.39863395691 --1.22237861156,1.71279811859,6.40221452713 --1.24335169792,1.71481108665,6.40280485153 --1.25133931637,1.71181702614,6.39160490036 --1.27331161499,1.71383035183,6.39518737793 --1.29628384113,1.71784377098,6.40377092361 --1.31325852871,1.71385586262,6.38636922836 --1.33723008633,1.71886956692,6.3979473114 --1.35420465469,1.71588158607,6.38054418564 --1.3761767149,1.71689486504,6.3811173439 --1.38716351986,1.7189013958,6.3849196434 --1.40813672543,1.71991407871,6.3855137825 --1.43210923672,1.72592735291,6.39910650253 --1.44808363914,1.71993935108,6.37569475174 --1.47005581856,1.72195255756,6.37627077103 --1.49802672863,1.73196661472,6.40485811234 --1.5120023489,1.72497808933,6.37545537949 --1.52098941803,1.72398424149,6.36925315857 --1.54396164417,1.72699737549,6.37483549118 --1.56593394279,1.72801053524,6.37541532516 --1.58890736103,1.73302328587,6.38501930237 --1.60887980461,1.73203623295,6.37559127808 --1.62985360622,1.73304867744,6.3761920929 --1.64383900166,1.73805570602,6.38798284531 --1.66381216049,1.73706829548,6.38056516647 --1.68278646469,1.73708033562,6.37316656113 --1.70575869083,1.73909366131,6.37674713135 --1.72773170471,1.74110639095,6.37833833694 --1.74870502949,1.74311900139,6.37592840195 --1.76767885685,1.74113118649,6.36652040482 --1.77966463566,1.74313783646,6.36930847168 --1.80263733864,1.74615073204,6.37389850616 --1.82361078262,1.74716329575,6.37149095535 --1.84358406067,1.74717581272,6.36407518387 --1.86255836487,1.74618780613,6.3556728363 --1.88653063774,1.75020074844,6.36225938797 --1.90650427341,1.75021314621,6.35584974289 --1.91649055481,1.75021958351,6.35063314438 --1.94046294689,1.7532324791,6.35722255707 --1.96543550491,1.75824534893,6.36781835556 --1.98640823364,1.75925815105,6.36239767075 --2.00238370895,1.75526940823,6.34500074387 --2.02635622025,1.75928235054,6.35058879852 --2.03834223747,1.76128876209,6.35338354111 --2.05531644821,1.75830078125,6.33496046066 --2.0762898922,1.75931310654,6.33155250549 --2.10026264191,1.7623257637,6.33815097809 --2.11723709106,1.76033747196,6.32173776627 --2.14420938492,1.76635062695,6.33633327484 --2.16918087006,1.77036380768,6.34191083908 --2.17516922951,1.76736903191,6.32771253586 --2.19514298439,1.76738119125,6.32030105591 --2.21811532974,1.76939404011,6.31987953186 --2.23708963394,1.7684057951,6.31047439575 --2.26306247711,1.77441847324,6.32207775116 --2.28003644943,1.77143025398,6.30465650558 --2.29901027679,1.7704423666,6.29323816299 --2.31099700928,1.77244842052,6.29704618454 --2.33197069168,1.77346050739,6.29163169861 --2.35394382477,1.77447295189,6.28921937943 --2.378916502,1.7794854641,6.295814991 --2.4008898735,1.78049778938,6.293405056 --2.4248623848,1.78451025486,6.29599428177 --2.43384981155,1.78351593018,6.28979110718 --2.45482301712,1.78452813625,6.28337287903 --2.47379755974,1.78353977203,6.27396965027 --2.50076937675,1.78855264187,6.28355836868 --2.51874446869,1.78756415844,6.27115249634 --2.54271745682,1.7915763855,6.27374696732 --2.56369066238,1.79158842564,6.26733112335 --2.56667923927,1.7865935564,6.24511861801 --2.59265208244,1.7916059494,6.25271606445 --2.61562514305,1.79361832142,6.25130224228 --2.63460016251,1.79362952709,6.24290847778 --2.65957307816,1.79664194584,6.24649810791 --2.677546978,1.79565358162,6.23207759857 --2.6975209713,1.79566526413,6.2236661911 --2.71350693703,1.80067181587,6.23446989059 --2.73648023605,1.80268383026,6.23306131363 --2.75245523453,1.79969501495,6.21464443207 --2.7804274559,1.80570757389,6.22524261475 --2.80040121078,1.80571937561,6.21582603455 --2.82037591934,1.80673062801,6.20842552185 --2.83336234093,1.80873680115,6.21122503281 --2.8553352356,1.80974888802,6.20479869843 --2.87630987167,1.81076037884,6.19939756393 --2.90028238297,1.81377267838,6.19797801971 --2.92025709152,1.81378388405,6.1905798912 --2.9402320385,1.81479501724,6.1831817627 --2.95920658112,1.81380653381,6.17176866531 --2.97019290924,1.8148124218,6.16855669022 --2.99116706848,1.81582391262,6.162150383 --3.01613998413,1.81883609295,6.16273498535 --3.03411531448,1.8188470602,6.15033102036 --3.05508923531,1.8188586235,6.14291763306 --3.07506370544,1.8198697567,6.13451385498 --3.10303616524,1.8248821497,6.141102314 --3.11302304268,1.82488787174,6.1358923912 --3.1359975338,1.82789921761,6.13449907303 --3.15197277069,1.8259100914,6.11708641052 --3.18194484711,1.83192253113,6.12768173218 --3.19892001152,1.82993328571,6.11227035522 --3.21989440918,1.83094465733,6.1048617363 --3.23188114166,1.83295047283,6.10365390778 --3.25585436821,1.8349622488,6.10124063492 --3.27582883835,1.835973382,6.09183263779 --3.29280519485,1.83498370647,6.07843828201 --3.31677865982,1.83699548244,6.0760269165 --3.33575344086,1.83700633049,6.06461811066 --3.36172676086,1.84101808071,6.06621217728 --3.37571334839,1.84402394295,6.06901168823 --3.39168834686,1.84203481674,6.05058908463 --3.41966152191,1.84704649448,6.05619049072 --3.44163632393,1.8490575552,6.05078983307 --3.46061038971,1.84806859493,6.03736495972 --3.4805855751,1.84907948971,6.02796077728 --3.50855827332,1.85409140587,6.0315489769 --3.50954771042,1.84909582138,6.01033830643 --3.53252267838,1.85110652447,6.00795221329 --3.55049753189,1.8501175642,5.99252462387 --3.57147192955,1.85112845898,5.98411512375 --3.59744620323,1.85613965988,5.98572206497 --3.61942076683,1.85715055466,5.9793176651 --3.62440919876,1.8551555872,5.96510457993 --3.65238213539,1.86016726494,5.96769285202 --3.66835832596,1.85817730427,5.95128774643 --3.69233250618,1.86118841171,5.94788312912 --3.71730613708,1.86419975758,5.94547367096 --3.73628211021,1.86420989037,5.93508052826 --3.75125837326,1.86222016811,5.91566133499 --3.7702434063,1.86722660065,5.9244556427 --3.7942173481,1.87023758888,5.92004537582 --3.80119681358,1.86424636841,5.89065074921 --3.82916975021,1.86925780773,5.89223909378 --3.85414385796,1.87226879597,5.88983631134 --3.86612057686,1.86827874184,5.86541175842 --3.8910946846,1.87128949165,5.86301040649 --3.90508198738,1.87429499626,5.86481714249 --3.92405748367,1.87430524826,5.85240697861 --3.94603204727,1.87631607056,5.84399271011 --3.97200608253,1.88032698631,5.84259033203 --3.98598313332,1.87733662128,5.82318496704 --4.00695800781,1.87834727764,5.81276655197 --4.02294492722,1.88235270977,5.81757831573 --4.04092073441,1.88236284256,5.80316448212 --4.06489515305,1.88437354565,5.79775524139 --4.087870121,1.88738405704,5.79135131836 --4.0988483429,1.88339316845,5.7679476738 --4.13082075119,1.89040470123,5.77353811264 --4.14479827881,1.88841414452,5.75413179398 --4.15778493881,1.88941955566,5.7519197464 --4.17976045609,1.89142978191,5.74452352524 --4.20373535156,1.8944401741,5.73911952972 --4.21971225739,1.89344966412,5.72271585464 --4.24368667603,1.89646029472,5.7163028717 --4.26566171646,1.89747059345,5.70688819885 --4.28463840485,1.89848017693,5.69549512863 --4.29862499237,1.90048575401,5.69428300858 --4.32060146332,1.90249550343,5.68689155579 --4.33857727051,1.90250527859,5.6724820137 --4.36055278778,1.90451538563,5.66307020187 --4.38252782822,1.90552556515,5.65365886688 --4.41450071335,1.91253662109,5.65724992752 --4.42648887634,1.91454148293,5.65505886078 --4.44246578217,1.91255092621,5.63764667511 --4.46144247055,1.91356050968,5.62524700165 --4.48841714859,1.91757071018,5.62284755707 --4.50439357758,1.9165803194,5.60442447662 --4.51237297058,1.91258859634,5.57802248001 --4.52435112,1.90959751606,5.55560827255 --4.5303401947,1.90860188007,5.5454120636 --4.54331827164,1.90661084652,5.52500486374 --4.55729627609,1.90461981297,5.50559473038 --4.56927347183,1.90262877941,5.48317718506 --4.5922498703,1.90463840961,5.47578001022 --4.61122655869,1.90564787388,5.46236896515 --4.63120317459,1.90665733814,5.4509677887 --4.63619232178,1.90466153622,5.43876075745 --4.65816831589,1.90767109394,5.42935562134 --4.67414569855,1.90668022633,5.41295194626 --4.68812322617,1.90468895435,5.39353990555 --4.71110010147,1.90769839287,5.38614654541 --4.71807956696,1.90370666981,5.35873365402 --4.74605369568,1.9077167511,5.35532140732 --4.74404525757,1.90372025967,5.33612251282 --4.76602172852,1.90572965145,5.32672071457 --4.78399896622,1.90573871136,5.31231355667 --4.80297517776,1.90674805641,5.29789304733 --4.82195281982,1.90775692463,5.28549671173 --4.84192943573,1.90876615047,5.27308750153 --4.850918293,1.90977036953,5.26689624786 --4.87289476395,1.91177976131,5.25648641586 --4.88687324524,1.91078817844,5.23808431625 --4.90884971619,1.91279745102,5.22767496109 --4.91782855988,1.90980553627,5.20326471329 --4.93880558014,1.91081476212,5.19185686111 --4.95878314972,1.91282343864,5.18046283722 --4.96477222443,1.91182780266,5.16925001144 --4.98674869537,1.91383683681,5.1588435173 --5.00872516632,1.91584587097,5.14843797684 --5.02870225906,1.91785466671,5.136033535 --5.04568004608,1.9178634882,5.119617939 --5.07065677643,1.9218724966,5.11322689056 --5.08463525772,1.91988098621,5.09381246567 --5.10262203217,1.92388594151,5.09561109543 --5.11060237885,1.92089354992,5.07120943069 --5.12957954407,1.92190229893,5.05679512024 --5.14855718613,1.92291080952,5.04339408875 --5.16853523254,1.92491936684,5.03099393845 --5.17851495743,1.92292702198,5.00859069824 --5.2034907341,1.92593622208,5.00018072128 --5.21347951889,1.92694044113,4.99398136139 --5.22046041489,1.92294788361,4.9685754776 --5.24543714523,1.92695665359,4.96118021011 --5.26341438293,1.92696535587,4.9447555542 --5.27039575577,1.92397248745,4.92036104202 --5.29437255859,1.92698132992,4.9109544754 --5.30536031723,1.92898571491,4.90474414825 --5.31934022903,1.927993536,4.88634204865 --5.3433175087,1.93100190163,4.87795114517 --5.35829544067,1.93101024628,4.85852432251 --5.37527418137,1.93101811409,4.84312677383 --5.38025569916,1.92702519894,4.81672620773 --5.40623235703,1.93103396893,4.80831384659 --5.41822052002,1.93303823471,4.80310726166 --5.43020057678,1.93204569817,4.78371572495 --5.4381814003,1.92905306816,4.75930452347 --5.42816543579,1.91905915737,4.71888780594 --5.47513771057,1.93106913567,4.72948884964 --5.48811769485,1.93107664585,4.71008491516 --5.49309921265,1.9270837307,4.68367862701 --5.49808931351,1.92608737946,4.6724729538 --5.50906896591,1.92409479618,4.65106344223 --5.53104734421,1.92710292339,4.63966321945 --5.50303602219,1.91110765934,4.58524847031 --5.36604595184,1.85510575771,4.43779468536 --5.3170375824,1.8321095705,4.36636257172 --5.32801818848,1.83111679554,4.34696054459 --5.32900953293,1.82912015915,4.33376169205 --5.34398841858,1.82912790775,4.31735515594 --5.35696840286,1.82913541794,4.29894256592 --5.38394546509,1.83414375782,4.29254150391 --5.38892698288,1.83015072346,4.2681350708 --5.40090751648,1.83015799522,4.24973487854 --5.40588903427,1.82716488838,4.22532653809 --5.40687942505,1.82416844368,4.21111059189 --5.42285919189,1.82517576218,4.1967215538 --5.42884016037,1.82318294048,4.17229890823 --5.44382095337,1.82319009304,4.1569070816 --5.45880031586,1.82419741154,4.14049959183 --5.45878267288,1.81920409203,4.1120839119 --5.46977233887,1.82120788097,4.1068854332 --5.48175191879,1.82021534443,4.0874671936 --5.48673391342,1.81722199917,4.06406736374 --5.51571130753,1.82323002815,4.05866909027 --5.47970056534,1.80523467064,4.003241539 --5.4796833992,1.80124115944,3.9758310318 --5.49266386032,1.80124819279,3.9584274292 --5.52065038681,1.80925273895,3.96623969078 --5.54162836075,1.8112603426,3.9538269043 --5.55860853195,1.81326746941,3.93942737579 --5.56558990479,1.81127429008,3.9170153141 --5.57957077026,1.81128120422,3.90061903 --5.58555221558,1.8092880249,3.87720060349 --5.59653377533,1.80929470062,3.8588051796 --5.60152435303,1.80829811096,3.84859728813 --5.61550426483,1.80930519104,3.83118510246 --5.62948513031,1.80931198597,3.81478881836 --5.62646818161,1.80431830883,3.78536963463 --5.6494474411,1.80832540989,3.77497148514 --5.64743089676,1.80333173275,3.74655485153 --5.66141176224,1.80333840847,3.73015809059 --5.66540241241,1.80334162712,3.71995925903 --5.67138385773,1.80134832859,3.69653511047 --5.69936227798,1.80635559559,3.68913578987 --5.71234321594,1.80736231804,3.67173457146 --5.71132707596,1.80236828327,3.64533376694 --5.74230527878,1.80937552452,3.63993954659 --5.74928712845,1.80738210678,3.61752033234 --5.77027511597,1.8123857975,3.61832523346 --5.77525806427,1.81039202213,3.59592628479 --5.78823852539,1.81039869785,3.5775103569 --5.79022216797,1.80740463734,3.55310773849 --5.81020212173,1.81041145325,3.53970265388 --5.82318353653,1.81041777134,3.52230334282 --5.83816432953,1.81142449379,3.50488471985 --5.84815454483,1.81342756748,3.49869155884 --5.85513687134,1.81143379211,3.47728657722 --5.86611843109,1.81144011021,3.45787501335 --5.88609886169,1.8144466877,3.44447445869 --5.90207958221,1.81645309925,3.42806434631 --5.91606140137,1.81745922565,3.41167378426 --5.91505289078,1.81546235085,3.39745688438 --5.93003463745,1.81646847725,3.381057024 --5.9370174408,1.81547451019,3.3596508503 --5.94500017166,1.81448042393,3.33925151825 --5.9619808197,1.81648659706,3.32385063171 --5.97196292877,1.81549286842,3.30343270302 --5.99094390869,1.81849908829,3.28903126717 --5.99393558502,1.81750178337,3.27884054184 --5.99791908264,1.81550765038,3.25542759895 --6.00590133667,1.81451368332,3.23401093483 --6.01288414001,1.81351947784,3.21260261536 --6.01186847687,1.80952513218,3.18719863892 --6.02385091782,1.81053102016,3.16879463196 --6.03383302689,1.81053686142,3.14939165115 --6.0378241539,1.80953991413,3.13817429543 --6.05980539322,1.81354570389,3.12578344345 --6.0767865181,1.81555175781,3.10937094688 --6.08876943588,1.81655740738,3.09096884727 --6.09675216675,1.8155630827,3.07056736946 --6.11373472214,1.81756877899,3.05517339706 --6.12671661377,1.81857454777,3.03676366806 --6.13570737839,1.82057750225,3.02855491638 --6.13969087601,1.81858301163,3.00615358353 --6.15167379379,1.81858849525,2.98775315285 --6.17165565491,1.8225941658,2.97335410118 --6.1676402092,1.8175996542,2.94593334198 --6.18562221527,1.82060515881,2.93053507805 --6.19060564041,1.81861066818,2.90812397003 --6.20259666443,1.82161331177,2.90192675591 --6.22557783127,1.82561898232,2.88852477074 --6.23456096649,1.82562434673,2.86811637878 --6.25654268265,1.82962965965,2.85472488403 --6.26952552795,1.8306350708,2.83632040024 --6.28550815582,1.83264040947,2.81891012192 --6.29049921036,1.83264315128,2.80870294571 --6.32547998428,1.8406484127,2.80131864548 --6.32446479797,1.83765351772,2.77590417862 --6.34744691849,1.84165871143,2.76251268387 --6.35543012619,1.84166395664,2.74109816551 --6.37641239166,1.84466910362,2.72569012642 --6.39539480209,1.84867417812,2.71029758453 --6.4033870697,1.84967648983,2.70210456848 --6.42336893082,1.85268175602,2.68569016457 --6.43335294724,1.85268652439,2.66629767418 --6.44433641434,1.85369169712,2.64588093758 --6.45332050323,1.8536965847,2.62547874451 --6.46530389786,1.8547013998,2.60607266426 --6.47928762436,1.85670638084,2.58767056465 --6.49027919769,1.85870862007,2.58047628403 --6.49726343155,1.85771346092,2.55907154083 --6.52024555206,1.86271822453,2.54366135597 --6.52523040771,1.86172306538,2.52125382423 --6.53321504593,1.86172771454,2.50085997581 --6.55719804764,1.86573219299,2.48646402359 --6.55118370056,1.86173713207,2.45904254913 --6.56317520142,1.8637393713,2.45184540749 --6.58215808868,1.86674404144,2.4344329834 --6.59514284134,1.86874842644,2.41604304314 --6.60512685776,1.86975300312,2.39563822746 --6.61811113358,1.87075746059,2.37623214722 --6.63509511948,1.87376177311,2.35883641243 --6.64107990265,1.87276625633,2.33642339706 --6.64907169342,1.87476861477,2.32722043991 --6.66705608368,1.87777268887,2.30982065201 --6.66604185104,1.87477731705,2.28541564941 --6.68102550507,1.87678170204,2.26600074768 --6.68301153183,1.87578606606,2.24259400368 --6.69999599457,1.87779009342,2.22520327568 --6.71997976303,1.88179433346,2.2077960968 --6.71397304535,1.87879657745,2.19358992577 --6.7219581604,1.87880086899,2.1721830368 --6.73794317245,1.88180482388,2.15378332138 --6.73492908478,1.87880933285,2.12836885452 --6.72691631317,1.87481379509,2.10196328163 --6.75390005112,1.8798173666,2.08757400513 --6.76288509369,1.88082146645,2.06616234779 --6.76487827301,1.87982356548,2.05496120453 --6.77886343002,1.88282740116,2.03555774689 --6.79084825516,1.8838313818,2.0151488781 --6.7868347168,1.88083577156,1.98973631859 --6.80881929398,1.88483929634,1.97334575653 --6.82780361176,1.88884282112,1.95493733883 --6.82179117203,1.88484716415,1.92953395844 --6.8377828598,1.88884866238,1.92233288288 --6.8347697258,1.88585281372,1.89793074131 --6.83475589752,1.8838570118,1.87351322174 --6.84774160385,1.88586044312,1.85411942005 --6.85472726822,1.88586437702,1.8317027092 --6.8587141037,1.88586819172,1.80930006504 --6.883705616,1.89186930656,1.80511391163 --6.89169120789,1.89287316799,1.78269374371 --6.8906788826,1.89087688923,1.75929737091 --6.90066432953,1.89188051224,1.73788571358 --6.91365003586,1.89388394356,1.71747899055 --6.90863800049,1.89088785648,1.69308161736 --6.92362356186,1.8928912878,1.67266690731 --6.94161558151,1.89789247513,1.66546726227 --6.93060350418,1.89289677143,1.6390594244 --6.94858980179,1.89689958096,1.6206690073 --6.95057630539,1.89590322971,1.59725809097 --6.95456361771,1.89490687847,1.57485616207 --6.95655012131,1.89391040802,1.5514446497 --6.95253753662,1.89091432095,1.52703881264 --6.93953227997,1.88691687584,1.51182544231 --6.96751785278,1.89291918278,1.49543476105 --6.97250461578,1.89292252064,1.47302830219 --6.98349142075,1.89492571354,1.45161700249 --6.99047803879,1.89592885971,1.42920339108 --6.99346542358,1.89493227005,1.40680480003 --7.00045251846,1.89593553543,1.38439142704 --7.00444602966,1.89593696594,1.37420094013 --7.0094332695,1.89594018459,1.35179507732 --7.02541971207,1.89894282818,1.33138692379 --7.0304069519,1.89894604683,1.30898177624 --7.02739524841,1.89694964886,1.28456783295 --7.03738212585,1.89895248413,1.26316356659 --7.03237009048,1.89595615864,1.23875522614 --7.02736473083,1.89395809174,1.22655832767 --7.0413517952,1.89696061611,1.20615959167 --7.05133867264,1.89796352386,1.18373906612 --7.06432628632,1.90096580982,1.16334533691 --7.07431411743,1.90296852589,1.14194369316 --7.08630132675,1.90497100353,1.12053716183 --7.07929563522,1.90197312832,1.10732710361 --7.09428310394,1.90497529507,1.08693051338 --7.10527038574,1.9069776535,1.06552839279 --7.10025930405,1.90498125553,1.04111671448 --7.11524677277,1.90798330307,1.02072250843 --7.1212348938,1.9089858532,0.998317301273 --7.13422250748,1.91098809242,0.976912677288 --7.13421106339,1.90999114513,0.953505396843 --7.13520479202,1.90999269485,0.941290259361 --7.14319324493,1.91099488735,0.919899046421 --7.15218162537,1.912997365,0.897488176823 --7.163169384,1.91499948502,0.876091301441 --7.17015790939,1.91600179672,0.853686332703 --7.18114614487,1.91800391674,0.831273257732 --7.18813467026,1.91900622845,0.808869481087 --7.18912887573,1.91900753975,0.797672748566 --7.20011711121,1.92100954056,0.775261521339 --7.20910549164,1.92301166058,0.752854943275 --7.2000951767,1.92001509666,0.728447198868 --7.21508359909,1.92301666737,0.707047939301 --7.21907281876,1.92401885986,0.684651494026 --7.21306705475,1.92102086544,0.671431958675 --7.2210559845,1.92302286625,0.649028599262 --7.23304510117,1.92602443695,0.627637147903 --7.23403406143,1.92502689362,0.60422873497 --7.2350230217,1.92502939701,0.580819785595 --7.24301195145,1.92603135109,0.558418631554 --7.25100135803,1.92803323269,0.535000145435 --7.25799608231,1.93003368378,0.524813592434 --7.26998519897,1.93203508854,0.502409100533 --7.2719745636,1.93203735352,0.47900018096 --7.28696346283,1.93603849411,0.456593513489 --7.29695320129,1.93803989887,0.434194087982 --7.29694318771,1.93804228306,0.410788327456 --7.31793212891,1.94304263592,0.388379186392 --7.32992744446,1.94604253769,0.378191530704 --7.32391691208,1.94404542446,0.353775084019 --7.32190656662,1.94304776192,0.330372005701 --7.33889627457,1.94704830647,0.307970941067 --7.33288621902,1.94505119324,0.283553481102 --7.32887649536,1.94405376911,0.260151267052 --7.3238658905,1.94205641747,0.235731676221 --7.33286094666,1.94405663013,0.224532291293 --7.34885120392,1.94805693626,0.20213586092 --7.34484148026,1.94705939293,0.178733244538 --7.34183120728,1.94606184959,0.154312089086 --7.34482145309,1.94606351852,0.13090595603 --7.34981203079,1.94706487656,0.108516901731 --7.34280204773,1.94506764412,0.0840962007642 --7.35079717636,1.94706773758,0.072900429368 --7.35178756714,1.94706952572,0.0494952388108 --7.35677814484,1.94807088375,0.0260895937681 --7.35176801682,1.94707334042,0.0016673571663 --7.36375951767,1.95007383823,-0.0207203980535 --7.35074901581,1.94607722759,-0.0451430417597 --7.34573984146,1.94507956505,-0.0685490444303 --7.34773445129,1.9450802803,-0.0807603299618 --7.35172557831,1.94608151913,-0.104165233672 --7.34771585464,1.94508373737,-0.1275716573 --7.34070682526,1.94308626652,-0.150979399681 --7.34269809723,1.94408774376,-0.174384951591 --7.34868907928,1.94508862495,-0.197788357735 --7.34267950058,1.94409108162,-0.221196994185 --7.34667491913,1.94509136677,-0.233406841755 --7.34066534042,1.9430937767,-0.25681579113 --7.33865642548,1.94309556484,-0.280223280191 --7.34164810181,1.94409680367,-0.3036275208 --7.34563922882,1.94509768486,-0.32703062892 --7.35063028336,1.94609868526,-0.351450026035 --7.35062122345,1.94610011578,-0.374855428934 --7.35561752319,1.94810009003,-0.386045187712 --7.34160804749,1.94410347939,-0.409462928772 --7.35259962082,1.94710326195,-0.433875620365 --7.35559129715,1.94810426235,-0.457277655602 --7.3475818634,1.9461067915,-0.48069113493 --7.34957408905,1.94710767269,-0.50409412384 --7.3475689888,1.94710862637,-0.516307890415 --7.34256124496,1.94611060619,-0.538701474667 --7.34555244446,1.94711148739,-0.563120424747 --7.35254430771,1.94911170006,-0.586516022682 --7.35253620148,1.95011281967,-0.609920620918 --7.34952831268,1.94911444187,-0.633329153061 --7.35552024841,1.95111477375,-0.657742083073 --7.3625164032,1.95311427116,-0.669942080975 --7.37150907516,1.95611405373,-0.694348752499 --7.36750030518,1.95511555672,-0.717757940292 --7.36349248886,1.95511722565,-0.741167724133 --7.36848545074,1.95711731911,-0.764561831951 --7.37347745895,1.95911765099,-0.788972735405 --7.3754696846,1.96011817455,-0.813388347626 --7.37546634674,1.96011865139,-0.824580430984 --7.38245916367,1.96211838722,-0.848985671997 --7.37244987488,1.96012079716,-0.872406542301 --7.38244390488,1.9641200304,-0.89680492878 --7.39343643188,1.96711909771,-0.922216832638 --7.38542890549,1.96612107754,-0.944616496563 --7.38942193985,1.96712112427,-0.969024658203 --7.39141798019,1.96812105179,-0.981228590012 --7.39341068268,1.96912145615,-1.00564038754 --7.38440322876,1.96812343597,-1.0280431509 --7.38639593124,1.96912384033,-1.0524545908 --7.39238929749,1.97212338448,-1.0768558979 --7.40138339996,1.97512221336,-1.10226583481 --7.37937402725,1.96912658215,-1.1236846447 --7.39337205887,1.97412443161,-1.13687360287 --7.39236497879,1.97412502766,-1.16129052639 --7.39335775375,1.9751251936,-1.18570196629 --7.38835096359,1.97512638569,-1.20911252499 --7.38934469223,1.97612667084,-1.23250615597 --7.39533853531,1.97912585735,-1.25791966915 --7.38633060455,1.97712779045,-1.28032398224 --7.39032793045,1.97912716866,-1.2935359478 --7.38532066345,1.97812819481,-1.31694602966 --7.40431642532,1.98512494564,-1.34333491325 --7.39330863953,1.98212718964,-1.36574530602 --7.38430118561,1.98112893105,-1.38916778564 --7.37629413605,1.98013043404,-1.41157054901 --7.391289711,1.98512768745,-1.43898391724 --7.38428592682,1.98412907124,-1.44917798042 --7.38627958298,1.98512864113,-1.47459828854 --7.38927412033,1.98712813854,-1.49899768829 --7.38326740265,1.98712921143,-1.52241051197 --7.38726186752,1.98912835121,-1.54782235622 --7.38125562668,1.98812937737,-1.57021772861 --7.3652472496,1.98513233662,-1.59264969826 --7.37824583054,1.98912978172,-1.60684049129 --7.37023925781,1.9881310463,-1.6292437315 --7.36523246765,1.98813176155,-1.65366995335 --7.36922836304,1.99113070965,-1.67806231976 --7.37022256851,1.99213027954,-1.7034817934 --7.36921691895,1.99313008785,-1.72789180279 --7.36421346664,1.99313092232,-1.73909759521 --7.36220788956,1.99313092232,-1.76249396801 --7.35520172119,1.9931319952,-1.7859108448 --7.36519765854,1.99712944031,-1.81230866909 --7.36219215393,1.99812948704,-1.83672523499 --7.35718631744,1.99813008308,-1.86013293266 --7.36318206787,2.00112819672,-1.88654434681 --7.36418008804,2.0021276474,-1.89874136448 --7.35317277908,2.00012946129,-1.92115724087 --7.35216808319,2.00112891197,-1.94556379318 --7.35416316986,2.00412774086,-1.97097349167 --7.34615707397,2.00312876701,-1.9943934679 --7.34815359116,2.00512766838,-2.01878523827 --7.3561501503,2.0091252327,-2.04619860649 --7.34714603424,2.00712656975,-2.05640625954 --7.35614347458,2.01212358475,-2.0838136673 --7.36714076996,2.01612043381,-2.11120963097 --7.3471326828,2.01212382317,-2.13061857224 --7.34412813187,2.01312351227,-2.15604686737 --7.34912490845,2.01612138748,-2.18245244026 --7.34912109375,2.01812028885,-2.20684838295 --7.35611820221,2.02211737633,-2.23425865173 --7.35411548615,2.02211737633,-2.24646544456 --7.34210968018,2.02111911774,-2.2678706646 --7.35610866547,2.02711439133,-2.29727578163 --7.35210371017,2.02711415291,-2.32168865204 --7.33609724045,2.02511668205,-2.34209823608 --7.35509777069,2.03211092949,-2.37350535393 --7.3590965271,2.0341091156,-2.38669610023 --7.33808851242,2.03011274338,-2.40611553192 --7.34408664703,2.03410983086,-2.43352270126 --7.35508584976,2.03910565376,-2.46293401718 --7.35008144379,2.04010534286,-2.48633313179 --7.34907817841,2.04110383987,-2.51174211502 --7.36507844925,2.04809808731,-2.5431535244 --7.34507274628,2.04310250282,-2.54936027527 --7.35607242584,2.04909801483,-2.5787653923 --7.36707162857,2.0540933609,-2.60816812515 --7.3490653038,2.05109620094,-2.62858963013 --7.35606431961,2.05509281158,-2.65598082542 --7.35206031799,2.05609178543,-2.68140220642 --7.35705947876,2.06008839607,-2.70880246162 --7.36105918884,2.06208658218,-2.72300124168 --7.35505580902,2.06308603287,-2.7474167347 --7.35905408859,2.06708264351,-2.77482032776 --7.35705137253,2.06808114052,-2.80022621155 --7.35404872894,2.07007980347,-2.82563829422 --7.35304641724,2.07207798958,-2.85205292702 --7.35604524612,2.07507491112,-2.87945795059 --7.37004804611,2.08106970787,-2.89765405655 --7.38505029678,2.08806347847,-2.93006086349 --7.37304544449,2.08706402779,-2.95247673988 --7.37404441833,2.08906149864,-2.97887396812 --7.37104225159,2.09105968475,-3.00427985191 --7.37104082108,2.09405708313,-3.03169703484 --7.3710398674,2.09605455399,-3.05809760094 --7.37003898621,2.09705352783,-3.07130408287 --7.37904024124,2.10304832458,-3.1017074585 --7.39204311371,2.10904169083,-3.13411307335 --7.39904403687,2.11403679848,-3.16350984573 --7.39304161072,2.11503577232,-3.18892884254 --7.38603878021,2.11603474617,-3.21333909035 --7.36803340912,2.11303710938,-3.23376107216 --7.35802984238,2.11103868484,-3.24296402931 --7.34602594376,2.11103916168,-3.26639318466 --7.32101774216,2.10604357719,-3.28280425072 --7.2920088768,2.10004925728,-3.29822921753 --7.27100229263,2.09705233574,-3.31766247749 --7.24399328232,2.09105753899,-3.33307719231 --7.24099206924,2.09405517578,-3.35949349403 --7.2209854126,2.08906006813,-3.36369490623 --7.21598434448,2.09005832672,-3.38910961151 --7.19697809219,2.0880613327,-3.40853333473 --7.18797445297,2.08806085587,-3.43194651604 --7.18097257614,2.08905959129,-3.4563601017 --7.16396713257,2.0870616436,-3.47577095032 --7.15196323395,2.08606219292,-3.49819111824 --7.13795900345,2.08306503296,-3.50539970398 --7.12595510483,2.0830655098,-3.52782058716 --7.12095355988,2.08406376839,-3.55323457718 --7.10194730759,2.08206653595,-3.57164859772 --7.09694576263,2.08306455612,-3.59706187248 --7.07593917847,2.08006811142,-3.61447691917 --7.0769405365,2.08406400681,-3.64288926125 --7.05793380737,2.08006858826,-3.64811038971 --7.03692722321,2.07607197762,-3.66552758217 --7.02092266083,2.07507395744,-3.68595218658 --7.013920784,2.07607245445,-3.71036601067 --6.99791574478,2.07407426834,-3.72977614403 --6.97790956497,2.07207727432,-3.74820423126 --6.97590923309,2.07307624817,-3.76039934158 --6.96690702438,2.07307553291,-3.78381419182 --6.97291088104,2.07906961441,-3.81522679329 --6.96490859985,2.08006858826,-3.8386323452 --6.92789649963,2.07207751274,-3.84806728363 --6.92389583588,2.07407474518,-3.87448525429 --6.91189289093,2.07407522202,-3.89589476585 --6.89488697052,2.07007908821,-3.90110969543 --6.88188362122,2.06907987595,-3.92252802849 --6.86187744141,2.06708288193,-3.9399471283 --6.83986997604,2.06308674812,-3.95636892319 --6.82486581802,2.06208825111,-3.97679138184 --6.81786489487,2.06408643723,-4.0012049675 --6.79985952377,2.06208896637,-4.01962423325 --6.78485441208,2.05909228325,-4.02584218979 --6.77885389328,2.06109023094,-4.05024671555 --6.75984811783,2.05909323692,-4.06766223907 --6.74284362793,2.05709505081,-4.08708953857 --6.72583818436,2.05509734154,-4.10550355911 --6.71383523941,2.05509757996,-4.12691688538 --6.69282913208,2.05310082436,-4.1443529129 --6.68682765961,2.05310106277,-4.15455293655 --6.66982269287,2.05110311508,-4.17296886444 --6.65782022476,2.05110311508,-4.19438314438 --6.6438164711,2.05010414124,-4.21480131149 --6.62581110001,2.0491065979,-4.2332277298 --6.61180782318,2.04810714722,-4.25364637375 --6.60580778122,2.05010509491,-4.27906370163 --6.59680509567,2.04910635948,-4.28726291656 --6.58380222321,2.04910683632,-4.30868721008 --6.56279563904,2.04711031914,-4.32511472702 --6.54879236221,2.04611134529,-4.34452009201 --6.53278827667,2.04511260986,-4.36394500732 --6.51778459549,2.04511380196,-4.38336086273 --6.51178503036,2.04711151123,-4.40877580643 --6.49077653885,2.04211783409,-4.40999221802 --6.47277164459,2.04012012482,-4.4274096489 --6.45576715469,2.03912234306,-4.44583177567 --6.44176435471,2.03912305832,-4.46625375748 --6.42475938797,2.03812479973,-4.48467683792 --6.41976118088,2.04012203217,-4.5100812912 --6.39875411987,2.03812551498,-4.5255022049 --6.38574934006,2.03512835503,-4.53171634674 --6.368745327,2.03413057327,-4.55014133453 --6.35074043274,2.03313302994,-4.56756210327 --6.333735466,2.03213500977,-4.58598804474 --6.31973266602,2.03213596344,-4.6053981781 --6.29872608185,2.02913951874,-4.62082290649 --6.28472328186,2.02914023399,-4.64124774933 --6.2737197876,2.02714252472,-4.64744472504 --6.25371360779,2.0251455307,-4.66387605667 --6.24771499634,2.02814269066,-4.68928861618 --6.22870969772,2.02614593506,-4.7057094574 --6.20570230484,2.02315068245,-4.71913194656 --6.19169950485,2.02315115929,-4.73955774307 --6.18370056152,2.02514886856,-4.76397562027 --6.16569280624,2.02115440369,-4.76518011093 --6.14668750763,2.02015733719,-4.78160429001 --6.12668132782,2.01816082001,-4.79702663422 --6.10267305374,2.0141658783,-4.81046390533 --6.09067201614,2.01516580582,-4.83087062836 --6.07766962051,2.01516604424,-4.85128688812 --6.06566572189,2.01416873932,-4.85750007629 --6.04866123199,2.01317071915,-4.87491941452 --6.02465248108,2.00917625427,-4.88734769821 --6.00664806366,2.00817847252,-4.90477895737 --5.98664188385,2.00618219376,-4.91919326782 --5.97364044189,2.0071823597,-4.93961143494 --5.95163249969,2.00418686867,-4.95303440094 --5.94363117218,2.00418758392,-4.96224689484 --5.93263053894,2.00518679619,-4.98365592957 --5.90662097931,2.00119328499,-4.99408578873 --5.89361953735,2.00219345093,-5.01450443268 --5.86360692978,1.99620175362,-5.02194166183 --5.85060501099,1.99720215797,-5.04134750366 --5.83360099792,1.99620389938,-5.05978536606 --5.81859493256,1.99420821667,-5.06299972534 --5.80859565735,1.9952069521,-5.08541107178 --5.79659461975,1.99620652199,-5.10581827164 --5.77158546448,1.99321246147,-5.11725759506 --5.75658273697,1.99321365356,-5.13567399979 --5.73257398605,1.99021923542,-5.14710330963 --5.72157430649,1.992218256,-5.169526577 --5.70956993103,1.99022102356,-5.17473459244 --5.69056415558,1.98822438717,-5.18914651871 --5.67055845261,1.98722815514,-5.20357084274 --5.6505522728,1.98523175716,-5.21799564362 --5.63354873657,1.98523366451,-5.23542451859 --5.61654424667,1.98423600197,-5.25184106827 --5.59653806686,1.98223972321,-5.26626729965 --5.58853673935,1.98224031925,-5.27548265457 --5.57153320312,1.98224258423,-5.29189968109 --5.56053352356,1.98424124718,-5.31432104111 --5.537525177,1.98124659061,-5.32574748993 --5.52052164078,1.98024868965,-5.34216451645 --5.50451850891,1.98025023937,-5.359582901 --5.48451280594,1.97925400734,-5.37401294708 --5.46450233459,1.97426140308,-5.37223672867 --5.45550441742,1.97725915909,-5.39564561844 --5.43850040436,1.97726130486,-5.41206502914 --5.41649341583,1.97426605225,-5.42449569702 --5.39948940277,1.97426819801,-5.44091558456 --5.38348674774,1.97426974773,-5.45833539963 --5.36648321152,1.97427165508,-5.47576808929 --5.35547971725,1.97327399254,-5.48198509216 --5.33947658539,1.97327578068,-5.49839258194 --5.32347393036,1.97327721119,-5.51581287384 --5.30446863174,1.97228062153,-5.53023386002 --5.28045940399,1.96928656101,-5.5406703949 --5.26946115494,1.97128498554,-5.56308889389 --5.25646066666,1.97228491306,-5.58249521255 --5.24545717239,1.97128736973,-5.58871364594 --5.22545146942,1.97029089928,-5.60314941406 --5.21044969559,1.97129178047,-5.62156963348 --5.19244527817,1.97029435635,-5.63699150085 --5.16643428802,1.96630227566,-5.64340925217 --5.14642858505,1.96530580521,-5.65784740448 --5.13743257523,1.96830284595,-5.68226146698 --5.12442684174,1.96630680561,-5.68547105789 --5.09341144562,1.96131765842,-5.68791103363 --5.07040262222,1.95832359791,-5.69733047485 --5.06541013718,1.96331810951,-5.72573804855 --5.04440355301,1.96132266521,-5.73816728592 --5.0243973732,1.96032643318,-5.75159597397 --5.01039075851,1.95833110809,-5.75381040573 --5.00039434433,1.96132862568,-5.77722358704 --4.98839569092,1.96332716942,-5.7996506691 --4.96138381958,1.95933580399,-5.80508041382 --4.93837499619,1.9573417902,-5.81450414658 --4.91036176682,1.95235109329,-5.81893920898 --4.89335870743,1.95235335827,-5.83435297012 --4.87034988403,1.95035922527,-5.84479141235 --4.87235784531,1.95435333252,-5.86398696899 --4.84434509277,1.95036256313,-5.8684258461 --4.83735132217,1.95435786247,-5.895840168 --4.8093380928,1.95036745071,-5.89926862717 --4.78432750702,1.94737482071,-5.90670394897 --4.77833509445,1.9523692131,-5.93511343002 --4.76833248138,1.95137143135,-5.94132471085 --4.75433206558,1.95337128639,-5.9607424736 --4.72631883621,1.94838070869,-5.96518659592 --4.71231889725,1.95038056374,-5.98460435867 --4.69231319427,1.94938480854,-5.99702787399 --4.66329860687,1.94439554214,-5.99845600128 --4.64929819107,1.94639539719,-6.01787424088 --4.64330053329,1.94739413261,-6.03009653091 --4.62229299545,1.94639933109,-6.04051303864 --4.6052904129,1.94640111923,-6.0569396019 --4.57727718353,1.94241094589,-6.06038093567 --4.56427812576,1.94441020489,-6.08079433441 --4.54527378082,1.94441366196,-6.09421730042 --4.51926136017,1.94042217731,-6.09965419769 --4.5092587471,1.94042420387,-6.10586833954 --4.4872508049,1.93843007088,-6.1152920723 --4.48126029968,1.94442343712,-6.14571094513 --4.44723939896,1.9374383688,-6.14014959335 --4.43624353409,1.94043576717,-6.16356372833 --4.41123199463,1.93744397163,-6.16899108887 --4.39222764969,1.93744707108,-6.18342685699 --4.38222455978,1.93644952774,-6.18863105774 --4.36221885681,1.93545365334,-6.2010602951 --4.33720731735,1.93246197701,-6.2064909935 --4.32220745087,1.93446230888,-6.22491025925 --4.30220174789,1.93346655369,-6.23734045029 --4.28219652176,1.93347072601,-6.24977207184 --4.26219034195,1.93247544765,-6.26018238068 --4.2581949234,1.93447232246,-6.27540063858 --4.22917842865,1.93048417568,-6.2748336792 --4.21618127823,1.93248271942,-6.29625225067 --4.19317150116,1.93048965931,-6.30367803574 --4.17316627502,1.93049383163,-6.31611061096 --4.15115785599,1.92850005627,-6.32453250885 --4.13715028763,1.92650568485,-6.32474946976 --4.11914730072,1.92650806904,-6.34018230438 --4.10114431381,1.92751038074,-6.35561561584 --4.07813453674,1.92551767826,-6.36203527451 --4.05612611771,1.9235240221,-6.37046003342 --4.03912448883,1.92452561855,-6.38688802719 --4.00710344315,1.91854059696,-6.38133001328 --3.99210476875,1.920540452,-6.40075731277 --3.98410344124,1.92054140568,-6.40795373917 --3.96710205078,1.92154300213,-6.42438173294 --3.94809770584,1.9215464592,-6.43781137466 --3.92308568954,1.91955518723,-6.44224739075 --3.90307998657,1.91855978966,-6.45367383957 --3.88507723808,1.91956245899,-6.46809768677 --3.86506056786,1.91357398033,-6.45831918716 --3.85006141663,1.91657400131,-6.47673559189 --3.82504916191,1.91358304024,-6.48117542267 --3.80904912949,1.91458380222,-6.49859666824 --3.78804183006,1.91358947754,-6.50802183151 --3.7670352459,1.91359472275,-6.51845645905 --3.74402475357,1.9116024971,-6.52387714386 --3.73902916908,1.91359984875,-6.53809070587 --3.71802210808,1.91260540485,-6.54751634598 --3.69200825691,1.90961551666,-6.5499587059 --3.66899776459,1.90762329102,-6.5553817749 --3.64899230003,1.90762782097,-6.56681156158 --3.62598180771,1.90563571453,-6.57223558426 --3.60998249054,1.90763616562,-6.59066486359 --3.59797668457,1.90664041042,-6.59288072586 --3.57496595383,1.90464830399,-6.59830617905 --3.55596232414,1.90465176105,-6.61173915863 --3.53194999695,1.90166068077,-6.61516332626 --3.51494932175,1.90366232395,-6.6315908432 --3.49093770981,1.90167093277,-6.63602590561 --3.46993112564,1.90067636967,-6.64646577835 --3.4559211731,1.89868330956,-6.64367294312 --3.44292736053,1.90268027782,-6.66810369492 --3.4189145565,1.89968967438,-6.67052316666 --3.39390039444,1.8966999054,-6.67195224762 --3.37690043449,1.89870107174,-6.68938732147 --3.35789704323,1.89970445633,-6.70282030106 --3.34388637543,1.89671182632,-6.69902181625 --3.32488298416,1.89771521091,-6.71245574951 --3.30387544632,1.89672124386,-6.72088050842 --3.28186678886,1.89572823048,-6.72831344604 --3.26085972786,1.89473390579,-6.73774671555 --3.23885083199,1.8937407732,-6.74518108368 --3.21183252335,1.88975381851,-6.74160909653 --3.19982671738,1.88875830173,-6.74383211136 --3.18182396889,1.88976120949,-6.75724935532 --3.16983294487,1.89475679398,-6.78366994858 --3.13580155373,1.88577830791,-6.76610708237 --3.11479520798,1.88578367233,-6.77655172348 --3.09378647804,1.88479053974,-6.78296422958 --2.0543410778,1.85015010834,-7.07867622375 --2.03734517097,1.85414981842,-7.09810209274 --2.02135467529,1.85914635658,-7.12354040146 --2.0003464222,1.85915350914,-7.12996673584 --1.97532463074,1.85516893864,-7.12239265442 --1.96833348274,1.8591645956,-7.13961553574 --1.94832754135,1.86017048359,-7.14803409576 --1.9263176918,1.8591786623,-7.15347337723 --1.90330505371,1.85818862915,-7.15591669083 --1.88831818104,1.86518323421,-7.18434476852 --1.86129009724,1.85920214653,-7.17078113556 --1.84529805183,1.86419987679,-7.19319438934 --1.83027887344,1.85921239853,-7.18141651154 --1.80927240849,1.86021876335,-7.18985319138 --1.79428577423,1.86621308327,-7.21827411652 --1.76725840569,1.86123180389,-7.20572090149 --1.7462502718,1.86123907566,-7.21214675903 --1.72524297237,1.86124587059,-7.21957826614 --1.71323633194,1.8612511158,-7.2208108902 --1.6922274828,1.8612588644,-7.22623205185 --1.67122018337,1.86126565933,-7.23366355896 --1.64720201492,1.85927891731,-7.23010158539 --1.62820255756,1.86128103733,-7.24553012848 --1.60418438911,1.85929441452,-7.24197006226 --1.58317804337,1.86030089855,-7.25040531158 --1.56116604805,1.85931038857,-7.25283384323 --1.55116486549,1.86031246185,-7.25905036926 --1.52814972401,1.8583240509,-7.25848579407 --1.504129529,1.85533845425,-7.25292015076 --1.48613631725,1.86033725739,-7.27435207367 --1.46412360668,1.85934734344,-7.27577733994 --1.43708956242,1.85236990452,-7.25621509552 --1.43110907078,1.85935997963,-7.28343820572 --1.409096241,1.8583701849,-7.28486442566 --1.38708412647,1.85737991333,-7.28729486465 --1.36407244205,1.85738956928,-7.29074907303 --1.34206044674,1.85639929771,-7.2931804657 --1.31602847576,1.85042071342,-7.2756152153 --1.30004656315,1.85841310024,-7.30804157257 --1.28300774097,1.84843683243,-7.27625370026 --1.26200509071,1.85044133663,-7.28870391846 --1.23998963833,1.84945297241,-7.28712320328 --1.22200226784,1.85544872284,-7.31456518173 --1.19596540928,1.84747266769,-7.29199075699 --1.17294931412,1.84648501873,-7.29043197632 --1.15295016766,1.84948754311,-7.30587005615 --1.14395534992,1.85248601437,-7.31808423996 --1.12395441532,1.85448944569,-7.33151388168 --1.07578265667,1.80959033966,-7.1759595871 --1.07389509678,1.84452950954,-7.30139064789 --1.05691170692,1.85152292252,-7.33181381226 --1.02987015247,1.84354996681,-7.30525970459 --1.0098720789,1.84655177593,-7.32169771194 --0.999869585037,1.84755480289,-7.32590532303 --0.974837183952,1.84157621861,-7.30834341049 --0.954841256142,1.84557723999,-7.32678556442 --0.930811345577,1.84059727192,-7.31121206284 --0.907791078091,1.83761179447,-7.30564832687 --0.862757027149,1.83463740349,-7.3005194664 --0.850744724274,1.83264601231,-7.29574346542 --0.83074426651,1.83564949036,-7.30917024612 --0.809738695621,1.83765590191,-7.31760454178 --0.785707235336,1.83167672157,-7.30103826523 --0.764704227448,1.83368170261,-7.31247901917 --0.745712459087,1.83968043327,-7.33390188217 --0.723699390888,1.83869099617,-7.33533811569 --0.712693452835,1.83869600296,-7.33655738831 --0.690685331821,1.83970415592,-7.34300422668 --0.668671548367,1.83971524239,-7.34343910217 --0.64665967226,1.83972537518,-7.34587812424 --0.625652194023,1.84073293209,-7.35230493546 --0.60363638401,1.83974504471,-7.3507361412 --0.580608963966,1.83476364613,-7.33816814423 --0.570616483688,1.83876132965,-7.35239124298 --0.546584665775,1.83378255367,-7.33583831787 --0.526590824127,1.83878266811,-7.35526704788 --0.504571020603,1.83679711819,-7.34969377518 --0.482562094927,1.83780574799,-7.35513782501 --0.458521932364,1.82983136177,-7.33057832718 --0.448521703482,1.83183324337,-7.33678674698 --0.426512748003,1.83284187317,-7.34223127365 --0.404490709305,1.82985746861,-7.33465909958 --0.382468611002,1.82687318325,-7.32708787918 --0.362488299608,1.83586621284,-7.35952568054 --0.34047332406,1.83487808704,-7.35896205902 --0.317438691854,1.82990086079,-7.33939933777 --0.306426525116,1.82790923119,-7.33461380005 --0.283385276794,1.81993532181,-7.30904769897 --0.261377543211,1.8219435215,-7.31549549103 --0.239362373948,1.82095551491,-7.3149356842 --0.218366608024,1.82595717907,-7.33237075806 --0.197367802262,1.82996034622,-7.34680175781 --0.175351753831,1.82897281647,-7.34524059296 --0.164322033525,1.82299077511,-7.32344675064 --0.142301753163,1.82100558281,-7.31788492203 --0.120282419026,1.81901979446,-7.31332397461 --0.0861968845129,1.80207180977,-7.25298166275 --0.0651875212789,1.80308067799,-7.25740909576 --0.0431881248951,1.80708444118,-7.27185964584 --0.033173315227,1.8050942421,-7.26406002045 --0.0111517412588,1.80310988426,-7.2575044632 -0.0108624352142,1.80312156677,-7.25795078278 -0.00414271932095,1.78887295723,-6.42430973053 -0.0251458957791,1.7868680954,-6.41469669342 -0.0471694692969,1.78887403011,-6.42409753799 -0.0681788474321,1.78787267208,-6.42048454285 -0.0791785940528,1.78586924076,-6.41368913651 -0.100185081363,1.7848662138,-6.40707778931 -0.122203476727,1.78586935997,-6.41147947311 -0.14319203794,1.77885687351,-6.38788032532 -0.165215790272,1.78186285496,-6.39727973938 -0.186223134398,1.77986049652,-6.39167070389 -0.207226663828,1.77785599232,-6.38206529617 -0.218241035938,1.77986037731,-6.38926267624 -0.240266606212,1.78286743164,-6.40065813065 -0.260263293982,1.77885949612,-6.38504123688 -0.281256467104,1.77284967899,-6.36544847488 -0.30328130722,1.77685618401,-6.37584400177 -0.323280125856,1.77284955978,-6.36222887039 -0.35530102253,1.77285122871,-6.36282062531 -0.377325713634,1.77685761452,-6.37321424484 -0.398328393698,1.77385282516,-6.362616539 -0.418325573206,1.76984536648,-6.34700870514 -0.44135761261,1.77485561371,-6.36440944672 -0.462362498045,1.77285194397,-6.35581064224 -0.472370862961,1.77285349369,-6.35799264908 -0.493377000093,1.77185034752,-6.35039281845 -0.514385819435,1.77084887028,-6.34578943253 -0.53438603878,1.76684319973,-6.3331823349 -0.557410299778,1.7708491087,-6.34259176254 -0.578426063061,1.7718514204,-6.34497594833 -0.600452065468,1.77485895157,-6.35735988617 -0.610444247723,1.77185165882,-6.34257268906 -0.629434525967,1.76584076881,-6.31997013092 -0.651458621025,1.7688472271,-6.3303565979 -0.671460270882,1.76584219933,-6.31875228882 -0.692466616631,1.76483941078,-6.3111577034 -0.714487731457,1.76684427261,-6.31854963303 -0.735501766205,1.76784551144,-6.31893730164 -0.744492590427,1.76383781433,-6.30314159393 -0.765497922897,1.76183462143,-6.2945523262 -0.786509990692,1.76183485985,-6.29294586182 -0.807521104813,1.76183474064,-6.29034233093 -0.828534960747,1.76183605194,-6.29073143005 -0.848536252975,1.75983083248,-6.27813577652 -0.870553612709,1.76083362103,-6.28153514862 -0.882572770119,1.76484048367,-6.29372406006 -0.902574837208,1.76183581352,-6.28212690353 -0.920564889908,1.75682497025,-6.25852823257 -0.942585766315,1.75882995129,-6.26591587067 -0.963598966599,1.75983095169,-6.26530694962 -0.98259806633,1.75682473183,-6.25070333481 -0.993605256081,1.75682556629,-6.25090742111 -1.01562643051,1.75983047485,-6.25829219818 -1.03462171555,1.7548224926,-6.23970460892 -1.05563306808,1.7548224926,-6.23710298538 -1.07463598251,1.75281834602,-6.22649049759 -1.09463953972,1.75081455708,-6.21589851379 -1.11866903305,1.75682353973,-6.23129034042 -1.12666273117,1.75281774998,-6.21848392487 -1.14767324924,1.75281739235,-6.21488571167 -1.16868305206,1.75281655788,-6.21029186249 -1.18869292736,1.75281608105,-6.20667600632 -1.21070754528,1.7538176775,-6.20708179474 -1.22971236706,1.75181484222,-6.1984667778 -1.25072300434,1.75181460381,-6.19486951828 -1.26072788239,1.75181436539,-6.19306182861 -1.28374934196,1.75481939316,-6.20045804977 -1.30274903774,1.75181376934,-6.18586778641 -1.32476639748,1.75381684303,-6.18926000595 -1.34678554535,1.75682079792,-6.19464349747 -1.36277329922,1.75080955029,-6.16804981232 -1.38579463959,1.75381457806,-6.17544317245 -1.39680016041,1.75381445885,-6.17365312576 -1.41479694843,1.74980759621,-6.15606212616 -1.43380129337,1.74780440331,-6.14645528793 -1.45582020283,1.7508084774,-6.1518368721 -1.4778342247,1.75180983543,-6.15124464035 -1.49482905865,1.74780201912,-6.13164806366 -1.5158405304,1.74780237675,-6.12904691696 -1.52684962749,1.74980425835,-6.13123893738 -1.54685723782,1.7488026619,-6.12463855743 -1.56686484814,1.74780118465,-6.11803817749 -1.58587026596,1.74679875374,-6.10942935944 -1.61089682579,1.75180613995,-6.12182760239 -1.62889587879,1.74880051613,-6.10623502731 -1.64890348911,1.74779903889,-6.09963560104 -1.65690088272,1.74579536915,-6.08983230591 -1.68493902683,1.75480830669,-6.11421966553 -1.69792282581,1.74679577351,-6.08361673355 -1.71793079376,1.7467944622,-6.07701730728 -1.73693478107,1.74479138851,-6.06642198563 -2.74638962746,1.75976598263,-5.78238010406 -2.76038551331,1.75676000118,-5.76179265976 -2.78440189362,1.75976264477,-5.76319408417 -2.79741311073,1.76176571846,-5.76837444305 -2.81341385841,1.75976169109,-5.75278043747 -2.83743071556,1.76376473904,-5.75517082214 -2.85342979431,1.76076006889,-5.73759508133 -2.87945055962,1.76576471329,-5.74398374557 -2.89745497704,1.76476240158,-5.73239040375 -2.91746425629,1.7657623291,-5.72677946091 -2.92646622658,1.76476120949,-5.72098350525 -2.94747614861,1.76576125622,-5.71538877487 -2.9634771347,1.76375746727,-5.69979810715 -2.98248314857,1.76375603676,-5.69020462036 -3.00950574875,1.76976132393,-5.69858455658 -3.02650809288,1.76775848866,-5.6849937439 -3.04250955582,1.76575505733,-5.6703953743 -3.05351543427,1.7667555809,-5.66859674454 -3.07552862167,1.7697571516,-5.66697978973 -3.09453511238,1.76975572109,-5.65738630295 -3.11153817177,1.76775324345,-5.64478778839 -3.13054442406,1.76775205135,-5.63519382477 -3.15656352043,1.77275586128,-5.639585495 -3.16656708717,1.77275526524,-5.63479614258 -3.18256831169,1.77075171471,-5.61920928955 -3.19957184792,1.769749403,-5.60661077499 -3.22558999062,1.77375280857,-5.61000823975 -3.24459767342,1.77475225925,-5.602394104 -3.26861190796,1.77775406837,-5.60080432892 -3.28461432457,1.77675127983,-5.58719873428 -3.29261493683,1.77474963665,-5.57940578461 -3.31462669373,1.77775061131,-5.57580137253 -3.33263158798,1.77674877644,-5.56420946121 -3.35163784027,1.77674734592,-5.5536236763 -3.37164664268,1.77774727345,-5.54701471329 -3.39365816116,1.77974820137,-5.54340839386 -3.41166329384,1.77974641323,-5.53181600571 -3.41265368462,1.77474105358,-5.51302194595 -3.43366360664,1.77674102783,-5.50642871857 -3.46068239212,1.78074479103,-5.51081943512 -3.4856979847,1.78474736214,-5.51121711731 -3.49969696999,1.78174316883,-5.49263286591 -3.52070689201,1.78374350071,-5.4870262146 -3.53871273994,1.78374218941,-5.47642374039 -3.54871702194,1.78474211693,-5.47262239456 -3.57273006439,1.7867436409,-5.47003173828 -3.5907356739,1.7867423296,-5.45942831039 -3.61174535751,1.78874230385,-5.4528298378 -3.63776230812,1.792745471,-5.45521450043 -3.65276265144,1.79074203968,-5.43763780594 -3.66176533699,1.79074132442,-5.43184089661 -3.6747636795,1.78773713112,-5.41225481033 -3.68676185608,1.78573322296,-5.39364337921 -3.71678328514,1.79173767567,-5.40004396439 -3.72377419472,1.78573095798,-5.37245321274 -3.74278116226,1.78673017025,-5.36285448074 -3.76779532433,1.78973209858,-5.3612613678 -3.78280615807,1.79273438454,-5.36445856094 -3.80882263184,1.79773712158,-5.36584472656 -3.81681418419,1.79173064232,-5.33827400208 -3.85284304619,1.80073797703,-5.35365629196 -3.87084817886,1.80073666573,-5.34206151962 -3.88384795189,1.79873323441,-5.32445716858 -3.89284229279,1.79472792149,-5.2998714447 -3.90685105324,1.79772949219,-5.30107116699 -3.92385530472,1.79672765732,-5.28748416901 -3.93785595894,1.79472482204,-5.2708864212 -3.95886564255,1.79672503471,-5.26428031921 -3.97486829758,1.79572284222,-5.24870204926 -3.99587750435,1.79772293568,-5.24110651016 -4.02289438248,1.80172586441,-5.24348497391 -4.041908741,1.80672943592,-5.25068616867 -4.05190515518,1.80372488499,-5.22809791565 -4.0729136467,1.80472481251,-5.21951150894 -4.08491325378,1.8027215004,-5.20090818405 -4.10992670059,1.80572319031,-5.19831037521 -4.12893342972,1.80672264099,-5.18870449066 -4.1359333992,1.80572104454,-5.17892408371 -4.16795539856,1.81272566319,-5.18630743027 -4.16994333267,1.80571830273,-5.15372514725 -4.19896125793,1.81172144413,-5.15612077713 -4.20895814896,1.80771756172,-5.13452720642 -4.23297071457,1.81171882153,-5.13091993332 -4.25097560883,1.81171751022,-5.11734580994 -4.25897789001,1.81171691418,-5.1115322113 -4.2819890976,1.8137178421,-5.10593318939 -4.29198598862,1.81071376801,-5.08335351944 -4.31699943542,1.81471538544,-5.08074522018 -4.33300256729,1.81371378899,-5.06615447998 -4.36001825333,1.81871581078,-5.06455993652 -4.38202810287,1.82071638107,-5.05795478821 -4.38302278519,1.81771314144,-5.04216480255 -4.39602279663,1.81571042538,-5.02358102798 -4.42704248428,1.82171404362,-5.02796459198 -4.44704961777,1.82271361351,-5.01737880707 -4.46005105972,1.82171118259,-4.99978256226 -4.47905778885,1.82271075249,-4.98918247223 -4.48705339432,1.81870651245,-4.96460533142 -4.46502590179,1.80569624901,-4.92283058167 -4.43798780441,1.78668117523,-4.85828256607 -4.39293289185,1.76066052914,-4.77276229858 -4.36389446259,1.74064564705,-4.70721817017 -4.33085298538,1.7206299305,-4.63866472244 -4.33284521103,1.71462500095,-4.60909748077 -4.33984231949,1.71062171459,-4.58552360535 -4.34684467316,1.71062135696,-4.5787191391 -4.35984802246,1.70962011814,-4.56312417984 -4.35983896255,1.7036151886,-4.53254938126 -4.3768453598,1.70361495018,-4.51997184753 -4.39285230637,1.70461475849,-4.50836610794 -4.3998503685,1.70161211491,-4.48677110672 -4.41785812378,1.70261240005,-4.4761800766 -4.41685295105,1.69860982895,-4.4594039917 -4.42985630035,1.69760870934,-4.44381284714 -4.44085884094,1.69660723209,-4.42622184753 -4.45886707306,1.69760775566,-4.41563177109 -4.4638633728,1.69360482693,-4.39204263687 -4.47886943817,1.69360458851,-4.37845277786 -4.47986650467,1.69060266018,-4.36466741562 -4.48086023331,1.68559885025,-4.33708333969 -4.48585748672,1.68159615993,-4.3135008812 -4.4998626709,1.6815956831,-4.29891395569 -4.50285816193,1.67659258842,-4.27333593369 -4.51886558533,1.67759287357,-4.26074886322 -4.5328707695,1.67759263515,-4.24714851379 -4.5278635025,1.67258965969,-4.22836017609 -4.54787349701,1.67459082603,-4.21976995468 -4.55487298965,1.67158901691,-4.19917821884 -4.56687688828,1.67058849335,-4.1825966835 -4.58188343048,1.67158854008,-4.16999673843 -4.58788251877,1.66858661175,-4.14742422104 -4.59888553619,1.66658592224,-4.13083124161 -4.59788227081,1.66358411312,-4.11604452133 -4.61088705063,1.6635838747,-4.10046434402 -4.62189054489,1.66258335114,-4.08387231827 -4.63389444351,1.66158294678,-4.06827974319 -4.64389753342,1.65958213806,-4.04970645905 -4.64889621735,1.65658056736,-4.02811193466 -4.65690040588,1.65758085251,-4.02231216431 -4.67490911484,1.6585817337,-4.01172447205 -4.6759057045,1.65457940102,-3.9851565361 -4.6919131279,1.65558004379,-3.97355723381 -4.70091533661,1.65357935429,-3.95497393608 -4.7139210701,1.6535794735,-3.94136619568 -4.72792673111,1.65357983112,-3.92678713799 -4.72592353821,1.65057826042,-3.91199707985 -4.7389292717,1.65057849884,-3.89740562439 -4.74793195724,1.64857792854,-3.87882566452 -4.7609372139,1.64857816696,-3.8642346859 -4.77394294739,1.64857852459,-3.84964370728 -4.78594827652,1.6485786438,-3.83405542374 -4.79395103455,1.64657819271,-3.81546425819 -4.792948246,1.64357697964,-3.80167722702 -4.81195783615,1.6455783844,-3.79208421707 -4.81895971298,1.6435778141,-3.77249789238 -4.83296632767,1.64457845688,-3.75890398026 -4.84196996689,1.64257824421,-3.74032902718 -4.84997272491,1.64157795906,-3.72174119949 -4.85697460175,1.63857746124,-3.70215845108 -4.86397790909,1.6395778656,-3.69536185265 -4.87798452377,1.64057850838,-3.6817688942 -4.88898944855,1.63957893848,-3.66518807411 -4.90299654007,1.64057958126,-3.65159463882 -4.9099984169,1.63757944107,-3.63201475143 -4.92100381851,1.6375797987,-3.61543440819 -4.92700576782,1.63557946682,-3.59584307671 -4.93000650406,1.63457942009,-3.5860478878 -4.94201231003,1.63458001614,-3.57046437263 -4.94401216507,1.63057911396,-3.54689383507 -4.95902013779,1.63158023357,-3.53429746628 -4.96302080154,1.62857997417,-3.513702631 -4.97702789307,1.62958097458,-3.49912762642 -4.97602701187,1.62758040428,-3.48732018471 -4.98403024673,1.62558066845,-3.46775913239 -4.9970369339,1.62558162212,-3.45415592194 -5.00404024124,1.62458193302,-3.43556642532 -5.00804185867,1.62158179283,-3.41399407387 -5.01404476166,1.61958193779,-3.39441180229 -5.02505064011,1.61958277225,-3.37882041931 -5.04005861282,1.62258422375,-3.37801504135 -5.04205942154,1.61958420277,-3.35543894768 -5.04906272888,1.61758446693,-3.3368537426 -5.05706691742,1.61658513546,-3.319262743 -5.06907367706,1.61658620834,-3.30368375778 -5.07407617569,1.61458659172,-3.28311181068 -5.07907915115,1.6125869751,-3.26352334023 -5.08608341217,1.61358761787,-3.25672793388 -5.09708929062,1.61358869076,-3.24113845825 -5.1030921936,1.61158931255,-3.22254514694 -5.1160993576,1.61159062386,-3.20796108246 -5.11710119247,1.60859084129,-3.18538355827 -5.13010835648,1.60959219933,-3.17079973221 -5.13911342621,1.60859322548,-3.15420675278 -5.13511180878,1.60559296608,-3.13943219185 -5.15712404251,1.60959517956,-3.13084030151 -5.1591258049,1.60659563541,-3.11024236679 -5.16713047028,1.60559666157,-3.09167575836 -5.1691327095,1.60259723663,-3.07108020782 -5.1831407547,1.60359883308,-3.05748939514 -5.18214035034,1.60159909725,-3.04471588135 -5.19414758682,1.60260045528,-3.03012132645 -5.20115232468,1.60160171986,-3.01252770424 -5.21516084671,1.60260331631,-2.99795436859 -5.22016429901,1.60060429573,-2.97935843468 -5.22917079926,1.60060572624,-2.9617869854 -5.23217344284,1.59760665894,-2.94218993187 -5.23317480087,1.59660720825,-2.93042302132 -5.24117994308,1.59560847282,-2.91382431984 -5.24818563461,1.59460985661,-2.89525222778 -5.25118875504,1.59261095524,-2.87565779686 -5.2611951828,1.59261262417,-2.85908102989 -5.2561955452,1.58761334419,-2.83449935913 -5.27120447159,1.589615345,-2.82091856003 -5.27220582962,1.58861589432,-2.81111764908 -5.28021144867,1.58761751652,-2.79354047775 -5.28521633148,1.58661901951,-2.77495193481 -5.28922080994,1.58462035656,-2.75537323952 -5.30222892761,1.58562231064,-2.74177122116 -5.29822969437,1.58162355423,-2.7172088623 -5.30823707581,1.58162546158,-2.70161581039 -5.31123971939,1.58062624931,-2.69183778763 -5.31824541092,1.58062791824,-2.67523384094 -5.33325433731,1.58163011074,-2.66165137291 -5.3302564621,1.57763147354,-2.6380853653 -5.33226013184,1.57563316822,-2.61849236488 -5.34226751328,1.57563519478,-2.60191965103 -5.3442697525,1.57563602924,-2.59311366081 -5.35027599335,1.57463788986,-2.57454133034 -5.355281353,1.57363986969,-2.55596017838 -5.35828542709,1.57064175606,-2.53638076782 -5.36629199982,1.57064378262,-2.51978969574 -5.37029790878,1.56964576244,-2.50022029877 -5.37530326843,1.56864786148,-2.48262190819 -5.38330841064,1.56964898109,-2.47583460808 -5.39031457901,1.56865119934,-2.45825505257 -5.39331960678,1.56765317917,-2.4396584034 -5.40332746506,1.56765544415,-2.42308712006 -5.41733646393,1.56965780258,-2.40949225426 -5.41333913803,1.56565988064,-2.3869137764 -5.41834497452,1.56466209888,-2.36833763123 -5.42134809494,1.56366324425,-2.35954475403 -5.43235635757,1.56466555595,-2.34396266937 -5.43436145782,1.56266784668,-2.32438111305 -5.44236850739,1.56267023087,-2.30779266357 -5.45037555695,1.56267261505,-2.2912042141 -5.45838308334,1.56267511845,-2.27363610268 -5.45738744736,1.56067752838,-2.25305104256 -5.46339178085,1.56067883968,-2.24526453018 -5.46239614487,1.55768120289,-2.22468161583 -5.47340488434,1.55968368053,-2.21007871628 -5.47641038895,1.55768632889,-2.1905105114 -5.47841596603,1.55568897724,-2.17093491554 -5.48442316055,1.55569159985,-2.15335178375 -5.495429039,1.55769276619,-2.14854478836 -5.49443387985,1.55469536781,-2.12796616554 -5.50144147873,1.55469810963,-2.11039185524 -5.50344705582,1.5537006855,-2.09179806709 -5.50745344162,1.552703619,-2.07322096825 -5.51646184921,1.55270636082,-2.0566432476 -5.52246904373,1.55270922184,-2.03906178474 -5.52747344971,1.55271053314,-2.03126645088 -5.53148031235,1.55171346664,-2.01269078255 -5.53648662567,1.55071628094,-1.99510228634 -5.54349422455,1.55071914196,-1.97850871086 -5.53749847412,1.54772222042,-1.95594096184 -5.53950500488,1.5457252264,-1.9373524189 -5.54450941086,1.54672658443,-1.92955696583 -5.55151748657,1.54672956467,-1.91198539734 -5.55652427673,1.54573273659,-1.89439928532 -5.56353235245,1.54573583603,-1.87682783604 -5.56653928757,1.54473888874,-1.85824859142 -5.56254434586,1.54174208641,-1.83766126633 -5.57455396652,1.54274523258,-1.82208454609 -5.57755756378,1.54274666309,-1.81427466869 -5.57856416702,1.54174995422,-1.794703722 -5.58557271957,1.54175317287,-1.7771333456 -5.59858226776,1.54375612736,-1.76254093647 -5.57958364487,1.53576004505,-1.73696172237 -5.58759212494,1.53676319122,-1.72037792206 -5.60460329056,1.53976631165,-1.70679104328 -5.60060548782,1.53776812553,-1.69599831104 -5.60661363602,1.53777146339,-1.67842209339 -5.60762071609,1.53577518463,-1.65885591507 -5.61662912369,1.53677821159,-1.64325678349 -5.61563587189,1.53478193283,-1.62367856503 -5.63064670563,1.53778517246,-1.60909605026 -5.62365198135,1.53378903866,-1.58752381802 -5.62865638733,1.53479063511,-1.57972705364 -5.6376657486,1.53579413891,-1.56314885616 -5.63467168808,1.53279793262,-1.54356110096 -5.63667917252,1.53180158138,-1.52498328686 -5.6476893425,1.53380489349,-1.50939536095 -5.64569616318,1.53080880642,-1.48981595039 -5.6627035141,1.53581023216,-1.48502480984 -5.65570878983,1.53181421757,-1.46443796158 -5.66271829605,1.53281795979,-1.44686877728 -5.66572618484,1.53182160854,-1.42927670479 -5.66773414612,1.53082549572,-1.41070103645 -5.66574144363,1.52882969379,-1.39112508297 -5.6747508049,1.52983343601,-1.37454557419 -5.68075609207,1.53083503246,-1.36675310135 -5.68376398087,1.52983891964,-1.34916210175 -5.68277168274,1.52884316444,-1.32959318161 -5.68777990341,1.52884685993,-1.31299173832 -5.69278907776,1.52885079384,-1.2954120636 -5.69979858398,1.52885472775,-1.2778429985 -5.70480728149,1.52885866165,-1.26026308537 -5.6878080368,1.52386176586,-1.246483922 -5.70781993866,1.52786493301,-1.23289275169 -5.70882797241,1.52686917782,-1.21431529522 -5.71883821487,1.52887272835,-1.19871616364 -5.71184492111,1.52587759495,-1.17814469337 -5.71885442734,1.52588140965,-1.16155338287 -5.72686433792,1.5268856287,-1.14398813248 -5.72486782074,1.52588760853,-1.13517737389 -5.72587633133,1.52489209175,-1.11660206318 -5.72588443756,1.52389657497,-1.09802246094 -5.73389434814,1.52490055561,-1.08143484592 -5.74590492249,1.52690446377,-1.06486415863 -5.7419128418,1.5249093771,-1.04528999329 -5.74191713333,1.52391147614,-1.03648984432 -5.74592638016,1.52391576767,-1.01890647411 -5.75593709946,1.52591967583,-1.00232565403 -5.75194501877,1.52392470837,-0.982753694057 -5.75995492935,1.52492880821,-0.9661642313 -5.75996351242,1.52393352985,-0.947587192059 -5.76197290421,1.5229382515,-0.929018676281 -5.7629776001,1.52294051647,-0.920223116875 -5.76698684692,1.52294492722,-0.902640104294 -5.75899457932,1.51995027065,-0.883057117462 -5.77400541306,1.52295398712,-0.867469906807 -5.77601575851,1.52295875549,-0.848901689053 -5.77902460098,1.52296340466,-0.831314921379 -5.78003358841,1.52196800709,-0.81372153759 -5.78403902054,1.52297031879,-0.80493670702 -5.78304815292,1.52197527885,-0.786359131336 -5.78105688095,1.5199804306,-0.767779231071 -5.78406667709,1.51998507977,-0.750193178654 -5.78307628632,1.51899015903,-0.7316172719 -5.79008674622,1.51999473572,-0.714043736458 -5.79509687424,1.52099943161,-0.696463525295 -5.79310083389,1.52000200748,-0.687660336494 -5.80511188507,1.52200603485,-0.671077787876 -5.81512260437,1.52401030064,-0.654488265514 -5.80313110352,1.52001667023,-0.633927941322 -5.80414056778,1.52002155781,-0.616336405277 -5.80415058136,1.5190268755,-0.597765386105 -5.79615497589,1.51603031158,-0.586993515491 -5.81016588211,1.52003419399,-0.571390211582 -5.80717515945,1.51803970337,-0.552812457085 -5.80618476868,1.51704514027,-0.534240067005 -5.81619596481,1.51904940605,-0.517647862434 -5.82220649719,1.52005434036,-0.500068366528 -5.8142156601,1.51706051826,-0.48050391674 -5.8172211647,1.51806294918,-0.471714049578 -5.81223058701,1.51606869698,-0.453134655952 -5.82024097443,1.51707327366,-0.436536461115 -5.82225227356,1.51707875729,-0.417971313 -5.82426214218,1.51708388329,-0.400383502245 -5.82227230072,1.5160895586,-0.381811350584 -5.82628297806,1.51709473133,-0.364226996899 -5.82728767395,1.51709735394,-0.355433136225 -5.81929731369,1.51410365105,-0.336852490902 -5.82630872726,1.51610851288,-0.319272756577 -5.83931970596,1.51911270618,-0.302678287029 -5.82432937622,1.51411998272,-0.283112436533 -5.82734012604,1.51512563229,-0.264549165964 -5.82935142517,1.5151309967,-0.24696187675 -5.81635522842,1.51113498211,-0.237174421549 -5.82536649704,1.51313996315,-0.219595819712 -5.83437776566,1.51514482498,-0.20201613009 -5.82438802719,1.51215159893,-0.183439567685 -5.82939910889,1.51315677166,-0.165855392814 -5.8324098587,1.51416218281,-0.14826887846 -5.83341503143,1.51416492462,-0.139475226402 -5.82842636108,1.51217138767,-0.120905533433 -5.84143829346,1.51517593861,-0.103325761855 -5.82444763184,1.51018357277,-0.0847493708134 -5.83345890045,1.51318848133,-0.067165941 -5.83847045898,1.51419377327,-0.0495798066258 -5.83148145676,1.51220059395,-0.0310113262385 -5.83348655701,1.51220333576,-0.0222181119025 -5.83249759674,1.51220929623,-0.00462954957038 -5.83150911331,1.51121556759,0.0139355836436 -5.82751941681,1.51022195816,0.0315240249038 -5.83253145218,1.51122760773,0.0500882193446 -5.82854270935,1.51023411751,0.0676760002971 -5.83154821396,1.51023674011,0.0764696374536 -5.82355976105,1.50824391842,0.0950334593654 -5.82757091522,1.50924944878,0.112621203065 -5.82858228683,1.50925540924,0.130208641291 -5.83059406281,1.51026153564,0.148773789406 -5.82860565186,1.50926780701,0.166360259056 -5.82861709595,1.50927388668,0.183947488666 -5.83262252808,1.51027655602,0.192743107677 -5.82663440704,1.50928366184,0.211304396391 -5.82264614105,1.50829041004,0.22888892889 -5.8206577301,1.50729715824,0.247451215982 -5.82466936111,1.50830292702,0.265041053295 -5.82068061829,1.50730955601,0.28262463212 -5.81869268417,1.50731611252,0.300209671259 -5.82269906998,1.50831902027,0.309983879328 -5.81971025467,1.50732564926,0.327567666769 -5.82572221756,1.50933110714,0.34516119957 -5.82473468781,1.50933790207,0.363724470139 -5.82274675369,1.50834453106,0.381309092045 -5.81975793839,1.50835132599,0.398892581463 -5.82576465607,1.50935387611,0.408671170473 -5.81377649307,1.50636196136,0.426241636276 -5.8167886734,1.50736796856,0.44383302331 -5.81580066681,1.50737452507,0.461418658495 -5.81481266022,1.50738143921,0.479981333017 -5.81582546234,1.50838780403,0.497570484877 -5.80483722687,1.50539600849,0.515138328075 -5.8258433342,1.51139628887,0.524947047234 -5.81885576248,1.50940382481,0.542522132397 -5.81786775589,1.50941050053,0.560108244419 -5.81688070297,1.50941753387,0.578671514988 -5.81389284134,1.50942456722,0.596253633499 -5.80890512466,1.50843203068,0.613830983639 -5.81091785431,1.50943815708,0.631423592567 -5.80492401123,1.50744247437,0.640204012394 -5.80693674088,1.50844919682,0.658773899078 -5.80594921112,1.50845599174,0.676359951496 -5.80096149445,1.50746333599,0.693936049938 -5.80097436905,1.50847005844,0.71152472496 -5.79698705673,1.50747740269,0.729102790356 -5.79600048065,1.50748467445,0.747665882111 -5.79900598526,1.508487463,0.756468474865 -5.79501867294,1.50849497318,0.774046599865 -5.79703235626,1.50950157642,0.792618632317 -5.79504442215,1.50950872898,0.810202360153 -5.79905748367,1.5105150938,0.828781187534 -5.78907012939,1.50852334499,0.845363378525 -5.78407764435,1.50752770901,0.854142665863 -5.79408931732,1.5105329752,0.872741401196 -5.7861032486,1.50954127312,0.89030611515 -5.77611589432,1.50754964352,0.906886041164 -5.77013015747,1.50655758381,0.9244556427 -5.76914262772,1.50656473637,0.942042052746 -5.77315568924,1.50857126713,0.96062374115 -5.76816272736,1.50757563114,0.969401240349 -5.76717567444,1.5075827837,0.986988127232 -5.765188694,1.50759005547,1.00457167625 -5.75820302963,1.50659835339,1.0221362114 -5.75721597672,1.50760555267,1.03972363472 -5.75122976303,1.50661373138,1.05729138851 -5.74824285507,1.50662136078,1.0748707056 -5.7562494278,1.50862407684,1.08565330505 -5.73826360703,1.50463366508,1.10023963451 -5.75127696991,1.50863909721,1.12081730366 -5.74029064178,1.50664794445,1.1373860836 -5.73530387878,1.50665569305,1.15397977829 -5.73631763458,1.50766301155,1.17255401611 -5.72532558441,1.50466859341,1.18032419682 -5.72733926773,1.50667560101,1.19890320301 -5.73235225677,1.50868201256,1.21749663353 -5.71536684036,1.50469207764,1.23305678368 -5.70838069916,1.50370037556,1.24963963032 -5.71039438248,1.50470745564,1.26821959019 -5.71440792084,1.50771415234,1.28681051731 -5.70141553879,1.50371992588,1.29358911514 -5.70042896271,1.50472736359,1.31117808819 -5.70644283295,1.50773394108,1.33075761795 -5.69345760345,1.50474333763,1.34633159637 -5.68947172165,1.50475156307,1.36390590668 -5.69548511505,1.50775814056,1.38348758221 -5.68349981308,1.50476741791,1.39906477928 -5.6915063858,1.50776994228,1.40986049175 -5.68952083588,1.50877809525,1.42842400074 -5.67253637314,1.50478827953,1.44299519062 -5.67754888535,1.50779461861,1.461597085 -5.66456413269,1.50480437279,1.47716629505 -5.65957927704,1.50481295586,1.49473488331 -5.66559314728,1.50781953335,1.51432204247 -5.66459989548,1.50782346725,1.52311515808 -5.6586151123,1.50783228874,1.54067873955 -5.64862966537,1.5058413744,1.55626273155 -5.65264415741,1.50784850121,1.57584071159 -5.64565896988,1.50785720348,1.59242022038 -5.64667320251,1.5088647604,1.61100375652 -5.64468002319,1.50886893272,1.61979150772 -5.64569473267,1.51087641716,1.63837623596 -5.63770961761,1.50988543034,1.65494930744 -5.62572526932,1.50789523125,1.67051887512 -5.62473964691,1.50890338421,1.68909144402 -5.63075351715,1.51190984249,1.70868802071 -5.61476993561,1.50892055035,1.72325229645 -5.61077690125,1.50792491436,1.73104906082 -5.61479139328,1.51093196869,1.75063431263 -5.61880588531,1.51393949986,1.77119874954 -5.59382343292,1.50795149803,1.78276538849 -5.59383773804,1.50895941257,1.80134677887 -5.59685230255,1.5109667778,1.82092785835 -5.5868601799,1.50897216797,1.82672655582 -5.57987546921,1.50898122787,1.84330427647 -5.57789087296,1.50998961926,1.86187326908 -5.57490587234,1.50999796391,1.87945735455 -5.5749206543,1.51200580597,1.89804184437 -5.57293558121,1.51301431656,1.9166123867 -5.55295276642,1.50902581215,1.9291819334 -5.55396032333,1.51002955437,1.93897092342 -5.55697488785,1.51303696632,1.95855736732 -5.53899097443,1.50904798508,1.97113907337 -5.53900671005,1.51005613804,1.99070346355 -5.54602050781,1.51406276226,2.01130104065 -5.53803682327,1.51407241821,2.0278711319 -5.53005313873,1.51308190823,2.04444098473 -5.52706098557,1.51308655739,2.05322265625 -5.51407718658,1.51109695435,2.06779575348 -5.4990940094,1.5081076622,2.08137369156 -5.50010919571,1.51011562347,2.100949049 -5.49412488937,1.51012468338,2.11753368378 -5.48814105988,1.51013374329,2.13411831856 -5.47315788269,1.50814461708,2.14769339561 -5.46816635132,1.50714945793,2.15547966957 -5.46718120575,1.50915789604,2.17406225204 -5.45719814301,1.50816786289,2.18963456154 -5.45921373367,1.51017606258,2.21020054817 -5.46222877502,1.51318347454,2.22979807854 -5.44124650955,1.50919568539,2.24136137962 -5.45025348663,1.51319801807,2.25416111946 -5.44026994705,1.51120817661,2.26973295212 -5.43728637695,1.51321709156,2.28830218315 -5.42530345917,1.51122760773,2.30287694931 -5.42431879044,1.51323592663,2.32146430016 -5.4033370018,1.50824785233,2.33204293251 -5.4283490181,1.5182517767,2.36163210869 -5.40536022186,1.51226019859,2.36240315437 -5.3943772316,1.51127040386,2.37698578835 -5.39839220047,1.51427793503,2.39757871628 -5.40240716934,1.5172855854,2.41915225983 -5.39642477036,1.5182954073,2.43671870232 -5.37344312668,1.51330780983,2.44629383087 -5.37145900726,1.51531648636,2.46487641335 -5.34447097778,1.50832593441,2.46364188194 -5.33748722076,1.50833523273,2.47923827171 -5.35550069809,1.51534044743,2.50682401657 -5.32152080536,1.50735509396,2.51139163971 -5.31253862381,1.50736522675,2.52696871758 -5.32355260849,1.51337170601,2.55155420303 -5.30956268311,1.50937867165,2.55533289909 -5.30957841873,1.51138710976,2.57491636276 -5.2995967865,1.51139771938,2.59048438072 -5.29161453247,1.51140785217,2.60705137253 -5.28063201904,1.51041841507,2.62162947655 -5.27464818954,1.5104278326,2.63821649551 -5.28666305542,1.51643431187,2.66380190849 -5.27567243576,1.51444065571,2.66858649254 -5.26868963242,1.5154504776,2.68516516685 -5.25770711899,1.51446115971,2.69974303246 -5.24972438812,1.51447105408,2.71533131599 -5.23674249649,1.51248192787,2.72890806198 -5.23375940323,1.51449120045,2.74748754501 -5.23576784134,1.51649546623,2.75926375389 -5.22678565979,1.51550579071,2.77484178543 -5.20980453491,1.51351761818,2.78641581535 -5.21282052994,1.51652574539,2.80800032616 -5.20983695984,1.51853489876,2.82658290863 -5.19485569,1.51654648781,2.83915710449 -5.18487405777,1.51555716991,2.85472416878 -5.18688201904,1.51756095886,2.86552381516 -5.17390060425,1.51657223701,2.87909841537 -5.1669178009,1.5165822506,2.8956785202 -5.16293525696,1.5185918808,2.91425251961 -5.15395307541,1.51860237122,2.9298312664 -5.13897180557,1.51661407948,2.9424021244 -5.13698911667,1.51862323284,2.96197962761 -5.1369972229,1.52062749863,2.97178030014 -5.13001537323,1.52063798904,2.98934221268 -5.11603450775,1.51864933968,3.0019235611 -5.10905218124,1.51965939999,3.01850581169 -5.10107040405,1.52066993713,3.03507685661 -5.09408807755,1.52067995071,3.05165934563 -5.08610630035,1.52169060707,3.06823062897 -5.0801153183,1.52069604397,3.07502222061 -5.07913255692,1.52370524406,3.09559798241 -5.06315231323,1.52171719074,3.10717344284 -5.06916761398,1.52572453022,3.13077521324 -5.05118751526,1.52373707294,3.14134597778 -5.04520559311,1.52474713326,3.15892314911 -5.04521417618,1.52575170994,3.16970920563 -5.0312333107,1.52476334572,3.18228793144 -5.02325201035,1.52477395535,3.19886136055 -5.01527023315,1.52578449249,3.21543502808 -5.00528860092,1.52579510212,3.23002338409 -4.9903087616,1.52380728722,3.24258804321 -4.98432683945,1.52481746674,3.26016736031 -4.98233604431,1.52582240105,3.26995062828 -4.96635532379,1.52383422852,3.28054046631 -4.96237373352,1.52584433556,3.30010771751 -4.95339250565,1.52585506439,3.31568932533 -4.9494099617,1.52886474133,3.33427762985 -4.93443012238,1.52687692642,3.34684062004 -4.92644834518,1.52788722515,3.3624355793 -4.92745685577,1.52989172935,3.37422132492 -4.90547847748,1.52590513229,3.38178801537 -4.90649557114,1.5299141407,3.4043674469 -4.89051532745,1.52792608738,3.41495370865 -4.89153289795,1.53093504906,3.43753528595 -4.88055276871,1.53094673157,3.45309305191 -4.85557413101,1.52596056461,3.45767235756 -4.86158180237,1.52996397018,3.47247123718 -4.85160160065,1.52997517586,3.48804187775 -4.84261989594,1.53098595142,3.50362610817 -4.83164024353,1.53099727631,3.51820254326 -4.82265949249,1.53100848198,3.53476834297 -4.80867958069,1.5300205946,3.54734110832 -4.80668830872,1.53102517128,3.55614852905 -4.80170726776,1.53303563595,3.57571411133 -4.78372716904,1.53104805946,3.58430600166 -4.77774620056,1.53205871582,3.60287737846 -4.76476669312,1.53207075596,3.61644482613 -4.76178455353,1.53508019447,3.63604044914 -4.7497959137,1.53208732605,3.63882112503 -4.74381494522,1.53409790993,3.6573946476 -4.73083496094,1.53310954571,3.66998028755 -4.72285461426,1.53512072563,3.68754506111 -4.72387218475,1.53912973404,3.71112847328 -4.70489358902,1.53614282608,3.71970200539 -4.6969127655,1.53715372086,3.73628664017 -4.69292163849,1.53815889359,3.74408793449 -4.67794370651,1.53717160225,3.75664544106 -4.66796398163,1.53718292713,3.77221989632 -4.66398191452,1.54019296169,3.79180955887 -4.65100240707,1.53920507431,3.80537748337 -4.63702297211,1.53821694851,3.81696653366 -4.63104200363,1.54022753239,3.83554720879 -4.62505245209,1.54023373127,3.84332084656 -4.61307287216,1.54024541378,3.85690331459 -4.59909296036,1.53925728798,3.86849164963 -4.59111309052,1.5412684679,3.88606262207 -4.58713197708,1.54427874088,3.90664124489 -4.57515192032,1.54429042339,3.92022442818 -4.56017351151,1.54330301285,3.93179798126 -4.55718374252,1.54430830479,3.94158220291 -4.55220222473,1.54631865025,3.96116614342 -4.5362238884,1.54533135891,3.97174191475 -4.52224493027,1.54434370995,3.98431277275 -4.51926374435,1.54835391045,4.00589513779 -4.50728416443,1.54836559296,4.01947927475 -4.49929523468,1.54737210274,4.02525854111 -4.48731565475,1.54738390446,4.03884267807 -4.4723367691,1.54639601707,4.04943227768 -4.46235752106,1.54740798473,4.06599617004 -4.45437765121,1.54941904545,4.08357477188 -4.44439792633,1.55043053627,4.09915685654 -4.43241834641,1.55044233799,4.11274194717 -4.43142843246,1.55244731903,4.12452793121 -4.41345024109,1.55046057701,4.13310432434 -4.40946960449,1.55347108841,4.15468120575 -4.39649105072,1.55348336697,4.16825199127 -4.38551139832,1.55349504948,4.18283700943 -4.3685336113,1.55250799656,4.19241142273 -4.36055421829,1.5545194149,4.21097898483 -4.35056447983,1.55252575874,4.21279096603 -4.34258556366,1.55553722382,4.23135900497 -4.32260847092,1.5525509119,4.23793315887 -4.31562805176,1.5545617342,4.25651788712 -4.30564880371,1.55557370186,4.2730884552 -4.29467058182,1.55658555031,4.28866004944 -4.28668165207,1.5565918684,4.29345369339 -4.27570199966,1.55660355091,4.30804204941 -4.26072406769,1.55661642551,4.31961393356 -4.24374580383,1.55462932587,4.32820081711 -4.23976564407,1.5586400032,4.35077476501 -4.22678661346,1.55865204334,4.36336326599 -4.20881080627,1.55666577816,4.37291812897 -4.20881986618,1.5596704483,4.38571596146 -4.19384145737,1.55868339539,4.39728784561 -4.18186378479,1.55969560146,4.41186141968 -4.1578874588,1.55571007729,4.41344118118 -4.15490674973,1.559720397,4.43702316284 -4.14292812347,1.55973219872,4.45061254501 -4.13294887543,1.56174409389,4.46719026566 -4.11296319962,1.55675315857,4.45996904373 -4.08598852158,1.55076849461,4.45853900909 -4.09600496292,1.56077611446,4.49612760544 -4.0870256424,1.56278765202,4.51370811462 -4.06704902649,1.5598013401,4.51928710938 -4.05807065964,1.56281328201,4.5378537178 -4.0540804863,1.56381881237,4.54665279388 -4.03510332108,1.56083238125,4.55323219299 -4.0251250267,1.56284415722,4.5698132515 -4.01414680481,1.56485652924,4.58637809753 -3.99816966057,1.56386947632,4.59596300125 -3.98519134521,1.56388199329,4.60953903198 -3.97221302986,1.56489408016,4.62212991714 -3.97022294998,1.56689941883,4.63392162323 -3.95224666595,1.56491315365,4.64248657227 -3.94026875496,1.56592535973,4.65706634521 -3.92429184914,1.56593871117,4.66763591766 -3.91031360626,1.56595110893,4.67922544479 -3.89933586121,1.56696355343,4.69579458237 -3.89134740829,1.56696999073,4.70058631897 -3.87637019157,1.56698298454,4.7121591568 -3.8723897934,1.57099342346,4.73575115204 -3.85641241074,1.57100641727,4.74533510208 -3.83243751526,1.56602120399,4.74590730667 -3.82345890999,1.5690330267,4.76448583603 -3.807482481,1.56804633141,4.77505540848 -3.80349302292,1.5700520277,4.78484725952 -3.78351688385,1.56706595421,4.78943014145 -3.76154088974,1.56407999992,4.79101896286 -3.44264054298,1.42815673351,4.42445135117 -3.42166566849,1.42517113686,4.42602062225 -3.40768837929,1.42518377304,4.43560409546 -3.40070915222,1.4281951189,4.4541888237 -3.68864631653,1.56113994122,4.83510398865 -3.69166445732,1.57014894485,4.86869716644 -3.67868757248,1.57116186619,4.88326597214 -3.66570997238,1.57217442989,4.89684867859 -3.65673112869,1.57418596745,4.91543626785 -3.63375616074,1.57120060921,4.91601419449 -3.62177872658,1.57221317291,4.93158912659 -3.60979151726,1.57022058964,4.9313750267 -3.5988137722,1.57223284245,4.94795465469 -3.57883834839,1.57024681568,4.9525308609 -3.56686091423,1.57225942612,4.96810722351 -3.54788565636,1.57027351856,4.97467422485 -3.52691030502,1.5672878027,4.97725629807 -3.50792479515,1.56229674816,4.96704006195 -3.50294518471,1.56730759144,4.99162817001 -3.48796820641,1.56732046604,5.0022149086 -3.45699548721,1.5593367815,4.99078845978 -3.4600148201,1.56834638119,5.0283613205 -3.46303343773,1.57835566998,5.06495141983 -3.45605516434,1.58236730099,5.08852481842 -3.46206259727,1.5883705616,5.11233711243 -3.47707819939,1.60437726974,5.16693401337 -3.4381082058,1.59239554405,5.14449596405 -3.41013479233,1.58641135693,5.13707065582 -3.43314838409,1.60641646385,5.20466756821 -3.42517066002,1.61042845249,5.22823572159 -3.43617749214,1.62043118477,5.26203155518 -3.41920113564,1.61944448948,5.27061843872 -3.39522767067,1.61545979977,5.27018356323 -3.33226394653,1.59248304367,5.20973825455 -3.24030685425,1.55251157284,5.10131120682 -3.33730125427,1.61150145531,5.2859287262 -3.25434303284,1.57652890682,5.19247913361 -3.19236946106,1.54854691029,5.11324548721 -3.33335185051,1.63052761555,5.36988258362 -3.31137728691,1.6275421381,5.37145900726 -3.30639791489,1.63355302811,5.39905309677 -3.29841995239,1.63856482506,5.42362880707 -3.20446538925,1.5975946188,5.30917310715 -3.24147510529,1.62659680843,5.40577459335 -3.20649385452,1.61160898209,5.3665599823 -3.23650598526,1.63661313057,5.45414400101 -3.23952507973,1.64762246609,5.49673318863 -3.22854757309,1.65163481236,5.51631736755 -3.17558193207,1.63165581226,5.46588039398 -3.20459294319,1.65665948391,5.5514960289 -3.1876180172,1.6566734314,5.56305885315 -3.17463111877,1.65468096733,5.55985212326 -3.1606554985,1.65669441223,5.57641792297 -3.15567564964,1.6627048254,5.60502529144 -3.13170266151,1.65972030163,5.60458517075 -3.11472702026,1.65973377228,5.61417007446 -3.10574936867,1.66474580765,5.63875007629 -3.09476184845,1.66275286674,5.6385474205 -3.08078575134,1.66576588154,5.65412807465 -3.06880903244,1.6687785387,5.67370653152 -3.05383324623,1.66979193687,5.6882815361 -3.04385566711,1.67480397224,5.71086978912 -3.02288150787,1.67281842232,5.71444368362 -3.00990486145,1.67583107948,5.73202800751 -2.99891853333,1.67483878136,5.73380565643 -2.98794102669,1.67885088921,5.75439929962 -2.96796655655,1.67686522007,5.75997209549 -2.95399022102,1.67987811565,5.77555990219 -2.93801498413,1.68089163303,5.78913116455 -2.92203950882,1.68190515041,5.80171251297 -2.90406441689,1.68191885948,5.81029462814 -2.89307761192,1.68092620373,5.81108045578 -2.88010072708,1.68393886089,5.82867240906 -2.86512517929,1.68595218658,5.84424638748 -2.84215188026,1.68296718597,5.84381771088 -2.82917499542,1.68597972393,5.86141204834 -2.81220030785,1.68699347973,5.87298727036 -2.80521273613,1.68900024891,5.88276672363 -2.78323841095,1.68601465225,5.88235521317 -2.75426650047,1.67903077602,5.86793470383 -2.74428939819,1.6840429306,5.8935174942 -2.721316576,1.68205809593,5.8930850029 -2.70534086227,1.68307113647,5.90467882156 -2.691365242,1.68608438969,5.92325115204 -2.69437408447,1.69408869743,5.95305109024 -2.66440296173,1.68710517883,5.93662214279 -2.66042423248,1.69611608982,5.97620916367 -2.64045000076,1.69513034821,5.98079109192 -2.62247538567,1.69614422321,5.99036836624 -2.60450100899,1.6961581707,5.9999461174 -2.58552622795,1.69617211819,6.00652980804 -2.57254052162,1.69418013096,6.00330781937 -2.55756497383,1.69619321823,6.01889467239 -2.53759074211,1.69520759583,6.0234746933 -2.51861596107,1.69522130489,6.02906608582 -2.49764227867,1.69323587418,6.03164291382 -2.48366689682,1.69724905491,6.05121946335 -2.47767829895,1.69925510883,6.06201934814 -2.45670509338,1.69826984406,6.06558847427 -2.44073009491,1.70028328896,6.08016777039 -2.42375469208,1.70129656792,6.09076023102 -2.40178179741,1.69931149483,6.09133291245 -2.38780617714,1.70332455635,6.11091518402 -2.37183046341,1.70533776283,6.12450551987 -2.36484313011,1.7073444128,6.13529109955 -2.34586882591,1.7073584795,6.1428694725 -2.32989406586,1.71037197113,6.1584482193 -2.30892109871,1.70938670635,6.16201782227 -2.29994320869,1.71639835835,6.19361782074 -2.28996682167,1.72441065311,6.22619533539 -2.27998995781,1.73142290115,6.2577829361 -2.28099942207,1.74042749405,6.28958177567 -2.25902628899,1.73844218254,6.28916597366 -2.24805045128,1.74545490742,6.32173538208 -2.23307514191,1.74946808815,6.34131908417 -2.21610093117,1.7524818182,6.35689306259 -2.19412732124,1.75049626827,6.35548496246 -2.17115449905,1.74751114845,6.35306310654 -2.16116714478,1.74751806259,6.35486078262 -2.13919425011,1.74553275108,6.35543727875 -2.11822080612,1.74454724789,6.3580198288 -2.09424805641,1.74056220055,6.35160112381 -2.06627702713,1.73357820511,6.33417224884 -2.04630351067,1.73359251022,6.33975219727 -2.03831601143,1.73559916019,6.34854364395 -2.01634287834,1.73261368275,6.34712791443 -1.99736869335,1.73362767696,6.35471439362 -1.97339677811,1.73064291477,6.34928274155 -1.9504237175,1.72765755653,6.34386920929 -1.93045008183,1.72667181492,6.34845352173 -1.91147637367,1.72768568993,6.35703325272 -1.89849019051,1.72469329834,6.34882831573 -1.87651777267,1.72270822525,6.34939575195 -1.85754406452,1.72372233868,6.35797595978 -1.83657085896,1.72273671627,6.35955667496 -1.81759691238,1.72375059128,6.36714220047 -1.79962301254,1.72576451302,6.37972068787 -1.78663647175,1.72177195549,6.36952257156 -1.76566338539,1.72078633308,6.37110185623 -1.74569046497,1.72180080414,6.37767362595 -1.72471737862,1.72081518173,6.37925243378 -1.70374429226,1.71882963181,6.38083171844 -1.68377029896,1.71884357929,6.38342380524 -1.66579639912,1.72085738182,6.39600467682 -1.65381026268,1.71886479855,6.39079475403 -1.63483655453,1.71987867355,6.3993768692 -1.61086404324,1.71489346027,6.38696479797 -1.58989143372,1.71490812302,6.38953638077 -1.5719178915,1.71692216396,6.40410900116 -1.55094385147,1.71493601799,6.40070915222 -1.52997136116,1.71495056152,6.40328073502 -1.51698541641,1.71095812321,6.39207553864 -1.50201106071,1.71697163582,6.41964817047 -1.48003840446,1.71498608589,6.41622781754 -1.46006464958,1.71500003338,6.41881847382 -1.43609285355,1.71001505852,6.40739202499 -1.42011797428,1.71502816677,6.4269862175 -1.39714550972,1.71104288101,6.41756916046 -1.38416016102,1.70805072784,6.40834999084 -1.36618590355,1.71006417274,6.41994047165 -1.34721195698,1.71107804775,6.42752885818 -1.32423973083,1.70709264278,6.41810750961 -1.30426681042,1.70810699463,6.42368412018 -1.28529286385,1.70912075043,6.43127346039 -1.27230739594,1.70512831211,6.41906166077 -1.25033438206,1.70214271545,6.41164875031 -1.23136162758,1.70415699482,6.42421770096 -1.20938873291,1.70117127895,6.41680335999 -1.18841612339,1.70018565655,6.41638183594 -1.16844308376,1.70119976997,6.42096090317 -1.15046918392,1.70421350002,6.43554544449 -1.13848280907,1.70022058487,6.42434358597 -1.11850976944,1.7012346983,6.42892408371 -1.09753715992,1.69924914837,6.42850112915 -1.07856321335,1.70126271248,6.43509483337 -1.05959022045,1.70327663422,6.44766902924 -1.03661739826,1.69729101658,6.4302611351 -1.02763104439,1.70029807091,6.4410443306 -1.00465893745,1.69531261921,6.4266242981 -0.983685612679,1.69332671165,6.42121505737 -0.965712189674,1.69734036922,6.43979263306 -0.944739580154,1.69635474682,6.43837070465 -0.925765991211,1.69836843014,6.44795703888 -0.903792858124,1.69438254833,6.43355178833 -0.89380633831,1.69438958168,6.43534326553 -0.872834324837,1.694404006,6.43691205978 -0.852860748768,1.69341778755,6.43750333786 -0.832887291908,1.69243144989,6.43809461594 -0.811915278435,1.69244599342,6.43966245651 -0.791941761971,1.69245970249,6.44025373459 -0.770969450474,1.69147408009,6.43882894516 -0.760982036591,1.68948066235,6.43363761902 -0.740010142326,1.68949520588,6.43620252609 -0.721036016941,1.69050848484,6.44180202484 -0.699064016342,1.68752288818,6.43137550354 -0.680090129375,1.68953645229,6.4389705658 -0.660117089748,1.68955028057,6.44255399704 -0.639144420624,1.68756437302,6.43713569641 -0.62915802002,1.68857133389,6.43992567062 -0.608185529709,1.68658554554,6.43550443649 -0.587213218212,1.68559980392,6.43307876587 -0.567240059376,1.68561351299,6.43466567993 -0.549266159534,1.69162690639,6.45825576782 -0.527293384075,1.6846408844,6.43484544754 -0.517307162285,1.68564796448,6.43963241577 -0.49733376503,1.68566167355,6.43922328949 -0.476361513138,1.68467581272,6.43579769135 -0.456388324499,1.68468952179,6.43738508224 -0.436415106058,1.68470323086,6.4379734993 -0.415442854166,1.68271744251,6.43354892731 -0.394470483065,1.68073153496,6.42612695694 -0.385483056307,1.68273794651,6.43493080139 -0.36451035738,1.6787519455,6.42151498795 -0.344537615776,1.68176591396,6.43009328842 -0.324564516544,1.68177962303,6.43267965317 -0.303592175245,1.67879366875,6.42325687408 -0.283618956804,1.67880725861,6.42184638977 -0.274631619453,1.68281364441,6.43564891815 -0.253659486771,1.68082785606,6.42922258377 -0.23368626833,1.68084144592,6.42881155014 -0.213712885976,1.67885494232,6.42340421677 -0.192740753293,1.67586910725,6.41397714615 -0.172767877579,1.6788828373,6.42356014252 -0.152794778347,1.67889642715,6.42614650726 -0.142808198929,1.67890322208,6.42594099045 -0.122835054994,1.67991673946,6.42752933502 -0.102862037718,1.6829303503,6.43711423874 -0.0818900465965,1.67994451523,6.42768573761 -0.0619169771671,1.68295812607,6.43927240372 -0.0419437848032,1.68397164345,6.44286108017 -0.0219705477357,1.68398523331,6.44045114517 -0.0119839133695,1.68099188805,6.42924642563 --0.000998625764623,1.68500065804,6.22397851944 --0.0209711417556,1.68501448631,6.22355413437 --0.0399450175464,1.68402767181,6.22115087509 --0.0599175058305,1.68304145336,6.2187256813 --0.0699036866426,1.68204843998,6.21251249313 --0.0888775140047,1.68106150627,6.21010828018 --0.108850046992,1.68207526207,6.21268463135 --0.127824023366,1.68308830261,6.21628236771 --0.147796422243,1.68210208416,6.2118563652 --0.166770324111,1.6831151247,6.21245384216 --0.186742708087,1.68212890625,6.20802688599 --0.195729508996,1.67513549328,6.18381977081 --0.215702354908,1.67814898491,6.19440174103 --0.234676226974,1.67916214466,6.19499874115 --0.253649830818,1.67717528343,6.18858957291 --0.273622512817,1.67918884754,6.19316959381 --0.293595045805,1.68020248413,6.1937456131 --0.302582532167,1.67920875549,6.19055175781 --0.322555541992,1.68222212791,6.19913673401 --0.342528223991,1.68323564529,6.20171689987 --0.360502332449,1.67824852467,6.18231248856 --0.379475802183,1.67626166344,6.17590141296 --0.399448156357,1.67627537251,6.17347383499 --0.418421506882,1.6752884388,6.16606044769 --0.429407954216,1.68129527569,6.18685770035 --0.448380857706,1.67730867863,6.17343568802 --0.46735444665,1.67732179165,6.16902637482 --0.487327575684,1.67933499813,6.17561388016 --0.505301713943,1.67634773254,6.16221046448 --0.525274455547,1.67736124992,6.16379022598 --0.545247197151,1.67837464809,6.16537046432 --0.555234134197,1.68038105965,6.17217206955 --0.575206935406,1.68139445782,6.17375326157 --0.595179617405,1.6824079752,6.17333126068 --0.614152789116,1.68042099476,6.16491413116 --0.635125637054,1.68543434143,6.17950344086 --0.655098617077,1.6864477396,6.1810874939 --0.666084647179,1.68945455551,6.1898765564 --0.684058487415,1.68646740913,6.17546653748 --0.704031944275,1.6884803772,6.18106079102 --0.724004685879,1.68849372864,6.17963886261 --0.742978572845,1.68850648403,6.17723560333 --0.763951182365,1.69252002239,6.18581914902 --0.783923983574,1.69253325462,6.18439912796 --0.792910933495,1.6915396452,6.17819499969 --0.811884760857,1.69155240059,6.17478942871 --0.832856714725,1.69256603718,6.17735958099 --0.851830422878,1.69257891178,6.17295217514 --0.872803807259,1.6965918541,6.1845498085 --0.892776668072,1.69760513306,6.18313121796 --0.910750806332,1.69561767578,6.17272663116 --0.923735499382,1.69962513447,6.18649959564 --0.941709816456,1.69763755798,6.17709827423 --0.963681817055,1.70165109634,6.18667459488 --0.982655525208,1.70166385174,6.18126583099 --1.00262904167,1.70267677307,6.18386220932 --1.02160179615,1.70068991184,6.17243242264 --1.04157555103,1.70270264149,6.17603349686 --1.05056273937,1.70170879364,6.17083072662 --1.07153522968,1.70472204685,6.17441225052 --1.09050893784,1.70373475552,6.1690030098 --1.11348104477,1.70974826813,6.18358516693 --1.13245475292,1.70876085758,6.17817735672 --1.15242779255,1.70977389812,6.17575979233 --1.16241371632,1.70878064632,6.17153978348 --1.18238723278,1.70979344845,6.17213439941 --1.20335996151,1.71180653572,6.17471694946 --1.22433328629,1.7148194313,6.18031311035 --1.24230694771,1.71283197403,6.16789722443 --1.2632805109,1.7158447504,6.17349481583 --1.2832531929,1.71585786343,6.16907167435 --1.29324042797,1.71686387062,6.17087697983 --1.31521260738,1.71987724304,6.1754527092 --1.33418571949,1.71789014339,6.1670331955 --1.35515928268,1.72090280056,6.17163038254 --1.37513256073,1.72191548347,6.16921806335 --1.3941065073,1.72192788124,6.16381216049 --1.41607880592,1.72494113445,6.16839170456 --1.43006408215,1.72994828224,6.18317985535 --1.45003771782,1.73096084595,6.18177461624 --1.47200977802,1.73297417164,6.18434906006 --1.48698508739,1.72798573971,6.16294813156 --1.50695884228,1.72899830341,6.16154336929 --1.52593243122,1.72801077366,6.15412950516 --1.53791856766,1.73101735115,6.16092443466 --1.5598911047,1.73403048515,6.16450643539 --1.57786476612,1.73204278946,6.15208768845 --1.60083711147,1.73605597019,6.15967130661 --1.62281084061,1.74006843567,6.16727733612 --1.64078474045,1.73808073997,6.1558637619 --1.66475713253,1.74309384823,6.16745328903 --1.66974449158,1.73709964752,6.14423179626 --1.69371724129,1.74211263657,6.15682840347 --1.71568965912,1.74512565136,6.15840673447 --1.73166501522,1.74213719368,6.14301013947 --1.75063824654,1.74114978313,6.13358688354 --1.77760946751,1.74916338921,6.1531701088 --1.79658329487,1.74817562103,6.14575958252 --1.80757009983,1.75018179417,6.1485619545 --1.82654368877,1.7491941452,6.14014530182 --1.84551739693,1.74920654297,6.13172912598 --1.86449182034,1.7492184639,6.12632989883 --1.89046311378,1.7552318573,6.13990783691 --1.90443849564,1.75024318695,6.11649942398 --1.9144256115,1.75024926662,6.11529922485 --1.93939757347,1.75526249409,6.12588214874 --1.95337343216,1.75127363205,6.10448312759 --1.97634541988,1.75428664684,6.10705709457 --2.00331711769,1.76129996777,6.12364435196 --2.02029204369,1.75931155682,6.11124229431 --2.04326438904,1.76232457161,6.11382102966 --2.04825305939,1.7583296299,6.0976228714 --2.06922578812,1.75934231281,6.09420156479 --2.08820104599,1.76035380363,6.08981227875 --2.1171708107,1.76736783981,6.10737800598 --2.13014698029,1.76237869263,6.08397865295 --2.15012121201,1.76339066029,6.07957172394 --2.17409396172,1.76740336418,6.08616352081 --2.18008184433,1.76440882683,6.07195520401 --2.2050538063,1.76942181587,6.07953691483 --2.2310256958,1.77443492413,6.0901222229 --2.24700093269,1.77244615555,6.07471752167 --2.26497530937,1.77145779133,6.06431007385 --2.28694868088,1.77347016335,6.06389713287 --2.29893517494,1.77547645569,6.06669330597 --2.32490682602,1.78048956394,6.07527160645 --2.34188222885,1.77950072289,6.06387615204 --2.36485505104,1.78251314163,6.0654630661 --2.38382863998,1.78152525425,6.05503797531 --2.40880084038,1.78653788567,6.06162595749 --2.42277693748,1.78254890442,6.04122018814 --2.43376374245,1.7835547924,6.04101657867 --2.4597363472,1.78956747055,6.05061149597 --2.48270916939,1.79157984257,6.051197052 --2.49768471718,1.78959071636,6.0337934494 --2.5166592598,1.78960239887,6.02538442612 --2.53563332558,1.78861415386,6.01596736908 --2.56160545349,1.79362690449,6.02355480194 --2.57059311867,1.79363238811,6.01935958862 --2.58956766129,1.79364395142,6.01095151901 --2.61154055595,1.79565620422,6.00752830505 --2.63051557541,1.79566752911,6.00012874603 --2.65248918533,1.79867935181,5.99872303009 --2.67146348953,1.79869103432,5.98930835724 --2.69044756889,1.80469822884,6.0050945282 --2.70942187309,1.80470979214,5.99568128586 --2.72439837456,1.80172026157,5.9802904129 --2.74737167358,1.80473232269,5.9798784256 --2.76934456825,1.80674445629,5.97545337677 --2.79331851006,1.81075620651,5.97905874252 --2.81629109383,1.81276845932,5.97663402557 --2.82227945328,1.81077373028,5.96442747116 --2.84425330162,1.81278538704,5.96202135086 --2.86822652817,1.81579732895,5.96361446381 --2.88320207596,1.81380832195,5.94519805908 --2.89917802811,1.81181895733,5.93079614639 --2.93114852905,1.81983208656,5.94738101959 --2.95212292671,1.82184374332,5.9419708252 --2.95511269569,1.81784808636,5.92577981949 --2.98108482361,1.82286047935,5.92936086655 --3.00105905533,1.82287192345,5.92094326019 --3.01803469658,1.82188272476,5.90854263306 --3.04500746727,1.82789480686,5.91513729095 --3.05798363686,1.82390522957,5.8937253952 --3.07097005844,1.82591128349,5.89551925659 --3.09394359589,1.82892298698,5.89310503006 --3.11691761017,1.83093440533,5.8917016983 --3.1348927021,1.83094537258,5.88029384613 --3.15486645699,1.83095681667,5.87087011337 --3.17984080315,1.835968256,5.87448072433 --3.19581651688,1.83397889137,5.85907077789 --3.20880317688,1.83598470688,5.86086893082 --3.22477841377,1.83499550819,5.84444904327 --3.2467520237,1.83600699902,5.83903074265 --3.27672481537,1.84401905537,5.85063743591 --3.28670215607,1.8390288353,5.82422447205 --3.31367540359,1.84404063225,5.8288192749 --3.33264994621,1.8440515995,5.81840658188 --3.34263730049,1.84405708313,5.81420135498 --3.36161184311,1.84406816959,5.80277919769 --3.38958477974,1.85008013248,5.80837202072 --3.40556120872,1.84909033775,5.79397201538 --3.43153476715,1.85310173035,5.7965722084 --3.43851280212,1.84711122513,5.76515388489 --3.45549845695,1.85111737251,5.77295207977 --3.47547388077,1.85212802887,5.76555490494 --3.50344562531,1.85714018345,5.76812648773 --3.51542305946,1.85414993763,5.74672174454 --3.53639793396,1.8551607132,5.74031972885 --3.55437397957,1.8551710844,5.72891712189 --3.57734751701,1.85818231106,5.72349357605 --3.58833503723,1.85918772221,5.72129583359 --3.61530852318,1.86419916153,5.72389030457 --3.63228464127,1.8632093668,5.71048498154 --3.65425896645,1.86522042751,5.70407104492 --3.66923522949,1.86323046684,5.6866569519 --3.68621134758,1.86324059963,5.67325115204 --3.71518468857,1.86925208569,5.67885112762 --3.72517251968,1.86925721169,5.67465114594 --3.74114871025,1.86826741695,5.65924167633 --3.75912427902,1.86827766895,5.64683151245 --3.78009963036,1.87028813362,5.63942670822 --3.80207371712,1.87229907513,5.6320066452 --3.82004976273,1.87230932713,5.619597435 --3.8380355835,1.87731528282,5.62740039825 --3.86400914192,1.88032650948,5.62598514557 --3.87798643112,1.87933588028,5.6085858345 --3.90196084976,1.88234686852,5.60417127609 --3.91493821144,1.87935626507,5.5847659111 --3.93491387367,1.8803665638,5.57536029816 --3.96388745308,1.88637769222,5.57895803452 --3.96687698364,1.88338196278,5.56475973129 --3.98385286331,1.88339221478,5.54933595657 --4.00382852554,1.88440227509,5.5399312973 --4.02880334854,1.88841295242,5.5375289917 --4.04977846146,1.88942301273,5.52912282944 --4.07975196838,1.89643442631,5.53271341324 --4.09072971344,1.8924434185,5.51030445099 --4.09971809387,1.89244830608,5.50410223007 --4.12869119644,1.89845943451,5.50569009781 --4.12867212296,1.88946723938,5.4692864418 --4.16164445877,1.89747869968,5.47587251663 --4.19661664963,1.9054902792,5.48546600342 --4.20659542084,1.90249896049,5.46306943893 --4.21357440948,1.89750754833,5.43565940857 --4.23256063461,1.90251338482,5.44245910645 --4.24653768539,1.90052270889,5.42404794693 --4.26751327515,1.90253281593,5.41463661194 --4.29748725891,1.90854358673,5.4172334671 --4.30546617508,1.90355205536,5.39182853699 --4.32344293594,1.90456151962,5.37942790985 --4.34642791748,1.9115678072,5.39022254944 --4.36340475082,1.91157722473,5.3758149147 --4.38338041306,1.91258704662,5.36439847946 --4.42035245895,1.92159855366,5.37398576736 --4.43233060837,1.91860735416,5.35358095169 --4.4433093071,1.91661608219,5.33217763901 --4.47128391266,1.92162644863,5.33076858521 --4.47127437592,1.91763019562,5.3135676384 --4.4902510643,1.91863954067,5.30216884613 --4.50522851944,1.91764867306,5.28475475311 --4.51020860672,1.91265666485,5.25634908676 --4.5131893158,1.9066644907,5.22594499588 --4.53416490555,1.90767419338,5.215528965 --4.53814554214,1.90268218517,5.18611955643 --4.54713439941,1.90268647671,5.18093299866 --4.58910512924,1.91369819641,5.19451856613 --4.59908485413,1.9117064476,5.17312288284 --4.61206293106,1.90971505642,5.15370941162 --4.63103961945,1.91072440147,5.1412987709 --4.63602018356,1.90573227406,5.11389541626 --4.65899562836,1.9087420702,5.10547971725 --4.67898178101,1.91374754906,5.11128044128 --4.68496179581,1.90875542164,5.08487462997 --4.69993925095,1.90876436234,5.06745624542 --4.70892000198,1.90577220917,5.04606962204 --4.72689628601,1.90678143501,5.03164815903 --4.74487400055,1.90779018402,5.0192527771 --4.75986099243,1.90979504585,5.01905059814 --4.77284002304,1.90880358219,5.00064659119 --4.79481601715,1.91181313992,4.99022436142 --4.81079387665,1.91182172298,4.97481870651 --4.81577444077,1.90682935715,4.94841766357 --4.84374952316,1.91183912754,4.94500732422 --4.87272548676,1.91784858704,4.94361162186 --4.87971448898,1.91685295105,4.93440341949 --4.89369297028,1.9168612957,4.91699934006 --4.90267276764,1.91386914253,4.89459514618 --4.92664861679,1.91687846184,4.88617801666 --4.94462680817,1.91788685322,4.87378692627 --4.95460653305,1.91589474678,4.85238218307 --4.97958230972,1.91990411282,4.84496736526 --4.9825720787,1.91790795326,4.83175754547 --5.00155067444,1.91891634464,4.82036828995 --5.0075302124,1.91492414474,4.79394674301 --5.03450584412,1.91993355751,4.78853607178 --5.05648374557,1.92294204235,4.77913665771 --5.0704627037,1.92195022106,4.76173305511 --5.08244228363,1.92095816135,4.74232769012 --5.08343267441,1.91796159744,4.72812700272 --5.09841156006,1.91796970367,4.7117228508 --5.1163892746,1.91897821426,4.69730854034 --5.13036823273,1.91898620129,4.67990398407 --5.15034627914,1.92099452019,4.66850614548 --5.1453294754,1.9130011797,4.6330909729 --5.18430328369,1.92301094532,4.63869190216 --5.14830207825,1.90501189232,4.59047651291 --5.07230091095,1.87001311779,4.49307203293 --5.01229572296,1.84101593494,4.40965032578 --5.01527690887,1.837023139,4.38323831558 --5.01925897598,1.83303034306,4.35884094238 --5.03023862839,1.83203816414,4.33942651749 --5.04022741318,1.83304226398,4.33422803879 --5.04420852661,1.82904946804,4.30881357193 --5.06118679047,1.830057621,4.29541015625 --5.07416677475,1.8300652504,4.27901315689 --5.0871462822,1.83007311821,4.26160144806 --5.09312677383,1.8270804882,4.23818778992 --5.09910821915,1.82408750057,4.21578788757 --5.10009908676,1.8220911026,4.20258235931 --5.12907552719,1.82709980011,4.19918107986 --5.13805627823,1.82610714436,4.17877244949 --5.14503717422,1.82411432266,4.15737247467 --5.15401744843,1.82212173939,4.13696289062 --5.16899681091,1.82212948799,4.12155532837 --5.18197631836,1.8221372366,4.10414171219 --5.18996667862,1.8231408596,4.0979552269 --5.20694541931,1.82414865494,4.08353853226 --5.21492671967,1.82215583324,4.06313943863 --5.22690629959,1.82216346264,4.04472303391 --5.2258887291,1.81716990471,4.01732254028 --5.24086856842,1.8171775341,4.00191450119 --5.25184869766,1.81718480587,3.98350811005 --5.26483678818,1.81918907166,3.97929358482 --5.26981925964,1.8161958456,3.95689582825 --5.27780008316,1.81520283222,3.9364926815 --5.29377937317,1.81621050835,3.92107319832 --5.30775976181,1.8162176609,3.90567803383 --5.32973766327,1.82022559643,3.89526867867 --5.33172035217,1.81623232365,3.86985564232 --5.32671308517,1.81223511696,3.85366225243 --5.3516907692,1.81624305248,3.84525132179 --5.35467290878,1.81324958801,3.82185554504 --5.35665512085,1.80925631523,3.79643821716 --5.3746342659,1.81126379967,3.78302907944 --5.39061403275,1.81227099895,3.76862764359 --5.38659858704,1.80727720261,3.74022698402 --5.39758777618,1.80928099155,3.73502421379 --5.40356874466,1.8062877655,3.71260595322 --5.41255044937,1.80529475212,3.69320178032 --5.45852518082,1.81730318069,3.69980788231 --5.45350885391,1.81130921841,3.67039775848 --5.47048854828,1.81331646442,3.65598750114 --5.4644818306,1.80931913853,3.63979482651 --5.47946214676,1.81032621861,3.62438988686 --5.48344421387,1.80733287334,3.60097432137 --5.52741861343,1.8193410635,3.60456800461 --5.51840353012,1.81134688854,3.5731613636 --5.52038621902,1.80835330486,3.54874920845 --5.53936624527,1.81136023998,3.53635215759 --5.55635547638,1.81536400318,3.53515720367 --5.57233524323,1.81637096405,3.51974487305 --5.5693192482,1.81137704849,3.49233412743 --5.57930088043,1.81138348579,3.47393465042 --5.57728433609,1.80638968945,3.44752693176 --5.60226345062,1.81139671803,3.4381210804 --5.60324668884,1.80740296841,3.41371393204 --5.60523796082,1.80640602112,3.40251088142 --5.62521696091,1.80941307545,3.38909173012 --5.63619947433,1.80941939354,3.3716981411 --5.64818096161,1.81042587757,3.3542945385 --5.66116189957,1.81043255329,3.33688116074 --5.67214298248,1.81043899059,3.31847119331 --5.68412446976,1.81144523621,3.30106806755 --5.70311307907,1.8154489994,3.29986476898 --5.71209526062,1.8154553175,3.28045845032 --5.71607875824,1.81246113777,3.25906729698 --5.72806072235,1.81346726418,3.24166488647 --5.7370429039,1.81247353554,3.22225809097 --5.74402523041,1.81147956848,3.20185303688 --5.75600671768,1.81248605251,3.18343377113 --5.77199602127,1.81548953056,3.1802315712 --5.78397750854,1.81649553776,3.1628305912 --5.79096031189,1.81550168991,3.14242553711 --5.82093954086,1.82150804996,3.13502788544 --5.83992004395,1.82451450825,3.12061524391 --5.85490131378,1.82652068138,3.10420632362 --5.84189558029,1.82052326202,3.08500146866 --5.84687900543,1.81852912903,3.06359767914 --5.86685991287,1.82153522968,3.05019450188 --5.87884187698,1.82254135609,3.03177857399 --5.88682460785,1.8215470314,3.01238203049 --5.90480613708,1.82455301285,2.99798202515 --5.90079069138,1.82055866718,2.97157025337 --5.90778207779,1.82056164742,2.96337103844 --5.9247636795,1.82256758213,2.94796395302 --5.92574739456,1.82057321072,2.92455816269 --5.94172954559,1.82257890701,2.90916085243 --5.94071388245,1.81958448887,2.88475346565 --5.95769500732,1.82159054279,2.86833071709 --5.97167778015,1.82259619236,2.85193443298 --5.97966909409,1.82459878922,2.84474539757 --5.99265098572,1.82560479641,2.82632350922 --6.00063419342,1.82461023331,2.80692648888 --6.02361536026,1.82961606979,2.79351019859 --6.03459835052,1.82962155342,2.77510690689 --6.04058170319,1.82862699032,2.75470924377 --6.05756425858,1.83163237572,2.73930978775 --6.05555677414,1.82963526249,2.72609853745 --6.06653928757,1.82964062691,2.70769572258 --6.10251903534,1.8386464119,2.70028877258 --6.09650468826,1.83365166187,2.67388057709 --6.11748600006,1.837657094,2.65947151184 --6.13146924973,1.83966219425,2.64308285713 --6.14345264435,1.8406676054,2.62467503548 --6.15144348145,1.84167027473,2.61647391319 --6.18142461777,1.84867560863,2.60607218742 --6.17541027069,1.8436807394,2.57966065407 --6.18739366531,1.84468591213,2.56125450134 --6.219373703,1.85169124603,2.55084323883 --6.22235870361,1.85069620609,2.52945208549 --6.24134159088,1.85370123386,2.5140504837 --6.26633071899,1.86070370674,2.51285362244 --6.26931524277,1.85870873928,2.49044585228 --6.27929925919,1.85971367359,2.47104096413 --6.29328203201,1.86071884632,2.45262598991 --6.28526878357,1.85572373867,2.42622303963 --6.31325006485,1.86172866821,2.41381812096 --6.33523273468,1.86673343182,2.39942073822 --6.33022594452,1.86373591423,2.38520765305 --6.33821058273,1.86374080181,2.36480045319 --6.36719226837,1.87074530125,2.35341262817 --6.3661775589,1.86775016785,2.3289949894 --6.3781619072,1.86875486374,2.31059789658 --6.40214443207,1.87375950813,2.29619455338 --6.39313077927,1.86876451969,2.26877427101 --6.41112184525,1.87376642227,2.2645881176 --6.42810487747,1.87577104568,2.24717950821 --6.42509126663,1.87277579308,2.22277259827 --6.43407535553,1.87378048897,2.20236110687 --6.4660577774,1.88078451157,2.19096875191 --6.46104383469,1.87678933144,2.16555571556 --6.46503639221,1.87679159641,2.15535354614 --6.47702074051,1.87879610062,2.13594317436 --6.47400665283,1.8758007288,2.1115334034 --6.49499082565,1.87980484962,2.09614181519 --6.52197360992,1.88580882549,2.08173537254 --6.50896120071,1.87981367111,2.05432891846 --6.52694511414,1.88381779194,2.03692221642 --6.54693603516,1.88881969452,2.03171992302 --6.5269241333,1.87982451916,2.00231432915 --6.53190946579,1.87982881069,1.980910182 --6.55789279938,1.88583266735,1.96549797058 --6.5628786087,1.88483703136,1.94409477711 --6.56786441803,1.88484120369,1.92269098759 --6.57585000992,1.88484537601,1.90228950977 --6.58084249496,1.88584733009,1.89208340645 --6.59682703018,1.88885128498,1.87367641926 --6.61081218719,1.89085507393,1.85528075695 --6.60979890823,1.88885939121,1.83187270164 --6.62478351593,1.89086318016,1.81347322464 --6.62776994705,1.88986742496,1.79106235504 --6.62775611877,1.88887166977,1.76764774323 --6.64174842834,1.89187324047,1.76045298576 --6.65373373032,1.89387691021,1.74105250835 --6.65272045135,1.89088118076,1.71764278412 --6.65970611572,1.8918851614,1.69623029232 --6.64569425583,1.88588964939,1.66982543468 --6.65468025208,1.88689351082,1.64942097664 --6.6676659584,1.88889706135,1.63001680374 --6.68165779114,1.89289867878,1.62180840969 --6.6836438179,1.89090251923,1.59940087795 --6.6836309433,1.88990652561,1.57700145245 --6.68561792374,1.88891041279,1.55459272861 --6.69460391998,1.8899140358,1.53419005871 --6.70958948135,1.89291739464,1.51478075981 --6.73458099365,1.89891827106,1.50958526134 --6.73956823349,1.89892184734,1.48818361759 --6.73855495453,1.89792585373,1.46476984024 --6.7295422554,1.89293026924,1.43935132027 --6.75052833557,1.89793300629,1.42195796967 --6.75251531601,1.89693665504,1.39954972267 --6.75850200653,1.89794027805,1.37814366817 --6.75648880005,1.89494419098,1.35473179817 --6.75448322296,1.89394593239,1.34353840351 --6.76547002792,1.89594912529,1.3231317997 --6.76845645905,1.89495289326,1.30071878433 --6.7744436264,1.89595615864,1.27931284904 --6.7824306488,1.89695930481,1.25891852379 --6.79141759872,1.8979626894,1.23750281334 --6.79340457916,1.89796614647,1.21509301662 --6.79539823532,1.89796793461,1.20388460159 --6.80238485336,1.89797115326,1.18247652054 --6.80837249756,1.89897429943,1.16107177734 --6.81935977936,1.9009771347,1.14066982269 --6.83334684372,1.90397965908,1.12127745152 --6.83133459091,1.90198338032,1.09786212444 --6.83132839203,1.90098512173,1.08666038513 --6.83731603622,1.90198814869,1.06525683403 --6.83230400085,1.89899194241,1.04184901714 --6.83929109573,1.89999496937,1.02044248581 --6.85427808762,1.90399730206,1.00003218651 --6.85626649857,1.90300071239,0.977622330189 --6.85025453568,1.9000043869,0.954215288162 --6.84824848175,1.8990060091,0.94301789999 --6.85823583603,1.90100872517,0.921604454517 --6.87222337723,1.90401113033,0.901200175285 --6.89121103287,1.9090129137,0.881803035736 --6.89019966125,1.90801620483,0.85940092802 --6.89418697357,1.90801918507,0.836986482143 --6.903175354,1.90902173519,0.815579414368 --6.9101691246,1.91102266312,0.805379450321 --6.91715717316,1.91202533245,0.783977746964 --6.93514490128,1.91602706909,0.763571441174 --6.93013334274,1.91403055191,0.740159392357 --6.92712211609,1.91303384304,0.717760682106 --6.92511034012,1.91103696823,0.694341242313 --6.94609880447,1.91603827477,0.674951016903 --6.95509290695,1.919039011,0.664750099182 --6.96808099747,1.92204093933,0.643340706825 --6.97407007217,1.92304337025,0.621944785118 --6.98005819321,1.92404568195,0.599530875683 --6.97504711151,1.92204904556,0.576116919518 --6.99103546143,1.92505049706,0.55572450161 --7.0080242157,1.9300519228,0.534313440323 --7.01701831818,1.93205237389,0.524117052555 --7.01400756836,1.93005549908,0.500700652599 --7.0199971199,1.93205761909,0.479307681322 --7.03098487854,1.93405938148,0.45689073205 --7.04297447205,1.93706095219,0.435491770506 --7.05196332932,1.93906259537,0.414097458124 --7.06595277786,1.94306409359,0.391680032015 --7.06294727325,1.94206559658,0.380482763052 --7.06293678284,1.94106817245,0.358081549406 --7.07392597198,1.94406974316,0.335669219494 --7.06591558456,1.94107294083,0.312257289886 --7.09090423584,1.94807302952,0.29085239768 --7.08589458466,1.94607591629,0.268455892801 --7.08988332748,1.94707798958,0.245033726096 --7.09587860107,1.94807851315,0.234847426414 --7.09586811066,1.94808089733,0.211428493261 --7.0968580246,1.94808316231,0.189027130604 --7.10584783554,1.95008456707,0.166621565819 --7.11583757401,1.95308578014,0.144216284156 --7.10382699966,1.94908940792,0.120803080499 --7.11281728745,1.95109069347,0.0983991250396 --7.10481214523,1.94909262657,0.0872014462948 --7.10780191422,1.94909453392,0.0637816563249 --7.10679197311,1.9490967989,0.0413808487356 --7.10978221893,1.94909870625,0.0189795643091 --7.09877204895,1.94610202312,-0.00443863682449 --7.10276222229,1.94710361958,-0.0268404129893 --7.10175704956,1.94710493088,-0.039059471339 --7.10174703598,1.94710695744,-0.061461057514 --7.1077375412,1.94810831547,-0.0838618427515 --7.11172771454,1.94911003113,-0.107280701399 --7.10671806335,1.94811248779,-0.129683092237 --7.10070848465,1.94611525536,-0.152086153626 --7.09169816971,1.94311833382,-0.1755091995 --7.0976934433,1.94511854649,-0.186708211899 --7.10668468475,1.94811940193,-0.209106475115 --7.09167480469,1.94312310219,-0.231515049934 --7.09666490555,1.94512438774,-0.254933089018 --7.1026558876,1.94712543488,-0.27733156085 --7.11564683914,1.95012569427,-0.300742655993 --7.1076374054,1.94812846184,-0.323149383068 --7.11163330078,1.9491288662,-0.334347009659 --7.10862350464,1.94913113117,-0.357768923044 --7.09861421585,1.94613409042,-0.380178689957 --7.11560535431,1.95113360882,-0.403582930565 --7.11159658432,1.95013570786,-0.425987541676 --7.10858726501,1.94913780689,-0.448391377926 --7.12457942963,1.95413720608,-0.471793055534 --7.12857484818,1.95513749123,-0.484006613493 --7.10656499863,1.94914209843,-0.505414128304 --7.11455631256,1.95214247704,-0.528823375702 --7.11054706573,1.95114457607,-0.551228761673 --7.11653900146,1.95314526558,-0.57463914156 --7.13253164291,1.95814442635,-0.598034620285 --7.11652135849,1.95414817333,-0.620457112789 --7.12851810455,1.95814704895,-0.632657170296 --7.1125087738,1.95315074921,-0.654062569141 --7.12450122833,1.95715034008,-0.677461028099 --7.11349201202,1.95415341854,-0.699878156185 --7.11948394775,1.95715367794,-0.723285377026 --7.12147569656,1.95815479755,-0.74669867754 --7.10846614838,1.9541580677,-0.768102824688 --7.13646411896,1.96315431595,-0.782304346561 --7.14545726776,1.96615409851,-0.805702328682 --7.14344835281,1.96615564823,-0.829120993614 --7.17044305801,1.974152565,-0.854516267776 --7.14943265915,1.96915686131,-0.875937223434 --7.14742469788,1.96915829182,-0.898337244987 --7.16241836548,1.97415685654,-0.922735691071 --7.14741325378,1.97015964985,-0.93294864893 --7.14540529251,1.97016108036,-0.956366419792 --7.17339992523,1.97915744781,-0.98276746273 --7.15239048004,1.9731618166,-1.00317537785 --7.14238119125,1.97116434574,-1.02559423447 --7.14737462997,1.97316431999,-1.04899394512 --7.13636541367,1.97116708755,-1.07141637802 --7.14136266708,1.97316658497,-1.08260059357 --7.15335655212,1.97716546059,-1.1080160141 --7.14134788513,1.97416818142,-1.12942349911 --7.1423406601,1.97616875172,-1.15283215046 --7.13933324814,1.97616994381,-1.17625141144 --7.11732339859,1.9701744318,-1.19565391541 --7.12932109833,1.97417271137,-1.20885157585 --7.1503162384,1.98116958141,-1.23525321484 --7.15330982208,1.98316955566,-1.25967097282 --7.15130233765,1.98317050934,-1.28308546543 --7.16129684448,1.98716926575,-1.30748021603 --7.14128732681,1.98217332363,-1.32789802551 --7.15628242493,1.98817098141,-1.35431075096 --7.15827989578,1.98917078972,-1.3654987812 --7.14927148819,1.98717296124,-1.38791739941 --7.14126396179,1.98617470264,-1.410333395 --7.14925813675,1.98917365074,-1.43473005295 --7.13625001907,1.9871764183,-1.45614624023 --7.13924407959,1.98917603493,-1.48055922985 --7.1582403183,1.99617254734,-1.50694906712 --7.13923454285,1.99117636681,-1.51617622375 --7.12922668457,1.98917853832,-1.53758251667 --7.13322114944,1.99117791653,-1.56198990345 --7.11721229553,1.9881811142,-1.58240234852 --7.12020683289,1.99018061161,-1.60681295395 --7.13120222092,1.99417853355,-1.63220882416 --7.11519384384,1.99118185043,-1.65262269974 --7.10918712616,1.99118304253,-1.67503285408 --7.12018585205,1.99418079853,-1.68923342228 --7.11317873001,1.99418222904,-1.71164703369 --7.10517168045,1.99318373203,-1.73406505585 --7.12316846848,2.00018000603,-1.76146113873 --7.10115909576,1.99418437481,-1.78088545799 --7.10315418243,1.99718379974,-1.8052957058 --7.10515165329,1.99818325043,-1.81749606133 --7.08514308929,1.9931871891,-1.83691453934 --7.09113836288,1.9971858263,-1.86232352257 --7.10413503647,2.00218272209,-1.88871669769 --7.09412813187,2.0011844635,-1.91012632847 --7.08512163162,2.00018620491,-1.93254899979 --7.09411764145,2.00418376923,-1.95895719528 --7.09011411667,2.00318431854,-1.97016596794 --7.07810735703,2.00218653679,-1.99056875706 --7.0951051712,2.00818228722,-2.0189704895 --7.08009767532,2.0061852932,-2.03938746452 --7.07809209824,2.0071849823,-2.06381058693 --7.07408666611,2.00718545914,-2.08620834351 --7.07408189774,2.00918483734,-2.11062073708 --7.07107830048,2.00918507576,-2.12182450294 --7.06707334518,2.0101852417,-2.14523935318 --7.07207012177,2.01318359375,-2.17064142227 --7.07006454468,2.01418304443,-2.19404482841 --7.07706165314,2.01818060875,-2.22045135498 --7.07405662537,2.01918053627,-2.24487566948 --7.07505273819,2.02117943764,-2.26927781105 --7.09005355835,2.02717518806,-2.286485672 --7.0860490799,2.02717518806,-2.30887913704 --7.08804512024,2.03017377853,-2.33429026604 --7.08404016495,2.03117370605,-2.35769987106 --7.0920381546,2.03517055511,-2.38510942459 --7.09003400803,2.03716993332,-2.40952348709 --7.10703420639,2.04416441917,-2.43992948532 --7.10603237152,2.04516386986,-2.4521355629 --7.10002708435,2.04516410828,-2.47555303574 --7.10602521896,2.04916143417,-2.50195097923 --7.10302066803,2.05016088486,-2.52534985542 --7.09901666641,2.05116033554,-2.5497713089 --7.10701560974,2.05615711212,-2.57717084885 --7.11701440811,2.06115269661,-2.60658931732 --7.10601043701,2.05915498734,-2.61478662491 --7.10300636292,2.0601541996,-2.6391992569 --7.11700677872,2.06714868546,-2.66960692406 --7.11300373077,2.06814813614,-2.69300746918 --7.12300300598,2.07414364815,-2.72241926193 --7.1230006218,2.07614207268,-2.74782586098 --7.11299562454,2.07514286041,-2.77024531364 --7.11999607086,2.07913994789,-2.7854449749 --7.10999059677,2.07814073563,-2.80786418915 --7.1159901619,2.08313727379,-2.83526277542 --7.1409945488,2.09312820435,-2.87066674232 --7.15399599075,2.09912252426,-2.90106368065 --7.13298845291,2.09512639046,-2.91948676109 --7.11198091507,2.09112977982,-2.93791127205 --7.10997915268,2.09212946892,-2.95011639595 --7.09397315979,2.09013175964,-2.96952581406 --7.07596588135,2.0871348381,-2.98894906044 --7.07796525955,2.09013199806,-3.01535081863 --7.06595993042,2.08913326263,-3.03676652908 --7.05595541,2.08913373947,-3.05918502808 --7.0339474678,2.08513784409,-3.07660651207 --7.02094268799,2.08214044571,-3.08380770683 --7.02794313431,2.0871360302,-3.11322069168 --6.99893331528,2.08114218712,-3.12764596939 --6.98492717743,2.07914400101,-3.14806270599 --6.97592353821,2.07914423943,-3.17047643661 --6.96992063522,2.08014345169,-3.19388437271 --6.95891618729,2.078145504,-3.20209050179 --6.95491409302,2.08014416695,-3.22649979591 --6.9309053421,2.0751490593,-3.24292802811 --6.919901371,2.07514977455,-3.26434135437 --6.90289497375,2.0731523037,-3.28376793861 --6.89589166641,2.07315206528,-3.30616760254 --6.87888526917,2.071154356,-3.32559537888 --6.86387968063,2.06715798378,-3.33180332184 --6.86287879944,2.07015562057,-3.35720562935 --6.83887004852,2.06616044044,-3.37364149094 --6.83786916733,2.06915783882,-3.39904284477 --6.81786203384,2.06516170502,-3.41646504402 --6.80085515976,2.06316423416,-3.43488121033 --6.80485630035,2.06715989113,-3.46328902245 --6.79085159302,2.06516313553,-3.46949410439 --6.7668428421,2.06016802788,-3.48492002487 --6.76184082031,2.06216669083,-3.50933599472 --6.74283409119,2.05917000771,-3.52675509453 --6.72182607651,2.05617403984,-3.54317617416 --6.73983287811,2.06516480446,-3.57857561111 --6.71382331848,2.06017041206,-3.59199142456 --6.69781780243,2.05617427826,-3.59821677208 --6.70281982422,2.06116938591,-3.62762618065 --6.69581699371,2.06216859818,-3.65002584457 --6.67681074142,2.06017184258,-3.66744875908 --6.67581033707,2.06316900253,-3.69385933876 --6.64179801941,2.0551776886,-3.70328688622 --6.6317949295,2.05617761612,-3.7257130146 --6.62679290771,2.05617761612,-3.73591017723 --6.60578536987,2.05218172073,-3.75233793259 --6.58277702332,2.04918646812,-3.76675462723 --6.5887799263,2.05418086052,-3.79716396332 --6.55876922607,2.04818820953,-3.80758166313 --6.54076290131,2.04619121552,-3.82500267029 --6.53176021576,2.0461909771,-3.84742093086 --6.52075624466,2.04519295692,-3.854626894 --6.50775146484,2.0441942215,-3.87505054474 --6.49974966049,2.04519343376,-3.89745974541 --6.46973800659,2.03920125961,-3.90788578987 --6.45373249054,2.03720331192,-3.92630767822 --6.43872737885,2.03620529175,-3.94472122192 --6.41871976852,2.03320908546,-3.96115088463 --6.41171789169,2.03320980072,-3.97035384178 --6.4117193222,2.03720593452,-3.99776530266 --6.38270807266,2.03121328354,-4.00818967819 --6.3797082901,2.0342104435,-4.033598423 --6.37070655823,2.03520989418,-4.05601739883 --6.34469652176,2.03021645546,-4.06743240356 --6.33069229126,2.03021788597,-4.08685493469 --6.33969688416,2.03521203995,-4.1060552597 --6.31468772888,2.03021812439,-4.11847734451 --6.29067850113,2.0262234211,-4.13190746307 --6.28167676926,2.02722287178,-4.15432691574 --6.25966835022,2.02422761917,-4.16773939133 --6.24266290665,2.02223014832,-4.18516302109 --6.24166440964,2.02622652054,-4.21257781982 --6.21965551376,2.02123332024,-4.21178293228 --6.21165418625,2.02223205566,-4.23520755768 --6.19164705276,2.02023625374,-4.24961853027 --6.1726398468,2.01723980904,-4.26503515244 --6.15363359451,2.01524305344,-4.28146743774 --6.15163516998,2.01923966408,-4.30787563324 --6.1426320076,2.01824116707,-4.3160867691 --6.12962865829,2.01824212074,-4.33550262451 --6.11262321472,2.01624512672,-4.35191631317 --6.09261608124,2.01424884796,-4.36734676361 --6.07561016083,2.01225137711,-4.38376140594 --6.07061052322,2.01524877548,-4.40918254852 --6.05460596085,2.01425123215,-4.42660188675 --6.03959989548,2.01125526428,-4.43081951141 --6.02359437943,2.01025772095,-4.44722509384 --6.01059103012,2.01025867462,-4.46664333344 --5.99058437347,2.00826239586,-4.48207807541 --5.97257852554,2.00626587868,-4.49749183655 --5.96457767487,2.00826430321,-4.5209145546 --5.94156932831,2.00526952744,-4.53334093094 --5.92856359482,2.00227332115,-4.53754091263 --5.92156410217,2.00527119637,-4.56196737289 --5.90155696869,2.0022752285,-4.57639122009 --5.89355659485,2.00427389145,-4.59879827499 --5.87054729462,2.00127959251,-4.61021375656 --5.86254739761,2.00327801704,-4.63363552094 --5.8325343132,1.99728691578,-4.64005947113 --5.82353162766,1.99628829956,-4.6482758522 --5.81653165817,1.99828636646,-4.67168569565 --5.80553007126,2.00028610229,-4.69311189651 --5.77651786804,1.99429476261,-4.69952869415 --5.75450897217,1.99129962921,-4.71296739578 --5.74250745773,1.99230015278,-4.73237752914 --5.72850322723,1.99230134487,-4.75079631805 --5.7265048027,1.99329972267,-4.76298999786 --5.70449638367,1.99130487442,-4.77541732788 --5.68849182129,1.99030685425,-4.79284524918 --5.66848468781,1.98831117153,-4.80626440048 --5.64847755432,1.98631548882,-4.8196849823 --5.6434803009,1.98931229115,-4.8450961113 --5.61346626282,1.98332130909,-4.8515381813 --5.60246229172,1.98232412338,-4.8567404747 --5.60146713257,1.9873187542,-4.88615894318 --5.58246088028,1.98532235622,-4.90058279037 --5.5564494133,1.98132991791,-4.907995224 --5.54044532776,1.98033201694,-4.92542648315 --5.51943778992,1.97833681107,-4.93784999847 --5.5034327507,1.97733914852,-4.95426797867 --5.49943351746,1.97833824158,-4.96546983719 --5.47542381287,1.97534453869,-4.97590398788 --5.45941925049,1.97434687614,-4.99232339859 --5.43140649796,1.96935546398,-4.99875497818 --5.42440795898,1.97235310078,-5.02215909958 --5.3993973732,1.96836018562,-5.03058242798 --5.38839673996,1.97035956383,-5.05200910568 --5.37238883972,1.96736514568,-5.05322551727 --5.36438989639,1.96936297417,-5.07664060593 --5.34938669205,1.9693646431,-5.09406280518 --5.32637691498,1.966370821,-5.1034784317 --5.31237411499,1.96737194061,-5.12190246582 --5.29236745834,1.9653762579,-5.1353354454 --5.26335334778,1.95938587189,-5.13976383209 --5.24934673309,1.9573905468,-5.14095973969 --5.23334264755,1.95739257336,-5.15839719772 --5.21533679962,1.95539605618,-5.17282056808 --5.20433616638,1.95739555359,-5.19323301315 --5.1833281517,1.95540070534,-5.20465707779 --5.1553144455,1.95040977001,-5.21009397507 --5.15631961823,1.95340573788,-5.22629404068 --5.14732074738,1.95640385151,-5.24971961975 --5.13031625748,1.95540678501,-5.26413106918 --5.12632131577,1.96040201187,-5.29154109955 --5.09830760956,1.95541131496,-5.29596805573 --5.07129478455,1.95042014122,-5.30139732361 --5.07230472565,1.95741200447,-5.33481645584 --5.04228925705,1.95242261887,-5.33724880219 --5.02628087997,1.94842863083,-5.33746623993 --5.01828384399,1.95242583752,-5.36188793182 --5.00728368759,1.95342516899,-5.38229703903 --4.96826076508,1.94444167614,-5.37472867966 --4.96526765823,1.94943583012,-5.40414476395 --4.94025611877,1.94544363022,-5.41056728363 --4.92724990845,1.94344782829,-5.41378641129 --4.92425727844,1.94944190979,-5.44320011139 --4.90024662018,1.94544911385,-5.45062303543 --4.87823724747,1.94345498085,-5.46105861664 --4.85923099518,1.94245910645,-5.47347831726 --4.8382229805,1.94046461582,-5.48390054703 --4.81821537018,1.93846952915,-5.49532270432 --4.81621932983,1.9414665699,-5.51054048538 --4.79621171951,1.93947124481,-5.52196264267 --4.77320194244,1.93747806549,-5.53039121628 --4.75719833374,1.93748044968,-5.54580783844 --4.73018455505,1.93248999119,-5.54923295975 --4.71618270874,1.93349087238,-5.56765890121 --4.69717645645,1.93249499798,-5.58008241653 --4.69517946243,1.93549215794,-5.59428501129 --4.66816616058,1.93050158024,-5.59872627258 --4.65516519547,1.9325016737,-5.61815023422 --4.63015317917,1.92851030827,-5.6225643158 --4.61314868927,1.92851305008,-5.63799762726 --4.5981464386,1.92951452732,-5.65441322327 --4.57513570786,1.92652177811,-5.66183757782 --4.56513261795,1.92552411556,-5.66805839539 --4.55413389206,1.92852282524,-5.68947601318 --4.52511787415,1.92353415489,-5.68990659714 --4.50110578537,1.91954219341,-5.6953253746 --4.49311065674,1.92353868484,-5.72074556351 --4.47210216522,1.92254447937,-5.73016834259 --4.45509767532,1.92254734039,-5.74459123611 --4.4490981102,1.9235470295,-5.75480079651 --4.42208337784,1.91855728626,-5.75723218918 --4.41008424759,1.92055642605,-5.77765083313 --4.4000878334,1.92455399036,-5.80107402802 --4.36306238174,1.9155715704,-5.79151964188 --4.35006189346,1.91657173634,-5.80992937088 --4.34506368637,1.91857039928,-5.82214641571 --4.3110408783,1.91058635712,-5.81457471848 --4.30004310608,1.91358482838,-5.83598899841 --4.30005788803,1.92257428169,-5.87341690063 --4.25902748108,1.91059565544,-5.85685443878 --4.24402523041,1.91159713268,-5.8732714653 --4.22301721573,1.91060316563,-5.88270235062 --4.20801448822,1.91160452366,-5.8991189003 --4.19300556183,1.90861105919,-5.89834213257 --4.18501186371,1.91360664368,-5.92476320267 --4.15899753571,1.90961658955,-5.92719364166 --4.14399576187,1.910618186,-5.94361066818 --4.12599086761,1.91062164307,-5.95704030991 --4.1029791832,1.90762960911,-5.96246004105 --4.09297561646,1.90663218498,-5.96767425537 --4.07897567749,1.90863263607,-5.98609733582 --4.05896759033,1.90763819218,-5.99551534653 --4.03996181488,1.90664231777,-6.00795078278 --4.02195644379,1.90664613247,-6.02037096024 --4.0029501915,1.90665066242,-6.03179645538 --3.97593402863,1.90166187286,-6.03223085403 --3.97193789482,1.90465962887,-6.04543685913 --3.94792580605,1.90166807175,-6.05087852478 --3.93192315102,1.90267014503,-6.06630039215 --3.91291689873,1.90167462826,-6.07772636414 --3.88790273666,1.89868497849,-6.07914495468 --3.86388993263,1.89569377899,-6.08358001709 --3.85689902306,1.90068793297,-6.11199188232 --3.83187556267,1.89270412922,-6.09421205521 --3.82188153267,1.89670038223,-6.11964035034 --3.80187344551,1.89570605755,-6.12906455994 --3.78386855125,1.89570987225,-6.14148759842 --3.76185870171,1.89471697807,-6.14892530441 --3.7458562851,1.89571905136,-6.16434621811 --3.72885298729,1.89572179317,-6.17877292633 --3.71584558487,1.89472687244,-6.17999982834 --3.69984340668,1.89572894573,-6.1954202652 --3.67582941055,1.89173877239,-6.19683170319 --3.65782570839,1.89274203777,-6.21127605438 --3.64082193375,1.89374506474,-6.22469329834 --3.61380434036,1.88875722885,-6.22312736511 --3.60980916023,1.89175438881,-6.23733520508 --3.58279156685,1.88676667213,-6.23577165604 --3.56678962708,1.88876855373,-6.25119256973 --3.54678201675,1.88777422905,-6.2606215477 --3.53178119659,1.88977539539,-6.27703475952 --3.51477861404,1.89077782631,-6.29247140884 --3.49377012253,1.88978421688,-6.30090761185 --3.47875785828,1.88579237461,-6.29611539841 --3.45875072479,1.88579809666,-6.30554580688 --3.44374990463,1.88679909706,-6.3219575882 --3.42674708366,1.88880181313,-6.33638477325 --3.39972925186,1.88381421566,-6.33483076096 --3.38372802734,1.88581585884,-6.35125923157 --3.36672520638,1.88681840897,-6.36568546295 --3.34770679474,1.88083100319,-6.3539018631 --3.32870030403,1.8808362484,-6.36331748962 --3.31470251083,1.8838353157,-6.38374757767 --3.30070447922,1.88683497906,-6.40316772461 --3.27268385887,1.88084948063,-6.39760112762 --3.25467944145,1.88185310364,-6.41002702713 --3.22866201401,1.87786543369,-6.4084649086 --3.21465158463,1.87487268448,-6.40568399429 --3.20766544342,1.88186442852,-6.43809747696 --3.1856546402,1.88087248802,-6.44352960587 --3.16364383698,1.87888038158,-6.44896316528 --3.1406314373,1.87688958645,-6.45239782333 --3.12062311172,1.8758957386,-6.46082353592 --3.10562467575,1.87889587879,-6.47924852371 --3.09261441231,1.87590289116,-6.47645330429 --3.07360911369,1.87690734863,-6.48788833618 --3.04859232903,1.87291944027,-6.48631763458 --3.03259181976,1.87492072582,-6.5027422905 --3.01058077812,1.8729288578,-6.50817966461 --2.98856949806,1.87193727493,-6.51260900497 --2.96655678749,1.8699464798,-6.51502323151 --2.96356773376,1.87494015694,-6.53625440598 --2.94255781174,1.87294745445,-6.54268312454 --2.92455434799,1.87495112419,-6.55510854721 --2.90554785728,1.8749563694,-6.56452655792 --2.88353610039,1.87296497822,-6.56895828247 --2.87154555321,1.87796032429,-6.59639596939 --2.85452795029,1.87297213078,-6.58561515808 --2.82750487328,1.86798787117,-6.57703447342 --2.81250810623,1.8709871769,-6.59746932983 --2.78348135948,1.86500537395,-6.58489608765 --2.76347303391,1.86401188374,-6.59231853485 --2.74747443199,1.86701238155,-6.61075496674 --2.72445964813,1.8640229702,-6.6111779213 --2.7084441185,1.86003351212,-6.60341024399 --2.69745540619,1.86602771282,-6.63183116913 --2.66441845894,1.85605227947,-6.60825634003 --2.64140439034,1.85406255722,-6.60969114304 --2.62440276146,1.85606503487,-6.62411499023 --2.60038542747,1.85207700729,-6.62254667282 --1.73099446297,1.83939218521,-6.88786077499 --1.71600532532,1.84538793564,-6.91429042816 --1.69700181484,1.84739232063,-6.92572069168 --1.66896522045,1.83841609955,-6.90416240692 --1.66598773003,1.84740412235,-6.93437147141 --1.64096057415,1.84142231941,-6.9218006134 --1.62095451355,1.8424282074,-6.93124103546 --1.60596859455,1.85042238235,-6.96067762375 --1.580940485,1.84444117546,-6.94710540771 --1.55892431736,1.84245312214,-6.94553232193 --1.53891777992,1.84345948696,-6.95396661758 --1.52790784836,1.84146618843,-6.95117092133 --1.50991094112,1.8454669714,-6.96961069107 --1.48689222336,1.84248030186,-6.96604967117 --1.46588015556,1.8424898386,-6.96847724915 --1.44989144802,1.84848582745,-6.99490976334 --1.42486131191,1.84250581264,-6.9793381691 --1.39882969856,1.83652675152,-6.96278572083 --1.38581168652,1.83253848553,-6.95199918747 --1.37082624435,1.83953237534,-6.98142147064 --1.34579753876,1.83355164528,-6.9678645134 --1.3257894516,1.83455896378,-6.97429132462 --1.30477702618,1.833568573,-6.97672176361 --1.28075158596,1.82958602905,-6.96616172791 --1.26074326038,1.82959330082,-6.97258853912 --1.25174427032,1.83159410954,-6.9808011055 --1.22972607613,1.82960724831,-6.97723007202 --1.20871555805,1.82961606979,-6.9816699028 --1.18770301342,1.82862579823,-6.98410177231 --1.16367554665,1.82364428043,-6.97154092789 --1.1486954689,1.8326356411,-7.00596666336 --1.12768781185,1.83364284039,-7.01341676712 --1.11466407776,1.82865774632,-6.9966211319 --1.09063351154,1.82267796993,-6.98105430603 --1.07566106319,1.83366513252,-7.0235004425 --1.05464804173,1.83367538452,-7.02492952347 --1.03363776207,1.83368420601,-7.02936887741 --1.01463401318,1.83568906784,-7.03978586197 --0.991613149643,1.83270394802,-7.03423404694 --0.983619809151,1.83670151234,-7.04743671417 --0.963614583015,1.83770740032,-7.05686998367 --0.9395840168,1.83272778988,-7.04131031036 --0.918570756912,1.83173811436,-7.042740345 --0.897559523582,1.83174741268,-7.04617738724 --0.876548230648,1.83175683022,-7.0496134758 --0.865534484386,1.82976603508,-7.04281902313 --0.842511594296,1.82678210735,-7.0352678299 --0.819476425648,1.81980466843,-7.01468420029 --0.797458648682,1.8178178072,-7.01212835312 --0.782496631145,1.83179962635,-7.06356477737 --0.760475218296,1.82881462574,-7.05699729919 --0.737441778183,1.82283639908,-7.03842353821 --0.728452861309,1.82783186436,-7.05665111542 --0.70642966032,1.82484805584,-7.04808187485 --0.686423897743,1.82685434818,-7.05651140213 --0.665409743786,1.82586550713,-7.05694246292 --0.643388152122,1.82288062572,-7.05038022995 --0.621363759041,1.81989741325,-7.04081296921 --0.601367592812,1.82389855385,-7.05926132202 --0.590353429317,1.82190799713,-7.05247449875 --0.569333553314,1.819922328,-7.04689645767 --0.549331843853,1.82292664051,-7.05933189392 --0.511229336262,1.79898786545,-6.98198080063 --0.488187044859,1.79101443291,-6.95541620255 --0.466150105,1.78403794765,-6.93384122849 --0.457165598869,1.79003119469,-6.95606660843 --0.438167452812,1.79403340816,-6.9714884758 --0.416142463684,1.79105055332,-6.96193552017 --0.394105225801,1.78407430649,-6.94036626816 --0.374094545841,1.78508353233,-6.94379281998 --0.353081047535,1.78509449959,-6.94523668289 --0.333072245121,1.78610253334,-6.9506649971 --0.323066323996,1.78610742092,-6.95187664032 --0.303064644337,1.78911185265,-6.96431207657 --0.283072292805,1.79511129856,-6.98575592041 --0.262062013149,1.7961204052,-6.99020051956 --0.241035267711,1.7921384573,-6.97863006592 --0.221020400524,1.79114985466,-6.97805023193 --0.199998825788,1.7891651392,-6.97148656845 --0.188963353634,1.78118598461,-6.94469738007 --0.16795925796,1.78419208527,-6.95514965057 --0.147953733802,1.78619849682,-6.96357727051 --0.12795458734,1.79020178318,-6.97800827026 --0.106947511435,1.79220938683,-6.98545503616 --0.0869433805346,1.79521536827,-6.99488067627 --0.0759148076177,1.78923249245,-6.9751033783 --0.0548834502697,1.78425300121,-6.95954084396 --0.0348622947931,1.78226792812,-6.95296192169 --0.0138352159411,1.77928626537,-6.94140386581 -0.00618406198919,1.77730023861,-6.93682718277 --0.0011648319196,1.76870238781,-6.12224149704 -0.0188331529498,1.76469516754,-6.10762929916 -0.0298343542963,1.76269245148,-6.10184288025 -0.0498558357358,1.76569759846,-6.10922527313 -0.0708764865994,1.76670229435,-6.11562776566 -0.0908934772015,1.7677052021,-6.11901140213 -0.1119165048,1.77071094513,-6.12741041183 -0.131923958659,1.76870882511,-6.12179851532 -0.152929246426,1.76670527458,-6.11320829391 -0.162924557924,1.76269984245,-6.10240888596 -0.182929262519,1.76069617271,-6.09380149841 -0.201918676496,1.75368487835,-6.07118797302 -0.223970174789,1.76470553875,-6.10658216476 -0.243963465095,1.75869596004,-6.08698749542 -0.263965249062,1.75569081306,-6.07538604736 -0.283980369568,1.75669276714,-6.07677173615 -0.294997006655,1.75869834423,-6.0859746933 -0.31500595808,1.75769710541,-6.081366539 -0.335009753704,1.75469315052,-6.0717663765 -0.356028586626,1.75669682026,-6.07616758347 -0.378072172403,1.76571333408,-6.10455369949 -0.398085057735,1.76571416855,-6.10394001007 -0.41808193922,1.76070654392,-6.08735084534 -0.427082151175,1.75870406628,-6.08153390884 -0.446072697639,1.75269317627,-6.05893754959 -0.468106001616,1.7587044239,-6.07733297348 -0.489122658968,1.75970697403,-6.07973527908 -0.509133577347,1.7587069273,-6.07712650299 -0.530153393745,1.76171112061,-6.0825214386 -0.54015827179,1.76071071625,-6.0807185173 -0.560164391994,1.75870811939,-6.07311964035 -0.579163074493,1.7547018528,-6.05851602554 -0.599171340466,1.75370025635,-6.05291461945 -0.620192110538,1.75670492649,-6.05930709839 -0.639191865921,1.75269913673,-6.04570531845 -0.659204006195,1.75269973278,-6.04409646988 -0.671226859093,1.75770843029,-6.05929327011 -0.690230488777,1.75470483303,-6.0496840477 -0.710233330727,1.75270020962,-6.03809833527 -0.730249285698,1.75370287895,-6.04047966003 -0.748241186142,1.74769318104,-6.01888370514 -0.7702652812,1.75169968605,-6.02828502655 -0.791284739971,1.75370383263,-6.03367710114 -0.798263430595,1.74569034576,-6.00588846207 -0.819286584854,1.74869668484,-6.01526975632 -0.840306222439,1.75170099735,-6.02066087723 -0.858302175999,1.74669349194,-6.00306081772 -0.880324184895,1.74969887733,-6.01046466827 -0.900337278843,1.74970006943,-6.00985383987 -0.920345067978,1.74869835377,-6.00326108932 -0.928338944912,1.74569261074,-5.99045610428 -0.949358284473,1.74769687653,-5.99584579468 -0.970373988152,1.74869918823,-5.99724721909 -0.988371372223,1.74469256401,-5.98065042496 -1.01039326191,1.7476978302,-5.98805093765 -1.02638304234,1.74168777466,-5.96444177628 -1.04639565945,1.74268853664,-5.96283435822 -1.05840945244,1.74469256401,-5.96904468536 -1.0794262886,1.74669539928,-5.97144174576 -1.09541451931,1.73968446255,-5.94584608078 -1.11744058132,1.74369215965,-5.95822525024 -1.13745129108,1.74369204044,-5.95462560654 -1.15344178677,1.73768222332,-5.93102645874 -1.17646944523,1.74269044399,-5.94441843033 -1.1844637394,1.7396851778,-5.9316239357 -1.20648396015,1.74268949032,-5.93702697754 -1.22951221466,1.74769818783,-5.95141124725 -1.24349367619,1.7386841774,-5.9188170433 -1.26250123978,1.73768270016,-5.91221189499 -1.28653180599,1.74369239807,-5.92860412598 -1.29251587391,1.7376819849,-5.90482282639 -1.31052017212,1.73567914963,-5.8952126503 -1.33454823494,1.7406873703,-5.90861606598 -1.35154700279,1.73768174648,-5.89301395416 -1.36955142021,1.73567903042,-5.88340473175 -1.39257526398,1.73968541622,-5.89280462265 -1.40957415104,1.7366797924,-5.87720441818 -1.41957962513,1.73667991161,-5.87540578842 -1.44159924984,1.73868429661,-5.88080358505 -1.45960223675,1.73668074608,-5.86920547485 -1.47660279274,1.73367619514,-5.85559988022 -1.4986218214,1.73668026924,-5.86000013351 -1.51863372326,1.73768091202,-5.85739660263 -1.53764081001,1.73667931557,-5.84980010986 -1.54764699936,1.73667991161,-5.84899568558 -1.56765723228,1.7366797924,-5.84440326691 -1.58566188812,1.73467731476,-5.83479881287 -1.60667860508,1.73768019676,-5.83718729019 -1.62568509579,1.73667836189,-5.82859706879 -1.6446928978,1.73567724228,-5.82199668884 -1.66370093822,1.73467636108,-5.8153963089 -1.6777203083,1.73968291283,-5.82759523392 -1.692715168,1.73467600346,-5.80799150467 -1.71473407745,1.73767983913,-5.81238555908 -1.73474669456,1.73868119717,-5.81077528 -1.75375473499,1.73868024349,-5.80417442322 -1.7747695446,1.73968243599,-5.80457115173 -1.79477906227,1.73968207836,-5.79898309708 -1.80378329754,1.73968172073,-5.79617071152 -1.81877875328,1.7356749773,-5.77657318115 -1.83979213238,1.73667645454,-5.77498102188 -1.85779738426,1.73567414284,-5.76538085938 -1.87580347061,1.73467254639,-5.75677537918 -1.88678598404,1.72665977478,-5.72319602966 -1.89579021931,1.72665953636,-5.72038507462 -1.91780793667,1.7286632061,-5.72378063202 -1.93581414223,1.72766149044,-5.71517801285 -1.94980740547,1.72265386581,-5.69259119034 -1.97282743454,1.72665846348,-5.69799089432 -1.99384307861,1.72866117954,-5.69937896729 -2.817278862,1.76167821884,-5.50499343872 -2.83728933334,1.76267886162,-5.50038766861 -2.85930323601,1.76468074322,-5.49878978729 -2.87430477142,1.76267755032,-5.484187603 -2.89030766487,1.76167488098,-5.47059440613 -2.89730644226,1.75967252254,-5.46080875397 -2.91831946373,1.76167416573,-5.459192276 -2.94333815575,1.76567792892,-5.46259641647 -2.95934128761,1.76467573643,-5.44999456406 -2.98536109924,1.76867985725,-5.45440483093 -3.00436997414,1.76967990398,-5.44779729843 -3.02237653732,1.7696788311,-5.43820047379 -3.0243678093,1.76567339897,-5.42040777206 -3.04638195038,1.76767575741,-5.41979408264 -3.06939649582,1.77067756653,-5.41820573807 -3.08540010452,1.76967561245,-5.40560483932 -3.10040140152,1.76767241955,-5.39001703262 -3.11640501022,1.76667034626,-5.37741708755 -3.13242006302,1.77067446709,-5.38560962677 -3.15343141556,1.77267551422,-5.38101387024 -3.17043685913,1.77167415619,-5.37041139603 -3.19645595551,1.77667796612,-5.37381839752 -3.2044467926,1.77067089081,-5.34722518921 -3.23146724701,1.77567541599,-5.35262775421 -3.24847245216,1.77567386627,-5.34103393555 -3.2564740181,1.77467286587,-5.33423948288 -3.27548313141,1.7756729126,-5.32762861252 -3.29649424553,1.77767395973,-5.32302951813 -3.31850671768,1.77967524529,-5.3194360733 -3.33651351929,1.77967453003,-5.30983829498 -3.34049892426,1.77166545391,-5.27626132965 -3.36752009392,1.77767026424,-5.28264427185 -3.36851143837,1.77266538143,-5.26485157013 -3.39653229713,1.77866983414,-5.27025938034 -3.41353869438,1.77866899967,-5.26064538956 -3.44356226921,1.7856746912,-5.26905012131 -3.45055365562,1.77966809273,-5.24245500565 -3.46956181526,1.78066778183,-5.23386240005 -3.49557948112,1.78467130661,-5.23626327515 -3.51059103012,1.7876740694,-5.24046325684 -3.5215883255,1.78466975689,-5.21987009048 -3.53358721733,1.78166604042,-5.20127296448 -3.55459785461,1.78366684914,-5.1956782341 -3.56759810448,1.78166377544,-5.1780872345 -3.58360242844,1.78066217899,-5.16549015045 -3.59961557388,1.78466558456,-5.17167949677 -3.62363004684,1.78766775131,-5.17008638382 -3.64564204216,1.79066896439,-5.16549253464 -3.65163373947,1.78466284275,-5.13889408112 -3.67965340614,1.79066705704,-5.1432929039 -3.69665932655,1.79066598415,-5.13169908524 -3.71867084503,1.7926671505,-5.1271033287 -3.73568463326,1.79667067528,-5.13429069519 -3.76270270348,1.80167412758,-5.13669061661 -3.76168513298,1.7926646471,-5.09812450409 -3.78369760513,1.79566609859,-5.09451532364 -3.81872582436,1.80467319489,-5.10889720917 -3.8167078495,1.79466378689,-5.07032155991 -3.8437256813,1.79966723919,-5.07271671295 -3.85473132133,1.80066776276,-5.0699224472 -3.86873316765,1.79966533184,-5.05333900452 -3.88473844528,1.79966425896,-5.04172754288 -3.90574812889,1.80066478252,-5.03414583206 -3.91574573517,1.79766118526,-5.01355028152 -3.94877004623,1.80566680431,-5.02294635773 -3.96377396584,1.80466520786,-5.00934314728 -3.96176457405,1.79966056347,-4.98955440521 -3.97877001762,1.79965960979,-4.97697067261 -4.01780128479,1.8106675148,-4.99435377121 -4.03180360794,1.80966556072,-4.97875881195 -4.03779745102,1.8046605587,-4.95316743851 -4.05680465698,1.80566048622,-4.94357585907 -4.07080793381,1.80465853214,-4.927983284 -4.08581733704,1.80666041374,-4.92919588089 -4.10882997513,1.81066203117,-4.92558717728 -4.11982917786,1.80765902996,-4.90600013733 -4.13583421707,1.80765807629,-4.89339971542 -4.16084814072,1.81166017056,-4.89080619812 -4.1748509407,1.8106584549,-4.87521409988 -4.19385910034,1.81165838242,-4.86561918259 -4.20987033844,1.81566095352,-4.86980295181 -4.2228717804,1.8136588335,-4.85222101212 -4.23086833954,1.80965483189,-4.82864427567 -4.26288986206,1.81665933132,-4.83503246307 -4.27288866043,1.81465637684,-4.81444597244 -4.28789281845,1.81365513802,-4.79985666275 -4.31091022491,1.82065963745,-4.81104564667 -4.31190013885,1.81365394592,-4.78046131134 -4.3369140625,1.81765592098,-4.77785873413 -4.34891557693,1.81565392017,-4.7602648735 -4.36191749573,1.8146520853,-4.74367284775 -4.35189723969,1.80264317989,-4.70011091232 -4.33787441254,1.79063332081,-4.6535358429 -4.29482841492,1.76761758327,-4.58977794647 -4.26579189301,1.74860346317,-4.52622890472 -4.23575496674,1.72858965397,-4.46267414093 -4.23174285889,1.72058355808,-4.42810487747 -4.23673915863,1.71558046341,-4.40451717377 -4.25274610519,1.71658062935,-4.39292287827 -4.2517375946,1.70957589149,-4.36234951019 -4.25773954391,1.70957541466,-4.35455179214 -4.27474784851,1.71057605743,-4.34494495392 -4.28074550629,1.70657336712,-4.32137775421 -4.28974628448,1.70457172394,-4.3027844429 -4.3037519455,1.70457160473,-4.29017782211 -4.31375360489,1.70257019997,-4.27061510086 -4.31174850464,1.69856786728,-4.25481987 -4.32475328445,1.69756734371,-4.24022960663 -4.32274532318,1.6905632019,-4.21064329147 -4.33374834061,1.68956243992,-4.19405555725 -4.35476016998,1.69256412983,-4.18746328354 -4.36376142502,1.69056296349,-4.16887664795 -4.37476539612,1.68956232071,-4.15327453613 -4.37276077271,1.68556010723,-4.13650226593 -4.38076210022,1.68355882168,-4.11790418625 -4.38876247406,1.68055737019,-4.09733772278 -4.41077518463,1.68355953693,-4.09272861481 -4.41877698898,1.68155825138,-4.07314729691 -4.41877174377,1.6755553484,-4.04656219482 -4.43477964401,1.67655611038,-4.03595876694 -4.43677806854,1.67455506325,-4.02318811417 -4.45178604126,1.67555570602,-4.01158571243 -4.46178913116,1.67455518246,-3.99499106407 -4.46878957748,1.67155396938,-3.97441697121 -4.47779226303,1.66955339909,-3.9568259716 -4.48479366302,1.66655230522,-3.93723917007 -4.49779987335,1.66655266285,-3.92364192009 -4.50280094147,1.66655242443,-3.91485357285 -4.5148062706,1.66555261612,-3.90025877953 -4.52481031418,1.66455233097,-3.88366794586 -4.53981781006,1.66555321217,-3.87108278275 -4.54281616211,1.66155147552,-3.84750938416 -4.55282020569,1.660551548,-3.8319041729 -4.56182289124,1.65855109692,-3.81333494186 -4.57383012772,1.66055250168,-3.81153154373 -4.58983898163,1.66155350208,-3.79994416237 -4.58783435822,1.65655124187,-3.77335643768 -4.59783840179,1.65555119514,-3.75677037239 -4.60984420776,1.65455162525,-3.74119520187 -4.6158452034,1.65255117416,-3.72258877754 -4.62585115433,1.65355205536,-3.71780586243 -4.64386129379,1.65555357933,-3.70919632912 -4.65186405182,1.65455341339,-3.69061732292 -4.65986728668,1.65255343914,-3.6730234623 -4.6688709259,1.65055334568,-3.65446019173 -4.67487287521,1.6485530138,-3.63585758209 -4.69788599014,1.65255558491,-3.63026165962 -4.69888591766,1.65055501461,-3.61945962906 -4.70588827133,1.64855480194,-3.59988856316 -4.71088981628,1.64555442333,-3.5793094635 -4.72089481354,1.64555490017,-3.56371116638 -4.72989940643,1.64455533028,-3.54711794853 -4.74690818787,1.64555680752,-3.53554296494 -4.7509098053,1.64255654812,-3.51495432854 -4.75591230392,1.64255678654,-3.50715589523 -4.76291561127,1.6405569315,-3.48857307434 -4.76791763306,1.63755691051,-3.46799993515 -4.78292608261,1.63955819607,-3.45541596413 -4.80193662643,1.64156019688,-3.44681358337 -4.80593824387,1.63956010342,-3.42622923851 -4.80893945694,1.63555979729,-3.40465164185 -4.81094026566,1.63455986977,-3.39485168457 -4.81694316864,1.63256025314,-3.3752784729 -4.83095121384,1.63356149197,-3.36366510391 -4.84295797348,1.63356256485,-3.34809684753 -4.85096216202,1.63256335258,-3.33149695396 -4.85896635056,1.63156402111,-3.31391501427 -4.85596466064,1.62756347656,-3.30012774467 -4.86997270584,1.62956500053,-3.2875316143 -4.86697149277,1.62456452847,-3.26196026802 -4.88798332214,1.62756669521,-3.25436043739 -4.90099096298,1.62756812572,-3.23978805542 -4.91299819946,1.62856948376,-3.22618508339 -4.91900157928,1.62657022476,-3.20760035515 -4.91399908066,1.62256968021,-3.19281196594 -4.91700124741,1.6205701828,-3.17222952843 -4.95902490616,1.63157463074,-3.17862057686 -4.95602369308,1.6265745163,-3.15403962135 -4.95402336121,1.62157464027,-3.12947320938 -4.96703147888,1.62257611752,-3.1158823967 -4.97103404999,1.62057685852,-3.09629678726 -4.96703290939,1.61657679081,-3.082508564 -4.99204730988,1.62157952785,-3.07592868805 -4.98804616928,1.61657965183,-3.05134487152 -4.99305009842,1.61558055878,-3.03275537491 -5.0050573349,1.61558222771,-3.01915407181 -5.0030579567,1.61158275604,-2.99459815025 -5.01606607437,1.61258435249,-2.98198986053 -5.03307533264,1.61658620834,-2.98120141029 -5.03007507324,1.61158668995,-2.95761823654 -5.03708028793,1.61058807373,-2.94003605843 -5.05008840561,1.6115899086,-2.926445961 -5.04608869553,1.60659050941,-2.90187478065 -5.05609560013,1.60659217834,-2.88628983498 -5.06610155106,1.60859334469,-2.88149547577 -5.07110595703,1.60659480095,-2.86291265488 -5.07911205292,1.60659635067,-2.84632492065 -5.08211565018,1.60359764099,-2.82674050331 -5.07911682129,1.59959852695,-2.8041498661 -5.0921254158,1.60060060024,-2.78957986832 -5.10913515091,1.6036028862,-2.77897524834 -5.10413455963,1.60060322285,-2.76519179344 -5.10913944244,1.59860479832,-2.74661374092 -5.11514472961,1.59760642052,-2.72902703285 -5.12115049362,1.59660828114,-2.71144104004 -5.12115335464,1.59260964394,-2.68987107277 -5.14516687393,1.59761238098,-2.68325972557 -5.1441693306,1.59461379051,-2.66167998314 -5.14016914368,1.59161448479,-2.64889359474 -5.1481757164,1.59161639214,-2.63231110573 -5.15218067169,1.58961820602,-2.61372756958 -5.15918684006,1.58862018585,-2.59713578224 -5.17719841003,1.59162271023,-2.58555674553 -5.17420005798,1.58762431145,-2.56298279762 -5.1762046814,1.58562612534,-2.5443816185 -5.19121265411,1.58862769604,-2.54159212112 -5.1892156601,1.5856294632,-2.52001094818 -5.19122028351,1.58363139629,-2.50043129921 -5.20823049545,1.58663403988,-2.48883986473 -5.20923519135,1.58363604546,-2.46827173233 -5.21524143219,1.58263814449,-2.45167303085 -5.2162437439,1.58163928986,-2.44188451767 -5.21824884415,1.57964134216,-2.42230820656 -5.22325468063,1.57864367962,-2.40472126007 -5.25226974487,1.58564651012,-2.39912009239 -5.25027370453,1.58164870739,-2.37754774094 -5.24627590179,1.57765066624,-2.35595774651 -5.25628471375,1.57865333557,-2.34037804604 -5.25328540802,1.57665431499,-2.32859516144 -5.25829219818,1.57565677166,-2.31101059914 -5.27730321884,1.57865953445,-2.30041217804 -5.27930879593,1.57666194439,-2.28084111214 -5.27731275558,1.57366430759,-2.26025509834 -5.28532028198,1.57366704941,-2.24367856979 -5.28032064438,1.57066810131,-2.2318816185 -5.29333019257,1.57267069817,-2.21828842163 -5.29833745956,1.57167339325,-2.19972681999 -5.30934619904,1.57267618179,-2.18513607979 -5.30835103989,1.56967866421,-2.16554355621 -5.32436132431,1.57268154621,-2.15295410156 -5.31936454773,1.56868422031,-2.13136982918 -5.31836700439,1.56668555737,-2.12059164047 -5.33437824249,1.56968832016,-2.10800123215 -5.32938146591,1.56569123268,-2.0864200592 -5.33338832855,1.56469404697,-2.06785368919 -5.33739519119,1.56369698048,-2.05026698112 -5.3484044075,1.56469976902,-2.03567552567 -5.35341119766,1.56370282173,-2.01809740067 -5.35741567612,1.56370425224,-2.01029968262 -5.36242294312,1.56370723248,-1.99272179604 -5.3654294014,1.56271016598,-1.97512805462 -5.367436409,1.56071317196,-1.95654857159 -5.36744213104,1.55871641636,-1.93697464466 -5.37745141983,1.55971944332,-1.92139613628 -5.38645982742,1.55972242355,-1.90580928326 -5.39746618271,1.56272387505,-1.90100204945 -5.39447164536,1.55972707272,-1.88042807579 -5.39047622681,1.5567303896,-1.85984754562 -5.39748477936,1.55673360825,-1.84326696396 -5.40549278259,1.55673670769,-1.82767248154 -5.41550254822,1.55773997307,-1.81209290028 -5.42150783539,1.55874168873,-1.80430996418 -5.41351175308,1.55374503136,-1.7827256918 -5.42352104187,1.55474829674,-1.76714611053 -5.42352724075,1.55375170708,-1.7485575676 -5.42853546143,1.55275523663,-1.73098492622 -5.43854475021,1.55375850201,-1.7154045105 -5.44955444336,1.55576169491,-1.70080888271 -5.44755744934,1.55376338959,-1.69101250172 -5.43956279755,1.5497674942,-1.66845786572 -5.44657087326,1.54977071285,-1.65285670757 -5.45157909393,1.54977440834,-1.63528501987 -5.46258926392,1.55177760124,-1.62068867683 -5.45959568024,1.54878139496,-1.60110723972 -5.46360349655,1.54778516293,-1.58352982998 -5.46660804749,1.54778707027,-1.57474780083 -5.47961854935,1.54979038239,-1.56016385555 -5.46862268448,1.54479444027,-1.53857696056 -5.4796333313,1.5467979908,-1.52300143242 -5.48464107513,1.54680168629,-1.50640928745 -5.490650177,1.54680538177,-1.48982357979 -5.48465633392,1.54380953312,-1.46925115585 -5.48566055298,1.54281151295,-1.46045744419 -5.49466991425,1.54381501675,-1.44486880302 -5.50367927551,1.54481875896,-1.42927956581 -5.5076880455,1.54482269287,-1.41170394421 -5.50669574738,1.54282677174,-1.39312136173 -5.5137052536,1.54383051395,-1.37654185295 -5.51871013641,1.5438324213,-1.36874997616 -5.51371669769,1.54183673859,-1.34916758537 -5.52872800827,1.54384028912,-1.33458948135 -5.53373670578,1.54384422302,-1.31799817085 -5.53274488449,1.54284858704,-1.29941785336 -5.52275085449,1.53785347939,-1.27785682678 -5.53876209259,1.54185676575,-1.26425898075 -5.54876804352,1.54385840893,-1.25747048855 -5.55277776718,1.54386270046,-1.23989617825 -5.54878425598,1.54086720943,-1.22130262852 -5.54779243469,1.53887152672,-1.20272600651 -5.56280374527,1.54287528992,-1.18814146519 -5.54880952835,1.53688049316,-1.16656720638 -5.54981851578,1.5358850956,-1.14800274372 -5.57382726669,1.54288578033,-1.14518976212 -5.56583404541,1.5388906002,-1.1256030798 -5.56284236908,1.53689563274,-1.10604202747 -5.57185268402,1.53789949417,-1.09044849873 -5.56185913086,1.53390479088,-1.0698786974 -5.58087110519,1.53790819645,-1.05628573895 -5.59188222885,1.53991210461,-1.04069960117 -5.57888412476,1.53591537476,-1.02891373634 -5.58689451218,1.5369194746,-1.01233696938 -5.5949048996,1.53792381287,-0.995759606361 -5.58691263199,1.53492903709,-0.976181209087 -5.59292221069,1.53493344784,-0.959595441818 -5.61893558502,1.54193627834,-0.947000741959 -5.59993696213,1.53594017029,-0.934219062328 -5.60194635391,1.53494477272,-0.916639328003 -5.60595655441,1.53494954109,-0.899067640305 -5.6109662056,1.53595399857,-0.882476627827 -5.60297393799,1.53295946121,-0.862904429436 -5.61998605728,1.5369631052,-0.848313510418 -5.61799526215,1.53496837616,-0.829742372036 -5.6189994812,1.53497052193,-0.821929812431 -5.62401008606,1.5349752903,-0.804361820221 -5.61801862717,1.53298068047,-0.785777390003 -5.60802650452,1.52898645401,-0.76620388031 -5.64304065704,1.53798878193,-0.754600226879 -5.62204742432,1.53099560738,-0.733036875725 -5.62305688858,1.53000068665,-0.715456187725 -5.64106416702,1.53500175476,-0.709652662277 -5.63107299805,1.53100776672,-0.690082848072 -5.63008213043,1.5300129652,-0.672496080399 -5.65009498596,1.53501677513,-0.656926572323 -5.63610267639,1.53002309799,-0.637347757816 -5.63711261749,1.5300283432,-0.619767725468 -5.6531252861,1.53403222561,-0.604183375835 -5.63912820816,1.52903604507,-0.593399822712 -5.63713741302,1.52804160118,-0.575812339783 -5.66115045547,1.53404474258,-0.561223745346 -5.64615917206,1.52905142307,-0.541649222374 -5.64116859436,1.52705740929,-0.523078680038 -5.66618156433,1.53406047821,-0.508487761021 -5.63718318939,1.52506577969,-0.496698141098 -5.65019512177,1.52807021141,-0.480124682188 -5.65620565414,1.52907502651,-0.463534086943 -5.66021680832,1.53008031845,-0.445961773396 -5.65522623062,1.52808618546,-0.428370714188 -5.66123771667,1.52909123898,-0.410802662373 -5.65324735641,1.5260976553,-0.392230480909 -5.65425300598,1.52610039711,-0.383442670107 -5.67126512527,1.53010427952,-0.36784774065 -5.67327547073,1.53010976315,-0.350271016359 -5.65828466415,1.52511680126,-0.331689238548 -5.65229511261,1.52312326431,-0.313124209642 -5.66130638123,1.52512800694,-0.296536505222 -5.66031169891,1.52513098717,-0.287745565176 -5.66232252121,1.52513659,-0.270170152187 -5.67133426666,1.52714133263,-0.25358068943 -5.66834449768,1.52614724636,-0.235998094082 -5.66835546494,1.5251531601,-0.218420043588 -5.66336584091,1.52415943146,-0.200836062431 -5.65337610245,1.5201665163,-0.182271659374 -5.67138338089,1.52516758442,-0.174478307366 -5.66739368439,1.52417385578,-0.156896546483 -5.66640472412,1.52318000793,-0.139318466187 -5.66741609573,1.52318584919,-0.121742151678 -5.67642736435,1.52519059181,-0.105148345232 -5.67343854904,1.52419686317,-0.0875687748194 -5.67444992065,1.52420282364,-0.0699921771884 -5.68445587158,1.52720451355,-0.0621856004 -5.66746616364,1.52221262455,-0.0436230488122 -5.66647768021,1.5212187767,-0.026046352461 -5.67348957062,1.52322423458,-0.00847239792347 -5.67350053787,1.52323007584,0.00812784582376 -5.67451190948,1.52323615551,0.0257042050362 -5.67851829529,1.52423870564,0.0344918482006 -5.67352962494,1.52324557304,0.0520692542195 -5.67954158783,1.52425098419,0.0696454271674 -5.66455221176,1.52025902271,0.087221339345 -5.66756391525,1.52026486397,0.104797132313 -5.6715760231,1.52127063274,0.122373737395 -5.67358732224,1.52227640152,0.138974025846 -5.67359304428,1.52227962017,0.14776211977 -5.67560482025,1.52328574657,0.165339171886 -5.66961669922,1.52129268646,0.18291258812 -5.66862821579,1.52029931545,0.200487688184 -5.673640728,1.52230513096,0.218066647649 -5.66765260696,1.52031230927,0.235638573766 -5.66966438293,1.52131843567,0.253215909004 -5.67166996002,1.52132105827,0.261028826237 -5.67168235779,1.52132749557,0.278604835272 -5.66169404984,1.51933538914,0.296171754599 -5.672706604,1.52234041691,0.313758194447 -5.66271829605,1.51934826374,0.331323504448 -5.66073036194,1.51935470104,0.347920507193 -5.66374206543,1.52036094666,0.365499675274 -5.66974830627,1.52136337757,0.374294906855 -5.65776109695,1.51837170124,0.391855210066 -5.66277313232,1.52037763596,0.409437865019 -5.66578578949,1.52138376236,0.427018284798 -5.66179800034,1.52039110661,0.444588303566 -5.65680980682,1.51939809322,0.461179882288 -5.65281677246,1.51840209961,0.46996113658 -5.66482877731,1.52140700817,0.487557470798 -5.66584157944,1.52241361141,0.505136013031 -5.65985393524,1.52042126656,0.522701442242 -5.66786623001,1.52342677116,0.540293812752 -5.66887903214,1.5244332552,0.557873308659 -5.65989208221,1.52144145966,0.575431764126 -5.6538977623,1.52044558525,0.583231091499 -5.65991067886,1.52245140076,0.600821077824 -5.66492366791,1.52445781231,0.61938649416 -5.65393638611,1.52146601677,0.635961890221 -5.64894866943,1.52047348022,0.652550637722 -5.65496206284,1.52247965336,0.671119332314 -5.65497493744,1.52348661423,0.688697338104 -5.66198062897,1.52548885345,0.697504580021 -5.64499425888,1.52049839497,0.7140609622 -5.64700698853,1.521504879,0.7316442132 -5.66101980209,1.52650976181,0.750238597393 -5.63403272629,1.51952040195,0.764810144901 -5.63604545593,1.5205271244,0.782393813133 -5.64505243301,1.52352941036,0.792186498642 -5.64106559753,1.52253711224,0.809753000736 -5.63107872009,1.52054560184,0.826323866844 -5.63909244537,1.52355158329,0.844904839993 -5.62410545349,1.51956069469,0.860481441021 -5.62111854553,1.51956796646,0.877073466778 -5.64213132858,1.52557218075,0.897654175758 -5.61813831329,1.51957917213,0.903431117535 -5.61015224457,1.51758754253,0.920005023479 -5.61916542053,1.52059328556,0.938592970371 -5.60617876053,1.51760232449,0.954171419144 -5.60719203949,1.51860928535,0.971754312515 -5.62220478058,1.52361416817,0.991344928741 -5.5942196846,1.51662552357,1.00490987301 -5.59122657776,1.51562976837,1.01368749142 -5.59823989868,1.51863598824,1.03227174282 -5.58625411987,1.51564502716,1.04784941673 -5.57926797867,1.51465332508,1.06442344189 -5.59428071976,1.51965820789,1.084020257 -5.58329486847,1.51766741276,1.10057735443 -5.58430862427,1.51867461205,1.11816263199 -5.58831548691,1.52067768574,1.12794780731 -5.5683298111,1.5156878233,1.14153289795 -5.56034421921,1.51369667053,1.15810036659 -5.58135700226,1.52070081234,1.17968559265 -5.56137180328,1.51571118832,1.1932669878 -5.558385849,1.51571917534,1.21083438396 -5.56639242172,1.5187214613,1.22064077854 -5.55740690231,1.51673042774,1.23720288277 -5.54042196274,1.51374077797,1.25177097321 -5.55743455887,1.51974534988,1.27236914635 -5.53744983673,1.51475584507,1.28594326973 -5.54346370697,1.51676273346,1.30551064014 -5.53847789764,1.5167709589,1.32209146023 -5.53248500824,1.51577544212,1.32889795303 -5.52349996567,1.51378464699,1.34545636177 -5.54251289368,1.52078914642,1.36705088615 -5.51552867889,1.51380085945,1.3786264658 -5.51754283905,1.51580822468,1.39719879627 -5.53055620193,1.52081370354,1.41778790951 -5.5115647316,1.51582062244,1.422565341 -5.50957965851,1.51582872868,1.44013905525 -5.51759338379,1.51983499527,1.45972549915 -5.51660776138,1.5208427906,1.47730672359 -5.50862312317,1.5198520422,1.49386966228 -5.50663661957,1.51985967159,1.51046788692 -5.49165248871,1.51687002182,1.52503323555 -5.49265956879,1.51787352562,1.53383302689 -5.49967384338,1.52088057995,1.55439567566 -5.48268938065,1.51689052582,1.56699240208 -5.47770500183,1.51689946651,1.58454930782 -5.47971868515,1.51890671253,1.60215103626 -5.46873474121,1.51691639423,1.6177148819 -5.46474933624,1.51692473888,1.63430094719 -5.47875595093,1.52192676067,1.6480743885 -5.47577095032,1.52293491364,1.66466844082 -5.4627866745,1.51994490623,1.67924082279 -5.45780181885,1.5199534893,1.69582104683 -5.46181678772,1.52296090126,1.71539521217 -5.43883323669,1.51697266102,1.72696435452 -5.4508471489,1.52197849751,1.74854981899 -5.44585514069,1.52198338509,1.75633406639 -5.43587017059,1.51999282837,1.77092421055 -5.42288684845,1.51800310612,1.78549230099 -5.42690134048,1.52101051807,1.80506956577 -5.41991662979,1.52001941204,1.82065784931 -5.42293167114,1.52202701569,1.84022951126 -5.41793966293,1.52203190327,1.84801292419 -5.40395593643,1.5190423727,1.86159360409 -5.41297054291,1.52404904366,1.88316750526 -5.39698696136,1.52005946636,1.89575433731 -5.38700294495,1.51906955242,1.9113188982 -5.39601802826,1.52407622337,1.93289613724 -5.39303255081,1.52408444881,1.94949293137 -5.38604068756,1.52308964729,1.95628201962 -5.37905740738,1.52209913731,1.97284734249 -5.38007211685,1.5251070261,1.99143242836 -5.38608694077,1.52811408043,2.0120139122 -5.3721036911,1.52612471581,2.02559041977 -5.35912084579,1.52413535118,2.04015135765 -5.3551363945,1.52414405346,2.05674147606 -5.35614395142,1.5251480341,2.06652808189 -5.34116029739,1.52215850353,2.07911539078 -5.32917737961,1.52116906643,2.09368228912 -5.34119224548,1.52617549896,2.11725401878 -5.33020877838,1.52518510818,2.13085174561 -5.31622552872,1.52219593525,2.14442253113 -5.31923341751,1.5241997242,2.15520644188 -5.3142490387,1.52520871162,2.17178916931 -5.30426692963,1.52421915531,2.18735003471 -5.30728149414,1.52622675896,2.20693802834 -5.30629777908,1.52823531628,2.22551369667 -5.29431438446,1.52624559402,2.23910021782 -5.27333259583,1.52225768566,2.24966979027 -5.27733945847,1.52426111698,2.26046609879 -5.26835680008,1.52427124977,2.276034832 -5.27637195587,1.52827835083,2.29860806465 -5.26638936996,1.52728843689,2.31318950653 -5.24540710449,1.52230036259,2.32277584076 -5.247423172,1.52530872822,2.34333920479 -5.2414317131,1.52531397343,2.35013079643 -5.24044799805,1.52632260323,2.36871004105 -5.24946212769,1.53132939339,2.391299963 -5.23148059845,1.52834117413,2.40286874771 -5.21449899673,1.52535259724,2.41444540024 -5.21551465988,1.52736091614,2.43402481079 -5.20153236389,1.52537178993,2.44660782814 -5.19654130936,1.52537715435,2.4543864727 -5.20155715942,1.52938497066,2.47596502304 -5.18857526779,1.52739584446,2.48953557014 -5.18259191513,1.52740550041,2.50611186028 -5.17760848999,1.52841484547,2.52269887924 -5.15962743759,1.525426507,2.53328108788 -5.16764259338,1.5304338932,2.55685257912 -5.19664716721,1.5404330492,2.5806427002 -5.17566537857,1.53644514084,2.58923697472 -5.15368556976,1.53145802021,2.5987970829 -5.15870046616,1.53546559811,2.62038588524 -5.14171934128,1.53247737885,2.63195466995 -5.13573694229,1.53348720074,2.64853382111 -5.139752388,1.53749525547,2.67011523247 -5.14276075363,1.53949916363,2.68189644814 -5.14477682114,1.54350733757,2.70248031616 -5.14579200745,1.54551553726,2.72207546234 -5.1548075676,1.55152273178,2.74665570259 -5.16882228851,1.55852901936,2.77423095703 -5.0720539093,1.56366169453,2.98672580719 -5.08506822586,1.5706679821,3.01431822777 -5.04108285904,1.55768048763,2.99910402298 -5.01710367203,1.55269384384,3.00568127632 -4.98912525177,1.54670810699,3.0102481842 -4.98214292526,1.5467184782,3.02682352066 -4.96116399765,1.54373145103,3.03539061546 -4.93618440628,1.53774511814,3.04096698761 -4.92320394516,1.53675639629,3.05354762077 -4.90921449661,1.53276348114,3.0553355217 -4.90823125839,1.53577256203,3.07492256165 -4.90525007248,1.53878247738,3.09448623657 -4.89626789093,1.53879284859,3.10907554626 -4.87328958511,1.53380668163,3.11662888527 -4.88030529022,1.53981423378,3.14122056961 -4.86931562424,1.53682100773,3.14500260353 -4.85633516312,1.53583240509,3.15758085251 -4.84835338593,1.53684294224,3.17316317558 -4.84437179565,1.53885281086,3.19173741341 -4.82939147949,1.53686487675,3.20330905914 -4.82340955734,1.53787493706,3.21989798546 -4.81042003632,1.53488183022,3.22169065475 -4.80343961716,1.53589272499,3.23924684525 -4.79745721817,1.5369027853,3.2558362484 -4.78947591782,1.53791332245,3.27141976357 -4.77749586105,1.53692495823,3.28498983383 -4.77451372147,1.53993439674,3.30358147621 -4.75653409958,1.53694713116,3.31314921379 -4.75154352188,1.53695249557,3.31994724274 -4.75356149673,1.54096162319,3.34351086617 -4.74358081818,1.54097270966,3.35808849335 -4.72760057449,1.53898465633,3.36768126488 -4.71861982346,1.53999578953,3.38325309753 -4.70664024353,1.53900742531,3.39682221413 -4.7016582489,1.54101741314,3.41441082954 -4.70066785812,1.54202258587,3.42518782616 -4.69368648529,1.54403305054,3.4417693615 -4.6757068634,1.54104566574,3.45035123825 -4.66972589493,1.54205620289,3.46792793274 -4.65174674988,1.54006886482,3.47650814056 -4.64276647568,1.54007995129,3.49208116531 -4.63778495789,1.54209029675,3.51065444946 -4.64179325104,1.54609405994,3.52444839478 -4.6178150177,1.54110777378,3.52803611755 -4.6138343811,1.5441185236,3.54858779907 -4.60385370255,1.54412937164,3.56218552589 -4.59587335587,1.54514038563,3.57875609398 -4.58689260483,1.5451515913,3.59433150291 -4.58390235901,1.54615676403,3.60312247276 -4.5729227066,1.54616856575,3.61768817902 -4.56194210052,1.54617989063,3.6312725544 -4.5479631424,1.54519200325,3.64284968376 -4.53998279572,1.54620301723,3.65942287445 -4.53300189972,1.54821372032,3.67601084709 -4.51902246475,1.54722583294,3.68758773804 -4.52003097534,1.54923009872,3.69938492775 -4.50105285645,1.54624330997,3.70696043968 -4.50507068634,1.55225217342,3.73353242874 -4.48709249496,1.55026519299,3.7421040535 -4.48011207581,1.55127608776,3.75967717171 -4.47613048553,1.55428624153,3.77926039696 -4.46515083313,1.55429768562,3.79284667969 -4.45716238022,1.55430436134,3.79862046242 -4.44418239594,1.55331611633,3.81021213531 -4.43620157242,1.55432713032,3.82679057121 -4.42622184753,1.55533850193,3.8413746357 -4.41224384308,1.55435109138,3.85393357277 -4.40626335144,1.55636191368,3.87250900269 -4.40227270126,1.55736720562,3.88030838966 -4.38929319382,1.55637896061,3.89190006256 -4.37131547928,1.5543923378,3.90046691895 -4.37633323669,1.56140112877,3.92904090881 -4.35735464096,1.55841422081,3.93562674522 -4.3393778801,1.55642747879,3.94419264793 -4.32939767838,1.55643880367,3.95877838135 -4.32440805435,1.55744469166,3.96656322479 -4.31542825699,1.55845594406,3.98214840889 -4.31144809723,1.56146681309,4.00371026993 -4.29246997833,1.55947995186,4.0102930069 -4.28049087524,1.55949163437,4.02288341522 -4.26451301575,1.55750477314,4.03344392776 -4.25253343582,1.55751657486,4.04603385925 -4.25254249573,1.560521245,4.05783176422 -4.24256372452,1.56153297424,4.0734038353 -4.22558641434,1.55954635143,4.08296442032 -4.21360683441,1.55955803394,4.09555482864 -4.20762777328,1.56256914139,4.11512565613 -4.19964694977,1.56458008289,4.13171577454 -4.18366003036,1.56058812141,4.12850618362 -4.17867994308,1.56359887123,4.14907884598 -4.16170310974,1.56161236763,4.15863847733 -4.15472221375,1.56462311745,4.17622947693 -4.1377453804,1.56263625622,4.18480443954 -4.11876726151,1.55964946747,4.19039487839 -4.11778640747,1.56465935707,4.21497249603 -4.12379455566,1.56966304779,4.2337641716 -4.09881877899,1.56467783451,4.23433637619 -4.07984209061,1.56269156933,4.24090909958 -4.08286094666,1.56970083714,4.27047777176 -4.0658826828,1.56771373749,4.27806806564 -4.04990530014,1.56672692299,4.28764200211 -4.05191421509,1.56973111629,4.30243682861 -4.03193759918,1.56674516201,4.30800771713 -4.0129609108,1.56475877762,4.3145775795 -4.01198005676,1.56976854801,4.33916759491 -3.96800851822,1.55678725243,4.31873750687 -3.97702598572,1.56679546833,4.35531044006 -3.98004341125,1.57280421257,4.38391017914 -3.96305680275,1.56881248951,4.37869930267 -3.95207810402,1.56982433796,4.3932800293 -3.94709920883,1.57383573055,4.41584062576 -3.92112350464,1.56785047054,4.41342639923 -3.9061460495,1.56786346436,4.42400026321 -3.90416574478,1.57287359238,4.44858407974 -3.88818788528,1.57188642025,4.4571723938 -3.87920045853,1.57089364529,4.46194028854 -3.86622166634,1.57090568542,4.47353410721 -3.84824562073,1.56991934776,4.48110151291 -3.84626460075,1.57492935658,4.50569152832 -3.83628630638,1.57594144344,4.52226400375 -3.81331062317,1.57195591927,4.5228471756 -3.79533457756,1.5709695816,4.53041267395 -3.79934334755,1.57597374916,4.54920244217 -3.78236627579,1.57398700714,4.5567855835 -3.75839090347,1.57000172138,4.5563621521 -3.760409832,1.57701122761,4.58694410324 -3.73343586922,1.57102680206,4.58350992203 -3.72045826912,1.57203936577,4.59608983994 -3.72246670723,1.5760434866,4.61189365387 -3.7044904232,1.5740571022,4.61847162247 -3.69251275063,1.5750695467,4.63304185867 -3.68353414536,1.57708132267,4.65062332153 -3.67055654526,1.57809376717,4.66320562363 -3.66057825089,1.58010566235,4.67978572845 -3.50763344765,1.5151463747,4.51435470581 -3.42366266251,1.47916805744,4.42114019394 -3.4106862545,1.47918117046,4.4336977005 -3.40870594978,1.48519134521,4.45828914642 -3.39872813225,1.48720347881,4.47386264801 -3.57570624352,1.57817804813,4.73445129395 -3.56172823906,1.5781904459,4.74504470825 -3.54974079132,1.57619774342,4.74383926392 -3.53776335716,1.57721030712,4.75841331482 -3.52678632736,1.57922291756,4.77497959137 -3.51980662346,1.58223378658,4.79457950592 -3.49183320999,1.57624971867,4.78814506531 -3.47685694695,1.57626283169,4.79871988297 -3.46587896347,1.57827496529,4.81430101395 -3.44789338112,1.57328367233,4.80508804321 -3.43891501427,1.57629561424,4.82366609573 -3.43193650246,1.58030700684,4.84524393082 -3.40796208382,1.57532191277,4.84282255173 -3.39498519897,1.57633471489,4.85639476776 -3.38300728798,1.57734692097,4.86998653412 -3.37102985382,1.57935941219,4.88456583023 -3.36904025078,1.58236479759,4.89735937119 -3.3480656147,1.57937932014,4.89992570877 -3.32309150696,1.57439434528,4.89550590515 -3.32011175156,1.58040487766,4.9230890274 -3.30613493919,1.581417799,4.93467140198 -3.29815649986,1.58542943001,4.95525312424 -3.29417777061,1.59144043922,4.9828248024 -3.29318785667,1.59444570541,4.99761867523 -3.28720927238,1.59945702553,5.02219390869 -3.23024249077,1.5774782896,4.96778345108 -3.21226763725,1.57649230957,4.9743514061 -3.17429661751,1.5635099411,4.94893074036 -3.16131997108,1.56552278996,4.96250486374 -3.15033245087,1.56352984905,4.96130418777 -3.1373565197,1.56554293633,4.97586631775 -3.08738827705,1.54656291008,4.92945623398 -3.03942060471,1.52858281136,4.8870267868 -3.03044271469,1.53159463406,4.90561151505 -3.02346467972,1.53660619259,4.92818880081 -3.06547403336,1.56760799885,5.03076791763 -3.05448675156,1.56661510468,5.02956438065 -3.09249663353,1.59561741352,5.12615633011 -3.05952525139,1.58663439751,5.10772657394 -3.15252256393,1.6486260891,5.299305439 -3.10755348206,1.63164496422,5.25989246368 -3.0815808773,1.62666082382,5.25445222855 -3.02761459351,1.60468173027,5.19903278351 -3.07161331177,1.63467800617,5.29282474518 -3.1016254425,1.6616820097,5.38141441345 -3.08764839172,1.6626945734,5.39400911331 -3.0536775589,1.65271174908,5.37358188629 -3.04170084,1.65572440624,5.39115953445 -3.00772976875,1.64574146271,5.36973714828 -3.03773260117,1.66874074936,5.44351816177 -3.02575564384,1.67075324059,5.46110153198 -3.01477909088,1.67476594448,5.48167324066 -2.99780344963,1.67477941513,5.49025774002 -2.98182797432,1.67579293251,5.50183010101 -2.96785116196,1.67780566216,5.5154209137 -2.95387554169,1.67981898785,5.5309920311 -2.94088864326,1.67682659626,5.52678489685 -2.92591285706,1.6778396368,5.53936767578 -2.91293692589,1.6808526516,5.5569396019 -2.8969604969,1.68086576462,5.56653404236 -2.88398432732,1.68387877941,5.58410787582 -2.86301016808,1.68189322948,5.58568668365 -2.84803462029,1.68390643597,5.59926271439 -2.84204626083,1.68491292,5.60905075073 -2.82906961441,1.68792557716,5.62563753128 -2.81309461594,1.68893921375,5.6382060051 -2.79811906815,1.69095242023,5.65178489685 -2.78114318848,1.69096565247,5.65938282013 -2.76316857338,1.69097971916,5.6679520607 -2.75718021393,1.69298613071,5.67774343491 -2.74020504951,1.69299972057,5.68732309341 -2.72822904587,1.69701242447,5.70789766312 -2.70925402641,1.69602620602,5.71248626709 -2.692278862,1.69703996181,5.72206783295 -2.67530369759,1.69705355167,5.73164892197 -2.6553299427,1.69606804848,5.73621749878 -2.65533947945,1.70207285881,5.758020401 -2.62936735153,1.69708859921,5.74958896637 -2.60739326477,1.69310295582,5.74717950821 -2.59441804886,1.69711625576,5.76774215698 -2.57444357872,1.69513034821,5.77032756805 -2.55047011375,1.69114530087,5.76391124725 -2.54049301147,1.69715738297,5.78850030899 -2.52750682831,1.69416511059,5.78328943253 -2.50853276253,1.69317924976,5.78886699677 -2.4915573597,1.69419276714,5.79844903946 -2.47458291054,1.69520664215,5.80902338028 -2.45460867882,1.69322085381,5.81160545349 -2.44563150406,1.70023286343,5.84018945694 -2.42665743828,1.69924688339,5.84576749802 -2.41367149353,1.69725477695,5.84055233002 -2.40069556236,1.70026755333,5.86013460159 -2.38072180748,1.69928193092,5.86370849609 -2.36474633217,1.70129513741,5.87529802322 -2.35476994514,1.70830762386,5.90387248993 -2.33879470825,1.70932090282,5.91645622253 -2.32780838013,1.70832848549,5.9162402153 -2.31983041763,1.716340065,5.94783592224 -2.30685544014,1.72135329247,5.97139835358 -2.30187702179,1.7323641777,6.01199197769 -2.29589962959,1.74237585068,6.05356407166 -2.27792525291,1.74338984489,6.06314086914 -2.25995016098,1.74340331554,6.06973981857 -2.26096129417,1.75340878963,6.10450744629 -2.24098682404,1.75242269039,6.10709810257 -2.21901321411,1.74943733215,6.10468530655 -2.20903730392,1.75744986534,6.1382522583 -2.18406534195,1.7524651289,6.12882995605 -2.16309070587,1.75047910213,6.12742757797 -2.15410447121,1.75148642063,6.1342048645 -2.12913155556,1.74650156498,6.12279129028 -2.10016036034,1.73751747608,6.10037231445 -2.08218622208,1.7385314703,6.10995006561 -2.06121206284,1.73654556274,6.108543396 -2.03923892975,1.7335600853,6.10512828827 -2.02326488495,1.73657393456,6.1226940155 -2.00827908516,1.73158192635,6.10848855972 -1.98930537701,1.73159599304,6.11506652832 -1.97433030605,1.73560917377,6.13364696503 -1.95335650444,1.73362338543,6.13223695755 -1.92838478088,1.7286387682,6.12080907822 -1.91141009331,1.72965228558,6.13239526749 -1.88943707943,1.72766685486,6.12897539139 -1.88344907761,1.73067319393,6.1427693367 -1.86247575283,1.728687644,6.14235019684 -1.84350168705,1.72870147228,6.14793395996 -1.82152926922,1.72671639919,6.14550542831 -1.80755329132,1.73172903061,6.16610097885 -1.78058171272,1.72374463081,6.14468240738 -1.76060795784,1.72275865078,6.14626836777 -1.75262081623,1.72376549244,6.15505552292 -1.7356467247,1.72677910328,6.16863393784 -1.71067464352,1.72079432011,6.15321445465 -1.68970119953,1.71880853176,6.15080070496 -1.67272663116,1.72082197666,6.16338539124 -1.65275335312,1.71983623505,6.16596412659 -1.64276659489,1.71984326839,6.16675615311 -1.62279391289,1.71985781193,6.17132425308 -1.60381948948,1.71887147427,6.17491722107 -1.58484578133,1.71988534927,6.18050003052 -1.56387257576,1.71789968014,6.17808389664 -1.54190051556,1.71491456032,6.17465162277 -1.52492594719,1.71792805195,6.18723917007 -1.51293981075,1.71493542194,6.18002939224 -1.49196648598,1.71294975281,6.17661523819 -1.47299349308,1.71396398544,6.18418741226 -1.45301985741,1.7129778862,6.18477344513 -1.43504571915,1.71399152279,6.19336223602 -1.41407227516,1.71100568771,6.18895053864 -1.40608513355,1.71401238441,6.19874000549 -1.38311326504,1.71002733707,6.18930912018 -1.36413955688,1.71004116535,6.19389629364 -1.34516584873,1.71005499363,6.19947862625 -1.32519233227,1.7090690136,6.19906663895 -1.30821824074,1.71308255196,6.21464681625 -1.28524577618,1.70809721947,6.20122909546 -1.27525949478,1.70810449123,6.20301437378 -1.25428652763,1.70511865616,6.19859743118 -1.23631250858,1.70713222027,6.20818376541 -1.21533954144,1.70514655113,6.20376586914 -1.19436645508,1.70216071606,6.19835042953 -1.17639267445,1.70417439938,6.20893383026 -1.15541899204,1.70118832588,6.20052909851 -1.14643263817,1.70319533348,6.20831155777 -1.12745893002,1.70320916176,6.21289777756 -1.10448682308,1.69822382927,6.19747495651 -1.08651340008,1.7002376318,6.21005249023 -1.0675393343,1.70025122166,6.21264600754 -1.04556715488,1.69626581669,6.20222234726 -1.02859318256,1.70127928257,6.22080183029 -1.01860642433,1.70028626919,6.21959686279 -0.998633265495,1.69930028915,6.21917963028 -0.977660655975,1.69731450081,6.21375751495 -0.958686709404,1.69732809067,6.21635055542 -0.939713776112,1.69934213161,6.22492456436 -0.91874063015,1.6953561306,6.21551322937 -0.907754540443,1.69336342812,6.20930099487 -0.887781381607,1.69237732887,6.20788431168 -0.868807554245,1.69239091873,6.21047592163 -0.849834024906,1.69340467453,6.21506261826 -0.828861653805,1.69041895866,6.20963525772 -0.809888243675,1.69143283367,6.21521902084 -0.790914833546,1.69344651699,6.2208032608 -0.781927585602,1.6934530735,6.22460317612 -0.760954618454,1.6894671917,6.21319007874 -0.741981446743,1.69148099422,6.22076892853 -0.723007977009,1.69249463081,6.22635412216 -0.701036095619,1.68750917912,6.21092653275 -0.684061467648,1.69252216816,6.22952365875 -0.672075867653,1.68752968311,6.21330690384 -0.654102444649,1.69154334068,6.23088645935 -0.634129464626,1.69055724144,6.2284693718 -0.614156067371,1.68857097626,6.22205972672 -0.595182776451,1.69058465958,6.22964191437 -0.575210034847,1.68959867954,6.22921943665 -0.557235479355,1.69161164761,6.23782205582 -0.546249330044,1.68761873245,6.22561264038 -0.527276813984,1.69263279438,6.24217987061 -0.506303548813,1.68564653397,6.21977472305 -0.488329559565,1.69065988064,6.23636484146 -0.468356400728,1.68767356873,6.22995138168 -0.447384506464,1.6856880188,6.22151947021 -0.429410129786,1.68870103359,6.23411893845 -0.419423788786,1.68870806694,6.23390722275 -0.399451494217,1.68972218037,6.23847723007 -0.379478186369,1.68673586845,6.2280664444 -0.359504729509,1.68174934387,6.21365976334 -0.340532213449,1.68876338005,6.23722839355 -0.321557849646,1.68677639961,6.22983360291 -0.302584677935,1.69078993797,6.2444152832 -0.291599065065,1.68679738045,6.23119544983 -0.272625088692,1.68581056595,6.22979354858 -0.252652198076,1.68382430077,6.22237539291 -0.232679948211,1.68583834171,6.22894525528 -0.213706105947,1.68585169315,6.23054027557 -0.194732442498,1.68786489964,6.23813247681 -0.184745937586,1.68587183952,6.23092508316 -0.164773195982,1.68388557434,6.22350406647 -0.144800588489,1.6828994751,6.22008132935 -0.12582693994,1.68591272831,6.22967338562 -0.105854362249,1.68492662907,6.22724962234 -0.0868805795908,1.68693983555,6.23484373093 -0.0669079571962,1.68495357037,6.22742128372 -0.0569217279553,1.68596065044,6.23120880127 -0.0379477925599,1.68497371674,6.22680616379 -0.0179752446711,1.68298757076,6.21838235855 --0.00399438245222,1.67800283432,6.05191278458 --0.0229676477611,1.67501616478,6.03949689865 --0.0419411621988,1.68402957916,6.07008647919 --0.0609141997993,1.67504298687,6.03866624832 --0.0798876360059,1.67805635929,6.04925441742 --0.0988607779145,1.67506980896,6.03883600235 --0.107848122716,1.67507612705,6.03863954544 --0.126821562648,1.67708945274,6.04422712326 --0.145795047283,1.67910265923,6.05081605911 --0.164767667651,1.67211639881,6.02638816833 --0.183741301298,1.67612946033,6.03697967529 --0.202714458108,1.67514288425,6.0325627327 --0.221687957644,1.67615604401,6.03715133667 --0.231674045324,1.67816305161,6.03993606567 --0.250647097826,1.67617642879,6.03351688385 --0.26862102747,1.67118942738,6.0171084404 --0.287594765425,1.67420244217,6.02570295334 --0.30656760931,1.67221605778,6.01627826691 --0.325541436672,1.67522895336,6.02487421036 --0.335527330637,1.6752358675,6.02365493774 --0.353501737118,1.67424869537,6.01825618744 --0.372474700212,1.67226207256,6.01283502579 --0.391448378563,1.67427504063,6.0174279213 --0.411420494318,1.67528879642,6.01899528503 --0.43039393425,1.67630195618,6.01958322525 --0.447368383408,1.6703145504,5.99817991257 --0.457354515791,1.67132139206,5.99996519089 --0.476328372955,1.67333436012,6.00556087494 --0.49530172348,1.67434751987,6.00514745712 --0.514274656773,1.67236089706,5.9997253418 --0.533247828484,1.6723741293,5.9973077774 --0.552221596241,1.67438697815,6.00090312958 --0.57219427824,1.67640042305,6.00648117065 --0.581181585789,1.67640662193,6.00528383255 --0.600154817104,1.67641973495,6.00286722183 --0.620128273964,1.68043279648,6.01446056366 --0.640100717545,1.68244636059,6.01703596115 --0.658074378967,1.67945933342,6.00562095642 --0.678047895432,1.68347227573,6.01621580124 --0.697020769119,1.68248558044,6.00979137421 --0.705008685589,1.68049132824,6.00260162354 --0.724981725216,1.68350458145,6.00818586349 --0.742955625057,1.68151736259,5.99977636337 --0.76292771101,1.68253099918,5.99834299088 --0.783900737762,1.68754422665,6.01293325424 --0.802874028683,1.68755733967,6.00951719284 --0.811860799789,1.68656361103,6.00430965424 --0.832833707333,1.69057703018,6.01689767838 --0.849808692932,1.68858897686,6.00650405884 --0.868781685829,1.68760216236,6.00108194351 --0.890754580498,1.69461548328,6.02067470551 --0.908727824688,1.69162833691,6.0082526207 --0.929700613022,1.69564163685,6.01783800125 --0.939686834812,1.69664824009,6.01762533188 --0.957661151886,1.69566082954,6.01122236252 --0.977634012699,1.69667387009,6.01280450821 --0.997607588768,1.69968676567,6.01739740372 --1.01758134365,1.70269954205,6.02299547195 --1.03455519676,1.69871199131,6.0065779686 --1.05252814293,1.69572508335,5.99314880371 --1.0655143261,1.70273184776,6.01395225525 --1.08548748493,1.7037447691,6.0155377388 --1.10446131229,1.7047573328,6.01413393021 --1.12243533134,1.70376980305,6.00572395325 --1.14640653133,1.71078383923,6.02429437637 --1.16238188744,1.70679557323,6.00889873505 --1.17336726189,1.70780265331,6.01067590714 --1.19334149361,1.71081507206,6.01628160477 --1.2123144865,1.71082794666,6.00985908508 --1.23428690434,1.71384131908,6.01944255829 --1.25226092339,1.71285367012,6.01103305817 --1.27123498917,1.71386611462,6.00862789154 --1.29420697689,1.7188795805,6.02120733261 --1.30219399929,1.71688568592,6.01099681854 --1.32016801834,1.71589815617,6.00258684158 --1.34314119816,1.72191107273,6.01918792725 --1.36111426353,1.71992385387,6.00676012039 --1.37908828259,1.71793615818,5.99835014343 --1.39806234837,1.71894860268,5.99594783783 --1.4190350771,1.72096157074,5.99852895737 --1.42702293396,1.71996724606,5.99233484268 --1.4529941082,1.72898113728,6.01491355896 --1.46896874905,1.72499299049,5.99850559235 --1.48794257641,1.72500550747,5.99409532547 --1.51091480255,1.73001873493,6.00367498398 --1.52988827229,1.73003125191,5.99826145172 --1.53687596321,1.72703707218,5.98605585098 --1.5598487854,1.73204994202,5.99764966965 --1.5768237114,1.73006176949,5.98724985123 --1.59679675102,1.73207449913,5.98483228683 --1.6207691431,1.73708760738,5.99842119217 --1.63674402237,1.73409950733,5.98301458359 --1.65971660614,1.73911249638,5.99260425568 --1.66870379448,1.73811841011,5.98840045929 --1.687677145,1.7381310463,5.98097705841 --1.7096503973,1.74214375019,5.98757362366 --1.7276238203,1.7401560545,5.97614812851 --1.7425994873,1.7371673584,5.9597530365 --1.76857113838,1.74418091774,5.97733640671 --1.79054379463,1.74719369411,5.98092031479 --1.79453206062,1.74119913578,5.95870828629 --1.81950485706,1.74821186066,5.97531080246 --1.83947789669,1.74922454357,5.97088861465 --1.85745286942,1.74923622608,5.96449327469 --1.87742650509,1.75024843216,5.96208286285 --1.89540028572,1.7492607832,5.95166301727 --1.90638649464,1.75026714802,5.9524512291 --1.92835986614,1.75327956676,5.95704746246 --1.94333517551,1.75029098988,5.93964147568 --1.96530818939,1.75330364704,5.94222640991 --1.98728179932,1.75631594658,5.9468255043 --2.00725460052,1.75732851028,5.94139957428 --2.02622866631,1.75734066963,5.93498659134 --2.03621530533,1.75734686852,5.93277692795 --2.05918884277,1.7623591423,5.94038105011 --2.08016180992,1.76337146759,5.93896389008 --2.09413766861,1.76038253307,5.91956138611 --2.12110900879,1.76639604568,5.93413925171 --2.13608455658,1.76340711117,5.9177365303 --2.1540594101,1.76341879368,5.90933084488 --2.16604495049,1.76542556286,5.91111183167 --2.18701887131,1.76743769646,5.91070556641 --2.20399403572,1.76644897461,5.90030574799 --2.22696661949,1.76946151257,5.90389156342 --2.24694037437,1.77047371864,5.89947748184 --2.26391482353,1.76948523521,5.88706254959 --2.27890086174,1.77449178696,5.89886331558 --2.29387545586,1.77050340176,5.88044261932 --2.31584906578,1.77351534367,5.88203716278 --2.33582305908,1.77452743053,5.87762546539 --2.35579681396,1.77553939819,5.87321376801 --2.37677049637,1.77755141258,5.87079954147 --2.39874482155,1.78156304359,5.8744134903 --2.40573215485,1.77856874466,5.86319589615 --2.42870521545,1.78258109093,5.86578416824 --2.45667719841,1.78959405422,5.88037443161 --2.46765398979,1.78360438347,5.85497140884 --2.48662853241,1.7846159935,5.84856700897 --2.50760197639,1.78662800789,5.84514904022 --2.52957510948,1.7886402607,5.843729496 --2.53756284714,1.78764569759,5.83753156662 --2.56253623962,1.79365801811,5.84513092041 --2.57751131058,1.7906690836,5.8277130127 --2.60248470306,1.79568123817,5.83531475067 --2.62145876884,1.79569292068,5.82689762115 --2.64343261719,1.79870474339,5.8264913559 --2.64942097664,1.79570996761,5.8152885437 --2.67239403725,1.79872214794,5.81587409973 --2.69136857986,1.79973340034,5.8084654808 --2.71034312248,1.79974484444,5.80105781555 --2.73531603813,1.80475711823,5.8056435585 --2.75928926468,1.80876910686,5.80924081802 --2.77126550674,1.80377972126,5.78582382202 --2.78725099564,1.808786273,5.7956199646 --2.80022764206,1.80579662323,5.77621841431 --2.82520079613,1.80980861187,5.7808098793 --2.84517478943,1.8108202219,5.77439594269 --2.87314677238,1.81683290005,5.78398084641 --2.88512372971,1.81384301186,5.7625784874 --2.90809702873,1.81585478783,5.76216650009 --2.91708469391,1.81586039066,5.756960392 --2.93406009674,1.81587123871,5.74555778503 --2.96203279495,1.82188355923,5.75514984131 --2.97600865364,1.81889414787,5.73673677444 --2.99598312378,1.81990540028,5.73032712936 --3.01495790482,1.82091653347,5.72191667557 --3.02694416046,1.82292258739,5.72170448303 --3.05291748047,1.82793438435,5.72730255127 --3.06689453125,1.82494461536,5.71090745926 --3.09086728096,1.828956604,5.71048641205 --3.10784316063,1.8279671669,5.6990852356 --3.12581849098,1.82797801495,5.68867635727 --3.15279054642,1.83299028873,5.69325399399 --3.16077876091,1.83299541473,5.68705749512 --3.18275332451,1.83600664139,5.68465709686 --3.20172858238,1.83601748943,5.67625188828 --3.22570204735,1.84002912045,5.67583847046 --3.23767876625,1.83603918552,5.65442705154 --3.26265215874,1.84005081654,5.6560177803 --3.28262686729,1.84106183052,5.64860677719 --3.29261398315,1.84206748009,5.64439630508 --3.31558871269,1.84507846832,5.64400434494 --3.33456397057,1.84608924389,5.63459253311 --3.35653805733,1.84810042381,5.63017988205 --3.373513937,1.84811091423,5.61777210236 --3.39648795128,1.85112214088,5.61536407471 --3.40547537804,1.85112762451,5.60915184021 --3.42345166206,1.85113787651,5.59975814819 --3.44642591476,1.85414898396,5.59735298157 --3.4654006958,1.85515987873,5.58693313599 --3.47937726974,1.85216987133,5.56952476501 --3.50635099411,1.85818111897,5.5741276741 --3.52732586861,1.86019206047,5.56771755219 --3.5333147049,1.85819685459,5.55751466751 --3.55029010773,1.85720741749,5.54409790039 --3.57826304436,1.86321890354,5.54868984222 --3.59024095535,1.8602284193,5.52929258347 --3.60621666908,1.85923874378,5.51387119293 --3.63418984413,1.86525022984,5.51846694946 --3.65116596222,1.86526036263,5.50606203079 --3.65415525436,1.86126494408,5.49085187912 --3.68612790108,1.8692766428,5.50145196915 --3.69410610199,1.86428582668,5.47504138947 --3.71808052063,1.86829686165,5.47263240814 --3.74005579948,1.87030720711,5.46823501587 --3.75603151321,1.86931741238,5.45281457901 --3.7650103569,1.86532640457,5.42941665649 --3.78899431229,1.87333321571,5.44521045685 --3.80796980858,1.87434351444,5.43479728699 --3.81794810295,1.87035274506,5.41239404678 --3.85691952705,1.88236486912,5.43199968338 --3.85689997673,1.87337303162,5.39458608627 --3.88387393951,1.8783839941,5.39618349075 --3.89286112785,1.87838935852,5.38896274567 --3.91683602333,1.88139975071,5.3865647316 --3.92781400681,1.87840902805,5.36515474319 --3.95878720284,1.88542032242,5.37175178528 --3.96776533127,1.88142931461,5.34733772278 --3.98274230957,1.88043892384,5.33193302155 --4.00871706009,1.88544952869,5.33153152466 --4.01570558548,1.88445413113,5.32333135605 --4.03868055344,1.88746464252,5.31791973114 --4.06165552139,1.89047503471,5.31250953674 --4.08163118362,1.89248502254,5.30309963226 --4.10660600662,1.89649558067,5.30069684982 --4.12458276749,1.89650511742,5.28929519653 --4.13955974579,1.89551472664,5.27288103104 --4.14854812622,1.89651942253,5.2676858902 --4.17452287674,1.90052974224,5.26628351212 --4.18950033188,1.89953923225,5.24986886978 --4.20347738266,1.89854860306,5.23245763779 --4.23445081711,1.90555942059,5.23705530167 --4.24642896652,1.9025683403,5.21765041351 --4.26340579987,1.90257775784,5.2042427063 --4.28239202499,1.90858364105,5.21003437042 --4.28937101364,1.90359199047,5.18462991714 --4.31634616852,1.9086022377,5.18423366547 --4.34132146835,1.91261219978,5.18083190918 --4.36329650879,1.91462218761,5.17241477966 --4.38327264786,1.91663205624,5.16200256348 --4.39726066589,1.9196369648,5.16281318665 --4.40423965454,1.91464543343,5.13639354706 --4.42521619797,1.91765487194,5.12799263 --4.44019412994,1.91666388512,5.11259222031 --4.45217180252,1.91467273235,5.09217262268 --4.47414827347,1.91768229008,5.08477163315 --4.47712802887,1.91069042683,5.05435371399 --4.48611736298,1.9116948843,5.04916334152 --4.49609565735,1.9087035656,5.02674388885 --4.50307559967,1.90471148491,5.00234079361 --4.51505374908,1.90272033215,4.98292922974 --4.54102945328,1.90772986412,4.98053646088 --4.54700899124,1.90273809433,4.95411920547 --4.58198261261,1.9117487669,4.96071863174 --4.58497238159,1.90975272655,4.94750928879 --4.60095024109,1.90976154804,4.93310594559 --4.61892747879,1.91077065468,4.92070055008 --4.63790416718,1.91177999973,4.90828227997 --4.64688396454,1.90878796577,4.88688468933 --4.66786050797,1.91079711914,4.87747764587 --4.67484045029,1.90780520439,4.85306739807 --4.69082784653,1.91081011295,4.85487413406 --4.70980548859,1.9128190279,4.84347009659 --4.71878433228,1.90982711315,4.82105731964 --4.74276065826,1.9138365984,4.81465244293 --4.75773906708,1.91384506226,4.79925060272 --4.76771831512,1.91085326672,4.77783632278 --4.7806968689,1.90986168385,4.7594203949 --4.79268455505,1.91186642647,4.75621938705 --4.80866336823,1.91287481785,4.74181747437 --4.82364177704,1.9128831625,4.72641563416 --4.84161949158,1.9138917923,4.71401453018 --4.85259866714,1.91190004349,4.69359779358 --4.87757444382,1.91590929031,4.68718671799 --4.87256717682,1.91091227531,4.66799354553 --4.88454627991,1.90992033482,4.64959001541 --4.86653184891,1.89592635632,4.60116577148 --4.85351610184,1.88493251801,4.55875349045 --4.79351091385,1.8539352417,4.47132492065 --4.76949739456,1.83794093132,4.41890287399 --4.7754778862,1.833948493,4.39549064636 --4.77546882629,1.83195209503,4.38128805161 --4.79244613647,1.83296084404,4.36787176132 --4.81442403793,1.83596932888,4.36047744751 --4.8254032135,1.83497726917,4.34206914902 --4.82838487625,1.82998466492,4.3166642189 --4.8433637619,1.83099269867,4.30226039886 --4.85334348679,1.82900059223,4.28284931183 --4.85633325577,1.82800471783,4.270632267 --4.87531137466,1.83001291752,4.2602353096 --4.88029241562,1.82602024078,4.23682880402 --4.89727020264,1.82802867889,4.22341394424 --4.91524887085,1.82903671265,4.21201658249 --4.92722845078,1.82904458046,4.19460773468 --4.94220733643,1.82905256748,4.18020486832 --4.9441986084,1.82805633545,4.16799879074 --4.95217847824,1.82506406307,4.14657926559 --4.96315908432,1.82507133484,4.13019704819 --4.97713804245,1.82507944107,4.11377620697 --4.99311685562,1.8260872364,4.10037612915 --4.9990978241,1.8230946064,4.07796430588 --5.01607656479,1.82510244846,4.06556653976 --5.01306772232,1.82110595703,4.04834365845 --5.03504562378,1.82411408424,4.03994607925 --5.04502630234,1.82312166691,4.02154397964 --5.04700803757,1.81912851334,3.99613237381 --5.07098579407,1.8231369257,3.98872709274 --5.08296632767,1.82314431667,3.97233128548 --5.08594703674,1.81915152073,3.94690465927 --5.0909371376,1.8181552887,3.93770265579 --5.10191822052,1.81816256046,3.92030215263 --5.1098985672,1.81616985798,3.89989066124 --5.11787986755,1.81517696381,3.88049387932 --5.13385868073,1.81618463993,3.86607933044 --5.1448392868,1.81519198418,3.84867787361 --5.15682792664,1.81719601154,3.84447073936 --5.1588101387,1.81320273876,3.82006525993 --5.17878866196,1.81621062756,3.80865168571 --5.18477010727,1.81421768665,3.78724527359 --5.20574903488,1.81722521782,3.77785348892 --5.21473026276,1.81623232365,3.75844335556 --5.21171283722,1.81123888493,3.73002719879 --5.21470403671,1.80924224854,3.71983075142 --5.22368478775,1.80824935436,3.70041799545 --5.23266506195,1.8072565794,3.68100476265 --5.25364494324,1.81126391888,3.671615839 --5.25762701035,1.80827057362,3.64921116829 --5.26860713959,1.80727791786,3.63079094887 --5.28458738327,1.80928504467,3.61739563942 --5.27657985687,1.80428814888,3.59817409515 --5.29755878448,1.80729568005,3.58777165413 --5.313539505,1.80930268764,3.57437729836 --5.32352018356,1.80830955505,3.55596780777 --5.34349918365,1.8113168478,3.54456329346 --5.35048055649,1.80932366848,3.52415442467 --5.391456604,1.82033193111,3.52675294876 --5.37845039368,1.81333446503,3.50554704666 --5.37843370438,1.80934071541,3.48114776611 --5.38941478729,1.80934751034,3.46374392509 --5.40939378738,1.81235492229,3.45132637024 --5.43637180328,1.81836247444,3.44391870499 --5.42935705185,1.81236815453,3.41552472115 --5.42634010315,1.8073745966,3.38810181618 --5.44132947922,1.81037819386,3.38590860367 --5.46430826187,1.81438541412,3.37549638748 --5.46529197693,1.81139147282,3.35209727287 --5.47127342224,1.80939817429,3.33067798615 --5.47525644302,1.80740439892,3.30927920341 --5.5022354126,1.81241154671,3.30187964439 --5.50022649765,1.80941474438,3.28766202927 --5.52220678329,1.81342148781,3.27726507187 --5.52119016647,1.80942749977,3.25286507607 --5.53517150879,1.81143426895,3.23644828796 --5.5421538353,1.80944049358,3.21705150604 --5.55113506317,1.80944705009,3.19763374329 --5.56811666489,1.81145346165,3.18423938751 --5.58510494232,1.81545710564,3.18203520775 --5.59008741379,1.81346333027,3.16062378883 --5.60006999969,1.81346940994,3.14323139191 --5.60905170441,1.81347584724,3.12381410599 --5.61103534698,1.81048190594,3.10141253471 --5.62901639938,1.81348824501,3.08801174164 --5.66099500656,1.82049500942,3.08261680603 --5.66498565674,1.82049822807,3.07240462303 --5.67796754837,1.82150435448,3.05600261688 --5.67595148087,1.81751036644,3.03058576584 --5.67793464661,1.81451618671,3.00818228722 --5.70091485977,1.81852281094,2.99677395821 --5.71789598465,1.82152891159,2.98237037659 --5.73087787628,1.82253491879,2.96596980095 --5.71687221527,1.81653749943,2.94676494598 --5.73185300827,1.81754386425,2.9303457737 --5.72583866119,1.81254947186,2.9039413929 --5.76481676102,1.82255589962,2.90155220032 --5.77879858017,1.82456183434,2.88514399529 --5.78878116608,1.8245677948,2.8667371273 --5.7927646637,1.82257354259,2.84532976151 --5.79875612259,1.82257640362,2.83713507652 --5.81873703003,1.82658243179,2.82372903824 --5.82472038269,1.82558822632,2.80332183838 --5.84070205688,1.82759404182,2.78791666031 --5.85868358612,1.83059990406,2.77351331711 --5.86366796494,1.82960546017,2.75311470032 --5.87864923477,1.83061134815,2.73670268059 --5.88664007187,1.83261430264,2.72849273682 --5.89162397385,1.83061981201,2.70809412003 --5.89860773087,1.83062529564,2.68869590759 --5.91458940506,1.83263111115,2.67227745056 --5.91457414627,1.82963633537,2.64988303185 --5.92755651474,1.83064210415,2.63247179985 --5.9515376091,1.83664762974,2.62006187439 --5.95552968979,1.83665025234,2.61086845398 --5.96751260757,1.8376557827,2.59346723557 --5.99749326706,1.84466123581,2.58406805992 --5.99047899246,1.83866667747,2.55765604973 --6.01645994186,1.84467208385,2.54625558853 --6.04244089127,1.85067760944,2.53383922577 --6.03642654419,1.84568285942,2.50843548775 --6.05641651154,1.85068535805,2.50624752045 --6.06939983368,1.85269057751,2.48884344101 --6.0783829689,1.85269582272,2.4694340229 --6.08436727524,1.85270106792,2.44902873039 --6.10135030746,1.85470604897,2.43363285065 --6.11333370209,1.85671138763,2.4152200222 --6.12632417679,1.85871398449,2.40901780128 --6.15330648422,1.86571884155,2.3976252079 --6.15029144287,1.86172401905,2.37321352959 --6.16027498245,1.86272907257,2.35379934311 --6.1912560463,1.86973404884,2.34340167046 --6.18324232101,1.8647390604,2.31698727608 --6.19822597504,1.86674392223,2.30059456825 --6.21921634674,1.87274610996,2.29739665985 --6.20720291138,1.866751194,2.26998925209 --6.22918558121,1.87075591087,2.25558710098 --6.24616909027,1.87376070023,2.23918390274 --6.24115467072,1.86976587772,2.213763237 --6.25913858414,1.87377035618,2.19837260246 --6.25912332535,1.87077522278,2.17495417595 --6.25911617279,1.86977767944,2.16375374794 --6.29209804535,1.87778198719,2.15336084366 --6.297082901,1.87778675556,2.13194680214 --6.30606746674,1.87779140472,2.11254453659 --6.31005239487,1.87679612637,2.09113669395 --6.32003688812,1.87780070305,2.07172846794 --6.33602142334,1.88080501556,2.05533885956 --6.34701251984,1.88280725479,2.04712629318 --6.35599756241,1.88381171227,2.02772569656 --6.35898351669,1.88281619549,2.00632405281 --6.37096834183,1.88382053375,1.98792469501 --6.3739528656,1.88282525539,1.96550440788 --6.38593816757,1.88482952118,1.94710540771 --6.39492321014,1.88583374023,1.92770600319 --6.39591598511,1.8848361969,1.91649842262 --6.39890146255,1.88384056091,1.8950959444 --6.40188646317,1.88284504414,1.87267458439 --6.4118719101,1.8838493824,1.85326969624 --6.42385721207,1.88585340977,1.83487308025 --6.43484163284,1.88685762882,1.81546413898 --6.44783353806,1.88985955715,1.80826628208 --6.45881891251,1.89186358452,1.78885865211 --6.4748044014,1.8948674202,1.7714625597 --6.48179006577,1.89487159252,1.7510586977 --6.47377634048,1.89087617397,1.72563827038 --6.48876190186,1.89387989044,1.7082490921 --6.50174665451,1.8958837986,1.68883383274 --6.49673366547,1.89188826084,1.66543352604 --6.51072597504,1.89588987827,1.65823602676 --6.50671195984,1.89289450645,1.63381123543 --6.51769828796,1.89489805698,1.61542546749 --6.51968431473,1.89390230179,1.59300839901 --6.51767063141,1.89090657234,1.56959068775 --6.54365539551,1.89790976048,1.55419313908 --6.54764175415,1.89691376686,1.53278565407 --6.55163526535,1.89791548252,1.52360069752 --6.55362176895,1.89591956139,1.50118327141 --6.5676074028,1.89892292023,1.48278772831 --6.57459354401,1.89992690086,1.46136724949 --6.58157968521,1.89993059635,1.44096589088 --6.57556724548,1.8969347477,1.41756260395 --6.58355998993,1.89893639088,1.40836179256 --6.59654569626,1.90093970299,1.38895475864 --6.59953308105,1.89994359016,1.36755156517 --6.59651947021,1.89794778824,1.34413409233 --6.6085062027,1.89995110035,1.32473242283 --6.61149263382,1.89995479584,1.30332839489 --6.5914812088,1.89195966721,1.27691745758 --6.59947490692,1.89396107197,1.26771843433 --6.59246206284,1.89096546173,1.24329340458 --6.59144878387,1.88896942139,1.22088313103 --6.60743522644,1.89197230339,1.20248675346 --6.61542224884,1.8939756155,1.18208193779 --6.62540864944,1.89497900009,1.16167104244 --6.62939548492,1.89498245716,1.14026212692 --6.64838838577,1.89998316765,1.13306665421 --6.65437555313,1.90098643303,1.11267101765 --6.66236257553,1.9019895792,1.09226918221 --6.66235017776,1.90099322796,1.06985557079 --6.66233730316,1.89999699593,1.04744148254 --6.67232465744,1.90199995041,1.02703404427 --6.67731189728,1.90200316906,1.00664246082 --6.67930603027,1.90200483799,0.995429396629 --6.67529392242,1.90000867844,0.973026156425 --6.68328094482,1.90101158619,0.952625930309 --6.67326927185,1.89701592922,0.928200483322 --6.68625640869,1.9000184536,0.908805549145 --6.71424341202,1.9070199728,0.891409933567 --6.6912317276,1.89902508259,0.864979207516 --6.70422554016,1.90302586555,0.856794297695 --6.71121311188,1.90402877331,0.835379779339 --6.73120069504,1.90903055668,0.816990792751 --6.72818851471,1.90703415871,0.79458296299 --6.73317670822,1.90803718567,0.773174583912 --6.7381644249,1.90804004669,0.751766741276 --6.74915218353,1.91104233265,0.731364548206 --6.75214624405,1.91104388237,0.720150589943 --6.75513410568,1.9110468626,0.698747754097 --6.76512241364,1.91404926777,0.678349494934 --6.77311038971,1.91505181789,0.656937479973 --6.76109886169,1.91105592251,0.63352638483 --6.76308727264,1.91105878353,0.612125396729 --6.78707504272,1.91706001759,0.592722833157 --6.79806947708,1.92006075382,0.582514822483 --6.80405759811,1.92106330395,0.561108887196 --6.81004619598,1.92206573486,0.539703428745 --6.8260345459,1.92606735229,0.519301474094 --6.82202291489,1.92407059669,0.496893852949 --6.83401203156,1.92707240582,0.476499795914 --6.84500074387,1.93007445335,0.455089509487 --6.84599542618,1.93007564545,0.444900304079 --6.85798406601,1.93307745457,0.423490077257 --6.85797262192,1.93208038807,0.401077270508 --6.8629617691,1.93308269978,0.379677027464 --6.87295055389,1.9360845089,0.358271420002 --6.87793970108,1.93708670139,0.336872279644 --6.87493467331,1.9360884428,0.325669020414 --6.88292312622,1.93709039688,0.30324870348 --6.89791250229,1.94109153748,0.282860100269 --6.90690135956,1.94409346581,0.260440528393 --6.89989089966,1.94109678268,0.238034635782 --6.91088056564,1.94409823418,0.216633349657 --6.91286945343,1.94410061836,0.194220557809 --6.91886472702,1.94610118866,0.184029608965 --6.9128537178,1.94410431385,0.161621689796 --6.91884326935,1.94510626793,0.139206975698 --6.91083288193,1.94310963154,0.116798810661 --6.92682266235,1.9471102953,0.095399223268 --6.93381214142,1.94911205769,0.0729855597019 --6.92680168152,1.94711518288,0.0505763404071 --6.92079687119,1.94511699677,0.0393720567226 --6.93178653717,1.94811809063,0.0179768484086 --6.92677640915,1.94612109661,-0.00443380419165 --6.92276620865,1.94512379169,-0.0268453862518 --6.91575574875,1.94312691689,-0.0492574684322 --6.91874551773,1.94312894344,-0.0716696232557 --6.93173599243,1.9471296072,-0.0930618643761 --6.94173145294,1.95012950897,-0.104266263545 --6.93472146988,1.94813263416,-0.126678839326 --6.94471120834,1.95113360882,-0.149087741971 --6.94870185852,1.95213520527,-0.171497359872 --6.93669128418,1.94813895226,-0.193912625313 --6.93868207932,1.94914078712,-0.215304628015 --6.94867277145,1.95214152336,-0.237710952759 --6.9496679306,1.95214235783,-0.248915717006 --6.93665742874,1.94814610481,-0.271334052086 --6.93964767456,1.94914782047,-0.293743550777 --6.9416384697,1.95014953613,-0.316153436899 --6.94662904739,1.95215082169,-0.338560789824 --6.94061994553,1.95015347004,-0.35995772481 --6.94261026382,1.9511551857,-0.38236707449 --6.95760631561,1.95515406132,-0.393558591604 --6.92959547043,1.94715976715,-0.41599598527 --6.93658638,1.94916081429,-0.438400149345 --6.95157766342,1.9541605711,-0.460794836283 --6.93556785583,1.94916450977,-0.482204586267 --6.93955898285,1.95116567612,-0.504610776901 --6.9405503273,1.95216727257,-0.527020215988 --6.94054555893,1.95216810703,-0.538225412369 --6.94653654099,1.95416903496,-0.560627520084 --6.95752811432,1.95716905594,-0.584040224552 --6.95051908493,1.95617175102,-0.605441272259 --6.94550991058,1.95517408848,-0.627858400345 --6.96650266647,1.96117258072,-0.651252686977 --6.95249271393,1.95717608929,-0.67266535759 --6.94548749924,1.95617806911,-0.683881819248 --6.97048091888,1.96417593956,-0.708284437656 --6.96747255325,1.96317768097,-0.729678571224 --6.94646167755,1.95718228817,-0.75110656023 --6.96945524216,1.96518027782,-0.77550804615 --6.96044635773,1.96318304539,-0.79691439867 --6.96344232559,1.96418333054,-0.808111965656 --6.98443555832,1.97018134594,-0.832512259483 --6.95942497253,1.9641866684,-0.852934241295 --6.95541620255,1.96318852901,-0.875349581242 --6.96240854263,1.9661886692,-0.898759186268 --6.95840024948,1.96519052982,-0.92015594244 --6.95639181137,1.96519207954,-0.942566752434 --6.96638917923,1.96919107437,-0.954764485359 --6.97238111496,1.97119116783,-0.978173315525 --6.95437192917,1.96719539165,-0.99858635664 --6.96336460114,1.97019481659,-1.02198696136 --6.94935560226,1.96719837189,-1.04341006279 --6.96334886551,1.97219705582,-1.06781435013 --6.98034334183,1.9771951437,-1.09220838547 --6.9653377533,1.97319817543,-1.10141444206 --6.97233057022,1.97619795799,-1.12583482265 --6.97632360458,1.97819817066,-1.14822602272 --6.96031427383,1.97420191765,-1.16965675354 --6.96530723572,1.97720193863,-1.1930629015 --6.96730041504,1.97820234299,-1.21545875072 --6.95329093933,1.97520565987,-1.23688578606 --6.96928596497,1.98120355606,-1.26127362251 --6.95227956772,1.9762070179,-1.27049183846 --6.95427322388,1.97820734978,-1.29390525818 --6.9492650032,1.97720909119,-1.31530439854 --6.96826028824,1.98420619965,-1.34171438217 --6.94925117493,1.98021030426,-1.36112451553 --6.95524454117,1.98220992088,-1.38553977013 --6.95524120331,1.98321008682,-1.3967397213 --6.95523452759,1.9842107296,-1.41913890839 --6.95422744751,1.98521137238,-1.44255948067 --6.95022010803,1.98521268368,-1.46395456791 --6.92921066284,1.9802172184,-1.48337697983 --6.93820476532,1.98421597481,-1.50777804852 --6.93619775772,1.98421680927,-1.53120160103 --6.92819356918,1.98221862316,-1.54039537907 --6.92818689346,1.98421895504,-1.5638115406 --6.93518161774,1.98721790314,-1.58821702003 --6.92317342758,1.98522055149,-1.60862612724 --6.93016815186,1.98821938038,-1.63303005695 --6.92216062546,1.98722136021,-1.65444123745 --6.91515302658,1.98622298241,-1.67686653137 --6.92615127563,1.99022078514,-1.6900537014 --6.90814256668,1.98622477055,-1.7094720602 --6.92213869095,1.99222195148,-1.73587822914 --6.92113256454,1.99322223663,-1.75929450989 --6.90912437439,1.99122488499,-1.77970600128 --6.91912031174,1.99622273445,-1.80510818958 --6.90311193466,1.99222624302,-1.82452011108 --6.92311239243,1.99922180176,-1.8407137394 --6.91010427475,1.99722468853,-1.86113023758 --6.89209508896,1.99322843552,-1.88055348396 --6.89108943939,1.99422860146,-1.90295016766 --6.89108419418,1.9962284565,-1.92635965347 --6.89307880402,1.99822771549,-1.95077633858 --6.88607215881,1.99722921848,-1.97218322754 --6.90207242966,2.00322532654,-1.98838758469 --6.87906265259,1.9982303381,-2.00580358505 --6.89406061172,2.00422668457,-2.03320527077 --6.89605569839,2.00622606277,-2.05660057068 --6.88504838943,2.0052280426,-2.0780274868 --6.88104248047,2.00522851944,-2.10043549538 --6.88203811646,2.00822782516,-2.1238348484 --6.8790345192,2.008228302,-2.1350440979 --6.88803195953,2.0122256279,-2.16145157814 --6.89102745056,2.01522421837,-2.18585515022 --6.89302301407,2.01722335815,-2.21026301384 --6.8860168457,2.01722431183,-2.23268485069 --6.88201189041,2.01822471619,-2.25508999825 --6.88800859451,2.0222222805,-2.28049111366 --6.90000867844,2.02621936798,-2.29568338394 --6.9040055275,2.03021740913,-2.32109308243 --6.91100263596,2.03421473503,-2.34750151634 --6.90199661255,2.03321623802,-2.36891436577 --6.89899158478,2.03421592712,-2.39232707024 --6.91399145126,2.04121112823,-2.42173671722 --6.91498756409,2.0432100296,-2.44614052773 --6.90898418427,2.04321098328,-2.4563472271 --6.9189825058,2.0482070446,-2.48374772072 --6.92598056793,2.05320429802,-2.51014757156 --6.92797756195,2.05520272255,-2.53555846214 --6.92697381973,2.05720162392,-2.55997014046 --6.94097423553,2.06419658661,-2.58937311172 --6.94097089767,2.06619524956,-2.61377644539 --6.96097421646,2.0741891861,-2.6329703331 --6.96597242355,2.07818627357,-2.65937328339 --6.97997283936,2.08418107033,-2.68978428841 --6.97096729279,2.08418178558,-2.71118974686 --6.96496295929,2.084182024,-2.7335922718 --6.96396017075,2.08718061447,-2.75901293755 --6.9439535141,2.0821852684,-2.7642250061 --6.94695186615,2.0851829052,-2.79063510895 --6.9259428978,2.08118677139,-2.80805397034 --6.93094205856,2.08518385887,-2.83445000648 --6.92393779755,2.08618378639,-2.85787558556 --6.89292621613,2.07819056511,-2.87129759789 --6.8769197464,2.07619357109,-2.89071965218 --6.85891294479,2.07119774818,-2.89592528343 --6.84890842438,2.07119870186,-2.91734099388 --6.83990287781,2.07119941711,-2.93976616859 --6.84990406036,2.07619476318,-2.96815657616 --6.81389093399,2.06820297241,-2.97959136963 --6.8008852005,2.06620502472,-2.99899625778 --6.81288671494,2.07319951057,-3.02940320969 --6.79788160324,2.07020282745,-3.03662586212 --6.78787612915,2.06920385361,-3.05702590942 --6.78387355804,2.07120275497,-3.08144783974 --6.76586580276,2.06820607185,-3.09987449646 --6.76586437225,2.07120394707,-3.12528252602 --6.74085474014,2.06620955467,-3.13969731331 --6.72884941101,2.06521105766,-3.16011404991 --6.72084569931,2.0632121563,-3.16932082176 --6.72684669495,2.06920814514,-3.1977314949 --6.69683551788,2.0622150898,-3.21015572548 --6.66782426834,2.05522203445,-3.22257494926 --6.6748251915,2.06121730804,-3.2509765625 --6.65981912613,2.05921983719,-3.27040219307 --6.64681339264,2.05822134018,-3.28981304169 --6.65581560135,2.06221747398,-3.30701708794 --6.63580799103,2.0592212677,-3.32343506813 --6.62280273438,2.05822277069,-3.34386253357 --6.60979700089,2.0572245121,-3.36327433586 --6.58078622818,2.05023145676,-3.37570357323 --6.57078170776,2.05023241043,-3.39610886574 --6.57878398895,2.05622720718,-3.42551064491 --6.5547747612,2.05023360252,-3.42774105072 --6.53176593781,2.04623889923,-3.44215846062 --6.53276586533,2.04923582077,-3.46856856346 --6.51575899124,2.04723858833,-3.48598504066 --6.5087556839,2.04823827744,-3.50839781761 --6.50375366211,2.0502371788,-3.53180909157 --6.48874759674,2.04823946953,-3.55022573471 --6.45573472977,2.03924942017,-3.54746246338 --6.44573068619,2.03925013542,-3.56787014008 --6.43672704697,2.03925037384,-3.58928465843 --6.41771936417,2.03725409508,-3.60570812225 --6.40871620178,2.0372543335,-3.62712287903 --6.38270568848,2.03226065636,-3.63954639435 --6.36770009995,2.03026294708,-3.65695238113 --6.38370609283,2.03825569153,-3.67915892601 --6.35969638824,2.03326129913,-3.69258236885 --6.33168554306,2.02726817131,-3.70401239395 --6.32768440247,2.03026676178,-3.72741484642 --6.30867671967,2.02727031708,-3.74384379387 --6.30567598343,2.03026843071,-3.7682518959 --6.28466749191,2.02627277374,-3.78368496895 --6.27566432953,2.02527427673,-3.79189586639 --6.26365995407,2.02527570724,-3.81029343605 --6.24565267563,2.02227926254,-3.82671618462 --6.21764135361,2.01728653908,-3.83714151382 --6.20963859558,2.01828598976,-3.85956501961 --6.21164035797,2.02228188515,-3.88697052002 --6.19463300705,2.01828670502,-3.89018201828 --6.16662168503,2.01329421997,-3.90061187744 --6.15861940384,2.01429390907,-3.9220199585 --6.14361381531,2.01329612732,-3.94044971466 --6.12860774994,2.01229834557,-3.95786476135 --6.11860466003,2.0122988224,-3.97827672958 --6.09559488297,2.00830411911,-3.99170994759 --6.08659172058,2.00730609894,-3.99890971184 --6.06358194351,2.00331163406,-4.01132917404 --6.06258296967,2.00730848312,-4.03774499893 --6.04957866669,2.00630998611,-4.05717229843 --6.04857969284,2.01030635834,-4.08358573914 --6.02557086945,2.00631213188,-4.09600830078 --6.0155673027,2.00731229782,-4.11642074585 --6.00756454468,2.00631380081,-4.12462711334 --5.97755146027,2.00032234192,-4.13204813004 --5.96354675293,2.00032401085,-4.15047359467 --5.93253326416,1.99333310127,-4.15689373016 --5.92653274536,1.99533176422,-4.18031167984 --5.91252708435,1.99433350563,-4.19873762131 --5.8965215683,1.99333620071,-4.21515512466 --5.88951921463,1.99333715439,-4.22436857224 --5.87551403046,1.99233913422,-4.24178028107 --5.87051391602,1.99533712864,-4.26620101929 --5.83749914169,1.98834729195,-4.27062225342 --5.82649612427,1.98834776878,-4.29104804993 --5.81549310684,1.98934841156,-4.31045866013 --5.79948711395,1.98835110664,-4.32687950134 --5.79448604584,1.98835098743,-4.33810091019 --5.78548383713,1.98935079575,-4.35850381851 --5.76147317886,1.98535704613,-4.36892414093 --5.75747489929,1.98935437202,-4.39434671402 --5.74046802521,1.98735761642,-4.40976428986 --5.73546934128,1.99035513401,-4.43418073654 --5.70145273209,1.98236620426,-4.43761348724 --5.71246099472,1.98935890198,-4.45880222321 --5.6914525032,1.98636376858,-4.47223711014 --5.66944360733,1.98236942291,-4.48365497589 --5.64643383026,1.9793753624,-4.49508571625 --5.63343000412,1.9793766737,-4.51350498199 --5.61042022705,1.97638273239,-4.5239238739 --5.58841085434,1.97238850594,-4.53534603119 --5.59041452408,1.97638487816,-4.55155992508 --5.55739784241,1.96839594841,-4.55398082733 --5.53839111328,1.96640026569,-4.56740045547 --5.52738809586,1.96740055084,-4.58782815933 --5.50938129425,1.96540415287,-4.60225105286 --5.49937963486,1.96740436554,-4.62165212631 --5.47136640549,1.96141278744,-4.62909507751 --5.48137521744,1.96840524673,-4.6512966156 --5.46036624908,1.96541059017,-4.66271305084 --5.44336032867,1.9644138813,-4.6781411171 --5.42935609818,1.96441566944,-4.695561409 --5.40234327316,1.95942401886,-4.70198297501 --5.39334249496,1.96042323112,-4.72339963913 --5.37333440781,1.95842802525,-4.73582363129 --5.36433076859,1.95742988586,-4.74303770065 --5.34132099152,1.95443630219,-4.75347185135 --5.33532238007,1.95743393898,-4.77687931061 --5.31331253052,1.95443999767,-4.78730201721 --5.29330444336,1.95244467258,-4.79972887039 --5.27529764175,1.95044863224,-4.81314563751 --5.28130483627,1.95544278622,-4.83234071732 --5.26830148697,1.95644390583,-4.85076475143 --5.24529123306,1.95245039463,-4.86018896103 --5.22928619385,1.95245325565,-4.87560987473 --5.22028541565,1.95445215702,-4.8980383873 --5.19727563858,1.95145869255,-4.90746545792 --5.18727445602,1.95245814323,-4.92787790298 --5.15525722504,1.94546973705,-4.92931318283 --5.14525365829,1.94447219372,-4.93552970886 --5.12524557114,1.94247722626,-4.94694900513 --5.10323524475,1.93948340416,-4.95636844635 --5.09023284912,1.94048452377,-4.97479438782 --5.09124040604,1.94647789001,-5.00519943237 --5.05321884155,1.93749308586,-5.00064086914 --5.04621648788,1.93749392033,-5.00884628296 --5.05222797394,1.94548428059,-5.04425096512 --5.02921772003,1.94249081612,-5.0536866188 --4.9992017746,1.93650197983,-5.05510854721 --4.98820066452,1.93750166893,-5.07553434372 --4.98320388794,1.94149839878,-5.09993219376 --4.94518136978,1.93251371384,-5.09538650513 --4.94218301773,1.93451225758,-5.1075925827 --4.91917276382,1.93151950836,-5.11500692368 --4.92018127441,1.93751192093,-5.14742851257 --4.90617799759,1.93851339817,-5.16485309601 --4.88116598129,1.9345215559,-5.17128372192 --4.85515260696,1.92953050137,-5.17570257187 --4.84715414047,1.932528615,-5.19811153412 --4.82513999939,1.92753839493,-5.1923418045 --4.80913496017,1.92654144764,-5.2067565918 --4.80514001846,1.93153679371,-5.23417520523 --4.77412223816,1.92454886436,-5.23360300064 --4.76011896133,1.92555058002,-5.25001716614 --4.7561249733,1.93054556847,-5.27844572067 --4.71710014343,1.92056310177,-5.26887559891 --4.71510314941,1.92356061935,-5.28309011459 --4.698097229,1.92256379128,-5.29752063751 --4.67608737946,1.91957044601,-5.30594539642 --4.65407657623,1.91657745838,-5.31335878372 --4.64708042145,1.92057418823,-5.33878850937 --4.63407802582,1.92157530785,-5.35620117188 --4.5990562439,1.91359043121,-5.35063886642 --4.60506677628,1.91958272457,-5.37283563614 --4.58505868912,1.91858792305,-5.38427400589 --4.57105541229,1.9185898304,-5.39967489243 --4.54704332352,1.91559779644,-5.40610980988 --4.52403211594,1.91260516644,-5.41354322433 --4.50602579117,1.91160929203,-5.42596721649 --4.50002574921,1.91260921955,-5.43618488312 --4.47701358795,1.90861725807,-5.44159555435 --4.46901702881,1.91261434555,-5.46602153778 --4.44600582123,1.90962207317,-5.47244644165 --4.43200302124,1.910623312,-5.48987340927 --4.41800022125,1.91162478924,-5.50628805161 --4.40600013733,1.9136248827,-5.52570867538 --4.38499069214,1.91163086891,-5.53514242172 --4.37398529053,1.91063463688,-5.53834867477 --4.35998296738,1.91163599491,-5.55476331711 --4.34097576141,1.91064095497,-5.56619215012 --4.32296895981,1.90964508057,-5.57861852646 --4.30396175385,1.90864992142,-5.59004878998 --4.27994918823,1.90465831757,-5.59548330307 --4.27795314789,1.90765547752,-5.60968589783 --4.25494194031,1.90466320515,-5.61611843109 --4.24294185638,1.90766298771,-5.6355381012 --4.21592617035,1.90267419815,-5.63596248627 --4.20893096924,1.90667021275,-5.6613740921 --4.18692064285,1.90467739105,-5.66880607605 --4.16891431808,1.90368151665,-5.68123483658 --4.15390443802,1.9006882906,-5.67944955826 --4.1419043541,1.90268802643,-5.69886684418 --4.12790298462,1.90468907356,-5.71629190445 --4.10188770294,1.89969956875,-5.71772003174 --4.08988809586,1.90269935131,-5.73713636398 --4.06387329102,1.89870965481,-5.73957872391 --4.05087280273,1.89970993996,-5.75799846649 --4.03986692429,1.89871382713,-5.76121139526 --4.00984716415,1.89272749424,-5.75765132904 --3.99284172058,1.89273118973,-5.77006816864 --3.97183156013,1.89073812962,-5.77749204636 --3.96283650398,1.89473462105,-5.80292701721 --3.94983577728,1.89673519135,-5.82033491135 --3.92382049561,1.89274597168,-5.82177352905 --3.90880966187,1.88875317574,-5.81898593903 --3.88980174065,1.88775873184,-5.82840251923 --3.87580060959,1.88975965977,-5.84582662582 --3.86179947853,1.89176058769,-5.86325073242 --3.83978819847,1.88876819611,-5.86968326569 --3.81877875328,1.88777518272,-5.87711191177 --3.8097755909,1.88777720928,-5.88332939148 --3.79377174377,1.8877799511,-5.897752285 --3.77676653862,1.88778364658,-5.91017007828 --3.75575685501,1.88679051399,-5.91760063171 --3.73374533653,1.88379848003,-5.9230260849 --3.71674132347,1.88480162621,-5.9374666214 --3.70273971558,1.88680279255,-5.95387744904 --3.69373703003,1.88680481911,-5.96009540558 --3.67172551155,1.88381278515,-5.96552276611 --3.65772485733,1.88581371307,-5.98294353485 --3.63771605492,1.88481986523,-5.99137067795 --3.61570453644,1.88282799721,-5.99680042267 --3.59870004654,1.88283133507,-6.01022958755 --3.57768940926,1.88083863258,-6.01665401459 --3.56367993355,1.87884533405,-6.01487493515 --3.54967975616,1.88084590435,-6.03330516815 --3.53067207336,1.87985134125,-6.0427274704 --3.5126657486,1.87985610962,-6.05314397812 --3.49666261673,1.88085877895,-6.06756639481 --3.47965812683,1.8808619976,-6.08099508286 --3.45764613152,1.878870368,-6.08541965485 --3.45064687729,1.88087034225,-6.09564399719 --3.42462921143,1.87588250637,-6.09407806396 --3.40762448311,1.87688612938,-6.10649824142 --3.39362478256,1.87888646126,-6.12492513657 --3.37361550331,1.87789309025,-6.13234758377 --3.35661101341,1.87889671326,-6.14476680756 --3.33960771561,1.87989962101,-6.15920591354 --3.32359290123,1.87490952015,-6.15140962601 --3.30358505249,1.87491548061,-6.16085338593 --3.27856826782,1.87092709541,-6.16028881073 --3.26657128334,1.87392568588,-6.1806974411 --3.2425558567,1.87093663216,-6.18112611771 --3.22855687141,1.8729364872,-6.20055961609 --3.20053505898,1.86795151234,-6.19399547577 --3.18952894211,1.86695575714,-6.19621229172 --3.17552924156,1.86895632744,-6.21362686157 --3.16353321075,1.87295460701,-6.23504161835 --3.13751459122,1.86796748638,-6.23248291016 --3.11750626564,1.86797392368,-6.24092006683 --3.10350632668,1.86997437477,-6.25833177567 --3.08849334717,1.86698329449,-6.25254869461 --3.06948661804,1.86698842049,-6.26298713684 --3.05849266052,1.87098550797,-6.28639793396 --3.03047037125,1.86600077152,-6.27984523773 --3.01346540451,1.86600470543,-6.29125595093 --2.99746465683,1.86800611019,-6.30870246887 --2.97545146942,1.86601543427,-6.3111243248 --2.96043753624,1.8620249033,-6.30433750153 --2.95144939423,1.86901831627,-6.3347697258 --2.92743325233,1.86602973938,-6.33420324326 --2.90341544151,1.86204195023,-6.33162069321 --2.88941764832,1.86504161358,-6.35104560852 --2.86039161682,1.85805916786,-6.340487957 --2.85040092468,1.86405432224,-6.36689853668 --2.84340310097,1.86605346203,-6.37812328339 --2.81537866592,1.86007034779,-6.36855888367 --2.79637002945,1.85907661915,-6.3759727478 --2.082020998,1.83534300327,-6.59024572372 --2.07402062416,1.83634400368,-6.59745025635 --2.06404161453,1.8463331461,-6.63589334488 --2.03701138496,1.83935320377,-6.62032556534 --2.01699995995,1.83836174011,-6.62374162674 --1.9969907999,1.83836913109,-6.63017702103 --1.97698223591,1.83837616444,-6.63761854172 --1.96198785305,1.84337484837,-6.65904664993 --1.95298612118,1.84437668324,-6.66526222229 --1.92695701122,1.83739602566,-6.65068912506 --1.90795075893,1.83840167522,-6.6601228714 --1.88794159889,1.8384090662,-6.66655874252 --1.86492204666,1.83542275429,-6.66199064255 --1.8449113369,1.83443105221,-6.66641521454 --1.82991862297,1.83942866325,-6.68984937668 --1.81991326809,1.83943283558,-6.69206142426 --1.79890120029,1.83844196796,-6.695499897 --1.78390812874,1.84344005585,-6.71792507172 --1.75486791134,1.83446598053,-6.69236421585 --1.73987483978,1.83946382999,-6.71478796005 --1.7158510685,1.83447992802,-6.70622301102 --1.69483816624,1.83348965645,-6.70865869522 --1.6838299036,1.83249568939,-6.70787620544 --1.66683077812,1.83549726009,-6.72430515289 --1.64380848408,1.83151245117,-6.7167301178 --1.62279415131,1.83052325249,-6.71715688705 --1.60780394077,1.83651959896,-6.7425904274 --1.58478307724,1.83253407478,-6.73702716827 --1.57079708576,1.84052813053,-6.76645755768 --1.55275940895,1.83055126667,-6.73566961288 --1.53375506401,1.83155596256,-6.74711084366 --1.51675474644,1.83455836773,-6.76152610779 --1.49775004387,1.83656346798,-6.771961689 --1.47171461582,1.82858633995,-6.75139379501 --1.45471787453,1.8325868845,-6.7698264122 --1.43270003796,1.83059966564,-6.76726293564 --1.42168903351,1.82860708237,-6.76347064972 --1.40368843079,1.83160984516,-6.77790355682 --1.37966310978,1.82662689686,-6.76835155487 --1.35764360428,1.82364058495,-6.76378250122 --1.33763480186,1.82464826107,-6.77022171021 --1.319632411,1.82665193081,-6.78264427185 --1.29459869862,1.81967389584,-6.76408052444 --1.28459525108,1.82067728043,-6.76830482483 --1.26659286022,1.82268095016,-6.78072738647 --1.24457240105,1.8196952343,-6.77515888214 --1.22355771065,1.81870615482,-6.77559518814 --1.20656251907,1.82370603085,-6.79502391815 --1.18856477737,1.82770740986,-6.8124628067 --1.17755246162,1.82471549511,-6.80767154694 --1.16056013107,1.83071386814,-6.8301076889 --1.13351142406,1.81974434853,-6.79654169083 --1.11450779438,1.82174897194,-6.80797767639 --1.09248697758,1.81876349449,-6.80241441727 --1.07146692276,1.815777421,-6.79683208466 --1.05045223236,1.81478857994,-6.79727125168 --1.04044890404,1.81579184532,-6.80149459839 --1.02144169807,1.81679856777,-6.80891609192 --1.00042629242,1.81581008434,-6.80835294724 --0.98041844368,1.81681728363,-6.81579494476 --0.9424071908,1.81982910633,-6.83364582062 --0.920386493206,1.81784379482,-6.82808876038 --0.914409697056,1.82583212852,-6.85830545425 --0.888359427452,1.81486332417,-6.82374572754 --0.87035793066,1.81786692142,-6.83615970612 --0.829260230064,1.79392588139,-6.76281356812 --0.809250712395,1.79493427277,-6.76825284958 --0.788232803345,1.79294705391,-6.76569223404 --0.777216553688,1.78995764256,-6.7569026947 --0.758217990398,1.79395985603,-6.7733502388 --0.737190842628,1.78997790813,-6.76076507568 --0.717183947563,1.79098463058,-6.76921224594 --0.697168707848,1.78999602795,-6.76863765717 --0.679172158241,1.79499709606,-6.78606367111 --0.658152222633,1.79201114178,-6.78150033951 --0.647141575813,1.79101860523,-6.77872848511 --0.626120865345,1.78903317451,-6.77316570282 --0.609134614468,1.79602849483,-6.80058813095 --0.588115990162,1.79504203796,-6.7970290184 --0.569114089012,1.79804623127,-6.80945968628 --0.547077953815,1.79106914997,-6.78888893127 --0.527070403099,1.79207646847,-6.7963309288 --0.517064213753,1.79208147526,-6.79754734039 --0.496039509773,1.78909826279,-6.78797960281 --0.476025104523,1.78810918331,-6.78840923309 --0.457026332617,1.79211175442,-6.80384349823 --0.435997605324,1.78813076019,-6.79027223587 --0.414972484112,1.78414773941,-6.78070831299 --0.406999766827,1.79413449764,-6.81393146515 --0.38698258996,1.7931470871,-6.81135702133 --0.364943891764,1.78617155552,-6.78879785538 --0.344938546419,1.78817784786,-6.79824066162 --0.325947165489,1.79417657852,-6.8206782341 --0.304913908243,1.78819787502,-6.80310773849 --0.284890681505,1.78621387482,-6.79452991486 --0.27386957407,1.78222715855,-6.7817530632 --0.25589337945,1.79221749306,-6.81817960739 --0.23385412991,1.78524231911,-6.79563140869 --0.213834628463,1.78325617313,-6.79105901718 --0.193827569485,1.78526365757,-6.79849767685 --0.173819571733,1.78727149963,-6.80493545532 --0.154818385839,1.79027545452,-6.81735420227 --0.144811287522,1.79028105736,-6.8175702095 --0.123783744872,1.78629934788,-6.80601596832 --0.103771708906,1.7873095274,-6.80844974518 --0.0837574750185,1.78732073307,-6.80888223648 --0.0637432485819,1.78733193874,-6.80931520462 --0.0437373742461,1.78933870792,-6.81775045395 --0.0237115696073,1.7863560915,-6.80717992783 --0.0137000009418,1.78436398506,-6.80339479446 -0.00630359817296,1.78736972809,-6.81383037567 --0.00131080078427,1.77161884308,-5.97424554825 -0.0186896286905,1.76761305332,-5.96164274216 -0.0386871919036,1.76360547543,-5.94604253769 -0.0587098859251,1.76561141014,-5.95443534851 -0.0777110233903,1.76260626316,-5.94281578064 -0.0877013504505,1.75759804249,-5.92702198029 -0.107731595635,1.76260793209,-5.94240999222 -0.12875905633,1.76561617851,-5.95481872559 -0.14775814116,1.76160991192,-5.94120359421 -0.168793961406,1.76762259007,-5.96160411835 -0.188798159361,1.7656185627,-5.95200634003 -0.197800293565,1.76361703873,-5.94818878174 -0.218820616603,1.76562142372,-5.9535984993 -0.237815871835,1.76061308384,-5.93599224091 -0.258847355843,1.76562345028,-5.95239067078 -0.277844846249,1.76161634922,-5.93678379059 -0.296838194132,1.75560712814,-5.91718387604 -0.316847711802,1.75460612774,-5.91258716583 -0.326854914427,1.7546069622,-5.91278600693 -0.345857650042,1.75160264969,-5.90217828751 -0.365880280733,1.75460863113,-5.91056489944 -0.385886818171,1.75260603428,-5.90297412872 -0.403880834579,1.74659752846,-5.88436174393 -0.424900233746,1.74860143661,-5.88877391815 -0.445937335491,1.75561487675,-5.91115474701 -0.454924076796,1.74960517883,-5.89136791229 -0.47495251894,1.75461435318,-5.90574073792 -0.495981365442,1.7586234808,-5.92013216019 -0.513968110085,1.75161099434,-5.89353942871 -0.533979654312,1.75061106682,-5.89094305038 -0.553996384144,1.75261390209,-5.89333581924 -0.571989178658,1.74660480022,-5.87273788452 -0.581997275352,1.74660623074,-5.87393522263 -0.603027284145,1.75261580944,-5.88931894302 -0.621012628078,1.744602561,-5.86074256897 -0.644061803818,1.75462210178,-5.89512109756 -0.662060558796,1.75061607361,-5.88051366806 -0.680050194263,1.74460506439,-5.85593223572 -0.69906026125,1.74360489845,-5.85232067108 -0.712092280388,1.75061821938,-5.87651824951 -0.731096863747,1.74861490726,-5.86692094803 -0.747081339359,1.74060189724,-5.83831644058 -0.76911431551,1.74661302567,-5.85670518875 -0.788118958473,1.74460995197,-5.84711027145 -0.806121051311,1.74160575867,-5.83550310135 -0.826131284237,1.74160516262,-5.83091497421 -0.83614307642,1.74260854721,-5.83609962463 -0.855147063732,1.74060499668,-5.82551050186 -0.877180457115,1.74661660194,-5.84488868713 -0.897192418575,1.74661707878,-5.84229421616 -0.91418671608,1.74160909653,-5.82269573212 -0.934202313423,1.74261152744,-5.82408952713 -0.942198455334,1.74060690403,-5.81328487396 -0.96020001173,1.73760247231,-5.80068683624 -0.982225239277,1.74160957336,-5.81108856201 -1.00022780895,1.73860573769,-5.79948806763 -1.02024066448,1.73860681057,-5.7978925705 -1.03925025463,1.73860633373,-5.79328775406 -1.05725395679,1.73660302162,-5.78268575668 -1.06826889515,1.73860800266,-5.7908744812 -1.08828389645,1.74061000347,-5.79126977921 -1.10327029228,1.73259842396,-5.76367664337 -1.12429118156,1.73560345173,-5.77006959915 -1.14631259441,1.73860871792,-5.77648115158 -1.16230785847,1.73360145092,-5.75787591934 -1.18232262135,1.73460376263,-5.75827217102 -1.19634950161,1.74161398411,-5.77746868134 -1.213347435,1.73760783672,-5.76087617874 -1.23034703732,1.73360288143,-5.74627733231 -1.24835205078,1.7326002121,-5.73667669296 -1.26836836338,1.73360335827,-5.73906373978 -1.28838312626,1.73460566998,-5.73945856094 -1.30337512493,1.72959673405,-5.71686029434 -1.31538820267,1.73160040379,-5.72207450867 -1.33942329884,1.73861253262,-5.74344921112 -1.35642433167,1.73660814762,-5.72984933853 -1.37242043018,1.73160147667,-5.71125602722 -1.39243280888,1.73260223866,-5.70866441727 -1.41545963287,1.73761022091,-5.72105693817 -1.43145763874,1.73360455036,-5.70445680618 -1.44347214699,1.73660898209,-5.71165704727 -1.45846700668,1.7316018343,-5.69205331802 -1.47848010063,1.73260319233,-5.69045639038 -1.49347507954,1.72759616375,-5.67085599899 -1.51650166512,1.73260402679,-5.68324375153 -1.53249919415,1.72859823704,-5.66565418243 -1.54250502586,1.72859847546,-5.66386127472 -1.56151688099,1.72959935665,-5.66125011444 -1.57952320576,1.72859764099,-5.65265226364 -1.60355091095,1.73360598087,-5.6660490036 -1.61854791641,1.72960007191,-5.64844417572 -1.6355496645,1.72659623623,-5.63485622406 -1.65355610847,1.72559452057,-5.62626075745 -1.66757714748,1.73060202599,-5.64045238495 -1.68759191036,1.73260438442,-5.64084148407 -1.70760583878,1.7336063385,-5.64023637772 -1.72862231731,1.73660933971,-5.64163732529 -2.40997576714,1.74561405182,-5.45203733444 -2.42998695374,1.7466148138,-5.44744873047 -2.44999885559,1.74861586094,-5.44385194778 -2.46900987625,1.74961698055,-5.44023561478 -2.4910261631,1.75261986256,-5.44163227081 -2.50803112984,1.75061821938,-5.43103885651 -2.51803660393,1.75161850452,-5.42824745178 -2.53404140472,1.75061666965,-5.41763544083 -2.56006526947,1.75562298298,-5.42703342438 -2.58408522606,1.75962769985,-5.43242740631 -2.60109019279,1.75862574577,-5.42084121704 -2.61609172821,1.75662255287,-5.40624570847 -2.63209581375,1.75562047958,-5.39464235306 -2.6431043148,1.75762236118,-5.3958325386 -2.66511917114,1.75962471962,-5.39524030685 -2.68412828445,1.75962471962,-5.38864660263 -2.69812822342,1.75762093067,-5.37205266953 -2.71313071251,1.75561821461,-5.35845136642 -2.73915314674,1.76062369347,-5.36585474014 -2.74615335464,1.75962209702,-5.35805416107 -2.76516389847,1.76062273979,-5.3534412384 -2.78116679192,1.75862026215,-5.33985853195 -2.80117869377,1.7606215477,-5.3362531662 -2.81718182564,1.75861907005,-5.32267141342 -2.83719420433,1.76062059402,-5.32005643845 -2.86221408844,1.765625,-5.32446193695 -2.8712182045,1.76562488079,-5.32066011429 -2.88121128082,1.75961852074,-5.29607868195 -2.90723395348,1.76562404633,-5.30446100235 -2.92223644257,1.76362168789,-5.29086256027 -2.93623733521,1.7616186142,-5.2752661705 -2.95925402641,1.76562178135,-5.27666091919 -2.97425580025,1.76261889935,-5.26108360291 -2.98726654053,1.76562130451,-5.26428174973 -3.00627660751,1.76662194729,-5.25867414474 -3.02328252792,1.7666208744,-5.24808168411 -3.04028820992,1.76561963558,-5.23748970032 -3.06029963493,1.76762080193,-5.23288869858 -3.08231425285,1.77062320709,-5.2322807312 -3.09531378746,1.76761972904,-5.21469068527 -3.11233067513,1.77262473106,-5.22488164902 -3.12933659554,1.77162361145,-5.21428918839 -3.15135073662,1.7746257782,-5.21268796921 -3.16535282135,1.77362322807,-5.19808483124 -3.19037151337,1.77762722969,-5.20148229599 -3.20637583733,1.77662551403,-5.1888923645 -3.22138905525,1.7806289196,-5.19508457184 -3.22737812996,1.77362143993,-5.16550540924 -3.25540089607,1.77962708473,-5.17389631271 -3.27240777016,1.77962648869,-5.16429185867 -3.2884118557,1.77862465382,-5.15071344376 -3.30642008781,1.77962470055,-5.14310359955 -3.31942081451,1.77762174606,-5.12650823593 -3.3304271698,1.77862250805,-5.12471532822 -3.34643220901,1.77762138844,-5.11311674118 -3.36444044113,1.77862119675,-5.10451745987 -3.38445091248,1.77962219715,-5.09891891479 -3.41147112846,1.78562653065,-5.10332489014 -3.419465065,1.780621171,-5.07972621918 -3.43647146225,1.78062045574,-5.06913280487 -3.45749211311,1.78762674332,-5.08332300186 -3.46047925949,1.77961874008,-5.05074596405 -3.47848653793,1.77961838245,-5.04115772247 -3.51752281189,1.79162883759,-5.06453752518 -3.51550388336,1.78161871433,-5.02496290207 -3.53451275826,1.78261911869,-5.01736688614 -3.56353569031,1.7896245718,-5.02574920654 -3.56452894211,1.78562057018,-5.00896263123 -3.59355115891,1.79162573814,-5.01635360718 -3.61456298828,1.79462707043,-5.01175165176 -3.62556171417,1.79162359238,-4.99216365814 -3.63555932045,1.78761994839,-4.97157335281 -3.65957427025,1.79162228107,-4.9699845314 -3.66957211494,1.78761863708,-4.94939565659 -3.68558502197,1.79162192345,-4.9555811882 -3.7055952549,1.79362273216,-4.94898462296 -3.71759581566,1.79162013531,-4.93139266968 -3.73760604858,1.79362082481,-4.92479610443 -3.76061987877,1.79662299156,-4.92219781876 -3.77262067795,1.79462039471,-4.90460634232 -3.79563474655,1.79762279987,-4.90299510956 -3.80864310265,1.79962432384,-4.90320014954 -3.81764030457,1.79662048817,-4.8816113472 -3.84165501595,1.79962289333,-4.88001298904 -3.86166572571,1.80262410641,-4.87439966202 -3.87066268921,1.79862010479,-4.85182523727 -3.88666796684,1.79861927032,-4.8392367363 -3.90968799591,1.80562508106,-4.85341882706 -3.91267871857,1.79861903191,-4.82384157181 -3.93669319153,1.8026214838,-4.82223796844 -3.94969558716,1.80161952972,-4.80565309525 -3.97070717812,1.80362093449,-4.80103969574 -3.98871445656,1.80462086201,-4.7904548645 -4.00472021103,1.80462014675,-4.77786540985 -4.00771760941,1.80261802673,-4.76606559753 -4.02972984314,1.80561971664,-4.76146459579 -4.04773807526,1.80661976337,-4.75186681747 -4.06174135208,1.80561840534,-4.73628568649 -4.07774734497,1.8056179285,-4.72468328476 -4.10776758194,1.811622262,-4.73007011414 -4.10975885391,1.80561673641,-4.69950485229 -4.13577985764,1.81362271309,-4.71568489075 -4.13977384567,1.8086181879,-4.68909835815 -4.16478872299,1.8126206398,-4.68749713898 -4.167781353,1.80661582947,-4.65991210938 -4.1887922287,1.8086168766,-4.65233039856 -4.2108039856,1.81161820889,-4.64673519135 -4.21280097961,1.80961632729,-4.63492441177 -4.24081897736,1.81561970711,-4.63632249832 -4.242811203,1.80861496925,-4.60774183273 -4.27483272552,1.816619277,-4.61314153671 -4.28983783722,1.81661880016,-4.60053491592 -4.26680612564,1.79860639572,-4.54299020767 -4.24377536774,1.78159439564,-4.48643827438 -4.21374225616,1.76458287239,-4.43669223785 -4.19171333313,1.74857151508,-4.38214063644 -4.16668224335,1.73055970669,-4.32459449768 -4.156665802,1.71955251694,-4.28502178192 -4.15465688705,1.71254789829,-4.2544426918 -4.16365814209,1.7095464468,-4.23585748672 -4.17566251755,1.70854592323,-4.22027301788 -4.17665958405,1.70554411411,-4.2064948082 -4.19466876984,1.70754528046,-4.19789838791 -4.20967626572,1.70854580402,-4.18630027771 -4.21167182922,1.70354282856,-4.16170310974 -4.2326836586,1.70554471016,-4.15512084961 -4.22867441177,1.69754004478,-4.12255811691 -4.22366476059,1.68953549862,-4.09096860886 -4.22766494751,1.68853485584,-4.08118009567 -4.25468301773,1.69453859329,-4.08256578445 -4.26268386841,1.6915371418,-4.06200504303 -4.26568126678,1.68753492832,-4.038418293 -4.28168964386,1.68853580952,-4.02782344818 -4.28869056702,1.68553459644,-4.0082359314 -4.30169630051,1.68553483486,-3.99464416504 -4.30869960785,1.68553519249,-3.98884010315 -4.31369924545,1.68153345585,-3.96725749969 -4.32770586014,1.68153393269,-3.95368123055 -4.33570766449,1.67953312397,-3.93509674072 -4.34571123123,1.67853283882,-3.91949439049 -4.35271263123,1.67553198338,-3.89892959595 -4.3657207489,1.67853355408,-3.89911699295 -4.36271476746,1.67153048515,-3.86955332756 -4.37171792984,1.66953027248,-3.85295605659 -4.38572502136,1.67053103447,-3.84036612511 -4.3907251358,1.6675298214,-3.81879353523 -4.41073703766,1.66953194141,-3.81219267845 -4.41773891449,1.66753137112,-3.79360127449 -4.42174053192,1.66653108597,-3.78382086754 -4.42874240875,1.66453063488,-3.76523089409 -4.44575214386,1.66553211212,-3.75563573837 -4.45175361633,1.66353142262,-3.73604941368 -4.46576118469,1.66353237629,-3.7234609127 -4.47876787186,1.66353309155,-3.70987462997 -4.47676324844,1.65753114223,-3.68329620361 -4.48476839066,1.65853178501,-3.67750763893 -4.49977636337,1.65953314304,-3.66690015793 -4.50978088379,1.65853333473,-3.65032362938 -4.51778459549,1.65653336048,-3.63273715973 -4.52778959274,1.65653383732,-3.61714458466 -4.54079627991,1.65653479099,-3.60356020927 -4.54980039597,1.65553498268,-3.58697199821 -4.55180120468,1.65353477001,-3.57618689537 -4.55380058289,1.64953398705,-3.55360746384 -4.57281208038,1.65253603458,-3.546002388 -4.58982181549,1.65353775024,-3.53542113304 -4.59282207489,1.65053725243,-3.5148229599 -4.60182666779,1.64953780174,-3.49823760986 -4.61083221436,1.65053868294,-3.49344491959 -4.6178355217,1.64853894711,-3.47585082054 -4.62383842468,1.64653909206,-3.45627903938 -4.63484430313,1.64653992653,-3.44070458412 -4.64785146713,1.64654123783,-3.42810440063 -4.65485525131,1.64454162121,-3.41051316261 -4.66686201096,1.6445428133,-3.39593482018 -4.6658616066,1.64254236221,-3.38413381577 -4.67286539078,1.64054274559,-3.36654448509 -4.69187641144,1.64354503155,-3.35795116425 -4.69187641144,1.63954460621,-3.33437871933 -4.70188236237,1.63854563236,-3.31879401207 -4.7148900032,1.6395471096,-3.30521202087 -4.72389507294,1.63854789734,-3.28961491585 -4.71789169312,1.63454711437,-3.27284479141 -4.73490190506,1.63654911518,-3.26324224472 -4.73890399933,1.63354945183,-3.24267363548 -4.74490785599,1.63155019283,-3.22507691383 -4.76391935349,1.63455247879,-3.21648025513 -4.76391983032,1.63055253029,-3.19390034676 -4.76692199707,1.62755298615,-3.17332339287 -4.79393815994,1.6355561018,-3.18151259422 -4.77392673492,1.62455415726,-3.14494490623 -4.79093742371,1.62655627728,-3.13435935974 -4.80494594574,1.62755799294,-3.12177252769 -4.81095027924,1.62655901909,-3.10417985916 -4.81995630264,1.62556028366,-3.08760666847 -4.83296394348,1.62856185436,-3.08580207825 -4.82496070862,1.62156152725,-3.0582280159 -4.83696842194,1.6225631237,-3.04463601112 -4.84597444534,1.62156462669,-3.02806401253 -4.84997844696,1.61956560612,-3.00947022438 -4.85898447037,1.61856710911,-2.99289941788 -4.87399435043,1.62056910992,-2.98130488396 -4.86599063873,1.61556875706,-2.96551394463 -4.8810005188,1.61757087708,-2.95391988754 -4.89500904083,1.61857295036,-2.94133234024 -4.89301013947,1.61457371712,-2.91874837875 -4.89501333237,1.61157476902,-2.89817452431 -4.91502523422,1.61557722092,-2.88957977295 -4.91102552414,1.61057794094,-2.86501526833 -4.91903066635,1.61157917976,-2.86020421982 -4.93003797531,1.61158108711,-2.84562087059 -4.93404245377,1.60958254337,-2.82605433464 -4.94304895401,1.60958433151,-2.81144809723 -4.955057621,1.61058628559,-2.79687595367 -4.95906209946,1.60858774185,-2.77927231789 -4.9610657692,1.60558927059,-2.75870609283 -4.9820766449,1.61159133911,-2.76090121269 -4.96907329559,1.60359179974,-2.73232603073 -4.98008155823,1.6035939455,-2.7177438736 -4.99409103394,1.60559618473,-2.70515465736 -4.99509429932,1.60259771347,-2.68458104134 -5.00110006332,1.60159957409,-2.66798377037 -5.00210189819,1.60060036182,-2.65819334984 -5.00510692596,1.59860217571,-2.63862419128 -5.01911640167,1.59960460663,-2.62603521347 -5.0271229744,1.59960663319,-2.61044096947 -5.02612638474,1.59560835361,-2.58887147903 -5.03313302994,1.59561049938,-2.57228755951 -5.04514169693,1.59661281109,-2.55869626999 -5.04114151001,1.59361350536,-2.54689669609 -5.03814458847,1.58961522579,-2.52433085442 -5.06716012955,1.59661853313,-2.51973414421 -5.0681643486,1.5936204195,-2.50015044212 -5.07317066193,1.59262251854,-2.48256802559 -5.08217811584,1.59262490273,-2.46698617935 -5.07317638397,1.58762562275,-2.45220088959 -5.08318424225,1.58862817287,-2.43760967255 -5.09119224548,1.58863043785,-2.42201852798 -5.09319734573,1.58663284779,-2.40244984627 -5.10520648956,1.5876352787,-2.38885831833 -5.11521434784,1.5876377821,-2.37426686287 -5.10921669006,1.58363997936,-2.35070371628 -5.12222385406,1.58664143085,-2.3478937149 -5.12322902679,1.58364379406,-2.32831835747 -5.13223695755,1.58364641666,-2.31273841858 -5.13324213028,1.58164894581,-2.29316473007 -5.1392493248,1.58165156841,-2.27657699585 -5.1542596817,1.58365428448,-2.26399207115 -5.15526437759,1.58165681362,-2.24539899826 -5.15426683426,1.57965803146,-2.23462057114 -5.16727685928,1.58166098595,-2.22103643417 -5.17528438568,1.58166360855,-2.20544743538 -5.17629003525,1.57866621017,-2.18685746193 -5.18029642105,1.57766890526,-2.16927433014 -5.18230247498,1.57567167282,-2.15069508553 -5.20231485367,1.57967460155,-2.14010977745 -5.19431495667,1.57567608356,-2.12633466721 -5.19632101059,1.57467865944,-2.10873508453 -5.20132827759,1.57368171215,-2.09116363525 -5.20733594894,1.57368457317,-2.07457971573 -5.21834516525,1.57468748093,-2.05999732018 -5.21535015106,1.57069051266,-2.03942131996 -5.22235488892,1.57169187069,-2.03361105919 -5.22936296463,1.57169497013,-2.01703667641 -5.23637104034,1.57169783115,-2.00144076347 -5.23337602615,1.56870102882,-1.98086750507 -5.24238491058,1.569704175,-1.96528935432 -5.24739217758,1.56870722771,-1.9486989975 -5.25540113449,1.56971025467,-1.93311226368 -5.25740480423,1.56871199608,-1.92432403564 -5.26641368866,1.56971502304,-1.90874516964 -5.26942110062,1.56771826744,-1.89116132259 -5.27442836761,1.56772148609,-1.87457156181 -5.27543544769,1.5657248497,-1.85599434376 -5.28244400024,1.56572818756,-1.8394215107 -5.28145027161,1.56373143196,-1.8208296299 -5.29045581818,1.56573295593,-1.8150318861 -5.29146242142,1.56373643875,-1.79645645618 -5.28546762466,1.55974006653,-1.77489387989 -5.30247926712,1.56274318695,-1.7632894516 -5.30548667908,1.56174659729,-1.74570894241 -5.30249261856,1.5587502718,-1.72612810135 -5.31050205231,1.55975389481,-1.70956432819 -5.31550645828,1.55975544453,-1.70275688171 -5.32551622391,1.56175887585,-1.68718492985 -5.33352518082,1.56176233292,-1.67159843445 -5.32653045654,1.55776619911,-1.65101408958 -5.33053922653,1.5577698946,-1.63344371319 -5.3425488472,1.55877327919,-1.61984157562 -5.35055494308,1.56077492237,-1.61305403709 -5.34756135941,1.5577788353,-1.5934792757 -5.35256958008,1.55778253078,-1.57689392567 -5.34957647324,1.55478644371,-1.55732119083 -5.3585858345,1.55578994751,-1.54271924496 -5.35959386826,1.5547939539,-1.52415251732 -5.36860370636,1.55579769611,-1.50857257843 -5.3676071167,1.55479955673,-1.49976837635 -5.37161588669,1.55380344391,-1.48220038414 -5.36962270737,1.55180752277,-1.46361613274 -5.38163375854,1.55381119251,-1.4490326643 -5.38764286041,1.55381500721,-1.43245518208 -5.38564968109,1.55181920528,-1.41387271881 -5.39366006851,1.55282306671,-1.39828538895 -5.40266609192,1.5548248291,-1.39149975777 -5.3946723938,1.55082941055,-1.37092721462 -5.39768028259,1.54983329773,-1.35433232784 -5.41569232941,1.55383658409,-1.34173631668 -5.40969944,1.55084145069,-1.32117855549 -5.41270780563,1.54984545708,-1.30458414555 -5.42271852493,1.55184936523,-1.28900718689 -5.41472101212,1.54885184765,-1.27821242809 -5.41372919083,1.54685640335,-1.25964188576 -5.43274068832,1.55085980892,-1.24704682827 -5.42474794388,1.54686462879,-1.22648358345 -5.42975759506,1.54686892033,-1.20990157127 -5.44276809692,1.54987239838,-1.19629335403 -5.42877006531,1.54487550259,-1.18351697922 -5.43377971649,1.54487979412,-1.16693544388 -5.45479202271,1.54988312721,-1.15434503555 -5.4457988739,1.54588842392,-1.13378202915 -5.44080686569,1.54289317131,-1.11519551277 -5.4598197937,1.54789674282,-1.10161459446 -5.45682764053,1.54590165615,-1.08303880692 -5.45183086395,1.54290425777,-1.0732460022 -5.47384405136,1.54890751839,-1.06065368652 -5.4578499794,1.54291331768,-1.03908646107 -5.46886062622,1.54491722584,-1.02448666096 -5.47487068176,1.54592168331,-1.00790894032 -5.45687675476,1.53892755508,-0.986338198185 -5.46988773346,1.54193150997,-0.971746563911 -5.49789714813,1.54993200302,-0.968940973282 -5.47190189362,1.54093885422,-0.945384919643 -5.4749121666,1.54094350338,-0.928794801235 -5.48492240906,1.54194760323,-0.913211286068 -5.48293209076,1.54095292091,-0.894646465778 -5.48194122314,1.53895783424,-0.877063691616 -5.50095367432,1.54396140575,-0.863468050957 -5.48595619202,1.5389649868,-0.851688921452 -5.49796724319,1.54196929932,-0.836111009121 -5.49797677994,1.5409744978,-0.818532824516 -5.49198532104,1.53797996044,-0.799956023693 -5.50599718094,1.54098391533,-0.785360574722 -5.51500797272,1.54298818111,-0.769768774509 -5.50401115417,1.53899157047,-0.758987605572 -5.50102090836,1.53699719906,-0.740424156189 -5.52103328705,1.54200065136,-0.726823091507 -5.50904130936,1.53800702095,-0.707252800465 -5.51005172729,1.53701221943,-0.689680755138 -5.51906299591,1.53901660442,-0.674087464809 -5.52307271957,1.539021492,-0.657501161098 -5.51507711411,1.53702485561,-0.647711932659 -5.51808738708,1.53703010082,-0.630146682262 -5.52609872818,1.5380345583,-0.614549100399 -5.5191078186,1.53504061699,-0.595978021622 -5.52211809158,1.53504574299,-0.57938939333 -5.52412843704,1.53505110741,-0.561821460724 -5.51813316345,1.53305447102,-0.55204218626 -5.52814483643,1.53505897522,-0.536448717117 -5.53115510941,1.53506398201,-0.519859910011 -5.5331659317,1.53506958485,-0.502292096615 -5.54117679596,1.53707408905,-0.486691355705 -5.53518724442,1.53508043289,-0.468128025532 -5.53219747543,1.5330862999,-0.450549274683 -5.54120349884,1.5350883007,-0.442760020494 -5.53321313858,1.53309452534,-0.425170332193 -5.5392241478,1.53409945965,-0.408588021994 -5.53323459625,1.53110587597,-0.390028655529 -5.54924678802,1.535110116,-0.37444165349 -5.54525756836,1.53411614895,-0.356862515211 -5.54526758194,1.53312170506,-0.340267986059 -5.53827238083,1.53112542629,-0.330494076014 -5.54028320312,1.53113079071,-0.31390362978 -5.54329395294,1.53113627434,-0.297314882278 -5.54830598831,1.53314185143,-0.279752463102 -5.54431676865,1.53114807606,-0.262176781893 -5.54432725906,1.53015375137,-0.245583623648 -5.55233383179,1.53315591812,-0.237785711884 -5.55434513092,1.53316175938,-0.220218643546 -5.54535531998,1.53016853333,-0.202638074756 -5.55836725235,1.53317320347,-0.186060294509 -5.54837799072,1.53018009663,-0.168480038643 -5.55338954926,1.53118538857,-0.151892453432 -5.54840040207,1.52919197083,-0.134319096804 -5.55140638351,1.53019487858,-0.125537529588 -5.55041694641,1.52920079231,-0.108944423497 -5.54742860794,1.52820730209,-0.0913739800453 -5.56044101715,1.53121185303,-0.0747909024358 -5.5554523468,1.53021872044,-0.057219106704 -5.55846309662,1.53022432327,-0.0406286902726 -5.56447505951,1.53222966194,-0.0240389239043 -5.56348085403,1.53123283386,-0.015254390426 -5.56949281693,1.53323829174,0.00133624405134 -5.5565032959,1.52924597263,0.0189083535224 -5.56651592255,1.5322508812,0.0354983918369 -5.5615272522,1.53025794029,0.0530672445893 -5.55253887177,1.52726531029,0.0706354081631 -5.56855106354,1.53226959705,0.0872275307775 -5.56055688858,1.53027367592,0.0960111841559 -5.56656837463,1.53127908707,0.112603701651 -5.55958032608,1.52928638458,0.130170300603 -5.56159210205,1.53029239178,0.146762669086 -5.56560468674,1.53129839897,0.164331898093 -5.56561613083,1.53130459785,0.18092392385 -5.56062173843,1.5293084383,0.189705327153 -5.5636343956,1.53031468391,0.20727469027 -5.56064605713,1.5293213129,0.223864614964 -5.5606584549,1.52932798862,0.241432249546 -5.56167030334,1.53033411503,0.258024901152 -5.55568265915,1.52834165096,0.275587409735 -5.55769443512,1.52934765816,0.292180746794 -5.56570100784,1.53134989738,0.30097219348 -5.55771255493,1.52935731411,0.317556083202 -5.55872488022,1.52936387062,0.335124731064 -5.5487370491,1.52637171745,0.351704478264 -5.54874992371,1.52637851238,0.3692715168 -5.55776166916,1.52938365936,0.385874897242 -5.55077457428,1.52739143372,0.403432875872 -5.56078100204,1.53039348125,0.412231206894 -5.55379343033,1.52940094471,0.428813040257 -5.54980564117,1.52740800381,0.445398241282 -5.55981826782,1.53141331673,0.462982982397 -5.54183101654,1.52642261982,0.479544013739 -5.54684400558,1.52742886543,0.497120380402 -5.56184959412,1.53242993355,0.50593239069 -5.54586267471,1.52743899822,0.522494316101 -5.54687595367,1.52844583988,0.540064513683 -5.55288887024,1.53045189381,0.557645380497 -5.54190063477,1.52745985985,0.573238492012 -5.54291391373,1.52846682072,0.590809047222 -5.54592704773,1.52947330475,0.608384549618 -5.53893280029,1.52747762203,0.616176486015 -5.53594589233,1.52748477459,0.632761895657 -5.5389585495,1.52849137783,0.650337874889 -5.53297185898,1.5274990797,0.666915476322 -5.5259847641,1.52550709248,0.683489620686 -5.53599786758,1.5295124054,0.70108550787 -5.52901077271,1.52752041817,0.717659235001 -5.53001737595,1.52752387524,0.726446509361 -5.54503011703,1.53352868557,0.74503582716 -5.52204418182,1.5265392065,0.760585844517 -5.51505708694,1.52554702759,0.776181817055 -5.52307033539,1.52755308151,0.794751822948 -5.52108383179,1.52756035328,0.811339378357 -5.52109718323,1.52856767178,0.828909695148 -5.52010345459,1.52857100964,0.836715459824 -5.51211690903,1.52657938004,0.853282749653 -5.51013040543,1.5265866518,0.869870007038 -5.51514434814,1.52959346771,0.888434529305 -5.48615837097,1.52160489559,0.901996433735 -5.50717115402,1.52760887146,0.921595215797 -5.5131778717,1.53061175346,0.931379556656 -5.49019193649,1.5236222744,0.94495934248 -5.5012049675,1.52762770653,0.963548660278 -5.50621891022,1.53063452244,0.982116520405 -5.48823308945,1.52564442158,0.996688067913 -5.47624731064,1.52265357971,1.01225817204 -5.49725961685,1.52965736389,1.03186905384 -5.47326755524,1.5226650238,1.03762590885 -5.46628141403,1.52167308331,1.05321514606 -5.47729444504,1.52567875385,1.07181060314 -5.46230983734,1.52268862724,1.08736455441 -5.46532297134,1.52369558811,1.10494971275 -5.47033643723,1.52670192719,1.12254536152 -5.44034481049,1.5177103281,1.12631237507 -5.4483590126,1.52171647549,1.14489769936 -5.4493727684,1.52272391319,1.16247487068 -5.45238637924,1.52373087406,1.1800621748 -5.43240118027,1.51874136925,1.19363260269 -5.4364156723,1.52174842358,1.21220171452 -5.43143033981,1.52075684071,1.2287735939 -5.42943716049,1.52076077461,1.23657393456 -5.42045164108,1.51876974106,1.25214838982 -5.42246580124,1.52077686787,1.26973259449 -5.42148065567,1.52178478241,1.28730154037 -5.41049480438,1.51879394054,1.30188775063 -5.40650939941,1.51880216599,1.31846415997 -5.41252326965,1.52180874348,1.33704841137 -5.40753078461,1.52081346512,1.34483194351 -5.40354585648,1.52082180977,1.36140859127 -5.40155982971,1.5218296051,1.37799692154 -5.41057395935,1.5258358717,1.39757823944 -5.39158964157,1.52084684372,1.41113853455 -5.39360380173,1.52285408974,1.42872726917 -5.39961767197,1.52586066723,1.44731736183 -5.36362791061,1.51487064362,1.44807684422 -5.37664175034,1.51987624168,1.46866202354 -5.3756570816,1.52188432217,1.48623394966 -5.39766931534,1.52988839149,1.50883305073 -5.35668706894,1.51790297031,1.51638805866 -5.34870243073,1.5169121027,1.53196191788 -5.35970830917,1.52091395855,1.54277515411 -5.35872364044,1.5219219923,1.56034803391 -5.35273933411,1.52193105221,1.57691216469 -5.34075403214,1.51894056797,1.59050571918 -5.34776830673,1.5229473114,1.61008644104 -5.34278440475,1.52295613289,1.62665712833 -5.33679914474,1.52196478844,1.64224410057 -5.35880470276,1.52996504307,1.65704751015 -5.03568696976,1.53147006035,2.52123260498 -5.0297036171,1.53147959709,2.53682208061 -5.00371599197,1.52448904514,2.53458714485 -5.00773143768,1.52849674225,2.55517506599 -4.99674987793,1.52750742435,2.56875300407 -4.9887676239,1.52751779556,2.58432006836 -4.98978424072,1.53052639961,2.60390019417 -4.97880220413,1.5285371542,2.61747789383 -4.98381710052,1.53254437447,2.63808250427 -4.97582769394,1.53155088425,2.64484381676 -4.95484638214,1.52756297588,2.65243768692 -4.95386314392,1.52957201004,2.67101979256 -4.97487688065,1.53957700729,2.70159697533 -4.95989561081,1.53658854961,2.71317219734 -4.95991277695,1.53959751129,2.73274898529 -4.94993162155,1.53960835934,2.74731779099 -4.93294143677,1.53461551666,2.74712204933 -4.93295812607,1.53762435913,2.76669979095 -4.92997550964,1.53963363171,2.7842862606 -4.91599464417,1.53764533997,2.79684972763 -4.90501308441,1.53665626049,2.81042647362 -4.9130282402,1.54266345501,2.83401870728 -4.89004087448,1.53567242622,2.83178758621 -4.88205814362,1.53568255901,2.84637856483 -4.88507509232,1.53969097137,2.86795568466 -4.86809492111,1.53670322895,2.87852215767 -4.86611223221,1.53971254826,2.89710330963 -4.85913038254,1.53972268105,2.91268658638 -4.85014009476,1.5387288332,2.91747331619 -4.83915901184,1.53773999214,2.93104863167 -4.8421754837,1.54174828529,2.95263195038 -4.82519578934,1.53876066208,2.96319508553 -4.81821393967,1.53977096081,2.97877907753 -4.81723117828,1.5427801609,2.99835681915 -4.81124925613,1.54379022121,3.01493430138 -4.79926013947,1.54079699516,3.01772165298 -4.79827737808,1.54380619526,3.03730154037 -4.7822971344,1.54081833363,3.04787421227 -4.77631521225,1.54282867908,3.06445240974 -4.76733398438,1.54283940792,3.07903313637 -4.75135374069,1.53985154629,3.08960390091 -4.75237131119,1.54386019707,3.11019277573 -4.75837802887,1.54786360264,3.12398934364 -4.74639797211,1.54687476158,3.13657212257 -4.73141765594,1.54488706589,3.14813518524 -4.72743606567,1.54689669609,3.16572260857 -4.70845651627,1.54290962219,3.1742913723 -4.70647478104,1.54591917992,3.19386649132 -4.6964931488,1.54593002796,3.2074546814 -4.68450450897,1.54293715954,3.21023440361 -4.68352270126,1.54694664478,3.23080468178 -4.67454099655,1.54695701599,3.24440646172 -4.66756010056,1.54796779156,3.26097679138 -4.64858055115,1.54398036003,3.26856064796 -4.64359855652,1.54599058628,3.28613829613 -4.63360929489,1.54399716854,3.28992271423 -4.63162708282,1.54700672626,3.3095035553 -4.62264728546,1.54801809788,3.32506680489 -4.60866689682,1.54602956772,3.33565831184 -4.610683918,1.55103850365,3.35823917389 -4.59770441055,1.54905045033,3.37080574036 -4.57672548294,1.54506361485,3.37639498711 -4.58673334122,1.55106663704,3.39516854286 -4.57675266266,1.55107760429,3.40875840187 -4.56277322769,1.55008971691,3.42032957077 -4.5577917099,1.55209994316,3.43791365623 -4.54281234741,1.55011212826,3.44848895073 -4.52683353424,1.54812502861,3.45904946327 -4.51885223389,1.54913532734,3.47364830971 -4.51486158371,1.54914081097,3.48143839836 -4.50588178635,1.55015218258,3.49700427055 -4.49990034103,1.55216240883,3.51359581947 -4.49092054367,1.55217373371,3.52916240692 -4.4769411087,1.55118560791,3.53975057602 -4.46596193314,1.55119752884,3.55430698395 -4.46996974945,1.55420136452,3.56810379028 -4.45099163055,1.5522146225,3.57567358017 -4.44401025772,1.55322504044,3.59127140045 -4.44002962112,1.55623531342,3.61084008217 -4.42305040359,1.55324816704,3.61941933632 -4.41706991196,1.55525875092,3.63699650764 -4.40709018707,1.55627024174,3.65156984329 -4.40210008621,1.55627572536,3.65836548805 -4.38312149048,1.55328881741,3.66494941711 -4.37614154816,1.5542999506,3.68251276016 -4.3591632843,1.55231285095,3.69108891487 -4.36118078232,1.55732154846,3.7146821022 -4.34720230103,1.55633401871,3.72624945641 -4.34122133255,1.55834472179,3.7438313961 -4.33423233032,1.55835092068,3.74961495399 -4.32725143433,1.56036162376,3.76620078087 -4.31127309799,1.55837452412,3.77577280998 -4.29529523849,1.55638718605,3.78534412384 -4.29431343079,1.5603967905,3.80693507195 -4.27433538437,1.55741012096,3.81251454353 -4.27534484863,1.56041491032,3.82529902458 -4.26236534119,1.55942678452,3.83688139915 -4.24638700485,1.55743980408,3.84645104408 -4.2444062233,1.56144976616,3.86803126335 -4.22742795944,1.55946230888,3.87562012672 -4.22144794464,1.5614733696,3.89419126511 -4.20746994019,1.56148600578,3.9057571888 -4.20447921753,1.56249129772,3.91455221176 -4.19250011444,1.56250321865,3.92713332176 -4.17652177811,1.56051576138,3.9357187748 -4.18053913116,1.56652462482,3.96329951286 -4.1625623703,1.5645378828,3.97087025642 -4.14758348465,1.56355047226,3.98045444489 -4.15259170532,1.56855428219,3.99724507332 -4.1336145401,1.56556785107,4.0038151741 -4.12263584137,1.56557965279,4.01739645004 -4.11865520477,1.56959009171,4.03797483444 -4.09567832947,1.56460404396,4.0395617485 -4.0846991539,1.56561589241,4.05314350128 -4.08171844482,1.56962609291,4.07472372055 -4.06873083115,1.56663370132,4.07450771332 -4.05875253677,1.56764566898,4.09007310867 -4.0547709465,1.57065570354,4.10967350006 -4.03079557419,1.56667053699,4.11123847961 -4.01981639862,1.56668233871,4.12482118607 -4.01683521271,1.57069242001,4.14640712738 -3.99685931206,1.56870651245,4.15197086334 -3.98687076569,1.56671321392,4.15376853943 -3.98489022255,1.57072341442,4.17734146118 -3.96891307831,1.56973671913,4.18690633774 -3.95093607903,1.56774997711,4.19348526001 -3.94795513153,1.57176017761,4.21507692337 -3.93297791481,1.5707732439,4.22564268112 -3.91899991035,1.57078564167,4.23622512817 -3.91900920868,1.57379055023,4.24901580811 -3.89803314209,1.56980454922,4.25258970261 -3.88205575943,1.56881761551,4.26116800308 -3.88207435608,1.57482719421,4.28675508499 -3.86509728432,1.57284045219,4.29433298111 -3.85511803627,1.57385206223,4.30892181396 -3.85112857819,1.57485771179,4.31771039963 -3.83015275002,1.57187211514,4.32128000259 -3.81517529488,1.5708848238,4.3308596611 -3.8101952076,1.57489550114,4.35144472122 -3.79021930695,1.57190966606,4.35601329803 -3.78323984146,1.57492077351,4.37459564209 -3.76726269722,1.5739338398,4.38317346573 -3.76127386093,1.57394015789,4.38995885849 -3.75729346275,1.5779504776,4.41155099869 -3.73831725121,1.57596433163,4.41712093353 -3.72234034538,1.57497739792,4.42569732666 -3.71136236191,1.575989604,4.44027328491 -3.69338583946,1.57400333881,4.44684362411 -3.68339729309,1.5730099678,4.44764852524 -3.6734187603,1.57402193546,4.4632267952 -3.65544295311,1.5730355978,4.46979618073 -3.64446496964,1.57404780388,4.48437261581 -3.63648629189,1.57705950737,4.50294494629 -3.62650728226,1.57807099819,4.51754140854 -3.60953021049,1.57708418369,4.52412796021 -3.59454417229,1.57309257984,4.52089691162 -3.57756733894,1.57110583782,4.52748203278 -3.57458758354,1.5771163702,4.55206203461 -3.53961634636,1.5671339035,4.53761959076 -3.4436583519,1.52816319466,4.44418430328 -3.41568493843,1.5211789608,4.43675374985 -3.41370511055,1.52618944645,4.46233081818 -3.41271519661,1.52919459343,4.47512054443 -3.47171974182,1.5651922226,4.57872962952 -3.48373579979,1.57719945908,4.62232732773 -3.47575688362,1.58021092415,4.64090967178 -3.45678114891,1.57822477818,4.64548397064 -3.43880534172,1.57623851299,4.65106153488 -3.42682766914,1.57725095749,4.6646399498 -3.4228386879,1.5792568922,4.6744260788 -3.4098610878,1.57926928997,4.68601417542 -3.39488506317,1.57928264141,4.69657897949 -3.38990545273,1.58429336548,4.71916913986 -3.37392902374,1.58330667019,4.7277431488 -3.36295104027,1.585318923,4.74233055115 -3.35296368599,1.58432602882,4.74411344528 -3.34298586845,1.58633804321,4.76069450378 -3.32600951195,1.58535146713,4.76727628708 -3.30803370476,1.58336508274,4.77285194397 -3.29705572128,1.58537721634,4.7874417305 -3.28107976913,1.58539068699,4.79601573944 -3.27110219002,1.5874029398,4.81358575821 -3.26011443138,1.58540987968,4.81238746643 -3.24813747406,1.58742249012,4.82696008682 -3.23216128349,1.58643591404,4.83553409576 -3.23018145561,1.59344625473,4.86412000656 -3.21820449829,1.59545886517,4.87869596481 -3.20622730255,1.5974714756,4.8932723999 -3.18625187874,1.5944852829,4.8948597908 -3.17626404762,1.59349226952,4.895652771 -3.10330343246,1.56151771545,4.81820201874 -3.07533049583,1.55453360081,4.80777359009 -3.04735732079,1.54754924774,4.79635429382 -3.05137562752,1.5575581789,4.83394956589 -3.01540565491,1.54657614231,4.81150627136 -2.98242378235,1.53258764744,4.77529668808 -2.97744584084,1.53759908676,4.80086374283 -2.95547127724,1.533613801,4.79844141006 -2.92749834061,1.52662956715,4.78601980209 -2.92551898956,1.53364002705,4.81560182571 -2.94353318214,1.5526458025,4.87621116638 -2.95555019379,1.56765365601,4.92979335785 -2.96555781364,1.57765674591,4.96358299255 -2.96657657623,1.58666610718,4.9981842041 -2.95560026169,1.58967876434,5.01575040817 -2.95162034035,1.59568929672,5.04235267639 -2.97263503075,1.61769521236,5.11393260956 -2.96765637398,1.62370646,5.14151287079 -2.97167468071,1.6357152462,5.18311452866 -2.97868299484,1.64471900463,5.21390295029 -2.99769735336,1.66472494602,5.28250598907 -2.97272372246,1.65973997116,5.27608728409 -2.97074437141,1.66875064373,5.31066608429 -2.9617664814,1.67276239395,5.33225345612 -2.94979000092,1.67577517033,5.34982824326 -2.9418027401,1.6767821312,5.35560941696 -2.9318253994,1.68079411983,5.3761920929 -2.91484928131,1.67980766296,5.38377809525 -2.8998734951,1.68082070351,5.39536142349 -2.88389801979,1.6818343401,5.40593576431 -2.86392402649,1.67984879017,5.40950489044 -2.85094738007,1.68186151981,5.4250869751 -2.84695863724,1.68486750126,5.43787574768 -2.83098244667,1.68488049507,5.44647169113 -2.81500649452,1.68589365482,5.4560585022 -2.79903149605,1.68690752983,5.46762466431 -2.78005623817,1.68492138386,5.47121286392 -2.76808023453,1.68893396854,5.48978853226 -2.75010514259,1.68794798851,5.49636650085 -2.74111747742,1.68795478344,5.49916028976 -2.72414183617,1.68796825409,5.50674819946 -2.71216654778,1.69198131561,5.52730798721 -2.68219518661,1.68299758434,5.50988054276 -2.66521930695,1.68301105499,5.5174665451 -2.65724134445,1.68902266026,5.54306030273 -2.63626766205,1.68603718281,5.54363536835 -2.62727952003,1.68604373932,5.54543781281 -2.61530375481,1.69005692005,5.56600236893 -2.59433031082,1.68807148933,5.56657600403 -2.57035660744,1.68208634853,5.55916261673 -2.55238175392,1.6821000576,5.56474781036 -2.53340697289,1.68111395836,5.56833076477 -2.52442002296,1.68112099171,5.57211351395 -2.50744462013,1.68113458157,5.5796995163 -2.49346876144,1.68314743042,5.59428358078 -2.4754948616,1.68316161633,5.60185050964 -2.46651697159,1.6891733408,5.62644815445 -2.43854522705,1.68118941784,5.61101675034 -2.42856860161,1.68720173836,5.63559627533 -2.42857837677,1.6932066679,5.65839719772 -2.40560555458,1.68922162056,5.6539683342 -2.3956284523,1.69523382187,5.67855358124 -2.38565158844,1.70124578476,5.70314121246 -2.36567735672,1.69926011562,5.70472240448 -2.3367061615,1.69027626514,5.68529558182 -2.3397154808,1.70028078556,5.71709060669 -2.32174110413,1.70029461384,5.7236700058 -2.30976486206,1.70430731773,5.74524831772 -2.30478692055,1.71431839466,5.78383350372 -2.29880833626,1.72332966328,5.8194270134 -2.28983139992,1.73134160042,5.8490114212 -2.2838537693,1.74135315418,5.88758945465 -2.27886581421,1.74535942078,5.90237569809 -2.26189041138,1.74537265301,5.91096973419 -2.25091362,1.75138509274,5.93655490875 -2.22993993759,1.7493994236,5.93613910675 -2.20996689796,1.74941408634,5.94070482254 -2.19599080086,1.75242686272,5.95829391479 -2.17501711845,1.75044119358,5.95787668228 -2.16303157806,1.74844908714,5.95565223694 -2.14405727386,1.7474629879,5.96023750305 -2.11308646202,1.73747944832,5.93181800842 -2.09311294556,1.73549377918,5.93439388275 -2.07014012337,1.73150873184,5.92797279358 -2.04916644096,1.7295229435,5.92655563354 -2.03119182587,1.72953665257,5.93314266205 -2.02520394325,1.73254287243,5.94493818283 -1.9992326498,1.72655880451,5.93150043488 -1.97925829887,1.72457265854,5.93109369278 -1.96328413486,1.72758638859,5.94666004181 -1.94431006908,1.72660040855,5.95024633408 -1.92633521557,1.7266138792,5.95584011078 -1.91734838486,1.72762095928,5.96062374115 -1.89537525177,1.72363555431,5.95520734787 -1.87340211868,1.72065007687,5.94978904724 -1.85242879391,1.71866440773,5.94737100601 -1.837454319,1.72267782688,5.96594238281 -1.8164806366,1.71969211102,5.96252965927 -1.79750692844,1.71970617771,5.96710729599 -1.78752028942,1.71871340275,5.96789503098 -1.76654684544,1.71572768688,5.96448087692 -1.74957239628,1.71774125099,5.9750623703 -1.73659694195,1.72375404835,5.99964427948 -1.7146242857,1.72076880932,5.99422025681 -1.69365119934,1.71878325939,5.99179792404 -1.68266415596,1.71579027176,5.98659896851 -1.66369068623,1.71580433846,5.99117612839 -1.64271712303,1.71381866932,5.98676347733 -1.62174427509,1.71083307266,5.98433732986 -1.60576951504,1.71384632587,5.99792575836 -1.58679628372,1.71386063099,6.00349664688 -1.56482326984,1.7098749876,5.99508190155 -1.55683600903,1.71188175678,6.00287103653 -1.5398619175,1.71389532089,6.01445198059 -1.51988863945,1.71290957928,6.01502895355 -1.49991440773,1.71092331409,6.01162672043 -1.48094058037,1.70993709564,6.01421260834 -1.46196722984,1.70995128155,6.01878881454 -1.4409943819,1.70796573162,6.01536369324 -1.43000793457,1.70597290993,6.01015710831 -1.41503286362,1.70998585224,6.02874755859 -1.39206111431,1.70600104332,6.01831245422 -1.3730866909,1.70501446724,6.01791191101 -1.35311377048,1.7030287981,6.01848459244 -1.33513987064,1.70504248142,6.02606725693 -1.32116425037,1.71105527878,6.04966020584 -1.3051803112,1.70306384563,6.02543306351 -1.28620612621,1.70207750797,6.02602624893 -1.2662332058,1.70109176636,6.0256023407 -1.24825930595,1.70210540295,6.03318500519 -1.22928571701,1.70211923122,6.03576850891 -1.20831310749,1.69913375378,6.0303440094 -1.20032548904,1.70114016533,6.03714418411 -1.18235111237,1.70115363598,6.0427365303 -1.16037929058,1.69816851616,6.03430080414 -1.14040589333,1.69518244267,6.03088665009 -1.1234318018,1.69819581509,6.04347229004 -1.10345828533,1.69620978832,6.03906106949 -1.0854845047,1.69822347164,6.04764223099 -1.07449877262,1.69623088837,6.04342222214 -1.05452549458,1.69424498081,6.0400056839 -1.03855085373,1.69925808907,6.05859279633 -1.01457881927,1.69027280807,6.03117704391 -0.997605085373,1.69428634644,6.04675531387 -0.978631317616,1.69330000877,6.04734420776 -0.967644929886,1.69030714035,6.03913593292 -0.951671123505,1.69732058048,6.06271076202 -0.929698228836,1.69033479691,6.04429864883 -0.910724878311,1.69034874439,6.04687976837 -0.895749747753,1.69736135006,6.07247400284 -0.872777581215,1.6893761158,6.04805469513 -0.853804588318,1.69038999081,6.0526304245 -0.843818247318,1.68939709663,6.05141782761 -0.826844096184,1.69341039658,6.06700372696 -0.805870652199,1.68742418289,6.05059766769 -0.786898076534,1.68943846226,6.05816507339 -0.768924355507,1.69145202637,6.06774902344 -0.748951077461,1.68946588039,6.06033658981 -0.729977965355,1.68947970867,6.06391525269 -0.720990300179,1.68948602676,6.06272315979 -0.701017379761,1.68649995327,6.05730342865 -0.681044816971,1.68551409245,6.05487537384 -0.66307079792,1.68752741814,6.06246614456 -0.644097864628,1.68854141235,6.06804084778 -0.624124765396,1.68555521965,6.05962610245 -0.605151414871,1.68556892872,6.06120967865 -0.596163809299,1.68557524681,6.06001663208 -0.577190279961,1.68458878994,6.05960416794 -0.557217717171,1.68260300159,6.05517816544 -0.540243268013,1.68761599064,6.07377147675 -0.519271433353,1.68363046646,6.06233692169 -0.50029784441,1.68364405632,6.06092643738 -0.491311401129,1.68665099144,6.07171106339 -0.471337378025,1.67966425419,6.04931402206 -0.451364994049,1.67767834663,6.0448846817 -0.434390723705,1.68469142914,6.06847667694 -0.415417551994,1.68570506573,6.072057724 -0.395444393158,1.68071889877,6.05664396286 -0.376471370459,1.68173265457,6.06222200394 -0.368483692408,1.68673884869,6.07902526855 -0.347511738539,1.68075311184,6.05859422684 -0.328538417816,1.6807667017,6.05917882919 -0.309564679861,1.67878007889,6.0527715683 -0.291590571404,1.68179321289,6.06436634064 -0.272617220879,1.68180680275,6.06495094299 -0.252644717693,1.67882072926,6.05352544785 -0.242658033967,1.67382752895,6.0373210907 -0.224684685469,1.68284094334,6.0699005127 -0.204711943865,1.67685484886,6.0494799614 -0.185738563538,1.67586827278,6.0470662117 -0.167764529586,1.68288135529,6.06865930557 -0.147792026401,1.67689526081,6.04923391342 -0.129817694426,1.68190824986,6.06483268738 -0.119831204414,1.67491495609,6.04162502289 -0.100858300924,1.67992866039,6.06120204926 -0.0818847715855,1.67694211006,6.04879140854 -0.0629114583135,1.67595541477,6.04737663269 -0.0439382493496,1.67996895313,6.05795955658 -0.0249649323523,1.6809823513,6.06154489517 -0.0149789340794,1.67798936367,6.0523276329 --0.0139798559248,1.69401013851,5.86468458176 --0.031953945756,1.69302308559,5.86227893829 --0.0509267859161,1.69903671741,5.88085508347 --0.0599136352539,1.69304323196,5.86064815521 --0.077887788415,1.69405627251,5.86424446106 --0.0968603119254,1.69207000732,5.85581350327 --0.114834398031,1.69208300114,5.85540771484 --0.133807227015,1.69409656525,5.86198329926 --0.151781156659,1.69210958481,5.85557556152 --0.169755131006,1.69112253189,5.85116767883 --0.179740980268,1.69412958622,5.85794734955 --0.197714701295,1.69114267826,5.84753513336 --0.216688022017,1.69615590572,5.86312007904 --0.233662202954,1.68716883659,5.83171033859 --0.252635985613,1.6941819191,5.85530519485 --0.27060970664,1.69219493866,5.84689283371 --0.28958272934,1.69420838356,5.8524723053 --0.297570377588,1.689214468,5.83727502823 --0.318542093039,1.70022857189,5.86784029007 --0.334516882896,1.68924093246,5.83243751526 --0.354489207268,1.69425475597,5.8480091095 --0.371463596821,1.68926739693,5.83060407639 --0.389437913895,1.69128000736,5.83320379257 --0.398424208164,1.68828678131,5.82298564911 --0.417397409678,1.690300107,5.82856798172 --0.435371100903,1.68931305408,5.82315587997 --0.453345328569,1.68932580948,5.82375335693 --0.472318589687,1.69233906269,5.82933759689 --0.49029135704,1.68835234642,5.81390571594 --0.508265316486,1.68836522102,5.81149768829 --0.519251227379,1.69337213039,5.82828474045 --0.535226166248,1.6873844862,5.80688285828 --0.557198286057,1.69839823246,5.84046220779 --0.572173535824,1.68941032887,5.81006193161 --0.591146290302,1.69042372704,5.80963659286 --0.610119581223,1.69243681431,5.81322097778 --0.620106339455,1.6954433918,5.82201862335 --0.638079941273,1.69445633888,5.81560230255 --0.657053411007,1.69646930695,5.82019090652 --0.675026834011,1.69448232651,5.81277227402 --0.695000469685,1.70049524307,5.82836866379 --0.711973965168,1.69550812244,5.81094551086 --0.730947911739,1.69852077961,5.81754207611 --0.739933848381,1.6965277195,5.80831670761 --0.760907053947,1.703540802,5.82891082764 --0.776881992817,1.69955301285,5.81250953674 --0.796854615211,1.70256638527,5.81908750534 --0.813828706741,1.69957900047,5.8066740036 --0.835800766945,1.70659255981,5.82625007629 --0.851775169373,1.70160496235,5.80783987045 --0.861762166023,1.70461130142,5.81464195251 --0.880735218525,1.70462441444,5.81321954727 --0.900708377361,1.70863747597,5.82080602646 --0.915683150291,1.70164966583,5.79739618301 --0.934656500816,1.70366251469,5.79798078537 --0.952630221844,1.70267534256,5.79256677628 --0.973603248596,1.70768845081,5.80615615845 --0.983589589596,1.70869493484,5.80794429779 --1.00456285477,1.71470797062,5.82153654099 --1.0205373764,1.71072018147,5.8061299324 --1.04250991344,1.71673357487,5.82171106339 --1.05748486519,1.71174550056,5.80130529404 --1.08145618439,1.72075951099,5.82487869263 --1.08844387531,1.71676540375,5.81167411804 --1.1084176302,1.72077810764,5.81927204132 --1.1233921051,1.71479022503,5.79685497284 --1.14736425877,1.72380375862,5.8224439621 --1.16433787346,1.72081637383,5.80902051926 --1.18331193924,1.72282886505,5.81061792374 --1.20028591156,1.72084128857,5.79920244217 --1.21327137947,1.72584831715,5.81398868561 --1.23024523258,1.72386074066,5.80257225037 --1.25121843815,1.72787368298,5.8111615181 --1.26619374752,1.72388541698,5.79375982285 --1.29016590118,1.73189878464,5.81534814835 --1.3061401844,1.72791099548,5.79993343353 --1.32511401176,1.72992348671,5.79852151871 --1.33410048485,1.72892987728,5.79430913925 --1.35707306862,1.73494303226,5.80989742279 --1.37204766273,1.7309551239,5.79048204422 --1.39602053165,1.73896813393,5.81208229065 --1.40999495983,1.73198008537,5.78665590286 --1.4349668026,1.74099373817,5.80823993683 --1.44794237614,1.73400521278,5.78283262253 --1.46092796326,1.73901212215,5.79462051392 --1.47390341759,1.73202347755,5.76921081543 --1.49887537956,1.74103701115,5.78979539871 --1.5138502121,1.73704874516,5.77238512039 --1.53982210159,1.74606227875,5.79697561264 --1.55079901218,1.73807299137,5.76758146286 --1.56078517437,1.73907959461,5.76636505127 --1.58175802231,1.7420924902,5.76994562149 --1.60273146629,1.74510490894,5.77553939819 --1.61970627308,1.74411678314,5.76713657379 --1.64167892933,1.74812972546,5.77371788025 --1.65665340424,1.74414169788,5.75529718399 --1.6826249361,1.75315511227,5.77588176727 --1.68661379814,1.74716031551,5.75668334961 --1.70658707619,1.74917292595,5.75626659393 --1.72656047344,1.75118541718,5.75585126877 --1.74653446674,1.75319755077,5.75744867325 --1.76350915432,1.75220954418,5.74804019928 --1.79148066044,1.76322293282,5.77463340759 --1.80045676231,1.75323390961,5.73721075058 --1.81544244289,1.75924062729,5.75401163101 --1.83341646194,1.75825273991,5.74659585953 --1.8553892374,1.76226568222,5.75117683411 --1.86936438084,1.75827693939,5.73176383972 --1.89833557606,1.76929068565,5.75835180283 --1.90931224823,1.7623013258,5.7319521904 --1.91929888725,1.76330757141,5.73074054718 --1.93727338314,1.76331949234,5.72433280945 --1.96224558353,1.76933252811,5.73792076111 --1.9742218256,1.76434338093,5.71451711655 --1.99819338322,1.76935660839,5.72208595276 --2.01216936111,1.76536774635,5.70468235016 --2.03314304352,1.76837980747,5.70727872849 --2.04212975502,1.76738607883,5.7020611763 --2.0611038208,1.7693978548,5.69865560532 --2.08007836342,1.77040970325,5.69525146484 --2.10405063629,1.77442264557,5.70282793045 --2.11902594566,1.77243387699,5.68842363358 --2.14199876785,1.77644646168,5.69400787354 --2.15397548676,1.77145707607,5.67260980606 --2.17196011543,1.77946436405,5.69240140915 --2.1829366684,1.77347493172,5.66699266434 --2.20890831947,1.78048813343,5.67957496643 --2.22288370132,1.77649927139,5.66115760803 --2.24385762215,1.7795112133,5.66275644302 --2.26483106613,1.78252339363,5.66234064102 --2.28480529785,1.78353524208,5.65993070602 --2.29279232025,1.78254115582,5.65271711349 --2.31876516342,1.78955364227,5.66631793976 --2.32974123955,1.78356432915,5.64090108871 --2.35371446609,1.78957676888,5.6484951973 --2.36968946457,1.7875880003,5.63608455658 --2.38866400719,1.78859949112,5.63168048859 --2.39765119553,1.78860533237,5.62747192383 --2.42162394524,1.79361796379,5.63305425644 --2.43759942055,1.79262900352,5.62165212631 --2.45757293701,1.79364109039,5.61723041534 --2.47754693031,1.79565286636,5.61381864548 --2.49852108955,1.79766452312,5.61341333389 --2.5124976635,1.7956751585,5.59801483154 --2.52548336983,1.79768168926,5.60179948807 --2.54645705223,1.80069351196,5.60038757324 --2.55843377113,1.79670393467,5.57998323441 --2.58440637589,1.8027163744,5.58957290649 --2.60138130188,1.80172765255,5.57916069031 --2.6203558445,1.80273902416,5.57375431061 --2.64532852173,1.80875134468,5.58034229279 --2.65331602097,1.80675697327,5.57312822342 --2.66829156876,1.805768013,5.5587182045 --2.70026230812,1.81578111649,5.57930421829 --2.70424127579,1.80579042435,5.54290151596 --2.72721505165,1.80980217457,5.54549598694 --2.7541873455,1.81681478024,5.55508184433 --2.75117826462,1.80881869793,5.52687883377 --2.77815055847,1.81483101845,5.53646659851 --2.79912471771,1.81684267521,5.53405618668 --2.81709980965,1.81685376167,5.52564668655 --2.84107327461,1.82186567783,5.52923965454 --2.85404896736,1.81887626648,5.50981807709 --2.87102460861,1.81888711452,5.50041818619 --2.87901234627,1.81789243221,5.49421262741 --2.90698480606,1.82490479946,5.50480270386 --2.91396284103,1.81791436672,5.47539329529 --2.94393444061,1.82592701912,5.4889793396 --2.96190977097,1.8269380331,5.48057222366 --2.97688555717,1.82494854927,5.46616077423 --2.99386143684,1.8249591589,5.45676183701 --3.01384544373,1.83196628094,5.47154760361 --3.02182388306,1.82597577572,5.44514322281 --3.0447974205,1.82998740673,5.44472694397 --3.06477236748,1.83199846745,5.44032526016 --3.08174800873,1.83200919628,5.42991828918 --3.1007232666,1.83301997185,5.42351579666 --3.12070798874,1.84002685547,5.43831062317 --3.13068509102,1.8350366354,5.41489601135 --3.15765762329,1.84104883671,5.42047643661 --3.17463326454,1.84105932713,5.41007137299 --3.18961000443,1.8400696516,5.39667034149 --3.20858407021,1.84008097649,5.38723945618 --3.24055671692,1.85009288788,5.40385389328 --3.23354816437,1.84009647369,5.37164020538 --3.25852203369,1.84510791302,5.37423229218 --3.28049659729,1.84811890125,5.3718252182 --3.29947161674,1.84912967682,5.36441898346 --3.31544780731,1.84913992882,5.35201120377 --3.33942198753,1.8531512022,5.35260534286 --3.34740018845,1.84816050529,5.32719612122 --3.36538505554,1.85316705704,5.33598184586 --3.3793618679,1.85117709637,5.32057666779 --3.39733695984,1.85218787193,5.31015634537 --3.41831207275,1.85419857502,5.30575180054 --3.44128656387,1.85820960999,5.30434656143 --3.45926213264,1.85821998119,5.29493904114 --3.4692504406,1.85922515392,5.29274654388 --3.49422359467,1.86323666573,5.29232168198 --3.502202034,1.85924577713,5.26791715622 --3.52717638016,1.86325669289,5.26951694489 --3.54115271568,1.86226689816,5.25309991837 --3.57012629509,1.86927819252,5.26070261002 --3.57810354233,1.8632876873,5.23427295685 --3.58509230614,1.86329245567,5.22707557678 --3.60706758499,1.86630308628,5.22367334366 --3.63104176521,1.87031412125,5.22226190567 --3.64401936531,1.86832368374,5.20586109161 --3.66999268532,1.87333500385,5.20644187927 --3.68197035789,1.87134432793,5.18803453445 --3.70594477654,1.87535524368,5.18662786484 --3.7099339962,1.87235975266,5.17442178726 --3.72691035271,1.87236976624,5.16301298141 --3.74888539314,1.87538027763,5.15860557556 --3.76586174965,1.87639021873,5.14719867706 --3.79083561897,1.8804012537,5.14578056335 --3.80581307411,1.8794106245,5.13238286972 --3.81180167198,1.87841546535,5.12317752838 --3.8357770443,1.88242590427,5.12177848816 --3.85175347328,1.88243567944,5.1083650589 --3.86473107338,1.88144493103,5.09196329117 --3.88670611382,1.88445544243,5.08655023575 --3.89868378639,1.88146471977,5.06814002991 --3.92365884781,1.88647508621,5.06774187088 --3.9306473732,1.88547992706,5.0595331192 --3.94962310791,1.88748991489,5.05012178421 --3.97259807587,1.89050042629,5.04570960999 --3.99557375908,1.89451038837,5.0423116684 --4.01454925537,1.89552056789,5.0318903923 --4.02252864838,1.89152920246,5.00949239731 --4.0485033989,1.89653968811,5.00908756256 --4.06348991394,1.90054512024,5.0108795166 --4.0764670372,1.89855444431,4.99346542358 --4.08844566345,1.89656329155,4.97606658936 --4.11642026901,1.90257382393,4.97766113281 --4.13739538193,1.90458393097,4.96923828125 --4.14937400818,1.90259277821,4.95183944702 --4.16236114502,1.9055981636,4.95062875748 --4.17533922195,1.90460705757,4.93422746658 --4.19831514359,1.90761685371,4.92982769012 --4.21329164505,1.90762627125,4.91440916061 --4.23226881027,1.90863573551,4.90500736237 --4.24524688721,1.90764462948,4.88860559464 --4.26022386551,1.9076539278,4.87318658829 --4.27121257782,1.9086586237,4.87099647522 --4.28618955612,1.90866792202,4.85557746887 --4.30716705322,1.91167724133,4.84918689728 --4.33114147186,1.91468727589,4.84376716614 --4.36011648178,1.92169749737,4.8453669548 --4.38209199905,1.92470729351,4.8379535675 --4.40506792068,1.92771685123,4.83255290985 --4.41305685043,1.92772138119,4.82534456253 --4.43703269958,1.93173110485,4.82094430923 --4.44101285934,1.92673909664,4.7935295105 --4.45999002457,1.92874825001,4.78312301636 --4.45997142792,1.9217556715,4.75272226334 --4.46894979477,1.9187643528,4.73029756546 --4.46094322205,1.91176724434,4.7071018219 --4.48591899872,1.91577672958,4.70370292664 --4.51189422607,1.92078649998,4.70029067993 --4.50787687302,1.91279363632,4.66588497162 --4.52285480499,1.9128023386,4.65148019791 --4.52783489227,1.90781033039,4.62606525421 --4.56080913544,1.91582036018,4.6306681633 --4.5627989769,1.91382431984,4.61746025085 --4.57677745819,1.91383314133,4.60104227066 --4.59775495529,1.91584193707,4.59365129471 --4.59773588181,1.90984940529,4.56323337555 --4.60771608353,1.90785741806,4.54484176636 --4.56970643997,1.88486170769,4.47742700577 --4.50670194626,1.85086405277,4.38601064682 --4.49369525909,1.84286677837,4.35880279541 --4.51867103577,1.84687626362,4.354388237 --4.52365255356,1.84388375282,4.3319940567 --4.53463125229,1.84289205074,4.31458806992 --4.56260633469,1.84890151024,4.31317806244 --4.57258605957,1.84690964222,4.2947716713 --4.5845746994,1.84891414642,4.292573452 --4.58655500412,1.843922019,4.26514434814 --4.60153341293,1.84393036366,4.2517414093 --4.61451292038,1.84393835068,4.23735141754 --4.63249063492,1.84594714642,4.22593736649 --4.63947057724,1.84295499325,4.20452451706 --4.65444946289,1.84396314621,4.19112157822 --4.65843963623,1.8429672718,4.18091535568 --4.68741464615,1.84897661209,4.17950391769 --4.67939805984,1.83998322487,4.14509630203 --4.69137763977,1.8399913311,4.12868833542 --4.72435283661,1.84800076485,4.13128757477 --4.72433519363,1.84300780296,4.10488891602 --4.73931312561,1.84301614761,4.09047222137 --4.74730300903,1.84402012825,4.08427238464 --4.75428390503,1.84102773666,4.06386995316 --4.76926279068,1.84203565121,4.05046796799 --4.77324390411,1.83804309368,4.02705717087 --4.78922224045,1.84005141258,4.0136423111 --4.79620265961,1.83705890179,3.99323678017 --4.81418085098,1.83906722069,3.98182725906 --4.81117296219,1.83607029915,3.96663069725 --4.82815217972,1.8370783329,3.95523452759 --4.84712982178,1.84008681774,3.94381356239 --4.85211133957,1.83709394932,3.92241621017 --4.85909175873,1.83410143852,3.9020075798 --4.8850684166,1.84011018276,3.89659261703 --4.87406158447,1.8331130743,3.8743827343 --4.89404010773,1.83612108231,3.86498212814 --4.91101884842,1.83712911606,3.85257291794 --4.91500091553,1.83413589001,3.83118438721 --4.92498064041,1.83314371109,3.81276726723 --4.94295930862,1.83615148067,3.80136179924 --4.93694257736,1.82815814018,3.7709505558 --4.93393468857,1.82516145706,3.75574374199 --4.95891189575,1.83016979694,3.74933242798 --4.96289396286,1.8271766901,3.72793865204 --4.97487354279,1.82718420029,3.71152687073 --4.9978518486,1.83119213581,3.70412731171 --4.98883581161,1.82319867611,3.6717107296 --5.0018157959,1.82320618629,3.65630221367 --5.03180170059,1.83321094513,3.66711735725 --5.00878858566,1.81921648979,3.6247010231 --5.02676677704,1.82122433186,3.6122815609 --5.05074548721,1.82623207569,3.60589051247 --5.04672861099,1.82023894787,3.57747030258 --5.05870866776,1.82024633884,3.56105732918 --5.08568668365,1.8262540102,3.55666732788 --5.07767963409,1.8212569952,3.53845930099 --5.09765815735,1.82426464558,3.52805328369 --5.12063646317,1.8282725811,3.51964688301 --5.11262130737,1.82127845287,3.49025011063 --5.13859844208,1.82728660107,3.48282670975 --5.15957736969,1.83029413223,3.47343015671 --5.14557218552,1.82329654694,3.45223522186 --5.15855169296,1.82430398464,3.43581151962 --5.17453193665,1.82531130314,3.42240524292 --5.16851568222,1.81931746006,3.39399337769 --5.19049501419,1.82332479954,3.3856048584 --5.19847583771,1.82233178616,3.3661866188 --5.21045732498,1.82333862782,3.35079216957 --5.22144651413,1.82434237003,3.34558200836 --5.22442865372,1.82134902477,3.32316732407 --5.23141098022,1.82035553455,3.30477666855 --5.2423915863,1.8203625679,3.28735852242 --5.25637245178,1.82136940956,3.27295970917 --5.24935674667,1.81537568569,3.24454689026 --5.26333665848,1.81638264656,3.22912979126 --5.26932811737,1.81738591194,3.22194099426 --5.28530788422,1.81839311123,3.20752096176 --5.30728769302,1.82340013981,3.19812464714 --5.32526779175,1.8254070282,3.18572044373 --5.32625055313,1.82241344452,3.16230416298 --5.33923244476,1.82341992855,3.14791822433 --5.35021305084,1.82342672348,3.13050103188 --5.35320425034,1.82343006134,3.12029194832 --5.37218379974,1.82543694973,3.10788035393 --5.39016389847,1.82844364643,3.09547996521 --5.38714885712,1.82444953918,3.0710837841 --5.39513063431,1.82345604897,3.05268001556 --5.41211128235,1.82546269894,3.03927326202 --5.43709039688,1.83146965504,3.02985811234 --5.41908502579,1.82347238064,3.00764656067 --5.4330663681,1.82447862625,2.99325346947 --5.44004869461,1.82348501682,2.97384119034 --5.44803094864,1.82349133492,2.95543622971 --5.4560136795,1.82249748707,2.93703150749 --5.47399377823,1.82550418377,2.92361855507 --5.46898651123,1.82150697708,2.90941405296 --5.48796701431,1.8255136013,2.89701008797 --5.50094890594,1.82651972771,2.8816113472 --5.50693178177,1.82552587986,2.86220788956 --5.52191305161,1.82753229141,2.84679055214 --5.54289340973,1.83153855801,2.83539009094 --5.54387712479,1.8285446167,2.81297922134 --5.54986810684,1.82854771614,2.80477666855 --5.5658493042,1.8315538168,2.79037046432 --5.58483028412,1.83456003666,2.77797436714 --5.59081363678,1.83356595039,2.7585709095 --5.60479545593,1.83557200432,2.74316740036 --5.62277698517,1.83857810497,2.72976493835 --5.63875770569,1.84058439732,2.71434521675 --5.65874671936,1.84658753872,2.71314740181 --5.65573120117,1.84159338474,2.68873405457 --5.66771411896,1.84359920025,2.67233300209 --5.67169761658,1.84160494804,2.65192961693 --5.68168067932,1.84161067009,2.63452839851 --5.70466041565,1.8466168642,2.62210679054 --5.70764493942,1.84462225437,2.60171175003 --5.71763563156,1.84662520885,2.59551501274 --5.71162033081,1.84163093567,2.57010316849 --5.7286028862,1.84463655949,2.55569911003 --5.74658441544,1.84764242172,2.5412876606 --5.7575674057,1.84964776039,2.52489876747 --5.76954984665,1.85065364838,2.50748324394 --5.7715344429,1.84765911102,2.48607611656 --5.77852535248,1.8496619463,2.47786951065 --5.79550743103,1.85166764259,2.46347045898 --5.79849147797,1.8506731987,2.4420542717 --5.81947278976,1.85467875004,2.42864346504 --5.82545661926,1.85368418694,2.40924096107 --5.84743881226,1.85868954659,2.3968436718 --5.84842348099,1.85669493675,2.37544298172 --5.86241388321,1.85969758034,2.37024092674 --5.87239694595,1.86070311069,2.35182666779 --5.88937902451,1.86370849609,2.33641624451 --5.90036249161,1.86471366882,2.31901454926 --5.9023475647,1.86271882057,2.29862451553 --5.92332983017,1.8667242527,2.28420543671 --5.92632198334,1.8667267561,2.27501416206 --5.9373049736,1.86773204803,2.25659561157 --5.94528913498,1.86773705482,2.23819899559 --5.97427034378,1.87574231625,2.22678303719 --5.98725414276,1.87674725056,2.21039032936 --6.00123786926,1.87975227833,2.19399094582 --6.01622056961,1.88175749779,2.17656707764 --6.02621221542,1.88375961781,2.17038488388 --6.0341963768,1.8837647438,2.15097332001 --6.03618144989,1.88276970387,2.12956476212 --6.05016469955,1.88477480412,2.11214995384 --6.06114912033,1.88577950001,2.09475636482 --6.0641336441,1.88478457928,2.07334065437 --6.08411693573,1.88878917694,2.05894470215 --6.08510971069,1.88879156113,2.04874968529 --6.09609365463,1.88979649544,2.03033876419 --6.11407661438,1.89280128479,2.01392149925 --6.10806322098,1.88880610466,1.99052524567 --6.11304807663,1.88881087303,1.97011506557 --6.13403081894,1.8928155899,1.95470011234 --6.14401531219,1.89382016659,1.93629789352 --6.13600921631,1.89082252979,1.92310035229 --6.15899276733,1.89582693577,1.90869522095 --6.15697813034,1.89283180237,1.88628995419 --6.17596197128,1.8968360424,1.87089216709 --6.18194675446,1.89684069157,1.85047721863 --6.19893121719,1.9008449316,1.83407449722 --6.20891618729,1.90184938908,1.81567537785 --6.2029094696,1.8988519907,1.80246257782 --6.20589494705,1.89785671234,1.78104579449 --6.22787857056,1.90286064148,1.76665616035 --6.23386383057,1.90286517143,1.74624228477 --6.23285055161,1.90086960793,1.72484755516 --6.23883581161,1.90087401867,1.70443332195 --6.23982858658,1.89987635612,1.69423699379 --6.24781322479,1.90088069439,1.67381191254 --6.24779939651,1.89888525009,1.65241014957 --6.25478506088,1.89988946915,1.63300943375 --6.25877094269,1.89889383316,1.61260533333 --6.27875566483,1.90389764309,1.59619677067 --6.28674077988,1.90390181541,1.57679271698 --6.28573417664,1.90290415287,1.56558656693 --6.292719841,1.90390813351,1.5461871624 --6.3077044487,1.9069122076,1.52776873112 --6.32568979263,1.91091561317,1.51137578487 --6.32567644119,1.90891993046,1.48997294903 --6.31966304779,1.90592455864,1.46655869484 --6.32664871216,1.90592873096,1.4461414814 --6.33264112473,1.90693068504,1.43694067001 --6.3316283226,1.90593481064,1.41554033756 --6.34761381149,1.9089384079,1.39814138412 --6.35659980774,1.90994226933,1.37873578072 --6.36358547211,1.91094613075,1.35831975937 --6.36857128143,1.91095006466,1.33791279793 --6.34656000137,1.90295541286,1.31150221825 --6.37155151367,1.90995633602,1.30630135536 --6.3875374794,1.91295957565,1.28890752792 --6.37652492523,1.90896427631,1.26448762417 --6.37751150131,1.90696835518,1.2430768013 --6.38949775696,1.90997171402,1.22468054295 --6.37548589706,1.90397655964,1.20026862621 --6.38647127151,1.90597999096,1.18085718155 --6.39846420288,1.90898132324,1.17265665531 --6.38345241547,1.90298628807,1.14824521542 --6.40343809128,1.90798914433,1.13084113598 --6.42742347717,1.91499173641,1.11444401741 --6.41341114044,1.90899646282,1.09002673626 --6.41739845276,1.90900015831,1.06962311268 --6.43738460541,1.91400277615,1.05222427845 --6.40437984467,1.90300691128,1.03500330448 --6.41536712646,1.90500986576,1.01661479473 --6.42035388947,1.90601336956,0.996207296848 --6.40034151077,1.89801871777,0.97078114748 --6.41132831573,1.90002179146,0.951373577118 --6.43731451035,1.90702390671,0.934980213642 --6.44430160522,1.90902721882,0.914567470551 --6.45329475403,1.91102850437,0.905364990234 --6.48328113556,1.91903018951,0.888965964317 --6.46026945114,1.9110352993,0.864562153816 --6.46525716782,1.91203868389,0.844156563282 --6.49724340439,1.92004013062,0.82775759697 --6.47223186493,1.91204559803,0.802334606647 --6.47521972656,1.91204893589,0.781934738159 --6.4842133522,1.91404998302,0.772735595703 --6.49620056152,1.91705262661,0.753333687782 --6.48418855667,1.91205716133,0.729912042618 --6.51717567444,1.92205810547,0.713520646095 --6.4901638031,1.91206383705,0.688093006611 --6.49415206909,1.91306698322,0.667690992355 --6.52414464951,1.92206645012,0.660488128662 --6.51713323593,1.91907024384,0.639091849327 --6.52312135696,1.9200732708,0.618687391281 --6.54310846329,1.92507505417,0.599275350571 --6.52509689331,1.91907989979,0.57585978508 --6.53608512878,1.92208230495,0.556466281414 --6.55807256699,1.92808389664,0.537054300308 --6.54006767273,1.92208695412,0.524851202965 --6.54605579376,1.92308974266,0.504448711872 --6.57504320145,1.93109047413,0.486048310995 --6.56303167343,1.92709469795,0.463637083769 --6.58601999283,1.93309593201,0.444230437279 --6.5920085907,1.93509840965,0.423830986023 --6.58699655533,1.93210208416,0.401408523321 --6.58699131012,1.93210363388,0.391212970018 --6.6029791832,1.93610537052,0.370801448822 --6.58296823502,1.93011021614,0.348396122456 --6.61395645142,1.93911039829,0.328988045454 --6.60594558716,1.93611419201,0.307587087154 --6.61893415451,1.93911588192,0.287183046341 --6.62792253494,1.94211804867,0.265764474869 --6.63191747665,1.94311916828,0.255565851927 --6.63890647888,1.9451212883,0.235169962049 --6.65789556503,1.95012223721,0.214765310287 --6.6498837471,1.94712603092,0.192343920469 --6.64887285233,1.94612896442,0.170936137438 --6.67086219788,1.95312952995,0.1505330652 --6.67385101318,1.95413208008,0.129123747349 --6.68784570694,1.95813190937,0.118922479451 --6.68483495712,1.95613491535,0.0975173786283 --6.68382406235,1.95613777637,0.0761106237769 --6.67481374741,1.95314133167,0.0547064878047 --6.66780281067,1.95114481449,0.033300485462 --6.68179225922,1.95514583588,0.0118891559541 --6.69978761673,1.96014511585,0.00169193209149 --6.70577716827,1.96214711666,-0.0197153929621 --6.6967663765,1.95915067196,-0.041121058166 --6.70175600052,1.96015262604,-0.0625277608633 --6.7097454071,1.96215415001,-0.0839337259531 --6.70573568344,1.96115720272,-0.105340458453 --6.70572471619,1.96115982533,-0.127766266465 --6.71171474457,1.96316146851,-0.149171277881 --6.702709198,1.9601637125,-0.159367144108 --6.7156996727,1.96416461468,-0.180769369006 --6.717689991,1.96516656876,-0.202174574137 --6.7126789093,1.96316969395,-0.224601894617 --6.70266866684,1.96017324924,-0.24601328373 --6.68865776062,1.95617735386,-0.267428338528 --6.69464826584,1.95817887783,-0.288831979036 --6.69664335251,1.9581797123,-0.299024313688 --6.70963382721,1.96218037605,-0.321440964937 --6.70862388611,1.96218264103,-0.342847973108 --6.6966137886,1.95918643475,-0.363245368004 --6.70260429382,1.96118795872,-0.385666012764 --6.70559501648,1.96218955517,-0.407069444656 --6.69358921051,1.95819234848,-0.417275011539 --6.71758127213,1.9661911726,-0.439675360918 --6.70557069778,1.96219491959,-0.461094260216 --6.71656227112,1.96619546413,-0.482487082481 --6.70755147934,1.96419882774,-0.50390380621 --6.71654272079,1.96719956398,-0.526316821575 --6.70953226089,1.96520245075,-0.547731459141 --6.72452926636,1.96920132637,-0.558922231197 --6.71351909637,1.9672049284,-0.580343127251 --6.71050977707,1.96620726585,-0.601752460003 --6.72050094604,1.96920764446,-0.623141229153 --6.7004904747,1.9642124176,-0.643559575081 --6.70048141479,1.96421420574,-0.664964616299 --6.70347261429,1.96521556377,-0.687383472919 --6.69446706772,1.9632178545,-0.697592735291 --6.67945671082,1.95922195911,-0.718006849289 --6.69144868851,1.96322190762,-0.740408658981 --6.70344114304,1.96722185612,-0.762808680534 --6.71443271637,1.97122180462,-0.785209298134 --6.70142316818,1.96822547913,-0.805620908737 --6.6934132576,1.9662283659,-0.827042102814 --6.70941019058,1.9712266922,-0.839237451553 --6.71540212631,1.97422730923,-0.861645936966 --6.72339439392,1.97722768784,-0.884048700333 --6.70938444138,1.97323143482,-0.904464483261 --6.71637678146,1.97623181343,-0.926868677139 --6.7103676796,1.97523415089,-0.948285281658 --6.71935987473,1.97823417187,-0.970682621002 --6.71635580063,1.97823536396,-0.981900572777 --6.7123465538,1.97723758221,-1.00331175327 --6.69833707809,1.97424125671,-1.02271270752 --6.70132875443,1.9752420187,-1.04512453079 --6.69131994247,1.97324514389,-1.06553483009 --6.68831110001,1.97324693203,-1.08694469929 --6.70630502701,1.98024511337,-1.11134958267 --6.6952996254,1.977247715,-1.12055373192 --6.69529151917,1.9772490263,-1.14297258854 --6.69028329849,1.97725105286,-1.16438806057 --6.66627264023,1.97025644779,-1.18178784847 --6.66526460648,1.97125792503,-1.20421099663 --6.68825912476,1.9792548418,-1.22961163521 --6.68525123596,1.97925651073,-1.25102031231 --6.67924642563,1.97825813293,-1.26123046875 --6.69124078751,1.98225700855,-1.28462553024 --6.69023275375,1.98325812817,-1.30704569817 --6.70322704315,1.98825669289,-1.33043432236 --6.68521690369,1.98426103592,-1.34985792637 --6.68120908737,1.98426282406,-1.37126946449 --6.68920230865,1.98726212978,-1.39467358589 --6.68919897079,1.98826253414,-1.40588104725 --6.67819023132,1.98526549339,-1.42629945278 --6.68518400192,1.98926508427,-1.44970571995 --6.68117570877,1.98926663399,-1.4711163044 --6.68316888809,1.99126696587,-1.49352169037 --6.67016077042,1.98827016354,-1.51293087006 --6.675157547,1.99026954174,-1.52513575554 --6.6691493988,1.99027144909,-1.54655456543 --6.66514205933,1.9902728796,-1.56796503067 --6.65313339233,1.98727607727,-1.58737206459 --6.64712572098,1.98727786541,-1.60777306557 --6.65612030029,1.99127662182,-1.63218319416 --6.65311288834,1.99127781391,-1.6546074152 --6.64710855484,1.99027919769,-1.66380250454 --6.63509988785,1.98828232288,-1.68321192265 --6.66009759903,1.99727761745,-1.71161973476 --6.65809106827,1.99827837944,-1.73301947117 --6.65308380127,1.99827980995,-1.75443291664 --6.64807653427,1.99828124046,-1.77584648132 --6.65807199478,2.00327944756,-1.80126178265 --6.65406799316,2.00228047371,-1.81146597862 --6.64706039429,2.00128221512,-1.83186984062 --6.644053936,2.00228309631,-1.85429131985 --6.63904666901,2.00228452682,-1.87570405006 --6.63904094696,2.00428462029,-1.89810979366 --6.6300330162,2.00328683853,-1.91852450371 --6.63002681732,2.00428700447,-1.94092929363 --6.61802196503,2.00128960609,-1.94913899899 --6.60701417923,2.00029230118,-1.96854698658 --6.60400724411,2.00029325485,-1.99096775055 --6.6070022583,2.00329232216,-2.01437425613 --6.61299800873,2.00729107857,-2.03878188133 --6.6109919548,2.00829124451,-2.06119537354 --6.60898590088,2.00929188728,-2.08259010315 --6.61298418045,2.01129078865,-2.09580469131 --6.60697746277,2.01129198074,-2.11722111702 --6.61097335815,2.01429080963,-2.14061689377 --6.6189699173,2.01928877831,-2.16602492332 --6.62596607208,2.02328681946,-2.191437006 --6.61595869064,2.02228879929,-2.2118563652 --6.64295959473,2.03328180313,-2.24325633049 --6.64295721054,2.03428149223,-2.25445389748 --6.67495965958,2.04627323151,-2.28785419464 --6.69595956802,2.0552675724,-2.31724452972 --6.69695568085,2.05826640129,-2.34166383743 --6.71595573425,2.06626105309,-2.37106084824 --6.74495792389,2.07825279236,-2.40446400642 --6.74595403671,2.08025169373,-2.42887711525 --6.7319483757,2.07625484467,-2.43608522415 --6.73694610596,2.08125257492,-2.46149086952 --6.71193599701,2.07525849342,-2.47690844536 --6.70292949677,2.074259758,-2.49833154678 --6.70192527771,2.0762591362,-2.52072119713 --6.67091369629,2.06826615334,-2.53414702415 --6.66390800476,2.06826710701,-2.55555891991 --6.66890716553,2.07126522064,-2.56977009773 --6.63289403915,2.06227421761,-2.58119869232 --6.63088989258,2.06327366829,-2.60461306572 --6.63788843155,2.06827044487,-2.63101863861 --6.615878582,2.06327557564,-2.6464278698 --6.60987329483,2.06427598,-2.66885113716 --6.61387300491,2.06627440453,-2.68204903603 --6.58786201477,2.06028032303,-2.69647145271 --6.57985639572,2.0602812767,-2.7178914547 --6.58985614777,2.06627750397,-2.74528884888 --6.55184221268,2.05628681183,-2.75471329689 --6.55683994293,2.06028413773,-2.78112769127 --6.5508351326,2.06128454208,-2.80253362656 --6.53582954407,2.05828809738,-2.80874586105 --6.52382278442,2.05629038811,-2.82816123962 --6.52482032776,2.05928874016,-2.85256767273 --6.49580860138,2.05229568481,-2.86498880386 --6.48680305481,2.05229687691,-2.88641810417 --6.48980140686,2.05629467964,-2.91080880165 --6.46679162979,2.05129981041,-2.92624092102 --6.46278905869,2.05130028725,-2.93644332886 --6.46978855133,2.05629658699,-2.9638531208 --6.43377494812,2.04730606079,-2.97226786613 --6.42176818848,2.04630804062,-2.99168753624 --6.43076848984,2.05230379105,-3.02009701729 --6.40075683594,2.04531097412,-3.03152179718 --6.38975048065,2.04431295395,-3.05093455315 --6.39575004578,2.04930925369,-3.07834792137 --6.36673927307,2.0403175354,-3.07756400108 --6.35973453522,2.04131793976,-3.09897971153 --6.36973619461,2.04731297493,-3.12737560272 --6.33472251892,2.03932237625,-3.13579916954 --6.32171583176,2.03732466698,-3.15523028374 --6.32271432877,2.04132246971,-3.17963051796 --6.30970859528,2.03832554817,-3.18584132195 --6.29370117188,2.03632903099,-3.20326495171 --6.28969812393,2.03732824326,-3.22567224503 --6.26768827438,2.03333353996,-3.24009728432 --6.26568603516,2.03633236885,-3.26350450516 --6.2596821785,2.03733205795,-3.28592824936 --6.232670784,2.03133893013,-3.29734897614 --6.22766780853,2.03133964539,-3.30756163597 --6.22166395187,2.03233981133,-3.32896900177 --6.18364906311,2.02235031128,-3.334389925 --6.18764877319,2.02734684944,-3.36079335213 --6.1856470108,2.03034543991,-3.38521552086 --6.15963554382,2.02435207367,-3.39663505554 --6.14562940598,2.02335453033,-3.41506505013 --6.14262723923,2.02335453033,-3.42526006699 --6.12061786652,2.01936006546,-3.43868041039 --6.10561084747,2.01736283302,-3.45610451698 --6.10460948944,2.02036094666,-3.47949934006 --6.08059883118,2.01636719704,-3.49192523956 --6.06659221649,2.01436972618,-3.51035809517 --6.0655913353,2.01736760139,-3.53375196457 --6.04658317566,2.01337313652,-3.53698277473 --6.02757453918,2.01037764549,-3.5513985157 --6.02457237244,2.01237607002,-3.57481074333 --6.00756502151,2.01038002968,-3.59022498131 --5.98855638504,2.00738430023,-3.60464334488 --5.98655557632,2.01038241386,-3.62906146049 --5.97755098343,2.01038312912,-3.64846491814 --5.96154403687,2.00738787651,-3.65268945694 --5.94953870773,2.00638961792,-3.6711063385 --5.92252635956,2.00039720535,-3.68052554131 --5.90852022171,1.99939978123,-3.69794797897 --5.90751981735,2.00339722633,-3.7223546505 --5.89951610565,2.00439739227,-3.74378180504 --5.87550544739,1.99940407276,-3.75419163704 --5.87050294876,1.99940443039,-3.76440739632 --5.85249519348,1.99740862846,-3.7788233757 --5.83048534393,1.9934142828,-3.79124903679 --5.83048582077,1.99741137028,-3.81665897369 --5.81247758865,1.99441552162,-3.83107686043 --5.80347394943,1.99541604519,-3.85149860382 --5.76445579529,1.9854285717,-3.85292887688 --5.77045869827,1.98942482471,-3.8691265583 --5.7554526329,1.98842763901,-3.88554811478 --5.7474489212,1.98942780495,-3.90595984459 --5.72944116592,1.98743212223,-3.92038202286 --5.71643543243,1.98643422127,-3.93779921532 --5.7134346962,1.98943221569,-3.96120429039 --5.68041944504,1.98144257069,-3.96664762497 --5.67441654205,1.98144352436,-3.97484326363 --5.67141628265,1.98444139957,-3.99926424026 --5.65641021729,1.98344433308,-4.0146727562 --5.63139867783,1.9784514904,-4.02511310577 --5.62439632416,1.98045098782,-4.0465297699 --5.60838890076,1.97845447063,-4.06093502045 --5.58637905121,1.97546052933,-4.07236146927 --5.58537960052,1.97745931149,-4.0845656395 --5.5643696785,1.97346484661,-4.0959815979 --5.56136989594,1.97746253014,-4.1203994751 --5.53335618973,1.97147119045,-4.12783479691 --5.52835512161,1.97346973419,-4.15024280548 --5.52035284042,1.97546958923,-4.17065382004 --5.49233865738,1.96748018265,-4.16488647461 --5.48533678055,1.96847963333,-4.18528604507 --5.48333740234,1.97247672081,-4.21070480347 --5.46633005142,1.97148060799,-4.22512769699 --5.44031763077,1.96548855305,-4.23254776001 --5.43731784821,1.96948611736,-4.25696134567 --5.42431306839,1.96948802471,-4.27438402176 --5.40430259705,1.96449542046,-4.27259397507 --5.39229822159,1.96449697018,-4.29000616074 --5.39730405807,1.97149038315,-4.32142925262 --5.34527540207,1.95551085472,-4.30886173248 --5.34327745438,1.95950770378,-4.33427667618 --5.3422794342,1.96450400352,-4.36069345474 --5.31026315689,1.95651507378,-4.36312055588 --5.30726242065,1.95851457119,-4.37331390381 --5.30326318741,1.96151208878,-4.39773464203 --5.2752494812,1.95552134514,-4.4031624794 --5.24223232269,1.94853317738,-4.40459442139 --5.24723815918,1.95552623272,-4.43600940704 --5.22222614288,1.9505341053,-4.44343471527 --5.20822048187,1.94953680038,-4.45884370804 --5.20922327042,1.95253396034,-4.47304534912 --5.19021463394,1.95053887367,-4.48547315598 --5.16219949722,1.94454860687,-4.48989582062 --5.16620635986,1.95154178143,-4.52131700516 --5.12918567657,1.94255590439,-4.51875257492 --5.11618089676,1.94255793095,-4.53516626358 --5.11318349838,1.94655478001,-4.56058454514 --5.08916902542,1.9395648241,-4.55379486084 --5.08316898346,1.94256317616,-4.57620716095 --5.07316684723,1.94356334209,-4.59664106369 --5.03414440155,1.93357920647,-4.59005594254 --5.03614997864,1.93957304955,-4.62048006058 --5.02514743805,1.94157397747,-4.63889789581 --5.00313615799,1.93758070469,-4.64731359482 --4.99313211441,1.93658351898,-4.65353822708 --4.98012733459,1.93658542633,-4.66995286942 --4.96011781693,1.9335911274,-4.68037414551 --4.94611310959,1.93359351158,-4.69680309296 --4.93711090088,1.93559324741,-4.71620798111 --4.90909576416,1.92960333824,-4.71963834763 --4.89108800888,1.9286082983,-4.7310500145 --4.89809560776,1.93360161781,-4.75226163864 --4.8540687561,1.92162084579,-4.74069833755 --4.85907745361,1.92961263657,-4.77309846878 --4.84907579422,1.93061256409,-4.79353046417 --4.82806587219,1.92861914635,-4.80194234848 --4.80805635452,1.92562496662,-4.81237030029 --4.80105686188,1.92862331867,-4.83478879929 --4.78404664993,1.92463028431,-4.83300113678 --4.76303625107,1.92163681984,-4.84243106842 --4.7660446167,1.92962896824,-4.8748497963 --4.7350268364,1.92264139652,-4.87427997589 --4.72502470016,1.92364144325,-4.89369630814 --4.73003530502,1.93263268471,-4.92709541321 --4.68400526047,1.91865408421,-4.91153383255 --4.68600988388,1.92264974117,-4.92874717712 --4.67000389099,1.92265319824,-4.94317913055 --4.64599084854,1.91766166687,-4.94860076904 --4.62598133087,1.91566777229,-4.95802259445 --4.61798191071,1.91866648197,-4.97943687439 --4.60197496414,1.91767001152,-4.9928560257 --4.58996915817,1.91567444801,-4.99506235123 --4.58697366714,1.92066979408,-5.02248430252 --4.55895757675,1.91568076611,-5.02391624451 --4.54495286942,1.91568315029,-5.03933429718 --4.5339512825,1.91768336296,-5.05876302719 --4.51494216919,1.91568887234,-5.06918716431 --4.50093793869,1.91569137573,-5.08359146118 --4.50194263458,1.91968715191,-5.10081005096 --4.48293399811,1.91769266129,-5.11123466492 --4.45491743088,1.91270399094,-5.11166095734 --4.44992113113,1.91670036316,-5.13707828522 --4.42390584946,1.91171050072,-5.13950395584 --4.41390562057,1.91371023655,-5.15891456604 --4.40490579605,1.91670906544,-5.18033695221 --4.38389110565,1.91071927547,-5.17356681824 --4.37188863754,1.91272056103,-5.18996810913 --4.35888528824,1.91372191906,-5.20739793777 --4.33287000656,1.90873217583,-5.20982933044 --4.32487249374,1.91272997856,-5.23326063156 --4.31086826324,1.91273224354,-5.24867868423 --4.29085826874,1.9107388258,-5.25608539581 --4.27284574509,1.90574729443,-5.25231599808 --4.26084375381,1.90774810314,-5.26973009109 --4.24583864212,1.90775096416,-5.28415155411 --4.23984336853,1.91274738312,-5.3095741272 --4.21783161163,1.90975511074,-5.31600189209 --4.1888127327,1.90276801586,-5.31342554092 --4.17781209946,1.9047678709,-5.33284854889 --4.17381286621,1.90676689148,-5.34405517578 --4.16181135178,1.90876746178,-5.3624792099 --4.12978935242,1.90078270435,-5.35590553284 --4.11378335953,1.90078628063,-5.3693318367 --4.09577560425,1.89979124069,-5.37975215912 --4.08177232742,1.90079319477,-5.39618396759 --4.06776857376,1.90179550648,-5.41059017181 --4.0517578125,1.89780294895,-5.408826828 --4.03374958038,1.89680802822,-5.41924858093 --4.02875566483,1.90280342102,-5.44565820694 --4.00073719025,1.89681613445,-5.44308185577 --3.98573279381,1.89681863785,-5.45851707458 --3.96972727776,1.89682233334,-5.47093200684 --3.94871592522,1.89482986927,-5.47735595703 --3.94471812248,1.89682817459,-5.49058294296 --3.93471932411,1.89982712269,-5.51099586487 --3.90469789505,1.89284181595,-5.50542449951 --3.89369821548,1.89584112167,-5.52585363388 --3.88069653511,1.89784216881,-5.54327917099 --3.84867238998,1.8898588419,-5.53369808197 --3.84067583084,1.89385616779,-5.55711174011 --3.83367443085,1.89385700226,-5.56532669067 --3.80665636063,1.88886928558,-5.56376171112 --3.7956571579,1.89186859131,-5.5841884613 --3.78465771675,1.89486813545,-5.6036028862 --3.75964140892,1.88987910748,-5.60403013229 --3.74163389206,1.88988423347,-5.61445760727 --3.7326374054,1.89388179779,-5.63788318634 --3.71562337875,1.88889122009,-5.63109350204 --3.69060659409,1.88390254974,-5.63051366806 --3.68161034584,1.88789999485,-5.65393829346 --3.65959811211,1.88590836525,-5.65937852859 --3.63658380508,1.8819180727,-5.66180181503 --3.62959051132,1.88791370392,-5.68822431564 --3.6185836792,1.88591837883,-5.68942737579 --3.60157728195,1.88592267036,-5.70085144043 --3.59258198738,1.89091968536,-5.72528171539 --3.56255793571,1.88293576241,-5.71670675278 --3.54755425453,1.88393831253,-5.7311296463 --3.54356598854,1.89193069935,-5.76355934143 --3.50553059578,1.87895429134,-5.74198532104 --3.49953985214,1.8859487772,-5.77040433884 --3.48753213882,1.88395380974,-5.77162837982 --3.46451735497,1.88096404076,-5.77304887772 --3.44951367378,1.88196647167,-5.7874712944 --3.43050503731,1.88097274303,-5.79589939117 --3.40949249268,1.8779810667,-5.80031919479 --3.39549183846,1.88098192215,-5.81876707077 --3.39650177956,1.88597536087,-5.83896541595 --3.35746335983,1.87300121784,-5.81338787079 --3.34746813774,1.87799835205,-5.8378276825 --3.33847379684,1.88199496269,-5.86224603653 --3.30944943428,1.87501144409,-5.85266637802 --3.286434412,1.87202167511,-5.85409593582 --3.28344964981,1.8810120821,-5.88951969147 --3.26443123817,1.8750243187,-5.87875127792 --3.24742484093,1.87502896786,-5.88916683197 --3.2344250679,1.87802934647,-5.90759277344 --3.20539975166,1.87004625797,-5.89701128006 --3.18839430809,1.87105035782,-5.90944910049 --3.17539477348,1.87405049801,-5.92787408829 --3.15037608147,1.86906313896,-5.92530536652 --3.1443772316,1.87106287479,-5.93551874161 --3.13037586212,1.87306416035,-5.9519405365 --3.10335302353,1.86607933044,-5.94436168671 --3.09335947037,1.87207579613,-5.96979951859 --3.07234668732,1.86908471584,-5.97322034836 --3.04732751846,1.86509788036,-5.96964931488 --3.03232502937,1.86609983444,-5.98507881165 --3.02332115173,1.86610281467,-5.9892873764 --2.99930357933,1.8621147871,-5.98771953583 --2.98430132866,1.86411690712,-6.00314950943 --2.97130155563,1.86711728573,-6.02055931091 --2.94127416611,1.85913562775,-6.00901126862 --2.9262714386,1.86113798618,-6.02343082428 --2.91627836227,1.86613428593,-6.04885911942 --2.90126371384,1.8621442318,-6.04106855392 --2.87424015999,1.85616016388,-6.03249883652 --2.8662507534,1.86315405369,-6.06192445755 --2.84123015404,1.85816812515,-6.05634689331 --2.82121896744,1.85617601871,-6.06177711487 --2.81022429466,1.86117327213,-6.08520078659 --2.7932062149,1.85618531704,-6.07442712784 --2.77519893646,1.85619080067,-6.08385658264 --2.7632021904,1.86018967628,-6.10427045822 --2.7301659584,1.84921336174,-6.08270978928 --2.72117614746,1.85620772839,-6.1111369133 --2.70216631889,1.85521495342,-6.11755943298 --2.68215537071,1.85422277451,-6.1229929924 --2.66414833069,1.85422837734,-6.13242292404 --2.65714812279,1.85522890091,-6.14062929153 --2.63513183594,1.8522400856,-6.14005041122 --2.61311626434,1.84925079346,-6.14048147202 --2.60112142563,1.85424864292,-6.16290712357 --2.5791053772,1.85125982761,-6.1623301506 --2.56009626389,1.85126650333,-6.16976356506 --2.55109333992,1.85126876831,-6.17599153519 --2.53007936478,1.84927880764,-6.17741441727 --2.5160806179,1.85227906704,-6.19584178925 --2.49506759644,1.85128819942,-6.19928216934 --2.47605681419,1.8492962122,-6.20369100571 --2.46005511284,1.85229849815,-6.21913194656 --2.44004201889,1.85030770302,-6.22154521942 --2.43003630638,1.84931182861,-6.22376012802 --2.40701794624,1.84632432461,-6.22119474411 --2.3910150528,1.84832751751,-6.23461818695 --2.36899971962,1.84533810616,-6.23606586456 --2.355001688,1.84933817387,-6.25448846817 --2.33398795128,1.84734785557,-6.25692462921 --2.31397485733,1.84535717964,-6.25934123993 --2.30697727203,1.84835648537,-6.27056741714 --2.28195214272,1.84237325191,-6.25998592377 --2.26695203781,1.8453745842,-6.27641105652 --2.25395750999,1.84937250614,-6.29883861542 --2.22191619873,1.83839917183,-6.2722826004 --2.20290613174,1.83840680122,-6.27770614624 --2.1768784523,1.83142507076,-6.2651386261 --1.51353764534,1.827688694,-6.47418880463 --1.50356423855,1.83967518806,-6.51661920547 --1.4795371294,1.83469331264,-6.50506496429 --1.46152889729,1.8357001543,-6.51147651672 --1.45051836967,1.8337072134,-6.50869417191 --1.42849814892,1.83072125912,-6.50413656235 --1.4054697752,1.8247398138,-6.49055719376 --1.39248812199,1.83373129368,-6.52499961853 --1.3694614172,1.82874906063,-6.51343202591 --1.34643125534,1.82276880741,-6.49784755707 --1.33642709255,1.82277226448,-6.50208044052 --1.31440150738,1.81778919697,-6.49150085449 --1.29639494419,1.81979513168,-6.49992465973 --1.27939498425,1.82279741764,-6.51535797119 --1.26742005348,1.83378529549,-6.55579280853 --1.24338805676,1.82780611515,-6.53923225403 --1.21935164928,1.81982934475,-6.51765298843 --1.20834159851,1.81783628464,-6.51588058472 --1.18731999397,1.8148509264,-6.50930500031 --1.16931450367,1.81685650349,-6.51873207092 --1.15332341194,1.82285392284,-6.54317617416 --1.13230335712,1.81986761093,-6.5386095047 --1.11429619789,1.82087409496,-6.54602622986 --1.0952899456,1.82288014889,-6.55547189713 --1.07824230194,1.80990850925,-6.51568555832 --1.05923342705,1.81091594696,-6.52212238312 --1.04323923588,1.81591510773,-6.5425453186 --1.0212085247,1.80993497372,-6.52696466446 --1.00219905376,1.81094300747,-6.5323972702 --0.98419880867,1.81394565105,-6.54784297943 --0.964179515839,1.81195902824,-6.54326152802 --0.954175710678,1.81296265125,-6.54749345779 --0.935165941715,1.81297063828,-6.55292510986 --0.912130713463,1.80599308014,-6.5333609581 --0.893119215965,1.80600214005,-6.53678750992 --0.875114798546,1.8080073595,-6.54721403122 --0.856103301048,1.8080163002,-6.5506401062 --0.833067774773,1.80103898048,-6.53108358383 --0.829106271267,1.81501889229,-6.57630825043 --0.805055975914,1.80304968357,-6.54172992706 --0.786049246788,1.80505621433,-6.55017185211 --0.769054114819,1.81005620956,-6.56959962845 --0.746011734009,1.80108249187,-6.54303073883 --0.71404504776,1.81806969643,-6.60489845276 --0.704035699368,1.81707620621,-6.60311222076 --0.684021055698,1.81708729267,-6.60355138779 --0.667032182217,1.8240840435,-6.62898588181 --0.643982768059,1.81311428547,-6.5954079628 --0.625985503197,1.81711566448,-6.61284303665 --0.605972588062,1.81712579727,-6.61528682709 --0.595960378647,1.81513392925,-6.61049509048 --0.573921918869,1.80815827847,-6.58792972565 --0.554915547371,1.81016480923,-6.59636592865 --0.533881187439,1.80318653584,-6.57779073715 --0.514868021011,1.80319678783,-6.57921409607 --0.494849056005,1.80121004581,-6.57564926147 --0.474825263023,1.7982262373,-6.56707668304 --0.455819785595,1.80023229122,-6.57651472092 --0.446831911802,1.80622720718,-6.59574842453 --0.425789386034,1.79725348949,-6.56916809082 --0.405758500099,1.79227340221,-6.55358743668 --0.386761158705,1.79727518559,-6.57103872299 --0.368767470121,1.80227482319,-6.59146881104 --0.349760353565,1.80428183079,-6.59890127182 --0.341795802116,1.81726443768,-6.64013576508 --0.32075804472,1.81028819084,-6.6185708046 --0.301740676165,1.80830073357,-6.61598825455 --0.282737702131,1.81130540371,-6.62742233276 --0.261707007885,1.80732560158,-6.61287117004 --0.243718132377,1.81432282925,-6.63729667664 --0.224714368582,1.81732821465,-6.64772701263 --0.212657019496,1.80236077309,-6.60094738007 --0.192628696561,1.79837942123,-6.58838176727 --0.173628926277,1.80238258839,-6.60281705856 --0.153591096401,1.79540634155,-6.58124637604 --0.134569376707,1.79242110252,-6.57466650009 --0.11454488337,1.78943765163,-6.56610822678 --0.0955191552639,1.78645479679,-6.55552911758 --0.0855094194412,1.78546178341,-6.55375242233 --0.067584477365,1.81142520905,-6.63819551468 --0.0475379899144,1.80245363712,-6.60862874985 --0.0275580957532,1.81244659424,-6.64208507538 --0.00852155126631,1.80546939373,-6.62150096893 -0.0114856148139,1.80847704411,-6.62894868851 -0.00150779134128,1.79051196575,-5.784304142 -0.011523636058,1.79251730442,-5.79250526428 -0.0305113904178,1.78550493717,-5.76789903641 -0.0505602173507,1.79552471638,-5.80029392242 -0.0695520341396,1.7885144949,-5.77968883514 -0.0895786508918,1.79252243042,-5.79108953476 -0.108568690717,1.78551149368,-5.76848936081 -0.127586036921,1.78651475906,-5.7718744278 -0.137587204576,1.78451240063,-5.76608228683 -0.156580671668,1.77850306034,-5.74648523331 -0.17560839653,1.78251206875,-5.75986289978 -0.193580657244,1.77049171925,-5.72026634216 -0.212585940957,1.76848876476,-5.7116651535 -0.232623666525,1.77550256252,-5.73405361176 -0.252638727427,1.77550458908,-5.73446321487 -0.263669490814,1.78251767159,-5.75666332245 -0.28167283535,1.77951395512,-5.74704313278 -0.300669908524,1.77450656891,-5.73045301437 -0.318665415049,1.76949870586,-5.71284532547 -0.336656838655,1.76248884201,-5.69124698639 -0.356677114964,1.76449346542,-5.69665193558 -0.377720177174,1.77350997925,-5.72404241562 -0.389761209488,1.78352820873,-5.7562379837 -0.406744122505,1.77451395988,-5.7266330719 -0.426769286394,1.77852129936,-5.73702526093 -0.445776671171,1.77651953697,-5.73042631149 -0.463779419661,1.77351558208,-5.71981430054 -0.482785105705,1.77151286602,-5.71122074127 -0.49482139945,1.77952873707,-5.73941230774 -0.510800302029,1.76951265335,-5.70580720901 -0.531823158264,1.77251851559,-5.7132229805 -0.550834774971,1.77251887321,-5.71061754227 -0.570855617523,1.77452409267,-5.71701383591 -0.587853252888,1.77051758766,-5.70139789581 -0.60787409544,1.77252292633,-5.70779371262 -0.616871297359,1.76951873302,-5.69800138474 -0.635885894299,1.7705206871,-5.69839000702 -0.656910538673,1.77452754974,-5.70779705048 -0.672900795937,1.76751768589,-5.68518352509 -0.693925440311,1.77152442932,-5.69458913803 -0.710923194885,1.76651823521,-5.67898082733 -0.730938494205,1.76752054691,-5.67939043045 -0.740947127342,1.76852202415,-5.68059158325 -0.759960591793,1.76852369308,-5.67998361588 -0.777961492538,1.76551866531,-5.66639280319 -0.800941228867,1.75350105762,-5.62598991394 -0.81693148613,1.74649119377,-5.60239505768 -0.835946321487,1.74749338627,-5.60278749466 -0.843944370747,1.74548995495,-5.59398174286 -0.86396074295,1.7464928627,-5.59539222717 -0.881972074509,1.74649357796,-5.5927734375 -0.899976789951,1.74349081516,-5.58318042755 -0.918990790844,1.74449265003,-5.58257627487 -0.936998546124,1.74349153042,-5.57597303391 -0.960034966469,1.75050425529,-5.59737062454 -0.969037473202,1.74950301647,-5.59257411957 -0.994087815285,1.76152265072,-5.62795591354 -1.00807213783,1.75351011753,-5.59835624695 -1.03211259842,1.76252484322,-5.62375068665 -1.04609692097,1.7535122633,-5.59415435791 -1.06611347198,1.75551521778,-5.59555959702 -1.08210730553,1.74950742722,-5.57497310638 -1.09010922909,1.74850594997,-5.57015752792 -1.1040943861,1.74049377441,-5.54057073593 -1.12009382248,1.73648893833,-5.5259642601 -1.13910782337,1.7374907732,-5.52536058426 -1.16012859344,1.74049580097,-5.53077077866 -1.18014919758,1.74350106716,-5.53715467453 -1.18613767624,1.73749315739,-5.51836395264 -1.20514988899,1.73749423027,-5.51576900482 -1.22215640545,1.73649287224,-5.50815486908 -1.24016559124,1.73649251461,-5.50255298615 -1.25917875767,1.73649406433,-5.50095319748 -1.2761811018,1.73349046707,-5.48836565018 -1.29720497131,1.7374972105,-5.49775266647 -1.30721378326,1.73949897289,-5.49895191193 -1.32220816612,1.73349165916,-5.47836446762 -1.34122145176,1.73449325562,-5.47676467896 -1.36324751377,1.73950099945,-5.48815822601 -1.38025414944,1.7374997139,-5.48054790497 -1.40127372742,1.74050426483,-5.48495483398 -1.41827917099,1.73950219154,-5.47535467148 -1.42427182198,1.73549640179,-5.46055746078 -1.44730067253,1.74050557613,-5.47495126724 -1.46229732037,1.73649942875,-5.45636081696 -1.47930204868,1.7344969511,-5.44576883316 -1.49630892277,1.73349583149,-5.43816041946 -1.5203410387,1.74050629139,-5.45555114746 -1.53534078598,1.73650205135,-5.44094276428 -1.54434406757,1.73650109768,-5.43615436554 -1.56235253811,1.73550057411,-5.42956113815 -1.58036339283,1.73550128937,-5.42595100403 -1.6013828516,1.7385058403,-5.43035173416 -1.61738550663,1.7365026474,-5.41775465012 -1.63639783859,1.73650407791,-5.41515779495 -1.65641498566,1.73950767517,-5.4175491333 -1.66241061687,1.73650348186,-5.40574502945 -1.68041789532,1.73550224304,-5.3971657753 -1.69943261147,1.73650491238,-5.39754915237 -1.72145414352,1.74051034451,-5.40395355225 -1.73244273663,1.7335010767,-5.37735080719 -1.74744343758,1.73049712181,-5.36275196075 -1.77450239658,1.7485216856,-5.41494941711 -1.7884991169,1.74351596832,-5.39635562897 -1.80249834061,1.7405115366,-5.38074350357 -1.82552266121,1.74551820755,-5.39014148712 -1.83951830864,1.74051189423,-5.36956501007 -1.85652625561,1.73951160908,-5.36295366287 -1.87253010273,1.73750913143,-5.35135698318 -1.87551784515,1.7325013876,-5.33056497574 -1.90054833889,1.73951125145,-5.34695053101 -2.49788951874,1.75653374195,-5.18500423431 -2.52090954781,1.76053857803,-5.19039392471 -2.54292726517,1.7635422945,-5.19279050827 -2.5539226532,1.75953686237,-5.17120170593 -2.58395648003,1.76854741573,-5.19157886505 -2.58594655991,1.76354134083,-5.17180347443 -2.60495781898,1.76454246044,-5.16720676422 -2.61595439911,1.76053762436,-5.14760255814 -2.63997578621,1.76554298401,-5.1539940834 -2.6489675045,1.75953614712,-5.1284122467 -2.66998338699,1.76253914833,-5.12880420685 -2.69199943542,1.76554226875,-5.12921333313 -2.70401000977,1.76754498482,-5.13240718842 -2.71600842476,1.76354074478,-5.11381578445 -2.74203252792,1.76954722404,-5.1232085228 -2.75302910805,1.76554238796,-5.10262012482 -2.78105664253,1.77355027199,-5.11600589752 -2.78504133224,1.7645406723,-5.08242034912 -2.81006264687,1.76954603195,-5.08881950378 -2.8150601387,1.76654314995,-5.07703351974 -2.83307027817,1.76854383945,-5.07142400742 -2.85007786751,1.76854372025,-5.06282711029 -2.86307835579,1.76554059982,-5.04624080658 -2.89210581779,1.7725481987,-5.05864477158 -2.89809536934,1.76554071903,-5.03005647659 -2.92111349106,1.76954483986,-5.03344345093 -2.92611098289,1.767542243,-5.02166032791 -2.94412088394,1.76854276657,-5.0150604248 -2.94410061836,1.75753164291,-4.97548723221 -2.96611738205,1.76153504848,-4.97687578201 -2.98512816429,1.7625361681,-4.9712843895 -2.99813079834,1.76053404808,-4.9576716423 -3.01715087891,1.76654040813,-4.97087287903 -3.04016804695,1.77054393291,-4.97227430344 -3.06018042564,1.77254581451,-4.9686756134 -3.08620214462,1.77855098248,-4.97507286072 -3.09519767761,1.77354609966,-4.95248746872 -3.11621189117,1.77654862404,-4.95088195801 -3.13021469116,1.77454662323,-4.93629789352 -3.14122271538,1.7765481472,-4.93649196625 -3.16323804855,1.77955102921,-4.93589162827 -3.17824316025,1.7785500288,-4.92429113388 -3.19525051117,1.77854979038,-4.91470336914 -3.21225857735,1.77954995632,-4.90610361099 -3.23227071762,1.78155148029,-4.90151071548 -3.24327039719,1.77854847908,-4.88391017914 -3.2552793026,1.78055036068,-4.88510799408 -3.27328824997,1.78155064583,-4.87652492523 -3.29330086708,1.78355276585,-4.87390708923 -3.30329918861,1.77954924107,-4.85431480408 -3.33432626724,1.78855645657,-4.86670827866 -3.34031891823,1.78255081177,-4.84013032913 -3.35932922363,1.78355169296,-4.83354043961 -3.37334084511,1.78755474091,-4.83773231506 -3.36531543732,1.77354240417,-4.79115772247 -3.38933229446,1.77754592896,-4.79157018661 -3.40634059906,1.77854609489,-4.78296995163 -3.40232181549,1.76753664017,-4.74437665939 -3.42533731461,1.77153944969,-4.7427945137 -3.44735240936,1.7745423317,-4.74218273163 -3.45635724068,1.77554261684,-4.7383852005 -3.47536730766,1.77654361725,-4.73080635071 -3.5003862381,1.78154802322,-4.73517990112 -3.5274066925,1.78755271435,-4.73958444595 -3.54341340065,1.78755247593,-4.7289891243 -3.57043361664,1.79355704784,-4.73339033127 -3.58343648911,1.79155528545,-4.7178068161 -3.60145258904,1.79755973816,-4.72699260712 -3.60544490814,1.7915545702,-4.70039844513 -3.63847208023,1.80056166649,-4.71279191971 -3.64146327972,1.79355585575,-4.68420982361 -3.67148637772,1.80056142807,-4.69161319733 -3.67948365211,1.79655790329,-4.6700258255 -3.68348264694,1.79455626011,-4.65923261642 -3.69548487663,1.79255461693,-4.64363574982 -3.71549677849,1.79555642605,-4.63902664185 -3.73350596428,1.79655694962,-4.63043642044 -3.75051379204,1.79755735397,-4.62084245682 -3.77052521706,1.79955887794,-4.61524438858 -3.78152656555,1.79755687714,-4.59765815735 -3.78452444077,1.79455494881,-4.58586502075 -3.80753898621,1.7985574007,-4.58327436447 -3.82254505157,1.79855716228,-4.57167434692 -3.84756159782,1.80256056786,-4.57207345963 -3.84955358505,1.79655539989,-4.54349327087 -3.87957572937,1.80356049538,-4.54988956451 -3.88857531548,1.80055820942,-4.53030109406 -3.89657855034,1.80055809021,-4.52450895309 -3.91658997536,1.80255973339,-4.51890563965 -3.93059515953,1.80255901814,-4.50531578064 -3.95561122894,1.80756223202,-4.50472068787 -3.96961641312,1.80656158924,-4.49113035202 -3.98662471771,1.80756223202,-4.48251867294 -4.00163078308,1.8075619936,-4.4699306488 -4.00963401794,1.8075619936,-4.46413707733 -4.02564144135,1.80856227875,-4.45353603363 -4.04164838791,1.80856239796,-4.44194984436 -4.05565357208,1.80856192112,-4.42835950851 -4.06865739822,1.80756103992,-4.41278266907 -4.08766794205,1.80956232548,-4.40617132187 -4.08966588974,1.80656051636,-4.39338541031 -4.10767459869,1.80856156349,-4.384786129 -4.12468338013,1.80956208706,-4.37518548965 -4.14769649506,1.81356430054,-4.3706035614 -4.15069198608,1.80756092072,-4.3460059166 -4.1406750679,1.79655361176,-4.30642938614 -4.11664533615,1.77854239941,-4.25087881088 -4.09562206268,1.76553440094,-4.21410083771 -4.07259464264,1.74852395058,-4.16054868698 -4.04756546021,1.73051321507,-4.10598802567 -4.03755092621,1.72050702572,-4.06840896606 -4.03954648972,1.71450424194,-4.04382276535 -4.04854869843,1.71250331402,-4.02525472641 -4.05855226517,1.71050286293,-4.00867271423 -4.07056093216,1.71350467205,-4.00885868073 -4.07856225967,1.71050357819,-3.99027705193 -4.08756542206,1.70950305462,-3.9736802578 -4.09856987,1.70750296116,-3.95908498764 -4.11257696152,1.70750367641,-3.94650387764 -4.12858581543,1.70950484276,-3.93592119217 -4.14459514618,1.71050608158,-3.92632341385 -4.13758707047,1.70450305939,-3.90653395653 -4.14558887482,1.70150244236,-3.88894248009 -4.14758682251,1.6975004673,-3.86535644531 -4.15659046173,1.69550013542,-3.84876680374 -4.17259931564,1.69650149345,-3.83818626404 -4.18860864639,1.69750285149,-3.82858967781 -4.19160890579,1.69650244713,-3.81879639626 -4.20061254501,1.69450223446,-3.8022081852 -4.21261882782,1.69450283051,-3.78861618042 -4.21861982346,1.69150209427,-3.76903367043 -4.23563051224,1.69350373745,-3.75945138931 -4.2256193161,1.68349981308,-3.72586488724 -4.23962688446,1.68450081348,-3.71427202225 -4.25463724136,1.68750309944,-3.715477705 -4.25463438034,1.68250131607,-3.69089460373 -4.26964330673,1.68350279331,-3.68030023575 -4.28164958954,1.68250346184,-3.66572856903 -4.28064632416,1.67750167847,-3.64113545418 -4.29065132141,1.67650210857,-3.6255531311 -4.31666851044,1.68250584602,-3.62494874001 -4.30465841293,1.67450273037,-3.60216593742 -4.32166910172,1.67650461197,-3.59258365631 -4.33767843246,1.67850637436,-3.58298611641 -4.34167957306,1.67450582981,-3.56240439415 -4.34968328476,1.67250621319,-3.54581284523 -4.37269830704,1.67750918865,-3.54221105576 -4.35868644714,1.66750562191,-3.50663542747 -4.37669849396,1.67150831223,-3.50984048843 -4.39270830154,1.67351007462,-3.50024175644 -4.38770341873,1.66650819778,-3.47167825699 -4.39370679855,1.66450846195,-3.45309710503 -4.42372560501,1.67151272297,-3.45548462868 -4.40471172333,1.65950882435,-3.41690707207 -4.42872714996,1.66451203823,-3.41331481934 -4.43973445892,1.66651344299,-3.41052150726 -4.43573093414,1.65951216221,-3.38394737244 -4.44373559952,1.65851283073,-3.36834478378 -4.4657497406,1.66251587868,-3.36275696754 -4.46274709702,1.65651488304,-3.33718347549 -4.47675561905,1.65851652622,-3.32559227943 -4.48876333237,1.65851795673,-3.31201004982 -4.48976373672,1.65651798248,-3.30220532417 -4.49977016449,1.65551912785,-3.28663277626 -4.51678085327,1.6585214138,-3.27802705765 -4.5037727356,1.64851939678,-3.24545526505 -4.52578687668,1.65252244473,-3.23986291885 -4.54279708862,1.65552449226,-3.23027467728 -4.54179668427,1.65252447128,-3.21848249435 -4.54880142212,1.65152537823,-3.20090818405 -4.56381130219,1.65252745152,-3.19129323959 -4.56581306458,1.64952778816,-3.16972827911 -4.57381868362,1.64852893353,-3.15413236618 -4.58582639694,1.64853060246,-3.14055204391 -4.58282518387,1.64353048801,-3.11696267128 -4.59283208847,1.64553189278,-3.11316871643 -4.61184406281,1.64853441715,-3.10458540916 -4.6038403511,1.64153397083,-3.07701039314 -4.61384725571,1.64153552055,-3.06340551376 -4.6338596344,1.64453828335,-3.05581498146 -4.617852211,1.63453710079,-3.02225756645 -4.64086675644,1.63954019547,-3.01666688919 -4.65587568283,1.64254212379,-3.01685833931 -4.64687204361,1.63554167747,-2.98928046227 -4.66088151932,1.63654386997,-2.97670817375 -4.68189477921,1.64154684544,-2.97010707855 -4.67589378357,1.63554692268,-2.94551491737 -4.67889690399,1.6325480938,-2.92594051361 -4.68990373611,1.63454961777,-2.92313599586 -4.70191240311,1.63555157185,-2.90955710411 -4.70491600037,1.63255286217,-2.89096498489 -4.71792507172,1.63355505466,-2.87837910652 -4.72793197632,1.63355696201,-2.86379528046 -4.72093105316,1.62755739689,-2.83822083473 -4.72993803024,1.62755918503,-2.82362651825 -4.74494695663,1.63056111336,-2.82282805443 -4.74695062637,1.62856245041,-2.80324745178 -4.75595808029,1.62856447697,-2.78865289688 -4.75295877457,1.62356555462,-2.76509475708 -4.7719707489,1.62656831741,-2.75748085976 -4.7869811058,1.62857079506,-2.74589753151 -4.77697944641,1.62157154083,-2.71834039688 -4.77998209,1.62057244778,-2.71053671837 -4.79199123383,1.622574687,-2.69793868065 -4.79499578476,1.61957645416,-2.67935705185 -4.79499912262,1.61657810211,-2.65878200531 -4.81901359558,1.62158131599,-2.65220117569 -4.81801652908,1.617582798,-2.63161635399 -4.82202196121,1.61658477783,-2.61402821541 -4.84003210068,1.62058675289,-2.6142334938 -4.83703422546,1.61658835411,-2.59264850616 -4.84304046631,1.61559045315,-2.57606434822 -4.85705041885,1.61759293079,-2.56446743011 -4.85305213928,1.61259460449,-2.54189586639 -4.87206459045,1.61659765244,-2.53231287003 -4.88007211685,1.61659991741,-2.51771020889 -4.87807321548,1.61360085011,-2.50593662262 -4.8880815506,1.61460340023,-2.49233579636 -4.89708948135,1.61460578442,-2.47774505615 -4.89209127426,1.60960757732,-2.4551692009 -4.89609718323,1.60760986805,-2.43758821487 -4.91410923004,1.61161279678,-2.42799019814 -4.90210676193,1.60561347008,-2.41121816635 -4.91411590576,1.60661625862,-2.39763998985 -4.93112754822,1.60961914062,-2.3870511055 -4.9141254425,1.60062074661,-2.35848331451 -4.9341378212,1.60462379456,-2.34988331795 -4.94214582443,1.60462641716,-2.33430480957 -4.94515132904,1.60362899303,-2.31671714783 -4.95215702057,1.60463035107,-2.31091666222 -4.96216583252,1.60463309288,-2.29633784294 -4.95116615295,1.5986353159,-2.27175855637 -4.9611749649,1.59963798523,-2.25815916061 -4.97618579865,1.60164117813,-2.24558877945 -4.97419023514,1.59764361382,-2.22599768639 -4.98519992828,1.59964644909,-2.21240782738 -4.99020385742,1.5996478796,-2.20560789108 -4.98320674896,1.59465062618,-2.182056427 -4.99421644211,1.59565365314,-2.16846680641 -5.00722646713,1.59765660763,-2.15587472916 -5.01123332977,1.59665942192,-2.13928127289 -5.0202422142,1.59666240215,-2.12469339371 -5.02424907684,1.59566533566,-2.10712242126 -5.01224803925,1.59066665173,-2.09233546257 -5.02825927734,1.59366977215,-2.08074879646 -5.03626775742,1.59367287159,-2.06517338753 -5.03227233887,1.5896756649,-2.04557442665 -5.04328203201,1.59067893028,-2.03100562096 -5.06129407883,1.59468209743,-2.02041220665 -5.0452914238,1.58768343925,-2.00461792946 -5.05430030823,1.58868658543,-1.99003076553 -5.07531356812,1.59368991852,-1.98044073582 -5.06131505966,1.58669304848,-1.95586752892 -5.07232522964,1.58769631386,-1.94129824638 -5.08633613586,1.58969950676,-1.92871022224 -5.07533884048,1.58370280266,-1.90612494946 -5.08534526825,1.58670449257,-1.90132319927 -5.09735536575,1.58770763874,-1.88773930073 -5.08335733414,1.58071124554,-1.86317682266 -5.09536790848,1.58271455765,-1.84959304333 -5.11638069153,1.58771777153,-1.83999478817 -5.10138320923,1.58072137833,-1.81542897224 -5.10739183426,1.5807248354,-1.79983925819 -5.13040208817,1.58672630787,-1.80003023148 -5.12240600586,1.58173000813,-1.77845907211 -5.13241624832,1.58373343945,-1.76387858391 -5.14842748642,1.58673667908,-1.75227880478 -5.13443040848,1.57974052429,-1.72870838642 -5.14043903351,1.57974398136,-1.71311879158 -5.15945196152,1.58374750614,-1.70154106617 -5.13944959641,1.57674956322,-1.68574678898 -5.14145755768,1.57475328445,-1.66817271709 -5.17147350311,1.58275663853,-1.66058707237 -5.15547609329,1.57576072216,-1.63701117039 -5.17448806763,1.57976388931,-1.62640702724 -5.18149757385,1.58076763153,-1.61082470417 -5.16849803925,1.57476997375,-1.597047925 -5.169506073,1.57377398014,-1.57946825027 -5.20152139664,1.58177697659,-1.57286429405 -5.17652273178,1.57178151608,-1.54630184174 -5.18753290176,1.57378518581,-1.5327038765 -5.19854402542,1.57578897476,-1.51812815666 -5.18854904175,1.57079350948,-1.49656498432 -5.19655513763,1.57179510593,-1.49076044559 -5.21256685257,1.57579863071,-1.47817242146 -5.19457006454,1.56780338287,-1.45460379124 -5.2125825882,1.57180678844,-1.44300591946 -5.22559356689,1.57481050491,-1.42941844463 -5.20159578323,1.56481575966,-1.4038618803 -5.22260904312,1.57081913948,-1.39325797558 -5.2216129303,1.56882143021,-1.38348448277 -5.22562217712,1.56882572174,-1.36690711975 -5.23563241959,1.57082927227,-1.35329854488 -5.23564147949,1.56883394718,-1.33474254608 -5.21964550018,1.56183874607,-1.31315696239 -5.24866104126,1.56984198093,-1.30357325077 -5.25567102432,1.57084619999,-1.28799104691 -5.24367237091,1.56584882736,-1.27619934082 -5.25868368149,1.56885242462,-1.26359593868 -5.26569366455,1.56985652447,-1.24801361561 -5.25570058823,1.56486165524,-1.22744846344 -5.25870943069,1.56486606598,-1.2108669281 -5.27572202682,1.56886970997,-1.19827198982 -5.26672458649,1.56487262249,-1.18650364876 -5.27373456955,1.56587696075,-1.17092144489 -5.29274702072,1.57088029385,-1.15931129456 -5.27475214005,1.56388616562,-1.13675546646 -5.28876399994,1.56588995457,-1.12316405773 -5.30177545547,1.56889379025,-1.10956561565 -5.28978204727,1.56389939785,-1.08899962902 -5.28978681564,1.56390178204,-1.08021318913 -5.30279827118,1.56590557098,-1.06661403179 -5.30180740356,1.56491041183,-1.04903662205 -5.30181646347,1.5639154911,-1.03146505356 -5.31482839584,1.56591951847,-1.01688754559 -5.30983638763,1.56392455101,-0.999291777611 -5.29883909225,1.55892789364,-0.987525224686 -5.31385087967,1.56293177605,-0.973932087421 -5.31186008453,1.5609369278,-0.956353247166 -5.31587028503,1.56094169617,-0.939779102802 -5.32888174057,1.56394565105,-0.926173985004 -5.30988836288,1.55695199966,-0.904615700245 -5.33590221405,1.56395530701,-0.893019616604 -5.32990598679,1.56195819378,-0.883232951164 -5.32291460037,1.55796384811,-0.864659428596 -5.33192539215,1.55996835232,-0.849082767963 -5.34593725204,1.56397235394,-0.835477888584 -5.32894468307,1.55697870255,-0.81491369009 -5.34195661545,1.55998289585,-0.80032813549 -5.34896707535,1.56098759174,-0.784741580486 -5.34297132492,1.55899083614,-0.774959206581 -5.34798192978,1.55899548531,-0.759365022182 -5.36599445343,1.56399953365,-0.744794726372 -5.35200214386,1.5590057373,-0.726201415062 -5.35501289368,1.5590108633,-0.709623634815 -5.35802316666,1.5590159893,-0.693045794964 -5.35503339767,1.55702149868,-0.675471484661 -5.37003993988,1.5610229969,-0.669668376446 -5.37105035782,1.56102824211,-0.653083086014 -5.3560590744,1.55503499508,-0.633518874645 -5.3610701561,1.55604016781,-0.616948187351 -5.36608028412,1.55604505539,-0.601353168488 -5.35908985138,1.55305111408,-0.583769619465 -5.3670964241,1.55605328083,-0.575988411903 -5.38110876083,1.55905759335,-0.561394929886 -5.36511707306,1.55306458473,-0.541835665703 -5.37712907791,1.55606901646,-0.527235090733 -5.38114023209,1.55707418919,-0.510660111904 -5.35714769363,1.54908192158,-0.491084396839 -5.37816095352,1.55508577824,-0.47650578618 -5.38116693497,1.55508828163,-0.468708902597 -5.38517808914,1.55609369278,-0.452133774757 -5.37618780136,1.55210018158,-0.434552282095 -5.38519906998,1.55510497093,-0.418964415789 -5.39721155167,1.55810964108,-0.403382450342 -5.4042224884,1.55911457539,-0.387788385153 -5.38423204422,1.55212247372,-0.368235528469 -5.37923669815,1.55112588406,-0.359445720911 -5.37924766541,1.55013167858,-0.34286314249 -5.40326166153,1.55713522434,-0.328276753426 -5.40127229691,1.55614113808,-0.311689168215 -5.39728307724,1.55414748192,-0.294123262167 -5.3992934227,1.55415296555,-0.278519034386 -5.39530515671,1.5521594286,-0.260954409838 -5.39331054688,1.55216276646,-0.252172112465 -5.39732170105,1.55216801167,-0.236571490765 -5.38533163071,1.54817533493,-0.218997091055 -5.39434432983,1.55118060112,-0.202427625656 -5.40535593033,1.55318534374,-0.186835318804 -5.39436721802,1.55019259453,-0.169264674187 -5.39537239075,1.55019533634,-0.161462903023 -5.41038560867,1.55420005322,-0.144897416234 -5.38839530945,1.54720842838,-0.127318486571 -5.40440797806,1.55221271515,-0.11172773689 -5.40942001343,1.55321848392,-0.0951504558325 -5.40043020248,1.55022537708,-0.0785621255636 -5.39244174957,1.54723262787,-0.0610006973147 -5.41344881058,1.55323326588,-0.0541869625449 -5.41446065903,1.55323934555,-0.0376059189439 -5.39847135544,1.54824745655,-0.020041314885 -5.42548465729,1.55625069141,-0.00444721663371 -5.4014954567,1.54925966263,0.0131182456389 -5.39850711823,1.54826629162,0.0296993069351 -5.41251993179,1.5522711277,0.0462768562138 -5.40252542496,1.54927551746,0.0550563633442 -5.39353656769,1.54628288746,0.0716369897127 -5.42054986954,1.5542858839,0.0872415751219 -5.38655996323,1.54329645634,0.10479490459 -5.41057395935,1.55130016804,0.121378049254 -5.40258550644,1.54830753803,0.137956470251 -5.39759731293,1.54631459713,0.154534637928 -5.39760303497,1.54631757736,0.16233676672 -5.40861606598,1.55032277107,0.178921297193 -5.39762735367,1.54633057117,0.195495784283 -5.40164041519,1.5483366251,0.212077870965 -5.40365219116,1.54834282398,0.22865884006 -5.39766454697,1.54635024071,0.245234280825 -5.39767122269,1.54635369778,0.254011690617 -5.42368412018,1.55535686016,0.270613878965 -5.37769460678,1.54036915302,0.28617683053 -5.40070819855,1.54837310314,0.303753733635 -5.39872074127,1.54737997055,0.320331305265 -5.39573335648,1.54638707638,0.336907565594 -5.39374494553,1.54639363289,0.352509588003 -5.41275262833,1.55239486694,0.3622867167 -5.39476490021,1.54640376568,0.377867847681 -5.38477706909,1.54341197014,0.394433230162 -5.39178991318,1.54641771317,0.411023110151 -5.38580274582,1.5444252491,0.427593231201 -5.39481544495,1.54743075371,0.444187641144 -5.38582849503,1.54543888569,0.460752308369 -5.37983465195,1.54344308376,0.468543708324 -5.37884759903,1.54345011711,0.485121160746 -5.40486049652,1.55145323277,0.502725958824 -5.37487316132,1.54246401787,0.517296552658 -5.37988615036,1.54447042942,0.534861624241 -5.39589929581,1.54947519302,0.552451372147 -5.38191223145,1.54548406601,0.568026006222 -5.35991859436,1.53949046135,0.574803292751 -5.38393211365,1.54649436474,0.593388974667 -5.36494493484,1.54150366783,0.60797315836 -5.36195802689,1.54051113129,0.624545097351 -5.38597106934,1.54851484299,0.643137335777 -5.35698413849,1.54052567482,0.656716048717 -5.36599111557,1.5435281992,0.666493058205 -5.36900424957,1.54453468323,0.683081746101 -5.36901760101,1.54554176331,0.699662744999 -5.36003065109,1.54254996777,0.715242028236 -5.36404466629,1.54455673695,0.732810199261 -5.35105752945,1.54056549072,0.747400641441 -5.36007070541,1.54457128048,0.764985144138 -5.35607767105,1.54357540607,0.772775411606 -5.36109113693,1.54558205605,0.790348529816 -5.34610462189,1.54159128666,0.804929614067 -5.34211921692,1.54059922695,0.821497023106 -5.35413265228,1.54560482502,0.840071260929 -5.34214639664,1.54261350632,0.85466003418 -5.34315299988,1.54261720181,0.863442063332 -5.32216644287,1.53662741184,0.877020359039 -5.33718013763,1.54263246059,0.895608723164 -5.32319450378,1.53864169121,0.910186290741 -5.34220790863,1.54564630985,0.929768800735 -5.34122133255,1.54565382004,0.946348130703 -5.32423591614,1.54066383839,0.960911631584 -5.3322429657,1.54366648197,0.970699131489 -5.32925653458,1.54367399216,0.986294746399 -5.31927108765,1.54168307781,1.00186049938 -5.307284832,1.53869211674,1.01644086838 -5.31829881668,1.54269790649,1.03502333164 -5.30631303787,1.53970694542,1.04960250854 -5.30932712555,1.54171419144,1.06717550755 -5.31533336639,1.54371678829,1.07598292828 -5.3033490181,1.54072642326,1.09153616428 -5.28836297989,1.53773593903,1.10512292385 -5.28637742996,1.53774380684,1.12169706821 -5.28439235687,1.53875184059,1.13827157021 -5.29840564728,1.54375731945,1.15785253048 -5.28641319275,1.53976273537,1.16364598274 -5.29042720795,1.54276967049,1.18122756481 -5.27744245529,1.53977930546,1.19579529762 -5.28245592117,1.54178619385,1.21338272095 -5.28247022629,1.54279363155,1.22996914387 -5.25848674774,1.5368052721,1.24252414703 -5.26149988174,1.53881204128,1.25912630558 -5.25750780106,1.53781652451,1.26690948009 -5.25052309036,1.53682553768,1.28248119354 -5.27653551102,1.54582905769,1.30506920815 -5.25255155563,1.53984045982,1.31664180756 -5.27356481552,1.54684495926,1.33823025227 -5.23958206177,1.53785812855,1.3477897644 -5.24359560013,1.53986513615,1.36537706852 -5.24560308456,1.54086863995,1.37417137623 -5.24761772156,1.54287612438,1.39174854755 -5.2346329689,1.53988587856,1.40533101559 -5.23064804077,1.53989458084,1.42189574242 -5.23566198349,1.54290127754,1.43949306011 -5.23367738724,1.54390954971,1.45607125759 -5.22769260406,1.54291832447,1.47164809704 -5.24769878387,1.54991900921,1.48544096947 -5.28971099854,1.56492042542,1.51402175426 -4.64042758942,1.57689881325,3.07738089561 -4.61045026779,1.56991362572,3.07795810699 -4.60746860504,1.57192349434,3.0965282917 -4.6284737587,1.58092415333,3.12032222748 -4.61754608154,1.59196281433,3.19463944435 -4.60556459427,1.58997392654,3.20623493195 -4.56658935547,1.5799908638,3.20079731941 -4.54660177231,1.5739992857,3.19757962227 -4.55561828613,1.58100688457,3.22416329384 -4.51764249802,1.57002341747,3.2187306881 -4.50466251373,1.56903517246,3.23030638695 -4.4996805191,1.5710452795,3.24689483643 -4.46970415115,1.56306028366,3.24646663666 -4.47771120071,1.56806337833,3.26226139069 -4.48172807693,1.57307183743,3.28584051132 -4.46174955368,1.57008504868,3.29241394997 -4.44877004623,1.56809699535,3.30398774147 -4.45178747177,1.57310557365,3.32657647133 -4.42481040955,1.56712019444,3.32814311981 -4.41882944107,1.56813073158,3.3447201252 -4.42283773422,1.5721347332,3.35850358009 -4.40385866165,1.5681476593,3.36508607864 -4.39687776566,1.57015824318,3.38066935539 -4.3968963623,1.57416784763,3.40224003792 -4.37591838837,1.57018136978,3.40781021118 -4.35993909836,1.56719374657,3.41639518738 -4.37095499039,1.57620096207,3.44597911835 -4.34396886826,1.5672107935,3.43576574326 -4.34198760986,1.57022058964,3.45534873009 -4.34200572968,1.57422995567,3.47692513466 -4.31302928925,1.56724500656,3.47550296783 -4.30104923248,1.56725656986,3.48708844185 -4.30506706238,1.57326567173,3.51265215874 -4.28308916092,1.56827926636,3.51623678207 -4.27710008621,1.56828546524,3.52301049232 -4.28011751175,1.57329416275,3.54660058022 -4.26013994217,1.57030749321,3.55217623711 -4.25115966797,1.57031881809,3.5667514801 -4.24717903137,1.57332909107,3.58533072472 -4.22620105743,1.56934273243,3.58990645409 -4.22720956802,1.57134687901,3.60071563721 -4.2202296257,1.57335793972,3.61728668213 -4.20225095749,1.57037079334,3.62387037277 -4.20127010345,1.57438063622,3.64544487 -4.19928836823,1.5783905983,3.66602373123 -4.16631317139,1.56940639019,3.65960621834 -4.15933322906,1.57141757011,3.67617917061 -4.16634130478,1.57642114162,3.69396018982 -4.15536212921,1.57643270493,3.70654416084 -4.13238525391,1.5714468956,3.70911622047 -4.14140176773,1.58045470715,3.73969626427 -4.12542390823,1.57846748829,3.74827218056 -4.11244535446,1.57747983932,3.75984215736 -4.09946632385,1.57749176025,3.77042984962 -4.09147691727,1.57649803162,3.77422595024 -4.08549642563,1.57850885391,3.79180264473 -4.07851648331,1.58051979542,3.80838179588 -4.0565404892,1.57653415203,3.81194519997 -4.0505604744,1.57854497433,3.8295238018 -4.0435795784,1.5805555582,3.84512209892 -4.02160358429,1.57657003403,3.84868264198 -4.0256114006,1.58057367802,3.86348390579 -4.0196313858,1.58258450031,3.88106560707 -4.00165462494,1.58059823513,3.88862133026 -3.98567652702,1.57861089706,3.89621019363 -3.9886944294,1.58461999893,3.92278885841 -3.960719347,1.57763516903,3.91936469078 -3.9647269249,1.58163893223,3.93417167664 -3.96074724197,1.58564960957,3.95473957062 -3.94277024269,1.58366310596,3.96131062508 -3.93479037285,1.58467423916,3.97689771652 -3.92381215096,1.58568632603,3.99046802521 -3.90283489227,1.58170008659,3.9930536747 -3.90284490585,1.58470523357,4.00583171844 -3.89186644554,1.58471739292,4.01940250397 -3.88088750839,1.58572900295,4.03199052811 -3.86790895462,1.58474123478,4.04257726669 -3.85493087769,1.58475375175,4.05414772034 -3.83995270729,1.58376634121,4.06273317337 -3.8279747963,1.58377861977,4.07530355453 -3.82898449898,1.58778345585,4.08908748627 -3.81400632858,1.58679616451,4.0976729393 -3.80402779579,1.58780789375,4.1122469902 -3.79804801941,1.5908190012,4.13082647324 -3.77407193184,1.58483338356,4.12941503525 -3.76809239388,1.58784425259,4.14799594879 -3.75511455536,1.58785688877,4.15956687927 -3.74512648582,1.58686387539,4.16135454178 -3.74114632607,1.59087431431,4.18194150925 -3.72916817665,1.59088659286,4.19451475143 -3.71519088745,1.59089946747,4.20508432388 -3.69721436501,1.58791291714,4.21066141129 -3.68523645401,1.58892536163,4.22323513031 -3.66625928879,1.58593869209,4.22682476044 -3.66227006912,1.58694458008,4.23560762405 -3.65729022026,1.59095513821,4.25519800186 -3.6403131485,1.5889685154,4.26177549362 -3.62333631516,1.58698189259,4.26835250854 -3.62035608292,1.59199225903,4.29093551636 -3.61537742615,1.59600353241,4.31249952316 -3.60139036179,1.59301126003,4.3092880249 -3.58641219139,1.59102368355,4.31688547134 -3.57143545151,1.59103691578,4.32645177841 -3.55345869064,1.58805024624,4.33103895187 -3.53548169136,1.58606362343,4.33562517166 -3.52750396729,1.58907568455,4.35418319702 -3.5205245018,1.59208667278,4.37177658081 -3.51653528214,1.59309244156,4.3805642128 -3.48856091499,1.58610796928,4.37314319611 -3.48558115959,1.59111857414,4.39672279358 -3.47560334206,1.59313070774,4.41229248047 -3.45262813568,1.58814525604,4.4108710289 -3.44764852524,1.59315598011,4.43146181107 -3.43367171288,1.59316897392,4.44203186035 -3.42168450356,1.59017646313,4.44081735611 -3.41770482063,1.59518718719,4.46340036392 -3.41472482681,1.60019755363,4.48699092865 -3.40374779701,1.60221028328,4.50254678726 -3.382771492,1.59822392464,4.5021443367 -3.36579561234,1.59723758698,4.50871562958 -3.36080574989,1.59724330902,4.51551818848 -3.34782862663,1.59825587273,4.52709436417 -3.33785152435,1.60026848316,4.54365730286 -3.3148765564,1.59528291225,4.54123973846 -3.31289625168,1.60129308701,4.56683063507 -3.30191874504,1.60330533981,4.58140563965 -3.28394341469,1.60131943226,4.58697032928 -3.2769548893,1.60132575035,4.5917634964 -3.27097558975,1.60633671284,4.61235284805 -3.2530002594,1.60435068607,4.61791753769 -3.24002242088,1.60436308384,4.628510952 -3.22804570198,1.60637569427,4.64208221436 -3.21306824684,1.60538840294,4.64967775345 -3.19709253311,1.60440206528,4.65823984146 -3.19310331345,1.60640764236,4.66703796387 -3.17312860489,1.60342216492,4.66960191727 -3.16015100479,1.6044344902,4.68019533157 -3.15417265892,1.6084458828,4.70276784897 -3.13419747353,1.60646009445,4.70434379578 -3.12921881676,1.61147117615,4.7279253006 -3.12822842598,1.61447632313,4.74172019958 -3.1062541008,1.61049091816,4.74029541016 -3.08028006554,1.60450613499,4.73188018799 -3.06630373001,1.6045191288,4.74245500565 -3.04133009911,1.59853434563,4.73602962494 -3.0243537426,1.59754765034,4.7406206131 -3.01837563515,1.60255920887,4.76418876648 -3.00738787651,1.60056614876,4.76199102402 -2.99141216278,1.59957969189,4.76956319809 -2.97843527794,1.6005923748,4.78114557266 -2.93346643448,1.58261156082,4.74172258377 -2.93248677254,1.59062182903,4.77230644226 -2.93650579453,1.60163116455,4.81188344955 -2.92052006721,1.5976395607,4.80266857147 -2.89154672623,1.58865511417,4.7872595787 -2.89456582069,1.59866452217,4.82484674454 -2.87459111214,1.59567892551,4.82542181015 -2.83062338829,1.57869827747,4.78697919846 -2.81964612007,1.58171057701,4.80156326294 -2.81366801262,1.58672189713,4.82514333725 -2.82267522812,1.59672498703,4.85694026947 -2.83169317245,1.61173331738,4.90652418137 -2.81271839142,1.6087474823,4.90909528732 -2.83673262596,1.63375282288,4.9856801033 -2.84974908829,1.6507601738,5.04327201843 -2.86376643181,1.66976797581,5.10583543777 -2.86078763008,1.67877876759,5.13741445541 -2.88179206848,1.69677960873,5.19320964813 -2.8468208313,1.68479657173,5.16679906845 -2.84284257889,1.69280791283,5.19836616516 -2.83086562157,1.69482028484,5.21395111084 -2.81189084053,1.69283437729,5.21752738953 -2.80191349983,1.69784653187,5.23711109161 -2.78493857384,1.69686019421,5.24468421936 -2.76995158195,1.69186794758,5.23448991776 -2.75997471809,1.69588029385,5.25506496429 -2.74899816513,1.69989275932,5.27364301682 -2.73102378845,1.6989068985,5.28020715714 -2.71804738045,1.70191967487,5.2947883606 -2.70107197762,1.700933218,5.30137300491 -2.69008493423,1.69894051552,5.30016088486 -2.67310976982,1.69895410538,5.3067445755 -2.66013336182,1.70096683502,5.32132768631 -2.63815951347,1.6979817152,5.31890153885 -2.62318444252,1.69899499416,5.33047533035 -2.6192047596,1.70700562,5.36207389832 -2.59423184395,1.70102071762,5.35265445709 -2.59024357796,1.70502698421,5.36643505096 -2.57426786423,1.70504021645,5.37502002716 -2.55529356003,1.7030544281,5.37859296799 -2.53631877899,1.70206844807,5.3811750412 -2.52534222603,1.70608079433,5.40075683594 -2.50436806679,1.70309531689,5.39933633804 -2.49737977982,1.70310163498,5.40513515472 -2.48640394211,1.7081143856,5.42670106888 -2.4704284668,1.70912754536,5.43528795242 -2.44845533371,1.70514261723,5.43285417557 -2.4334795475,1.70615553856,5.4434428215 -2.41250562668,1.70317018032,5.44201850891 -2.39853000641,1.7061830759,5.45560121536 -2.39054203033,1.70618963242,5.45939874649 -2.3715672493,1.70420348644,5.4609875679 -2.35959124565,1.70821642876,5.48055887222 -2.34761548042,1.71222913265,5.50013256073 -2.33863782883,1.71824097633,5.52472639084 -2.32766199112,1.72425353527,5.54729890823 -2.31668543816,1.72926616669,5.56987380981 -2.31369614601,1.73327159882,5.58567476273 -2.30072021484,1.73728442192,5.60325527191 -2.29274368286,1.74529671669,5.63482236862 -2.27876830101,1.74830973148,5.65040254593 -2.26479148865,1.75032234192,5.66400051117 -2.25581526756,1.75833463669,5.69357204437 -2.22784328461,1.74935054779,5.67415237427 -2.21885609627,1.74935746193,5.67694330215 -2.20488119125,1.75337076187,5.69451189041 -2.18890547752,1.75438392162,5.70410442352 -2.16793179512,1.75139820576,5.70168781281 -2.15195655823,1.75241148472,5.71227264404 -2.13098359108,1.75042617321,5.71084737778 -2.11899733543,1.74743378162,5.70662975311 -2.0940246582,1.74144899845,5.69321107864 -2.0720512867,1.73746347427,5.68679904938 -2.05607652664,1.73847699165,5.69837474823 -2.03810191154,1.73849070072,5.70296192169 -2.01812839508,1.73650515079,5.70353603363 -2.00215315819,1.73751819134,5.7131280899 -1.99316596985,1.73752510548,5.71591711044 -1.97319257259,1.73553955555,5.71649074554 -1.95521831512,1.73555350304,5.7220697403 -1.93624413013,1.73456728458,5.72365570068 -1.92126893997,1.73758041859,5.73724126816 -1.8992960453,1.73359525204,5.73181343079 -1.88232147694,1.73460876942,5.7393989563 -1.87033462524,1.73061597347,5.73120117188 -1.85735929012,1.73562896252,5.75277519226 -1.83438682556,1.73164403439,5.74335002899 -1.81441307068,1.7286580801,5.74193286896 -1.79543912411,1.72767198086,5.74351549149 -1.78146314621,1.73168480396,5.75911188126 -1.77047681808,1.72969210148,5.75589799881 -1.75150287151,1.72870612144,5.75748062134 -1.73652780056,1.73171925545,5.77206420898 -1.72155356407,1.73573279381,5.78963088989 -1.69758105278,1.72874772549,5.77421426773 -1.67760694027,1.72576165199,5.77080488205 -1.66063296795,1.72777533531,5.78037977219 -1.65164554119,1.72778201103,5.78118085861 -1.63267171383,1.72579598427,5.78276109695 -1.61669743061,1.72880971432,5.79633426666 -1.59572422504,1.72582387924,5.78991985321 -1.57874977589,1.72683751583,5.79850101471 -1.56077563763,1.7268512249,5.80308532715 -1.53980278969,1.72386562824,5.79766178131 -1.53281450272,1.72587180138,5.80546522141 -1.5138412714,1.72488594055,5.80803918839 -1.49686658382,1.72589933872,5.81562757492 -1.47589361668,1.72291374207,5.80920743942 -1.45791959763,1.72292745113,5.81379079819 -1.44094538689,1.72494101524,5.82336902618 -1.42995941639,1.72294855118,5.81915235519 -1.40998625755,1.7199627161,5.81672906876 -1.39601099491,1.72597563267,5.83731603622 -1.37403786182,1.71998989582,5.82390594482 -1.35606384277,1.72000360489,5.82848882675 -1.33409130573,1.71601831913,5.81706523895 -1.32211577892,1.72503089905,5.84864521027 -1.30912923813,1.71803820133,5.83045053482 -1.29215538502,1.72005176544,5.84102630615 -1.27318203449,1.72006583214,5.8426027298 -1.25420820713,1.71807956696,5.84119272232 -1.23323464394,1.71309363842,5.82978439331 -1.21726095676,1.71810734272,5.84735155106 -1.20228564739,1.72212016582,5.86394691467 -1.18730008602,1.7131279707,5.83574390411 -1.17132616043,1.71714150906,5.85231781006 -1.15035331249,1.71315574646,5.84289598465 -1.12938046455,1.70917010307,5.83247709274 -1.11540555954,1.71618306637,5.85805892944 -1.09343314171,1.71019744873,5.84263706207 -1.07445919514,1.70821118355,5.8402261734 -1.06947112083,1.7152172327,5.86401939392 -1.04649865627,1.70723176003,5.84060335159 -1.02852523327,1.70824563503,5.84717798233 -1.01055145264,1.70925927162,5.85176134109 -0.992576539516,1.70727229118,5.85036659241 -0.973603248596,1.70628631115,5.84994602203 -0.968615472317,1.71529233456,5.87773275375 -0.944643497467,1.70430719852,5.8463139534 -0.928668916225,1.70832026005,5.86190223694 -0.909695863724,1.70733428001,5.86247777939 -0.892721831799,1.71034765244,5.87406015396 -0.870748639107,1.70236170292,5.84865522385 -0.854774415493,1.70737493038,5.8672375679 -0.84178930521,1.70038282871,5.84601593018 -0.824814975262,1.70239603519,5.85560512543 -0.807841300964,1.70640957355,5.86918306351 -0.788867413998,1.70342314243,5.86377573013 -0.768894970417,1.7014374733,5.8583445549 -0.752920150757,1.70645034313,5.87493896484 -0.742933750153,1.70445740223,5.87072753906 -0.723959743977,1.7014708519,5.86332321167 -0.70698672533,1.70748460293,5.88388729095 -0.687012851238,1.70149815083,5.86648607254 -0.670039176941,1.70651161671,5.88306283951 -0.650066494942,1.70252561569,5.87363958359 -0.632092773914,1.70353925228,5.87922239304 -0.622105956078,1.70054602623,5.87002038956 -0.605131804943,1.70455932617,5.88360786438 -0.584159255028,1.69757342339,5.86218547821 -0.568185210228,1.70558655262,5.88976573944 -0.549211323261,1.70260000229,5.88036060333 -0.530238330364,1.70161390305,5.87893724442 -0.511264324188,1.69762718678,5.86753320694 -0.503277778625,1.70363402367,5.88831329346 -0.484303504229,1.69864726067,5.87291622162 -0.465330272913,1.69666099548,5.86849689484 -0.447357207537,1.70067465305,5.88107013702 -0.429383009672,1.70068776608,5.88166570663 -0.410410106182,1.69970166683,5.88024044037 -0.391436964273,1.69771528244,5.87582063675 -0.382449328899,1.69572162628,5.86862850189 -0.364476144314,1.69973528385,5.88220453262 -0.346502512693,1.70274853706,5.89078807831 -0.326529711485,1.69476258755,5.86836767197 -0.309555143118,1.69977545738,5.88496446609 -0.290582597256,1.70078933239,5.88853406906 -0.280596196651,1.69679629803,5.87532329559 -0.262621998787,1.69680929184,5.87391996384 -0.244648590684,1.70082271099,5.88949966431 -0.225675106049,1.69583618641,5.87308740616 -0.207701131701,1.69684946537,5.87667942047 -0.188728436828,1.69686317444,5.87725114822 -0.169755369425,1.69387686253,5.86583089828 -0.160768300295,1.69388341904,5.86562824249 -0.142794817686,1.69989681244,5.88721036911 -0.123821601272,1.69391024113,5.86779260635 -0.105847664177,1.69692337513,5.87538433075 -0.0878740549088,1.7059366703,5.90596866608 -0.0689007863402,1.69495022297,5.87155246735 -0.0599137730896,1.69695675373,5.87534952164 -0.0419395752251,1.69396960735,5.86694574356 -0.0229668878019,1.69198346138,5.86151838303 -0.00499281799421,1.69799637794,5.87811231613 --0.0129809407517,1.71000957489,5.72469997406 --0.0299559496343,1.70702207088,5.71330690384 --0.0479295887053,1.70903527737,5.71989202499 --0.0669018700719,1.71304917336,5.73045635223 --0.0838768407702,1.71006166935,5.7220621109 --0.0928634405136,1.7070684433,5.7108502388 --0.110837124288,1.70908153057,5.71543693542 --0.128810867667,1.71009469032,5.72102451324 --0.146784260869,1.70810782909,5.71260499954 --0.164757966995,1.70912098885,5.71519136429 --0.182731688023,1.7101341486,5.71777915955 --0.200705230236,1.71014738083,5.71536254883 --0.209692001343,1.71015393734,5.71415424347 --0.227665156126,1.7071672678,5.70373058319 --0.245638564229,1.7061804533,5.69931125641 --0.263612896204,1.71019327641,5.71291065216 --0.281586170197,1.70920646191,5.70548820496 --0.298560142517,1.70321929455,5.68707513809 --0.308546513319,1.70922613144,5.70386552811 --0.325521171093,1.70723879337,5.69646501541 --0.344493687153,1.70925235748,5.70103406906 --0.362467288971,1.7092654705,5.69961881638 --0.379441529512,1.70627808571,5.68821048737 --0.397415399551,1.70729112625,5.69080066681 --0.415389239788,1.70830392838,5.69238996506 --0.423376321793,1.70431029797,5.67818212509 --0.442349374294,1.70732367039,5.68776226044 --0.460323154926,1.70833647251,5.68835020065 --0.47729703784,1.70434939861,5.67493438721 --0.496270269156,1.70836257935,5.68451786041 --0.51324480772,1.7073751688,5.67811489105 --0.531217753887,1.70538842678,5.6706867218 --0.540204703808,1.7063947916,5.67148208618 --0.559177875519,1.70940804482,5.679063797 --0.577151417732,1.70942103863,5.67664670944 --0.593125760555,1.70343351364,5.65723466873 --0.612100124359,1.70944619179,5.67384052277 --0.63107329607,1.71245932579,5.67942047119 --0.647047460079,1.70647192001,5.6600060463 --0.65703356266,1.70847868919,5.6647901535 --0.674007773399,1.70649135113,5.65637969971 --0.693981230259,1.71350443363,5.67397260666 --0.710954964161,1.71051716805,5.66255331039 --0.728929281235,1.71252977848,5.66515207291 --0.74790251255,1.71454274654,5.66973352432 --0.758888244629,1.7185498476,5.68051719666 --0.774863302708,1.71556198597,5.66811704636 --0.793836951256,1.71857488155,5.67470741272 --0.811809778214,1.71758794785,5.66727685928 --0.830783545971,1.72060072422,5.67386960983 --0.848757445812,1.72061347961,5.67245912552 --0.864731431007,1.71562600136,5.65503931046 --0.87471807003,1.71863257885,5.6608338356 --0.893691241741,1.72064554691,5.66341495514 --0.912665784359,1.72465789318,5.67302179337 --0.928639113903,1.71867084503,5.65258789062 --0.947613537312,1.7226831913,5.66119384766 --0.966586709023,1.72469615936,5.66277360916 --0.982561051846,1.72070848942,5.64835977554 --0.992547512054,1.72271502018,5.65215063095 --1.01352071762,1.72872805595,5.66774320602 --1.02949523926,1.72574031353,5.65433216095 --1.04746890068,1.72575294971,5.65091705322 --1.06844186783,1.7317661047,5.6635017395 --1.08441591263,1.72777843475,5.64908456802 --1.10238993168,1.72879099846,5.64667415619 --1.11637628078,1.73779773712,5.67448425293 --1.13234996796,1.7338103056,5.65805864334 --1.15332329273,1.73882317543,5.67065095901 --1.17029726505,1.73783564568,5.66123342514 --1.18827188015,1.73884785175,5.66083526611 --1.20624542236,1.73886036873,5.65641832352 --1.2162321806,1.74086678028,5.65921115875 --1.23320555687,1.73787951469,5.64778375626 --1.25417876244,1.74289238453,5.65837335587 --1.2711533308,1.74290442467,5.65197038651 --1.28712713718,1.73891699314,5.63654327393 --1.3081009388,1.74392950535,5.64914703369 --1.32807433605,1.74694228172,5.65373420715 --1.33606112003,1.74594843388,5.64551782608 --1.35603451729,1.74896121025,5.65010643005 --1.37300872803,1.74697351456,5.64169216156 --1.39098370075,1.74898540974,5.64129924774 --1.40995693207,1.74999797344,5.63987970352 --1.42993068695,1.7530105114,5.64447212219 --1.44390559196,1.74802231789,5.62405729294 --1.44989299774,1.74402821064,5.60884284973 --1.47486555576,1.7530413866,5.63343954086 --1.49883770943,1.76105463505,5.65102338791 --1.51081383228,1.75406587124,5.62562036514 --1.52878701687,1.75307846069,5.61819028854 --1.54876124859,1.75709068775,5.62379407883 --1.55974769592,1.76009702682,5.62858724594 --1.57872128487,1.76110959053,5.62717294693 --1.5986944437,1.76312220097,5.62875556946 --1.61466956139,1.76113390923,5.61835241318 --1.63364303112,1.76314640045,5.6159324646 --1.6466190815,1.75815761089,5.59552955627 --1.66759157181,1.76117050648,5.59910535812 --1.68357658386,1.76917767525,5.61989736557 --1.69955170155,1.76718938351,5.60949325562 --1.7155264616,1.76520121098,5.59808254242 --1.73749959469,1.77021384239,5.6066737175 --1.75147473812,1.76622521877,5.58825826645 --1.77544701099,1.77223837376,5.60184383392 --1.79342150688,1.77325022221,5.59743690491 --1.8014087677,1.77225625515,5.59122800827 --1.82038319111,1.77426815033,5.59082746506 --1.83835697174,1.77428030968,5.5844078064 --1.85733163357,1.77529227734,5.5840086937 --1.8763051033,1.77730453014,5.58058977127 --1.8982783556,1.78131699562,5.58717918396 --1.91425323486,1.77932870388,5.57576704025 --1.92423987389,1.78033494949,5.57555866241 --1.94821310043,1.78734743595,5.58915996552 --1.96318852901,1.78535878658,5.57575464249 --1.97916305065,1.78337049484,5.56333494186 --1.99913704395,1.78538262844,5.56392860413 --2.01911044121,1.78739500046,5.56250715256 --2.02609777451,1.78540074825,5.55329561234 --2.04807162285,1.7894128561,5.5598950386 --2.06104755402,1.78642380238,5.54149055481 --2.08202123642,1.7894359827,5.54408168793 --2.10399413109,1.79244863987,5.54766130447 --2.11696958542,1.78845965862,5.52824783325 --2.13694381714,1.79147160053,5.52783870697 --2.146930933,1.79247772694,5.52763462067 --2.16390562057,1.79148924351,5.51922416687 --2.18288016319,1.79350101948,5.51682138443 --2.20785212517,1.79951381683,5.52740240097 --2.22182750702,1.79652488232,5.51098918915 --2.23880314827,1.7965362072,5.50358772278 --2.26077628136,1.80054843426,5.50717639923 --2.26876401901,1.79955410957,5.50197410583 --2.2887377739,1.80156612396,5.49955463409 --2.30971121788,1.80457818508,5.50014162064 --2.32268714905,1.80058920383,5.48172903061 --2.34266161919,1.80360078812,5.4813284874 --2.36263608932,1.80561232567,5.48092889786 --2.36562466621,1.80061745644,5.46271467209 --2.39059734344,1.80662989616,5.47230243683 --2.4185693264,1.81564283371,5.48889446259 --2.43154597282,1.81265330315,5.47249794006 --2.44252181053,1.80666410923,5.44806909561 --2.47149372101,1.81667709351,5.46666479111 --2.48247051239,1.81168746948,5.444252491 --2.49345707893,1.81369364262,5.44504451752 --2.51543092728,1.81670546532,5.44763994217 --2.52740693092,1.81271612644,5.4272236824 --2.5473818779,1.81472754478,5.42582273483 --2.57335448265,1.82173991203,5.43641614914 --2.58333110809,1.81675028801,5.41200017929 --2.60630464554,1.82076227665,5.41559028625 --2.62029123306,1.82476830482,5.42339324951 --2.63426709175,1.82277905941,5.4079823494 --2.6482424736,1.81979000568,5.39156103134 --2.67521548271,1.82780230045,5.4041633606 --2.68519282341,1.82281219959,5.38176107407 --2.70516681671,1.82482397556,5.37733840942 --2.72315192223,1.83083069324,5.3921380043 --2.73412871361,1.82684111595,5.37072467804 --2.75510334969,1.82985234261,5.37032365799 --2.78007650375,1.83586442471,5.37691640854 --2.78805351257,1.82887458801,5.34848928452 --2.81302714348,1.83488619328,5.35609436035 --2.83700108528,1.83989799023,5.36069059372 --2.84198951721,1.83690297604,5.34948730469 --2.85596489906,1.83491373062,5.33306312561 --2.88193798065,1.84092581272,5.34065532684 --2.8989136219,1.84093666077,5.3312458992 --2.91688919067,1.84194743633,5.32484817505 --2.93986272812,1.84595918655,5.32542991638 --2.95383906364,1.84396958351,5.31102609634 --2.96782517433,1.84797561169,5.31581783295 --2.98679995537,1.84898686409,5.30940437317 --2.99977660179,1.8459969759,5.2929983139 --3.0247502327,1.85200881958,5.29758930206 --3.03972601891,1.85101926327,5.28417778015 --3.05370283127,1.84902954102,5.26977300644 --3.06568980217,1.8510351181,5.27157449722 --3.08966374397,1.85604667664,5.27416753769 --3.10264062881,1.85405683517,5.25776052475 --3.12261486053,1.8560680151,5.2523431778 --3.14358925819,1.85807907581,5.24892997742 --3.16356420517,1.86009013653,5.24452543259 --3.18253970146,1.86210083961,5.23811769485 --3.19252729416,1.86310613155,5.2359161377 --3.20750331879,1.86211657524,5.22250509262 --3.23147797585,1.86712777615,5.22510766983 --3.24545407295,1.86513805389,5.20969295502 --3.25743150711,1.86214780807,5.19229030609 --3.27940559387,1.86515891552,5.1898765564 --3.29938006401,1.86716997623,5.18345451355 --3.30936789513,1.86817526817,5.18125534058 --3.32534456253,1.86818528175,5.17085981369 --3.34831857681,1.87219655514,5.16944360733 --3.36729454994,1.87420701981,5.16304206848 --3.38526988029,1.87421762943,5.15362453461 --3.40624499321,1.87822830677,5.15022325516 --3.41423273087,1.87723338604,5.14401531219 --3.42821002007,1.87624323368,5.12961101532 --3.45218372345,1.88025450706,5.12919473648 --3.46116185188,1.87626385689,5.10678386688 --3.48213720322,1.87927436829,5.10338640213 --3.50311160088,1.88128519058,5.09796667099 --3.53008556366,1.88729643822,5.10256290436 --3.53107619286,1.88430047035,5.08736896515 --3.54905104637,1.88431107998,5.07694339752 --3.56202816963,1.88232088089,5.06053161621 --3.58200454712,1.88533091545,5.05614423752 --3.60198020935,1.88734138012,5.04973363876 --3.61595726013,1.88635098934,5.03532886505 --3.64193153381,1.89236187935,5.03792715073 --3.6539182663,1.89336752892,5.036714077 --3.66489648819,1.89137685299,5.01831150055 --3.68387126923,1.89238727093,5.00888442993 --3.70684719086,1.89639747143,5.00850152969 --3.71282601357,1.89140641689,4.98208284378 --3.73880028725,1.89641726017,4.98367643356 --3.75078725815,1.89842271805,4.98246622086 --3.77176332474,1.90143287182,4.97807073593 --3.78773999214,1.90144264698,4.96565961838 --3.79871797562,1.89945161343,4.94725513458 --3.82069277763,1.90246236324,4.94183301926 --3.83666944504,1.9024720192,4.9294219017 --3.84764742851,1.89948117733,4.91101646423 --3.8646337986,1.9044867754,4.91681623459 --3.87861227989,1.90449595451,4.90342521667 --3.89858722687,1.90650629997,4.89500141144 --3.91556477547,1.90751552582,4.8856139183 --3.94253849983,1.9125264883,4.88619470596 --3.95051765442,1.9095351696,4.86378479004 --3.97049403191,1.91154503822,4.85738945007 --3.97648286819,1.91054964066,4.84817790985 --3.99645853043,1.91255950928,4.8407702446 --4.02043390274,1.9175696373,4.83836603165 --4.03241205215,1.91557884216,4.82095623016 --4.04838895798,1.9155882597,4.80854892731 --4.06936407089,1.91859829426,4.80112886429 --4.07535409927,1.91760241985,4.79394340515 --4.09033203125,1.91761159897,4.7805390358 --4.111307621,1.92062163353,4.77312040329 --4.12528514862,1.91963100433,4.75770521164 --4.1422624588,1.92064011097,4.74731063843 --4.16723775864,1.92565000057,4.74591350555 --4.17621660233,1.92265880108,4.72449493408 --4.18820381165,1.92466402054,4.72228479385 --4.20318174362,1.92467296124,4.70888185501 --4.22715711594,1.92868280411,4.70547771454 --4.23813581467,1.92669153214,4.68706798553 --4.25711250305,1.92870092392,4.67765903473 --4.26309299469,1.92470908165,4.654255867 --4.28306913376,1.92671859264,4.64584684372 --4.29705619812,1.92972373962,4.64563751221 --4.30903530121,1.92873227596,4.62923908234 --4.33401107788,1.93374192715,4.62684059143 --4.3579864502,1.93775165081,4.62243080139 --4.37696313858,1.9397611618,4.61201381683 --4.39694023132,1.94177031517,4.60361099243 --4.40892887115,1.9447748661,4.60242176056 --4.42490673065,1.94578385353,4.58900880814 --4.44888210297,1.94979345798,4.58460569382 --4.46186065674,1.94880199432,4.56819534302 --4.47183990479,1.94681036472,4.54878568649 --4.47981929779,1.94381856918,4.52737522125 --4.48879861832,1.94082677364,4.5069642067 --4.49978733063,1.94283151627,4.50376462936 --4.51876401901,1.94484055042,4.49335193634 --4.5047492981,1.93184661865,4.45095252991 --4.50972938538,1.92785453796,4.42653656006 --4.51470947266,1.92386257648,4.4021191597 --4.50569295883,1.91286921501,4.36470985413 --4.5146727562,1.91087722778,4.34530353546 --4.51266384125,1.90688085556,4.32909727097 --4.50964546204,1.89888811111,4.29768228531 --4.50962686539,1.89289557934,4.26926660538 --4.5126080513,1.88790333271,4.24385023117 --4.50759124756,1.87990999222,4.21245527267 --4.51157236099,1.87591767311,4.18905067444 --4.52655029297,1.8769261837,4.1756401062 --4.49854707718,1.86092782021,4.13542747498 --4.51252555847,1.86093640327,4.12101316452 --4.52550411224,1.86094486713,4.10559749603 --4.53148508072,1.85795235634,4.08520317078 --4.54246377945,1.85696053505,4.06778430939 --4.57144021988,1.86496973038,4.0683927536 --4.56343269348,1.85797297955,4.04717731476 --4.58840894699,1.86298191547,4.04378128052 --4.60138750076,1.86299014091,4.0283665657 --4.61136770248,1.86199808121,4.01096105576 --4.61034965515,1.85600531101,3.98354911804 --4.63732624054,1.86201429367,3.98114585876 --4.63330793381,1.85502147675,3.95072484016 --4.64429712296,1.85702562332,3.94752669334 --4.67127370834,1.86303460598,3.94512677193 --4.66825580597,1.85604178905,3.91570448875 --4.69323301315,1.86105024815,3.91231846809 --4.7042131424,1.86105811596,3.8959133625 --4.70719385147,1.85706567764,3.87148690224 --4.71517467499,1.85507309437,3.85308909416 --4.73616123199,1.86107802391,3.85788941383 --4.73614358902,1.85608494282,3.83248472214 --4.74712371826,1.85509264469,3.81607842445 --4.77110099792,1.86010110378,3.81068015099 --4.77108240128,1.85510838032,3.78425550461 --4.77406406403,1.85111582279,3.76083850861 --4.80204105377,1.85812413692,3.75945591927 --4.79203367233,1.85112714767,3.73824048042 --4.80701303482,1.85213506222,3.72483062744 --4.82499170303,1.85514295101,3.71443200111 --4.82797336578,1.85115039349,3.69101142883 --4.84595251083,1.85415804386,3.68061375618 --4.85993146896,1.85416591167,3.66620159149 --4.85492372513,1.85016906261,3.6499979496 --4.87090301514,1.85217678547,3.63759303093 --4.87988424301,1.85118412971,3.62019348145 --4.88886404037,1.84919154644,3.6017768383 --4.90384340286,1.8511993885,3.58836889267 --4.9108247757,1.8492064476,3.56895971298 --4.92480516434,1.85021388531,3.55556464195 --4.93079471588,1.8502177,3.54735398293 --4.943775177,1.85122513771,3.53295493126 --4.9477558136,1.84723234177,3.51053023338 --4.96073627472,1.84823966026,3.4961309433 --4.973716259,1.84924721718,3.48071479797 --4.98969602585,1.85125470161,3.46831393242 --4.99267816544,1.84726130962,3.44691610336 --4.99966812134,1.84826517105,3.43971061707 --5.0096487999,1.84727239609,3.42229628563 --5.01463031769,1.84527933598,3.40188956261 --5.02861022949,1.84628677368,3.38747906685 --5.04059171677,1.84729349613,3.37309265137 --5.04557275772,1.84430062771,3.35166668892 --5.05855369568,1.845307827,3.33726859093 --5.06954336166,1.84731149673,3.33306980133 --5.07752418518,1.84631848335,3.31466031075 --5.08650541306,1.84632539749,3.29725646973 --5.09748649597,1.84633255005,3.28084731102 --5.097468853,1.84133934975,3.25642299652 --5.10944986343,1.84234619141,3.24101877213 --5.1244301796,1.84435331821,3.22761678696 --5.12042188644,1.84035634995,3.21341300011 --5.13740205765,1.84336364269,3.20100641251 --5.13838481903,1.83937001228,3.17860198021 --5.14836597443,1.83937704563,3.16118478775 --5.16934585571,1.84338414669,3.15178871155 --5.1703286171,1.84039056301,3.12938189507 --5.17231941223,1.83839380741,3.11917948723 --5.18430089951,1.83940052986,3.10377645493 --5.20028114319,1.84140765667,3.09036588669 --5.20426368713,1.83941411972,3.06995987892 --5.22524309158,1.84342122078,3.05955076218 --5.2342247963,1.8434278965,3.04214501381 --5.24220705032,1.84243428707,3.02474975586 --5.24719762802,1.84243774414,3.01553249359 --5.25517988205,1.84144425392,2.99813699722 --5.26416063309,1.84145104885,2.97971248627 --5.27314376831,1.84145724773,2.9633243084 --5.28312444687,1.84146392345,2.94590759277 --5.28610801697,1.83847010136,2.92550826073 --5.30408811569,1.84147691727,2.91310048103 --5.30208063126,1.83947980404,2.90089964867 --5.32206058502,1.84348666668,2.88949108124 --5.33804178238,1.84549319744,2.87608766556 --5.34202432632,1.84349954128,2.85567712784 --5.35800552368,1.84650599957,2.84227490425 --5.37398672104,1.84851241112,2.82887387276 --5.36797046661,1.84351861477,2.80244994164 --5.38495969772,1.84752202034,2.80024456978 --5.4019408226,1.8505282402,2.7878537178 --5.40492391586,1.84753453732,2.76643323898 --5.40990781784,1.84654045105,2.74804806709 --5.42788791656,1.84954690933,2.73463082314 --5.44386959076,1.8525531292,2.72123384476 --5.44785261154,1.85055923462,2.70082092285 --5.46384191513,1.85456252098,2.69761300087 --5.47082471848,1.85456860065,2.67920947075 --5.48680639267,1.85657465458,2.66581559181 --5.49378871918,1.85558080673,2.6463932991 --5.5127696991,1.85958695412,2.63399219513 --5.51775360107,1.85859286785,2.61458849907 --5.5437335968,1.86459898949,2.60518264771 --5.54272603989,1.86260187626,2.59398436546 --5.55670785904,1.86460793018,2.57857561111 --5.57168960571,1.8666138649,2.56417775154 --5.57467412949,1.86561954021,2.54377293587 --5.58465623856,1.86562550068,2.52636313438 --5.59863805771,1.86763131618,2.5109565258 --5.59963035583,1.86663413048,2.50075817108 --5.61261320114,1.86863982677,2.48536109924 --5.62959480286,1.87164580822,2.47094964981 --5.62058019638,1.8656514883,2.44453144073 --5.6375617981,1.86865735054,2.43012070656 --5.64154577255,1.86666285992,2.41072440147 --5.65652799606,1.86966860294,2.3953127861 --5.65552043915,1.8676712513,2.38411045074 --5.6775021553,1.87267673016,2.37271904945 --5.68848514557,1.87368249893,2.35530400276 --5.69846773148,1.8746881485,2.33789753914 --5.71845054626,1.87869346142,2.325507164 --5.73343324661,1.8806989193,2.31010103226 --5.73941659927,1.88070440292,2.2906897068 --5.7534070015,1.88370728493,2.28548431396 --5.74839258194,1.87971270084,2.2620818615 --5.76837444305,1.88371801376,2.24867749214 --5.7833571434,1.88672327995,2.23327493668 --5.7943406105,1.88772857189,2.21586465836 --5.81032323837,1.89073395729,2.20045638084 --5.8143081665,1.88973915577,2.18106126785 --5.82329940796,1.89174175262,2.17385983467 --5.83928251266,1.89474701881,2.15845370293 --5.84426689148,1.89375209808,2.13905191422 --5.85924959183,1.89675736427,2.12263536453 --5.87523269653,1.89976251125,2.10723209381 --5.88321685791,1.89976751804,2.08882880211 --5.89820051193,1.90277242661,2.07343435287 --5.89919281006,1.90177500248,2.06323456764 --5.9121761322,1.90378010273,2.04581689835 --5.92715978622,1.90678489208,2.0304248333 --5.93114471436,1.90578997135,2.01001143456 --5.93712902069,1.90579497814,1.99060404301 --5.95011281967,1.90780007839,1.97318851948 --5.95510530472,1.90780234337,1.96500086784 --5.96708869934,1.9098072052,1.94759333134 --5.97207307816,1.90881216526,1.9271736145 --5.96905994415,1.90581703186,1.90578508377 --5.99204206467,1.91182172298,1.8913667202 --5.99102783203,1.90882658958,1.86996531487 --6.00301218033,1.91083133221,1.85255992413 --6.0090045929,1.9118335247,1.84436702728 --6.00498962402,1.90883862972,1.82094347477 --6.01997375488,1.91184318066,1.80454039574 --6.03195810318,1.91384780407,1.78713679314 --6.02294492722,1.90885293484,1.76272165775 --6.04592847824,1.91385698318,1.74933218956 --6.05191326141,1.91386163235,1.7299259901 --6.05090618134,1.91286420822,1.71871650219 --6.06989049911,1.91686832905,1.70331454277 --6.07687520981,1.91787302494,1.68390333652 --6.06986188889,1.91387784481,1.66049182415 --6.07784700394,1.91388225555,1.6420943737 --6.09283161163,1.91688668728,1.62467873096 --6.07781839371,1.91089177132,1.5992680788 --6.09580993652,1.91489350796,1.59407317638 --6.11679458618,1.92089724541,1.57968652248 --6.10778093338,1.91590225697,1.55526185036 --6.11676645279,1.91690659523,1.53686058521 --6.14475011826,1.92491006851,1.52346158028 --6.13673686981,1.91991496086,1.50004959106 --6.14072227478,1.9199193716,1.47963511944 --6.15571451187,1.92392098904,1.47344303131 --6.15570020676,1.92192554474,1.452029109 --6.14168787003,1.91593050957,1.42762231827 --6.17867183685,1.92593348026,1.41622877121 --6.1606593132,1.91893863678,1.39081907272 --6.16964435577,1.91994285583,1.37140107155 --6.18762969971,1.92494630814,1.35500180721 --6.17862319946,1.92094910145,1.34178507328 --6.17960977554,1.91995334625,1.32138383389 --6.1955947876,1.92295706272,1.30397593975 --6.17358350754,1.91496229172,1.27857458591 --6.18556880951,1.91696596146,1.26016426086 --6.20755338669,1.92296934128,1.24375283718 --6.20254087448,1.91997373104,1.22235560417 --6.21053314209,1.92197561264,1.21314334869 --6.2255191803,1.92497897148,1.19574403763 --6.21150636673,1.91898405552,1.1713218689 --6.22049283981,1.92098772526,1.15292680264 --6.24047851562,1.92599070072,1.13653028011 --6.22346591949,1.91899573803,1.11211585999 --6.22945261002,1.91999959946,1.0927131176 --6.23844575882,1.92200124264,1.08349967003 --6.25043201447,1.92500472069,1.06509590149 --6.25441884995,1.92500841618,1.04570186138 --6.26540470123,1.9270118475,1.02628326416 --6.2463927269,1.92001712322,1.0018683672 --6.25237941742,1.9200206995,0.982466638088 --6.28237104416,1.92902088165,0.977266132832 --6.26135969162,1.92202615738,0.952854216099 --6.26634693146,1.92202973366,0.933456599712 --6.27733325958,1.9250330925,0.91403990984 --6.26832056046,1.92003774643,0.891626000404 --6.27730798721,1.92204082012,0.873236298561 --6.29129457474,1.92604386806,0.854832470417 --6.29728746414,1.92704546452,0.84461414814 --6.29627513885,1.92604935169,0.824214994907 --6.30526208878,1.92805254459,0.804807603359 --6.29524946213,1.92305707932,0.782392561436 --6.30923652649,1.92705976963,0.763992249966 --6.31622409821,1.92806303501,0.744591593742 --6.30421209335,1.92306768894,0.722179055214 --6.29920578003,1.92206990719,0.710969269276 --6.31019306183,1.92407286167,0.691558539867 --6.31618070602,1.92507600784,0.672160565853 --6.31916809082,1.92507958412,0.65174973011 --6.33815526962,1.93108177185,0.633343338966 --6.3431429863,1.93108487129,0.613949716091 --6.34913063049,1.93308806419,0.593533694744 --6.35212421417,1.93308961391,0.583326160908 --6.35811233521,1.93409252167,0.56393122673 --6.3591003418,1.93409597874,0.543526172638 --6.36308813095,1.93409919739,0.523115634918 --6.36007547379,1.93310308456,0.501697480679 --6.37506389618,1.93710505962,0.483307927847 --6.39205121994,1.94210708141,0.463896363974 --6.38204574585,1.93810963631,0.452691793442 --6.378033638,1.93611347675,0.431275069714 --6.39902162552,1.94211483002,0.412880003452 --6.40500974655,1.94311773777,0.392468959093 --6.39499855042,1.94012188911,0.371060311794 --6.41598653793,1.94612324238,0.352669686079 --6.41498041153,1.945125103,0.341450035572 --6.42196941376,1.94712746143,0.322059303522 --6.42595767975,1.94813036919,0.301652699709 --6.42694568634,1.94813358784,0.280229598284 --6.43593454361,1.95013582706,0.260838538408 --6.43592262268,1.95013904572,0.239416733384 --6.44291162491,1.95114135742,0.220028951764 --6.44790029526,1.95314407349,0.198602959514 --6.44489431381,1.95114588737,0.188404947519 --6.45288324356,1.95414817333,0.167997181416 --6.47187232971,1.95914924145,0.148603275418 --6.46886110306,1.95815253258,0.127184823155 --6.46185016632,1.95615613461,0.106788024306 --6.46283864975,1.95615911484,0.0853664055467 --6.46982765198,1.95716130733,0.0649625808001 --6.47982215881,1.96116173267,0.0547580607235 --6.47981119156,1.9611645937,0.034357752651 --6.47880077362,1.96016740799,0.013957824558 --6.47378969193,1.95817089081,-0.00746163073927 --6.48377895355,1.96117269993,-0.0278638508171 --6.48676872253,1.96217501163,-0.0482644289732 --6.48076248169,1.96017718315,-0.059484295547 --6.48475170135,1.96117949486,-0.0798847526312 --6.48374128342,1.96118235588,-0.100285358727 --6.48973035812,1.96218430996,-0.121704742312 --6.48772001266,1.96218717098,-0.142105534673 --6.48770952225,1.96219003201,-0.163525894284 --6.49369907379,1.9641919136,-0.183924198151 --6.50169420242,1.96619224548,-0.194121032953 --6.49168300629,1.96319615841,-0.215544953942 --6.50567340851,1.96719694138,-0.235937893391 --6.49766254425,1.9652005434,-0.257361769676 --6.50665283203,1.96820187569,-0.277755856514 --6.49664211273,1.96520555019,-0.298161923885 --6.50063180923,1.96620762348,-0.319578498602 --6.50062704086,1.96620881557,-0.32977822423 --6.50161647797,1.96721124649,-0.351196914911 --6.49560642242,1.96521437168,-0.37160167098 --6.49459648132,1.96521687508,-0.392002314329 --6.49658584595,1.96521902084,-0.413419574499 --6.49357652664,1.96522176266,-0.433822512627 --6.50256681442,1.96822297573,-0.455231487751 --6.49856138229,1.96722471714,-0.465435773134 --6.51455259323,1.97222471237,-0.486834466457 --6.51554250717,1.97322678566,-0.508251130581 --6.50653266907,1.97023034096,-0.528661310673 --6.50952243805,1.97123217583,-0.550075054169 --6.51651334763,1.9742333889,-0.571482419968 --6.5115032196,1.97323620319,-0.591887772083 --6.51249885559,1.97323703766,-0.602084815502 --6.51848983765,1.97623836994,-0.62349230051 --6.5214805603,1.9772400856,-0.644903719425 --6.51647090912,1.97624278069,-0.665309250355 --6.51846122742,1.97724461555,-0.686722040176 --6.51145124435,1.97524750233,-0.70713186264 --6.50944232941,1.9752497673,-0.727532565594 --6.52043819427,1.97924923897,-0.739748299122 --6.51842880249,1.97925138474,-0.760148346424 --6.49941825867,1.97325623035,-0.779564857483 --6.51140975952,1.9782563448,-0.801974892616 --6.50940084457,1.97825849056,-0.822375178337 --6.50139093399,1.97626161575,-0.842789411545 --6.49738121033,1.97526407242,-0.864214658737 --6.50437784195,1.97826385498,-0.874395728111 --6.48336648941,1.97126913071,-0.893823325634 --6.47535705566,1.97027218342,-0.914240479469 --6.47734832764,1.97127366066,-0.935651600361 --6.49134063721,1.97627305984,-0.95804977417 --6.4803314209,1.97327649593,-0.977455198765 --6.47932195663,1.97427845001,-0.998873412609 --6.50132036209,1.98127543926,-1.0120677948 --6.49431085587,1.98027825356,-1.0324819088 --6.49230194092,1.9802801609,-1.05288171768 --6.49329376221,1.98128163815,-1.0742919445 --6.4942855835,1.98228299618,-1.0957018137 --6.49927806854,1.985283494,-1.11709880829 --6.49527311325,1.98428499699,-1.12730765343 --6.5092663765,1.99028384686,-1.15071380138 --6.50325727463,1.98928642273,-1.17112469673 --6.49224758148,1.98628973961,-1.19053316116 --6.49524021149,1.98829066753,-1.2129535675 --6.50323295593,1.99229049683,-1.23535585403 --6.47322130203,1.98329734802,-1.25177383423 --6.49421977997,1.99029409885,-1.2659727335 --6.48921108246,1.99029624462,-1.28638112545 --6.48420238495,1.98929846287,-1.30678939819 --6.47319364548,1.98730182648,-1.32620131969 --6.47118520737,1.9873033762,-1.34761857986 --6.47317790985,1.98930418491,-1.36902010441 --6.4751701355,1.99130487442,-1.39144051075 --6.46416473389,1.98830759525,-1.39963984489 --6.46415710449,1.98930871487,-1.42104828358 --6.48315238953,1.99630606174,-1.44645631313 --6.46614265442,1.99231052399,-1.46487534046 --6.47913694382,1.99830877781,-1.48826658726 --6.4751291275,1.99831056595,-1.50968945026 --6.45611858368,1.99331533909,-1.52710008621 --6.47111701965,1.99831271172,-1.54130518436 --6.46110868454,1.9963157177,-1.56071591377 --6.45710086823,1.99631738663,-1.58111965656 --6.45409297943,1.99731886387,-1.60253846645 --6.46308755875,2.00131773949,-1.62593996525 --6.4460773468,1.99732220173,-1.64334583282 --6.42806768417,1.99332666397,-1.66177737713 --6.43706560135,1.99632513523,-1.6739654541 --6.43405818939,1.99732661247,-1.69538390636 --6.43105077744,1.9983278513,-1.716802001 --6.43804550171,2.00132703781,-1.73918938637 --6.42203569412,1.99833106995,-1.75761401653 --6.42302894592,2.00033164024,-1.78003048897 --6.42002248764,2.00033283234,-1.80042827129 --6.41401767731,1.99933433533,-1.81065046787 --6.42001247406,2.00333356857,-1.83303976059 --6.42800760269,2.00733232498,-1.85745513439 --6.40599632263,2.00133752823,-1.87387609482 --6.41499233246,2.00633621216,-1.8982847929 --6.44299173355,2.01732993126,-1.92666435242 --6.44198513031,2.01833033562,-1.94908487797 --6.45898532867,2.0253264904,-1.96427440643 --6.49298667908,2.03831887245,-1.99566805363 --6.48897981644,2.03832006454,-2.01708197594 --6.51297950745,2.04831433296,-2.0454685688 --6.54197978973,2.06030774117,-2.07586050034 --6.52297019958,2.0563120842,-2.09328198433 --6.53196668625,2.06030988693,-2.11869072914 --6.54396629333,2.06530714035,-2.13287878036 --6.52895784378,2.06231045723,-2.15129613876 --6.53495359421,2.06730890274,-2.17671942711 --6.53694915771,2.06930828094,-2.19910979271 --6.50293588638,2.06031632423,-2.21255111694 --6.49492931366,2.05931806564,-2.23296570778 --6.49892807007,2.06231713295,-2.24516129494 --6.47491693497,2.05632281303,-2.26058316231 --6.47891235352,2.0593214035,-2.28499722481 --6.49291133881,2.06631755829,-2.31138396263 --6.46590042114,2.05932402611,-2.32580947876 --6.45989370346,2.0593252182,-2.347230196 --6.45988941193,2.06232476234,-2.36963105202 --6.43888092041,2.05632996559,-2.37485790253 --6.43587589264,2.05733013153,-2.39626002312 --6.44087266922,2.0613284111,-2.42066311836 --6.41086006165,2.05333590508,-2.43409848213 --6.39485168457,2.05033946037,-2.45151519775 --6.40785074234,2.05733561516,-2.47891759872 --6.38684034348,2.05234074593,-2.49433279037 --6.38783884048,2.05433988571,-2.5065433979 --6.38483381271,2.05534029007,-2.5279443264 --6.35982275009,2.04934644699,-2.5423719883 --6.35281658173,2.04934763908,-2.56278347969 --6.35081195831,2.05134725571,-2.5851957798 --6.33780431747,2.04935026169,-2.60361361504 --6.32679700851,2.04835247993,-2.62303614616 --6.31879091263,2.04835391045,-2.64243721962 --6.30878639221,2.04535627365,-2.65065431595 --6.30578136444,2.04735636711,-2.67307305336 --6.30877828598,2.05135464668,-2.69748234749 --6.28376722336,2.0453608036,-2.71090292931 --6.27276039124,2.04336333275,-2.72930932045 --6.27875852585,2.04836058617,-2.7547121048 --6.26375246048,2.04536437988,-2.76093459129 --6.23674058914,2.03837132454,-2.77335786819 --6.24073791504,2.04236936569,-2.79775714874 --6.22572994232,2.04037261009,-2.81517887115 --6.22372627258,2.04237222672,-2.83758807182 --6.2117190361,2.04037451744,-2.85600423813 --6.18570756912,2.03438138962,-2.86842679977 --6.18870687485,2.03737974167,-2.88163518906 --6.1947054863,2.04237699509,-2.90703225136 --6.14768743515,2.02838993073,-2.91046857834 --6.15868759155,2.03538537025,-2.93887734413 --6.14668083191,2.03438782692,-2.9572968483 --6.11866855621,2.02739524841,-2.96872615814 --6.10666179657,2.0263979435,-2.98612976074 --6.11266183853,2.02939534187,-3.00134563446 --6.08865118027,2.02440142632,-3.01376271248 --6.09865188599,2.03139686584,-3.04217410088 --6.08164310455,2.02840089798,-3.05758571625 --6.06963634491,2.02640366554,-3.0749900341 --6.04862642288,2.02240872383,-3.08942127228 --6.05162525177,2.02640628815,-3.11483621597 --6.03861904144,2.02340984344,-3.12003946304 --6.02261066437,2.02141356468,-3.13646388054 --6.01860713959,2.02341341972,-3.15786981583 --5.99759674072,2.01841878891,-3.1712872982 --5.9725856781,2.01342558861,-3.18372583389 --5.9775853157,2.01842212677,-3.20912003517 --5.96157693863,2.01542592049,-3.22554779053 --5.96657800674,2.0194234848,-3.23974728584 --5.94856882095,2.01642775536,-3.25517678261 --5.930560112,2.01343226433,-3.26958990097 --5.92155504227,2.01343369484,-3.28900694847 --5.90554618835,2.01043725014,-3.30442023277 --5.88553667068,2.00744247437,-3.31783819199 --5.88453483582,2.01044106483,-3.34124898911 --5.88053274155,2.01044154167,-3.35146188736 --5.85151910782,2.00344967842,-3.35988163948 --5.83951234818,2.00345206261,-3.37831234932 --5.8315076828,2.00345301628,-3.39772129059 --5.81850099564,2.00245571136,-3.41514468193 --5.80849552155,2.00245738029,-3.43355631828 --5.79849004745,2.00245904922,-3.45196795464 --5.78648424149,2.00046229362,-3.45819211006 --5.77447795868,1.99946463108,-3.47560691833 --5.76947498322,2.00146436691,-3.49702048302 --5.74446296692,1.99547147751,-3.50744748116 --5.73445701599,1.99547314644,-3.5258603096 --5.72745323181,1.99647343159,-3.54627656937 --5.70544290543,1.99247956276,-3.55769395828 --5.69343709946,1.99048292637,-3.56290531158 --5.69143533707,1.99348139763,-3.58632111549 --5.67342615128,1.99048602581,-3.59973335266 --5.66141986847,1.98948836327,-3.61715126038 --5.64741325378,1.98849129677,-3.63357400894 --5.63940906525,1.98949205875,-3.6529841423 --5.62139987946,1.98649668694,-3.66639924049 --5.61739826202,1.98749709129,-3.67661309242 --5.59138584137,1.98150479794,-3.68604850769 --5.58638286591,1.98350417614,-3.70746040344 --5.57537698746,1.98350608349,-3.72486972809 --5.5573682785,1.98151063919,-3.73930573463 --5.53435707092,1.9765175581,-3.74871373177 --5.53935956955,1.98051404953,-3.76492881775 --5.52035045624,1.97751927376,-3.77734422684 --5.5033416748,1.97552347183,-3.79075527191 --5.49833965302,1.97752285004,-3.81318259239 --5.47632837296,1.97352910042,-3.82360100746 --5.46532344818,1.97353100777,-3.84101271629 --5.46232223511,1.97652935982,-3.86443281174 --5.43430805206,1.96753978729,-3.85865497589 --5.43030595779,1.97053849697,-3.88106989861 --5.41629934311,1.96954166889,-3.89648389816 --5.39829063416,1.9675463438,-3.90991187096 --5.38728570938,1.96754813194,-3.92732453346 --5.37427949905,1.96655070782,-3.94374442101 --5.35727071762,1.96455514431,-3.95716238022 --5.34426450729,1.96155929565,-3.96036744118 --5.35327005386,1.96955227852,-3.99177336693 --5.32825756073,1.96456003189,-4.00020599365 --5.30724668503,1.96156609058,-4.01164102554 --5.29924345016,1.96256649494,-4.03003501892 --5.27923345566,1.95957219601,-4.04247665405 --5.26722812653,1.95957446098,-4.05888700485 --5.26322650909,1.95957446098,-4.06909990311 --5.24021482468,1.95558166504,-4.07751512527 --5.23721504211,1.95957958698,-4.10194587708 --5.22520923615,1.95958173275,-4.11835622787 --5.19919586182,1.95359027386,-4.12477874756 --5.18619012833,1.95359277725,-4.14120340347 --5.18619155884,1.95758926868,-4.16660881042 --5.16618061066,1.95259678364,-4.16482973099 --5.15217447281,1.95159995556,-4.18025112152 --5.15217638016,1.95659637451,-4.20565509796 --5.12316131592,1.95060634613,-4.21009159088 --5.10515213013,1.94761145115,-4.22150039673 --5.10615491867,1.95360708237,-4.24892187119 --5.07413721085,1.94561886787,-4.25035381317 --5.07413864136,1.94761705399,-4.26254606247 --5.06613588333,1.94961702824,-4.28297042847 --5.04112291336,1.94462549686,-4.2893948555 --5.02911758423,1.94462752342,-4.30580854416 --5.02111530304,1.94662749767,-4.32623243332 --5.00010490417,1.94363379478,-4.33667087555 --4.97609186172,1.93864190578,-4.34308624268 --4.98109674454,1.94363737106,-4.36028862 --4.94907855988,1.9356495142,-4.36071968079 --4.94207668304,1.93764877319,-4.38214588165 --4.9280705452,1.93765187263,-4.39655637741 --4.91406440735,1.93665504456,-4.41096687317 --4.8950548172,1.93466043472,-4.42239999771 --4.88204956055,1.93466305733,-4.43781328201 --4.85903501511,1.92767286301,-4.43203735352 --4.86104011536,1.93366754055,-4.46044683456 --4.85604047775,1.9376655817,-4.48387384415 --4.82602310181,1.92967712879,-4.4842915535 --4.81401872635,1.93067920208,-4.50070810318 --4.80701732635,1.93367826939,-4.52213048935 --4.78600597382,1.92968511581,-4.53054952621 --4.76499319077,1.92369425297,-4.52576971054 --4.75799226761,1.92669355869,-4.54617738724 --4.73598051071,1.92270076275,-4.55461406708 --4.72397613525,1.92370271683,-4.5710310936 --4.71497392654,1.92570281029,-4.5904507637 --4.69096040726,1.92071127892,-4.59688806534 --4.6759519577,1.91771745682,-4.59609079361 --4.67395448685,1.92271363735,-4.62149953842 --4.64593791962,1.91572451591,-4.62393808365 --4.63793706894,1.91872406006,-4.64435768127 --4.61992788315,1.91672921181,-4.65578794479 --4.59591388702,1.91173815727,-4.66020202637 --4.57990694046,1.91174209118,-4.67363548279 --4.58291149139,1.91573798656,-4.68983078003 --4.57090759277,1.9157397747,-4.70624780655 --4.54689359665,1.91174852848,-4.71168136597 --4.53589010239,1.9127497673,-4.72909879684 --4.52388620377,1.91375160217,-4.74551677704 --4.50287485123,1.91075885296,-4.75293731689 --4.49987840652,1.9157551527,-4.77835130692 --4.48286724091,1.91176235676,-4.77657938004 --4.47186422348,1.912763834,-4.79298210144 --4.46286249161,1.91476345062,-4.81341171265 --4.44485330582,1.91276884079,-4.82383203506 --4.41983890533,1.90877866745,-4.82726049423 --4.40183019638,1.90678393841,-4.83768320084 --4.39783287048,1.91178047657,-4.86310768127 --4.38782787323,1.90978384018,-4.86732006073 --4.37382221222,1.90978682041,-4.88173913956 --4.35581350327,1.90879249573,-4.89114904404 --4.34881401062,1.91179072857,-4.91357326508 --4.33280706406,1.91179466248,-4.92700910568 --4.31379747391,1.90880095959,-4.93542146683 --4.2987909317,1.90880453587,-4.94884252548 --4.28878593445,1.907807827,-4.95305681229 --4.27878379822,1.90980803967,-4.97146940231 --4.26477861404,1.90981066227,-4.98690223694 --4.2447681427,1.90781760216,-4.99431943893 --4.23376560211,1.90981829166,-5.01274681091 --4.21475601196,1.90682458878,-5.02116203308 --4.19974994659,1.90682804585,-5.03458404541 --4.18273830414,1.90283608437,-5.03181695938 --4.17874240875,1.90783238411,-5.05621337891 --4.1607336998,1.9068377018,-5.06664276123 --4.14472675323,1.9058419466,-5.07906723022 --4.12571716309,1.90384805202,-5.08850002289 --4.1137137413,1.90484941006,-5.10491466522 --4.09870815277,1.90485286713,-5.11833667755 --4.07869291306,1.89886343479,-5.11055660248 --4.07469797134,1.9048589468,-5.13697481155 --4.05668878555,1.90386474133,-5.14639377594 --4.04268407822,1.90386724472,-5.16182661057 --4.02267360687,1.90187418461,-5.16925239563 --4.00366353989,1.89988052845,-5.17767524719 --3.99266195297,1.90188121796,-5.19508552551 --3.98365736008,1.90088403225,-5.20030260086 --3.97065377235,1.90188598633,-5.21571826935 --3.94864082336,1.89889442921,-5.22115421295 --3.93163299561,1.89789938927,-5.23157215118 --3.91062116623,1.89590728283,-5.2380065918 --3.89561510086,1.89591085911,-5.25041818619 --3.88561534882,1.89891028404,-5.27084875107 --3.87460875511,1.89691460133,-5.27306175232 --3.85359597206,1.8939230442,-5.27747249603 --3.85560941696,1.90291321278,-5.31288862228 --3.82658863068,1.89592707157,-5.30933427811 --3.81358551979,1.89792907238,-5.32474994659 --3.79958152771,1.8989315033,-5.34018182755 --3.78256797791,1.89394056797,-5.33439922333 --3.76656126976,1.8939448595,-5.34581613541 --3.75756287575,1.89794337749,-5.36723709106 --3.73855280876,1.89594984055,-5.37566757202 --3.71153330803,1.88996303082,-5.37208938599 --3.70654010773,1.8959581852,-5.39951372147 --3.6765165329,1.8879737854,-5.39194107056 --3.66751861572,1.89097225666,-5.41335916519 --3.66251897812,1.89297187328,-5.42357063293 --3.63449811935,1.88698589802,-5.41900396347 --3.61949276924,1.88698911667,-5.43242931366 --3.60749149323,1.88998997211,-5.4498500824 --3.58747959137,1.88699769974,-5.45526695251 --3.57247471809,1.88800108433,-5.4686923027 --3.57248210907,1.89299607277,-5.4869093895 --3.53845262527,1.88201582432,-5.47233724594 --3.52745270729,1.88501560688,-5.49176311493 --3.51945710182,1.89001250267,-5.51619338989 --3.49043393135,1.8830281496,-5.50862121582 --3.47042179108,1.88103628159,-5.51303100586 --3.46442914009,1.88703131676,-5.54045820236 --3.44340896606,1.87904477119,-5.52768659592 --3.42539930344,1.87805116177,-5.53509712219 --3.42441368103,1.88704156876,-5.57052373886 --3.39238595963,1.87806022167,-5.55795764923 --3.37537837029,1.87806534767,-5.56838560104 --3.36437916756,1.88106489182,-5.58780622482 --3.33635640144,1.87408006191,-5.5812420845 --3.33035588264,1.876080513,-5.58944511414 --3.32135939598,1.88007831573,-5.61186218262 --3.29634094238,1.87509059906,-5.61030244827 --3.28133630753,1.87609386444,-5.62372779846 --3.26432847977,1.87609922886,-5.63314628601 --3.23930978775,1.87111198902,-5.63057947159 --3.23331832886,1.87710630894,-5.65900278091 --3.2223110199,1.876111269,-5.66022062302 --3.19528865814,1.8701261282,-5.65365028381 --3.18028378487,1.87012958527,-5.66606426239 --3.16728281975,1.87313067913,-5.68349599838 --3.133248806,1.86215305328,-5.66392183304 --3.1292617321,1.87014472485,-5.69735622406 --3.11626052856,1.87314605713,-5.71377515793 --3.09924387932,1.86715698242,-5.70500183105 --3.08223628998,1.86716234684,-5.71442222595 --3.06622982025,1.86716687679,-5.72483444214 --3.0482211113,1.86717307568,-5.73326396942 --3.02420258522,1.86218523979,-5.7317032814 --3.01620912552,1.86818158627,-5.75610923767 --3.00119495392,1.86319077015,-5.75033473969 --2.9851899147,1.86519467831,-5.76276874542 --2.97419214249,1.8681936264,-5.78318738937 --2.95117521286,1.86520504951,-5.78262233734 --2.92515277863,1.85922002792,-5.77605485916 --2.91315317154,1.86222028732,-5.79346227646 --2.89714837074,1.86322391033,-5.80690574646 --2.87813735008,1.86223161221,-5.81232690811 --2.86412453651,1.85824012756,-5.80754995346 --2.84811878204,1.85924434662,-5.81897354126 --2.83311414719,1.86024773121,-5.831387043 --2.82011389732,1.86324846745,-5.84881067276 --2.79809880257,1.86025893688,-5.85025310516 --2.77908778191,1.85926663876,-5.855676651 --2.7670776844,1.85627317429,-5.85389375687 --2.74806642532,1.85528099537,-5.85931873322 --2.7310590744,1.855286479,-5.86874294281 --2.71505403519,1.85629022121,-5.8811750412 --2.6990480423,1.8572947979,-5.89158916473 --2.67903518677,1.85530376434,-5.89501571655 --2.66403317451,1.85730564594,-5.91146564484 --2.65602946281,1.85730826855,-5.91566228867 --2.6360168457,1.85631716251,-5.91909074783 --2.61700582504,1.85432505608,-5.92451763153 --2.60200238228,1.85632801056,-5.93793821335 --2.57798171043,1.8513417244,-5.93337488174 --2.56398081779,1.85434317589,-5.94980239868 --2.54496979713,1.85335111618,-5.95523118973 --2.53596568108,1.85335421562,-5.95944929123 --2.516954422,1.8523619175,-5.96487808228 --2.49393463135,1.84837543964,-5.96030044556 --2.47792983055,1.84937918186,-5.97273159027 --2.46493244171,1.85337865353,-5.99317169189 --2.43690133095,1.8453990221,-5.97659444809 --2.42891383171,1.85339212418,-6.00701713562 --2.41189193726,1.84640622139,-5.99223518372 --2.39288020134,1.84541451931,-5.99665927887 --2.38088488579,1.84941256046,-6.01909208298 --2.37089395523,1.85640799999,-6.04551649094 --2.34887576103,1.85342049599,-6.04294252396 --1.71451544762,1.83668577671,-6.22754096985 --1.69249463081,1.8326997757,-6.22298383713 --1.67849779129,1.83769965172,-6.24139738083 --1.65647637844,1.83371400833,-6.23583602905 --1.64950466156,1.8466989994,-6.28025197983 --1.61744892597,1.83173382282,-6.23969936371 --1.61346197128,1.83772706985,-6.26091003418 --1.59545350075,1.83773374557,-6.26834058762 --1.5704189539,1.82975590229,-6.24876737595 --1.55140662193,1.82876491547,-6.2521982193 --1.54142868519,1.8397538662,-6.29063177109 --1.51538920403,1.82977890968,-6.26605701447 --1.4993878603,1.83278143406,-6.28048372269 --1.49038589001,1.83478367329,-6.28671360016 --1.47337925434,1.83578956127,-6.29512786865 --1.45336484909,1.83479988575,-6.29656982422 --1.43736374378,1.83780252934,-6.31099367142 --1.41533875465,1.83281898499,-6.30142211914 --1.39632642269,1.83182799816,-6.30485343933 --1.37932264805,1.83483242989,-6.31628322601 --1.36931562424,1.83383738995,-6.317507267 --1.34829366207,1.82985210419,-6.31093263626 --1.33229553699,1.83485329151,-6.32836914062 --1.31629562378,1.83785521984,-6.34379386902 --1.28824424744,1.82488703728,-6.30823564529 --1.27626156807,1.83387899399,-6.34065341949 --1.25423717499,1.82989537716,-6.33209657669 --1.24523341656,1.8298984766,-6.33631324768 --1.22822976112,1.83290290833,-6.3477396965 --1.20720756054,1.82891774178,-6.34117174149 --1.19120812416,1.83291971684,-6.35659265518 --1.1711909771,1.83093178272,-6.35502624512 --1.15217792988,1.82994139194,-6.35745573044 --1.13417029381,1.83194804192,-6.36488485336 --1.1251693964,1.83294987679,-6.37211370468 --1.10313940048,1.82696914673,-6.35753917694 --1.08513176441,1.8289757967,-6.3649687767 --1.06712472439,1.82998216152,-6.37340068817 --1.04811096191,1.82899224758,-6.37482786179 --1.02709126472,1.8270059824,-6.37128019333 --1.00908005238,1.82701468468,-6.37469291687 --0.999074041843,1.82701933384,-6.37692403793 --0.982069730759,1.82902407646,-6.38734054565 --0.964065730572,1.83202886581,-6.3987827301 --0.941025435925,1.8220539093,-6.37420558929 --0.925032973289,1.82905220985,-6.3966422081 --0.905014872551,1.827064991,-6.39407920837 --0.892991006374,1.82107973099,-6.37829303741 --0.873978972435,1.82108902931,-6.38172960281 --0.85597127676,1.82209563255,-6.38915729523 --0.83494502306,1.81811308861,-6.37859392166 --0.81593298912,1.81812238693,-6.38203144073 --0.801954448223,1.82911300659,-6.41745615005 --0.78092622757,1.82413136959,-6.40488815308 --0.760907888412,1.82214426994,-6.40232944489 --0.754927456379,1.83013474941,-6.42854070663 --0.714745998383,1.77723836899,-6.26798057556 --0.711857736111,1.81617879868,-6.39039802551 --0.693855822086,1.81918251514,-6.40384101868 --0.674838423729,1.81819498539,-6.40126276016 --0.653804004192,1.811216712,-6.38268852234 --0.64682495594,1.81920647621,-6.41091918945 --0.626801848412,1.81622207165,-6.40335178375 --0.607787191868,1.81623291969,-6.40378284454 --0.590791225433,1.82123363018,-6.4222111702 --0.570769786835,1.81824827194,-6.41664981842 --0.552766442299,1.82125294209,-6.42808294296 --0.534760355949,1.82325911522,-6.43650770187 --0.510592937469,1.7743524313,-6.28372859955 --0.504722595215,1.81828427315,-6.42215681076 --0.489753007889,1.83127057552,-6.46558237076 --0.466690123081,1.81630778313,-6.42001438141 --0.447677284479,1.81631779671,-6.42245054245 --0.4317073524,1.82930445671,-6.4658908844 --0.40864187479,1.8133431673,-6.41832971573 --0.399637907743,1.81434679031,-6.42153978348 --0.380622059107,1.81335842609,-6.42097139359 --0.361604332924,1.81237113476,-6.41840028763 --0.34462121129,1.82136511803,-6.4488325119 --0.324595779181,1.81838202477,-6.43927383423 --0.30659198761,1.82138717175,-6.44969701767 --0.286562234163,1.81640636921,-6.43613433838 --0.277565419674,1.81940627098,-6.44635248184 --0.257531583309,1.8134278059,-6.42878723145 --0.239529728889,1.81643176079,-6.44121170044 --0.220518141985,1.81744122505,-6.44464826584 --0.200487166643,1.81246125698,-6.4300904274 --0.181465253234,1.8104763031,-6.42351913452 --0.162453398108,1.81048583984,-6.42695665359 --0.153446406126,1.81049108505,-6.42716264725 --0.135482504964,1.82547521591,-6.4756102562 --0.115431718528,1.81550586224,-6.44204378128 --0.0963999852538,1.80952584743,-6.42646837234 --0.0773769319057,1.80754160881,-6.41890048981 --0.0583851784468,1.8135406971,-6.44134616852 --0.0393461287022,1.80656468868,-6.41877269745 --0.0303433109075,1.80756783485,-6.42298078537 --0.0113381696865,1.81057417393,-6.43242025375 -0.00769268907607,1.80559384823,-6.41785240173 --0.00266865873709,1.79841172695,-5.60722589493 -0.0163621176034,1.80342209339,-5.62261962891 -0.0353652313352,1.80041790009,-5.61202001572 -0.0543819069862,1.80042099953,-5.61441707611 -0.0633984282613,1.80342686176,-5.62360143661 -0.0823752805591,1.79240882397,-5.58801746368 -0.101410992444,1.79842185974,-5.60840511322 -0.120417483151,1.7964195013,-5.60080814362 -0.139432236552,1.79642140865,-5.60120677948 -0.15743586421,1.79341781139,-5.59159231186 -0.167470797896,1.80243325233,-5.61778020859 -0.185452625155,1.7924182415,-5.58718490601 -0.204464316368,1.7914185524,-5.58458757401 -0.223479121923,1.79142069817,-5.58498716354 -0.242488950491,1.79042005539,-5.58039188385 -0.261524319649,1.79743301868,-5.60076808929 -0.281549036503,1.80044007301,-5.61017560959 -0.289536863565,1.79443120956,-5.59236621857 -0.307526737452,1.78742027283,-5.56877708435 -0.325532644987,1.78441810608,-5.56116771698 -0.344538658857,1.78241550922,-5.55258178711 -0.363565593958,1.78642392159,-5.56496429443 -0.382573544979,1.78442251682,-5.55837631226 -0.401593476534,1.78642725945,-5.56376791 -0.410597771406,1.78642678261,-5.56096220016 -0.429615586996,1.78743052483,-5.56435728073 -0.448632448912,1.788433671,-5.56675338745 -0.47158485651,1.76740157604,-5.50037050247 -0.490600138903,1.76840388775,-5.50077390671 -0.509616315365,1.76940667629,-5.50217533112 -0.518622517586,1.76940727234,-5.50136899948 -0.535623431206,1.76540267467,-5.48875904083 -0.552614808083,1.75839304924,-5.46617412567 -0.573659598827,1.76841044426,-5.49555253983 -0.591664552689,1.7664077282,-5.48595905304 -0.608659982681,1.76040017605,-5.46736860275 -0.627677023411,1.76140356064,-5.46976804733 -0.6397113204,1.77041816711,-5.49595499039 -0.658731102943,1.77242326736,-5.50134420395 -0.676739871502,1.77142238617,-5.4957408905 -0.697772502899,1.7774336338,-5.51313734055 -0.7157792449,1.7754317522,-5.5055398941 -0.733789980412,1.77543199062,-5.50193119049 -0.752802371979,1.7754329443,-5.49934053421 -0.758784770966,1.76742196083,-5.47554159164 -0.779821038246,1.77543497086,-5.49691963196 -0.796816051006,1.7694272995,-5.47734212875 -0.813818752766,1.76642370224,-5.46574068069 -0.830819785595,1.7634190321,-5.45214700699 -0.855878531933,1.77744328976,-5.4955291748 -0.862870573997,1.77343678474,-5.48072767258 -0.882896363735,1.77744483948,-5.49211025238 -0.903923809528,1.78245329857,-5.50450801849 -0.916900992393,1.77143716812,-5.46791505814 -0.93591350317,1.771438241,-5.4653263092 -0.955934762955,1.77444374561,-5.47172403336 -0.972937643528,1.77144026756,-5.46012735367 -0.982951045036,1.77444446087,-5.46631383896 -1.00196695328,1.77544736862,-5.46770858765 -1.0189691782,1.77244365215,-5.45511722565 -1.03999900818,1.77845335007,-5.47049617767 -1.05700194836,1.77544999123,-5.45890140533 -1.08003997803,1.78346371651,-5.48228549957 -1.09704220295,1.78045988083,-5.46969509125 -1.10504007339,1.77845644951,-5.45990467072 -1.12204408646,1.7754535675,-5.44930887222 -1.13905012608,1.77445185184,-5.44070339203 -1.15706181526,1.77445292473,-5.43809318542 -1.17607700825,1.77545535564,-5.43848991394 -1.19609379768,1.77745866776,-5.43990182877 -1.21209549904,1.77445495129,-5.42729663849 -1.22110104561,1.77445530891,-5.42549371719 -1.24111831188,1.77545881271,-5.42790126801 -1.25711882114,1.77245438099,-5.41330766678 -1.2751313448,1.77245604992,-5.41169214249 -1.29414582253,1.77445816994,-5.41109228134 -1.31014442444,1.7694529295,-5.39451265335 -1.33016300201,1.77245700359,-5.39791250229 -1.34117817879,1.77546203136,-5.40609931946 -1.35416662693,1.76745212078,-5.37951231003 -1.37318110466,1.76945436001,-5.37891197205 -1.39219760895,1.77045786381,-5.38129615784 -1.4041826725,1.76244628429,-5.35071611404 -1.42520642281,1.76645302773,-5.3601026535 -1.43320655823,1.7644507885,-5.35231399536 -1.44920837879,1.76144719124,-5.3387260437 -1.47424793243,1.77146136761,-5.36410045624 -1.4882440567,1.7664552927,-5.34550046921 -1.50525081158,1.76545393467,-5.33690452576 -1.52526891232,1.76745820045,-5.34030103683 -1.54428172112,1.76845955849,-5.33771085739 -1.54826891422,1.7624515295,-5.31692075729 -1.56929159164,1.7664577961,-5.32530546188 -1.59633302689,1.77747249603,-5.35170030594 -2.16062259674,1.7674715519,-5.14273643494 -2.18264174461,1.77047598362,-5.14614868164 -2.20466256142,1.77548134327,-5.15253400803 -2.21565675735,1.76947510242,-5.12994766235 -2.23167920113,1.77648305893,-5.14612722397 -2.25269675255,1.77948701382,-5.14852380753 -2.26469254494,1.77448129654,-5.12695074081 -2.28771471977,1.77948713303,-5.13434171677 -2.29670548439,1.77247977257,-5.1087474823 -2.32173109055,1.77848684788,-5.11914920807 -2.29063367844,1.73944175243,-4.99862575531 -2.34072971344,1.77348065376,-5.09276294708 -2.35873985291,1.77448153496,-5.08716917038 -2.38877725601,1.7844940424,-5.11153697968 -2.3977689743,1.77848672867,-5.08594894409 -2.41176962852,1.77548336983,-5.06937837601 -2.4317855835,1.77848672867,-5.07075786591 -2.44879341125,1.77748656273,-5.06217193604 -2.45880103111,1.77848803997,-5.06236600876 -2.47580957413,1.77848803997,-5.05476999283 -2.49582457542,1.78149080276,-5.05416584015 -2.51082968712,1.78048956394,-5.04355955124 -2.5348508358,1.78449487686,-5.04897356033 -2.54885435104,1.78349292278,-5.03636741638 -2.56987094879,1.78649640083,-5.03775978088 -2.57687163353,1.78449499607,-5.02997207642 -2.59187602997,1.78349328041,-5.01738595963 -2.60988688469,1.78449451923,-5.012778759 -2.62990045547,1.78649663925,-5.01019001007 -2.64490532875,1.7844953537,-4.99859523773 -2.65991044044,1.78349399567,-4.98700046539 -2.66791415215,1.78349399567,-4.98319292068 -2.68592405319,1.78449475765,-4.97660446167 -2.70193099976,1.78349423409,-4.96701002121 -2.72595310211,1.78949999809,-4.97439098358 -2.73695063591,1.78449583054,-4.95480489731 -2.74794912338,1.78149199486,-4.93620920181 -2.76395559311,1.78049123287,-4.92562580109 -2.77696752548,1.78349435329,-4.9298286438 -2.79598021507,1.78549659252,-4.92721652985 -2.80597734451,1.78149211407,-4.90662622452 -2.82799434662,1.78449571133,-4.90802764893 -2.84600543976,1.78649711609,-4.90341663361 -2.87803888321,1.79650723934,-4.92280578613 -2.8780195713,1.78549659252,-4.88422822952 -2.88401913643,1.78349459171,-4.87444829941 -2.9050347805,1.78649783134,-4.87483787537 -2.91703510284,1.78349483013,-4.85725784302 -2.94906830788,1.79450488091,-4.8766374588 -2.95105338097,1.78449606895,-4.84305238724 -2.96605849266,1.78349494934,-4.83047389984 -2.98406910896,1.78449618816,-4.82487249374 -2.99307441711,1.78549683094,-4.82207155228 -3.00908231735,1.78549695015,-4.81346607208 -3.03510451317,1.79150235653,-4.8198723793 -3.05511808395,1.79450464249,-4.81727027893 -3.07212686539,1.79450523853,-4.8096704483 -3.08112335205,1.78950107098,-4.78808736801 -3.1031396389,1.79350435734,-4.7884850502 -3.11514902115,1.79550647736,-4.7896900177 -3.12815237045,1.79450500011,-4.77608680725 -3.15116977692,1.7985086441,-4.7774887085 -3.15816378593,1.79250359535,-4.75290870667 -3.17717576027,1.79450523853,-4.74830818176 -3.19518613815,1.79550659657,-4.74270105362 -3.21620035172,1.79850900173,-4.74011087418 -3.15110182762,1.75547039509,-4.61941003799 -3.23620629311,1.79650700092,-4.71971797943 -3.24320173264,1.79150271416,-4.69712162018 -3.26822161674,1.79750752449,-4.70151519775 -3.29123783112,1.80051076412,-4.70093250275 -3.32226610184,1.80951857567,-4.71530532837 -3.31224560738,1.7995095253,-4.68253469467 -3.32925415039,1.80051004887,-4.67394351959 -3.35026860237,1.80351269245,-4.67233562469 -3.37428689003,1.80851686001,-4.67472791672 -3.38829112053,1.80651569366,-4.6611456871 -3.40630125999,1.80851686001,-4.65454435349 -3.42331051826,1.80951762199,-4.64693832397 -3.40928578377,1.79650735855,-4.60917758942 -3.44832253456,1.80951809883,-4.63255786896 -3.4613263607,1.80851709843,-4.61895895004 -3.4803378582,1.8105186224,-4.61336088181 -3.49834752083,1.81151950359,-4.60577058792 -3.50534391403,1.80651581287,-4.58318662643 -3.51934957504,1.80651521683,-4.57059288025 -3.52935576439,1.80751633644,-4.56878900528 -3.56038141251,1.81652283669,-4.57918310165 -3.56237196922,1.80851721764,-4.54960870743 -3.5783803463,1.80951762199,-4.54099702835 -3.60039448738,1.81252026558,-4.53840637207 -3.62641382217,1.81852471828,-4.54180145264 -3.63240981102,1.81352090836,-4.51821947098 -3.6374104023,1.81251990795,-4.50942325592 -3.6534178257,1.81252014637,-4.49883651733 -3.67943739891,1.81852471828,-4.50321435928 -3.68943762779,1.81552243233,-4.48364877701 -3.70844912529,1.81752419472,-4.47902965546 -3.71844983101,1.81452190876,-4.45946550369 -3.730458498,1.81752383709,-4.46064853668 -3.73745584488,1.81252074242,-4.43807792664 -3.76147294044,1.81752443314,-4.4394569397 -3.7814848423,1.82052624226,-4.43386459351 -3.79348874092,1.81952524185,-4.41926622391 -3.80949616432,1.81952571869,-4.40867805481 -3.83050942421,1.82252800465,-4.40507221222 -3.83350777626,1.82052636147,-4.39328765869 -3.85652303696,1.8245292902,-4.391685009 -3.85551333427,1.81652390957,-4.36110401154 -3.88052988052,1.82152736187,-4.36051797867 -3.89453625679,1.82152736187,-4.34891080856 -3.91955280304,1.82653069496,-4.34832191467 -3.92454957962,1.82152760029,-4.3247423172 -3.93555641174,1.82352900505,-4.32294464111 -3.94655966759,1.82152795792,-4.30734729767 -3.98558998108,1.83353590965,-4.32373094559 -3.98858547211,1.82853245735,-4.2991361618 -3.9945833683,1.82352983952,-4.27656173706 -4.01559591293,1.82753181458,-4.27097558975 -4.02059364319,1.82252931595,-4.24937391281 -4.0346031189,1.8255314827,-4.25057649612 -4.04660749435,1.82453072071,-4.23499631882 -4.05961227417,1.82353067398,-4.22140264511 -4.08262681961,1.82853341103,-4.2188000679 -4.10063695908,1.83053457737,-4.21020889282 -4.08661699295,1.81652665138,-4.1666469574 -4.06259202957,1.80251812935,-4.12687587738 -4.04957389832,1.78951096535,-4.0853099823 -4.02654695511,1.77150094509,-4.0317773819 -4.02153730392,1.76349651814,-4.00019311905 -3.99851155281,1.74548709393,-3.94864439964 -3.98649573326,1.73348104954,-3.909085989 -3.98448967934,1.72747778893,-3.88149905205 -3.99549674988,1.72847926617,-3.87970519066 -3.99849510193,1.72447729111,-3.85613632202 -4.00749874115,1.72247707844,-3.83955216408 -4.0305147171,1.72748053074,-3.83892917633 -4.02850818634,1.71947741508,-3.81036782265 -4.04451847076,1.72147917747,-3.8017642498 -4.05952692032,1.7224804163,-3.79117703438 -4.05652236938,1.71747863293,-3.77539277077 -4.06952953339,1.71747946739,-3.76280808449 -4.08754110336,1.72048163414,-3.75521755219 -4.08153247833,1.71147823334,-3.72463846207 -4.09554100037,1.71247935295,-3.71305370331 -4.1095495224,1.71348071098,-3.70245194435 -4.11755275726,1.71148073673,-3.68585920334 -4.12355613708,1.71148121357,-3.67906832695 -4.13756418228,1.71148240566,-3.66748404503 -4.13255739212,1.70347964764,-3.63791489601 -4.14856767654,1.70548152924,-3.62931108475 -4.17058229446,1.71048462391,-3.62571167946 -4.16857862473,1.70348262787,-3.599142313 -4.17758321762,1.70248305798,-3.5835518837 -4.18959140778,1.70448470116,-3.5817668438 -4.18858861923,1.69948327541,-3.55816531181 -4.19959449768,1.69848418236,-3.5435898304 -4.21760606766,1.70048654079,-3.53599739075 -4.2186050415,1.6964854002,-3.51242947578 -4.23061275482,1.69648659229,-3.49983477592 -4.24362039566,1.6964880228,-3.48823785782 -4.24061727524,1.69348716736,-3.47443914413 -4.24762153625,1.6904873848,-3.45587801933 -4.25162315369,1.68748724461,-3.43727350235 -4.26062822342,1.68648803234,-3.4216902256 -4.2786397934,1.68849050999,-3.41311383247 -4.29364967346,1.69049239159,-3.40351033211 -4.28564357758,1.68449068069,-3.38473463058 -4.29565000534,1.68349182606,-3.37014985085 -4.31566286087,1.68749451637,-3.3645465374 -4.31466197968,1.68249392509,-3.34096598625 -4.32266664505,1.68049478531,-3.32537150383 -4.34167909622,1.68349742889,-3.31778860092 -4.33867645264,1.67749655247,-3.29222083092 -4.34267950058,1.6774970293,-3.28442406654 -4.3636932373,1.68149995804,-3.27981376648 -4.36169195175,1.67549955845,-3.25524568558 -4.36569452286,1.6724998951,-3.23567199707 -4.38470697403,1.67550265789,-3.2290687561 -4.39271259308,1.67450380325,-3.21249628067 -4.4047203064,1.67550551891,-3.20088672638 -4.40772294998,1.67450594902,-3.1911149025 -4.41372728348,1.67250680923,-3.17451643944 -4.42473459244,1.67250847816,-3.16093111038 -4.4357419014,1.67251014709,-3.14734554291 -4.43574285507,1.6685103178,-3.1257610321 -4.45075273514,1.6695125103,-3.11517453194 -4.45675706863,1.66951346397,-3.10838890076 -4.45475673676,1.66451358795,-3.08579945564 -4.463763237,1.66451513767,-3.07120776176 -4.4787735939,1.6665173769,-3.06062030792 -4.48778009415,1.6655189991,-3.04602909088 -4.48778152466,1.66151952744,-3.02445244789 -4.49979019165,1.66152155399,-3.0118637085 -4.50179195404,1.66052210331,-3.003064394 -4.50679636002,1.65852332115,-2.98449921608 -4.52280712128,1.66052591801,-2.97490477562 -4.52681159973,1.65852701664,-2.95632767677 -4.53681850433,1.65852880478,-2.94273209572 -4.54682636261,1.65853071213,-2.92913675308 -4.54982995987,1.65553200245,-2.90956878662 -4.54682970047,1.65253221989,-2.8967859745 -4.56784296036,1.65653526783,-2.89117598534 -4.56484365463,1.65153598785,-2.86761212349 -4.57785320282,1.65253829956,-2.85601687431 -4.5868601799,1.65254032612,-2.84142994881 -4.59586715698,1.65254223347,-2.8268430233 -4.59987211227,1.64954376221,-2.80925369263 -4.60587692261,1.65054488182,-2.80246925354 -4.60687971115,1.64654636383,-2.78190374374 -4.61788845062,1.64754855633,-2.769302845 -4.62589550018,1.64655053616,-2.75372552872 -4.63690376282,1.64755284786,-2.74112462997 -4.63790750504,1.6445543766,-2.7215423584 -4.66092157364,1.64955770969,-2.71594643593 -4.64591598511,1.64155721664,-2.69617033005 -4.65492343903,1.64155948162,-2.68158626556 -4.67293548584,1.64456236362,-2.6729888916 -4.66893720627,1.64056360722,-2.65041160583 -4.67694473267,1.63956594467,-2.63483715057 -4.6889538765,1.64056837559,-2.6222486496 -4.68395328522,1.63656902313,-2.60945749283 -4.69796323776,1.6385717392,-2.59787249565 -4.71497535706,1.6415746212,-2.58828020096 -4.71597957611,1.63857650757,-2.56870675087 -4.72298622131,1.63857877254,-2.55410027504 -4.73199415207,1.63858115673,-2.53951787949 -4.73600006104,1.63658344746,-2.52194023132 -4.73700237274,1.6355843544,-2.51313996315 -4.74901199341,1.63658714294,-2.5005505085 -4.74601459503,1.63258910179,-2.4789788723 -4.7580242157,1.63359165192,-2.46638941765 -4.76903343201,1.63359439373,-2.45280981064 -4.76203489304,1.62859630585,-2.42923879623 -4.78104782104,1.632599473,-2.42064237595 -4.78505134583,1.6326007843,-2.41285705566 -4.77505207062,1.62560248375,-2.38827824593 -4.78806209564,1.62760531902,-2.37667870522 -4.8050737381,1.63060843945,-2.36610031128 -4.80007600784,1.62561058998,-2.34451723099 -4.80708360672,1.62461340427,-2.3289372921 -4.81609296799,1.62561607361,-2.31435704231 -4.82009649277,1.62561738491,-2.30755114555 -4.82210254669,1.62262010574,-2.28898286819 -4.83211135864,1.6236230135,-2.27539229393 -4.83811855316,1.62262570858,-2.2598028183 -4.84112548828,1.62162852287,-2.24222517014 -4.8591375351,1.6246316433,-2.23263096809 -4.84113359451,1.61663246155,-2.21385765076 -4.85214281082,1.61863553524,-2.20027780533 -4.87315654755,1.62263870239,-2.19266939163 -4.86615896225,1.61764132977,-2.17010140419 -4.86816549301,1.61564421654,-2.15251755714 -4.88617801666,1.61964762211,-2.14194178581 -4.88518285751,1.61665034294,-2.12335038185 -4.88418531418,1.6146517992,-2.11356139183 -4.9051990509,1.61965513229,-2.10496902466 -4.90420484543,1.61665821075,-2.08540177345 -4.91321372986,1.61666119099,-2.07180070877 -4.92222261429,1.61766433716,-2.05722093582 -4.90722370148,1.60966730118,-2.03165483475 -4.92923736572,1.61567044258,-2.02404522896 -4.94224500656,1.6186722517,-2.02025866508 -4.92524528503,1.60967540741,-1.99370038509 -4.93225336075,1.60967850685,-1.97910344601 -4.95126628876,1.61368179321,-1.96950650215 -4.94026947021,1.6076849699,-1.94594323635 -4.94427680969,1.60668838024,-1.9293640852 -4.95928859711,1.60969185829,-1.91777336597 -4.94928836823,1.60469341278,-1.90399837494 -4.96129894257,1.6066968441,-1.89140236378 -4.97330951691,1.60870015621,-1.87880539894 -4.9693145752,1.60470342636,-1.85922396183 -4.97232246399,1.60370719433,-1.84166061878 -4.98633337021,1.60571038723,-1.83005809784 -4.97333288193,1.60071229935,-1.81528615952 -4.98034191132,1.60071575642,-1.80069100857 -4.99735403061,1.6047192812,-1.78911340237 -4.99536037445,1.6017229557,-1.77053177357 -4.99436759949,1.59872663021,-1.75196015835 -5.0133805275,1.60273015499,-1.74137449265 -5.01038599014,1.59973371029,-1.72278678417 -5.01539134979,1.60073554516,-1.71598982811 -5.02340078354,1.60173916817,-1.70140230656 -5.01640605927,1.59674310684,-1.68083071709 -5.03041744232,1.5997467041,-1.66824626923 -5.04642963409,1.60275018215,-1.65665352345 -5.02643156052,1.59375464916,-1.63109707832 -5.03344106674,1.59475815296,-1.616502285 -5.04544782639,1.59775984287,-1.61269056797 -5.03945446014,1.5937640667,-1.59213328362 -5.04446315765,1.59376788139,-1.57654643059 -5.05947494507,1.59677147865,-1.56494295597 -5.05048036575,1.59177589417,-1.543389678 -5.05648946762,1.59177982807,-1.52781116962 -5.07150173187,1.59478330612,-1.51620590687 -5.06450366974,1.59178555012,-1.50541222095 -5.06651210785,1.59078979492,-1.48785114288 -5.08852529526,1.59579312801,-1.47824811935 -5.07753133774,1.59079790115,-1.45668721199 -5.08254051208,1.59080183506,-1.44110143185 -5.09755277634,1.59380567074,-1.42851567268 -5.09455537796,1.59180772305,-1.41970765591 -5.09456348419,1.58981192112,-1.40213441849 -5.10357379913,1.59081602097,-1.3875528574 -5.10258197784,1.58882045746,-1.36997377872 -5.1165933609,1.59182417393,-1.35737788677 -5.11660194397,1.59082865715,-1.33980596066 -5.1106095314,1.5868332386,-1.32121932507 -5.12261629105,1.58983504772,-1.31544172764 -5.12862586975,1.59083914757,-1.30083870888 -5.12663459778,1.58784389496,-1.28228020668 -5.13264417648,1.5888479948,-1.26767742634 -5.14365577698,1.59085214138,-1.25310599804 -5.14666509628,1.5898566246,-1.23653197289 -5.13566684723,1.58585929871,-1.22572791576 -5.14567804337,1.58786344528,-1.21114969254 -5.14668655396,1.58586800098,-1.19456505775 -5.15169668198,1.58587241173,-1.17898035049 -5.15370607376,1.58587706089,-1.16240179539 -5.15971660614,1.58588147163,-1.14682304859 -5.16272640228,1.5858861208,-1.13025081158 -5.17373275757,1.5888876915,-1.12543439865 -5.16574048996,1.58389306068,-1.10587286949 -5.17375087738,1.58589732647,-1.09128046036 -5.17776155472,1.58590209484,-1.07471418381 -5.17376947403,1.58290708065,-1.05712914467 -5.183781147,1.58491146564,-1.04254710674 -5.19679307938,1.58791553974,-1.0289555788 -5.18579530716,1.58391857147,-1.01816511154 -5.18280363083,1.5809237957,-1.00058805943 -5.20181703568,1.58592760563,-0.988001585007 -5.1938252449,1.58293306828,-0.969423949718 -5.19583511353,1.58193802834,-0.952848851681 -5.19984531403,1.58194279671,-0.937259435654 -5.19385385513,1.57894837856,-0.91869533062 -5.19785928726,1.57995033264,-0.911885797977 -5.21287155151,1.58295452595,-0.898299157619 -5.20488023758,1.57996022701,-0.879727423191 -5.20989084244,1.57996499538,-0.864142894745 -5.22290325165,1.58296942711,-0.849568963051 -5.21491098404,1.57997500896,-0.831975400448 -5.22491788864,1.58197700977,-0.825191020966 -5.23192930222,1.58298182487,-0.809613764286 -5.23093891144,1.58198714256,-0.793027102947 -5.22694826126,1.57999265194,-0.775453388691 -5.23896026611,1.58299708366,-0.760871231556 -5.2289686203,1.57800328732,-0.74229991436 -5.233979702,1.57900822163,-0.72671431303 -5.24298620224,1.58101022243,-0.719921708107 -5.23899555206,1.57901573181,-0.703326046467 -5.24200630188,1.57902109623,-0.686757266521 -5.2480173111,1.58002591133,-0.671174526215 -5.24502754211,1.57803153992,-0.654584407806 -5.2390370369,1.5750374794,-0.637009620667 -5.2580499649,1.58104157448,-0.62342107296 -5.24305343628,1.57504558563,-0.61264359951 -5.25106525421,1.57705044746,-0.597067117691 -5.26107645035,1.58005511761,-0.582471191883 -5.25208616257,1.5760614872,-0.564889788628 -5.25509691238,1.57606697083,-0.548321723938 -5.26310920715,1.57807195187,-0.53274333477 -5.26011896133,1.57607781887,-0.516157507896 -5.26112413406,1.57608044147,-0.50835943222 -5.26913642883,1.57808542252,-0.492779999971 -5.26214647293,1.57509183884,-0.475209236145 -5.27115869522,1.57709681988,-0.459631800652 -5.27516937256,1.57810211182,-0.444040566683 -5.26617956161,1.57410883904,-0.426467210054 -5.27918672562,1.57811045647,-0.419673442841 -5.28119707108,1.57811594009,-0.404076993465 -5.27120733261,1.57412278652,-0.386503368616 -5.26721858978,1.57212913036,-0.368944704533 -5.27923059464,1.5751336813,-0.35434576869 -5.26524019241,1.57014095783,-0.336767315865 -5.27525234222,1.5731459856,-0.321188151836 -5.29226016998,1.57814729214,-0.314396083355 -5.27126932144,1.57115542889,-0.29583221674 -5.27928161621,1.57316064835,-0.280247867107 -5.29029321671,1.57616519928,-0.265642464161 -5.28430461884,1.57417213917,-0.24808332324 -5.27831506729,1.5711786747,-0.231500640512 -5.2923283577,1.57518339157,-0.215922832489 -5.28033256531,1.57118761539,-0.207131445408 -5.27934408188,1.57019388676,-0.190557330847 -5.29435634613,1.57519817352,-0.1759532094 -5.27636766434,1.56920659542,-0.157408609986 -5.28137922287,1.57021200657,-0.141817077994 -5.29339170456,1.57421708107,-0.126231893897 -5.28140211105,1.5692243576,-0.10964782536 -5.2764081955,1.56722807884,-0.100869990885 -5.30042123795,1.57523155212,-0.086268030107 -5.28543233871,1.57023966312,-0.0687087699771 -5.28644371033,1.57024550438,-0.0531124733388 -5.2974562645,1.57325053215,-0.0375222153962 -5.2764673233,1.56625938416,-0.0199639704078 -5.28647375107,1.5692615509,-0.0121708363295 -5.2954864502,1.57226657867,0.00342227960937 -5.28849744797,1.56927382946,0.0199964717031 -5.28450965881,1.56828069687,0.036569006741 -5.29652261734,1.57228553295,0.0521632879972 -5.28553390503,1.56829333305,0.0687361061573 -5.28654623032,1.56829977036,0.0853069797158 -5.30355358124,1.57430112362,0.0931057110429 -5.29056501389,1.56930911541,0.109676413238 -5.27757692337,1.56531715393,0.126245319843 -5.30058956146,1.57232069969,0.141846612096 -5.27460098267,1.56433057785,0.15840986371 -5.28061389923,1.56633651257,0.174982234836 -5.29962682724,1.57234048843,0.190587177873 -5.2766327858,1.56434690952,0.199348002672 -5.28064441681,1.56635272503,0.214945927262 -5.28765726089,1.56835865974,0.231520995498 -5.27666950226,1.56436645985,0.24710854888 -5.2706823349,1.56337404251,0.263673752546 -5.28569507599,1.56737875938,0.280256986618 -5.27170705795,1.56338715553,0.295839130878 -5.27571392059,1.5643903017,0.304615437984 -5.28472661972,1.56739544868,0.320220917463 -5.27673959732,1.56540346146,0.336782336235 -5.2667517662,1.56241130829,0.352365165949 -5.27576446533,1.56541705132,0.368946969509 -5.27177810669,1.56442463398,0.385511666536 -5.26178407669,1.56142938137,0.393294632435 -5.2667965889,1.56343519688,0.408897221088 -5.26480960846,1.56244242191,0.425463736057 -5.27482271194,1.56644797325,0.442050904036 -5.27983570099,1.56745421886,0.458630412817 -5.26384925842,1.56346333027,0.474197387695 -5.26286125183,1.5634701252,0.489790976048 -5.26286745071,1.56347346306,0.497588694096 -5.26988124847,1.56547939777,0.514173328876 -5.26489448547,1.56448745728,0.530733764172 -5.25190782547,1.56049621105,0.546301007271 -5.26492071152,1.56450128555,0.562900722027 -5.25793409348,1.56350910664,0.578480839729 -5.25694131851,1.56351315975,0.587251245975 -5.25195407867,1.56152069569,0.602834701538 -5.24696731567,1.56052839756,0.618417859077 -5.24898052216,1.56153523922,0.634993672371 -5.25399398804,1.56354165077,0.651578247547 -5.24500751495,1.56155002117,0.667149841785 -5.23902130127,1.56055796146,0.682729005814 -5.24602794647,1.56256055832,0.691522061825 -5.24104118347,1.5615683794,0.707103848457 -5.24505472183,1.56357491016,0.723687589169 -5.24506855011,1.56358230114,0.740259468555 -5.24108171463,1.56358993053,0.755844175816 -5.23409557343,1.56159818172,0.771418273449 -5.2261095047,1.55960667133,0.786988317966 -5.23511600494,1.56260883808,0.795792341232 -5.22912979126,1.56161701679,0.81136906147 -5.23114395142,1.56262397766,0.827948510647 -5.22315740585,1.56063258648,0.843517124653 -5.22317075729,1.56163954735,0.859114944935 -5.22118520737,1.56164741516,0.875680208206 -5.24319124222,1.56864774227,0.886488616467 -5.25020551682,1.57165420055,0.904066085815 -5.23821973801,1.56866323948,0.918644070625 -5.26623296738,1.5786665678,0.939233720303 -5.22624778748,1.56667983532,0.949795365334 -5.22426176071,1.5666873455,0.965386986732 -5.24927473068,1.57569110394,0.985970377922 -5.24328136444,1.57369554043,0.992770373821 -5.25129652023,1.57770204544,1.01133370399 -4.67899894714,1.57066786289,2.62282419205 -4.68201541901,1.57467591763,2.64241695404 -4.68103265762,1.57668530941,2.66098451614 -4.68804836273,1.58269250393,2.68258595467 -4.67306852341,1.57970476151,2.69413709641 -4.65808773041,1.57771658897,2.70470929146 -4.66609382629,1.58171904087,2.71752381325 -4.65111351013,1.57973086834,2.72809553146 -4.65313005447,1.58273935318,2.7476837635 -4.63515138626,1.57975208759,2.75723838806 -4.62516927719,1.57876265049,2.76982784271 -4.61818790436,1.57977342606,2.78539037704 -4.60619783401,1.57677984238,2.7871928215 -4.60421562195,1.57878911495,2.80477619171 -4.59423494339,1.57880020142,2.81834340096 -4.58125448227,1.57681179047,2.82991433144 -4.58027172089,1.57982110977,2.84849143028 -4.57828903198,1.58183038235,2.86607766151 -4.55831003189,1.57784354687,2.87364172935 -4.55431890488,1.57784867287,2.88043808937 -4.55733585358,1.58185696602,2.90102815628 -4.54035568237,1.57886910439,2.90960860252 -4.53037548065,1.57888042927,2.92317509651 -4.52939319611,1.58188962936,2.94175720215 -4.51741218567,1.57990098,2.9533393383 -4.51342105865,1.579906106,2.96013617516 -4.50843954086,1.58191633224,2.97670793533 -4.49845933914,1.58192765713,2.99027490616 -4.49547719955,1.58393740654,3.00785446167 -4.485496521,1.58294820786,3.02044272423 -4.46851682663,1.57996070385,3.02901697159 -4.45853662491,1.57997202873,3.04258370399 -4.46854305267,1.58597445488,3.0583896637 -4.44356584549,1.57998859882,3.06195425987 -4.4405837059,1.58199834824,3.07953619957 -4.4286031723,1.58100986481,3.09111595154 -4.42562150955,1.58301961422,3.10869956017 -4.41464090347,1.58303105831,3.12127304077 -4.41565847397,1.58703994751,3.14185428619 -4.39867115021,1.58204817772,3.14062952995 -4.39568901062,1.58505785465,3.15821576118 -4.39070749283,1.58606815338,3.17479419708 -4.37072849274,1.58208096027,3.18037939072 -4.36374807358,1.58309185505,3.19594955444 -4.36976528168,1.59010004997,3.2205286026 -4.34478712082,1.58311390877,3.2221186161 -4.34479570389,1.58511841297,3.23191571236 -4.34081506729,1.58812904358,3.25047159195 -4.32483577728,1.58514142036,3.25905060768 -4.30685758591,1.5821543932,3.26661896706 -4.31287431717,1.58816242218,3.29120612144 -4.2938952446,1.58517515659,3.29679894447 -4.28990507126,1.58518075943,3.30457782745 -4.28592443466,1.58819103241,3.32215714455 -4.26894521713,1.5852035284,3.32973814011 -4.26296472549,1.58621442318,3.3463075161 -4.26698207855,1.59222280979,3.36989331245 -4.23700523376,1.58423817158,3.3674697876 -4.2280254364,1.58524906635,3.38105344772 -4.24103212357,1.59225130081,3.40184164047 -4.21905374527,1.58726501465,3.40542030334 -4.2080745697,1.58727669716,3.4179930687 -4.19909524918,1.58828830719,3.43255805969 -4.18311595917,1.58530056477,3.44014906883 -4.18013429642,1.58831048012,3.45873141289 -4.18115329742,1.59332001209,3.4813015461 -4.16416549683,1.58832812309,3.47808909416 -4.15418481827,1.58833932877,3.49067783356 -4.14620494843,1.59035027027,3.50526070595 -4.12822723389,1.58636343479,3.51183605194 -4.11924743652,1.58737492561,3.52640223503 -4.10826826096,1.58738672733,3.53897500038 -4.09628868103,1.5863982439,3.54956936836 -4.09829759598,1.59040272236,3.56235456467 -4.08831787109,1.59041440487,3.57592511177 -4.07633924484,1.5904263258,3.58750081062 -4.0653591156,1.59043776989,3.59909296036 -4.06737709045,1.59544694424,3.62267422676 -4.04040145874,1.58846187592,3.62124609947 -4.0384106636,1.59046685696,3.63004398346 -4.03742980957,1.59447693825,3.6516160965 -4.01545333862,1.59049117565,3.65517425537 -4.00447416306,1.59050273895,3.66676616669 -4.00649166107,1.59551167488,3.69035506248 -3.98651480675,1.59152543545,3.69492554665 -3.9795255661,1.59153163433,3.69971489906 -3.97654461861,1.59454190731,3.71929597855 -3.96156620979,1.59355437756,3.72787618637 -3.95158720016,1.59356606007,3.7414495945 -3.94560670853,1.59657680988,3.75803732872 -3.9296298027,1.59458994865,3.76659965515 -3.92065048218,1.59560143948,3.78117275238 -3.91666007042,1.59660685062,3.78797745705 -3.89668369293,1.5926207304,3.79254150391 -3.89070320129,1.59463143349,3.8091313839 -3.88872265816,1.59964168072,3.8307030201 -3.86474633217,1.59365606308,3.83028435707 -3.85576725006,1.59466767311,3.84485936165 -3.84978675842,1.59767818451,3.8614525795 -3.85179591179,1.60068261623,3.87524008751 -3.83181905746,1.59769630432,3.87881755829 -3.82383966446,1.59970784187,3.89439487457 -3.81486082077,1.6007193327,3.90897250175 -3.80588150024,1.60173082352,3.92355108261 -3.79590272903,1.60274255276,3.93712997437 -3.77792477608,1.5997556448,3.94172215462 -3.7759346962,1.60176086426,3.95151329041 -3.76795530319,1.60377216339,3.96709418297 -3.74997925758,1.60078597069,3.97365045547 -3.73800086975,1.60079824924,3.98522806168 -3.73002099991,1.60280907154,3.99982738495 -3.7130446434,1.60082280636,4.00738286972 -3.71505331993,1.6048271656,4.02118206024 -3.70807385445,1.60783815384,4.03776741028 -3.68509864807,1.60285294056,4.03833150864 -3.67311954498,1.60286474228,4.04892635345 -3.66214108467,1.60287666321,4.0615067482 -3.64916396141,1.60288953781,4.07306718826 -3.6391851902,1.60490143299,4.08664989471 -3.63319611549,1.60490751266,4.09243965149 -3.62121748924,1.60491931438,4.10303544998 -3.61423897743,1.60793101788,4.12159252167 -3.59926104546,1.60594367981,4.12918233871 -3.5902826786,1.60795545578,4.14475297928 -3.57530498505,1.60696816444,4.15234279633 -3.57432389259,1.61197793484,4.17593479156 -3.55233955383,1.60498785973,4.16470003128 -3.53936195374,1.6050003767,4.17527770996 -3.53938055038,1.6110098362,4.1998758316 -3.51740527153,1.60702443123,4.2004442215 -3.50742650032,1.60803604126,4.21403121948 -3.49944782257,1.61104762554,4.23060941696 -3.48945951462,1.60905444622,4.23140335083 -3.47748231888,1.60906708241,4.24396944046 -3.46550440788,1.61007940769,4.25555181503 -3.44652819633,1.60709321499,4.25912475586 -3.43554997444,1.60810518265,4.27170991898 -3.43457007408,1.61411547661,4.29728651047 -3.41259455681,1.61012983322,4.29686307907 -3.40660572052,1.6101360321,4.30265426636 -3.4026260376,1.61514663696,4.324239254 -3.38264989853,1.61116051674,4.32582092285 -3.37167239189,1.61217284203,4.33939361572 -3.36069393158,1.61418473721,4.3519821167 -3.34371757507,1.6121982336,4.35755968094 -3.32774162292,1.61121165752,4.36512613297 -3.3317501545,1.61621582508,4.38391876221 -3.31277370453,1.61322927475,4.38551616669 -3.29879713058,1.61324250698,4.39607715607 -3.29381775856,1.61725318432,4.41666698456 -3.27784109116,1.61626636982,4.42324829102 -3.26386427879,1.61627924442,4.43282461166 -3.26587414742,1.62128412724,4.45060062408 -3.24689769745,1.61829769611,4.45219564438 -3.23092126846,1.61731088161,4.45877599716 -3.22294259071,1.6203224659,4.47635650635 -3.19996833801,1.61533737183,4.47392606735 -3.18799138069,1.61634981632,4.48649930954 -3.18801093102,1.62335991859,4.51508522034 -3.17702317238,1.62136685848,4.513879776 -3.16504597664,1.6223795414,4.5264544487 -3.15006923676,1.622392416,4.53404092789 -3.12809443474,1.61740708351,4.53261137009 -3.12111544609,1.62141811848,4.55120372772 -3.11413764954,1.62542998791,4.57177066803 -3.10115003586,1.62243723869,4.5665769577 -3.09317278862,1.62544941902,4.58613872528 -3.08119487762,1.62646150589,4.5977306366 -3.05822134018,1.62247669697,4.59529018402 -3.04824304581,1.62448847294,4.60988235474 -3.04226374626,1.6284995079,4.63047552109 -3.0212893486,1.62551403046,4.63004636765 -3.01530051231,1.62552011013,4.63584327698 -3.0073223114,1.62953174114,4.6544251442 -2.98434853554,1.62454664707,4.65099287033 -2.97537016869,1.62755835056,4.6675825119 -2.96739196777,1.63156998158,4.68616819382 -2.95041656494,1.63058376312,4.69173908234 -2.94143891335,1.63359570503,4.70931863785 -2.93545126915,1.63460230827,4.71709156036 -2.90347886086,1.62361884117,4.69767427444 -2.90249943733,1.63162899017,4.7282538414 -2.88652348518,1.63164246082,4.73483228683 -2.86954712868,1.62965559959,4.73842716217 -2.87356638908,1.64066505432,4.77800512314 -2.85459160805,1.63867938519,4.78057289124 -2.83860516548,1.63368725777,4.76937675476 -2.82962799072,1.63669931889,4.78795146942 -2.81365203857,1.63671278954,4.79452991486 -2.80267524719,1.63872528076,4.81010198593 -2.7956969738,1.64373672009,4.83168697357 -2.77672076225,1.64075016975,4.83128833771 -2.77273225784,1.64275622368,4.84207105637 -2.75075864792,1.63877093792,4.83864450455 -2.78276991844,1.66877436638,4.92824172974 -2.75979590416,1.6637891531,4.9228219986 -2.76481437683,1.67679810524,4.96641159058 -2.80582308769,1.7127995491,5.07401752472 -2.78285002708,1.70881462097,5.07058191299 -2.77686166763,1.70982098579,5.07836914062 -2.7668838501,1.71383285522,5.09596300125 -2.75290775299,1.71484589577,5.10754299164 -2.73893165588,1.7158588171,5.1191239357 -2.72395610809,1.71687221527,5.12969589233 -2.7029812336,1.71288633347,5.1272854805 -2.70099210739,1.71789205074,5.14307069778 -2.68701601028,1.71890485287,5.15465354919 -2.66904115677,1.71791887283,5.15922832489 -2.65506482124,1.71893179417,5.17081165314 -2.6420879364,1.72094428539,5.18340539932 -2.62211418152,1.71795880795,5.18497085571 -2.61013770103,1.72097146511,5.20055484772 -2.60314965248,1.72197782993,5.20634698868 -2.58417510986,1.71999192238,5.20892190933 -2.56620025635,1.71900582314,5.21349620819 -2.54822492599,1.71701931953,5.21609020233 -2.5322496891,1.71803295612,5.22466468811 -2.51527500153,1.71704673767,5.23123836517 -2.50129938126,1.71905982494,5.24381446838 -2.49630999565,1.72106564045,5.25261974335 -2.48133444786,1.72207891941,5.26319646835 -2.46235942841,1.7190926075,5.26378774643 -2.44738388062,1.7211060524,5.27436494827 -2.43040966988,1.72111999989,5.28192949295 -2.41643309593,1.72213256359,5.2925286293 -2.40345740318,1.72514557838,5.30810070038 -2.39546942711,1.7251522541,5.31189441681 -2.37449622154,1.72216689587,5.31046104431 -2.35952091217,1.72318029404,5.32103967667 -2.35754108429,1.73419034481,5.35864257812 -2.33756732941,1.73220479488,5.35921192169 -2.33758711815,1.74421477318,5.40280866623 -2.34659457207,1.75821781158,5.44560718536 -2.33861780167,1.76622986794,5.47418117523 -2.32164263725,1.76624345779,5.48076534271 -2.30366826057,1.76525747776,5.48633766174 -2.28669238091,1.76527059078,5.49093961716 -2.26771879196,1.76328492165,5.49450731277 -2.25174379349,1.76529836655,5.50408649445 -2.2387573719,1.7603058815,5.4958820343 -2.21578383446,1.75532066822,5.48746681213 -2.19281101227,1.75033557415,5.48004102707 -2.1778357029,1.75234878063,5.49162244797 -2.16585946083,1.75736153126,5.51120138168 -2.1418864727,1.75037646294,5.4997844696 -2.1219124794,1.74839067459,5.49836778641 -2.11292600632,1.74839794636,5.50214385986 -2.09894967079,1.75041055679,5.5147395134 -2.07797694206,1.74742531776,5.51230859756 -2.05900239944,1.74643921852,5.51289463043 -2.04402780533,1.74845278263,5.52646207809 -2.02605295181,1.74746632576,5.52905321121 -2.01506662369,1.74547386169,5.5268330574 -1.99909126759,1.74648702145,5.53442764282 -1.98511648178,1.74950039387,5.55099582672 -1.96514284611,1.74751460552,5.54957437515 -1.94416832924,1.7435284853,5.54217529297 -1.93519151211,1.75054061413,5.57175540924 -1.9102191925,1.74355578423,5.55533647537 -1.90523171425,1.74756228924,5.57110977173 -1.88525760174,1.74457633495,5.56769990921 -1.8692830801,1.74658989906,5.57827377319 -1.85130882263,1.74660372734,5.58185529709 -1.83833241463,1.74961614609,5.59845256805 -1.81336057186,1.7426315546,5.58202409744 -1.79838550091,1.74464476109,5.59460687637 -1.78939819336,1.74465155602,5.5954041481 -1.77242422104,1.74566531181,5.603972435 -1.75345015526,1.74367928505,5.60355901718 -1.73747563362,1.74569272995,5.61413526535 -1.71850144863,1.74370670319,5.61372089386 -1.69852745533,1.74072062969,5.60931110382 -1.69054067135,1.74172759056,5.61608982086 -1.67256569862,1.74074089527,5.61668920517 -1.65359306335,1.74075555801,5.62024641037 -1.63861691952,1.74176812172,5.6298532486 -1.61664426327,1.73678290844,5.62042760849 -1.60067009926,1.73979651928,5.63199949265 -1.58869373798,1.74580872059,5.65459299088 -1.57170915604,1.73581731319,5.62837934494 -1.55673420429,1.7388304472,5.64196300507 -1.54075992107,1.74184405804,5.65353775024 -1.52078640461,1.73885810375,5.64912033081 -1.50181293488,1.73687231541,5.64969444275 -1.48683786392,1.74088525772,5.66328144073 -1.46386516094,1.73389995098,5.64686441422 -1.45887649059,1.73790574074,5.66166734695 -1.44090354443,1.73892009258,5.66822910309 -1.42092943192,1.73493373394,5.66082429886 -1.40295529366,1.73394751549,5.66340780258 -1.38798046112,1.73796057701,5.6779923439 -1.36400830746,1.72997546196,5.65657138824 -1.35003387928,1.73598885536,5.67814159393 -1.34304630756,1.73799526691,5.68793296814 -1.32107317448,1.73200964928,5.67252111435 -1.30209958553,1.7300235033,5.67110157013 -1.28912436962,1.73703634739,5.69568347931 -1.27014994621,1.73404991627,5.69127988815 -1.25017738342,1.73206436634,5.68784713745 -1.24418962002,1.73607063293,5.70263910294 -1.22121739388,1.7290854454,5.68321657181 -1.20624160767,1.73209810257,5.69581794739 -1.18926799297,1.73411178589,5.70538902283 -1.16729569435,1.72812640667,5.68996477127 -1.15332007408,1.73313903809,5.70955896378 -1.13734531403,1.73615205288,5.7201499939 -1.12435984612,1.73015987873,5.7029337883 -1.10338675976,1.72417414188,5.68951749802 -1.08841252327,1.73018729687,5.7090921402 -1.06943821907,1.72720086575,5.70268917084 -1.05046570301,1.72621524334,5.70425128937 -1.03349137306,1.72722864151,5.71083831787 -1.02450442314,1.72723543644,5.71163129807 -1.00553107262,1.72524917126,5.7092089653 -0.989555776119,1.72726213932,5.71781158447 -0.969583392143,1.72527635098,5.71237802505 -0.951609551907,1.72429001331,5.71396255493 -0.93463498354,1.72530317307,5.71955442429 -0.915661513805,1.72331702709,5.71513795853 -0.906674563885,1.72332382202,5.71592998505 -0.888701319695,1.7233376503,5.72050285339 -0.870727360249,1.72335112095,5.72109079361 -0.851754486561,1.72236526012,5.71966171265 -0.834780335426,1.72337853909,5.72724819183 -0.813807547092,1.71739280224,5.70882844925 -0.795833349228,1.71640610695,5.70742082596 -0.789845585823,1.72241234779,5.7292137146 -0.76987272501,1.71842634678,5.71779155731 -0.753897607327,1.72143912315,5.72939014435 -0.734925031662,1.72045326233,5.72895669937 -0.716950893402,1.71946668625,5.72754812241 -0.697977244854,1.71648025513,5.71913671494 -0.682003259659,1.72249352932,5.73871564865 -0.670017838478,1.71550107002,5.71849489212 -0.653043687344,1.71751439571,5.72708177567 -0.636068880558,1.71852731705,5.73068237305 -0.617095470428,1.71554100513,5.72326421738 -0.60012203455,1.7195545435,5.73783826828 -0.583147644997,1.72156763077,5.74543046951 -0.572161614895,1.7165749073,5.72821760178 -0.55318826437,1.71258866787,5.71880149841 -0.537214338779,1.7206017971,5.74437761307 -0.518240392208,1.71461522579,5.72897338867 -0.501266241074,1.717628479,5.7395606041 -0.483292907476,1.71964204311,5.74413776398 -0.464319318533,1.71465563774,5.73072624207 -0.455333173275,1.71666264534,5.73850488663 -0.437359124422,1.71567583084,5.73509645462 -0.41938585043,1.71668946743,5.74067258835 -0.402411222458,1.71870231628,5.74727058411 -0.383438497782,1.71671628952,5.7418422699 -0.365464299917,1.71472942829,5.73543787003 -0.356477886438,1.71673631668,5.74122142792 -0.338503926992,1.71474957466,5.73781204224 -0.320529967546,1.71376276016,5.73340272903 -0.302556186914,1.71277618408,5.7319893837 -0.284583449364,1.71778988838,5.7475566864 -0.266609311104,1.71480309963,5.74015045166 -0.248635575175,1.71481633186,5.73873662949 -0.239649027586,1.71682310104,5.74452352524 -0.220675975084,1.70983684063,5.72610282898 -0.202702328563,1.70985019207,5.72568750381 -0.185727521777,1.71186280251,5.73228979111 -0.166755259037,1.7118768692,5.72985267639 -0.14878153801,1.70989012718,5.72643947601 -0.130807965994,1.71090340614,5.72802257538 -0.122819900513,1.71390938759,5.7358341217 -0.104846224189,1.71292281151,5.73441982269 -0.0868726894259,1.71493601799,5.74000310898 -0.0679002851248,1.70994997025,5.72456979752 -0.0499267168343,1.71096313,5.7281537056 -0.0329517051578,1.71497583389,5.73875951767 -0.0139794861898,1.7119897604,5.72932291031 -0.00499267550185,1.71199631691,5.73111534119 --0.00199696864001,1.69800150394,5.48895168304 --0.0189711917192,1.69701445103,5.48654270172 --0.035945456475,1.69902729988,5.49113416672 --0.0449318252504,1.69903409481,5.49091815948 --0.0619059875607,1.69704711437,5.48450756073 --0.0798788368702,1.700060606,5.49207687378 --0.096853017807,1.69907355309,5.4876666069 --0.113827183843,1.69808638096,5.48425674438 --0.130801528692,1.69909918308,5.48785066605 --0.147775694728,1.69911205769,5.48443984985 --0.156762063503,1.69911885262,5.48422384262 --0.173736155033,1.69713175297,5.47981262207 --0.190710186958,1.69614470005,5.47439956665 --0.208683088422,1.69715821743,5.47797012329 --0.224658295512,1.69417047501,5.46657514572 --0.242631003261,1.69418406487,5.46614170074 --0.259605914354,1.69919645786,5.47774648666 --0.268592059612,1.69720339775,5.47352552414 --0.285566151142,1.69721615314,5.47011375427 --0.302539855242,1.69422924519,5.46169471741 --0.319514513016,1.69724178314,5.46729469299 --0.337487369776,1.69725525379,5.46786403656 --0.353462219238,1.69426763058,5.45546197891 --0.362448841333,1.69527423382,5.45825004578 --0.379422843456,1.69428706169,5.45483732224 --0.397395968437,1.69630026817,5.45841169357 --0.414369791746,1.69531321526,5.45299482346 --0.431344777346,1.69732558727,5.45960044861 --0.447318911552,1.69233834743,5.44218444824 --0.466292053461,1.69935154915,5.45976543427 --0.475278377533,1.69935822487,5.45854759216 --0.491253465414,1.69737052917,5.45114994049 --0.508226931095,1.69538354874,5.44272565842 --0.525201380253,1.69539618492,5.44332122803 --0.542174518108,1.69340920448,5.43289089203 --0.560148835182,1.69742190838,5.44448947906 --0.577122449875,1.69643473625,5.43806838989 --0.586109578609,1.69844102859,5.44286584854 --0.603083431721,1.69745397568,5.43844985962 --0.618058800697,1.6934658289,5.42305183411 --0.637031316757,1.69647932053,5.43062019348 --0.654005885124,1.69749176502,5.4312171936 --0.670979738235,1.69750452042,5.42680072784 --0.687953650951,1.69651722908,5.42238378525 --0.698940217495,1.70352387428,5.44218301773 --0.713914096355,1.69653654099,5.41875505447 --0.73288744688,1.70154953003,5.4293384552 --0.749862134457,1.70256197453,5.42993831635 --0.766836345196,1.7025744915,5.42752933502 --0.783809959888,1.70158731937,5.42110586166 --0.79279756546,1.70359325409,5.42691373825 --0.81177008152,1.70660662651,5.43148183823 --0.82874417305,1.7066192627,5.42806959152 --0.847717583179,1.70963215828,5.43665456772 --0.862692654133,1.70664417744,5.42224931717 --0.8816665411,1.71065700054,5.43284368515 --0.900639533997,1.71367001534,5.43842077255 --0.905627787113,1.70667552948,5.41621780396 --0.928599536419,1.71768939495,5.4447927475 --0.944573819637,1.71470177174,5.43437814713 --0.960549235344,1.71471369267,5.42898368835 --0.978522002697,1.71472680569,5.42554998398 --0.994497299194,1.71373867989,5.42015504837 --1.01047122478,1.7117511034,5.40873384476 --1.0194580555,1.7117575407,5.40852355957 --1.03843224049,1.7167699337,5.41812419891 --1.05640554428,1.7167828083,5.41670036316 --1.07338023186,1.71779501438,5.41429615021 --1.09435212612,1.72280859947,5.42586421967 --1.10732805729,1.7168200016,5.40446424484 --1.11931419373,1.72282671928,5.419257164 --1.13628816605,1.72183918953,5.41383981705 --1.15526127815,1.72485208511,5.41742038727 --1.16923666,1.71986377239,5.40001249313 --1.18921029568,1.72487652302,5.41060638428 --1.20718359947,1.72588932514,5.40818119049 --1.22515797615,1.72790145874,5.40977811813 --1.23414492607,1.72890782356,5.40957117081 --1.25111925602,1.72892010212,5.40515995026 --1.27009224892,1.72993290424,5.40673494339 --1.28906619549,1.73394536972,5.41132736206 --1.30404126644,1.73095715046,5.39891910553 --1.32201528549,1.73196947575,5.3985080719 --1.34098827839,1.73398244381,5.39908123016 --1.34797620773,1.7319880724,5.39188194275 --1.36894893646,1.73700106144,5.40146112442 --1.38692343235,1.73901331425,5.40205860138 --1.40189862251,1.7370249033,5.3906545639 --1.42586994171,1.74503850937,5.40922403336 --1.43884575367,1.74004995823,5.38981723785 --1.46281802654,1.7490632534,5.41040325165 --1.46380794048,1.74006783962,5.38221025467 --1.48278188705,1.74208033085,5.38480091095 --1.50275528431,1.74609279633,5.39038848877 --1.52072954178,1.7471050024,5.38897848129 --1.53570437431,1.74511671066,5.37656641006 --1.5516782999,1.74312901497,5.36513710022 --1.56666362286,1.75113606453,5.38493061066 --1.58163845539,1.74814784527,5.37251806259 --1.60261189938,1.75316035748,5.38110923767 --1.61558771133,1.74917173386,5.36270046234 --1.63756072521,1.75418436527,5.37429237366 --1.65553426743,1.75519680977,5.36986589432 --1.66751050949,1.75020778179,5.34946298599 --1.68249583244,1.75721490383,5.36725521088 --1.69647109509,1.75422632694,5.35184192657 --1.71544528008,1.75623846054,5.35343647003 --1.73441886902,1.75825083256,5.35301780701 --1.75139343739,1.75826263428,5.34760808945 --1.77036750317,1.76127481461,5.34819841385 --1.78834152222,1.76128685474,5.34478235245 --1.79932785034,1.76429331303,5.34857082367 --1.81730234623,1.76530528069,5.34616327286 --1.83227753639,1.76331663132,5.33475446701 --1.85125100613,1.76532912254,5.33333301544 --1.87022566795,1.76834082603,5.33493566513 --1.89019954205,1.77135300636,5.3375248909 --1.89318811893,1.76535832882,5.31831407547 --1.91316235065,1.76937019825,5.32191181183 --1.93313539028,1.77138268948,5.32248783112 --1.94611144066,1.76839363575,5.30608177185 --1.96908414364,1.77340638638,5.31566524506 --1.98805844784,1.77641832829,5.31525707245 --2.0050330162,1.7764300108,5.30884504318 --2.01002144814,1.77343523502,5.29664087296 --2.03199505806,1.77844750881,5.30423545837 --2.04696989059,1.77645909786,5.29181671143 --2.0619456768,1.77447021008,5.28141403198 --2.08191919327,1.77748250961,5.28199625015 --2.09689474106,1.77649354935,5.27159357071 --2.11586856842,1.77850556374,5.26917314529 --2.12885499001,1.78251194954,5.27797412872 --2.14183139801,1.77952265739,5.26257133484 --2.16680335999,1.78653562069,5.27414655685 --2.18477725983,1.78654754162,5.26872491837 --2.19675397873,1.78355813026,5.25132465363 --2.21872782707,1.78857004642,5.25792455673 --2.22871398926,1.78857648373,5.2556977272 --2.23869156837,1.78358662128,5.23430204391 --2.25666546822,1.78459846973,5.22888040543 --2.27963876724,1.79061067104,5.23647260666 --2.29661345482,1.79062223434,5.2290558815 --2.31158900261,1.78863334656,5.21764373779 --2.33356332779,1.79364514351,5.22425174713 --2.3375518322,1.79065024853,5.21004009247 --2.35452651978,1.79066181183,5.20262336731 --2.38149881363,1.79867446423,5.21821641922 --2.39347505569,1.79568517208,5.19980049133 --2.4074511528,1.79369580746,5.18739938736 --2.43242430687,1.80070817471,5.19799184799 --2.44340062141,1.79571866989,5.17757558823 --2.45738625526,1.80072510242,5.18536615372 --2.4773607254,1.80273675919,5.18495893478 --2.49233579636,1.80174779892,5.17253780365 --2.51131129265,1.80375909805,5.17114257812 --2.52928638458,1.80577027798,5.16673851013 --2.54226255417,1.80278086662,5.15132808685 --2.56124639511,1.81078827381,5.1671037674 --2.5742225647,1.80779886246,5.15169286728 --2.5861992836,1.80480909348,5.13529157639 --2.61117243767,1.81082129478,5.14388036728 --2.62414860725,1.80883193016,5.12846851349 --2.64312291145,1.81084346771,5.12404823303 --2.65709972382,1.80885374546,5.11265659332 --2.67208576202,1.81386017799,5.12145090103 --2.68706083298,1.81287109852,5.10902929306 --2.70703601837,1.81588220596,5.10863304138 --2.72601103783,1.81789338589,5.10522699356 --2.74398493767,1.81890487671,5.09779930115 --2.76195979118,1.8199160099,5.09138202667 --2.77993607521,1.82192659378,5.08799743652 --2.78592348099,1.81993210316,5.07777357101 --2.81089735031,1.82594382763,5.08537101746 --2.82287359238,1.82295417786,5.06795454025 --2.84584760666,1.82796573639,5.07155132294 --2.85682439804,1.82497596741,5.05213165283 --2.88079857826,1.82998740673,5.05773305893 --2.88678717613,1.82899260521,5.0495300293 --2.90576219559,1.83100354671,5.04512023926 --2.92673611641,1.83401501179,5.04370594025 --2.94371199608,1.83502554893,5.03630304337 --2.95768809319,1.83303594589,5.02289104462 --2.98066186905,1.83804750443,5.02447462082 --2.99363875389,1.83605766296,5.01007032394 --3.00362586975,1.83706343174,5.00785827637 --3.02659964561,1.84107482433,5.00944519043 --3.03557753563,1.83708453178,4.98803663254 --3.0535531044,1.83809518814,4.98162841797 --3.07252788544,1.84010624886,4.97621297836 --3.08950471878,1.84111630917,4.96982479095 --3.10747981071,1.84312713146,4.96240711212 --3.11646771431,1.84313237667,4.95920419693 --3.13944149017,1.84814381599,4.95978736877 --3.15141844749,1.8451539278,4.94337749481 --3.17139387131,1.84816455841,4.93997144699 --3.18737006187,1.84817481041,4.93056917191 --3.20634531975,1.8501855135,4.92515993118 --3.21433353424,1.85019075871,4.91995286942 --3.23730778694,1.8552018404,4.92054271698 --3.25428318977,1.85521245003,4.91112470627 --3.26526141167,1.8532217741,4.89473152161 --3.28823518753,1.85723304749,4.89431285858 --3.3042113781,1.85724329948,4.88390111923 --3.31718850136,1.85625314713,4.86949491501 --3.32917642593,1.85825836658,4.87130260468 --3.34915113449,1.86126923561,4.86588048935 --3.36312818527,1.86027908325,4.85348176956 --3.3781042099,1.86028921604,4.84106397629 --3.40007925034,1.86329984665,4.83965826035 --3.41005682945,1.86030948162,4.82024288177 --3.4390308857,1.86932063103,4.82985258102 --3.43702101707,1.86332476139,4.8096370697 --3.45099854469,1.86233437061,4.79723739624 --3.47497224808,1.86734557152,4.79681348801 --3.49394845963,1.86935567856,4.79141616821 --3.50792551041,1.86936545372,4.7780046463 --3.52990102768,1.87237596512,4.77660751343 --3.53588891029,1.87138092518,4.7673869133 --3.55086612701,1.87139058113,4.75598430634 --3.57284116745,1.87540125847,4.75357627869 --3.58681821823,1.87441086769,4.74016571045 --3.60079526901,1.87442052364,4.72675514221 --3.62377023697,1.87843120098,4.72534608841 --3.63674759865,1.87744057178,4.71093988419 --3.64673519135,1.87844586372,4.7077293396 --3.66871094704,1.88245618343,4.70532751083 --3.68868613243,1.88446652889,4.69890832901 --3.69266629219,1.8794747591,4.67350959778 --3.71963977814,1.88548588753,4.67609214783 --3.72961878777,1.88249468803,4.65869665146 --3.74659562111,1.88450431824,4.64929008484 --3.75258421898,1.88350915909,4.64108228683 --3.77455973625,1.88751935959,4.63767290115 --3.78753733635,1.88552868366,4.62326717377 --3.80651426315,1.8885383606,4.61686944962 --3.82249093056,1.88954794407,4.60545492172 --3.84346628189,1.89255821705,4.60003948212 --3.85345411301,1.89356327057,4.5968337059 --3.86543250084,1.89257216454,4.58143091202 --3.89040732384,1.89758253098,4.58102178574 --3.89738702774,1.89359116554,4.55961799622 --3.91336369514,1.89460062981,4.548204422 --3.93933773041,1.89961123466,4.54778289795 --3.93831992149,1.89261865616,4.51839494705 --3.96030545235,1.89962458611,4.52919387817 --3.98427963257,1.90463507175,4.52576589584 --3.9892604351,1.89964306355,4.50337743759 --4.0082359314,1.90165317059,4.49394655228 --4.02921295166,1.90566253662,4.48955583572 --4.03919124603,1.90267133713,4.47114229202 --4.04917049408,1.90167999268,4.45374202728 --4.07215547562,1.90868592262,4.4645357132 --4.07213640213,1.90169382095,4.43512201309 --4.09011411667,1.90370297432,4.42672395706 --4.11208963394,1.90771281719,4.42130804062 --4.13106679916,1.90972197056,4.41391134262 --4.13404655457,1.90473020077,4.38748884201 --4.16202163696,1.91174042225,4.3890838623 --4.16401195526,1.90874445438,4.3768787384 --4.17798995972,1.90875327587,4.36347341537 --4.19296789169,1.90976214409,4.35106754303 --4.20294713974,1.90777051449,4.3336648941 --4.21992444992,1.90877974033,4.32325792313 --4.24589967728,1.91478943825,4.32184791565 --4.24289131165,1.90979301929,4.30464267731 --4.2568693161,1.90980172157,4.29123783112 --4.29484224319,1.92181265354,4.30182886124 --4.32981586456,1.93182301521,4.30942440033 --4.3307967186,1.92483079433,4.28200960159 --4.35977220535,1.9328404665,4.2836098671 --4.36875104904,1.9308488369,4.26419401169 --4.38373804092,1.93385386467,4.26498842239 --4.40971374512,1.93986356258,4.2625784874 --4.41869449615,1.93787121773,4.24519252777 --4.42967319489,1.93687975407,4.22777700424 --4.45064973831,1.93988883495,4.22036790848 --4.46362924576,1.9398971796,4.20596885681 --4.4596118927,1.93190419674,4.17455673218 --4.46660089493,1.93190860748,4.16734886169 --4.45158576965,1.91891479492,4.12593698502 --4.4635643959,1.91892302036,4.11053323746 --4.45754814148,1.90992987156,4.07812356949 --4.46652746201,1.90793800354,4.05971336365 --4.45951128006,1.89894473553,4.02731323242 --4.47248983383,1.89895296097,4.01290559769 --4.46548175812,1.89295625687,3.99268984795 --4.45846509933,1.88396310806,3.96028137207 --4.47144412994,1.88397145271,3.94587159157 --4.47342586517,1.87997865677,3.92247414589 --4.45641136169,1.86598467827,3.88207101822 --4.48038816452,1.87099373341,3.87766313553 --4.46438217163,1.86099636555,3.85045146942 --4.46636390686,1.85700368881,3.82704591751 --4.47334384918,1.85401141644,3.80763363838 --4.47532510757,1.85001897812,3.78422474861 --4.49330329895,1.85302734375,3.77482056618 --4.50428247452,1.85203552246,3.75839924812 --4.53225898743,1.85904443264,3.75800657272 --4.5192527771,1.85104715824,3.7348048687 --4.53823137283,1.85405540466,3.72640514374 --4.54021263123,1.84906280041,3.7029914856 --4.56418895721,1.85407173634,3.69757461548 --4.56217193604,1.84907853603,3.67218017578 --4.57915019989,1.85108709335,3.66075968742 --4.5941286087,1.85209512711,3.64835047722 --4.59112119675,1.84809839725,3.63415360451 --4.60110092163,1.84810626507,3.61774396896 --4.61608028412,1.84911417961,3.60533475876 --4.63505840302,1.85212254524,3.5959239006 --4.63104152679,1.846129179,3.5695309639 --4.6520190239,1.84913766384,3.56111097336 --4.67999601364,1.85614609718,3.55972027779 --4.66598987579,1.84814894199,3.53650951385 --4.67297077179,1.84615635872,3.5181043148 --4.68794965744,1.8481644392,3.50467944145 --4.69893026352,1.84817171097,3.49029040337 --4.70891046524,1.84717929363,3.47388005257 --4.71689128876,1.84618663788,3.45647740364 --4.7298707962,1.84619450569,3.44206237793 --4.73086166382,1.84419798851,3.43085575104 --4.74784135818,1.84720563889,3.4204595089 --4.75682210922,1.84621298313,3.40406107903 --4.76680278778,1.84622049332,3.38764929771 --4.7717833519,1.8432277441,3.36723041534 --4.78676319122,1.84523534775,3.35482573509 --4.80075120926,1.84823966026,3.35261273384 --4.79873466492,1.84324634075,3.3282096386 --4.80471611023,1.84125328064,3.3098115921 --4.82169532776,1.84426093102,3.29840087891 --4.82467746735,1.84126782417,3.27800345421 --4.83265829086,1.83927512169,3.25957894325 --4.83664035797,1.83728194237,3.24018502235 --4.84962892532,1.84028613567,3.23696994781 --4.8606095314,1.84029340744,3.22156238556 --4.87858915329,1.84330093861,3.21116065979 --4.87357234955,1.83730745316,3.18474721909 --4.89155244827,1.84031486511,3.17434620857 --4.90053319931,1.83932173252,3.15794467926 --4.90751457214,1.83832895756,3.13952970505 --4.91250514984,1.83833253384,3.13132286072 --4.92648506165,1.83933973312,3.11791658401 --4.93646621704,1.83934652805,3.10252141953 --4.94344806671,1.83835363388,3.08410573006 --4.96242809296,1.84236073494,3.07471585274 --4.96441030502,1.83936738968,3.05330300331 --4.97139167786,1.83737444878,3.03488659859 --4.98338079453,1.84037840366,3.03067302704 --4.98336410522,1.83638465405,3.00928115845 --4.99134588242,1.83639144897,2.99187088013 --5.00732564926,1.83839869499,2.97946310043 --5.00730895996,1.83440494537,2.95806837082 --5.01029205322,1.83241164684,2.93765711784 --5.03826999664,1.83941912651,2.93224740028 --5.0282626152,1.83342206478,2.91503834724 --5.05124187469,1.83842933178,2.90663003922 --5.04922533035,1.83443570137,2.88321614265 --5.06320619583,1.83644247055,2.86981463432 --5.07118797302,1.83544933796,2.85240292549 --5.08916807175,1.83845627308,2.84099698067 --5.09115123749,1.83646249771,2.82059335709 --5.09814119339,1.83646595478,2.81338405609 --5.10412359238,1.83547258377,2.79497456551 --5.11810493469,1.83747923374,2.78157520294 --5.12408685684,1.83648562431,2.76316547394 --5.14406728745,1.84049248695,2.75276184082 --5.14705085754,1.83749866486,2.73336458206 --5.14904212952,1.8375017643,2.72416973114 --5.15802335739,1.83750844002,2.70674729347 --5.17100477219,1.83851504326,2.6923418045 --5.18298625946,1.83952152729,2.67692780495 --5.19696807861,1.84152793884,2.6635324955 --5.20195102692,1.840534091,2.64513230324 --5.2159318924,1.84254062176,2.63071870804 --5.22692203522,1.84454405308,2.62551116943 --5.22690582275,1.84155023098,2.6041021347 --5.24288654327,1.84455668926,2.5906894207 --5.25486898422,1.84556281567,2.57629799843 --5.25985145569,1.84456920624,2.55687737465 --5.27483272552,1.84657549858,2.54347705841 --5.28781509399,1.84858167171,2.52907729149 --5.29080629349,1.84858477116,2.51987171173 --5.30078840256,1.84859097004,2.50346207619 --5.32776880264,1.8555971384,2.49606895447 --5.3307518959,1.85360336304,2.47564816475 --5.33873510361,1.85360920429,2.45925879478 --5.34171772003,1.85161542892,2.43883681297 --5.36069869995,1.85562157631,2.42642498016 --5.36469078064,1.85562443733,2.4182305336 --5.37767267227,1.85763049126,2.40281581879 --5.38765478134,1.85863649845,2.38640928268 --5.39863777161,1.85964226723,2.37101411819 --5.40962123871,1.860648036,2.35561919212 --5.41760396957,1.86065399647,2.33821153641 --5.42358732224,1.85965979099,2.3198018074 --5.42957830429,1.86066293716,2.3115901947 --5.43556070328,1.85966873169,2.2931804657 --5.45154380798,1.86367440224,2.27978372574 --5.46152544022,1.86368048191,2.26235985756 --5.47050952911,1.86468601227,2.24596476555 --5.4814915657,1.86569178104,2.22955298424 --5.48648357391,1.8666946888,2.22135138512 --5.49946594238,1.86870038509,2.20594406128 --5.51244878769,1.87070596218,2.19053721428 --5.5144329071,1.86871147156,2.17114090919 --5.52541589737,1.86971712112,2.15473151207 --5.53539991379,1.87072253227,2.13833045959 --5.54838180542,1.87272834778,2.1219060421 --5.56437253952,1.87673091888,2.11871957779 --5.56435680389,1.87473666668,2.09729862213 --5.58033943176,1.87774193287,2.08289289474 --5.59032297134,1.87874734402,2.06649446487 --5.5943069458,1.87775278091,2.04708218575 --5.60629034042,1.87975811958,2.03168916702 --5.61627388,1.88076353073,2.01427197456 --5.62126588821,1.88176620007,2.00607347488 --5.62524986267,1.88077151775,1.98666071892 --5.65623140335,1.88877642155,1.97827243805 --5.65221643448,1.88578188419,1.95585811138 --5.65520143509,1.88378727436,1.9364528656 --5.67218446732,1.88779222965,1.92204880714 --5.65217065811,1.87879812717,1.893622756 --5.67116117477,1.88380038738,1.89042830467 --5.70114374161,1.89280509949,1.88103711605 --5.68213033676,1.88381063938,1.85362100601 --5.70511341095,1.88881552219,1.84122037888 --5.7040977478,1.88682091236,1.81980025768 --5.71008205414,1.88682603836,1.80139386654 --5.71806716919,1.88683092594,1.78399455547 --5.73705720901,1.89283323288,1.77978801727 --5.73304319382,1.88883829117,1.75838673115 --5.74402666092,1.89084339142,1.74096894264 --5.75701093674,1.89384794235,1.72557997704 --5.76099586487,1.89285314083,1.70616710186 --5.76398086548,1.89185810089,1.68676006794 --5.79096364975,1.89886260033,1.67434811592 --5.7719578743,1.89186561108,1.6581376791 --5.78294229507,1.89387023449,1.64174294472 --5.80492591858,1.89887452126,1.62834465504 --5.80391120911,1.89687979221,1.60692083836 --5.81289577484,1.89788448811,1.58951961994 --5.82687997818,1.90088891983,1.57311034203 --5.81786680222,1.89589393139,1.55071091652 --5.82985830307,1.89889621735,1.54349863529 --5.84484291077,1.90290057659,1.5281059742 --5.85382699966,1.90390515327,1.50968658924 --5.84181404114,1.89791047573,1.48628008366 --5.8597984314,1.9029147625,1.47087299824 --5.86178398132,1.9009193182,1.45147156715 --5.86676883698,1.90092408657,1.43205332756 --5.88176107407,1.90592563152,1.42687118053 --5.87174749374,1.9009308815,1.40344929695 --5.87373304367,1.89893555641,1.38404655457 --5.89471721649,1.90493965149,1.36862969398 --5.9037027359,1.90594375134,1.35123383999 --5.90468835831,1.90494859219,1.33081579208 --5.90468215942,1.90395069122,1.32162976265 --5.89666843414,1.89995586872,1.29921281338 --5.90165328979,1.89996039867,1.27979445457 --5.92563867569,1.90696370602,1.2664116621 --5.91562509537,1.90196895599,1.24298107624 --5.92961025238,1.90497279167,1.22658467293 --5.94159603119,1.90797686577,1.20917749405 --5.95258808136,1.91097843647,1.20198333263 --5.93857526779,1.9039837122,1.17856788635 --5.96256017685,1.91098690033,1.16417264938 --5.9655456543,1.91099143028,1.1437445879 --5.95053339005,1.90399646759,1.12135016918 --5.9695186615,1.91000008583,1.10493779182 --5.9715051651,1.90900433064,1.08553421497 --5.97349834442,1.90900635719,1.0763386488 --5.97948408127,1.91001057625,1.05691885948 --5.98147058487,1.90901470184,1.03751480579 --5.98345708847,1.90801906586,1.01811075211 --5.98344326019,1.90702342987,0.99769282341 --5.99842882156,1.91102683544,0.980281770229 --6.00141620636,1.91103076935,0.9618948102 --6.00340890884,1.91103291512,0.951678693295 --6.0013961792,1.90903735161,0.931267499924 --6.01038217545,1.91104102135,0.912859380245 --6.01236867905,1.91004514694,0.893455028534 --6.02635478973,1.9140484333,0.876052260399 --6.01834201813,1.91005313396,0.854638695717 --6.02932929993,1.91305649281,0.837247014046 --6.03332185745,1.91305851936,0.827025055885 --6.04330873489,1.91606163979,0.809637844563 --6.04329538345,1.91506588459,0.789218902588 --6.04028272629,1.91307032108,0.768808424473 --6.06426858902,1.92007267475,0.752403378487 --6.05925607681,1.9170769453,0.731998801231 --6.06824970245,1.92007827759,0.723805963993 --6.06123685837,1.91608273983,0.70238506794 --6.05722379684,1.91408705711,0.681975662708 --6.07221078873,1.91808998585,0.664579570293 --6.07919836044,1.92009341717,0.645163059235 --6.08118534088,1.92009711266,0.625759363174 --6.07617282867,1.91710138321,0.60535132885 --6.08515930176,1.91910469532,0.585931003094 --6.09115362167,1.92110598087,0.577749192715 --6.09214067459,1.92010986805,0.557326972485 --6.09212875366,1.92011356354,0.53792744875 --6.09811544418,1.92111706734,0.518515408039 --6.10410308838,1.92212021351,0.499103933573 --6.11209106445,1.92412316799,0.480710059404 --6.11207818985,1.92312705517,0.460289925337 --6.10807228088,1.92112934589,0.450087040663 --6.11206007004,1.92213261127,0.430680006742 --6.13004684448,1.928134799,0.412270516157 --6.12103509903,1.92413914204,0.391865313053 --6.13802242279,1.92914128304,0.3734600842 --6.13601016998,1.92814517021,0.353043109179 --6.1500043869,1.93214547634,0.344854742289 --6.14799261093,1.93114936352,0.324438035488 --6.16098070145,1.935151577,0.306043028831 --6.15096855164,1.93115603924,0.285636454821 --6.15795707703,1.93315887451,0.266229093075 --6.1599445343,1.93316221237,0.245807215571 --6.16493320465,1.93416512012,0.226403206587 --6.16692686081,1.93516671658,0.216191247106 --6.17391490936,1.93716943264,0.196786001325 --6.16990327835,1.93517315388,0.177391290665 --6.18389177322,1.93917500973,0.157981216908 --6.18088006973,1.93817877769,0.137564465404 --6.1838684082,1.93818175793,0.11816431582 --6.18685722351,1.93918466568,0.098764128983 --6.19885110855,1.94318521023,0.088547617197 --6.19384002686,1.94118881226,0.0691527575254 --6.20482826233,1.94419109821,0.0487291514874 --6.216817379,1.94819283485,0.0293273031712 --6.20380544662,1.94319748878,0.00891396682709 --6.21179485321,1.94619977474,-0.010485669598 --6.21078300476,1.94520294666,-0.0309033468366 --6.20877790451,1.94520461559,-0.0400914177299 --6.2097659111,1.94520771503,-0.0605097487569 --6.21175575256,1.94521045685,-0.0799070075154 --6.22774410248,1.95021176338,-0.100324273109 --6.22573375702,1.95021498203,-0.119721062481 --6.22572231293,1.95021796227,-0.140138432384 --6.22571134567,1.95022106171,-0.16055585444 --6.22970581055,1.9512219429,-0.169742450118 --6.24369573593,1.95522320271,-0.190154448152 --6.23368406296,1.95222735405,-0.210574999452 --6.2396736145,1.95422947407,-0.229968115687 --6.22966194153,1.95123362541,-0.250390231609 --6.23165225983,1.95223605633,-0.269785374403 --6.23664140701,1.95423841476,-0.290199011564 --6.23263549805,1.95224022865,-0.30041000247 --6.23662519455,1.9542427063,-0.320823907852 --6.23061466217,1.95224606991,-0.340224713087 --6.23160362244,1.95224869251,-0.360640585423 --6.22559309006,1.95025217533,-0.380042403936 --6.21158218384,1.94625687599,-0.399453550577 --6.22257184982,1.95025801659,-0.419859290123 --6.22456693649,1.95025908947,-0.430065363646 --6.2255563736,1.9512617588,-0.450481265783 --6.2265458107,1.95226418972,-0.470896959305 --6.22953605652,1.95326626301,-0.490288674831 --6.22852563858,1.95326900482,-0.510706484318 --6.22751522064,1.95327174664,-0.5311242342 --6.23050546646,1.95427381992,-0.550514936447 --6.22550010681,1.95327579975,-0.560730934143 --6.24949169159,1.96127486229,-0.582128286362 --6.22548007965,1.95428073406,-0.600542426109 --6.22746992111,1.95528292656,-0.620954692364 --6.23746109009,1.95928382874,-0.641351938248 --6.23045015335,1.95728731155,-0.661779999733 --6.23244524002,1.95728814602,-0.671983361244 --6.22143507004,1.95429217815,-0.690378785133 --6.22342538834,1.95529413223,-0.7107899189 --6.23141622543,1.95929539204,-0.732208788395 --6.23540639877,1.96029698849,-0.752613961697 --6.22939634323,1.95930016041,-0.772020757198 --6.22038602829,1.95730376244,-0.79143512249 --6.2253818512,1.95930409431,-0.801630496979 --6.22337245941,1.95930659771,-0.822049260139 --6.23236322403,1.96230733395,-0.843460977077 --6.22635316849,1.96131050587,-0.862868666649 --6.23434448242,1.96431136131,-0.884281218052 --6.22833442688,1.96331429482,-0.903689086437 --6.23132610321,1.96531581879,-0.92409324646 --6.2283205986,1.96431744099,-0.934307456017 --6.22631168365,1.96431970596,-0.953704535961 --6.23130273819,1.96732103825,-0.975122392178 --6.22929334641,1.96732318401,-0.994518876076 --6.22328424454,1.96532607079,-1.01392734051 --6.22627496719,1.96732759476,-1.03534960747 --6.21426486969,1.96433150768,-1.05375730991 --6.20925951004,1.96333324909,-1.06295835972 --6.21725225449,1.96733379364,-1.08436393738 --6.21724319458,1.96733570099,-1.10477387905 --6.2122335434,1.9673384428,-1.12520098686 --6.20922422409,1.96734070778,-1.14460074902 --6.20421504974,1.96634328365,-1.16400754452 --6.20320653915,1.96734523773,-1.18442094326 --6.18819952011,1.96234881878,-1.19263911247 --6.1891913414,1.96435034275,-1.21304559708 --6.18818235397,1.9643522501,-1.23345887661 --6.1921749115,1.96735310555,-1.25385296345 --6.18516540527,1.96535599232,-1.27326822281 --6.18215608597,1.96535813808,-1.29368877411 --6.19014978409,1.9693582058,-1.31508541107 --6.18014335632,1.96736109257,-1.32430958748 --6.17013406754,1.96436440945,-1.34271764755 --6.19212913513,1.97336161137,-1.36711525917 --6.18711996078,1.97236406803,-1.38652217388 --6.18511199951,1.9733659029,-1.40693688393 --6.18710422516,1.97536683083,-1.42733383179 --6.18109464645,1.97436952591,-1.44776546955 --6.18109083176,1.97537016869,-1.45796811581 --6.18608379364,1.97837042809,-1.47937035561 --6.16807317734,1.97337543964,-1.49577605724 --6.16906547546,1.97537648678,-1.51719629765 --6.17105817795,1.9773774147,-1.53861105442 --6.18305206299,1.98237609863,-1.56201720238 --6.17204332352,1.98037946224,-1.57941222191 --6.19404268265,1.98837554455,-1.59562671185 --6.18903446198,1.98837769032,-1.61503183842 --6.21403169632,1.99837338924,-1.64142751694 --6.23002719879,2.00537085533,-1.6668446064 --6.22901916504,2.00637221336,-1.68724608421 --6.25101661682,2.01536822319,-1.71364784241 --6.2820186615,2.02636194229,-1.73184275627 --6.27701044083,2.02636384964,-1.75226044655 --6.27600383759,2.02836465836,-1.7726572752 --6.28699874878,2.03336310387,-1.79706799984 --6.29499387741,2.03836202621,-1.82047331333 --6.27598333359,2.03336691856,-1.83688688278 --6.29498052597,2.04136323929,-1.86328852177 --6.28097391129,2.03736662865,-1.8705009222 --6.277967453,2.03836798668,-1.89090549946 --6.27195930481,2.03836989403,-1.91132676601 --6.25394916534,2.03337478638,-1.92773854733 --6.25094223022,2.03437590599,-1.94916296005 --6.24693489075,2.03537726402,-1.96957349777 --6.24892950058,2.03737711906,-1.99198687077 --6.24592542648,2.03737807274,-2.00117850304 --6.24992036819,2.04037761688,-2.02459812164 --6.24191236496,2.04038000107,-2.0440120697 --6.22590303421,2.03638410568,-2.06041693687 --6.22889709473,2.03938364983,-2.08384108543 --6.19988489151,2.03139090538,-2.09625148773 --6.20488023758,2.03538990021,-2.11966300011 --6.20387411118,2.0373904705,-2.14107298851 --6.19786977768,2.03539204597,-2.15028333664 --6.17685937881,2.03039765358,-2.16570615768 --6.18585538864,2.03539538383,-2.19010829926 --6.18484973907,2.03739595413,-2.21151685715 --6.16183805466,2.03140187263,-2.22593617439 --6.15983247757,2.03340268135,-2.24735164642 --6.15982961655,2.03440260887,-2.25754284859 --6.12881660461,2.02541065216,-2.26896238327 --6.14181423187,2.0324075222,-2.2953710556 --6.12280416489,2.02841234207,-2.31078791618 --6.11079597473,2.02641558647,-2.32921528816 --6.10378837585,2.0264172554,-2.34862709045 --6.10978460312,2.03041553497,-2.37304186821 --6.09077787399,2.02542066574,-2.37725305557 --6.08176994324,2.02442288399,-2.39566063881 --6.07676315308,2.0254240036,-2.41607761383 --6.05475282669,2.01943016052,-2.42948532104 --6.04874563217,2.02043151855,-2.4499104023 --6.04073905945,2.0194337368,-2.46831178665 --6.02673006058,2.0164372921,-2.48472070694 --6.02672767639,2.01843714714,-2.49592995644 --6.00671720505,2.01344251633,-2.51136636734 --6.00671243668,2.01644229889,-2.53276515007 --5.99970579147,2.01644396782,-2.55217933655 --5.99569988251,2.0174446106,-2.57258892059 --5.98169136047,2.01544833183,-2.58900117874 --5.96868276596,2.01345181465,-2.60642504692 --5.96367883682,2.01245284081,-2.61563467979 --5.95067071915,2.01045632362,-2.63204097748 --5.94666481018,2.0114569664,-2.65346932411 --5.9376578331,2.01145911217,-2.67188191414 --5.92264890671,2.0084631443,-2.68728709221 --5.92764663696,2.01346111298,-2.71169757843 --5.90163421631,2.00646853447,-2.72311973572 --5.89462995529,2.00547003746,-2.73132872581 --5.8936252594,2.00846982002,-2.75375056267 --5.87761592865,2.00447416306,-2.76814842224 --5.872610569,2.00647521019,-2.78856611252 --5.86160326004,2.00447773933,-2.80597877502 --5.84459352493,2.00148224831,-2.82140660286 --5.83858776093,2.00248336792,-2.84081459045 --5.83058309555,2.00148558617,-2.84903407097 --5.81257343292,1.99749052525,-2.86243581772 --5.80756759644,1.99849116802,-2.88285374641 --5.80056190491,1.99949264526,-2.90227079391 --5.77554941177,1.99249982834,-2.91370081902 --5.76154088974,1.9915034771,-2.92910814285 --5.7635383606,1.99450194836,-2.95251774788 --5.75053215027,1.99150574207,-2.95773053169 --5.73552370071,1.98950970173,-2.97314810753 --5.72651672363,1.98951172829,-2.99156665802 --5.71851062775,1.98951339722,-3.00997543335 --5.70250177383,1.98651766777,-3.02540445328 --5.6994972229,1.98851752281,-3.04580330849 --5.68048667908,1.98452293873,-3.05922532082 --5.67748451233,1.98552334309,-3.06943917274 --5.66147518158,1.98252773285,-3.08385229111 --5.65246868134,1.9825296402,-3.10227203369 --5.64046144485,1.9815325737,-3.11868453026 --5.63645648956,1.98353278637,-3.14011073112 --5.61044406891,1.97754061222,-3.14953374863 --5.6054391861,1.97854113579,-3.16893315315 --5.60243654251,1.97954154015,-3.17914700508 --5.5864276886,1.9765458107,-3.19356489182 --5.57742166519,1.97654783726,-3.21096777916 --5.57141685486,1.97754859924,-3.23139452934 --5.54540348053,1.9715565443,-3.23980760574 --5.53739738464,1.97255802155,-3.25923776627 --5.53739643097,1.97455728054,-3.27043867111 --5.51338434219,1.96856451035,-3.27985286713 --5.51038074493,1.97056412697,-3.30126690865 --5.50037431717,1.97056627274,-3.31969976425 --5.48636627197,1.9695700407,-3.33410263062 --5.46035289764,1.96257805824,-3.34252548218 --5.45534849167,1.96457839012,-3.3629424572 --5.44534301758,1.96258127689,-3.36915898323 --5.43033456802,1.96058535576,-3.38357567787 --5.42132902145,1.9605871439,-3.40098142624 --5.42132711411,1.96458542347,-3.42439675331 --5.39831495285,1.9595925808,-3.43381261826 --5.39431190491,1.96259224415,-3.45523524284 --5.37430095673,1.95859825611,-3.4666557312 --5.36629629135,1.95760047436,-3.47387123108 --5.36929655075,1.96259748936,-3.49826836586 --5.34128189087,1.95560669899,-3.50469183922 --5.33127593994,1.95560872555,-3.52210998535 --5.32427120209,1.95660960674,-3.54152965546 --5.30426025391,1.95261561871,-3.55295538902 --5.28925180435,1.95061969757,-3.56636071205 --5.28825092316,1.95261895657,-3.57858633995 --5.26823997498,1.94862520695,-3.58899736404 --5.25223112106,1.94662976265,-3.60241603851 --5.24722766876,1.94862961769,-3.62283015251 --5.22621631622,1.9446362257,-3.63325619698 --5.22521495819,1.94863450527,-3.65565752983 --5.21320819855,1.94763720036,-3.67208313942 --5.19619941711,1.94364321232,-3.67330503464 --5.17418718338,1.93865025043,-3.68272948265 --5.18119001389,1.94564509392,-3.71113777161 --5.15417575836,1.93965423107,-3.71655464172 --5.14417028427,1.93965625763,-3.73295807838 --5.14717102051,1.9456526041,-3.75937652588 --5.11615419388,1.93766355515,-3.76281189919 --5.10514831543,1.93566715717,-3.76701855659 --5.10514831543,1.93966460228,-3.79143738747 --5.0821352005,1.93467235565,-3.7988474369 --5.06612682343,1.93267691135,-3.8122754097 --5.06612682343,1.93767428398,-3.83669233322 --5.04511547089,1.93368113041,-3.8461151123 --5.04211378098,1.9366799593,-3.86751651764 --5.03210830688,1.93468296528,-3.87273049355 --5.01309776306,1.93168902397,-3.88314700127 --5.00109100342,1.93169176579,-3.89957785606 --4.99809026718,1.93469035625,-3.92097759247 --4.97207546234,1.92869949341,-3.92741894722 --4.95606660843,1.92670416832,-3.93983411789 --4.96207046509,1.93369853497,-3.96823382378 --4.94706249237,1.93070399761,-3.96944880486 --4.93105363846,1.92870867252,-3.9818649292 --4.91904735565,1.92871129513,-3.99829649925 --4.90604066849,1.92771446705,-4.01270723343 --4.88703012466,1.92472040653,-4.02313184738 --4.87902593613,1.92672121525,-4.04256105423 --4.85801410675,1.92272818089,-4.05098009109 --4.85901546478,1.92572629452,-4.06316900253 --4.85101175308,1.92672693729,-4.08259677887 --4.82899951935,1.92273449898,-4.09001493454 --4.81399154663,1.92173862457,-4.10343933105 --4.80899000168,1.92473769188,-4.1248588562 --4.79097986221,1.92174351215,-4.13527441025 --4.78497648239,1.92174470425,-4.14349079132 --4.77597284317,1.92374587059,-4.16089916229 --4.7579627037,1.92075133324,-4.17233276367 --4.74595689774,1.92075395584,-4.18774938583 --4.73495197296,1.92175614834,-4.20416879654 --4.71994352341,1.92076027393,-4.21657896042 --4.70193386078,1.917765975,-4.226998806 --4.69793224335,1.91876614094,-4.23721981049 --4.67191696167,1.91277599335,-4.2406411171 --4.664914608,1.91577601433,-4.26005315781 --4.65991353989,1.91877496243,-4.28146743774 --4.63689994812,1.91378331184,-4.28789758682 --4.61688899994,1.91079008579,-4.29631900787 --4.61288881302,1.91478836536,-4.31873416901 --4.59787940979,1.91079449654,-4.3189535141 --4.58187055588,1.90879929066,-4.33036661148 --4.5718665123,1.91080069542,-4.34778833389 --4.55485725403,1.90880596638,-4.35820102692 --4.53784799576,1.90681111813,-4.36962985992 --4.53184700012,1.90981042385,-4.39004039764 --4.50883293152,1.90481889248,-4.39647960663 --4.50383090973,1.90581965446,-4.4046831131 --4.49482774734,1.90782046318,-4.42310476303 --4.47581672668,1.90482699871,-4.43151903152 --4.45980882645,1.90383183956,-4.4429359436 --4.45380783081,1.90683066845,-4.46435880661 --4.43379640579,1.90383791924,-4.47177505493 --4.42179059982,1.90384018421,-4.48820972443 --4.40778207779,1.90084600449,-4.48842525482 --4.39777803421,1.90184724331,-4.50584602356 --4.37776613235,1.89885449409,-4.51326465607 --4.37276697159,1.90285289288,-4.5346698761 --4.35075330734,1.89886105061,-4.54110574722 --4.34375238419,1.90186059475,-4.5605096817 --4.32874488831,1.90086472034,-4.57394504547 --4.31273365021,1.8968719244,-4.57115030289 --4.30172967911,1.89787375927,-4.58757066727 --4.29472923279,1.90087294579,-4.60900306702 --4.27771949768,1.89887857437,-4.61841011047 --4.2627120018,1.8988827467,-4.63083219528 --4.2517080307,1.89988434315,-4.64725065231 --4.22469043732,1.8938959837,-4.64768362045 --4.22169065475,1.89489507675,-4.65889787674 --4.21769237518,1.89989244938,-4.68231010437 --4.19267654419,1.89490282536,-4.68474388123 --4.18167209625,1.89590454102,-4.70116186142 --4.17066860199,1.89690613747,-4.71758031845 --4.15465974808,1.89591121674,-4.72798967361 --4.13665008545,1.89391720295,-4.73741817474 --4.13965606689,1.89891242981,-4.75563573837 --4.11964416504,1.89591991901,-4.76205253601 --4.09462738037,1.89093053341,-4.76347970963 --4.08962965012,1.89492809772,-4.78690099716 --4.07061862946,1.89293503761,-4.79431867599 --4.05961465836,1.89393663406,-4.81073522568 --4.0466094017,1.8949393034,-4.82515621185 --4.03460121155,1.89194440842,-4.82637119293 --4.01859378815,1.89194917679,-4.83779859543 --4.01359558105,1.89594662189,-4.86121463776 --3.98757815361,1.88995814323,-4.8616528511 --3.97257065773,1.88996243477,-4.87306499481 --3.96156740189,1.89196383953,-4.88948059082 --3.95456457138,1.89196550846,-4.89669895172 --3.93154931068,1.88697528839,-4.8991189003 --3.92054629326,1.88897657394,-4.91654872894 --3.90353703499,1.88798224926,-4.92596769333 --3.88852977753,1.88698649406,-4.93738031387 --3.88953900337,1.89497923851,-4.96879816055 --3.85651373863,1.88599634171,-4.95922803879 --3.83850359917,1.88400256634,-4.96765184402 --3.83950901031,1.88799834251,-4.98487138748 --3.81949687004,1.88600611687,-4.99130296707 --3.80248785019,1.88501167297,-5.00072431564 --3.79649019241,1.8890093565,-5.02313232422 --3.77447557449,1.88501870632,-5.02655887604 --3.76046991348,1.88602209091,-5.03998327255 --3.75947356224,1.88901913166,-5.05419158936 --3.73445534706,1.88303112984,-5.05260562897 --3.71744704247,1.88303637505,-5.06405591965 --3.7084467411,1.8860360384,-5.08347272873 --3.68442964554,1.88104724884,-5.08288669586 --3.67042422295,1.88205051422,-5.09631156921 --3.65942144394,1.88305163383,-5.11373519897 --3.6414065361,1.8780618906,-5.10595226288 --3.62539839745,1.87706685066,-5.11637306213 --3.61539745331,1.88006687164,-5.13580560684 --3.59538435936,1.87707543373,-5.13920688629 --3.57637310028,1.87508249283,-5.14664363861 --3.57037711143,1.88007938862,-5.17106723785 --3.54535841942,1.87509179115,-5.16848421097 --3.53635334969,1.87409496307,-5.17270040512 --3.52635288239,1.87709486485,-5.19213008881 --3.50834202766,1.87510192394,-5.19853782654 --3.48632717133,1.87211167812,-5.20096874237 --3.47632694244,1.8751115799,-5.22039699554 --3.45531272888,1.87212073803,-5.2238240242 --3.4453125,1.87512052059,-5.2432513237 --3.44331598282,1.87811815739,-5.25645256042 --3.41529345512,1.87113296986,-5.25089740753 --3.40128803253,1.87213647366,-5.2633099556 --3.38828396797,1.87313902378,-5.27772808075 --3.36726951599,1.87014842033,-5.28014707565 --3.35226345062,1.87015211582,-5.29359006882 --3.33925914764,1.87215483189,-5.30699586868 --3.32124257088,1.86616587639,-5.29822492599 --3.31024098396,1.8681666851,-5.31564188004 --3.30024147034,1.87216627598,-5.33506393433 --3.27021503448,1.86318385601,-5.32449913025 --3.25921392441,1.86618435383,-5.34191608429 --3.24520897865,1.86718761921,-5.3553404808 --3.23319983482,1.86519372463,-5.35455799103 --3.21318674088,1.86220228672,-5.35898923874 --3.20118403435,1.8642039299,-5.37439966202 --3.18317389488,1.86321079731,-5.38182973862 --3.16516280174,1.86121785641,-5.38824796677 --3.15616559982,1.86621594429,-5.41068124771 --3.13314771652,1.86122775078,-5.40910339355 --3.11413621902,1.86023581028,-5.41453123093 --3.10713362694,1.86023712158,-5.42174863815 --3.08712029457,1.85824620724,-5.4251742363 --3.07411718369,1.86024820805,-5.44060182571 --3.06111359596,1.86125051975,-5.45501661301 --3.03709435463,1.85626327991,-5.45245313644 --3.02409100533,1.85826563835,-5.46686840057 --3.01708912849,1.85926699638,-5.4740858078 --2.99607396126,1.85627710819,-5.4755115509 --2.98206925392,1.85728025436,-5.48893451691 --2.9620552063,1.85528957844,-5.49135351181 --2.94805073738,1.8562926054,-5.50477600098 --2.93004107475,1.85529923439,-5.51322317123 --2.91203022003,1.85430645943,-5.5196480751 --2.90102148056,1.85231232643,-5.51885652542 --2.89402890205,1.85830783844,-5.54528045654 --2.87000775337,1.8533217907,-5.53969621658 --2.85400104523,1.85332643986,-5.55113649368 --2.83498859406,1.85133469105,-5.55556201935 --2.81998205185,1.85233914852,-5.56597137451 --2.8039753437,1.85334384441,-5.57741212845 --2.79897642136,1.85534358025,-5.58660840988 --2.78196811676,1.85534930229,-5.59604740143 --2.76896619797,1.85735082626,-5.61247777939 --2.74694776535,1.85336303711,-5.60989332199 --2.72793579102,1.85137093067,-5.61533117294 --2.71493387222,1.85437273979,-5.6307516098 --2.68490123749,1.84439396858,-5.61318016052 --2.67789959908,1.84539532661,-5.6203956604 --2.66990733147,1.85139083862,-5.64682388306 --2.65089440346,1.85039973259,-5.65024471283 --2.63188147545,1.84840857983,-5.65366601944 --2.61587429047,1.84841346741,-5.66409540176 --2.59686112404,1.84642219543,-5.66751766205 --2.58785629272,1.84642589092,-5.67073345184 --2.57385325432,1.84842813015,-5.68617105484 --2.55684375763,1.84843492508,-5.69258260727 --2.53582692146,1.84444606304,-5.69200849533 --2.52282643318,1.84844720364,-5.70944404602 --2.50481581688,1.84745442867,-5.71587657928 --2.48480033875,1.84446489811,-5.71629428864 --2.47880148888,1.84646451473,-5.72651433945 --2.46179151535,1.84647130966,-5.73292732239 --2.44378113747,1.84547877312,-5.73936080933 --2.42577052116,1.84448599815,-5.7457947731 --2.40775942802,1.84349381924,-5.75121974945 --2.38874697685,1.84250235558,-5.75565719604 --2.37574625015,1.84550356865,-5.77207803726 --2.36573863029,1.84450876713,-5.77228927612 --2.34572339058,1.84151899815,-5.77372121811 --2.33071899414,1.84352266788,-5.78614759445 --2.31371045113,1.84352886677,-5.79457950592 --2.29770350456,1.84453392029,-5.80399894714 --2.28069448471,1.8445404768,-5.81142234802 --2.26067996025,1.84255039692,-5.81386566162 --2.25367879868,1.84355163574,-5.82107591629 --2.23366332054,1.84156215191,-5.82150316238 --2.21765613556,1.84156739712,-5.83092260361 --2.19864296913,1.8405765295,-5.83435583115 --2.18063163757,1.839584589,-5.83877563477 --2.16562843323,1.84158742428,-5.85321521759 --2.14761757851,1.84159517288,-5.85864448547 --2.13460230827,1.83760511875,-5.85085868835 --2.11759328842,1.83761167526,-5.85828351974 --2.10158705711,1.83861649036,-5.86871147156 --2.08357477188,1.83762514591,-5.87212514877 --2.06255698204,1.83463716507,-5.87056493759 --2.05256605148,1.8416326046,-5.89698982239 --2.03355169296,1.83964252472,-5.89840984344 --2.02354383469,1.83864796162,-5.89862728119 --2.00453042984,1.83665704727,-5.90206384659 --1.98651921749,1.83666527271,-5.90648841858 --1.96550047398,1.83367788792,-5.90392398834 --1.95450866222,1.83967423439,-5.9293551445 --1.46120548248,1.83189570904,-6.06615161896 --1.44419789314,1.83290183544,-6.07458114624 --1.42116677761,1.82592177391,-6.05901050568 --1.40215229988,1.82493209839,-6.06044721603 --1.38213217258,1.82194566727,-6.05587387085 --1.36713254452,1.82494711876,-6.0723028183 --1.3501251936,1.82695317268,-6.08073282242 --1.33609950542,1.81996917725,-6.06295442581 --1.32210409641,1.82496833801,-6.08338069916 --1.30409193039,1.8249771595,-6.08680677414 --1.28306758404,1.81999325752,-6.07823896408 --1.26505470276,1.82000267506,-6.08066225052 --1.24905228615,1.82300591469,-6.09409427643 --1.23803758621,1.82001543045,-6.08731126785 --1.22103130817,1.82202100754,-6.09674549103 --1.20603311062,1.82602202892,-6.11417198181 --1.18500685692,1.82103908062,-6.10360050201 --1.16599142551,1.82005000114,-6.10403728485 --1.14998936653,1.82305324078,-6.1174659729 --1.13097035885,1.82006597519,-6.11388397217 --1.11095154285,1.81807899475,-6.11133146286 --1.10395693779,1.82207691669,-6.12455129623 --1.08795237541,1.82408154011,-6.13496398926 --1.06692397594,1.81809973717,-6.12239074707 --1.05092406273,1.82210195065,-6.13782501221 --1.03090059757,1.81811738014,-6.13025283813 --1.01088094711,1.81613075733,-6.12669944763 --1.00690293312,1.82511949539,-6.15591096878 --0.985874593258,1.82013785839,-6.14334392548 --0.966856479645,1.81815040112,-6.14077234268 --0.950857400894,1.82215201855,-6.15720558167 --0.928822755814,1.81517398357,-6.13864278793 --0.912823796272,1.81917560101,-6.15507507324 --0.89682495594,1.82317733765,-6.1715054512 --0.884799182415,1.8171929121,-6.15371847153 --0.866784393787,1.816203475,-6.15413713455 --0.848773419857,1.8172121048,-6.15857076645 --0.832776665688,1.82221269608,-6.17700576782 --0.815773665905,1.82521688938,-6.18944168091 --0.797764480114,1.8262244463,-6.19587945938 --0.777739107609,1.82224106789,-6.1863117218 --0.768727183342,1.82024884224,-6.18150520325 --0.752735435963,1.82724690437,-6.20495080948 --0.728673040867,1.81028389931,-6.15936803818 --0.710660219193,1.81029355526,-6.16179609299 --0.693660378456,1.8152961731,-6.17723894119 --0.675646424294,1.81430625916,-6.17866373062 --0.656630814075,1.81331765652,-6.17910909653 --0.65165990591,1.82530283928,-6.21432304382 --0.628600478172,1.81033825874,-6.17174434662 --0.610591292381,1.81134593487,-6.1781835556 --0.593584060669,1.81335258484,-6.18560123444 --0.573558986187,1.80936896801,-6.17704868317 --0.55554407835,1.80837976933,-6.1774725914 --0.539556264877,1.81737601757,-6.20391130447 --0.530551671982,1.81737983227,-6.20712900162 --0.509508430958,1.808406353,-6.18056249619 --0.492503136396,1.81041181087,-6.18998289108 --0.47348177433,1.80842638016,-6.18441867828 --0.454460144043,1.80544090271,-6.17885541916 --0.437458962202,1.80944430828,-6.19228315353 --0.418425709009,1.80346524715,-6.17469787598 --0.411452412605,1.8134521246,-6.207924366 --0.392428934574,1.81046772003,-6.20035886765 --0.375431895256,1.81546902657,-6.21778869629 --0.355401575565,1.81048846245,-6.20423746109 --0.337389916182,1.81149768829,-6.20766830444 --0.319368034601,1.80851244926,-6.20108318329 --0.300344377756,1.80552816391,-6.19352149963 --0.29134824872,1.80952763557,-6.20475053787 --0.273319214582,1.80454611778,-6.19115829468 --0.254293292761,1.800563097,-6.18159675598 --0.23628680408,1.8035697937,-6.19003486633 --0.217248439789,1.79559326172,-6.16846179962 --0.199246004224,1.79959774017,-6.18090391159 --0.190237402916,1.79860389233,-6.18011713028 --0.172232910991,1.80160927773,-6.19055557251 --0.154222458601,1.80361819267,-6.1949877739 --0.136206492782,1.80262970924,-6.19441461563 --0.118187621236,1.80164289474,-6.19084072113 --0.100179158151,1.80365073681,-6.19727325439 --0.0821695178747,1.80465888977,-6.20270442963 --0.073155798018,1.80266773701,-6.19691514969 --0.0541306585073,1.79968440533,-6.18836402893 --0.0361222550273,1.80169212818,-6.19479560852 --0.0181148778647,1.8036993742,-6.20222663879 --7.85946322139e-05,1.79672157764,-6.1826505661 --0.0119131347165,1.78927695751,-5.37004518509 -0.00608877371997,1.78527247906,-5.35844182968 -0.0150823574513,1.78126621246,-5.34564304352 -0.034105412662,1.78327250481,-5.35305738449 -0.0521224476397,1.78427600861,-5.35545063019 -0.0780836343765,1.76524746418,-5.29905223846 -0.096104003489,1.76725280285,-5.30444717407 -0.114116825163,1.76625394821,-5.30284738541 -0.12313182652,1.76925909519,-5.31004095078 -0.140132501721,1.7652541399,-5.29742670059 -0.158146560192,1.76525604725,-5.29682636261 -0.176164701581,1.76626014709,-5.30022144318 -0.194181635976,1.76626360416,-5.30261802673 -0.212189748883,1.76526224613,-5.29602336884 -0.230209752917,1.76626741886,-5.30141639709 -0.239203095436,1.76226115227,-5.28763246536 -0.257223337889,1.76426625252,-5.29302501678 -0.275234371424,1.76326656342,-5.28942871094 -0.293250352144,1.76326966286,-5.29082632065 -0.309243708849,1.75726127625,-5.27121067047 -0.329293638468,1.76828157902,-5.30460262299 -0.347295880318,1.76527714729,-5.29202079773 -0.355290591717,1.76127195358,-5.28021812439 -0.374332427979,1.77028822899,-5.30659341812 -0.391324818134,1.76327908039,-5.28500890732 -0.409345775843,1.76528477669,-5.29139614105 -0.426345437765,1.76127934456,-5.27680110931 -0.444359570742,1.76128149033,-5.27620172501 -0.453372061253,1.76328527927,-5.28139019012 -0.471381247044,1.76128482819,-5.27580165863 -0.487371504307,1.75427484512,-5.25220918655 -0.509438455105,1.77130365372,-5.30258226395 -0.525427699089,1.76329314709,-5.27799367905 -0.542429685593,1.76028895378,-5.26540088654 -0.563479661942,1.77130925655,-5.29977989197 -0.568449676037,1.76029169559,-5.26398086548 -0.585448741913,1.75528609753,-5.24839925766 -0.60750323534,1.76830852032,-5.28678417206 -0.626526594162,1.77131533623,-5.29518032074 -0.643535256386,1.77031469345,-5.28957033157 -0.661546766758,1.7703152895,-5.28597640991 -0.676537871361,1.7633061409,-5.26337480545 -0.684536159039,1.76030290127,-5.25457811356 -0.70254778862,1.76030361652,-5.25098800659 -0.719556450844,1.75830316544,-5.24538230896 -0.738577246666,1.76130855083,-5.2507853508 -0.755587756634,1.76030910015,-5.24717330933 -0.774608433247,1.76331436634,-5.25257492065 -0.791613578796,1.76031208038,-5.24298334122 -0.799619436264,1.76031279564,-5.2421631813 -0.817633867264,1.76131510735,-5.24156236649 -0.834637403488,1.75831198692,-5.22997999191 -0.853661298752,1.76131916046,-5.2393655777 -0.871675670147,1.76232147217,-5.23876428604 -0.889688193798,1.76232278347,-5.23617124557 -0.907700717449,1.76232421398,-5.23357725143 -0.917716145515,1.76532936096,-5.24176549911 -0.933720946312,1.76332712173,-5.23215532303 -0.951733469963,1.76332855225,-5.22956228256 -0.970754683018,1.76633429527,-5.23595333099 -0.987762928009,1.76533353329,-5.22935438156 -1.00778484344,1.76833951473,-5.23576498032 -1.01880252361,1.77134585381,-5.24596214294 -1.03279387951,1.76533687115,-5.22237157822 -1.05080723763,1.7653387785,-5.2207736969 -1.0587720871,1.74931776524,-5.17217206955 -1.08984994888,1.77135026455,-5.23356771469 -1.1078659296,1.77335357666,-5.23495340347 -1.12889277935,1.77836167812,-5.24635601044 -1.13187360764,1.77035045624,-5.2205452919 -1.15189599991,1.77335679531,-5.22794532776 -1.16990697384,1.77335727215,-5.22335863113 -1.19595754147,1.78637695312,-5.25874567032 -1.2069375515,1.77536308765,-5.22415876389 -1.22595751286,1.77836823463,-5.22954273224 -1.23995292187,1.77336156368,-5.2099480629 -1.24594414234,1.76835513115,-5.19316625595 -1.26295661926,1.76835691929,-5.19154500961 -1.28398156166,1.77336418629,-5.20094966888 -1.29496669769,1.76435303688,-5.17135047913 -1.3139834404,1.7663564682,-5.17275571823 -1.32798016071,1.7613505125,-5.15416479111 -1.34800076485,1.76435601711,-5.15956878662 -1.35600435734,1.76335549355,-5.15576410294 -1.36899888515,1.75834870338,-5.13516664505 -1.3850029707,1.75534629822,-5.1235833168 -1.41105043888,1.76836442947,-5.15694856644 -1.4200271368,1.75634920597,-5.11738204956 -1.43904519081,1.75835359097,-5.1207742691 -1.45605647564,1.75835466385,-5.11716556549 -1.46205246449,1.75535070896,-5.10536909103 -1.4790623188,1.75535106659,-5.09977293015 -1.49908220768,1.75835609436,-5.10417890549 -1.51709485054,1.7583578825,-5.10158491135 -1.52808713913,1.75235033035,-5.07897043228 -1.55211997032,1.76036119461,-5.09637451172 -1.5671235323,1.75735902786,-5.08477592468 -1.57211732864,1.75335419178,-5.07097625732 -1.59514641762,1.76036322117,-5.08438158035 -1.60814344883,1.75535786152,-5.06578874588 -1.62916612625,1.75936412811,-5.07319021225 -1.64718031883,1.76036667824,-5.0725812912 -1.65817153454,1.75335884094,-5.04799127579 -1.67018735409,1.75736403465,-5.05619096756 -1.68719887733,1.75836527348,-5.05258083344 -1.70019686222,1.75336050987,-5.03498744965 -2.23054361343,1.77040064335,-4.90424442291 -2.23051738739,1.75638639927,-4.86065387726 -2.25554513931,1.76339459419,-4.87305355072 -2.26954841614,1.76139259338,-4.85947132111 -2.29056739807,1.76539719105,-4.86287069321 -2.30557441711,1.7643969059,-4.85426235199 -2.32059311867,1.76940310001,-4.86546182632 -2.33860516548,1.77040481567,-4.8618645668 -2.36162853241,1.77641129494,-4.8702507019 -2.37262606621,1.77140700817,-4.85066747665 -2.37660980225,1.76139688492,-4.81609344482 -2.39762973785,1.76640200615,-4.82146787643 -2.41564202309,1.76740396023,-4.81787014008 -2.42665171623,1.76940619946,-4.81908082962 -2.4456653595,1.77140855789,-4.81649208069 -2.45967078209,1.7704076767,-4.80588340759 -2.46966743469,1.7654030323,-4.78529834747 -2.49369168282,1.7714099884,-4.79468536377 -2.5016849041,1.76540398598,-4.77010345459 -2.51969671249,1.76640570164,-4.76551532745 -2.53170919418,1.7694092989,-4.77070140839 -2.54070472717,1.76440441608,-4.74911212921 -2.56072020531,1.76640760899,-4.7485203743 -2.57572746277,1.76640737057,-4.73892402649 -2.58873128891,1.76440608501,-4.72632074356 -2.60974812508,1.76740968227,-4.72673606873 -2.63076615334,1.77141392231,-4.72912883759 -2.63175845146,1.76640939713,-4.71233320236 -2.64977025986,1.76741111279,-4.7077422142 -2.67178916931,1.77141582966,-4.71114110947 -2.6857945919,1.77041482925,-4.6995472908 -2.70080184937,1.77041482925,-4.68995141983 -2.71580910683,1.76941478252,-4.68035650253 -2.73382139206,1.77141678333,-4.67675161362 -2.73882126808,1.76941537857,-4.66795063019 -2.76184153557,1.77442038059,-4.67235183716 -2.77384281158,1.77141797543,-4.65577793121 -2.79385852814,1.77442145348,-4.65616464615 -2.81287193298,1.7764236927,-4.65257692337 -2.82086825371,1.77141940594,-4.63098573685 -2.83287930489,1.77442252636,-4.63516998291 -2.84588336945,1.77242136002,-4.62158298492 -2.86589860916,1.77542436123,-4.62097787857 -2.88290882111,1.77642560005,-4.61438512802 -2.8969142437,1.77542483807,-4.60180616379 -2.91392493248,1.77642631531,-4.59620141983 -2.92492628098,1.77342402935,-4.57961463928 -2.93894004822,1.77742826939,-4.58679628372 -2.95595026016,1.77842915058,-4.57921457291 -2.96695184708,1.77542722225,-4.56361627579 -2.98796772957,1.77843058109,-4.56302499771 -2.99796795845,1.77542805672,-4.54543304443 -3.01698184013,1.7784307003,-4.54282712936 -3.03299045563,1.77843129635,-4.53423833847 -3.04199671745,1.77943253517,-4.53243160248 -3.06201100349,1.78243529797,-4.52984237671 -3.07301282883,1.77943348885,-4.51424694061 -3.09202623367,1.78243589401,-4.51065063477 -3.11103868484,1.7834379673,-4.50606584549 -3.12204098701,1.78143632412,-4.4904718399 -3.13704872131,1.78143668175,-4.48087644577 -3.15106153488,1.78544020653,-4.48607063293 -3.17207694054,1.78844344616,-4.48546934128 -3.17907381058,1.78343987465,-4.4638800621 -3.19708585739,1.78544199467,-4.45927381516 -3.20808815956,1.78344023228,-4.44269561768 -3.22910404205,1.78744363785,-4.44209098816 -3.25312900543,1.7964515686,-4.46127891541 -3.24710893631,1.78344190121,-4.41972017288 -3.27012729645,1.78844618797,-4.42211055756 -3.28213119507,1.78744518757,-4.40752506256 -3.30214571953,1.79044818878,-4.40591192245 -3.31615185738,1.78944814205,-4.394323349 -3.32415103912,1.78544557095,-4.37473535538 -3.34817552567,1.79545307159,-4.39292240143 -3.35517334938,1.79045021534,-4.37233066559 -3.39120650291,1.80245959759,-4.39072608948 -3.37918186188,1.78744864464,-4.34415102005 -3.40420174599,1.79345333576,-4.34755325317 -3.40819644928,1.7874494791,-4.32296705246 -3.43922305107,1.79645657539,-4.33436203003 -3.44222140312,1.79345488548,-4.32258033752 -3.4602329731,1.79545688629,-4.31697893143 -3.47323894501,1.79545688629,-4.305372715 -3.48624420166,1.7934564352,-4.29179525375 -3.50525665283,1.79645872116,-4.28719568253 -3.52326798439,1.79846036434,-4.28060626984 -3.52926588058,1.7934576273,-4.25902080536 -3.54227614403,1.7974601984,-4.26121711731 -3.56028747559,1.79946208,-4.25561237335 -3.57028961182,1.79646074772,-4.23804044724 -3.58930230141,1.79946303368,-4.23343801498 -3.60130691528,1.7974627018,-4.21984434128 -3.61431288719,1.7974627018,-4.20725297928 -3.62832379341,1.80046546459,-4.21044874191 -3.64233088493,1.80046606064,-4.19984531403 -3.652333498,1.79846477509,-4.18227624893 -3.66133546829,1.79546368122,-4.16567707062 -3.68735527992,1.80246829987,-4.16907072067 -3.6983590126,1.80046772957,-4.1534910202 -3.71336722374,1.80046868324,-4.14388990402 -3.71636676788,1.79946744442,-4.13310241699 -3.73337697983,1.80046916008,-4.12550544739 -3.74438118935,1.79946863651,-4.11091136932 -3.76839828491,1.80447256565,-4.11130952835 -3.77439761162,1.80047059059,-4.09072399139 -3.79641270638,1.80447363853,-4.0881319046 -3.81542468071,1.80647563934,-4.08154964447 -3.81542158127,1.80347394943,-4.06874608994 -3.85245108604,1.81448161602,-4.08313798904 -3.85344552994,1.8084782362,-4.05656337738 -3.86044645309,1.80547690392,-4.03796672821 -3.87445378304,1.80547761917,-4.02637767792 -3.89346551895,1.80747961998,-4.01979207993 -3.89145827293,1.8004758358,-3.9912071228 -3.90947198868,1.80547952652,-3.99838876724 -3.92948508263,1.80948185921,-3.99280238152 -3.932482481,1.804479599,-3.97020769119 -3.94949245453,1.80548107624,-3.96063542366 -3.96650290489,1.80748283863,-3.95303058624 -3.95448708534,1.79547667503,-3.91445398331 -3.93646645546,1.78046905994,-3.86988306046 -3.92745614052,1.77246534824,-3.84710764885 -3.90242981911,1.75445628166,-3.79554700851 -3.89141654968,1.74345099926,-3.75897455215 -3.88240480423,1.73244643211,-3.72440648079 -3.86238431931,1.71743929386,-3.6798312664 -3.8553750515,1.7074354887,-3.64727282524 -3.87338733673,1.71043813229,-3.6416683197 -3.87238526344,1.70743703842,-3.62887263298 -3.87938833237,1.70443689823,-3.61129355431 -3.90140414238,1.70944046974,-3.60870170593 -3.90040063858,1.70243859291,-3.58411455154 -3.91541051865,1.70444047451,-3.57452893257 -3.92841887474,1.70444202423,-3.56392836571 -3.92341375351,1.69944012165,-3.54714226723 -3.93842363358,1.70044207573,-3.53755712509 -3.95743703842,1.70444488525,-3.53196525574 -3.95042943954,1.69544219971,-3.50237846375 -3.96143627167,1.69444322586,-3.48880052567 -3.97244334221,1.69444453716,-3.47620463371 -3.97644495964,1.69044423103,-3.45662283897 -3.98745274544,1.69344615936,-3.45581436157 -4.00246286392,1.69444811344,-3.44622898102 -4.00746536255,1.69144809246,-3.42764663696 -4.00946569443,1.68744766712,-3.40607237816 -4.02347517014,1.68844974041,-3.39647173882 -4.03148031235,1.68645048141,-3.38088583946 -4.04148674011,1.68545174599,-3.3672952652 -4.05549669266,1.68945407867,-3.36849427223 -4.04849100113,1.6814520359,-3.33991384506 -4.06149959564,1.68245398998,-3.32833409309 -4.07751083374,1.6834564209,-3.31974577904 -4.0785112381,1.67945611477,-3.29914736748 -4.09252119064,1.68045818806,-3.28856492043 -4.09652423859,1.6804587841,-3.28077363968 -4.10052633286,1.67745912075,-3.26218700409 -4.11253499985,1.67746090889,-3.24961161613 -4.12354278564,1.67746257782,-3.23702096939 -4.12854576111,1.67446327209,-3.22041511536 -4.13655185699,1.67346441746,-3.20483613014 -4.15256309509,1.67546701431,-3.19624590874 -4.14555883408,1.6704659462,-3.17946243286 -4.15956830978,1.67146813869,-3.16986107826 -4.16957569122,1.67046976089,-3.15529537201 -4.17257833481,1.66747033596,-3.1367020607 -4.18058443069,1.66647171974,-3.12210774422 -4.19459438324,1.66747415066,-3.11152505875 -4.19859790802,1.66547501087,-3.09393024445 -4.19559669495,1.66147470474,-3.08015704155 -4.2136092186,1.66447770596,-3.07355546951 -4.21561193466,1.6604783535,-3.05397319794 -4.2306227684,1.66248095036,-3.0443854332 -4.24163103104,1.66348290443,-3.03277826309 -4.2386302948,1.65748310089,-3.0092048645 -4.25364112854,1.65948569775,-2.99961686134 -4.25764465332,1.65848648548,-2.99183177948 -4.26465034485,1.65748810768,-2.97624707222 -4.27065610886,1.65548956394,-2.95966911316 -4.28266525269,1.65649187565,-2.94807696342 -4.29267263412,1.65649390221,-2.93547654152 -4.30268096924,1.65649592876,-2.92189598083 -4.31268882751,1.65649807453,-2.90831565857 -4.29968214035,1.64849698544,-2.88853549957 -4.32369852066,1.65450072289,-2.88593006134 -4.33270597458,1.65450274944,-2.8723359108 -4.33370923996,1.65050387383,-2.85275363922 -4.34171628952,1.65050578117,-2.83816719055 -4.35772752762,1.65250885487,-2.82956910133 -4.34572172165,1.64550805092,-2.81079173088 -4.36373472214,1.64851117134,-2.80222082138 -4.37274265289,1.64851331711,-2.78960824013 -4.37674760818,1.64651501179,-2.77203083038 -4.38175344467,1.64451694489,-2.75544762611 -4.3937625885,1.6455193758,-2.74385547638 -4.392765522,1.6415207386,-2.72327637672 -4.40077114105,1.64252233505,-2.71848630905 -4.41177988052,1.64352476597,-2.70590162277 -4.41478490829,1.64052653313,-2.68831586838 -4.41478824615,1.63652813435,-2.66873335838 -4.42379617691,1.63653051853,-2.65514469147 -4.43580627441,1.6385332346,-2.64355230331 -4.44881629944,1.63953614235,-2.63197302818 -4.45282030106,1.63953733444,-2.6251718998 -4.44982242584,1.63453876972,-2.60359764099 -4.46383285522,1.63654172421,-2.59300971031 -4.47884464264,1.63854467869,-2.58341264725 -4.47684717178,1.63454639912,-2.56283307076 -4.48585605621,1.63454914093,-2.54826617241 -4.48786067963,1.63155114651,-2.53067588806 -4.48286056519,1.62855172157,-2.51789140701 -4.49787187576,1.63055479527,-2.50829386711 -4.51488399506,1.6335580349,-2.49969816208 -4.51388788223,1.62955999374,-2.48011612892 -4.52089595795,1.62956273556,-2.46454739571 -4.52790355682,1.62856531143,-2.4499578476 -4.52590465546,1.62656629086,-2.43917155266 -4.52791023254,1.62356865406,-2.42158746719 -4.54392194748,1.62657177448,-2.41297721863 -4.54792881012,1.62457442284,-2.39541816711 -4.54993438721,1.62257683277,-2.37783575058 -4.55794286728,1.62257957458,-2.36423826218 -4.56795167923,1.62258243561,-2.35164260864 -4.56395292282,1.61958360672,-2.33985924721 -4.59196996689,1.62758743763,-2.33627605438 -4.5829706192,1.62158942223,-2.3136780262 -4.58797836304,1.619592309,-2.29711270332 -4.61099338531,1.62559592724,-2.29151129723 -4.60599660873,1.62059831619,-2.26994180679 -4.61100387573,1.61960124969,-2.25435495377 -4.62001037598,1.62160301208,-2.24956893921 -4.61601352692,1.61660540104,-2.22997021675 -4.62402296066,1.61660850048,-2.21539640427 -4.63703393936,1.61861169338,-2.20381116867 -4.63203716278,1.61461436749,-2.18322682381 -4.63904571533,1.6136174202,-2.16864299774 -4.66005992889,1.61862099171,-2.16105461121 -4.65305948257,1.61462211609,-2.14924883842 -4.6520652771,1.61162507534,-2.13066792488 -4.66207504272,1.61262834072,-2.11709427834 -4.66708278656,1.61163151264,-2.10151195526 -4.66308736801,1.60763430595,-2.08192491531 -4.68710279465,1.6136380434,-2.07534050941 -4.68110322952,1.60963952541,-2.06355118752 -4.68311023712,1.60764253139,-2.04696178436 -4.69712209702,1.61064612865,-2.03538346291 -4.69912862778,1.60864925385,-2.01879477501 -4.69813489914,1.60565257072,-2.00022172928 -4.72215032578,1.61165618896,-1.99363005161 -4.70515012741,1.60265910625,-1.96805667877 -4.71715784073,1.60566091537,-1.96524858475 -4.72816801071,1.60766434669,-1.95266067982 -4.72917556763,1.60566782951,-1.93508815765 -4.73118257523,1.60367119312,-1.91850352287 -4.74019241333,1.60467469692,-1.90491855145 -4.74119949341,1.60267806053,-1.88832509518 -4.74120616913,1.59968161583,-1.87074649334 -4.75521469116,1.60368347168,-1.86795306206 -4.75122022629,1.59968698025,-1.84838306904 -4.7562289238,1.59969043732,-1.83378338814 -4.77324151993,1.60269427299,-1.82320451736 -4.76224517822,1.59669780731,-1.80161833763 -4.77025508881,1.59770154953,-1.78704810143 -4.78626728058,1.600705266,-1.77645742893 -4.78026866913,1.59770703316,-1.76566195488 -4.77427387238,1.59271073341,-1.74608123302 -4.79328727722,1.59771442413,-1.73649299145 -4.79229450226,1.59471821785,-1.71891212463 -4.79630374908,1.59472203255,-1.70332932472 -4.80831480026,1.59572589397,-1.69074738026 -4.80631780624,1.5947278738,-1.68096804619 -4.80132436752,1.59073174,-1.66237843037 -4.83434200287,1.59973537922,-1.65778791904 -4.82734727859,1.59573936462,-1.63820540905 -4.82435417175,1.59274351597,-1.61963546276 -4.83936595917,1.59574711323,-1.6090284586 -4.84137487411,1.59475111961,-1.59245407581 -4.84237861633,1.59375309944,-1.58465540409 -4.84338712692,1.59175741673,-1.56709814072 -4.84139442444,1.58976125717,-1.55049228668 -4.85140514374,1.59076535702,-1.53691411018 -4.85441398621,1.5897693634,-1.52132642269 -4.85642290115,1.58877372742,-1.50475549698 -4.85742712021,1.58777570724,-1.49695825577 -4.86543750763,1.5887799263,-1.4823871851 -4.8614449501,1.58578407764,-1.46479427814 -4.87745761871,1.58978796005,-1.45321249962 -4.87546539307,1.58679258823,-1.43563687801 -4.87747430801,1.58579671383,-1.42004394531 -4.88648462296,1.58680081367,-1.40645563602 -4.89049053192,1.58780300617,-1.39868175983 -4.89450025558,1.58680737019,-1.38310456276 -4.88850736618,1.58281207085,-1.36452698708 -4.89551734924,1.58381605148,-1.350923419 -4.91153001785,1.58781993389,-1.33933544159 -4.90853786469,1.58482456207,-1.3217574358 -4.92655181885,1.58982861042,-1.31018149853 -4.91855382919,1.58583128452,-1.29939639568 -4.92256355286,1.58583557606,-1.28479504585 -4.93557548523,1.58783984184,-1.27123165131 -4.9285826683,1.5838445425,-1.2536290884 -4.92659139633,1.58184945583,-1.23606216908 -4.94160366058,1.58585333824,-1.22446095943 -4.93761205673,1.58285844326,-1.20590651035 -4.93961715698,1.58286046982,-1.19909393787 -4.944627285,1.58286523819,-1.18352520466 -4.94863700867,1.58286964893,-1.16892492771 -4.95464801788,1.5828744173,-1.1533626318 -4.95565700531,1.58187913895,-1.137768507 -4.95266628265,1.57888424397,-1.12020051479 -4.95667123795,1.57988631725,-1.11340034008 -4.96868371964,1.58289074898,-1.09982442856 -4.97069311142,1.58189558983,-1.08423733711 -4.96370124817,1.57790064812,-1.06664764881 -4.97371339798,1.57990527153,-1.0520837307 -4.98272418976,1.58190977573,-1.03848767281 -4.98873519897,1.58291435242,-1.02389907837 -4.99074029922,1.5829167366,-1.01611149311 -4.98374843597,1.57892215252,-0.998525857925 -4.99276065826,1.58092689514,-0.983953893185 -5.0027718544,1.58293128014,-0.970361530781 -4.99177932739,1.57793700695,-0.951782166958 -4.99579048157,1.57794201374,-0.936208486557 -5.01180315018,1.58194625378,-0.923620998859 -5.00680685043,1.57894909382,-0.914823055267 -5.00481653214,1.5779542923,-0.898243367672 -5.0158290863,1.57995915413,-0.88367921114 -5.01483869553,1.5789642334,-0.868079960346 -5.02985143661,1.58296871185,-0.854508161545 -5.0298614502,1.5809738636,-0.838914215565 -5.02187013626,1.57797968388,-0.821333646774 -5.02187585831,1.57698249817,-0.8125628829 -5.04188919067,1.58298635483,-0.80096000433 -5.0278968811,1.57699263096,-0.782380461693 -5.03690862656,1.578997612,-0.767802834511 -5.05092144012,1.58300197124,-0.754220426083 -5.04493093491,1.57900774479,-0.737628221512 -5.03193426132,1.57401156425,-0.726854324341 -5.04794740677,1.57901597023,-0.713278830051 -5.04895782471,1.57802128792,-0.697691917419 -5.04996824265,1.57802677155,-0.682105064392 -5.05097866058,1.57703208923,-0.666518747807 -5.0549902916,1.57803750038,-0.650943875313 -5.06600284576,1.58004236221,-0.636369764805 -5.06300735474,1.57904517651,-0.628563344479 -5.05801725388,1.5760512352,-0.611981272697 -5.05002737045,1.57305765152,-0.594415128231 -5.0750412941,1.58006107807,-0.582811176777 -5.06105041504,1.57406818867,-0.564251601696 -5.06106138229,1.5740737915,-0.548663318157 -5.08207464218,1.58007752895,-0.536066234112 -5.06307792664,1.57308220863,-0.525288581848 -5.05808830261,1.57108843327,-0.508711457253 -5.07110118866,1.57409334183,-0.494138807058 -5.06211090088,1.57109975815,-0.47755074501 -5.06612300873,1.57110536098,-0.461976438761 -5.08213567734,1.57610976696,-0.448383271694 -5.05914449692,1.56811761856,-0.429811447859 -5.08515310287,1.57611823082,-0.425011008978 -5.0911655426,1.57712376118,-0.409439861774 -5.07217407227,1.57013130188,-0.391857117414 -5.07218551636,1.56913733482,-0.37627223134 -5.09619951248,1.57714104652,-0.362691938877 -5.08320999146,1.57214844227,-0.345127940178 -5.07121372223,1.56815254688,-0.336334466934 -5.09722805023,1.57615590096,-0.323728710413 -5.08723926544,1.57216310501,-0.30617415905 -5.07424879074,1.56717038155,-0.289589673281 -5.09426259995,1.57317447662,-0.275992661715 -5.08127307892,1.56818211079,-0.258436173201 -5.09228610992,1.57118713856,-0.243846029043 -5.10229253769,1.57418906689,-0.237045094371 -5.07330179214,1.56419837475,-0.218491092324 -5.09031438828,1.5692025423,-0.204883232713 -5.09532690048,1.57120835781,-0.189306974411 -5.08533811569,1.56721556187,-0.172735646367 -5.08034944534,1.56522226334,-0.157146498561 -5.09636259079,1.57022678852,-0.142558127642 -5.09936904907,1.57122981548,-0.134770080447 -5.08938026428,1.56723713875,-0.118201941252 -5.10139274597,1.57124209404,-0.103605814278 -5.09840536118,1.56924915314,-0.0870461836457 -5.08841609955,1.56625628471,-0.0714546665549 -5.09642887115,1.5682618618,-0.0558793358505 -5.0954413414,1.56826841831,-0.0402962192893 -5.07544565201,1.56127381325,-0.0315180756152 -5.09445953369,1.56727802753,-0.016922717914 -5.0934715271,1.56628465652,-0.00134056503884 -5.09248352051,1.56629121304,0.0142415929586 -5.09149694443,1.56529808044,0.0307970456779 -5.09350824356,1.56630408764,0.0454040728509 -5.08051395416,1.5613090992,0.0541712678969 -5.09452772141,1.56631410122,0.0697496905923 -5.09454011917,1.56632065773,0.0853310078382 -5.0835518837,1.56232833862,0.100911915302 -5.09356498718,1.56533384323,0.116493172944 -5.09557771683,1.56634032726,0.132074713707 -5.08658981323,1.56234788895,0.147653222084 -5.08059597015,1.56135201454,0.155441880226 -5.08860874176,1.56335771084,0.171024739742 -5.08362102509,1.56136500835,0.186602845788 -5.08363389969,1.56137168407,0.202182993293 -5.07964658737,1.56037890911,0.217760697007 -5.0776591301,1.55938601494,0.233338996768 -5.07566547394,1.55938959122,0.241127505898 -5.07567834854,1.55939638615,0.256707012653 -5.08269166946,1.56140232086,0.272292882204 -5.08070468903,1.56140935421,0.287871211767 -5.07471752167,1.55941700935,0.303444743156 -5.07273054123,1.55842411518,0.319021910429 -5.07374382019,1.55943083763,0.334602832794 -5.06974887848,1.55743432045,0.341413617134 -5.06776237488,1.55744159222,0.356990396976 -5.07077503204,1.55844807625,0.372573971748 -5.07978963852,1.5614541769,0.389141023159 -5.06780195236,1.55746233463,0.4037283957 -5.06781482697,1.55746936798,0.419307917356 -5.07282829285,1.55947566032,0.434896498919 -5.0758357048,1.56147909164,0.443666040897 -5.06784820557,1.55848693848,0.458257526159 -5.07286262512,1.56049358845,0.47482123971 -5.07187461853,1.56050026417,0.489425987005 -5.07088804245,1.56050753593,0.505004525185 -5.06390190125,1.55851578712,0.520569741726 -5.07290935516,1.5615183115,0.52935397625 -5.06292200089,1.55852651596,0.543937921524 -5.05593538284,1.55653440952,0.558527767658 -5.05994939804,1.55854129791,0.575091779232 -5.06896305084,1.56154739857,0.591669380665 -5.05997657776,1.55955564976,0.606253385544 -5.05799007416,1.55956315994,0.621829032898 -5.04799699783,1.55656802654,0.628617942333 -5.06401014328,1.56157279015,0.645217835903 -5.05502462387,1.55958163738,0.660773515701 -5.05203771591,1.55858898163,0.675371944904 -5.04805183411,1.55759692192,0.690940976143 -5.04706573486,1.5576043129,0.706519186497 -5.0370798111,1.55561304092,0.721094429493 -5.05408668518,1.56161439419,0.730889081955 -5.04410028458,1.55862319469,0.745463788509 -5.04311466217,1.55863058567,0.761042356491 -5.05612754822,1.56363582611,0.777644753456 -5.04814291,1.56164479256,0.793199419975 -5.03515625,1.55765366554,0.80678653717 -5.0391702652,1.55966079235,0.823358297348 -5.03017807007,1.55766582489,0.830141603947 -5.03419160843,1.55967235565,0.84573996067 -5.03220558167,1.55968022346,0.861315369606 -5.02822065353,1.55868840218,0.876882493496 -5.03123378754,1.56069517136,0.892478585243 -5.02224874496,1.55770397186,0.907050549984 -5.02225589752,1.55870771408,0.914842486382 -5.03127002716,1.56271409988,0.932413876057 -5.00528478622,1.55472540855,0.943987488747 -5.01329851151,1.55773162842,0.96058100462 -5.0203127861,1.56173801422,0.977171957493 -5.00732755661,1.55774748325,0.990748345852 -5.00634145737,1.55775523186,1.00632834435 -5.01234912872,1.56075847149,1.01609790325 -5.01136398315,1.56176626682,1.03167903423 -5.00137853622,1.55877518654,1.04526734352 -5.01239204407,1.5627809763,1.06285667419 -5.00140810013,1.560790658,1.07741367817 -4.9934220314,1.55879926682,1.09101045132 -4.99443721771,1.55980706215,1.10757648945 -4.98544454575,1.55781209469,1.11337387562 -4.98745965958,1.55981969833,1.129945755 -5.00347280502,1.56582462788,1.14854323864 -4.98048877716,1.55883610249,1.16010761261 -4.98650360107,1.56184315681,1.17767775059 -5.00151777267,1.56884837151,1.19627535343 -4.9875254631,1.56385433674,1.20106685162 -4.98553991318,1.5648624897,1.21664512157 -4.98455476761,1.56487035751,1.23222899437 -4.97757005692,1.56387925148,1.2468034029 -4.98158550262,1.56688678265,1.26436698437 -4.97260046005,1.56489598751,1.27795422077 -4.93161773682,1.55191028118,1.28452038765 -4.31163215637,1.59703457355,3.01699542999 -4.2876458168,1.58904409409,3.01077151299 -4.273665905,1.58705580235,3.02035093307 -4.24968767166,1.58106970787,3.02292966843 -4.24970579147,1.58507907391,3.04250264168 -4.22672748566,1.57909250259,3.04509305954 -4.21774721146,1.57910382748,3.05865883827 -4.21776533127,1.58311331272,3.07823419571 -4.20677661896,1.58011996746,3.0800242424 -4.19579648972,1.58013141155,3.09160256386 -4.19081497192,1.58114159107,3.10718774796 -4.17083692551,1.57715499401,3.11275315285 -4.16885566711,1.58016502857,3.13132238388 -4.17187309265,1.58517372608,3.15290760994 -4.14889526367,1.58018743992,3.15548706055 -4.1489033699,1.58119165897,3.16429877281 -4.14792251587,1.58520150185,3.18386650085 -4.12694358826,1.58021473885,3.18745326996 -4.11496496201,1.58022677898,3.19901442528 -4.10698413849,1.58023774624,3.21259713173 -4.09900379181,1.58124864101,3.22618031502 -4.09101438522,1.58025479317,3.22997021675 -4.08703374863,1.58226537704,3.24753522873 -4.06905508041,1.57827806473,3.25312232971 -4.06807374954,1.58228778839,3.27269625664 -4.06509256363,1.58529782295,3.2902803421 -4.04911422729,1.58331036568,3.29785776138 -4.03812551498,1.58031749725,3.29963731766 -4.04214191437,1.58632576466,3.32223629951 -4.02416467667,1.58333909512,3.32879972458 -4.01618385315,1.58334994316,3.34238529205 -4.00720453262,1.58436155319,3.35595464706 -4.00822305679,1.58937096596,3.3775305748 -3.98624610901,1.584384799,3.3801047802 -3.98325490952,1.58538961411,3.38691496849 -3.97527551651,1.58640098572,3.40148210526 -3.96529603004,1.58641266823,3.41405582428 -3.95231699944,1.58542454243,3.42363858223 -3.93433880806,1.58143770695,3.42921495438 -3.93435740471,1.58644711971,3.44980096817 -3.9223780632,1.58545899391,3.46038007736 -3.91239023209,1.58346617222,3.46315026283 -3.90640997887,1.58547687531,3.47873425484 -3.89742970467,1.5864880085,3.49132585526 -3.88845038414,1.58649945259,3.50489807129 -3.87047290802,1.58351278305,3.5104701519 -3.86949181557,1.58852267265,3.53104615211 -3.85851287842,1.58853447437,3.5426235199 -3.84952330589,1.58654069901,3.54442763329 -3.84154415131,1.58755207062,3.55899953842 -3.83456468582,1.58956336975,3.5745704174 -3.82258486748,1.58857488632,3.58416843414 -3.8226044178,1.59358489513,3.60673141479 -3.80162787437,1.58959889412,3.60930323601 -3.79663777351,1.58960449696,3.6151008606 -3.78665876389,1.59061610699,3.62767744064 -3.7796792984,1.59262728691,3.64325165749 -3.76769971848,1.5916390419,3.65284943581 -3.75672078133,1.59165084362,3.66442775726 -3.73674440384,1.5876647234,3.66799259186 -3.73576331139,1.59267437458,3.68858408928 -3.73777270317,1.59567916393,3.70236063004 -3.71879529953,1.5926926136,3.70594263077 -3.71081614494,1.59370398521,3.72052073479 -3.69983744621,1.59371590614,3.73209953308 -3.68585920334,1.59272825718,3.74067878723 -3.67987966537,1.59573924541,3.75725865364 -3.6659014225,1.59375178814,3.76583743095 -3.65891218185,1.59375786781,3.76963567734 -3.64393544197,1.59277105331,3.77819538116 -3.63995409012,1.59578108788,3.79579615593 -3.63597464561,1.5987919569,3.81536269188 -3.61799693108,1.59580492973,3.81895637512 -3.60801911354,1.59781706333,3.83251976967 -3.60002994537,1.59582340717,3.83531665802 -3.58805251122,1.59583604336,3.84687805176 -3.58607149124,1.60084593296,3.86746931076 -3.56909370422,1.59785878658,3.87206077576 -3.55711555481,1.59787106514,3.88264083862 -3.55413556099,1.60288155079,3.90321683884 -3.53415966034,1.59889566898,3.90578484535 -3.54216766357,1.60589897633,3.92657208443 -3.52619075775,1.6039121151,3.93314671516 -3.51121234894,1.60192465782,3.93973970413 -3.50623297691,1.60593557358,3.95831727982 -3.4942548275,1.60594773293,3.96889925003 -3.47028040886,1.59996294975,3.9674539566 -3.4613006115,1.60097396374,3.98005867004 -3.45831179619,1.60297989845,3.98983073235 -3.43733596802,1.59899413586,3.99040675163 -3.43435573578,1.60300433636,4.01099348068 -3.42537736893,1.60501623154,4.02556657791 -3.40939974785,1.60302913189,4.03115415573 -3.39642214775,1.60304164886,4.04073238373 -3.39743208885,1.60604643822,4.05451917648 -3.37845563889,1.6030601263,4.05709648132 -3.37247633934,1.60607123375,4.07468128204 -3.3604991436,1.60708391666,4.08624744415 -3.34752058983,1.60609591007,4.09484291077 -3.33154344559,1.60410892963,4.10042762756 -3.33156394958,1.61111927032,4.12698936462 -3.3145775795,1.60612761974,4.11878108978 -3.30359911919,1.60613965988,4.13036775589 -3.30161881447,1.61214971542,4.15295791626 -3.28164339066,1.60816395283,4.15452623367 -3.26766633987,1.60817670822,4.16310167313 -3.25968766212,1.61018824577,4.17868709564 -3.25269937515,1.61019492149,4.18346643448 -3.24072241783,1.6112074852,4.19503545761 -3.23174333572,1.61321890354,4.20863389969 -3.20676898956,1.60623395443,4.20320510864 -3.20079088211,1.61024558544,4.22277164459 -3.18681311607,1.60925805569,4.23036241531 -3.17283630371,1.60927093029,4.23893690109 -3.17084670067,1.61127626896,4.24972677231 -3.16586709023,1.61628711224,4.26931810379 -3.14689183235,1.61330127716,4.27188301086 -3.12991452217,1.61031413078,4.27448797226 -3.12593650818,1.61632549763,4.29804182053 -3.1079595089,1.61333870888,4.29964113235 -3.09498286247,1.61335170269,4.31020689011 -3.09399342537,1.61635696888,4.32299184799 -3.08101606369,1.61636948586,4.33257389069 -3.0630402565,1.61438310146,4.3351559639 -3.05806088448,1.61839413643,4.35574150085 -3.04108524323,1.61640763283,4.3603143692 -3.03110718727,1.61841964722,4.37390089035 -3.02512812614,1.62343072891,4.39348506927 -3.01014256477,1.61843919754,4.3872590065 -2.99916505814,1.62045145035,4.39983987808 -2.99018621445,1.62246286869,4.41443586349 -2.97221064568,1.62047660351,4.41701459885 -2.96223378181,1.62248909473,4.43257665634 -2.94925618172,1.62250137329,4.44117450714 -2.94126820564,1.62150800228,4.44396305084 -2.9322912693,1.62552046776,4.46152019501 -2.92331242561,1.6275318861,4.47611999512 -2.90333747864,1.6235461235,4.47569608688 -2.89236068726,1.62555849552,4.48926877975 -2.87838411331,1.62557148933,4.49784660339 -2.86240839958,1.62458479404,4.50342321396 -2.86141872406,1.62859022617,4.51721096039 -2.8484416008,1.62860274315,4.52679729462 -2.82546758652,1.62361764908,4.52137231827 -2.81649017334,1.62662947178,4.53794956207 -2.80951166153,1.63064110279,4.55753183365 -2.79353547096,1.62965416908,4.5621213913 -2.78754687309,1.6306604147,4.56791257858 -2.7805685997,1.63467180729,4.58749818802 -2.7585940361,1.62968635559,4.58307647705 -2.74961638451,1.63269817829,4.5996594429 -2.73564076424,1.63371157646,4.60922718048 -2.7266626358,1.63672339916,4.62581253052 -2.72768306732,1.64673340321,4.66038703918 -2.71169710159,1.64074158669,4.64918088913 -2.69971990585,1.6427539587,4.66076898575 -2.69874048233,1.65076446533,4.69234514236 -2.6827647686,1.65077781677,4.69792366028 -2.65979099274,1.64479267597,4.69149923325 -2.66680932045,1.65980136395,4.7370839119 -2.64583492279,1.65481567383,4.73366498947 -2.63284826279,1.65082335472,4.72745513916 -2.65386366844,1.67582952976,4.80002784729 -2.63788723946,1.67484259605,4.80462360382 -2.61591386795,1.66985762119,4.80118370056 -2.60093808174,1.66987085342,4.80876350403 -2.60395812988,1.68288052082,4.85033607483 -2.59798002243,1.68889200687,4.8749165535 -2.57499527931,1.67790126801,4.8487200737 -2.59001207352,1.69890856743,4.9132976532 -2.56903815269,1.69492328167,4.91086864471 -2.55906009674,1.69893491268,4.92647218704 -2.52209091187,1.68295288086,4.89403104782 -2.53610682487,1.70395994186,4.95663022995 -2.52212142944,1.6999682188,4.94940567017 -2.51514339447,1.70597970486,4.97298955917 -2.50216722488,1.70799267292,4.9855670929 -2.48819088936,1.70900535583,4.99515628815 -2.47021603584,1.70701920986,4.99773406982 -2.46123886108,1.71203124523,5.01831388474 -2.44326400757,1.71004509926,5.02089214325 -2.43227767944,1.70805263519,5.01867437363 -2.41630172729,1.70706582069,5.02426290512 -2.40732479095,1.71207797527,5.04583692551 -2.39134955406,1.71209144592,5.05241584778 -2.37437415123,1.71110498905,5.05600404739 -2.36639714241,1.71711695194,5.08057308197 -2.34742259979,1.71513092518,5.08015871048 -2.3534309864,1.72613465786,5.1129565239 -2.34845304489,1.73414599895,5.14452886581 -2.34147500992,1.74115753174,5.17012071609 -2.33949613571,1.75316822529,5.20869731903 -2.31552410126,1.74718368053,5.20025730133 -2.29854822159,1.74619686604,5.20286035538 -2.2955596447,1.75020265579,5.21864271164 -2.27758431435,1.7482162714,5.22023439407 -2.25961017609,1.74723029137,5.22380638123 -2.2456343174,1.74924325943,5.23539018631 -2.22765994072,1.7482572794,5.23896121979 -2.21468424797,1.75127017498,5.25354003906 -2.19570946693,1.74828410149,5.25312614441 -2.1807243824,1.7432923317,5.24090862274 -2.16574788094,1.74330508709,5.24850749969 -2.14477491379,1.73931992054,5.24507379532 -2.12480020523,1.73633372784,5.24067020416 -2.11182427406,1.73934662342,5.25524997711 -2.09485054016,1.73936069012,5.26181316376 -2.07987427711,1.73937344551,5.26941204071 -2.07188677788,1.73938024044,5.27320051193 -2.05591201782,1.74039363861,5.28077793121 -2.03893780708,1.74040746689,5.28635072708 -2.01896333694,1.73642146587,5.28194141388 -2.00298857689,1.73743498325,5.28951883316 -1.9860137701,1.73644864559,5.29409837723 -1.97802686691,1.73745548725,5.29887866974 -1.96005165577,1.73546898365,5.29847812653 -1.94307780266,1.73548305035,5.30504083633 -1.92910158634,1.73749554157,5.31563901901 -1.91212654114,1.7365090847,5.31922674179 -1.89315319061,1.73452329636,5.31979370117 -1.88217711449,1.74053585529,5.34137296677 -1.86819136143,1.73454380035,5.32816171646 -1.85421586037,1.73755669594,5.3407459259 -1.83824062347,1.73857009411,5.34733295441 -1.81726682186,1.73258423805,5.33892250061 -1.80429172516,1.7375972271,5.35649251938 -1.78731691837,1.73661077023,5.36007928848 -1.76534426212,1.73162567616,5.35065078735 -1.75535714626,1.72963249683,5.34744644165 -1.7463799715,1.73764431477,5.37503623962 -1.72740662098,1.73565864563,5.37460756302 -1.70843243599,1.73267245293,5.37219142914 -1.69145750999,1.73268580437,5.3747844696 -1.67048454285,1.72770035267,5.36735725403 -1.65650856495,1.73071300983,5.37895393372 -1.6485222578,1.73172032833,5.38572311401 -1.62754845619,1.726734519,5.37531375885 -1.61157417297,1.72774803638,5.38388633728 -1.59459865093,1.72676110268,5.38449144363 -1.57662558556,1.72677528858,5.38805246353 -1.56165087223,1.72878861427,5.39962911606 -1.55566203594,1.73079442978,5.40743875504 -1.53069067001,1.72180998325,5.38600349426 -1.51671469212,1.72482252121,5.39760351181 -1.50174045563,1.72783601284,5.41116905212 -1.484765172,1.72684919834,5.41177225113 -1.46879053116,1.7278624773,5.41935348511 -1.45081710815,1.72687661648,5.4219212532 -1.44182980061,1.72588324547,5.4207201004 -1.42485547066,1.72589683533,5.42430353165 -1.40688157082,1.72491061687,5.42488193512 -1.38990688324,1.72392404079,5.42747116089 -1.36993420124,1.72093844414,5.42203760147 -1.35595822334,1.72395098209,5.43463754654 -1.34597241879,1.72295844555,5.43341207504 -1.32899808884,1.7229719162,5.43699502945 -1.31402254105,1.72498476505,5.44659042358 -1.29205024242,1.71799945831,5.431163311 -1.27707564831,1.72201275826,5.44374275208 -1.26110100746,1.72302591801,5.45132684708 -1.2431268692,1.72103953362,5.44991350174 -1.23014116287,1.71504724026,5.43270015717 -1.2171651125,1.72005963326,5.45129680634 -1.19819235802,1.71807396412,5.44886350632 -1.18021762371,1.71508717537,5.44446277618 -1.16524338722,1.71910059452,5.45903635025 -1.1462700367,1.71711468697,5.45461130142 -1.13129425049,1.71812713146,5.46321582794 -1.1233073473,1.72013390064,5.46899938583 -1.10333418846,1.71514809132,5.45857858658 -1.08735954762,1.7171612978,5.4661655426 -1.06938576698,1.71517491341,5.46474742889 -1.05241167545,1.71518838406,5.46832895279 -1.03443837166,1.71520233154,5.46890115738 -1.02046251297,1.71921479702,5.48450136185 -1.00947630405,1.71522200108,5.47329044342 -0.98950356245,1.71023631096,5.46286249161 -0.973529398441,1.71324968338,5.47244167328 -0.955555558205,1.71126329899,5.47002506256 -0.939581215382,1.71327650547,5.47960615158 -0.922606647015,1.7132897377,5.48020076752 -0.911620676517,1.70829713345,5.46898412704 -0.895645618439,1.7103099823,5.47458171844 -0.879671037197,1.71132314205,5.48316812515 -0.861697137356,1.71033668518,5.47975301743 -0.843723356724,1.70835018158,5.47633695602 -0.826749742031,1.70936381817,5.48191165924 -0.808776319027,1.70837759972,5.48048782349 -0.800788402557,1.7083837986,5.48129415512 -0.784814357758,1.71139717102,5.49287319183 -0.766840279102,1.70841050148,5.48746204376 -0.749866604805,1.71042406559,5.49303817749 -0.731892943382,1.7084376812,5.48962020874 -0.713919460773,1.70645141602,5.48719739914 -0.704932928085,1.70645833015,5.48698282242 -0.687958955765,1.70647168159,5.49056577682 -0.670984387398,1.70648467541,5.49016046524 -0.652011215687,1.70149862766,5.47873830795 -0.637036681175,1.70851147175,5.49932193756 -0.619062840939,1.70552492142,5.49290847778 -0.602088570595,1.70553815365,5.49449729919 -0.593101620674,1.70454490185,5.49129009247 -0.576127707958,1.70555818081,5.49487304688 -0.557154655457,1.70057201385,5.48145055771 -0.541180491447,1.70458519459,5.49603128433 -0.524205744267,1.70359814167,5.49362945557 -0.507232189178,1.70561158657,5.50020694733 -0.490257680416,1.70462465286,5.49979972839 -0.481271237135,1.704631567,5.49958467484 -0.463297277689,1.70064485073,5.48917388916 -0.44732388854,1.70865833759,5.51374101639 -0.429349422455,1.70267128944,5.49734067917 -0.412375301123,1.70368456841,5.49992752075 -0.394402086735,1.70169818401,5.49550294876 -0.378427416086,1.70571100712,5.50909614563 -0.368441134691,1.70071804523,5.49288225174 -0.351467043161,1.70073115826,5.49546909332 -0.334492504597,1.69974422455,5.49206542969 -0.317518830299,1.70175743103,5.500644207 -0.300544768572,1.70377063751,5.5042309761 -0.282571673393,1.70178425312,5.49980354309 -0.273584783077,1.69879090786,5.4915971756 -0.257609903812,1.70380353928,5.50719404221 -0.239636570215,1.70081710815,5.49677324295 -0.222662344575,1.70083010197,5.49736356735 -0.204689562321,1.70084381104,5.49693059921 -0.187715396285,1.70085692406,5.49951934814 -0.170741200447,1.7018699646,5.50110960007 -0.161754846573,1.70187675953,5.50189256668 -0.1447802037,1.69788956642,5.49049091339 -0.127806201577,1.70090258121,5.49807691574 -0.109833441675,1.70091629028,5.49764442444 -0.0928590744734,1.69892930984,5.4922375679 -0.0758847221732,1.6969422102,5.48583078384 -0.0668984949589,1.69894909859,5.49361181259 -0.0499241836369,1.69696199894,5.48720407486 -0.0329499728978,1.69797492027,5.48879432678 -0.0149772502482,1.69698858261,5.48536157608 --0.00599068356678,1.69300460815,5.32485103607 --0.0219657979906,1.69101715088,5.31645345688 --0.038939408958,1.69203031063,5.32003211975 --0.05591307953,1.69404351711,5.32561206818 --0.0718879327178,1.68805599213,5.30720901489 --0.0808741226792,1.69106292725,5.31698894501 --0.0968489870429,1.68707549572,5.30458688736 --0.113822773099,1.69108855724,5.3131685257 --0.130796283484,1.69010174274,5.31074571609 --0.147769913077,1.69111478329,5.31132411957 --0.163745045662,1.69112718105,5.31092739105 --0.180718764663,1.69214034081,5.31350803375 --0.188706070185,1.69014668465,5.30730438232 --0.205679759383,1.69115960598,5.3088850975 --0.221654444933,1.68817222118,5.29947853088 --0.238628402352,1.69118511677,5.30606460571 --0.2556014359,1.68719851971,5.29563140869 --0.272575646639,1.69121134281,5.30522203445 --0.288550287485,1.68922388554,5.29681491852 --0.297536939383,1.69223046303,5.30560493469 --0.313511401415,1.68924307823,5.29519414902 --0.330484926701,1.68925619125,5.29377126694 --0.347459197044,1.69226896763,5.30136299133 --0.363433629274,1.68928146362,5.29195261002 --0.380406826735,1.68829464912,5.2865228653 --0.396381735802,1.68730711937,5.28312110901 --0.405368626118,1.69131350517,5.29191493988 --0.424341917038,1.70032680035,5.31849861145 --0.437317192554,1.68533873558,5.27308750153 --0.457290202379,1.69835221767,5.30967140198 --0.472264170647,1.69036495686,5.28324556351 --0.487239003181,1.68537724018,5.26583623886 --0.496226459742,1.68938350677,5.27764177322 --0.513200044632,1.68939650059,5.27621984482 --0.530174791813,1.69240891933,5.28381967545 --0.546148777008,1.69042158127,5.27340078354 --0.563122153282,1.68943464756,5.26997375488 --0.580096125603,1.6914473772,5.27156019211 --0.598069965839,1.69546020031,5.28214788437 --0.604057908058,1.6894659996,5.26194429398 --0.622032046318,1.69447875023,5.27453899384 --0.639005362988,1.69349169731,5.27111291885 --0.655979692936,1.69550430775,5.27370452881 --0.670954287052,1.6915166378,5.25829029083 --0.687928974628,1.69352889061,5.26288938522 --0.704902470112,1.69354188442,5.26046562195 --0.718888103962,1.70854902267,5.30226230621 --0.729863643646,1.69356071949,5.25684356689 --0.751836419106,1.7075741291,5.29343318939 --0.763812184334,1.69658577442,5.26002597809 --0.780786573887,1.69859826565,5.2616186142 --0.79775929451,1.69661152363,5.25417852402 --0.809746444225,1.70761787891,5.28299379349 --0.823721468449,1.70162987709,5.26358270645 --0.837696194649,1.69564211369,5.24316501617 --0.856669425964,1.70065510273,5.25374603271 --0.889617919922,1.70068001747,5.24692058563 --0.916578829288,1.70469892025,5.25530338287 --0.933552443981,1.70471167564,5.25188016891 --0.951526939869,1.7087239027,5.25947999954 --0.971500754356,1.71573674679,5.27707767487 --0.988474011421,1.71474957466,5.27164793015 --1.00144982338,1.70976114273,5.25124502182 --1.02242314816,1.71777403355,5.27183771133 --1.02541077137,1.70677983761,5.23861217499 --1.04438459873,1.71179246902,5.24820327759 --1.06135892868,1.71280479431,5.24779605865 --1.08233225346,1.72081780434,5.26638650894 --1.09630680084,1.71482980251,5.24796390533 --1.11728036404,1.72384262085,5.26756381989 --1.12825655937,1.71485388279,5.23815441132 --1.14424073696,1.72586166859,5.2689332962 --1.15721619129,1.72087335587,5.24852132797 --1.17219138145,1.71888518333,5.23911809921 --1.18916547298,1.71889746189,5.23670339584 --1.20614016056,1.72090959549,5.23630046844 --1.22711265087,1.72592282295,5.24887466431 --1.23310101032,1.72392833233,5.23867845535 --1.25207448006,1.72694087029,5.24426364899 --1.27004814148,1.72895348072,5.24484539032 --1.28602230549,1.72796571255,5.23642349243 --1.30199754238,1.72797751427,5.23202419281 --1.32097101212,1.73099017143,5.23660755157 --1.34494423866,1.74200308323,5.26421260834 --1.34593248367,1.73100841045,5.22998666763 --1.36290752888,1.7320202589,5.22958898544 --1.37988102436,1.73203277588,5.22416114807 --1.39985513687,1.73704504967,5.23476314545 --1.41383039951,1.73405683041,5.2203502655 --1.43980145454,1.7460706234,5.24792337418 --1.45677673817,1.74708235264,5.24753093719 --1.45476698875,1.73408675194,5.20832681656 --1.47574019432,1.74009943008,5.2189116478 --1.49171423912,1.73911166191,5.21048927307 --1.51068842411,1.74212396145,5.21508359909 --1.52466332912,1.73913562298,5.20066690445 --1.54463720322,1.74314796925,5.20826053619 --1.5516244173,1.74115395546,5.2000451088 --1.57059824467,1.744166255,5.20363616943 --1.58757293224,1.74517822266,5.20022535324 --1.60554778576,1.74819004536,5.20182752609 --1.63051903248,1.75720369816,5.22139883041 --1.64049577713,1.7502143383,5.19599342346 --1.65347146988,1.74622571468,5.17958116531 --1.66845619678,1.75323295593,5.1963634491 --1.68343222141,1.75224411488,5.18897199631 --1.70640444756,1.75925719738,5.20154666901 --1.71738064289,1.75326824188,5.17913484573 --1.73635518551,1.75628018379,5.18273496628 --1.76132750511,1.76529324055,5.20232343674 --1.76730442047,1.75330364704,5.16389894485 --1.77829122543,1.75730991364,5.1696972847 --1.797265172,1.75932204723,5.17128610611 --1.81723952293,1.7643340826,5.17688512802 --1.83021485806,1.76034533978,5.1604681015 --1.84519040585,1.75935673714,5.15106153488 --1.86716353893,1.76436924934,5.1606502533 --1.87515044212,1.76437532902,5.15543222427 --1.88812613487,1.76138651371,5.14002084732 --1.90510082245,1.76139819622,5.13561010361 --1.92907369137,1.76941096783,5.15020084381 --1.94204938412,1.76642203331,5.13478899002 --1.95902502537,1.76743340492,5.13239574432 --1.97999763489,1.77144598961,5.1359667778 --1.9839861393,1.76745128632,5.12175989151 --2.0029604435,1.77046310902,5.12235021591 --2.02193570137,1.77347457409,5.12495851517 --2.03591036797,1.77048623562,5.11053037643 --2.05288529396,1.77149760723,5.10612344742 --2.07885766029,1.78051054478,5.12371349335 --2.08683514595,1.77352058887,5.09731006622 --2.10382056236,1.78152751923,5.11610889435 --2.11579656601,1.77753841877,5.09869718552 --2.13077187538,1.77654969692,5.08828163147 --2.15174603462,1.78056156635,5.09388113022 --2.16971993446,1.78257346153,5.08945608139 --2.18269658089,1.77958416939,5.07605648041 --2.19568252563,1.78459048271,5.08385038376 --2.21165728569,1.78360199928,5.0754327774 --2.22263431549,1.77961242199,5.05702781677 --2.24860692024,1.78862500191,5.07262086868 --2.26058316231,1.78463566303,5.05621385574 --2.27555823326,1.78364706039,5.0447883606 --2.29553246498,1.78665876389,5.04638147354 --2.31251788139,1.79466545582,5.06318378448 --2.32449364662,1.79067659378,5.04475545883 --2.33847022057,1.78968703747,5.03436183929 --2.35944318771,1.79369926453,5.03593730927 --2.38441729546,1.80071115494,5.04954910278 --2.39439344406,1.79572188854,5.02712202072 --2.41036891937,1.7957328558,5.01971626282 --2.41835641861,1.79573845863,5.0155081749 --2.44332933426,1.80275082588,5.02609682083 --2.45130729675,1.79776060581,5.00269699097 --2.47028136253,1.79977238178,4.99927043915 --2.49225592613,1.80478394032,5.00487470627 --2.50823116302,1.80479502678,4.99646139145 --2.51821827888,1.80580079556,4.99625444412 --2.53219437599,1.80481135845,4.98485136032 --2.55216884613,1.80782294273,4.98443889618 --2.57114386559,1.80983412266,4.98303842545 --2.58611941338,1.8098449707,4.97262525558 --2.5990960598,1.80785536766,4.95922088623 --2.62106966972,1.81186723709,4.96180391312 --2.6300573349,1.81287276745,4.9595990181 --2.64703202248,1.81388413906,4.9521780014 --2.6600086689,1.81189441681,4.93877315521 --2.67598485947,1.81190502644,4.93137264252 --2.69196033478,1.81191587448,4.92296123505 --2.71593332291,1.81792795658,4.92854309082 --2.72291207314,1.81193733215,4.90514802933 --2.73989725113,1.81894397736,4.91693878174 --2.7578728199,1.82095491886,4.91253376007 --2.77384853363,1.8209656477,4.90412473679 --2.78482556343,1.81797575951,4.88671350479 --2.80579996109,1.82098698616,4.88730621338 --2.82277441025,1.82199835777,4.87887763977 --2.83176279068,1.82300341129,4.87768793106 --2.8517370224,1.82601475716,4.87526893616 --2.86871290207,1.82702541351,4.86886501312 --2.87968993187,1.82403552532,4.85145187378 --2.90466332436,1.83004713058,4.85804224014 --2.91664099693,1.82905709743,4.84364366531 --2.93061685562,1.8270676136,4.8312292099 --2.95160198212,1.83607423306,4.84903144836 --2.96857690811,1.83708524704,4.84060764313 --2.97255659103,1.83009397984,4.81321001053 --2.99753069878,1.83610546589,4.81980895996 --3.00850701332,1.83311569691,4.80138111115 --3.03048181534,1.83812665939,4.80298089981 --3.0444586277,1.83713686466,4.79157876968 --3.05444574356,1.83814239502,4.78936290741 --3.06642317772,1.83615219593,4.77496290207 --3.09239578247,1.84316408634,4.78053998947 --3.1113717556,1.84517467022,4.77714252472 --3.12634825706,1.84518480301,4.7667350769 --3.14432430267,1.84719526768,4.76133298874 --3.15031242371,1.84620022774,4.7531208992 --3.16628909111,1.84721040726,4.74471998215 --3.18426442146,1.84922099113,4.73830652237 --3.20024108887,1.84923112392,4.72990703583 --3.22021555901,1.85224211216,4.72548294067 --3.23319268227,1.85025203228,4.71207618713 --3.25216841698,1.85326230526,4.70767211914 --3.26215577126,1.85426783562,4.70546150208 --3.28813052177,1.86127877235,4.71207094193 --3.29510831833,1.85628819466,4.68864774704 --3.3160841465,1.86029875278,4.68724918365 --3.32906079292,1.85930871964,4.67283010483 --3.34903693199,1.86231887341,4.67043876648 --3.36101341248,1.86032891273,4.65401220322 --3.37600040436,1.8653345108,4.65981769562 --3.3889772892,1.86334431171,4.64539909363 --3.41195273399,1.86835491657,4.64700937271 --3.41992998123,1.8643643856,4.62457513809 --3.44090628624,1.86837470531,4.62318468094 --3.4558827877,1.86838459969,4.61177015305 --3.46786952019,1.87039017677,4.61155557632 --3.48484635353,1.87240004539,4.60415887833 --3.49982380867,1.87240958214,4.59375810623 --3.51280045509,1.87141931057,4.57933950424 --3.53477668762,1.87642943859,4.57895040512 --3.54675340652,1.8744392395,4.56252241135 --3.55973100662,1.87344884872,4.54911708832 --3.56971907616,1.87445378304,4.54691410065 --3.5986931324,1.88346481323,4.55451631546 --3.59467458725,1.87247252464,4.51910686493 --3.62764716148,1.88348400593,4.53069734573 --3.6396253109,1.88149309158,4.51629686356 --3.65660142899,1.88350319862,4.50687837601 --3.66557955742,1.87951231003,4.48745965958 --3.68456554413,1.88651823997,4.49625825882 --3.68754601479,1.88052642345,4.47085762024 --3.70552253723,1.88253617287,4.4634513855 --3.73049783707,1.88854658604,4.46505308151 --3.74047541618,1.88555586338,4.44663000107 --3.75645303726,1.88756513596,4.43723106384 --3.77242994308,1.88757479191,4.42681932449 --3.78141832352,1.8885794878,4.42362451553 --3.7963950634,1.88858926296,4.41120147705 --3.81637144089,1.89259898663,4.40579509735 --3.83034896851,1.89260816574,4.39338922501 --3.84032821655,1.89061689377,4.37699174881 --3.86430311203,1.895627141,4.37557935715 --3.86729335785,1.89363121986,4.36538505554 --3.8812713623,1.89364039898,4.35297966003 --3.91224431992,1.90165138245,4.35855770111 --3.92322301865,1.90066003799,4.34315919876 --3.92820262909,1.89666855335,4.31974077225 --3.95217823982,1.90167856216,4.3183350563 --3.96615624428,1.90168762207,4.30593156815 --3.96914577484,1.89969182014,4.29472017288 --3.98712277412,1.90170133114,4.2863111496 --3.9971010685,1.89971005917,4.26889801025 --4.00808000565,1.89771866798,4.25349712372 --4.03205633163,1.9037283659,4.2520980835 --4.04503488541,1.90373718739,4.23869609833 --4.0580124855,1.90274620056,4.22427940369 --4.06400203705,1.9027504921,4.21707868576 --4.06898164749,1.89775872231,4.19466686249 --4.0889582634,1.90176808834,4.18825960159 --4.10093736649,1.90077674389,4.1738576889 --4.11591482162,1.90178585052,4.16143941879 --4.13789176941,1.90579497814,4.15804958344 --4.1608672142,1.91080474854,4.15363168716 --4.16185855865,1.90780854225,4.14143180847 --4.17383718491,1.90781700611,4.12703084946 --4.19381332397,1.91082644463,4.11961460114 --4.21879005432,1.91683590412,4.11821651459 --4.21677160263,1.9088435173,4.08879709244 --4.2417473793,1.91485309601,4.08638525009 --4.24673652649,1.9138572216,4.07818508148 --4.26971292496,1.91786658764,4.07377481461 --4.2946896553,1.92387580872,4.07238388062 --4.30666875839,1.92388439178,4.05696964264 --4.32764530182,1.92689359188,4.05056285858 --4.35462141037,1.93390285969,4.05016326904 --4.37359952927,1.93691146374,4.0427737236 --4.37459039688,1.93491530418,4.03057050705 --4.39656639099,1.93792450428,4.02415418625 --4.41054487228,1.93893301487,4.01074504852 --4.43452119827,1.94394218922,4.00633382797 --4.43650245667,1.93894970417,3.98192453384 --4.45048093796,1.93995821476,3.96851587296 --4.45346260071,1.93496572971,3.94510531425 --4.4364566803,1.92396819592,3.91690015793 --4.44743680954,1.92397618294,3.90149974823 --4.4414191246,1.91498315334,3.87008261681 --4.4453997612,1.91099095345,3.84766602516 --4.44638156891,1.90599834919,3.82325792313 --4.44436454773,1.90000522137,3.79685759544 --4.4553437233,1.89901340008,3.7814514637 --4.44733572006,1.89301669598,3.76123309135 --4.44931697845,1.88802409172,3.73781991005 --4.4472990036,1.88203120232,3.71141123772 --4.45527887344,1.88003921509,3.69299340248 --4.45726108551,1.87504649162,3.67059183121 --4.46024179459,1.87105417252,3.64817452431 --4.44422721863,1.85906028748,3.61076641083 --4.46421432495,1.86606514454,3.61556887627 --4.46619462967,1.8610727787,3.59214425087 --4.46717739105,1.85707974434,3.56974864006 --4.47615623474,1.85508787632,3.55232644081 --4.48813581467,1.85509586334,3.53791379929 --4.49911642075,1.85510361195,3.52351546288 --4.50910568237,1.8571075201,3.52032351494 --4.51308679581,1.8541148901,3.49991703033 --4.52606630325,1.85512292385,3.48650813103 --4.53704595566,1.85513079166,3.47109174728 --4.55202436447,1.85613906384,3.45867371559 --4.56100559235,1.85514628887,3.4432849884 --4.56298732758,1.85115373135,3.42086625099 --4.57797527313,1.85515809059,3.42066264153 --4.59395360947,1.85716605186,3.40925049782 --4.59393644333,1.85317289829,3.38685679436 --4.60691547394,1.85318100452,3.37243151665 --4.61189699173,1.85118830204,3.35302257538 --4.63187599182,1.85519611835,3.34563040733 --4.63185787201,1.85020327568,3.32221460342 --4.63084936142,1.8482067585,3.31000995636 --4.65682697296,1.85421478748,3.30661296844 --4.65580892563,1.84922194481,3.28218960762 --4.67078876495,1.85122966766,3.27079296112 --4.67477083206,1.84823656082,3.25139331818 --4.6907491684,1.8502446413,3.23896622658 --4.71772766113,1.8572524786,3.23658251762 --4.70272159576,1.8492552042,3.21437048912 --4.71970129013,1.85126292706,3.20396876335 --4.72368192673,1.84927010536,3.18354845047 --4.74366092682,1.85327792168,3.17514705658 --4.74164390564,1.84828484058,3.1507267952 --4.74862480164,1.84629189968,3.13332223892 --4.76960420609,1.8512994051,3.1259291172 --4.76659631729,1.84830272198,3.11272382736 --4.77857589722,1.84831011295,3.09831285477 --4.78255844116,1.84631705284,3.07890677452 --4.79553890228,1.84732425213,3.06550240517 --4.80751943588,1.84833157063,3.05109167099 --4.81250143051,1.8463383913,3.03269076347 --4.82248163223,1.84634578228,3.0162665844 --4.82847261429,1.84634912014,3.01008057594 --4.84045314789,1.84735620022,2.9956703186 --4.8464345932,1.84636330605,2.97725605965 --4.84741687775,1.84237003326,2.95584344864 --4.86139774323,1.84437692165,2.94344782829 --4.88037776947,1.84838426113,2.93405127525 --4.87237024307,1.84238731861,2.91783857346 --4.88835000992,1.84539473057,2.90542054176 --4.89133262634,1.8424012661,2.88601994514 --4.90731334686,1.84540832043,2.87462210655 --4.91229486465,1.84341526031,2.85519742966 --4.92127656937,1.84342193604,2.83980345726 --4.93125724792,1.84342908859,2.82337903976 --4.9352478981,1.84343242645,2.8151781559 --4.95622825623,1.84843933582,2.80678510666 --4.95721101761,1.84444594383,2.78536534309 --4.97919034958,1.85045313835,2.77696347237 --4.982172966,1.84745955467,2.75755953789 --4.98715543747,1.84646618366,2.73915171623 --4.99813652039,1.84647297859,2.72373700142 --4.98812961578,1.84047591686,2.70753192902 --5.00011110306,1.84248256683,2.69312500954 --5.01609182358,1.84448945522,2.68071484566 --5.02607297897,1.84549605846,2.66531062126 --5.03305578232,1.84450232983,2.64891958237 --5.03203868866,1.84050893784,2.6264936924 --5.05101919174,1.84451556206,2.61609387398 --5.07300806046,1.85151922703,2.61790180206 --5.06499242783,1.84552526474,2.59248924255 --5.0799741745,1.84853172302,2.58009386063 --5.09395503998,1.8505384922,2.56567001343 --5.10593652725,1.85154497623,2.55126786232 --5.10092115402,1.84655106068,2.52785921097 --5.12590074539,1.85255753994,2.52046537399 --5.13789081573,1.85556089878,2.51626420021 --5.13487482071,1.85156702995,2.49385404587 --5.14785671234,1.85357344151,2.47944331169 --5.17283630371,1.85957992077,2.47103571892 --5.16982030869,1.85558617115,2.44862318039 --5.18280172348,1.85759246349,2.43421459198 --5.18679332733,1.85759544373,2.42601490021 --5.20477437973,1.86060166359,2.41461968422 --5.20975732803,1.85960781574,2.39620900154 --5.20774173737,1.85561382771,2.37480354309 --5.23272180557,1.8626203537,2.36538505554 --5.23170566559,1.85962605476,2.34498953819 --5.2466878891,1.8616322279,2.33158612251 --5.26067733765,1.86563551426,2.32737541199 --5.27166032791,1.86664152145,2.31197047234 --5.26164579391,1.86064720154,2.28757429123 --5.28362560272,1.86565351486,2.27615022659 --5.30260753632,1.86965942383,2.26475596428 --5.31259012222,1.87066543102,2.24834132195 --5.31157493591,1.86767113209,2.22794270515 --5.30956697464,1.86567413807,2.21673560143 --5.33454751968,1.87168002129,2.2073328495 --5.3395318985,1.87168562412,2.18994212151 --5.36151266098,1.87669157982,2.17852783203 --5.34749889374,1.86869740486,2.15211558342 --5.36848020554,1.87370312214,2.14071178436 --5.36846446991,1.87170898914,2.12030100822 --5.37445545197,1.87171196938,2.11208677292 --5.38343906403,1.87271761894,2.095682621 --5.39742136002,1.87572324276,2.08127880096 --5.40040588379,1.87372875214,2.06288385391 --5.42538690567,1.88073432446,2.052475214 --5.41937208176,1.87573993206,2.03007006645 --5.42835569382,1.87674558163,2.01366758347 --5.43634700775,1.87874829769,2.00645947456 --5.44033098221,1.8777538538,1.98805606365 --5.45231437683,1.87975931168,1.97265172005 --5.47229623795,1.88476467133,1.96024906635 --5.46028184891,1.8777705431,1.93482291698 --5.47526502609,1.8807759285,1.92041814327 --5.4962477684,1.88578093052,1.90903186798 --5.49923944473,1.88578367233,1.89982306957 --5.50422334671,1.88478922844,1.88141226768 --5.49920892715,1.88079452515,1.86001217365 --5.51119184494,1.88279998302,1.84359109402 --5.53117513657,1.88880503178,1.83119666576 --5.53115940094,1.88581049442,1.81077992916 --5.54214382172,1.88781547546,1.79538905621 --5.54313564301,1.88681840897,1.78517329693 --5.55111932755,1.8878235817,1.76776230335 --5.55710411072,1.8878287077,1.75036525726 --5.56308794022,1.88783407211,1.73194742203 --5.57307195663,1.88883912563,1.71554458141 --5.58005666733,1.88984429836,1.69814109802 --5.59004068375,1.89084923267,1.6817394495 --5.59603261948,1.8918517828,1.67353212833 --5.59501791,1.88985705376,1.65311861038 --5.5990023613,1.88886213303,1.63471412659 --5.61298656464,1.89186704159,1.61930894852 --5.64196920395,1.90087127686,1.60891568661 --5.61695671082,1.88987708092,1.5815038681 --5.62894821167,1.89287936687,1.57530283928 --5.62193393707,1.88888478279,1.55288124084 --5.64891672134,1.89588904381,1.54148471355 --5.65190219879,1.89589393139,1.52308666706 --5.65788650513,1.89589893818,1.50467085838 --5.65587234497,1.89290416241,1.4842594862 --5.67185640335,1.89690864086,1.4688488245 --5.67784786224,1.89791107178,1.46064507961 --5.6698346138,1.89391613007,1.43924582005 --5.68581914902,1.89792072773,1.42383730412 --5.69480371475,1.89892530441,1.40642678738 --5.68178987503,1.89193081856,1.38300979137 --5.70277404785,1.89793491364,1.36961901188 --5.7057595253,1.89793980122,1.35019886494 --5.70575284958,1.89694201946,1.34100723267 --5.70373821259,1.89394712448,1.32059168816 --5.72872161865,1.90095090866,1.30718493462 --5.74370670319,1.9049551487,1.29178929329 --5.72869348526,1.89796066284,1.26837515831 --5.72867965698,1.89696538448,1.24896931648 --5.72966527939,1.89597010612,1.22955787182 --5.74465751648,1.89997184277,1.22335648537 --5.75264263153,1.90097618103,1.20595490932 --5.77162790298,1.90697991848,1.19156575203 --5.77061367035,1.90498483181,1.1711435318 --5.77259922028,1.90398943424,1.15172827244 --5.77558517456,1.90299391747,1.1333296299 --5.79257059097,1.90799760818,1.11793279648 --5.78656387329,1.90500032902,1.10672390461 --5.80554914474,1.91000390053,1.09132039547 --5.80953502655,1.91000819206,1.07291841507 --5.80652141571,1.90801310539,1.05250298977 --5.81150722504,1.90901732445,1.03409636021 --5.82149267197,1.91002130508,1.01669156551 --5.82148551941,1.91002368927,1.00647687912 --5.82247161865,1.90902805328,0.987065434456 --5.82845878601,1.91003203392,0.969677090645 --5.85044384003,1.91603517532,0.954271137714 --5.8434305191,1.91204023361,0.932847440243 --5.84241724014,1.91104459763,0.913442790508 --5.8424038887,1.91004908085,0.894034206867 --5.86438894272,1.91605210304,0.87863355875 --5.86038255692,1.91405451298,0.868432819843 --5.85236930847,1.91005957127,0.847008764744 --5.87235546112,1.91606235504,0.831618189812 --5.85834312439,1.91006755829,0.810212492943 --5.86532926559,1.91207146645,0.791801393032 --5.86631584167,1.91107571125,0.772388339043 --5.87330198288,1.91207957268,0.753978192806 --5.87829589844,1.91408109665,0.745790064335 --5.87228250504,1.91008591652,0.725376546383 --5.87826967239,1.91208958626,0.706969559193 --5.89825582504,1.91809237003,0.690566658974 --5.8822426796,1.91109788418,0.668136417866 --5.89222955704,1.91410112381,0.650741219521 --5.90322303772,1.91710245609,0.642538905144 --5.90520954132,1.91710650921,0.62312322855 --5.90619707108,1.91611027718,0.604731798172 --5.90718412399,1.91611433029,0.58531832695 --5.920170784,1.9191173315,0.567919492722 --5.92815828323,1.92112076283,0.549511909485 --5.92114543915,1.91812539101,0.529095649719 --5.93513870239,1.9231262207,0.520891368389 --5.94112634659,1.92412960529,0.502489864826 --5.95311260223,1.92713260651,0.484076499939 --5.94910049438,1.92513680458,0.464674711227 --5.97008752823,1.93213891983,0.447266995907 --5.94207525253,1.92114543915,0.424845397472 --5.95506286621,1.92514789104,0.407453924417 --5.96205663681,1.92714929581,0.398247122765 --5.98104429245,1.93315136433,0.380847930908 --5.96403121948,1.92715680599,0.359422892332 --5.96901941299,1.92816007137,0.341026097536 --5.98200702667,1.93216264248,0.322617858648 --5.99099445343,1.93416535854,0.304217010736 --5.9849820137,1.93216979504,0.283793866634 --5.99297618866,1.93417072296,0.275610864162 --5.99496412277,1.93417418003,0.256198823452 --5.99295186996,1.93317806721,0.236791417003 --5.98993968964,1.9321821928,0.216362953186 --5.99292755127,1.93218529224,0.197971180081 --5.9909157753,1.93118917942,0.17856271565 --6.00690412521,1.936191082,0.160159289837 --6.00889778137,1.93719279766,0.149941802025 --6.01388645172,1.93819570541,0.131549820304 --6.02687454224,1.94219791889,0.112131007016 --6.02786254883,1.94220125675,0.0927216336131 --6.0278506279,1.94220471382,0.07331276685 --6.03083944321,1.94320774078,0.0549237541854 --6.04082775116,1.94621014595,0.0355105102062 --6.04882192612,1.94821083546,0.0263140257448 --6.04981040955,1.94821405411,0.00690597807989 --6.04679918289,1.94721770287,-0.0125010414049 --6.05678749084,1.95021986961,-0.0319110825658 --6.06677627563,1.9542222023,-0.0513200946152 --6.0617647171,1.95222580433,-0.0707265734673 --6.05975341797,1.95122933388,-0.0901337563992 --6.05974769592,1.95123112202,-0.100348211825 --6.05673599243,1.95023453236,-0.119756013155 --6.05072450638,1.94823849201,-0.139164760709 --6.05471372604,1.94924128056,-0.158571869135 --6.05170202255,1.9482446909,-0.177980706096 --6.05669116974,1.95024716854,-0.19738702476 --6.05467987061,1.94925057888,-0.216795608401 --6.06067466736,1.9512513876,-0.22700740397 --6.04566287994,1.94625639915,-0.246423155069 --6.06265258789,1.95225715637,-0.265821248293 --6.06364154816,1.9522601366,-0.285227805376 --6.0576300621,1.95026385784,-0.304639518261 --6.05561923981,1.95026707649,-0.324048936367 --6.05161380768,1.9482691288,-0.333245277405 --6.04560279846,1.94727277756,-0.352659016848 --6.04659223557,1.94727563858,-0.37206619978 --6.03858041763,1.94527971745,-0.391483008862 --6.04957008362,1.94828116894,-0.41190046072 --6.05656003952,1.95128309727,-0.43130004406 --6.04254817963,1.94728779793,-0.450725138187 --6.0445432663,1.94728887081,-0.45991563797 --6.0485329628,1.94929122925,-0.479318231344 --6.0495223999,1.95029377937,-0.498724430799 --6.04751205444,1.94929695129,-0.518134653568 --6.06150245667,1.95429766178,-0.538541436195 --6.04149055481,1.94830322266,-0.556959211826 --6.04948043823,1.95130479336,-0.577374458313 --6.0544757843,1.95330548286,-0.587579905987 --6.05346536636,1.95330822468,-0.606988132 --6.0544552803,1.9543107748,-0.626392602921 --6.04844427109,1.95231425762,-0.645810246468 --6.0604352951,1.95731496811,-0.666213929653 --6.04642391205,1.95231962204,-0.684626758099 --6.0524148941,1.95532119274,-0.704020082951 --6.0434088707,1.95232379436,-0.713231742382 --6.04639911652,1.95432603359,-0.733652472496 --6.04238891602,1.95332896709,-0.752045869827 --6.05238008499,1.95732986927,-0.772449016571 --6.04236841202,1.95433402061,-0.79187810421 --6.05236005783,1.95833480358,-0.812279462814 --6.04834938049,1.95733773708,-0.831693947315 --6.0383439064,1.95434057713,-0.839890301228 --6.0433344841,1.95734202862,-0.860303223133 --6.04732513428,1.95934391022,-0.880717635155 --6.05831670761,1.96334421635,-0.901111364365 --6.02630376816,1.95335185528,-0.917542695999 --6.02329397202,1.9533547163,-0.936956167221 --6.04028654099,1.95935404301,-0.958351492882 --6.05028247833,1.96335339546,-0.969554364681 --6.03827142715,1.96035766602,-0.987972855568 --6.03926277161,1.96135962009,-1.00737226009 --6.0392537117,1.96236157417,-1.02677452564 --6.02724313736,1.95936596394,-1.0451952219 --6.02823352814,1.96036791801,-1.06561529636 --6.02322387695,1.95937085152,-1.08401334286 --6.03222084045,1.96337020397,-1.09521484375 --6.01920986176,1.95937466621,-1.11364090443 --6.02220058441,1.96137607098,-1.13405287266 --6.01619100571,1.96037912369,-1.15245497227 --6.0201830864,1.96338033676,-1.17286241055 --6.02617502213,1.96638119221,-1.19326102734 --6.02016496658,1.96538412571,-1.2126840353 --6.02616119385,1.96738409996,-1.22389185429 --6.02015209198,1.96738696098,-1.2422940731 --6.01514196396,1.96638977528,-1.26171326637 --6.02013444901,1.96839058399,-1.28211236 --6.02012586594,1.97039234638,-1.30253183842 --6.03111886978,1.97539186478,-1.32392477989 --6.03911590576,1.9783911705,-1.33512020111 --6.03910732269,1.97939288616,-1.3555368185 --6.05410146713,1.98639154434,-1.37792909145 --6.07909679413,1.99638819695,-1.40333628654 --6.07508802414,1.99639046192,-1.42274606228 --6.0790810585,1.99839103222,-1.44314002991 --6.08407306671,2.00139164925,-1.46454882622 --6.08206892014,2.00139260292,-1.47476351261 --6.08706188202,2.00539302826,-1.49617123604 --6.10405683517,2.01239085197,-1.51956129074 --6.11805152893,2.01838922501,-1.54296290874 --6.12504482269,2.02238893509,-1.56537592411 --6.13603878021,2.02738809586,-1.58878791332 --6.12002897263,2.02339267731,-1.60519099236 --6.11302375793,2.02139472961,-1.61440825462 --6.10501480103,2.02039766312,-1.63281333447 --6.1110086441,2.0243973732,-1.65522778034 --6.10099887848,2.0224006176,-1.6736433506 --6.09299039841,2.0214035511,-1.6920491457 --6.07697963715,2.01740813255,-1.70947790146 --6.07797288895,2.01940917969,-1.72987687588 --6.08096599579,2.02140927315,-1.75128400326 --6.07996225357,2.02240991592,-1.76149117947 --6.05695009232,2.01541614532,-1.77692091465 --6.06694555283,2.02141475677,-1.79930865765 --6.07093906403,2.02441501617,-1.82172811031 --6.04992771149,2.01842069626,-1.83714985847 --6.05192136765,2.02142095566,-1.85856044292 --6.04791688919,2.02042245865,-1.86776423454 --6.01890468597,2.01242995262,-1.88017690182 --6.04590320587,2.0234246254,-1.90857791901 --6.02589225769,2.01842999458,-1.9239988327 --6.01188182831,2.01543402672,-1.94142496586 --6.0138759613,2.0174343586,-1.96283316612 --6.01786994934,2.02143406868,-1.98422837257 --5.9968624115,2.01443958282,-1.98843967915 --5.98885393143,2.01444220543,-2.00787091255 --5.99784898758,2.01944065094,-2.03127288818 --5.97983884811,2.01444554329,-2.04668784142 --5.97383117676,2.01444768906,-2.06610608101 --5.96082210541,2.01245141029,-2.0825111866 --5.96081542969,2.01445221901,-2.10392975807 --5.95581102371,2.013453722,-2.11314225197 --5.9448018074,2.0114569664,-2.13055515289 --5.93279266357,2.00946068764,-2.14797544479 --5.93978881836,2.01445913315,-2.1703646183 --5.92277812958,2.01046395302,-2.18680024147 --5.92077207565,2.01146483421,-2.20619130135 --5.90876293182,2.00946855545,-2.22361326218 --5.90575933456,2.00946950912,-2.23281311989 --5.8907494545,2.00647377968,-2.24923801422 --5.89274358749,2.00947356224,-2.27165913582 --5.8817358017,2.00747680664,-2.28805589676 --5.8767285347,2.00847840309,-2.30746841431 --5.86671972275,2.00648140907,-2.32589769363 --5.86171293259,2.00748300552,-2.34531021118 --5.85170793533,2.00548553467,-2.35150408745 --5.8467001915,2.0054872036,-2.37193608284 --5.82769012451,2.00149273872,-2.38533806801 --5.83468675613,2.00649094582,-2.40975642204 --5.81767654419,2.00249576569,-2.42416405678 --5.82067155838,2.00649499893,-2.44759225845 --5.79966020584,2.00150084496,-2.46101331711 --5.79465675354,2.00050234795,-2.46921014786 --5.78764915466,2.00050449371,-2.48761916161 --5.78564310074,2.00250506401,-2.50904679298 --5.76463222504,1.99751102924,-2.52145242691 --5.75262355804,1.99551451206,-2.53786444664 --5.76062059402,2.00151205063,-2.56328701973 --5.73560857773,1.9945192337,-2.57470989227 --5.73460531235,1.99551951885,-2.58491373062 --5.72359752655,1.99452257156,-2.60131907463 --5.72159194946,1.99652290344,-2.62172579765 --5.71558570862,1.99652457237,-2.64114665985 --5.68357038498,1.98753404617,-2.64957857132 --5.69156837463,1.99353122711,-2.67397618294 --5.67355775833,1.98953652382,-2.68840575218 --5.67855739594,1.99253487587,-2.70059466362 --5.65154409409,1.9855427742,-2.71102809906 --5.65253973007,1.98854219913,-2.73344564438 --5.63452911377,1.98554742336,-2.74686002731 --5.63652563095,1.98854637146,-2.76926732063 --5.61451387405,1.98355293274,-2.7817003727 --5.59450292587,1.9795589447,-2.79411673546 --5.60150337219,1.98355638981,-2.80730319023 --5.58649396896,1.98056066036,-2.82273221016 --5.57148456573,1.97756516933,-2.83714294434 --5.55947637558,1.97656846046,-2.85356497765 --5.55847167969,1.97956824303,-2.87497901917 --5.53645992279,1.97457492352,-2.88640141487 --5.54145956039,1.97757303715,-2.89960336685 --5.51544618607,1.97058093548,-2.90902733803 --5.51044034958,1.97258198261,-2.92844176292 --5.49343061447,1.9685870409,-2.94185781479 --5.4904255867,1.97058725357,-2.96227121353 --5.4684138298,1.96559405327,-2.9737007618 --5.47141122818,1.97059226036,-2.9971113205 --5.45540332794,1.96559739113,-2.99931001663 --5.44639635086,1.96559965611,-3.01774525642 --5.43438816071,1.96460306644,-3.03315377235 --5.42938280106,1.96560394764,-3.05256724358 --5.41337347031,1.96360862255,-3.06699872017 --5.41537094116,1.96760714054,-3.08939623833 --5.39736032486,1.96361243725,-3.10181117058 --5.38635396957,1.96161592007,-3.10702133179 --5.37134504318,1.95862030983,-3.12144470215 --5.35733604431,1.95662438869,-3.13585877419 --5.34832954407,1.95662665367,-3.15327692032 --5.34232378006,1.95762765408,-3.17270040512 --5.32131242752,1.95363426208,-3.18311619759 --5.30830383301,1.95263791084,-3.19854092598 --5.30730199814,1.95363783836,-3.20874047279 --5.29129219055,1.95064258575,-3.22216057777 --5.2752828598,1.94864737988,-3.23558235168 --5.27828121185,1.9526450634,-3.25898122787 --5.26727390289,1.95264792442,-3.27540397644 --5.24926376343,1.94865357876,-3.28783035278 --5.23925638199,1.94865608215,-3.30424237251 --5.22324848175,1.94466161728,-3.30646157265 --5.21224069595,1.94366443157,-3.32186746597 --5.20623588562,1.9456653595,-3.34129095078 --5.19122695923,1.9436699152,-3.35470604897 --5.17821836472,1.94167351723,-3.37013578415 --5.17021274567,1.94267511368,-3.3875451088 --5.15720462799,1.94167888165,-3.40195727348 --5.13619327545,1.93468642235,-3.40118575096 --5.13419055939,1.9386857748,-3.42259931564 --5.12118196487,1.93668949604,-3.43701291084 --5.10617303848,1.93469381332,-3.45043253899 --5.09816789627,1.93569552898,-3.46784257889 --5.08415937424,1.93469953537,-3.48226976395 --5.07015037537,1.93270373344,-3.49567890167 --5.06414699554,1.93270528316,-3.50389933586 --5.0461359024,1.92871105671,-3.51532173157 --5.03012609482,1.92671597004,-3.52773928642 --5.02312135696,1.92771708965,-3.54615616798 --5.00410985947,1.92472326756,-3.55657601357 --4.98810052872,1.92172837257,-3.56899571419 --4.98509788513,1.92572772503,-3.5904173851 --4.98309612274,1.92672765255,-3.60062456131 --4.96508598328,1.92373347282,-3.61103439331 --4.95307826996,1.92273664474,-3.62645983696 --4.94907522202,1.92573654652,-3.64585542679 --4.93806791306,1.92573916912,-3.66228604317 --4.92405939102,1.9237433672,-3.67570090294 --4.904047966,1.919749856,-3.68614053726 --4.90805006027,1.92374718189,-3.70034050941 --4.88403606415,1.91875576973,-3.70574426651 --4.87302923203,1.91875851154,-3.7221763134 --4.86002159119,1.91776204109,-3.73659896851 --4.85902023315,1.92176043987,-3.75900578499 --4.83500623703,1.9167689085,-3.76543235779 --4.83900785446,1.91976594925,-3.78064584732 --4.81599473953,1.91477417946,-3.78706097603 --4.80298709869,1.91477775574,-3.80148530006 --4.80198669434,1.9187759161,-3.82388925552 --4.78297519684,1.91478228569,-3.83330607414 --4.77597093582,1.9167829752,-3.85273694992 --4.76196289062,1.91578722,-3.86514019966 --4.7519569397,1.91379070282,-3.87036561966 --4.73594760895,1.91179561615,-3.88177990913 --4.72494077682,1.91179835796,-3.89719581604 --4.72193956375,1.91579711437,-3.91962242126 --4.69292211533,1.90780842304,-3.92104506493 --4.69892644882,1.91580283642,-3.94944906235 --4.67591285706,1.91081130505,-3.95587730408 --4.66690731049,1.90981423855,-3.96109127998 --4.64789581299,1.90582084656,-3.97051715851 --4.64389419556,1.90981996059,-3.99092102051 --4.62888526917,1.9078245163,-4.00435972214 --4.62088108063,1.90982568264,-4.02075052261 --4.60287046432,1.90683174133,-4.03118181229 --4.58185768127,1.90283930302,-4.03962373734 --4.58085775375,1.9048384428,-4.04980993271 --4.57185316086,1.90583992004,-4.06723165512 --4.55984640121,1.90584290028,-4.08266305923 --4.55284309387,1.90784335136,-4.10107183456 --4.54383850098,1.90984487534,-4.11747598648 --4.52082443237,1.90485358238,-4.12391710281 --4.51181983948,1.90585494041,-4.14133787155 --4.50581645966,1.90585649014,-4.1485452652 --4.48980712891,1.90386176109,-4.15895223618 --4.47479867935,1.90286624432,-4.17137861252 --4.45778846741,1.90087199211,-4.18180274963 --4.45478868484,1.90487003326,-4.20421552658 --4.43077325821,1.89987945557,-4.20864629745 --4.4237704277,1.90187966824,-4.22806882858 --4.40776062012,1.89788663387,-4.22628068924 --4.40175819397,1.89988636971,-4.2456870079 --4.39175319672,1.9018882513,-4.26210546494 --4.36073303223,1.89290165901,-4.2605509758 --4.3627371788,1.89989686012,-4.28694868088 --4.34472608566,1.89690315723,-4.2963757515 --4.32871723175,1.89590835571,-4.30780601501 --4.32571601868,1.89690816402,-4.31699991226 --4.31270933151,1.89691150188,-4.33143186569 --4.29069566727,1.89292037487,-4.33584403992 --4.27468633652,1.89092552662,-4.34727573395 --4.2646818161,1.8929271698,-4.36369419098 --4.24566984177,1.88993430138,-4.3711104393 --4.23066186905,1.8889387846,-4.3835439682 --4.23066329956,1.8909368515,-4.39573669434 --4.21365308762,1.88994252682,-4.40617084503 --4.20164728165,1.88994550705,-4.42058849335 --4.19164276123,1.89094722271,-4.43700551987 --4.17463254929,1.88995301723,-4.44642496109 --4.15562152863,1.88695991039,-4.45486116409 --4.15062141418,1.8909586668,-4.47627592087 --4.13360881805,1.8859667778,-4.47249126434 --4.12160301208,1.88596963882,-4.48690891266 --4.11560201645,1.88996875286,-4.50732278824 --4.09959316254,1.88797402382,-4.51774358749 --4.07958078384,1.88498187065,-4.52416944504 --4.07658290863,1.88997888565,-4.54859256744 --4.05556678772,1.88298976421,-4.53980302811 --4.05156850815,1.88798737526,-4.56322669983 --4.03555870056,1.88599276543,-4.57364940643 --4.01954984665,1.88499796391,-4.58407258987 --4.00754451752,1.88600087166,-4.59849023819 --3.99353718758,1.88600480556,-4.61091136932 --3.98053073883,1.88600826263,-4.62433004379 --3.95351171494,1.8790204525,-4.62377500534 --3.95251321793,1.88201880455,-4.63495969772 --3.9325003624,1.87902677059,-4.6413936615 --3.91849327087,1.87903082371,-4.65381669998 --3.90848994255,1.88103210926,-4.67124509811 --3.89248037338,1.87903749943,-4.68065643311 --3.87547039986,1.87704372406,-4.68907165527 --3.8824801445,1.88403606415,-4.71127843857 --3.85445976257,1.87704956532,-4.70872116089 --3.84045243263,1.87705349922,-4.72114419937 --3.8244433403,1.87605917454,-4.73055839539 --3.81043624878,1.87606310844,-4.74298191071 --3.79642915726,1.87606716156,-4.75540494919 --3.78542494774,1.87706899643,-4.770819664 --3.76941275597,1.87307727337,-4.76704454422 --3.75740742683,1.87407982349,-4.78146266937 --3.73539209366,1.87008976936,-4.7838845253 --3.71838212013,1.86809575558,-4.79331922531 --3.71338438988,1.87309348583,-4.81572723389 --3.69737553596,1.87209868431,-4.8261590004 --3.67535972595,1.8681088686,-4.82757043839 --3.67136001587,1.87010836601,-4.83880090714 --3.66335940361,1.87310791016,-4.85821628571 --3.64334583282,1.87011647224,-4.86263656616 --3.63033986092,1.8701196909,-4.87605714798 --3.60832452774,1.86612963676,-4.87848711014 --3.58931231499,1.86413729191,-4.88492012024 --3.58431506157,1.86913442612,-4.90833520889 --3.58231687546,1.87113308907,-4.91952514648 --3.56630825996,1.87113833427,-4.92995929718 --3.54229044914,1.86614990234,-4.92938899994 --3.53128695488,1.86815154552,-4.94581413269 --3.50826954842,1.86216270924,-4.94522762299 --3.50327372551,1.86815929413,-4.97066450119 --3.48526215553,1.86616647243,-4.9770822525 --3.47625660896,1.86517012119,-4.98029136658 --3.45524191856,1.86217951775,-4.9837269783 --3.43422698975,1.8581892252,-4.98614931107 --3.41821789742,1.8571947813,-4.99557352066 --3.40921735764,1.8611946106,-5.01500034332 --3.3882021904,1.85720455647,-5.01641225815 --3.3781952858,1.85520899296,-5.01862955093 --3.37019586563,1.85920798779,-5.03904867172 --3.35518836975,1.85921251774,-5.05048084259 --3.33617544174,1.85722088814,-5.05489778519 --3.32016658783,1.85622644424,-5.06432342529 --3.31116580963,1.85922634602,-5.08273267746 --3.29615855217,1.85923099518,-5.09416532516 --3.27914834023,1.85823762417,-5.10158443451 --3.26814007759,1.85624265671,-5.10280990601 --3.25513505936,1.85724580288,-5.11623001099 --3.23712325096,1.85525345802,-5.12164449692 --3.2141058445,1.85126471519,-5.12209320068 --3.20510601997,1.85526442528,-5.14151191711 --3.18809556961,1.85327100754,-5.14893341064 --3.17608618736,1.85127711296,-5.14815664291 --3.1620798111,1.85228133202,-5.15957069397 --3.15207910538,1.85528159142,-5.17799425125 --3.13406729698,1.85328924656,-5.18341159821 --3.11405277252,1.85029864311,-5.18583250046 --3.1040520668,1.85329890251,-5.20425415039 --3.08604097366,1.85230600834,-5.21169805527 --3.07302951813,1.84831345081,-5.20891952515 --3.06703472137,1.85430979729,-5.23333358765 --3.04401564598,1.84932219982,-5.23075628281 --3.03000974655,1.85032606125,-5.24318218231 --3.01099634171,1.84833478928,-5.24660015106 --3.00099611282,1.85133481026,-5.2650179863 --2.98098182678,1.84834420681,-5.26845645905 --2.97097468376,1.84734892845,-5.26967048645 --2.96798467636,1.85534226894,-5.29907560349 --2.93895673752,1.84636044502,-5.28752040863 --2.92094492912,1.84436821938,-5.29294490814 --2.89892673492,1.8403801918,-5.29136991501 --2.88892745972,1.84437978268,-5.31079626083 --2.86991429329,1.84238839149,-5.31523180008 --2.85890460014,1.8393945694,-5.31343364716 --2.84489917755,1.84139835835,-5.32586050034 --2.83189511299,1.84240102768,-5.34028816223 --2.80587053299,1.83541715145,-5.33172178268 --2.79286623001,1.83741998672,-5.34513902664 --2.77485394478,1.83542823792,-5.34955787659 --2.76684975624,1.83543086052,-5.35477972031 --2.7518427372,1.83643567562,-5.3652048111 --2.73383069038,1.83544361591,-5.37063598633 --2.7188231945,1.83544874191,-5.38004875183 --2.70181274414,1.83445549011,-5.38748168945 --2.68680596352,1.83546030521,-5.39790630341 --2.66578793526,1.83147192001,-5.39632558823 --2.65878629684,1.83247315884,-5.40456008911 --2.64678430557,1.83547484875,-5.41997528076 --2.62977385521,1.83448159695,-5.42740869522 --2.61276292801,1.83348894119,-5.43282175064 --2.59374928474,1.83149802685,-5.43625593185 --2.58274960518,1.83549833298,-5.45467996597 --2.56273341179,1.83250892162,-5.45510482788 --2.55673313141,1.83350908756,-5.46432638168 --2.54272770882,1.83551311493,-5.47573900223 --2.52471590042,1.83352100849,-5.48117446899 --2.50670385361,1.83252906799,-5.48660993576 --2.49470257759,1.83553028107,-5.50303077698 --2.47668981552,1.83353877068,-5.50644636154 --2.46569132805,1.83853840828,-5.52587413788 --2.45768690109,1.83854138851,-5.5300860405 --2.4306576252,1.83056056499,-5.51652669907 --2.42366623878,1.8375556469,-5.54293584824 --2.39964175224,1.83057165146,-5.53436422348 --2.38864326477,1.83557116985,-5.55378866196 --2.36562132835,1.83058559895,-5.54822826385 --2.35261845589,1.83258783817,-5.56264591217 --2.34160804749,1.83059489727,-5.55985641479 --2.32660198212,1.83159911633,-5.57128810883 --2.30357956886,1.82661366463,-5.5657324791 --2.29759168625,1.83460700512,-5.59513759613 --2.27156162262,1.82662630081,-5.58056497574 --2.25555372238,1.82663190365,-5.58999967575 --2.24054789543,1.82863628864,-5.60143136978 --2.23354625702,1.82963764668,-5.60864973068 --2.21853995323,1.83064246178,-5.61907052994 --2.19852232933,1.8276540041,-5.61749267578 --2.18552112579,1.8306555748,-5.63392353058 --2.1645014286,1.82666838169,-5.63035154343 --2.14849376678,1.82767403126,-5.63978528976 --2.14750480652,1.83366763592,-5.65897607803 --2.12648510933,1.82968068123,-5.65540552139 --2.10947537422,1.82968759537,-5.66284370422 --2.09547257423,1.83269023895,-5.67727565765 --1.62114953995,1.81391596794,-5.79584980011 --1.60614418983,1.81592047215,-5.80626487732 --1.59013712406,1.8169260025,-5.81569480896 --1.58213341236,1.81792902946,-5.81990671158 --1.5631159544,1.8149408102,-5.81833267212 --1.54409980774,1.81295180321,-5.81877326965 --1.52207219601,1.80696940422,-5.80720615387 --1.50907468796,1.81196951866,-5.82562589645 --1.49106025696,1.81097948551,-5.82705163956 --1.48305642605,1.81098246574,-5.83126306534 --1.46404123306,1.80999314785,-5.83271312714 --1.44803225994,1.81099975109,-5.83912420273 --1.43202543259,1.81200540066,-5.84855318069 --1.41300857067,1.8100168705,-5.84799146652 --1.39900970459,1.81401765347,-5.86542129517 --1.37697863579,1.80703747272,-5.84984111786 --1.36197698116,1.81104016304,-5.86427593231 --1.35497653484,1.81304132938,-5.87148094177 --1.3349571228,1.81005430222,-5.86893320084 --1.31995224953,1.81205868721,-5.87934303284 --1.30193841457,1.81106841564,-5.88177728653 --1.2839256525,1.81107759476,-5.88521766663 --1.26289880276,1.80509495735,-5.87465238571 --1.25690424442,1.80909264088,-5.88786506653 --1.23989284039,1.80910086632,-5.89228773117 --1.22388672829,1.8111063242,-5.90171384811 --1.20587146282,1.8101170063,-5.90213918686 --1.18484354019,1.80413472652,-5.89057445526 --1.17285573483,1.81312978268,-5.91799688339 --1.15182709694,1.80714809895,-5.90542888641 --1.14081180096,1.80415773392,-5.89865541458 --1.12078714371,1.79917371273,-5.89008665085 --1.10779595375,1.80617058277,-5.91451358795 --1.09078574181,1.80717849731,-5.919942379 --1.07377386093,1.80718719959,-5.92336082458 --1.05576181412,1.80719614029,-5.92780828476 --1.03774547577,1.80520737171,-5.92723274231 --1.02974379063,1.80720937252,-5.93345117569 --1.01072394848,1.80422258377,-5.92988634109 --0.993710517883,1.80423223972,-5.93129777908 --0.974693238735,1.8022441864,-5.93074798584 --0.959693312645,1.80624604225,-5.94617080688 --0.938661575317,1.80026638508,-5.93060779572 --0.926680028439,1.81025791168,-5.96403074265 --0.915660023689,1.80527031422,-5.95224523544 --0.898649930954,1.80627799034,-5.95767307281 --0.880633711815,1.8052893877,-5.95710134506 --0.862617492676,1.80430078506,-5.95653009415 --0.84259313345,1.8003166914,-5.94898080826 --0.825581967831,1.80032515526,-5.95340538025 --0.809577345848,1.80333006382,-5.96382713318 --0.800571382046,1.80333447456,-5.96605110168 --0.782554268837,1.80234634876,-5.9644780159 --0.766551434994,1.80535018444,-5.97690534592 --0.744506001472,1.7943778038,-5.94833850861 --0.729512214661,1.80037665367,-5.96977138519 --0.712499439716,1.80038607121,-5.97218894958 --0.694483101368,1.79939746857,-5.97162151337 --0.685476303101,1.79940247536,-5.97284221649 --0.670482814312,1.80540132523,-5.99426984787 --0.652469336987,1.8054112196,-5.99671030045 --0.635460555553,1.80741858482,-6.00313901901 --0.615427315235,1.80043935776,-5.98657417297 --0.597411990166,1.80045044422,-5.98701143265 --0.583428323269,1.80944383144,-6.01743125916 --0.57239818573,1.80246174335,-5.99563932419 --0.552364587784,1.79548275471,-5.97908115387 --0.535359621048,1.79848814011,-5.98952007294 --0.517342031002,1.79650020599,-5.98795318604 --0.500328421593,1.79651010036,-5.98936986923 --0.482311040163,1.79552233219,-5.987803936 --0.473306268454,1.79652631283,-5.99103021622 --0.456300258636,1.79853224754,-6.00046443939 --0.436247766018,1.78556334972,-5.96487617493 --0.42227897048,1.80054914951,-6.00930929184 --0.403254836798,1.79756510258,-6.00175666809 --0.385227590799,1.79358255863,-5.99017381668 --0.368217796087,1.79459047318,-5.99559879303 --0.359217017889,1.79659235477,-6.00283145905 --0.341192632914,1.79360830784,-5.99425601959 --0.32317301631,1.79162168503,-5.99069070816 --0.30616119504,1.79163074493,-5.99411153793 --0.288149952888,1.7936398983,-5.99855947495 --0.181025460362,1.78072404861,-5.97015237808 --0.164011716843,1.7807341814,-5.97157335281 --0.14597427845,1.77375710011,-5.95099973679 --0.136974871159,1.77675843239,-5.9592294693 --0.119958907366,1.77576982975,-5.95864963531 --0.101943261921,1.77578127384,-5.95909547806 --0.0849275141954,1.77579271793,-5.95851659775 --0.0679327398539,1.7817928791,-5.97794818878 --0.0238690655679,1.77383422852,-5.95502758026 --0.00585981924087,1.77584254742,-5.96147584915 --0.00214958144352,1.76114284992,-5.13029289246 -0.0158554688096,1.75813984871,-5.12070655823 -0.0769042670727,1.7561467886,-5.11810493469 -0.0939266234636,1.75915324688,-5.12548923492 -0.110932968557,1.75615143776,-5.11788415909 -0.128942400217,1.75415086746,-5.1123008728 -0.145966872573,1.75815832615,-5.12168216705 -0.154974713922,1.75815975666,-5.12188768387 -0.171982377768,1.75615847111,-5.11528348923 -0.188997209072,1.75616109371,-5.11567306519 -0.207016006112,1.75716555119,-5.11908149719 -0.224018543959,1.75316166878,-5.10748577118 -0.24103859067,1.75516700745,-5.11286830902 -0.258037269115,1.75016105175,-5.09727954865 -0.267050296068,1.75216507912,-5.10247945786 -0.284066319466,1.7531683445,-5.10386753082 -0.303097099066,1.75817883015,-5.1182808876 -0.371138721704,1.75318002701,-5.10186815262 -0.379132926464,1.74917459488,-5.08907556534 -0.396143972874,1.7481752634,-5.08547401428 -0.414168566465,1.75118279457,-5.09486913681 -0.43219217658,1.7541898489,-5.10326433182 -0.447182178497,1.74717986584,-5.07965993881 -0.465199947357,1.74818384647,-5.0820684433 -0.482211083174,1.747184515,-5.07846784592 -0.491225838661,1.75018966198,-5.08565711975 -0.508236050606,1.74918997288,-5.08105945587 -0.52726328373,1.75319862366,-5.09246635437 -0.545286655426,1.75620567799,-5.10085725784 -0.562297999859,1.75620639324,-5.09725522995 -0.578299701214,1.75220239162,-5.08465623856 -0.597327530384,1.75621163845,-5.09705686569 -0.605329990387,1.75521039963,-5.09225320816 -0.62335062027,1.75821590424,-5.09764862061 -0.641370177269,1.76022076607,-5.10204553604 -0.659389615059,1.76222586632,-5.10644245148 -0.67438429594,1.75621843338,-5.08684635162 -0.693408191204,1.75922548771,-5.09525299072 -0.702421724796,1.76222991943,-5.10143709183 -0.716411054134,1.75422000885,-5.07683801651 -0.734425067902,1.75422215462,-5.07525491714 -0.751438140869,1.75422394276,-5.0736489296 -0.767444193363,1.75222229958,-5.06504440308 -0.784457325935,1.75222420692,-5.06343889236 -0.804489195347,1.75823533535,-5.07983446121 -0.81248831749,1.75623238087,-5.07104921341 -0.831512987614,1.76023983955,-5.08044576645 -0.848526835442,1.76024222374,-5.07983446121 -0.864528477192,1.75623834133,-5.0662522316 -0.882550597191,1.76024460793,-5.07363080978 -0.901570677757,1.76224982738,-5.07804393768 -0.917576014996,1.76024782658,-5.06844615936 -0.926585614681,1.7612503767,-5.07064151764 -0.94259083271,1.75824844837,-5.06104564667 -0.957593679428,1.75524544716,-5.04943656921 -0.976615488529,1.7582514286,-5.05583906174 -0.994631409645,1.7602545023,-5.05624437332 -1.01566576958,1.76726686954,-5.07563018799 -1.0296612978,1.76226019859,-5.05603694916 -1.03967320919,1.76326370239,-5.06024360657 -1.05567979813,1.76226246357,-5.05164480209 -1.0777182579,1.771276474,-5.07502746582 -1.09473192692,1.77127897739,-5.07441234589 -1.10973095894,1.7672740221,-5.05783081055 -1.12573897839,1.76527357101,-5.05122423172 -1.17178237438,1.7702832222,-5.05622959137 -1.18879544735,1.77128529549,-5.05461835861 -1.21478009224,1.75726950169,-5.00845241547 -1.23179197311,1.75727081299,-5.00485515594 -1.25282371044,1.76428174973,-5.0222287178 -1.25178706646,1.74926233292,-4.97746086121 -1.26980447769,1.75126647949,-4.97985315323 -1.27978670597,1.74125385284,-4.94627523422 -1.34284687042,1.74826788902,-4.95365333557 -1.36186742783,1.75127339363,-4.9590473175 -1.37185192108,1.74226200581,-4.92746925354 -1.39087080956,1.74426686764,-4.93087625504 -1.40989124775,1.74727225304,-4.93626832962 -1.42690241337,1.74727332592,-4.93167972565 -1.44492053986,1.75027787685,-4.9350605011 -1.45292317867,1.74927699566,-4.92927789688 -1.86520957947,1.75831401348,-4.83509397507 -1.86318647861,1.74730193615,-4.80232620239 -1.88721740246,1.75431215763,-4.8187122345 -1.89821350574,1.74930691719,-4.79812812805 -1.91522574425,1.75030863285,-4.79452943802 -1.93123590946,1.75030958652,-4.78892660141 -1.94624269009,1.74930906296,-4.77933692932 -1.96024775505,1.74730789661,-4.76873588562 -1.96825289726,1.74730837345,-4.76593494415 -1.98326086998,1.74630856514,-4.75832939148 -2.00628757477,1.75331664085,-4.76972532272 -2.01527929306,1.74530959129,-4.74415302277 -2.05531930923,1.75332021713,-4.75392818451 -2.07132792473,1.75332033634,-4.74535226822 -2.07933282852,1.75332093239,-4.74255037308 -2.09434103966,1.75232112408,-4.7349448204 -2.12338042259,1.76333475113,-4.76032686234 -2.13137197495,1.75632786751,-4.7347407341 -2.1483836174,1.75732946396,-4.73014783859 -2.15938162804,1.75332510471,-4.7105717659 -2.18441200256,1.7613350153,-4.72694587708 -2.18540072441,1.75432860851,-4.70617055893 -2.21842360497,1.75633168221,-4.69696378708 -2.23342990875,1.75433111191,-4.68638849258 -2.24843835831,1.75433158875,-4.67878341675 -2.26444864273,1.75433278084,-4.67317914963 -2.32351231575,1.77135145664,-4.69915628433 -2.32749795914,1.76134228706,-4.6665763855 -2.34350752831,1.76134324074,-4.65998077393 -2.35951662064,1.76134395599,-4.65239572525 -2.37753105164,1.76334679127,-4.65078878403 -2.39454197884,1.76334822178,-4.64520359039 -2.40455079079,1.7653503418,-4.64639949799 -2.41655278206,1.76234805584,-4.63081598282 -2.43356490135,1.76335012913,-4.62720870972 -2.45157837868,1.76535260677,-4.62461042404 -2.46358156204,1.76335096359,-4.61100721359 -2.47658586502,1.76134979725,-4.59841489792 -2.48859834671,1.76435351372,-4.60360622406 -2.50260424614,1.76335275173,-4.59202384949 -2.51661038399,1.76235246658,-4.58143091202 -2.53662705421,1.76535618305,-4.58183813095 -2.55464076996,1.76735877991,-4.57923746109 -2.56864690781,1.76535844803,-4.56864500046 -2.59267115593,1.77236545086,-4.57802867889 -2.59166026115,1.76535952091,-4.55724573135 -2.61067509651,1.76836264133,-4.55565166473 -2.62367987633,1.76636171341,-4.54306268692 -2.63668513298,1.76536095142,-4.53146219254 -2.66070818901,1.77136731148,-4.53886270523 -2.67171025276,1.76836550236,-4.52425765991 -2.68571615219,1.76736521721,-4.51267766953 -2.68971467018,1.76436316967,-4.50188779831 -2.7107334137,1.76936781406,-4.50527095795 -2.72774410248,1.76936924458,-4.49869251251 -2.74776148796,1.77337348461,-4.50106525421 -2.75976443291,1.77137184143,-4.48549413681 -2.7747733593,1.7713726759,-4.47788763046 -2.78877997398,1.77037262917,-4.46729707718 -2.81080627441,1.78038156033,-4.48748683929 -2.81579875946,1.77237606049,-4.46091413498 -2.83180904388,1.77337729931,-4.45431375504 -2.84481453896,1.77237701416,-4.44271564484 -2.86883664131,1.77838277817,-4.44911003113 -2.88384509087,1.77838349342,-4.44051361084 -2.89385318756,1.78038525581,-4.44070768356 -2.89984846115,1.77438104153,-4.41712474823 -2.91585803032,1.77438235283,-4.41052389145 -2.93587374687,1.77838563919,-4.40893554688 -2.94887924194,1.77638530731,-4.39733934402 -2.96488904953,1.77738666534,-4.38974952698 -2.98190045357,1.778388381,-4.38415336609 -2.99190855026,1.78039014339,-4.38434505463 -2.99990701675,1.77638721466,-4.36376905441 -3.02392816544,1.78239274025,-4.36916255951 -3.03893685341,1.78239357471,-4.36056566238 -3.05194306374,1.78139364719,-4.34995651245 -3.070956707,1.78339624405,-4.34636926651 -3.08296108246,1.78239560127,-4.33278083801 -3.09497189522,1.78539848328,-4.33596801758 -3.10697579384,1.78339743614,-4.321393013 -3.1309967041,1.78940284252,-4.32677698135 -3.13799476624,1.78439998627,-4.30618953705 -3.16902375221,1.79440820217,-4.31959342957 -3.1660091877,1.78340065479,-4.28501033783 -3.17701268196,1.78139960766,-4.26943302155 -3.19002437592,1.78540289402,-4.27362012863 -3.1900138855,1.77639687061,-4.24304533005 -3.2150349617,1.78240251541,-4.24844121933 -3.24306058884,1.79140937328,-4.25881958008 -3.24905776978,1.78540623188,-4.23624897003 -3.26807117462,1.78840887547,-4.23265361786 -3.26606440544,1.78340542316,-4.21585464478 -3.289083004,1.78840994835,-4.21824789047 -3.29407906532,1.78240668774,-4.19467735291 -3.31609654427,1.78741061687,-4.19507837296 -3.33110547066,1.78741168976,-4.18647909164 -3.3541238308,1.79241621494,-4.18886709213 -3.36512756348,1.79141533375,-4.17329359055 -3.37813854218,1.79441821575,-4.17648506165 -3.38413667679,1.78941559792,-4.15490913391 -3.40214920044,1.7924182415,-4.15128946304 -3.41615700722,1.79241883755,-4.14069986343 -3.42816233635,1.79141867161,-4.12711763382 -3.44317126274,1.79141998291,-4.11851596832 -3.4641866684,1.79542338848,-4.11691808701 -3.46518397331,1.79242157936,-4.10412693024 -3.48119354248,1.79242300987,-4.09554290771 -3.50020718575,1.79642558098,-4.09193658829 -3.51321363449,1.79542601109,-4.07935810089 -3.53022503853,1.7974281311,-4.0737452507 -3.54423260689,1.79742896557,-4.06315374374 -3.55223417282,1.79442751408,-4.04457855225 -3.56224155426,1.79642915726,-4.04376745224 -3.58325648308,1.80043244362,-4.04117679596 -3.59125804901,1.79643118382,-4.02358818054 -3.60927033424,1.79943346977,-4.01798963547 -3.62728214264,1.80143558979,-4.01140546799 -3.64829707146,1.80543887615,-4.00881099701 -3.65629887581,1.80243802071,-3.99220776558 -3.65529489517,1.79843568802,-3.97643661499 -3.66629958153,1.79643583298,-3.96284103394 -3.69332075119,1.80344092846,-3.96723723412 -3.70632791519,1.80344164371,-3.95564293861 -3.71332931519,1.80044066906,-3.93804168701 -3.73534488678,1.80544412136,-3.93644237518 -3.75135493279,1.80644571781,-3.92785143852 -3.76236271858,1.80844736099,-3.92606663704 -3.76936411858,1.80544638634,-3.9074819088 -3.78637504578,1.80744838715,-3.90087509155 -3.78036427498,1.79744374752,-3.86829948425 -3.81138801575,1.80644965172,-3.87570142746 -3.8253967762,1.80745089054,-3.86609101295 -3.83340144157,1.80745172501,-3.86130309105 -3.8414041996,1.80545115471,-3.84372258186 -3.86341953278,1.80945456028,-3.84211421013 -3.86141324043,1.80145132542,-3.81355023384 -3.89543938637,1.81245791912,-3.82394075394 -3.89643597603,1.80645561218,-3.79936242104 -3.88041782379,1.79244911671,-3.75778985023 -3.86640381813,1.78244423866,-3.73002409935 -3.84638261795,1.76543676853,-3.68348026276 -3.83336830139,1.75343155861,-3.64590620995 -3.81034564972,1.73642396927,-3.59736037254 -3.80734014511,1.72842144966,-3.56979227066 -3.80833888054,1.72342014313,-3.54720687866 -3.79932904243,1.71341645718,-3.51463246346 -3.80933618546,1.71441817284,-3.51283407211 -3.80833339691,1.70841658115,-3.48727440834 -3.82034134865,1.70841801167,-3.47568511963 -3.84135699272,1.71342170238,-3.47308444977 -3.84535837173,1.70942127705,-3.45350527763 -3.86237049103,1.71142411232,-3.44789099693 -3.86837458611,1.71142482758,-3.4411137104 -3.87137556076,1.70742440224,-3.42152070999 -3.88038110733,1.7064255476,-3.40693664551 -3.89138865471,1.70542693138,-3.39435005188 -3.89839315414,1.7044274807,-3.37875247002 -3.90139460564,1.70042741299,-3.35916471481 -3.90939974785,1.6984282732,-3.34260439873 -3.91340255737,1.69742870331,-3.33579730988 -3.91440248489,1.69242823124,-3.31323623657 -3.92140722275,1.69042909145,-3.29764437675 -3.93841958046,1.69343197346,-3.29104614258 -3.9594347477,1.69743561745,-3.28745484352 -3.95042800903,1.68843352795,-3.25787043571 -3.96443796158,1.68943572044,-3.24827980995 -3.95643234253,1.68343412876,-3.22950959206 -3.97844815254,1.68843793869,-3.22789478302 -3.97944927216,1.68443787098,-3.20632553101 -4.00046443939,1.68844163418,-3.20371198654 -4.01047134399,1.68744313717,-3.19013357162 -4.00947093964,1.68244290352,-3.1675555706 -4.02248096466,1.68344521523,-3.15696787834 -4.0274848938,1.6834461689,-3.15017938614 -4.03749227524,1.6824477911,-3.13660287857 -4.04549837112,1.68144929409,-3.12201452255 -4.05550575256,1.68145108223,-3.10941886902 -4.06751489639,1.68245327473,-3.09881520271 -4.07151889801,1.67845404148,-3.08024549484 -4.07352113724,1.67545485497,-3.06066584587 -4.07652425766,1.67445540428,-3.05286812782 -4.0865316391,1.67345738411,-3.03929424286 -4.09754037857,1.6744594574,-3.02769589424 -4.10654735565,1.67346131802,-3.01410722733 -4.10554838181,1.66846168041,-2.99252796173 -4.12055969238,1.6704646349,-2.98295068741 -4.11655807495,1.66646420956,-2.9701499939 -4.14157533646,1.67346847057,-2.96954059601 -4.13557338715,1.66646838188,-2.94397163391 -4.15758895874,1.6714720726,-2.94037604332 -4.15158748627,1.66447210312,-2.9148106575 -4.17360305786,1.66947591305,-2.91121315956 -4.16660070419,1.66247594357,-2.88563680649 -4.17360591888,1.66247725487,-2.88084053993 -4.18061256409,1.66147911549,-2.86526751518 -4.19362258911,1.66248178482,-2.85565924644 -4.19462537766,1.6584829092,-2.83608269691 -4.19763040543,1.65648448467,-2.81849479675 -4.21864509583,1.66048824787,-2.81291866302 -4.21764755249,1.65648925304,-2.79233717918 -4.22565317154,1.65749084949,-2.78853344917 -4.23966407776,1.65949356556,-2.77893805504 -4.24466991425,1.65749549866,-2.76236104965 -4.24367237091,1.65349674225,-2.74178385735 -4.24667692184,1.6504983902,-2.72420215607 -4.26368999481,1.65350162983,-2.71660661697 -4.27369832993,1.65350413322,-2.70401787758 -4.27169895172,1.65150475502,-2.69322109222 -4.28871154785,1.65450799465,-2.6856238842 -4.2857131958,1.64950931072,-2.66404700279 -4.29672288895,1.64951205254,-2.65147280693 -4.3187379837,1.65551567078,-2.6468770504 -4.31073760986,1.64751672745,-2.62230062485 -4.3167424202,1.64851808548,-2.61650919914 -4.31374502182,1.64351963997,-2.59493923187 -4.32675552368,1.64552247524,-2.58532786369 -4.33776521683,1.646525383,-2.57275342941 -4.33276605606,1.64052689075,-2.55018281937 -4.34577703476,1.64252996445,-2.5395925045 -4.3487830162,1.63953232765,-2.52202224731 -4.35478782654,1.64053356647,-2.51720952988 -4.37280130386,1.64453709126,-2.50961828232 -4.36880350113,1.63853883743,-2.48804521561 -4.37481117249,1.63754153252,-2.47247242928 -4.38581991196,1.63854432106,-2.46185517311 -4.38482427597,1.63554644585,-2.44228100777 -4.39183235168,1.63454926014,-2.42770075798 -4.39983892441,1.63555085659,-2.42291307449 -4.40784740448,1.63555371761,-2.40932321548 -4.41285467148,1.6345564127,-2.39374041557 -4.42686605453,1.63655972481,-2.38315963745 -4.41886711121,1.62956166267,-2.35959362984 -4.43688011169,1.63356518745,-2.35199522972 -4.44288825989,1.63356792927,-2.33740377426 -4.4388885498,1.62956893444,-2.32660102844 -4.44589710236,1.62957191467,-2.31202292442 -4.45890855789,1.63157522678,-2.30045080185 -4.44690799713,1.62357711792,-2.27586841583 -4.46392059326,1.62658071518,-2.26727747917 -4.47293043137,1.62758362293,-2.25467944145 -4.47193241119,1.62558507919,-2.24489402771 -4.48494386673,1.6275883913,-2.23332095146 -4.48795032501,1.62559127808,-2.21772003174 -4.50096178055,1.6275947094,-2.20614624023 -4.50196790695,1.62459766865,-2.18856859207 -4.52298212051,1.62960135937,-2.18197250366 -4.50598096848,1.62060344219,-2.15539383888 -4.51598787308,1.62260532379,-2.15160131454 -4.5269985199,1.62460875511,-2.14000296593 -4.52600383759,1.62061166763,-2.12142920494 -4.53701448441,1.62261509895,-2.10885357857 -4.54302310944,1.62161839008,-2.09426832199 -4.54503011703,1.61962151527,-2.07768440247 -4.54603672028,1.61762475967,-2.06011343002 -4.55504322052,1.61862647533,-2.05630683899 -4.55004739761,1.61462962627,-2.03574109077 -4.56405925751,1.61763298512,-2.02612829208 -4.5780711174,1.61963665485,-2.01553797722 -4.57507658005,1.615639925,-1.99597358704 -4.58708763123,1.61764335632,-1.98438441753 -4.60009908676,1.61964714527,-1.97280478477 -4.59510040283,1.61664867401,-1.96201014519 -4.59110593796,1.61265194416,-1.94243896008 -4.60711812973,1.61565566063,-1.93284380436 -4.6021232605,1.61165904999,-1.91326439381 -4.61413431168,1.61366260052,-1.90167379379 -4.61914348602,1.61266624928,-1.88610517979 -4.62714958191,1.61466813087,-1.88130581379 -4.61715316772,1.60867154598,-1.85972762108 -4.63616657257,1.61267530918,-1.85113525391 -4.63017177582,1.60867881775,-1.83155238628 -4.642182827,1.60968279839,-1.81898415089 -4.64719200134,1.60968637466,-1.80439305305 -4.6361951828,1.60268998146,-1.78281378746 -4.64620256424,1.605692029,-1.77803230286 -4.65121173859,1.60469567776,-1.76344311237 -4.66222238541,1.60669946671,-1.75183928013 -4.67723464966,1.60970318317,-1.74124908447 -4.67124032974,1.60570704937,-1.72167503834 -4.67224836349,1.60371100903,-1.70509684086 -4.67725419998,1.6047129631,-1.69831371307 -4.67626142502,1.60171675682,-1.68171811104 -4.66526556015,1.59572088718,-1.6601524353 -4.69728326797,1.60472452641,-1.65654611588 -4.70329284668,1.60472846031,-1.64196681976 -4.69529819489,1.59973275661,-1.62140762806 -4.69430589676,1.59773683548,-1.60481572151 -4.70631361008,1.60073876381,-1.60102152824 -4.71032333374,1.5997428894,-1.58545029163 -4.71033143997,1.59774696827,-1.56886863708 -4.72634363174,1.60175073147,-1.55925488472 -4.73235321045,1.60175490379,-1.54467630386 -4.72936153412,1.59875941277,-1.5261194706 -4.73537111282,1.59876334667,-1.5125169754 -4.74137687683,1.59976541996,-1.50574100018 -4.74838733673,1.60076951981,-1.49214625359 -4.75239610672,1.59977352619,-1.47755146027 -4.74840450287,1.59677827358,-1.45899021626 -4.75441408157,1.59678256512,-1.44441282749 -4.76642560959,1.59878647327,-1.43280911446 -4.77043581009,1.59879088402,-1.41723966599 -4.76943969727,1.59779286385,-1.4094312191 -4.77044868469,1.59579753876,-1.39286386967 -4.77445793152,1.59580183029,-1.37827062607 -4.79747247696,1.60180556774,-1.36967432499 -4.79648113251,1.59981000423,-1.35309159756 -4.78948879242,1.59581518173,-1.33353984356 -4.79949522018,1.59781706333,-1.32874119282 -4.80250501633,1.59782135487,-1.31414020061 -4.80151367188,1.59582602978,-1.29756045341 -4.79552173615,1.59183108807,-1.27899563313 -4.81853580475,1.59783470631,-1.27039027214 -4.81954526901,1.59683966637,-1.25382602215 -4.82255506516,1.59584403038,-1.23922646046 -4.828561306,1.59784626961,-1.23244535923 -4.82957029343,1.59585094452,-1.21685731411 -4.8395819664,1.59785532951,-1.20328080654 -4.83659076691,1.59586012363,-1.18669080734 -4.82559728622,1.5898655653,-1.16712486744 -4.84061050415,1.59386980534,-1.15553081036 -4.84162044525,1.59187483788,-1.13897061348 -4.84162521362,1.59187734127,-1.13117432594 -4.84563493729,1.59188187122,-1.1165831089 -4.85964775085,1.59488618374,-1.10400474072 -4.85265541077,1.59089148045,-1.08642017841 -4.8606672287,1.59189605713,-1.07282853127 -4.86467790604,1.59190106392,-1.05726289749 -4.86868810654,1.59190583229,-1.04267144203 -4.87269353867,1.59290802479,-1.03587496281 -4.88570594788,1.5959123373,-1.02328562737 -4.88571548462,1.59491729736,-1.00769555569 -4.88272571564,1.59192299843,-0.990140378475 -4.89873838425,1.59692704678,-0.9785400033 -4.891746521,1.5929325819,-0.960962951183 -4.90075397491,1.59593462944,-0.955167591572 -4.89776277542,1.59293997288,-0.938588500023 -4.89577293396,1.59094548225,-0.922015964985 -4.89978313446,1.59095036983,-0.907424807549 -4.90879535675,1.59295499325,-0.893833994865 -4.90480470657,1.58996081352,-0.876278460026 -4.90981626511,1.59096586704,-0.86169219017 -4.9048204422,1.58896887302,-0.85289978981 -4.91883277893,1.59197318554,-0.840307295322 -4.91884279251,1.59097850323,-0.824721693993 -4.93485641479,1.59598278999,-0.812136054039 -4.92186450958,1.58998918533,-0.793566644192 -4.93587732315,1.59399366379,-0.780969917774 -4.93688774109,1.59299898148,-0.765389859676 -4.9368929863,1.59200179577,-0.75759780407 -4.93090295792,1.58900797367,-0.74003893137 -4.94291496277,1.59201228619,-0.727430522442 -4.93892478943,1.59001815319,-0.710855603218 -4.93793582916,1.58902406693,-0.694294691086 -4.94594717026,1.59002876282,-0.680693864822 -4.94595861435,1.58903479576,-0.664137601852 -4.95096492767,1.59003710747,-0.657340705395 -4.95197582245,1.5900427103,-0.641762495041 -4.95098638535,1.58904850483,-0.626176953316 -4.96399879456,1.59205281734,-0.613566756248 -4.96500968933,1.59205853939,-0.59798848629 -4.95501995087,1.58706521988,-0.580423355103 -4.95602560043,1.5870680809,-0.572636842728 -4.96803808212,1.59007275105,-0.559046566486 -4.9630484581,1.58807909489,-0.542474865913 -4.95605897903,1.58508551121,-0.525897800922 -4.9640712738,1.58709073067,-0.511318802834 -4.9600815773,1.58509671688,-0.495726972818 -4.96609354019,1.58610212803,-0.481140941381 -4.96909999847,1.58710503578,-0.473360747099 -4.96011018753,1.58311164379,-0.456781715155 -4.9681224823,1.58511686325,-0.44220110774 -4.97213363647,1.58512234688,-0.427608400583 -4.969145298,1.58312880993,-0.411048918962 -4.97415733337,1.58513426781,-0.39645832777 -4.98016929626,1.58613967896,-0.381870180368 -4.97317457199,1.58314347267,-0.373090147972 -4.98318719864,1.58614873886,-0.358511477709 -4.97319793701,1.58215582371,-0.341936916113 -4.97320985794,1.58116185665,-0.326360970736 -4.97122097015,1.58016812801,-0.310780644417 -4.98223352432,1.58317291737,-0.297175765038 -4.98224544525,1.58317923546,-0.281599521637 -4.98125123978,1.58218240738,-0.273809731007 -4.97726202011,1.58018887043,-0.25822648406 -4.99127578735,1.58519387245,-0.243650555611 -4.98028707504,1.5802012682,-0.227082058787 -4.99029970169,1.58320653439,-0.212497502565 -4.97931051254,1.57921409607,-0.195931121707 -4.97431612015,1.57721757889,-0.188136219978 -4.97732782364,1.57822346687,-0.173540204763 -4.99534225464,1.58322811127,-0.158965170383 -4.97335243225,1.57623660564,-0.142387598753 -4.9923658371,1.58124113083,-0.127811640501 -4.98337745667,1.57824838161,-0.112226784229 -4.99038982391,1.58025383949,-0.0976341217756 -4.97939491272,1.57625854015,-0.0888625383377 -4.97040653229,1.57326579094,-0.0732809975743 -4.98142004013,1.57627105713,-0.0586918704212 -4.9874329567,1.57827711105,-0.0431236550212 -4.98844480515,1.57828319073,-0.02852454409 -4.99145793915,1.57928955555,-0.0129531780258 -4.98546361923,1.57729327679,-0.00516306329519 -4.98447608948,1.5763001442,0.0104100033641 -4.99448919296,1.58030533791,0.0250053945929 -4.98550081253,1.5763130188,0.0405813492835 -4.97651290894,1.57332062721,0.0561559945345 -4.98852682114,1.57732605934,0.0717257037759 -4.97753858566,1.57333409786,0.087298989296 -4.97954463959,1.57433688641,0.0941115692258 -4.98255777359,1.57434332371,0.109683118761 -4.99057102203,1.57734918594,0.125256165862 -4.9905834198,1.57735550404,0.139855399728 -4.96559476852,1.56936538219,0.155420616269 -4.97960853577,1.5733705759,0.170996069908 -4.97762107849,1.5723772049,0.185593351722 -4.97962760925,1.57338047028,0.193380102515 -4.97964048386,1.57338750362,0.208951592445 -4.97765398026,1.57239460945,0.224521636963 -4.97766637802,1.57240116596,0.239119753242 -4.97567987442,1.57240831852,0.254689604044 -4.96769285202,1.56941652298,0.270253360271 -4.97869968414,1.57341849804,0.278049319983 -4.99071264267,1.57742345333,0.292660057545 -4.97672557831,1.5724323988,0.308216810226 -4.97873878479,1.57343924046,0.323790758848 -4.98375177383,1.57544505596,0.33839571476 -4.97576522827,1.57245326042,0.353956818581 -4.98077917099,1.57445979118,0.36953574419 -4.97078466415,1.57146430016,0.376333653927 -4.97279834747,1.57247114182,0.391908198595 -4.97781181335,1.57447767258,0.407488137484 -4.96182489395,1.56948673725,0.422059118748 -4.96683883667,1.57049310207,0.437638938427 -4.97585201263,1.57449901104,0.453227847815 -4.97486495972,1.57450592518,0.467824965715 -4.98587226868,1.57850813866,0.476606875658 -4.96388483047,1.57051801682,0.490186870098 -4.96889877319,1.57252442837,0.505769610405 -4.97691297531,1.57653093338,0.522333800793 -4.96692657471,1.57253932953,0.53690969944 -4.96894025803,1.57454633713,0.552487373352 -4.97795343399,1.57755208015,0.568082988262 -4.96996021271,1.57455670834,0.574875831604 -4.95897388458,1.57156550884,0.589446604252 -4.96498775482,1.57457184792,0.60503578186 -4.97300195694,1.57757818699,0.621604979038 -4.95101594925,1.57058858871,0.635168492794 -4.95202875137,1.57059538364,0.64977055788 -4.96203613281,1.57459771633,0.658560693264 -4.95205020905,1.57160651684,0.673130095005 -4.95206451416,1.57261395454,0.688703536987 -4.96407747269,1.57661914825,0.70431625843 -4.94709205627,1.57162940502,0.718860626221 -4.91510677338,1.56164121628,0.730430781841 -4.3851146698,1.57775580883,2.53020429611 -4.38113164902,1.57976508141,2.54480075836 -4.38214063644,1.58176958561,2.55458068848 -4.36416101456,1.57778203487,2.56215524673 -4.35717916489,1.57779240608,2.57573509216 -4.34919834137,1.57780313492,2.58930182457 -4.35321474075,1.58181118965,2.60889172554 -4.3322353363,1.57682418823,2.61446809769 -4.3202457428,1.57383084297,2.61625814438 -4.34026050568,1.58483636379,2.64583849907 -4.30728292465,1.57485163212,2.64440822601 -4.3142991066,1.58085930347,2.66599822044 -4.30131912231,1.57887101173,2.67656517029 -4.31633377075,1.58787715435,2.70315623283 -4.28235673904,1.5778927803,2.70072603226 -4.30636119843,1.58889245987,2.72353863716 -4.26538658142,1.5759100914,2.71807432175 -4.27540254593,1.58291709423,2.74166965485 -4.2574224472,1.57892942429,2.74825382233 -4.26243972778,1.58393788338,2.76982712746 -4.25345897675,1.58394885063,2.78240418434 -4.26347398758,1.59095561504,2.80600857735 -4.23148870468,1.57996666431,2.79576992989 -4.24750328064,1.58997237682,2.82337379456 -4.22952461243,1.58598542213,2.83093237877 -4.21754455566,1.58499693871,2.84151029587 -4.19956493378,1.58100962639,2.84808802605 -4.21158123016,1.58901667595,2.87466454506 -4.19160270691,1.58502984047,2.88023400307 -4.18761205673,1.58503484726,2.88604092598 -4.19162893295,1.59004354477,2.90761399269 -4.1746506691,1.58705615997,2.91518187523 -4.1646695137,1.58606731892,2.92676639557 -4.15768861771,1.58707773685,2.94035196304 -4.15070724487,1.58708822727,2.95393800735 -4.14071798325,1.58509492874,2.9567193985 -4.13673782349,1.5871052742,2.97328615189 -4.12975645065,1.58811581135,2.98687267303 -4.11777591705,1.58712697029,2.99646949768 -4.11279582977,1.5891379118,3.01302242279 -4.10081481934,1.58714914322,3.02261829376 -4.10382413864,1.59115338326,3.03440594673 -4.08884525299,1.58816576004,3.04297614098 -4.08086442947,1.58917677402,3.05654859543 -4.05988645554,1.5831900835,3.06012964249 -4.06690359116,1.59119832516,3.08470463753 -4.05692243576,1.59020900726,3.09530997276 -4.04594278336,1.58922076225,3.1068778038 -4.0459523201,1.59122550488,3.11666488647 -4.04097127914,1.59323585033,3.13224458694 -4.02099323273,1.58924937248,3.13681554794 -4.01301240921,1.58925998211,3.14941048622 -4.00203323364,1.58927178383,3.16097784042 -4.00005149841,1.59228134155,3.17856621742 -3.9870724678,1.59129345417,3.18814277649 -3.9780831337,1.58929991722,3.19093155861 -3.97410225868,1.59131014347,3.20750951767 -3.96312332153,1.5913220644,3.21907711029 -3.9491443634,1.5893342495,3.22765636444 -3.9391644001,1.58934557438,3.23923945427 -3.94718146324,1.59635365009,3.26581501961 -3.92220449448,1.59036791325,3.26539468765 -3.92621278763,1.59437179565,3.27819418907 -3.91323375702,1.59238374233,3.28776884079 -3.90225458145,1.59239578247,3.29933595657 -3.88327717781,1.5884090662,3.30390954018 -3.88329529762,1.59241831303,3.32350087166 -3.86931633949,1.59143078327,3.33207726479 -3.87532520294,1.5964345932,3.34785580635 -3.86234545708,1.59444642067,3.35644960403 -3.84336805344,1.59145987034,3.36101937294 -3.8433868885,1.59546947479,3.38159608841 -3.83440732956,1.59648084641,3.39417862892 -3.82042765617,1.59449279308,3.40177345276 -3.80844926834,1.5935049057,3.41234302521 -3.81445765495,1.59850859642,3.428129673 -3.7974793911,1.59552145004,3.43371105194 -3.78250145912,1.59353411198,3.44128680229 -3.77452158928,1.59454536438,3.45486760139 -3.76754164696,1.59655630589,3.46944737434 -3.75656318665,1.59656834602,3.48101472855 -3.7575814724,1.60157763958,3.50260233879 -3.73959422112,1.59558582306,3.49639630318 -3.73461413383,1.59859657288,3.51297450066 -3.71763730049,1.59561002254,3.51953101158 -3.71165633202,1.597620368,3.53413152695 -3.69267916679,1.59363389015,3.53770804405 -3.69669771194,1.60064291954,3.56327986717 -3.68470907211,1.59764993191,3.56207990646 -3.66973161697,1.59566271305,3.56965112686 -3.66874980927,1.60067224503,3.58925032616 -3.65477204323,1.59868490696,3.59782075882 -3.65079164505,1.60169529915,3.61540484428 -3.63681364059,1.60070800781,3.62397551537 -3.62183618546,1.59872090816,3.63154554367 -3.61784648895,1.59972655773,3.63833904266 -3.60886788368,1.60073816776,3.65190792084 -3.5858912468,1.59475231171,3.65049505234 -3.57991194725,1.59776341915,3.66706395149 -3.57193255424,1.59877467155,3.68065214157 -3.56595230103,1.60178542137,3.69624209404 -3.55397439003,1.60179781914,3.70681118965 -3.55298399925,1.60380268097,3.71660804749 -3.53900647163,1.60181558132,3.72517633438 -3.52202916145,1.59982860088,3.72975993156 -3.52004861832,1.60383880138,3.75033807755 -3.50407195091,1.60185205936,3.75690364838 -3.49609160423,1.60386276245,3.76951408386 -3.48910307884,1.60286939144,3.77428865433 -3.48212409019,1.6058806181,3.78986477852 -3.46514701843,1.60289382935,3.79444551468 -3.45816779137,1.60490512848,3.81002306938 -3.44319081306,1.60391831398,3.81758785248 -3.43321180344,1.60392987728,3.82917904854 -3.42623281479,1.60694110394,3.84475874901 -3.42024445534,1.60694754124,3.85053515434 -3.4072663784,1.60595977306,3.85912108421 -3.39928722382,1.60797119141,3.87370038033 -3.38031029701,1.60398471355,3.87529015541 -3.36933255196,1.60499691963,3.8868625164 -3.3653523922,1.60900735855,3.90545320511 -3.35636496544,1.60801446438,3.9082224369 -3.35238480568,1.6120249033,3.92681527138 -3.33640766144,1.61003804207,3.93239307404 -3.32243013382,1.60805058479,3.93997573853 -3.31645059586,1.61206150055,3.95656561852 -3.29547548294,1.60707604885,3.95712614059 -3.28549718857,1.60808801651,3.96970391273 -3.28450703621,1.61109304428,3.98049807549 -3.27452874184,1.61210501194,3.99307727814 -3.25655221939,1.60911846161,3.99566197395 -3.24657416344,1.61013042927,4.00824117661 -3.25159215927,1.61913907528,4.03882837296 -3.22461771965,1.61215436459,4.03041028976 -3.21363997459,1.61216664314,4.04198741913 -3.21265029907,1.61517202854,4.05376958847 -3.19867229462,1.61418426037,4.06036806107 -3.1816971302,1.61219835281,4.0659198761 -3.16971898079,1.61221039295,4.07550954819 -3.16074037552,1.61422204971,4.08909654617 -3.14376378059,1.61223530769,4.09267997742 -3.13678574562,1.61524713039,4.11024522781 -3.12479805946,1.61225426197,4.10704374313 -3.11382102966,1.61326694489,4.1196064949 -3.1098408699,1.61727714539,4.13920497894 -3.09886407852,1.61928975582,4.1517701149 -3.08388733864,1.61730289459,4.15834569931 -3.07490849495,1.61931431293,4.17193746567 -3.05092477798,1.61032450199,4.15371370316 -3.04694437981,1.61433470249,4.17331695557 -3.0409655571,1.61834609509,4.19189500809 -3.02898836136,1.61935853958,4.20247173309 -3.015011549,1.61837136745,4.2100520134 -2.99703598022,1.61538517475,4.21262407303 -2.98905754089,1.61839675903,4.22820949554 -2.98606753349,1.6204020977,4.23700857162 -2.97209239006,1.62041568756,4.24655914307 -2.95811486244,1.61942815781,4.2531542778 -2.94713783264,1.62144052982,4.26572370529 -2.9351606369,1.6214530468,4.27630233765 -2.91618466377,1.61746668816,4.2758936882 -2.9181933403,1.62247097492,4.29169940948 -2.90421795845,1.62248456478,4.3012509346 -2.89124059677,1.62249708176,4.30983781815 -2.87926292419,1.62350916862,4.31943225861 -2.86728572845,1.62452161312,4.33001279831 -2.85530924797,1.62553453445,4.34157896042 -2.84633111954,1.62854623795,4.35616827011 -2.83834338188,1.62755298615,4.3589515686 -2.82636642456,1.62856543064,4.36953306198 -2.81538844109,1.6295773983,4.38112354279 -2.79341435432,1.62459206581,4.37669897079 -2.78343725204,1.62660443783,4.39126873016 -2.77545881271,1.63061594963,4.40785551071 -2.75448417664,1.62563025951,4.40443563461 -2.7574930191,1.63163435459,4.42323827744 -2.74251699448,1.63064777851,4.4298119545 -2.73054027557,1.63166046143,4.44138288498 -2.7205619812,1.63367211819,4.45398521423 -2.70058751106,1.63068640232,4.45255661011 -2.69860839844,1.63769698143,4.48013448715 -2.6786339283,1.63371145725,4.47870492935 -2.68064284325,1.63971567154,4.49650907516 -2.66366767883,1.63772952557,4.50007915497 -2.6476919651,1.63674294949,4.50465726852 -2.64471244812,1.64375340939,4.5302491188 -2.62773728371,1.64176726341,4.53381872177 -2.61176156998,1.64078056812,4.53839683533 -2.59877514839,1.63678836823,4.53218364716 -2.58279824257,1.63480114937,4.53478622437 -2.56482362747,1.63181507587,4.53635549545 -2.55984520912,1.63882637024,4.55993652344 -2.5678627491,1.65383446217,4.60553503036 -2.55688667297,1.65584719181,4.62010192871 -2.53391194344,1.64986145496,4.61069869995 -2.53592157364,1.65586638451,4.631483078 -2.52794384956,1.66087794304,4.65007066727 -2.51996612549,1.66488993168,4.66964769363 -2.50998902321,1.66890192032,4.68523025513 -2.50201153755,1.67291367054,4.70481109619 -2.48603630066,1.67192733288,4.71038198471 -2.47405982018,1.67394006252,4.7229590416 -2.46307182312,1.67094671726,4.71777153015 -2.46809124947,1.68595612049,4.76334476471 -2.46111249924,1.69096720219,4.78394556046 -2.45413470268,1.69697880745,4.80652618408 -2.45215582848,1.70698940754,4.83910703659 -2.44517755508,1.71200096607,4.86169338226 -2.43419075012,1.71000826359,4.85848331451 -2.42121505737,1.71202135086,4.87105035782 -2.40523982048,1.71103489399,4.87662887573 -2.3942630291,1.71404719353,4.8922085762 -2.38328552246,1.71705901623,4.90581178665 -2.36930990219,1.7180724144,4.91638183594 -2.36033320427,1.72308456898,4.93695688248 -2.36434173584,1.73208856583,4.96375846863 -2.35336494446,1.73610079288,4.97934675217 -2.34438753128,1.74111282825,4.99992847443 -2.33341026306,1.74412500858,5.01551961899 -2.31743597984,1.74413883686,5.0230846405 -2.30645918846,1.74815106392,5.03966760635 -2.2924823761,1.7481637001,5.04826784134 -2.28049707413,1.74617183208,5.04503202438 -2.26252245903,1.74418568611,5.04661226273 -2.25054550171,1.74719786644,5.06020689011 -2.23257088661,1.74521172047,5.06178665161 -2.21259689331,1.74122607708,5.05936098099 -2.19962048531,1.74323868752,5.0709528923 -2.18563461304,1.73824667931,5.06073713303 -2.16266179085,1.73226165771,5.05130815506 -2.14968633652,1.73527467251,5.06488037109 -2.13271093369,1.73428809643,5.06746864319 -2.11373734474,1.73130249977,5.06703996658 -2.10375952721,1.7363140583,5.08464431763 -2.08978366852,1.73732709885,5.095225811 -2.07679748535,1.73233473301,5.08601474762 -2.05782341957,1.73034882545,5.08459329605 -2.04784679413,1.73536109924,5.10517311096 -2.0248734951,1.72937572002,5.09275960922 -2.01589655876,1.73538792133,5.11633777618 -1.99992191792,1.73540151119,5.12291097641 -1.98194754124,1.73341536522,5.12349224091 -1.97096014023,1.73042237759,5.11729383469 -1.95798492432,1.73343539238,5.13186502457 -1.93801116943,1.72944962978,5.12744235992 -1.92503547668,1.73246252537,5.14102315903 -1.9080606699,1.7314760685,5.14360761642 -1.88908696175,1.72949016094,5.14217948914 -1.87711012363,1.73250246048,5.15677690506 -1.87112188339,1.73450863361,5.16457223892 -1.84914970398,1.72952377796,5.15613222122 -1.83417379856,1.72953653336,5.16272830963 -1.8181989193,1.72955000401,5.16830968857 -1.80222439766,1.73056364059,5.17488288879 -1.78125119209,1.72557806969,5.16646099091 -1.77626276016,1.72858405113,5.17725658417 -1.7602878809,1.72859752178,5.1828379631 -1.74031364918,1.72361147404,5.1754283905 -1.72733771801,1.72762405872,5.18901634216 -1.70936429501,1.72563827038,5.19058179855 -1.69338941574,1.72565162182,5.19616270065 -1.67941343784,1.72766423225,5.20576047897 -1.66442859173,1.72067272663,5.18853759766 -1.65045285225,1.72268545628,5.1991276741 -1.63347923756,1.72269940376,5.20369243622 -1.61550521851,1.720713377,5.2032699585 -1.6015291214,1.72272586823,5.21286821365 -1.58455479145,1.72173964977,5.21544742584 -1.57356786728,1.71874666214,5.20724582672 -1.56359195709,1.72575902939,5.23381900787 -1.54861724377,1.72777235508,5.2433962822 -1.52264463902,1.71578729153,5.21299171448 -1.50567114353,1.71580135822,5.21755456924 -1.49469506741,1.72181379795,5.24013805389 -1.47172152996,1.71282804012,5.21873474121 -1.45873594284,1.7078359127,5.20451927185 -1.45075905323,1.71784758568,5.2381029129 -1.43378460407,1.71686124802,5.23968601227 -1.41581070423,1.71487498283,5.2382645607 -1.39983642101,1.71588850021,5.24483919144 -1.38286161423,1.71490168571,5.24443387985 -1.36688756943,1.71591544151,5.25200223923 -1.35790061951,1.71492218971,5.25079393387 -1.337926507,1.70893609524,5.23838949203 -1.3199532032,1.7079501152,5.23795795441 -1.30597817898,1.71096313,5.25153779984 -1.2900031805,1.71097624302,5.25513029099 -1.27602827549,1.71498918533,5.26970720291 -1.25905418396,1.71400284767,5.27128791809 -1.24806785583,1.71001005173,5.26207542419 -1.23209273815,1.71002316475,5.26566839218 -1.21511900425,1.71003687382,5.26824235916 -1.19614541531,1.7060508728,5.26082277298 -1.18516898155,1.71406292915,5.28641653061 -1.16519594193,1.70907711983,5.27499341965 -1.15520894527,1.70608401299,5.26778936386 -1.14323329926,1.71309649944,5.29137325287 -1.12326014042,1.70811069012,5.27895259857 -1.10528659821,1.70612454414,5.27652740479 -1.08831214905,1.70413792133,5.27611541748 -1.07333755493,1.70715093613,5.2866973877 -1.05736279488,1.70816409588,5.29128456116 -1.05037462711,1.70917022228,5.29609107971 -1.0373994112,1.71518290043,5.31767129898 -1.02042603493,1.71619677544,5.32223749161 -0.998452723026,1.70521080494,5.29383325577 -0.981479525566,1.70622479916,5.29839754105 -0.96550399065,1.70523738861,5.29900360107 -0.954518795013,1.70224523544,5.29077100754 -0.940543532372,1.70625793934,5.30635976791 -0.920570611954,1.70027208328,5.29093647003 -0.909593701363,1.71028387547,5.32054185867 -0.89061999321,1.70429754257,5.30812835693 -0.872646927834,1.70231151581,5.30569696426 -0.856671988964,1.70332443714,5.30929040909 -0.849684476852,1.70633089542,5.31808376312 -0.829712092876,1.70034527779,5.30364894867 -0.813737332821,1.70135819912,5.30724191666 -0.797763049603,1.70237135887,5.31382417679 -0.781788170338,1.70238435268,5.31741714478 -0.763814687729,1.7003980875,5.31199407578 -0.746840715408,1.69941151142,5.31157684326 -0.737854123116,1.69841837883,5.3093624115 -0.719879806042,1.69343173504,5.29795694351 -0.703906536102,1.69744539261,5.31052017212 -0.688931763172,1.70145833492,5.32410621643 -0.670958220959,1.6984719038,5.31668567657 -0.654983103275,1.69848465919,5.31828546524 -0.638009190559,1.69749796391,5.31786680222 -0.62902289629,1.69750499725,5.31664800644 -0.61404722929,1.69951760769,5.32525253296 -0.598072886467,1.70153069496,5.33283662796 -0.580099999905,1.69954454899,5.32840442657 -0.563125610352,1.69755756855,5.32399606705 -0.54615175724,1.69757091999,5.32357645035 -0.539164602757,1.70257747173,5.33936405182 -0.521190881729,1.69759094715,5.32794713974 -0.504216372967,1.69560396671,5.32154178619 -0.487242937088,1.69561755657,5.32411432266 -0.471268385649,1.69763040543,5.33070325851 -0.45329529047,1.69464433193,5.32227563858 -0.438320457935,1.70065689087,5.34086608887 -0.429333209991,1.69666349888,5.32966566086 -0.413358986378,1.69967663288,5.34024906158 -0.39638492465,1.69868981838,5.33683538437 -0.379411160946,1.69770300388,5.33641529083 -0.362437516451,1.69771647453,5.33699321747 -0.345463097095,1.69472956657,5.32858562469 -0.338475137949,1.69973564148,5.34338855743 -0.32050204277,1.69574916363,5.33096170425 -0.303527981043,1.69376242161,5.32554769516 -0.287553519011,1.69677531719,5.33613634109 -0.270580083132,1.69778871536,5.33971071243 -0.253605544567,1.69280159473,5.32530641556 -0.2366322577,1.69481515884,5.33087778091 -0.22864459455,1.693821311,5.32968091965 -0.211671099067,1.69483470917,5.33225679398 -0.194697350264,1.69384789467,5.3298368454 -0.177723512053,1.69186115265,5.32441997528 -0.161748528481,1.69387376308,5.32901859283 -0.144774705172,1.69188690186,5.32260084152 -0.1278013587,1.69390034676,5.33017444611 -0.119813926518,1.6959066391,5.33597278595 -0.102840162814,1.69391977787,5.33055400848 -0.0868649408221,1.69393229485,5.32815790176 -0.0698914304376,1.69594550133,5.33373403549 -0.0529176555574,1.69195878506,5.3223156929 -0.0359441190958,1.69397199154,5.3278927803 -0.0199689548463,1.69398450851,5.32749605179 -0.0109828989953,1.69099140167,5.31727313995 --0.00499208597466,1.70300388336,5.19787311554 --0.0209667924792,1.70501661301,5.20346689224 --0.0379398912191,1.70503008366,5.20103549957 --0.0459270663559,1.699036479,5.18582868576 --0.0619019791484,1.70604896545,5.20342683792 --0.0778765752912,1.70406162739,5.19701862335 --0.0948496237397,1.70307505131,5.19458627701 --0.110824003816,1.6990878582,5.1831741333 --0.127797573805,1.70510101318,5.19875144958 --0.134786143899,1.70110666752,5.1875667572 --0.151759326458,1.70311999321,5.19013690948 --0.167734146118,1.70413255692,5.19273328781 --0.183707967401,1.69714558125,5.17331027985 --0.200681731105,1.70315861702,5.18689155579 --0.216656669974,1.70517110825,5.19149065018 --0.232630580664,1.70018398762,5.177069664 --0.240618288517,1.70219004154,5.18287324905 --0.257591575384,1.70320320129,5.18544578552 --0.273565411568,1.6992162466,5.17202281952 --0.290539324284,1.70322918892,5.18260669708 --0.306514441967,1.70524156094,5.18720912933 --0.322488307953,1.70225441456,5.17578697205 --0.338462591171,1.70126700401,5.17037343979 --0.347448974848,1.70327377319,5.1771569252 --0.363423645496,1.70328629017,5.17575025558 --0.377399384975,1.69529831409,5.15235376358 --0.396371424198,1.70331203938,5.17291212082 --0.411346822977,1.70132410526,5.16351413727 --0.428320407867,1.70333707333,5.16709280014 --0.436307609081,1.7023434639,5.16488647461 --0.453281253576,1.70435643196,5.16846513748 --0.468256115913,1.70036876202,5.15505695343 --0.48522990942,1.70238161087,5.15963888168 --0.50020468235,1.69839394093,5.14622831345 --0.517179310322,1.70340645313,5.15682601929 --0.532153964043,1.69941878319,5.14341402054 --0.541140973568,1.70242524147,5.1522102356 --0.557114899158,1.70043802261,5.14478778839 --0.576087892056,1.70845127106,5.16436433792 --0.588063895702,1.69646286964,5.12896251678 --0.607037305832,1.7054759264,5.15054798126 --0.623011946678,1.70548832417,5.14813995361 --0.639985918999,1.70750105381,5.15172529221 --0.647972881794,1.70650732517,5.14851474762 --0.664946675301,1.70752024651,5.15009450912 --0.680920958519,1.70753276348,5.14568090439 --0.69789493084,1.70954537392,5.14826488495 --0.712870061398,1.7075574398,5.13986206055 --0.727844655514,1.70356976986,5.12844753265 --0.743818759918,1.70358228683,5.12302875519 --0.751806080341,1.70358848572,5.12182426453 --0.768780052662,1.70560121536,5.12441015244 --0.785753548145,1.70561408997,5.12398481369 --0.800728559494,1.70362603664,5.11557912827 --0.816703081131,1.70363843441,5.11216688156 --0.837675273418,1.71365201473,5.13573980331 --0.846662580967,1.71565818787,5.14154052734 --0.862637221813,1.71567046642,5.13813114166 --0.87461322546,1.70768201351,5.11272859573 --0.892586410046,1.7106949091,5.11730194092 --0.927534341812,1.7157201767,5.12547445297 --0.943508923054,1.71573233604,5.12206506729 --0.953495800495,1.71973872185,5.13186359406 --0.968470215797,1.71775102615,5.12044286728 --0.987443864346,1.72276377678,5.1320309639 --1.0034185648,1.72277593613,5.12862348557 --1.01639318466,1.71578800678,5.10619735718 --1.03736674786,1.72480082512,5.12879419327 --1.05533969402,1.72681379318,5.13036346436 --1.062327981,1.72681939602,5.12617206573 --1.07930231094,1.72783172131,5.12676143646 --1.0932765007,1.72384417057,5.10933160782 --1.11125063896,1.72685647011,5.11492347717 --1.12722539902,1.72686851025,5.11151695251 --1.14519941807,1.72988092899,5.11610555649 --1.15518534184,1.73188769817,5.11988449097 --1.17116057873,1.73289954662,5.11748456955 --1.18813431263,1.73291218281,5.11506128311 --1.20410943031,1.73392403126,5.11266279221 --1.21808433533,1.72993588448,5.09824371338 --1.23805761337,1.73594868183,5.10982894897 --1.25603199005,1.73896098137,5.11442470551 --1.2630187273,1.73696708679,5.1052031517 --1.27999377251,1.73897910118,5.10680532455 --1.30096662045,1.74499201775,5.12038612366 --1.31294286251,1.74000322819,5.10098218918 --1.33291578293,1.74501621723,5.10955905914 --1.34988939762,1.745028615,5.10613393784 --1.36186599731,1.74103963375,5.08873987198 --1.37185239792,1.74304616451,5.09252595901 --1.39282536507,1.74905908108,5.10510921478 --1.40580117702,1.74507033825,5.0897026062 --1.42577409744,1.75008320808,5.09728002548 --1.44174981117,1.75109469891,5.09488725662 --1.45472514629,1.74710631371,5.07847118378 --1.46271193027,1.74611258507,5.07425498962 --1.48368561268,1.75312495232,5.0878534317 --1.49366223812,1.74513578415,5.06244421005 --1.51663434505,1.7531491518,5.07902002335 --1.53760814667,1.76016151905,5.09161806107 --1.5465849638,1.75117230415,5.06320762634 --1.56655776501,1.75518500805,5.06878042221 --1.57454574108,1.75619077682,5.06758594513 --1.59251976013,1.75820291042,5.068171978 --1.60949349403,1.75921523571,5.06374549866 --1.62846744061,1.76222765446,5.06733179092 --1.6434429884,1.76123893261,5.05993032455 --1.66141724586,1.763250947,5.06051969528 --1.67739248276,1.76426255703,5.05611801147 --1.68937754631,1.76726961136,5.06188631058 --1.70335376263,1.76628065109,5.05249261856 --1.72032809258,1.76729261875,5.04907655716 --1.73330414295,1.76430368423,5.03567409515 --1.75527703762,1.77031648159,5.04625463486 --1.77025270462,1.76932775974,5.03885412216 --1.78223824501,1.77333438396,5.04563522339 --1.79721319675,1.77234613895,5.03621816635 --1.81118881702,1.77035748959,5.02480840683 --1.82916307449,1.77236938477,5.02439641953 --1.84713792801,1.77438104153,5.02499437332 --1.85911405087,1.77039206028,5.00858640671 --1.87708818913,1.77240407467,5.00716781616 --1.8880751133,1.77641010284,5.01296901703 --1.90804898739,1.7804223299,5.01755857468 --1.92202413082,1.77843368053,5.00513887405 --1.93599963188,1.77644491196,4.99372625351 --1.9549741745,1.77945673466,4.99632406235 --1.97494792938,1.78346884251,4.9999089241 --1.9899225235,1.7824805975,4.98948335648 --1.99591052532,1.78048598766,4.98127746582 --2.01488471031,1.78349781036,4.98286914825 --2.02586197853,1.77950835228,4.96546888351 --2.04783511162,1.78452074528,4.97305011749 --2.06780910492,1.78853261471,4.97664117813 --2.07978534698,1.78554344177,4.96123600006 --2.08877205849,1.78654956818,4.95901727676 --2.10874629021,1.79056143761,4.96261072159 --2.12772011757,1.792573452,4.96219062805 --2.14069676399,1.79058408737,4.94979000092 --2.15767097473,1.79159581661,4.94436788559 --2.17264676094,1.79060697556,4.93596076965 --2.19262075424,1.79461872578,4.93855047226 --2.19760990143,1.79262363911,4.93036317825 --2.2135848999,1.7926350832,4.92294406891 --2.23555803299,1.79864740372,4.92852210999 --2.24753475189,1.79565787315,4.91412162781 --2.26450920105,1.79666936398,4.90870189667 --2.28248405457,1.79868102074,4.90629005432 --2.29746031761,1.79869174957,4.89889431 --2.30444836617,1.79769706726,4.89369249344 --2.32242202759,1.79870903492,4.8892621994 --2.34539580345,1.80572092533,4.89785766602 --2.3573718071,1.8027317524,4.88143539429 --2.37534761429,1.80474257469,4.88104867935 --2.39632081985,1.80875480175,4.88261938095 --2.40030932426,1.80575990677,4.870408535 --2.41828417778,1.8077712059,4.86800289154 --2.4362590313,1.80978262424,4.86458826065 --2.45223474503,1.81079351902,4.85818433762 --2.47020936012,1.81280481815,4.85477018356 --2.48318600655,1.81081533432,4.84236621857 --2.50615954399,1.81582725048,4.84895610809 --2.51214814186,1.81483244896,4.84175395966 --2.52712416649,1.81484305859,4.83335113525 --2.54309892654,1.81485426426,4.82492780685 --2.55807518959,1.8148649931,4.81652498245 --2.58004951477,1.81987655163,4.82112073898 --2.59502458572,1.81988763809,4.81069660187 --2.61100077629,1.81989824772,4.80429649353 --2.61798834801,1.81990373135,4.79808330536 --2.63596320152,1.82191514969,4.79366540909 --2.65593767166,1.82492637634,4.79325151443 --2.66991400719,1.82393693924,4.78284883499 --2.68688964844,1.82594776154,4.77744150162 --2.70886349678,1.82995939255,4.78002500534 --2.71385288239,1.82896399498,4.77284193039 --2.72382950783,1.82497429848,4.75341653824 --2.74580359459,1.82998585701,4.75600194931 --2.76477861404,1.83199703693,4.75359201431 --2.77175712585,1.82700645924,4.73119068146 --2.79872965813,1.83501851559,4.74177312851 --2.81270623207,1.83402884007,4.73137187958 --2.81969451904,1.83403396606,4.72617101669 --2.83566951752,1.83404505253,4.71674108505 --2.85364603996,1.83705532551,4.71435546875 --2.87162137032,1.8390661478,4.70994663239 --2.89459490776,1.84407782555,4.71252393723 --2.89957404137,1.8380869627,4.68711996078 --2.91455006599,1.83809733391,4.67771100998 --2.9295361042,1.84210371971,4.68449926376 --2.94551181793,1.84311425686,4.6760840416 --2.96248745918,1.84412491322,4.66967391968 --2.9744644165,1.84213495255,4.65526342392 --2.99244070053,1.84514534473,4.65187168121 --3.01541471481,1.85015666485,4.65445899963 --3.02340221405,1.85016214848,4.64924001694 --3.03337979317,1.84717178345,4.63182973862 --3.05635428429,1.85218298435,4.6344203949 --3.06733226776,1.85019242764,4.62002897263 --3.09230613708,1.857203722,4.62562227249 --3.09628486633,1.85021305084,4.59819841385 --3.12425780296,1.85822463036,4.60778808594 --3.12824749947,1.85622906685,4.59859514236 --3.13522624969,1.85223841667,4.57718849182 --3.16719794273,1.86225056648,4.59177207947 --3.17617630959,1.85925996304,4.57336521149 --3.19515156746,1.86127054691,4.56895160675 --3.22112512589,1.8682820797,4.57453870773 --3.22110557556,1.8592903614,4.54312944412 --3.23309278488,1.86229586601,4.54492950439 --3.25906658173,1.86930704117,4.55052042007 --3.27004384995,1.86731684208,4.53410100937 --3.2740240097,1.86132538319,4.50970411301 --3.30699586868,1.87233746052,4.52429008484 --3.30997490883,1.86534643173,4.49686956406 --3.33095049858,1.86935687065,4.4954662323 --3.34193849564,1.87136185169,4.49627637863 --3.35291647911,1.86937129498,4.48086881638 --3.36989212036,1.87138164043,4.47244596481 --3.39586615562,1.87739276886,4.47703742981 --3.39284729958,1.86740076542,4.44262313843 --3.41682219505,1.87341141701,4.44522619247 --3.4348077774,1.87941753864,4.45300960541 --3.43878722191,1.87342619896,4.42860269547 --3.44276762009,1.86843454838,4.40520811081 --3.47573971748,1.87944626808,4.41779327393 --3.48771739006,1.87745583057,4.40337991714 --3.50569343567,1.87946581841,4.39697217941 --3.52167081833,1.88147544861,4.38857221603 --3.52266097069,1.87747955322,4.3753695488 --3.53763794899,1.87848937511,4.36495923996 --3.56061220169,1.88350009918,4.36353588104 --3.56659245491,1.87950837612,4.34314203262 --3.58556842804,1.88151836395,4.33773374557 --3.60654377937,1.88552880287,4.33432006836 --3.61552286148,1.88353765011,4.31691551208 --3.61851286888,1.88154172897,4.30671691895 --3.6424870491,1.88655245304,4.30629730225 --3.65046548843,1.88356149197,4.28687953949 --3.66644310951,1.88457083702,4.27848339081 --3.6844201088,1.88758039474,4.27208280563 --3.70139622688,1.88859045506,4.26265621185 --3.71137452126,1.88659930229,4.24624681473 --3.73635983467,1.89660561085,4.26205539703 --3.72734260559,1.88461267948,4.22364330292 --3.75031805038,1.8896228075,4.22223472595 --3.77129364014,1.893633008,4.21781682968 --3.78227257729,1.89164173603,4.20341968536 --3.80324816704,1.89565169811,4.19900465012 --3.81323671341,1.89765644073,4.19680547714 --3.8112180233,1.88966405392,4.16739940643 --3.83519387245,1.89567410946,4.16699647903 --3.85117077827,1.89668369293,4.15657615662 --3.8601500988,1.89469206333,4.14018154144 --3.87812662125,1.89670181274,4.13175916672 --3.8921046257,1.89771068096,4.12035799026 --3.9050924778,1.90071570873,4.12115859985 --3.91207194328,1.89772415161,4.10174942017 --3.92804908752,1.89873349667,4.09133148193 --3.95402407646,1.90474355221,4.09192228317 --3.96400356293,1.90375208855,4.07652568817 --3.96798372269,1.89976012707,4.05411577225 --3.98795986176,1.902769804,4.0476975441 --4.00794649124,1.90877521038,4.05550146103 --4.01692533493,1.9067838192,4.03808927536 --4.03490304947,1.90979278088,4.03069019318 --4.0478811264,1.90980160236,4.01727724075 --4.0638589859,1.910810709,4.00686454773 --4.07583761215,1.91081917286,3.99346780777 --4.08481693268,1.90882766247,3.97605395317 --4.08880662918,1.90783178806,3.9668469429 --4.10578393936,1.90984094143,3.95743465424 --4.1287612915,1.91484999657,3.95504283905 --4.13674068451,1.91285836697,3.93662810326 --4.15571784973,1.91586756706,3.92921996117 --4.16569662094,1.91487598419,3.91280627251 --4.18067502975,1.91588449478,3.90241241455 --4.19666242599,1.92088961601,3.9041993618 --4.20264291763,1.91689753532,3.88479781151 --4.2086224556,1.91390573978,3.86437892914 --4.23059940338,1.91891479492,3.85997819901 --4.24257850647,1.91892325878,3.84556627274 --4.25655698776,1.91893172264,3.83315706253 --4.27154397964,1.92293667793,3.83394789696 --4.30051994324,1.93094611168,3.8355474472 --4.32349729538,1.93695497513,3.83215618134 --4.33047676086,1.93396306038,3.81273889542 --4.35545349121,1.93997216225,3.81033778191 --4.36243343353,1.9369802475,3.79092001915 --4.39140892029,1.94498968124,3.79151368141 --4.38740062714,1.9409930706,3.77530550957 --4.40837812424,1.94500184059,3.76890134811 --4.42335700989,1.94600999355,3.75750136375 --4.43833589554,1.94701850414,3.74508547783 --4.42532062531,1.93602478504,3.70968341827 --4.43230104446,1.93303239346,3.69127845764 --4.42528438568,1.92503929138,3.66086864471 --4.42927455902,1.92404294014,3.65267491341 --4.44325304031,1.92505145073,3.63925266266 --4.44123601913,1.91905844212,3.61385154724 --4.4382185936,1.91206550598,3.58744502068 --4.45119762421,1.91307353973,3.57403469086 --4.4531788826,1.90808093548,3.55162382126 --4.45316076279,1.90308833122,3.52720355988 --4.45715141296,1.90209209919,3.51900672913 --4.45113420486,1.89409887791,3.49059796333 --4.45611524582,1.89210641384,3.47119069099 --4.45809745789,1.88811349869,3.44978880882 --4.46507835388,1.88612103462,3.43238711357 --4.46106100082,1.87912809849,3.40597653389 --4.47204113007,1.87913584709,3.39157056808 --4.4570350647,1.87013852596,3.36836361885 --4.45701646805,1.8651458025,3.34494519234 --4.47599458694,1.86815416813,3.3365354538 --4.47897624969,1.86516141891,3.31612801552 --4.48395776749,1.86216855049,3.29772853851 --4.48993873596,1.86017620564,3.27931427956 --4.498919487,1.86018359661,3.26391363144 --4.51190757751,1.86318802834,3.26169896126 --4.51988792419,1.86219549179,3.24529409409 --4.52986907959,1.86220288277,3.23089838028 --4.53884887695,1.86121070385,3.21447896957 --4.56182670593,1.86621880531,3.20907735825 --4.56280946732,1.86222577095,3.1876718998 --4.57079935074,1.8642295599,3.18247151375 --4.5827794075,1.86423707008,3.16906881332 --4.58376169205,1.86024415493,3.14766097069 --4.59574127197,1.86125195026,3.13323879242 --4.60472202301,1.8602591753,3.11783766747 --4.61170291901,1.85926651955,3.10042405128 --4.62468338013,1.86027395725,3.08802723885 --4.62967348099,1.86027777195,3.07981038094 --4.64265394211,1.86228513718,3.06741428375 --4.65563440323,1.86329245567,3.05501866341 --4.66261529922,1.86229968071,3.03760457039 --4.67259550095,1.86230707169,3.02219033241 --4.67457818985,1.85931396484,3.00178074837 --4.68755817413,1.86032152176,2.98836660385 --4.69854736328,1.8623251915,2.98517084122 --4.70053005219,1.85933208466,2.96475982666 --4.7085108757,1.85933923721,2.94835019112 --4.70749378204,1.85434615612,2.92593502998 --4.71647548676,1.85435283184,2.91155099869 --4.73645401001,1.85836064816,2.90212988853 --4.73743677139,1.85536730289,2.88172674179 --4.74542617798,1.85637128353,2.87551188469 --4.75440883636,1.85637795925,2.86112833023 --4.76438903809,1.85638511181,2.84571290016 --4.76737165451,1.85339188576,2.82630300522 --4.77835226059,1.85439884663,2.81189489365 --4.79333257675,1.85740625858,2.79947948456 --4.80131387711,1.8564132452,2.7830684185 --4.80930423737,1.85741662979,2.77787542343 --4.82428407669,1.86042380333,2.76546192169 --4.82726669312,1.85743057728,2.74604964256 --4.83824825287,1.85843753815,2.73164367676 --4.84523010254,1.85744416714,2.71524405479 --4.85521173477,1.85845077038,2.70084953308 --4.85720205307,1.85745441914,2.69062638283 --4.87218379974,1.85946106911,2.67923593521 --4.88116455078,1.85946810246,2.66281366348 --4.88114786148,1.85647451878,2.64241123199 --4.8951292038,1.85848128796,2.63001298904 --4.90411043167,1.8584882021,2.6135904789 --4.91409254074,1.85949456692,2.59919714928 --4.9170832634,1.85849809647,2.58998227119 --4.9140663147,1.85350453854,2.56756877899 --4.93504714966,1.85951113701,2.55917739868 --4.9370303154,1.85651767254,2.53976964951 --4.9540104866,1.85952436924,2.52836298943 --4.97099065781,1.86253142357,2.51593756676 --4.9669752121,1.85853731632,2.49455094337 --4.98496389389,1.86354100704,2.49334096909 --4.99794578552,1.86554741859,2.47993922234 --4.99592971802,1.86155378819,2.45853018761 --5.00791072845,1.86256027222,2.44411873817 --5.02589130402,1.86656701565,2.4327082634 --5.03587341309,1.86757338047,2.41729831696 --5.05485486984,1.872579813,2.4069006443 --5.04884719849,1.86858284473,2.39369392395 --5.06582832336,1.87158918381,2.38229703903 --5.08180999756,1.87459564209,2.36989140511 --5.06979465485,1.86660170555,2.34347343445 --5.0887761116,1.87160789967,2.33308005333 --5.10075759888,1.8726143837,2.31765270233 --5.10673999786,1.87262058258,2.30024242401 --5.11473178864,1.87462353706,2.29506182671 --5.13671207428,1.8796299696,2.28464460373 --5.11969852448,1.8706356287,2.2572453022 --5.13068056107,1.87164199352,2.24182891846 --5.158659935,1.87964832783,2.23442077637 --5.15064525604,1.87365412712,2.21101593971 --5.16162729263,1.87466037273,2.19560098648 --5.17461776733,1.87866342068,2.19139814377 --5.18160104752,1.87866926193,2.17500019073 --5.1935839653,1.88067519665,2.16059875488 --5.20856571198,1.88268113136,2.14719247818 --5.21054887772,1.88068723679,2.12777686119 --5.20153427124,1.87469315529,2.10437321663 --5.23951387405,1.88669884205,2.10097670555 --5.21550893784,1.87670183182,2.08076548576 --5.22449111938,1.87670791149,2.06434988976 --5.24647331238,1.88271355629,2.0539495945 --5.24545717239,1.87971949577,2.03353595734 --5.25044059753,1.87872517109,2.01613402367 --5.27642154694,1.88673102856,2.00672531128 --5.26040792465,1.87773692608,1.98030805588 --5.27439832687,1.8817397356,1.97610723972 --5.28938102722,1.88474535942,1.96270823479 --5.2893652916,1.8827508688,1.94330477715 --5.28334999084,1.87775683403,1.92088496685 --5.31633090973,1.8877620697,1.91449272633 --5.29631757736,1.8777680397,1.88707602024 --5.31330776215,1.88277065754,1.88387751579 --5.33229017258,1.8877761364,1.87147271633 --5.31527614594,1.87878215313,1.84504926205 --5.32526016235,1.8807874918,1.82965028286 --5.34624147415,1.88579308987,1.817232728 --5.33622741699,1.87979865074,1.79483652115 --5.33321285248,1.8768042326,1.77442848682 --5.36320209503,1.88680660725,1.77522599697 --5.36018657684,1.88281214237,1.75481843948 --5.35917186737,1.88081765175,1.73541629314 --5.37015533447,1.88282287121,1.72001254559 --5.36714029312,1.87882852554,1.69960212708 --5.39112234116,1.88583362103,1.68819320202 --5.4041056633,1.88883888721,1.67277777195 --5.40109825134,1.88684165478,1.66258263588 --5.41608190536,1.88984680176,1.64817607403 --5.42706489563,1.89185202122,1.63175487518 --5.42705059052,1.88985729218,1.61336565018 --5.44703292847,1.8948622942,1.59995019436 --5.44901847839,1.89386749268,1.5815474987 --5.46200227737,1.89687252045,1.56613731384 --5.45499563217,1.89287519455,1.55494475365 --5.45898008347,1.89288055897,1.5365281105 --5.45696496964,1.88988602161,1.51610612869 --5.45994997025,1.88889098167,1.49871683121 --5.47593402863,1.89289581776,1.48431146145 --5.48891782761,1.89590060711,1.46890437603 --5.48490333557,1.89290606976,1.44849300385 --5.48689556122,1.89290857315,1.43928432465 --5.48688030243,1.89091384411,1.4198693037 --5.48086643219,1.88691914082,1.39946687222 --5.50584936142,1.89392352104,1.38705682755 --5.52183389664,1.89792811871,1.37265789509 --5.52481889725,1.89693307877,1.35424721241 --5.52681112289,1.89693558216,1.34503889084 --5.54079580307,1.90094006062,1.32963180542 --5.55278015137,1.90294468403,1.3142374754 --5.54276704788,1.89795005322,1.29283237457 --5.54175233841,1.89595508575,1.2734208107 --5.54973697662,1.89695990086,1.2560043335 --5.55472230911,1.89696455002,1.23860430717 --5.56970691681,1.90096890926,1.2231965065 --5.58069896698,1.90497100353,1.21598601341 --5.5776848793,1.90197598934,1.19658398628 --5.58966970444,1.90498054028,1.18017196655 --5.59165477753,1.90398526192,1.16176640987 --5.60164070129,1.9059895277,1.14536583424 --5.59662628174,1.90299475193,1.12494921684 --5.60061264038,1.90299928188,1.1075553894 --5.61160421371,1.906001091,1.10034966469 --5.61258983612,1.90500617027,1.08092606068 --5.61457586288,1.90401077271,1.06251966953 --5.61656141281,1.90301549435,1.04411303997 --5.63454723358,1.90801906586,1.02972435951 --5.64253234863,1.91002345085,1.01231443882 --5.63352537155,1.90602648258,1.00008797646 --5.63451147079,1.90503108501,0.981685400009 --5.63849782944,1.90503537655,0.964292347431 --5.63648366928,1.90304028988,0.944879233837 --5.64546966553,1.90504443645,0.927465856075 --5.66045475006,1.90904819965,0.911051869392 --5.6614408493,1.90805280209,0.892649173737 --5.65743398666,1.90605521202,0.882442653179 --5.67742013931,1.91205847263,0.868056774139 --5.67940616608,1.9120631218,0.848628222942 --5.6843919754,1.91206717491,0.83123344183 --5.69137907028,1.91407120228,0.81383150816 --5.68136501312,1.90907657146,0.792400300503 --5.69735097885,1.91407978535,0.77701228857 --5.70234394073,1.91508185863,0.767795860767 --5.70733070374,1.91608572006,0.750402152538 --5.70831632614,1.91509032249,0.730977237225 --5.70930337906,1.9140945673,0.71257430315 --5.73228931427,1.92209732533,0.697170197964 --5.72727632523,1.91910207272,0.677763879299 --5.73426294327,1.92010581493,0.660366177559 --5.73325586319,1.92010819912,0.650146842003 --5.74924230576,1.92411124706,0.633746743202 --5.74023008347,1.92011606693,0.614349961281 --5.74121618271,1.92012047768,0.594924807549 --5.75820302963,1.92512333393,0.578524887562 --5.75718975067,1.92412769794,0.559105634689 --5.75717687607,1.92313182354,0.540705740452 --5.76816987991,1.92613315582,0.532501518726 --5.77215671539,1.92713689804,0.514092445374 --5.77014446259,1.92614114285,0.495697170496 --5.77613067627,1.92714476585,0.477283984423 --5.78211784363,1.92814850807,0.458871364594 --5.79510498047,1.9321513176,0.441467106342 --5.80309200287,1.93415474892,0.423052102327 --5.81008577347,1.93615615368,0.414861291647 --5.80807256699,1.93516039848,0.395444184542 --5.81505966187,1.9371638298,0.377032607794 --5.82104682922,1.9381673336,0.35862365365 --5.82803487778,1.9401704073,0.341235607862 --5.82802200317,1.94017446041,0.321815013885 --5.82600927353,1.93817865849,0.30239751935 --5.82800292969,1.93918025494,0.293194979429 --5.83699131012,1.94218313694,0.275805532932 --5.83897829056,1.94218695164,0.256382346153 --5.84396648407,1.94319033623,0.237977594137 --5.84895420074,1.94419360161,0.219573348761 --5.84294176102,1.94219791889,0.200159579515 --5.85692977905,1.94620025158,0.182768389583 --5.86692333221,1.95020115376,0.173559114337 --5.86091089249,1.94720542431,0.154145404696 --5.86389923096,1.9482088089,0.1357447505 --5.87188720703,1.95021164417,0.117340572178 --5.88087463379,1.95321452618,0.0979144275188 --5.88186359406,1.95321798325,0.0795167759061 --5.8988571167,1.95921802521,0.0703076943755 --5.89384555817,1.95722198486,0.0519144572318 --5.89483356476,1.95722544193,0.0324955694377 --5.88782119751,1.9542299509,0.0130800334737 --5.89980983734,1.95823204517,-0.00532106077299 --5.89279747009,1.95523631573,-0.0247374046594 --5.89378595352,1.95523965359,-0.0431343950331 --5.88777971268,1.95324218273,-0.0533539429307 --5.89376831055,1.95524477959,-0.0717518180609 --5.90575742722,1.95924687386,-0.0901490300894 --5.89474582672,1.95525145531,-0.109567731619 --5.89673376083,1.9562548399,-0.128986626863 --5.90072250366,1.95725750923,-0.1473826617 --5.89171028137,1.95426213741,-0.166803717613 --5.8937048912,1.95526337624,-0.17600184679 --5.88369274139,1.9512680769,-0.195424556732 --5.86368083954,1.94427382946,-0.213831022382 --5.87066936493,1.94727623463,-0.233249008656 --5.86865854263,1.94627976418,-0.251648783684 --5.8606467247,1.94428396225,-0.270052969456 --5.87363576889,1.94828557968,-0.289465039968 --5.87363004684,1.9482871294,-0.298664242029 --5.87361860275,1.94829046726,-0.318084776402 --5.87160778046,1.94829380512,-0.336485087872 --5.8745970726,1.94929671288,-0.355902761221 --5.87958621979,1.95129907131,-0.374295860529 --5.86557435989,1.94630396366,-0.392708957195 --5.86756277084,1.94730687141,-0.41212746501 --5.88255834579,1.95230638981,-0.422330617905 --5.8715467453,1.94931101799,-0.440742224455 --5.87353563309,1.95031380653,-0.46015971899 --5.86852502823,1.94831740856,-0.478564471006 --5.86751413345,1.948320508,-0.496964037418 --5.87250328064,1.95032274723,-0.516376316547 --5.86749219894,1.9493265152,-0.534782111645 --5.88048791885,1.95332598686,-0.544981300831 --5.87347698212,1.95132994652,-0.563390254974 --5.86646509171,1.9503339529,-0.58282238245 --5.88845682144,1.95733356476,-0.603222370148 --5.86444425583,1.95034003258,-0.620643019676 --5.84943246841,1.94534504414,-0.638048350811 --5.87142372131,1.9533444643,-0.65844476223 --5.8744187355,1.95434558392,-0.668658614159 --5.87840843201,1.95634770393,-0.688068032265 --5.86939764023,1.95335173607,-0.706483840942 --5.86238718033,1.95135545731,-0.723874211311 --5.87737751007,1.9573558569,-0.745300650597 --5.86936712265,1.95535969734,-0.762693583965 --5.86035585403,1.95336389542,-0.781111955643 --5.8593506813,1.95336532593,-0.79031252861 --5.86934137344,1.95736634731,-0.810725748539 --5.85432958603,1.95237135887,-0.828139185905 --5.85932064056,1.95537304878,-0.847543001175 --5.88031244278,1.96337223053,-0.868944048882 --5.85129928589,1.95337963104,-0.885377883911 --5.86429548264,1.9583786726,-0.89658087492 --5.87128686905,1.96138000488,-0.915975570679 --5.85927581787,1.95838439465,-0.93338406086 --5.84626436234,1.95438909531,-0.95079690218 --5.86425638199,1.96138846874,-0.973220586777 --5.8652472496,1.96339058876,-0.991610348225 --5.84823560715,1.95739591122,-1.00903785229 --5.87323331833,1.96739280224,-1.02223706245 --5.85922241211,1.9633975029,-1.03965508938 --5.85521268845,1.9624004364,-1.05806112289 --5.87620544434,1.97139906883,-1.08046460152 --5.88819789886,1.97639906406,-1.10187590122 --5.8871884346,1.97740137577,-1.12026870251 --5.90318107605,1.98340058327,-1.14268290997 --5.90717744827,1.98540091515,-1.15288293362 --5.91016817093,1.98740255833,-1.17330098152 --5.93516254425,1.99739992619,-1.19669604301 --5.9391541481,2.00040125847,-1.21710705757 --5.9361448288,2.00040364265,-1.23652410507 --5.95513868332,2.00840187073,-1.25891423225 --5.94112825394,2.00440645218,-1.27633321285 --5.94311952591,2.00640797615,-1.29674935341 --5.96611881256,2.01440429688,-1.30992639065 --5.94010639191,2.00641131401,-1.3253557682 --5.94209766388,2.00841259956,-1.34577035904 --5.95909166336,2.01641106606,-1.36815977097 --5.94808149338,2.01341509819,-1.38658845425 --5.94807338715,2.01441669464,-1.40598881245 --5.95006942749,2.01641726494,-1.41619026661 --5.92905759811,2.01042318344,-1.43262553215 --5.91404676437,2.00642776489,-1.44903445244 --5.92503976822,2.01142716408,-1.47144520283 --5.92003154755,2.01042985916,-1.48984825611 --5.91402244568,2.01043248177,-1.50825679302 --5.93001651764,2.01743078232,-1.53165948391 --5.91901016235,2.01443386078,-1.53988277912 --5.91100120544,2.01243686676,-1.55728006363 --5.91199302673,2.01443815231,-1.57769405842 --5.89698266983,2.01044297218,-1.59410786629 --5.89597463608,2.01244449615,-1.6145324707 --5.89596700668,2.01344609261,-1.63392996788 --5.88595724106,2.01144957542,-1.65133976936 --5.884953022,2.01245045662,-1.66155445576 --5.87494373322,2.01045393944,-1.67896533012 --5.86893463135,2.00945687294,-1.69737505913 --5.86592626572,2.01045870781,-1.7167891264 --5.84491443634,2.00446462631,-1.73120236397 --5.85290813446,2.00846409798,-1.75361514091 --5.84589958191,2.008466959,-1.77203190327 --5.83489370346,2.00447010994,-1.77924287319 --5.82788467407,2.00447297096,-1.79766070843 --5.82487678528,2.00447463989,-1.81605386734 --5.8108663559,2.00147914886,-1.83247339725 --5.82786273956,2.00947642326,-1.85788810253 --5.81485271454,2.00648069382,-1.87430143356 --5.79884195328,2.00248551369,-1.88971436024 --5.80584001541,2.0064842701,-1.9019190073 --5.78982973099,2.00248908997,-1.91733312607 --5.78982257843,2.0044901371,-1.93774795532 --5.78281402588,2.00349283218,-1.9551460743 --5.77480459213,2.00249576569,-1.97357177734 --5.75679397583,1.9985011816,-1.98798263073 --5.75378608704,1.99850285053,-2.00739645958 --5.76478528976,2.00450062752,-2.02161097527 --5.75777721405,2.00350308418,-2.03900980949 --5.74876832962,2.0025062561,-2.05642271042 --5.74075889587,2.00150918961,-2.07484984398 --5.72774934769,1.99851322174,-2.09025073051 --5.71974086761,1.99851608276,-2.10867905617 --5.71773386002,1.9995174408,-2.12808442116 --5.71272945404,1.998519063,-2.1362850666 --5.71072244644,2.00052046776,-2.15671086311 --5.70071363449,1.99852359295,-2.17311263084 --5.69370508194,1.99852609634,-2.19153404236 --5.68169546127,1.99652993679,-2.20795226097 --5.66868591309,1.99353408813,-2.2233581543 --5.66767930984,1.99553501606,-2.24377560616 --5.65767431259,1.99353790283,-2.24997544289 --5.65966844559,1.99653792381,-2.27138972282 --5.65366077423,1.99654018879,-2.28980398178 --5.64565229416,1.99554288387,-2.30721354485 --5.63664340973,1.99454581738,-2.32463121414 --5.61763286591,1.99055147171,-2.33804869652 --5.62762975693,1.99654912949,-2.36245679855 --5.60662078857,1.98955535889,-2.36466765404 --5.60661506653,1.9925557375,-2.38507461548 --5.59860706329,1.99155831337,-2.40248584747 --5.58659744263,1.98956215382,-2.41891002655 --5.57959032059,1.98956441879,-2.43631386757 --5.58158493042,1.99356412888,-2.45874238014 --5.56557750702,1.98856890202,-2.46193885803 --5.56157064438,1.98957037926,-2.48135733604 --5.56056499481,1.99157083035,-2.50176978111 --5.54255390167,1.98757636547,-2.51518797874 --5.52554368973,1.98358154297,-2.52859902382 --5.51453447342,1.98258507252,-2.54501914978 --5.51752996445,1.98658430576,-2.56743621826 --5.51552724838,1.98758494854,-2.57663488388 --5.50151729584,1.9845893383,-2.59206199646 --5.49250936508,1.98359203339,-2.60846471786 --5.49750566483,1.9885904789,-2.63188052177 --5.4674911499,1.97959983349,-2.63929533958 --5.45648241043,1.97860324383,-2.65571832657 --5.46548080444,1.98560035229,-2.68113493919 --5.44347047806,1.97760736942,-2.68134021759 --5.43546295166,1.97760975361,-2.69875574112 --5.43945980072,1.98260831833,-2.72217702866 --5.40644359589,1.97261881828,-2.72759175301 --5.40543842316,1.97561883926,-2.74800086021 --5.40043210983,1.97662031651,-2.76742768288 --5.3894238472,1.97562360764,-2.78283309937 --5.37741708755,1.97162747383,-2.78702998161 --5.3794131279,1.97562658787,-2.80944728851 --5.36440372467,1.97363126278,-2.82387399673 --5.3533949852,1.97163462639,-2.83928060532 --5.35339069366,1.97563421726,-2.86069631577 --5.32837772369,1.9686422348,-2.87012672424 --5.32137107849,1.96964430809,-2.88753414154 --5.31636667252,1.96864569187,-2.89574313164 --5.30035638809,1.96565079689,-2.90916442871 --5.28234529495,1.96165657043,-2.92158770561 --5.28534269333,1.96665501595,-2.94399023056 --5.26933240891,1.96366000175,-2.9574136734 --5.25232172012,1.95966553688,-2.96982932091 --5.24031305313,1.95866918564,-2.98525190353 --5.23631000519,1.95867025852,-2.99345183372 --5.23030376434,1.95967185497,-3.01186919212 --5.23029994965,1.96367120743,-3.03328037262 --5.21028804779,1.9586776495,-3.04369258881 --5.18927574158,1.95368456841,-3.0541176796 --5.19227361679,1.9586827755,-3.07753372192 --5.17826414108,1.95668709278,-3.0919611454 --5.16225528717,1.95169270039,-3.09315824509 --5.16525363922,1.95669078827,-3.11657238007 --5.14624214172,1.95269691944,-3.12799954414 --5.13123273849,1.95070171356,-3.14040207863 --5.12822771072,1.95270192623,-3.16082382202 --5.11421871185,1.95070636272,-3.17423534393 --5.10020923615,1.94871068001,-3.18866682053 --5.09420537949,1.94871258736,-3.19587182999 --5.08119630814,1.94671654701,-3.21029281616 --5.06118440628,1.94272315502,-3.21970033646 --5.06418323517,1.94772100449,-3.24412727356 --5.04717254639,1.94472670555,-3.25553917885 --5.03316307068,1.94273102283,-3.26895523071 --5.03316068649,1.94672989845,-3.29137682915 --5.0101480484,1.9387383461,-3.28859472275 --5.00114154816,1.93874084949,-3.30399084091 --4.99513626099,1.94074201584,-3.32240772247 --4.98512887955,1.94074487686,-3.33883476257 --4.96611738205,1.93675124645,-3.34925794601 --4.96311330795,1.9387512207,-3.36865615845 --4.95410776138,1.93775415421,-3.37488126755 --4.93509626389,1.93376064301,-3.38530707359 --4.927090168,1.93476259708,-3.40171051025 --4.91708278656,1.9347653389,-3.41813898087 --4.90407419205,1.93276941776,-3.43154811859 --4.89306688309,1.93277263641,-3.44595193863 --4.87805700302,1.93077743053,-3.45938801765 --4.86705064774,1.92778134346,-3.4625852108 --4.86004495621,1.9287828207,-3.48101377487 --4.85604143143,1.93178296089,-3.5004222393 --4.83802986145,1.92878913879,-3.51084280014 --4.83102464676,1.92979049683,-3.52825188637 --4.82101774216,1.92979311943,-3.54468107224 --4.80400705338,1.9267989397,-3.55610918999 --4.796002388,1.92580151558,-3.56130814552 --4.78999757767,1.9278024435,-3.57972240448 --4.77698898315,1.92680644989,-3.59313631058 --4.76498126984,1.92580997944,-3.60755586624 --4.75397348404,1.92581307888,-3.62298107147 --4.73896408081,1.923817873,-3.63540458679 --4.72695636749,1.92282140255,-3.64982533455 --4.71895170212,1.92182409763,-3.65502619743 --4.70794391632,1.92182719707,-3.67045211792 --4.69593667984,1.92083072662,-3.68385529518 --4.6909327507,1.92383098602,-3.7042901516 --4.67592382431,1.92183589935,-3.71569800377 --4.66491651535,1.92183887959,-3.73112440109 --4.65691137314,1.92284035683,-3.74854469299 --4.64390325546,1.91984546185,-3.74974489212 --4.63689851761,1.92084670067,-3.76715111732 --4.61688613892,1.91685390472,-3.77557826042 --4.60888051987,1.9188555479,-3.79299902916 --4.59287071228,1.91686069965,-3.80442523956 --4.58686685562,1.91886150837,-3.82283473015 --4.57485961914,1.91886484623,-3.83725810051 --4.56785488129,1.91786706448,-3.84346628189 --4.55084466934,1.91487288475,-3.85389065742 --4.54384040833,1.91687381268,-3.87231326103 --4.5328335762,1.91687679291,-3.88672280312 --4.51582288742,1.91488265991,-3.89714932442 --4.50481653214,1.91488564014,-3.91155910492 --4.48980665207,1.91289055347,-3.92399263382 --4.48780584335,1.91489028931,-3.93318128586 --4.47179603577,1.91289567947,-3.94461297989 --4.46579265594,1.91489613056,-3.96301865578 --4.45278453827,1.91489994526,-3.97644114494 --4.42976951599,1.90890908241,-3.98187398911 --4.42376661301,1.91190934181,-4.00027942657 --4.41476154327,1.91291105747,-4.0177116394 --4.39875078201,1.90891802311,-4.0159201622 --4.38174057007,1.9059240818,-4.02533578873 --4.37974023819,1.91092216969,-4.04774808884 --4.3637304306,1.90892755985,-4.05918359756 --4.35172319412,1.90893101692,-4.07259321213 --4.34572029114,1.91093111038,-4.0920124054 --4.32971048355,1.90893661976,-4.10243177414 --4.32470750809,1.90993762016,-4.1106467247 --4.31069898605,1.9089422226,-4.12205314636 --4.29368877411,1.9069480896,-4.13249015808 --4.28468370438,1.90794980526,-4.14890384674 --4.25766563416,1.9009616375,-4.1483130455 --4.24665975571,1.90196418762,-4.16374254227 --4.25066375732,1.90596032143,-4.1799492836 --4.23665571213,1.90596473217,-4.19237518311 --4.2206454277,1.90397036076,-4.20178222656 --4.21464347839,1.90697002411,-4.22221374512 --4.18562316895,1.89898300171,-4.22064733505 --4.1746172905,1.89998579025,-4.23505973816 --4.17361927032,1.90498268604,-4.25947570801 --4.1526055336,1.9009912014,-4.26490068436 --4.13959646225,1.89799690247,-4.26511287689 --4.14360284805,1.9059907198,-4.29452753067 --4.11658382416,1.89800298214,-4.29293727875 --4.11058235168,1.9020024538,-4.31336545944 --4.10057687759,1.9030046463,-4.32877635956 --4.07555961609,1.89701557159,-4.33020687103 --4.06655406952,1.89601898193,-4.33442258835 --4.06055259705,1.89901852608,-4.35484886169 --4.03853797913,1.89402782917,-4.35826587677 --4.02452993393,1.89403235912,-4.36967992783 --4.01952934265,1.89803111553,-4.39110374451 --4.00251817703,1.89603734016,-4.40053653717 --3.98650860786,1.89404320717,-4.40893650055 --3.99151515961,1.9000377655,-4.42815589905 --3.96549630165,1.89304971695,-4.42758274078 --3.9594950676,1.89604926109,-4.44698858261 --3.9494907856,1.89805078506,-4.46442937851 --3.92947721481,1.89405930042,-4.46883678436 --3.91446876526,1.894064188,-4.48026990891 --3.91046977043,1.89806210995,-4.5026845932 --3.89245557785,1.89207148552,-4.49588680267 --3.87844753265,1.89207601547,-4.50730323792 --3.86644124985,1.8920789957,-4.52173137665 --3.84542703629,1.8880879879,-4.52616119385 --3.8334209919,1.88909113407,-4.53957462311 --3.8264195919,1.89209091663,-4.55899238586 --3.80140137672,1.88610255718,-4.55943441391 --3.79639935493,1.88710355759,-4.56663131714 --3.78739643097,1.89010441303,-4.58506822586 --3.77138638496,1.88811016083,-4.59449052811 --3.75137257576,1.88411879539,-4.5978937149 --3.74136853218,1.88612055779,-4.61431694031 --3.72936296463,1.88712358475,-4.62772989273 --3.70634627342,1.88213407993,-4.63017511368 --3.70334625244,1.88413345814,-4.64038038254 --3.6933426857,1.88613510132,-4.65680217743 --3.67733287811,1.88514089584,-4.66622829437 --3.67033219337,1.88814043999,-4.68563938141 --3.64030838013,1.88015627861,-4.67806768417 --3.63330721855,1.88315570354,-4.69747829437 --3.62129855156,1.88016140461,-4.69769859314 --3.60829210281,1.88116502762,-4.71113061905 --3.58727669716,1.87717461586,-4.71354818344 --3.58227872849,1.88217246532,-4.73596429825 --3.55826044083,1.87618422508,-4.73539495468 --3.5482571125,1.87818562984,-4.75181484222 --3.53925490379,1.88118636608,-4.76922988892 --3.51223325729,1.87420046329,-4.76466274261 --3.49922275543,1.87020719051,-4.76287841797 --3.49222278595,1.87420630455,-4.78329896927 --3.48121833801,1.87620866299,-4.79770755768 --3.46220517159,1.87321686745,-4.80313873291 --3.45020008087,1.87421953678,-4.81756591797 --3.43419027328,1.87322568893,-4.82598352432 --3.43119120598,1.87622463703,-4.83719682693 --3.41518115997,1.87423062325,-4.84561443329 --3.40217494965,1.87523436546,-4.85803174973 --3.37715506554,1.86924731731,-4.85546922684 --3.36915421486,1.87224709988,-4.87387466431 --3.35414600372,1.87225198746,-4.88531684875 --3.34514498711,1.87625229359,-4.90373945236 --3.32812929153,1.87026262283,-4.89595842361 --3.3111178875,1.86826968193,-4.90237092972 --3.29811215401,1.86927294731,-4.91580247879 --3.28110051155,1.86728012562,-4.92221641541 --3.26609230042,1.86728513241,-4.9326467514 --3.25108361244,1.8662904501,-4.94206237793 --3.24008011818,1.8682924509,-4.95748090744 --3.22907161713,1.86629784107,-4.95769786835 --3.21206045151,1.86530482769,-4.96512746811 --3.20305967331,1.86830496788,-4.98354578018 --3.18304491043,1.86531448364,-4.98596906662 --3.1620285511,1.86132478714,-4.98740005493 --3.15402913094,1.8653241396,-5.00681018829 --3.13801956177,1.86433005333,-5.01624822617 --3.12801170349,1.86233508587,-5.01644802094 --3.11500644684,1.86433839798,-5.02987909317 --3.10099935532,1.86434268951,-5.04130220413 --3.07798027992,1.85935497284,-5.0397400856 --3.06998109818,1.86335420609,-5.05914640427 --3.0569756031,1.86435747147,-5.07257556915 --3.04396390915,1.86136507988,-5.06878757477 --3.0179400444,1.8543806076,-5.06121444702 --3.00092935562,1.85338759422,-5.0686507225 --2.98391795158,1.85139477253,-5.0750746727 --2.9749174118,1.85539495945,-5.09247398376 --2.95490193367,1.8514046669,-5.09490919113 --2.94990825653,1.85840070248,-5.12032461166 --2.93489360809,1.85341012478,-5.11455869675 --2.91688084602,1.85141825676,-5.11897945404 --2.90387535095,1.8534219265,-5.13139724731 --2.8888669014,1.85342729092,-5.14081907272 --2.87385892868,1.85343229771,-5.15125226974 --2.85183978081,1.84844470024,-5.14867401123 --2.84284043312,1.8524440527,-5.16809225082 --2.83583760262,1.85344612598,-5.17431020737 --2.82683825493,1.85744547844,-5.19372606277 --2.80181479454,1.85046088696,-5.1861538887 --2.79481959343,1.85645771027,-5.21058559418 --2.76779150963,1.84747576714,-5.19799995422 --2.75478720665,1.84947860241,-5.21243906021 --2.73877763748,1.84948503971,-5.21985960007 --2.73978686333,1.855479002,-5.23905944824 --2.71576476097,1.84949350357,-5.23349809647 --2.70876932144,1.85549044609,-5.25691127777 --2.68274378777,1.84750699997,-5.24836063385 --2.67574882507,1.85350394249,-5.27177238464 --2.65272760391,1.84851765633,-5.26720666885 --2.6427283287,1.85251736641,-5.28663444519 --2.63572454453,1.8525198698,-5.29082870483 --2.6137046814,1.84753286839,-5.28725576401 --2.60370564461,1.85153245926,-5.306681633 --2.59070134163,1.85353553295,-5.320104599 --2.57068490982,1.85054624081,-5.32053518295 --2.55467557907,1.85055243969,-5.32896757126 --2.54267263412,1.85355460644,-5.34337902069 --2.53667163849,1.85455524921,-5.35159492493 --2.51364970207,1.8495695591,-5.34602832794 --2.50264930725,1.85257017612,-5.36344909668 --2.48263216019,1.84958136082,-5.36287307739 --2.46461963654,1.84758961201,-5.36831760406 --2.4536190033,1.85159039497,-5.38472652435 --2.43960309029,1.84660065174,-5.37694835663 --2.42259120941,1.84560871124,-5.3813624382 --2.41159129143,1.84960877895,-5.39979028702 --2.39357852936,1.84761738777,-5.4042263031 --2.3755645752,1.84562671185,-5.40664291382 --2.36556696892,1.85062563419,-5.42706632614 --2.34855604172,1.84963285923,-5.43350124359 --2.34255599976,1.85163319111,-5.44272327423 --2.32554483414,1.8516408205,-5.44814920425 --2.30051636696,1.84365904331,-5.43557357788 --2.28951692581,1.84765946865,-5.45298576355 --2.27150392532,1.84566807747,-5.45742464066 --2.25449180603,1.84467613697,-5.46184206009 --2.24048686028,1.84667980671,-5.47427034378 --2.23148036003,1.84568417072,-5.47649049759 --2.2094578743,1.84069871902,-5.46991539001 --2.18843817711,1.83671140671,-5.46735811234 --2.18144822121,1.8447060585,-5.49477148056 --2.15742087364,1.83772373199,-5.48319864273 --2.13740253448,1.83373558521,-5.48163080215 --2.12941122055,1.84173095226,-5.50805282593 --2.11639499664,1.83674144745,-5.49926376343 --2.09938335419,1.83574926853,-5.50469446182 --2.08938765526,1.84174740314,-5.52611255646 --2.0623524189,1.83176982403,-5.50654459 --2.04634356499,1.83177602291,-5.51498126984 --2.03434348106,1.83577716351,-5.53139781952 --2.02033805847,1.83778107166,-5.54281377792 --2.01634454727,1.8417775631,-5.55904531479 --2.00334310532,1.84577953815,-5.57447195053 --1.97730839252,1.8358014822,-5.55489253998 --1.95929408073,1.83381092548,-5.5573220253 --1.94629323483,1.83781254292,-5.57375717163 --1.93128621578,1.83881771564,-5.58317708969 --1.90625357628,1.82983839512,-5.56660938263 --1.90326142311,1.83483409882,-5.58281230927 --1.88424432278,1.83184540272,-5.58224201202 --1.87525439262,1.83984041214,-5.60967159271 --1.45101356506,1.85401713848,-5.79380273819 --1.41593694687,1.83006334305,-5.73324632645 --1.39089441299,1.81808960438,-5.70667362213 --1.37789607048,1.82309019566,-5.72409105301 --1.36788499355,1.82109749317,-5.72131204605 --1.34986841679,1.81910848618,-5.72073793411 --1.33887898922,1.82710397243,-5.74715900421 --1.32387530804,1.83010780811,-5.75958919525 --1.29581928253,1.81414175034,-5.72002601624 --1.2848315239,1.82213628292,-5.74845457077 --1.26580929756,1.81815087795,-5.74187231064 --1.25780713558,1.82015299797,-5.74809932709 --1.24380683899,1.82415485382,-5.7635216713 --1.22478854656,1.82216715813,-5.76196861267 --1.20878016949,1.82317376137,-5.7693939209 --1.19076347351,1.821185112,-5.76882266998 --1.17475497723,1.82219159603,-5.77624702454 --1.16075658798,1.82719242573,-5.79367542267 --1.15476381779,1.83218932152,-5.80889844894 --1.13272547722,1.82221293449,-5.7863111496 --1.11873054504,1.82821202278,-5.80775690079 --1.10473155975,1.83321321011,-5.82417535782 --1.08973097801,1.83721542358,-5.83961105347 --1.07272052765,1.83822345734,-5.84504508972 --1.05671572685,1.84022808075,-5.85648298264 -1.38779342175,1.76121902466,-4.81552886963 -1.40480804443,1.76222193241,-4.81492328644 -1.41981506348,1.76122128963,-4.80632448196 -1.43582594395,1.76122248173,-4.80172348022 -1.44882512093,1.75621831417,-4.78513622284 -1.466843009,1.75922262669,-4.78753185272 -1.47284173965,1.75622034073,-4.77873182297 -1.48985636234,1.75722336769,-4.77812576294 -1.50586605072,1.75722384453,-4.77153921127 -1.51987016201,1.7542219162,-4.7599439621 -1.54591345787,1.76623785496,-4.78832960129 -1.55891382694,1.76223433018,-4.77274036407 -1.56790304184,1.75422585011,-4.74614429474 -1.5759074688,1.75322592258,-4.74235582352 -1.59392523766,1.75623035431,-4.74474811554 -1.60893332958,1.75523030758,-4.73714828491 -1.62795162201,1.75723493099,-4.73956203461 -2.09129071236,1.77528762817,-4.6338224411 -2.09528779984,1.77228498459,-4.62301540375 -2.10428214073,1.76627922058,-4.59944438934 -2.12029314041,1.76628088951,-4.59484100342 -2.13730669022,1.76828336716,-4.59223794937 -2.15431976318,1.76928591728,-4.58963537216 -2.17233467102,1.77128899097,-4.58804273605 -2.17732286453,1.76228117943,-4.55944490433 -2.18432617188,1.76228106022,-4.554646492 -2.20534658432,1.76628625393,-4.55806827545 -2.22336220741,1.76828992367,-4.55845499039 -2.24237895012,1.77129375935,-4.55886173248 -2.25738811493,1.77129471302,-4.55225515366 -2.27239656448,1.77029502392,-4.54366970062 -2.28239583969,1.76629185677,-4.52607393265 -2.28739500046,1.76429009438,-4.51628637314 -2.31342601776,1.77329993248,-4.53266906738 -2.32442688942,1.76929724216,-4.51608514786 -2.34143948555,1.77029955387,-4.51248884201 -2.35444521904,1.76929914951,-4.50188398361 -2.37346148491,1.77230274677,-4.5012960434 -2.39347910881,1.77530694008,-4.50270700455 -2.39347076416,1.77030229568,-4.48589468002 -2.40948152542,1.77030384541,-4.48029851913 -2.4264934063,1.77130568027,-4.47472286224 -2.44250512123,1.77230787277,-4.47110414505 -2.4545083046,1.77030622959,-4.4565243721 -2.46951794624,1.77030742168,-4.44991827011 -2.48453497887,1.77531278133,-4.45912885666 -2.49453520775,1.77131009102,-4.44154405594 -2.51555538177,1.77631545067,-4.44593429565 -2.52355217934,1.77031159401,-4.425344944 -2.53755998611,1.77031183243,-4.41575241089 -2.56458926201,1.77832090855,-4.43014669418 -2.5755918026,1.77631926537,-4.41555023193 -2.58359718323,1.77632009983,-4.41275072098 -2.60161137581,1.7783229351,-4.41015672684 -2.61161279678,1.77532100677,-4.39455318451 -2.62361741066,1.77332019806,-4.3819565773 -2.64062952995,1.77432250977,-4.37736606598 -2.66365098953,1.78032803535,-4.38178634644 -2.67265105247,1.77632546425,-4.36419010162 -2.67965531349,1.77632594109,-4.36038208008 -2.69766879082,1.77832865715,-4.35679721832 -2.7196893692,1.78333413601,-4.36218118668 -2.72969079018,1.78033220768,-4.34559440613 -2.74369835854,1.779332757,-4.33600282669 -2.7597091198,1.78033423424,-4.329413414 -2.77371716499,1.78033494949,-4.32080841064 -2.78372502327,1.78133678436,-4.32002210617 -2.79673171043,1.78033685684,-4.30942344666 -2.81374406815,1.78233921528,-4.30482721329 -2.82975506783,1.78334105015,-4.299223423 -2.84476423264,1.78334200382,-4.29063892365 -2.86177682877,1.78534460068,-4.28702783585 -2.86677742004,1.78334343433,-4.27725744247 -2.89079999924,1.79034972191,-4.28464031219 -2.90380597115,1.78834962845,-4.27305459976 -2.9128074646,1.78534793854,-4.25645589828 -2.93282341957,1.7883515358,-4.25586223602 -2.94382739067,1.78635084629,-4.24226427078 -2.95683431625,1.78635120392,-4.23166561127 -2.96684193611,1.78735280037,-4.22988843918 -2.98785996437,1.79235732555,-4.23227024078 -2.98784852028,1.782351017,-4.20070409775 -3.0118701458,1.78835654259,-4.20610284805 -3.03989696503,1.79736423492,-4.21749353409 -3.03588151932,1.78635644913,-4.18190956116 -3.06390762329,1.79436385632,-4.19231176376 -3.07792067528,1.79836750031,-4.19751119614 -3.08091497421,1.79236340523,-4.172914505 -3.09892773628,1.79436576366,-4.16734266281 -3.11994481087,1.7983700037,-4.16872882843 -3.12394046783,1.79236626625,-4.14415550232 -3.12893724442,1.78636324406,-4.12256240845 -3.15996742249,1.79737198353,-4.13793754578 -3.15795969963,1.79136812687,-4.11916971207 -3.17296934128,1.79236960411,-4.11058187485 -3.2140109539,1.80838239193,-4.13993835449 -3.20499062538,1.79437327385,-4.09738636017 -3.2179980278,1.79437398911,-4.08678865433 -3.22599935532,1.79037249088,-4.06920003891 -3.24401259422,1.79337525368,-4.06559467316 -3.24901437759,1.79237496853,-4.0578045845 -3.27803993225,1.80038201809,-4.06721258163 -3.27603030205,1.79237675667,-4.03761577606 -3.29003858566,1.79237794876,-4.02802371979 -3.30705070496,1.79438018799,-4.02242708206 -3.32105898857,1.79438126087,-4.01184892654 -3.33106303215,1.79238092899,-3.99725747108 -3.35708808899,1.80238866806,-4.01644945145 -3.36208701134,1.79838633537,-3.99585580826 -3.36608457565,1.79238402843,-3.97426104546 -3.3901040554,1.79838871956,-3.97666811943 -3.40611457825,1.80039072037,-3.96907901764 -3.41812133789,1.79939126968,-3.95747900009 -3.43013095856,1.80239367485,-3.95868062973 -3.42912316322,1.79438948631,-3.93010735512 -3.45414376259,1.80039477348,-3.9344959259 -3.47415852547,1.80439782143,-3.93091511726 -3.48216104507,1.8013972044,-3.91530609131 -3.48716020584,1.79639530182,-3.89373779297 -3.50917720795,1.80139946938,-3.89412903786 -3.51117610931,1.7983982563,-3.8823530674 -3.5291891098,1.8014010191,-3.87774991989 -3.54620075226,1.80340325832,-3.87116003036 -3.55520486832,1.80140316486,-3.8565557003 -3.56821250916,1.80140411854,-3.8449742794 -3.58422279358,1.80240619183,-3.83738136292 -3.59422826767,1.80140638351,-3.82377958298 -3.59722852707,1.79940581322,-3.81399273872 -3.61524128914,1.8024084568,-3.80840182304 -3.63225293159,1.80441081524,-3.80180907249 -3.63625216484,1.79940927029,-3.78121852875 -3.65526580811,1.8024122715,-3.77662706375 -3.66927456856,1.80341374874,-3.76703000069 -3.68628835678,1.80841732025,-3.77223944664 -3.69629383087,1.80741775036,-3.75863862038 -3.70429682732,1.80441749096,-3.74205374718 -3.7153031826,1.80441820621,-3.72945451736 -3.73231458664,1.80542051792,-3.72187495232 -3.74732470512,1.80742239952,-3.7132768631 -3.75732970238,1.8054227829,-3.69869470596 -3.77434325218,1.81142616272,-3.70389556885 -3.78935313225,1.8124281168,-3.69529604912 -3.79835772514,1.81042838097,-3.67971348763 -3.80936384201,1.8094291687,-3.66711449623 -3.8193693161,1.80842971802,-3.65253281593 -3.83538031578,1.81043195724,-3.64493203163 -3.81235742569,1.79242432117,-3.59736990929 -3.80134654045,1.78442072868,-3.57359957695 -3.79333734512,1.77441716194,-3.54202055931 -3.78132486343,1.76241278648,-3.50644922256 -3.76130604744,1.74640655518,-3.46289038658 -3.75429868698,1.73740363121,-3.43330717087 -3.73528122902,1.72139823437,-3.39174222946 -3.73027610779,1.71439599991,-3.36416554451 -3.72927474976,1.71039545536,-3.35236787796 -3.73427772522,1.7073956728,-3.33380079269 -3.75129055977,1.71039867401,-3.3281981945 -3.75729465485,1.70739936829,-3.31161260605 -3.7642993927,1.7054002285,-3.2960267067 -3.78531551361,1.71040415764,-3.29343366623 -3.78231263161,1.70340299606,-3.26884937286 -3.79532241821,1.70640540123,-3.27004742622 -3.80332827568,1.70540654659,-3.25546073914 -3.81233501434,1.70440793037,-3.24187278748 -3.81733846664,1.70140862465,-3.22527599335 -3.82134175301,1.69840919971,-3.20670199394 -3.82834720612,1.69641029835,-3.19112157822 -3.83235001564,1.69541096687,-3.18432092667 -3.8423576355,1.69441270828,-3.1717338562 -3.84836268425,1.69241380692,-3.15613889694 -3.86337375641,1.69441664219,-3.14853692055 -3.86637663841,1.69041717052,-3.12897205353 -3.86837887764,1.68641757965,-3.10939240456 -3.88639259338,1.69042098522,-3.10379981995 -3.887393713,1.68842124939,-3.09401082993 -3.88939595222,1.68442177773,-3.07541513443 -3.8954012394,1.68242311478,-3.05982589722 -3.9094119072,1.68342590332,-3.05024719238 -3.91341614723,1.68042683601,-3.03364682198 -3.92542552948,1.68142926693,-3.02305579185 -3.9344329834,1.68043124676,-3.0094769001 -3.93443393707,1.67843139172,-2.99869608879 -3.94744420052,1.67943406105,-2.98910069466 -3.95445036888,1.67843568325,-2.97451114655 -3.95745396614,1.67443680763,-2.95692038536 -3.97246551514,1.67643976212,-2.94833636284 -3.97046637535,1.67144024372,-2.92675042152 -3.98347663879,1.67244303226,-2.91715550423 -3.98447847366,1.67144346237,-2.9073741436 -3.99148511887,1.66944539547,-2.89278864861 -4.00949859619,1.67244899273,-2.88620877266 -4.01050138474,1.66945004463,-2.86663389206 -4.01850938797,1.66845202446,-2.85402369499 -4.02551603317,1.6674541235,-2.83944010735 -4.02551746368,1.66545462608,-2.82964706421 -4.04052877426,1.66745769978,-2.8210606575 -4.04953718185,1.66746008396,-2.80846619606 -4.04653787613,1.66146087646,-2.78590130806 -4.05854845047,1.66246366501,-2.77531147003 -4.06955718994,1.66346621513,-2.76470589638 -4.08557033539,1.66546964645,-2.75613260269 -4.08156919479,1.66146969795,-2.74334740639 -4.07556867599,1.65547037125,-2.71976590157 -4.106590271,1.66447556019,-2.72315835953 -4.0955862999,1.65547561646,-2.69657087326 -4.10859775543,1.65747869015,-2.68599510193 -4.12260961533,1.65948188305,-2.67641186714 -4.12361335754,1.65548336506,-2.65881180763 -4.12561607361,1.65448451042,-2.65003371239 -4.13962745667,1.65648770332,-2.64045000076 -4.13963127136,1.65248942375,-2.62186002731 -4.14363718033,1.65049159527,-2.60528469086 -4.16665363312,1.65649569035,-2.60267615318 -4.15565156937,1.64749646187,-2.5761077404 -4.17266464233,1.65149998665,-2.56852173805 -4.18467330933,1.65450203419,-2.56771183014 -4.17667293549,1.6475032568,-2.54314637184 -4.1836810112,1.64650583267,-2.52955174446 -4.20169448853,1.65050935745,-2.52295517921 -4.19969749451,1.64551115036,-2.50336837769 -4.2137093544,1.64751470089,-2.49280381203 -4.2167134285,1.64751601219,-2.4859995842 -4.21571731567,1.64351797104,-2.46642971039 -4.22272539139,1.64252078533,-2.45283675194 -4.23873758316,1.64552414417,-2.44523143768 -4.22473526001,1.63652539253,-2.41766905785 -4.23574590683,1.63752865791,-2.40608644485 -4.26176357269,1.64453291893,-2.40350103378 -4.24775934219,1.63753306866,-2.38669729233 -4.25276613235,1.63553571701,-2.37112522125 -4.27778339386,1.64253997803,-2.36852240562 -4.2727856636,1.63754200935,-2.3479321003 -4.27979421616,1.63654506207,-2.33336424828 -4.28480195999,1.63554787636,-2.31877088547 -4.2928109169,1.6355509758,-2.30519366264 -4.29381465912,1.63355243206,-2.29641270638 -4.29982233047,1.63355529308,-2.28280997276 -4.30182886124,1.63055813313,-2.26622629166 -4.30983781815,1.63056135178,-2.25265049934 -4.33085298538,1.63556528091,-2.24705410004 -4.31585216522,1.62656724453,-2.22048902512 -4.32986402512,1.62957084179,-2.21089625359 -4.33887052536,1.63157272339,-2.20710134506 -4.33387470245,1.62657535076,-2.18652701378 -4.34288406372,1.62657856941,-2.17491865158 -4.35889673233,1.62958240509,-2.1653482914 -4.35290002823,1.62458503246,-2.14476585388 -4.35890865326,1.62458825111,-2.13116717339 -4.37591934204,1.62959051132,-2.13137292862 -4.3669219017,1.62259316444,-2.1088051796 -4.36792850494,1.62059628963,-2.09221839905 -4.39394521713,1.62760043144,-2.08862280846 -4.39095020294,1.62360346317,-2.07003617287 -4.39495849609,1.6226067543,-2.05446243286 -4.40196752548,1.62261021137,-2.04087686539 -4.41097450256,1.62461221218,-2.03707695007 -4.40797996521,1.62061524391,-2.01849460602 -4.41899108887,1.62161898613,-2.00690793991 -4.4239988327,1.62062239647,-1.99232399464 -4.4230055809,1.61762571335,-1.97474372387 -4.43501710892,1.61962962151,-1.9631677866 -4.43802165985,1.61963140965,-1.95636975765 -4.45103311539,1.62163507938,-1.94578003883 -4.44703865051,1.61763834953,-1.92719316483 -4.45604896545,1.61864209175,-1.91460680962 -4.46305847168,1.61864566803,-1.90102243423 -4.46106481552,1.61464929581,-1.88343727589 -4.47507715225,1.61765301228,-1.87285625935 -4.46607780457,1.61265480518,-1.86007523537 -4.47908973694,1.61565864086,-1.84948313236 -4.4780960083,1.61266231537,-1.83191168308 -4.48210525513,1.61166608334,-1.81732141972 -4.49111557007,1.61266982555,-1.8047349453 -4.49912643433,1.61267375946,-1.79116237164 -4.50213432312,1.61167752743,-1.77656209469 -4.50213813782,1.61067950726,-1.7677834034 -4.50514698029,1.60868346691,-1.75220906734 -4.51915931702,1.6126871109,-1.74259865284 -4.52216768265,1.61069118977,-1.72702467442 -4.5341796875,1.61269509792,-1.71544229984 -4.52618455887,1.6076990366,-1.69585800171 -4.536195755,1.60870313644,-1.68328046799 -4.53920078278,1.60870504379,-1.67648422718 -4.54020881653,1.60670900345,-1.66089248657 -4.54921960831,1.60871303082,-1.6483039856 -4.5602312088,1.61071693897,-1.63670969009 -4.55723762512,1.60672104359,-1.61913096905 -4.56224775314,1.60672521591,-1.60455429554 -4.55825090408,1.6037273407,-1.59476745129 -4.57226324081,1.60673141479,-1.5841755867 -4.57427215576,1.60573554039,-1.56859624386 -4.58728456497,1.6087397337,-1.55701816082 -4.58129072189,1.60374414921,-1.53844225407 -4.58630037308,1.60374820232,-1.52484154701 -4.59331130981,1.60475230217,-1.51125872135 -4.59331560135,1.6027547121,-1.5024869442 -4.59832525253,1.60275876522,-1.48888635635 -4.60933685303,1.60476315022,-1.47631335258 -4.60734510422,1.6027674675,-1.45972752571 -4.62235784531,1.6057716608,-1.44913744926 -4.62236690521,1.60377621651,-1.43257009983 -4.62237548828,1.601780653,-1.41697824001 -4.62838125229,1.60278272629,-1.41118240356 -4.62939023972,1.60178720951,-1.39559948444 -4.63140010834,1.60079181194,-1.38002562523 -4.63841104507,1.60079622269,-1.36644268036 -4.64742231369,1.60280048847,-1.35384941101 -4.65043210983,1.60180497169,-1.33925890923 -4.66444444656,1.604809165,-1.32767903805 -4.65444660187,1.60081207752,-1.31590795517 -4.65145540237,1.5978167057,-1.29932272434 -4.66746807098,1.60182094574,-1.28873169422 -4.66347646713,1.59882569313,-1.27213966846 -4.66948747635,1.5988304615,-1.25757372379 -4.67049646378,1.59783494473,-1.24296975136 -4.67650318146,1.59883737564,-1.23619651794 -4.68851470947,1.60184156895,-1.22459697723 -4.68652391434,1.59884655476,-1.2080231905 -4.68753385544,1.59785139561,-1.19244623184 -4.6885433197,1.59685647488,-1.17686986923 -4.69055366516,1.59586107731,-1.16227531433 -4.7005648613,1.59786558151,-1.14968526363 -4.69556903839,1.59486842155,-1.13991141319 -4.72158432007,1.60287201405,-1.13230061531 -4.72059392929,1.600877285,-1.11573696136 -4.71360206604,1.59688270092,-1.09815990925 -4.7346162796,1.60288655758,-1.08856201172 -4.72762489319,1.5988920927,-1.07098650932 -4.72463417053,1.59689748287,-1.05441248417 -4.73364067078,1.59889936447,-1.04960227013 -4.73965215683,1.59990429878,-1.03503417969 -4.73966217041,1.59890949726,-1.0194542408 -4.75667572021,1.60291349888,-1.00884962082 -4.74268293381,1.59691977501,-0.989288926125 -4.74869394302,1.59692454338,-0.975694775581 -4.75970602036,1.59992897511,-0.963103353977 -4.7407078743,1.59293293953,-0.950333237648 -4.7577214241,1.59693741798,-0.938751161098 -4.76473283768,1.59894216061,-0.925161540508 -4.75574159622,1.59394812584,-0.907586455345 -4.76675367355,1.59695267677,-0.894993007183 -4.78276729584,1.60095691681,-0.883399665356 -4.77377033234,1.59696030617,-0.873614907265 -4.76978063583,1.59496593475,-0.857044100761 -4.78479385376,1.59897065163,-0.844469666481 -4.77880334854,1.59497642517,-0.827889740467 -4.78381443024,1.59598135948,-0.814287960529 -4.79782772064,1.59998595715,-0.801705062389 -4.79083681107,1.59599196911,-0.785122156143 -4.78084039688,1.59199547768,-0.775339007378 -4.80785560608,1.60099899769,-0.765738010406 -4.78586292267,1.59100651741,-0.745192170143 -4.80487728119,1.5970107317,-0.733602941036 -4.80588769913,1.59701609612,-0.719007730484 -4.79989767075,1.59302222729,-0.702435076237 -4.8029088974,1.59302759171,-0.687850296497 -4.83791971207,1.60502767563,-0.687031984329 -4.82192850113,1.59903478622,-0.668468773365 -4.82293987274,1.59804058075,-0.652901113033 -4.81794977188,1.59504640102,-0.637308657169 -4.81696081161,1.59405243397,-0.621733725071 -4.83697462082,1.60005640984,-0.610136330128 -4.82798480988,1.59606301785,-0.593556344509 -4.81998872757,1.59306645393,-0.584766924381 -4.83800268173,1.59807097912,-0.572185516357 -4.85301589966,1.6030755043,-0.559589922428 -4.84502601624,1.59908211231,-0.543016552925 -4.84303712845,1.59708821774,-0.52743947506 -4.84204864502,1.59609425068,-0.511866271496 -4.84905529022,1.59809672832,-0.505078732967 -4.84506607056,1.59610295296,-0.489495784044 -4.85107851028,1.59710848331,-0.474919676781 -4.85509061813,1.59811413288,-0.460336387157 -4.84810066223,1.5951205492,-0.44474580884 -4.84611177444,1.59312689304,-0.429172098637 -4.84912395477,1.59313261509,-0.414586573839 -4.84612894058,1.59213590622,-0.406794101 -4.83714008331,1.58814287186,-0.390229105949 -4.8371515274,1.5871489048,-0.37563636899 -4.8401632309,1.58815467358,-0.361051589251 -4.83817529678,1.58716118336,-0.345480978489 -4.85018825531,1.59016609192,-0.331891655922 -4.84119367599,1.58717024326,-0.323113977909 -4.84320545197,1.58717620373,-0.308526873589 -4.84121751785,1.58518266678,-0.292958080769 -4.85023021698,1.58818793297,-0.279359042645 -4.84424114227,1.58519470692,-0.263781964779 -4.8512544632,1.58720052242,-0.249205008149 -4.84126567841,1.584207654,-0.233621269464 -4.85727357864,1.58920955658,-0.226842746139 -4.84128379822,1.58321714401,-0.211249604821 -4.85029649734,1.5852227211,-0.196675345302 -4.85130882263,1.58522891998,-0.182086423039 -4.85532140732,1.58623492718,-0.167502239347 -4.85233354568,1.58524167538,-0.151934489608 -4.84434509277,1.58224916458,-0.136360630393 -4.85435199738,1.58525121212,-0.129565805197 -4.84936475754,1.58325839043,-0.113996878266 -4.84837675095,1.58226490021,-0.0994063988328 -4.84438896179,1.5802719593,-0.0838403850794 -4.8614025116,1.58627653122,-0.0702412649989 -4.85341453552,1.58328402042,-0.0546713881195 -4.84842061996,1.58128786087,-0.0468861684203 -4.86043310165,1.58529269695,-0.0332796052098 -4.85344552994,1.58230030537,-0.0177126321942 -4.8504576683,1.58130705357,-0.00312187965028 -4.85447120667,1.58231365681,0.0124369431287 -4.85748434067,1.58331978321,0.0270243082196 -4.84849596024,1.58032727242,0.0416165329516 -4.86050319672,1.5843296051,0.0493928976357 -4.8415145874,1.57733798027,0.0639863461256 -4.85352802277,1.5813434124,0.078571729362 -4.85754156113,1.58235001564,0.0941321626306 -4.85455417633,1.58135700226,0.108720652759 -4.85256671906,1.58036375046,0.123308591545 -4.84557962418,1.57837164402,0.138867944479 -4.84958600998,1.57937443256,0.145676195621 -4.8515996933,1.58038127422,0.16123713553 -4.85961294174,1.58238708973,0.175827950239 -4.84062480927,1.57639598846,0.190407440066 -4.85563850403,1.58140099049,0.205002769828 -4.84465169907,1.57740950584,0.220556199551 -4.84266471863,1.57641661167,0.235141858459 -4.84967088699,1.57941889763,0.241954773664 -4.85568523407,1.58142530918,0.257520139217 -4.84769773483,1.57843315601,0.272100687027 -4.85471057892,1.58143913746,0.286695659161 -4.84672451019,1.57844746113,0.302247345448 -4.84473800659,1.57845461369,0.316832691431 -4.85374498367,1.58145701885,0.324623912573 -4.84675788879,1.57846486568,0.339202642441 -4.84977149963,1.58047139645,0.353794902563 -4.84378480911,1.5784791708,0.368373990059 -4.84679841995,1.57948613167,0.383938908577 -4.85181188583,1.5814923048,0.398535370827 -4.83982515335,1.57750105858,0.413102805614 -4.84183168411,1.57850408554,0.419914036989 -4.84484577179,1.57951116562,0.435480058193 -4.84785890579,1.58051753044,0.450074195862 -4.84487342834,1.58052551746,0.46562948823 -4.83688640594,1.5775333643,0.479228228331 -4.8389005661,1.57854056358,0.49479329586 -4.8309135437,1.57654857635,0.508390784264 -4.85492086411,1.58454930782,0.518172502518 -4.83493471146,1.57855927944,0.531741261482 -4.83394861221,1.57856655121,0.54632717371 -4.85696268082,1.58657062054,0.562920928001 -4.83397626877,1.57858121395,0.576476991177 -4.831990242,1.57858872414,0.591060459614 -4.83899736404,1.58159136772,0.598861157894 -4.83101129532,1.57859992981,0.613427400589 -4.82702541351,1.57860779762,0.628005027771 -4.83903932571,1.58261334896,0.643603563309 -4.82805299759,1.57962214947,0.657186686993 -4.8250670433,1.57862985134,0.671766579151 -4.83308172226,1.58263659477,0.688328564167 -4.81708908081,1.57664251328,0.694110631943 -4.81510305405,1.57665014267,0.708693265915 -4.82711648941,1.58165550232,0.724298119545 -4.81813144684,1.57866454124,0.738856315613 -4.81214523315,1.57767260075,0.752451956272 -4.82916021347,1.58467793465,0.770024955273 -4.81617450714,1.58068740368,0.783593714237 -4.80618143082,1.57669234276,0.789390742779 -4.81519603729,1.58069884777,0.805962860584 -4.80621051788,1.5787075758,0.819544970989 -4.80422496796,1.5787153244,0.834127902985 -4.81523895264,1.58272135258,0.850711524487 -4.79625415802,1.57673180103,0.863276004791 -4.79026842117,1.57573997974,0.876868128777 -4.80227565765,1.58074235916,0.886649489403 -4.79429006577,1.57875108719,0.900232732296 -4.77730560303,1.57276129723,0.912800133228 -4.79931879044,1.58176529408,0.930413901806 -4.7763338089,1.57477653027,0.941978216171 -4.79134845734,1.58078193665,0.959562063217 -4.8023557663,1.58478438854,0.969345211983 -4.77837085724,1.57679545879,0.979927778244 -4.77738571167,1.57780313492,0.994515836239 -4.7844004631,1.58080995083,1.01109135151 -4.75541543961,1.57182204723,1.02066838741 -4.76743030548,1.57682812214,1.03824388981 -4.77044534683,1.57883536816,1.05382704735 -4.76545286179,1.5778400898,1.06061053276 -4.7664680481,1.57884788513,1.0761834383 -4.77848291397,1.58485400677,1.09376549721 -4.73149967194,1.5688688755,1.09933555126 -4.7225151062,1.56687831879,1.11290311813 -4.06761455536,1.58204686642,2.78551244736 -4.10662555695,1.60104870796,2.82910513878 -4.0916466713,1.59906113148,2.837672472 -4.10966110229,1.61006653309,2.8672721386 -4.07367706299,1.59707844257,2.85303378105 -4.04470014572,1.5880934,2.85160636902 -4.03471899033,1.58710420132,2.86220121384 -4.02973794937,1.58911454678,2.87678408623 -4.0257563591,1.59112465382,2.89236116409 -4.01877593994,1.59113538265,2.90593624115 -4.0127954483,1.59314608574,2.92050552368 -4.00680541992,1.59215176105,2.92529821396 -3.98582744598,1.58716523647,2.92887330055 -3.98584580421,1.59117472172,2.94744944572 -3.98186469078,1.59318482876,2.96302986145 -3.96488595009,1.58919775486,2.9695994854 -3.95790457726,1.59020793438,2.98219799995 -3.96391272545,1.5952116251,2.99598670006 -3.94793343544,1.59122395515,3.00257134438 -3.94295334816,1.59323453903,3.01813769341 -3.93397283554,1.59324550629,3.0297267437 -3.92299318314,1.59325706959,3.04030442238 -3.91601276398,1.59326791763,3.0538828373 -3.91103243828,1.59527850151,3.06945157051 -3.9050424099,1.59528434277,3.0742430687 -3.88906359673,1.59229683876,3.08082294464 -3.89708018303,1.59930455685,3.10541749001 -3.87710237503,1.59531784058,3.10899424553 -3.86712384224,1.59532988071,3.12154507637 -3.85614418983,1.5943416357,3.13212180138 -3.85716223717,1.59935069084,3.15171146393 -3.84217429161,1.59435844421,3.14949727058 -3.8401927948,1.59736824036,3.1670794487 -3.82821273804,1.59637963772,3.17568159103 -3.82523226738,1.59939002991,3.19324851036 -3.81325292587,1.5984017849,3.20282959938 -3.79327583313,1.59341549873,3.20639634132 -3.7982840538,1.59841918945,3.22018933296 -3.78730463982,1.59743094444,3.23076558113 -3.77732563019,1.59744262695,3.24233865738 -3.76734638214,1.59745419025,3.25391197205 -3.76236510277,1.5994644165,3.2685110569 -3.75538492203,1.6014752388,3.28209662437 -3.73940706253,1.59848809242,3.28866696358 -3.74341511726,1.60249173641,3.30147004128 -3.73143696785,1.60150420666,3.31202888489 -3.71745800972,1.59951651096,3.31961321831 -3.70447921753,1.59852850437,3.32819414139 -3.70449852943,1.60353839397,3.34876513481 -3.68851995468,1.60055088997,3.35435295105 -3.68054080009,1.60156238079,3.36792302132 -3.67555117607,1.60156822205,3.37370991707 -3.66157269478,1.59958064556,3.38129210472 -3.65559244156,1.60159122944,3.39587926865 -3.65061306953,1.60460221767,3.41244602203 -3.64063310623,1.60461342335,3.42304110527 -3.63565349579,1.60762429237,3.43960976601 -3.62366509438,1.60363137722,3.43840694427 -3.62068510056,1.60764181614,3.45697402954 -3.6027071476,1.60365498066,3.46055912971 -3.59072852135,1.60366714001,3.47013664246 -3.58574819565,1.60567748547,3.48572778702 -3.5737695694,1.60568964481,3.49530553818 -3.56279110909,1.60570156574,3.50588226318 -3.56780076027,1.61070609093,3.52264547348 -3.550822258,1.60771858692,3.52624535561 -3.53584456444,1.60573136806,3.53282403946 -3.53886318207,1.61174070835,3.55739808083 -3.52088594437,1.6087539196,3.56097698212 -3.50190901756,1.60476756096,3.56355428696 -3.5089173317,1.61077105999,3.58134388924 -3.4889395237,1.60578429699,3.58193922043 -3.48596048355,1.60979521275,3.60149979591 -3.48298025131,1.61380553246,3.62008166313 -3.46000361443,1.60781955719,3.61767268181 -3.45302414894,1.60983073711,3.63225317001 -3.45304393768,1.61584079266,3.65482139587 -3.42805862427,1.60585057735,3.63961267471 -3.42507815361,1.60986089706,3.65819811821 -3.4161002636,1.61187291145,3.67175984383 -3.40512180328,1.61188495159,3.6823387146 -3.38614487648,1.60789823532,3.68392491341 -3.39116382599,1.61590754986,3.71248936653 -3.3671875,1.60992181301,3.70808553696 -3.3641974926,1.61092710495,3.71587872505 -3.35521960258,1.61193919182,3.72944283485 -3.34524106979,1.61295104027,3.74102377892 -3.335262537,1.61396276951,3.75260519981 -3.32828402519,1.61597418785,3.76817536354 -3.31430578232,1.6149866581,3.774766922 -3.29432940483,1.61000061035,3.77534365654 -3.2993388176,1.61600470543,3.79312300682 -3.28835964203,1.61601626873,3.80272126198 -3.26938343048,1.6120300293,3.80429840088 -3.26640343666,1.61704051495,3.82388281822 -3.25842499733,1.61905217171,3.83845496178 -3.237449646,1.61406648159,3.8380241394 -3.2414586544,1.62007081509,3.85480856895 -3.22048187256,1.61408424377,3.85241103172 -3.21350312233,1.61709570885,3.86798763275 -3.20752382278,1.62010681629,3.88456892967 -3.18454885483,1.61412131786,3.88114404678 -3.18556833267,1.62213134766,3.90671730042 -3.16959142685,1.61914432049,3.91129875183 -3.15960335732,1.61715126038,3.91108989716 -3.15362405777,1.62016236782,3.92767477036 -3.14464712143,1.62217462063,3.94223237038 -3.123670578,1.61718845367,3.93982481956 -3.11469244957,1.61920034885,3.95339941978 -3.10671329498,1.62121140957,3.96699619293 -3.09772586823,1.62021863461,3.96877241135 -3.08774805069,1.62123072147,3.9813439846 -3.07677030563,1.62224280834,3.99192857742 -3.07079076767,1.62525379658,4.00852060318 -3.04981589317,1.62026822567,4.00708961487 -3.04983520508,1.6272778511,4.03168058395 -3.03485894203,1.62629115582,4.03824663162 -3.02587080002,1.62429797649,4.03903770447 -3.0128929615,1.62431025505,4.04662942886 -3.00391507149,1.62632203102,4.06021022797 -2.99093866348,1.62633514404,4.06976985931 -2.97896051407,1.62634718418,4.07836723328 -2.96798419952,1.62735998631,4.09092235565 -2.95700526237,1.62837171555,4.10052585602 -2.95301628113,1.62937748432,4.10831356049 -2.934040308,1.62539124489,4.10790061951 -2.92906165123,1.63040232658,4.12747859955 -2.91708469391,1.63041508198,4.13804531097 -2.90010857582,1.62842845917,4.14062786102 -2.88813185692,1.62844121456,4.15119457245 -2.88115262985,1.63245213032,4.16679573059 -2.87216567993,1.63045942783,4.16856765747 -2.86018824577,1.63147175312,4.17815160751 -2.85020971298,1.63248348236,4.18974924088 -2.83623361588,1.63249647617,4.1973195076 -2.82125711441,1.63050973415,4.20289707184 -2.80827975273,1.63052201271,4.21048879623 -2.8022916317,1.63152849674,4.21626615524 -2.79331493378,1.63354098797,4.23182821274 -2.77733850479,1.63255405426,4.23541355133 -2.76736068726,1.63356614113,4.24799919128 -2.75838303566,1.63657796383,4.2625784874 -2.7464056015,1.63759028912,4.27216529846 -2.72843003273,1.63360393047,4.27274751663 -2.72644090652,1.63760960102,4.28452968597 -2.71446371078,1.63762187958,4.29411649704 -2.70148706436,1.63763463497,4.30269575119 -2.69050955772,1.63964688778,4.31427717209 -2.67753362656,1.6396600008,4.32384300232 -2.66255712509,1.63867294788,4.32843399048 -2.65258049965,1.64168548584,4.34299755096 -2.6435918808,1.63969171047,4.34180784225 -2.63461446762,1.6427038908,4.35738134384 -2.62063789368,1.64171671867,4.36396694183 -2.60966134071,1.6437292099,4.37653827667 -2.59268522263,1.6417427063,4.37812423706 -2.57870936394,1.64175581932,4.38569545746 -2.57372093201,1.64276182652,4.39248657227 -2.57074189186,1.64977252483,4.41806840897 -2.55676531792,1.64978528023,4.42465543747 -2.54178929329,1.64879858494,4.43023252487 -2.5278134346,1.64881169796,4.43780565262 -2.51683664322,1.65082418919,4.4503827095 -2.50485873222,1.65183615685,4.45898914337 -2.50387001038,1.65584182739,4.47475910187 -2.48289513588,1.65085589886,4.46835327148 -2.4719183445,1.65286827087,4.48093223572 -2.46294164658,1.65688073635,4.49849510193 -2.4419670105,1.65189480782,4.49208545685 -2.46398186684,1.67790067196,4.56566286087 -2.45600485802,1.68291270733,4.58523273468 -2.46101284027,1.69091641903,4.610039711 -2.44903707504,1.69292938709,4.62260818481 -2.44205880165,1.69894075394,4.64319515228 -2.430082798,1.70095348358,4.65576601028 -2.43010234833,1.71096348763,4.6893620491 -2.42212533951,1.71697533131,4.70993375778 -2.417137146,1.71898162365,4.71871614456 -2.41915726662,1.73099148273,4.75829792023 -2.40718007088,1.73300385475,4.76988983154 -2.39720344543,1.73701620102,4.78745985031 -2.38922572136,1.74202799797,4.80804300308 -2.38624691963,1.75203859806,4.8386297226 -2.37827014923,1.75805079937,4.86119651794 -2.37828016281,1.76405596733,4.87998819351 -2.35630655289,1.75807058811,4.87356185913 -2.33933067322,1.75608384609,4.87515878677 -2.32935428619,1.7610963583,4.8937292099 -2.31237840652,1.75910949707,4.89532613754 -2.29540371895,1.75812327862,4.89890050888 -2.28742647171,1.76413524151,4.92147731781 -2.27044081688,1.75614356995,4.90427303314 -2.26446342468,1.76415526867,4.9318447113 -2.25148749352,1.76616799831,4.94342708588 -2.22951388359,1.76018261909,4.93600177765 -2.21553778648,1.76119554043,4.94459247589 -2.19856238365,1.76020896435,4.94717597961 -2.17259001732,1.75022435188,4.92975568771 -2.16660189629,1.75223064423,4.9365477562 -2.15362668037,1.75424396992,4.95011043549 -2.1356511116,1.75225734711,4.94870853424 -2.11767625809,1.74927103519,4.94829511642 -2.10170197487,1.74928486347,4.95485830307 -2.08472704887,1.74829852581,4.95743751526 -2.07773852348,1.74830448627,4.96024703979 -2.06676268578,1.75231730938,4.97881031036 -2.04778862,1.7493314743,4.97639083862 -2.03081274033,1.74734461308,4.97698831558 -2.02183675766,1.75435709953,5.00055360794 -2.00186228752,1.74937093258,4.99414634705 -1.98288750648,1.74638485909,4.9907336235 -1.97989916801,1.75039064884,5.00651550293 -1.95692622662,1.74440574646,4.9940905571 -1.9419503212,1.74441850185,4.99968576431 -1.92897510529,1.74643158913,5.01325559616 -1.91299962997,1.74644482136,5.01684570312 -1.90102338791,1.74945735931,5.03143167496 -1.88903689384,1.74546480179,5.0232219696 -1.87206292152,1.74447882175,5.02678823471 -1.85508871078,1.74349248409,5.02936267853 -1.84811019897,1.75150370598,5.05596494675 -1.82613706589,1.74551832676,5.0445432663 -1.80816257,1.74253201485,5.04312753677 -1.79318797588,1.74454557896,5.05169773102 -1.78420090675,1.74255239964,5.05148506165 -1.7682261467,1.74256587029,5.05606555939 -1.75125062466,1.74057912827,5.05566310883 -1.73327636719,1.73859286308,5.05424451828 -1.72130036354,1.74260532856,5.06982946396 -1.70232725143,1.73961985111,5.06739425659 -1.68235349655,1.73463392258,5.05997371674 -1.67836368084,1.7386392355,5.07079076767 -1.66738831997,1.74465215206,5.09235620499 -1.64441490173,1.73566651344,5.07394790649 -1.63144016266,1.73967981339,5.08951330185 -1.61346578598,1.73669350147,5.08709859848 -1.59549117088,1.73470687866,5.08369016647 -1.58051645756,1.73572039604,5.09226226807 -1.57152938843,1.73472726345,5.09105348587 -1.55555486679,1.73474061489,5.09563207626 -1.53857958317,1.73275387287,5.09422969818 -1.52660393715,1.73676657677,5.1118106842 -1.50863015652,1.73478043079,5.11038446426 -1.49265491962,1.73479354382,5.11297702789 -1.48166871071,1.73080098629,5.10576057434 -1.46669340134,1.73181402683,5.11234855652 -1.45071864128,1.73182737827,5.11593389511 -1.43474495411,1.73284101486,5.12249851227 -1.41577017307,1.72785449028,5.11309862137 -1.40479421616,1.73486697674,5.13567733765 -1.38182234764,1.72588205338,5.11624383926 -1.37583363056,1.72788798809,5.12305164337 -1.35886001587,1.72690188885,5.12561798096 -1.3448843956,1.72891461849,5.13521242142 -1.33090877533,1.73192739487,5.14580154419 -1.31193590164,1.72894155979,5.14036941528 -1.29496121407,1.72695493698,5.13896036148 -1.28597462177,1.72596204281,5.13874006271 -1.27099978924,1.72697520256,5.14632368088 -1.25402545929,1.72598862648,5.14590740204 -1.23705101013,1.7250020504,5.14549064636 -1.2220761776,1.72601521015,5.15307569504 -1.20710086823,1.72702813148,5.15966701508 -1.19112682343,1.72804152966,5.16523981094 -1.1801404953,1.72304880619,5.15403175354 -1.16616535187,1.7270617485,5.16661405563 -1.14719116688,1.72207546234,5.1552066803 -1.13521540165,1.72808778286,5.1767911911 -1.11724221706,1.72610187531,5.17435884476 -1.09926748276,1.72211515903,5.16595697403 -1.08129346371,1.71912872791,5.15954303741 -1.07530653477,1.72313535213,5.17431688309 -1.05933177471,1.72314858437,5.17690610886 -1.04235732555,1.72216188908,5.17449474335 -1.02738249302,1.72317492962,5.18307924271 -1.01040828228,1.72218835354,5.18166303635 -0.990435838699,1.7162027359,5.16822862625 -0.976460695267,1.72021555901,5.18181419373 -0.967473566532,1.71822226048,5.17760896683 -0.953497946262,1.72223484516,5.18920564651 -0.935523808002,1.7182482481,5.18079423904 -0.919550061226,1.71926188469,5.18736457825 -0.903575539589,1.72027504444,5.19094896317 -0.885601639748,1.71628856659,5.182533741 -0.877614021301,1.71529495716,5.18233394623 -0.863639235497,1.72030794621,5.19891357422 -0.845665812492,1.7173217535,5.19248914719 -0.827691435814,1.71233510971,5.18108320236 -0.813716769218,1.71834802628,5.19866132736 -0.795742869377,1.71436154842,5.18924617767 -0.77976834774,1.71437466145,5.19183349609 -0.771781861782,1.71638154984,5.1976108551 -0.754807293415,1.71339476109,5.19220256805 -0.73983246088,1.71640765667,5.20179080963 -0.720859706402,1.7104216814,5.1883597374 -0.705885231495,1.71443474293,5.19994115829 -0.689910113811,1.7134475708,5.19953918457 -0.680923819542,1.71245467663,5.1973195076 -0.665948688984,1.71446740627,5.2059135437 -0.647975623608,1.71148121357,5.19848299026 -0.63200032711,1.71049380302,5.19608592987 -0.616026818752,1.71250748634,5.20565271378 -0.60005158186,1.7115200758,5.20325613022 -0.582078158855,1.70653378963,5.19183301926 -0.576091110706,1.71554017067,5.21661186218 -0.558116912842,1.70855343342,5.19920444489 -0.541142463684,1.70556652546,5.19079637527 -0.527168095112,1.71457958221,5.21837043762 -0.510193586349,1.71059262753,5.20896434784 -0.478245198727,1.71461892128,5.22012853622 -0.469258159399,1.71062552929,5.20992422104 -0.45228394866,1.70663869381,5.20151233673 -0.4363104105,1.71065211296,5.2130818367 -0.420335352421,1.70966482162,5.21068143845 -0.404361575842,1.71267819405,5.22125530243 -0.3883869946,1.71369099617,5.22384595871 -0.370413988829,1.70870471001,5.20941638947 -0.362425774336,1.70471072197,5.20022964478 -0.346452534199,1.71072423458,5.21779346466 -0.330477625132,1.71073698997,5.21639060974 -0.313503623009,1.7067501545,5.20597553253 -0.297529608011,1.7097632885,5.21555519104 -0.280555814505,1.70677661896,5.20713567734 -0.272568702698,1.70778298378,5.21092748642 -0.256593763828,1.70679581165,5.20752573013 -0.240619719028,1.71080887318,5.21910572052 -0.223645970225,1.70682215691,5.20868635178 -0.207671225071,1.7068349123,5.20828056335 -0.19069801271,1.70584833622,5.20685005188 -0.17472332716,1.70586109161,5.20744276047 -0.166736513376,1.71086776257,5.22022914886 -0.150761887431,1.71188056469,5.22382116318 -0.133787721395,1.70089352131,5.19440984726 -0.117813497782,1.70690643787,5.20899391174 -0.100840359926,1.70692002773,5.20856285095 -0.0848658531904,1.70993280411,5.21815299988 -0.0688910856843,1.70894539356,5.21674823761 -0.0599051378667,1.70595240593,5.20652246475 -0.043930541724,1.7089651823,5.21611452103 -0.0279557388276,1.70597779751,5.20671033859 -0.0109826298431,1.70899128914,5.21327877045 --0.0109823597595,1.71600878239,5.11271572113 --0.0269566886127,1.71502172947,5.11030244827 --0.0429311655462,1.72003448009,5.12289190292 --0.0599038302898,1.71704804897,5.11445140839 --0.075878597796,1.72406065464,5.13504648209 --0.083865173161,1.71306741238,5.10482788086 --0.099840298295,1.72507977486,5.13542985916 --0.115813978016,1.71609282494,5.10900402069 --0.131788700819,1.72010540962,5.11959838867 --0.146763190627,1.70511806011,5.07918262482 --0.163736760616,1.71313130856,5.10075950623 --0.171723797917,1.71313774586,5.09755086899 --0.187698930502,1.71915006638,5.11415338516 --0.203672289848,1.71216320992,5.09372091293 --0.220646381378,1.72117602825,5.11730861664 --0.235621571541,1.71618831158,5.10290622711 --0.252594798803,1.719201684,5.10947704315 --0.267570406199,1.71721374989,5.1030831337 --0.276556372643,1.71922063828,5.107858181 --0.290532141924,1.71023273468,5.08246183395 --0.307505965233,1.71624553204,5.09604454041 --0.323479115963,1.71125876904,5.08060836792 --0.339453756809,1.71227133274,5.08320045471 --0.355429053307,1.7162835598,5.09280633926 --0.370402276516,1.70629668236,5.06336593628 --0.379389405251,1.71230316162,5.079164505 --0.39536473155,1.71631526947,5.0877699852 --0.412337988615,1.71832847595,5.09134149551 --0.42631277442,1.70934081078,5.06492614746 --0.442287266254,1.70935332775,5.06551599503 --0.460261464119,1.71936607361,5.09011030197 --0.475235253572,1.71337890625,5.07068061829 --0.485221773386,1.72038555145,5.09047269821 --0.49919757247,1.71639740467,5.07507658005 --0.516171276569,1.71841037273,5.08065605164 --0.531145215034,1.7134231329,5.06422948837 --0.549120187759,1.72343540192,5.08983945847 --0.564093649387,1.71744835377,5.07040309906 --0.573081254959,1.72245442867,5.08321046829 --0.584056973457,1.70646607876,5.03779697418 --0.60303068161,1.71647906303,5.06338787079 --0.620003700256,1.71749222279,5.06295347214 --0.633979678154,1.71350395679,5.05156040192 --0.652952194214,1.72051739693,5.06712722778 --0.665927827358,1.71352922916,5.04472208023 --0.672915518284,1.71153509617,5.03751945496 --0.691888928413,1.7195482254,5.05710315704 --0.707863211632,1.71956062317,5.05468893051 --0.726836442947,1.72657370567,5.07227134705 --0.739812076092,1.72058558464,5.05086421967 --0.756786584854,1.72359800339,5.05745887756 --0.77076113224,1.71861028671,5.04003810883 --0.782746732235,1.72661721706,5.06282377243 --0.794722855091,1.71862888336,5.03742074966 --0.812696754932,1.72364151478,5.04800844193 --0.828670918941,1.72365403175,5.04459190369 --0.844645619392,1.72466623783,5.04318332672 --0.859619379044,1.72067892551,5.03075265884 --0.866607248783,1.71968472004,5.02555370331 --0.882581472397,1.71969711781,5.02213573456 --0.900555729866,1.72470963001,5.03273057938 --0.9195291996,1.73072254658,5.04631614685 --0.936504125595,1.73373472691,5.05191707611 --0.948478877544,1.72474658489,5.02448940277 --0.971451282501,1.73876011372,5.05807495117 --0.977438807487,1.73476600647,5.04486274719 --0.991414010525,1.7307779789,5.03245401382 --1.00938892365,1.736790061,5.04305839539 --1.02736222744,1.73880290985,5.04763507843 --1.03833758831,1.72981452942,5.01821327209 --1.05731165409,1.73582720757,5.03080654144 --1.0712864399,1.73283910751,5.01738929749 --1.08127355576,1.7368452549,5.0271935463 --1.10024738312,1.74185800552,5.03778123856 --1.11822128296,1.745870471,5.04336833954 --1.13319575787,1.74388277531,5.03394889832 --1.14917111397,1.74489438534,5.03355360031 --1.16514492035,1.74390697479,5.02712488174 --1.17213273048,1.74291276932,5.02192354202 --1.19410598278,1.75292563438,5.04552078247 --1.20408117771,1.74293720722,5.01308870316 --1.22505521774,1.75194990635,5.03269100189 --1.23902988434,1.74796175957,5.01926994324 --1.25300514698,1.74597346783,5.00785970688 --1.2719796896,1.75098574162,5.01846218109 --1.27996611595,1.74999201298,5.0142416954 --1.30193889141,1.75900518894,5.03282403946 --1.31191539764,1.75101613998,5.00641679764 --1.33088946342,1.75602853298,5.01501131058 --1.3408652544,1.74703991413,4.98658657074 --1.36083889008,1.75305235386,4.99817848206 --1.37781357765,1.75506436825,4.99877262115 --1.38480126858,1.75407016277,4.99356937408 --1.40577411652,1.76008307934,5.00614881516 --1.41575014591,1.75209438801,4.97973012924 --1.43672347069,1.75910699368,4.99331951141 --1.4516992569,1.75911843777,4.98792314529 --1.46867346764,1.76013052464,4.98650693893 --1.47865951061,1.76213717461,4.98928785324 --1.49963402748,1.77014935017,5.00489854813 --1.5136089325,1.76716113091,4.99247789383 --1.53158295155,1.77017331123,4.99406290054 --1.54455924034,1.76718437672,4.98166513443 --1.55553424358,1.76019585133,4.95823192596 --1.57950782776,1.7712085247,4.98183917999 --1.58249616623,1.76521396637,4.9626250267 --1.60646831989,1.77522706985,4.98220682144 --1.61944377422,1.77123844624,4.96779203415 --1.63541913033,1.77225005627,4.96439027786 --1.64939463139,1.77026152611,4.95398139954 --1.66836798191,1.77327382565,4.95655632019 --1.68334400654,1.77328503132,4.95116329193 --1.69233047962,1.77429139614,4.94994354248 --1.70630633831,1.77330255508,4.94054174423 --1.72228097916,1.7733143568,4.93512487411 --1.74425458908,1.78032684326,4.94872379303 --1.75623059273,1.77633786201,4.93231153488 --1.77520430088,1.77935016155,4.93489265442 --1.78219163418,1.77835595608,4.92867898941 --1.80016601086,1.78136789799,4.9292678833 --1.81314253807,1.77937877178,4.91787242889 --1.83011710644,1.78039062023,4.91546010971 --1.84809160233,1.78340232372,4.91605091095 --1.8740644455,1.79441511631,4.93865060806 --1.8780412674,1.78142571449,4.89820861816 --1.88902795315,1.78443181515,4.90400743484 --1.9090025425,1.7894436121,4.9106092453 --1.92397809029,1.78945493698,4.90320205688 --1.9389526844,1.78746664524,4.89377689362 --1.95292818546,1.78647780418,4.8833656311 --1.97390210629,1.79148983955,4.89095830917 --1.99087750912,1.79450118542,4.8895611763 --1.99786436558,1.79250729084,4.88233757019 --2.00884151459,1.78851759434,4.86593770981 --2.02781558037,1.79152953625,4.86752462387 --2.042791605,1.7915405035,4.86112737656 --2.06676363945,1.79955351353,4.8726978302 --2.07674098015,1.79456377029,4.85430002213 --2.09472608566,1.80457079411,4.87509584427 --2.10470294952,1.79958128929,4.85568809509 --2.12467718124,1.80359315872,4.85927820206 --2.13265419006,1.79660344124,4.83486366272 --2.1516289711,1.80061507225,4.8364572525 --2.16660380363,1.79962646961,4.82703256607 --2.18657803535,1.80363833904,4.83062648773 --2.19456505775,1.80364429951,4.82640790939 --2.21154046059,1.80565536022,4.82401037216 --2.22351694107,1.80266594887,4.80960178375 --2.24749016762,1.81067824364,4.82119226456 --2.25946617126,1.80668902397,4.80577373505 --2.2784409523,1.81070065498,4.80636501312 --2.29241609573,1.80871188641,4.79494285583 --2.3064031601,1.81471765041,4.80676031113 --2.31538009644,1.80972802639,4.78534269333 --2.33535456657,1.8137396574,4.78793668747 --2.35032963753,1.81275093555,4.77851343155 --2.37230420113,1.81876242161,4.78612041473 --2.38527989388,1.81677341461,4.7726984024 --2.39326763153,1.81677901745,4.76949214935 --2.41024327278,1.81878995895,4.76609182358 --2.42521834373,1.81880104542,4.75666904449 --2.44119477272,1.81981158257,4.75228023529 --2.45717024803,1.82082259655,4.74586963654 --2.48014354706,1.82683467865,4.75245380402 --2.48812174797,1.82184457779,4.73104858398 --2.4991080761,1.8238505125,4.73283529282 --2.51208376884,1.82186150551,4.71941137314 --2.52906036377,1.82387197018,4.71702623367 --2.54903411865,1.82788360119,4.71660089493 --2.57000875473,1.83189499378,4.72020101547 --2.57598686218,1.82590460777,4.69478797913 --2.60295939445,1.83391714096,4.7073674202 --2.60694789886,1.83192229271,4.69615602493 --2.62592387199,1.83493292332,4.69676828384 --2.63690090179,1.83194303513,4.68136262894 --2.65287637711,1.8329539299,4.67394542694 --2.67385101318,1.83796525002,4.67654180527 --2.6878259182,1.83597624302,4.66410827637 --2.7028131485,1.84198200703,4.67492771149 --2.71179008484,1.83799219131,4.65450239182 --2.73076581955,1.84100294113,4.65410900116 --2.74774074554,1.84201407433,4.64768600464 --2.75871801376,1.84002411366,4.63227748871 --2.78169250488,1.84603536129,4.63787794113 --2.79066991806,1.84204530716,4.61846113205 --2.80065774918,1.84405064583,4.61926841736 --2.8136343956,1.84206104279,4.60685491562 --2.83960723877,1.85007297993,4.61543655396 --2.8455851078,1.84408259392,4.59101629257 --2.87655806541,1.85509455204,4.60962581635 --2.88253617287,1.84910416603,4.58520412445 --2.89751315117,1.85011422634,4.5778131485 --2.90050148964,1.84711921215,4.56458806992 --2.92947506905,1.85713088512,4.57919549942 --2.93645262718,1.85114049911,4.55677556992 --2.94743037224,1.84915018082,4.54237604141 --2.97140431404,1.85516178608,4.54696130753 --2.9853811264,1.85517191887,4.53655338287 --2.9963581562,1.85318171978,4.52114057541 --3.01434397697,1.86018800735,4.53294038773 --3.019323349,1.85419690609,4.5095410347 --3.05429506302,1.8672093153,4.53114032745 --3.06327223778,1.86321902275,4.5117149353 --3.07224988937,1.86022877693,4.49330043793 --3.08122825623,1.85723805428,4.47589826584 --3.11121106148,1.87224555016,4.50469970703 --3.11718988419,1.86625468731,4.48229026794 --3.12116837502,1.85926401615,4.4558634758 --3.15114188194,1.86927545071,4.46947097778 --3.15412092209,1.86228454113,4.44204807281 --3.18509435654,1.87329602242,4.45665550232 --3.19807124138,1.87230587006,4.44424343109 --3.20106053352,1.86931049824,4.43303585052 --3.21303796768,1.86832022667,4.41962814331 --3.24101138115,1.87733161449,4.42821884155 --3.24299120903,1.86934018135,4.40080785751 --3.26596593857,1.87535107136,4.40240001678 --3.27894377708,1.87436056137,4.39100122452 --3.29392051697,1.87537050247,4.38159322739 --3.29690909386,1.87237536907,4.36936855316 --3.33088159561,1.8843870163,4.38596963882 --3.32586336136,1.87339496613,4.34955596924 --3.35683608055,1.88340651989,4.36114788055 --3.36281514168,1.87841534615,4.33973884583 --3.36979436874,1.87442409992,4.32033729553 --3.39176893234,1.8794349432,4.31891536713 --3.40975546837,1.88644063473,4.32872676849 --3.41073584557,1.87844896317,4.30132007599 --3.43471074104,1.88445961475,4.30290842056 --3.44768810272,1.8844691515,4.29049634933 --3.46366500854,1.8854790926,4.28208875656 --3.47364354134,1.88348805904,4.26668787003 --3.48463058472,1.88549351692,4.26547336578 --3.49560880661,1.88450264931,4.25106859207 --3.51658463478,1.88851296902,4.24865961075 --3.52856230736,1.88752222061,4.2352514267 --3.55453681946,1.89453279972,4.23884534836 --3.55451726913,1.88654100895,4.21042919159 --3.58149170876,1.894551754,4.21502256393 --3.5854818821,1.89255595207,4.20683145523 --3.60345816612,1.89556574821,4.20042276382 --3.60643815994,1.88957417011,4.17600870132 --3.63941073418,1.90058553219,4.18659305573 --3.63939166069,1.892593503,4.15918445587 --3.65736842155,1.89560329914,4.15277767181 --3.66534781456,1.89261186123,4.13537883759 --3.68233418465,1.89861750603,4.14117431641 --3.68931317329,1.89462614059,4.12176179886 --3.71828794479,1.90363657475,4.12836694717 --3.71726822853,1.89564478397,4.09893751144 --3.73524522781,1.8986543417,4.09253501892 --3.76022100449,1.90566432476,4.09413719177 --3.76220154762,1.89967238903,4.06972980499 --3.78418707848,1.90767836571,4.08052635193 --3.78316855431,1.89968597889,4.05312156677 --3.80914354324,1.90669631958,4.05471229553 --3.81212306023,1.90170490742,4.03028392792 --3.82510113716,1.90171384811,4.01787567139 --3.83608031273,1.90072238445,4.00448465347 --3.85305738449,1.90273165703,3.99607205391 --3.85904693604,1.90273594856,3.98987650871 --3.87102484703,1.90174520016,3.9754524231 --3.89300131798,1.90675473213,3.97305512428 --3.90298032761,1.90576326847,3.95764899254 --3.91395926476,1.90477192402,3.94324207306 --3.93093657494,1.90678119659,3.93483304977 --3.93992471695,1.90778589249,3.93062114716 --3.95890235901,1.91179490089,3.92522954941 --3.96888136864,1.9098033905,3.90982341766 --3.97586154938,1.90781164169,3.89141607285 --3.98983883858,1.90782082081,3.87899327278 --4.01081562042,1.91183018684,3.87458896637 --4.02279424667,1.91183876991,3.86118268967 --4.03478193283,1.91484355927,3.85997438431 --4.05275964737,1.91785252094,3.85257220268 --4.05574035645,1.91286051273,3.83016061783 --4.06671953201,1.91186904907,3.81575369835 --4.08369779587,1.91487777233,3.80735206604 --4.10067462921,1.9168869257,3.79793453217 --4.10965538025,1.91589486599,3.78254246712 --4.11564445496,1.91589915752,3.77533125877 --4.13062286377,1.91690778732,3.764929533 --4.14060115814,1.91591644287,3.74850463867 --4.15358018875,1.91592478752,3.73610067368 --4.16256046295,1.91493272781,3.72070741653 --4.17753839493,1.91594147682,3.7092897892 --4.19151639938,1.91695022583,3.69687080383 --4.20350551605,1.91995453835,3.69668769836 --4.21748399734,1.92096316814,3.68426990509 --4.22946310043,1.92097139359,3.67086553574 --4.24544095993,1.9229799509,3.66045260429 --4.26242017746,1.92598831654,3.65206003189 --4.27739810944,1.92699694633,3.64064693451 --4.28737831116,1.92700505257,3.62523889542 --4.31036376953,1.93501031399,3.63303637505 --4.34034061432,1.94301939011,3.63564705849 --4.36631679535,1.95002865791,3.63323330879 --4.36929750443,1.94603598118,3.61182713509 --4.38527679443,1.94804441929,3.60142254829 --4.41125392914,1.95505309105,3.60003113747 --4.42623186111,1.95606148243,3.58760857582 --4.44521903992,1.96206641197,3.59140753746 --4.44620132446,1.95807349682,3.56901144981 --4.4521818161,1.95508122444,3.54959535599 --4.46916055679,1.95808935165,3.54019808769 --4.48413944244,1.95909762383,3.52777767181 --4.47212362289,1.94810426235,3.49436569214 --4.47911310196,1.94910812378,3.48816156387 --4.48409414291,1.94611561298,3.46875548363 --4.48207616806,1.94012284279,3.44333863258 --4.48305797577,1.93513000011,3.42093157768 --4.48803901672,1.93313741684,3.40152072906 --4.49302005768,1.93014502525,3.38210892677 --4.5030002594,1.92915272713,3.36669993401 --4.49099349976,1.92115569115,3.34548401833 --4.49897384644,1.92016327381,3.32908201218 --4.50495481491,1.91817069054,3.31067061424 --4.51893424988,1.91917860508,3.29825901985 --4.51291704178,1.91218554974,3.2708439827 --4.5128993988,1.90719258785,3.2484369278 --4.50188350677,1.89719903469,3.21802830696 --4.51687240601,1.90220332146,3.21782422066 --4.51185560226,1.89520990849,3.19242429733 --4.51183795929,1.89021706581,3.17001056671 --4.52181768417,1.89022481441,3.15459275246 --4.52279996872,1.88623189926,3.13318133354 --4.53178024292,1.88523936272,3.11777591705 --4.54176092148,1.88524663448,3.10337567329 --4.54075193405,1.88325035572,3.09115982056 --4.54773330688,1.88125753403,3.07476067543 --4.55771350861,1.88126516342,3.05934047699 --4.55969619751,1.87827193737,3.03994822502 --4.56967639923,1.87827956676,3.02452754974 --4.57665777206,1.87728667259,3.00812625885 --4.57064151764,1.87029337883,2.98271846771 --4.57863092422,1.87129712105,2.97751712799 --4.61160755157,1.88130557537,2.97811055183 --4.62958717346,1.88531315327,2.96870517731 --4.63456869125,1.88332033157,2.95029091835 --4.6485490799,1.88532745838,2.9388988018 --4.6475315094,1.88033437729,2.91648077965 --4.65252113342,1.8803383112,2.90826106071 --4.67949914932,1.88734602928,2.90486454964 --4.67148351669,1.8803524971,2.87845277786 --4.68246412277,1.8813598156,2.86403989792 --4.69144582748,1.88136661053,2.84965205193 --4.70542573929,1.88337397575,2.83724284172 --4.7164068222,1.88338112831,2.82283091545 --4.71439886093,1.8813842535,2.81163668633 --4.73037862778,1.88339161873,2.8002243042 --4.73436117172,1.88139843941,2.7818171978 --4.74034261703,1.88040542603,2.76440572739 --4.73832511902,1.87541210651,2.74198842049 --4.7543053627,1.87841939926,2.73057699203 --4.75028848648,1.87342607975,2.70716094971 --4.77527713776,1.88142967224,2.71298766136 --4.78925704956,1.88343703747,2.69956207275 --4.78624153137,1.87944328785,2.67817282677 --4.78922319412,1.87645018101,2.65875339508 --4.80620288849,1.87945747375,2.64733409882 --4.81918478012,1.88146412373,2.63494181633 --4.84316301346,1.88747131824,2.62752723694 --4.82115888596,1.87747383118,2.60532832146 --4.83313941956,1.87848103046,2.59090685844 --4.86111831665,1.88648808002,2.58651137352 --4.86110162735,1.88349461555,2.56610274315 --4.86208438873,1.87950098515,2.54670262337 --4.86806678772,1.87950766087,2.529286623 --4.87804889679,1.87951421738,2.51488900185 --4.87404108047,1.87651729584,2.50268507004 --4.89102172852,1.87952423096,2.49127316475 --4.89100456238,1.87653064728,2.47085952759 --4.90198564529,1.87753725052,2.4564511776 --4.92696619034,1.88454401493,2.45006012917 --4.9269490242,1.88155043125,2.42964553833 --4.93293142319,1.88055694103,2.41222882271 --4.94592094421,1.88356029987,2.40903043747 --4.95190429688,1.88356649876,2.3926346302 --4.96288633347,1.88457298279,2.37822914124 --4.97286748886,1.88557958603,2.36281323433 --4.97485113144,1.88358569145,2.34441661835 --4.99283218384,1.88759219646,2.33300352097 --5.00481367111,1.88859879971,2.31859016418 --5.00280666351,1.88660168648,2.30840039253 --5.00378990173,1.88360786438,2.28899121284 --5.02476978302,1.88961458206,2.27857303619 --5.03475189209,1.88962090015,2.26315975189 --5.04373455048,1.89062702656,2.24775600433 --5.05771684647,1.893633008,2.23536777496 --5.06669950485,1.89363908768,2.21996545792 --5.06369113922,1.89164245129,2.20774054527 --5.07667350769,1.89364850521,2.1943423748 --5.07165718079,1.88865470886,2.17192363739 --5.07364082336,1.88666069508,2.15352225304 --5.0896229744,1.88966679573,2.14111804962 --5.11060380936,1.89567291737,2.13071155548 --5.09559822083,1.88767576218,2.11450910568 --5.11757850647,1.89368200302,2.10409474373 --5.11956262589,1.89168798923,2.08569264412 --5.14554309845,1.89969396591,2.07728862762 --5.15252637863,1.89969980717,2.06088542938 --5.14751148224,1.8947057724,2.03948092461 --5.16249370575,1.89771163464,2.02607107162 --5.17348432541,1.90071451664,2.02086853981 --5.1674695015,1.89572024345,1.99947071075 --5.17645168304,1.89672636986,1.98304963112 --5.17643594742,1.89373219013,1.96364104748 --5.17542076111,1.89173793793,1.94423949718 --5.18940258026,1.89374387264,1.9298197031 --5.20638513565,1.89774954319,1.91741907597 --5.18837881088,1.88975274563,1.90020036697 --5.21036052704,1.89575827122,1.88980269432 --5.21834516525,1.89676368237,1.87441253662 --5.2253279686,1.89676964283,1.85698759556 --5.22931194305,1.89577519894,1.83958673477 --5.23629522324,1.89578080177,1.82318341732 --5.24427890778,1.89678645134,1.80677247047 --5.2452712059,1.89578926563,1.79756867886 --5.24625492096,1.89379513264,1.77814662457 --5.26423740387,1.89880049229,1.76574599743 --5.26022291183,1.89480626583,1.74533987045 --5.26720666885,1.89581167698,1.72893679142 --5.280189991,1.89781713486,1.71453309059 --5.2831735611,1.89682269096,1.69611656666 --5.2861661911,1.89682531357,1.68791902065 --5.2971496582,1.89883077145,1.67250955105 --5.32213163376,1.90683579445,1.66210973263 --5.34411478043,1.91284072399,1.65071237087 --5.34009981155,1.90884625912,1.63030350208 --5.34108352661,1.9068518877,1.61088013649 --5.33607721329,1.90485453606,1.60069513321 --5.35406017303,1.90885961056,1.58728551865 --5.35304546356,1.90686511993,1.56787467003 --5.35103034973,1.90387046337,1.54846978188 --5.35101509094,1.90187609196,1.52905023098 --5.37099838257,1.90688085556,1.5166529417 --5.36998319626,1.90488636494,1.4972397089 --5.38496685028,1.90889120102,1.48283326626 --5.38695955276,1.90889358521,1.47464358807 --5.38894319534,1.90689921379,1.45521068573 --5.41192722321,1.91390359402,1.44382286072 --5.41291236877,1.91290891171,1.42541885376 --5.39689826965,1.90491497517,1.40098512173 --5.40688276291,1.90691971779,1.38559091091 --5.42086696625,1.90992426872,1.37119567394 --5.42085981369,1.9089268446,1.36199581623 --5.41284561157,1.90493249893,1.34057545662 --5.43082904816,1.90893721581,1.32615864277 --5.41381549835,1.90094304085,1.30274343491 --5.44679880142,1.91194677353,1.29335427284 --5.42978525162,1.90395259857,1.26993644238 --5.43077754974,1.90295529366,1.26072955132 --5.440762043,1.90496003628,1.24431586266 --5.45374727249,1.90896427631,1.22993147373 --5.46173191071,1.90996932983,1.2125082016 --5.46971702576,1.91097390652,1.19610786438 --5.48670101166,1.91597807407,1.1817060709 --5.47668743134,1.91098368168,1.16028738022 --5.47468090057,1.90898609161,1.15109586716 --5.48066568375,1.90999090672,1.1336838007 --5.51064968109,1.91899442673,1.1222884655 --5.49663591385,1.91300022602,1.09986364841 --5.50062179565,1.91300487518,1.08246254921 --5.50760698318,1.91400945187,1.0650472641 --5.52859163284,1.92001318932,1.05165731907 --5.52658414841,1.91901576519,1.04144215584 --5.53756999969,1.92101991177,1.02605545521 --5.53355646133,1.91902494431,1.00664675236 --5.53354167938,1.91702997684,0.987219512463 --5.54852676392,1.92103397846,0.971816956997 --5.54251337051,1.91803896427,0.952415049076 --5.55149888992,1.92004311085,0.936016738415 --5.54249238968,1.91604602337,0.924806177616 --5.57047700882,1.92504918575,0.911398530006 --5.5734629631,1.92505383492,0.89298158884 --5.57344913483,1.92305850983,0.874576508999 --5.58143520355,1.92606258392,0.858184874058 --5.58742046356,1.92606711388,0.839756906033 --5.58440732956,1.92407166958,0.821362257004 --5.59939956665,1.92907309532,0.81414937973 --5.59638643265,1.92707777023,0.795754611492 --5.60137224197,1.92808222771,0.777330815792 --5.61235809326,1.93008601665,0.760932207108 --5.62634420395,1.93408954144,0.744524359703 --5.62733030319,1.93409395218,0.726115703583 --5.61131763458,1.92709946632,0.705716490746 --5.62231016159,1.93010115623,0.697500705719 --5.64129638672,1.93610429764,0.682102739811 --5.6422829628,1.93610858917,0.663693964481 --5.63927030563,1.93411302567,0.645296990871 --5.65325593948,1.93811666965,0.62787270546 --5.65924263,1.93912041187,0.610472619534 --5.65822982788,1.9381248951,0.592069506645 --5.67022180557,1.94212627411,0.583856642246 --5.68020915985,1.94412970543,0.5674700737 --5.6671962738,1.93913495541,0.547052979469 --5.66618251801,1.93813955784,0.52762645483 --5.67716932297,1.94114279747,0.511238276958 --5.68015670776,1.94114685059,0.492825031281 --5.70814275742,1.95014870167,0.477422952652 --5.70513677597,1.94915103912,0.468227207661 --5.72012329102,1.95415401459,0.450812280178 --5.71511077881,1.95115840435,0.432418584824 --5.71309757233,1.95016276836,0.412995010614 --5.71108531952,1.94816696644,0.394593775272 --5.71907186508,1.95017051697,0.376173198223 --5.72306585312,1.95217204094,0.367985457182 --5.7440533638,1.9591742754,0.351588338614 --5.74203968048,1.95717847347,0.332165390253 --5.76202774048,1.96418058872,0.315773695707 --5.76501512527,1.96518421173,0.297365784645 --5.75000238419,1.95918977261,0.276939630508 --5.7459897995,1.95719397068,0.258540779352 --5.74698352814,1.95719575882,0.249336972833 --5.77597141266,1.96719694138,0.232939615846 --5.76195812225,1.96120238304,0.212508693337 --5.76894617081,1.96320533752,0.195118889213 --5.76493358612,1.96120977402,0.175696760416 --5.76792144775,1.96221315861,0.157289236784 --5.78390979767,1.96721541882,0.139892607927 --5.76390361786,1.96021926403,0.129686146975 --5.77389097214,1.96322202682,0.111273109913 --5.78987932205,1.96922409534,0.0938791260123 --5.78486680984,1.96722841263,0.0744567140937 --5.78285503387,1.96523225307,0.0560543760657 --5.79084300995,1.96823501587,0.0376459509134 --5.79183101654,1.96823859215,0.0192418992519 --5.80482530594,1.97323906422,0.0100344512612 --5.79281234741,1.96824407578,-0.00938637554646 --5.7718000412,1.96125006676,-0.0288068465889 --5.78778886795,1.96625173092,-0.046192869544 --5.79177713394,1.96725487709,-0.0645975768566 --5.7927646637,1.96725845337,-0.0840240269899 --5.7847533226,1.96526277065,-0.10242831707 --5.79274749756,1.96726369858,-0.11163007468 --5.78773546219,1.96526765823,-0.130034655333 --5.78172302246,1.96327197552,-0.149462729692 --5.79171228409,1.9672743082,-0.167865216732 --5.79570102692,1.96827709675,-0.186268016696 --5.76668834686,1.95828413963,-0.204683542252 --5.77067708969,1.95928704739,-0.223087564111 --5.78967142105,1.96628654003,-0.233303412795 --5.78565979004,1.965290308,-0.25171020627 --5.77764797211,1.96229457855,-0.270119965076 --5.77763700485,1.96229791641,-0.288525104523 --5.78362607956,1.96430051327,-0.306925475597 --5.77761411667,1.96230447292,-0.325335323811 --5.7846031189,1.9653069973,-0.344756454229 --5.74859523773,1.95231330395,-0.352971017361 --5.75158452988,1.9533162117,-0.371374875307 --5.77357435226,1.96131658554,-0.390779674053 --5.76356267929,1.95832109451,-0.409196764231 --5.75955104828,1.95732486248,-0.427607595921 --5.76054000854,1.95732784271,-0.446012049913 --5.74452781677,1.95233333111,-0.464440375566 --5.76052331924,1.9583325386,-0.473620861769 --5.76151180267,1.95933568478,-0.493047565222 --5.75150108337,1.95534002781,-0.51044601202 --5.77149152756,1.96334028244,-0.529841721058 --5.77448034286,1.96434307098,-0.549263417721 --5.75946855545,1.95934820175,-0.566671848297 --5.76446342468,1.96134901047,-0.576887726784 --5.76545286179,1.96235179901,-0.595290482044 --5.76244163513,1.96135520935,-0.613700628281 --5.75342988968,1.95935964584,-0.63212364912 --5.76142024994,1.96236109734,-0.65051150322 --5.75040912628,1.95936596394,-0.668939769268 --5.76639986038,1.96536624432,-0.688330709934 --5.77139472961,1.96736705303,-0.698543429375 --5.762383461,1.96437120438,-0.715945005417 --5.74737167358,1.95937633514,-0.733362317085 --5.77236366272,1.96937525272,-0.75477129221 --5.76135206223,1.96537971497,-0.772179186344 --5.76834249496,1.96938145161,-0.791585981846 --5.7723326683,1.97138345242,-0.810999393463 --5.78632926941,1.97638249397,-0.821183979511 --5.78831911087,1.97838485241,-0.840601086617 --5.81631231308,1.98838269711,-0.861986994743 --5.81430149078,1.98838579655,-0.881412684917 --5.80629110336,1.98638963699,-0.898812234402 --5.8232831955,1.99338924885,-0.920224070549 --5.80727148056,1.98839437962,-0.93662661314 --5.81626272202,1.99239552021,-0.957038998604 --5.84526109695,2.00339150429,-0.970231235027 --5.84425115585,2.00439429283,-0.989650666714 --5.83124017715,2.00039887428,-1.00604450703 --5.85423326492,2.0093972683,-1.0284473896 --5.84822320938,2.00840044022,-1.0468609333 --5.84021234512,2.00640439987,-1.0652821064 --5.86321115494,2.01540112495,-1.07746112347 --5.84319925308,2.00940728188,-1.09388208389 --5.87619400024,2.02140331268,-1.11828112602 --5.86918354034,2.02040672302,-1.13669729233 --5.857172966,2.01741123199,-1.15411174297 --5.8501625061,2.01541447639,-1.17252910137 --5.85115337372,2.0174164772,-1.19193696976 --5.83514690399,2.01142048836,-1.19915294647 --5.83213710785,2.01142311096,-1.21755576134 --5.81012535095,2.0054295063,-1.23297333717 --5.82411813736,2.01142883301,-1.25437009335 --5.84111213684,2.0184276104,-1.27677321434 --5.81709909439,2.01143431664,-1.29220211506 --5.80808877945,2.00943803787,-1.30961024761 --5.81708574295,2.01343727112,-1.32182967663 --5.81607675552,2.01343941689,-1.34022283554 --5.80706644058,2.0114428997,-1.35763144493 --5.80305719376,2.01144576073,-1.37706053257 --5.80004787445,2.01144814491,-1.39546322823 --5.79003763199,2.00945234299,-1.41287839413 --5.77902698517,2.00745630264,-1.43029940128 --5.78302383423,2.0094563961,-1.44049549103 --5.78101444244,2.00945854187,-1.45991504192 --5.7700047493,2.00746250153,-1.47631561756 --5.76599550247,2.00746512413,-1.49472427368 --5.76698684692,2.00946688652,-1.51514983177 --5.75897741318,2.00747013092,-1.53255772591 --5.73696517944,2.00047659874,-1.54697644711 --5.7509636879,2.00747442245,-1.56018149853 --5.7379527092,2.00347876549,-1.57659614086 --5.73594474792,2.00448083878,-1.59499442577 --5.71693277359,1.99848663807,-1.61042308807 --5.72092485428,2.00248742104,-1.63083100319 --5.71191549301,2.00049090385,-1.64824783802 --5.72190904617,2.00549006462,-1.66964054108 --5.70890235901,2.00149393082,-1.67686653137 --5.71489572525,2.00549387932,-1.69725978374 --5.70988750458,2.00549650192,-1.71567463875 --5.68587446213,1.99850356579,-1.72909760475 --5.68786668777,2.00050473213,-1.7495136261 --5.68485879898,2.001506567,-1.76791715622 --5.68184995651,2.00250887871,-1.78734183311 --5.67184400558,1.99951183796,-1.79455399513 --5.65783405304,1.99651646614,-1.80996382236 --5.66082668304,1.99851703644,-1.83037149906 --5.66482019424,2.00251746178,-1.8507720232 --5.66181230545,2.00351929665,-1.86917459965 --5.64179992676,1.99752545357,-1.88360440731 --5.62978982925,1.99452960491,-1.90002536774 --5.63178682327,1.99652969837,-1.91022479534 --5.63577985764,2.0005300045,-1.93164420128 --5.61476802826,1.99453639984,-1.94506418705 --5.6147608757,1.99653744698,-1.9644677639 --5.59474897385,1.9905436039,-1.97788369656 --5.5997428894,1.99454343319,-1.99929428101 --5.58673286438,1.99254786968,-2.01470541954 --5.57672643661,1.98955094814,-2.02192568779 --5.57171869278,1.98955333233,-2.04034352303 --5.58371448517,1.99655115604,-2.06374263763 --5.57770681381,1.99655377865,-2.0811457634 --5.56169557571,1.99255895615,-2.09556007385 --5.54668474197,1.98856377602,-2.1109893322 --5.55268287659,1.99256277084,-2.12319731712 --5.53467130661,1.98756837845,-2.13660860062 --5.54566812515,1.99456632137,-2.1600086689 --5.52565574646,1.98857247829,-2.17343688011 --5.51964759827,1.98857498169,-2.19084143639 --5.50663757324,1.98657929897,-2.20625972748 --5.50763130188,1.98857975006,-2.22667169571 --5.50462675095,1.98858106136,-2.23588418961 --5.50362014771,1.99058198929,-2.25529050827 --5.47060441971,1.9805918932,-2.26372671127 --5.48560285568,1.98858845234,-2.28912734985 --5.46158981323,1.98259592056,-2.29953527451 --5.46358394623,1.98559594154,-2.32095766068 --5.46257781982,1.98759686947,-2.34036254883 --5.44156837463,1.98060309887,-2.34258151054 --5.43856143951,1.98260462284,-2.36098337173 --5.45055913925,1.9896017313,-2.3864004612 --5.4165430069,1.97861206532,-2.39281892776 --5.41153526306,1.9796141386,-2.41123771667 --5.41853141785,1.98461258411,-2.43363308907 --5.38551568985,1.97462272644,-2.44107079506 --5.38551235199,1.97562289238,-2.45127868652 --5.3875079155,1.97962284088,-2.47167611122 --5.38150024414,1.98062503338,-2.49010300636 --5.36949062347,1.97862899303,-2.50552248955 --5.37948799133,1.98462629318,-2.52992606163 --5.33746910095,1.97163951397,-2.53235507011 --5.33746337891,1.97363972664,-2.55276823044 --5.34946489334,1.98063611984,-2.56796550751 --5.32145023346,1.97164511681,-2.57639336586 --5.31244182587,1.97164821625,-2.59280872345 --5.31243610382,1.97364842892,-2.61321997643 --5.30242776871,1.97365176678,-2.62964463234 --5.28841781616,1.97065627575,-2.64304709435 --5.27940940857,1.96965944767,-2.65946292877 --5.26039981842,1.96366548538,-2.66169071198 --5.26439666748,1.96866440773,-2.68410253525 --5.25138664246,1.96666872501,-2.69851827621 --5.23537635803,1.96367394924,-2.71092414856 --5.22236680984,1.96167826653,-2.72534203529 --5.23736715317,1.96967339516,-2.75274038315 --5.21435403824,1.96368086338,-2.76215815544 --5.19334363937,1.95768785477,-2.76339435577 --5.19533967972,1.96168720722,-2.78480195999 --5.17732858658,1.95769309998,-2.79621315002 --5.17232179642,1.95869469643,-2.8146314621 --5.18132066727,1.96569144726,-2.84004402161 --5.14830350876,1.95570266247,-2.84447431564 --5.14329767227,1.95670425892,-2.8618721962 --5.14929676056,1.96070194244,-2.87609100342 --5.12428331375,1.95371043682,-2.88350152969 --5.12227773666,1.95671093464,-2.9039273262 --5.11126947403,1.95571446419,-2.91832947731 --5.09625864029,1.95271945,-2.93175578117 --5.10125684738,1.95771729946,-2.95516300201 --5.08224487305,1.95372378826,-2.96659445763 --5.06323480606,1.94773030281,-2.96680641174 --5.04322290421,1.94273722172,-2.97621226311 --5.05422353745,1.95073282719,-3.00362992287 --5.03120994568,1.94474077225,-3.01205134392 --5.01519918442,1.94274604321,-3.02447509766 --5.00819253922,1.94274818897,-3.04189562798 --5.01419305801,1.94674575329,-3.05508589745 --5.0051856041,1.94674861431,-3.07150912285 --4.98517370224,1.94275546074,-3.08092164993 --4.96916246414,1.93976080418,-3.09334850311 --4.97416114807,1.94475841522,-3.11674618721 --4.95614957809,1.94176459312,-3.12817788124 --4.9441409111,1.9407684803,-3.14259839058 --4.92713165283,1.93477451801,-3.14280200005 --4.92612791061,1.93877434731,-3.163210392 --4.91311836243,1.93677866459,-3.1776444912 --4.90611219406,1.93778049946,-3.19404506683 --4.89310312271,1.93678486347,-3.20848011971 --4.88609600067,1.93678677082,-3.22488021851 --4.87308740616,1.93579101562,-3.23931622505 --4.87208509445,1.93679106236,-3.24850463867 --4.85307312012,1.93279767036,-3.25893759727 --4.83206033707,1.92880523205,-3.26735830307 --4.82905578613,1.93080544472,-3.28676772118 --4.81204462051,1.92781126499,-3.29819822311 --4.80103683472,1.92681491375,-3.3126115799 --4.80103397369,1.93081378937,-3.33402013779 --4.78902673721,1.92881822586,-3.33723330498 --4.78402137756,1.93081915379,-3.3566660881 --4.77201271057,1.92882299423,-3.37007308006 --4.76200580597,1.92882597446,-3.3854932785 --4.74599504471,1.92683160305,-3.39589619637 --4.73798847198,1.92683386803,-3.41230964661 --4.72497940063,1.92583799362,-3.42573189735 --4.7239780426,1.92783772945,-3.43695640564 --4.70196437836,1.92184603214,-3.44336485863 --4.6859536171,1.91985142231,-3.45479083061 --4.68795251846,1.92484927177,-3.4782037735 --4.67994642258,1.92585134506,-3.49461722374 --4.67694330215,1.92885124683,-3.51503777504 --4.64992666245,1.92186164856,-3.51846337318 --4.64492273331,1.92186319828,-3.52566480637 --4.63191366196,1.91986727715,-3.53908991814 --4.62090587616,1.91987073421,-3.55350708961 --4.61089897156,1.91987359524,-3.56892943382 --4.60989713669,1.92387247086,-3.59033870697 --4.58888339996,1.91988027096,-3.59776473045 --4.57487392426,1.91788506508,-3.61018681526 --4.56987047195,1.91788649559,-3.61738872528 --4.56386613846,1.91988742352,-3.63581061363 --4.5478553772,1.91789317131,-3.646225214 --4.52784252167,1.91390073299,-3.65364217758 --4.52483987808,1.91690015793,-3.67405772209 --4.51283168793,1.9159040451,-3.68747210503 --4.49882268906,1.91490876675,-3.69989752769 --4.48881578445,1.91291248798,-3.70411705971 --4.48081016541,1.91391444206,-3.72052979469 --4.47380542755,1.91591572762,-3.73794579506 --4.47280406952,1.9199141264,-3.76036429405 --4.43978309631,1.90992808342,-3.75779628754 --4.44478559494,1.91792356968,-3.78419876099 --4.42377185822,1.91293168068,-3.790620327 --4.41876888275,1.91293311119,-3.79782295227 --4.40475940704,1.91193771362,-3.81025123596 --4.40976285934,1.91893315315,-3.83664798737 --4.38474607468,1.91294312477,-3.84109711647 --4.36973667145,1.91094851494,-3.85150551796 --4.34972333908,1.90695619583,-3.85893678665 --4.35372638702,1.9119528532,-3.87414646149 --4.33871650696,1.90995824337,-3.88455605507 --4.32670879364,1.90996181965,-3.89899206161 --4.31770277023,1.90996408463,-3.91338133812 --4.31470155716,1.91396307945,-3.93480229378 --4.28568172455,1.90597558022,-3.93423557281 --4.29468917847,1.9159681797,-3.9656457901 --4.27567672729,1.91197550297,-3.97306632996 --4.26266765594,1.90898108482,-3.97428846359 --4.25366210938,1.9099830389,-3.99071240425 --4.23865222931,1.90798842907,-4.00010824203 --4.22364282608,1.90699362755,-4.01153993607 --4.2266459465,1.91398918629,-4.03794717789 --4.19562530518,1.90500307083,-4.03539037704 --4.2026309967,1.91099774837,-4.05359220505 --4.18862199783,1.91000247002,-4.06500816345 --4.17361211777,1.90800774097,-4.07542324066 --4.14859485626,1.90201842785,-4.07786369324 --4.14459371567,1.90601789951,-4.09725761414 --4.12758255005,1.90402412415,-4.10770750046 --4.11857748032,1.90502595901,-4.12311267853 --4.11557579041,1.90602612495,-4.13231658936 --4.09356117249,1.90203535557,-4.13674736023 --4.0885591507,1.90503489971,-4.15717172623 --4.08455848694,1.90903389454,-4.17757797241 --4.06154203415,1.90404379368,-4.18101119995 --4.03752565384,1.89705431461,-4.18242931366 --4.02852058411,1.89905619621,-4.19885110855 --4.02551984787,1.90105628967,-4.20805358887 --4.00550603867,1.8970644474,-4.21347522736 --3.99550008774,1.89806687832,-4.22889661789 --3.9814915657,1.89707136154,-4.241335392 --3.97048544884,1.8980743885,-4.25575685501 --3.95447492599,1.89608049393,-4.26416397095 --3.94146704674,1.89608466625,-4.27658653259 --3.92345356941,1.89009356499,-4.27181339264 --3.92045402527,1.89509177208,-4.29321336746 --3.90444350243,1.89309775829,-4.30263900757 --3.88843297958,1.89110374451,-4.31206512451 --3.89243984222,1.89909732342,-4.34147071838 --3.87042427063,1.89510691166,-4.34490346909 --3.86242103577,1.89710783958,-4.36232042313 --3.85341501236,1.89611160755,-4.36552715302 --3.83540296555,1.89311873913,-4.37295722961 --3.81739068031,1.89112603664,-4.38038873672 --3.80738568306,1.89212810993,-4.39580821991 --3.78837275505,1.88913619518,-4.40122652054 --3.77536511421,1.8891402483,-4.41365146637 --3.77736878395,1.89313685894,-4.42885541916 --3.75335121155,1.88714802265,-4.42928504944 --3.74534797668,1.8901488781,-4.44670009613 --3.72733569145,1.8871563673,-4.45311975479 --3.71432828903,1.88716042042,-4.46554517746 --3.700319767,1.887165308,-4.47595691681 --3.69732189178,1.89216256142,-4.49937295914 --3.67530560493,1.88717269897,-4.50180482864 --3.67931199074,1.89316749573,-4.52001285553 --3.64828705788,1.88318407536,-4.5114402771 --3.63427877426,1.88318872452,-4.52286958694 --3.62427425385,1.88519084454,-4.5372710228 --3.61226773262,1.8851941824,-4.55069351196 --3.592253685,1.88220286369,-4.55614185333 --3.58825230598,1.88320338726,-4.56433916092 --3.57724690437,1.88520598412,-4.57875871658 --3.56624174118,1.88620865345,-4.59317731857 --3.54422497749,1.88121914864,-4.59460496902 --3.52721357346,1.87922596931,-4.60203075409 --3.50519704819,1.87523663044,-4.6034617424 --3.51020860672,1.885227561,-4.63686418533 --3.48618650436,1.87524235249,-4.62209367752 --3.48218894005,1.88123977184,-4.64551448822 --3.46017217636,1.87625038624,-4.64694833755 --3.44716477394,1.87625467777,-4.65734577179 --3.4311542511,1.87526094913,-4.66577148438 --3.41614484787,1.87426626682,-4.67620801926 --3.39713144302,1.8712747097,-4.68164777756 --3.39913702011,1.87627065182,-4.69683027267 --3.37712001801,1.87128138542,-4.69827032089 --3.36411309242,1.87228524685,-4.71069860458 --3.35210680962,1.87228870392,-4.72310590744 --3.33909988403,1.87329256535,-4.73553323746 --3.3240904808,1.87229812145,-4.74495649338 --3.30407571793,1.86930751801,-4.7483921051 --3.29707145691,1.86930990219,-4.75360155106 --3.28907036781,1.87231004238,-4.77201604843 --3.26805400848,1.86832046509,-4.77344512939 --3.25805044174,1.87032210827,-4.78885555267 --3.23503160477,1.86533427238,-4.78728437424 --3.22502851486,1.86833572388,-4.80370903015 --3.22303056717,1.8703340292,-4.81591701508 --3.20101284981,1.86634540558,-4.8153424263 --3.1910097599,1.86834681034,-4.83176517487 --3.17399811745,1.86635410786,-4.8381896019 --3.15999007225,1.86635887623,-4.84860944748 --3.14998722076,1.86936032772,-4.86503124237 --3.12596654892,1.8633736372,-4.86146116257 --3.11796116829,1.86237704754,-4.8646645546 --3.09894704819,1.86038589478,-4.86910533905 --3.08293604851,1.85839271545,-4.87551307678 --3.07293343544,1.86139392853,-4.89193439484 --3.05792474747,1.86139929295,-4.90237569809 --3.04191422462,1.86040604115,-4.90979766846 --3.02690505981,1.86041164398,-4.91922664642 --3.02090215683,1.8604131937,-4.92542982101 --3.00188755989,1.85742259026,-4.92784833908 --2.98587727547,1.85642898083,-4.93628549576 --2.97887897491,1.86142754555,-4.95669317245 --2.95886301994,1.85843765736,-4.95913505554 --2.94285225868,1.85644447803,-4.9655456543 --2.93084740639,1.85844731331,-4.97997808456 --2.92384362221,1.85844969749,-4.98518848419 --2.90182471275,1.85446178913,-4.98362398148 --2.88681507111,1.85346794128,-4.99102878571 --2.8758122921,1.85646951199,-5.00746488571 --2.85980153084,1.85547626019,-5.01489067078 --2.84078645706,1.85248601437,-5.01630496979 --2.82978343964,1.85448765755,-5.03273868561 --2.8177728653,1.85249459743,-5.03096866608 --2.80777049065,1.85449588299,-5.0463681221 --2.79576611519,1.85649847984,-5.06079673767 --2.77975583076,1.85650515556,-5.06822395325 --2.76274371147,1.85451292992,-5.07364845276 --2.75274276733,1.85851359367,-5.09107017517 --2.73472929001,1.85652208328,-5.09550380707 --2.73072981834,1.85852181911,-5.10469865799 --2.7147192955,1.8575284481,-5.11212587357 --2.7027156353,1.85953092575,-5.12655162811 --2.67969417572,1.8545447588,-5.12198781967 --2.66468501091,1.85455060005,-5.13040685654 --2.6596930027,1.86154556274,-5.15783262253 --2.64167165756,1.85455930233,-5.14405822754 --2.62065243721,1.84957170486,-5.14147996902 --2.61966705322,1.86056232452,-5.17589759827 --2.59363937378,1.85158026218,-5.16331291199 --2.57662796974,1.85058760643,-5.1707649231 --2.56863117218,1.85658562183,-5.19218063354 --2.54761171341,1.851598382,-5.18859577179 --2.54161024094,1.85259926319,-5.19681787491 --2.53261160851,1.85759854317,-5.21622991562 --2.50658392906,1.84961640835,-5.20466709137 --2.49057340622,1.84862315655,-5.21209859848 --2.47957205772,1.85262441635,-5.22851991653 --2.46055531502,1.84863519669,-5.2279291153 --2.43452692032,1.84065330029,-5.21637535095 --2.42551922798,1.83965826035,-5.21657657623 --2.40850758553,1.83866584301,-5.22302246094 --2.39550185204,1.83966970444,-5.23443317413 --2.38550257683,1.84366977215,-5.25285148621 --2.36748933792,1.84267854691,-5.25729799271 --2.3574898243,1.8466783762,-5.27571344376 --2.34849333763,1.85267674923,-5.29713726044 --2.33146953583,1.84369182587,-5.2803401947 --2.32547926903,1.85268604755,-5.3087682724 --2.30546140671,1.84869766235,-5.3082075119 --2.28945040703,1.8477050066,-5.31362009048 --2.27243900299,1.84771263599,-5.32006597519 --2.25542593002,1.84572124481,-5.32348108292 --2.24041795731,1.84672665596,-5.33291244507 --2.23141002655,1.84573185444,-5.33311700821 --2.20938777924,1.8397462368,-5.32755756378 --2.19437837601,1.83975243568,-5.33497047424 --2.17335700989,1.83576643467,-5.32939195633 --2.15734696388,1.8357732296,-5.33682823181 -1.87407243252,1.77222454548,-4.57353973389 -1.88106238842,1.76421701908,-4.54694509506 -1.88806569576,1.76321685314,-4.54214954376 -1.91009187698,1.76922500134,-4.55255174637 -1.92710578442,1.77122759819,-4.54996061325 -1.94412064552,1.77323079109,-4.54935073853 -1.95010900497,1.76422274113,-4.52076101303 -1.98115611076,1.77923977375,-4.55314731598 -1.98513972759,1.76822960377,-4.51956415176 -2.00116372108,1.77523815632,-4.53576564789 -2.00414538383,1.76422739029,-4.50018310547 -2.03218460083,1.77524089813,-4.52457094193 -2.04519081116,1.77424061298,-4.51495790482 -2.0581946373,1.77123904228,-4.50138521194 -2.06117844582,1.76122927666,-4.46779346466 -2.08520698547,1.76823806763,-4.48020505905 -2.09822368622,1.77324354649,-4.48940086365 -2.10521602631,1.7652374506,-4.46481180191 -2.1242351532,1.7692425251,-4.46820020676 -2.14225053787,1.77124607563,-4.46760749817 -2.15325212479,1.76824367046,-4.45201635361 -2.16826200485,1.76824486256,-4.44541978836 -2.18127846718,1.77325034142,-4.45460987091 -2.19729018211,1.77325224876,-4.45001316071 -2.21630787849,1.77725672722,-4.4514169693 -2.23432374001,1.77926051617,-4.45180892944 -2.24131679535,1.77225458622,-4.42624187469 -2.26935315132,1.78326678276,-4.44861078262 -2.28035521507,1.78026485443,-4.43401193619 -2.29036450386,1.78226733208,-4.43521738052 -2.29635691643,1.77526128292,-4.40963363647 -2.3193821907,1.78126895428,-4.42001914978 -2.33439183235,1.78126990795,-4.41243124008 -2.34739732742,1.77926945686,-4.40084552765 -2.36140561104,1.7792699337,-4.39224767685 -2.39144325256,1.7912825346,-4.41562747955 -2.38442111015,1.77927219868,-4.38285446167 -2.40744543076,1.78627920151,-4.39125347137 -2.41444039345,1.77927458286,-4.36866855621 -2.44347596169,1.79128623009,-4.39004087448 -2.45047044754,1.78428113461,-4.36548042297 -2.47048926353,1.7882860899,-4.36886882782 -2.47748494148,1.7822817564,-4.34628820419 -2.4904999733,1.78728652,-4.3544678688 -2.4984972477,1.78128266335,-4.33289909363 -2.51751422882,1.78528702259,-4.3342871666 -2.53853416443,1.79029214382,-4.33769178391 -2.5485355854,1.78629028797,-4.3220949173 -2.5665500164,1.78829324245,-4.31950855255 -2.56954789162,1.78629124165,-4.30870485306 -2.58656048775,1.78729367256,-4.30412149429 -2.59856557846,1.78529310226,-4.29153203964 -2.61758208275,1.78829705715,-4.29192733765 -2.63259243965,1.78929877281,-4.28631353378 -2.64459729195,1.78729808331,-4.27273750305 -2.67062449455,1.79530632496,-4.28512334824 -2.6716196537,1.79130327702,-4.27132034302 -2.70065116882,1.80131292343,-4.28771352768 -2.69863462448,1.79030418396,-4.25114297867 -2.72365999222,1.79731154442,-4.26152706146 -2.7306573391,1.79230821133,-4.23995304108 -2.74767041206,1.79431080818,-4.23635149002 -2.75266551971,1.78730666637,-4.21276712418 -2.76968431473,1.79431247711,-4.2239689827 -2.77868580818,1.79031097889,-4.20836210251 -2.79469680786,1.79131257534,-4.20079231262 -2.81371235847,1.79431629181,-4.20019006729 -2.82371544838,1.79231536388,-4.18559122086 -2.84072875977,1.79431796074,-4.18198776245 -2.87476491928,1.80632925034,-4.20338773727 -2.86174106598,1.79331922531,-4.16761159897 -2.88175797462,1.79732346535,-4.16801214218 -2.89877080917,1.7993260622,-4.16440582275 -2.91578388214,1.80132877827,-4.16079807281 -2.92278265953,1.79632604122,-4.14022493362 -2.94680452347,1.80233204365,-4.145632267 -2.94679474831,1.7943264246,-4.11703252792 -2.96781730652,1.80233359337,-4.13223981857 -2.97181296349,1.79633009434,-4.10963869095 -2.97480678558,1.78932571411,-4.08307647705 -2.99682641029,1.79433071613,-4.08646821976 -3.01183652878,1.79533243179,-4.07887554169 -3.0168337822,1.79032957554,-4.05728673935 -3.036850214,1.79333341122,-4.05669307709 -3.05687141418,1.80234014988,-4.07186794281 -3.05786395073,1.7943354845,-4.04428911209 -3.07087159157,1.79333615303,-4.03370141983 -3.08588123322,1.79433774948,-4.02512311935 -3.09888958931,1.79433894157,-4.01650619507 -3.09988212585,1.7863342762,-3.98795032501 -3.11890125275,1.79334008694,-4.0001411438 -3.15393614769,1.8063505888,-4.021504879 -3.15593004227,1.79934668541,-3.99494051933 -3.17394399643,1.80234968662,-3.99134302139 -3.18194556236,1.79834854603,-3.97474884987 -3.20396447182,1.80435335636,-3.97713661194 -3.21997570992,1.80535554886,-3.97054409981 -3.23498916626,1.81035923958,-3.97575211525 -3.23898673058,1.80435669422,-3.9541580677 -3.2700150013,1.81536459923,-3.966558218 -3.26299977303,1.80235779285,-3.92998838425 -3.28802156448,1.80936348438,-3.93537926674 -3.29602360725,1.80636262894,-3.91878819466 -3.314037323,1.80936563015,-3.915184021 -3.31203174591,1.8043628931,-3.89840865135 -3.33104634285,1.80736625195,-3.89580702782 -3.34905958176,1.81036913395,-3.89121651649 -3.3580634594,1.80836892128,-3.87661552429 -3.37307333946,1.80837059021,-3.86803197861 -3.38007497787,1.80536961555,-3.85044240952 -3.40209579468,1.81437563896,-3.86462450027 -3.40809631348,1.81037437916,-3.84504818916 -3.41810107231,1.80837452412,-3.83046770096 -3.42910718918,1.80737507343,-3.81885814667 -3.45112466812,1.81237924099,-3.8182721138 -3.45412230492,1.80637705326,-3.79569387436 -3.47613978386,1.81138134003,-3.79609012604 -3.48314476013,1.81238222122,-3.79228019714 -3.50015664101,1.81438469887,-3.78569698334 -3.49915099144,1.80638158321,-3.75911664963 -3.51916623116,1.8103852272,-3.75750565529 -3.53517746925,1.81238734722,-3.74893641472 -3.54518270493,1.81038784981,-3.73534274101 -3.55318617821,1.80838763714,-3.71876311302 -3.57320332527,1.81539237499,-3.72895145416 -3.58020615578,1.81339216232,-3.71333742142 -3.59621715546,1.81439423561,-3.70476698875 -3.60121798515,1.81039333344,-3.68518662453 -3.63124227524,1.81939959526,-3.69357562065 -3.62823581696,1.81139647961,-3.66599106789 -3.65025281906,1.81640052795,-3.66538858414 -3.66626548767,1.82140398026,-3.67058062553 -3.6652610302,1.81440150738,-3.64401745796 -3.69528484344,1.8234077692,-3.65239667892 -3.692278862,1.81540489197,-3.62481927872 -3.7112929821,1.81940793991,-3.62022781372 -3.73130750656,1.82341134548,-3.61663532257 -3.72830200195,1.81540870667,-3.58906292915 -3.73630785942,1.81640982628,-3.58625030518 -3.7533197403,1.81841242313,-3.57867431641 -3.76532745361,1.81841385365,-3.56708288193 -3.77633428574,1.8174148798,-3.55449223518 -3.78834199905,1.81741631031,-3.54290103912 -3.79734730721,1.81641697884,-3.52929472923 -3.78233361244,1.80541265011,-3.50153493881 -3.76831960678,1.7924079895,-3.46397185326 -3.76231312752,1.78340518475,-3.43440532684 -3.75430464745,1.77340221405,-3.40284585953 -3.72828197479,1.75439536572,-3.35527777672 -3.7282807827,1.74839448929,-3.33171772957 -3.71927285194,1.7383916378,-3.30015563965 -3.70426034927,1.72738802433,-3.27536559105 -3.71727013588,1.72839033604,-3.26479268074 -3.71927142143,1.7233902216,-3.24520230293 -3.74228930473,1.7293946743,-3.24559187889 -3.75229692459,1.72939634323,-3.23202395439 -3.76230454445,1.72839808464,-3.2194378376 -3.78031802177,1.73140156269,-3.21483373642 -3.76630735397,1.72239840031,-3.19105625153 -3.78031802177,1.72340106964,-3.18246221542 -3.77831673622,1.71740043163,-3.15888929367 -3.79232788086,1.7194031477,-3.15029549599 -3.80433702469,1.71940541267,-3.13970685005 -3.80533862114,1.71540558338,-3.119130373 -3.80734062195,1.71140611172,-3.10053348541 -3.8043384552,1.70640563965,-3.08675813675 -3.81935048103,1.70940852165,-3.0791618824 -3.83035945892,1.70941066742,-3.06757807732 -3.84737253189,1.71241402626,-3.06197404861 -3.86238431931,1.71441698074,-3.05339503288 -3.87039089203,1.71341872215,-3.03980112076 -3.86738967896,1.70941829681,-3.02603030205 -3.87039279938,1.70541930199,-3.00843787193 -3.87339639664,1.70242023468,-2.99084615707 -3.87840151787,1.69942164421,-2.97328853607 -3.88941049576,1.70042407513,-2.9626865387 -3.89241409302,1.6964250803,-2.94509887695 -3.91743302345,1.70342993736,-2.94549608231 -3.90542578697,1.69542837143,-2.92473244667 -3.92243885994,1.69843173027,-2.91912388802 -3.93244743347,1.69843411446,-2.90752625465 -3.93545174599,1.69543540478,-2.88896226883 -3.94445967674,1.69443750381,-2.87637090683 -3.95947146416,1.69744062424,-2.86876916885 -3.95947384834,1.69244170189,-2.84820318222 -3.94846820831,1.68544065952,-2.82942676544 -3.97448730469,1.69244539738,-2.82982945442 -3.97949314117,1.69044721127,-2.81423974037 -3.97749423981,1.6854480505,-2.79364824295 -3.99951076508,1.69045221806,-2.79006886482 -3.99951338768,1.68645334244,-2.77146816254 -4.01552581787,1.68945670128,-2.76387953758 -4.02453327179,1.69145846367,-2.76107859612 -4.03154039383,1.69046080112,-2.74650073051 -4.03454494476,1.68746244907,-2.72990608215 -4.04855680466,1.68946564198,-2.72032785416 -4.05256223679,1.68646752834,-2.70374941826 -4.06057024002,1.68647003174,-2.69016695023 -4.06657552719,1.68647146225,-2.68536305428 -4.06557846069,1.68147289753,-2.66479897499 -4.07558727264,1.68247568607,-2.65320420265 -4.08859825134,1.68447875977,-2.64361000061 -4.08359956741,1.67747998238,-2.62103533745 -4.0886054039,1.6754822731,-2.6054558754 -4.1066198349,1.67948591709,-2.59886884689 -4.09861755371,1.67448604107,-2.58408045769 -4.1076259613,1.67448878288,-2.57149457932 -4.12764120102,1.67949259281,-2.56689047813 -4.1346487999,1.67849516869,-2.55329728127 -4.14065599442,1.67749774456,-2.53871202469 -4.13565778732,1.67149925232,-2.51614928246 -4.14466714859,1.67150223255,-2.50356435776 -4.15567493439,1.67350423336,-2.50176334381 -4.16568470001,1.67450714111,-2.49016928673 -4.16468858719,1.67050933838,-2.47060036659 -4.1716966629,1.66951203346,-2.45701050758 -4.18070554733,1.66951501369,-2.44442558289 -4.18271160126,1.66751742363,-2.42783474922 -4.1867184639,1.66552019119,-2.41127252579 -4.19372415543,1.66652166843,-2.40745830536 -4.2057352066,1.66752505302,-2.39686965942 -4.20774126053,1.66552770138,-2.37930393219 -4.21274852753,1.66353034973,-2.36471199989 -4.21475505829,1.66153299809,-2.3481259346 -4.2227640152,1.66153609753,-2.33455228806 -4.23377132416,1.66353809834,-2.33274435997 -4.23577833176,1.6615408659,-2.31518268585 -4.24378681183,1.66154396534,-2.30258631706 -4.2527961731,1.66154706478,-2.29098010063 -4.26080513,1.66155028343,-2.2774066925 -4.2708158493,1.66255366802,-2.26581263542 -4.27082157135,1.65955638885,-2.24725222588 -4.26982355118,1.65755772591,-2.23844814301 -4.28083467484,1.6585611105,-2.22686767578 -4.29084444046,1.65956449509,-2.21527385712 -4.29385232925,1.65756762028,-2.1987080574 -4.29986000061,1.65657067299,-2.18511104584 -4.29586410522,1.65157341957,-2.16552996635 -4.30587148666,1.6545753479,-2.16272521019 -4.30287647247,1.64957821369,-2.14315867424 -4.31488752365,1.65158176422,-2.13256692886 -4.32089662552,1.65058517456,-2.11799502373 -4.33690929413,1.65458893776,-2.10940313339 -4.34792041779,1.65559256077,-2.09782075882 -4.34792661667,1.65259563923,-2.08122396469 -4.34192705154,1.64859688282,-2.0694372654 -4.35794019699,1.65260076523,-2.06084299088 -4.36494922638,1.6526042223,-2.04726004601 -4.36095428467,1.64760744572,-2.02769088745 -4.36796379089,1.647611022,-2.01410913467 -4.37497329712,1.64761459827,-2.00052714348 -4.39098596573,1.65061819553,-1.99192976952 -4.38398647308,1.64661967754,-1.98013746738 -4.39299726486,1.64762341976,-1.96755456924 -4.39600515366,1.64662694931,-1.95197534561 -4.40701627731,1.64763069153,-1.94039094448 -4.40902376175,1.64563405514,-1.92480170727 -4.41103172302,1.64363789558,-1.90823721886 -4.41704130173,1.64364147186,-1.89464521408 -4.42904901505,1.64664340019,-1.89282751083 -4.44106054306,1.64864730835,-1.88125216961 -4.42606258392,1.64065074921,-1.8566981554 -4.43607330322,1.64165449142,-1.84510207176 -4.44208288193,1.64165830612,-1.83151066303 -4.44709205627,1.64066207409,-1.81693375111 -4.46110057831,1.64466416836,-1.81513273716 -4.44910383224,1.63766789436,-1.79257166386 -4.46511697769,1.64167165756,-1.78396356106 -4.47312736511,1.64267551899,-1.77136874199 -4.47513580322,1.64067947865,-1.75481033325 -4.47614336014,1.63868331909,-1.73921787739 -4.48015260696,1.63768732548,-1.72463214397 -4.49216032028,1.6406891346,-1.72182965279 -4.4861664772,1.63669335842,-1.70226669312 -4.50417995453,1.64069724083,-1.69367313385 -4.50518846512,1.63870120049,-1.67808270454 -4.50519657135,1.63670527935,-1.66150796413 -4.51620769501,1.63870930672,-1.64991748333 -4.51321458817,1.63471341133,-1.63234019279 -4.51321935654,1.63371562958,-1.62356674671 -4.53623437881,1.64071953297,-1.61696517467 -4.53024053574,1.63572371006,-1.59838616848 -4.52524757385,1.6317281723,-1.57981836796 -4.5412607193,1.63573205471,-1.57022285461 -4.54226922989,1.63373625278,-1.55463755131 -4.55828237534,1.63774037361,-1.54503953457 -4.55228471756,1.63474273682,-1.53426289558 -4.55929470062,1.63474667072,-1.5216575861 -4.56030416489,1.63275122643,-1.50509917736 -4.56531381607,1.63275539875,-1.49150109291 -4.57132482529,1.6327599287,-1.47693753242 -4.5733332634,1.6317640543,-1.46233844757 -4.57733917236,1.632766366,-1.45555269718 -4.57934856415,1.6307708025,-1.43998014927 -4.58835983276,1.63277506828,-1.42739140987 -4.57936573029,1.62677967548,-1.40880215168 -4.59637880325,1.63178372383,-1.39920461178 -4.59838867188,1.62978839874,-1.38363361359 -4.60840034485,1.63279283047,-1.37105178833 -4.61340618134,1.63279485703,-1.36524820328 -4.60941410065,1.62979960442,-1.3476793766 -4.60942316055,1.62780416012,-1.33209323883 -4.61743497849,1.6288087368,-1.31852078438 -4.64545059204,1.63781237602,-1.31290006638 -4.61845350266,1.62581825256,-1.28735923767 -4.63946771622,1.63182222843,-1.27875840664 -4.64047241211,1.63082456589,-1.27097392082 -4.63547992706,1.62782931328,-1.25437712669 -4.64949321747,1.630833745,-1.24279689789 -4.64150094986,1.62583899498,-1.22423160076 -4.64651203156,1.62584388256,-1.20966124535 -4.65252256393,1.62684845924,-1.19607174397 -4.65753316879,1.6268529892,-1.18247497082 -4.65753793716,1.62585544586,-1.17468452454 -4.65454673767,1.62386059761,-1.15810859203 -4.67956256866,1.63086462021,-1.14952361584 -4.66556882858,1.62387025356,-1.12994968891 -4.67858171463,1.6278744936,-1.11835587025 -4.6925945282,1.63087892532,-1.10676777363 -4.68359708786,1.62688183784,-1.09696912766 -4.67160463333,1.62088763714,-1.07741522789 -4.68961858749,1.6258919239,-1.06682670116 -4.69362878799,1.62589657307,-1.05322277546 -4.69063854218,1.62390208244,-1.03665232658 -4.70365095139,1.62690639496,-1.02505409718 -4.69665956497,1.62291204929,-1.00748598576 -4.70666694641,1.62591433525,-1.00170838833 -4.71067762375,1.62591910362,-0.988104462624 -4.69968557358,1.61992526054,-0.969541370869 -4.70669746399,1.62193012238,-0.95595651865 -4.71270847321,1.62193500996,-0.942365646362 -4.71772050858,1.62294006348,-0.927794754505 -4.72173118591,1.62294530869,-0.913218021393 -4.73073816299,1.62594723701,-0.908403277397 -4.71274471283,1.6179536581,-0.888833999634 -4.73275899887,1.62395787239,-0.878241300583 -4.72876882553,1.62096369267,-0.861673533916 -4.73778152466,1.62296867371,-0.84809756279 -4.72678995132,1.61797487736,-0.83052033186 -4.74480342865,1.6229789257,-0.819911360741 -4.73480653763,1.61898243427,-0.810126841068 -4.7368183136,1.61798810959,-0.794567346573 -4.76183271408,1.62599182129,-0.784963488579 -4.74084043503,1.61799883842,-0.765394747257 -4.75385332108,1.62100350857,-0.752809286118 -4.76786661148,1.62500834465,-0.740226686001 -4.76887226105,1.62501084805,-0.73341947794 -4.75388050079,1.61801767349,-0.714859962463 -4.76589298248,1.62202239037,-0.702266275883 -4.77090501785,1.62202787399,-0.687693595886 -4.76791524887,1.62003386021,-0.672111749649 -4.75392436981,1.61404061317,-0.6545368433 -4.78694009781,1.6250436306,-0.64592307806 -4.74694013596,1.61005008221,-0.630185425282 -4.76495409012,1.61605429649,-0.618587195873 -4.75996446609,1.61306035519,-0.603001117706 -4.75697517395,1.61106657982,-0.587424218655 -4.77598905563,1.61707079411,-0.575825929642 -4.76799917221,1.61307740211,-0.559257090092 -4.77800655365,1.61607944965,-0.553458631039 -4.76801633835,1.61208629608,-0.53688365221 -4.79203128815,1.62009036541,-0.525298178196 -4.78404188156,1.61609709263,-0.508732020855 -4.79905509949,1.62010169029,-0.496138185263 -4.77506351471,1.61110985279,-0.477573871613 -4.78807640076,1.61511456966,-0.464972227812 -4.77808094025,1.61111831665,-0.456185311079 -4.80309581757,1.61912226677,-0.444593071938 -4.76810264587,1.60613143444,-0.425030350685 -4.79411792755,1.61413526535,-0.413438498974 -4.78112792969,1.60914254189,-0.396865367889 -4.78914165497,1.61114823818,-0.382299691439 -4.81315565109,1.61915194988,-0.370694577694 -4.78915834427,1.61015713215,-0.360902905464 -4.79917192459,1.61316263676,-0.34634077549 -4.80118370056,1.61316859722,-0.331756949425 -4.80619573593,1.61417412758,-0.318153113127 -4.81920909882,1.61817908287,-0.304567545652 -4.81322050095,1.61618590355,-0.288991391659 -4.81422710419,1.6161891222,-0.281212836504 -4.82323980331,1.61819434166,-0.267616063356 -4.81125116348,1.61420214176,-0.251056551933 -4.79826164246,1.60820949078,-0.235470384359 -4.81427526474,1.61421442032,-0.221886262298 -4.81428718567,1.61322057247,-0.207298502326 -4.82330083847,1.6162263155,-0.192726284266 -4.8193063736,1.61422991753,-0.18493925035 -4.81731843948,1.6132363081,-0.170348256826 -4.81633090973,1.61224317551,-0.154786914587 -4.82934427261,1.6162481308,-0.141190901399 -4.82235622406,1.61425542831,-0.125620722771 -4.82036781311,1.61226201057,-0.111031241715 -4.81538057327,1.61026930809,-0.0954659730196 -4.83038759232,1.61627054214,-0.0896481722593 -4.81539964676,1.61027920246,-0.0731001868844 -4.82341194153,1.61228442192,-0.0594943575561 -4.82042455673,1.61129164696,-0.0439325608313 -4.83643817902,1.61629617214,-0.0303314737976 -4.81244897842,1.60830533504,-0.014754448086 -4.83246326447,1.61431002617,-0.000181756258826 -4.83046913147,1.61431324482,0.0066268616356 -4.82948255539,1.61332035065,0.02218635194 -4.8164935112,1.60832822323,0.036778062582 -4.83050775528,1.61333346367,0.0513589344919 -4.8235206604,1.6103413105,0.0669192820787 -4.82953357697,1.61234724522,0.0815041512251 -4.82953977585,1.61235034466,0.0883110538125 -4.82455253601,1.6103579998,0.10386967659 -4.83256578445,1.61336374283,0.118455968797 -4.8235783577,1.61037158966,0.133040979505 -4.8295917511,1.61237752438,0.147627875209 -4.82760381699,1.61138451099,0.162213161588 -4.83361721039,1.61339056492,0.176801353693 -4.82962417603,1.61239469051,0.184579029679 -4.83563756943,1.61440062523,0.199168160558 -4.82165050507,1.6094096899,0.214718282223 -4.81966352463,1.60841667652,0.229302048683 -4.82567691803,1.61042284966,0.243891879916 -4.82568979263,1.61042976379,0.258477509022 -4.82970333099,1.61243605614,0.273067206144 -4.82370996475,1.61044049263,0.280840396881 -4.81972312927,1.60844790936,0.295421421528 -4.82473611832,1.6104542017,0.310012638569 -4.83575057983,1.61445999146,0.325584709644 -4.81876373291,1.60846924782,0.340148478746 -4.81277704239,1.60647714138,0.354725241661 -4.83078432083,1.61347818375,0.362530708313 -4.82079744339,1.61048674583,0.377101719379 -4.81280994415,1.60749447346,0.390701860189 -4.83082437515,1.61449921131,0.406290799379 -4.80983781815,1.6065094471,0.420839220285 -4.81885099411,1.61051511765,0.435441732407 -4.81186485291,1.60852324963,0.450013965368 -4.8028717041,1.6045280695,0.456802040339 -4.79988479614,1.60353553295,0.471380531788 -4.8048992157,1.60654234886,0.486949026585 -4.78491306305,1.59955239296,0.500516116619 -4.79092645645,1.60155856609,0.515114247799 -4.81494045258,1.61056268215,0.531702756882 -4.77095413208,1.59557580948,0.543260216713 -4.80896091461,1.60957419872,0.553081393242 -4.79697561264,1.60558331013,0.567635834217 -4.7899889946,1.6035913229,0.581229865551 -4.78200292587,1.6006000042,0.595792293549 -4.77701759338,1.59960830212,0.610362529755 -4.77003145218,1.5976164341,0.62395375967 -4.78504562378,1.60362184048,0.640529572964 -4.7880525589,1.60462522507,0.648318111897 -4.72906637192,1.58364069462,0.656878709793 -4.77408123016,1.60064196587,0.676471889019 -4.79109430313,1.60764658451,0.692088007927 -4.2241358757,1.60278069973,2.43241071701 -4.20614767075,1.59678864479,2.43118977547 -4.20716428757,1.60079717636,2.4477891922 -4.19818353653,1.59980821609,2.46034932137 -4.20219993591,1.60481619835,2.47894382477 -4.18722009659,1.60082828999,2.48751783371 -4.18923664093,1.60483658314,2.5051112175 -4.19525337219,1.61084473133,2.52569055557 -4.18326377869,1.60785150528,2.52747416496 -4.18228197098,1.60986077785,2.54405260086 -4.1683011055,1.60787236691,2.55263900757 -4.17031860352,1.61188137531,2.57121396065 -4.17233610153,1.6158901453,2.58979105949 -4.15335607529,1.61090266705,2.59537577629 -4.15537405014,1.61491143703,2.61395454407 -4.14038467407,1.60991883278,2.61373710632 -4.13540410995,1.61192917824,2.6283094883 -4.13142204285,1.61293888092,2.64289736748 -4.11944198608,1.61195075512,2.65346217155 -4.11346054077,1.61196100712,2.66704440117 -4.11047887802,1.61397063732,2.68262505531 -4.09249973297,1.60998344421,2.68919253349 -4.10350608826,1.61598551273,2.70400714874 -4.08552742004,1.61199843884,2.71057391167 -4.07254743576,1.61001014709,2.72014451027 -4.08256340027,1.61801719666,2.74373888969 -4.06958293915,1.6160286665,2.75233340263 -4.05260419846,1.61204171181,2.75988841057 -4.05361318588,1.61404621601,2.76967263222 -4.04663181305,1.61505639553,2.78226566315 -4.0336523056,1.61306846142,2.7918343544 -4.03366994858,1.6160775423,2.80942130089 -4.01669120789,1.61309015751,2.81599569321 -4.02170705795,1.61809813976,2.8365945816 -4.00672864914,1.61611068249,2.84515357018 -4.0147356987,1.62111353874,2.85896205902 -3.99875712395,1.61812615395,2.86652755737 -3.98777699471,1.61713767052,2.87710356712 -3.97379779816,1.61414980888,2.88567614555 -3.96981596947,1.6161595583,2.90027356148 -3.96883440018,1.62016904354,2.91785287857 -3.96585345268,1.62217926979,2.93442368507 -3.94886541367,1.61718714237,2.93121528625 -3.93588638306,1.61519920826,2.94077968597 -3.93790388107,1.62020814419,2.96036624908 -3.92592430115,1.61821973324,2.96994709969 -3.91794371605,1.61923074722,2.98252677917 -3.90296506882,1.61624312401,2.99010109901 -3.90897297859,1.62124669552,3.00389122963 -3.89399433136,1.6182590723,3.01146531105 -3.89101338387,1.62126922607,3.02804112434 -3.8670361042,1.61428332329,3.02861595154 -3.88305139542,1.62628948689,3.05920696259 -3.85507392883,1.61730408669,3.05579948425 -3.85609292984,1.62231385708,3.07635879517 -3.85910058022,1.62531745434,3.08717083931 -3.84012389183,1.62133133411,3.0927169323 -3.83214378357,1.6223423481,3.10529875755 -3.83216190338,1.62635159492,3.12388920784 -3.82118272781,1.62536323071,3.13446354866 -3.80720329285,1.6233754158,3.14205002785 -3.79322504997,1.62138795853,3.15061354637 -3.79723334312,1.62539184093,3.16340565681 -3.78525352478,1.62440335751,3.17200446129 -3.77827334404,1.62541413307,3.18558430672 -3.76729416847,1.62442600727,3.19615769386 -3.76031398773,1.62643694878,3.20973849297 -3.74633622169,1.62444961071,3.21830058098 -3.75434327126,1.63045239449,3.23410630226 -3.72636675835,1.62146735191,3.22969174385 -3.72538566589,1.62547695637,3.24827551842 -3.71340751648,1.62448954582,3.25883030891 -3.70642757416,1.62650036812,3.27241301537 -3.70144629478,1.62851047516,3.28701114655 -3.68146896362,1.62352406979,3.28958678246 -3.69347643852,1.6315267086,3.31037092209 -3.67649817467,1.62853944302,3.31495904922 -3.66452026367,1.62755203247,3.32551383972 -3.67053723335,1.63556015491,3.3501124382 -3.64856028557,1.62957406044,3.35068845749 -3.63958144188,1.63058567047,3.3632581234 -3.63759088516,1.63159072399,3.37105870247 -3.61761403084,1.62660455704,3.37362742424 -3.61863207817,1.63261365891,3.39422154427 -3.6056535244,1.630625844,3.40279817581 -3.59467601776,1.63063836098,3.4143512249 -3.58769512177,1.63264882565,3.42695999146 -3.57471680641,1.63066101074,3.43553566933 -3.57172703743,1.63266670704,3.44332027435 -3.55474948883,1.62867975235,3.44789910316 -3.56076717377,1.63768827915,3.47447824478 -3.52879405022,1.62670493126,3.46602749825 -3.53081154823,1.63271379471,3.48763227463 -3.52083206177,1.63272511959,3.4982252121 -3.51085424423,1.63373744488,3.51077914238 -3.50486421585,1.63274312019,3.514585495 -3.49688529968,1.63475453854,3.52815914154 -3.48390722275,1.63376700878,3.5367333889 -3.4739279747,1.63377833366,3.54732656479 -3.46794843674,1.63678944111,3.56290173531 -3.44897174835,1.63280320168,3.56547355652 -3.43599295616,1.63081514835,3.57306551933 -3.44500160217,1.63881862164,3.59384083748 -3.41702651978,1.62983393669,3.58642411232 -3.41404628754,1.6338442564,3.60500335693 -3.4110660553,1.63785469532,3.6235845089 -3.3980884552,1.6378672123,3.63215780258 -3.37811160088,1.63288092613,3.63274145126 -3.38512015343,1.6398845911,3.65152478218 -3.36414361,1.63389849663,3.65110564232 -3.35816431046,1.63690948486,3.66668748856 -3.35218477249,1.6399204731,3.68227028847 -3.33720684052,1.63793313503,3.68785810471 -3.33222794533,1.64094424248,3.70542550087 -3.31325125694,1.63695776463,3.70700526237 -3.30526232719,1.6359641552,3.70880627632 -3.30028319359,1.63897514343,3.72637557983 -3.29530334473,1.64198577404,3.74296474457 -3.26832842827,1.63400113583,3.73554110527 -3.27034807205,1.64201080799,3.7611117363 -3.26136922836,1.64302253723,3.77369379997 -3.24938178062,1.64002978802,3.77148342133 -3.24040317535,1.64104151726,3.784065485 -3.2204272747,1.63605558872,3.78463435173 -3.21944665909,1.64206540585,3.80622267723 -3.20846867561,1.64207756519,3.81680011749 -3.19449114799,1.64109015465,3.8233859539 -3.19051241875,1.64610123634,3.84295201302 -3.1815237999,1.6441078186,3.84374690056 -3.16354680061,1.64012110233,3.84533572197 -3.15456819534,1.64213275909,3.85792064667 -3.14459085464,1.64314508438,3.87048530579 -3.137611866,1.64615643024,3.88606190681 -3.13063240051,1.64816749096,3.90065741539 -3.11265683174,1.64518117905,3.90322613716 -3.10566759109,1.6441873312,3.90602660179 -3.0956902504,1.64619970322,3.91859340668 -3.08671140671,1.64721107483,3.93118214607 -3.07073497772,1.64522445202,3.93575692177 -3.05975723267,1.6462366581,3.94633746147 -3.04977989197,1.64724886417,3.95890569687 -3.03780150414,1.64726090431,3.96749854088 -3.02781462669,1.64526844025,3.96826720238 -3.01983499527,1.64727914333,3.98087930679 -3.01285648346,1.65029084682,3.99744868279 -2.99188137054,1.6453050375,3.99502754211 -2.98690319061,1.65031647682,4.01459217072 -2.96792697906,1.64633011818,4.01417970657 -2.96393799782,1.64733600616,4.02196311951 -2.94396233559,1.64235007763,4.02054262161 -2.93998193741,1.64736020565,4.03914880753 -2.936003685,1.65237152576,4.0607085228 -2.92302560806,1.6523835659,4.06731271744 -2.90105104446,1.6463984251,4.06387710571 -2.89507317543,1.6504099369,4.08244466782 -2.89608168602,1.65441405773,4.09526205063 -2.87710738182,1.65142869949,4.09681177139 -2.86712908745,1.65244042873,4.10840320587 -2.85015320778,1.65045404434,4.11098003387 -2.84417414665,1.6544649601,4.12856817245 -2.83119773865,1.6544778347,4.13714122772 -2.8162214756,1.65249109268,4.14271450043 -2.81423139572,1.65549623966,4.15251779556 -2.79925513268,1.65450942516,4.1580915451 -2.78527855873,1.65352237225,4.16467189789 -2.77530026436,1.65453398228,4.17626667023 -2.76832222939,1.6585457325,4.19383955002 -2.75034666061,1.65555942059,4.19442081451 -2.74535894394,1.65656602383,4.20218896866 -2.73338031769,1.65657770634,4.20979976654 -2.7124068737,1.65259253979,4.20735454559 -2.71042609215,1.65860259533,4.23095655441 -2.69644975662,1.65861546993,4.23753738403 -2.68447399139,1.65962851048,4.24909067154 -2.67249703407,1.66064107418,4.25867366791 -2.66550779343,1.65964698792,4.26048564911 -2.65453052521,1.66165947914,4.27206325531 -2.63855552673,1.65967309475,4.27662658691 -2.6285777092,1.66168510914,4.28921365738 -2.61860013008,1.66369700432,4.30180168152 -2.61262106895,1.6687079668,4.32039833069 -2.58564925194,1.65972423553,4.3079457283 -2.58665823936,1.66472864151,4.32276010513 -2.56368541718,1.65874397755,4.31631326675 -2.55670619011,1.6627548933,4.33291721344 -2.54872894287,1.66676700115,4.3504858017 -2.53775119781,1.6677788496,4.36108207703 -2.51377725601,1.66079378128,4.35066175461 -2.51378774643,1.66579902172,4.36644554138 -2.49881243706,1.66481256485,4.3720164299 -2.48383617401,1.66382551193,4.3766002655 -2.48185634613,1.67183578014,4.40319538116 -2.46388173103,1.66884982586,4.40376329422 -2.46390128136,1.67785954475,4.43435764313 -2.45192503929,1.6798722744,4.44493579865 -2.46193170547,1.69187498093,4.4777431488 -2.44895577431,1.69288802147,4.48731517792 -2.4369790554,1.69390046597,4.49789762497 -2.45699310303,1.71890592575,4.56550645828 -2.45801305771,1.72991597652,4.601085186 -2.44803619385,1.73392820358,4.61666202545 -2.43206071854,1.73194146156,4.62024831772 -2.42407250404,1.73194813728,4.62204122543 -2.43009138107,1.74695694447,4.66762685776 -2.42611289024,1.75496804714,4.69520425797 -2.41213703156,1.75598120689,4.70378112793 -2.4001595974,1.75699329376,4.71438074112 -2.39318156242,1.76300477982,4.73596715927 -2.38220477104,1.76601719856,4.75054597855 -2.37521719933,1.76702392101,4.75532960892 -2.36723971367,1.77203571796,4.77591085434 -2.35426354408,1.77404844761,4.78649234772 -2.34328603745,1.776060462,4.80008649826 -2.32431221008,1.77407479286,4.79965496063 -2.30433726311,1.76908886433,4.79524374008 -2.29435110092,1.76809632778,4.79501533508 -2.28937292099,1.77610754967,4.82259511948 -2.26639914513,1.76912236214,4.81217765808 -2.25542187691,1.77213442326,4.82577514648 -2.23244833946,1.76514911652,4.81535434723 -2.20447731018,1.75516545773,4.79591083527 -2.1945002079,1.75917756557,4.81249856949 -2.18751192093,1.75918400288,4.81629371643 -2.16753840446,1.7551984787,4.81286096573 -2.15656161308,1.75821077824,4.82744836807 -2.14058661461,1.75722420216,4.83202409744 -2.12261176109,1.75523805618,4.83160448074 -2.11063551903,1.75725054741,4.84419107437 -2.10364747047,1.7572568655,4.84798669815 -2.07967472076,1.75027215481,4.83455705643 -2.06869769096,1.75328433514,4.84914731979 -2.05772137642,1.7572966814,4.86472845078 -2.03474760056,1.74931144714,4.85131692886 -2.02177214622,1.751324296,4.86289215088 -2.00679636002,1.75133740902,4.86847925186 -1.99681067467,1.75034511089,4.86824321747 -1.9848331213,1.75235700607,4.87885284424 -1.97185790539,1.75537014008,4.89142084122 -1.95088374615,1.74938440323,4.88200902939 -1.93990802765,1.75339710712,4.89957714081 -1.92693173885,1.75540971756,4.91016578674 -1.90495848656,1.74942445755,4.8987455368 -1.90596807003,1.75742900372,4.92254734039 -1.88399529457,1.75144398212,4.91211557388 -1.87101900578,1.75345659256,4.92270517349 -1.85604345798,1.75346958637,4.92829322815 -1.83806920052,1.75048339367,4.92687225342 -1.82209432125,1.7494969368,4.93045282364 -1.80811941624,1.75151026249,4.94102048874 -1.79313397408,1.74451839924,4.92380952835 -1.78615677357,1.75353002548,4.95238828659 -1.76318359375,1.74554467201,4.93597316742 -1.75120747089,1.74855720997,4.95055532455 -1.73023378849,1.74257147312,4.93914222717 -1.71825766563,1.74558401108,4.95372486115 -1.71326971054,1.74959027767,4.96451187134 -1.69329535961,1.7436041832,4.9551024437 -1.68032002449,1.74661719799,4.96767997742 -1.6703441143,1.75362956524,4.99025058746 -1.6433724165,1.74064517021,4.96083068848 -1.63439488411,1.7476568222,4.98342657089 -1.61742019653,1.7456703186,4.98301315308 -1.60943281651,1.74567699432,4.98480224609 -1.59645724297,1.74768972397,4.99738407135 -1.57548379898,1.74170422554,4.98496484756 -1.56450879574,1.7477170229,5.00652742386 -1.5455340147,1.74373066425,4.99812412262 -1.53255867958,1.74674355984,5.01170063019 -1.52257180214,1.7437505722,5.00649309158 -1.50759732723,1.7457638979,5.01406621933 -1.48662400246,1.73877835274,5.00064659119 -1.47464752197,1.7427905798,5.0152425766 -1.45767354965,1.74180436134,5.01581716537 -1.44869589806,1.74881589413,5.04041719437 -1.42572391033,1.73983097076,5.02098560333 -1.42373538017,1.74783658981,5.04476833344 -1.39976251125,1.73685145378,5.01835727692 -1.39278590679,1.74886322021,5.05493068695 -1.36981284618,1.73887777328,5.03151893616 -1.36083590984,1.74788951874,5.05910921097 -1.33386421204,1.73190498352,5.02069234848 -1.32188880444,1.73691773415,5.03926897049 -1.31190240383,1.73492479324,5.03405332565 -1.29892647266,1.7379373312,5.04664611816 -1.28195178509,1.73595070839,5.04423618317 -1.26997601986,1.74196326733,5.06281805038 -1.25100290775,1.736977458,5.05538845062 -1.23602831364,1.73899066448,5.06296634674 -1.21705460548,1.73400461674,5.05354642868 -1.21206569672,1.73701024055,5.06435537338 -1.19209313393,1.73202478886,5.05292081833 -1.17711830139,1.7330378294,5.05950403214 -1.16114401817,1.73305130005,5.06308031082 -1.14416909218,1.73106443882,5.05867671967 -1.12919425964,1.73207759857,5.06526041031 -1.1242057085,1.73608326912,5.0780620575 -1.10623204708,1.73309707642,5.07263851166 -1.09325647354,1.73710978031,5.08822488785 -1.07228434086,1.73012447357,5.07078886032 -1.05830895901,1.73313713074,5.08137798309 -1.03933525085,1.72715103626,5.06896114349 -1.027359128,1.73316323757,5.08855581284 -1.01637387276,1.72917103767,5.07932424545 -1.00039851665,1.72818386555,5.07792520523 -0.984424173832,1.72819709778,5.08050537109 -0.972448766232,1.73520970345,5.10408592224 -0.953475415707,1.7302236557,5.0916633606 -0.938500702381,1.73223674297,5.09924650192 -0.926514744759,1.72424411774,5.07903528214 -0.913539528847,1.73025679588,5.09761857986 -0.896565139294,1.72727012634,5.0932059288 -0.882590174675,1.73128294945,5.10678911209 -0.864615678787,1.72629630566,5.09438419342 -0.849641799927,1.72930967808,5.10595226288 -0.832666993141,1.72632277012,5.09854984283 -0.825679421425,1.72832906246,5.10534286499 -0.808705508709,1.72634255886,5.10192203522 -0.792731463909,1.72735595703,5.10549926758 -0.7747579813,1.72336959839,5.09607601166 -0.762781739235,1.73138177395,5.12067365646 -0.743808925152,1.72539579868,5.10624265671 -0.727834165096,1.72440886497,5.10583400726 -0.718847632408,1.72241580486,5.10161924362 -0.706872344017,1.73342823982,5.1331987381 -0.686898589134,1.72144198418,5.10279321671 -0.673922717571,1.72845423222,5.12338972092 -0.655949294567,1.72346794605,5.11196613312 -0.641975164413,1.73148107529,5.13453435898 -0.624000906944,1.72449433804,5.11712789536 -0.617013812065,1.72850084305,5.12891197205 -0.599040329456,1.72351455688,5.11549091339 -0.587064087391,1.73352646828,5.14708995819 -0.56609159708,1.71954083443,5.10766506195 -0.551117300987,1.72355389595,5.12024354935 -0.53614205122,1.72556638718,5.12684011459 -0.529153943062,1.72757256031,5.13264465332 -0.510181486607,1.71958673,5.11220979691 -0.495206743479,1.72259950638,5.12279653549 -0.480231940746,1.72561228275,5.13338470459 -0.462258636951,1.71962594986,5.11696052551 -0.44628444314,1.7206389904,5.11954212189 -0.430310159922,1.72065210342,5.12112617493 -0.422323137522,1.72165870667,5.12291622162 -0.408347517252,1.72767114639,5.1425151825 -0.390373826027,1.71968448162,5.11909914017 -0.374399632215,1.71969759464,5.12168121338 -0.358425617218,1.72171080112,5.12626028061 -0.344450384378,1.73072314262,5.15385150909 -0.325477689505,1.71773719788,5.1184220314 -0.319488823414,1.7247427702,5.13723707199 -0.302515596151,1.7227563858,5.13280582428 -0.28754067421,1.72776901722,5.14839696884 -0.270566374063,1.72078192234,5.12798786163 -0.254592716694,1.72479534149,5.13956069946 -0.237618982792,1.71980857849,5.12514019012 -0.222643524408,1.72282099724,5.13474273682 -0.213657289743,1.71882784367,5.12352275848 -0.197683289647,1.72184097767,5.13110208511 -0.181708529592,1.71885371208,5.12369632721 -0.165734946728,1.7258669138,5.14226770401 -0.148761123419,1.71588015556,5.11684942245 -0.133785948157,1.72389268875,5.13944673538 -0.124799840152,1.71889960766,5.12422418594 -0.108825556934,1.7199126482,5.12780952454 -0.0928510725498,1.71892535686,5.12339878082 -0.0768766254187,1.71793830395,5.11998748779 -0.0609021484852,1.71495103836,5.11257648468 -0.0449280925095,1.72396397591,5.1361579895 -0.0289535075426,1.71597671509,5.11574888229 -0.0209663435817,1.71698319912,5.11754226685 -0.00499197375029,1.71299600601,5.10712909698 --0.00599014898762,1.71100485325,4.96584033966 --0.0209652725607,1.6950173378,4.92243623734 --0.0369390621781,1.70403039455,4.94601202011 --0.0519139990211,1.6950429678,4.92060470581 --0.0599009804428,1.70004940033,4.93339443207 --0.074875921011,1.69406187534,4.91798686981 --0.0918485671282,1.7050756216,4.94754552841 --0.106823205948,1.69708812237,4.92413282394 --0.122797593474,1.7061008215,4.94772052765 --0.136773496866,1.69611287117,4.91932630539 --0.152747273445,1.69812583923,4.92390203476 --0.159735277295,1.6941318512,4.91370630264 --0.176708549261,1.70514512062,4.94127702713 --0.190683409572,1.6901576519,4.90086269379 --0.206657543778,1.6941703558,4.91144514084 --0.22163246572,1.69318270683,4.90603780746 --0.237607210875,1.7001953125,4.92363166809 --0.252581626177,1.69620788097,4.91121530533 --0.26156809926,1.70221471786,4.92899990082 --0.275543153286,1.69322693348,4.90358924866 --0.291516810656,1.69423997402,4.90416288376 --0.307491779327,1.70025241375,4.91976118088 --0.321466952562,1.69326448441,4.89935350418 --0.338440209627,1.6992777586,4.9129242897 --0.353414565325,1.6962903738,4.9025053978 --0.359403073788,1.69029605389,4.88631343842 --0.376376658678,1.69630908966,4.90189123154 --0.39035230875,1.69232106209,4.88949251175 --0.409324377775,1.70433485508,4.91905069351 --0.422299683094,1.69334685802,4.88963937759 --0.440273225307,1.70436000824,4.91522121429 --0.44526180625,1.6943655014,4.88902568817 --0.461236655712,1.69837784767,4.89762163162 --0.475211560726,1.693390131,4.88120794296 --0.493184506893,1.70040345192,4.89977884293 --0.508158922195,1.69841587543,4.89236164093 --0.521134912968,1.6924277544,4.87296247482 --0.539109051228,1.70244038105,4.89755582809 --0.545096516609,1.69644641876,4.87934350967 --0.561070859432,1.69845890999,4.88293027878 --0.57604521513,1.69647157192,4.8755106926 --0.593019127846,1.70048439503,4.88609457016 --0.605994224548,1.69349634647,4.86367845535 --0.622967898846,1.69750928879,4.87225723267 --0.629955887794,1.69651508331,4.86906147003 --0.649928629398,1.70852839947,4.89863634109 --0.661904156208,1.69954025745,4.87122440338 --0.677878439426,1.70055282116,4.87280893326 --0.690854728222,1.69656419754,4.85941696167 --0.709827303886,1.7045776844,4.87698364258 --0.721803188324,1.69658923149,4.8535785675 --0.731789708138,1.70259594917,4.86736965179 --0.747764348984,1.70460820198,4.86996030807 --0.76373898983,1.70662045479,4.87255191803 --0.779712677002,1.70663321018,4.87012338638 --0.794688165188,1.70764517784,4.86872625351 --0.80666321516,1.69865703583,4.84330272675 --0.822637915611,1.70066940784,4.84589576721 --0.83062428236,1.70067596436,4.84267187119 --0.845599472523,1.70068800449,4.84026861191 --0.866572082043,1.71170127392,4.86784791946 --0.879548311234,1.70871269703,4.85545301437 --0.893522560596,1.70472502708,4.84202528 --0.913495540619,1.71373820305,4.86260557175 --0.92547172308,1.70774960518,4.84420442581 --0.938457489014,1.71875655651,4.86999607086 --0.951432585716,1.71376848221,4.8535785675 --0.96540749073,1.71078050137,4.8431634903 --0.982382416725,1.71479260921,4.8507642746 --0.995357275009,1.70980453491,4.83434295654 --1.01832973957,1.72381794453,4.86792993546 --1.02331721783,1.71882390976,4.85070943832 --1.04429042339,1.72883689404,4.87430000305 --1.05326712132,1.7178478241,4.84189176559 --1.07024133205,1.72086024284,4.84547662735 --1.08321630955,1.71687209606,4.83005666733 --1.10718846321,1.73088562489,4.86464262009 --1.11516571045,1.71889638901,4.83023929596 --1.13015067577,1.73090362549,4.85902643204 --1.13712882996,1.71891403198,4.82263278961 --1.15710151196,1.72592711449,4.83620548248 --1.17007756233,1.72293841839,4.82480573654 --1.18405258656,1.72095024586,4.81539201736 --1.20702493191,1.73196351528,4.84197568893 --1.21800041199,1.7249751091,4.81854963303 --1.22898685932,1.72998154163,4.83034706116 --1.24096298218,1.72599291801,4.81393909454 --1.25893735886,1.73000514507,4.82153463364 --1.27191233635,1.72601699829,4.80711221695 --1.29788422585,1.74203050137,4.84370326996 --1.30786049366,1.73504149914,4.8192896843 --1.32383489609,1.73505365849,4.81687307358 --1.33182179928,1.73505985737,4.81465768814 --1.34579730034,1.73407149315,4.80624961853 --1.36277198792,1.73708343506,4.80884361267 --1.37874686718,1.73809528351,4.80743551254 --1.39272153378,1.73610723019,4.79701280594 --1.4126957655,1.74311947823,4.81061458588 --1.41068589687,1.73012387753,4.77540826797 --1.4326583147,1.73913705349,4.79198312759 --1.45063245296,1.74214923382,4.79657173157 --1.47160601616,1.75016176701,4.81116294861 --1.4815826416,1.7441726923,4.78975582123 --1.50755381584,1.75618636608,4.81732749939 --1.51653122902,1.74919700623,4.79392814636 --1.52651715279,1.75120353699,4.79670476913 --1.53749358654,1.74621450901,4.77930021286 --1.55246961117,1.74722576141,4.77590608597 --1.5684441328,1.74823760986,4.77248811722 --1.58441901207,1.74924945831,4.77007818222 --1.60139322281,1.7512614727,4.76966094971 --1.61836802959,1.75327324867,4.77025365829 --1.62735486031,1.75527942181,4.77104187012 --1.64432919025,1.7572914362,4.77062702179 --1.66030442715,1.75830304623,4.76822042465 --1.6772788763,1.7603148222,4.76780700684 --1.68425643444,1.75132524967,4.73939800262 --1.7012308836,1.75333714485,4.73898410797 --1.71621632576,1.76234412193,4.75677680969 --1.74018847942,1.77135705948,4.77435445786 --1.74316775799,1.75836646557,4.73695755005 --1.75714290142,1.75737810135,4.72753953934 --1.7771166563,1.76239025593,4.73512887955 --1.79709029198,1.76740252972,4.74171209335 --1.81306481361,1.76841425896,4.73729228973 --1.81705355644,1.76441955566,4.72508716583 --1.83502840996,1.76843118668,4.72768449783 --1.8440053463,1.76244175434,4.70627498627 --1.86197936535,1.76445376873,4.70685434341 --1.8769544363,1.76446521282,4.70043992996 --1.89392900467,1.76647686958,4.69902610779 --1.90490627289,1.76348733902,4.68463087082 --1.92189061642,1.77249479294,4.70341014862 --1.93286776543,1.76850509644,4.68901443481 --1.95184123516,1.7725174427,4.69058561325 --1.96581697464,1.77152848244,4.6821770668 --1.98079323769,1.77253949642,4.6777844429 --1.99676764011,1.77355110645,4.67235851288 --2.0237402916,1.78456389904,4.69495677948 --2.01873159409,1.77356767654,4.66275262833 --2.04170393944,1.7795804739,4.67332649231 --2.05168104172,1.77559089661,4.65592050552 --2.06965613365,1.77960216999,4.6575217247 --2.08063292503,1.77561295033,4.64211130142 --2.10760426521,1.78662610054,4.66068220139 --2.10659456253,1.77963030338,4.63948726654 --2.12656831741,1.78364229202,4.64306592941 --2.139544487,1.78265309334,4.63266134262 --2.16451716423,1.79166567326,4.64724493027 --2.17249441147,1.78467595577,4.62482738495 --2.19646811485,1.79368817806,4.63842821121 --2.2004468441,1.78469753265,4.60902357101 --2.21743202209,1.7927043438,4.62581968307 --2.23040795326,1.79171514511,4.61440420151 --2.24338436127,1.78972578049,4.60399913788 --2.25036144257,1.78273618221,4.57957458496 --2.27933382988,1.79574882984,4.60217189789 --2.28531217575,1.7887583971,4.57776832581 --2.30628585815,1.79377043247,4.58235025406 --2.31127405167,1.79177570343,4.57313537598 --2.32624983788,1.79178655148,4.56672954559 --2.3472237587,1.79679834843,4.57131481171 --2.36819839478,1.80280995369,4.57691383362 --2.37317681313,1.79481947422,4.5505027771 --2.40214800835,1.80583262444,4.56907653809 --2.39713931084,1.79583632946,4.54187440872 --2.41511416435,1.79884767532,4.54046201706 --2.4310901165,1.80085849762,4.53605985641 --2.44606637955,1.80086910725,4.52965688705 --2.46104121208,1.80088031292,4.52123069763 --2.47901654243,1.80389142036,4.51982164383 --2.49699211121,1.80690217018,4.51942634583 --2.50198030472,1.80490756035,4.51020860672 --2.51695656776,1.80591821671,4.50380754471 --2.52993249893,1.8049287796,4.49238920212 --2.55390667915,1.81194043159,4.50198793411 --2.55988478661,1.80595016479,4.47857522964 --2.57686042786,1.80796098709,4.47516918182 --2.59483528137,1.81097221375,4.47275400162 --2.59782409668,1.80697703362,4.46053934097 --2.62679696083,1.81898927689,4.47813892365 --2.62377762794,1.8059977293,4.43972587585 --2.63875389099,1.80700814724,4.43332672119 --2.65772843361,1.8100194931,4.43190574646 --2.67270517349,1.81102979183,4.42550754547 --2.68769049644,1.81603622437,4.43329000473 --2.70166754723,1.81604647636,4.42488861084 --2.71764278412,1.81805729866,4.41847133636 --2.72562050819,1.81306707859,4.39905548096 --2.75559329987,1.82507920265,4.41665506363 --2.762570858,1.81908905506,4.3952331543 --2.78254580498,1.82309997082,4.39582586288 --2.78553509712,1.82110476494,4.38461828232 --2.80051136017,1.82111513615,4.3772110939 --2.80749034882,1.81712448597,4.35781145096 --2.83346319199,1.8251363039,4.36638832092 --2.85143828392,1.82814717293,4.36297416687 --2.86541461945,1.82815742493,4.35356283188 --2.86739516258,1.82016599178,4.32716941833 --2.87938213348,1.82317173481,4.32996177673 --2.9023566246,1.83018290997,4.33455514908 --2.9133336544,1.8281929493,4.32013750076 --2.91831350327,1.82220172882,4.29874563217 --2.95328378677,1.8362146616,4.3193192482 --2.96226143837,1.83222436905,4.30190086365 --2.97324895859,1.83522963524,4.30370473862 --2.97622847557,1.82823848724,4.27829551697 --3.00320124626,1.83625030518,4.28687429428 --3.01517939568,1.83625996113,4.27547740936 --3.0281560421,1.83526992798,4.26406049728 --3.04013395309,1.83427965641,4.25266361237 --3.05411076546,1.83428966999,4.24325418472 --3.07109546661,1.84129607677,4.25102806091 --3.08007454872,1.83830523491,4.23563432693 --3.10104966164,1.84331583977,4.23623085022 --3.11602568626,1.84332621098,4.22680425644 --3.13000321388,1.84433591366,4.21841239929 --3.13898158073,1.841345191,4.20200204849 --3.15895700455,1.84535586834,4.2005944252 --3.16794514656,1.84736096859,4.19838857651 --3.18991971016,1.85237181187,4.19897317886 --3.19189977646,1.84538030624,4.17356681824 --3.21187543869,1.84939062595,4.17216300964 --3.2308511734,1.85240101814,4.16875076294 --3.24182915688,1.85141038895,4.15534496307 --3.23981928825,1.84541463852,4.13812971115 --3.26079511642,1.85042512417,4.1377248764 --3.28676915169,1.85843598843,4.14331579208 --3.29374837875,1.85444486141,4.12491178513 --3.30272650719,1.85245418549,4.10849809647 --3.31870222092,1.85346436501,4.10007190704 --3.34667682648,1.86247515678,4.10867834091 --3.34466743469,1.85747909546,4.09247255325 --3.36364388466,1.86148917675,4.08906793594 --3.36362481117,1.85349714756,4.06266880035 --3.39359760284,1.86350858212,4.07124423981 --3.40157699585,1.86051750183,4.05484771729 --3.41155481339,1.8585267067,4.03942871094 --3.43552947044,1.86453747749,4.04101371765 --3.44651722908,1.86754262447,4.04081010818 --3.45249652863,1.86355125904,4.02140235901 --3.46847367287,1.86556088924,4.01399755478 --3.4794511795,1.86357021332,3.99957537651 --3.50142788887,1.86958003044,4.00018787384 --3.51740455627,1.87058997154,3.99177002907 --3.52839231491,1.87359499931,3.9915702343 --3.53137207031,1.86860346794,3.96815013885 --3.54535031319,1.86861264706,3.95875310898 --3.55432844162,1.8666216135,3.94233417511 --3.57330489159,1.87063145638,3.93792748451 --3.58028459549,1.86764001846,3.92052745819 --3.60725879669,1.8756506443,3.9241092205 --3.61124873161,1.87365496159,3.91590881348 --3.62422728539,1.8746638298,3.90551495552 --3.62720632553,1.86867249012,3.88208723068 --3.65618109703,1.87768280506,3.88868880272 --3.65016388893,1.86869013309,3.85728597641 --3.69013524055,1.88270187378,3.8738629818 --3.69111561775,1.87670993805,3.84945058823 --3.68910694122,1.87271356583,3.83525395393 --3.72108078003,1.88272428513,3.84384608269 --3.72206115723,1.8767323494,3.81943035126 --3.74803686142,1.88474237919,3.82203102112 --3.75301647186,1.87975084782,3.80161142349 --3.76399517059,1.87975955009,3.78820466995 --3.77098464966,1.87976384163,3.78401756287 --3.78096294403,1.8787728548,3.76859378815 --3.79394125938,1.87978160381,3.75718641281 --3.81191849709,1.88179087639,3.75077939034 --3.82789635658,1.88479995728,3.74237322807 --3.83787536621,1.88380861282,3.72796678543 --3.84185576439,1.87981665134,3.70755767822 --3.85584330559,1.88382172585,3.70935702324 --3.86282300949,1.88083004951,3.69194841385 --3.87580156326,1.88183867931,3.68054223061 --3.89877748489,1.8868483305,3.67812633514 --3.91275572777,1.88885724545,3.66772246361 --3.92273497581,1.88686549664,3.65331554413 --3.93771338463,1.88887441158,3.64391326904 --3.93670415878,1.8858782053,3.63070297241 --3.95268249512,1.88788700104,3.6223025322 --3.97965741158,1.89589691162,3.62288188934 --3.98363757133,1.89090502262,3.60246729851 --3.9936170578,1.89091336727,3.58805990219 --4.01359415054,1.89492237568,3.58265089989 --4.01258563995,1.89092600346,3.57045507431 --4.04056072235,1.89993560314,3.57204437256 --4.04454183578,1.89594340324,3.55264472961 --4.05652141571,1.89595174789,3.54024195671 --4.07249832153,1.89796078205,3.52981209755 --4.08647727966,1.89996910095,3.51941418648 --4.09645700455,1.89897739887,3.50500750542 --4.10444641113,1.89998149872,3.50081133842 --4.11642503738,1.89998996258,3.4873919487 --4.1334028244,1.90299868584,3.4789853096 --4.13738441467,1.90000629425,3.45958089828 --4.1613612175,1.90601539612,3.45717692375 --4.16134262085,1.90002286434,3.43376040459 --4.19231796265,1.91003215313,3.43736195564 --4.1923084259,1.90703618526,3.42514419556 --4.19728946686,1.9050437212,3.40674066544 --4.20227050781,1.90205156803,3.38833642006 --4.22224807739,1.90606021881,3.38192629814 --4.23422765732,1.90706813335,3.3695268631 --4.2442073822,1.90607607365,3.35512089729 --4.28118133545,1.91808593273,3.36170339584 --4.29716920853,1.92309045792,3.3635058403 --4.30015182495,1.9200977087,3.34411287308 --4.31712961197,1.92310607433,3.33469963074 --4.34410619736,1.93011510372,3.33329129219 --4.35608577728,1.93112301826,3.31987929344 --4.36706590652,1.93113064766,3.30648183823 --4.3950510025,1.94113612175,3.31626844406 --4.40303134918,1.94014382362,3.29986000061 --4.4210100174,1.94315195084,3.29145884514 --4.43299007416,1.94415974617,3.27805018425 --4.4389705658,1.94216740131,3.25963234901 --4.43895339966,1.93717432022,3.23824095726 --4.44793319702,1.9361821413,3.22181677818 --4.4369263649,1.92918503284,3.20261216164 --4.43790864944,1.92519235611,3.18120217323 --4.46088600159,1.93020069599,3.17579078674 --4.45286989212,1.92220723629,3.14838862419 --4.45385169983,1.91821444035,3.12697458267 --4.46083259583,1.91622173786,3.11057281494 --4.46381473541,1.91322886944,3.09116697311 --4.45880699158,1.90923213959,3.07696533203 --4.46778726578,1.90823972225,3.06155347824 --4.45177268982,1.89624595642,3.02914881706 --4.46175289154,1.89625346661,3.01474022865 --4.47273397446,1.89726090431,3.00133752823 --4.47371530533,1.89326822758,2.9799118042 --4.47869682312,1.89127540588,2.96251010895 --4.47068929672,1.88527858257,2.94630074501 --4.46667289734,1.87928533554,2.92289757729 --4.4666557312,1.87529206276,2.90249848366 --4.48063516617,1.8772996664,2.89109277725 --4.47161912918,1.86930656433,2.86366963387 --4.47560119629,1.86731338501,2.84627366066 --4.47559213638,1.8643168211,2.83607172966 --4.49357128143,1.86832475662,2.82665348053 --4.48955535889,1.86233115196,2.80425906181 --4.4905371666,1.85933840275,2.78383827209 --4.49651861191,1.85834550858,2.76743292809 --4.4995007515,1.85535252094,2.74902510643 --4.51648044586,1.85836005211,2.73962163925 --4.51947116852,1.85836350918,2.7314183712 --4.53345060349,1.86037123203,2.71899318695 --4.5394320488,1.85837829113,2.70258712769 --4.52741670609,1.84938454628,2.67517924309 --4.57139205933,1.86439299583,2.68177223206 --4.56337690353,1.85839939117,2.65737390518 --4.58335638046,1.86240661144,2.64998054504 --4.58634662628,1.86241042614,2.64075660706 --4.60332679749,1.86541759968,2.63136053085 --4.5993103981,1.86042416096,2.60895061493 --4.61529064178,1.8634314537,2.59854722023 --4.63027095795,1.86643862724,2.5871360302 --4.64425086975,1.86844599247,2.57471704483 --4.64623355865,1.865452528,2.55631613731 --4.63722658157,1.86045563221,2.54110741615 --4.63720989227,1.85646224022,2.5217063427 --4.6571893692,1.86146950722,2.51330137253 --4.68316793442,1.86947691441,2.50789117813 --4.69015026093,1.86848342419,2.49249362946 --4.69013261795,1.86449027061,2.47207021713 --4.69811487198,1.86449670792,2.45768094063 --4.7041053772,1.86550045013,2.4504635334 --4.70708847046,1.86350691319,2.43306732178 --4.70707082748,1.86051368713,2.41264033318 --4.7180519104,1.86152052879,2.39923810959 --4.73003339767,1.86252725124,2.38582515717 --4.73201704025,1.86053359509,2.36843800545 --4.7280087471,1.85753679276,2.35622429848 --4.73399114609,1.85654354095,2.339812994 --4.74897193909,1.85955023766,2.32841038704 --4.759953022,1.86055707932,2.31398820877 --4.76893520355,1.86156368256,2.29958796501 --4.78291702271,1.86456990242,2.28819894791 --4.78389978409,1.86157667637,2.2687766552 --4.79688930511,1.86458003521,2.26557350159 --4.79887247086,1.86258649826,2.24716114998 --4.81285381317,1.86559307575,2.23475337029 --4.81683731079,1.86459922791,2.21836304665 --4.8258190155,1.86460590363,2.20294260979 --4.82480287552,1.86161220074,2.18353748322 --4.83778429031,1.86361885071,2.17011976242 --4.85477352142,1.86962211132,2.16892504692 --4.87375450134,1.87362849712,2.15851521492 --4.87473773956,1.87163472176,2.1401116848 --4.87672138214,1.86964118481,2.12169694901 --4.88370418549,1.86964726448,2.10629844666 --4.8956861496,1.87165355682,2.09289479256 --4.88567113876,1.86465954781,2.06948542595 --4.89566135406,1.86766278744,2.06427741051 --4.90964365005,1.86966907978,2.05187749863 --4.91462564468,1.86967551708,2.03445363045 --4.91960906982,1.86868155003,2.01805186272 --4.94158983231,1.87468779087,2.00864553452 --4.94757270813,1.87369394302,1.99223542213 --4.9605550766,1.87670004368,1.97882676125 --4.96554660797,1.87770295143,1.97162556648 --4.97252988815,1.8777089119,1.95622885227 --4.97551298141,1.87671530247,1.9378015995 --4.98749542236,1.87872111797,1.92440450191 --4.98847961426,1.8767272234,1.90599441528 --5.00546169281,1.88073289394,1.89459884167 --4.99744606018,1.87473917007,1.87217795849 --5.00643730164,1.87674188614,1.86698758602 --5.02441978455,1.88174772263,1.85558533669 --5.02440309525,1.87875390053,1.83616054058 --5.01838731766,1.87375998497,1.81474077702 --5.04736852646,1.88276565075,1.80733823776 --5.05835103989,1.88577139378,1.79293239117 --5.04234552383,1.87777447701,1.77772879601 --5.04632949829,1.87678015232,1.76133537292 --5.05931138992,1.87978613377,1.74691295624 --5.0542974472,1.87579166889,1.72752475739 --5.06727981567,1.87879753113,1.71310317516 --5.06326389313,1.87380361557,1.69268262386 --5.07624721527,1.87680912018,1.6792845726 --5.09323787689,1.88281166553,1.67608273029 --5.08222293854,1.87681770325,1.65366995335 --5.10220527649,1.8818230629,1.64226543903 --5.08719158173,1.87382900715,1.61885762215 --5.10617399216,1.87883424759,1.60746252537 --5.11515760422,1.88083982468,1.59205305576 --5.11614179611,1.87884557247,1.57363533974 --5.12513303757,1.88084828854,1.56743204594 --5.12211799622,1.8778539896,1.54802024364 --5.14710092545,1.88585889339,1.53863310814 --5.13808584213,1.8798648119,1.51721823215 --5.15406894684,1.88387012482,1.50380706787 --5.14805412292,1.87987601757,1.48339140415 --5.1480383873,1.87788152695,1.46497809887 --5.14403104782,1.8748844862,1.45477604866 --5.17601299286,1.88588917255,1.44637227058 --5.1629986763,1.87889516354,1.4239552021 --5.1799826622,1.88289988041,1.41156494617 --5.18196725845,1.88190531731,1.39416050911 --5.20594978333,1.8899102211,1.38274991512 --5.21293401718,1.88991558552,1.36633741856 --5.20592689514,1.88691854477,1.35512912273 --5.20891237259,1.88592350483,1.3387414217 --5.22689533234,1.89092838764,1.32532858849 --5.23487949371,1.89193367958,1.30891084671 --5.22086620331,1.88593935966,1.28751194477 --5.22785043716,1.88594460487,1.2710994482 --5.23184251785,1.88694727421,1.26289021969 --5.24382686615,1.88995194435,1.24849486351 --5.25481081009,1.89195692539,1.23308348656 --5.26879501343,1.89596164227,1.21867871284 --5.26378059387,1.89196717739,1.19926822186 --5.267765522,1.89197230339,1.18185174465 --5.27375030518,1.89297735691,1.16544747353 --5.27074289322,1.89098012447,1.15523195267 --5.27072906494,1.88998520374,1.13783693314 --5.2807135582,1.89198994637,1.12243425846 --5.29569768906,1.89599442482,1.10802924633 --5.29968261719,1.89599943161,1.09061348438 --5.30866765976,1.89800417423,1.07521867752 --5.31065273285,1.89700937271,1.05679023266 --5.30564546585,1.89401221275,1.04658281803 --5.30963087082,1.89401686192,1.03019011021 --5.31461620331,1.89502191544,1.01276922226 --5.31160211563,1.89202713966,0.994363725185 --5.33358621597,1.89903104305,0.980955719948 --5.32957267761,1.8970361948,0.962554454803 --5.35155677795,1.90304005146,0.949150383472 --5.35554933548,1.90404224396,0.940945923328 --5.34553527832,1.89904785156,0.920524418354 --5.36352109909,1.90505158901,0.907141625881 --5.3695063591,1.9060562849,0.889719486237 --5.38149118423,1.90906047821,0.874319136143 --5.383477211,1.90806531906,0.856914877892 --5.37346315384,1.90307092667,0.836489140987 --5.38045597076,1.90607273579,0.82929700613 --5.38944196701,1.90807712078,0.812887489796 --5.38642787933,1.90608203411,0.794478595257 --5.38941383362,1.90608668327,0.777069330215 --5.41539859772,1.91408979893,0.763668000698 --5.40638494492,1.91009521484,0.744257450104 --5.42037057877,1.91409885883,0.728856563568 --5.41436386108,1.91110169888,0.718644320965 --5.42334985733,1.91310596466,0.702238917351 --5.42633581161,1.9131103754,0.684831440449 --5.44932174683,1.92111349106,0.67042773962 --5.42230844498,1.91012012959,0.648001790047 --5.44829463959,1.91912269592,0.634614467621 --5.44928026199,1.91812741756,0.616190969944 --5.44827318192,1.91712987423,0.606983661652 --5.45625972748,1.91913366318,0.590585649014 --5.48124599457,1.92813634872,0.576185882092 --5.46323251724,1.92014229298,0.555770576 --5.48021888733,1.92614543438,0.54037296772 --5.47520494461,1.9231505394,0.520942866802 --5.45919179916,1.91615605354,0.501540184021 --5.47518491745,1.92115724087,0.494335174561 --5.49517154694,1.92816007137,0.47893434763 --5.49015808105,1.92616486549,0.460526078939 --5.49814462662,1.92816865444,0.44311016798 --5.50013160706,1.92817282677,0.425708532333 --5.50511789322,1.92917668819,0.40830039978 --5.51411151886,1.93217813969,0.400094360113 --5.53209781647,1.93818104267,0.383684009314 --5.51708507538,1.93218660355,0.364271402359 --5.49507236481,1.92319273949,0.344869852066 --5.52105951309,1.93219459057,0.329469978809 --5.52404546738,1.93319880962,0.311044037342 --5.54803323746,1.94120073318,0.295653223991 --5.5510263443,1.94220256805,0.286438822746 --5.53401327133,1.93520843983,0.267023354769 --5.55000066757,1.94021105766,0.25062584877 --5.55498790741,1.94221460819,0.233222559094 --5.55397510529,1.94121897221,0.214804768562 --5.56496191025,1.94422209263,0.19739484787 --5.57594966888,1.94822502136,0.179986089468 --5.57094287872,1.94622755051,0.170782804489 --5.57193088531,1.9462313652,0.153386339545 --5.56691837311,1.94423592091,0.134972602129 --5.56290531158,1.9422403574,0.116557151079 --5.56889295578,1.94424378872,0.0991555303335 --5.57388114929,1.9452470541,0.0817556455731 --5.56486797333,1.9422519207,0.0633427426219 --5.57686185837,1.94625294209,0.0541247390211 --5.56484889984,1.94125807285,0.0357129052281 --5.56683731079,1.94226157665,0.0183148980141 --5.56182432175,1.93926608562,-0.000102669800981 --5.56481218338,1.94026958942,-0.0175010673702 --5.56279993057,1.93927371502,-0.0359208732843 --5.55978727341,1.93827807903,-0.0543409474194 --5.5597820282,1.93827986717,-0.0625280663371 --5.58276987076,1.94628095627,-0.0799284353852 --5.56675767899,1.94028663635,-0.09834703058 --5.56874513626,1.94129025936,-0.116767682135 --5.54973268509,1.93429613113,-0.13416673243 --5.55572032928,1.93629932404,-0.152587637305 --5.54671430588,1.93330228329,-0.161800429225 --5.54070186615,1.93030667305,-0.179200723767 --5.56569099426,1.93930733204,-0.197614341974 --5.54667854309,1.93331336975,-0.215020343661 --5.54266643524,1.93131744862,-0.232421055436 --5.55365467072,1.9353197813,-0.250837177038 --5.54464244843,1.93232440948,-0.268241465092 --5.55563116074,1.93632674217,-0.286655753851 --5.55162477493,1.93532907963,-0.295869737864 --5.56261396408,1.93933105469,-0.31325879693 --5.56060218811,1.93833506107,-0.33168143034 --5.5655913353,1.94033765793,-0.34907412529 --5.55757856369,1.93734240532,-0.367503166199 --5.56856775284,1.94234442711,-0.385911941528 --5.56555652618,1.94134819508,-0.403312414885 --5.56154966354,1.9393504858,-0.412527412176 --5.55953884125,1.93935406208,-0.429927438498 --5.55852651596,1.93935775757,-0.448349535465 --5.56151580811,1.94036066532,-0.465742260218 --5.56950521469,1.94436299801,-0.484150379896 --5.56149339676,1.94136738777,-0.501559495926 --5.57248830795,1.94536757469,-0.511774539948 --5.55847549438,1.94037282467,-0.529194533825 --5.56446456909,1.94337534904,-0.547603845596 --5.56945466995,1.94537770748,-0.564990520477 --5.56444263458,1.94438183308,-0.583419322968 --5.57443284988,1.94838345051,-0.601818144321 --5.59142351151,1.95538413525,-0.621223926544 --5.59441804886,1.95638525486,-0.630425870419 --5.59540700912,1.95738816261,-0.648840069771 --5.60739707947,1.96238946915,-0.668251991272 --5.60938596725,1.96339225769,-0.686662197113 --5.63937854767,1.97539055347,-0.70705062151 --5.6263666153,1.97139561176,-0.724472224712 --5.62335586548,1.9703990221,-0.741869688034 --5.63335132599,1.9743989706,-0.752073287964 --5.62233972549,1.97140359879,-0.769491791725 --5.62232875824,1.97140657902,-0.787904262543 --5.63431978226,1.97640752792,-0.807305812836 --5.64531087875,1.98140847683,-0.826708316803 --5.63429880142,1.97741317749,-0.844127893448 --5.63228845596,1.97741639614,-0.8625446558 --5.63128328323,1.97741794586,-0.871752977371 --5.65627527237,1.98841643333,-0.893153905869 --5.64726400375,1.98542070389,-0.910568118095 --5.66125535965,1.99142110348,-0.930976510048 --5.65224504471,1.98942518234,-0.947368741035 --5.65323448181,1.99042773247,-0.966795563698 --5.64922428131,1.9894310236,-0.984194040298 --5.63121700287,1.98343551159,-0.991415679455 --5.65320968628,1.99243426323,-1.01281309128 --5.62219572067,1.982442379,-1.02724254131 --5.61418533325,1.98044621944,-1.04363536835 --5.61717557907,1.98244833946,-1.06305515766 --5.61616563797,1.98245108128,-1.08146679401 --5.60615491867,1.98045527935,-1.09786891937 --5.62015151978,1.98545396328,-1.11008489132 --5.6081404686,1.98245882988,-1.12649524212 --5.60112953186,1.98046243191,-1.14390861988 --5.60912132263,1.98446333408,-1.16330492496 --5.60111045837,1.98246729374,-1.18072283268 --5.60110139847,1.98446965218,-1.19912970066 --5.58708953857,1.98047471046,-1.21555244923 --5.59108543396,1.98247516155,-1.22576057911 --5.58407449722,1.98047876358,-1.2431756258 --5.58306503296,1.98148143291,-1.26158642769 --5.57405471802,1.97948539257,-1.2779892683 --5.61105108261,1.99448037148,-1.30439996719 --5.58203744888,1.98448824883,-1.31680715084 --5.56402492523,1.97949421406,-1.33223223686 --5.56802129745,1.98149442673,-1.34243762493 --5.55901098251,1.97949838638,-1.35884237289 --5.55500125885,1.97950136662,-1.37624514103 --5.55699205399,1.98150312901,-1.39566195011 --5.54998207092,1.98050665855,-1.41307997704 --5.5459728241,1.98050951958,-1.43048262596 --5.53996706009,1.97851192951,-1.43869388103 --5.55996179581,1.98750984669,-1.46210217476 --5.52694702148,1.9765188694,-1.47352743149 --5.51593637466,1.97352313995,-1.48892462254 --5.50792598724,1.97252690792,-1.50635123253 --5.5209197998,1.97852599621,-1.52774846554 --5.50390720367,1.97353172302,-1.54318153858 --5.52390670776,1.9825284481,-1.55737948418 --5.50689506531,1.97753405571,-1.57179093361 --5.51188755035,1.98053467274,-1.59118556976 --5.51087856293,1.98253691196,-1.61061501503 --5.48686599731,1.97454404831,-1.62302732468 --5.46985387802,1.96954977512,-1.63744413853 --5.46884536743,1.97155177593,-1.65585279465 --5.46984100342,1.97255253792,-1.66606962681 --5.46883249283,1.973554492,-1.68447721004 --5.45882225037,1.97155845165,-1.69987511635 --5.4488120079,1.96956264973,-1.71629607677 --5.44780397415,1.97156453133,-1.73470377922 --5.4467959404,1.9725664854,-1.75311040878 --5.42778348923,1.96657264233,-1.7665258646 --5.42377853394,1.96657443047,-1.77473115921 --5.43877363205,1.97357237339,-1.79814016819 --5.42676353455,1.97157692909,-1.81355476379 --5.41075134277,1.96658241749,-1.82797551155 --5.41274404526,1.96958351135,-1.8473829031 --5.40373420715,1.96858727932,-1.86380076408 --5.38672208786,1.96359288692,-1.8772097826 --5.38871860504,1.9655932188,-1.88843917847 --5.38370990753,1.96559596062,-1.90585148335 --5.40170669556,1.97459292412,-1.9302495718 --5.37469244003,1.96660113335,-1.94066882133 --5.35768079758,1.96160697937,-1.95408248901 --5.36467456818,1.96660649776,-1.97549319267 --5.35566520691,1.964610219,-1.99089157581 --5.35566139221,1.96661090851,-2.00111198425 --5.34565162659,1.96461486816,-2.01651859283 --5.33264064789,1.96161961555,-2.03194952011 --5.3426361084,1.96761822701,-2.05435419083 --5.32462406158,1.96262407303,-2.06675958633 --5.31861495972,1.96262693405,-2.08418035507 --5.31860780716,1.96462833881,-2.10359621048 --5.30160045624,1.95963346958,-2.10680007935 --5.29959201813,1.96063506603,-2.12521028519 --5.30058526993,1.96363604069,-2.14461731911 --5.29257631302,1.96263933182,-2.16103291512 --5.27756500244,1.95964467525,-2.17546391487 --5.27555799484,1.9606461525,-2.19387316704 --5.26854896545,1.96064925194,-2.21028113365 --5.25754261017,1.95765280724,-2.21548438072 --5.25653553009,1.959654212,-2.23490643501 --5.23752355576,1.95466053486,-2.24631094933 --5.2335152626,1.95566260815,-2.26473784447 --5.23751020432,1.95966243744,-2.28513622284 --5.2094950676,1.9506714344,-2.29355931282 --5.21049213409,1.95267152786,-2.3037674427 --5.20848417282,1.95467317104,-2.32319736481 --5.19747495651,1.9526771307,-2.33760046959 --5.18546485901,1.95068156719,-2.35201334953 --5.19446086884,1.95667982101,-2.37542700768 --5.16644620895,1.94868886471,-2.38283896446 --5.15843725204,1.94769203663,-2.39925932884 --5.17744016647,1.95668673515,-2.41746783257 --5.16342973709,1.95369172096,-2.43087983131 --5.13641452789,1.94570064545,-2.43828845024 --5.13640832901,1.94870126247,-2.45769739151 --5.11939716339,1.94470727444,-2.47012019157 --5.12039089203,1.94770753384,-2.4905397892 --5.12338638306,1.95170724392,-2.51195955276 --5.094373703,1.94171667099,-2.50816130638 --5.09036636353,1.94271850586,-2.52658677101 --5.10636615753,1.95171403885,-2.55298161507 --5.07334899902,1.94172501564,-2.55739974976 --5.0593380928,1.93873000145,-2.57082009315 --5.06533479691,1.9447286129,-2.59322810173 --5.04932308197,1.94073414803,-2.60564827919 --5.03331232071,1.93773984909,-2.61807012558 --5.04131221771,1.94273746014,-2.63228440285 --5.0192990303,1.93574500084,-2.64068508148 --5.02029371262,1.93974506855,-2.66109919548 --5.01728725433,1.94174647331,-2.67951202393 --5.01027917862,1.94174909592,-2.69592499733 --4.99526834488,1.93875443935,-2.70936059952 --4.98826313019,1.93775689602,-2.71556329727 --4.96224784851,1.92976593971,-2.72197318077 --4.95924186707,1.93176734447,-2.74038624763 --4.94823265076,1.93077123165,-2.75480341911 --4.94222450256,1.93077349663,-2.77222776413 --4.93221569061,1.93077719212,-2.78663444519 --4.93121051788,1.93377768993,-2.80604457855 --4.91019964218,1.92678511143,-2.80628180504 --4.90619325638,1.92778658867,-2.82368373871 --4.8991856575,1.92878913879,-2.8400990963 --4.88117361069,1.92479550838,-2.85051560402 --4.87616682053,1.92579746246,-2.86792874336 --4.86615753174,1.92480099201,-2.88335824013 --4.8471455574,1.91980791092,-2.89276862144 --4.84114074707,1.91981005669,-2.89998579025 --4.85214042664,1.92780590057,-2.92639660835 --4.84413290024,1.9278087616,-2.94180250168 --4.8371257782,1.92881131172,-2.95821714401 --4.8211145401,1.92481696606,-2.96963596344 --4.79409837723,1.91782689095,-2.97506642342 --4.79009199142,1.9198281765,-2.99348735809 --4.78608846664,1.91982960701,-3.00068068504 --4.78408336639,1.92183017731,-3.02009654045 --4.76206970215,1.9168381691,-3.02751231194 --4.75906419754,1.91883909702,-3.04591965675 --4.73705005646,1.91284716129,-3.05435848236 --4.72804164886,1.91285037994,-3.06875920296 --4.72303581238,1.91485190392,-3.08617091179 --4.72503471375,1.91785097122,-3.09839081764 --4.71102428436,1.91585600376,-3.11081409454 --4.69401264191,1.91186225414,-3.12021517754 --4.68000221252,1.90986740589,-3.13263988495 --4.67399549484,1.91086924076,-3.15006351471 --4.66098594666,1.90887403488,-3.16247677803 --4.64797639847,1.90787863731,-3.17489075661 --4.64697408676,1.90887880325,-3.18510651588 --4.64396953583,1.91187930107,-3.20351004601 --4.62495660782,1.90788650513,-3.21294355392 --4.60794448853,1.90389299393,-3.22235178947 --4.59893703461,1.90389597416,-3.23777484894 --4.58692789078,1.90290021896,-3.2501783371 --4.58392333984,1.90590071678,-3.26960086823 --4.57891893387,1.90590250492,-3.27680897713 --4.56290769577,1.9029084444,-3.2872273922 --4.56290435791,1.90690755844,-3.30864691734 --4.5358877182,1.89991819859,-3.31207871437 --4.55589532852,1.91290867329,-3.34647870064 --4.52687740326,1.90392041206,-3.34790062904 --4.51386785507,1.90192496777,-3.36031961441 --4.50286054611,1.89992928505,-3.36353373528 --4.49485349655,1.89993178844,-3.37894320488 --4.49385070801,1.90393126011,-3.39935231209 --4.49484872818,1.90892970562,-3.42177081108 --4.48083877563,1.90693473816,-3.43318533897 --4.45782327652,1.90194380283,-3.43861246109 --4.44081163406,1.89795041084,-3.44803309441 --4.43880987167,1.89995062351,-3.45723843575 --4.43680620193,1.90295040607,-3.47765755653 --4.4127907753,1.89696002007,-3.48208475113 --4.40378332138,1.89796280861,-3.49750876427 --4.41378736496,1.90695691109,-3.52590513229 --4.38877105713,1.89996707439,-3.52933073044 --4.37175941467,1.89397442341,-3.52754354477 --4.35975122452,1.89297866821,-3.53995394707 --4.35374593735,1.89497995377,-3.55737185478 --4.34974145889,1.89798045158,-3.57679724693 --4.33873319626,1.89798414707,-3.5902121067 --4.31571817398,1.89199352264,-3.59463596344 --4.32172060013,1.89998912811,-3.62104225159 --4.31271409988,1.89799261093,-3.6252553463 --4.29270029068,1.89300072193,-3.6316742897 --4.28169250488,1.89300441742,-3.64509034157 --4.27868938446,1.89700400829,-3.66551589966 --4.25867557526,1.89301216602,-3.67193865776 --4.24566602707,1.89101696014,-3.68334817886 --4.24766731262,1.8980140686,-3.70776939392 --4.24566507339,1.89901423454,-3.71696949005 --4.21264266968,1.88902878761,-3.71341109276 --4.21564435959,1.89502537251,-3.73781394958 --4.19462919235,1.89003407955,-3.74323868752 --4.18061971664,1.88903927803,-3.75364804268 --4.17961835861,1.89303779602,-3.77607321739 --4.16160583496,1.89004504681,-3.78349065781 --4.17061233521,1.89703917503,-3.80269837379 --4.15059804916,1.89304745197,-3.8091301918 --4.15360021591,1.90004372597,-3.83454179764 --4.12457990646,1.89105689526,-3.83195519447 --4.12157773972,1.8950561285,-3.85237050056 --4.10756778717,1.89306128025,-3.86379933357 --4.08755397797,1.88906955719,-3.86921787262 --4.11057090759,1.90305602551,-3.90142297745 --4.0825510025,1.89506864548,-3.89984560013 --4.07054281235,1.89507269859,-3.9122607708 --4.05353069305,1.89207947254,-3.92068648338 --4.0415225029,1.89108359814,-3.93310213089 --4.02851343155,1.8910882473,-3.94451713562 --4.02751398087,1.89608609676,-3.96794581413 --4.01150226593,1.89109385014,-3.96414279938 --4.00149536133,1.89109671116,-3.97856092453 --3.99048805237,1.89209997654,-3.9929959774 --3.97347640991,1.8891068697,-4.00040864944 --3.9664721489,1.89110815525,-4.01782846451 --3.9584672451,1.89310979843,-4.03424739838 --3.94645929337,1.89311373234,-4.0476808548 --3.94946241379,1.89811050892,-4.06187534332 --3.92144179344,1.88912391663,-4.05828619003 --3.9014275074,1.88513255119,-4.06371927261 --3.89042043686,1.88613605499,-4.07713794708 --3.88842058182,1.89113402367,-4.0995554924 --3.85639595985,1.88014996052,-4.0919752121 --3.84138584137,1.87915563583,-4.10241270065 --3.84639072418,1.88415110111,-4.11860179901 --3.81937074661,1.87716412544,-4.11704397202 --3.82337617874,1.88515841961,-4.14545536041 --3.80436229706,1.88216662407,-4.15087842941 --3.77934360504,1.87517869473,-4.15030765533 --3.78835391998,1.88616979122,-4.18371009827 --3.76533651352,1.8801804781,-4.18513870239 --3.75332736969,1.87718617916,-4.18535470963 --3.74632406235,1.88018703461,-4.20276927948 --3.74332404137,1.88418531418,-4.22417783737 --3.71630334854,1.87719869614,-4.221616745 --3.69929099083,1.87420594692,-4.22802686691 --3.68428087234,1.87321186066,-4.23745250702 --3.69228935242,1.88020479679,-4.25865745544 --3.66827106476,1.87421643734,-4.25808048248 --3.65726447105,1.87521982193,-4.27149963379 --3.63324570656,1.86923158169,-4.27092695236 --3.62223887444,1.86923491955,-4.28434658051 --3.62924933434,1.88022601604,-4.31877708435 --3.60422968864,1.87323880196,-4.31619262695 --3.59021806717,1.86924600601,-4.31340551376 --3.57220506668,1.86625397205,-4.3188252449 --3.56420135498,1.86925518513,-4.33625364304 --3.56220364571,1.87525236607,-4.35966539383 --3.5471932888,1.87325823307,-4.36909341812 --3.5281791687,1.87026691437,-4.37351846695 --3.50816369057,1.8662763834,-4.37593126297 --3.50716519356,1.86927485466,-4.38814353943 --3.49515771866,1.86927866936,-4.40056419373 --3.47814512253,1.86628627777,-4.40596961975 --3.46313548088,1.86629199982,-4.41641807556 --3.45313000679,1.86729454994,-4.43083286285 --3.42610692978,1.85930931568,-4.42424488068 --3.42611217499,1.86630439758,-4.45167064667 --3.41210055351,1.86231195927,-4.44889497757 --3.39809131622,1.86231744289,-4.45831012726 --3.38508319855,1.86232197285,-4.46973609924 --3.38308620453,1.86831867695,-4.49313306808 --3.35506272316,1.86033403873,-4.48758983612 --3.34005188942,1.85834026337,-4.49499416351 --3.32303953171,1.8563477993,-4.50142335892 --3.32504487038,1.86134362221,-4.51762962341 --3.30502891541,1.85735368729,-4.51904249191 --3.29302167892,1.85735750198,-4.53146457672 --3.28301715851,1.86035966873,-4.54689311981 --3.26500344276,1.85736811161,-4.55131387711 --3.24398612976,1.85237896442,-4.55173587799 --3.2439930439,1.8603733778,-4.58015775681 --3.23098158836,1.85638058186,-4.57737445831 --3.21797370911,1.85738515854,-4.58880186081 --3.20096087456,1.85439312458,-4.59320545197 --3.19195747375,1.85739445686,-4.60962677002 --3.17494511604,1.85540211201,-4.61606121063 --3.15592980385,1.85141146183,-4.61847829819 --3.14792823792,1.85541200638,-4.63690710068 --3.14392757416,1.85741209984,-4.64612054825 --3.12090754509,1.85142469406,-4.64354944229 --3.10990166664,1.85242772102,-4.6569647789 --3.09689426422,1.85343229771,-4.66839265823 --3.08188414574,1.85243833065,-4.67681837082 --3.06787467003,1.85144388676,-4.68522357941 --3.05686950684,1.85344672203,-4.69965267181 --3.0448589325,1.85045349598,-4.69787406921 --3.03285241127,1.85145711899,-4.71029472351 --3.01283597946,1.84746754169,-4.71172809601 --3.0038330555,1.85046887398,-4.72712850571 --2.99182701111,1.85147225857,-4.7405629158 --2.97180986404,1.8474830389,-4.74098396301 --2.96180653572,1.85048484802,-4.75640439987 --2.9548022747,1.85048747063,-4.76162147522 --2.93478512764,1.84649813175,-4.76204586029 --2.91977524757,1.84550440311,-4.7704744339 --2.90977168083,1.84850621223,-4.78589344025 --2.88975477219,1.84451687336,-4.7863202095 --2.8807528019,1.84751772881,-4.80374383926 --2.87675261497,1.84951770306,-4.81295108795 --2.85172843933,1.84253311157,-4.80538034439 --2.84573054314,1.84753131866,-4.82679128647 --2.8397333622,1.85352909565,-4.849214077 --2.83573961258,1.86052453518,-4.87665700912 --2.80370497704,1.84854698181,-4.85708332062 --2.78969621658,1.84855222702,-4.86650466919 --2.77368426323,1.84655964375,-4.87191724777 --2.76467704773,1.84556436539,-4.87312650681 --2.76168513298,1.85355889797,-4.90155506134 --2.74166750908,1.84957003593,-4.90097761154 --2.71864581108,1.84358406067,-4.89641618729 --2.70463657379,1.84358966351,-4.90482664108 --2.68862462044,1.84259712696,-4.91024208069 --2.69564247131,1.85258555412,-4.93945646286 --2.67161822319,1.84560096264,-4.93188285828 --2.64959764481,1.83961415291,-4.92831850052 --2.63759255409,1.84261739254,-4.94174766541 --2.62759041786,1.84561860561,-4.95816850662 --2.60556840897,1.83963251114,-4.95258283615 --2.5925617218,1.84063673019,-4.96400880814 --2.58655905724,1.84163844585,-4.97021627426 --2.56754231453,1.83764910698,-4.97064113617 --2.55754065514,1.84165012836,-4.98706007004 --2.54353260994,1.84265530109,-4.99749517441 --2.52651977539,1.84066343307,-5.00293684006 --2.50850439072,1.83767330647,-5.00435400009 --2.49850273132,1.84167432785,-5.02077054977 --2.48949503899,1.83967912197,-5.02198505402 --2.47248148918,1.83768785,-5.02540540695 --2.45947504044,1.83969199657,-5.03682947159 --2.43745279312,1.83370625973,-5.03125905991 --2.42344498634,1.83471131325,-5.04169464111 --2.41444587708,1.83971083164,-5.06111955643 --2.39542841911,1.8357219696,-5.06054162979 --2.38642096519,1.83472681046,-5.06175899506 --2.38042712212,1.84172308445,-5.0861697197 --2.35439682007,1.83274245262,-5.07159566879 --2.34139037132,1.83374655247,-5.08301877975 --2.3343963623,1.84074306488,-5.10845947266 --2.30435729027,1.82776784897,-5.08387327194 --2.29034900665,1.82877314091,-5.09329748154 --2.29236292839,1.83676469326,-5.11751556396 --2.26633095741,1.82678484917,-5.10093259811 --2.25733351707,1.83278369904,-5.12237071991 --2.2453289032,1.83478677273,-5.13477945328 --2.22430729866,1.82980060577,-5.13021469116 --2.21130132675,1.83180463314,-5.14163589478 --2.20830535889,1.83580231667,-5.15484428406 --2.18928790092,1.83181357384,-5.15427732468 --2.18129324913,1.83881056309,-5.17871665955 --2.15926885605,1.83282625675,-5.17013835907 --2.14425778389,1.83183336258,-5.17554187775 --2.13426017761,1.83783245087,-5.19699335098 --2.10922884941,1.82885229588,-5.18141841888 --2.09321594238,1.82686066628,-5.18482685089 --2.09222555161,1.83385503292,-5.20404291153 --2.07721590996,1.83386147022,-5.21146774292 --2.06120419502,1.83286929131,-5.21689558029 --2.05020427704,1.83786976337,-5.2353348732 --2.02717518806,1.82888793945,-5.22174215317 --2.0111644268,1.82889533043,-5.22818183899 --2.01117753983,1.83688759804,-5.25140523911 --1.98313760757,1.82491266727,-5.22683095932 --1.9731388092,1.82891237736,-5.24524307251 --1.95612382889,1.82692217827,-5.24665927887 --1.94412302971,1.8319234848,-5.264108181 --1.92109417915,1.8239415884,-5.25153779984 --1.9080889225,1.82594561577,-5.26295375824 --1.90008211136,1.82495009899,-5.26415538788 --1.88607525826,1.82695484161,-5.2745847702 --1.87006294727,1.82596313953,-5.27900743484 --1.85505461693,1.8269687891,-5.28845119476 --1.84104812145,1.82897365093,-5.29888010025 --1.83506250381,1.83896577358,-5.33130931854 -2.16618251801,1.76119565964,-4.27621078491 -2.16316795349,1.75318837166,-4.25241231918 -2.1791806221,1.75419080257,-4.24782991409 -2.19419145584,1.75419270992,-4.24223709106 -2.20519542694,1.75119173527,-4.22963428497 -2.22621822357,1.75719833374,-4.2360367775 -2.24423480034,1.76020240784,-4.2364397049 -2.25624036789,1.75820207596,-4.22484779358 -2.25422811508,1.75019586086,-4.20306158066 -2.27424907684,1.75520157814,-4.20746183395 -2.2942700386,1.76020753384,-4.21284818649 -2.30226755142,1.75420415401,-4.19227695465 -2.31627726555,1.75420558453,-4.18567228317 -2.34030485153,1.7622140646,-4.19707202911 -2.34930515289,1.7582116127,-4.17948865891 -2.36732983589,1.76722025871,-4.19766712189 -2.37332487106,1.76021564007,-4.17409181595 -2.38933777809,1.76121842861,-4.17049360275 -2.39934015274,1.75821685791,-4.1549115181 -2.43238210678,1.77223110199,-4.18229866028 -2.4293627739,1.75922107697,-4.14371967316 -2.4413690567,1.75822114944,-4.13312101364 -2.45238041878,1.76022446156,-4.136323452 -2.47240042686,1.76522994041,-4.1407084465 -2.47939825058,1.76022672653,-4.12012767792 -2.49641251564,1.76223015785,-4.11753606796 -2.5094203949,1.76123082638,-4.10794687271 -2.53044176102,1.7672368288,-4.11333560944 -2.54144668579,1.76523637772,-4.10074186325 -2.55345892906,1.76824009418,-4.10494804382 -2.56045722961,1.76323711872,-4.08437395096 -2.58448290825,1.7702447176,-4.09475708008 -2.58547282219,1.7612388134,-4.06616306305 -2.6104991436,1.76924645901,-4.07557725906 -2.61249065399,1.76024115086,-4.04898262024 -2.63051176071,1.76824808121,-4.06219100952 -2.64051556587,1.76524746418,-4.04859304428 -2.65953326225,1.76925206184,-4.04998207092 -2.67654705048,1.77125501633,-4.04639577866 -2.68955540657,1.77125597,-4.0368065834 -2.7015619278,1.7692565918,-4.02621078491 -2.71356916428,1.76925718784,-4.01561498642 -2.71756958961,1.76725637913,-4.00682401657 -2.72356796265,1.76125359535,-3.98624372482 -2.74558973312,1.7672598362,-3.9926211834 -2.7555937767,1.76525914669,-3.97804141045 -2.78562569618,1.77626907825,-3.99444007874 -2.78561639786,1.7672637701,-3.96585178375 -2.80463290215,1.77026772499,-3.96526074409 -2.82565689087,1.78027558327,-3.9824514389 -2.83465957642,1.77627468109,-3.96686601639 -2.82964420319,1.76526713371,-3.93128156662 -2.8556702137,1.77327477932,-3.94167280197 -2.87468671799,1.77627885342,-3.94107699394 -2.87467765808,1.76727390289,-3.91151547432 -2.88368153572,1.7652733326,-3.896920681 -2.89969849586,1.77127861977,-3.90710020065 -2.9066991806,1.76727712154,-3.8885242939 -2.92771792412,1.77128207684,-3.89092278481 -2.92871165276,1.76427817345,-3.86533141136 -2.95974302292,1.77528738976,-3.88073444366 -2.97275185585,1.77528870106,-3.87114644051 -2.98976588249,1.7782920599,-3.8685336113 -2.97874879837,1.76728522778,-3.83975219727 -3.0067756176,1.77629292011,-3.85016226768 -3.02178692818,1.77729535103,-3.84455370903 -3.03579711914,1.7782971859,-3.8369550705 -3.03879380226,1.77129459381,-3.81436896324 -3.05781006813,1.77529835701,-3.81277751923 -3.06381058693,1.77129709721,-3.79419136047 -3.08182859421,1.77830243111,-3.80439209938 -3.09283471107,1.7763030529,-3.79181194305 -3.11785793304,1.78430950642,-3.79919338226 -3.12285733223,1.77930796146,-3.77960515022 -3.14487671852,1.78531301022,-3.78200292587 -3.13986515999,1.7743074894,-3.74844408035 -3.15187573433,1.7773103714,-3.75064635277 -3.16188168526,1.77631092072,-3.73903226852 -3.17489075661,1.77631258965,-3.72944521904 -3.18789982796,1.77631413937,-3.71985793114 -3.22393393517,1.78932416439,-3.73924541473 -3.21692109108,1.77831852436,-3.70467615128 -3.24895071983,1.7893269062,-3.71807813644 -3.23493289948,1.77732050419,-3.68829846382 -3.24293684959,1.77432048321,-3.67271399498 -3.26295375824,1.77932476997,-3.67309570312 -3.27396059036,1.77832567692,-3.66051912308 -3.29698014259,1.78433084488,-3.66292190552 -3.30198121071,1.78032982349,-3.64433121681 -3.31298828125,1.77933108807,-3.63273859024 -3.32900285721,1.78533518314,-3.63992261887 -3.35402417183,1.79234063625,-3.64333987236 -3.36603236198,1.79234218597,-3.63373041153 -3.36402630806,1.78333902359,-3.606164217 -3.38904738426,1.79034471512,-3.61056065559 -3.3940486908,1.78634393215,-3.59099125862 -3.40605688095,1.78634548187,-3.58138298988 -3.40105056763,1.78034293652,-3.56359767914 -3.42607140541,1.78734838963,-3.56700658798 -3.44508647919,1.79135203362,-3.5644056797 -3.46009778976,1.79235458374,-3.55681681633 -3.45609092712,1.78335142136,-3.52824449539 -3.46910047531,1.78435337543,-3.51963710785 -3.47610569,1.78535461426,-3.51583361626 -3.4690964222,1.77435088158,-3.48426604271 -3.49211525917,1.7803555727,-3.48468279839 -3.51613473892,1.78736078739,-3.48806238174 -3.53514957428,1.79036438465,-3.48447346687 -3.54715800285,1.79036593437,-3.47289872169 -3.56517219543,1.79436933994,-3.46928906441 -3.56416988373,1.79036843777,-3.4574842453 -3.57217502594,1.78836894035,-3.44191026688 -3.58518481255,1.78937113285,-3.4323182106 -3.60620117188,1.7943751812,-3.43072319031 -3.61320543289,1.79137563705,-3.41513299942 -3.61920881271,1.7883759737,-3.3985440731 -3.62821507454,1.78737711906,-3.3849542141 -3.63522028923,1.78737831116,-3.38016700745 -3.66824674606,1.79838526249,-3.39055752754 -3.66023874283,1.78838229179,-3.35998272896 -3.67324852943,1.78938448429,-3.3494079113 -3.66724228859,1.78038215637,-3.32181882858 -3.67724967003,1.77938377857,-3.30923128128 -3.64922571182,1.7593767643,-3.26066064835 -3.62220358849,1.74237024784,-3.2238881588 -3.62120270729,1.73636972904,-3.20032668114 -3.62420487404,1.73236989975,-3.18174219131 -3.58617448807,1.70736145973,-3.12419605255 -3.59117889404,1.70436239243,-3.10859656334 -3.60519051552,1.70636546612,-3.1000187397 -3.5991859436,1.70036411285,-3.08422803879 -3.61820149422,1.70436811447,-3.08063960075 -3.6302113533,1.7053706646,-3.07104611397 -3.6292116642,1.70037066936,-3.05044436455 -3.64822697639,1.70437455177,-3.04685354233 -3.65523314476,1.70237624645,-3.03227305412 -3.66924476624,1.70437920094,-3.02467393875 -3.67524981499,1.70438051224,-3.01889681816 -3.69126319885,1.70738399029,-3.01231026649 -3.69026350975,1.70138406754,-2.99171590805 -3.69026494026,1.69638454914,-2.97212052345 -3.69226789474,1.69238555431,-2.95256090164 -3.68826651573,1.68538534641,-2.9299633503 -3.69727468491,1.68438756466,-2.91738319397 -3.697275877,1.68238794804,-2.90758895874 -3.69827842712,1.67738890648,-2.88801980019 -3.71229028702,1.68039214611,-2.88042187691 -3.72330021858,1.68039488792,-2.86983561516 -3.71929955482,1.67339491844,-2.84724926949 -3.7343120575,1.67639839649,-2.84064626694 -3.75032544136,1.67940199375,-2.83405947685 -3.73631739616,1.67040038109,-2.81229019165 -3.75032925606,1.67240357399,-2.80469179153 -3.77835059166,1.68040907383,-2.80711126328 -3.75733923912,1.66640686989,-2.77152991295 -3.77835583687,1.67141127586,-2.76893901825 -3.78236150742,1.66841316223,-2.75334644318 -3.80237746239,1.67341732979,-2.74975752831 -3.79037117958,1.66641628742,-2.73097038269 -3.82039356232,1.6754219532,-2.73536992073 -3.8023853302,1.66242086887,-2.70181322098 -3.83040618896,1.67142605782,-2.70519852638 -3.82040309906,1.66242623329,-2.67862439156 -3.8374171257,1.66642999649,-2.67302656174 -3.82641386986,1.65643012524,-2.64546394348 -3.85943603516,1.66943538189,-2.66065907478 -3.85643768311,1.66443657875,-2.64007139206 -3.84943699837,1.65643727779,-2.61648964882 -3.85244250298,1.65343940258,-2.59991335869 -3.86145186424,1.6534422636,-2.58832097054 -3.87746548653,1.6574460268,-2.58172631264 -3.8764667511,1.65444684029,-2.57193374634 -3.88247442245,1.65344941616,-2.5573618412 -3.88848185539,1.65145206451,-2.54376840591 -3.9034948349,1.65445566177,-2.5361790657 -3.89849615097,1.64845705032,-2.51459741592 -3.90750575066,1.64846014977,-2.5030066967 -3.91451430321,1.64746308327,-2.48943042755 -3.90651154518,1.64246320724,-2.47562718391 -3.90851736069,1.63946557045,-2.45904564857 -3.92953372002,1.64446985722,-2.45545482635 -3.93354058266,1.64247250557,-2.44085812569 -3.9345459938,1.63947486877,-2.42328667641 -3.94755792618,1.6414784193,-2.41468787193 -3.96057009697,1.64348196983,-2.40511107445 -3.95156741142,1.63748240471,-2.39032483101 -3.96557998657,1.63948607445,-2.38174033165 -3.97559022903,1.64048933983,-2.37114191055 -3.97459506989,1.63649177551,-2.3525698185 -3.99060821533,1.63949561119,-2.34596586227 -4.02263021469,1.65050089359,-2.34838032722 -4.01262807846,1.64450132847,-2.33358621597 -4.02564001083,1.64650499821,-2.32400560379 -4.02264356613,1.64150726795,-2.30540823936 -4.0356554985,1.64351093769,-2.29582762718 -4.04666662216,1.6445145607,-2.28524136543 -4.05067443848,1.64251768589,-2.26967453957 -4.05968427658,1.64352083206,-2.25905990601 -4.06368923187,1.64352250099,-2.25228095055 -4.06569576263,1.64052557945,-2.23571181297 -4.06870269775,1.63852846622,-2.2211098671 -4.07671260834,1.63853192329,-2.20852971077 -4.07771921158,1.63553488255,-2.19194984436 -4.09073114395,1.6375387907,-2.18236637115 -4.10574436188,1.6415425539,-2.17476058006 -4.09674310684,1.63554334641,-2.16097545624 -4.11275672913,1.63954746723,-2.15338253975 -4.10575962067,1.63355004787,-2.13181948662 -4.12677526474,1.63855433464,-2.12721967697 -4.13278436661,1.63755786419,-2.11363720894 -4.13479137421,1.63556098938,-2.098051548 -4.13379764557,1.63256418705,-2.08047604561 -4.13980340958,1.63356602192,-2.07567620277 -4.13080596924,1.62656879425,-2.05409693718 -4.14781999588,1.63057291508,-2.04651284218 -4.15482950211,1.63057649136,-2.0339217186 -4.16884231567,1.63358032703,-2.02532100677 -4.15084123611,1.62258291245,-1.99875795841 -4.17685937881,1.63058745861,-1.99616062641 -4.18986845016,1.6345897913,-1.9943728447 -4.18087148666,1.62759292126,-1.97280406952 -4.19388341904,1.63059663773,-1.96418869495 -4.19489097595,1.62760031223,-1.94762289524 -4.19489812851,1.62460398674,-1.93104624748 -4.1989068985,1.6236076355,-1.91646969318 -4.19991064072,1.6226092577,-1.9096571207 -4.20091867447,1.61961317062,-1.89309537411 -4.20892906189,1.62061679363,-1.88149344921 -4.22794389725,1.62562119961,-1.87392175198 -4.2279510498,1.62262475491,-1.85832440853 -4.23396110535,1.62262868881,-1.84474790096 -4.23596906662,1.62063241005,-1.83015060425 -4.25097846985,1.62563467026,-1.82935082912 -4.2519865036,1.62363839149,-1.81376707554 -4.25399494171,1.62164247036,-1.79819571972 -4.26200580597,1.62164652348,-1.78561794758 -4.26801586151,1.62165033817,-1.77301692963 -4.27302503586,1.62165427208,-1.75943005085 -4.28303670883,1.62265837193,-1.74784851074 -4.27203655243,1.61766016483,-1.73505747318 -4.28604984283,1.61966466904,-1.72449553013 -4.28105592728,1.61566841602,-1.70690190792 -4.29806995392,1.61967277527,-1.69832026958 -4.29707717896,1.61767661572,-1.68272054195 -4.30008602142,1.61568081379,-1.66814029217 -4.30809783936,1.61668503284,-1.65556204319 -4.31610488892,1.61868727207,-1.65077674389 -4.31211137772,1.6146914959,-1.6332000494 -4.3171210289,1.6146954298,-1.62059009075 -4.31612920761,1.61169970036,-1.60402178764 -4.32714128494,1.61370384693,-1.59342288971 -4.33015060425,1.61270821095,-1.57884502411 -4.33315563202,1.61271035671,-1.57205855846 -4.33016347885,1.60871469975,-1.55547273159 -4.34417629242,1.61271882057,-1.5458766222 -4.35018730164,1.61272335052,-1.53230381012 -4.36219978333,1.61572766304,-1.52171170712 -4.35120487213,1.60873234272,-1.50115478039 -4.37021923065,1.61373651028,-1.49355208874 -4.362221241,1.60973882675,-1.48276376724 -4.37823534012,1.613743186,-1.47318267822 -4.37524318695,1.61074769497,-1.45660233498 -4.38225412369,1.61075210571,-1.44401299953 -4.3912653923,1.6127563715,-1.43241548538 -4.38927412033,1.6097612381,-1.41584730148 -4.39328432083,1.60876572132,-1.4022564888 -4.41129398346,1.61576759815,-1.40144896507 -4.41130304337,1.61277222633,-1.38587367535 -4.39730834961,1.60577738285,-1.36530542374 -4.40732049942,1.60778176785,-1.35371625423 -4.40933036804,1.6067866087,-1.33913505077 -4.41734170914,1.60779106617,-1.32655394077 -4.41535043716,1.60479581356,-1.31096529961 -4.42535829544,1.60779821873,-1.30618667603 -4.41236400604,1.60080337524,-1.28661155701 -4.43237829208,1.60680747032,-1.27899873257 -4.44139099121,1.60881221294,-1.26642453671 -4.43339824677,1.60381734371,-1.24884212017 -4.43840885162,1.60382211208,-1.23526203632 -4.45441865921,1.60882425308,-1.23247528076 -4.45542812347,1.60782897472,-1.21788799763 -4.44943618774,1.60383415222,-1.2012989521 -4.45744800568,1.60483884811,-1.18871581554 -4.4534573555,1.60184419155,-1.17214512825 -4.45946788788,1.60184884071,-1.15954601765 -4.46547985077,1.60285377502,-1.1459736824 -4.47748756409,1.60685586929,-1.14217507839 -4.47049570084,1.6018614769,-1.12461137772 -4.4825091362,1.60486602783,-1.11302947998 -4.45751237869,1.59387218952,-1.09144282341 -4.488530159,1.60487580299,-1.08583760262 -4.49154090881,1.60388112068,-1.07126963139 -4.4685459137,1.59288752079,-1.04970598221 -4.47355222702,1.59488976002,-1.04390692711 -4.50156879425,1.60389363766,-1.03729939461 -4.49057674408,1.59789967537,-1.01874351501 -4.50358963013,1.60190415382,-1.00813639164 -4.50460004807,1.59990942478,-0.993556201458 -4.49760961533,1.59591543674,-0.976004719734 -4.50262069702,1.59692037106,-0.963397264481 -4.52263069153,1.60392212868,-0.960613071918 -4.49763536453,1.59292864799,-0.940028429031 -4.52165079117,1.5999327898,-0.93143415451 -4.51566028595,1.5969388485,-0.914865791798 -4.53067350388,1.60094320774,-0.904265463352 -4.53068494797,1.59994900227,-0.888708353043 -4.52468919754,1.59695219994,-0.879920840263 -4.51769781113,1.59295785427,-0.864322721958 -4.52671098709,1.59496283531,-0.851739287376 -4.52272081375,1.5919687748,-0.836161315441 -4.53673458099,1.59597361088,-0.824578285217 -4.54574728012,1.59797859192,-0.811992406845 -4.54875802994,1.59798395634,-0.798399329185 -4.54176330566,1.59498751163,-0.78863877058 -4.55177545547,1.59799230099,-0.777029335499 -4.55678701401,1.59799766541,-0.763447642326 -4.55479860306,1.59600377083,-0.747883856297 -4.55280923843,1.59400951862,-0.733293116093 -4.57182359695,1.60001385212,-0.722699999809 -4.56382751465,1.59701728821,-0.713910281658 -4.5578379631,1.59302377701,-0.697356522083 -4.56785058975,1.59602856636,-0.685743272305 -4.57086229324,1.59603440762,-0.671178877354 -4.56087255478,1.5910410881,-0.654608368874 -4.58388710022,1.59904503822,-0.64499861002 -4.57389736176,1.59405183792,-0.628429710865 -4.58290433884,1.59705424309,-0.622639834881 -4.56891345978,1.59106099606,-0.606055021286 -4.58992767334,1.59806525707,-0.595458447933 -4.58093833923,1.59307217598,-0.578898310661 -4.59895324707,1.59907674789,-0.567313194275 -4.58596277237,1.59308385849,-0.550738215446 -4.58497428894,1.59209001064,-0.53615796566 -4.60298204422,1.5980912447,-0.532343566418 -4.61299610138,1.60109674931,-0.518777430058 -4.60000514984,1.596103549,-0.503178298473 -4.60301733017,1.59610974789,-0.488613665104 -4.6030292511,1.59511578083,-0.474038004875 -4.61504268646,1.59812092781,-0.461449086666 -4.60405254364,1.59312784672,-0.445863157511 -4.60305929184,1.59313130379,-0.438086271286 -4.61607265472,1.59713637829,-0.425498783588 -4.62408638,1.59914195538,-0.411921411753 -4.61309623718,1.59414899349,-0.396339446306 -4.61310863495,1.59315538406,-0.381765365601 -4.61512041092,1.59316122532,-0.368169158697 -4.62312698364,1.59616351128,-0.362363189459 -4.61413812637,1.59217071533,-0.346791535616 -4.6121506691,1.59117722511,-0.332212746143 -4.61016225815,1.58918380737,-0.317634880543 -4.62417650223,1.59418869019,-0.305042207241 -4.62418889999,1.59319519997,-0.290469259024 -4.62620162964,1.59320151806,-0.275901377201 -4.62520742416,1.5932046175,-0.269098192453 -4.62822008133,1.5932110548,-0.254532784224 -4.62423229218,1.59121787548,-0.239951491356 -4.6242442131,1.59122407436,-0.226350963116 -4.62725734711,1.59123051167,-0.211785659194 -4.63227033615,1.59323632717,-0.198195040226 -4.64128351212,1.59624195099,-0.184611350298 -4.63828992844,1.59424567223,-0.176834151149 -4.63130187988,1.5912528038,-0.162250056863 -4.64031505585,1.59425854683,-0.148664996028 -4.64332723618,1.59526443481,-0.135069221258 -4.64634084702,1.59627103806,-0.12050165236 -4.63435220718,1.59127867222,-0.105913326144 -4.64636611938,1.59528398514,-0.092329479754 -4.64137220383,1.593288064,-0.0845517739654 -4.64938545227,1.59629380703,-0.070961214602 -4.647397995,1.59430074692,-0.0563877522945 -4.63640975952,1.59030854702,-0.0418057106435 -4.64642333984,1.59331405163,-0.0282159075141 -4.64543676376,1.59332108498,-0.0136440210044 -4.64044237137,1.59132480621,-0.00684059970081 -4.64245557785,1.59133148193,0.00772810447961 -4.65646934509,1.59633660316,0.0213189702481 -4.65348291397,1.5953438282,0.0358919091523 -4.63749408722,1.58935248852,0.0504692792892 -4.65250873566,1.59435749054,0.0640627145767 -4.63051986694,1.58636665344,0.0786384120584 -4.64352703094,1.59136867523,0.0854348838329 -4.65354156494,1.59437465668,0.100003734231 -4.65255498886,1.5933817625,0.114574275911 -4.63356637955,1.58739054203,0.128172054887 -4.6525812149,1.59339535236,0.142744019628 -4.6395945549,1.58940410614,0.157311186194 -4.63660669327,1.58741116524,0.170907855034 -4.64761447906,1.59141361713,0.178682416677 -4.64062738419,1.58942115307,0.192277789116 -4.65364170074,1.59342670441,0.206854462624 -4.65165472031,1.59343361855,0.220452487469 -4.6326675415,1.58644318581,0.235008388758 -4.6396818161,1.58944964409,0.249583080411 -4.62869405746,1.5844578743,0.26317051053 -4.62270069122,1.58246207237,0.269963204861 -4.62871456146,1.58446848392,0.284537374973 -4.65072917938,1.5934728384,0.299131512642 -4.63174247742,1.58648228645,0.312706917524 -4.63475608826,1.58748924732,0.327279657125 -4.63076925278,1.58649659157,0.340871930122 -4.64377689362,1.59149861336,0.348661154509 -4.62679004669,1.58450806141,0.362233161926 -4.63380432129,1.58751440048,0.376813411713 -4.61981773376,1.58252346516,0.390387147665 -4.63283205032,1.58752894402,0.404979169369 -4.62984609604,1.58753681183,0.419543176889 -4.63485956192,1.58954298496,0.433151245117 -4.63486719131,1.58954691887,0.440921843052 -4.62588071823,1.58655536175,0.454501330853 -4.61389446259,1.58256435394,0.468072682619 -4.61290836334,1.5825715065,0.48166757822 -4.61592245102,1.58357846737,0.496243178844 -4.59793567657,1.57758808136,0.508824765682 -4.62195110321,1.58659267426,0.525396883488 -4.62695741653,1.58859527111,0.532209277153 -4.6089720726,1.58260560036,0.545759499073 -4.60598611832,1.58161318302,0.559348762035 -4.61599969864,1.58561897278,0.573946654797 -4.59401464462,1.57862961292,0.586508572102 -4.60402917862,1.58263599873,0.602078914642 -4.60504245758,1.58264291286,0.615680038929 -4.58705043793,1.57664942741,0.621450185776 -4.59706401825,1.58065509796,0.636051535606 -4.59407949448,1.58066344261,0.650610923767 -4.6040930748,1.58466923237,0.665215134621 -4.58410787582,1.5776797533,0.677771687508 -4.59512281418,1.58268594742,0.693352460861 -4.58912944794,1.5806902647,0.699158370495 -4.57614374161,1.57569956779,0.711736261845 -4.59115886688,1.58270549774,0.728306412697 -4.59317398071,1.58371269703,0.742885112762 -4.58218812943,1.58072173595,0.755469083786 -4.5912027359,1.58472824097,0.771048486233 -4.56521749496,1.57573950291,0.781624555588 -4.57922506332,1.58074116707,0.790426254272 -4.57524061203,1.58074986935,0.80498021841 -4.56825447083,1.57875823975,0.817577362061 -4.57226896286,1.58076524734,0.832166433334 -4.56828403473,1.57977354527,0.845748066902 -4.54929924011,1.57378411293,0.857315838337 -4.55330705643,1.57578742504,0.865105807781 -4.56232118607,1.57979393005,0.880691885948 -4.53833675385,1.57180523872,0.891259491444 -4.53035259247,1.56981468201,0.904818058014 -4.54136705399,1.57382047176,0.920415818691 -4.53938150406,1.57382845879,0.934005439281 -4.52139759064,1.56883919239,0.945567429066 -4.54240465164,1.57683992386,0.956365227699 -4.53642034531,1.57584881783,0.969933867455 -4.53243541718,1.57485735416,0.983512759209 -4.5154504776,1.56986749172,0.994104027748 -4.52146577835,1.57287454605,1.00968134403 -4.49348115921,1.56288647652,1.01826238632 -4.50149726868,1.56689369678,1.03482317924 -4.52650356293,1.57689368725,1.04662942886 -4.49951934814,1.56790554523,1.05521190166 -4.49853515625,1.56891393661,1.06977820396 -4.49755048752,1.56992185116,1.08337342739 -4.50256586075,1.57192909718,1.09894955158 -4.47758245468,1.56394124031,1.10850632191 -4.47759008408,1.56494510174,1.11530697346 -4.47860527039,1.56595301628,1.12988615036 -4.47562122345,1.56596148014,1.14346826077 -4.47563648224,1.5669696331,1.15804195404 -3.78290748596,1.59122431278,2.82195830345 -3.77992749214,1.59323489666,2.83851146698 -3.78694438934,1.60024273396,2.86109828949 -3.7469689846,1.58625948429,2.84869170189 -3.75798535347,1.59526669979,2.87427949905 -3.75299596786,1.59527266026,2.88005518913 -3.74901580811,1.59728324413,2.8956182003 -3.73903512955,1.59629428387,2.90521550179 -3.73805403709,1.60030412674,2.92278718948 -3.73207378387,1.6013147831,2.93636393547 -3.72309327126,1.60132575035,2.94695663452 -3.7081143856,1.59833812714,2.95353460312 -3.7051243782,1.59934353828,2.96032309532 -3.71014142036,1.60535168648,2.98191523552 -3.69016456604,1.60036563873,2.98547101021 -3.68418431282,1.60237634182,2.99904990196 -3.66920590401,1.59938883781,3.00562477112 -3.65922522545,1.59839987755,3.01522111893 -3.65324521065,1.60041058064,3.02880072594 -3.65725421906,1.60441482067,3.04158401489 -3.65327382088,1.60742521286,3.05715751648 -3.63829541206,1.60443794727,3.06373047829 -3.63831305504,1.60844683647,3.08133411407 -3.6083381176,1.59846270084,3.07589507103 -3.61535549164,1.6064709425,3.10047483444 -3.6083753109,1.60748159885,3.11306214333 -3.59438753128,1.60248923302,3.11084699631 -3.5864071846,1.603500247,3.12243723869 -3.59542441368,1.61250817776,3.1490187645 -3.57244873047,1.60652279854,3.14956903458 -3.56046867371,1.60453426838,3.15717172623 -3.56048798561,1.60954415798,3.17674136162 -3.54550075531,1.60455203056,3.17352342606 -3.54052019119,1.60756242275,3.18810725212 -3.54253840446,1.6125715971,3.20869708061 -3.51456260681,1.60358667374,3.20327186584 -3.5175807476,1.60959565639,3.22486138344 -3.50760173798,1.60960733891,3.23543739319 -3.48662495613,1.60462117195,3.23601365089 -3.4936337471,1.6106249094,3.25278949738 -3.48265504837,1.60963690281,3.26236748695 -3.46567678452,1.60664963722,3.26595497131 -3.46069645882,1.60866010189,3.28054404259 -3.45471692085,1.61067116261,3.29511451721 -3.44673800468,1.61168265343,3.30768871307 -3.42876029015,1.60769557953,3.31027412415 -3.42477107048,1.60870158672,3.31705069542 -3.41479253769,1.60871338844,3.32762694359 -3.40381288528,1.6077247858,3.33622407913 -3.4088306427,1.6157335043,3.36081123352 -3.38985443115,1.61174738407,3.36337327957 -3.3758764267,1.6097599268,3.36995196342 -3.37989497185,1.61676907539,3.3945248127 -3.36290764809,1.61077690125,3.38732624054 -3.34892964363,1.60878956318,3.3939037323 -3.34095048904,1.609801054,3.40648031235 -3.33597111702,1.61281180382,3.42205810547 -3.32699227333,1.61382341385,3.43363618851 -3.32401204109,1.61783385277,3.45121693611 -3.30602526665,1.61084210873,3.44301009178 -3.29904699326,1.6128538847,3.45756959915 -3.30206441879,1.61986243725,3.48017692566 -3.28208827972,1.6148763895,3.48074817657 -3.26311087608,1.6098896265,3.4813375473 -3.26213097572,1.61589992046,3.50190591812 -3.2561416626,1.6149058342,3.50570392609 -3.23716545105,1.61091971397,3.50727105141 -3.239184618,1.61792933941,3.5308470726 -3.23720479012,1.62293970585,3.55042004585 -3.21622848511,1.61695361137,3.54900193214 -3.20225024223,1.61496603489,3.55459403992 -3.19527101517,1.6169770956,3.56817960739 -3.1942820549,1.61998271942,3.57894897461 -3.19030165672,1.62299311161,3.59554243088 -3.16532611847,1.61600768566,3.5891289711 -3.16434574127,1.62101769447,3.60971164703 -3.15436816216,1.62203001976,3.62127447128 -3.12939286232,1.6140447855,3.61485528946 -3.12241363525,1.61605584621,3.62844395638 -3.12142443657,1.61906135082,3.63921761513 -3.1114461422,1.62007331848,3.64979958534 -3.1084651947,1.62408316135,3.66740274429 -3.09048962593,1.62109720707,3.66996121407 -3.08551025391,1.6241080761,3.68654179573 -3.07053279877,1.62212085724,3.69112682343 -3.05855512619,1.62113320827,3.69970321655 -3.05656552315,1.62313866615,3.70849657059 -3.04258799553,1.6221511364,3.71408414841 -3.04160833359,1.62816166878,3.73664832115 -3.02063298225,1.62317585945,3.73422646523 -3.01265454292,1.62518751621,3.74780130386 -3.00567579269,1.62819886208,3.76238131523 -2.99968600273,1.62720441818,3.76519656181 -2.98170995712,1.62321829796,3.76676559448 -2.97873044014,1.62822878361,3.7863471508 -2.95875477791,1.62324285507,3.78492259979 -2.95777511597,1.63025307655,3.80749893188 -2.9397995472,1.62626695633,3.80906510353 -2.93282055855,1.62927818298,3.82364964485 -2.92683148384,1.62928426266,3.8274474144 -2.91285514832,1.62829732895,3.83401465416 -2.90087771416,1.62830984592,3.84259223938 -2.89189910889,1.62932121754,3.85418558121 -2.89091968536,1.63633179665,3.87775611877 -2.86394476891,1.62634670734,3.8653523922 -2.86096549034,1.63235735893,3.8859307766 -2.85797643661,1.63436317444,3.89471244812 -2.83500170708,1.62737774849,3.88829278946 -2.8330218792,1.63338804245,3.90988087654 -2.81604576111,1.63040149212,3.91146183014 -2.81606531143,1.63741123676,3.93604969978 -2.79608988762,1.63242530823,3.93362736702 -2.79410099983,1.63543117046,3.94440197945 -2.77712440491,1.6324442625,3.94499731064 -2.77714514732,1.64045476913,3.97155928612 -2.76116847992,1.63746786118,3.97414493561 -2.74319314957,1.63448166847,3.97471547127 -2.73121547699,1.63449382782,3.98231101036 -2.72523713112,1.63850522041,3.9998857975 -2.71624898911,1.63651204109,3.99967813492 -2.70027351379,1.63452553749,4.00324487686 -2.69429421425,1.63853657246,4.01983785629 -2.67731785774,1.63454973698,4.02042722702 -2.66934084892,1.63856184483,4.0359916687 -2.66536188126,1.64357280731,4.05657339096 -2.64638614655,1.63958632946,4.05416154861 -2.64539718628,1.64359200001,4.06693840027 -2.62842082977,1.63960528374,4.06752586365 -2.61344504356,1.63861858845,4.07209777832 -2.60646629333,1.6416298151,4.08769083023 -2.59748864174,1.64464175701,4.10126876831 -2.58251285553,1.64365506172,4.10584115982 -2.57152581215,1.63966238499,4.1026263237 -2.55854940414,1.63967525959,4.11019945145 -2.55157065392,1.64368641376,4.12579679489 -2.53859424591,1.64369928837,4.13337087631 -2.52661705017,1.64371168613,4.141954422 -2.5106408596,1.64172482491,4.14354515076 -2.50266313553,1.6447365284,4.1591219902 -2.49367570877,1.64374363422,4.15890741348 -2.48369860649,1.64575588703,4.17148160934 -2.47872042656,1.65076696873,4.19206190109 -2.46074461937,1.64778065681,4.19064617157 -2.44276881218,1.64379405975,4.18824291229 -2.44079065323,1.65180516243,4.21580123901 -2.43580102921,1.65281069279,4.22061157227 -2.42382526398,1.65382373333,4.23117017746 -2.42784452438,1.6668330431,4.2677564621 -2.42186617851,1.671844244,4.28734016418 -2.4148876667,1.67585551739,4.30493021011 -2.41390872002,1.68586611748,4.3345041275 -2.41192936897,1.69387662411,4.36208534241 -2.4099407196,1.69788241386,4.37486696243 -2.41395998001,1.71189165115,4.41345310211 -2.4069814682,1.71590304375,4.43204259872 -2.39000701904,1.71391689777,4.43460464478 -2.39702510834,1.72992551327,4.47919750214 -2.38404870033,1.73093831539,4.48777961731 -2.37607216835,1.73595046997,4.5073428154 -2.37508249283,1.74095571041,4.52213382721 -2.36710500717,1.74496746063,4.5407128334 -2.32213664055,1.71998667717,4.4882941246 -2.29616308212,1.71100175381,4.47088575363 -2.28618574142,1.71401369572,4.48447561264 -2.29720473289,1.73402225971,4.54203271866 -2.27922940254,1.7310359478,4.54061889648 -2.28523850441,1.7420399189,4.57040309906 -2.26026415825,1.73205471039,4.55400133133 -2.2402908802,1.72806942463,4.55056095123 -2.24630951881,1.74507820606,4.59715270996 -2.23333358765,1.7460911274,4.60672950745 -2.21135950089,1.73910570145,4.5973110199 -2.20437121391,1.73911201954,4.60011005402 -2.18439698219,1.734126091,4.59468984604 -2.17042088509,1.73413896561,4.60127496719 -2.15444540977,1.73315238953,4.60385799408 -2.13647150993,1.73016643524,4.60342550278 -2.12449526787,1.73217916489,4.61500263214 -2.11551737785,1.73619091511,4.63159704208 -2.0995323658,1.72919929028,4.61637735367 -2.08955550194,1.73321151733,4.63195943832 -2.0775783062,1.7342236042,4.64156103134 -2.06560301781,1.7372367382,4.6551194191 -2.04462885857,1.73125100136,4.64570808411 -2.0306532383,1.73226416111,4.65328264236 -2.02566480637,1.73427009583,4.66107606888 -2.00669002533,1.72928392887,4.65566682816 -1.99371361732,1.73029661179,4.66425561905 -1.98273742199,1.73430907726,4.67883110046 -1.96476340294,1.73132324219,4.6774020195 -1.95078802109,1.73233628273,4.68497753143 -1.93781113625,1.73234856129,4.6925778389 -1.92582535744,1.7283564806,4.68535470963 -1.91384863853,1.73036873341,4.69594907761 -1.89787423611,1.72938239574,4.69951581955 -1.88189840317,1.72739553452,4.70011234283 -1.86792361736,1.72940886021,4.70867824554 -1.85394823551,1.72942197323,4.71625471115 -1.8319747448,1.72243654728,4.70283651352 -1.82698607445,1.72444248199,4.71063518524 -1.81401073933,1.72645556927,4.72120714188 -1.80003404617,1.72646796703,4.72581243515 -1.78505933285,1.72648143768,4.73138332367 -1.77408230305,1.72949337959,4.74497890472 -1.75610888004,1.72750771046,4.74354076385 -1.74113321304,1.72652077675,4.74712991714 -1.74014389515,1.73352599144,4.76692199707 -1.71717131138,1.7255409956,4.75049448013 -1.70419502258,1.7265535593,4.7590880394 -1.69521832466,1.73256552219,4.78066730499 -1.67024600506,1.721580863,4.75724554062 -1.65627038479,1.72259366512,4.76383209229 -1.65228295326,1.72760009766,4.77860069275 -1.63530790806,1.72461342812,4.77619123459 -1.62333142757,1.72762572765,4.78778648376 -1.60435688496,1.72263944149,4.77937650681 -1.59238195419,1.72665262222,4.7949385643 -1.57840621471,1.72766530514,4.80152750015 -1.55843234062,1.72067940235,4.79011392593 -1.55744361877,1.72968494892,4.81389093399 -1.53846871853,1.72369849682,4.80349302292 -1.52749288082,1.72871100903,4.82106924057 -1.50451982021,1.7187256813,4.7996544838 -1.4915446043,1.7217386961,4.81122875214 -1.47956871986,1.72575116158,4.82481384277 -1.46259450912,1.72376489639,4.82339000702 -1.45760607719,1.72577083111,4.83318567276 -1.43863236904,1.72078490257,4.82476329803 -1.43165576458,1.73279666901,4.85733556747 -1.40868270397,1.72181129456,4.83392286301 -1.39870595932,1.72782325745,4.85451221466 -1.37873196602,1.72083711624,4.84010457993 -1.37274491787,1.72384393215,4.84987831116 -1.35477030277,1.71985733509,4.84246826172 -1.34279453754,1.72386991978,4.85705375671 -1.32282149792,1.71788418293,4.84462547302 -1.31684446335,1.73089587688,4.88319969177 -1.29387032986,1.71890985966,4.85380983353 -1.28489458561,1.72792220116,4.88337469101 -1.27090907097,1.71893012524,4.86116361618 -1.26293134689,1.72894144058,4.88976383209 -1.23995912075,1.71795630455,4.86433792114 -1.22498476505,1.71896970272,4.86991119385 -1.21100914478,1.71998226643,4.87650442123 -1.20003306866,1.72599470615,4.89708709717 -1.17805945873,1.71500873566,4.87068319321 -1.17407178879,1.7210149765,4.88946056366 -1.15509831905,1.71602904797,4.87803697586 -1.14312291145,1.72104167938,4.89561605453 -1.12314939499,1.7140557766,4.87820005417 -1.11317253113,1.72106742859,4.90179777145 -1.09319925308,1.71408164501,4.88437795639 -1.08821094036,1.71808755398,4.89717245102 -1.07023727894,1.71410143375,4.88875007629 -1.0582613945,1.71911382675,4.90633535385 -1.04128789902,1.71712768078,4.90390443802 -1.02931261063,1.72414028645,4.9234828949 -1.00833892822,1.71315419674,4.89707660675 -0.997363209724,1.72116649151,4.92165613174 -0.989375412464,1.71917295456,4.91945838928 -0.97440123558,1.72118628025,4.92603111267 -0.95642632246,1.71519935131,4.91163301468 -0.943451225758,1.71921217442,4.92721223831 -0.920479536057,1.70622718334,4.89277935028 -0.90950345993,1.7142393589,4.91736745834 -0.892529547215,1.71125280857,4.91194581985 -0.887541174889,1.71625876427,4.92674303055 -0.869567275047,1.71027231216,4.91432666779 -0.858590781689,1.71928429604,4.93892335892 -0.83761793375,1.70729839802,4.90950298309 -0.826641976833,1.71731078625,4.93708896637 -0.808668315411,1.71132433414,4.92466831207 -0.794693529606,1.71533727646,4.93624830246 -0.784707546234,1.71034455299,4.92602777481 -0.773731589317,1.72135674953,4.95561361313 -0.753757476807,1.70837020874,4.92421340942 -0.739783346653,1.7133834362,4.93978071213 -0.721808969975,1.70639681816,4.9213757515 -0.710833966732,1.71940934658,4.95794391632 -0.697847783566,1.70441675186,4.91974401474 -0.684872806072,1.71142947674,4.9403219223 -0.667898058891,1.70644247532,4.9269194603 -0.6539234519,1.71045541763,4.94149541855 -0.636949241161,1.70646858215,4.93008375168 -0.623973608017,1.71248102188,4.94867515564 -0.605000853539,1.70349502563,4.92624378204 -0.600012481213,1.71050083637,4.94704341888 -0.580039381981,1.69751477242,4.9116230011 -0.56906414032,1.71252739429,4.95419788361 -0.552088916302,1.70454013348,4.93480396271 -0.538114786148,1.71155309677,4.95437383652 -0.520141005516,1.70256650448,4.93195867538 -0.516152083874,1.71457207203,4.96376276016 -0.497178077698,1.7005854845,4.92735624313 -0.484203398228,1.71059823036,4.9569311142 -0.466230362654,1.70361208916,4.93750143051 -0.452255278826,1.70862460136,4.95308923721 -0.435281515121,1.70363807678,4.93966817856 -0.422305971384,1.7136503458,4.9662604332 -0.412318766117,1.70165705681,4.93506383896 -0.397345036268,1.70667028427,4.94963121414 -0.381370216608,1.70168304443,4.93922567368 -0.367395013571,1.70869553089,4.95681667328 -0.350420951843,1.70070874691,4.93640184402 -0.336446195841,1.70872151852,4.95998430252 -0.319472283125,1.70173478127,4.93956661224 -0.311485797167,1.70274150372,4.94334602356 -0.295511782169,1.70075464249,4.93892526627 -0.281536132097,1.70676696301,4.95552492142 -0.264562636614,1.69978046417,4.93609905243 -0.250587433577,1.70879280567,4.96069049835 -0.23461265862,1.70180559158,4.94428491592 -0.219638317823,1.70781850815,4.95986509323 -0.21065197885,1.7008254528,4.94064664841 -0.195677131414,1.70383810997,4.94823694229 -0.17970302701,1.69985115528,4.93881845474 -0.164728745818,1.70786392689,4.96039772034 -0.148753553629,1.69487655163,4.92400026321 -0.133779272437,1.70388948917,4.94857978821 -0.125792071223,1.69989597797,4.93737363815 -0.110817395151,1.70690858364,4.95596075058 -0.0948431789875,1.69892156124,4.93554401398 -0.0798686370254,1.71093428135,4.96712875366 -0.0638943314552,1.69794714451,4.9337143898 -0.0479208640754,1.70196044445,4.94228315353 -0.0329453386366,1.69097268581,4.91388750076 -0.0249587967992,1.70197939873,4.94366788864 -0.00998348742723,1.69799172878,4.9322681427 --0.011979774572,1.70701014996,4.80767059326 --0.0199663881212,1.71301686764,4.82445240021 --0.0349410288036,1.70802938938,4.80903911591 --0.0499157309532,1.70704209805,4.80662679672 --0.0648905783892,1.710054636,4.81321716309 --0.0798651725054,1.70706725121,4.80580282211 --0.0948397293687,1.70507991314,4.79938793182 --0.109814532101,1.70609235764,4.80197715759 --0.117801047862,1.70609903336,4.8017578125 --0.132775813341,1.70711159706,4.80234718323 --0.147750630975,1.70812404156,4.80393695831 --0.162725090981,1.7061368227,4.79751968384 --0.177700072527,1.70814919472,4.80211353302 --0.193673208356,1.70816254616,4.80267572403 --0.200661420822,1.7081682682,4.80248403549 --0.215635687113,1.70618104935,4.79406356812 --0.230610489845,1.70619356632,4.79465293884 --0.245585039258,1.70620620251,4.79123735428 --0.260559856892,1.70621860027,4.79182767868 --0.275534123182,1.70423126221,4.78540754318 --0.290509223938,1.70624363422,4.78900241852 --0.298495143652,1.70325052738,4.78177165985 --0.313469618559,1.70326304436,4.77835512161 --0.32744500041,1.6992752552,4.76695013046 --0.34241977334,1.7002876997,4.76753997803 --0.359393775463,1.71030056477,4.79212474823 --0.373368322849,1.70331299305,4.77370405197 --0.380356788635,1.70431876183,4.77551651001 --0.396330595016,1.70733165741,4.7810921669 --0.41130515933,1.70734405518,4.77867794037 --0.425279319286,1.70035672188,4.75924921036 --0.441254347563,1.7063690424,4.77384853363 --0.456229031086,1.70638144016,4.7724366188 --0.470203787088,1.70239377022,4.75901937485 --0.47819134593,1.70539999008,4.7658200264 --0.493165642023,1.70441246033,4.7613992691 --0.508140325546,1.70442485809,4.75998735428 --0.524114131927,1.70643758774,4.76356220245 --0.540088474751,1.71045029163,4.77014827728 --0.553064227104,1.70446205139,4.7537446022 --0.568039476871,1.70647418499,4.75534248352 --0.577026426792,1.71148049831,4.76713657379 --0.591000854969,1.70649290085,4.75371313095 --0.60697466135,1.7085057497,4.75628852844 --0.61995023489,1.70351755619,4.74088287354 --0.634925186634,1.70452976227,4.74047470093 --0.651898384094,1.70854282379,4.74804210663 --0.665874660015,1.70855438709,4.74565505981 --0.67286169529,1.70656073093,4.73843860626 --0.690834879875,1.71357381344,4.75401306152 --0.704810202122,1.71158564091,4.74660730362 --0.718784928322,1.70859789848,4.73618841171 --0.734758973122,1.71061062813,4.73876810074 --0.748734891415,1.70962226391,4.73437356949 --0.756721436977,1.70962870121,4.7331533432 --0.77269667387,1.71364080906,4.74075651169 --0.785671770573,1.70865273476,4.72533988953 --0.803644776344,1.71466588974,4.73690891266 --0.816620707512,1.71167743206,4.72550868988 --0.833594560623,1.71569013596,4.73308944702 --0.847569525242,1.71370220184,4.72467565536 --0.856557130814,1.71770823002,4.73448228836 --0.870532393456,1.71672010422,4.7270731926 --0.887505710125,1.71873307228,4.73164319992 --0.902480840683,1.71974492073,4.73023748398 --0.915456354618,1.71675670147,4.71782875061 --0.931431233883,1.71876883507,4.72142267227 --0.947405815125,1.7217810154,4.72401189804 --0.957391381264,1.72478806973,4.73078346252 --0.970367372036,1.72179949284,4.72038412094 --0.986341834068,1.72381186485,4.72197008133 --1.00131630898,1.72382414341,4.71754980087 --1.01829063892,1.72783637047,4.72413873672 --1.03426587582,1.73084831238,4.72773933411 --1.04824006557,1.72786056995,4.71731138229 --1.05822718143,1.73286676407,4.7281126976 --1.07320213318,1.73287880421,4.7247004509 --1.08617711067,1.72889077663,4.71128034592 --1.10115230083,1.72990250587,4.70887327194 --1.12012565136,1.73591530323,4.72145462036 --1.13010287285,1.72892606258,4.70006132126 --1.14008831978,1.7319329977,4.70483064651 --1.15806221962,1.7369453907,4.71341657639 --1.17203760147,1.7359572649,4.70600557327 --1.1850130558,1.73296880722,4.69459486008 --1.20298731327,1.73798120022,4.70318412781 --1.21896231174,1.7399930954,4.70478105545 --1.23193740845,1.73700475693,4.6923623085 --1.23892557621,1.73701035976,4.69016647339 --1.25689923763,1.74102294445,4.69674730301 --1.26987540722,1.73903429508,4.68734788895 --1.28884875774,1.74504685402,4.69692659378 --1.30282330513,1.74305891991,4.68750095367 --1.31779885292,1.74407052994,4.68510007858 --1.33577263355,1.74808299541,4.69068002701 --1.33976149559,1.74408817291,4.67748212814 --1.35673570633,1.74610042572,4.68006658554 --1.37271046638,1.7481123209,4.67965602875 --1.38368678093,1.74312341213,4.66224527359 --1.40266060829,1.74813580513,4.67183494568 --1.41863596439,1.75114750862,4.67243337631 --1.42562258244,1.74915373325,4.66620826721 --1.43859910965,1.74816465378,4.65781402588 --1.45957136154,1.75517773628,4.67038154602 --1.4715474844,1.75118899345,4.65697336197 --1.4915214777,1.75820124149,4.66957044601 --1.50349807739,1.7562122345,4.65716981888 --1.51647377014,1.7532235384,4.6467590332 --1.52845931053,1.75823044777,4.65653800964 --1.54543375969,1.76124238968,4.65812587738 --1.55441105366,1.75525295734,4.63672399521 --1.57338500023,1.76026511192,4.64431285858 --1.59135901928,1.76327729225,4.64789533615 --1.60333538055,1.76128828526,4.63549184799 --1.62330913544,1.76730072498,4.64507818222 --1.62929677963,1.76530647278,4.63786745071 --1.64027297497,1.76131749153,4.62145233154 --1.6582467556,1.76432967186,4.62403011322 --1.67422235012,1.7663410902,4.62363195419 --1.68919813633,1.76735234261,4.62023210526 --1.70317268372,1.7663640976,4.61080360413 --1.71914839745,1.76837539673,4.61040687561 --1.72713494301,1.76838171482,4.60718107224 --1.73911201954,1.76639223099,4.59679222107 --1.76208519936,1.77540481091,4.61338329315 --1.77406001091,1.7714164257,4.5979475975 --1.7850369215,1.76842701435,4.58354473114 --1.80601108074,1.77543914318,4.59514379501 --1.81299805641,1.77444505692,4.58992433548 --1.82697474957,1.77445590496,4.58453369141 --1.84694778919,1.77946841717,4.59010410309 --1.85992395878,1.77847933769,4.58069992065 --1.87190067768,1.77549004555,4.56929922104 --1.88887488842,1.77850186825,4.56787633896 --1.90384960175,1.77851355076,4.5614528656 --1.91183769703,1.77951896191,4.56125879288 --1.92681348324,1.78053021431,4.5568561554 --1.94078874588,1.77954149246,4.54843616486 --1.94876623154,1.7735517025,4.52702713013 --1.97073984146,1.78056395054,4.53862094879 --1.98671543598,1.78257513046,4.536216259 --2.00268936157,1.78358709812,4.5307803154 --2.01267671585,1.78559291363,4.53458309174 --2.02265310287,1.78160357475,4.51716423035 --2.04362726212,1.78861546516,4.52575874329 --2.05660295486,1.78662645817,4.5153427124 --2.06758022308,1.7836369276,4.50194072723 --2.0855550766,1.78764843941,4.50353527069 --2.09254336357,1.78765380383,4.50033664703 --2.10551905632,1.78566479683,4.48991918564 --2.12749290466,1.79267680645,4.49951028824 --2.13946890831,1.79068768024,4.48709487915 --2.15044593811,1.78869795799,4.47369098663 --2.16742038727,1.79070961475,4.47126913071 --2.19139456749,1.79972147942,4.48587703705 --2.19238376617,1.79372644424,4.46866083145 --2.213357687,1.79973816872,4.47525072098 --2.22533392906,1.7977489233,4.46283435822 --2.23431134224,1.79275906086,4.4454293251 --2.25128674507,1.7957701683,4.44402265549 --2.27526044846,1.80478215218,4.45661973953 --2.28023767471,1.79579234123,4.42918777466 --2.29122519493,1.79979801178,4.43399238586 --2.31019949913,1.80380964279,4.43557929993 --2.32217693329,1.80281972885,4.42518472672 --2.33215355873,1.79883027077,4.4087638855 --2.35212802887,1.80384171009,4.41235399246 --2.36410427094,1.80185234547,4.39993524551 --2.37209177017,1.80285787582,4.39772796631 --2.39506649971,1.81086933613,4.40833950043 --2.40504312515,1.80687975883,4.39191627502 --2.42101860046,1.80789077282,4.38750505447 --2.43199586868,1.80590105057,4.37409543991 --2.4419734478,1.80291104317,4.35969495773 --2.46694636345,1.81192302704,4.37128257751 --2.47693347931,1.81392896175,4.37207078934 --2.48391151428,1.80893862247,4.35166120529 --2.49788832664,1.80894911289,4.34425878525 --2.51686215401,1.81296050549,4.34383440018 --2.52883911133,1.81097090244,4.33242607117 --2.54681491852,1.81498169899,4.33202600479 --2.56279015541,1.81599271297,4.32660675049 --2.56378006935,1.81199705601,4.31240224838 --2.58375573158,1.81700801849,4.31601285934 --2.59773111343,1.81701886654,4.30658626556 --2.61170721054,1.81702947617,4.29817295074 --2.62568354607,1.81703996658,4.28976011276 --2.64365959167,1.82005047798,4.28936624527 --2.65064764023,1.82005572319,4.28515958786 --2.66562342644,1.82106649876,4.277739048 --2.68159985542,1.82307696342,4.27333784103 --2.6925766468,1.82108712196,4.2599234581 --2.71255254745,1.82609772682,4.26253175735 --2.72652816772,1.82610845566,4.25310754776 --2.73850464821,1.82511878014,4.24068450928 --2.74449419975,1.82512331009,4.23650026321 --2.76046943665,1.82613432407,4.23007440567 --2.77644586563,1.82814455032,4.2256770134 --2.78942227364,1.82815480232,4.21526050568 --2.80239963531,1.8281648159,4.20585775375 --2.81737565994,1.82817530632,4.19844102859 --2.8303527832,1.8281853199,4.18903827667 --2.83734107018,1.8281904459,4.18483352661 --2.85431718826,1.83120083809,4.18143177032 --2.86929273605,1.83221161366,4.17300224304 --2.88327026367,1.83322131634,4.16560792923 --2.90224552155,1.83623206615,4.16419649124 --2.91522216797,1.83624219894,4.15378093719 --2.92021107674,1.83524703979,4.1465754509 --2.94318652153,1.84225785732,4.15218496323 --2.95816206932,1.84226834774,4.1437587738 --2.9691400528,1.84127783775,4.13135671616 --2.9801170826,1.8402878046,4.11793899536 --2.99409484863,1.84029746056,4.11054849625 --3.01306986809,1.84430813789,4.10812950134 --3.02605676651,1.84831380844,4.11192321777 --3.03403496742,1.8453233242,4.09450817108 --3.05101132393,1.84733355045,4.09010314941 --3.06398892403,1.8473430872,4.08070516586 --3.07996463776,1.84935367107,4.07327651978 --3.08794331551,1.84636271,4.05687332153 --3.1099190712,1.85237324238,4.05947685242 --3.120906353,1.85537862778,4.06027173996 --3.13288331032,1.85438847542,4.04784965515 --3.14386129379,1.8523979187,4.03544712067 --3.1598379612,1.85540807247,4.02903699875 --3.17581534386,1.85741770267,4.02364349365 --3.18679261208,1.85542738438,4.01022577286 --3.19878005981,1.8594326973,4.01202011108 --3.21475672722,1.86144268513,4.00561285019 --3.22173595428,1.85745155811,3.98821115494 --3.23871135712,1.85946190357,3.98178482056 --3.24968981743,1.8594712019,3.96938204765 --3.2696659565,1.86348128319,3.96797776222 --3.27764439583,1.86049044132,3.95157003403 --3.29063177109,1.86449575424,3.95436644554 --3.30760765076,1.86750602722,3.94794392586 --3.31558656693,1.86451494694,3.93153548241 --3.32456469536,1.8625241518,3.91612291336 --3.34654045105,1.86753439903,3.91671872139 --3.36251783371,1.86954402924,3.9103178978 --3.36649799347,1.86455237865,3.88991951942 --3.38048434258,1.86955797672,3.8927025795 --3.39346289635,1.86956703663,3.88331151009 --3.40743970871,1.87057697773,3.8728852272 --3.41641783714,1.86858606339,3.85747098923 --3.43239545822,1.87059545517,3.85107326508 --3.44537329674,1.87160468102,3.8406662941 --3.44436454773,1.86760854721,3.82747030258 --3.46433997154,1.87161874771,3.82404875755 --3.48031687737,1.87362837791,3.81663680077 --3.49229502678,1.87363755703,3.80523252487 --3.50327396393,1.872646451,3.79282999039 --3.52225017548,1.87665629387,3.78841495514 --3.5282292366,1.87266492844,3.77000331879 --3.54721665382,1.88067018986,3.77982521057 --3.55519485474,1.87767934799,3.762393713 --3.56817269325,1.87868845463,3.75198936462 --3.58315062523,1.87969756126,3.74358344078 --3.59812831879,1.88270688057,3.73517799377 --3.60410761833,1.87871551514,3.71676325798 --3.61708593369,1.87972438335,3.70635962486 --3.62207508087,1.87872898579,3.69915032387 --3.63805270195,1.88073825836,3.69174551964 --3.65902900696,1.88574790955,3.68933916092 --3.6680085659,1.88475632668,3.67493891716 --3.67898654938,1.88376545906,3.66152024269 --3.69296479225,1.88477432728,3.65211844444 --3.70195317268,1.8867790699,3.64890885353 --3.7149310112,1.88678812981,3.63749074936 --3.72591114044,1.88679647446,3.6261074543 --3.74988651276,1.89380645752,3.62569284439 --3.74786829948,1.88681387901,3.60028767586 --3.76484537125,1.88982331753,3.59287214279 --3.7818236351,1.89183235168,3.58647537231 --3.78481316566,1.89083647728,3.57726454735 --3.79979085922,1.89184558392,3.56785011292 --3.81776785851,1.89585483074,3.56143832207 --3.82374811172,1.89286291599,3.54403400421 --3.84072566032,1.89587199688,3.53662276268 --3.85870313644,1.8998811245,3.53021430969 --3.85968399048,1.89388906956,3.507802248 --3.87167239189,1.8968937397,3.50760245323 --3.89664912224,1.90490293503,3.50820636749 --3.89862966537,1.89991080761,3.48679423332 --3.91260790825,1.90091967583,3.47638297081 --3.93158578873,1.90492856503,3.47098112106 --3.94056487083,1.90393710136,3.45556163788 --3.96254229546,1.90894603729,3.45316839218 --3.95853352547,1.90494954586,3.43795919418 --3.96651363373,1.90295767784,3.42255520821 --3.98849034309,1.90896689892,3.41914606094 --4.00946807861,1.91397559643,3.41575551033 --4.00444984436,1.90498328209,3.38731956482 --4.02442836761,1.90999186039,3.38292765617 --4.03541707993,1.9129961729,3.38173532486 --4.04439544678,1.91200494766,3.36529684067 --4.05537509918,1.91201293468,3.35290145874 --4.08035182953,1.91902208328,3.35149216652 --4.08033418655,1.91402924061,3.33010101318 --4.09131336212,1.91403758526,3.31668710709 --4.1092915535,1.91704618931,3.30927824974 --4.10228347778,1.91104960442,3.2920665741 --4.11526298523,1.91205787659,3.28065919876 --4.14023923874,1.91906678677,3.27925825119 --4.14222097397,1.91507422924,3.25885009766 --4.15719938278,1.91708278656,3.2484331131 --4.17117881775,1.91909086704,3.23803210258 --4.18615722656,1.92109918594,3.22761678696 --4.18114900589,1.91610276699,3.21240568161 --4.20712661743,1.92411124706,3.21201777458 --4.19910955429,1.91411828995,3.18360114098 --4.21508836746,1.91712665558,3.17419099808 --4.23506736755,1.92213475704,3.16880011559 --4.22905015945,1.91414177418,3.1423869133 --4.24702835083,1.91815018654,3.13396835327 --4.26301622391,1.92315459251,3.13577437401 --4.26999664307,1.92216229439,3.11936283112 --4.29597425461,1.92917072773,3.11796879768 --4.31395292282,1.93317902088,3.1095559597 --4.31693410873,1.92918646336,3.09014463425 --4.34191131592,1.93619501591,3.08673214912 --4.35689973831,1.94119918346,3.08754014969 --4.36288070679,1.93920683861,3.07012557983 --4.37886047363,1.94221460819,3.06072664261 --4.40183877945,1.94922268391,3.05632948875 --4.40582036972,1.94622993469,3.03792333603 --4.42079925537,1.94823813438,3.02650237083 --4.4227809906,1.94424498081,3.00710248947 --4.43377017975,1.94724917412,3.00389361382 --4.44375085831,1.94725680351,2.98948264122 --4.44573307037,1.94426381588,2.97008085251 --4.45271396637,1.9422712326,2.95367026329 --4.449696064,1.93627810478,2.93025374413 --4.4516787529,1.93328523636,2.91084814072 --4.44666147232,1.92729210854,2.8864338398 --4.45965099335,1.93029606342,2.88524055481 --4.46763086319,1.92930364609,2.86881256104 --4.46461439133,1.92431044579,2.84640836716 --4.47659492493,1.92531788349,2.83400726318 --4.47957658768,1.92232477665,2.81560277939 --4.48455858231,1.92033207417,2.79819130898 --4.49353933334,1.92033922672,2.78378844261 --4.48053216934,1.91234242916,2.76456832886 --4.49451208115,1.91434979439,2.75316095352 --4.49749469757,1.91235685349,2.73475146294 --4.49647760391,1.90736365318,2.71435141563 --4.4864616394,1.89937007427,2.68793964386 --4.49244213104,1.89737761021,2.6705083847 --4.49142551422,1.89338433743,2.65010261536 --4.50241518021,1.8963881731,2.64689993858 --4.51239585876,1.89739525318,2.63350057602 --4.51337814331,1.89340209961,2.61408829689 --4.52235984802,1.89340925217,2.59968042374 --4.51934289932,1.88841593266,2.57827353477 --4.52932357788,1.88942337036,2.56385207176 --4.52531528473,1.8854265213,2.55164647102 --4.5322971344,1.88543355465,2.53624010086 --4.53227996826,1.88144028187,2.51683402061 --4.53626203537,1.87944734097,2.49942016602 --4.53424501419,1.87545382977,2.47901391983 --4.54822587967,1.87746095657,2.46760702133 --4.55420684814,1.8764680624,2.45118904114 --4.55219936371,1.87347114086,2.44099664688 --4.55618143082,1.87247812748,2.42357945442 --4.57116222382,1.8754850626,2.41318368912 --4.56814527512,1.8704918623,2.39176154137 --4.57712650299,1.87049877644,2.3773496151 --4.58510828018,1.87050557137,2.36294984818 --4.59508943558,1.87151265144,2.34852647781 --4.60308074951,1.87351584435,2.34434604645 --4.61906099319,1.87752258778,2.33394241333 --4.62204408646,1.87552928925,2.31653499603 --4.63202476501,1.87553632259,2.30211377144 --4.638007164,1.8755428791,2.28671526909 --4.64298963547,1.8745496273,2.27030611038 --4.64597225189,1.87255609035,2.2528963089 --4.65996217728,1.87655961514,2.25069642067 --4.65694570541,1.87256610394,2.23028635979 --4.6829252243,1.88057291508,2.22488975525 --4.67690896988,1.87457954884,2.2024667263 --4.68389081955,1.87458610535,2.18705654144 --4.69287347794,1.87559270859,2.1726474762 --4.69585561752,1.87359929085,2.15523552895 --4.7078461647,1.87660253048,2.15204071999 --4.70982933044,1.87460887432,2.13463878632 --4.72181081772,1.87661552429,2.12122106552 --4.73079252243,1.87762200832,2.10681319237 --4.74077510834,1.87862837315,2.0934176445 --4.74475717545,1.87763488293,2.07599401474 --4.75174045563,1.87764132023,2.06058478355 --4.75873088837,1.87864470482,2.0543782711 --4.75971460342,1.87665081024,2.03698444366 --4.77069664001,1.87865710258,2.02358007431 --4.78267860413,1.88066351414,2.01016640663 --4.7946600914,1.88266992569,1.99675369263 --4.80464315414,1.88367605209,1.98336148262 --4.80263519287,1.88167917728,1.97315430641 --4.81061697006,1.88268554211,1.95773601532 --4.81960010529,1.88369178772,1.94333136082 --4.82758331299,1.88369774818,1.9289368391 --4.82156705856,1.87870419025,1.90751469135 --4.83554887772,1.88171029091,1.89510893822 --4.84653186798,1.88371634483,1.88170933723 --4.85852241516,1.88771927357,1.87750649452 --4.85450601578,1.88372564316,1.85708618164 --4.86548900604,1.88573157787,1.84368789196 --4.87747144699,1.8877376318,1.83028149605 --4.8874540329,1.8887437582,1.81587100029 --4.88943767548,1.88774979115,1.79846298695 --4.89542150497,1.8877556324,1.78306531906 --4.89841270447,1.88775873184,1.77485489845 --4.90539598465,1.88776469231,1.75944852829 --4.90937995911,1.88677060604,1.74304509163 --4.91136360168,1.88577651978,1.72563517094 --4.91434669495,1.88378274441,1.70821654797 --4.91633081436,1.88278865814,1.69080531597 --4.94131231308,1.89079415798,1.68241071701 --4.93930435181,1.88779723644,1.67219591141 --4.94428873062,1.88780283928,1.65680682659 --4.95527172089,1.89080870152,1.64239192009 --4.96825456619,1.89281451702,1.62898540497 --4.96123886108,1.88782036304,1.60857665539 --4.97222185135,1.89082610607,1.59416294098 --4.97620630264,1.8898319006,1.57775866985 --4.98419761658,1.89183473587,1.57155644894 --4.99318027496,1.89284050465,1.55613720417 --4.98916625977,1.8898460865,1.53774738312 --5.007147789,1.89485168457,1.52533018589 --5.01413202286,1.89585721493,1.50992715359 --5.01611614227,1.89386296272,1.49251484871 --5.01810836792,1.89386570454,1.48431277275 --5.02709245682,1.89587104321,1.46991872787 --5.03007650375,1.89487695694,1.45249843597 --5.03706026077,1.89588224888,1.43709623814 --5.03204536438,1.8908880949,1.41768527031 --5.04502916336,1.89489328861,1.40428769588 --5.05601215363,1.89689898491,1.38885831833 --5.06700372696,1.9009013176,1.38366496563 --5.06798839569,1.89890682697,1.36625850201 --5.07797241211,1.90091204643,1.35186159611 --5.07595729828,1.8979177475,1.33345103264 --5.09994077682,1.90592229366,1.32305705547 --5.10092449188,1.90492808819,1.30462682247 --5.10090970993,1.90293359756,1.28722596169 --5.11390113831,1.90693581104,1.28202521801 --5.11588573456,1.90594124794,1.26461184025 --5.12087011337,1.90594661236,1.24820303917 --5.12685537338,1.90695166588,1.23281168938 --5.13683891296,1.90895676613,1.21739661694 --5.12882423401,1.90396273136,1.19697165489 --5.15080785751,1.91096699238,1.18558073044 --5.14180135727,1.90697014332,1.17437326908 --5.15178537369,1.90897512436,1.15895974636 --5.17376947403,1.91597938538,1.14757335186 --5.1527557373,1.90598571301,1.12414765358 --5.16574048996,1.90999054909,1.10974216461 --5.17872476578,1.91299521923,1.09533858299 --5.16971063614,1.90800082684,1.07593631744 --5.1867017746,1.91400277615,1.07072591782 --5.20468616486,1.92000722885,1.05732214451 --5.19467163086,1.91401302814,1.0369001627 --5.19665718079,1.9130179882,1.02050948143 --5.20864152908,1.91702270508,1.00509154797 --5.20762777328,1.91502773762,0.98769235611 --5.20561313629,1.91303324699,0.969273328781 --5.20860528946,1.91303563118,0.961067974567 --5.20559072495,1.91004097462,0.942652881145 --5.2105755806,1.91104578972,0.926246523857 --5.24156045914,1.92204904556,0.915863215923 --5.23054599762,1.91605484486,0.895437121391 --5.23553180695,1.91705965996,0.879032313824 --5.26051616669,1.92506313324,0.866635560989 --5.24250984192,1.91806674004,0.854428052902 --5.25049543381,1.92007136345,0.838011085987 --5.25748062134,1.92107605934,0.821599245071 --5.2534661293,1.91808128357,0.80318570137 --5.26145219803,1.92008554935,0.787793934345 --5.28543710709,1.92808902264,0.77438724041 --5.26242351532,1.91809546947,0.752975702286 --5.27341604233,1.92209720612,0.745765209198 --5.2884016037,1.92710101604,0.731373012066 --5.28838777542,1.92510581017,0.713966846466 --5.29637384415,1.92811024189,0.697554588318 --5.31035900116,1.9321141243,0.682146251202 --5.2983455658,1.92611980438,0.662734091282 --5.3123383522,1.93112111092,0.656542241573 --5.3223233223,1.93412518501,0.640126109123 --5.31931018829,1.93213009834,0.622729837894 --5.31029653549,1.92813575268,0.603303849697 --5.33528184891,1.9361385107,0.589913964272 --5.33026885986,1.93314361572,0.571499049664 --5.33225440979,1.93314814568,0.55408602953 --5.34124755859,1.93614971638,0.546892106533 --5.33823394775,1.93415462971,0.528469979763 --5.34422016144,1.93515884876,0.512070119381 --5.34620666504,1.93516325951,0.494657576084 --5.33919286728,1.93216848373,0.47624450922 --5.36117935181,1.94017112255,0.461852133274 --5.36116600037,1.93917560577,0.444445371628 --5.36215925217,1.93917798996,0.435227453709 --5.36814546585,1.9401819706,0.418830275536 --5.37313175201,1.94218611717,0.401411652565 --5.37911891937,1.9431899786,0.38501560688 --5.36810493469,1.93819570541,0.365584313869 --5.36809158325,1.93720006943,0.348176568747 --5.36907863617,1.93720448017,0.330766379833 --5.38107204437,1.94220542908,0.323574870825 --5.39205884933,1.94520890713,0.307171136141 --5.39404535294,1.94521307945,0.289760738611 --5.39903211594,1.94721698761,0.272345066071 --5.39801931381,1.94622147083,0.254939883947 --5.39800643921,1.94522571564,0.237532883883 --5.40699338913,1.94822907448,0.221136257052 --5.41898679733,1.95223009586,0.212927758694 --5.40897417068,1.94823539257,0.194511219859 --5.41496181488,1.9502389431,0.178120493889 --5.4069480896,1.94724404812,0.159699320793 --5.4099354744,1.94724798203,0.14228862524 --5.39992189407,1.94325327873,0.123867668211 --5.39691638947,1.94225549698,0.115678466856 --5.39190292358,1.94026041031,0.0972503721714 --5.39689016342,1.94126415253,0.0798370465636 --5.39387702942,1.94026851654,0.062430344522 --5.39286422729,1.93927276134,0.0450218394399 --5.39885187149,1.94127631187,0.0276085417718 --5.40184020996,1.94227981567,0.0112217515707 --5.39482688904,1.93928480148,-0.00720794918016 --5.40082025528,1.94128620625,-0.0154033312574 --5.39380788803,1.93829095364,-0.0328099764884 --5.39279508591,1.93729507923,-0.0502194315195 --5.39278268814,1.93729913235,-0.0676294863224 --5.39677047729,1.93930256367,-0.0850403085351 --5.38575792313,1.93530786037,-0.102449551225 --5.39574575424,1.93831074238,-0.119859956205 --5.3977394104,1.93931257725,-0.129076987505 --5.39772701263,1.93931651115,-0.146486893296 --5.39771461487,1.93932032585,-0.16389682889 --5.39070224762,1.93632519245,-0.181308686733 --5.40369033813,1.94132745266,-0.198714494705 --5.40567827225,1.94233107567,-0.216123193502 --5.41267299652,1.94533193111,-0.224312603474 --5.40866088867,1.94333636761,-0.24172347784 --5.42164945602,1.9483383894,-0.259124457836 --5.42963790894,1.95134115219,-0.276526927948 --5.43062591553,1.95234465599,-0.293933749199 --5.44161462784,1.95634710789,-0.312355577946 --5.44760322571,1.95834994316,-0.329756379128 --5.45959758759,1.96335017681,-0.338959813118 --5.45958566666,1.96335375309,-0.356364816427 --5.47357606888,1.96935546398,-0.373754382133 --5.48856449127,1.97435700893,-0.392163932323 --5.48555278778,1.97436094284,-0.409570664167 --5.48354053497,1.97336483002,-0.427999705076 --5.49753046036,1.97936618328,-0.445382982492 --5.51952648163,1.9873650074,-0.45558732748 --5.51851463318,1.98736846447,-0.472988933325 --5.52550363541,1.99037086964,-0.49140137434 --5.52249240875,1.9893746376,-0.508805692196 --5.52548122406,1.99137759209,-0.527223587036 --5.51846933365,1.98938202858,-0.544635534286 --5.52145814896,1.99038481712,-0.563052713871 --5.51745271683,1.98938703537,-0.571248352528 --5.51244068146,1.98739111423,-0.588657557964 --5.51443004608,1.98939418793,-0.607076644897 --5.51942014694,1.99139642715,-0.624465048313 --5.50440692902,1.98640203476,-0.641897141933 --5.51439714432,1.99040365219,-0.660297095776 --5.50938558578,1.98940765858,-0.677707791328 --5.50637960434,1.98840975761,-0.68692612648 --5.49236726761,1.9834151268,-0.70333635807 --5.49235677719,1.98441815376,-0.720736265182 --5.4923453331,1.98442137241,-0.739159107208 --5.4943356514,1.98642408848,-0.756553113461 --5.49332427979,1.98642742634,-0.774978220463 --5.49331378937,1.98643040657,-0.792376756668 --5.49430847168,1.9874317646,-0.80158495903 --5.48629665375,1.98543608189,-0.819007098675 --5.48628664017,1.98643910885,-0.836405754089 --5.48827600479,1.98744177818,-0.854821145535 --5.4862651825,1.98744511604,-0.87222546339 --5.4932551384,1.99144685268,-0.891647219658 --5.47424268723,1.98445308208,-0.907060742378 --5.47723770142,1.9864538908,-0.91626149416 --5.48022794724,1.98845624924,-0.934672176838 --5.4732170105,1.9864603281,-0.951070547104 --5.47020578384,1.98646378517,-0.969502091408 --5.46419477463,1.98446762562,-0.985897898674 --5.46918535233,1.98746943474,-1.00429987907 --5.46817493439,1.9884724617,-1.02272367477 --5.45816850662,1.98447561264,-1.02992534637 --5.46615982056,1.98947691917,-1.0493376255 --5.45314741135,1.98448216915,-1.065762043 --5.46313858032,1.98948299885,-1.08516430855 --5.45312786102,1.98648750782,-1.101577878 --5.44811677933,1.9864910841,-1.11899495125 --5.45211219788,1.98849153519,-1.12818741798 --5.44610118866,1.98649537563,-1.14560842514 --5.44109153748,1.9864988327,-1.16200268269 --5.43608093262,1.98550236225,-1.17942023277 --5.4330701828,1.98550546169,-1.19682896137 --5.42806005478,1.98450911045,-1.2142469883 --5.42905044556,1.98651146889,-1.23266041279 --5.42404460907,1.98451375961,-1.24086952209 --5.41503381729,1.9825180769,-1.25728428364 --5.41002321243,1.98152148724,-1.27470326424 --5.41201400757,1.98452353477,-1.29311132431 --5.41200447083,1.98552584648,-1.31050515175 --5.40499401093,1.98452985287,-1.32793450356 --5.40498495102,1.98553204536,-1.34532785416 --5.40197944641,1.98453402519,-1.35455143452 --5.38396692276,1.97954010963,-1.36897063255 --5.38195753098,1.97954273224,-1.38637506962 --5.39795064926,1.98754167557,-1.40777349472 --5.3839392662,1.98354697227,-1.42319643497 --5.38192987442,1.98454964161,-1.44059979916 --5.36891841888,1.98055458069,-1.45601904392 --5.3599114418,1.97755777836,-1.4632319212 --5.34990119934,1.97556197643,-1.47863638401 --5.35189247131,1.97756385803,-1.49704039097 --5.34588193893,1.97656738758,-1.51446795464 --5.34687328339,1.97956931591,-1.5328772068 --5.34286403656,1.97957229614,-1.55029261112 --5.3348531723,1.9775762558,-1.56670963764 --5.3258471489,1.97457921505,-1.5729033947 --5.31783676147,1.97358310223,-1.58932209015 --5.31582784653,1.97458565235,-1.60672593117 --5.30781698227,1.9725894928,-1.62314498425 --5.30680799484,1.97459185123,-1.64156532288 --5.30379915237,1.97459447384,-1.65897500515 --5.29578876495,1.97359836102,-1.67539513111 --5.29978513718,1.97559833527,-1.68559741974 --5.29277515411,1.97460198402,-1.70201086998 --5.28276491165,1.97260630131,-1.71742236614 --5.28175592422,1.97460842133,-1.73584127426 --5.25874233246,1.96761572361,-1.74725317955 --5.24373054504,1.96262121201,-1.76167953014 --5.26172637939,1.97261881828,-1.78507828712 --5.23971748352,1.96462500095,-1.78728151321 --5.23670864105,1.96462750435,-1.80469214916 --5.25370407104,1.9736250639,-1.82809317112 --5.22668981552,1.96463358402,-1.83851969242 --5.22568130493,1.96663558483,-1.85693788528 --5.22367286682,1.96763777733,-1.87433993816 --5.20466041565,1.9626442194,-1.88675773144 --5.21065807343,1.96564352512,-1.89796221256 --5.20564842224,1.96564650536,-1.91538715363 --5.19463777542,1.96365094185,-1.92979097366 --5.1876282692,1.96265435219,-1.94620943069 --5.19262170792,1.96765482426,-1.9666236639 --5.16960763931,1.95966243744,-1.97805655003 --5.17260503769,1.96266222,-1.98723685741 --5.17559766769,1.96566307545,-2.00766515732 --5.14858293533,1.95767176151,-2.01709008217 --5.15057611465,1.95967268944,-2.03548073769 --5.16257143021,1.96767103672,-2.05890011787 --5.13555669785,1.95867967606,-2.06832957268 --5.13354873657,1.95968163013,-2.08573007584 --5.14254760742,1.96467983723,-2.09792351723 --5.11253166199,1.95468962193,-2.10636115074 --5.10452270508,1.9546931982,-2.12176918983 --5.11851930618,1.9626904726,-2.14516425133 --5.0965051651,1.95569801331,-2.15660452843 --5.09349727631,1.95770013332,-2.17401337624 --5.09449005127,1.95970118046,-2.19342970848 --5.07047939301,1.95170867443,-2.19364643097 --5.07147359848,1.95470964909,-2.2120411396 --5.07546710968,1.95870959759,-2.23245191574 --5.0464515686,1.94971930981,-2.24089813232 --5.04444408417,1.95072102547,-2.25829696655 --5.05344009399,1.95771944523,-2.28070402145 --5.03442716599,1.95272624493,-2.29212808609 --5.01841545105,1.94773209095,-2.30454778671 --5.01841211319,1.94973266125,-2.31374883652 --5.00840187073,1.9477366209,-2.32815670967 --4.99439096451,1.94574189186,-2.3415825367 --5.00238656998,1.95074057579,-2.36399292946 --4.98137331009,1.94574797153,-2.37442207336 --4.96936273575,1.94275259972,-2.38782978058 --4.9823641777,1.94974911213,-2.40201067924 --4.95634889603,1.94175815582,-2.41044855118 --4.94933986664,1.94176125526,-2.42687416077 --4.94933366776,1.94476211071,-2.44527244568 --4.93232154846,1.94076824188,-2.45669007301 --4.93031454086,1.94276976585,-2.47510790825 --4.92330551147,1.9427728653,-2.49153351784 --4.91530036926,1.94077575207,-2.49672746658 --4.90929174423,1.94077849388,-2.51314258575 --4.89528036118,1.93778383732,-2.52657675743 --4.87826824188,1.9337900877,-2.53697824478 --4.88126373291,1.93778979778,-2.55738544464 --4.86425113678,1.93379616737,-2.56881046295 --4.84623861313,1.92980277538,-2.58024835587 --4.84923696518,1.93280208111,-2.59043502808 --4.8452296257,1.93380403519,-2.60785126686 --4.83822107315,1.93380701542,-2.62427806854 --4.81520700455,1.92781531811,-2.63168811798 --4.81019926071,1.92881762981,-2.64809370041 --4.80919313431,1.93081855774,-2.66751909256 --4.79518222809,1.92882394791,-2.67993974686 --4.79217815399,1.92882514,-2.68814778328 --4.77316522598,1.92383229733,-2.69756197929 --4.77415990829,1.92783236504,-2.71696329117 --4.77315425873,1.93083310127,-2.73638653755 --4.75314092636,1.92584061623,-2.74581503868 --4.74713277817,1.92584311962,-2.76223134995 --4.73812437057,1.92584657669,-2.77664017677 --4.7251162529,1.92185151577,-2.77985978127 --4.71610736847,1.92085504532,-2.79426956177 --4.71410131454,1.92385601997,-2.81268119812 --4.70009040833,1.92086136341,-2.82510852814 --4.69008159637,1.92086529732,-2.83851003647 --4.68207263947,1.92086839676,-2.85392951965 --4.66906261444,1.9188734293,-2.86634707451 --4.67106103897,1.9208728075,-2.87755727768 --4.67005586624,1.92387330532,-2.89697504044 --4.64704084396,1.91788196564,-2.90339040756 --4.63903236389,1.91788506508,-2.918810606 --4.63502597809,1.91988670826,-2.93622279167 --4.61501264572,1.91489434242,-2.94464707375 --4.60400342941,1.91389858723,-2.95806407928 --4.61100435257,1.91889595985,-2.97227072716 --4.59899425507,1.91690039635,-2.98467898369 --4.5859837532,1.91490542889,-2.99710083008 --4.58397865295,1.91790616512,-3.01550650597 --4.5619635582,1.91191458702,-3.02294206619 --4.55995893478,1.91491532326,-3.04134726524 --4.54494762421,1.91192102432,-3.05277681351 --4.54194355011,1.91292226315,-3.06098437309 --4.52393102646,1.90892922878,-3.06939291954 --4.52292633057,1.91192936897,-3.08880400658 --4.51191759109,1.91093361378,-3.10222363472 --4.49990749359,1.909938097,-3.11565756798 --4.49290037155,1.91094076633,-3.13106536865 --4.47888946533,1.9089461565,-3.14248585701 --4.48088884354,1.91094505787,-3.15368628502 --4.46587753296,1.90895092487,-3.16410064697 --4.45686912537,1.90895426273,-3.17851519585 --4.44085741043,1.90596055984,-3.18894505501 --4.44485569,1.9109582901,-3.21134209633 --4.42384147644,1.90696668625,-3.21878194809 --4.41983795166,1.90696811676,-3.2259824276 --4.41783332825,1.90996837616,-3.24540019035 --4.40282201767,1.90697419643,-3.255818367 --4.38681030273,1.90398061275,-3.26625180244 --4.38080453873,1.90598249435,-3.28164458275 --4.36179065704,1.90199005604,-3.29008293152 --4.36178779602,1.90598940849,-3.31048941612 --4.35078001022,1.90299391747,-3.31371068954 --4.33676958084,1.90099942684,-3.32411885262 --4.32576036453,1.90000343323,-3.33754396439 --4.3277592659,1.90600168705,-3.3599588871 --4.30774497986,1.90100991726,-3.36637616158 --4.30273914337,1.90301120281,-3.38379263878 --4.29773378372,1.90501248837,-3.40120840073 --4.26971626282,1.89402496815,-3.39142870903 --4.26871347427,1.89902448654,-3.41184520721 --4.27871656418,1.90801870823,-3.4402525425 --4.25570106506,1.90202832222,-3.44366121292 --4.24068975449,1.89903438091,-3.45408892632 --4.22467803955,1.89704072475,-3.46351361275 --4.27070426941,1.92301774025,-3.51889252663 --4.05254173279,1.90110051632,-3.70582056046 --4.03853130341,1.89910590649,-3.71725988388 --4.04153251648,1.90610253811,-3.74064540863 --4.02752256393,1.90410792828,-3.7520840168 --4.0275220871,1.90710687637,-3.76329064369 --3.99349784851,1.89612293243,-3.75672650337 --3.98349046707,1.8961263895,-3.77013874054 --3.95346856117,1.88714039326,-3.76657032967 --3.95947241783,1.89513516426,-3.79397439957 --3.92644810677,1.8841509819,-3.78740549088 --3.91544008255,1.88415491581,-3.80083680153 --3.9374563694,1.89814174175,-3.83203673363 --3.90142965317,1.88515937328,-3.82246875763 --3.89842748642,1.88915884495,-3.84187293053 --3.88341641426,1.88716495037,-3.85129880905 --3.88041448593,1.89216434956,-3.87171936035 --3.86240124702,1.88817226887,-3.87712430954 --3.85539627075,1.89017379284,-3.89353966713 --3.84138584137,1.88618052006,-3.89276695251 --3.82637453079,1.88418662548,-3.90117716789 --3.82437372208,1.88918530941,-3.92259502411 --3.79935479164,1.88219726086,-3.92201972008 --3.79835486412,1.88719511032,-3.94545412064 --3.79235100746,1.89019608498,-3.9628674984 --3.7833442688,1.88820016384,-3.96506381035 --3.76633167267,1.88520741463,-3.97249388695 --3.7613286972,1.88920760155,-3.99090647697 --3.74031281471,1.88421726227,-3.99433851242 --3.73030591011,1.88522052765,-4.00775146484 --3.72530317307,1.88822078705,-4.02616167068 --3.70829033852,1.88522815704,-4.03257703781 --3.69928383827,1.88423204422,-4.03681182861 --3.69328069687,1.88723278046,-4.0542216301 --3.67326521873,1.88224208355,-4.05764102936 --3.65625238419,1.88024961948,-4.06406021118 --3.65625429153,1.88624644279,-4.08847999573 --3.63523817062,1.88125646114,-4.090903759 --3.62923526764,1.88525688648,-4.1093287468 --3.61722564697,1.88126301765,-4.10853433609 --3.59921169281,1.87727105618,-4.11395788193 --3.58319973946,1.87527799606,-4.12137937546 --3.57519507408,1.87727975845,-4.13780593872 --3.55918312073,1.87528669834,-4.14522886276 --3.55117845535,1.87728846073,-4.16063690186 --3.53716850281,1.87729394436,-4.17107439041 --3.53416705132,1.87829434872,-4.17926740646 --3.51114845276,1.87230575085,-4.17970657349 --3.50714802742,1.8773047924,-4.20012235641 --3.49714159966,1.87830781937,-4.21353340149 --3.4811296463,1.87631487846,-4.22095918655 --3.46711969376,1.87532031536,-4.23139715195 --3.44910573959,1.87232875824,-4.23581314087 --3.44410276413,1.87233018875,-4.24302721024 --3.4421043396,1.87832772732,-4.26543188095 --3.41908550262,1.87233948708,-4.2648639679 --3.40707755089,1.87234389782,-4.27628087997 --3.39406847954,1.87234866619,-4.28771734238 --3.3790576458,1.87135505676,-4.29614448547 --3.36304545403,1.86936223507,-4.30255937576 --3.35804271698,1.8703635931,-4.30977249146 --3.33802628517,1.86537361145,-4.31220245361 --3.32101297379,1.8623816967,-4.31660699844 --3.31601238251,1.86738085747,-4.33703136444 --3.2949950695,1.86239171028,-4.33745241165 --3.28799247742,1.86539232731,-4.35486745834 --3.27498364449,1.86539721489,-4.36630582809 --3.27498602867,1.86939501762,-4.37849760056 --3.25396847725,1.86440598965,-4.37892246246 --3.25497484207,1.87240040302,-4.40734577179 --3.22694969177,1.86341667175,-4.39877223969 --3.21694397926,1.86541950703,-4.41218137741 --3.20493626595,1.86542356014,-4.42461442947 --3.18992543221,1.86443006992,-4.43203163147 --3.18292069435,1.86443281174,-4.43725347519 --3.16891050339,1.86343860626,-4.44668149948 --3.15490055084,1.86244440079,-4.4550948143 --3.1398897171,1.86145102978,-4.46251344681 --3.12487840652,1.86045765877,-4.46993303299 --3.10786533356,1.85846579075,-4.47536373138 --3.09986186028,1.86046683788,-4.49177503586 --3.09786319733,1.86346578598,-4.50298404694 --3.07284045219,1.8564800024,-4.49843215942 --3.06784129143,1.86147868633,-4.51883935928 --3.05283021927,1.86048531532,-4.52626037598 --3.03781938553,1.85949170589,-4.53469657898 --3.0188035965,1.85550153255,-4.53712844849 --3.02080917358,1.86049735546,-4.55230951309 --2.99878978729,1.85550963879,-4.55074691772 --2.99078726768,1.85851049423,-4.56816864014 --2.97677779198,1.85851609707,-4.57760000229 --2.96677303314,1.86051857471,-4.59201860428 --2.9437520504,1.85453188419,-4.58845329285 --2.93775248528,1.85953080654,-4.60887289047 --2.92073869705,1.85653936863,-4.61228179932 --2.91773915291,1.85953879356,-4.62249088287 --2.90773463249,1.861541152,-4.63690757751 --2.88671588898,1.85655283928,-4.63634729385 --2.86769962311,1.85356318951,-4.63777446747 --2.86069917679,1.85756289959,-4.65618228912 --2.8416826725,1.85357320309,-4.65761041641 --2.83768224716,1.85557305813,-4.66783857346 --2.82267069817,1.85458016396,-4.67323684692 --2.79764604568,1.84659588337,-4.66567420959 --2.79765629768,1.85658860207,-4.69710636139 --2.79065585136,1.86058831215,-4.71550798416 --2.76062393188,1.84960865974,-4.69994974136 --2.75462603569,1.85560703278,-4.72137069702 --2.75262832642,1.85860538483,-4.73357868195 --2.72760272026,1.85062170029,-4.72399711609 --2.71259188652,1.84962832928,-4.73142623901 --2.71060013771,1.85862267017,-4.75984811783 --2.68557429314,1.85063886642,-4.75128507614 --2.66755914688,1.8476485014,-4.75371551514 --2.66456604004,1.85564374924,-4.780128479 --2.64854741096,1.84865546227,-4.76934194565 --2.63253450394,1.84666347504,-4.77375555038 --2.62653827667,1.85366106033,-4.79719305038 --2.60551714897,1.8476742506,-4.79260158539 --2.58449721336,1.84268701077,-4.79003953934 --2.58551120758,1.85367763042,-4.82445669174 --2.56549239159,1.84968948364,-4.82288551331 --2.54646849632,1.8407047987,-4.8061003685 --2.54147315025,1.8467015028,-4.82950925827 --2.53247213364,1.85070204735,-4.84794282913 --2.51545810699,1.84871089458,-4.85136985779 --2.50545501709,1.85171282291,-4.8657746315 --2.4724149704,1.83773827553,-4.84223365784 --2.46341371536,1.84173882008,-4.85965394974 --2.4654238224,1.84873259068,-4.8788433075 --2.44340109825,1.84274697304,-4.87327766418 --2.42438340187,1.83875787258,-4.87371826172 --2.41337895393,1.84076070786,-4.88713312149 --2.39436125755,1.83777201176,-4.88656377792 --2.38235473633,1.83877587318,-4.89797639847 --2.38035917282,1.84377348423,-4.91118001938 --2.35533046722,1.83479142189,-4.89962148666 --2.3393175602,1.8337996006,-4.90404510498 --2.32931542397,1.83680093288,-4.92047023773 --2.31330251694,1.8358092308,-4.92489433289 --2.30129718781,1.83781278133,-4.93731832504 --2.28528428078,1.83682096004,-4.94174289703 --2.26826930046,1.8338303566,-4.94416809082 --2.26727628708,1.83982598782,-4.96138858795 --2.24825739861,1.83583807945,-4.95880413055 --2.23224425316,1.83384633064,-4.96323013306 --2.21923732758,1.83585107327,-4.9736533165 --2.20422673225,1.83585786819,-4.98109006882 --2.19121909142,1.83686280251,-4.99050140381 --2.18221068382,1.83486819267,-4.99071645737 --2.17220973969,1.83886885643,-5.00814390182 --2.15619683266,1.83787727356,-5.012570858 --2.13517355919,1.83189189434,-5.00599861145 --2.12216663361,1.83389651775,-5.01642036438 --2.10114312172,1.82791137695,-5.00985145569 --2.08512973785,1.8269200325,-5.01327180862 --2.09315729141,1.84090328217,-5.05148410797 --2.07313632965,1.83691644669,-5.04792499542 --2.06113147736,1.83891987801,-5.06034135818 --2.04010725021,1.83293509483,-5.05276632309 --2.02810382843,1.83593785763,-5.06720399857 -1.89292168617,1.77012372017,-4.24811792374 -1.90693223476,1.7701253891,-4.24251079559 -1.92595291138,1.77413129807,-4.24691677094 -1.92793595791,1.76212143898,-4.21233272552 -1.95297002792,1.77213299274,-4.23073005676 -1.95996499062,1.76512813568,-4.20913028717 -1.9749776125,1.76613080502,-4.20552539825 -1.97997784615,1.76412940025,-4.19674062729 -1.99799597263,1.76713418961,-4.19815206528 -2.00899982452,1.76413321495,-4.18555259705 -2.02401208878,1.76513552666,-4.18095874786 -2.03301167488,1.7601326704,-4.16337013245 -2.04501748085,1.75813233852,-4.15178585052 -2.06403875351,1.76213884354,-4.15816259384 -2.07605361938,1.76714348793,-4.16437339783 -2.09808039665,1.77415192127,-4.17575836182 -2.11108779907,1.77215242386,-4.16617393494 -2.12209177017,1.77015125751,-4.15258836746 -2.14211440086,1.77515804768,-4.159968853 -2.14209651947,1.76214838028,-4.12340068817 -2.15911245346,1.76515197754,-4.12181663513 -2.16210961342,1.76114964485,-4.11002826691 -2.18112969398,1.76515543461,-4.11441898346 -2.19914770126,1.76916015148,-4.11581993103 -2.20714664459,1.76415729523,-4.09723186493 -2.21815156937,1.76115679741,-4.08464193344 -2.24618768692,1.77316892147,-4.10602617264 -2.25318527222,1.76716578007,-4.08643054962 -2.25618314743,1.76416349411,-4.07464599609 -2.27620506287,1.77016985416,-4.08102750778 -2.28921246529,1.76817047596,-4.07045936584 -2.30322289467,1.7681722641,-4.06386423111 -2.31623244286,1.76817381382,-4.05724668503 -2.33324718475,1.77017724514,-4.05466890335 -2.33524441719,1.76717507839,-4.04286575317 -2.35025644302,1.76717758179,-4.03826856613 -2.37027716637,1.77218341827,-4.04266691208 -2.38428711891,1.77218496799,-4.03508377075 -2.39429116249,1.77018427849,-4.02148914337 -2.40429496765,1.76718366146,-4.00789499283 -2.41930699348,1.76718604565,-4.00231027603 -2.43132066727,1.77219033241,-4.00849819183 -2.44633245468,1.77219259739,-4.00291204453 -2.45934176445,1.77219414711,-3.99530625343 -2.47435331345,1.77319645882,-3.98971843719 -2.48535919189,1.77119636536,-3.97713637352 -2.50237464905,1.77420032024,-3.9765253067 -2.51538324356,1.7732013464,-3.96694755554 -2.52339076996,1.77520334721,-3.96712327003 -2.53039002419,1.77020096779,-3.9475505352 -2.54840683937,1.77320539951,-3.94794583321 -2.56041407585,1.77220618725,-3.93736028671 -2.57642817497,1.77420949936,-3.93475198746 -2.58943676949,1.77321064472,-3.92517471313 -2.59844017029,1.77020990849,-3.91058135033 -2.6104528904,1.77421367168,-3.91478562355 -2.62546491623,1.77521622181,-3.91018199921 -2.63546943665,1.77221608162,-3.89659690857 -2.65548872948,1.77722132206,-3.89900040627 -2.66849803925,1.77722299099,-3.89139485359 -2.67650055885,1.77422201633,-3.87579655647 -2.69151210785,1.77522432804,-3.86922001839 -2.70352482796,1.77922809124,-3.87440443039 -2.71853661537,1.78023040295,-3.86782646179 -2.73354840279,1.78123307228,-3.86223340034 -2.74255251884,1.77823269367,-3.84863042831 -2.75556182861,1.7782343626,-3.84003901482 -2.76756954193,1.77723562717,-3.83044195175 -2.78258180618,1.77923810482,-3.82484793663 -2.79559516907,1.78324198723,-3.83004760742 -2.80960583687,1.78424429893,-3.8234462738 -2.82361602783,1.78424632549,-3.81585979462 -2.8316192627,1.78124558926,-3.80026888847 -2.83561658859,1.77524292469,-3.77770209312 -2.84762525558,1.77524447441,-3.7690911293 -2.85863542557,1.77724730968,-3.77030563354 -2.87164497375,1.77724909782,-3.7617149353 -2.88365340233,1.77725040913,-3.75211858749 -2.90267038345,1.78125488758,-3.75251221657 -2.9186835289,1.78325784206,-3.74792051315 -2.92368340492,1.77825629711,-3.72833609581 -2.93769407272,1.77925860882,-3.72173428535 -2.94369792938,1.77825903893,-3.71496748924 -2.95670795441,1.77926123142,-3.70834469795 -2.98974132538,1.79227113724,-3.72574830055 -2.99974751472,1.79027187824,-3.71414160728 -3.00174379349,1.78326904774,-3.68958067894 -3.01575446129,1.78427135944,-3.68199276924 -3.02576065063,1.78227221966,-3.67038846016 -3.02876162529,1.78027164936,-3.66159462929 -3.04577589035,1.78327512741,-3.65800213814 -3.05878520012,1.78327691555,-3.64842605591 -3.08380866051,1.79128348827,-3.65581178665 -3.10082292557,1.79428696632,-3.65221524239 -3.11283135414,1.79428851604,-3.64261674881 -3.10882234573,1.78428435326,-3.613032341 -3.11582756042,1.78428542614,-3.60825419426 -3.12283086777,1.78128528595,-3.592659235 -3.13483929634,1.78028678894,-3.58208107948 -3.16086339951,1.78929364681,-3.59045886993 -3.19089126587,1.79930150509,-3.6018614769 -3.19789481163,1.79730153084,-3.58724880219 -3.1908853054,1.78929793835,-3.5664665699 -3.20489597321,1.78930020332,-3.55789208412 -3.21790575981,1.79030239582,-3.54929709435 -3.2239086628,1.78730213642,-3.53270339966 -3.23791909218,1.78730452061,-3.52412891388 -3.25593447685,1.7913081646,-3.52152705193 -3.26694202423,1.79030966759,-3.50994539261 -3.27895283699,1.79431247711,-3.51214003563 -3.28495550156,1.7903124094,-3.4955496788 -3.29396152496,1.78931343555,-3.48294734955 -3.30597066879,1.78931522369,-3.47236800194 -3.3189804554,1.78931736946,-3.46377277374 -3.33098959923,1.78931927681,-3.4541759491 -3.34700226784,1.79232239723,-3.44760084152 -3.35000395775,1.79032254219,-3.43979883194 -3.37302350998,1.79732763767,-3.4421942234 -3.38803529739,1.79833030701,-3.43461632729 -3.39103579521,1.79332971573,-3.41502857208 -3.40104317665,1.79233121872,-3.40342950821 -3.41405320168,1.79333341122,-3.39483189583 -3.43707227707,1.79933845997,-3.39623808861 -3.42606139183,1.79033482075,-3.37345075607 -3.44407606125,1.79433846474,-3.36985445023 -3.45808696747,1.79534113407,-3.36225652695 -3.47209811211,1.79734373093,-3.35465741158 -3.49311542511,1.80234801769,-3.3530755043 -3.51613426208,1.80835294724,-3.35447263718 -3.50512361526,1.79934954643,-3.33169531822 -3.51713299751,1.7993516922,-3.32111406326 -3.53314566612,1.80235481262,-3.31551194191 -3.53814888,1.79835510254,-3.29793453217 -3.5451540947,1.79635608196,-3.28333854675 -3.57017421722,1.80336129665,-3.28574609756 -3.58118271828,1.803363204,-3.27514624596 -3.59119081497,1.80536532402,-3.27336001396 -3.60119819641,1.80436694622,-3.26176095009 -3.6082034111,1.80236804485,-3.24618434906 -3.61821126938,1.80236971378,-3.23458552361 -3.63022041321,1.80237197876,-3.22498440742 -3.62521624565,1.79437041283,-3.19841051102 -3.6192111969,1.78436875343,-3.1698615551 -3.60520029068,1.77536559105,-3.14607906342 -3.59319067001,1.762362957,-3.11351060867 -3.57617783546,1.74835920334,-3.07497668266 -3.57818007469,1.74335968494,-3.05638861656 -3.56717228889,1.73235762119,-3.02581238747 -3.55116081238,1.718354702,-2.99025344849 -3.55316376686,1.71435534954,-2.97167420387 -3.55516600609,1.71235597134,-2.96289300919 -3.55817008018,1.70935702324,-2.94531416893 -3.56917977333,1.70935976505,-2.93571424484 -3.57318425179,1.70636117458,-2.91913485527 -3.58019113541,1.70436310768,-2.90554738045 -3.61822104454,1.71837091446,-2.91992259026 -3.59920907021,1.70436799526,-2.8823788166 -3.60721564293,1.70536994934,-2.87958097458 -3.61122083664,1.70237135887,-2.86398482323 -3.60521864891,1.69437122345,-2.83940601349 -3.61122536659,1.69237327576,-2.82384800911 -3.6422495842,1.70337963104,-2.83123493195 -3.63924980164,1.69638001919,-2.80964946747 -3.64625716209,1.69538223743,-2.79606699944 -3.6572663784,1.69838476181,-2.79527640343 -3.74135923386,1.68441367149,-2.63624405861 -3.74636602402,1.68241608143,-2.6216583252 -3.75237345695,1.68041861057,-2.60806798935 -3.77539181709,1.68742346764,-2.60648584366 -3.76238751411,1.67642343044,-2.57792377472 -3.76539325714,1.67342567444,-2.56233215332 -3.7714009285,1.67242836952,-2.5487446785 -3.77240347862,1.67042934895,-2.54094171524 -3.79041838646,1.67443346977,-2.53634357452 -3.78942227364,1.66943538189,-2.51678180695 -3.80843782425,1.67443966866,-2.51317429543 -3.80944275856,1.67144179344,-2.49560022354 -3.8064455986,1.66544377804,-2.47503399849 -3.8094496727,1.66544508934,-2.46824193001 -3.82346224785,1.66744887829,-2.4606461525 -3.8234667778,1.66345095634,-2.44306135178 -3.82747411728,1.66145372391,-2.42749428749 -3.84248733521,1.66445755959,-2.42088937759 -3.83949041367,1.65945959091,-2.40130829811 -3.8515021801,1.66046321392,-2.39172697067 -3.85850858688,1.66246509552,-2.3879275322 -3.86551737785,1.66146814823,-2.3753387928 -3.87352657318,1.66147136688,-2.36374187469 -3.88253712654,1.66147482395,-2.35118365288 -3.88154172897,1.65747725964,-2.33359313011 -3.89055156708,1.65748047829,-2.32298874855 -3.89555978775,1.65648365021,-2.30841875076 -3.90156579018,1.65748548508,-2.30362701416 -3.90657353401,1.65548849106,-2.29003453255 -3.9145834446,1.65549182892,-2.27843928337 -3.91959166527,1.65449512005,-2.26387119293 -3.92259883881,1.65249800682,-2.2492749691 -3.93761277199,1.65550208092,-2.24070978165 -3.93861865997,1.65250504017,-2.22510957718 -3.94762611389,1.65450704098,-2.22231197357 -3.96163916588,1.65751111507,-2.21373009682 -3.95964360237,1.65251374245,-2.19613695145 -3.96265149117,1.65051686764,-2.18056797981 -3.980666399,1.6555211544,-2.17496871948 -3.97867155075,1.6505240202,-2.15640330315 -3.97867774963,1.64752721786,-2.13981866837 -3.98968577385,1.65052914619,-2.13899731636 -3.98969244957,1.64753258228,-2.12143850327 -3.9937005043,1.64553570747,-2.10783839226 -4.00671339035,1.64753985405,-2.0982644558 -4.00872039795,1.64554309845,-2.08268666267 -4.01472997665,1.64554655552,-2.07009005547 -4.02473783493,1.64754891396,-2.06730055809 -4.02074241638,1.64355194569,-2.0487177372 -4.03475570679,1.64555597305,-2.04013061523 -4.03576278687,1.64355933666,-2.02454257011 -4.03777074814,1.64056289196,-2.00896930695 -4.04678153992,1.64156675339,-1.99738955498 -4.05979394913,1.64457070827,-1.98878645897 -4.06079816818,1.64357256889,-1.9810000658 -4.06080532074,1.64057600498,-1.96442782879 -4.06981563568,1.64057981968,-1.95382273197 -4.06982278824,1.63858342171,-1.93725204468 -4.07883405685,1.63858747482,-1.92567205429 -4.08684444427,1.63959133625,-1.91407847404 -4.08785200119,1.63659501076,-1.89849841595 -4.09385824203,1.63859701157,-1.89370119572 -4.10487031937,1.63960123062,-1.88312029839 -4.10087585449,1.63560461998,-1.8655295372 -4.1028842926,1.63360857964,-1.84996449947 -4.11589670181,1.635612607,-1.84135699272 -4.11290359497,1.63161635399,-1.82378268242 -4.1249165535,1.63362073898,-1.81321310997 -4.12992191315,1.63462269306,-1.80840265751 -4.13593196869,1.63462686539,-1.79483652115 -4.12893676758,1.6286303997,-1.77624416351 -4.14695167542,1.63363468647,-1.76964116096 -4.14495944977,1.63063883781,-1.75208461285 -4.15997266769,1.63364315033,-1.74349582195 -4.1669793129,1.63564527035,-1.73870766163 -4.15798377991,1.62864911556,-1.71912407875 -4.16899633408,1.63065338135,-1.70853924751 -4.18401002884,1.63465774059,-1.69994699955 -4.17501449585,1.62866163254,-1.68036746979 -4.18202543259,1.62866592407,-1.66778874397 -4.20003938675,1.63367009163,-1.66117584705 -4.18803977966,1.62767219543,-1.64740920067 -4.19204950333,1.62667644024,-1.63382327557 -4.21006441116,1.63168084621,-1.62623417377 -4.19906902313,1.62468516827,-1.60566818714 -4.20507955551,1.6246894598,-1.59307897091 -4.22609472275,1.63069355488,-1.58746623993 -4.21510028839,1.62369811535,-1.56690526009 -4.2211060524,1.62570011616,-1.56210267544 -4.23511981964,1.62870454788,-1.55251824856 -4.22612571716,1.62270915508,-1.53295648098 -4.22913551331,1.6217135191,-1.51936268806 -4.24414920807,1.62571799755,-1.50978696346 -4.24615812302,1.62372231483,-1.49618303776 -4.25116920471,1.623726964,-1.48260998726 -4.25617551804,1.6247292757,-1.47682225704 -4.25118303299,1.62073397636,-1.45925581455 -4.26519584656,1.62373816967,-1.45063960552 -4.27720880508,1.6267427206,-1.44005548954 -4.26021289825,1.61774778366,-1.41750860214 -4.27222537994,1.62075197697,-1.40789759159 -4.28323364258,1.62375438213,-1.40411329269 -4.2712392807,1.61675930023,-1.38453960419 -4.27524995804,1.61676394939,-1.3709590435 -4.29226398468,1.62176835537,-1.3623663187 -4.28527164459,1.61677336693,-1.3447906971 -4.28828191757,1.61577796936,-1.33120167255 -4.30029439926,1.6187826395,-1.32061398029 -4.29429769516,1.61478531361,-1.31083250046 -4.29930877686,1.61479020119,-1.29726231098 -4.31932353973,1.62179422379,-1.29063570499 -4.30332946777,1.61279976368,-1.26909577847 -4.31134080887,1.61380445957,-1.25749778748 -4.3233537674,1.61680912971,-1.24690687656 -4.31936264038,1.61381435394,-1.2303403616 -4.31636667252,1.61181676388,-1.22253537178 -4.33638143539,1.61782085896,-1.21492922306 -4.32238864899,1.60982692242,-1.19439065456 -4.32639884949,1.60983169079,-1.18178534508 -4.34141254425,1.61383605003,-1.17218887806 -4.33542203903,1.60984182358,-1.15463900566 -4.34343338013,1.61184644699,-1.14303874969 -4.34743928909,1.61184883118,-1.13723862171 -4.34444856644,1.60885417461,-1.12166023254 -4.35046100616,1.60985946655,-1.10809910297 -4.3584728241,1.61186408997,-1.0964974165 -4.3524813652,1.60686969757,-1.07992625237 -4.35649299622,1.60687494278,-1.06634986401 -4.36750078201,1.61087691784,-1.06254649162 -4.36451053619,1.60788249969,-1.04697227478 -4.36152029037,1.60488796234,-1.03139960766 -4.3775343895,1.60989260674,-1.0218000412 -4.37054347992,1.60589826107,-1.0052267313 -4.38355636597,1.60890305042,-0.994631707668 -4.39156913757,1.61090815067,-0.982055127621 -4.38257265091,1.60691142082,-0.972272872925 -4.38758420944,1.60691642761,-0.959675610065 -4.40059709549,1.61092102528,-0.949076771736 -4.38860607147,1.6039276123,-0.930531561375 -4.39961862564,1.60693264008,-0.918946504593 -4.40463066101,1.60793757439,-0.906348228455 -4.39763402939,1.60394072533,-0.897557199001 -4.40664768219,1.60694611073,-0.884985387325 -4.41666030884,1.60895097256,-0.873391151428 -4.40966939926,1.6049567461,-0.857800841331 -4.42068338394,1.6079621315,-0.845240235329 -4.42569446564,1.60896730423,-0.832641005516 -4.41770458221,1.60397362709,-0.816076397896 -4.41770982742,1.6039763689,-0.809275984764 -4.43072366714,1.60698139668,-0.797697007656 -4.42973470688,1.6059871912,-0.783119082451 -4.43474674225,1.60699248314,-0.77051961422 -4.43675851822,1.60599839687,-0.755960166454 -4.44277048111,1.60700368881,-0.743366062641 -4.43878078461,1.60400950909,-0.728773415089 -4.45178890228,1.60901176929,-0.723988056183 -4.44479894638,1.60501801968,-0.708408296108 -4.45181131363,1.60702335835,-0.695818603039 -4.45882368088,1.60802865028,-0.683228433132 -4.44683361053,1.60203552246,-0.666654765606 -4.45484638214,1.60404086113,-0.654069662094 -4.45985937119,1.6050465107,-0.64049744606 -4.45386362076,1.60204982758,-0.632698237896 -4.45987653732,1.60405564308,-0.619130849838 -4.45888805389,1.60206186771,-0.604559004307 -4.46490049362,1.60406720638,-0.59196215868 -4.46791267395,1.60407304764,-0.578380227089 -4.46892404556,1.60307884216,-0.564789295197 -4.47493076324,1.60508131981,-0.558989346027 -4.47394275665,1.60408771038,-0.544418334961 -4.47495555878,1.60309398174,-0.529856681824 -4.47696733475,1.603099823,-0.516270339489 -4.48698091507,1.6061052084,-0.503687679768 -4.479991436,1.60211181641,-0.489094108343 -4.47300291061,1.59911882877,-0.473530858755 -4.48300933838,1.6021207571,-0.468714982271 -4.49802303314,1.60712563992,-0.457119762897 -4.48903417587,1.60313260555,-0.441550254822 -4.48804664612,1.60213923454,-0.426982402802 -4.4950594902,1.60414469242,-0.414384871721 -4.49707221985,1.60415112972,-0.399827629328 -4.49608421326,1.60215735435,-0.386231690645 -4.5000910759,1.60416030884,-0.37944817543 -4.49510240555,1.60116708279,-0.364868879318 -4.50011587143,1.60217308998,-0.351292461157 -4.50612831116,1.60417854786,-0.338689118624 -4.50914096832,1.60418474674,-0.325105726719 -4.50415229797,1.60219156742,-0.310528427362 -4.51516628265,1.60519683361,-0.297937899828 -4.51617336273,1.60520040989,-0.290173590183 -4.50618457794,1.60120761395,-0.275584727526 -4.51119709015,1.60221374035,-0.262006372213 -4.51521062851,1.60321986675,-0.248424872756 -4.5162229538,1.60322618484,-0.234835937619 -4.5192360878,1.60423243046,-0.221251443028 -4.51824140549,1.60323560238,-0.214453816414 -4.52125453949,1.60424184799,-0.200869128108 -4.51726722717,1.6022490263,-0.186299458146 -4.52228021622,1.60325503349,-0.172718822956 -4.52929401398,1.60526108742,-0.159141033888 -4.5363073349,1.60726714134,-0.145562186837 -4.52031850815,1.6012750864,-0.130973860621 -4.52432537079,1.60227811337,-0.124185405672 -4.53733968735,1.60728371143,-0.110614679754 -4.5213508606,1.60029184818,-0.0960306674242 -4.52236366272,1.60029840469,-0.0824426114559 -4.54137849808,1.60730302334,-0.0698472484946 -4.53839111328,1.60631024837,-0.0552821308374 -4.53740406036,1.60531687737,-0.0416907630861 -4.55841207504,1.61331796646,-0.0358872227371 -4.54442405701,1.60732638836,-0.0213119275868 -4.53243637085,1.60233449936,-0.00674084760249 -4.53844976425,1.60434067249,0.00684422021732 -4.52046251297,1.59735000134,0.0223868004978 -4.54747772217,1.60735368729,0.0349896848202 -4.55749130249,1.61135935783,0.0485758110881 -4.54049634933,1.60436439514,0.0553781539202 -4.53150892258,1.6013725996,0.0699415355921 -4.54752397537,1.60737776756,0.0835268050432 -4.5365357399,1.60238564014,0.0971182435751 -4.53154945374,1.6003934145,0.111678235233 -4.54856395721,1.60739850998,0.125267922878 -4.53356933594,1.60140347481,0.132061466575 -4.52658319473,1.59841156006,0.146619454026 -4.5445971489,1.60541641712,0.160212621093 -4.52060937881,1.59642612934,0.173793509603 -4.52462244034,1.59743261337,0.18738271296 -4.53263759613,1.60043907166,0.20194555819 -4.51765012741,1.5954477787,0.215524688363 -4.51765680313,1.59545135498,0.222318306565 -4.53967142105,1.60345554352,0.235922545195 -4.51768493652,1.59546589851,0.250463336706 -4.50969839096,1.59247398376,0.264042913914 -4.53371238708,1.6014778614,0.277654737234 -4.51672554016,1.59548711777,0.291224241257 -4.51873874664,1.5954939127,0.304813802242 -4.51974725723,1.59649789333,0.312579572201 -4.50876045227,1.59250664711,0.326152145863 -4.50977420807,1.59251356125,0.339740246534 -4.51878786087,1.59651935101,0.353341341019 -4.50680208206,1.5925283432,0.366909533739 -4.51781654358,1.59653425217,0.381485968828 -4.52083015442,1.59754109383,0.395079314709 -4.49483680725,1.58754813671,0.400854110718 -4.50685167313,1.5925539732,0.415434360504 -4.51786565781,1.5975600481,0.430014997721 -4.50187921524,1.59156918526,0.4425984025 -4.50289344788,1.59257638454,0.456187844276 -4.51190757751,1.59558260441,0.47076651454 -4.49391460419,1.58958876133,0.47654747963 -4.50092935562,1.59259545803,0.491122066975 -4.50394296646,1.59360206127,0.504717171192 -4.49695777893,1.59161067009,0.518286705017 -4.49797153473,1.59261786938,0.531877100468 -4.50298643112,1.59462475777,0.546449661255 -4.49600124359,1.59263348579,0.560017764568 -4.51600790024,1.60063385963,0.567841827869 -4.50002241135,1.59464371204,0.580412209034 -4.49303674698,1.59265244007,0.593978941441 -4.50305128098,1.59665834904,0.608570337296 -4.49206495285,1.59266746044,0.621152460575 -4.47807979584,1.58767700195,0.633722603321 -4.48308753967,1.59068024158,0.641504645348 -4.47610282898,1.5876891613,0.655067741871 -4.47811698914,1.5896961689,0.668663263321 -4.48413181305,1.59270298481,0.683244943619 -4.47914648056,1.59071135521,0.696814775467 -4.47716140747,1.59071922302,0.710396111012 -4.47217512131,1.58972740173,0.722994625568 -4.45818328857,1.58473348618,0.728761553764 -4.4631986618,1.5877405405,0.743341088295 -4.46521234512,1.58874762058,0.75693821907 -4.46022748947,1.58775639534,0.770505845547 -4.46424293518,1.58976352215,0.785083353519 -4.47825717926,1.59576904774,0.800678014755 -4.50427150726,1.60677301884,0.818272531033 -4.48527860641,1.59977936745,0.822068750858 -3.94831037521,1.60589742661,2.39534854889 -3.93833017349,1.60490846634,2.40592002869 -3.9133515358,1.59692239761,2.40749263763 -3.90337014198,1.59593319893,2.41708683968 -3.90437912941,1.59793758392,2.42587351799 -3.90039730072,1.59894752502,2.43945789337 -3.89441728592,1.59995830059,2.45301198959 -3.89243507385,1.60196757317,2.46760320663 -3.87845468521,1.59897947311,2.47518539429 -3.86747455597,1.59799075127,2.48476266861 -3.87248253822,1.60199415684,2.49556493759 -3.86450266838,1.60200548172,2.5081140995 -3.86252045631,1.6040148735,2.52270841599 -3.85154008865,1.60202622414,2.53228521347 -3.84056019783,1.6010376215,2.54186177254 -3.83957791328,1.6040469408,2.55744886398 -3.8315975666,1.60405790806,2.56902337074 -3.82160806656,1.60106432438,2.5708129406 -3.81362771988,1.60107529163,2.5823867321 -3.81464481354,1.60408401489,2.59898424149 -3.80166554451,1.60209596157,2.60755085945 -3.79768395424,1.6041059494,2.62114214897 -3.79870200157,1.60811507702,2.63871860504 -3.78271389008,1.60212278366,2.63650345802 -3.77773308754,1.60413324833,2.65007901192 -3.77475166321,1.60614311695,2.66466426849 -3.76477217674,1.60515463352,2.67523050308 -3.76279067993,1.60816431046,2.69080972672 -3.75180983543,1.60617542267,2.69940710068 -3.74582886696,1.6071857214,2.71199250221 -3.74083971977,1.60719180107,2.71776366234 -3.73785805702,1.60920166969,2.73235273361 -3.71887969971,1.60421466827,2.73593211174 -3.71189975739,1.60522556305,2.74850058556 -3.70391941071,1.60523664951,2.76007580757 -3.70193815231,1.60824632645,2.77566051483 -3.68995857239,1.60625815392,2.78423833847 -3.6969666481,1.61126160622,2.7980287075 -3.68398690224,1.60927343369,2.80561304092 -3.67700719833,1.61028432846,2.81818389893 -3.67902493477,1.61529314518,2.8367729187 -3.65404748917,1.60730731487,2.83535432816 -3.64706754684,1.60831844807,2.84792542458 -3.64708614349,1.61232805252,2.86550521851 -3.63009858131,1.60633599758,2.86129426956 -3.6261177063,1.60834622383,2.87587285042 -3.63213443756,1.61535418034,2.89747095108 -3.61115789413,1.60936844349,2.9000222683 -3.60117816925,1.60937964916,2.90960979462 -3.60319542885,1.61438834667,2.92820858955 -3.58820819855,1.60939645767,2.92598080635 -3.57622933388,1.60740828514,2.9345536232 -3.58324670792,1.61541652679,2.95813345909 -3.56426882744,1.61042976379,2.96071457863 -3.55528903008,1.61044096947,2.97129702568 -3.55630731583,1.61545014381,2.98988485336 -3.53433036804,1.60946440697,2.99045157433 -3.53433942795,1.61146903038,2.9992480278 -3.53735756874,1.61647796631,3.01983094215 -3.51638031006,1.61149156094,3.02041363716 -3.51140022278,1.61350226402,3.03498244286 -3.50642061234,1.61551308632,3.04955267906 -3.4914419651,1.61252570152,3.05513334274 -3.48846125603,1.61553561687,3.07072043419 -3.48647046089,1.61654055119,3.0775270462 -3.47149300575,1.61455357075,3.08408474922 -3.46051359177,1.61356508732,3.09267377853 -3.45553350449,1.61557579041,3.10724711418 -3.44155550003,1.61358833313,3.11382174492 -3.43557453156,1.61459875107,3.12642025948 -3.43159484863,1.61760938168,3.14199328423 -3.42660522461,1.61761510372,3.14678668976 -3.41462683678,1.61662733555,3.15535616875 -3.41364574432,1.62063694,3.17294716835 -3.3976688385,1.61765038967,3.17850232124 -3.39168810844,1.61966073513,3.19110393524 -3.38570809364,1.62167155743,3.20468521118 -3.36672210693,1.61468052864,3.19745659828 -3.36374187469,1.61769092083,3.21403336525 -3.35976099968,1.62070095539,3.22863388062 -3.34978270531,1.62071287632,3.2392001152 -3.33080554008,1.61572647095,3.24077486992 -3.33082389832,1.6207357645,3.25937366486 -3.3198363781,1.6177431345,3.2591509819 -3.31585621834,1.62075352669,3.27473378181 -3.30987620354,1.62276446819,3.28831887245 -3.29689860344,1.62177693844,3.29588699341 -3.28691959381,1.62178850174,3.30547451973 -3.27794098854,1.62180042267,3.31704115868 -3.26196312904,1.61881303787,3.32062888145 -3.26497197151,1.62281739712,3.33342266083 -3.25299453735,1.62182974815,3.34198975563 -3.24201464653,1.62184107304,3.34959769249 -3.23103785515,1.62185382843,3.36014413834 -3.2280561924,1.62486350536,3.3757557869 -3.21207952499,1.62187683582,3.38031983376 -3.20310139656,1.62288868427,3.39188838005 -3.20211076736,1.62489366531,3.4006857872 -3.1851336956,1.62190675735,3.40326738358 -3.18115401268,1.62491750717,3.41984200478 -3.17317461967,1.6269286871,3.43143296242 -3.15919685364,1.62494122982,3.43701648712 -3.15521717072,1.62795186043,3.45359420776 -3.14323973656,1.62696444988,3.46216058731 -3.13325071335,1.62497091293,3.46096682549 -3.12727165222,1.62698209286,3.47554302216 -3.11529445648,1.62699460983,3.48410892487 -3.10531568527,1.62700629234,3.49369835854 -3.09833669662,1.62901759148,3.50727510452 -3.09035730362,1.63002872467,3.51886987686 -3.0793697834,1.62703609467,3.51765060425 -3.06839203835,1.62704837322,3.52721881866 -3.06541204453,1.63205862045,3.54480814934 -3.05343389511,1.63107073307,3.55239367485 -3.03845763206,1.62908422947,3.55795073509 -3.03247857094,1.6320952177,3.57253479958 -3.02050042152,1.63110733032,3.58011960983 -3.01251196861,1.62911403179,3.58190560341 -3.00453281403,1.63112509251,3.59350347519 -2.99255466461,1.63013744354,3.60108780861 -2.97957801819,1.62915027142,3.6086499691 -2.97759819031,1.63416051865,3.62823390961 -2.96362113953,1.63317334652,3.63381123543 -2.95064282417,1.63218545914,3.63941025734 -2.94865298271,1.63419079781,3.6482000351 -2.93267679214,1.63120412827,3.65176773071 -2.92269897461,1.63221633434,3.66234207153 -2.92071890831,1.63722646236,3.68193387985 -2.90374207497,1.63423967361,3.68351411819 -2.88876581192,1.63225293159,3.68808436394 -2.89177465439,1.63725709915,3.70288276672 -2.87879753113,1.63626980782,3.70946240425 -2.86482048035,1.63428258896,3.71503686905 -2.85584259033,1.63629448414,3.72661852837 -2.84486413002,1.63630640507,3.73520803452 -2.83588624001,1.6373180151,3.74679040909 -2.82490944862,1.63833093643,3.75734567642 -2.81792116165,1.637337327,3.76013231277 -2.80694246292,1.6373488903,3.7677397728 -2.79796409607,1.63936054707,3.77932405472 -2.77998971939,1.63537502289,3.78087306023 -2.7700111866,1.63638663292,3.7904689312 -2.76803159714,1.64239704609,3.81204605103 -2.75105524063,1.63941025734,3.81263399124 -2.74406695366,1.63841688633,3.81541991234 -2.74008750916,1.6434276104,3.83400511742 -2.72411155701,1.64044094086,3.83658099174 -2.71713352203,1.64445257187,3.8521490097 -2.70915484428,1.64646399021,3.86474514008 -2.68918013573,1.6414784193,3.86230874062 -2.68319153786,1.64148461819,3.86610102654 -2.68221187592,1.64849483967,3.88968205452 -2.66023612022,1.64150893688,3.88227796555 -2.64925909042,1.64252114296,3.89185380936 -2.63728165627,1.64253354073,3.89943861961 -2.62430500984,1.6415463686,3.90601587296 -2.60932970047,1.63955974579,3.91057753563 -2.61833715439,1.64956283569,3.93637466431 -2.60136055946,1.64657604694,3.93596982956 -2.59638214111,1.65158724785,3.95454835892 -2.58940386772,1.65459859371,3.97012901306 -2.56543016434,1.64761376381,3.9606962204 -2.5554523468,1.64862573147,3.97128367424 -2.56145977974,1.65662908554,3.99210047722 -2.54148554802,1.65164351463,3.98866677284 -2.53550720215,1.65565478802,4.00624465942 -2.52752876282,1.65866625309,4.01983737946 -2.50855469704,1.6546806097,4.01839447021 -2.49957609177,1.65669214725,4.02999448776 -2.49559760094,1.66270315647,4.05156612396 -2.48161172867,1.65671133995,4.04334783554 -2.47163295746,1.65872275829,4.0529551506 -2.46765422821,1.66473388672,4.0745306015 -2.44867920876,1.65974760056,4.07111358643 -2.44370126724,1.66575908661,4.09168338776 -2.44771957397,1.67776787281,4.12528467178 -2.43574357033,1.67878079414,4.13485002518 -2.44075226784,1.68678486347,4.15764093399 -2.44277095795,1.69779407978,4.1882481575 -2.43479299545,1.70080566406,4.20383024216 -2.42681598663,1.70581758022,4.22040081024 -2.43083524704,1.71882688999,4.25698423386 -2.41685891151,1.71783995628,4.26256656647 -2.41387891769,1.72485017776,4.28616809845 -2.42488574982,1.7378526926,4.31997108459 -2.40791034698,1.73586630821,4.32055330276 -2.41192984581,1.74887573719,4.3591299057 -2.40995073318,1.75788617134,4.3867149353 -2.40197300911,1.7628980875,4.40429162979 -2.38199853897,1.75791227818,4.3998708725 -2.37601017952,1.75791847706,4.40466356277 -2.35503649712,1.75293314457,4.39922904968 -2.33806109428,1.74994671345,4.39981079102 -2.3270843029,1.75195896626,4.4113945961 -2.30910897255,1.74797272682,4.40997600555 -2.28913497925,1.74298715591,4.40554618835 -2.27415847778,1.74199986458,4.40814638138 -2.2611720562,1.73700761795,4.39993238449 -2.25219464302,1.74101960659,4.41551446915 -2.24621653557,1.74703097343,4.4370970726 -2.22424340248,1.74104595184,4.42866230011 -2.21426606178,1.74305796623,4.44224786758 -2.19928956032,1.7420706749,4.4448466301 -2.1903026104,1.74107789993,4.444627285 -2.17432689667,1.73809111118,4.44621276855 -2.16335129738,1.74110400677,4.45977592468 -2.14937448502,1.74111652374,4.46437358856 -2.13639807701,1.74112915993,4.47196054459 -2.12242245674,1.74114227295,4.47853469849 -2.10744738579,1.7411557436,4.48310756683 -2.09945940971,1.74016237259,4.48389959335 -2.08848261833,1.74217450619,4.49548912048 -2.075507164,1.74318766594,4.50505447388 -2.05653238297,1.73820149899,4.49964237213 -2.04155683517,1.73821461201,4.50322532654 -2.03157997131,1.74122679234,4.51780843735 -2.01960420609,1.7432397604,4.52937746048 -2.00961685181,1.74124670029,4.52517366409 -1.99564087391,1.74125957489,4.53075933456 -1.9826644659,1.74127221107,4.5383477211 -1.96768951416,1.74128556252,4.54292011261 -1.95471417904,1.74229860306,4.55248785019 -1.94173741341,1.74331104755,4.55908823013 -1.92676234245,1.74232435226,4.56366014481 -1.91777479649,1.74033117294,4.56145572662 -1.90279948711,1.73934447765,4.56503772736 -1.88982367516,1.7413572073,4.57361698151 -1.87384927273,1.73937106133,4.57618379593 -1.85987341404,1.73938393593,4.5817694664 -1.84689760208,1.74139666557,4.59034967422 -1.83990871906,1.74040257931,4.59116315842 -1.82293486595,1.73841667175,4.59172344208 -1.8069601059,1.73643028736,4.59329891205 -1.79798281193,1.7414419651,4.61089134216 -1.78300750256,1.74145519733,4.61447238922 -1.7700316906,1.74246788025,4.62305498123 -1.75205767155,1.73848199844,4.61962747574 -1.74506926537,1.73848819733,4.6214299202 -1.73009419441,1.73850142956,4.62501001358 -1.71511912346,1.73751461506,4.62858915329 -1.70014345646,1.73652768135,4.63117790222 -1.68416810036,1.73454070091,4.63076877594 -1.67119324207,1.7365540266,4.64133358002 -1.65421843529,1.73356759548,4.63891649246 -1.65122914314,1.73857295513,4.651720047 -1.63725376129,1.73858606815,4.65829753876 -1.61927938461,1.73459970951,4.65288066864 -1.60330462456,1.73361325264,4.65346002579 -1.58732950687,1.73162651062,4.65304756165 -1.57235515118,1.73163998127,4.65761566162 -1.56536722183,1.73164641857,4.66040849686 -1.5503923893,1.7316596508,4.66398525238 -1.53641736507,1.73167276382,4.67056274414 -1.52544045448,1.73568475246,4.68415927887 -1.50946581364,1.73369824886,4.68473625183 -1.49449062347,1.73371136189,4.6873216629 -1.47851610184,1.73172485828,4.68789768219 -1.46952903271,1.72973167896,4.68468856812 -1.45855236053,1.73374390602,4.69927978516 -1.43857944012,1.72775828838,4.68784713745 -1.42660284042,1.73077046871,4.6984462738 -1.41162848473,1.73078393936,4.70301485062 -1.39765298367,1.73179686069,4.70860242844 -1.38667619228,1.73580884933,4.72319889069 -1.37768995762,1.73381614685,4.72197151184 -1.36271524429,1.73382937908,4.72554922104 -1.34774017334,1.7338424921,4.72813367844 -1.3287665844,1.72785651684,4.71771001816 -1.31379115582,1.72686958313,4.71930074692 -1.2988165617,1.72688281536,4.72287607193 -1.2918292284,1.72788929939,4.72666311264 -1.27985298634,1.73190176487,4.7392539978 -1.26287841797,1.7279150486,4.73384141922 -1.24790382385,1.72792840004,4.73741769791 -1.23692762852,1.73394072056,4.75500297546 -1.2199524641,1.72895371914,4.74760246277 -1.20297944546,1.72696793079,4.74615955353 -1.19999039173,1.7339733839,4.76395988464 -1.17901730537,1.72398781776,4.74353694916 -1.1650415659,1.72500026226,4.74813270569 -1.15506482124,1.73201227188,4.76972484589 -1.13309323788,1.722027421,4.74728155136 -1.12111747265,1.727039814,4.76186752319 -1.10914051533,1.7300516367,4.77347421646 -1.09815490246,1.72505927086,4.76224946976 -1.08417999744,1.72707235813,4.76982784271 -1.07220423222,1.73208487034,4.78541231155 -1.05323112011,1.72509884834,4.7719836235 -1.03925538063,1.72611141205,4.77658128738 -1.02527999878,1.72712433338,4.78316688538 -1.0083065033,1.72413814068,4.77873563766 -1.00031924248,1.72414469719,4.77752733231 -0.98634403944,1.7251573801,4.78411388397 -0.968370437622,1.72017121315,4.77269172668 -0.955394387245,1.72218358517,4.78228902817 -0.942418813705,1.72619616985,4.79387664795 -0.924445033073,1.72020971775,4.78145647049 -0.916458129883,1.72021651268,4.78124141693 -0.904481947422,1.72422873974,4.79683685303 -0.88850736618,1.72224199772,4.79342269897 -0.871533989906,1.72025573254,4.78798961639 -0.85855782032,1.72226798534,4.79759120941 -0.840584218502,1.71628177166,4.78416824341 -0.828608453274,1.72229409218,4.802754879 -0.820622384548,1.72330117226,4.80552577972 -0.803647518158,1.71731436253,4.79312181473 -0.78967243433,1.72032701969,4.80070734024 -0.775697290897,1.72233986855,4.8082947731 -0.758723318577,1.71735334396,4.79887390137 -0.745747983456,1.72236585617,4.81345891953 -0.736761152744,1.71937263012,4.80524873734 -0.720786988735,1.71738600731,4.80182790756 -0.705811858177,1.71639871597,4.80142116547 -0.692836523056,1.72141122818,4.81700563431 -0.673864305019,1.71342563629,4.79756355286 -0.657889902592,1.71043872833,4.79214763641 -0.645913422108,1.71745073795,4.8107509613 -0.635927796364,1.7124581337,4.79852247238 -0.622952103615,1.7174705267,4.81311559677 -0.607977032661,1.71648323536,4.812707901 -0.591003417969,1.71149682999,4.80128240585 -0.577027916908,1.713509202,4.80787754059 -0.564053118229,1.72152197361,4.82945346832 -0.547078847885,1.71453523636,4.81304073334 -0.53809273243,1.71154236794,4.80581712723 -0.526115834713,1.71855401993,4.82542991638 -0.509142816067,1.71456778049,4.81599330902 -0.493168920279,1.71258115768,4.81156778336 -0.478194147348,1.71259403229,4.81215524673 -0.464218080044,1.71260619164,4.81576251984 -0.448244422674,1.71161949635,4.81233358383 -0.441256254911,1.71162545681,4.81313943863 -0.427281677723,1.71763837337,4.82871770859 -0.411307066679,1.71265137196,4.81730699539 -0.396332889795,1.71466434002,4.82288312912 -0.381357967854,1.71367704868,4.82247304916 -0.365384012461,1.71069025993,4.81505060196 -0.359395742416,1.71669614315,4.83085393906 -0.342422574759,1.71070981026,4.81442070007 -0.327447682619,1.70972251892,4.81301164627 -0.312473654747,1.71273565292,4.82158470154 -0.296499460936,1.7077486515,4.80916690826 -0.282524555922,1.71476137638,4.82775211334 -0.268548727036,1.71777355671,4.83635520935 -0.260561734438,1.71578001976,4.83114385605 -0.244587495923,1.70979309082,4.81572771072 -0.229612782598,1.70980584621,4.81631469727 -0.213639616966,1.70881927013,4.81487703323 -0.19966340065,1.71083128452,4.81848859787 -0.184688776731,1.71084403992,4.8210735321 -0.176701962948,1.70885062218,4.81585931778 -0.16172747314,1.71086347103,4.82144212723 -0.14675270021,1.71087610722,4.8210310936 -0.130779057741,1.70588934422,4.80660295486 -0.115804553032,1.70790219307,4.81218624115 -0.100830003619,1.70991504192,4.81777095795 -0.0858551934361,1.70892751217,4.81536054611 -0.0788670703769,1.71093344688,4.81916618347 -0.0628938600421,1.70794689655,4.81173038483 -0.0479190982878,1.70695960522,4.80931901932 -0.032944381237,1.7069722414,4.80890655518 -0.0179697293788,1.71198487282,4.8214931488 -0.00299494178034,1.70599746704,4.80608272552 --0.00898450147361,1.71000778675,4.68274641037 --0.0229602884501,1.70401978493,4.66734933853 --0.0379342362285,1.69903278351,4.65392208099 --0.0459207072854,1.70703959465,4.67570114136 --0.0608952268958,1.71505224705,4.69528484344 --0.0748708844185,1.71006441116,4.6818857193 --0.0888462737203,1.70307648182,4.66248083115 --0.10382078588,1.70808923244,4.67506456375 --0.118794731796,1.7061021328,4.6686372757 --0.133768871427,1.7061150074,4.6682138443 --0.140757322311,1.71112072468,4.68002653122 --0.154732435942,1.70413303375,4.6626162529 --0.169706657529,1.70514583588,4.66419506073 --0.184681147337,1.70815849304,4.66977834702 --0.199655756354,1.711171031,4.67636394501 --0.213630571961,1.70418345928,4.65894794464 --0.228604644537,1.70419633389,4.65752315521 --0.235592439771,1.70420241356,4.65532302856 --0.250566482544,1.70421516895,4.6538977623 --0.265542119741,1.71122717857,4.67150354385 --0.279516458511,1.70423984528,4.6520781517 --0.293492078781,1.70325183868,4.64867830276 --0.30946546793,1.70726501942,4.65824556351 --0.322441548109,1.7022768259,4.64184856415 --0.331427544355,1.70728373528,4.65662479401 --0.34440267086,1.69929587841,4.63220930099 --0.359377920628,1.70330810547,4.64180755615 --0.373352915049,1.70032048225,4.63339519501 --0.388327538967,1.70233285427,4.63698101044 --0.404301762581,1.70834553242,4.6505651474 --0.411288887262,1.70635187626,4.64335155487 --0.42626324296,1.70736443996,4.64393234253 --0.44023886323,1.70637643337,4.64053153992 --0.456212252378,1.70938944817,4.64609909058 --0.470187991858,1.70940136909,4.64370107651 --0.485161572695,1.70741426945,4.63826656342 --0.500136196613,1.70942664146,4.63985204697 --0.507124423981,1.71043252945,4.64065980911 --0.521098732948,1.70644497871,4.62923336029 --0.53607404232,1.70945703983,4.63483285904 --0.549049317837,1.70446908474,4.61942005157 --0.563023746014,1.70148146152,4.60999679565 --0.578998327255,1.70649397373,4.6205868721 --0.595972418785,1.71350669861,4.63717222214 --0.601959586143,1.70851278305,4.62295436859 --0.616934776306,1.71052491665,4.62655115128 --0.632908880711,1.71453750134,4.6331319809 --0.645884275436,1.71054959297,4.61972045898 --0.657860398293,1.7045609951,4.60231876373 --0.673834562302,1.70757365227,4.60890054703 --0.688809037209,1.70858597755,4.60848283768 --0.695796966553,1.70859181881,4.60728406906 --0.710771024227,1.70860433578,4.60485839844 --0.723746776581,1.70561623573,4.59445333481 --0.737721145153,1.70362842083,4.58602809906 --0.754695475101,1.7106410265,4.59961843491 --0.769670546055,1.71165311337,4.60121250153 --0.775657773018,1.70765924454,4.58999490738 --0.791632354259,1.7116714716,4.59658432007 --0.804608404636,1.70968306065,4.58818626404 --0.82258105278,1.71569633484,4.59974718094 --0.836556434631,1.71470820904,4.5953412056 --0.851531386375,1.71572029591,4.59593296051 --0.86550706625,1.71573197842,4.5925321579 --0.874493539333,1.71873855591,4.59831571579 --0.891467690468,1.72375106812,4.60790205002 --0.903442978859,1.7187628746,4.59048271179 --0.921416461468,1.72477567196,4.60306024551 --0.934393048286,1.72378695011,4.59667205811 --0.948367714882,1.721799016,4.58925056458 --0.964342176914,1.72481131554,4.59283590317 --0.973329544067,1.72881746292,4.60063648224 --0.983304917812,1.71882915497,4.57320785522 --1.00227832794,1.72684192657,4.5897898674 --1.01425421238,1.72285342216,4.57538032532 --1.03122925758,1.72886550426,4.58598423004 --1.04920291901,1.7348780632,4.59656429291 --1.05019187927,1.72288322449,4.5663523674 --1.06916511059,1.72989606857,4.58093070984 --1.08713889122,1.73590862751,4.5915145874 --1.09611642361,1.72791934013,4.56711816788 --1.1160889864,1.73593246937,4.58368873596 --1.13406312466,1.7419449091,4.59427785873 --1.14104115963,1.7309551239,4.56288385391 --1.15202689171,1.73596203327,4.57366228104 --1.17000150681,1.7429741621,4.58526134491 --1.1809772253,1.73698556423,4.56684350967 --1.19895172119,1.74299776554,4.57743883133 --1.21092760563,1.73900926113,4.56402778625 --1.2259016037,1.73902153969,4.55959892273 --1.24087643623,1.74003338814,4.5571846962 --1.24886345863,1.74003958702,4.55697154999 --1.26084053516,1.73805046082,4.54758644104 --1.27481555939,1.73706221581,4.5411696434 --1.29278898239,1.74207496643,4.54774332047 --1.30976378918,1.74608683586,4.55333852768 --1.3207398653,1.7410980463,4.53692531586 --1.34071266651,1.7481110096,4.54949712753 --1.34670102596,1.7471165657,4.54430007935 --1.36167573929,1.74812841415,4.54088163376 --1.37665069103,1.74814009666,4.53847169876 --1.38862669468,1.74515140057,4.52606010437 --1.40660119057,1.75116348267,4.53365182877 --1.42357599735,1.75417542458,4.53824806213 --1.42456531525,1.74618029594,4.51604175568 --1.44053924084,1.74819254875,4.51461410522 --1.46451163292,1.76020562649,4.5391960144 --1.47548782825,1.75621676445,4.52378463745 --1.49246251583,1.75922870636,4.52737665176 --1.50843679905,1.76124072075,4.52595376968 --1.52341187,1.76125240326,4.52254056931 --1.52740061283,1.75825762749,4.51134157181 --1.54437565804,1.76126933098,4.51493740082 --1.55635142326,1.75928068161,4.50252199173 --1.57432627678,1.76429247856,4.50912046432 --1.59130048752,1.76630449295,4.51070165634 --1.60227644444,1.76231563091,4.49528408051 --1.61725211143,1.76432704926,4.49288129807 --1.62623846531,1.76533341408,4.49365997314 --1.64221358299,1.76734507084,4.4932513237 --1.65119063854,1.76135551929,4.4738445282 --1.67016434669,1.76636779308,4.48042535782 --1.68313992023,1.76537919044,4.47100925446 --1.69711589813,1.76539039612,4.46560525894 --1.70110476017,1.76239538193,4.45540714264 --1.72207808495,1.76940786839,4.46698999405 --1.73405468464,1.76741874218,4.45658922195 --1.75402784348,1.77343118191,4.4641623497 --1.76300466061,1.76744186878,4.44474744797 --1.77698111534,1.76845264435,4.44035434723 --1.79895401001,1.77646529675,4.45293140411 --1.79594492912,1.7664693594,4.42573451996 --1.81791830063,1.77448177338,4.43932390213 --1.8378919363,1.78049397469,4.44690608978 --1.84586846828,1.77350461483,4.4244799614 --1.86084461212,1.77451562881,4.42208480835 --1.87781941891,1.77752733231,4.42267227173 --1.89579391479,1.78153908253,4.42525720596 --1.90078270435,1.78054428101,4.41805934906 --1.9227553606,1.78755688667,4.42863178253 --1.93073320389,1.78156685829,4.40923213959 --1.94270980358,1.78057765961,4.39882850647 --1.96368324757,1.78658986092,4.40740871429 --1.97765898705,1.78660094738,4.40100002289 --1.98264718056,1.78460633755,4.3927898407 --1.99462389946,1.78261697292,4.38238573074 --2.01159930229,1.78562831879,4.38298082352 --2.02757358551,1.78763997555,4.37955665588 --2.04654717445,1.79165196419,4.38212823868 --2.05752491951,1.78966224194,4.37073659897 --2.06350302696,1.78267204762,4.34732913971 --2.07648825645,1.78767883778,4.35510492325 --2.08846497536,1.78568947315,4.34469890594 --2.10943937302,1.79270112514,4.35329580307 --2.12641453743,1.79571247101,4.35288667679 --2.13239169121,1.78872263432,4.3284611702 --2.14736819267,1.78973340988,4.32506513596 --2.16434335709,1.79274463654,4.32465744019 --2.16933083534,1.79075038433,4.31543016434 --2.18730640411,1.79476130009,4.31803607941 --2.20528054237,1.79777312279,4.31760692596 --2.21725845337,1.79678308964,4.3092250824 --2.22523546219,1.79179334641,4.28980398178 --2.24720907211,1.79880535603,4.298391819 --2.25319695473,1.79781079292,4.29217624664 --2.26717329025,1.79882156849,4.28577184677 --2.28314805031,1.79983282089,4.28134489059 --2.2941262722,1.79884278774,4.27096128464 --2.30610227585,1.79685342312,4.2595410347 --2.32707643509,1.80286514759,4.26512479782 --2.34005236626,1.80187594891,4.25570678711 --2.3430416584,1.7988806963,4.24550914764 --2.36201620102,1.80389213562,4.24709224701 --2.37499332428,1.80390238762,4.23969984055 --2.38796949387,1.80291295052,4.23028182983 --2.40194606781,1.80392348766,4.22387933731 --2.41492199898,1.80293416977,4.2144613266 --2.43589615822,1.80894589424,4.21904277802 --2.43888545036,1.80595064163,4.20884227753 --2.45086216927,1.8049608469,4.19843435287 --2.46583771706,1.80597186089,4.19200992584 --2.4808139801,1.80698227882,4.18761301041 --2.49778962135,1.80999326706,4.18519830704 --2.51476550102,1.81300401688,4.18379831314 --2.52475237846,1.81500983238,4.18458509445 --2.54072809219,1.81802070141,4.18016862869 --2.54970622063,1.81503021717,4.16577482224 --2.56268191338,1.81404101849,4.15534448624 --2.57965826988,1.81705164909,4.1539478302 --2.5916352272,1.81606173515,4.14354038239 --2.60861086845,1.81907248497,4.14113235474 --2.61659836769,1.82007813454,4.13791179657 --2.63157463074,1.82108855247,4.13250732422 --2.64555191994,1.82209861279,4.12611198425 --2.65752744675,1.82110929489,4.113676548 --2.67750287056,1.82612013817,4.11627674103 --2.69947719574,1.83213150501,4.12086391449 --2.71445417404,1.83414173126,4.11546373367 --2.72344136238,1.83514714241,4.11425304413 --2.73541879654,1.83415722847,4.10384750366 --2.74639582634,1.83316707611,4.09143543243 --2.77136898041,1.84117901325,4.09900856018 --2.78334641457,1.8401889801,4.08860397339 --2.79532361031,1.83919882774,4.07819986343 --2.79931282997,1.83820354939,4.06999635696 --2.80929064751,1.83621323109,4.0565905571 --2.81926774979,1.83422327042,4.04216814041 --2.84924077988,1.84523510933,4.05776309967 --2.86121749878,1.84524524212,4.04634380341 --2.88219285011,1.85025596619,4.04894304276 --2.89317035675,1.84926569462,4.03653097153 --2.89316082001,1.84526979923,4.02333593369 --2.91213679314,1.84928023815,4.02293491364 --2.88612294197,1.82328617573,3.95851325989 --2.9500875473,1.85730159283,4.02010774612 --2.95706486702,1.85331130028,4.00067329407 --2.96604418755,1.85032045841,3.98728704453 --2.9750225544,1.84832966328,3.97288441658 --2.99000811577,1.85333573818,3.97866463661 --2.99598670006,1.84934508801,3.95924711227 --3.01496338844,1.8533551693,3.95885396004 --3.02194190025,1.85036444664,3.94144463539 --3.04391646385,1.85537552834,3.94302296638 --3.04689717293,1.85038387775,3.92163205147 --3.05788421631,1.85338926315,3.92242217064 --3.06486272812,1.84939849377,3.90501046181 --3.10183382034,1.86441087723,3.92558956146 --3.10481333733,1.85841953754,3.90318012238 --3.12079048157,1.8614294529,3.8977766037 --3.12776899338,1.85743868351,3.88036370277 --3.14274573326,1.85844862461,3.8729493618 --3.14573597908,1.85745275021,3.86476016045 --3.16671085358,1.86246347427,3.86433911324 --3.17568945885,1.86047267914,3.84993243217 --3.1986644268,1.86648321152,3.85252356529 --3.20264434814,1.86149179935,3.83211827278 --3.21962022781,1.86450195312,3.82669997215 --3.22959852219,1.86351120472,3.81328892708 --3.24358606339,1.86851668358,3.81809568405 --3.2515642643,1.86552584171,3.80167460442 --3.25254487991,1.85853397846,3.77827358246 --3.27851939201,1.86654472351,3.78386473656 --3.2864985466,1.86455368996,3.76845884323 --3.3014755249,1.86656332016,3.76104998589 --3.30646443367,1.86556816101,3.75383543968 --3.32444143295,1.86957776546,3.75043725967 --3.33042025566,1.86558675766,3.73201751709 --3.35339570045,1.87159705162,3.73360991478 --3.35437607765,1.86560535431,3.71019983292 --3.371352911,1.86861515045,3.7047894001 --3.39932703972,1.87762582302,3.71137690544 --3.39731907845,1.87362933159,3.69819235802 --3.41029620171,1.87463879585,3.68777489662 --3.43027257919,1.87864875793,3.68536400795 --3.44425058365,1.87965786457,3.67696380615 --3.45522856712,1.87966704369,3.66455078125 --3.46920585632,1.88067650795,3.65513396263 --3.48018407822,1.87968564034,3.64272093773 --3.47917532921,1.87668919563,3.63052988052 --3.50115156174,1.88269925117,3.63012313843 --3.51312947273,1.88270843029,3.61870908737 --3.5241086483,1.88271713257,3.60731387138 --3.54008483887,1.88472688198,3.59888005257 --3.55006408691,1.88373553753,3.58648586273 --3.55404424667,1.87974381447,3.56707549095 --3.56903076172,1.88474929333,3.56985664368 --3.57001233101,1.87875711918,3.54846405983 --3.58299016953,1.87976622581,3.53804969788 --3.60496616364,1.88577604294,3.53663611412 --3.60594677925,1.87978410721,3.51422190666 --3.62192511559,1.88279306889,3.50782728195 --3.64890933037,1.89379942417,3.52261829376 --3.6358935833,1.88080608845,3.48721528053 --3.64787197113,1.88081502914,3.47580194473 --3.67984652519,1.89282524586,3.4844019413 --3.67382907867,1.88283252716,3.45599603653 --3.69880437851,1.89084255695,3.45657634735 --3.71278262138,1.89185154438,3.44716763496 --3.70877385139,1.88685512543,3.43196105957 --3.72875094414,1.89186441898,3.42855906487 --3.74872756004,1.89587390423,3.42414021492 --3.75770759583,1.89588212967,3.41074514389 --3.75768876076,1.88988983631,3.38833665848 --3.78666424751,1.89889967442,3.39293503761 --3.79264378548,1.89590799809,3.37551641464 --3.7996327877,1.89691257477,3.3703045845 --3.81561112404,1.89992117882,3.36290359497 --3.82559013367,1.89892983437,3.34949207306 --3.83356952667,1.89793813229,3.3340754509 --3.84954810143,1.90094685555,3.32667660713 --3.85752749443,1.89895522594,3.31125998497 --3.8695063591,1.89996361732,3.29985260963 --3.87749624252,1.9019677639,3.29666352272 --3.88447570801,1.89897608757,3.28024363518 --3.90045452118,1.90198457241,3.27284789085 --3.92143106461,1.90699386597,3.26842927933 --3.92341208458,1.90300166607,3.24801373482 --3.92639374733,1.89900922775,3.22961878777 --3.95137906075,1.91001474857,3.23940753937 --3.94936084747,1.90302217007,3.21599674225 --3.97133779526,1.90903127193,3.21258640289 --3.9813182354,1.90903913975,3.20019507408 --3.98929786682,1.90704739094,3.18477702141 --4.00427675247,1.91005575657,3.17536473274 --4.00825691223,1.90706372261,3.15695095062 --4.02524423599,1.91206860542,3.15974283218 --4.02522659302,1.90707576275,3.13935184479 --4.03420639038,1.90708386898,3.12493658066 --4.05718326569,1.91309273243,3.12152075768 --4.06616401672,1.91210055351,3.10812616348 --4.08514165878,1.91710913181,3.10171627998 --4.0931224823,1.91611683369,3.08731770515 --4.08911418915,1.91212046146,3.07310128212 --4.09509468079,1.91012811661,3.05669236183 --4.11407232285,1.91413664818,3.05028510094 --4.1340508461,1.91914498806,3.04488444328 --4.1410317421,1.91815257072,3.02948069572 --4.1420135498,1.91316008568,3.00906562805 --4.16199207306,1.91816830635,3.00366806984 --4.16598129272,1.91817247868,2.99544811249 --4.1749625206,1.91817998886,2.98205399513 --4.18694114685,1.91818809509,2.96963596344 --4.20092105865,1.92019617558,2.95922970772 --4.20290231705,1.91720354557,2.93981599808 --4.21388292313,1.91821122169,2.92741298676 --4.23286056519,1.92221963406,2.91999673843 --4.23285198212,1.92022323608,2.90979337692 --4.24683189392,1.92223095894,2.89938926697 --4.26381063461,1.92623889446,2.8909842968 --4.27479124069,1.92624652386,2.87858390808 --4.27677249908,1.92325389385,2.85916662216 --4.30175018311,1.93026232719,2.85575532913 --4.31273889542,1.9332665205,2.85254049301 --4.32571983337,1.93527388573,2.84215545654 --4.33970022202,1.93728137016,2.83175754547 --4.35667848587,1.94128930569,2.8223400116 --4.37265777588,1.9442974329,2.81191706657 --4.38663816452,1.94630479813,2.80152225494 --4.392619133,1.94431209564,2.78511214256 --4.39261054993,1.94231569767,2.77490592003 --4.41258907318,1.94732356071,2.76749420166 --4.44656562805,1.95933198929,2.76908516884 --4.44454860687,1.95433878899,2.7476785183 --4.4445309639,1.95034587383,2.72726416588 --4.46450996399,1.95535361767,2.71985816956 --4.46649217606,1.95236039162,2.70145797729 --4.47748184204,1.9553643465,2.69825339317 --4.46746587753,1.94637084007,2.67183971405 --4.4844455719,1.95037841797,2.66243314743 --4.49442672729,1.95038545132,2.64903306961 --4.49340963364,1.94639217854,2.62862563133 --4.49939107895,1.94439935684,2.61221241951 --4.50737285614,1.94440627098,2.59781575203 --4.51336336136,1.94540989399,2.59161353111 --4.51234579086,1.94141674042,2.5712018013 --4.51232910156,1.93742346764,2.55179738998 --4.51331090927,1.93443048,2.53237891197 --4.52129268646,1.93443727493,2.51798009872 --4.52927398682,1.9344445467,2.50255966187 --4.53625583649,1.93345141411,2.48715162277 --4.52224969864,1.92545437813,2.46995544434 --4.52623128891,1.92346131802,2.45253825188 --4.54421138763,1.92746865749,2.44312548637 --4.54419374466,1.92347538471,2.42371273041 --4.54317808151,1.92048168182,2.40533185005 --4.54316091537,1.91648852825,2.38591647148 --4.54814291,1.91549527645,2.36950588226 --4.55713224411,1.91749918461,2.36428952217 --4.5601143837,1.91550576687,2.34688019753 --4.55909776688,1.91151249409,2.32747244835 --4.57307958603,1.91451907158,2.31708836555 --4.57106256485,1.9105257988,2.29666829109 --4.58204364777,1.91153275967,2.28325271606 --4.57803583145,1.90753602982,2.2720541954 --4.57701921463,1.90454256535,2.25264143944 --4.59299945831,1.90754950047,2.24223613739 --4.58198451996,1.89955592155,2.21782279015 --4.59396600723,1.90256273746,2.20541739464 --4.59694814682,1.8995693922,2.18800139427 --4.59893083572,1.89757597446,2.17059516907 --4.59792327881,1.89557898045,2.16140270233 --4.60790538788,1.89658558369,2.14799761772 --4.61388683319,1.89659261703,2.13156867027 --4.62286949158,1.89659893513,2.11817550659 --4.61585378647,1.89160525799,2.09677267075 --4.62183523178,1.8906121254,2.08034229279 --4.62881803513,1.89061844349,2.0659468174 --4.63380908966,1.89162194729,2.05873298645 --4.62879276276,1.88662827015,2.03832674026 --4.63077545166,1.88363480568,2.02091360092 --4.63175916672,1.88164114952,2.00351023674 --4.64174127579,1.88364768028,1.99010503292 --4.64172554016,1.88065373898,1.97271096706 --4.65170717239,1.88166022301,1.95930624008 --4.65569782257,1.88166379929,1.9510794878 --4.65468263626,1.87866973877,1.9336938858 --4.66366434097,1.87967634201,1.91927611828 --4.66964673996,1.87968277931,1.90386557579 --4.68262863159,1.88268911839,1.89145565033 --4.68761205673,1.88169538975,1.87605559826 --4.69359493256,1.88170170784,1.86064529419 --4.69858503342,1.88270485401,1.85343241692 --4.70556783676,1.88271141052,1.83801269531 --4.70755147934,1.88071739674,1.82161736488 --4.71753406525,1.88272356987,1.80821597576 --4.72351694107,1.88272976875,1.7928057909 --4.73649930954,1.88573598862,1.78040099144 --4.74848985672,1.88873910904,1.77619540691 --4.74047422409,1.8837454319,1.754773736 --4.75145769119,1.88575124741,1.74238908291 --4.75544071198,1.88475751877,1.72597396374 --4.7664232254,1.88676357269,1.71256685257 --4.77940607071,1.88976943493,1.70016646385 --4.77138996124,1.88377583027,1.67873907089 --4.78638029099,1.88877880573,1.67553555965 --4.79236364365,1.8887847662,1.66012692451 --4.79834699631,1.88879084587,1.64471828938 --4.79533100128,1.88579678535,1.62631523609 --4.81831264496,1.8928027153,1.61690497398 --4.80629825592,1.88580858707,1.59550511837 --4.82328033447,1.89081442356,1.5840998888 --4.84027051926,1.89681732655,1.58088743687 --4.83525466919,1.89182341099,1.56147527695 --4.8532371521,1.89682912827,1.55006575584 --4.87222003937,1.90283453465,1.53967416286 --4.87620401382,1.90284049511,1.52326071262 --4.87418794632,1.89984643459,1.50484657288 --4.88617086411,1.90285205841,1.49144172668 --4.88516330719,1.90085494518,1.48223412037 --4.89414644241,1.90286076069,1.46782946587 --4.91012954712,1.90686619282,1.45542037487 --4.90811347961,1.9038721323,1.43700432777 --4.92309713364,1.90787756443,1.42460489273 --4.92108201981,1.90488314629,1.40721201897 --4.90106773376,1.89488971233,1.3827804327 --4.90905952454,1.89689230919,1.37657737732 --4.91904354095,1.89989757538,1.36319112778 --4.91702795029,1.89690351486,1.34477043152 --4.92301225662,1.89690899849,1.32936489582 --4.94999408722,1.90591394901,1.31995892525 --4.92898082733,1.89592027664,1.29654717445 --4.942964077,1.89992570877,1.28313589096 --4.96495437622,1.90792775154,1.28093874454 --4.95293998718,1.90093362331,1.26053488255 --4.96092367172,1.9029392004,1.24511754513 --4.9689078331,1.90394461155,1.22970104218 --4.98089170456,1.90694963932,1.2163079977 --4.97587776184,1.90295541286,1.19790267944 --4.99286031723,1.9079605341,1.18447935581 --4.98785305023,1.90496361256,1.17426753044 --4.98983812332,1.90496897697,1.15786528587 --5.00182151794,1.90797412395,1.14345097542 --5.00580692291,1.90797924995,1.12806141376 --5.007791996,1.90698444843,1.11165952682 --5.03477525711,1.91598880291,1.10125756264 --5.02476024628,1.91099488735,1.08082818985 --5.02475309372,1.90999758244,1.07263314724 --5.0377368927,1.913002491,1.05821800232 --5.02372264862,1.90600848198,1.03780758381 --5.04570579529,1.91301310062,1.02539265156 --5.06169080734,1.91901755333,1.01198840141 --5.04767656326,1.91102361679,0.991574943066 --5.05066919327,1.9120259285,0.984387397766 --5.06165409088,1.91503071785,0.969987154007 --5.05263948441,1.91003656387,0.950567960739 --5.06362438202,1.91304123402,0.93616849184 --5.08560752869,1.92004561424,0.922740161419 --5.06859445572,1.9120516777,0.902333557606 --5.07157945633,1.9120568037,0.885925650597 --5.09857034683,1.92205798626,0.882722973824 --5.0785574913,1.9130641222,0.862326622009 --5.09454202652,1.91806864738,0.847908079624 --5.10652732849,1.92107307911,0.833509922028 --5.10651254654,1.92007827759,0.816092550755 --5.10549783707,1.91908347607,0.798678994179 --5.12148332596,1.9240874052,0.785290420055 --5.10647678375,1.91709089279,0.774084091187 --5.12446117401,1.92309510708,0.759663820267 --5.12344646454,1.92110025883,0.742250025272 --5.13043212891,1.92310476303,0.726852476597 --5.12541818619,1.92011034489,0.70842897892 --5.13040399551,1.92111480236,0.693039655685 --5.13638925552,1.92211949825,0.676622390747 --5.13838195801,1.92212188244,0.668417692184 --5.14936733246,1.92612624168,0.653007209301 --5.14335393906,1.92213129997,0.635609924793 --5.16433858871,1.92913496494,0.621190726757 --5.16832447052,1.93013966084,0.604783117771 --5.16531085968,1.92814481258,0.587374389172 --5.16029691696,1.9251499176,0.569971442223 --5.16729021072,1.92715167999,0.562776088715 --5.15827655792,1.92315733433,0.544359862804 --5.1752614975,1.92916107178,0.528936386108 --5.17024755478,1.92616629601,0.511531591415 --5.17023420334,1.92517089844,0.495135843754 --5.17221975327,1.92517578602,0.477709263563 --5.18121290207,1.92817747593,0.470510840416 --5.18719863892,1.92918169498,0.4540989995 --5.18518590927,1.92818641663,0.437708467245 --5.19217205048,1.93019068241,0.421294599771 --5.20215749741,1.93319475651,0.404874175787 --5.20014476776,1.93219923973,0.388483434916 --5.20213031769,1.9322040081,0.371058285236 --5.21111726761,1.93520772457,0.355667024851 --5.19911003113,1.92921113968,0.345446407795 --5.21509647369,1.93521440029,0.330040752888 --5.20908308029,1.93221950531,0.312632620335 --5.20506954193,1.93022453785,0.295219391584 --5.22505617142,1.93722724915,0.279809892178 --5.20304250717,1.92823386192,0.261404365301 --5.21302938461,1.93223750591,0.244989573956 --5.22202301025,1.93523871899,0.237800911069 --5.21900987625,1.93324363232,0.220384731889 --5.22999572754,1.93724703789,0.203971236944 --5.2359828949,1.93925094604,0.187566518784 --5.22696971893,1.93525624275,0.17015825212 --5.23495674133,1.93725979328,0.153751507401 --5.24495029449,1.94126117229,0.145540952682 --5.24793720245,1.94226515293,0.129141867161 --5.24892377853,1.94226956367,0.111720584333 --5.25891113281,1.94527280331,0.0953152030706 --5.26389837265,1.94727659225,0.0789155587554 --5.26588535309,1.94828081131,0.0614943541586 --5.26687288284,1.94828486443,0.0450989715755 --5.25786590576,1.94428801537,0.0358835831285 --5.27785348892,1.95129013062,0.0194753408432 --5.2988409996,1.95929217339,0.00306942476891 --5.29582881927,1.95829641819,-0.0133217703551 --5.29081583023,1.95630121231,-0.0307372063398 --5.30180263519,1.96030426025,-0.0481587201357 --5.3097910881,1.96330738068,-0.0645533427596 --5.32678508759,1.96930754185,-0.0727528110147 --5.32377243042,1.96831190586,-0.0901677533984 --5.34076023102,1.97531414032,-0.10758433491 --5.34474849701,1.97631752491,-0.123974010348 --5.36173677444,1.98331952095,-0.141386404634 --5.34672355652,1.97732532024,-0.158801794052 --5.36371183395,1.98332726955,-0.1762111485 --5.36570596695,1.984328866,-0.184404805303 --5.35869312286,1.9813337326,-0.20181979239 --5.3586807251,1.9813375473,-0.219232797623 --5.36166906357,1.98334109783,-0.23664444685 --5.35965633392,1.98234534264,-0.254058361053 --5.35764408112,1.98134934902,-0.271472543478 --5.35963201523,1.98235297203,-0.288884103298 --5.35962629318,1.98235487938,-0.297078371048 --5.35361385345,1.98035931587,-0.314496517181 --5.34960222244,1.97836351395,-0.330889075994 --5.35059022903,1.97936725616,-0.348301678896 --5.33857727051,1.97537255287,-0.365728497505 --5.35356616974,1.98037421703,-0.383124649525 --5.34955406189,1.97937858105,-0.400542765856 --5.33054733276,1.9723829031,-0.407737642527 --5.32353496552,1.96938765049,-0.425161808729 --5.33252334595,1.97338998318,-0.442563831806 --5.33951234818,1.97639262676,-0.459967404604 --5.32949972153,1.97239792347,-0.477396994829 --5.32048749924,1.96940267086,-0.493802160025 --5.33647680283,1.97640407085,-0.512213230133 --5.33047056198,1.97440671921,-0.520418703556 --5.33145904541,1.9754101038,-0.537830710411 --5.32144641876,1.97141504288,-0.554239451885 --5.3364367485,1.97741639614,-0.57264739275 --5.32442426682,1.97342169285,-0.589061439037 --5.33041334152,1.97642421722,-0.606462001801 --5.33140182495,1.97742760181,-0.623872816563 --5.33639669418,1.97942852974,-0.633079767227 --5.33638525009,1.98043191433,-0.650492191315 --5.3243727684,1.97543716431,-0.666909217834 --5.33336257935,1.98043894768,-0.684299468994 --5.31734991074,1.97444498539,-0.700728774071 --5.32834005356,1.97944664955,-0.719136297703 --5.32233381271,1.9774492979,-0.727346479893 --5.31732225418,1.97545325756,-0.743748247623 --5.31931114197,1.97745633125,-0.76115489006 --5.31729984283,1.97745990753,-0.778572678566 --5.30228757858,1.97246563435,-0.793981552124 --5.31227731705,1.97646713257,-0.812387108803 --5.30226564407,1.97347199917,-0.828806519508 --5.30726051331,1.97547280788,-0.838008403778 --5.29924869537,1.97347736359,-0.854422271252 --5.29923772812,1.97448050976,-0.871834218502 --5.29322624207,1.97248470783,-0.888242185116 --5.30221700668,1.97748625278,-0.906646490097 --5.30020570755,1.97748982906,-0.924064397812 --5.2911939621,1.97449445724,-0.940483808517 --5.3021903038,1.97949409485,-0.950684547424 --5.28717708588,1.97449982166,-0.966103136539 --5.28516674042,1.97450304031,-0.982497394085 --5.28815603256,1.97650563717,-1.0009200573 --5.29114675522,1.9785078764,-1.01831781864 --5.28313541412,1.9765124321,-1.03473579884 --5.28612518311,1.97851467133,-1.05213272572 --5.28111934662,1.97751712799,-1.06034636497 --5.27510786057,1.97552108765,-1.07675683498 --5.27009677887,1.97552502155,-1.09418809414 --5.27608776093,1.97852683067,-1.11259436607 --5.27007675171,1.97753083706,-1.12900578976 --5.28006744385,1.98253178596,-1.14841592312 --5.27005624771,1.97953641415,-1.16382169724 --5.27005147934,1.98053765297,-1.17201352119 --5.26003932953,1.97754251957,-1.1884444952 --5.25702953339,1.97754573822,-1.20484256744 --5.24601745605,1.97455060482,-1.22025632858 --5.26301050186,1.9825501442,-1.2416741848 --5.23099517822,1.97055912018,-1.25309956074 --5.23998641968,1.97555994987,-1.27250862122 --5.23998212814,1.97656130791,-1.28069996834 --5.22997093201,1.97356593609,-1.2961114645 --5.23396158218,1.97656774521,-1.31452035904 --5.22995090485,1.97657120228,-1.33194804192 --5.19993638992,1.96557986736,-1.34235203266 --5.21592950821,1.97357916832,-1.36376535892 --5.21591997147,1.97558164597,-1.38117110729 --5.19991207123,1.96958637238,-1.38638150692 --5.19390153885,1.96859014034,-1.40279841423 --5.20189332962,1.97259104252,-1.42220473289 --5.18288040161,1.9675976038,-1.43562757969 --5.17887020111,1.96760082245,-1.45203351974 --5.17686033249,1.96760380268,-1.4694507122 --5.16584920883,1.96460855007,-1.48385226727 --5.17184591293,1.96760845184,-1.49405324459 --5.15983390808,1.96461355686,-1.50948572159 --5.16382551193,1.96761500835,-1.52788865566 --5.1468129158,1.9626210928,-1.54130709171 --5.14380311966,1.96362411976,-1.55873131752 --5.14179372787,1.9646269083,-1.57512497902 --5.12678575516,1.95963144302,-1.58034348488 --5.14678144455,1.96862900257,-1.60273182392 --5.11176490784,1.95663940907,-1.61115860939 --5.10675477982,1.95664286613,-1.62757384777 --5.10674571991,1.95764493942,-1.64497756958 --5.10173559189,1.95764839649,-1.66139256954 --5.09372472763,1.9566526413,-1.67782902718 --5.09872198105,1.95965254307,-1.68803036213 --5.08170890808,1.95365869999,-1.70043683052 --5.07169866562,1.95166325569,-1.71484184265 --5.07368946075,1.9546649456,-1.73427736759 --5.05467700958,1.94867157936,-1.74567949772 --5.05566835403,1.95167350769,-1.76409864426 --5.06166124344,1.95567393303,-1.78350186348 --5.05565547943,1.95367658138,-1.7907128334 --5.03964328766,1.94968259335,-1.80311965942 --5.04063510895,1.95168435574,-1.82153666019 --5.02962350845,1.94968914986,-1.83595347404 --5.01761198044,1.94669413567,-1.85037910938 --5.02660655975,1.95269370079,-1.8707780838 --5.00759315491,1.94670045376,-1.88219046593 --5.00258350372,1.94670367241,-1.89860785007 --5.00558042526,1.94870388508,-1.90881812572 --4.9855670929,1.9437110424,-1.92024290562 --4.98255777359,1.94371366501,-1.9366440773 --4.99155235291,1.94971299171,-1.95703732967 --4.96453666687,1.94072198868,-1.96647822857 --4.97653198242,1.94872057438,-1.98889088631 --4.96852636337,1.94572353363,-1.99407660961 --4.95751476288,1.94372832775,-2.00849986076 --4.94850444794,1.94273245335,-2.02392983437 --4.95249843597,1.94573307037,-2.04231452942 --4.93248414993,1.9407402277,-2.05375003815 --4.9264755249,1.94074356556,-2.06915426254 --4.92446660995,1.94174587727,-2.08656859398 --4.91446018219,1.93874943256,-2.09177660942 --4.90845060349,1.93875277042,-2.10820436478 --4.9044418335,1.93975543976,-2.12461400032 --4.90743541718,1.94375610352,-2.14402699471 --4.88542079926,1.93676400185,-2.15344309807 --4.88341283798,1.93776607513,-2.17085647583 --4.86840105057,1.93477189541,-2.18327879906 --4.86039495468,1.93277490139,-2.18847203255 --4.86438846588,1.93677532673,-2.20889639854 --4.85537862778,1.93577933311,-2.2233080864 --4.84736919403,1.93478310108,-2.2377102375 --4.83535814285,1.93278801441,-2.25112986565 --4.82734823227,1.93179190159,-2.26655602455 --4.81933832169,1.93079566956,-2.28095960617 --4.81933450699,1.93279623985,-2.29016709328 --4.80632352829,1.92980146408,-2.30257606506 --4.8033156395,1.93080377579,-2.31999754906 --4.78830385208,1.92780959606,-2.33140587807 --4.77829313278,1.92581403255,-2.34583187103 --4.77828598022,1.92881524563,-2.3642449379 --4.78028011322,1.93281579018,-2.38365864754 --4.75726890564,1.92382359505,-2.38185715675 --4.75025987625,1.92382705212,-2.39727592468 --4.74625110626,1.92482948303,-2.41470742226 --4.73624134064,1.92383384705,-2.42811322212 --4.72823190689,1.92283737659,-2.44251966476 --4.71822166443,1.92184185982,-2.45694899559 --4.71921539307,1.92484247684,-2.4753472805 --4.70520734787,1.92084765434,-2.47857165337 --4.70219993591,1.92184960842,-2.49496865273 --4.68518733978,1.91785621643,-2.50538754463 --4.67917823792,1.91885924339,-2.52181863785 --4.67717170715,1.92086076736,-2.53922653198 --4.67016267776,1.92086410522,-2.55464577675 --4.65815162659,1.91886901855,-2.56705546379 --4.65414714813,1.91887080669,-2.57425999641 --4.64413738251,1.91687500477,-2.58766961098 --4.63112640381,1.91488039494,-2.60009336472 --4.62711811066,1.91688251495,-2.61752319336 --4.60810470581,1.9118899107,-2.62592959404 --4.60709857941,1.91389107704,-2.64434576035 --4.59308719635,1.91189670563,-2.65576171875 --4.59008359909,1.91189813614,-2.6629550457 --4.59207820892,1.91589820385,-2.68337774277 --4.57606554031,1.91190445423,-2.69379687309 --4.56405544281,1.90990948677,-2.70621275902 --4.55404520035,1.90891373158,-2.71962690353 --4.55303907394,1.91191458702,-2.73803973198 --4.54002809525,1.90991997719,-2.7504696846 --4.52501916885,1.904925704,-2.7516810894 --4.52401256561,1.90792667866,-2.77009367943 --4.51400327682,1.90693080425,-2.78350901604 --4.49498939514,1.90193843842,-2.79192996025 --4.49798583984,1.90693771839,-2.81233382225 --4.47396993637,1.89994728565,-2.81775593758 --4.48497200012,1.90594339371,-2.83396530151 --4.48596763611,1.91094338894,-2.85336995125 --4.46395206451,1.90395212173,-2.85979032516 --4.44794034958,1.90095853806,-2.86919999123 --4.45393800735,1.90695643425,-2.89262413979 --4.42792081833,1.89896690845,-2.89603734016 --4.41491031647,1.89697217941,-2.90745329857 --4.4239115715,1.90296888351,-2.92265963554 --4.4028968811,1.89697730541,-2.92907524109 --4.39388799667,1.89698112011,-2.94350337982 --4.39688444138,1.90198004246,-2.96491861343 --4.38187265396,1.89898622036,-2.97534203529 --4.36686086655,1.89599239826,-2.98576664925 --4.36185407639,1.89799451828,-3.0011613369 --4.34784507751,1.89300024509,-3.00237846375 --4.34283781052,1.8950022459,-3.01879477501 --4.34183311462,1.89800274372,-3.03821802139 --4.31781673431,1.89101266861,-3.04162311554 --4.31381034851,1.89301431179,-3.05904555321 --4.31380653381,1.89801418781,-3.07947468758 --4.30079555511,1.89601957798,-3.08987522125 --4.28078317642,1.88802790642,-3.08710002899 --4.28578138351,1.89502561092,-3.10949778557 --4.27377080917,1.89303052425,-3.12192773819 --4.25575780869,1.88903796673,-3.12934064865 --4.25675439835,1.89403748512,-3.15077209473 --4.24174261093,1.89104366302,-3.16018462181 --4.22372913361,1.8870511055,-3.16760063171 --4.22973060608,1.89204835892,-3.18180704117 --4.20271253586,1.88305997849,-3.18221139908 --4.19670534134,1.88506221771,-3.19864010811 --4.19970321655,1.89006054401,-3.22105717659 --4.17368507385,1.88207173347,-3.22247314453 --4.17068052292,1.88507258892,-3.23987579346 --4.16367292404,1.88707518578,-3.25631809235 --4.1666727066,1.89007365704,-3.26852226257 --4.14865922928,1.88608133793,-3.27492451668 --4.14965724945,1.89108026028,-3.29634571075 --4.11863565445,1.88109397888,-3.29478669167 --4.11262893677,1.88209605217,-3.31019186974 --4.11162567139,1.88709592819,-3.32960057259 --4.1066198349,1.88909745216,-3.34702968597 --4.09761285782,1.88710129261,-3.35023379326 --4.09260702133,1.88910293579,-3.36664104462 --4.07859611511,1.8871088028,-3.37706875801 --4.0635843277,1.88511514664,-3.38649296761 --4.06858444214,1.89211177826,-3.41090202332 --4.05057144165,1.88811969757,-3.41731381416 --4.04156303406,1.88812303543,-3.43174338341 --4.03855991364,1.88912391663,-3.43995404243 --4.03255414963,1.89112591743,-3.45637464523 --4.01253890991,1.88613474369,-3.46078205109 --4.01553869247,1.89313220978,-3.48419570923 --3.99752545357,1.88814008236,-3.49061155319 --3.98551535606,1.88814485073,-3.50203061104 --3.97650766373,1.88814818859,-3.51645922661 --3.96049594879,1.88215565681,-3.51366615295 --3.95148825645,1.8831590414,-3.52809596062 --3.95248699188,1.88915717602,-3.55051660538 --3.94247889519,1.88916099072,-3.56292200089 --3.56818795204,1.89330124855,-3.99957752228 --3.56818985939,1.9002982378,-4.02400493622 --3.55117630959,1.89730584621,-4.03043365479 --3.51714801788,1.88532447815,-4.01886987686 --3.50413823128,1.88432991505,-4.0282793045 --3.49313020706,1.88433396816,-4.03968572617 --3.47611665726,1.8813419342,-4.04612016678 --3.48112249374,1.88833701611,-4.06434011459 --3.45409965515,1.87935137749,-4.05875873566 --3.43908786774,1.87735819817,-4.06617450714 --3.43108272552,1.87936019897,-4.08159303665 --3.41206717491,1.87436962128,-4.0840010643 --3.39705562592,1.87337625027,-4.09243631363 --3.36602830887,1.86139380932,-4.08185958862 --3.37303638458,1.86938738823,-4.10206794739 --3.36503171921,1.87238943577,-4.11748695374 --3.33600592613,1.86140573025,-4.10891103745 --3.32299613953,1.86141121387,-4.11832761765 --3.32500123978,1.86940610409,-4.14676713943 --3.30998945236,1.86741304398,-4.15317201614 --3.29798078537,1.86741781235,-4.16358423233 --3.29297733307,1.8684194088,-4.17080450058 --3.27496242523,1.86442828178,-4.17422056198 --3.25995087624,1.86343502998,-4.18266153336 --3.25494909286,1.86743474007,-4.20208263397 --3.23593330383,1.86344456673,-4.20348882675 --3.21491527557,1.85845577717,-4.20392084122 --3.22092342377,1.86544930935,-4.22413063049 --3.210916996,1.86645245552,-4.23755216599 --3.18589425087,1.85846686363,-4.23197031021 --3.1828956604,1.86446475983,-4.25439548492 --3.16087627411,1.85847699642,-4.25282049179 --3.14486336708,1.85648441315,-4.25925350189 --3.13986253738,1.86148405075,-4.27765226364 --3.11684179306,1.85449695587,-4.27508640289 --3.1208486557,1.86149168015,-4.29329490662 --3.10283327103,1.85750091076,-4.29672241211 --3.08782148361,1.85650801659,-4.30313682556 --3.06780385971,1.85051894188,-4.3035607338 --3.07181382179,1.86151099205,-4.33598899841 --3.04478812218,1.8525274992,-4.32640457153 --3.04278850555,1.85552668571,-4.33762264252 --3.03578591347,1.85852730274,-4.35504102707 --3.0137655735,1.85254013538,-4.35144996643 --3.00776410103,1.85653996468,-4.36986207962 --2.98674535751,1.85155165195,-4.36929941177 --2.9777405262,1.8535541296,-4.38371276855 --2.96072626114,1.85056269169,-4.38814353943 --2.96072936058,1.85556018353,-4.40134572983 --2.93971061707,1.85057199001,-4.40078687668 --2.93070578575,1.85257422924,-4.41519880295 --2.92070031166,1.8545769453,-4.42963171005 --2.89467453957,1.84559333324,-4.42106437683 --2.88466858864,1.84759640694,-4.43346786499 --2.87766695023,1.85159671307,-4.45189476013 --2.86565542221,1.84860408306,-4.4491147995 --2.85064339638,1.84661114216,-4.45553684235 --2.84464263916,1.85061097145,-4.47393941879 --2.82762861252,1.84861969948,-4.47837734222 --2.81261658669,1.84762680531,-4.48480081558 --2.80761766434,1.85262537003,-4.50520801544 --2.78058958054,1.84264302254,-4.49464941025 --2.77558660507,1.84364485741,-4.49983549118 --2.76858592033,1.84864473343,-4.51927185059 --2.74956846237,1.84465539455,-4.51969909668 --2.73355507851,1.84266364574,-4.5241189003 --2.72555279732,1.84566450119,-4.54154539108 --2.71354484558,1.84666907787,-4.55196142197 --2.68851852417,1.83768570423,-4.54238605499 --2.69553351402,1.84867584705,-4.56859874725 --2.67551374435,1.84268796444,-4.56601142883 --2.66450834274,1.84569108486,-4.58046102524 --2.64749312401,1.84270036221,-4.58287811279 --2.63348221779,1.8417069912,-4.58928346634 --2.62047362328,1.84271228313,-4.59972238541 --2.61146521568,1.84071743488,-4.59992980957 --2.59445023537,1.83772659302,-4.60336351395 --2.58043980598,1.83773303032,-4.61078500748 --2.5784471035,1.84572780132,-4.63820171356 --2.55442118645,1.83774411678,-4.62862205505 --2.54241347313,1.83874869347,-4.6390376091 --2.53040623665,1.84075307846,-4.65046691895 --2.51739764214,1.84075820446,-4.6609044075 --2.50738716125,1.83776473999,-4.65809822083 --2.49838471413,1.84176599979,-4.67452287674 --2.47636175156,1.83478045464,-4.66895914078 --2.45834422112,1.8317912817,-4.66837120056 --2.45334887505,1.83878815174,-4.69280576706 --2.43633341789,1.83579778671,-4.69523286819 --2.43032979965,1.83679997921,-4.7004404068 --2.42433238029,1.84279811382,-4.72185516357 --2.39830207825,1.83281719685,-4.70829105377 --2.38429141045,1.83282399178,-4.71470212936 --2.37528967857,1.83682477474,-4.73213434219 --2.36127972603,1.83683097363,-4.74057006836 --2.34526538849,1.83484005928,-4.74297809601 --2.33926177025,1.83484196663,-4.74919700623 --2.32425022125,1.8348493576,-4.75563240051 --2.30823588371,1.83285844326,-4.75804233551 --2.29622936249,1.83486235142,-4.77048015594 --2.27821183205,1.83087348938,-4.76990222931 --2.26921057701,1.83487415314,-4.78732776642 --2.26321458817,1.84187150002,-4.80974054337 --2.24518942833,1.83288753033,-4.79195833206 --2.23218083382,1.83289277554,-4.80138206482 --2.21416306496,1.82990396023,-4.80080842972 --2.20015287399,1.82991051674,-4.80823373795 --2.18914818764,1.83291339874,-4.82165670395 --2.17413544655,1.83092141151,-4.82607030869 --2.15611815453,1.82793235779,-4.82651185989 --2.14811110497,1.82693660259,-4.82873153687 --2.14111375809,1.83293509483,-4.8491358757 --2.12409853935,1.83094489574,-4.85157728195 --2.11108970642,1.8319504261,-4.85998916626 --2.09407329559,1.82896077633,-4.86040830612 --2.08306884766,1.83196365833,-4.87382745743 --2.07105374336,1.82697319984,-4.86704540253 --2.06305599213,1.83297204971,-4.88746786118 --2.04503846169,1.8299831152,-4.88791418076 --2.02401351929,1.82399880886,-4.87933683395 --2.01401138306,1.82700037956,-4.89475154877 --2.00000166893,1.82800662518,-4.90318822861 --1.97897660732,1.82202243805,-4.89461565018 --1.97798335552,1.82701838017,-4.9098033905 --1.9639737606,1.82702457905,-4.91823959351 --1.94795966148,1.82603359222,-4.92167282104 --1.94196712971,1.8340293169,-4.94708776474 --1.92495119572,1.83203959465,-4.94852495193 --1.90893602371,1.83004927635,-4.94993782043 --1.90093958378,1.83604741096,-4.97135591507 --1.8788998127,1.82107198238,-4.93857097626 --1.86990296841,1.82707035542,-4.96102428436 --1.86090445518,1.83307015896,-4.97943496704 --1.84088015556,1.82708525658,-4.97186040878 -2.09702110291,1.7761131525,-4.03240251541 -2.10902810097,1.7741137743,-4.02280664444 -2.11602640152,1.76911056042,-4.00321388245 -2.12703180313,1.76611042023,-3.99162125587 -2.1440486908,1.76911497116,-3.99202251434 -2.14303898811,1.76210975647,-3.97224640846 -2.15905404091,1.76411354542,-3.9706492424 -2.17807412148,1.7691192627,-3.97405838966 -2.19308781624,1.77012240887,-3.97144842148 -2.20409345627,1.76812243462,-3.95985746384 -2.22411513329,1.77312862873,-3.96427369118 -2.22810959816,1.76612436771,-3.94166135788 -2.24413061142,1.77313160896,-3.95486760139 -2.25613808632,1.77213227749,-3.94428801537 -2.26814675331,1.77113354206,-3.93667078018 -2.28115582466,1.77013480663,-3.92809009552 -2.29116010666,1.76713442802,-3.9145052433 -2.30717515945,1.76913821697,-3.91290235519 -2.3251926899,1.77314281464,-3.91331720352 -2.33219885826,1.77414429188,-3.91150474548 -2.34120202065,1.77014327049,-3.89691305161 -2.35821819305,1.77314758301,-3.8963162899 -2.37122797966,1.77314925194,-3.88872218132 -2.38724279404,1.77515292168,-3.88711547852 -2.39524435997,1.77115154266,-3.87053012848 -2.42227578163,1.7811614275,-3.88495182991 -2.41425824165,1.77015388012,-3.85814261436 -2.42225980759,1.7661523819,-3.84057497978 -2.42926073074,1.76115083694,-3.82397270203 -2.44627690315,1.76415514946,-3.82337379456 -2.47831630707,1.77916812897,-3.84775853157 -2.47630310059,1.76716125011,-3.8151807785 -2.48230695724,1.76616168022,-3.8094022274 -2.48930811882,1.76216042042,-3.79280376434 -2.52635407448,1.78017556667,-3.82419013977 -2.52634429932,1.77017009258,-3.79462170601 -2.53735160828,1.76917099953,-3.78402733803 -2.5543680191,1.77217543125,-3.78440737724 -2.57739257812,1.78018271923,-3.79280209541 -2.5813934803,1.77718222141,-3.78402256966 -2.59941029549,1.78118658066,-3.7834353447 -2.5963973999,1.76918017864,-3.75085759163 -2.60940766335,1.7691822052,-3.74326491356 -2.62842679024,1.77418756485,-3.74663949013 -2.6394340992,1.77318835258,-3.73506188393 -2.65945386887,1.77819395065,-3.73845553398 -2.66345524788,1.77619349957,-3.72967934608 -2.67646574974,1.77719581127,-3.72306966782 -2.69548392296,1.78120076656,-3.72446870804 -2.69347381592,1.77119553089,-3.69488453865 -2.70848631859,1.77219855785,-3.68930411339 -2.74152326584,1.78620994091,-3.71069407463 -2.73350572586,1.77220237255,-3.67311120033 -2.74151277542,1.77320384979,-3.67033076286 -2.75952935219,1.77720832825,-3.66973471642 -2.77854752541,1.78121328354,-3.67112755775 -2.7825460434,1.77521121502,-3.6505446434 -2.79455542564,1.77521300316,-3.64194440842 -2.80356049538,1.77321350574,-3.62836003304 -2.81457138062,1.77621650696,-3.63056325912 -2.82557916641,1.77521789074,-3.62095808983 -2.84860157967,1.78222429752,-3.62538170815 -2.8566057682,1.77922427654,-3.61079311371 -2.86661267281,1.77722537518,-3.59919953346 -2.87661957741,1.77622628212,-3.5876057148 -2.8876273632,1.77522778511,-3.57800149918 -2.89963912964,1.77923107147,-3.58022069931 -2.91765522957,1.7822355032,-3.57961416245 -2.92365765572,1.77923500538,-3.5630197525 -2.94067263603,1.78223884106,-3.56042361259 -2.94767594337,1.77823865414,-3.54385256767 -2.96769452095,1.78324365616,-3.54525017738 -2.98671174049,1.78824818134,-3.54465866089 -2.98771071434,1.78524744511,-3.53484725952 -3.00072097778,1.78524959087,-3.5252828598 -3.01573371887,1.78725266457,-3.52067494392 -3.02373838425,1.78425312042,-3.50609326363 -3.02473592758,1.77725124359,-3.48350691795 -3.04575514793,1.78325641155,-3.48590064049 -3.0677754879,1.78926193714,-3.48831272125 -3.06877470016,1.78626132011,-3.47850513458 -3.08578944206,1.78926503658,-3.4749174118 -3.0867869854,1.78226327896,-3.45233654976 -3.11181020737,1.79026985168,-3.45873451233 -3.12682318687,1.79327273369,-3.45313835144 -3.14183521271,1.79427576065,-3.44655966759 -3.1418337822,1.79027485847,-3.43477010727 -3.14083003998,1.78327274323,-3.41117310524 -3.16284990311,1.7892781496,-3.41357469559 -3.17285752296,1.7882796526,-3.40198540688 -3.18386602402,1.78828144073,-3.39139795303 -3.20888829231,1.79628765583,-3.39679980278 -3.20688414574,1.78828549385,-3.37220835686 -3.21789360046,1.79028820992,-3.37242388725 -3.23090434074,1.79129064083,-3.36383962631 -3.2409119606,1.79029238224,-3.35323286057 -3.24991893768,1.78929364681,-3.34064340591 -3.27393984795,1.79629933834,-3.34405255318 -3.27794194221,1.79229927063,-3.32645797729 -3.2859480381,1.79030036926,-3.311886549 -3.29095196724,1.79030132294,-3.30707454681 -3.30296158791,1.79030358791,-3.29748868942 -3.31997585297,1.79330718517,-3.29388713837 -3.33498883247,1.7963104248,-3.28828310966 -3.35100197792,1.79831373692,-3.28171563148 -3.34899902344,1.7903124094,-3.25812554359 -3.36701440811,1.79431629181,-3.25453972816 -3.35600376129,1.78531301022,-3.23176455498 -3.38602995872,1.79632008076,-3.24213981628 -3.39703893661,1.79632222652,-3.23155236244 -3.40704703331,1.79532420635,-3.21996569633 -3.41405248642,1.79332530499,-3.20538020134 -3.43507003784,1.79832994938,-3.20478796959 -3.44607925415,1.79833209515,-3.19420051575 -3.45508670807,1.80033421516,-3.19338464737 -3.4751033783,1.80533850193,-3.1917886734 -3.47410225868,1.79833781719,-3.16921186447 -3.49111628532,1.80134141445,-3.16363668442 -3.5051279068,1.80434441566,-3.15702462196 -3.5041270256,1.79734396935,-3.13445234299 -3.51813864708,1.7983468771,-3.12686085701 -3.53114938736,1.80334961414,-3.12905502319 -3.52714657784,1.79534876347,-3.1044716835 -3.54215908051,1.79735195637,-3.09787774086 -3.5611743927,1.80135595798,-3.09429502487 -3.56117510796,1.79635596275,-3.07370877266 -3.56718039513,1.79335725307,-3.05911254883 -3.57018327713,1.79235804081,-3.05034422874 -3.55617332458,1.77935528755,-3.01677584648 -3.54816794395,1.76935398579,-2.99017834663 -3.53615999222,1.75835192204,-2.95959424973 -3.53415989876,1.75135207176,-2.93703007698 -3.5181491375,1.73734939098,-2.90246725082 -3.51014518738,1.72834849358,-2.87588620186 -3.49713635445,1.71934640408,-2.85411405563 -3.4901330471,1.7103458643,-2.82951641083 -3.49213695526,1.70534718037,-2.81095695496 -3.49614238739,1.70334899426,-2.79537057877 -3.50815320015,1.70435202122,-2.78775763512 -3.51816320419,1.70435488224,-2.77717280388 -3.52316951752,1.70235693455,-2.76258516312 -3.52717375755,1.70135819912,-2.75580787659 -3.5361828804,1.70136094093,-2.74520587921 -3.53918790817,1.69736278057,-2.72862911224 -3.53819036484,1.69236385822,-2.7090485096 -3.57421827316,1.70537126064,-2.7194621563 -3.57622289658,1.70237290859,-2.70286870003 -3.55320835114,1.68836987019,-2.67508292198 -3.5632185936,1.68837296963,-2.66450166702 -3.55821871758,1.68137359619,-2.64192581177 -3.54121088982,1.66837251186,-2.60936832428 -3.8205268383,1.67247629166,-2.26334762573 -3.85655140877,1.68548214436,-2.27072381973 -3.85855841637,1.68248510361,-2.25416350365 -3.85856413841,1.67948782444,-2.23757457733 -3.83955717087,1.66848766804,-2.21680116653 -3.86157441139,1.67449235916,-2.2142033577 -3.8595790863,1.67049515247,-2.19661331177 -3.84557819366,1.66049706936,-2.17104434967 -3.8405816555,1.65449965,-2.15146493912 -3.85859727859,1.65950405598,-2.14587926865 -3.85560202599,1.65450704098,-2.12730717659 -3.86460971832,1.656509161,-2.1245136261 -3.87161946297,1.65651273727,-2.11291456223 -3.86962485313,1.65251588821,-2.09533548355 -3.87663459778,1.65251946449,-2.08373737335 -3.89264917374,1.65552377701,-2.07616829872 -3.89865875244,1.6555274725,-2.063580513 -3.88966107368,1.64753031731,-2.04200744629 -3.90967392921,1.65553295612,-2.04618954659 -3.91168165207,1.65253663063,-2.03062224388 -3.91569042206,1.65154016018,-2.01703286171 -3.92970347404,1.65454435349,-2.00943112373 -3.92570877075,1.6495475769,-1.99085867405 -3.93772149086,1.65155172348,-1.98127949238 -3.945728302,1.65355372429,-1.97846579552 -3.95273852348,1.6535576582,-1.96589314938 -3.93873953819,1.64456057549,-1.94231748581 -3.9607565403,1.6505651474,-1.93871891499 -3.95075941086,1.64356839657,-1.91715013981 -3.9647731781,1.64657270908,-1.90857040882 -3.97578454018,1.64857661724,-1.89994955063 -3.97178673744,1.64457845688,-1.88918113708 -3.96679234505,1.63958203793,-1.87060821056 -3.99181079865,1.64758682251,-1.86801493168 -3.97981309891,1.63959002495,-1.84643089771 -3.9818212986,1.6375939846,-1.83184921741 -4.00183773041,1.64359855652,-1.82626473904 -4.01184940338,1.64460277557,-1.81568098068 -3.99484610558,1.63660407066,-1.79988312721 -4.01686286926,1.64260876179,-1.79529523849 -4.01787137985,1.64061248302,-1.78070211411 -4.02288103104,1.63961684704,-1.76713418961 -4.03189277649,1.64162099361,-1.75653684139 -4.02389717102,1.63462495804,-1.73696708679 -4.03490972519,1.63662910461,-1.72736871243 -4.04791927338,1.64163160324,-1.72558116913 -4.04292535782,1.63663554192,-1.70799839497 -4.05093669891,1.63663983345,-1.69641554356 -4.05494642258,1.63664412498,-1.68283712864 -4.05595493317,1.63364827633,-1.66825067997 -4.06696748734,1.63665246964,-1.65864920616 -4.08197689056,1.64165484905,-1.65785336494 -4.05797719955,1.62865889072,-1.63129556179 -4.07399129868,1.63266336918,-1.62369906902 -4.08500385284,1.63466787338,-1.6131234169 -4.08901357651,1.63367199898,-1.60052025318 -4.08502149582,1.62967669964,-1.58296120167 -4.09603309631,1.63168096542,-1.5733577013 -4.09303665161,1.62968313694,-1.56456780434 -4.10104846954,1.63068759441,-1.55298399925 -4.11306142807,1.63369202614,-1.54338991642 -4.10206651688,1.6256967783,-1.52284026146 -4.10607671738,1.62570106983,-1.51023995876 -4.1180896759,1.62870562077,-1.50064516068 -4.12410116196,1.62871015072,-1.48806643486 -4.12310504913,1.62671244144,-1.48027515411 -4.13711929321,1.63071715832,-1.47069966793 -4.14112901688,1.62972164154,-1.45809924603 -4.13113546371,1.62372648716,-1.43854403496 -4.14814996719,1.62873101234,-1.43094325066 -4.14115715027,1.62373578548,-1.41336750984 -4.14516735077,1.62274026871,-1.40076911449 -4.15217447281,1.62474274635,-1.39597964287 -4.16518783569,1.62774717808,-1.38638949394 -4.15619468689,1.62175238132,-1.36782562733 -4.16120529175,1.62175703049,-1.35523784161 -4.16621637344,1.62176179886,-1.34265005589 -4.16922712326,1.62076663971,-1.32907056808 -4.17923498154,1.62376892567,-1.32528042793 -4.17024183273,1.6177738905,-1.30769610405 -4.18725633621,1.62377858162,-1.29911220074 -4.19026756287,1.62278354168,-1.28553307056 -4.19127702713,1.6207883358,-1.27193546295 -4.19628810883,1.62079310417,-1.25934779644 -4.19629812241,1.61879825592,-1.24477005005 -4.19830369949,1.61880075932,-1.23798573017 -4.1953125,1.61580598354,-1.22240972519 -4.2073264122,1.61881089211,-1.21183025837 -4.20633602142,1.61681592464,-1.19724547863 -4.21634864807,1.61882066727,-1.18664669991 -4.22636175156,1.62082564831,-1.17507493496 -4.21836471558,1.61682856083,-1.16528820992 -4.21737480164,1.61483383179,-1.15070581436 -4.23738956451,1.62083816528,-1.14310610294 -4.23139858246,1.61684381962,-1.12653815746 -4.23340940475,1.61584889889,-1.11295425892 -4.23942089081,1.61685371399,-1.1013469696 -4.23743104935,1.61385929585,-1.08578765392 -4.23943710327,1.61386203766,-1.07900452614 -4.24644899368,1.61586689949,-1.06740510464 -4.23845720291,1.60987269878,-1.05082833767 -4.24446964264,1.61087787151,-1.03825008869 -4.25048160553,1.61188316345,-1.0256717205 -4.25249290466,1.61088848114,-1.01209044456 -4.25950479507,1.61289334297,-1.00049030781 -4.26351118088,1.61289584637,-0.994694173336 -4.26752281189,1.6129014492,-0.981128275394 -4.2745347023,1.61490643024,-0.969526708126 -4.28054714203,1.61591172218,-0.956946253777 -4.27555704117,1.61191761494,-0.941372215748 -4.27556753159,1.6099230051,-0.927777826786 -4.30058383942,1.61892724037,-0.920187950134 -4.280585289,1.60993146896,-0.907422721386 -4.2955994606,1.61493599415,-0.897818088531 -4.28960943222,1.6109418869,-0.882240951061 -4.29362106323,1.61094760895,-0.868675410748 -4.3026342392,1.6129527092,-0.857085287571 -4.30964708328,1.61495828629,-0.844509661198 -4.31265306473,1.6159607172,-0.838703691959 -4.30366182327,1.60996675491,-0.823111414909 -4.31967639923,1.61597168446,-0.812534749508 -4.30868577957,1.60997831821,-0.795960903168 -4.3176984787,1.61198341846,-0.784368157387 -4.32771205902,1.61498856544,-0.772780239582 -4.31672143936,1.6089951992,-0.756210684776 -4.31572628021,1.6079980135,-0.749409973621 -4.32473993301,1.61000359058,-0.73684489727 -4.3317527771,1.61200916767,-0.724266886711 -4.33776569366,1.61301457882,-0.71168255806 -4.34677839279,1.6160197258,-0.700084984303 -4.33478832245,1.61002671719,-0.683517038822 -4.32679796219,1.60503315926,-0.66794449091 -4.35180854797,1.61503446102,-0.666138887405 -4.33681726456,1.60804140568,-0.649558722973 -4.34082937241,1.60804700851,-0.636963486671 -4.35484409332,1.61305212975,-0.625389456749 -4.34985494614,1.61005866528,-0.610806286335 -4.35786819458,1.61206424236,-0.598229825497 -4.35487890244,1.61007022858,-0.584628403187 -4.34588336945,1.60507404804,-0.575851380825 -4.36489868164,1.61207890511,-0.565267264843 -4.36691093445,1.61208498478,-0.551690220833 -4.37892484665,1.61609005928,-0.540099322796 -4.35393238068,1.60509800911,-0.522520005703 -4.36294651031,1.60810375214,-0.509945571423 -4.36995363235,1.61010634899,-0.504154026508 -4.36696434021,1.60811245441,-0.49055659771 -4.38598012924,1.61411762238,-0.4789917171 -4.36799001694,1.60612547398,-0.462422907352 -4.37900304794,1.61013066769,-0.450823366642 -4.38701629639,1.61213624477,-0.438240587711 -4.3740272522,1.606143713,-0.422666966915 -4.38803529739,1.61114561558,-0.417868077755 -4.3840470314,1.60915255547,-0.403299450874 -4.3720574379,1.60315966606,-0.388703942299 -4.38607120514,1.60816466808,-0.37711083889 -4.40108680725,1.61317014694,-0.364548653364 -4.37709569931,1.60317873955,-0.347976475954 -4.39010953903,1.60818374157,-0.336376696825 -4.38911581039,1.60718715191,-0.32958266139 -4.39512968063,1.60819327831,-0.316019326448 -4.39414215088,1.60819983482,-0.302434206009 -4.40215539932,1.61020565033,-0.28984567523 -4.39216661453,1.60521292686,-0.275266349316 -4.39417982101,1.60521936417,-0.261691004038 -4.39919233322,1.60722529888,-0.249093070626 -4.40719985962,1.61022782326,-0.243292808533 -4.40521287918,1.60823488235,-0.228736639023 -4.41422653198,1.61124050617,-0.216146677732 -4.39623689651,1.60424864292,-0.20155467093 -4.40125083923,1.60525500774,-0.187985911965 -4.41726541519,1.61126029491,-0.175408780575 -4.39826917648,1.60326528549,-0.167610242963 -4.4122838974,1.60827052593,-0.155027762055 -4.41529750824,1.60927712917,-0.141452804208 -4.42231082916,1.61128282547,-0.128854602575 -4.40832233429,1.60529100895,-0.114280946553 -4.42633724213,1.61229610443,-0.101699166 -4.40634822845,1.60430490971,-0.0871193930507 -4.41035556793,1.60530793667,-0.0803356990218 -4.41736984253,1.60831427574,-0.0667655616999 -4.4053812027,1.60232210159,-0.0531717464328 -4.40439462662,1.60232901573,-0.039592128247 -4.41440916061,1.60533499718,-0.0260245352983 -4.41142177582,1.60434222221,-0.0124427741393 -4.4114356041,1.60434925556,0.00113572541159 -4.42544269562,1.60935091972,0.00694379257038 -4.4184551239,1.60635852814,0.020528241992 -4.42046928406,1.60736525059,0.0341059491038 -4.43448400497,1.61237096786,0.047677628696 -4.4214963913,1.60737919807,0.0612631887197 -4.42751026154,1.60938560963,0.0748399868608 -4.41552305222,1.60439383984,0.0884219780564 -4.41552972794,1.60439729691,0.0952110439539 -4.41054296494,1.60240495205,0.10878957808 -4.42755699158,1.60840964317,0.121397055686 -4.41057014465,1.60241925716,0.135944619775 -4.4125828743,1.60242557526,0.148552402854 -4.41459703445,1.60343241692,0.162130624056 -4.40960359573,1.60143661499,0.168917864561 -4.41161775589,1.60244357586,0.182496041059 -4.41163158417,1.60245084763,0.196073487401 -4.4096455574,1.60145819187,0.209649652243 -4.39865875244,1.59746682644,0.223219275475 -4.40567302704,1.60047316551,0.236801147461 -4.39468574524,1.59548127651,0.249398335814 -4.40369415283,1.59948444366,0.257164567709 -4.41270828247,1.60249054432,0.270750463009 -4.40772151947,1.60049784184,0.283352673054 -4.39973497391,1.59750640392,0.296920180321 -4.40274953842,1.59951329231,0.310500860214 -4.39676380157,1.5975215435,0.32406938076 -4.39877080917,1.59752488136,0.330860227346 -4.40178537369,1.59953188896,0.344441711903 -4.40579891205,1.60053861141,0.358025074005 -4.40081214905,1.59954619408,0.370624274015 -4.392827034,1.59655487537,0.384186774492 -4.38884162903,1.59456300735,0.397755354643 -4.40285539627,1.60056817532,0.411359876394 -4.40886259079,1.60257101059,0.418160885572 -4.39887714386,1.59958004951,0.431717842817 -4.40189170837,1.60058701038,0.445301949978 -4.39890623093,1.60059499741,0.458873093128 -4.40192079544,1.60160195827,0.472458094358 -4.38993453979,1.59761106968,0.485036253929 -4.38894939423,1.59761881828,0.498610943556 -4.38495540619,1.59562265873,0.50441890955 -4.39297056198,1.59962940216,0.518988132477 -4.38498497009,1.59663784504,0.531573414803 -4.39099884033,1.59964442253,0.545168638229 -4.38801383972,1.59865248203,0.558737754822 -4.3830280304,1.59766054153,0.571330547333 -4.37703561783,1.59466540813,0.578100144863 -4.38705062866,1.59967172146,0.592680513859 -4.37806510925,1.59668052197,0.605259001255 -4.38207960129,1.59868741035,0.618850946426 -4.37609434128,1.59669578075,0.631438434124 -4.38310909271,1.60070252419,0.646012485027 -4.38612365723,1.60170960426,0.659602880478 -4.3741312027,1.59771537781,0.665377557278 -4.37614631653,1.5987226963,0.678964197636 -4.37316083908,1.59773111343,0.692531585693 -4.37717580795,1.60073781013,0.706127583981 -4.3751912117,1.60074603558,0.719699442387 -4.37020540237,1.59875428677,0.732288241386 -4.37222099304,1.60076212883,0.746847271919 -4.36522865295,1.59776711464,0.752636611462 -4.36924314499,1.60077393055,0.76623493433 -4.35825872421,1.596783638,0.778795301914 -4.36527347565,1.60079038143,0.793378472328 -4.36328792572,1.60079801083,0.805980145931 -4.3473033905,1.59480845928,0.817543506622 -4.36531877518,1.60281383991,0.834123253822 -4.36032581329,1.60081827641,0.83991920948 -4.36234092712,1.60282576084,0.853511571884 -4.36335706711,1.60383379459,0.868069648743 -4.3653717041,1.60584115982,0.881663501263 -4.37238645554,1.60884785652,0.896254897118 -4.35140275955,1.60185921192,0.906814694405 -4.33441019058,1.59486567974,0.910601973534 -4.33742618561,1.59787344933,0.925171136856 -4.35843992233,1.60687768459,0.941784024239 -4.34345674515,1.60188817978,0.953342020512 -4.31147241592,1.58990097046,0.96091657877 -4.31348752975,1.59190833569,0.974510252476 -4.30150365829,1.58791840076,0.986079156399 -4.30251073837,1.58892214298,0.992876112461 -4.35752487183,1.61192178726,1.01747238636 -4.34054088593,1.60593247414,1.02804207802 -4.33055686951,1.60294210911,1.03962421417 -4.31357336044,1.59795296192,1.05018937588 -4.3325881958,1.60595786572,1.0677806139 -4.31360435486,1.59996891022,1.07736003399 -4.31961250305,1.60297238827,1.08613419533 -4.29462814331,1.59398388863,1.09372878075 -4.29864501953,1.59699189663,1.10928237438 -3.69378042221,1.61916458607,2.62038660049 -3.70581579208,1.63218140602,2.66253352165 -3.694835186,1.63119256496,2.67112541199 -3.68685531616,1.63120377064,2.68269491196 -3.65787768364,1.62021815777,2.67829036713 -3.63489985466,1.61323213577,2.67886400223 -3.62891077995,1.61223840714,2.68363595009 -3.62292957306,1.61324846745,2.69523692131 -3.60495185852,1.60926187038,2.69979596138 -3.60796952248,1.61427044868,2.71838641167 -3.6009888649,1.61528110504,2.72997045517 -3.57801198959,1.60729527473,2.73053312302 -3.57403087616,1.6103053093,2.74412178993 -3.5840382576,1.61630809307,2.75991606712 -3.55706214905,1.60732316971,2.75747489929 -3.56007933617,1.61233186722,2.7760720253 -3.56209778786,1.61834084988,2.7946536541 -3.54911899567,1.61535298824,2.80222463608 -3.53114104271,1.61136615276,2.80579829216 -3.53815841675,1.61837422848,2.8283803463 -3.52217006683,1.61238193512,2.8241789341 -3.51319050789,1.61239337921,2.83475089073 -3.51820778847,1.61940157413,2.85534787178 -3.50323009491,1.61641454697,2.86190271378 -3.49225091934,1.61542606354,2.87048459053 -3.48027133942,1.61343789101,2.87807011604 -3.48328089714,1.61744248867,2.8898460865 -3.47630047798,1.61845314503,2.90143346786 -3.47231936455,1.62046301365,2.91503167152 -3.45134282112,1.61447739601,2.91658449173 -3.44736170769,1.61648726463,2.93018293381 -3.43238353729,1.61349999905,2.93575525284 -3.43339300156,1.61650466919,2.94554376602 -3.42241358757,1.61551630497,2.95412325859 -3.42343235016,1.62052571774,2.97270679474 -3.4054543972,1.61553871632,2.97528743744 -3.39847421646,1.61654961109,2.98687648773 -3.40149354935,1.62355911732,3.00843477249 -3.38151597977,1.61757254601,3.00901889801 -3.37852549553,1.61857759953,3.01482391357 -3.38054466248,1.62358725071,3.03538918495 -3.37356567383,1.62559843063,3.04795861244 -3.34758973122,1.61661338806,3.04353117943 -3.35460639,1.62462115288,3.06713342667 -3.33362936974,1.61863493919,3.06671285629 -3.33264875412,1.6236448288,3.08429193497 -3.32965898514,1.62365043163,3.09107637405 -3.31768012047,1.62266242504,3.0986571312 -3.30570173264,1.62067437172,3.10623717308 -3.30272102356,1.62468457222,3.12182402611 -3.27974486351,1.61769890785,3.1193985939 -3.27876400948,1.62170875072,3.1369831562 -3.27278470993,1.62371981144,3.15055441856 -3.25879669189,1.61872720718,3.1463534832 -3.25881648064,1.62373733521,3.16591835022 -3.25983524323,1.62974667549,3.18550658226 -3.24485707283,1.6267592907,3.19008874893 -3.23387861252,1.62677121162,3.19866681099 -3.21990060806,1.62378370762,3.20424580574 -3.21291184425,1.62279009819,3.2070350647 -3.21193146706,1.62780022621,3.22560858727 -3.19795370102,1.62581264973,3.23118710518 -3.18297600746,1.62282562256,3.23576426506 -3.18499493599,1.62883496284,3.25734138489 -3.17101740837,1.62684762478,3.26291847229 -3.16103887558,1.6268594265,3.27249574661 -3.1600484848,1.62886452675,3.28128623962 -3.15206885338,1.62987554073,3.29188585281 -3.13909101486,1.62888789177,3.29846215248 -3.1321117878,1.62989914417,3.31104230881 -3.122133255,1.62991094589,3.3206205368 -3.11715340614,1.63292169571,3.33520412445 -3.09417748451,1.62593591213,3.33078861237 -3.09018802643,1.62694168091,3.33657836914 -3.08520936966,1.62895286083,3.35214209557 -3.07323145866,1.62896513939,3.35971784592 -3.06925153732,1.63197565079,3.37530565262 -3.05327391624,1.62898850441,3.37789440155 -3.04529595375,1.63000035286,3.39045619965 -3.04530525208,1.63300514221,3.40025568008 -3.0323278904,1.63201773167,3.40682888031 -3.01934957504,1.63002991676,3.4124212265 -3.02136921883,1.63703966141,3.43598866463 -3.01239037514,1.63805127144,3.44657182693 -2.9914150238,1.63206541538,3.44414377213 -2.98743486404,1.6360758543,3.45973992348 -2.98944401741,1.64008033276,3.47253036499 -2.96646928787,1.63309526443,3.46809363365 -2.96049070358,1.63610649109,3.48266673088 -2.952511549,1.6371178627,3.49425387383 -2.93953371048,1.63613009453,3.49984455109 -2.93255519867,1.63814163208,3.51341676712 -2.91557884216,1.63515496254,3.51499295235 -2.91258883476,1.63616037369,3.52179074287 -2.90761065483,1.64017176628,3.53835296631 -2.89963150024,1.64118301868,3.54994320869 -2.87665605545,1.63419735432,3.54353070259 -2.87467646599,1.63920772076,3.56310749054 -2.86569786072,1.64021933079,3.57369470596 -2.86070871353,1.64022529125,3.57848620415 -2.84773182869,1.64023804665,3.58505630493 -2.82875609398,1.63525187969,3.5836353302 -2.82777547836,1.6402618885,3.60422277451 -2.8157992363,1.64027476311,3.61277866364 -2.80082154274,1.63728737831,3.61537432671 -2.79384303093,1.64029884338,3.62895488739 -2.79285383224,1.64330434799,3.63973164558 -2.77587723732,1.64031755924,3.6403157711 -2.75590133667,1.63433146477,3.63689994812 -2.76391983032,1.64634001255,3.67047524452 -2.74594402313,1.64235365391,3.67005181313 -2.72796750069,1.63736701012,3.66864442825 -2.73697566986,1.64737033844,3.69243001938 -2.71899986267,1.64338409901,3.69200444221 -2.67103075981,1.61940348148,3.65058684349 -2.69604539871,1.64340889454,3.70815849304 -2.68206787109,1.64042127132,3.71175456047 -2.67908859253,1.64643204212,3.73133420944 -2.66711068153,1.64544403553,3.73792624474 -2.66012263298,1.64545071125,3.74070668221 -2.64614605904,1.6434636116,3.74528431892 -2.64216732979,1.64847457409,3.76386260986 -2.62019181252,1.64148879051,3.75645208359 -2.61221456528,1.64450061321,3.77002024651 -2.6142334938,1.65351009369,3.79661250114 -2.59225893021,1.64652490616,3.79018139839 -2.59526848793,1.65252923965,3.8069691658 -2.58629083633,1.65454101562,3.81855130196 -2.57431292534,1.65355324745,3.82514405251 -2.55733680725,1.65056657791,3.82473039627 -2.55135941505,1.65457832813,3.84228825569 -2.53538274765,1.65159142017,3.84288096428 -2.53640246391,1.66060113907,3.8694665432 -2.52441549301,1.65660870075,3.86425423622 -2.51143860817,1.65562129021,3.86983895302 -2.49946165085,1.65563380718,3.87741541862 -2.49248409271,1.65964543819,3.89298796654 -2.47450828552,1.65465903282,3.89057588577 -2.46453094482,1.65667116642,3.90115499496 -2.46554088593,1.66167616844,3.91594314575 -2.4535639286,1.66168868542,3.92352151871 -2.45258498192,1.66969919205,3.94909238815 -2.44760608673,1.67571020126,3.96767616272 -2.45262503624,1.68771922588,4.0022649765 -2.42965126038,1.68073403835,3.99283599854 -2.43766951561,1.69574260712,4.03341531754 -2.43468022346,1.69774830341,4.04220724106 -2.4367005825,1.70875811577,4.07378196716 -2.43871974945,1.7197675705,4.10437679291 -2.42174530029,1.71678161621,4.10593366623 -2.41876578331,1.72379207611,4.12852859497 -2.42078495026,1.73480153084,4.16011953354 -2.42179536819,1.7408066988,4.17690229416 -2.41181874275,1.74381935596,4.19046354294 -2.41083860397,1.75282919407,4.21706199646 -2.39686250687,1.75184214115,4.22264099121 -2.39688324928,1.76285243034,4.25321483612 -2.3849067688,1.76286518574,4.26278924942 -2.36693167686,1.75987899303,4.26136827469 -2.35894298553,1.75788521767,4.2611746788 -2.34396719933,1.75689828396,4.26475715637 -2.33099079132,1.75691115856,4.27233362198 -2.31501507759,1.75492453575,4.27391719818 -2.2980401516,1.75193822384,4.27448892593 -2.28806233406,1.75395011902,4.28608512878 -2.27308654785,1.75296330452,4.28966522217 -2.26509952545,1.75197017193,4.29144239426 -2.25412154198,1.75298213959,4.30104207993 -2.23414802551,1.7479968071,4.29660081863 -2.2181725502,1.7460103035,4.29817962646 -2.20419621468,1.74502301216,4.30276823044 -2.19021987915,1.74503576756,4.30735683441 -2.1722445488,1.74004936218,4.30394697189 -2.1632578373,1.73905670643,4.30372238159 -2.15727901459,1.74506759644,4.32332038879 -2.13230729103,1.73508346081,4.30887031555 -2.13032746315,1.74509358406,4.33647155762 -2.11535263062,1.7441072464,4.34103393555 -2.10237622261,1.74411988258,4.34762191772 -2.09038877487,1.7391269207,4.33842992783 -2.07341384888,1.736140728,4.33800077438 -2.06643629074,1.74215221405,4.35758209229 -2.04846096039,1.73716580868,4.35317564011 -2.03348517418,1.73617899418,4.35575914383 -2.02251005173,1.73919200897,4.36931371689 -2.00753426552,1.73720502853,4.37189769745 -2.00054645538,1.73721158504,4.3746843338 -1.98557090759,1.73622477055,4.37726736069 -1.97059476376,1.73423755169,4.37886095047 -1.95362067223,1.73225164413,4.37842607498 -1.94164407253,1.73326408863,4.38701486588 -1.93066692352,1.73527610302,4.39760780334 -1.91869080067,1.73728871346,4.40718746185 -1.90670406818,1.73229622841,4.39797973633 -1.89472854137,1.73430907726,4.40854787827 -1.87875247002,1.7313221693,4.40714645386 -1.86277770996,1.72933554649,4.40772199631 -1.85280060768,1.73234760761,4.42130947113 -1.83782541752,1.73136091232,4.42388820648 -1.83083832264,1.73236775398,4.4276638031 -1.81886219978,1.7333804369,4.43724536896 -1.80288696289,1.73139369488,4.43683004379 -1.78891181946,1.73140692711,4.44240188599 -1.77693510056,1.73241913319,4.45099544525 -1.76195943356,1.73143219948,4.45258331299 -1.75198328495,1.73544454575,4.46815729141 -1.7399969101,1.7304520607,4.45794677734 -1.73101902008,1.7344635725,4.47354793549 -1.71804380417,1.73647677898,4.48211765289 -1.70106887817,1.73249018192,4.47870254517 -1.68009483814,1.72450435162,4.4642906189 -1.67511796951,1.73551607132,4.49485254288 -1.66014206409,1.73352897167,4.49544858932 -1.64915597439,1.72953641415,4.4882273674 -1.6421790123,1.73754823208,4.51280164719 -1.6232047081,1.73256206512,4.50338745117 -1.61122786999,1.73357439041,4.51198577881 -1.59825217724,1.73458707333,4.51956701279 -1.57927906513,1.72960150242,4.51213026047 -1.57229113579,1.72960782051,4.51392602921 -1.5633136034,1.73461949825,4.53152179718 -1.54833889008,1.73463284969,4.53409719467 -1.53036475182,1.72964668274,4.52767419815 -1.51638936996,1.72965967655,4.53225660324 -1.50241351128,1.72967243195,4.53584861755 -1.48743879795,1.72968578339,4.5384221077 -1.485450387,1.73569154739,4.55720233917 -1.46747481823,1.72970461845,4.54681015015 -1.45649886131,1.73471713066,4.56138706207 -1.44352304935,1.73572981358,4.56897258759 -1.42354977131,1.72874414921,4.5555472374 -1.41357386112,1.73475646973,4.57412099838 -1.39659869671,1.72976970673,4.56771564484 -1.38661277294,1.72677731514,4.56248807907 -1.37563586235,1.73078930378,4.57508659363 -1.36565971375,1.7368016243,4.59366559982 -1.34968554974,1.7348151207,4.59323644638 -1.32971119881,1.72682893276,4.57583284378 -1.31873571873,1.73184156418,4.59240293503 -1.30475997925,1.73185431957,4.59599542618 -1.29377317429,1.72586143017,4.58379030228 -1.28279721737,1.73087382317,4.59937143326 -1.26382374763,1.7248878479,4.58694791794 -1.25284802914,1.72990036011,4.60352277756 -1.23787248135,1.72791314125,4.60311698914 -1.22489702702,1.7299258709,4.61169958115 -1.21591079235,1.72793316841,4.60847663879 -1.2009345293,1.72594571114,4.60608386993 -1.18695998192,1.7269589901,4.6126537323 -1.1729850769,1.72797191143,4.61823129654 -1.16000878811,1.72998416424,4.6248292923 -1.14203476906,1.72399795055,4.61341381073 -1.12806046009,1.72501122952,4.62097835541 -1.12207210064,1.72701728344,4.62578105927 -1.10609781742,1.72503066063,4.62335729599 -1.09112262726,1.72304356098,4.62294721603 -1.07914698124,1.72705614567,4.63652849197 -1.06417238712,1.7270693779,4.63810586929 -1.05019783974,1.72808241844,4.64467906952 -1.04221045971,1.72708916664,4.64247274399 -1.02523553371,1.72210228443,4.6320681572 -1.00826108456,1.71711564064,4.62265443802 -0.998285293579,1.7251278162,4.64723014832 -0.983309924603,1.72414076328,4.64582395554 -0.966335892677,1.7191542387,4.63740253448 -0.95735925436,1.73016607761,4.66598939896 -0.943373203278,1.71617364883,4.63279008865 -0.931397557259,1.72118604183,4.64737462997 -0.917424023151,1.72419965267,4.65792798996 -0.898450016975,1.71421337128,4.63651657104 -0.885473489761,1.71622538567,4.64212417603 -0.871498882771,1.71723842621,4.64869976044 -0.858523309231,1.72025096416,4.65828800201 -0.851535797119,1.7212574482,4.66107940674 -0.837561786175,1.72427070141,4.67064142227 -0.821587443352,1.72128403187,4.66522407532 -0.80861222744,1.72529661655,4.67680549622 -0.794637143612,1.72630941868,4.68238973618 -0.775662720203,1.7143228054,4.65498924255 -0.761687338352,1.71533536911,4.65858125687 -0.755700707436,1.72034215927,4.67235088348 -0.741725623608,1.72235500813,4.67793560028 -0.728749752045,1.72536718845,4.68753099442 -0.710775792599,1.71638083458,4.66711616516 -0.697800338268,1.71939337254,4.67870378494 -0.681825995445,1.71640646458,4.67128705978 -0.675838530064,1.72041285038,4.68307113647 -0.661864042282,1.72342586517,4.69164609909 -0.644890129566,1.71743929386,4.67722702026 -0.631913840771,1.71945142746,4.68583059311 -0.616940021515,1.72046470642,4.68939733505 -0.60096514225,1.71547758579,4.67799043655 -0.586990594864,1.71849060059,4.68656778336 -0.580002605915,1.71849668026,4.68736886978 -0.564027965069,1.71350967884,4.67595863342 -0.549054205418,1.71452307701,4.67952537537 -0.534078776836,1.71153557301,4.67312431335 -0.518104493618,1.70654881001,4.66270637512 -0.507128715515,1.7195609808,4.69729042053 -0.497142553329,1.71156811714,4.67607355118 -0.484166711569,1.71558022499,4.68867063522 -0.469192147255,1.71459329128,4.68725252151 -0.453217953444,1.70960640907,4.67583417892 -0.440243184566,1.71761918068,4.69741010666 -0.425268381834,1.71663188934,4.69399785995 -0.411293148994,1.71864449978,4.70058774948 -0.40330645442,1.71765124798,4.69737100601 -0.387331306934,1.70866382122,4.67597103119 -0.374357134104,1.71967685223,4.70653533936 -0.358382165432,1.71168959141,4.68513250351 -0.344407856464,1.71770262718,4.70070505142 -0.329432606697,1.71371507645,4.6913022995 -0.314458608627,1.7147282362,4.69387435913 -0.30747115612,1.71673452854,4.69966650009 -0.292496144772,1.71274721622,4.69125938416 -0.277521193027,1.70975983143,4.68285083771 -0.263546437025,1.71477258205,4.69743204117 -0.247572287917,1.70678555965,4.67601394653 -0.233597248793,1.71079814434,4.68760156631 -0.219622313976,1.71681070328,4.70218706131 -0.211635708809,1.71481752396,4.69696855545 -0.196661025286,1.71183025837,4.68955469131 -0.181686758995,1.71084308624,4.68813323975 -0.167710930109,1.71185529232,4.68973636627 -0.152736157179,1.70686805248,4.67732477188 -0.137762352824,1.70988118649,4.68489456177 -0.130774393678,1.70988714695,4.68469715118 -0.115800499916,1.71190023422,4.69226789474 -0.101824820042,1.71491241455,4.69986867905 -0.0858514532447,1.70292568207,4.66743516922 -0.0718761757016,1.71193814278,4.69202804565 -0.0569018535316,1.70995104313,4.68460798264 -0.0429259054363,1.70796298981,4.68021392822 -0.0349396467209,1.70696985722,4.675989151 -0.0209638830274,1.7119820118,4.6905913353 -0.00598970288411,1.71699488163,4.70216846466 --0.849504947662,1.72873282433,4.47938346863 --0.864478945732,1.72974526882,4.4779548645 --0.88245344162,1.73875772953,4.49655246735 --0.901415646076,1.73277580738,4.47691440582 --0.503519296646,0.91171503067,2.47676348686 --0.916390895844,1.73478770256,4.47951078415 --0.929366409779,1.73279941082,4.47110033035 --0.945341289043,1.73681151867,4.4776930809 --0.956316828728,1.73082327843,4.45827245712 --0.974290192127,1.73683595657,4.47084760666 --0.980278432369,1.73584163189,4.46564912796 --0.993254482746,1.73385310173,4.45924949646 --1.00722908974,1.73386526108,4.45382738113 --1.02320420742,1.73787713051,4.46042585373 --1.03817784786,1.73788976669,4.45698928833 --1.04815506935,1.73190045357,4.43859386444 --1.06812798977,1.74191367626,4.45816993713 --1.07211720943,1.73691868782,4.44597959518 --1.08609259129,1.73693037033,4.44257116318 --1.10206663609,1.73994278908,4.44514846802 --1.11604213715,1.73995447159,4.44174051285 --1.13001716137,1.73996627331,4.4373254776 --1.14998996258,1.74897944927,4.45490121841 --1.14998030663,1.73898386955,4.42770957947 --1.16595494747,1.74199593067,4.43129730225 --1.1869276762,1.75200903416,4.45187282562 --1.19390523434,1.74201953411,4.42246818542 --1.21087920666,1.74603199959,4.4280462265 --1.22585463524,1.74804353714,4.42864370346 --1.23883032799,1.74605512619,4.4212346077 --1.24681735039,1.74806118011,4.42202425003 --1.26179182529,1.74907338619,4.41959905624 --1.27876722813,1.75408506393,4.42820644379 --1.29074251652,1.75109660625,4.41578626633 --1.3077173233,1.75510847569,4.42237997055 --1.31869316101,1.75111997128,4.40696191788 --1.33366835117,1.75213158131,4.40655517578 --1.34665489197,1.76113808155,4.42535877228 --1.35663020611,1.75514960289,4.4049243927 --1.3706060648,1.75516092777,4.40152215958 --1.3885807991,1.76117289066,4.41112136841 --1.40155625343,1.76018440723,4.40270423889 --1.41153264046,1.75519549847,4.38529062271 --1.42251849174,1.75920212269,4.39407253265 --1.43649446964,1.76021337509,4.39067173004 --1.45146965981,1.76122510433,4.38926172256 --1.46344566345,1.75923633575,4.3788523674 --1.48141920567,1.76424872875,4.38442564011 --1.49639451504,1.76526033878,4.38301753998 --1.51436960697,1.77127206326,4.39162111282 --1.51535797119,1.76327729225,4.36939430237 --1.52933347225,1.76328873634,4.36498594284 --1.55030822754,1.77330076694,4.3825969696 --1.55928492546,1.76731157303,4.36318206787 --1.57225978374,1.76532328129,4.35375404358 --1.58923447132,1.76933503151,4.35734319687 --1.60220944881,1.76734673977,4.34791517258 --1.60819780827,1.76735210419,4.34371852875 --1.62717199326,1.77336406708,4.3523068428 --1.6391479969,1.77037537098,4.34189462662 --1.65312385559,1.77138650417,4.33748912811 --1.66410052776,1.76839733124,4.32508230209 --1.67907571793,1.77040886879,4.32266950607 --1.68806290627,1.7724148035,4.32546520233 --1.70703709126,1.7784267664,4.33305215836 --1.7170137167,1.7734375,4.31763982773 --1.7309885025,1.77344918251,4.31121444702 --1.74796450138,1.77846038342,4.31582641602 --1.75694048405,1.77247142792,4.29639530182 --1.77391588688,1.7764827013,4.29999780655 --1.78190290928,1.77748882771,4.29878091812 --1.79587948322,1.77849948406,4.29538869858 --1.80985450745,1.77851104736,4.28896474838 --1.82483005524,1.77952229977,4.28655862808 --1.83680617809,1.7785333395,4.27614212036 --1.84978222847,1.77754437923,4.26873254776 --1.87475514412,1.78955698013,4.28932619095 --1.8697463274,1.77756083012,4.25912189484 --1.88972043991,1.78457272053,4.26771259308 --1.9026966095,1.78358364105,4.26030397415 --1.91467189789,1.78159487247,4.24887514114 --1.93264663219,1.7856066227,4.25246524811 --1.94762325287,1.7886172533,4.25107526779 --1.95261096954,1.78562295437,4.24285697937 --1.9635874033,1.78363358974,4.23044157028 --1.98356223106,1.79064524174,4.23904275894 --1.99153900146,1.78465569019,4.21961975098 --2.01351261139,1.79266786575,4.23120975494 --2.02348995209,1.78967809677,4.21780633926 --2.03646564484,1.78868913651,4.20938682556 --2.04645347595,1.79269480705,4.21419715881 --2.06142926216,1.79470574856,4.21078872681 --2.07140541077,1.7907166481,4.19535923004 --2.08638095856,1.79172766209,4.1919503212 --2.10235714912,1.79473853111,4.19155454636 --2.11433315277,1.79374945164,4.18113565445 --2.12830924988,1.7947602272,4.17572832108 --2.13729596138,1.79576635361,4.17550706863 --2.14727377892,1.79377639294,4.16311120987 --2.16524839401,1.7967877388,4.16469573975 --2.17422580719,1.79379808903,4.14928483963 --2.19320034981,1.79880964756,4.15287208557 --2.20517778397,1.79781973362,4.1444773674 --2.21216487885,1.79782557487,4.1402554512 --2.22614121437,1.79883623123,4.13485097885 --2.24211668968,1.80084741116,4.13243722916 --2.25509309769,1.80085790157,4.12503194809 --2.27306818962,1.80586910248,4.12662363052 --2.28804397583,1.80687999725,4.12221097946 --2.30501961708,1.80989098549,4.12180376053 --2.3070089817,1.80589580536,4.10959672928 --2.32098484039,1.80690658092,4.10318183899 --2.33795976639,1.80991780758,4.10176324844 --2.34993672371,1.80892825127,4.09235620499 --2.36191344261,1.80893850327,4.08294916153 --2.37788915634,1.81094932556,4.08054304123 --2.39286541939,1.81195998192,4.07613372803 --2.39685368538,1.80996525288,4.06691598892 --2.41283035278,1.81297564507,4.06552505493 --2.4298055172,1.81598675251,4.06411170959 --2.44478106499,1.81799757481,4.05869150162 --2.46175742149,1.82100820541,4.0582947731 --2.4737329483,1.82001900673,4.04686117172 --2.48172187805,1.82102406025,4.04667520523 --2.49569749832,1.82203483582,4.03925180435 --2.5186727047,1.83004593849,4.04886198044 --2.52765059471,1.82705581188,4.03445577621 --2.54362630844,1.83006632328,4.03104543686 --2.56859898567,1.83907854557,4.04061698914 --2.57557749748,1.83408808708,4.02321338654 --2.59056425095,1.84109401703,4.03301620483 --2.59854197502,1.83710384369,4.01660346985 --2.61351823807,1.83911430836,4.01119089127 --2.62449526787,1.83712434769,3.99978160858 --2.65346908569,1.85013604164,4.01739263535 --2.6554479599,1.84214532375,3.99096608162 --2.66942405701,1.84215569496,3.98354887962 --2.68241167068,1.84816110134,3.99036192894 --2.69938755035,1.85117173195,3.98795390129 --2.71336388588,1.85118210316,3.98053908348 --2.70634555817,1.83719015121,3.94212412834 --2.72032165527,1.83820044994,3.93470668793 --2.73329782486,1.83821094036,3.92528152466 --2.74128675461,1.83921587467,3.92408871651 --2.7582628727,1.84222638607,3.92168307304 --2.76724052429,1.84023606777,3.90726971626 --2.78021764755,1.84024620056,3.89886069298 --2.79419469833,1.84225606918,3.89246034622 --2.81217050552,1.84526669979,3.89105129242 --2.82114815712,1.84327626228,3.87663674355 --2.8301358223,1.84528172016,3.87542533875 --2.84111332893,1.84429144859,3.86401367188 --2.85509133339,1.84530103207,3.85863161087 --2.86606812477,1.84431111813,3.8462035656 --2.88204455376,1.84732139111,3.84179520607 --2.90002083778,1.85133159161,3.84039282799 --2.91199874878,1.85134124756,3.83099222183 --2.9209856987,1.85234689713,3.82876801491 --2.93096375465,1.85135626793,3.81636190414 --2.94794011116,1.85436654091,3.81295228004 --2.96891522408,1.86037731171,3.81454062462 --2.98289275169,1.86138689518,3.80814862251 --3.00086903572,1.86539721489,3.8057384491 --3.01785564423,1.87240290642,3.81554603577 --3.0388302803,1.87741374969,3.81612634659 --3.03281140327,1.86542201042,3.78169488907 --3.04878926277,1.86843144894,3.77831363678 --3.05976724625,1.86844098568,3.76690459251 --3.07174444199,1.86845064163,3.75649118423 --3.0817220211,1.86646020412,3.74306917191 --3.09170985222,1.86846554279,3.74286365509 --3.10568737984,1.87047505379,3.73545980453 --3.12566328049,1.87548542023,3.73505187035 --3.12664270401,1.86849415302,3.71062779427 --3.15061879158,1.87650430202,3.71624183655 --3.15459799767,1.87151312828,3.69582223892 --3.15957736969,1.86652195454,3.67741465569 --3.16156697273,1.86452639103,3.66720294952 --3.18854212761,1.87453687191,3.67581319809 --3.18552207947,1.86454546452,3.64637494087 --3.20449876785,1.8685554266,3.64497661591 --3.22747516632,1.87656533718,3.64858746529 --3.22745537758,1.86857378483,3.62417078018 --3.24243283272,1.87158322334,3.61776828766 --3.25442051888,1.87458837032,3.61956620216 --3.26239871979,1.87259757519,3.6041457653 --3.27437663078,1.87260699272,3.59373378754 --3.29735183716,1.87961733341,3.59531855583 --3.29233431816,1.86962485313,3.56692147255 --3.31131005287,1.87463510036,3.56349730492 --3.32029891014,1.87663972378,3.56230425835 --3.32427930832,1.87164795399,3.54390573502 --3.34525465965,1.87765836716,3.54248166084 --3.36123251915,1.88066768646,3.53708386421 --3.36121296883,1.87367594242,3.51366996765 --3.37818980217,1.87668561935,3.50825405121 --3.4021654129,1.88369572163,3.51085066795 --3.40315580368,1.88169968128,3.5006506443 --3.41113424301,1.87970876694,3.48522639275 --3.43011164665,1.88371825218,3.48283076286 --3.43109154701,1.87772655487,3.46040987968 --3.44706988335,1.88073563576,3.45501708984 --3.47604513168,1.89174592495,3.46262192726 --3.47702503204,1.88575422764,3.44019889832 --3.48101472855,1.88475847244,3.43299531937 --3.49499249458,1.88676762581,3.42458748817 --3.50097227097,1.8837761879,3.40817928314 --3.51594948769,1.88578557968,3.39975380898 --3.53292775154,1.88979446888,3.39536738396 --3.54190611839,1.88780355453,3.38094067574 --3.54588603973,1.88381183147,3.36252951622 --3.566873312,1.89281690121,3.3733549118 --3.56885313988,1.88782536983,3.35192322731 --3.57683253288,1.88683390617,3.33751344681 --3.6068072319,1.89684414864,3.34410691261 --3.59978985786,1.88685131073,3.31570029259 --3.60776948929,1.88585996628,3.30128955841 --3.6317551136,1.89586555958,3.31309151649 --3.63373565674,1.89087378979,3.2926735878 --3.65371251106,1.89588308334,3.28926253319 --3.65869307518,1.89289104939,3.27286696434 --3.66967153549,1.89289999008,3.26044225693 --3.68065142632,1.89390814304,3.25005626678 --3.69562911987,1.8959171772,3.24163985252 --3.69461941719,1.89292120934,3.22942399979 --3.71659755707,1.89893007278,3.2290430069 --3.72157716751,1.89593827724,3.2116253376 --3.73255586624,1.89594709873,3.19920134544 --3.74453496933,1.89695560932,3.18879985809 --3.75451421738,1.89696395397,3.17639327049 --3.77049231529,1.89997267723,3.16898345947 --3.77948188782,1.90197706223,3.16679215431 --3.78246283531,1.89898478985,3.14838552475 --3.79444146156,1.89899349213,3.13696551323 --3.81441950798,1.90500223637,3.13357114792 --3.82139921188,1.90301036835,3.11815643311 --3.83737778664,1.90601909161,3.11075139046 --3.84435749054,1.90502715111,3.09533596039 --3.85534620285,1.90803170204,3.09413504601 --3.86032629013,1.90503978729,3.07671189308 --3.8743057251,1.90704810619,3.06832242012 --3.8802857399,1.90505611897,3.05190205574 --3.89426445961,1.90706467628,3.04249310493 --3.90524411201,1.90807271004,3.03109288216 --3.91922330856,1.91008102894,3.02168536186 --3.9212141037,1.90808475018,3.0134909153 --3.94019126892,1.9130936861,3.00706553459 --3.94517207146,1.91110146046,2.99065995216 --3.95115303993,1.90810906887,2.97525858879 --3.97213053703,1.91411793232,2.97084569931 --3.97911071777,1.91312587261,2.95542836189 --3.98510074615,1.91412985325,2.95023179054 --3.98708224297,1.91013717651,2.93182992935 --4.00106143951,1.91214549541,2.92242670059 --4.02003955841,1.91715407372,2.9160091877 --4.0220208168,1.91316139698,2.897605896 --4.03300046921,1.91416954994,2.8851878643 --4.04498100281,1.91517722607,2.87479686737 --4.04997062683,1.9151815176,2.86757516861 --4.06794929504,1.92018973827,2.8611779213 --4.07592964172,1.91919744015,2.84676527977 --4.0839099884,1.91820526123,2.83235239983 --4.09189033508,1.91721308231,2.81793904305 --4.10986948013,1.92222106457,2.81154608727 --4.12784910202,1.92622888088,2.80515503883 --4.12683963776,1.9232326746,2.79393792152 --4.1498169899,1.93024134636,2.78951787949 --4.16879701614,1.93524897099,2.78413724899 --4.18277645111,1.93725681305,2.77372503281 --4.18275785446,1.93326425552,2.75330281258 --4.19973659515,1.93727231026,2.74489045143 --4.22371578217,1.94428014755,2.74250817299 --4.24170446396,1.95128428936,2.74531817436 --4.27867937088,1.96429312229,2.74990725517 --4.2416677475,1.94229900837,2.7044711113 --4.25664758682,1.94530665874,2.69507098198 --4.25462961197,1.94031393528,2.67365074158 --4.29760551453,1.95632219315,2.68327307701 --4.32958221436,1.9673306942,2.6838593483 --4.34757137299,1.97433447838,2.68668031693 --4.31455850601,1.95434045792,2.64525341988 --4.30454206467,1.94534742832,2.61883068085 --4.3395190239,1.95835578442,2.62142562866 --4.37149715424,1.969363451,2.62304377556 --4.37547826767,1.96737074852,2.60562729836 --4.36246204376,1.95637750626,2.57719659805 --4.34545707703,1.94638001919,2.55800914764 --4.37943410873,1.95838820934,2.55960726738 --4.39141464233,1.96039569378,2.54719185829 --4.4133939743,1.96740305424,2.54180002213 --4.39237928391,1.95240950584,2.5093755722 --4.38636255264,1.94641637802,2.48594999313 --4.41035079956,1.95542025566,2.49177455902 --4.44132804871,1.96642827988,2.49035978317 --4.46430778503,1.97343564034,2.4849627018 --4.43529415131,1.95544171333,2.44853973389 --4.42527914047,1.94744813442,2.42413663864 --4.45125722885,1.95545578003,2.41972470284 --4.4672369957,1.95946323872,2.40930700302 --4.46222925186,1.95546650887,2.39710378647 --4.48620843887,1.96247386932,2.39170002937 --4.47619342804,1.95448029041,2.36729097366 --4.49517250061,1.95948755741,2.35888361931 --4.5011548996,1.95849442482,2.34347915649 --4.50613689423,1.95750129223,2.32706356049 --4.50711917877,1.95450806618,2.3086502552 --4.51211071014,1.95551145077,2.30245709419 --4.5200920105,1.9555182457,2.28804969788 --4.52907466888,1.95552492142,2.27465319633 --4.5370554924,1.95553207397,2.25922369957 --4.55303573608,1.95953905582,2.24881458282 --4.54402017593,1.95254564285,2.22540020943 --4.56100082397,1.95655226707,2.21600294113 --4.56599235535,1.95755553246,2.2098107338 --4.57497406006,1.95856249332,2.19539308548 --4.5639591217,1.94956862926,2.17199611664 --4.57993888855,1.95357584953,2.16056728363 --4.59492063522,1.95758235455,2.15017342567 --4.58390569687,1.94958865643,2.12677145004 --4.58588838577,1.94659519196,2.10936117172 --4.59287834167,1.94859886169,2.10314702988 --4.59486150742,1.94660532475,2.08573555946 --4.58184671402,1.9376116991,2.06132411957 --4.60782575607,1.94561874866,2.05490541458 --4.61080884933,1.94362509251,2.03850483894 --4.60979270935,1.94063150883,2.02009916306 --4.62978124619,1.94763505459,2.01988816261 --4.62676525116,1.94364142418,2.0004799366 --4.64474630356,1.94864785671,1.99108421803 --4.65172815323,1.94865441322,1.975664258 --4.65771198273,1.9486604929,1.96127808094 --4.65969514847,1.94666695595,1.94386267662 --4.67667627335,1.95067346096,1.93345820904 --4.66766881943,1.94567668438,1.92024600506 --4.67965126038,1.94768285751,1.90784585476 --4.67563438416,1.94368958473,1.8874181509 --4.67861747742,1.94169569016,1.87101352215 --4.68860054016,1.94370210171,1.85761022568 --4.67558526993,1.93470835686,1.83419573307 --4.68756771088,1.93771457672,1.82179605961 --4.69055843353,1.93771791458,1.81357824802 --4.68654298782,1.93272411823,1.79416692257 --4.69552612305,1.93473017216,1.78077292442 --4.71050691605,1.93773663044,1.76834702492 --4.71149110794,1.93574261665,1.75195789337 --4.71047496796,1.93274891376,1.73353898525 --4.72445774078,1.93675470352,1.72214794159 --4.71744966507,1.93175816536,1.70992600918 --4.71943378448,1.9307641983,1.69352507591 --4.73541545868,1.93477022648,1.68211758137 --4.73240041733,1.93177628517,1.66371333599 --4.73838329315,1.93178248405,1.6483001709 --4.74736595154,1.93278861046,1.63388490677 --4.7343506813,1.92479491234,1.61146867275 --4.7423415184,1.92679798603,1.6052544117 --4.75632476807,1.93080365658,1.59386813641 --4.7563085556,1.92880964279,1.57645761967 --4.75129318237,1.92381596565,1.55704021454 --4.77027511597,1.92982172966,1.54663813114 --4.76225948334,1.92382788658,1.52621972561 --4.76524448395,1.92383360863,1.51082992554 --4.78223419189,1.92883646488,1.50761783123 --4.78421831131,1.92784237862,1.49121260643 --4.7802028656,1.92384839058,1.4728064537 --4.79918479919,1.92985415459,1.46138656139 --4.80416870117,1.92985999584,1.44598162174 --4.80815267563,1.92886555195,1.43058466911 --4.82713508606,1.93487119675,1.41916954517 --4.81712770462,1.92987453938,1.40695333481 --4.81811237335,1.92888021469,1.39055418968 --4.81609678268,1.92588615417,1.37315261364 --4.81608104706,1.92389202118,1.35573494434 --4.81706476212,1.9218981266,1.33830904961 --4.84804725647,1.93290269375,1.33193492889 --4.83703231812,1.9269092083,1.3104981184 --4.8360247612,1.92491197586,1.302308321 --4.8420085907,1.92591762543,1.28689539433 --4.83399343491,1.92092370987,1.26748216152 --4.84897708893,1.92492890358,1.25508058071 --4.86196041107,1.9289342165,1.24166953564 --4.8529458046,1.92294037342,1.22226059437 --4.8529381752,1.9219430685,1.2140622139 --4.8639216423,1.92494857311,1.19964087009 --4.86190605164,1.92195439339,1.18223202229 --4.87988996506,1.92795920372,1.17084085941 --4.88087415695,1.92696499825,1.15341222286 --4.88785886765,1.92797029018,1.1390196085 --4.87984371185,1.92297637463,1.11959695816 --4.89983463287,1.92997837067,1.11639750004 --4.903819561,1.92998361588,1.10099983215 --4.89180469513,1.92398989201,1.08057427406 --4.90978956223,1.92899441719,1.06919145584 --4.9067735672,1.9270004034,1.05075979233 --4.90675878525,1.92500579357,1.03435981274 --4.91774272919,1.92801094055,1.01994597912 --4.92273521423,1.92901349068,1.01274251938 --4.92472076416,1.92901849747,0.997355818748 --4.9327044487,1.93002390862,0.981935918331 --4.93269014359,1.92902910709,0.965535163879 --4.94167423248,1.93103444576,0.950110673904 --4.93965864182,1.92903995514,0.932694911957 --4.94664430618,1.93004488945,0.91830688715 --4.95163679123,1.93204724789,0.911105155945 --4.95362138748,1.93105268478,0.894693374634 --4.96760654449,1.93505704403,0.881296515465 --4.96359109879,1.93206298351,0.862864494324 --4.979575634,1.93806743622,0.849459826946 --4.98056077957,1.9370726347,0.833053469658 --4.98054647446,1.93507778645,0.816651701927 --4.9855389595,1.93708002567,0.809452295303 --4.99252414703,1.93808495998,0.794043242931 --5.00050926208,1.94108986855,0.778630077839 --4.99849414825,1.93809533119,0.761211812496 --5.00248003006,1.93910002708,0.74581682682 --5.01646471024,1.94410455227,0.731404900551 --5.01845741272,1.94410705566,0.723195493221 --5.01544380188,1.94111216068,0.706805706024 --5.02542829514,1.94411683083,0.691387593746 --5.02841377258,1.94412183762,0.674973130226 --5.03439950943,1.94612646103,0.659572124481 --5.04638528824,1.95013058186,0.645174264908 --5.04337072372,1.94713592529,0.627758145332 --5.05535650253,1.95114004612,0.613362133503 --5.05134916306,1.94914293289,0.604150176048 --5.06833457947,1.95514678955,0.589738249779 --5.05931997299,1.95015251637,0.571316957474 --5.07430696487,1.95615613461,0.557939231396 --5.0732922554,1.95416140556,0.540515363216 --5.09327840805,1.96216452122,0.527124643326 --5.08826446533,1.95916998386,0.509713709354 --5.0892572403,1.95917236805,0.501509666443 --5.10324239731,1.96317625046,0.486091345549 --5.10322856903,1.9621809721,0.469689965248 --5.13421487808,1.974183321,0.457301825285 --5.11420106888,1.96518969536,0.437881350517 --5.13518714905,1.97319281101,0.423474609852 --5.13417959213,1.97219562531,0.414252221584 --5.13916683197,1.97419965267,0.39886417985 --5.12815237045,1.96820545197,0.38044077158 --5.14813899994,1.97620844841,0.36604231596 --5.13912534714,1.9712138176,0.34863781929 --5.16511154175,1.98121631145,0.33422985673 --5.14409732819,1.97222304344,0.314799666405 --5.1580915451,1.97722387314,0.308620303869 --5.15607738495,1.9762288332,0.291198909283 --5.15706396103,1.97623324394,0.274796336889 --5.16605043411,1.97923719883,0.258379131556 --5.18403673172,1.98624002934,0.242972403765 --5.16702413559,1.97824597359,0.225576713681 --5.17801094055,1.98224973679,0.209158629179 --5.17800426483,1.98225188255,0.200958564878 --5.17799043655,1.98125660419,0.183533623815 --5.17497730255,1.98026120663,0.167137309909 --5.17996406555,1.98126518726,0.150730237365 --5.17495059967,1.9792702198,0.133310750127 --5.17293787003,1.97727477551,0.116912230849 --5.17692470551,1.97927880287,0.100506387651 --5.17791795731,1.97928118706,0.0912797674537 --5.16890478134,1.97528624535,0.0748871639371 --5.16989135742,1.9752907753,0.0574591718614 --5.17487859726,1.97729468346,0.0410530418158 --5.1768655777,1.97729873657,0.0246499683708 --5.17185258865,1.9753036499,0.00722616212443 --5.16383934021,1.97130870819,-0.00917151663452 --5.16383266449,1.97131085396,-0.0173730291426 --5.16782045364,1.97331464291,-0.0337779782712 --5.1798081398,1.97731769085,-0.0501848869026 --5.15779447556,1.96832442284,-0.0676058977842 --5.17278194427,1.9743270874,-0.0840126350522 --5.17376947403,1.97433114052,-0.100415304303 --5.19375753403,1.98333287239,-0.116818934679 --5.16974973679,1.97333800793,-0.126044616103 --5.1717376709,1.97434186935,-0.142447516322 --5.16872406006,1.97234666348,-0.159875839949 --5.16171121597,1.96935153008,-0.176280647516 --5.16669893265,1.9713549614,-0.192682728171 --5.16368627548,1.97035944462,-0.20908729732 --5.16667366028,1.97136330605,-0.226514548063 --5.16166734695,1.96936607361,-0.234718829393 --5.15965509415,1.9683701992,-0.251123666763 --5.1606426239,1.96937417984,-0.267526984215 --5.15863037109,1.96837842464,-0.28393214941 --5.16461801529,1.97138178349,-0.301356315613 --5.1606054306,1.96938633919,-0.317763209343 --5.15959310532,1.9693903923,-0.334167927504 --5.15758705139,1.96839261055,-0.342371761799 --5.15757417679,1.96839678288,-0.359800696373 --5.16756296158,1.97339916229,-0.376192569733 --5.16155052185,1.97140395641,-0.392603158951 --5.157538414,1.96940839291,-0.409011662006 --5.15452575684,1.96841263771,-0.425419420004 --5.15851974487,1.97041416168,-0.434640586376 --5.15550756454,1.96941840649,-0.451048463583 --5.15649557114,1.9704220295,-0.467450261116 --5.16148376465,1.97242534161,-0.484869837761 --5.14747142792,1.96743094921,-0.500272572041 --5.15746021271,1.9714332819,-0.517682433128 --5.15844869614,1.97243690491,-0.53408318758 --5.15244197845,1.97043955326,-0.542296528816 --5.14942979813,1.96944379807,-0.558705508709 --5.14141702652,1.96644878387,-0.57512563467 --5.1524066925,1.97145080566,-0.592529535294 --5.14039325714,1.96745646,-0.608959853649 --5.14638280869,1.97045898438,-0.625348508358 --5.14737081528,1.97146260738,-0.64277356863 --5.14436483383,1.97046482563,-0.650982260704 --5.1413526535,1.96946907043,-0.667392194271 --5.14334154129,1.97147214413,-0.68378931284 --5.14233016968,1.97147583961,-0.700193881989 --5.1383190155,1.97047996521,-0.716606974602 --5.13130664825,1.96848475933,-0.733029305935 --5.139295578,1.97148692608,-0.750432252884 --5.13128948212,1.96848988533,-0.75763207674 --5.1422791481,1.97449171543,-0.776049971581 --5.13126659393,1.97049689293,-0.791460633278 --5.1292552948,1.97050070763,-0.807868421078 --5.12024259567,1.96750581264,-0.824299633503 --5.13123321533,1.97250723839,-0.841688334942 --5.12922143936,1.97251093388,-0.858095765114 --5.13121652603,1.97451233864,-0.867314040661 --5.12820482254,1.97351610661,-0.883724570274 --5.12519359589,1.97352004051,-0.900135576725 --5.11418104172,1.96952533722,-0.915551960468 --5.11716985703,1.97152805328,-0.932965457439 --5.11715936661,1.97253131866,-0.949365198612 --5.11714887619,1.97353434563,-0.965764522552 --5.12814474106,1.97853410244,-0.975969195366 --5.10713100433,1.97154116631,-0.990404486656 --5.11412143707,1.97454309464,-1.00779879093 --5.11711120605,1.97754573822,-1.02520930767 --5.09509706497,1.96855282784,-1.03862833977 --5.09008550644,1.96855700016,-1.05505001545 --5.10207700729,1.97455787659,-1.07344424725 --5.08206892014,1.96656310558,-1.07866001129 --5.09106016159,1.97156453133,-1.09706687927 --5.08604812622,1.97056853771,-1.11348843575 --5.07403612137,1.96657395363,-1.12789440155 --5.07302570343,1.9675770998,-1.144297719 --5.08701753616,1.97457742691,-1.1637005806 --5.07300519943,1.96958315372,-1.17811799049 --5.05999755859,1.96558713913,-1.18433356285 --5.06598806381,1.96858906746,-1.20274972916 --5.06297683716,1.96859252453,-1.21916246414 --5.04596424103,1.96259880066,-1.23257541656 --5.06095647812,1.97059881687,-1.25299096107 --5.03594207764,1.96160674095,-1.26440048218 --5.04493904114,1.96560633183,-1.2745988369 --5.03292655945,1.96261155605,-1.28901338577 --5.01591348648,1.9566180706,-1.3024327755 --5.02590513229,1.96261882782,-1.32184696198 --5.02189397812,1.96262252331,-1.33826684952 --5.01688337326,1.96162629128,-1.35366773605 --5.00987243652,1.95963060856,-1.36908102036 --5.01486825943,1.96263086796,-1.37929821014 --4.99485445023,1.95663809776,-1.39171767235 --4.99884605408,1.95963990688,-1.40911388397 --4.99283504486,1.95864379406,-1.4245223999 --4.98082256317,1.95464920998,-1.43894469738 --4.98181295395,1.95665168762,-1.45635867119 --4.98180341721,1.95865428448,-1.47377836704 --4.97079610825,1.95465803146,-1.47897410393 --4.96178483963,1.95266270638,-1.49440443516 --4.96677684784,1.95666408539,-1.5117906332 --4.94776344299,1.95067095757,-1.52421581745 --4.95075368881,1.9536730051,-1.54263937473 --4.94574356079,1.95267653465,-1.55804347992 --4.9377322197,1.95068109035,-1.57346916199 --4.92572021484,1.94768631458,-1.58687508106 --4.9327173233,1.95168590546,-1.5970710516 --4.9127035141,1.94469308853,-1.60848665237 --4.90969371796,1.9456962347,-1.62490296364 --4.90968418121,1.94769871235,-1.64232134819 --4.90267372131,1.94670295715,-1.6577423811 --4.89166212082,1.94370794296,-1.67114508152 --4.89665842056,1.94670796394,-1.68135249615 --4.88764762878,1.94471251965,-1.69576513767 --4.87663555145,1.94171762466,-1.71019411087 --4.88262844086,1.94671845436,-1.72858834267 --4.86161375046,1.93972599506,-1.74002432823 --4.85660362244,1.93972945213,-1.75543224812 --4.86259651184,1.94473040104,-1.77484869957 --4.849588871,1.93973469734,-1.77905225754 --4.83657693863,1.93574023247,-1.79145276546 --4.83456754684,1.93774306774,-1.80888557434 --4.82955741882,1.93774652481,-1.82429397106 --4.82354688644,1.93675029278,-1.83971095085 --4.81953763962,1.93775343895,-1.85511124134 --4.80252456665,1.93276000023,-1.86652600765 --4.80352020264,1.93376088142,-1.87573683262 --4.80851316452,1.93876171112,-1.89515590668 --4.78949975967,1.93276882172,-1.90556657314 --4.78949117661,1.93477082253,-1.92298018932 --4.78047990799,1.93277537823,-1.93740081787 --4.77547025681,1.93277871609,-1.95281028748 --4.76445913315,1.93078374863,-1.96622633934 --4.76045322418,1.92978584766,-1.97343289852 --4.75444316864,1.92978954315,-1.9888522625 --4.74543237686,1.92879402637,-2.00327563286 --4.74942588806,1.93279480934,-2.02167344093 --4.72941160202,1.92680239677,-2.03210520744 --4.72540235519,1.92780530453,-2.0475063324 --4.72339391708,1.92880785465,-2.06391167641 --4.72038888931,1.92880964279,-2.07213354111 --4.70937776566,1.92681467533,-2.08555459976 --4.70736885071,1.92781698704,-2.10195922852 --4.69635772705,1.92582201958,-2.11538100243 --4.68834686279,1.92482614517,-2.12979769707 --4.67933702469,1.92383050919,-2.14320111275 --4.67632818222,1.92483305931,-2.15961551666 --4.66532087326,1.92183732986,-2.16382408142 --4.66231203079,1.92283987999,-2.18023848534 --4.65630245209,1.92284333706,-2.19565987587 --4.63628816605,1.9168510437,-2.2050845623 --4.64628410339,1.92384970188,-2.22648119926 --4.62927055359,1.91885650158,-2.23690009117 --4.63126420975,1.92285740376,-2.25530791283 --4.62325811386,1.92086064816,-2.26051306725 --4.60824537277,1.91686677933,-2.27193689346 --4.60723733902,1.91886878014,-2.28935217857 --4.60122776031,1.91887223721,-2.30477404594 --4.5892162323,1.91687738895,-2.31719136238 --4.58320713043,1.91688072681,-2.33159017563 --4.57319688797,1.91588544846,-2.34501028061 --4.57519388199,1.91788554192,-2.35522413254 --4.55417919159,1.91189360619,-2.36365103722 --4.5511713028,1.9128960371,-2.38006353378 --4.54616212845,1.91389906406,-2.39547491074 --4.53615140915,1.9129036665,-2.40889692307 --4.52413988113,1.90990900993,-2.42131924629 --4.5181312561,1.90991222858,-2.4357187748 --4.51412630081,1.90991425514,-2.44293069839 --4.5091176033,1.9109171629,-2.45834207535 --4.49710607529,1.90892255306,-2.47076678276 --4.49209785461,1.90992534161,-2.4861779213 --4.49309158325,1.91292619705,-2.50458645821 --4.47807884216,1.90993249416,-2.51500177383 --4.46907186508,1.90693616867,-2.52022790909 --4.47506809235,1.91293513775,-2.540620327 --4.45505332947,1.90694320202,-2.5490527153 --4.44104146957,1.90394926071,-2.55945944786 --4.43703317642,1.90595173836,-2.57588148117 --4.41801929474,1.90095949173,-2.5843064785 --4.41801309586,1.90396046638,-2.60170078278 --4.41200733185,1.90296316147,-2.60791611671 --4.40199708939,1.90096771717,-2.62134432793 --4.39298725128,1.9009718895,-2.63476085663 --4.40198516846,1.90796947479,-2.65715169907 --4.37596797943,1.899979949,-2.66158127785 --4.3699593544,1.90098309517,-2.67700505257 --4.36395025253,1.9009860754,-2.69242835045 --4.34894132614,1.89599204063,-2.69262647629 --4.34293270111,1.8969950676,-2.70805096626 --4.3389248848,1.8979973793,-2.72344756126 --4.32091140747,1.89400494099,-2.73187279701 --4.31490278244,1.89500796795,-2.74729704857 --4.30889463425,1.89501094818,-2.76169776917 --4.29088020325,1.89101862907,-2.77114915848 --4.29187822342,1.89301860332,-2.78034067154 --4.29187250137,1.89701914787,-2.79874968529 --4.27285814285,1.89202713966,-2.80617165565 --4.26384878159,1.89103138447,-2.81959152222 --4.25984144211,1.89303350449,-2.83600974083 --4.24783086777,1.89103877544,-2.84640455246 --4.23081684113,1.8870459795,-2.85584878922 --4.239818573,1.8930426836,-2.8700363636 --4.21280050278,1.88405394554,-2.87246704102 --4.20979404449,1.88605570793,-2.88887023926 --4.21679258347,1.89405333996,-2.91228556633 --4.18777275085,1.88406538963,-2.91372799873 --4.18276548386,1.88606798649,-2.92913722992 --4.17975902557,1.88806951046,-2.94553804398 --4.17175245285,1.88607299328,-2.95076704025 --4.15273761749,1.88108122349,-2.95718169212 --4.15473413467,1.88608074188,-2.97759723663 --4.14172267914,1.88408637047,-2.9880130291 --4.13371372223,1.88408994675,-3.00142097473 --4.12770605087,1.88609278202,-3.01684308052 --4.11269378662,1.88309931755,-3.02626895905 --4.10568761826,1.88110244274,-3.03148531914 --4.10168075562,1.88310420513,-3.04789876938 --4.08666849136,1.88011085987,-3.0563044548 --4.08566379547,1.88411128521,-3.07471466064 --4.10767173767,1.89910173416,-3.10911726952 --4.10066413879,1.90010464191,-3.12352824211 --4.06063747406,1.88512229919,-3.11597561836 --4.07864570618,1.89611434937,-3.13817167282 --4.07363939285,1.89811635017,-3.15357351303 --3.58020234108,1.87432670593,-3.68665385246 --3.56118679047,1.87033605576,-3.69007086754 --3.55918455124,1.87433540821,-3.70947670937 --3.55017709732,1.87533891201,-3.72289824486 --3.53216218948,1.87134766579,-3.72731781006 --3.52515649796,1.87135076523,-3.73254823685 --3.51614880562,1.87135434151,-3.74495029449 --3.50814199448,1.87335705757,-3.75937175751 --3.4861240387,1.86736822128,-3.75979614258 --3.47511458397,1.86737287045,-3.77121901512 --3.46710801125,1.86837565899,-3.7856400013 --3.45409727097,1.86738145351,-3.79404497147 --3.45509815216,1.87137985229,-3.80625224113 --3.43608212471,1.8663892746,-3.80968046188 --3.42907643318,1.86839139462,-3.82509970665 --3.41206240654,1.86539971828,-3.8305284977 --3.40505695343,1.86840176582,-3.84594750404 --3.39404821396,1.86840629578,-3.85737013817 --3.37703371048,1.86441469193,-3.86178255081 --3.37903571129,1.86841225624,-3.8749833107 --3.35501527786,1.86142516136,-3.87240791321 --3.35001182556,1.86542582512,-3.8908405304 --3.34100484848,1.86642897129,-3.90426015854 --3.31798505783,1.8604413271,-3.90268826485 --3.31598424911,1.86544013023,-3.92309403419 --3.31398320198,1.86743998528,-3.93331646919 --3.2889611721,1.85945379734,-3.92873430252 --3.28295707703,1.86245501041,-3.94514703751 --3.27094745636,1.86246025562,-3.95557332039 --3.25593495369,1.86046743393,-3.96198940277 --3.24392533302,1.86047255993,-3.97343444824 --3.23992323875,1.86447227001,-3.99183869362 --3.21490073204,1.8564863205,-3.98726773262 --3.20889592171,1.8564889431,-3.99248147011 --3.20789718628,1.86248672009,-4.01387548447 --3.18387556076,1.85450005531,-4.01132297516 --3.17286705971,1.855504632,-4.02274799347 --3.17286968231,1.86250138283,-4.04615211487 --3.14684557915,1.85351657867,-4.03957700729 --3.14284276962,1.85451769829,-4.0467839241 --3.12983226776,1.85452353954,-4.05621671677 --3.11582040787,1.85253024101,-4.06363582611 --3.10280990601,1.85153615475,-4.07205152512 --3.09780812263,1.85653614998,-4.09148645401 --3.0777900219,1.85154724121,-4.09089756012 --3.06277704239,1.84855473042,-4.09732294083 --3.06678318977,1.85554981232,-4.11554479599 --3.04676508904,1.85056102276,-4.11495876312 --3.04076194763,1.85456168652,-4.13237762451 --3.02474832535,1.85156989098,-4.13679170609 --3.01474118233,1.85257363319,-4.14921140671 --2.99672484398,1.84858345985,-4.15163707733 --2.99072217941,1.8525840044,-4.1690530777 --2.97770953178,1.84859192371,-4.16527080536 --2.96069478989,1.84560084343,-4.16971158981 --2.96169996262,1.85359609127,-4.19510412216 --2.93667602539,1.84561133385,-4.18853998184 --2.92666888237,1.84661495686,-4.20095920563 --2.92266893387,1.85161375999,-4.22137546539 --2.90064787865,1.84562695026,-4.21779918671 --2.89163947105,1.8436319828,-4.21901607513 --2.88563728333,1.84763228893,-4.23642635345 --2.86361646652,1.84164535999,-4.23387098312 --2.85561203957,1.84464728832,-4.24929285049 --2.84960985184,1.84864771366,-4.26670074463 --2.81857728958,1.83566856384,-4.2501282692 --2.81457805634,1.84166693687,-4.27155447006 --2.81257867813,1.84466612339,-4.28277444839 --2.78855443001,1.83668136597,-4.27519321442 --2.78856062889,1.84567642212,-4.30261945724 --2.77655100822,1.84568178654,-4.31101846695 --2.75452923775,1.8386951685,-4.30745887756 --2.74852776527,1.84269547462,-4.32486104965 --2.73751688004,1.83970201015,-4.3240981102 --2.71950030327,1.83671224117,-4.32552862167 --2.70749092102,1.8367177248,-4.33392953873 --2.70148992538,1.84171748161,-4.35336017609 --2.68247151375,1.83672893047,-4.35176992416 --2.66545557976,1.83373844624,-4.35419607162 --2.66045665741,1.8397371769,-4.3756313324 --2.64143753052,1.83374869823,-4.37404441833 --2.63443207741,1.83375203609,-4.37826824188 --2.62542724609,1.83675467968,-4.39167451859 --2.60941267014,1.83376324177,-4.39611005783 --2.59239697456,1.83077299595,-4.39854001999 --2.58339214325,1.83377528191,-4.41296005249 --2.57038235664,1.83378124237,-4.42138576508 --2.56237483025,1.8327858448,-4.4225897789 --2.55537319183,1.83678627014,-4.44000387192 --2.53635454178,1.83279788494,-4.43944120407 --2.52634882927,1.83480095863,-4.45286750793 --2.50933265686,1.83181095123,-4.45428752899 --2.496322155,1.8308172226,-4.46169900894 --2.48731851578,1.83481895924,-4.47814321518 --2.47230029106,1.82783055305,-4.46734714508 --2.463296175,1.8308327198,-4.48176240921 --2.44928479195,1.83083963394,-4.48919868469 --2.43527293205,1.82984662056,-4.49562120438 --2.414249897,1.82286095619,-4.48903274536 --2.41225743294,1.83185577393,-4.516456604 --2.39724421501,1.83086407185,-4.52087640762 --2.38723373413,1.82787036896,-4.52010631561 --2.37322235107,1.82787740231,-4.52653026581 --2.36021232605,1.82788336277,-4.53495740891 --2.35120820999,1.83088576794,-4.54835414886 --2.3381986618,1.83089148998,-4.55779314041 --2.32018017769,1.82690286636,-4.55620861053 --2.30917358398,1.82890665531,-4.56863975525 --2.30016422272,1.82691240311,-4.5678486824 --2.28414940834,1.82492184639,-4.57027053833 --2.2721414566,1.82592654228,-4.58171224594 --2.26113462448,1.82793068886,-4.59211587906 --2.24612116814,1.82593894005,-4.59654045105 --2.23110771179,1.82494711876,-4.60096549988 --2.22810959816,1.82794594765,-4.61319494247 --2.20508122444,1.81896352768,-4.60060167313 --2.20008587837,1.82696056366,-4.62402153015 --2.18807816505,1.82796514034,-4.63546037674 --2.17707204819,1.83096909523,-4.64687490463 --2.16706800461,1.83397138119,-4.66130018234 --2.15105271339,1.83098089695,-4.66372585297 --2.15506768227,1.84097158909,-4.68893432617 --2.1270301342,1.82799506187,-4.66736698151 --2.10600543022,1.82201039791,-4.65979957581 --2.09800481796,1.82601082325,-4.67720890045 -1.94482290745,1.76804101467,-3.91112303734 -1.94982385635,1.76504004002,-3.90235495567 -1.966843009,1.76904571056,-3.90573859215 -1.98085546494,1.7700483799,-3.90114426613 -1.99386513233,1.76905012131,-3.89356136322 -2.00988125801,1.77105426788,-3.89296674728 -2.01988577843,1.76805388927,-3.88037228584 -2.03089308739,1.7670545578,-3.87076640129 -2.04391026497,1.77206027508,-3.87898445129 -2.05090904236,1.7660574913,-3.86039423943 -2.06892895699,1.77106332779,-3.86379504204 -2.08193993568,1.77106559277,-3.85818815231 -2.09294724464,1.76906633377,-3.84858345985 -2.1029510498,1.7650655508,-3.83402013779 -2.12197327614,1.7710723877,-3.84040307999 -2.12296819687,1.76606929302,-3.82562208176 -2.13798260689,1.76807272434,-3.82302474976 -2.1519947052,1.76807558537,-3.81842899323 -2.1730196476,1.77508330345,-3.82682871819 -2.18102121353,1.77108180523,-3.81024670601 -2.19303011894,1.77008318901,-3.80165481567 -2.20003676414,1.77108490467,-3.80083632469 -2.21505069733,1.77208828926,-3.79724979401 -2.22405457497,1.76908779144,-3.78365492821 -2.24307513237,1.77409374714,-3.78706693649 -2.25308084488,1.77109408379,-3.77546977997 -2.26308679581,1.76909446716,-3.76387310028 -2.28210735321,1.77410030365,-3.76728272438 -2.29412198067,1.77910506725,-3.77446889877 -2.30112266541,1.77410340309,-3.75688529015 -2.31613636017,1.77510666847,-3.75329589844 -2.3301486969,1.77610945702,-3.74770975113 -2.34115576744,1.77411043644,-3.73712444305 -2.3541674614,1.77511298656,-3.73250055313 -2.36517477036,1.77411401272,-3.72191572189 -2.37318229675,1.77411592007,-3.7201321125 -2.39019942284,1.77812051773,-3.7205286026 -2.39920401573,1.77512049675,-3.70694160461 -2.41221475601,1.77512276173,-3.70034623146 -2.42823004723,1.77812683582,-3.69874668121 -2.44524693489,1.78113138676,-3.69815468788 -2.44924426079,1.77412867546,-3.67657279968 -2.46626543999,1.78313565254,-3.69075608253 -2.47226572037,1.77713418007,-3.6721777916 -2.48727989197,1.78013765812,-3.66956710815 -2.50029039383,1.7801399231,-3.66198563576 -2.51630592346,1.78314387798,-3.66038107872 -2.52931642532,1.78314614296,-3.65279889107 -2.53432011604,1.78214681149,-3.64798927307 -2.5473306179,1.78214907646,-3.64040732384 -2.55934023857,1.78215110302,-3.632802248 -2.57335209846,1.78315365314,-3.62622690201 -2.58836627007,1.78515744209,-3.62361216545 -2.59637022018,1.7821573019,-3.6090259552 -2.61438798904,1.78616213799,-3.60943031311 -2.61939120293,1.7851626873,-3.60363674164 -2.63740849495,1.78816723824,-3.60305523872 -2.64941835403,1.78816926479,-3.59544920921 -2.66343069077,1.7901724577,-3.5908396244 -2.67543983459,1.7891741991,-3.58126521111 -2.68344426155,1.78617429733,-3.56668305397 -2.70146203041,1.79117918015,-3.56806445122 -2.70746684074,1.79118025303,-3.56426119804 -2.72848796844,1.79718625546,-3.56767392159 -2.73749351501,1.79418694973,-3.55508208275 -2.73848938942,1.78618407249,-3.5305120945 -2.75650668144,1.7911888361,-3.53090548515 -2.76250886917,1.78618824482,-3.51333355904 -2.78352952003,1.79219424725,-3.51772451401 -2.77852106094,1.78519070148,-3.49794793129 -2.79353451729,1.7871941328,-3.49434065819 -2.80554461479,1.78719627857,-3.48575139046 -2.82656502724,1.79320204258,-3.48915433884 -2.83056569099,1.78820109367,-3.47056055069 -2.86360025406,1.80221176147,-3.48994684219 -2.85158395767,1.79020571709,-3.46216440201 -2.86459493637,1.791208148,-3.4545788765 -2.8846142292,1.79621362686,-3.45697116852 -2.88961601257,1.79121315479,-3.43938612938 -2.89762115479,1.78821372986,-3.42481517792 -2.92064356804,1.79622018337,-3.4302148819 -2.9296503067,1.79422140121,-3.418612957 -2.93565511703,1.7942224741,-3.41382622719 -2.94866609573,1.79522514343,-3.40623879433 -2.9566719532,1.79322600365,-3.39363408089 -2.96667957306,1.79122757912,-3.38107275963 -2.99270510674,1.80123496056,-3.39143776894 -2.98769640923,1.79023134708,-3.36088299751 -3.00371098518,1.79323494434,-3.35728645325 -3.00971603394,1.79323613644,-3.35249996185 -3.02072501183,1.7932382822,-3.34388875961 -3.02672886848,1.78923869133,-3.32731866837 -3.04474568367,1.79424321651,-3.32670688629 -3.05575442314,1.79324519634,-3.31613183022 -3.07176876068,1.79624903202,-3.31253170967 -3.08177709579,1.79525089264,-3.30193567276 -3.07576990128,1.78824818134,-3.28316140175 -3.08878111839,1.7892510891,-3.27655482292 -3.11180257797,1.79625701904,-3.27996563911 -3.11380290985,1.79125642776,-3.26037549973 -3.12881612778,1.79325985909,-3.25577092171 -3.15383911133,1.8012663126,-3.26117920876 -3.14983391762,1.79226410389,-3.23460245132 -3.15884184837,1.79426622391,-3.23281979561 -3.1728541851,1.79626941681,-3.22721147537 -3.17585587502,1.79126942158,-3.20862913132 -3.19186997414,1.79427313805,-3.20404100418 -3.20688319206,1.79627656937,-3.19845104218 -3.2128880024,1.79327762127,-3.18385481834 -3.23090386391,1.79728198051,-3.18224644661 -3.23490738869,1.79728269577,-3.17545819283 -3.24091243744,1.79428374767,-3.16086316109 -3.25392365456,1.7942866087,-3.15229034424 -3.26693511009,1.79628956318,-3.14469695091 -3.27394104004,1.79429101944,-3.13110375404 -3.28595161438,1.79429376125,-3.12251091003 -3.29896306992,1.79929685593,-3.12570261955 -3.29596042633,1.79129576683,-3.10015249252 -3.31597805023,1.79630053043,-3.09955596924 -3.34700489044,1.80830812454,-3.11093068123 -3.35901546478,1.80931067467,-3.10233354568 -3.3720266819,1.81031370163,-3.09473562241 -3.36602187157,1.80031216145,-3.06717562675 -3.38804078102,1.81031727791,-3.07935094833 -3.43207812309,1.8293274641,-3.10173583031 -3.61233282089,1.69241333008,-2.39175701141 -3.61734127998,1.69141638279,-2.37817406654 -3.63035368919,1.69342041016,-2.37058210373 -3.62335443497,1.68542194366,-2.34899401665 -3.62135601044,1.68242287636,-2.33920192719 -3.62736535072,1.68142616749,-2.32563972473 -3.63937711716,1.68343007565,-2.31803131104 -3.64038348198,1.67943274975,-2.30146074295 -3.64239001274,1.676435709,-2.2858839035 -3.65240120888,1.67743945122,-2.27629160881 -3.65240693092,1.67344212532,-2.25970864296 -3.66241550446,1.67644453049,-2.25791978836 -3.67542862892,1.67944860458,-2.25032567978 -3.67543435097,1.67545151711,-2.23374462128 -3.68344497681,1.67545521259,-2.22216916084 -3.68945360184,1.67445850372,-2.21056246758 -3.69446277618,1.67346191406,-2.19698929787 -3.70047211647,1.67246544361,-2.18440794945 -3.70747852325,1.67346739769,-2.1815931797 -3.70448327065,1.66847014427,-2.16302132607 -3.7214987278,1.67347466946,-2.15743684769 -3.73451185226,1.67547905445,-2.14886403084 -3.72751426697,1.66848134995,-2.12925934792 -3.7385263443,1.67048549652,-2.1196808815 -3.74853467941,1.67348778248,-2.11788439751 -3.74854135513,1.66949105263,-2.10131454468 -3.7555513382,1.66949486732,-2.08972549438 -3.75956010818,1.66749835014,-2.07614207268 -3.76857089996,1.66850209236,-2.06653213501 -3.77758216858,1.669506073,-2.05594754219 -3.78159093857,1.66750979424,-2.04236555099 -3.78259515762,1.66651153564,-2.0345852375 -3.7896053791,1.66651535034,-2.02299714088 -3.79661560059,1.66651916504,-2.01140880585 -3.78561782837,1.65752232075,-1.98786818981 -3.80163216591,1.66152656078,-1.98225736618 -3.81864738464,1.66653108597,-1.97665882111 -3.81265187263,1.66053438187,-1.95709180832 -3.8206589222,1.66253650188,-1.95428490639 -3.83167147636,1.66454076767,-1.94470250607 -3.83167886734,1.66154432297,-1.92911994457 -3.83868932724,1.66154837608,-1.91753327847 -3.84069752693,1.6585521698,-1.90295505524 -3.83970451355,1.6555557251,-1.88736200333 -3.85471892357,1.65856027603,-1.87978231907 -3.86272597313,1.66156244278,-1.87697184086 -3.85673141479,1.65556609631,-1.85741758347 -3.86674308777,1.65657031536,-1.84782016277 -3.88175749779,1.66057503223,-1.8402364254 -3.87776327133,1.65657842159,-1.8236335516 -3.87977194786,1.65358245373,-1.809060812 -3.88777971268,1.65658485889,-1.80527448654 -3.884786129,1.65158867836,-1.78868913651 -3.8897960186,1.65059268475,-1.77610456944 -3.9028096199,1.65359723568,-1.76751804352 -3.90381789207,1.65160131454,-1.75293445587 -3.91082906723,1.65160560608,-1.74134933949 -3.92484331131,1.65561020374,-1.7327735424 -3.9178442955,1.65061199665,-1.72198021412 -3.92485523224,1.65061628819,-1.71039521694 -3.93586802483,1.65362083912,-1.70080637932 -3.92887377739,1.64762496948,-1.6822334528 -3.93788576126,1.64862930775,-1.67164695263 -3.95590114594,1.65363395214,-1.66506302357 -3.95490884781,1.65063798428,-1.65045940876 -3.9449095726,1.64464020729,-1.63769102097 -3.9609246254,1.64964485168,-1.63010764122 -3.95493102074,1.64464914799,-1.61252784729 -3.95393896103,1.64165329933,-1.59792888165 -3.9719543457,1.64665794373,-1.591340065 -3.97596478462,1.64566254616,-1.57777428627 -3.9699716568,1.64066696167,-1.5602003336 -3.97997975349,1.64366936684,-1.55740249157 -3.9799888134,1.64167380333,-1.54281830788 -3.98299860954,1.63967847824,-1.5292429924 -3.99001026154,1.64068305492,-1.51765871048 -3.99602103233,1.64068746567,-1.50606286526 -4.00303268433,1.64169216156,-1.49447798729 -4.00903940201,1.64269459248,-1.48968625069 -4.00404691696,1.63869917393,-1.47310483456 -4.01005840302,1.6387039423,-1.46053719521 -4.02407169342,1.64170837402,-1.45291864872 -4.01507806778,1.63571321964,-1.43435263634 -4.02609205246,1.6387181282,-1.42378377914 -4.03110265732,1.63872253895,-1.41217684746 -4.02510547638,1.63472509384,-1.40239405632 -4.03011655807,1.63472998142,-1.38981628418 -4.04112911224,1.63673460484,-1.38021790981 -4.03713798523,1.63273978233,-1.36365759373 -4.04415035248,1.63374447823,-1.35207283497 -4.056163311,1.63674926758,-1.34248304367 -4.0531668663,1.6347515583,-1.33467936516 -4.06017875671,1.63575637341,-1.32309389114 -4.06819105148,1.63676130772,-1.31151819229 -4.0611987114,1.63176631927,-1.29493272305 -4.07521295547,1.63577127457,-1.2853603363 -4.08022499084,1.63577628136,-1.27278244495 -4.07023143768,1.62978160381,-1.25519990921 -4.07623815536,1.63078391552,-1.25040316582 -4.0982542038,1.63878822327,-1.24479067326 -4.08626079559,1.63079369068,-1.22622084618 -4.08727169037,1.62979924679,-1.21166324615 -4.09128284454,1.62980389595,-1.20004820824 -4.10329627991,1.63280904293,-1.18947970867 -4.10230636597,1.62981426716,-1.17490470409 -4.10131072998,1.62881672382,-1.16809821129 -4.10032129288,1.62682211399,-1.1535243988 -4.11533498764,1.63082671165,-1.14492344856 -4.11634635925,1.62983238697,-1.13036823273 -4.11835718155,1.62883734703,-1.11776471138 -4.13237142563,1.63284230232,-1.10818016529 -4.14138364792,1.63484704494,-1.09757900238 -4.11938381195,1.62385082245,-1.08282542229 -4.1263961792,1.6258559227,-1.07123720646 -4.13640880585,1.62786090374,-1.06064522266 -4.13842058182,1.62686645985,-1.04707241058 -4.14043140411,1.62687158585,-1.03447043896 -4.15344572067,1.62987673283,-1.02390110493 -4.14144802094,1.62388014793,-1.01312565804 -4.14846086502,1.62588524818,-1.0015360117 -4.15847396851,1.62789022923,-0.990940690041 -4.15148305893,1.62389600277,-0.975356459618 -4.15349435806,1.62290167809,-0.961786031723 -4.16950893402,1.62790620327,-0.953176915646 -4.16251850128,1.62391257286,-0.936625301838 -4.16852521896,1.62491500378,-0.931819498539 -4.17153692245,1.62492036819,-0.91922712326 -4.17955064774,1.62692606449,-0.90667206049 -4.18056106567,1.62593126297,-0.894065022469 -4.19557523727,1.62993621826,-0.884470880032 -4.17558240891,1.62094318867,-0.864920735359 -4.19659805298,1.62794756889,-0.857308328152 -4.19660377502,1.6269505024,-0.850516498089 -4.18961381912,1.62295663357,-0.834943950176 -4.19662714005,1.62396240234,-0.822380125523 -4.21964263916,1.63296675682,-0.814773857594 -4.20265054703,1.62397348881,-0.797196686268 -4.21666526794,1.62897861004,-0.786617219448 -4.21167516708,1.62498474121,-0.772032856941 -4.20768022537,1.6229878664,-0.764246344566 -4.21569347382,1.62499332428,-0.752656757832 -4.22270679474,1.62699902058,-0.740089833736 -4.22071743011,1.62400496006,-0.726497292519 -4.21972894669,1.62301087379,-0.712911188602 -4.22874164581,1.62501633167,-0.701325774193 -4.22074651718,1.62101995945,-0.692548811436 -4.22675991058,1.62302565575,-0.679975032806 -4.23177194595,1.62403106689,-0.668365120888 -4.236784935,1.62403678894,-0.655785143375 -4.22879505157,1.62004375458,-0.640222668648 -4.24381017685,1.62504887581,-0.629637002945 -4.23382043839,1.62005579472,-0.614065945148 -4.23482561111,1.62005841732,-0.608252704144 -4.25084066391,1.62506353855,-0.597669541836 -4.23685073853,1.61807084084,-0.581111311913 -4.23986291885,1.61807668209,-0.568520784378 -4.25087738037,1.62208223343,-0.55693924427 -4.24588871002,1.61908888817,-0.542369544506 -4.24490070343,1.61809527874,-0.528789877892 -4.26290893555,1.624096632,-0.525966346264 -4.24991941452,1.61810386181,-0.510391175747 -4.25493192673,1.619109869,-0.497809439898 -4.26594591141,1.62311530113,-0.486223101616 -4.25395679474,1.61712276936,-0.47065731883 -4.25796985626,1.61812865734,-0.458070635796 -4.27098417282,1.62213408947,-0.446490645409 -4.25898885727,1.61713850498,-0.437715321779 -4.26300191879,1.61814439297,-0.425128221512 -4.27201509476,1.62114989758,-0.413529843092 -4.25802612305,1.6141576767,-0.397964596748 -4.26503992081,1.61616361141,-0.38538891077 -4.28205442429,1.62216854095,-0.374787330627 -4.26605844498,1.61517322063,-0.366004735231 -4.2700715065,1.61617922783,-0.353416949511 -4.2860865593,1.622184515,-0.341838777065 -4.27709817886,1.61819183826,-0.327267318964 -4.27911090851,1.61819803715,-0.314671993256 -4.29312515259,1.62320327759,-0.303083181381 -4.27513551712,1.61521172523,-0.287518292665 -4.27614307404,1.6152150631,-0.280736237764 -4.2881565094,1.61922037601,-0.26913946867 -4.28416919708,1.6172273159,-0.255557507277 -4.28618240356,1.61723411083,-0.24199283123 -4.29519605637,1.62023949623,-0.230384707451 -4.28520774841,1.61524736881,-0.21582005918 -4.29722213745,1.62025260925,-0.204217746854 -4.31323051453,1.62625467777,-0.198439389467 -4.29024171829,1.61626374722,-0.182877540588 -4.2842540741,1.61327111721,-0.169295430183 -4.30426931381,1.62127590179,-0.157706543803 -4.29928159714,1.61828303337,-0.144126787782 -4.29129362106,1.61529064178,-0.130542248487 -4.30130767822,1.61829638481,-0.117960952222 -4.28531312943,1.61230158806,-0.11017934978 -4.29432725906,1.6153075695,-0.0975957363844 -4.30034065247,1.61731362343,-0.0850059241056 -4.30135345459,1.61732017994,-0.0724079832435 -4.29736709595,1.61532759666,-0.0588340759277 -4.29938077927,1.6153345108,-0.0452687479556 -4.30238771439,1.61633729935,-0.0394574962556 -4.29940080643,1.6153447628,-0.0258857998997 -4.30541467667,1.61735081673,-0.0132932756096 -4.29842758179,1.61435866356,0.000281396642094 -4.29744148254,1.6133658886,0.0138495266438 -4.2964553833,1.61237323284,0.0274173431098 -4.2964682579,1.61238002777,0.0400153063238 -4.29347467422,1.61138391495,0.0468005873263 -4.29548931122,1.61239099503,0.0603662542999 -4.29850244522,1.61239755154,0.0729623660445 -4.29851675034,1.6124048233,0.0865292474627 -4.30853033066,1.61641049385,0.0991250351071 -4.30154418945,1.6134185791,0.11269338429 -4.29755020142,1.61242222786,0.118508212268 -4.29556465149,1.61142981052,0.132074609399 -4.29657888412,1.61143708229,0.145640939474 -4.30359268188,1.61444318295,0.15823996067 -4.29860639572,1.61245119572,0.171805307269 -4.30762004852,1.61545705795,0.184406429529 -4.3056344986,1.61546468735,0.197972968221 -4.29164028168,1.60946953297,0.203779414296 -4.29265451431,1.60947692394,0.217345744371 -4.29866838455,1.61248314381,0.22994735837 -4.30368328094,1.6144900322,0.243518128991 -4.30169725418,1.61349773407,0.257083177567 -4.29671096802,1.61150538921,0.269675701857 -4.29272556305,1.60951352119,0.283237367868 -4.29573202133,1.61151635647,0.289055168629 -4.28874635696,1.60852491856,0.302612423897 -4.29576015472,1.61153101921,0.315218925476 -4.30077457428,1.6135379076,0.32879281044 -4.31178951263,1.6185438633,0.342377394438 -4.30380344391,1.61555218697,0.354963183403 -4.31681060791,1.62055408955,0.361769199371 -4.31182527542,1.61856234074,0.375328987837 -4.32484006882,1.62456798553,0.388922512531 -4.33485412598,1.62857401371,0.40251237154 -4.32886838913,1.62658202648,0.415101587772 -4.30088233948,1.61559379101,0.427641510963 -4.30689716339,1.6186003685,0.441223353148 -4.29790401459,1.61460530758,0.447017341852 -4.28391885757,1.60961484909,0.459582000971 -4.27893304825,1.60762286186,0.472166895866 -4.2729473114,1.60563111305,0.484748452902 -4.30696249008,1.61963415146,0.500345468521 -4.31197690964,1.62164092064,0.513929009438 -4.30299186707,1.61864972115,0.526503801346 -4.30699872971,1.62065303326,0.533300459385 -4.29401350021,1.61566269398,0.54586148262 -4.2970290184,1.61766993999,0.559440016747 -4.30704259872,1.62167572975,0.573041915894 -4.31105804443,1.62468290329,0.58662623167 -4.31407213211,1.62569010258,0.600207746029 -4.31808710098,1.62769711018,0.613793730736 -4.29709482193,1.6197040081,0.618566215038 -4.27711009979,1.61271476746,0.630124866962 -4.25212478638,1.60272610188,0.640691459179 -4.26113891602,1.60673224926,0.654293239117 -4.26015472412,1.60674035549,0.6678571105 -4.2771692276,1.61474537849,0.682463943958 -4.26717710495,1.61075091362,0.688238501549 -4.31719112396,1.63175106049,0.706864655018 -4.2972073555,1.62476217747,0.718414723873 -4.3012213707,1.62676918507,0.732005119324 -4.33423614502,1.64077222347,0.749604344368 -4.31225156784,1.63278317451,0.760172605515 -4.27726745605,1.61879599094,0.768737137318 -4.3002743721,1.62879657745,0.778540253639 -4.33328819275,1.64279937744,0.796151578426 -3.80916643143,1.61783468723,2.16739988327 -3.78718662262,1.61084759235,2.16998958588 -3.78820419312,1.61385655403,2.18556880951 -3.77422428131,1.61086833477,2.19313955307 -3.77124166489,1.61187767982,2.20574069023 -3.78425812721,1.6208845377,2.22831702232 -3.77926754951,1.61988997459,2.23310613632 -3.7532889843,1.61090409756,2.23367929459 -3.7593061924,1.61691212654,2.25225996971 -3.75932335854,1.6199208498,2.26685738564 -3.7443447113,1.61693358421,2.27440929413 -3.73436427116,1.61494457722,2.28398418427 -3.73638081551,1.61895298958,2.29958820343 -3.72439193726,1.61495983601,2.30037140846 -3.71741127968,1.61497068405,2.31193995476 -3.72042822838,1.61997902393,2.32853579521 -3.70744800568,1.61699068546,2.336114645 -3.70346736908,1.61800098419,2.34967923164 -3.70248532295,1.6210103035,2.36426687241 -3.68549752235,1.61401832104,2.36204266548 -3.67951607704,1.61502861977,2.37362766266 -3.68853259087,1.62303590775,2.3942232132 -3.66555452347,1.61504971981,2.39579129219 -3.66357302666,1.61705958843,2.41036462784 -3.66559076309,1.62206828594,2.42695403099 -3.64761185646,1.61708116531,2.43152213097 -3.65361905098,1.62108421326,2.4423365593 -3.65263819695,1.6240940094,2.45790410042 -3.63065981865,1.61710751057,2.45948004723 -3.63867735863,1.62511563301,2.48104715347 -3.64069461823,1.62912428379,2.49764370918 -3.62271547318,1.62413680553,2.50123286247 -3.61873459816,1.62614703178,2.51480484009 -3.61474490166,1.62615275383,2.5205821991 -3.59376621246,1.61916601658,2.52216672897 -3.59178495407,1.62217581272,2.53674793243 -3.58280420303,1.62118661404,2.54633522034 -3.57482528687,1.62119817734,2.55788874626 -3.5628452301,1.61920976639,2.5654733181 -3.56486225128,1.62321817875,2.5820775032 -3.5498752594,1.61822640896,2.58083558083 -3.54489469528,1.62023675442,2.59341716766 -3.55491065979,1.62824392319,2.6160171032 -3.53293251991,1.62125754356,2.61659646034 -3.52795314789,1.62326836586,2.63015460968 -3.52597141266,1.62627804279,2.6447429657 -3.5219810009,1.626283288,2.64954566956 -3.50400257111,1.62029623985,2.65311670303 -3.50802087784,1.6263051033,2.67269253731 -3.48604345322,1.62031900883,2.67326259613 -3.49006152153,1.62632775307,2.69284105301 -3.48508071899,1.62733817101,2.70542764664 -3.47809076309,1.62634408474,2.70822358131 -3.47211003304,1.62635445595,2.7198164463 -3.46613025665,1.62836527824,2.73238563538 -3.45515084267,1.62637710571,2.74095869064 -3.44417095184,1.62538826466,2.74855542183 -3.43319177628,1.62340021133,2.75712704659 -3.42321300507,1.62341189384,2.76669335365 -3.42322278023,1.62541687489,2.77547478676 -3.42224097252,1.62942636013,2.79106879234 -3.40826201439,1.6264384985,2.79665493965 -3.40028214455,1.62644958496,2.80723547935 -3.40130138397,1.63145935535,2.82579922676 -3.38332247734,1.6264718771,2.82740139961 -3.38334178925,1.63048160076,2.84497189522 -3.38135147095,1.63248682022,2.85176634789 -3.36337351799,1.62649989128,2.8543419838 -3.35639381409,1.62751102448,2.86591935158 -3.3564119339,1.63252019882,2.88251757622 -3.34143447876,1.62953317165,2.88807892799 -3.33545470238,1.63054394722,2.90065383911 -3.32947492599,1.63255488873,2.9132297039 -3.32248568535,1.63056099415,2.9160194397 -3.30850625038,1.62757301331,2.92062163353 -3.31652379036,1.63658106327,2.94520068169 -3.29754662514,1.6315946579,2.94677138329 -3.28256964684,1.62860763073,2.95232820511 -3.28958582878,1.63661527634,2.97493958473 -3.28059792519,1.63462233543,2.97671055794 -3.27061843872,1.6336337328,2.98529982567 -3.26863741875,1.63764357567,3.00089287758 -3.24866080284,1.63165736198,3.00145888329 -3.24767947197,1.63566708565,3.01805114746 -3.23970103264,1.63667869568,3.02961373329 -3.22272348404,1.63269174099,3.0321931839 -3.22573232651,1.63669598103,3.04398465157 -3.21775269508,1.63770723343,3.05457043648 -3.20477485657,1.63571965694,3.06114125252 -3.19379687309,1.63473176956,3.06970882416 -3.19181537628,1.63874137402,3.08530974388 -3.17783761024,1.63575422764,3.0908806324 -3.17585730553,1.63976430893,3.10746145248 -3.16686892509,1.6377710104,3.10824847221 -3.1538901329,1.63578307629,3.11383938789 -3.14691066742,1.63679397106,3.12542533875 -3.13693237305,1.6368060112,3.13499188423 -3.12995362282,1.63881754875,3.14755702019 -3.12397313118,1.63982784748,3.15916657448 -3.11598443985,1.63883435726,3.16095066071 -3.10200715065,1.63584733009,3.16651725769 -3.09302783012,1.63585877419,3.17610502243 -3.09104824066,1.64086925983,3.19367337227 -3.07707023621,1.63888144493,3.19826078415 -3.07209014893,1.64089214802,3.21185159683 -3.06411147118,1.64190375805,3.22342014313 -3.05812287331,1.64190995693,3.22720336914 -3.04714417458,1.64092183113,3.23479127884 -3.04116511345,1.64293313026,3.2483625412 -3.02918601036,1.64194452763,3.25397062302 -3.02420663834,1.64495551586,3.26854491234 -3.02022814751,1.64796686172,3.28510069847 -3.0072491169,1.64597856998,3.28970718384 -3.00325989723,1.64698433876,3.29549336433 -2.9942817688,1.64799630642,3.30606436729 -2.97830462456,1.64400923252,3.30864334106 -2.97432494164,1.64802002907,3.32422375679 -2.96734619141,1.6500313282,3.33679986 -2.95036864281,1.64504420757,3.33739495277 -2.94537973404,1.64505028725,3.34217953682 -2.93740129471,1.6470618248,3.35375404358 -2.92742276192,1.64707350731,3.36234402657 -2.91644501686,1.64708590508,3.37091088295 -2.91046595573,1.64909696579,3.38449239731 -2.89548826218,1.64610958099,3.38708782196 -2.88551139832,1.64712202549,3.3976380825 -2.88452029228,1.64912652969,3.40545582771 -2.86754393578,1.64514017105,3.40702319145 -2.86656308174,1.65114986897,3.42562437057 -2.85558581352,1.65116226673,3.43419218063 -2.84260821342,1.64917469025,3.43977212906 -2.82763147354,1.6461879015,3.44334363937 -2.83663916588,1.65519082546,3.46414518356 -2.8116645813,1.64620602131,3.45571541786 -2.8006875515,1.64621841908,3.46428227425 -2.80470585823,1.6552273035,3.48987531662 -2.78672981262,1.65124094486,3.4894516468 -2.77675127983,1.65125262737,3.49804329872 -2.76677370071,1.65126478672,3.50761580467 -2.76278424263,1.65227043629,3.51340723038 -2.74980640411,1.65128266811,3.51800346375 -2.74482727051,1.65429365635,3.5335829258 -2.72485160828,1.64830768108,3.53016161919 -2.72487211227,1.6563179493,3.5527317524 -2.71789312363,1.65832912922,3.56532263756 -2.69191980362,1.64834475517,3.55488324165 -2.68393135071,1.64735126495,3.55567145348 -2.67195415497,1.6463637352,3.56225156784 -2.66097712517,1.64637625217,3.57081890106 -2.64000177383,1.63939034939,3.5653989315 -2.63602232933,1.64440095425,3.58199000359 -2.62404489517,1.64341342449,3.58856868744 -2.59807181358,1.63342916965,3.57712936401 -2.6150765419,1.64843010902,3.60995006561 -2.60409975052,1.648442626,3.61851835251 -2.60011982918,1.65345299244,3.63511633873 -2.59114170074,1.65446472168,3.64569973946 -2.57916545868,1.65447759628,3.6532626152 -2.56118917465,1.64949095249,3.65085315704 -2.5751953125,1.66249287128,3.68165516853 -2.55921959877,1.66050636768,3.68322610855 -2.54924106598,1.66051805019,3.69182229042 -2.54726243019,1.66752874851,3.71339344978 -2.53328633308,1.66554188728,3.71796131134 -2.52130818367,1.66555392742,3.72356081009 -2.51133060455,1.66556596756,3.73314237595 -2.50234270096,1.66357278824,3.73193478584 -2.49136662483,1.66458570957,3.74149131775 -2.48638749123,1.66859650612,3.75808095932 -2.48140835762,1.67360723019,3.77467274666 -2.47942948341,1.68061804771,3.79724264145 -2.47544956207,1.68662834167,3.81484770775 -2.47046113014,1.68663465977,3.82062506676 -2.46148371696,1.68964660168,3.83220601082 -2.46250247955,1.69865584373,3.85781145096 -2.46052360535,1.70566666126,3.88137865067 -2.4565448761,1.71167755127,3.90096282959 -2.45756459236,1.72168731689,3.92854809761 -2.456584692,1.7296974659,3.95313501358 -2.45759367943,1.73470187187,3.96694350243 -2.44861626625,1.73671388626,3.97952270508 -2.45163488388,1.74872291088,4.01012516022 -2.44965577126,1.75673353672,4.03469944 -2.45167541504,1.76774311066,4.06528663635 -2.43170022964,1.76175713539,4.05987262726 -2.4297208786,1.76976752281,4.08445549011 -2.41873383522,1.76677489281,4.08024549484 -2.40475773811,1.76578807831,4.08581495285 -2.39178061485,1.76480042934,4.09140825272 -2.37480568886,1.76181435585,4.0919752121 -2.36382865906,1.76282656193,4.10156011581 -2.35185217857,1.76383924484,4.11013460159 -2.33787584305,1.76285219193,4.11471700668 -2.33488631248,1.7648576498,4.12351465225 -2.31791162491,1.76187169552,4.12407875061 -2.30293488503,1.75988423824,4.1256775856 -2.29295754433,1.76189649105,4.13726043701 -2.28298020363,1.76390850544,4.1488442421 -2.26000714302,1.75592362881,4.13840723038 -2.24702095985,1.75093150139,4.13019132614 -2.2320458889,1.74894499779,4.13375759125 -2.21806836128,1.74795734882,4.13636255264 -2.208091259,1.74996948242,4.14794540405 -2.19111728668,1.74698352814,4.14850091934 -2.17914056778,1.74799609184,4.15608787537 -2.16816329956,1.74900829792,4.16567373276 -2.16217494011,1.7490144968,4.16946792603 -2.14519906044,1.74602782726,4.16706085205 -2.13522315025,1.74904048443,4.18062019348 -2.12124609947,1.74705290794,4.18322229385 -2.10527157784,1.74506664276,4.1847858429 -2.09629464149,1.74907886982,4.1993598938 -2.08431792259,1.74909126759,4.20694828033 -2.07233095169,1.74409866333,4.19874191284 -2.06435322762,1.74911022186,4.21433115005 -2.04737782478,1.7451236248,4.2119178772 -2.03340339661,1.74513733387,4.21846723557 -2.0214266777,1.74614977837,4.2260556221 -2.0094499588,1.74616217613,4.23364448547 -2.00046253204,1.74416911602,4.23143577576 -1.99648320675,1.75217950344,4.25503635406 -1.97650969028,1.74619412422,4.24760198593 -1.95953464508,1.7432076931,4.24518251419 -1.95255732536,1.74921953678,4.26475811005 -1.93558180332,1.7452327013,4.26134967804 -1.92260539532,1.74524533749,4.2669377327 -1.91461777687,1.74325203896,4.26672792435 -1.90364122391,1.7462644577,4.27730941772 -1.88966536522,1.74527728558,4.28089427948 -1.87069201469,1.74029183388,4.27545166016 -1.85971558094,1.74230420589,4.28603363037 -1.84673881531,1.74231660366,4.29063272476 -1.8327640295,1.74233007431,4.29619407654 -1.82677519321,1.74233591557,4.29900074005 -1.81579971313,1.74534881115,4.31156253815 -1.80382359028,1.74636149406,4.32014417648 -1.78784763813,1.7433744669,4.31774139404 -1.77587151527,1.74538695812,4.32632350922 -1.75889718533,1.74140095711,4.32389259338 -1.75290894508,1.7424069643,4.32768917084 -1.73993325233,1.74341988564,4.33426618576 -1.72595751286,1.74243283272,4.33784914017 -1.70898199081,1.73744606972,4.332447052 -1.70000517368,1.74345815182,4.34902524948 -1.68602967262,1.74247097969,4.35260820389 -1.66905581951,1.73948514462,4.35017204285 -1.66706562042,1.74349009991,4.36298370361 -1.64809203148,1.73750424385,4.35455465317 -1.63811516762,1.7415163517,4.36814212799 -1.62713885307,1.74452877045,4.37972402573 -1.60916471481,1.74054265022,4.37329864502 -1.59418988228,1.73855602741,4.37487268448 -1.58421289921,1.74256789684,4.388463974 -1.57322669029,1.73757553101,4.38024425507 -1.55925095081,1.7375882864,4.38283443451 -1.55027461052,1.74360048771,4.40140676498 -1.53229987621,1.73761403561,4.39299440384 -1.51832413673,1.737626791,4.39558410645 -1.50734853745,1.74063956738,4.40915250778 -1.49037349224,1.73665297031,4.40274477005 -1.48038709164,1.73266017437,4.39652681351 -1.47240936756,1.73967170715,4.41612386703 -1.45943331718,1.74068415165,4.42171382904 -1.43846035004,1.73169887066,4.40528249741 -1.43248319626,1.74171042442,4.43385839462 -1.41450881958,1.73572397232,4.42444419861 -1.40851998329,1.73672986031,4.42725276947 -1.39854383469,1.7417422533,4.44382953644 -1.37857115269,1.73475670815,4.43039178848 -1.36859405041,1.73876869678,4.44498825073 -1.35561800003,1.73978126049,4.45057868958 -1.33764517307,1.73479557037,4.44413280487 -1.32466840744,1.73480761051,4.44774007797 -1.32267916203,1.74181306362,4.46553659439 -1.30170691013,1.73282790184,4.44809484482 -1.2887314558,1.73484063148,4.45467758179 -1.2787539959,1.73885238171,4.46928071976 -1.26077997684,1.73286604881,4.45886039734 -1.2458050251,1.73187935352,4.45844316483 -1.23881757259,1.73188579082,4.46023273468 -1.22484242916,1.73189878464,4.46381187439 -1.2128674984,1.73491168022,4.47637844086 -1.19689238071,1.73192477226,4.47096967697 -1.18391668797,1.73293745518,4.47755479813 -1.16894185543,1.73195064068,4.47713565826 -1.15796542168,1.73596274853,4.49072599411 -1.14997887611,1.73496973515,4.49050283432 -1.13600313663,1.73498237133,4.49209737778 -1.12102770805,1.73199522495,4.48969125748 -1.10505354404,1.72900879383,4.48626327515 -1.09007894993,1.72802197933,4.4858417511 -1.07810342312,1.73203456402,4.49742269516 -1.06312870979,1.73004770279,4.49700117111 -1.05814003944,1.73305356503,4.50580072403 -1.04316580296,1.73206698895,4.50637197495 -1.02819061279,1.73007977009,4.50396299362 -1.01821434498,1.73809182644,4.52454710007 -1.00423872471,1.7371045351,4.52614164352 -0.982266008854,1.72311902046,4.49372005463 -0.97129034996,1.72913146019,4.51129722595 -0.965302705765,1.73113775253,4.5180850029 -0.953327357769,1.73515033722,4.53166246414 -0.941351354122,1.73916268349,4.54325342178 -0.926376521587,1.73817574978,4.54183673859 -0.48658183217,0.920300126076,2.55616140366 --1.16990506649,1.74301934242,4.31231069565 --1.18687880039,1.74703192711,4.31888628006 --1.19785499573,1.7440431118,4.3054766655 --1.21382975578,1.74705517292,4.31006669998 --1.2288043499,1.74906718731,4.30964708328 --1.23878026009,1.74307847023,4.29122304916 --1.24776780605,1.7470843792,4.29802751541 --1.26074337959,1.74609589577,4.29161500931 --1.27671766281,1.7491080761,4.29419279099 --1.28769445419,1.74611902237,4.28279542923 --1.30666840076,1.75313138962,4.29638385773 --1.31664443016,1.74814260006,4.27896213531 --1.32263219357,1.74714839458,4.2737531662 --1.34160590172,1.75416088104,4.28633737564 --1.35458159447,1.7531722784,4.27992582321 --1.36855685711,1.75418388844,4.27651262283 --1.38353192806,1.75619566441,4.27609872818 --1.39350938797,1.75220620632,4.26270723343 --1.4134824276,1.76021885872,4.27628278732 --1.41847097874,1.75822424889,4.26908254623 --1.43044650555,1.75623571873,4.25866222382 --1.44242286682,1.75424671173,4.25025939941 --1.45839774609,1.75725853443,4.25284814835 --1.46937394142,1.75426959991,4.24043464661 --1.48634874821,1.75928139687,4.24602651596 --1.49932396412,1.75829291344,4.23860549927 --1.50631141663,1.75829875469,4.23639583588 --1.52428531647,1.76331102848,4.24297380447 --1.5372620821,1.76332187653,4.23858213425 --1.54723775387,1.7593331337,4.22215414047 --1.56721222401,1.76734530926,4.23575115204 --1.57718837261,1.7633562088,4.22033166885 --1.58517587185,1.76436209679,4.22112560272 --1.60015141964,1.76637351513,4.22072124481 --1.61612546444,1.76938557625,4.2202911377 --1.62610256672,1.76539623737,4.20688962936 --1.64107835293,1.7674074173,4.2064871788 --1.65205478668,1.7654184103,4.19507741928 --1.6700283289,1.76943063736,4.19964838028 --1.67801606655,1.77143633366,4.20044565201 --1.68799245358,1.7674472332,4.18603038788 --1.70096898079,1.76745808125,4.18063020706 --1.72094225883,1.77447044849,4.19020652771 --1.7349178791,1.77548182011,4.1857919693 --1.7458947897,1.77349233627,4.17539215088 --1.75886964798,1.77250397205,4.16695976257 --1.76485896111,1.77250885963,4.16477918625 --1.77783501148,1.7725199461,4.15836906433 --1.7968082428,1.7775323391,4.16393613815 --1.81078386307,1.77854347229,4.15952348709 --1.82476055622,1.77955424786,4.15713453293 --1.83673667908,1.77856516838,4.14771795273 --1.84172415733,1.77657091618,4.1394944191 --1.85869967937,1.78058218956,4.14309740067 --1.87167525291,1.7795933485,4.13567733765 --1.8846514225,1.77960431576,4.12926912308 --1.90162611008,1.78361594677,4.13085126877 --1.90860509872,1.77862536907,4.113468647 --1.91958081722,1.77663648129,4.10103940964 --1.93356692791,1.78264307976,4.11383390427 --1.9455435276,1.78265368938,4.105427742 --1.96051836014,1.783665061,4.10200500488 --1.9744938612,1.78467643261,4.09658432007 --1.98847031593,1.78568708897,4.09318828583 --1.99544787407,1.77969717979,4.07377386093 --2.01442289352,1.78570866585,4.08037471771 --2.02340912819,1.78771495819,4.0801448822 --2.03438639641,1.78572535515,4.06973934174 --2.04936146736,1.78773665428,4.06631994247 --2.06233859062,1.78874695301,4.06092691422 --2.07231497765,1.78575766087,4.04750680923 --2.090290308,1.78976893425,4.05110263824 --2.09827828407,1.79177439213,4.05090093613 --2.10625505447,1.7867847681,4.03347873688 --2.12623023987,1.79379630089,4.04107999802 --2.13620686531,1.79080677032,4.02765846252 --2.15318179131,1.79481804371,4.0282459259 --2.17315649986,1.80082952976,4.03484010696 --2.18013501167,1.79583930969,4.01743936539 --2.18312382698,1.79284417629,4.0072312355 --2.20609688759,1.80185639858,4.01780796051 --2.21607398987,1.79886674881,4.00539827347 --2.22005271912,1.79187619686,3.98198628426 --2.24502658844,1.80288803577,3.99758768082 --2.26600050926,1.80889987946,4.0041680336 --2.26997900009,1.80190932751,3.98075318336 --2.28396606445,1.80891537666,3.99156284332 --2.29894137383,1.80992639065,3.98714137077 --2.30392050743,1.80393576622,3.96674084663 --2.31289744377,1.80094587803,3.95232462883 --2.33787035942,1.81095814705,3.96490073204 --2.33984994888,1.80296719074,3.93949770927 --2.3598344326,1.81297421455,3.95828413963 --2.36581230164,1.80798399448,3.93886852264 --2.38478779793,1.81299495697,3.94246864319 --2.40176272392,1.81600618362,3.94104671478 --2.41573929787,1.81801664829,3.93563985825 --2.43471503258,1.82302749157,3.93924570084 --2.44369244576,1.82003748417,3.92482805252 --2.46067762375,1.8280441761,3.93761539459 --2.46565628052,1.82205367088,3.91720438004 --2.49662852287,1.83706605434,3.93879795074 --2.50160717964,1.83107542992,3.91838645935 --2.50458717346,1.82408428192,3.89598941803 --2.52556061745,1.83009600639,3.89955735207 --2.53653860092,1.82910573483,3.89016580582 --2.55252385139,1.83611226082,3.89994359016 --2.56750011444,1.83812272549,3.89553594589 --2.60147166252,1.8541353941,3.92012929916 --2.59343409538,1.83015179634,3.85331249237 --2.60241222382,1.82816147804,3.83990478516 --2.61439847946,1.83216750622,3.84369015694 --2.62637543678,1.83217775822,3.83427524567 --2.64035248756,1.83318769932,3.8288769722 --2.65532851219,1.8351982832,3.82345628738 --2.66730618477,1.83520805836,3.81505775452 --2.68128275871,1.83621835709,3.80864524841 --2.69126081467,1.83522796631,3.79724502563 --2.69824910164,1.83523309231,3.794039011 --2.71322417259,1.8372439146,3.78760480881 --2.73020076752,1.8412541151,3.78620624542 --2.73917889595,1.83826375008,3.77279639244 --2.75115680695,1.83827340603,3.76439857483 --2.76613211632,1.84028422832,3.7579665184 --2.78110909462,1.84229421616,3.75356793404 --2.78809762001,1.84329915047,3.75036358833 --2.80107498169,1.84430897236,3.74296164513 --2.81005239487,1.84131884575,3.72853350639 --2.82502937317,1.8443287611,3.72413682938 --2.83800625801,1.84533894062,3.71571874619 --2.84798359871,1.84334862232,3.70330071449 --2.86795926094,1.84835910797,3.70489645004 --2.87594747543,1.85036432743,3.70268893242 --2.88392686844,1.84837329388,3.68929791451 --2.89490389824,1.84738326073,3.67787432671 --2.91287922859,1.85139381886,3.67545127869 --2.92885661125,1.854403615,3.6720559597 --2.93683481216,1.85141289234,3.65764665604 --2.94682216644,1.85441839695,3.65743207932 --2.95080256462,1.84942686558,3.63903975487 --2.94878387451,1.84043502808,3.61263632774 --2.98775362968,1.85744798183,3.63519954681 --2.99773216248,1.85745716095,3.62379837036 --3.01370978355,1.86046683788,3.620408535 --3.02668714523,1.86147642136,3.61199641228 --3.03067541122,1.8594814539,3.6037735939 --3.02865719795,1.8514893055,3.57837939262 --3.06162977219,1.86450099945,3.59396839142 --3.08560395241,1.87251210213,3.59753966331 --3.07758688927,1.86051928997,3.56514406204 --3.08556556702,1.85752856731,3.55073046684 --3.08854579926,1.85253691673,3.5313308239 --3.10853075981,1.86154317856,3.54211306572 --3.11850953102,1.86155235767,3.53071117401 --3.13548564911,1.86456251144,3.52629065514 --3.14046502113,1.86057126522,3.50888323784 --3.15644240379,1.86358070374,3.50448489189 --3.16941928864,1.86459052563,3.49505782127 --3.17140078545,1.85859847069,3.47567296028 --3.18238759041,1.8616039753,3.47545003891 --3.20036482811,1.86661362648,3.47305011749 --3.20934271812,1.86462295055,3.45963168144 --3.22532057762,1.86763226986,3.45523786545 --3.23030018806,1.86464095116,3.43782520294 --3.24227833748,1.86465013027,3.42841982841 --3.24726748466,1.86465477943,3.42220926285 --3.25524663925,1.86266350746,3.40880894661 --3.27122378349,1.86567318439,3.40339922905 --3.27620339394,1.86168181896,3.38598275185 --3.29517889023,1.86669206619,3.38255286217 --3.30715727806,1.86770117283,3.37314867973 --3.30913829803,1.86170911789,3.35375118256 --3.31912684441,1.86471390724,3.35355591774 --3.340102911,1.87072384357,3.35314798355 --3.35308051109,1.87173318863,3.34372591972 --3.36705851555,1.87474226952,3.33632326126 --3.38103604317,1.87575185299,3.32790279388 --3.38901543617,1.87476027012,3.31450152397 --3.39299488068,1.8707690239,3.29607963562 --3.40998244286,1.87777400017,3.30289077759 --3.41796207428,1.87578260899,3.28948926926 --3.42894005775,1.87579166889,3.27806925774 --3.4379196167,1.87480020523,3.26566720009 --3.45689535141,1.87981021404,3.26123332977 --3.45187902451,1.87081718445,3.23685956001 --3.47385454178,1.87782728672,3.23542928696 --3.47784376144,1.87683165073,3.22821807861 --3.48782300949,1.8768402338,3.21681666374 --3.50380063057,1.8798494339,3.21040320396 --3.50978064537,1.8778578043,3.19499731064 --3.52075886726,1.877866745,3.18357753754 --3.53373789787,1.87887537479,3.17518162727 --3.55071544647,1.88288450241,3.16977334023 --3.55670452118,1.88388907909,3.16456484795 --3.56168484688,1.88089728355,3.14815545082 --3.57566380501,1.88290584087,3.14076328278 --3.58864212036,1.88391470909,3.1313495636 --3.60162043571,1.88592350483,3.1219367981 --3.60959935188,1.88393223286,3.10751247406 --3.61858844757,1.88693654537,3.10531258583 --3.62456846237,1.88394486904,3.08990311623 --3.63854694366,1.8869535923,3.08149409294 --3.63452959061,1.87896096706,3.05809640884 --3.65950608253,1.88697016239,3.05969905853 --3.66648626328,1.88597846031,3.04529118538 --3.68146371841,1.88798749447,3.03686714172 --3.69745182991,1.8939923048,3.04067277908 --3.68743467331,1.88399958611,3.01124930382 --3.70841193199,1.89000844955,3.00884699821 --3.71839094162,1.89001703262,2.99642848969 --3.73236989975,1.89202558994,2.98802447319 --3.7473487854,1.89503395557,2.98062562943 --3.74633002281,1.88904178143,2.9592063427 --3.76131749153,1.89404666424,2.96099543571 --3.76929783821,1.89405477047,2.94759011269 --3.78427672386,1.8970631361,2.94019365311 --3.78825712204,1.89407122135,2.92277145386 --3.80523538589,1.8970798254,2.91636443138 --3.83221197128,1.90708887577,2.91796255112 --3.82719421387,1.89909636974,2.89354038239 --3.82518649101,1.89609956741,2.88336205482 --3.84516406059,1.90110826492,2.87895154953 --3.84914422035,1.89811635017,2.86152696609 --3.85812473297,1.89812421799,2.8491268158 --3.86910414696,1.89913237095,2.83771562576 --3.87408447266,1.89714050293,2.82129406929 --3.88606381416,1.89814841747,2.81088876724 --3.90505170822,1.90615308285,2.8156940937 --3.90403342247,1.90016055107,2.79528188705 --3.92501187325,1.90716898441,2.79188680649 --3.93899106979,1.9091771841,2.78247475624 --3.93997311592,1.90518450737,2.76407194138 --3.95395207405,1.90719270706,2.75466060638 --3.96093249321,1.90720057487,2.74024987221 --3.97892093658,1.91320478916,2.7440598011 --3.998898983,1.91921329498,2.73864626884 --3.9748852253,1.90221965313,2.70223116875 --4.00186157227,1.91122829914,2.70182085037 --4.00184345245,1.90723574162,2.68240666389 --4.02682161331,1.91524398327,2.68100881577 --4.05880641937,1.92924952507,2.69279336929 --4.04179143906,1.91625583172,2.66239213943 --4.03677511215,1.90926289558,2.63998365402 --4.07973146439,1.9222792387,2.63117527962 --4.12070560455,1.93828845024,2.63875579834 --4.15268182755,1.94929718971,2.64034080505 --4.13067770004,1.93629944324,2.61715316772 --4.11166334152,1.9233058691,2.58574295044 --4.11864423752,1.92231345177,2.57133316994 --4.15362024307,1.93532204628,2.57492470741 --4.20559310913,1.95633149147,2.58850431442 --4.19557714462,1.94733822346,2.56309437752 --4.17356395721,1.93334424496,2.53069210052 --4.17055511475,1.92934775352,2.51948928833 --4.20053243637,1.93935608864,2.51907444 --4.24450826645,1.95736443996,2.52869415283 --4.26548671722,1.96337234974,2.52227807045 --4.2394733429,1.94637858868,2.48685312271 --4.22245883942,1.93438482285,2.4584569931 --4.25843477249,1.94839334488,2.46104049683 --4.28342199326,1.95839762688,2.46684169769 --4.31839990616,1.97140562534,2.46944737434 --4.25839138031,1.93841052055,2.41503047943 --4.25337505341,1.93241739273,2.39362215996 --4.28035259247,1.9414254427,2.39019942284 --4.32832765579,1.96043384075,2.39980149269 --4.37330341339,1.97844195366,2.4074048996 --4.35929727554,1.96944475174,2.39020299911 --4.34228134155,1.95745170116,2.3607673645 --4.30327033997,1.93545746803,2.32035636902 --4.33125019073,1.94546461105,2.31897735596 --4.34223031998,1.94647181034,2.30656504631 --4.33121442795,1.93747878075,2.28113150597 --4.32820653915,1.93448197842,2.27093958855 --4.3321890831,1.93348860741,2.2555437088 --4.34816837311,1.93649625778,2.2451145649 --4.35415077209,1.93650305271,2.23071742058 --4.36113262177,1.93650996685,2.21630787849 --4.36911344528,1.93651723862,2.20188593864 --4.36909675598,1.93352377415,2.18449115753 --4.38108587265,1.93652760983,2.18127655983 --4.37906980515,1.93253409863,2.1628818512 --4.39604997635,1.93654119968,2.15346884727 --4.41103076935,1.94054830074,2.1430580616 --4.41201353073,1.93755507469,2.12564969063 --4.42199516296,1.93956172466,2.11325192451 --4.43097734451,1.93956851959,2.09984326363 --4.43396854401,1.93957185745,2.09264445305 --4.45094919205,1.94457876682,2.08323812485 --4.44793224335,1.93958544731,2.06382679939 --4.46491336823,1.94459223747,2.05442214012 --4.46389579773,1.94059932232,2.03498625755 --4.4768781662,1.94360566139,2.02460503578 --4.48585891724,1.94461262226,2.01017475128 --4.47385215759,1.93761575222,1.99597632885 --4.48683404922,1.94062232971,1.98457229137 --4.5138130188,1.94962930679,1.97915947437 --4.49579954147,1.93863534927,1.95376181602 --4.52077913284,1.94664216042,1.94734978676 --4.53176116943,1.94964873791,1.93494749069 --4.52674436569,1.94365549088,1.91452467442 --4.54373407364,1.94965875149,1.91332161427 --4.54671669006,1.94866538048,1.8969091177 --4.55469989777,1.94967150688,1.88351583481 --4.56268215179,1.9496781826,1.86909925938 --4.56566476822,1.94868469238,1.85268580914 --4.57664728165,1.95069098473,1.84028673172 --4.58363008499,1.95069730282,1.82588088512 --4.58762121201,1.9517005682,1.81867265701 --4.60760307312,1.95770668983,1.81028199196 --4.60058641434,1.9517134428,1.78884732723 --4.61856794357,1.95671951771,1.77945458889 --4.60855293274,1.94972586632,1.75804650784 --4.62853384018,1.95573222637,1.74863648415 --4.634516716,1.95573854446,1.73321759701 --4.64450740814,1.95874154568,1.72902607918 --4.63649225235,1.9527477026,1.70861876011 --4.64247512817,1.9527541399,1.69319927692 --4.65845727921,1.95775997639,1.68280827999 --4.65244102478,1.95276665688,1.66237866879 --4.67542219162,1.95977258682,1.65397441387 --4.67940616608,1.95877861977,1.63857448101 --4.67139911652,1.9547816515,1.62737905979 --4.69637966156,1.96278774738,1.61896121502 --4.68436527252,1.95579397678,1.59755659103 --4.68434858322,1.95280015469,1.58014154434 --4.67433452606,1.9468061924,1.55973887444 --4.6763176918,1.94481241703,1.54332828522 --4.68730831146,1.94881558418,1.5381103754 --4.68629217148,1.94582164288,1.52070081234 --4.69427633286,1.94682729244,1.50731265545 --4.70025920868,1.94683349133,1.49189245701 --4.69924354553,1.94483959675,1.47448074818 --4.71522569656,1.94984531403,1.46307682991 --4.7152094841,1.94685149193,1.44565665722 --4.73020029068,1.95285415649,1.44246089458 --4.73818349838,1.95386004448,1.42805075645 --4.73316860199,1.94986605644,1.40964496136 --4.75015068054,1.95487165451,1.39823877811 --4.75713443756,1.95587730408,1.38383769989 --4.74911975861,1.949883461,1.36442816257 --4.76610279083,1.95588886738,1.35302495956 --4.75609493256,1.94989228249,1.34080266953 --4.77307796478,1.95589768887,1.32940101624 --4.78706121445,1.95890319347,1.31699931622 --4.79004478455,1.95890915394,1.30057954788 --4.80302858353,1.96291434765,1.28818702698 --4.8040137291,1.96092009544,1.2717820406 --4.81599664688,1.96392560005,1.25837373734 --4.81098937988,1.96092867851,1.24815988541 --4.81697320938,1.96193432808,1.23274409771 --4.81795740128,1.95994007587,1.21633803844 --4.83094072342,1.963945508,1.20292496681 --4.82592630386,1.95995116234,1.18553388119 --4.83791017532,1.96295642853,1.172129035 --4.84189367294,1.96296226978,1.15570247173 --4.84588623047,1.96396493912,1.14850127697 --4.84487056732,1.96197068691,1.13108181953 --4.85585451126,1.96497583389,1.11768591404 --4.864839077,1.96698117256,1.10327851772 --4.86182355881,1.96398687363,1.08587086201 --4.86980867386,1.96599197388,1.07147014141 --4.86580133438,1.96299493313,1.06226849556 --4.87178564072,1.96400034428,1.04685509205 --4.87876939774,1.96600580215,1.0314360857 --4.88675403595,1.96701085567,1.01703727245 --4.88273954391,1.96401655674,0.999632060528 --4.88972377777,1.96602189541,0.984213829041 --4.88670873642,1.96302747726,0.966801464558 --4.88669395447,1.96103298664,0.950397014618 --4.8956861496,1.9640352726,0.944195926189 --4.90267038345,1.96604049206,0.928778767586 --4.90365552902,1.96504592896,0.912368655205 --4.91863965988,1.96905064583,0.898961484432 --4.91462469101,1.96605622768,0.881552100182 --4.91061019897,1.96306180954,0.864141464233 --4.91559553146,1.96406698227,0.848735511303 --4.91158819199,1.96206986904,0.839526593685 --4.92557287216,1.96607446671,0.826128065586 --4.93655776978,1.96907913685,0.811720192432 --4.93754291534,1.96908450127,0.795309305191 --4.93452787399,1.96609008312,0.777891337872 --4.94651317596,1.97009432316,0.764506161213 --4.93550682068,1.96509754658,0.754301249981 --4.91449260712,1.95510423183,0.733883917332 --4.9304766655,1.96010875702,0.719455778599 --4.94646167755,1.96611297131,0.706055164337 --4.94344806671,1.96311819553,0.68965947628 --4.94943332672,1.96512305737,0.674251377583 --4.95641851425,1.96612787247,0.658840179443 --4.96641016006,1.97012996674,0.651621699333 --4.96139717102,1.96713519096,0.635232806206 --4.95738220215,1.96414077282,0.61781334877 --4.9653673172,1.96614539623,0.602399528027 --4.97635316849,1.97014963627,0.588001132011 --4.97133874893,1.96715521812,0.570584177971 --4.97532463074,1.96815979481,0.555185973644 --4.98831653595,1.97216176987,0.547962486744 --4.98130273819,1.96916735172,0.530550956726 --4.98528862,1.96917188168,0.515153765678 --5.00027418137,1.97517573833,0.500747203827 --5.00925970078,1.97818005085,0.485335767269 --5.00824594498,1.97618508339,0.468930214643 --5.0082321167,1.97619009018,0.452520787716 --5.00322437286,1.97319304943,0.443305045366 --4.99421072006,1.96919870377,0.425894349813 --5.01119613647,1.9752022028,0.411488324404 --5.0111823082,1.97420716286,0.395078271627 --4.99816894531,1.96821308136,0.37767547369 --5.0091547966,1.97221708298,0.362262070179 --5.00114202499,1.96822237968,0.345870167017 --4.99913358688,1.96622526646,0.336643338203 --5.00812005997,1.96922934055,0.321236252785 --5.00710678101,1.96923422813,0.304826259613 --5.01809215546,1.97223818302,0.289416760206 --5.01607894897,1.97124302387,0.273009091616 --5.01706504822,1.97124779224,0.256595104933 --5.01305150986,1.96925282478,0.24019035697 --5.01404476166,1.96925508976,0.231982246041 --5.01203107834,1.9672601223,0.21557316184 --5.01601791382,1.96926426888,0.200178965926 --5.02700471878,1.97226786613,0.18477460742 --5.00999116898,1.96527409554,0.167361959815 --5.01397752762,1.96627855301,0.150942414999 --5.02696418762,1.9712818861,0.135537073016 --5.0269575119,1.97128427029,0.127330631018 --5.03394365311,1.97328829765,0.110909357667 --5.04593086243,1.97829151154,0.0955089852214 --5.02291679382,1.96829843521,0.0780956149101 --5.02890396118,1.97030222416,0.0627019703388 --5.0318903923,1.97130656242,0.0462859161198 --5.02287721634,1.96731209755,0.029879918322 --5.02287054062,1.96731436253,0.0216728337109 --5.02585697174,1.96831858158,0.00525659369305 --5.02484369278,1.96732318401,-0.0111567573622 --5.03083086014,1.96932709217,-0.0275740213692 --5.03681850433,1.97233068943,-0.0429647900164 --5.02280521393,1.96633660793,-0.0593732148409 --5.04079866409,1.97333693504,-0.067586094141 --5.04378557205,1.9743411541,-0.083999954164 --5.02877235413,1.9683470726,-0.100410856307 --5.03275966644,1.96935117245,-0.116825282574 --5.03674650192,1.9713550806,-0.133239373565 --5.02373361588,1.96636068821,-0.148628622293 --5.02772092819,1.96736466885,-0.165042594075 --5.03871488571,1.97236549854,-0.173247590661 --5.02270126343,1.96537172794,-0.189665973186 --5.02768850327,1.96737551689,-0.206079021096 --5.03667593002,1.97137868404,-0.222489461303 --5.02366352081,1.96638429165,-0.237884625793 --5.02565050125,1.96638834476,-0.254298001528 --5.0326385498,1.96939170361,-0.270707756281 --5.02963161469,1.96839416027,-0.278917104006 --5.03061914444,1.96939826012,-0.295330762863 --5.03260660172,1.96940219402,-0.311742872 --5.02659368515,1.96740722656,-0.328162968159 --5.0225815773,1.96641170979,-0.343555986881 --5.02756929398,1.96841514111,-0.35996478796 --5.01555538177,1.96342098713,-0.376393914223 --5.01954984665,1.9654225111,-0.384596407413 --5.02753829956,1.96942543983,-0.401000320911 --5.0185251236,1.96543061733,-0.416401356459 --5.01951313019,1.96643459797,-0.432814568281 --5.01850032806,1.96643877029,-0.449230700731 --5.01748800278,1.96644294262,-0.465646862984 --5.01147556305,1.96344769001,-0.481045752764 --5.01046943665,1.96344983578,-0.489255070686 --5.02445793152,1.9694519043,-0.50666898489 --5.00944471359,1.96345794201,-0.522086322308 --5.01343345642,1.96646130085,-0.53849285841 --5.01642131805,1.96746480465,-0.554900228977 --5.01640939713,1.96846854687,-0.571314036846 --4.99939632416,1.96147489548,-0.585714995861 --5.02039194107,1.97047364712,-0.595924675465 --5.01737928391,1.96947813034,-0.612344741821 --5.01436805725,1.96948218346,-0.627739608288 --5.02235651016,1.97248494625,-0.645157277584 --5.00834369659,1.96749067307,-0.659555315971 --5.01633262634,1.97149324417,-0.676972091198 --5.01832103729,1.97249662876,-0.693378388882 --5.00631427765,1.96850037575,-0.700593292713 --5.01530313492,1.97250270844,-0.718004822731 --5.00629091263,1.96950781345,-0.733418047428 --4.99927854538,1.96751260757,-0.74882632494 --5.00926780701,1.97251462936,-0.766232430935 --5.00925636292,1.97251820564,-0.78264349699 --5.00324440002,1.97152268887,-0.798049271107 --4.99123668671,1.96652662754,-0.805270016193 --4.99922657013,1.97052884102,-0.822679758072 --4.99521493912,1.96953308582,-0.83807939291 --4.98620271683,1.96653807163,-0.853497743607 --4.99519252777,1.97154009342,-0.870901405811 --4.98317909241,1.96754586697,-0.886332094669 --4.98617458344,1.9695469141,-0.894526183605 --4.97316169739,1.96455264091,-0.908936679363 --4.97415065765,1.96655583382,-0.925344347954 --4.98514032364,1.97155749798,-0.94376128912 --4.96612739563,1.96456420422,-0.957173645496 --4.97111606598,1.9675668478,-0.974588811398 --4.96510457993,1.96657121181,-0.989999592304 --4.97310066223,1.96957147121,-0.999194920063 --4.96308755875,1.96657669544,-1.01462352276 --4.95307588577,1.96358180046,-1.02902770042 --4.96406602859,1.96958315372,-1.04743814468 --4.94505214691,1.96258997917,-1.0608600378 --4.93704080582,1.95959472656,-1.07525706291 --4.94503068924,1.96459650993,-1.09367954731 --4.92902326584,1.95860111713,-1.09888637066 --4.93501329422,1.9626032114,-1.11629235744 --4.94000387192,1.96560549736,-1.13370156288 --4.92198991776,1.95961225033,-1.14712667465 --4.92097902298,1.9596157074,-1.16354119778 --4.91296720505,1.9576202631,-1.17794203758 --4.91895771027,1.96162223816,-1.19534432888 --4.91194581985,1.95962679386,-1.210765481 --4.9159412384,1.9626275301,-1.21997332573 --4.89092683792,1.9536356926,-1.23139429092 --4.89491701126,1.95663809776,-1.24880623817 --4.89390611649,1.95664131641,-1.26522028446 --4.89089536667,1.95664489269,-1.28062033653 --4.88188362122,1.95464980602,-1.2950309515 --4.888879776,1.95864987373,-1.30524408817 --4.88186836243,1.95665431023,-1.319642663 --4.86985588074,1.95365989208,-1.33407306671 --4.86584472656,1.95366370678,-1.34948027134 --4.8608341217,1.95266759396,-1.36489367485 --4.85882282257,1.95367109776,-1.38131380081 --4.85581302643,1.95367455482,-1.39671456814 --4.85180711746,1.95267677307,-1.40391850471 --4.84279537201,1.9506816864,-1.41833376884 --4.84078502655,1.95068502426,-1.43475341797 --4.8277721405,1.94769084454,-1.44817197323 --4.83176326752,1.95069265366,-1.46557641029 --4.82075119019,1.94769787788,-1.47898244858 --4.81774044037,1.94770145416,-1.49540925026 --4.8147354126,1.94770348072,-1.50260818005 --4.80872392654,1.94670772552,-1.5180311203 --4.79571199417,1.94271337986,-1.53042912483 --4.79870271683,1.94571530819,-1.54783821106 --4.78568983078,1.94172120094,-1.56126320362 --4.78268003464,1.94272446632,-1.57666575909 --4.78066968918,1.9437277317,-1.59308564663 --4.77166318893,1.94073104858,-1.59828054905 --4.76165056229,1.9377361536,-1.61271154881 --4.76064109802,1.93973898888,-1.62912416458 --4.76563310623,1.9437404871,-1.64753937721 --4.75562143326,1.94074547291,-1.66094589233 --4.74961090088,1.94074940681,-1.67534697056 --4.73759889603,1.93775498867,-1.68877160549 --4.74759578705,1.94275379181,-1.7009922266 --4.72558164597,1.93476176262,-1.71039891243 --4.73157405853,1.93976271152,-1.72880232334 --4.72356271744,1.93776726723,-1.74322080612 --4.71355104446,1.93577218056,-1.7566318512 --4.71054172516,1.93677544594,-1.77203404903 --4.70253038406,1.93477976322,-1.78645384312 --4.6945233345,1.93278312683,-1.79267394543 --4.69451475143,1.93478548527,-1.80907511711 --4.6845035553,1.9327903986,-1.822488904 --4.67449140549,1.93079543114,-1.83590364456 --4.6694817543,1.93079912663,-1.85132420063 --4.66747188568,1.93180203438,-1.86774218082 --4.66746330261,1.93480420113,-1.88414180279 --4.66045665741,1.93180727959,-1.89035534859 --4.64244318008,1.92681443691,-1.90077197552 --4.64643573761,1.93081557751,-1.91918349266 --4.63242340088,1.92682158947,-1.93058943748 --4.6264128685,1.92682552338,-1.94602036476 --4.62640428543,1.92882752419,-1.96241819859 --4.61139154434,1.92483389378,-1.97383677959 --4.61638832092,1.92783367634,-1.98506128788 --4.60637760162,1.92583847046,-1.99745690823 --4.60436868668,1.92784118652,-2.0138733387 --4.59335613251,1.92484641075,-2.02730441093 --4.58934688568,1.92584967613,-2.04271578789 --4.58733844757,1.92785215378,-2.05810666084 --4.56632375717,1.92086029053,-2.06754302979 --4.56831979752,1.92286074162,-2.07674479485 --4.56231021881,1.9228644371,-2.09115219116 --4.54629659653,1.91887116432,-2.10259032249 --4.54728889465,1.92187285423,-2.11999893188 --4.55028152466,1.92487382889,-2.13840913773 --4.53226852417,1.91988098621,-2.14782190323 --4.52926301956,1.91988289356,-2.15502595901 --4.52125310898,1.91888713837,-2.16843104362 --4.5122423172,1.9178917408,-2.18184781075 --4.5042309761,1.9168959856,-2.19627833366 --4.50322341919,1.91889822483,-2.21268081665 --4.48520994186,1.91390550137,-2.22210073471 --4.48420143127,1.91590750217,-2.23850274086 --4.47419452667,1.91291153431,-2.24271297455 --4.47318601608,1.91491365433,-2.26013875008 --4.46717643738,1.91491723061,-2.27454781532 --4.46416759491,1.91691982746,-2.29097127914 --4.45415687561,1.91492462158,-2.30337786674 --4.43814373016,1.91093146801,-2.31278252602 --4.44413805008,1.91693115234,-2.33422112465 --4.42812919617,1.91093707085,-2.33440923691 --4.42812204361,1.91393864155,-2.35182070732 --4.42311286926,1.91494178772,-2.36724233627 --4.40810012817,1.91094839573,-2.37766313553 --4.40109014511,1.91095221043,-2.39208507538 --4.39007902145,1.90895736217,-2.40348362923 --4.38506984711,1.90896058083,-2.4189054966 --4.37506246567,1.90596461296,-2.42312431335 --4.37405490875,1.90896642208,-2.44054532051 --4.35604095459,1.90397393703,-2.44896101952 --4.35703468323,1.90797495842,-2.46635627747 --4.34702348709,1.90597987175,-2.47979283333 --4.33501195908,1.90398538113,-2.49120783806 --4.33500528336,1.9069865942,-2.50861358643 --4.31699466705,1.89999353886,-2.50782012939 --4.31398677826,1.90199589729,-2.52424073219 --4.31197929382,1.90499782562,-2.54064750671 --4.28996324539,1.89800691605,-2.54707694054 --4.28595495224,1.89900958538,-2.56248569489 --4.27894544601,1.89901340008,-2.57691025734 --4.27693843842,1.90201508999,-2.59331583977 --4.26793146133,1.89901912212,-2.59753012657 --4.25792121887,1.89802372456,-2.60892438889 --4.24991083145,1.89802789688,-2.6233625412 --4.23789930344,1.89603340626,-2.63478446007 --4.23589229584,1.89803516865,-2.65118837357 --4.22788238525,1.89803922176,-2.66460323334 --4.21587133408,1.89604473114,-2.67602682114 --4.2148680687,1.89704549313,-2.68422794342 --4.19585323334,1.89205372334,-2.69165611267 --4.1938457489,1.89405548573,-2.70805859566 --4.18383550644,1.89306020737,-2.72047948837 --4.17182445526,1.89106571674,-2.73088240623 --4.1688170433,1.89306771755,-2.74729752541 --4.15780591965,1.89207291603,-2.75973367691 --4.14779853821,1.88907718658,-2.76192378998 --4.14279031754,1.89007997513,-2.77734375 --4.13678216934,1.8910831213,-2.79175519943 --4.12977313995,1.8920866251,-2.80618071556 --4.11776161194,1.88909208775,-2.81658673286 --4.1207575798,1.89509165287,-2.83700323105 --4.10874557495,1.89309716225,-2.84843230247 --4.09873819351,1.89010155201,-2.85164952278 --4.08772706985,1.88910663128,-2.8630657196 --4.07171440125,1.88511383533,-2.87046599388 --4.06970787048,1.88811528683,-2.88788509369 --4.05669593811,1.88612127304,-2.89831018448 --4.04968690872,1.88612473011,-2.91273546219 --4.05068540573,1.88912439346,-2.92192530632 --4.04867935181,1.89212572575,-2.93934130669 --4.02165985107,1.88313770294,-2.94077920914 --4.01765346527,1.88513982296,-2.95618128777 --4.01664733887,1.88914048672,-2.97460341454 --4.00663757324,1.88814520836,-2.98702931404 --3.98962330818,1.88315296173,-2.99343085289 --3.98161697388,1.88215649128,-2.99764728546 --3.97460842133,1.88315999508,-3.01207256317 --3.96960115433,1.88416230679,-3.02646565437 --3.95358753204,1.88016963005,-3.03489971161 --3.95258259773,1.88417029381,-3.0522954464 --3.92956495285,1.87718069553,-3.05573296547 --3.93756556511,1.88617742062,-3.08013772964 --3.92755770683,1.88318192959,-3.08234405518 --3.91854810715,1.88318610191,-3.09577870369 --3.91454172134,1.88518798351,-3.11117506027 --3.89652681351,1.88019621372,-3.11760282516 --3.87851238251,1.87620460987,-3.12403297424 --3.88151025772,1.88220310211,-3.14544534683 --3.87250089645,1.88220715523,-3.1578578949 --3.86749601364,1.88220953941,-3.164072752 --3.85848689079,1.88221359253,-3.1764857769 --3.84547519684,1.88021957874,-3.18590044975 --3.84046816826,1.88222181797,-3.20233297348 --3.82945775986,1.88122689724,-3.21375823021 --3.84246253967,1.89322030544,-3.24316382408 --3.80743718147,1.87923693657,-3.23456668854 --3.80243229866,1.87923920155,-3.24078178406 --1.44086360931,0.657412469387,-1.45492708683 --1.41076767445,0.652459561825,-1.47316706181 --1.37272727489,0.633485078812,-1.44960033894 --1.42674815655,0.665464162827,-1.50406706333 --3.25893902779,1.87148082256,-3.8305811882 --3.24893093109,1.87248492241,-3.84199333191 --3.22691106796,1.86549699306,-3.84041190147 --3.20689320564,1.86050772667,-3.84184765816 --3.19187998772,1.85751521587,-3.8482735157 --3.18587517738,1.86051690578,-3.86367797852 --3.18387436867,1.86351680756,-3.87390494347 --3.16685914993,1.85952568054,-3.87731862068 --3.15685081482,1.86053001881,-3.88873243332 --3.14684247971,1.86053419113,-3.90014576912 --3.13082814217,1.85754227638,-3.90557742119 --3.13483405113,1.86753666401,-3.93400096893 --3.11481595039,1.86254775524,-3.93442773819 --3.10280442238,1.85755491257,-3.93061256409 --3.09079456329,1.85756027699,-3.94105100632 --3.07578134537,1.85556781292,-3.94748258591 --3.0707783699,1.85956847668,-3.96387767792 --3.05176091194,1.85457897186,-3.96530723572 --3.04475617409,1.85758078098,-3.98174452782 --3.03174495697,1.85658729076,-3.98813462257 --3.02273654938,1.85459208488,-3.99036622047 --3.0127286911,1.85559618473,-4.00178003311 --2.99471187592,1.8516061306,-4.00319290161 --2.99171209335,1.85760498047,-4.02462720871 --2.97169280052,1.8516163826,-4.02405118942 --2.9556787014,1.84862494469,-4.02847576141 --2.95768237114,1.85462152958,-4.04369258881 --2.94367027283,1.85262870789,-4.0501074791 --2.93966913223,1.85762822628,-4.06850671768 --2.92565655708,1.85563516617,-4.07593870163 --2.90964245796,1.85364377499,-4.08036565781 --2.89663147926,1.85264992714,-4.08879375458 --2.88161802292,1.8506578207,-4.09421682358 --2.86560320854,1.847666502,-4.09762954712 --2.86260175705,1.84966683388,-4.10684919357 --2.83857798576,1.84168183804,-4.10027694702 --2.83958292007,1.84967720509,-4.12567424774 --2.81856250763,1.84368991852,-4.12310361862 --2.80555129051,1.84269630909,-4.13051843643 --2.79854774475,1.84669756889,-4.14796113968 --2.79354405403,1.84769952297,-4.15417528152 --2.78053283691,1.84670579433,-4.16159009933 --2.76051306725,1.84071815014,-4.15900230408 --2.75751447678,1.84771609306,-4.18143224716 --2.74049830437,1.84372591972,-4.18284273148 --2.73049092293,1.84472966194,-4.19526958466 --2.71747994423,1.84473609924,-4.20268583298 --2.70646905899,1.84174287319,-4.20091056824 --2.69546055794,1.84174764156,-4.21132850647 --2.68144798279,1.8407548666,-4.21775341034 --2.67043948174,1.8417596817,-4.22715616226 --2.66443753242,1.84575998783,-4.24558210373 --2.64942455292,1.84476792812,-4.25101518631 --2.62740111351,1.83678233624,-4.24442577362 --2.63341259956,1.84577441216,-4.26764392853 --2.61940026283,1.84478139877,-4.27508497238 --2.59937977791,1.83879411221,-4.27149868011 --2.5923769474,1.8427952528,-4.28791284561 --2.57435941696,1.83880603313,-4.28834342957 --2.56234955788,1.83881163597,-4.29675388336 --2.55634880066,1.84481143951,-4.31618833542 --2.55034399033,1.84481430054,-4.32039308548 --2.52932143211,1.83782827854,-4.31480789185 --2.51631069183,1.83783447742,-4.32324266434 --2.504301548,1.83883965015,-4.33368349075 --2.49529623985,1.84084272385,-4.34608125687 --2.48328709602,1.84184777737,-4.35652160645 --2.47628068924,1.84085166454,-4.35872077942 --2.46427154541,1.84185695648,-4.36814594269 --2.44825601578,1.83886635303,-4.3705663681 --2.4392516613,1.8418687582,-4.38499069214 --2.4212334156,1.83787989616,-4.38543176651 --2.406219244,1.8358887434,-4.38782978058 --2.39420986176,1.8358938694,-4.39826965332 --2.39121031761,1.83889341354,-4.40848684311 --2.37519431114,1.83590316772,-4.40989637375 --2.36819314957,1.84090352058,-4.42731142044 --2.3511762619,1.83791387081,-4.42874670029 --2.33716344833,1.83592164516,-4.43315076828 --2.31513810158,1.8289372921,-4.42457342148 --2.30713582039,1.83293843269,-4.44201135635 --2.30313491821,1.8359388113,-4.45123624802 --2.29413104057,1.83894097805,-4.46565437317 --2.27511000633,1.83295381069,-4.4620757103 --2.27712440491,1.8459444046,-4.49648952484 --2.25009012222,1.83396577835,-4.47790956497 --2.23607802391,1.83297324181,-4.48434400558 --2.22406888008,1.83397841454,-4.49376821518 --2.21305584908,1.82998669147,-4.4889793396 --2.20505452156,1.83498752117,-4.50640964508 --2.19605112076,1.83898925781,-4.52183628082 --2.17903327942,1.83500039577,-4.52125453949 --2.16802573204,1.83600485325,-4.531665802 --2.15100812912,1.8330155611,-4.53209924698 --2.14100337029,1.83601856232,-4.54552316666 --2.12998962402,1.83202707767,-4.539727211 --2.11697912216,1.83203351498,-4.54715013504 --2.10697507858,1.83603596687,-4.56259822845 --2.08895468712,1.83104848862,-4.55901002884 --2.07594418526,1.83105492592,-4.56643390656 --2.06694149971,1.83505666256,-4.58185386658 --2.05192708969,1.83306539059,-4.58527803421 --2.04492115974,1.83306908607,-4.58849668503 --2.03191065788,1.83307552338,-4.59591960907 --2.0188999176,1.8330821991,-4.60233020782 --2.00087976456,1.82909488678,-4.5987496376 --1.9908759594,1.83209717274,-4.61419153214 --1.98187398911,1.83709836006,-4.63061857224 -2.1419570446,1.78005170822,-3.72345018387 -2.15997648239,1.78405725956,-3.72487688065 -2.15195155144,1.76604580879,-3.68128800392 -2.17097330093,1.77105247974,-3.68668556213 -2.17096805573,1.76604938507,-3.67189455032 -2.18097448349,1.76405000687,-3.66030907631 -2.19699144363,1.76705479622,-3.66070127487 -2.2130074501,1.769059062,-3.65912032127 -2.22601914406,1.77006161213,-3.65352249146 -2.23903059959,1.77006411552,-3.64693927765 -2.24703454971,1.76706421375,-3.63432121277 -2.26105237007,1.77306985855,-3.6435303688 -2.27306175232,1.77207183838,-3.63495135307 -2.27906227112,1.76707029343,-3.6173593998 -2.29808354378,1.77207660675,-3.62175917625 -2.30708932877,1.77007699013,-3.61015272141 -2.32310461998,1.77208125591,-3.60758161545 -2.34012293816,1.77608633041,-3.60897350311 -2.33410906792,1.76608026028,-3.58420467377 -2.35513353348,1.77408790588,-3.59357094765 -2.36614179611,1.77208936214,-3.58299970627 -2.37815213203,1.77209162712,-3.57639169693 -2.39116334915,1.77209413052,-3.5688226223 -2.41118526459,1.77810072899,-3.57421922684 -2.42019128799,1.77610135078,-3.56261587143 -2.4271979332,1.77710294724,-3.55982732773 -2.43920826912,1.77710533142,-3.5532181263 -2.45021653175,1.77510678768,-3.54264831543 -2.4712395668,1.78211379051,-3.54904580116 -2.47623991966,1.77711236477,-3.53046107292 -2.48724889755,1.77611422539,-3.52186012268 -2.49725937843,1.77911734581,-3.52406144142 -2.51027131081,1.78012013435,-3.51845884323 -2.52528524399,1.78112375736,-3.51388669014 -2.53729557991,1.78112614155,-3.50629210472 -2.55331110954,1.78413045406,-3.50469326973 -2.55931353569,1.78012979031,-3.48810601234 -2.56531620026,1.77612948418,-3.4725048542 -2.58333683014,1.78413629532,-3.48570561409 -2.59434604645,1.78413808346,-3.47612023354 -2.60335230827,1.78113889694,-3.46353983879 -2.61836671829,1.78414285183,-3.46093082428 -2.63037705421,1.78414511681,-3.4523525238 -2.63838243484,1.78114593029,-3.44073414803 -2.65840291977,1.78715181351,-3.44315266609 -2.66641068459,1.7881538868,-3.44235014915 -2.67041110992,1.78315281868,-3.42375946045 -2.68041872978,1.78115439415,-3.41218757629 -2.69643425941,1.78415858746,-3.41058063507 -2.70343875885,1.7811589241,-3.39599347115 -2.71745181084,1.78316235542,-3.39139175415 -2.73346710205,1.78616654873,-3.38879966736 -2.73646879196,1.78416645527,-3.38002157211 -2.74647688866,1.78316819668,-3.37041687965 -2.76149106026,1.78517210484,-3.36681842804 -2.76549220085,1.78017127514,-3.34823894501 -2.78050613403,1.78217506409,-3.34365773201 -2.80352950096,1.79018199444,-3.35005712509 -2.81153559685,1.78718304634,-3.33746170998 -2.8105328083,1.78318154812,-3.32466983795 -2.82955145836,1.78818690777,-3.32606673241 -2.82954859734,1.78118503094,-3.30347704887 -2.84055829048,1.78018724918,-3.29291439056 -2.8655834198,1.7891947031,-3.30229449272 -2.86958503723,1.78419458866,-3.28470563889 -2.87659049034,1.78119540215,-3.27012896538 -2.88760137558,1.7851985693,-3.27331137657 -2.89460659027,1.78219950199,-3.2587351799 -2.90761852264,1.78320240974,-3.25116086006 -2.9196293354,1.78420519829,-3.24356412888 -2.92963814735,1.78320729733,-3.23396229744 -2.94164896011,1.78421008587,-3.22636580467 -2.94765424728,1.78421151638,-3.22158575058 -2.95766282082,1.78321349621,-3.21100282669 -2.9686729908,1.7832159996,-3.20240354538 -2.99169492722,1.7902225256,-3.20779418945 -2.99870085716,1.78822350502,-3.19420337677 -2.9866874218,1.77421879768,-3.1586329937 -3.01971936226,1.78722834587,-3.17501997948 -3.01971888542,1.78422784805,-3.16324782372 -3.0287270546,1.78322970867,-3.15264487267 -3.04273962975,1.78423321247,-3.14606976509 -3.05374956131,1.78423583508,-3.13747048378 -3.0627579689,1.78423786163,-3.12686753273 -3.07476878166,1.78424072266,-3.118288517 -3.08377695084,1.78324270248,-3.10670638084 -3.08878159523,1.78324389458,-3.10190582275 -3.1027944088,1.78524756432,-3.09630894661 -3.10879993439,1.78224873543,-3.08172488213 -3.12681674957,1.78725337982,-3.08012938499 -3.13182115555,1.78325438499,-3.06454586983 -3.14883685112,1.78725874424,-3.06096792221 -3.15083861351,1.78525924683,-3.05414700508 -3.16685342789,1.78826320171,-3.04956746101 -3.16985654831,1.78426384926,-3.03198575974 -3.17786383629,1.78226578236,-3.02038598061 -3.19187688828,1.78426933289,-3.0138053894 -3.20288729668,1.78427219391,-3.00422501564 -3.21990275383,1.78827643394,-3.00162148476 -3.22390651703,1.7872774601,-2.99484181404 -3.23691868782,1.78928077221,-2.98823904991 -3.24192380905,1.78628218174,-2.97266197205 -3.25593662262,1.78828561306,-2.96705794334 -3.26494526863,1.78728806973,-2.95645833015 -3.27995896339,1.7902919054,-2.95087218285 -3.29297113419,1.79229521751,-2.94426679611 -3.29397249222,1.7902957201,-2.93547105789 -3.29797720909,1.78629696369,-2.91889977455 -3.32299900055,1.79430305958,-2.92231678963 -3.33000612259,1.79330503941,-2.90971946716 -3.34602069855,1.79630899429,-2.90512752533 -3.35202717781,1.79431092739,-2.89153265953 -3.37104392052,1.79931557178,-2.88993263245 -3.36303830147,1.79131412506,-2.87215924263 -3.37705135345,1.79431772232,-2.86556911469 -3.37705302238,1.78831839561,-2.84697031975 -3.4040760994,1.79732477665,-2.85138964653 -3.39807367325,1.7893242836,-2.82680797577 -3.41909170151,1.79532933235,-2.82719731331 -3.42609930038,1.79433166981,-2.81362438202 -3.45212030411,1.80533719063,-2.82682466507 -3.44511699677,1.79633665085,-2.80222988129 -3.46913743019,1.80334222317,-2.80364608765 -1.45622050762,0.610241115093,-0.714907050133 -3.6714951992,1.68547797203,-2.08743977547 -3.70551896095,1.69848382473,-2.09381532669 -3.67050790787,1.67748451233,-2.05527424812 -3.66150975227,1.67048704624,-2.03467869759 -3.65451002121,1.66548836231,-2.02190852165 -3.66452169418,1.66649222374,-2.01329922676 -3.67053198814,1.66549634933,-2.00073218346 -3.67654180527,1.66550016403,-1.98913931847 -3.68155169487,1.66450405121,-1.97655761242 -3.68556046486,1.66250777245,-1.96396148205 -3.69457244873,1.6635119915,-1.95338821411 -3.70758247375,1.66851460934,-1.95358371735 -3.71159172058,1.66651856899,-1.94001400471 -3.72160410881,1.66852283478,-1.93042767048 -3.7086045742,1.65852546692,-1.90881991386 -3.71961760521,1.66053009033,-1.89924967289 -3.72562789917,1.66053414345,-1.88765871525 -3.72963762283,1.65853822231,-1.8740926981 -3.72663998604,1.65553975105,-1.86529064178 -3.73965358734,1.65854430199,-1.85769462585 -3.73866128922,1.65554833412,-1.84113824368 -3.7436709404,1.65455234051,-1.82953488827 -3.7576854229,1.65855693817,-1.82195103168 -3.75369143486,1.65256083012,-1.80438292027 -3.76170301437,1.65356504917,-1.79379498959 -3.76170682907,1.652567029,-1.78698563576 -3.77071857452,1.65357112885,-1.777384758 -3.77572894096,1.65257561207,-1.76480960846 -3.79374504089,1.65858030319,-1.75922238827 -3.77374458313,1.64558374882,-1.7336602211 -3.78375720978,1.64758837223,-1.72407317162 -3.78876376152,1.64859056473,-1.71927928925 -3.80577874184,1.65359520912,-1.71367537975 -3.80778837204,1.65159964561,-1.69911599159 -3.81680011749,1.65260410309,-1.68951296806 -3.80680465698,1.6456079483,-1.66993391514 -3.8128156662,1.64561235905,-1.65834736824 -3.81582570076,1.64361691475,-1.64477741718 -3.82683420181,1.64761936665,-1.64297747612 -3.82284140587,1.64262366295,-1.62640023232 -3.82985258102,1.64362800121,-1.61579918861 -3.8278605938,1.63963246346,-1.60022258759 -3.8558807373,1.64963757992,-1.59863722324 -3.850887537,1.64564180374,-1.5820505619 -3.86289644241,1.64864432812,-1.58025884628 -3.85690331459,1.64364886284,-1.5626899004 -3.86791610718,1.64565324783,-1.55408155918 -3.8699259758,1.64465796947,-1.54050159454 -3.86993527412,1.64266264439,-1.52592623234 -3.88094830513,1.64466738701,-1.51634478569 -3.88295769691,1.64267170429,-1.50373840332 -3.88096213341,1.64067423344,-1.49497032166 -3.87797045708,1.6366789341,-1.47939074039 -3.89198446274,1.64068353176,-1.47178697586 -3.89399456978,1.63968837261,-1.45821094513 -3.89600491524,1.63769316673,-1.44463598728 -3.9080183506,1.64069771767,-1.43603467941 -3.90302634239,1.63670265675,-1.41946494579 -3.91603541374,1.64070510864,-1.41767287254 -3.91804552078,1.63970983028,-1.40506982803 -3.92805886269,1.64171481133,-1.394500494 -3.93206977844,1.64071965218,-1.38192081451 -3.93407964706,1.63972437382,-1.36931860447 -3.93008780479,1.63572919369,-1.35373747349 -3.93710017204,1.63673436642,-1.34216320515 -3.93610501289,1.63473701477,-1.334384799 -3.94311666489,1.63574159145,-1.32378125191 -3.9461274147,1.63474655151,-1.31119251251 -3.95614075661,1.63675165176,-1.3006207943 -3.94714832306,1.63075685501,-1.28305089474 -3.96616411209,1.63676166534,-1.27645659447 -3.96616911888,1.63676416874,-1.26966094971 -3.97518181801,1.63776922226,-1.25907695293 -3.97119092941,1.63377439976,-1.24350476265 -3.96719956398,1.62977945805,-1.22890484333 -3.98421478271,1.63578426838,-1.22131311893 -3.99022650719,1.6367893219,-1.20972633362 -3.98423576355,1.6317949295,-1.19316768646 -3.99024248123,1.63279747963,-1.1883752346 -4.00725793839,1.63880217075,-1.18077814579 -3.99926590919,1.63280773163,-1.16420257092 -3.9932744503,1.62881314754,-1.14861857891 -4.00228738785,1.63081812859,-1.13803160191 -4.00930023193,1.63182342052,-1.12645471096 -4.01531219482,1.63282871246,-1.11486768723 -4.01331663132,1.63083100319,-1.10805737972 -4.00932645798,1.62683689594,-1.0924975872 -4.02334070206,1.63184165955,-1.0838944912 -4.03835535049,1.63684654236,-1.07529878616 -4.02336168289,1.62785255909,-1.05673158169 -4.03437614441,1.63085782528,-1.04615902901 -4.04238843918,1.63286292553,-1.03555858135 -4.05139732361,1.63586556911,-1.03078651428 -4.04240465164,1.6298712492,-1.01518809795 -4.04841709137,1.63087642193,-1.00359988213 -4.05042886734,1.62988233566,-0.990037560463 -4.06144237518,1.63288724422,-0.980430543423 -4.06545448303,1.63289272785,-0.967854499817 -4.05645799637,1.62889611721,-0.958081543446 -4.06046962738,1.62890124321,-0.946476519108 -4.06448221207,1.62890696526,-0.933901548386 -4.06449365616,1.62691271305,-0.920325279236 -4.06650495529,1.62691819668,-0.907734692097 -4.08051919937,1.63092327118,-0.898146867752 -4.06652784348,1.62392997742,-0.88058501482 -4.08253717422,1.62993216515,-0.877798318863 -4.08954906464,1.63093721867,-0.867184996605 -4.08255958557,1.62694358826,-0.851618647575 -4.08057022095,1.62394940853,-0.838030695915 -4.09958600998,1.63095426559,-0.829442977905 -4.0865945816,1.62396085262,-0.812867760658 -4.08660650253,1.62296688557,-0.799295723438 -4.09561443329,1.62596940994,-0.794511854649 -4.10462760925,1.6279746294,-0.783910751343 -4.10163831711,1.62598061562,-0.770317971706 -4.1176533699,1.63098561764,-0.76073205471 -4.11166381836,1.62699198723,-0.74615085125 -4.113676548,1.62699818611,-0.732592880726 -4.11268806458,1.62500441074,-0.719016075134 -4.12169504166,1.62800645828,-0.715196609497 -4.11570549011,1.62401294708,-0.700619280338 -4.12171936035,1.6260188818,-0.688056349754 -4.12673187256,1.62702441216,-0.676456212997 -4.11874198914,1.62203097343,-0.661869943142 -4.12475585938,1.62403702736,-0.649306774139 -4.12476205826,1.62304008007,-0.642522931099 -4.12377309799,1.62104606628,-0.629918992519 -4.12478590012,1.62005257607,-0.616357982159 -4.14580106735,1.62805700302,-0.607754230499 -4.13681125641,1.62406373024,-0.593167662621 -4.13082313538,1.62007057667,-0.57859992981 -4.12583398819,1.61707699299,-0.565007984638 -4.12884092331,1.61708033085,-0.558241784573 -4.13685464859,1.62008607388,-0.546656429768 -4.15086984634,1.62409126759,-0.536069631577 -4.13987970352,1.61909818649,-0.521480381489 -4.14589262009,1.62010395527,-0.509883582592 -4.1389040947,1.61711108685,-0.49531686306 -4.15091896057,1.62011671066,-0.483748167753 -4.15392541885,1.62111949921,-0.477948904037 -4.1489367485,1.61812615395,-0.464362472296 -4.15495061874,1.62013244629,-0.451795011759 -4.15796327591,1.62013828754,-0.440182745457 -4.15897655487,1.62014496326,-0.426624000072 -4.14798736572,1.61415231228,-0.41204726696 -4.15700149536,1.61715805531,-0.400460153818 -4.16600847244,1.62016034126,-0.39565294981 -4.15702056885,1.61616778374,-0.381086707115 -4.16603422165,1.61917352676,-0.369497418404 -4.17104816437,1.62017977238,-0.356923311949 -4.16805934906,1.61818623543,-0.344319611788 -4.16907310486,1.61819303036,-0.330762118101 -4.17208003998,1.61919605732,-0.32496073842 -4.17009305954,1.61720299721,-0.311393350363 -4.17210578918,1.61720943451,-0.298808336258 -4.17011833191,1.61621594429,-0.286210358143 -4.17313146591,1.61722242832,-0.273628473282 -4.17714500427,1.61722886562,-0.261049747467 -4.17815828323,1.61723530293,-0.248461484909 -4.17916488647,1.61723875999,-0.241684600711 -4.1771774292,1.61624538898,-0.229088127613 -4.18219089508,1.61725187302,-0.216511130333 -4.17720413208,1.61525928974,-0.202939063311 -4.1752166748,1.61426591873,-0.190344154835 -4.18723201752,1.61827194691,-0.177783161402 -4.18623781204,1.61727511883,-0.171969994903 -4.18425130844,1.61628234386,-0.158406868577 -4.18126344681,1.61428928375,-0.145810902119 -4.18627786636,1.6162956953,-0.133231654763 -4.18729114532,1.61630237103,-0.120644077659 -4.18630504608,1.61530983448,-0.107084520161 -4.18731832504,1.6153165102,-0.0944971814752 -4.17932415009,1.61132061481,-0.0877052247524 -4.18933868408,1.61532688141,-0.0751327872276 -4.19535303116,1.61733317375,-0.0625527352095 -4.1923661232,1.61634016037,-0.0499591343105 -4.19537973404,1.61734688282,-0.0373740568757 -4.20039367676,1.61835324764,-0.0247911699116 -4.19140672684,1.61436140537,-0.0112236831337 -4.18641328812,1.61236560345,-0.00444009527564 -4.19442653656,1.61537134647,0.0071718506515 -4.19544124603,1.61537873745,0.0207277853042 -4.19545459747,1.61538565159,0.0333162844181 -4.19446802139,1.61439263821,0.0459051467478 -4.19348192215,1.61439979076,0.0584940053523 -4.18748855591,1.61140406132,0.0652750059962 -4.20250320435,1.61740970612,0.0778563395143 -4.2015171051,1.61741673946,0.0904455035925 -4.20153188705,1.61742436886,0.104002431035 -4.20454549789,1.61743104458,0.116590276361 -4.18955802917,1.6114397049,0.129179134965 -4.20257282257,1.6174454689,0.14176774025 -4.19757986069,1.61444973946,0.148545145988 -4.20159387589,1.61645638943,0.161134153605 -4.19760751724,1.61446404457,0.173721000552 -4.19962263107,1.61547148228,0.187278136611 -4.20363664627,1.61747813225,0.199868455529 -4.19765043259,1.61448609829,0.212452948093 -4.19966411591,1.61549305916,0.225042328238 -4.19467163086,1.61349749565,0.231816619635 -4.21068620682,1.62050271034,0.244418427348 -4.19969987869,1.61551129818,0.256996721029 -4.1977148056,1.61451935768,0.270550966263 -4.19372844696,1.61352705956,0.283134400845 -4.20974302292,1.62053215504,0.295742541552 -4.19675683975,1.61454129219,0.308313786983 -4.19876480103,1.6155449152,0.315094858408 -4.20177841187,1.61755180359,0.32768791914 -4.20479393005,1.61855912209,0.341249704361 -4.20080804825,1.61756706238,0.353832036257 -4.2058224678,1.61957359314,0.366429805756 -4.19583654404,1.61558258533,0.379000037909 -4.19984436035,1.61758589745,0.385786354542 -4.19185876846,1.61459445953,0.398358821869 -4.20087242126,1.61760044098,0.410966306925 -4.19588708878,1.61660861969,0.423544555902 -4.20090246201,1.61861562729,0.437113583088 -4.20791721344,1.6216224432,0.450688719749 -4.19393157959,1.61663174629,0.462275147438 -4.20293855667,1.62063419819,0.469077378511 -4.20195293427,1.62064182758,0.481664866209 -4.19496774673,1.61765050888,0.494235485792 -4.19798326492,1.61965799332,0.50780248642 -4.1899971962,1.61666631699,0.5194003582 -4.19101285934,1.61767423153,0.532961606979 -4.19002723694,1.61768186092,0.545548439026 -4.19603443146,1.62068486214,0.552347183228 -4.19004964828,1.61769342422,0.564917743206 -4.19206428528,1.61970055103,0.577515244484 -4.19108009338,1.61970889568,0.591071128845 -4.18809461594,1.61871695518,0.603651225567 -4.19010925293,1.6207242012,0.616249799728 -4.18211698532,1.61772930622,0.622031092644 -4.17213153839,1.61373817921,0.633614599705 -4.1761469841,1.61574566364,0.647189021111 -4.18716239929,1.62075209618,0.661761641502 -4.17817735672,1.61776101589,0.673347771168 -4.17519235611,1.61776924133,0.685926735401 -4.17020654678,1.61577749252,0.697527825832 -4.16921472549,1.61578178406,0.704303324223 -4.16623020172,1.61479008198,0.716881155968 -4.1752448082,1.61979627609,0.730482876301 -4.20626020432,1.63379991055,0.748064577579 -4.17127656937,1.6198130846,0.756618201733 -4.16229152679,1.61682224274,0.768198549747 -4.18230628967,1.62582707405,0.783796846867 -4.16731452942,1.61983346939,0.788565576077 -4.16732978821,1.62084126472,0.801159203053 -4.15834522247,1.61785042286,0.812737345695 -4.1573600769,1.61785840988,0.82532531023 -4.17037582397,1.62486469746,0.840896070004 -4.17039060593,1.62487244606,0.853491306305 -4.16440677643,1.62388157845,0.866053581238 -4.18741369247,1.63388192654,0.87587249279 -4.18342924118,1.63289058208,0.888447523117 -4.16944503784,1.62790060043,0.899026036263 -4.16046094894,1.62490999699,0.910600781441 -4.14847755432,1.62092030048,0.922156155109 -4.14149332047,1.61892926693,0.933740317822 -4.1435008049,1.62093293667,0.940535187721 -4.13951730728,1.61994183064,0.953106284142 -4.13153266907,1.61795115471,0.964682638645 -4.12754821777,1.61695945263,0.976283788681 -4.12856388092,1.61796760559,0.989855349064 -4.12558031082,1.61797630787,1.00243222713 -4.11259651184,1.61398649216,1.01300311089 -4.12960338593,1.62098789215,1.02280855179 -4.11361980438,1.61599838734,1.03238916397 -4.09163665771,1.60801005363,1.04095566273 -4.11965227127,1.6210142374,1.06053388119 -4.14166641235,1.63101863861,1.07813668251 -4.12068319321,1.62403011322,1.08670854568 -3.62172293663,1.6691390276,2.50414657593 -3.57774829865,1.65115666389,2.49072027206 -3.54677200317,1.6391723156,2.48628044128 -3.55078101158,1.64317631721,2.49706530571 -3.53580164909,1.63918864727,2.50264453888 -3.49682569504,1.62320506573,2.49123382568 -3.49684405327,1.62721455097,2.50681710243 -3.4858648777,1.62622618675,2.51538443565 -3.47588467598,1.62423741817,2.52396941185 -3.47690320015,1.62924671173,2.54054808617 -3.47191381454,1.62825262547,2.54532766342 -3.45793390274,1.62526452541,2.55091619492 -3.46095252037,1.63027369976,2.56948280334 -3.45097160339,1.62928438187,2.57709336281 -3.43999266624,1.62729632854,2.58565878868 -3.4440100193,1.63330471516,2.60424900055 -3.42603254318,1.62831807137,2.6078107357 -3.4190428257,1.62632417679,2.61060261726 -3.41606163979,1.62933409214,2.62419080734 -3.41108131409,1.63034451008,2.63676738739 -3.41010022163,1.63435435295,2.65234541893 -3.39812135696,1.63236641884,2.65991592407 -3.38814163208,1.63137769699,2.66849899292 -3.37715291977,1.62738466263,2.66828751564 -3.37317276001,1.6293951273,2.68185973167 -3.37618947029,1.63540351391,2.69946885109 -3.37021040916,1.63641452789,2.71203017235 -3.35423135757,1.63242697716,2.71562004089 -3.35025119781,1.63443732262,2.72919559479 -3.3422703743,1.63444805145,2.73879218102 -3.33328223228,1.63245499134,2.74056577682 -3.32830190659,1.63346540928,2.75314736366 -3.32232260704,1.63547670841,2.76571035385 -3.31434226036,1.63548743725,2.7753071785 -3.2983648777,1.63150048256,2.77986598015 -3.29438447952,1.63351094723,2.7934448719 -3.29540205002,1.63851964474,2.8100528717 -3.29341268539,1.63952553272,2.81781959534 -3.26943564415,1.631539464,2.81440758705 -3.27845311165,1.64054751396,2.8389878273 -3.26347494125,1.63756012917,2.84356355667 -3.25249576569,1.63557183743,2.85114765167 -3.24551558495,1.63658237457,2.86174178123 -3.24052739143,1.63658905029,2.86749601364 -3.23954582214,1.64059853554,2.88309526443 -3.2295665741,1.63961005211,2.89167618752 -3.21358895302,1.63562297821,2.89525032043 -3.21060848236,1.63963317871,2.90983438492 -3.20462799072,1.64064371586,2.92142772675 -3.19665002823,1.64165556431,2.93297958374 -3.19265961647,1.64166092873,2.93777918816 -3.1796810627,1.63967311382,2.94336628914 -3.17370080948,1.64068365097,2.95496034622 -3.16172289848,1.63969612122,2.96252131462 -3.15974211693,1.64270603657,2.9781088829 -3.16176080704,1.64871525764,2.99769186974 -3.1457836628,1.64572846889,3.00125980377 -3.13679504395,1.64273524284,3.00204443932 -3.12681531906,1.64274632931,3.00964736938 -3.12183594704,1.64475727081,3.02322077751 -3.10985732079,1.6427693367,3.02980303764 -3.10287928581,1.64478099346,3.04235720634 -3.09490036964,1.64579248428,3.05293536186 -3.09190988541,1.64579772949,3.05873513222 -3.08293104172,1.64580929279,3.06831479073 -3.07095265388,1.6448212862,3.07489585876 -3.06097388268,1.64483308792,3.08347558975 -3.0599937439,1.64884305,3.10105323792 -3.04701566696,1.64685535431,3.1066339016 -3.041036129,1.64886641502,3.11921453476 -3.0320482254,1.64687335491,3.11999320984 -3.01806926727,1.64388537407,3.12359380722 -3.01708984375,1.64889585972,3.14215517044 -3.00811004639,1.64890694618,3.15075755119 -2.99613213539,1.64791917801,3.15733647346 -2.9901535511,1.64993059635,3.1708984375 -2.98216557503,1.64893734455,3.17267489433 -2.97018671036,1.64694917202,3.17827439308 -2.96920681,1.65195941925,3.1968433857 -2.95622801781,1.64997148514,3.20144152641 -2.94725060463,1.65098357201,3.21200227737 -2.94027137756,1.6519947052,3.22358727455 -2.9322912693,1.65300559998,3.23319292068 -2.92330360413,1.65101265907,3.23396587372 -2.91632437706,1.65202367306,3.24555182457 -2.90834641457,1.65403556824,3.25711607933 -2.89836812019,1.65404736996,3.26569747925 -2.88538980484,1.65205955505,3.27029252052 -2.87941217422,1.65507137775,3.28484177589 -2.86643266678,1.65208292007,3.28845667839 -2.86744308472,1.65608811378,3.30023217201 -2.85946512222,1.65809988976,3.3117992878 -2.84348797798,1.65411281586,3.31338429451 -2.83850812912,1.65712332726,3.32698106766 -2.82852983475,1.65713524818,3.33556318283 -2.81355237961,1.6541479826,3.33814907074 -2.80157566071,1.65316092968,3.345703125 -2.80758404732,1.66016447544,3.36250281334 -2.79860520363,1.66117608547,3.37208986282 -2.78462862968,1.65918898582,3.37665772438 -2.77565002441,1.65920054913,3.38624429703 -2.7686715126,1.6622120142,3.3988199234 -2.74769616127,1.65522634983,3.3943965435 -2.74670696259,1.65823173523,3.40417528152 -2.74172663689,1.66124212742,3.4177801609 -2.7307498455,1.6612547636,3.42633986473 -2.71977114677,1.66026651859,3.43293833733 -2.70579385757,1.65827918053,3.43652200699 -2.69681620598,1.65929114819,3.44709086418 -2.69483661652,1.66530144215,3.46567678452 -2.67985057831,1.65930986404,3.45844650269 -2.67387151718,1.66232097149,3.47203207016 -2.66789269447,1.66533195972,3.48561954498 -2.65391540527,1.66234469414,3.48920106888 -2.64493703842,1.66335630417,3.49879169464 -2.62896108627,1.66036975384,3.50036072731 -2.62597155571,1.66237521172,3.5071554184 -2.62199306488,1.6663864851,3.52472043037 -2.6090157032,1.66539883614,3.52930688858 -2.59203863144,1.66041183472,3.52790379524 -2.58206152916,1.66142427921,3.53747034073 -2.57808208466,1.66543483734,3.55405855179 -2.5651049614,1.6644474268,3.55864334106 -2.56511449814,1.66845226288,3.56944298744 -2.55413794518,1.66846489906,3.57800531387 -2.53716230392,1.66447854042,3.57757949829 -2.53518223763,1.67048859596,3.59716963768 -2.52120494843,1.66850113869,3.59976458549 -2.51722693443,1.6735124588,3.61832594872 -2.50724887848,1.67452430725,3.62691521645 -2.49926114082,1.67253112793,3.62769603729 -2.49828124046,1.6795412302,3.64928483963 -2.48130559921,1.67555487156,3.64885592461 -2.47932672501,1.68256568909,3.67042326927 -2.47834730148,1.6905759573,3.69300246239 -2.4733684063,1.69458699226,3.70958638191 -2.46938896179,1.70059752464,3.72718071938 -2.47039961815,1.70560276508,3.74195337296 -2.46941971779,1.71361279488,3.76454377174 -2.46643996239,1.71962332726,3.78413724899 -2.46646046638,1.72863352299,3.80971002579 -2.45848298073,1.7316454649,3.8232820034 -2.44750499725,1.73165738583,3.83087730408 -2.46651101112,1.75065886974,3.87365961075 -2.44553661346,1.74367332458,3.86723327637 -2.44055747986,1.74968421459,3.88482284546 -2.45557570457,1.77069199085,3.93637895584 -2.45059609413,1.77570259571,3.95397639275 -2.43861937523,1.77571511269,3.96155714989 -2.41964435577,1.77072918415,3.95813274384 -2.418653965,1.77473402023,3.96893954277 -2.40267848969,1.77174758911,3.9705119133 -2.3897023201,1.77176058292,3.97708201408 -2.38072395325,1.77377212048,3.98867630959 -2.36574792862,1.77178525925,3.99125671387 -2.35177111626,1.76979792118,3.99484634399 -2.33979535103,1.77081084251,4.00341129303 -2.32780838013,1.76581835747,3.9971985817 -2.32282924652,1.77182924747,4.01579189301 -2.31185269356,1.77284157276,4.02536821365 -2.2928776741,1.76785564423,4.02094697952 -2.28290081024,1.76986789703,4.03251934052 -2.27092432976,1.76988053322,4.04009962082 -2.25693702698,1.76288807392,4.02890253067 -2.24496078491,1.76390075684,4.03648138046 -2.2289853096,1.7609140873,4.03705835342 -2.21300911903,1.75792717934,4.03664827347 -2.19803357124,1.75594067574,4.03921985626 -2.18505716324,1.75595343113,4.04480028152 -2.1790792942,1.76096475124,4.06337928772 -2.16809248924,1.75697207451,4.05816507339 -2.15511536598,1.75698447227,4.06275939941 -2.14213991165,1.7569975853,4.06932592392 -2.13016295433,1.75700986385,4.07591867447 -2.12018680573,1.76002252102,4.08848142624 -2.1012108326,1.75303602219,4.08108186722 -2.09023451805,1.75504851341,4.09065914154 -2.08624577522,1.75705444813,4.09844732285 -2.07726883888,1.76006650925,4.11202526093 -2.05929350853,1.75608026981,4.10760784149 -2.04731750488,1.75709271431,4.11518764496 -2.03933930397,1.76010429859,4.12978076935 -2.02436447144,1.75911784172,4.13234806061 -2.01737618446,1.7581243515,4.1341381073 -2.00339984894,1.75713694096,4.13673067093 -1.99342358112,1.76014947891,4.14930057526 -1.97744762897,1.75716257095,4.14789009094 -1.97046983242,1.76217412949,4.16547775269 -1.95449459553,1.75918757915,4.16505432129 -1.93851900101,1.75620079041,4.16364240646 -1.93853008747,1.76320612431,4.18141889572 -1.91955542564,1.75722002983,4.17400121689 -1.90657949448,1.75723290443,4.17958116531 -1.89860165119,1.76124453545,4.19517230988 -1.88062751293,1.75725853443,4.19074058533 -1.86665201187,1.75627160072,4.19431829453 -1.85567462444,1.75728356838,4.20291566849 -1.84668767452,1.75529062748,4.2006983757 -1.83871090412,1.76030266285,4.21827125549 -1.81973516941,1.75331604481,4.20787811279 -1.80876016617,1.75732910633,4.22042989731 -1.7927839756,1.75334191322,4.21703338623 -1.7818082571,1.75635480881,4.22859859467 -1.76783180237,1.75436735153,4.23019695282 -1.76084411144,1.75337386131,4.23198461533 -1.74686825275,1.75338673592,4.23457145691 -1.73089325428,1.75040018559,4.23314809799 -1.72191667557,1.75441241264,4.24872493744 -1.70694196224,1.75342583656,4.25029468536 -1.69496548176,1.75443828106,4.25788021088 -1.68897688389,1.75444424152,4.26068401337 -1.67500162125,1.75345742702,4.26425933838 -1.66202640533,1.75447046757,4.27082920074 -1.64805066586,1.75348329544,4.27341413498 -1.63307404518,1.75049579144,4.27102422714 -1.61709952354,1.74750936031,4.26959514618 -1.6041238308,1.74852228165,4.2751750946 -1.5981361866,1.74952876568,4.2799577713 -1.57816171646,1.74154269695,4.26555013657 -1.56918525696,1.74655473232,4.28212690353 -1.56120741367,1.75256609917,4.29972362518 -1.53923404217,1.74158072472,4.28030633926 -1.53125822544,1.74959313869,4.30186462402 -1.52726864815,1.75159847736,4.30967473984 -1.51329410076,1.75161194801,4.31423854828 -1.4953199625,1.74662578106,4.30581712723 -1.48234283924,1.74563777447,4.30842590332 -1.46736824512,1.7446513176,4.30899810791 -1.45939135551,1.75066316128,4.32957601547 -1.44341647625,1.74767637253,4.3261590004 -1.43942737579,1.75068199635,4.33496332169 -1.42345297337,1.74769556522,4.33253526688 -1.4104783535,1.74970889091,4.34009885788 -1.39450216293,1.74472165108,4.33370542526 -1.38552629948,1.75173389912,4.35327339172 -1.37254977226,1.75174617767,4.35687446594 -1.35757613182,1.75075995922,4.35942792892 -1.34758841991,1.74576663971,4.34923505783 -1.33361363411,1.74577987194,4.35280656815 -1.31863844395,1.74379301071,4.35139226913 -1.30566287041,1.74480581284,4.35697460175 -1.29368686676,1.74681818485,4.36556053162 -1.27571296692,1.74083209038,4.35513544083 -1.26473701,1.74484455585,4.36771631241 -1.2587480545,1.7448502779,4.36953020096 -1.24377417564,1.74386382103,4.37108945847 -1.23279726505,1.74687576294,4.38168907166 -1.21582329273,1.74188959599,4.37426280975 -1.20484781265,1.7469022274,4.38883304596 -1.19387114048,1.75091421604,4.4004278183 -1.18388426304,1.74492120743,4.39022159576 -1.16590988636,1.7379347086,4.37680864334 -1.15693283081,1.7449464798,4.39640045166 -1.13995909691,1.74096035957,4.38896846771 -1.12598311901,1.73897278309,4.38856840134 -1.11300861835,1.7419860363,4.39713096619 -1.0970338583,1.73799920082,4.39071655273 -1.0930454731,1.74200510979,4.40350914001 -1.08006954193,1.74301755428,4.40810203552 --5.55609226227,11.5565414429,27.1012992859 --1.19381260872,1.73206269741,4.18060016632 --1.21578621864,1.74607551098,4.20819759369 --1.22476315498,1.73908627033,4.18979167938 --1.23373949528,1.7320972681,4.17037439346 --1.25171363354,1.73910963535,4.18195962906 --1.25270330906,1.73211431503,4.1617603302 --1.2716780901,1.74112653732,4.17836284637 --1.28565311432,1.74213826656,4.17594671249 --1.29762887955,1.74014949799,4.16753435135 --1.31060397625,1.73916137218,4.16111135483 --1.32757902145,1.74517309666,4.16970872879 --1.33156716824,1.74117863178,4.15849637985 --1.34754180908,1.74519062042,4.16207885742 --1.36451649666,1.75020253658,4.16967153549 --1.37349390984,1.74521315098,4.15327072144 --1.38846790791,1.74622535706,4.15183782578 --1.3984452486,1.74323582649,4.13944292068 --1.41441965103,1.74624800682,4.14202070236 --1.42540585995,1.75225448608,4.1518073082 --1.43838202953,1.75226569176,4.14740467072 --1.44635927677,1.74627614021,4.1279964447 --1.46333456039,1.75128781796,4.13559865952 --1.47730863094,1.75129985809,4.13015842438 --1.49028432369,1.75131130219,4.12474632263 --1.50326108932,1.75232219696,4.12135362625 --1.5122474432,1.7543284893,4.12413406372 --1.52722346783,1.75733971596,4.12573766708 --1.53819954395,1.75435078144,4.11432027817 --1.55217468739,1.75536227226,4.11090230942 --1.56615042686,1.75637364388,4.10849475861 --1.5781263113,1.75538480282,4.1000790596 --1.58511424065,1.75639045238,4.09887552261 --1.60308814049,1.76140260696,4.10545444489 --1.61306536198,1.75841319561,4.0930519104 --1.62104284763,1.75342345238,4.07564878464 --1.64101648331,1.76043581963,4.08723020554 --1.65499138832,1.76144754887,4.0828037262 --1.66896796227,1.76345837116,4.08141088486 --1.67595589161,1.763463974,4.08020925522 --1.6859318018,1.76047503948,4.06578111649 --1.70290791988,1.76548624039,4.07239723206 --1.71288371086,1.76149725914,4.05796813965 --1.72685992718,1.76350820065,4.05556535721 --1.74083483219,1.76351976395,4.05114078522 --1.75281143188,1.76353061199,4.04373598099 --1.76379871368,1.76853644848,4.05254364014 --1.77577424049,1.76754784584,4.04311609268 --1.78874981403,1.76755905151,4.03669595718 --1.80172646046,1.76756978035,4.03229951859 --1.81270229816,1.76558089256,4.02087402344 --1.82767820358,1.76759195328,4.02047252655 --1.8356654644,1.76959776878,4.0202589035 --1.84364295006,1.76460802555,4.00385093689 --1.86361777782,1.77261960506,4.01445245743 --1.87259495258,1.76863002777,4.00004148483 --1.88756990433,1.77064156532,3.99761843681 --1.90454542637,1.7746527195,4.00121831894 --1.91352188587,1.77066349983,3.98579335213 --1.92450881004,1.77566945553,3.99259090424 --1.9344855547,1.77268004417,3.9801762104 --1.95246040821,1.77769160271,3.98476672173 --1.96743631363,1.78070259094,3.9833612442 --1.97841274738,1.77871322632,3.97294521332 --1.99038887024,1.77772414684,3.96452879906 --1.99836742878,1.77473390102,3.9501376152 --2.01235342026,1.78074038029,3.96192955971 --2.02432966232,1.78075122833,3.95351314545 --2.03630566597,1.77976191044,3.94509649277 --2.04928231239,1.7807725668,3.93969321251 --2.05925893784,1.77778315544,3.92727446556 --2.07223629951,1.77879333496,3.9228849411 --2.07922410965,1.77979886532,3.92067742348 --2.09619927406,1.7838101387,3.92226719856 --2.10717582703,1.78182077408,3.91184878349 --2.12315154076,1.78483188152,3.91143918037 --2.13812708855,1.78784286976,3.90902853012 --2.14810371399,1.7848533392,3.89660787582 --2.16307973862,1.78786420822,3.89419841766 --2.17306661606,1.79087018967,3.89698672295 --2.18304467201,1.78887999058,3.88659358025 --2.20301866531,1.79489171505,3.89217305183 --2.21699500084,1.79690241814,3.88776421547 --2.22597241402,1.79391264915,3.87435364723 --2.24094843864,1.79592323303,3.87194919586 --2.25392484665,1.79693377018,3.86553812027 --2.26191306114,1.79893922806,3.8653383255 --2.27788877487,1.80195009708,3.86392569542 --2.2898645401,1.80096101761,3.85449719429 --2.29884266853,1.79897069931,3.84209871292 --2.31481909752,1.80198121071,3.84170293808 --2.32979512215,1.80399215221,3.83828878403 --2.33778333664,1.80599737167,3.83809185028 --2.35275936127,1.80800807476,3.83467936516 --2.37473297119,1.81601977348,3.84226083755 --2.37771177292,1.8080291748,3.81884431839 --2.40168523788,1.81704115868,3.82942557335 --2.42965984344,1.830052495,3.84904956818 --2.43063831329,1.82106184959,3.82161951065 --2.41863036156,1.80606532097,3.78739285469 --2.44360566139,1.81707644463,3.80201768875 --2.45958065987,1.82008743286,3.79858732224 --2.47455716133,1.82209801674,3.79518222809 --2.491533041,1.82610869408,3.79477667809 --2.51450753212,1.83412003517,3.80336976051 --2.51848602295,1.82812941074,3.78194999695 --2.51847600937,1.82313382626,3.76874732971 --2.51845622063,1.8141425848,3.7423388958 --2.54043078423,1.8221539259,3.74892783165 --2.54440975189,1.81616306305,3.72851634026 --2.56238508224,1.82017374039,3.72910737991 --2.57436227798,1.82018387318,3.72069740295 --2.58933854103,1.82319438457,3.71628141403 --2.59932613373,1.82619988918,3.71807956696 --2.60330510139,1.82020914555,3.69766306877 --2.62328052521,1.82621991634,3.7012617588 --2.63425755501,1.82522988319,3.69084358215 --2.64623475075,1.82523989677,3.68243479729 --2.65821290016,1.82624959946,3.67504239082 --2.66919946671,1.82925546169,3.67682170868 --2.67717814445,1.82726478577,3.66342282295 --2.69115519524,1.82827472687,3.65801882744 --2.70013237,1.82628464699,3.64459609985 --2.72010803223,1.83229541779,3.64718937874 --2.73308491707,1.83330535889,3.6397767067 --2.74106383324,1.83031463623,3.62637639046 --2.74405241013,1.82831954956,3.61715602875 --2.76402831078,1.83433020115,3.61975455284 --2.77200675011,1.83233940601,3.60635328293 --2.78498387337,1.83334934711,3.59894132614 --2.79396224022,1.8313587904,3.58653330803 --2.81393742561,1.8373695612,3.58812046051 --2.81591749191,1.83037817478,3.56671333313 --2.82090592384,1.83038318157,3.56049752235 --2.84488034248,1.83839428425,3.56708574295 --2.86285710335,1.84340429306,3.56668806076 --2.85983753204,1.83341276646,3.53826475143 --2.8838121891,1.84142363071,3.54485917091 --2.9117872715,1.85343444347,3.55747532845 --2.90576887131,1.84144234657,3.52606058121 --2.92175507545,1.84844827652,3.53385329247 --2.92973399162,1.84645736217,3.52044939995 --2.94471073151,1.84846735001,3.51503610611 --2.94069194794,1.83847546577,3.48662185669 --2.96366715431,1.84648609161,3.49121499062 --2.98364186287,1.85149693489,3.49078583717 --2.98863220215,1.85150098801,3.48660707474 --2.9826130867,1.84050941467,3.45517444611 --3.02856349945,1.85553050041,3.46335840225 --3.03754210472,1.8545396328,3.45094966888 --3.03852248192,1.84854793549,3.42954397202 --3.04850053787,1.8475574255,3.41813063622 --3.06148791313,1.85156261921,3.42193102837 --3.07246589661,1.85157203674,3.41151571274 --3.07744574547,1.84858071804,3.39511418343 --3.09742236137,1.85459065437,3.39571547508 --3.11239886284,1.85660052299,3.38929247856 --3.12537717819,1.85860979557,3.38189315796 --3.13035678864,1.85461843014,3.36548995972 --3.13934516907,1.85662329197,3.36428594589 --3.14532375336,1.8536324501,3.34786081314 --3.16230082512,1.85764217377,3.34445595741 --3.17227911949,1.85665130615,3.33304333687 --3.18525767326,1.85866034031,3.32564592361 --3.19323635101,1.85666930676,3.31223535538 --3.19521617889,1.8516780138,3.29181098938 --3.21220254898,1.85868358612,3.29860234261 --3.22418117523,1.85869252682,3.29020738602 --3.23715901375,1.86070203781,3.28179240227 --3.25513625145,1.86571145058,3.27939486504 --3.26111483574,1.8627204895,3.26296544075 --3.26909399033,1.86072933674,3.24955391884 --3.28907203674,1.86673843861,3.2501783371 --3.29206132889,1.86574304104,3.24196314812 --3.30303955078,1.86575210094,3.23155140877 --3.31001973152,1.86376035213,3.21815896034 --3.32699680328,1.86776983738,3.21374821663 --3.33897423744,1.86877942085,3.20331788063 --3.34695315361,1.86678802967,3.18990540504 --3.35294294357,1.86779236794,3.18571019173 --3.36392140388,1.86780142784,3.17529940605 --3.36690235138,1.86380934715,3.15790224075 --3.38387989998,1.86781871319,3.15349650383 --3.38985919952,1.86582732201,3.13808035851 --3.40883564949,1.86983692646,3.1346590519 --3.42481446266,1.87384569645,3.13027596474 --3.42580413818,1.87185001373,3.12005519867 --3.44178199768,1.87485909462,3.11465334892 --3.44276213646,1.86986744404,3.09422850609 --3.46873807907,1.87887728214,3.09782505035 --3.47171902657,1.87488520145,3.08042287827 --3.48569774628,1.87689399719,3.07302069664 --3.48767757416,1.87290239334,3.05359435081 --3.50466513634,1.8799072504,3.05940461159 --3.50764608383,1.87591528893,3.04200005531 --3.50962591171,1.87092375755,3.02257084846 --3.53360271454,1.87893307209,3.02417516708 --3.54858064651,1.88194203377,3.01675844193 --3.55855989456,1.88195049763,3.00535011292 --3.55654191971,1.87595820427,2.98394823074 --3.56553077698,1.87796270847,2.98174500465 --3.58150863647,1.88097167015,2.97533345222 --3.59748768806,1.88498008251,2.96994423866 --3.59946751595,1.87998843193,2.95050978661 --3.60744810104,1.87999653816,2.93811559677 --3.62942481041,1.88700568676,2.93670773506 --3.64140439034,1.88801407814,2.92730808258 --3.64639377594,1.88801836967,2.92109417915 --3.64437532425,1.88202595711,2.89968323708 --3.65135478973,1.88003432751,2.88526320457 --3.67333245277,1.8870433569,2.88386201859 --3.68331193924,1.88705158234,2.87245559692 --3.69529151917,1.88905990124,2.86305785179 --3.70926952362,1.89106881618,2.85362672806 --3.71026062965,1.89007234573,2.84543800354 --3.71824026108,1.88908064365,2.83202290535 --3.7292201519,1.89008867741,2.82162189484 --3.74219918251,1.89209723473,2.81220936775 --3.74717974663,1.89010500908,2.7968006134 --3.76115870476,1.8921135664,2.78839445114 --3.75215172768,1.88511657715,2.77219510078 --3.78012824059,1.89512550831,2.77479791641 --3.78310894966,1.89213359356,2.75737762451 --3.79408812523,1.89314186573,2.74595689774 --3.80406928062,1.89414954185,2.73557472229 --3.81004881859,1.89215779305,2.72014760971 --3.82802772522,1.89716613293,2.71474695206 --3.82701778412,1.89417016506,2.70352053642 --3.85199594498,1.90217840672,2.7041425705 --3.84697914124,1.89518547058,2.68173623085 --3.86395692825,1.89919424057,2.67431139946 --3.87693667412,1.90120220184,2.66490674019 --3.87691783905,1.89720988274,2.64548397064 --3.89889645576,1.90421807766,2.64309549332 --3.90188598633,1.90322220325,2.63487052917 --3.90586781502,1.90122961998,2.61947345734 --3.91584825516,1.90123736858,2.60807275772 --3.93182730675,1.90524530411,2.60067009926 --3.93880772591,1.90425336361,2.58624911308 --3.96378540993,1.91326165199,2.58484721184 --3.96376752853,1.90826892853,2.56644272804 --3.96875762939,1.90927290916,2.56023216248 --3.99273562431,1.91728127003,2.55782818794 --4.01771402359,1.92528939247,2.55643486977 --4.03369379044,1.92929708958,2.5490424633 --4.02567672729,1.92130422592,2.52461910248 --4.0216588974,1.91531133652,2.50320148468 --4.04063796997,1.92031955719,2.49678874016 --4.06662464142,1.93132400513,2.5045940876 --4.04661035538,1.91733050346,2.47317862511 --4.05059146881,1.9153380394,2.4567553997 --4.08955049515,1.92635345459,2.44597125053 --4.10053062439,1.92836093903,2.43456459045 --4.11251974106,1.93236517906,2.43235063553 --4.09050607681,1.91737139225,2.40094733238 --4.10648536682,1.92137908936,2.39253926277 --4.09846878052,1.91338610649,2.36911892891 --4.14144420624,1.93039476871,2.37671017647 --4.2044172287,1.9574034214,2.39733576775 --4.21239757538,1.95741093159,2.38290905952 --4.18439388275,1.94241344929,2.35771179199 --4.16038036346,1.92641973495,2.32529520988 --4.16636133194,1.92542695999,2.31088900566 --4.19233942032,1.93443489075,2.307472229 --4.1933221817,1.93144190311,2.2900633812 --4.18330621719,1.9224486351,2.2666580677 --4.18428850174,1.91945564747,2.24924564362 --4.19327831268,1.92245960236,2.24503326416 --4.20325899124,1.92346680164,2.23262047768 --4.21424007416,1.92547404766,2.22121858597 --4.22622108459,1.92748141289,2.20980477333 --4.23720169067,1.92948842049,2.19840455055 --4.24918270111,1.9314956665,2.18699216843 --4.24316692352,1.92550230026,2.16659474373 --4.23115873337,1.91750586033,2.15036582947 --4.25113916397,1.92351281643,2.14397144318 --4.27111911774,1.92951989174,2.13757944107 --4.27810049057,1.92952716351,2.12315988541 --4.28508329391,1.92953383923,2.1097638607 --4.29206466675,1.92954099178,2.09534406662 --4.2980465889,1.92954790592,2.08093619347 --4.29903793335,1.92855131626,2.072732687 --4.31801843643,1.93355822563,2.06533670425 --4.31300163269,1.92856502533,2.04491615295 --4.31898355484,1.92757201195,2.0305082798 --4.32696533203,1.9285787344,2.01710033417 --4.34994459152,1.93658590317,2.01068639755 --4.34992742538,1.9325927496,1.99327671528 --4.34991979599,1.93159580231,1.98508346081 --4.36990022659,1.93760275841,1.97768437862 --4.3688826561,1.93360948563,1.95926046371 --4.37886476517,1.93561637402,1.94685637951 --4.38484716415,1.93562304974,1.93244898319 --4.38283014297,1.93162965775,1.91403377056 --4.40680980682,1.9396365881,1.90762102604 --4.40980148315,1.93963992596,1.90041780472 --4.41078472137,1.93664634228,1.88401734829 --4.41376781464,1.93565285206,1.8686183691 --4.41975021362,1.93565952778,1.85421097279 --4.43273210526,1.93866598606,1.84280204773 --4.43271493912,1.93567276001,1.82538545132 --4.45869541168,1.94467926025,1.8199877739 --4.45368671417,1.94068264961,1.80877113342 --4.46366977692,1.94268906116,1.79637205601 --4.46765232086,1.94169545174,1.78096222878 --4.45963668823,1.93570208549,1.76055204868 --4.48161745071,1.94270837307,1.7531542778 --4.48060131073,1.93971478939,1.73574507236 --4.48559141159,1.93971824646,1.72852170467 --4.50157356262,1.94472467899,1.71811425686 --4.50055646896,1.94173109531,1.70070397854 --4.49754142761,1.93773722649,1.68331217766 --4.51352310181,1.94274353981,1.67290687561 --4.51750612259,1.94174981117,1.65749561787 --4.52848863602,1.94375622272,1.64509165287 --4.53647947311,1.94675910473,1.63989078999 --4.53846263885,1.94476556778,1.62347400188 --4.54344654083,1.94477164745,1.60907828808 --4.54642868042,1.94377827644,1.59265100956 --4.5614118576,1.9477840662,1.58226263523 --4.55539560318,1.94279062748,1.56284284592 --4.55537891388,1.9397970438,1.54541683197 --4.56136989594,1.94180011749,1.53921163082 --4.56535291672,1.94080638885,1.52379906178 --4.57333612442,1.94281232357,1.51040077209 --4.56832122803,1.93781864643,1.49199175835 --4.57530403137,1.93882477283,1.47757697105 --4.58728647232,1.94183075428,1.46516990662 --4.60326957703,1.94683635235,1.45478022099 --4.60226106644,1.94483971596,1.44556176662 --4.61024475098,1.94684553146,1.43216574192 --4.60822868347,1.94385182858,1.41475272179 --4.61321306229,1.94385766983,1.40035653114 --4.61519575119,1.94186377525,1.38393449783 --4.63517856598,1.94886934757,1.37454330921 --4.65016078949,1.95387530327,1.36211895943 --4.6551527977,1.95387804508,1.35592758656 --4.65613651276,1.95288407803,1.33951437473 --4.6611199379,1.95289003849,1.32409489155 --4.66510438919,1.95289564133,1.30970859528 --4.66808795929,1.95190179348,1.29327905178 --4.67107152939,1.95090770721,1.27787470818 --4.67706346512,1.95291042328,1.27167665958 --4.68304777145,1.95391607285,1.25727534294 --4.70003080368,1.9589215517,1.24587011337 --4.70801401138,1.960927248,1.23145580292 --4.69999885559,1.95493352413,1.2120295763 --4.70598268509,1.9559391737,1.19762933254 --4.71496677399,1.95794451237,1.18423402309 --4.71795082092,1.95795059204,1.16780424118 --4.71294355392,1.95395362377,1.15860855579 --4.72592735291,1.95795881748,1.14621245861 --4.73191070557,1.95896458626,1.13078796864 --4.74489498138,1.96296966076,1.11839425564 --4.7418794632,1.95997560024,1.10097873211 --4.74186372757,1.95798146725,1.08456850052 --4.74784851074,1.9589868784,1.07017028332 --4.75284051895,1.96098959446,1.06295847893 --4.77282333374,1.96799445152,1.05155050755 --4.7608089447,1.96100068092,1.03213751316 --4.76079368591,1.95900642872,1.01572585106 --4.75777816772,1.9560123682,0.998305678368 --4.77176237106,1.96101725101,0.985912144184 --4.77575445175,1.96101987362,0.978708326817 --4.77373981476,1.9590255022,0.962307095528 --4.78572416306,1.9630304575,0.948902189732 --4.78970861435,1.96303594112,0.933492362499 --4.78969287872,1.96104156971,0.917079269886 --4.79267835617,1.96104693413,0.901674568653 --4.80166244507,1.96405208111,0.887263417244 --4.79465484619,1.96005535126,0.877042233944 --4.79563999176,1.95906078815,0.861647963524 --4.80462503433,1.9610657692,0.847237706184 --4.80960893631,1.96207106113,0.831822812557 --4.81259441376,1.96207630634,0.816418349743 --4.80657958984,1.9580821991,0.799006462097 --4.80756521225,1.95808744431,0.783610761166 --4.80555725098,1.9560905695,0.774385988712 --4.80654287338,1.95509564877,0.758989870548 --4.81152772903,1.9561009407,0.743574619293 --4.81751251221,1.95810616016,0.728154957294 --4.8224978447,1.95811092854,0.713766872883 --4.83048343658,1.96111571789,0.699365496635 --4.8354678154,1.96112084389,0.683952391148 --4.83646059036,1.9611235857,0.675739169121 --4.83544540405,1.9601290226,0.659325182438 --4.83443069458,1.95813441277,0.642910838127 --4.83741664886,1.95813953876,0.627505838871 --4.83640193939,1.95714485645,0.611090362072 --4.84238767624,1.95814955235,0.59669983387 --4.85037231445,1.96115446091,0.581275761127 --4.8553647995,1.9621566534,0.574073731899 --4.85335063934,1.9611620903,0.557661533356 --4.85733604431,1.96116697788,0.542253851891 --4.84932184219,1.95717287064,0.524835646152 --4.8563079834,1.95917737484,0.510443389416 --4.84929323196,1.95518314838,0.49301970005 --4.86427879333,1.96118700504,0.479627996683 --4.86227178574,1.95918977261,0.471424251795 --4.86425685883,1.95919501781,0.454996883869 --4.87724351883,1.96419870853,0.441614866257 --4.86422872543,1.95820510387,0.4231800735 --4.8662147522,1.95820987225,0.407778739929 --4.870200634,1.95821464062,0.392372041941 --4.87018585205,1.95821976662,0.375949680805 --4.87217903137,1.95822203159,0.368759721518 --4.88916492462,1.96522569656,0.354346007109 --4.88715028763,1.96323084831,0.337929874659 --4.88813686371,1.96323561668,0.322532057762 --4.88412284851,1.96124100685,0.306119412184 --4.90110874176,1.96724450588,0.291711628437 --4.9000954628,1.96624922752,0.276318848133 --4.89908838272,1.9652518034,0.268110215664 --4.90607452393,1.96825611591,0.252700328827 --4.90406036377,1.96626126766,0.236282899976 --4.90704679489,1.96726584435,0.220881685615 --4.90503311157,1.96527087688,0.204463541508 --4.90601873398,1.96527576447,0.188039541245 --4.91201210022,1.96827757359,0.180844634771 --4.90799856186,1.9652826786,0.164429202676 --4.90298461914,1.96328806877,0.148013964295 --4.91497182846,1.96829140186,0.133626699448 --4.90895795822,1.9652967453,0.117212355137 --4.9039440155,1.96230208874,0.100795716047 --4.90693092346,1.963306427,0.0853950828314 --4.91292381287,1.9653083086,0.0771767869592 --4.91191053391,1.96531295776,0.0617810040712 --4.91089677811,1.96431791782,0.0453587658703 --4.90988397598,1.96332252026,0.0299626868218 --4.90287017822,1.9603279829,0.0135443834588 --4.91285705566,1.96433162689,-0.00186052639037 --4.91684341431,1.96533584595,-0.0182865262032 --4.90483617783,1.96033942699,-0.026491465047 --4.90282344818,1.95934426785,-0.0418884940445 --4.91481113434,1.96434736252,-0.0572916418314 --4.88579559326,1.95135545731,-0.0747326314449 --4.90278339386,1.95835804939,-0.0901364162564 --4.9047703743,1.95936226845,-0.105535253882 --4.8957567215,1.95536792278,-0.121959552169 --4.89975070953,1.95736944675,-0.129146009684 --4.89973688126,1.95737409592,-0.145571455359 --4.89072418213,1.95337963104,-0.160971537232 --4.90171098709,1.95838296413,-0.177395388484 --4.89469814301,1.95438814163,-0.1927960217 --4.90368556976,1.95839130878,-0.208191871643 --4.8796710968,1.94839894772,-0.224628612399 --4.89466524124,1.95439934731,-0.232834264636 --4.89665269852,1.95540332794,-0.248232409358 --4.88463926315,1.9514092207,-0.263640105724 --4.88862657547,1.95241308212,-0.280063539743 --4.89361381531,1.95441675186,-0.295458942652 --4.87460041046,1.9474234581,-0.310876399279 --4.88758802414,1.95242619514,-0.327290326357 --4.89458227158,1.95542740822,-0.335495978594 --4.89056968689,1.95443224907,-0.350899845362 --4.89355611801,1.9554361105,-0.367321938276 --4.88954401016,1.95444095135,-0.382726371288 --4.8835310936,1.95144593716,-0.39813387394 --4.88251876831,1.95145010948,-0.413535088301 --4.88750600815,1.95445382595,-0.429953664541 --4.88950014114,1.95445561409,-0.438163012266 --4.88848781586,1.95445978642,-0.453563660383 --4.88447523117,1.95346438885,-0.468969792128 --4.87546205521,1.95046985149,-0.484385877848 --4.87144851685,1.94847476482,-0.500819802284 --4.87443733215,1.95047831535,-0.516213715076 --4.87642431259,1.95148229599,-0.532635450363 --4.87841844559,1.95248389244,-0.540843963623 --4.87640619278,1.95248818398,-0.556247532368 --4.87939453125,1.9544917345,-0.571639478207 --4.88338279724,1.95649516582,-0.588054835796 --4.87336921692,1.95250070095,-0.603477776051 --4.88335847855,1.95750308037,-0.619877099991 --4.86635112762,1.95050764084,-0.626080751419 --4.87433958054,1.95451056957,-0.6435110569 --4.86532688141,1.9515157938,-0.657907783985 --4.86231470108,1.9505200386,-0.673314869404 --4.87530374527,1.95652198792,-0.690727889538 --4.86629056931,1.95352733135,-0.706152617931 --4.85927772522,1.9515324831,-0.721572458744 --4.85827207565,1.95153439045,-0.728761434555 --4.86426115036,1.95453727245,-0.745166361332 --4.8492474556,1.94854354858,-0.759587168694 --4.85723686218,1.95254588127,-0.775984406471 --4.86022520065,1.95454919338,-0.792397677898 --4.84421157837,1.94855570793,-0.806825518608 --4.84820079803,1.95155882835,-0.823235213757 --4.83819389343,1.94756221771,-0.829431295395 --4.84318208694,1.95056533813,-0.846863031387 --4.84317111969,1.95156896114,-0.86226016283 --4.84115982056,1.95157289505,-0.877664864063 --4.82614564896,1.94557929039,-0.892095923424 --4.84213685989,1.95357990265,-0.9094799757 --4.83212327957,1.9505854845,-0.924918234348 --4.82711172104,1.94858980179,-0.939309418201 --4.8111038208,1.94259464741,-0.945537984371 --4.8270945549,1.95059537888,-0.963943660259 --4.80808067322,1.94360232353,-0.976346313953 --4.8130698204,1.94660508633,-0.993773043156 --4.81405925751,1.9476082325,-1.00916433334 --4.80304670334,1.94461393356,-1.02358651161 --4.80004024506,1.94361615181,-1.03078591824 --4.80402946472,1.94661903381,-1.04821538925 --4.79101657867,1.94162487984,-1.06162285805 --4.7860045433,1.94062936306,-1.077044487 --4.78399324417,1.94063317776,-1.09245097637 --4.7789812088,1.9406375885,-1.10787343979 --4.77596998215,1.94064164162,-1.12328529358 --4.7799654007,1.94264233112,-1.13147473335 --4.76995277405,1.93964779377,-1.14589810371 --4.77094268799,1.94065082073,-1.16128778458 --4.75292778015,1.93465793133,-1.17473173141 --4.76091861725,1.93965959549,-1.19213461876 --4.76190757751,1.94066274166,-1.20854949951 --4.75689697266,1.94066691399,-1.22294712067 --4.74488925934,1.93567097187,-1.22814941406 --4.7468791008,1.93767380714,-1.24455845356 --4.73486566544,1.93367981911,-1.25899958611 --4.73885631561,1.93768203259,-1.27539598942 --4.7348446846,1.9376860857,-1.29081487656 --4.72683238983,1.9346909523,-1.30523264408 --4.72982311249,1.93769347668,-1.32163333893 --4.71581506729,1.93269813061,-1.32685506344 --4.71780490875,1.93470072746,-1.34326183796 --4.69679117203,1.92670845985,-1.35366332531 --4.71478366852,1.93670761585,-1.37406742573 --4.70177078247,1.93271350861,-1.38749587536 --4.68775749207,1.92771971226,-1.39990651608 --4.70375108719,1.93671929836,-1.42031860352 --4.67974042892,1.92672622204,-1.42253923416 --4.66172647476,1.92073333263,-1.43395590782 --4.67972040176,1.930732131,-1.45435082912 --4.6687078476,1.92673766613,-1.46777009964 --4.65769529343,1.92374324799,-1.48119103909 --4.6586856842,1.92674601078,-1.49760222435 --4.65367460251,1.92574989796,-1.51200520992 --4.65266942978,1.92675173283,-1.52022171021 --4.6486582756,1.92675566673,-1.53564333916 --4.63764667511,1.92376101017,-1.54804134369 --4.63363552094,1.92376494408,-1.56346356869 --4.6486287117,1.93176412582,-1.58386516571 --4.62661361694,1.92377233505,-1.59429991245 --4.61760234833,1.92177724838,-1.6077105999 --4.61859750748,1.92377841473,-1.6159106493 --4.61658716202,1.92378163338,-1.63131606579 --4.5945725441,1.91678965092,-1.64073228836 --4.5895614624,1.91679382324,-1.65616428852 --4.59055233002,1.9187964201,-1.67257130146 --4.5845413208,1.91780054569,-1.68698549271 --4.57953071594,1.9178044796,-1.70139145851 --4.5735244751,1.91680729389,-1.70759928226 --4.57451534271,1.91880965233,-1.72400450706 --4.55950212479,1.91381621361,-1.73542129993 --4.56149291992,1.91681826115,-1.75284314156 --4.54247808456,1.91082596779,-1.76327288151 --4.54847145081,1.91582679749,-1.78065764904 --4.55046224594,1.91882896423,-1.79807722569 --4.53745365143,1.91383373737,-1.80229997635 --4.52044057846,1.90884077549,-1.81271624565 --4.52743339539,1.91384136677,-1.83111429214 --4.52442312241,1.91484463215,-1.84652817249 --4.52141332626,1.91584789753,-1.86194169521 --4.51140165329,1.91285300255,-1.87434530258 --4.50339460373,1.91085648537,-1.88057684898 --4.49138259888,1.90786218643,-1.89197635651 --4.49237394333,1.91086435318,-1.90940248966 --4.48636293411,1.90986835957,-1.92382013798 --4.47535085678,1.90787386894,-1.93623733521 --4.46834039688,1.90687811375,-1.94964039326 --4.46433019638,1.90788161755,-1.96506440639 --4.47432947159,1.91287982464,-1.97624242306 --4.4513130188,1.90588879585,-1.9846830368 --4.44630336761,1.90589249134,-1.99909186363 --4.44929599762,1.90989375114,-2.01649308205 --4.419277668,1.89890491962,-2.02193713188 --4.4262714386,1.90390515327,-2.04134607315 --4.42226171494,1.90490829945,-2.05574417114 --4.42125701904,1.90590977669,-2.06395792961 --4.42024850845,1.90791225433,-2.08037376404 --4.41623926163,1.90891551971,-2.09477114677 --4.39322328568,1.90092456341,-2.10220074654 --4.38221120834,1.89893007278,-2.11462664604 --4.38120222092,1.90093243122,-2.13104224205 --4.38219451904,1.90393424034,-2.14845919609 --4.34517765045,1.8889465332,-2.14067745209 --4.36517620087,1.89994239807,-2.16607999802 --4.34916305542,1.89594936371,-2.17549061775 --4.35415697098,1.90094983578,-2.19491028786 --4.34014415741,1.89695608616,-2.20532417297 --4.32713127136,1.89396238327,-2.21675276756 --4.31111717224,1.88896918297,-2.22616815567 --4.32611894608,1.89796543121,-2.24136590958 --4.31210613251,1.8939718008,-2.25178289413 --4.30409574509,1.89297616482,-2.26417922974 --4.29708528519,1.89298033714,-2.27861380577 --4.28307199478,1.88898670673,-2.28903388977 --4.27606201172,1.88899087906,-2.30244445801 --4.27305316925,1.89099371433,-2.31785511971 --4.27705144882,1.89399325848,-2.32805395126 --4.25503540039,1.88700222969,-2.33447766304 --4.255027771,1.89000403881,-2.35189962387 --4.24001407623,1.88601076603,-2.36131262779 --4.23900651932,1.88901269436,-2.37772202492 --4.23899936676,1.89201438427,-2.39514183998 --4.2199845314,1.88602268696,-2.4025592804 --4.21197795868,1.88402605057,-2.40676212311 --4.20496749878,1.88403022289,-2.42119884491 --4.19395589828,1.88203561306,-2.43158984184 --4.1899471283,1.88303864002,-2.44701170921 --4.18793916702,1.88504087925,-2.46343111992 --4.17992925644,1.88504517078,-2.47583246231 --4.16391515732,1.88105249405,-2.48526787758 --4.16891431808,1.88505136967,-2.4964697361 --4.14889812469,1.87805998325,-2.50288724899 --4.14488983154,1.88006293774,-2.51830863953 --4.13687992096,1.87906706333,-2.53071117401 --4.1288690567,1.87907147408,-2.54413843155 --4.12986278534,1.88307261467,-2.56256198883 --4.11484956741,1.87907934189,-2.57096529007 --4.11984872818,1.8830780983,-2.58216166496 --4.10083341599,1.87808656693,-2.5895986557 --4.08381986618,1.87309420109,-2.59700918198 --4.08181190491,1.8750962019,-2.61342453957 --4.0758023262,1.87609982491,-2.6278488636 --4.06379079819,1.87410545349,-2.63826274872 --4.06578874588,1.87710535526,-2.6484746933 --4.05677747726,1.8761100769,-2.66089344025 --4.04476642609,1.87411570549,-2.67130851746 --4.02074861526,1.8661261797,-2.67473387718 --4.03274822235,1.87512266636,-2.6991314888 --4.01573371887,1.87113046646,-2.7065513134 --4.00272130966,1.86813676357,-2.71698451042 --4.00872135162,1.87313485146,-2.72918057442 --4.00271272659,1.87413811684,-2.74257993698 --3.99670362473,1.87514150143,-2.75700283051 --3.96968436241,1.86515343189,-2.75843691826 --3.96767735481,1.86815524101,-2.77484726906 --3.96366977692,1.87015771866,-2.79026317596 --3.96466469765,1.87515819073,-2.80867242813 --3.94265007973,1.8651676178,-2.80389475822 --3.94064378738,1.86816930771,-2.82030296326 --3.933634758,1.86917304993,-2.83371806145 --3.9286262989,1.87117600441,-2.84914827347 --3.92261791229,1.87217915058,-2.86254668236 --3.90460300446,1.8671875,-2.86897182465 --3.90359711647,1.87018859386,-2.88638401031 --3.89158797264,1.86619400978,-2.88759922981 --3.89958715439,1.87519133091,-2.91100525856 --3.91759204865,1.88818407059,-2.94140791893 --3.36704659462,1.85644733906,-3.52661013603 --3.34002304077,1.84646201134,-3.5210287571 --3.34302425385,1.85445904732,-3.5444381237 --3.33501696587,1.85246312618,-3.54766011238 --3.32600831985,1.85346722603,-3.56008577347 --3.31499814987,1.85247254372,-3.56949067116 --3.30999279022,1.85547423363,-3.58489465714 --3.29698085785,1.8544806242,-3.59332060814 --3.27996563911,1.85048949718,-3.59774875641 --3.27395963669,1.85249173641,-3.61215186119 --3.26194906235,1.84849834442,-3.61137890816 --3.25494217873,1.85150098801,-3.62580299377 --3.24893641472,1.85350322723,-3.64020466805 --3.223913908,1.84451711178,-3.63664507866 --3.21190285683,1.84452295303,-3.64607429504 --3.2099006176,1.84852266312,-3.66447067261 --3.19989156723,1.84952712059,-3.67691612244 --3.18687963486,1.84453451633,-3.6741309166 --3.18387675285,1.84953463078,-3.69254636765 --3.16185665131,1.84254693985,-3.69097304344 --3.16285777092,1.84954440594,-3.71337938309 --3.14684295654,1.84655284882,-3.71779727936 --3.13683390617,1.84655749798,-3.72820353508 --3.1268248558,1.84756207466,-3.73962950706 --3.12382221222,1.84856295586,-3.74784708023 --3.10580563545,1.84457278252,-3.75027251244 --3.09779834747,1.84557616711,-3.76267409325 --3.08278465271,1.84358394146,-3.76911330223 --3.07277584076,1.84458839893,-3.78053927422 --3.05776166916,1.84059643745,-3.78494143486 --3.060765028,1.84659314156,-3.80015897751 --3.03774356842,1.83860659599,-3.79556798935 --3.03374052048,1.84360706806,-3.81399416924 --3.01572370529,1.8386169672,-3.81642746925 --3.00571489334,1.83962154388,-3.82683539391 --2.99070096016,1.83762943745,-3.83327960968 --2.98970127106,1.84362781048,-3.85367202759 --2.97368645668,1.84063649178,-3.85810208321 --2.9666800499,1.83964002132,-3.86131310463 --2.95967435837,1.84164237976,-3.87572646141 --2.93965530396,1.83665406704,-3.87515687943 --2.9306473732,1.83765769005,-3.88859605789 --2.91863656044,1.83766376972,-3.89599442482 --2.90762710571,1.83766889572,-3.9064245224 --2.90162158012,1.83767175674,-3.91063284874 --2.88260293007,1.83168292046,-3.91004657745 --2.87760019302,1.83668351173,-3.92848420143 --2.86258602142,1.83369159698,-3.93391609192 --2.84657073021,1.83070063591,-3.93733668327 --2.84357047081,1.8366997242,-3.95674347878 --2.8295571804,1.83470714092,-3.9631717205 --2.82355165482,1.83371019363,-3.96636271477 --2.80753660202,1.83071935177,-3.96978592873 --2.79752850533,1.83272349834,-3.98222851753 --2.77850937843,1.82673490047,-3.9816532135 --2.77550959587,1.83373367786,-4.00207185745 --2.76650214195,1.83473730087,-4.01448917389 --2.74748325348,1.82974886894,-4.01289987564 --2.74247932434,1.83075106144,-4.01912117004 --2.72746491432,1.82775938511,-4.02354240417 --2.71645545959,1.82776451111,-4.03295612335 --2.70144104958,1.82577300072,-4.03737974167 --2.69944286346,1.83277058601,-4.05980014801 --2.67341518402,1.82278800011,-4.04923295975 --2.66941452026,1.82778739929,-4.06864833832 --2.65840244293,1.82379460335,-4.06484413147 --2.64939618111,1.82679796219,-4.07827758789 --2.63938832283,1.82780206203,-4.09071683884 --2.62137007713,1.82381308079,-4.09013366699 --2.61436581612,1.82681500912,-4.10453367233 --2.60235524178,1.82682085037,-4.11397123337 --2.59234476089,1.82382726669,-4.11218070984 --2.57632923126,1.82083654404,-4.11561822891 --2.56932497025,1.82383835316,-4.1300163269 --2.56332278252,1.82883882523,-4.14845371246 --2.5453042984,1.82385003567,-4.14787626266 --2.53028964996,1.82185876369,-4.15129232407 --2.51627659798,1.81986653805,-4.1567158699 --2.5182826519,1.826862216,-4.1729221344 --2.5012652874,1.82287275791,-4.17333984375 --2.48925471306,1.82287871838,-4.18176269531 --2.4762430191,1.82188546658,-4.18919372559 --2.46723747253,1.82488834858,-4.2036356926 --2.45122122765,1.82189810276,-4.2050485611 --2.43620657921,1.81990695,-4.20846891403 --2.43620991707,1.82390427589,-4.22166967392 --2.41518640518,1.81691861153,-4.21610164642 --2.41118812561,1.8239171505,-4.23650884628 --2.39617395401,1.8219255209,-4.24196052551 --2.38216018677,1.81993353367,-4.24637269974 --2.36914873123,1.81994044781,-4.25279092789 --2.3651509285,1.82693839073,-4.27522230148 --2.35013175011,1.81895041466,-4.26342058182 --2.34312939644,1.82395136356,-4.27983665466 --2.32711315155,1.81996119022,-4.28227138519 --2.30709052086,1.81397509575,-4.27669143677 --2.29107403755,1.81098508835,-4.27811431885 --2.28106713295,1.8129888773,-4.29054641724 --2.28107619286,1.82398271561,-4.31895446777 --2.25804400444,1.81000292301,-4.29418087006 --2.25104188919,1.81400358677,-4.311606884 --2.24403977394,1.81900453568,-4.3280172348 --2.23303174973,1.82000911236,-4.33945655823 --2.217015028,1.81701934338,-4.33986902237 --2.20500564575,1.81802499294,-4.34930610657 --2.21102547646,1.83401191235,-4.38869762421 --2.18699073792,1.81903374195,-4.36194038391 --2.17297697067,1.81704211235,-4.36534547806 --2.16797947884,1.82404005527,-4.38777971268 -1.94972026348,1.74697244167,-3.62488031387 -1.97375333309,1.75798368454,-3.64128398895 -1.98075425625,1.75198209286,-3.62469363213 -1.9967726469,1.7559876442,-3.62707710266 -2.00478172302,1.75799012184,-3.62728190422 -2.01679158211,1.75699222088,-3.61969804764 -2.03180742264,1.75899648666,-3.61810803413 -2.03880929947,1.75499534607,-3.60250782967 -2.05683016777,1.75900161266,-3.60592460632 -2.0658352375,1.7560018301,-3.59333515167 -2.07584238052,1.75400269032,-3.58274388313 -2.08485341072,1.75700616837,-3.58592963219 -2.10187244415,1.76101183891,-3.58833098412 -2.11488509178,1.76201498508,-3.58372950554 -2.12789678574,1.76201760769,-3.57715678215 -2.13790416718,1.76001870632,-3.56755256653 -2.15292000771,1.76202309132,-3.56595754623 -2.16292691231,1.76002395153,-3.55438280106 -2.17494249344,1.76602911949,-3.56256484985 -2.18394780159,1.76202964783,-3.54998064041 -2.19495725632,1.76203143597,-3.54138731956 -2.20997262001,1.76403558254,-3.53978991508 -2.22198367119,1.76403808594,-3.53319191933 -2.23599743843,1.76604175568,-3.52959799767 -2.23999905586,1.76304149628,-3.52181768417 -2.25401377678,1.76604557037,-3.52019309998 -2.26802754402,1.76704919338,-3.51659822464 -2.28204083443,1.76805245876,-3.511033535 -2.29204845428,1.76605391502,-3.50143194199 -2.30405926704,1.76605629921,-3.49384880066 -2.3160700798,1.7660588026,-3.48725056648 -2.32908582687,1.77206397057,-3.49445772171 -2.33909368515,1.77006530762,-3.48485684395 -2.34108972549,1.76206254959,-3.462266922 -2.3591094017,1.76706826687,-3.4646718502 -2.37813019753,1.77207446098,-3.46808338165 -2.38813853264,1.77107608318,-3.45848298073 -2.39714503288,1.7690769434,-3.44590735435 -2.39614033699,1.76307463646,-3.43210864067 -2.41516137123,1.76908111572,-3.43748474121 -2.42216563225,1.76608097553,-3.42191123962 -2.44619321823,1.77508974075,-3.43330550194 -2.45219564438,1.77008926868,-3.41672611237 -2.4692132473,1.77409434319,-3.41712975502 -2.48322701454,1.77609789371,-3.41254353523 -2.47621488571,1.76609301567,-3.39074206352 -2.49623656273,1.77209961414,-3.39514899254 -2.50123810768,1.76709890366,-3.37756752968 -2.51124668121,1.76610064507,-3.36797165871 -2.52225637436,1.76610291004,-3.35938239098 -2.53426742554,1.76610565186,-3.35180020332 -2.54027080536,1.76210570335,-3.33621406555 -2.55428671837,1.76811075211,-3.34440517426 -2.56329393387,1.76611220837,-3.33380436897 -2.56729483604,1.76011133194,-3.31424283981 -2.57830500603,1.76011383533,-3.30663847923 -2.59932732582,1.76712059975,-3.31203961372 -2.60032486916,1.75911867619,-3.28946518898 -2.62635374069,1.77012753487,-3.3028383255 -2.62835407257,1.76712727547,-3.29306006432 -2.6643948555,1.78514027596,-3.31942820549 -2.65938520432,1.7731359005,-3.28885960579 -2.66238570213,1.76713514328,-3.26928329468 -2.67539787292,1.76913833618,-3.26368689537 -2.69141387939,1.77214276791,-3.26110482216 -2.69141244888,1.76814186573,-3.2503027916 -2.70442485809,1.76914525032,-3.24470615387 -2.71243166924,1.76714658737,-3.23212265968 -2.72644519806,1.76915025711,-3.22753000259 -2.73245000839,1.76615095139,-3.21293902397 -2.74746441841,1.76815497875,-3.20935034752 -2.77649497986,1.780164361,-3.2247235775 -2.78350162506,1.78116619587,-3.22193431854 -2.78650307655,1.77616584301,-3.20335054398 -2.79751324654,1.77616846561,-3.19476127625 -2.81452989578,1.77917313576,-3.1931746006 -2.81252598763,1.7711712122,-3.16859698296 -2.8315448761,1.77617669106,-3.17097854614 -2.83554768562,1.77217698097,-3.1534049511 -2.8495619297,1.77718126774,-3.1595993042 -2.85356473923,1.77218151093,-3.14202737808 -2.85756778717,1.76818180084,-3.12445735931 -2.87958979607,1.77618825436,-3.13082265854 -2.89660644531,1.7791929245,-3.12922978401 -2.90361261368,1.77719438076,-3.11564922333 -2.91262149811,1.77919685841,-3.11584377289 -2.92363166809,1.77919960022,-3.1072537899 -2.93564295769,1.78020262718,-3.09966564178 -2.9436507225,1.7792044878,-3.08806943893 -2.95466089249,1.77920734882,-3.07849907875 -2.96066641808,1.77620851994,-3.06392025948 -2.9706761837,1.77621114254,-3.05531001091 -2.98268771172,1.77921450138,-3.05752515793 -2.99069523811,1.778216362,-3.04593086243 -3.00170588493,1.77821922302,-3.03734111786 -3.01571917534,1.78022301197,-3.03175449371 -3.02773046494,1.78122615814,-3.02416491508 -3.03774046898,1.78122878075,-3.01555347443 -3.04374599457,1.77823030949,-3.0009791851 -3.0457482338,1.77623081207,-2.99318194389 -3.05876088142,1.77823424339,-2.98659300804 -3.07777881622,1.78323936462,-2.98698568344 -3.07477664948,1.77523851395,-2.9624311924 -3.0857872963,1.77624154091,-2.95482087135 -3.10680699348,1.78224730492,-2.95623087883 -3.10680794716,1.77624738216,-2.93566155434 -3.11781811714,1.77925026417,-2.93784499168 -3.14784574509,1.79125809669,-2.94824743271 -3.15785551071,1.79126083851,-2.93865418434 -3.18688201904,1.80326831341,-2.94902896881 -3.43325638771,1.67240011692,-2.21112990379 -3.45327091217,1.68040370941,-2.21830248833 -3.46028113365,1.67940735817,-2.2067284584 -3.46829175949,1.67941129208,-2.19614601135 -3.4743013382,1.67841482162,-2.18455505371 -3.48831582069,1.68241941929,-2.17797327042 -3.49732708931,1.6824233532,-2.16838240623 -3.50533461571,1.68542551994,-2.16656899452 -3.50434064865,1.68042862415,-2.14901280403 -3.50134515762,1.67543137074,-2.13142538071 -3.51636004448,1.67843592167,-2.1258327961 -3.5223698616,1.67843961716,-2.11424303055 -3.52537798882,1.67544317245,-2.10065579414 -3.53739118576,1.67844736576,-2.09306240082 -3.53839540482,1.67644917965,-2.08528709412 -3.53840184212,1.67245256901,-2.06970453262 -3.551415205,1.67545688152,-2.0631005764 -3.54942154884,1.67146015167,-2.04553937912 -3.56343579292,1.67446470261,-2.03895115852 -3.56944584846,1.67346858978,-2.02736401558 -3.57145380974,1.6714720726,-2.01376533508 -3.57345843315,1.67047405243,-2.00698256493 -3.58146977425,1.67047822475,-1.99640190601 -3.58848071098,1.67048239708,-1.98483192921 -3.59048867226,1.6684858799,-1.97123599052 -3.59349751472,1.66548991203,-1.95765733719 -3.60350966454,1.66749405861,-1.94905519485 -3.61052060127,1.66749835014,-1.93748581409 -3.61252522469,1.66650009155,-1.93167805672 -3.61253285408,1.66350388527,-1.91610825062 -3.62954854965,1.66850852966,-1.91150534153 -3.62955641747,1.6655125618,-1.89593684673 -3.63356566429,1.66351640224,-1.8833501339 -3.6445786953,1.66552102566,-1.87476110458 -3.64658331871,1.6655228138,-1.86895394325 -3.65159368515,1.6645270586,-1.85638272762 -3.65260195732,1.66153109074,-1.84180688858 -3.66161394119,1.662535429,-1.83221447468 -3.66262245178,1.65953946114,-1.81764018536 -3.6676325798,1.65854358673,-1.8060438633 -3.67864561081,1.66154813766,-1.7974524498 -3.66864490509,1.65454959869,-1.7846647501 -3.6846601963,1.6595543623,-1.77906358242 -3.68566942215,1.65655875206,-1.7635204792 -3.69768285751,1.65956330299,-1.75591480732 -3.70469379425,1.65956759453,-1.74531984329 -3.70870375633,1.65857183933,-1.73273777962 -3.700704813,1.65357375145,-1.72095882893 -3.7167198658,1.65857839584,-1.7153519392 -3.72773337364,1.66058325768,-1.70578491688 -3.72173929214,1.65458726883,-1.68820488453 -3.73275208473,1.65659177303,-1.67960977554 -3.73476171494,1.65459620953,-1.66603064537 -3.74077296257,1.65460073948,-1.65445053577 -3.73077297211,1.64860248566,-1.64265275002 -3.74878907204,1.6546074152,-1.63706684113 -3.75179934502,1.65261220932,-1.62350332737 -3.75881099701,1.65361654758,-1.61290848255 -3.7568192482,1.64962112904,-1.59733653069 -3.75582766533,1.6466255188,-1.58275067806 -3.77284312248,1.6516302824,-1.57714569569 -3.77985024452,1.65363264084,-1.573351264 -3.77885866165,1.6506370306,-1.55876624584 -3.77786803246,1.64764201641,-1.54321157932 -3.79188251495,1.65164673328,-1.5356208086 -3.78088712692,1.64365100861,-1.51702666283 -3.78990030289,1.64465606213,-1.50645852089 -3.8069152832,1.65066063404,-1.50084543228 -3.79991769791,1.64566302299,-1.4900752306 -3.80692958832,1.64666771889,-1.4794806242 -3.81094050407,1.64567255974,-1.46690666676 -3.8089492321,1.64267730713,-1.45231735706 -3.82496404648,1.64768207073,-1.44571614265 -3.82697463036,1.64568698406,-1.43214762211 -3.81597566605,1.6396894455,-1.4203646183 -3.8429942131,1.64969408512,-1.41874682903 -3.8380022049,1.64469909668,-1.4021832943 -3.83701181412,1.64170408249,-1.38761043549 -3.83702158928,1.63970899582,-1.37402117252 -3.8510363102,1.64371407032,-1.3654487133 -3.84904575348,1.64071893692,-1.35086655617 -3.85305142403,1.64072132111,-1.34606015682 -3.86706638336,1.64472639561,-1.33748483658 -3.85807347298,1.63873159885,-1.31991374493 -3.87008714676,1.64173638821,-1.31131494045 -3.86609601974,1.63774168491,-1.29574406147 -3.87310814857,1.63874650002,-1.28514790535 -3.87411880493,1.6377518177,-1.27157473564 -3.87512373924,1.63675403595,-1.26576435566 -3.88513755798,1.63875937462,-1.25520062447 -3.88314723969,1.63576459885,-1.24062621593 -3.89616155624,1.63976955414,-1.23203349113 -3.88016700745,1.63077509403,-1.21246254444 -3.90918588638,1.64077973366,-1.20985710621 -3.91219735146,1.64078485966,-1.19727659225 -3.9031996727,1.63578760624,-1.18748354912 -3.91521382332,1.63879287243,-1.17790675163 -3.91822528839,1.63779819012,-1.16532766819 -3.91923570633,1.63680326939,-1.1527286768 -3.92724823952,1.63780844212,-1.14213979244 -3.92425847054,1.63481390476,-1.12756240368 -3.92626404762,1.63481652737,-1.12176346779 -3.93227648735,1.6358217001,-1.11018455029 -3.94729161263,1.64082682133,-1.10160112381 -3.93729925156,1.63383257389,-1.08502030373 -3.93831086159,1.63283836842,-1.07145452499 -3.95132493973,1.63684308529,-1.06284987926 -3.95833706856,1.63784825802,-1.05224883556 -3.95534181595,1.63585114479,-1.04446423054 -3.96435523033,1.63785648346,-1.03388094902 -3.95836496353,1.63386237621,-1.01831400394 -3.95537567139,1.63086819649,-1.00374531746 -3.96938967705,1.63487315178,-0.995144844055 -3.96840071678,1.63287889957,-0.981564164162 -3.97441339493,1.63388431072,-0.969983756542 -3.97941994667,1.63488686085,-0.965180039406 -3.97443056107,1.63089311123,-0.9496281147 -3.98144316673,1.63289833069,-0.939025044441 -3.98145461082,1.63090407848,-0.925455629826 -3.98046588898,1.6289100647,-0.911878764629 -3.98247742653,1.6279156208,-0.899296462536 -3.99249076843,1.63092064857,-0.889685928822 -4.00549936295,1.63592290878,-0.886882245541 -3.98350596428,1.62493002415,-0.867325603962 -4.00652265549,1.63393461704,-0.8607224226 -3.99253153801,1.62594151497,-0.843171596527 -3.99654340744,1.6259469986,-0.831574976444 -4.01555967331,1.63295221329,-0.822997689247 -3.99556136131,1.62395620346,-0.8112205863 -4.00457429886,1.62596154213,-0.800630271435 -4.0165886879,1.62996673584,-0.791029155254 -4.02660274506,1.63297224045,-0.780443072319 -4.01761245728,1.62697887421,-0.764877259731 -4.02762651443,1.63098418713,-0.754290044308 -4.01663589478,1.62399089336,-0.738713622093 -4.03464508057,1.63099265099,-0.736899614334 -4.03565692902,1.63099849224,-0.724311590195 -4.03867006302,1.63100457191,-0.711737573147 -4.03268098831,1.62701117992,-0.697167217731 -4.04069471359,1.62901699543,-0.685595095158 -4.02570343018,1.62102377415,-0.670001268387 -4.04171848297,1.62702906132,-0.660416543484 -4.0377240181,1.62403261662,-0.652643144131 -4.04173660278,1.62503838539,-0.641045033932 -4.03974866867,1.62304472923,-0.627473652363 -4.04376125336,1.62405049801,-0.615875601768 -4.05777597427,1.62805604935,-0.605304479599 -4.05078744888,1.62406301498,-0.590736627579 -4.05380010605,1.62406873703,-0.579132378101 -4.05080509186,1.62307202816,-0.572336435318 -4.03781557083,1.61607944965,-0.556771159172 -4.05783176422,1.62408459187,-0.547196924686 -4.05884456635,1.62309074402,-0.534613788128 -4.05785608292,1.62109708786,-0.522020578384 -4.05586910248,1.62010395527,-0.50845426321 -4.07387781143,1.62710547447,-0.505640745163 -4.064889431,1.62211275101,-0.491071134806 -4.06190156937,1.62011957169,-0.477501124144 -4.06991529465,1.62212538719,-0.465921163559 -4.06092596054,1.6171323061,-0.452324390411 -4.06493997574,1.61813867092,-0.439757168293 -4.07795476913,1.62314403057,-0.429165959358 -4.06295871735,1.61614871025,-0.420386314392 -4.07397270203,1.62015414238,-0.409785330296 -4.07198572159,1.61816108227,-0.396223634481 -4.07799959183,1.62016713619,-0.384631663561 -4.08001279831,1.62017357349,-0.372054815292 -4.08002519608,1.61918008327,-0.359470158815 -4.08103132248,1.61918318272,-0.353665858507 -4.09204626083,1.62318897247,-0.342091023922 -4.08105707169,1.61719632149,-0.328497767448 -4.07907056808,1.61620354652,-0.314938873053 -4.07508230209,1.61321032047,-0.30234208703 -4.08609724045,1.61721622944,-0.290764957666 -4.08711051941,1.61722290516,-0.278185069561 -4.08211612701,1.6152266264,-0.271393358707 -4.09513139725,1.62023246288,-0.259819686413 -4.09814453125,1.62023854256,-0.2482136935 -4.09215736389,1.61724603176,-0.234644934535 -4.08817052841,1.61525344849,-0.221083328128 -4.08818387985,1.61426019669,-0.208501845598 -4.08919715881,1.61426699162,-0.19592307508 -4.09720373154,1.61726927757,-0.191104888916 -4.09721708298,1.61727619171,-0.178522825241 -4.10023117065,1.61728286743,-0.165948584676 -4.09924459457,1.61728978157,-0.15336433053 -4.09825801849,1.61629676819,-0.14078079164 -4.09627056122,1.61430382729,-0.128195807338 -4.09327793121,1.61330771446,-0.12141533196 -4.09429121017,1.6133146286,-0.108837045729 -4.10230541229,1.61632049084,-0.0972393900156 -4.11632013321,1.6213259697,-0.0856509208679 -4.10833358765,1.61733412743,-0.0720881894231 -4.10734701157,1.61734127998,-0.0595054700971 -4.11336183548,1.61934781075,-0.0469334311783 -4.10636806488,1.6163520813,-0.0401492826641 -4.107380867,1.6163585186,-0.0285380166024 -4.10439491272,1.61436641216,-0.0149865858257 -4.1014084816,1.61337375641,-0.00240334682167 -4.10742235184,1.61537992954,0.0092023704201 -4.10843610764,1.61538696289,0.0217813048512 -4.11445045471,1.61739349365,0.0343563780189 -4.11345815659,1.61739742756,0.0411313064396 -4.10647106171,1.61340522766,0.053715672344 -4.11248588562,1.61641192436,0.0662920624018 -4.1034989357,1.61241996288,0.0788758397102 -4.11651325226,1.61742544174,0.0904826596379 -4.11752700806,1.61743247509,0.10306250304 -4.11154127121,1.61544036865,0.115643687546 -4.11354875565,1.61644399166,0.12241718173 -4.1125626564,1.61545145512,0.13499674201 -4.11457681656,1.61645853519,0.147576600313 -4.11059093475,1.61446630955,0.160155370831 -4.11860561371,1.61747264862,0.172737151384 -4.12562036514,1.62047922611,0.185320198536 -4.11162614822,1.61448419094,0.191120132804 -4.1206407547,1.61849045753,0.203704670072 -4.11665487289,1.61749839783,0.216282442212 -4.12066936493,1.61850512028,0.228865206242 -4.10568332672,1.61251461506,0.241432502866 -4.11269807816,1.61552107334,0.254018127918 -4.12771272659,1.62152647972,0.266613632441 -4.12171936035,1.6195306778,0.272413700819 -4.16973543167,1.63953208923,0.286020338535 -4.15275001526,1.6325417757,0.298583388329 -4.15776443481,1.63454842567,0.311174094677 -4.14677858353,1.63055753708,0.323741883039 -4.15579271317,1.63456356525,0.336339682341 -4.15480709076,1.63457107544,0.348922282457 -4.14181375504,1.62857651711,0.354707360268 -4.1268286705,1.62258636951,0.367262452841 -4.11684322357,1.61859536171,0.379824370146 -4.12185764313,1.62060213089,0.392415374517 -4.10887145996,1.61561131477,0.404000818729 -4.13688755035,1.62761545181,0.418580174446 -4.16689586639,1.64061510563,0.426393121481 -4.18190956116,1.6476200819,0.439015299082 -4.18192481995,1.64762806892,0.45257127285 -4.14993858337,1.6346398592,0.463139861822 -4.118953228,1.62165164948,0.473704874516 -4.13896894455,1.63065695763,0.488279104233 -4.13998365402,1.63166427612,0.500866353512 -4.14299106598,1.63266789913,0.507651329041 -4.14500617981,1.63467502594,0.520242631435 -4.14602041245,1.63468253613,0.532830834389 -4.12903547287,1.62769269943,0.544393122196 -4.10904979706,1.62070310116,0.55497443676 -4.12506580353,1.62770879269,0.569548130035 -4.11608028412,1.6247177124,0.581132471561 -4.09308862686,1.61472523212,0.585888981819 -4.09810256958,1.61773192883,0.598489165306 -4.09511852264,1.61674034595,0.611059844494 -4.09713315964,1.61774766445,0.623649775982 -4.10814809799,1.62375378609,0.63724476099 -4.1091632843,1.624761343,0.649832904339 -4.08717870712,1.61577260494,0.660388588905 -4.09018659592,1.61777615547,0.66717672348 -4.08720111847,1.61678397655,0.678778588772 -4.11821603775,1.6307874918,0.695371866226 -4.12823104858,1.63479363918,0.708971560001 -3.75185441971,1.62167787552,1.87215387821 -3.75687050819,1.62568545341,1.8877556324 -3.73390865326,1.62070763111,1.90490865707 -3.72292852402,1.61871922016,1.91446137428 -3.73593521118,1.62572109699,1.92726802826 -3.71795535088,1.6197334528,1.9328366518 -3.71097373962,1.61874377728,1.94341623783 -3.69099283218,1.61175608635,1.94700956345 -3.69001102448,1.61476528645,1.96058833599 -3.66903281212,1.60777890682,1.96513342857 -3.67204904556,1.61178696156,1.97974252701 -3.66905856133,1.61179220676,1.98552405834 -3.65807771683,1.60880339146,1.99409866333 -3.64709711075,1.60681450367,2.00267219543 -3.65111494064,1.61182320118,2.01924228668 -3.63213443756,1.60483527184,2.02283668518 -3.63815188408,1.61084353924,2.04041051865 -3.63416957855,1.61185324192,2.05200433731 -3.63917803764,1.61485671997,2.06179523468 -3.62119817734,1.60986924171,2.0663728714 -3.63021564484,1.61687707901,2.08594250679 -3.63023257256,1.61988568306,2.09954452515 -3.60625433922,1.61189961433,2.1011095047 -3.61027169228,1.6159080267,2.11769008636 -3.60028219223,1.61291456223,2.11947417259 -3.61329841614,1.62192130089,2.14106011391 -3.61031651497,1.62393093109,2.15364670753 -3.59433674812,1.61894321442,2.15921998024 -3.58835506439,1.618953228,2.16981387138 -3.57837557793,1.61796474457,2.17937064171 -3.58338356018,1.62196826935,2.18917250633 -3.56440424919,1.61498093605,2.19274806976 -3.56542253494,1.61899030209,2.20831775665 -3.55644106865,1.61800074577,2.2169175148 -3.55246019363,1.6190110445,2.22948908806 -3.5464785099,1.61902105808,2.2400829792 -3.53649926186,1.61803281307,2.24963736534 -3.54450678825,1.62303566933,2.26144099236 -3.53752613068,1.62304627895,2.27201914787 -3.52954506874,1.62205696106,2.28160762787 -3.52056527138,1.62206816673,2.29117894173 -3.51858353615,1.62407779694,2.3047606945 -3.5026037693,1.61908984184,2.30934691429 -3.49162459373,1.61710166931,2.3179090023 -3.50463199615,1.62610387802,2.3336994648 -3.49465179443,1.62411510944,2.34227967262 -3.47867226601,1.61912739277,2.34686231613 -3.47969031334,1.62313652039,2.3624458313 -3.47371006012,1.62414729595,2.37401485443 -3.46872901917,1.62515735626,2.38560199738 -3.4537498951,1.62116980553,2.39117145538 -3.44975972176,1.62117516994,2.39596486092 -3.44577884674,1.62218546867,2.40854310989 -3.44179773331,1.62419557571,2.42112231255 -3.43781709671,1.62620568275,2.43370223045 -3.42783594131,1.62421655655,2.44130635262 -3.42185592651,1.62522721291,2.45287656784 -3.41486620903,1.62323319912,2.45566797256 -3.40988516808,1.62424349785,2.46725702286 -3.40190577507,1.62425482273,2.47781729698 -3.39892506599,1.62626504898,2.49139165878 -3.39294505119,1.62727582455,2.50296378136 -3.37796568871,1.62328791618,2.50755023956 -3.37498497963,1.62629806995,2.52112650871 -3.37199378014,1.62630283833,2.52593851089 -3.37001347542,1.6293129921,2.54050922394 -3.35803341866,1.62632453442,2.54709792137 -3.34405589104,1.62333738804,2.55364751816 -3.35607123375,1.63334393501,2.5772562027 -3.33709311485,1.62735712528,2.57883834839 -3.32711386681,1.62636864185,2.58741235733 -3.33512163162,1.63337171078,2.60120749474 -3.31114530563,1.62438642979,2.59976530075 -3.31716179848,1.63139426708,2.61936974525 -3.30618262291,1.62940585613,2.6269493103 -3.2972035408,1.62941741943,2.63651704788 -3.28122520447,1.62542998791,2.64009785652 -3.28823256493,1.63043296337,2.65290641785 -3.28125357628,1.63144445419,2.66446328163 -3.2752726078,1.63245475292,2.67506575584 -3.27029252052,1.63346540928,2.68763804436 -3.26131343842,1.63347697258,2.69720625877 -3.25633358955,1.63548779488,2.7097799778 -3.24735331535,1.63449883461,2.71837329865 -3.2353656292,1.63050603867,2.71715450287 -3.22738552094,1.63051700592,2.72674179077 -3.22540450096,1.63352692127,2.74132823944 -3.20842647552,1.62953996658,2.74390459061 -3.20744562149,1.63354969025,2.75948834419 -3.20346570015,1.63556027412,2.77306079865 -3.19648599625,1.6365711689,2.78364610672 -3.18749690056,1.63357770443,2.78443431854 -3.18751692772,1.63858783245,2.80199480057 -3.17553710938,1.63659930229,2.80759763718 -3.17255711555,1.63960969448,2.82217073441 -3.16257834435,1.63862144947,2.83074259758 -3.14859986305,1.63563394547,2.83532595634 -3.14661002159,1.63663911819,2.84211468697 -3.13962984085,1.63765001297,2.85270166397 -3.1266515255,1.63566231728,2.8582804203 -3.1236717701,1.63867259026,2.87285733223 -3.11969137192,1.64068317413,2.88643789291 -3.1027135849,1.63669598103,2.88802480698 -3.0967335701,1.63770675659,2.89961051941 -3.10274267197,1.64371073246,2.91438579559 -3.08176660538,1.63672482967,2.91295409203 -3.08278465271,1.64273405075,2.9305524826 -3.07280516624,1.6417453289,2.93814730644 -3.06182813644,1.64075803757,2.94669628143 -3.0478489399,1.63777005672,2.9502954483 -3.04485917091,1.63877534866,2.95608949661 -3.03088140488,1.63578808308,2.96066379547 -3.03190159798,1.64179801941,2.98022270203 -3.02692127228,1.64380860329,2.9928123951 -3.01194286346,1.64082098007,2.99540948868 -3.00396418571,1.64083254337,3.00597834587 -2.9969856739,1.64284396172,3.01754760742 -2.98599720001,1.63885080814,3.01534581184 -2.98501610756,1.64386057854,3.03193688393 -2.9740383625,1.64287281036,3.03950738907 -2.96106076241,1.64088535309,3.04507708549 -2.96307826042,1.64689385891,3.06369495392 -2.95110034943,1.64490628242,3.07026529312 -2.94112229347,1.64491832256,3.07883572578 -2.94013285637,1.64792382717,3.08761262894 -2.92515492439,1.64393627644,3.09020209312 -2.90717887878,1.63894999027,3.09076523781 -2.91019654274,1.64595878124,3.11136984825 -2.90721702576,1.64996922016,3.12694883347 -2.89323973656,1.64798223972,3.13151526451 -2.8772623539,1.64399504662,3.13309955597 -2.88227033615,1.64899849892,3.146910429 -2.86629390717,1.64501202106,3.14947199821 -2.84631800652,1.63902592659,3.14704608917 -2.84633827209,1.64503622055,3.16661286354 -2.83435988426,1.64404821396,3.1722009182 -2.82538104057,1.64405953884,3.18079471588 -2.83138895035,1.65106320381,3.19659423828 -2.8174123764,1.64807629585,3.20115613937 -2.80143547058,1.64408934116,3.20273327827 -2.79345631599,1.64510047436,3.21233034134 -2.78347849846,1.64511263371,3.220900774 -2.77649974823,1.64712381363,3.23248028755 -2.77452015877,1.65213429928,3.25005555153 -2.75553369522,1.64314293861,3.23784899712 -2.75755286217,1.65115237236,3.25943851471 -2.7535738945,1.65516316891,3.2750108242 -2.7385969162,1.65117621422,3.27758622169 -2.73061752319,1.6521872282,3.28718662262 -2.71864056587,1.65120005608,3.2937514782 -2.71565032005,1.65220522881,3.2995557785 -2.70267391205,1.6512182951,3.30511593819 -2.69469547272,1.65222966671,3.31569695473 -2.68171715736,1.65024185181,3.31929707527 -2.6827378273,1.65825200081,3.34185862541 -2.67075920105,1.65626382828,3.34646368027 -2.66078138351,1.65627598763,3.35503745079 -2.65879178047,1.65828132629,3.36282920837 -2.6518137455,1.66129291058,3.37539887428 -2.64483475685,1.66330397129,3.38698935509 -2.63585662842,1.66431581974,3.39657044411 -2.61588168144,1.6583302021,3.39313197136 -2.61889982224,1.66633892059,3.41673970222 -2.59892511368,1.66035342216,3.41329908371 -2.59193563461,1.65835940838,3.41410422325 -2.59495449066,1.66836857796,3.43869805336 -2.56798171997,1.65738451481,3.42625045776 -2.56200313568,1.66039574146,3.43983101845 -2.55202460289,1.66040742397,3.44742631912 -2.54704546928,1.66441833973,3.4620153904 -2.53306937218,1.66243124008,3.4655854702 -2.53907752037,1.66943502426,3.48438048363 -2.52110266685,1.66544902325,3.48294305801 -2.50812578201,1.66346180439,3.48751878738 -2.50314617157,1.66747248173,3.50211286545 -2.49516773224,1.66948390007,3.5127055645 -2.49418759346,1.67649388313,3.53329539299 -2.49519753456,1.68049871922,3.54608392715 -2.48122048378,1.67851138115,3.54867267609 -2.48124027252,1.68652141094,3.57125782967 -2.47626209259,1.69053268433,3.58782601357 -2.47928071022,1.7005417347,3.61442327499 -2.45130801201,1.68855762482,3.59799194336 -2.43333339691,1.6835719347,3.59654760361 -2.4673333168,1.71256911755,3.65538358688 -2.46835374832,1.72157907486,3.68096017838 -2.46537446976,1.72858965397,3.70054221153 -2.46339440346,1.73559999466,3.72113513947 -2.45841550827,1.73961079121,3.73772263527 -2.45943498611,1.74962043762,3.76331353188 -2.44845890999,1.74963331223,3.77287101746 -2.45146727562,1.75663721561,3.7886826992 -2.44448900223,1.7596487999,3.80326104164 -2.42351484299,1.75266337395,3.79683017731 -2.41753530502,1.75667405128,3.81143474579 -2.40355968475,1.755687356,3.81600022316 -2.39458203316,1.75769925117,3.82757925987 -2.40258979797,1.76870250702,3.85238218307 -2.39661169052,1.77371382713,3.86896133423 -2.39363265038,1.78072452545,3.89054012299 -2.37365651131,1.77373814583,3.88314509392 -2.36567926407,1.77675020695,3.89770889282 -2.34770345688,1.77176380157,3.89429926872 -2.33972597122,1.77477538586,3.90787982941 -2.35073280334,1.78877794743,3.93868398666 -2.22688674927,1.74686455727,3.89512205124 -2.22089791298,1.74687063694,3.8979203701 -2.20692205429,1.74588382244,3.9014942646 -2.21393966675,1.76089203358,3.94009709358 -2.19196677208,1.75290703773,3.93065595627 -2.17099142075,1.74592101574,3.92025232315 -2.15101766586,1.738935709,3.91381263733 -2.15102696419,1.74394035339,3.92662215233 -2.14404988289,1.74895215034,3.94319009781 -2.12707400322,1.74396538734,3.93978404999 -2.11409878731,1.74397873878,3.94633865356 -2.1001226902,1.74299156666,3.9489235878 -2.08614635468,1.74100446701,3.95150780678 -2.07616877556,1.74301636219,3.96109938622 -2.07517933846,1.7470215559,3.97388958931 -2.05420517921,1.73903608322,3.96346879005 -2.04122900963,1.73904883862,3.96805024147 -2.03425073624,1.743060112,3.98364019394 -2.01927566528,1.7410736084,3.98520946503 -2.00529956818,1.73908662796,3.98779129982 -1.99432361126,1.7410992384,3.99735832214 -1.98433530331,1.7371057272,3.99116969109 -1.96836066246,1.73411941528,3.99073600769 -1.96438217163,1.74213039875,4.01331853867 -1.94940650463,1.73914372921,4.01389884949 -1.93442964554,1.7361562252,4.0125041008 -1.92745256424,1.74216794968,4.03007650375 -1.9114780426,1.73918187618,4.02964067459 -1.90248990059,1.7361882925,4.02544736862 -1.89351308346,1.73920059204,4.03901958466 -1.87653791904,1.73521387577,4.03460550308 -1.86156260967,1.73222720623,4.0351805687 -1.85558414459,1.73923838139,4.05377435684 -1.83861041069,1.73525249958,4.05133199692 -1.83262193203,1.73525857925,4.05412864685 -1.82364392281,1.73827016354,4.06573057175 -1.80966889858,1.73728346825,4.0692949295 -1.79069435596,1.73029732704,4.05988073349 -1.78271770477,1.73630940914,4.07644987106 -1.76974117756,1.7353219986,4.0800409317 -1.75676476955,1.73433446884,4.0836315155 -1.74577796459,1.72934174538,4.07542181015 -1.731803298,1.72935521603,4.07898330688 -1.72582435608,1.73536610603,4.09758996964 -1.71184968948,1.73437941074,4.10115194321 -1.69487464428,1.72939300537,4.09573554993 -1.684897542,1.73240494728,4.10632705688 -1.67990982533,1.73441123962,4.11310625076 -1.66793298721,1.73442351818,4.11870098114 -1.64895927906,1.72843790054,4.10927009583 -1.63898265362,1.73145008087,4.1208524704 -1.62900483608,1.73346161842,4.13045835495 -1.60803246498,1.72547662258,4.11701059341 -1.59905576706,1.72948861122,4.13158941269 -1.59406745434,1.73149478436,4.13738250732 -1.58409070969,1.73450672626,4.14896869659 -1.56711530685,1.72952008247,4.14156341553 -1.55114102364,1.72553384304,4.13913059235 -1.54316341877,1.7315454483,4.15572166443 -1.53218710423,1.73355770111,4.16530370712 -1.51121413708,1.72457230091,4.148873806 -1.50322604179,1.72257876396,4.14567613602 -1.49824857712,1.73259007931,4.1722536087 -1.48427259922,1.73060286045,4.17284393311 -1.46929788589,1.72861623764,4.1724152565 -1.46032071114,1.73262798786,4.18700695038 -1.44234669209,1.72664189339,4.17758131027 -1.42737162113,1.72465503216,4.17616033554 -1.42138385773,1.72566151619,4.17994880676 -1.40640890598,1.72267472744,4.17852640152 -1.39843130112,1.72968614101,4.19612121582 -1.38345694542,1.72669970989,4.19568920135 -1.37347924709,1.72971117496,4.20629644394 -1.35850429535,1.72772443295,4.20487356186 -1.35251748562,1.72973120213,4.21064424515 -1.33754086494,1.72574365139,4.20525741577 -1.32356572151,1.72475671768,4.20683336258 -1.31059038639,1.72476959229,4.21141052246 -1.29761505127,1.72578251362,4.21598863602 -1.28463876247,1.72479486465,4.21858358383 -1.27166438103,1.72580814362,4.22514390945 -1.2616764307,1.71981465816,4.21295833588 -1.25070106983,1.72382748127,4.22552394867 -1.2397248745,1.72683978081,4.23610877991 -1.22275054455,1.72185337543,4.22668981552 -1.20977437496,1.72086572647,4.2292842865 -1.19979846478,1.72587811947,4.24485874176 -1.18481338024,1.71388626099,4.21764326096 --1.3475035429,1.75320851803,4.07729816437 --1.36547875404,1.76122033596,4.08990478516 --1.36845624447,1.74623060226,4.05347442627 --1.37244486809,1.74323582649,4.04427146912 --1.3834220171,1.74224662781,4.03587627411 --1.40339493752,1.75025939941,4.05044841766 --1.41237199306,1.74627006054,4.03504180908 --1.42434740067,1.74428164959,4.02661705017 --1.45331907272,1.7652951479,4.06821250916 --1.45429849625,1.75030446053,4.03080940247 --1.4612865448,1.75131011009,4.03061008453 --1.47426176071,1.75132155418,4.02518796921 --1.48423790932,1.74733269215,4.01176786423 --1.5012127161,1.75334453583,4.01835775375 --1.51618731022,1.7553563118,4.01793289185 --1.53216230869,1.75936806202,4.02152299881 --1.54214012623,1.75737833977,4.01113367081 --1.54812788963,1.75638401508,4.00692129135 --1.55910491943,1.75439465046,3.99852442741 --1.57407975197,1.75740647316,3.99810194969 --1.59705281258,1.76941919327,4.0186882019 --1.59703159332,1.75442874432,3.98026752472 --1.61400592327,1.75844061375,3.98484635353 --1.62798202038,1.76045167446,3.98344373703 --1.63796877861,1.76445794106,3.98923277855 --1.64494669437,1.75846803188,3.97083258629 --1.67091917992,1.77348101139,3.99741959572 --1.67089891434,1.75949025154,3.96201634407 --1.68687295914,1.76250219345,3.96258354187 --1.70384776592,1.76751387119,3.96717190742 --1.70783638954,1.76551914215,3.95896744728 --1.72781062126,1.77353107929,3.97055840492 --1.73578798771,1.76854145527,3.9541478157 --1.74576556683,1.7655518055,3.94375276566 --1.76573956013,1.77356374264,3.95433712006 --1.77171695232,1.76657414436,3.93291759491 --1.78569293022,1.76858520508,3.93050980568 --1.78868126869,1.76459050179,3.91929197311 --1.80765581131,1.77160227299,3.9278845787 --1.82363045216,1.77461385727,3.92846179008 --1.83360743523,1.77262449265,3.91705274582 --1.84858310223,1.77463555336,3.91664624214 --1.8585600853,1.77264606953,3.90523600578 --1.87253558636,1.77365720272,3.90181922913 --1.88052332401,1.77566289902,3.90261626244 --1.89150059223,1.7746733427,3.89421701431 --1.9064759016,1.77668452263,3.89280056953 --1.91845166683,1.7766957283,3.88437414169 --1.9334269762,1.77870690823,3.88295960426 --1.93440759182,1.76871562004,3.85557508469 --1.95739018917,1.7847237587,3.88434576988 --1.96036958694,1.77573311329,3.85994625092 --1.97234511375,1.77474415302,3.8515188694 --1.98832118511,1.77875494957,3.853120327 --1.99729883671,1.77576518059,3.84071850777 --2.01427412033,1.7807765007,3.84330892563 --2.02724957466,1.78078758717,3.83688354492 --2.03323745728,1.78079307079,3.83266997337 --2.04521465302,1.780803442,3.82627081871 --2.06818914413,1.79081511497,3.84087610245 --2.07016777992,1.78082454205,3.81446027756 --2.07514619827,1.77483427525,3.7940466404 --2.10311770439,1.78884732723,3.81461262703 --2.10009980202,1.77585542202,3.78223466873 --2.12608218193,1.7928634882,3.81401586533 --2.12606167793,1.78187251091,3.78460001945 --2.13803792,1.78188312054,3.77718710899 --2.1500146389,1.78189373016,3.76977396011 --2.16199111938,1.78190422058,3.76236104965 --2.17896676064,1.78591537476,3.76395201683 --2.19195342064,1.79292142391,3.77275037766 --2.19993162155,1.78893101215,3.75935339928 --2.20790839195,1.78494143486,3.74392533302 --2.21988511086,1.78495192528,3.73651313782 --2.41555356979,1.81009995937,3.67676210403 --2.4185321331,1.80310940742,3.6543366909 --2.40752601624,1.79011201859,3.62615680695 --2.42250180244,1.7931227684,3.62273740768 --2.44647574425,1.80213439465,3.63332676888 --2.47444820404,1.81514668465,3.64890384674 --2.49042439461,1.81815707684,3.64749979973 --2.51539850235,1.8281686306,3.65909290314 --2.52937459946,1.83017909527,3.65367627144 --2.52336668968,1.82118272781,3.63247609138 --2.52534675598,1.81419146061,3.61108183861 --2.53932285309,1.81520187855,3.60566282272 --2.55829787254,1.82121300697,3.60724186897 --2.56527662277,1.81822228432,3.5928413868 --2.57725334167,1.81823241711,3.58442115784 --2.58823132515,1.81824207306,3.57602524757 --2.59721899033,1.82024753094,3.57581186295 --2.61119532585,1.82225799561,3.57039618492 --2.63017082214,1.82726883888,3.5719833374 --2.63414955139,1.82227802277,3.55256509781 --2.65812492371,1.83128881454,3.56217479706 --2.66110396385,1.82529783249,3.54176139832 --2.67309093475,1.83030354977,3.54555082321 --2.68006968498,1.82731294632,3.5311460495 --2.69004774094,1.82632243633,3.52074027061 --2.70602345467,1.82933306694,3.51731777191 --2.71600151062,1.82834255695,3.50691199303 --2.71898055077,1.82235181332,3.48649072647 --2.72695875168,1.81936132908,3.4730758667 --2.7419462204,1.82736670971,3.48189115524 --2.75292372704,1.82737648487,3.47247934341 --2.76890063286,1.83038640022,3.47007846832 --2.77288007736,1.8253954649,3.45166516304 --2.91361141205,1.83151125908,3.35074687004 --2.90759325027,1.82051920891,3.32133245468 --2.94256544113,1.83653092384,3.33992385864 --2.95754218102,1.83854091167,3.33450317383 --2.97152900696,1.84454655647,3.33929443359 --2.98450636864,1.84655618668,3.33188152313 --2.98548698425,1.83956456184,3.31148004532 --3.00246286392,1.84357464314,3.30805754662 --3.01544141769,1.84558403492,3.30166459084 --3.03541755676,1.85159397125,3.30225753784 --3.03839755058,1.84660255909,3.28384852409 --3.04038691521,1.844607234,3.27463245392 --3.05836391449,1.84961700439,3.27323198318 --3.0643427372,1.84662592411,3.25781488419 --3.07932090759,1.84963524342,3.25342154503 --3.09229874611,1.85064470768,3.24601316452 --3.10627627373,1.85365402699,3.23960375786 --3.10326695442,1.84765815735,3.22539162636 --3.11824440956,1.85066771507,3.21998167038 --3.13322067261,1.85367763042,3.21355271339 --3.13820099831,1.8506860733,3.19815325737 --3.15617752075,1.85469579697,3.19574332237 --3.16715621948,1.8557049036,3.18633913994 --3.17513561249,1.85371351242,3.17393684387 --3.18412399292,1.85671842098,3.17273330688 --3.19210243225,1.85472750664,3.1593105793 --3.20008182526,1.85373616219,3.14690756798 --3.21505951881,1.85674548149,3.14150381088 --3.22103953362,1.85375392437,3.12710022926 --3.23301720619,1.85476338863,3.11767697334 --3.24499559402,1.85677230358,3.10927438736 --3.24998521805,1.85677671432,3.10407280922 --3.26996135712,1.86178660393,3.10265541077 --3.27993965149,1.86179578304,3.09123325348 --3.28591942787,1.85980427265,3.07682776451 --3.30189776421,1.86381328106,3.07243132591 --3.30687761307,1.86082172394,3.05702447891 --3.3108663559,1.85982644558,3.04980158806 --3.33084392548,1.86583566666,3.04941248894 --3.34082221985,1.86584460735,3.03799080849 --3.35180163383,1.86685323715,3.02859163284 --3.3567814827,1.86386156082,3.01318287849 --3.37275934219,1.86787092686,3.007771492 --3.39373540878,1.87388074398,3.00635075569 --3.3977253437,1.87288486958,3.00014925003 --3.40070557594,1.86989307404,2.98273539543 --3.42068314552,1.87590229511,2.98133730888 --3.43366146088,1.87691116333,2.97292494774 --3.43064308167,1.86991894245,2.95051598549 --3.46961641312,1.88692951202,2.96510767937 --3.45260119438,1.87193620205,2.93070173264 --3.47958636284,1.88494193554,2.94449996948 --3.47656798363,1.87694966793,2.92208719254 --3.48454785347,1.87695801258,2.90968370438 --3.49152684212,1.87496674061,2.89525508881 --3.5235016346,1.88797676563,2.90284442902 --3.51248645782,1.87698328495,2.87546348572 --3.53246283531,1.88199281693,2.87203717232 --3.53645300865,1.88199687004,2.86583542824 --3.53343510628,1.87500429153,2.84443426132 --3.53841543198,1.87301266193,2.82901763916 --3.56639075279,1.88302230835,2.8326048851 --3.5653719902,1.8770301342,2.81218600273 --3.57435202599,1.87703824043,2.80078554153 --3.59233903885,1.88504338264,2.80557751656 --3.60431814194,1.88605189323,2.79617023468 --3.60130023956,1.88005936146,2.7747604847 --3.61927843094,1.88506805897,2.77035856247 --3.61526036263,1.87707567215,2.74794149399 --3.63623785973,1.88408470154,2.74553370476 --3.64721822739,1.88509249687,2.73614478111 --3.65020847321,1.88509654999,2.72893762589 --3.65418839455,1.88110482693,2.71251273155 --3.68616390228,1.89411437511,2.71810293198 --3.67414808273,1.88312113285,2.69070267677 --3.70512366295,1.89513039589,2.69529247284 --3.70510554314,1.89013791084,2.67688941956 --3.71108579636,1.88914608955,2.66247415543 --3.71207690239,1.88714969158,2.65427732468 --3.73705363274,1.89615881443,2.65386295319 --3.73603534698,1.89016628265,2.63445067406 --3.75601387024,1.89617466927,2.63105463982 --3.75699472427,1.89218258858,2.61263036728 --3.75997567177,1.8891903162,2.59621739388 --3.76995658875,1.89019799232,2.58582687378 --3.78894352913,1.89820289612,2.58961176872 --3.78692579269,1.89221024513,2.57020998001 --3.79390668869,1.89221799374,2.55679965019 --3.81488370895,1.89822673798,2.55237364769 --3.81086707115,1.89223384857,2.53197717667 --3.83084535599,1.89824223518,2.52756977081 --3.84483289719,1.90324687958,2.5273501873 --3.8418161869,1.89725387096,2.50795912743 --3.86379408836,1.90426230431,2.5045478344 --3.86577606201,1.90126955509,2.48814678192 --3.87175655365,1.90027737617,2.47372961044 --3.88573646545,1.90328514576,2.46532940865 --3.89371657372,1.90329313278,2.45190501213 --3.90270590782,1.90529727936,2.44869875908 --3.91068673134,1.90530478954,2.43629813194 --3.90866994858,1.90031158924,2.41790747643 --3.92464852333,1.9043200016,2.40948009491 --3.93162941933,1.904327631,2.39607071877 --3.9406106472,1.90433490276,2.38467907906 --3.95758962631,1.90934300423,2.37726402283 --3.9555811882,1.90634655952,2.36705780029 --3.9645614624,1.90735423565,2.35464286804 --3.98054146767,1.91136181355,2.34724545479 --3.99152159691,1.91236972809,2.33582687378 --3.98950457573,1.90837657452,2.31742882729 --4.00648403168,1.91238439083,2.31001996994 --4.01946353912,1.91539216042,2.29959797859 --4.05744838715,1.93239712715,2.31339550018 --4.07642793655,1.93840479851,2.3069896698 --4.03841590881,1.91541075706,2.26656937599 --4.02839946747,1.90641772747,2.24315786362 --4.04338026047,1.91042506695,2.23475766182 --4.06336021423,1.91643261909,2.22936248779 --4.0803399086,1.9214400053,2.22196269035 --4.06333351135,1.91144347191,2.20273709297 --4.07131481171,1.91145062447,2.19033908844 --4.06729698181,1.90545785427,2.1699090004 --4.08527755737,1.91146504879,2.16352105141 --4.10825681686,1.9194726944,2.15911769867 --4.10923862457,1.91547989845,2.14169239998 --4.10323143005,1.91148304939,2.13050436974 --4.11821126938,1.91549050808,2.12108778954 --4.12719249725,1.91549766064,2.10867834091 --4.14117240906,1.91950535774,2.0982530117 --4.14615488052,1.91851186752,2.08487153053 --4.14513731003,1.91451919079,2.06644368172 --4.16011762619,1.91852641106,2.05703186989 --4.16010951996,1.91652977467,2.04883575439 --4.17009115219,1.91853666306,2.03743958473 --4.18707132339,1.92354393005,2.02903008461 --4.19005346298,1.92155086994,2.0136244297 --4.19203567505,1.91955792904,1.99720513821 --4.21001625061,1.92456483841,1.98981177807 --4.21199846268,1.92257189751,1.97339236736 --4.21698904037,1.92357540131,1.96718323231 --4.2349691391,1.9285825491,1.9587687254 --4.24195146561,1.92858946323,1.94536375999 --4.24293422699,1.92659628391,1.92895531654 --4.2469162941,1.9246032238,1.91353559494 --4.26089811325,1.92860984802,1.90414786339 --4.26588058472,1.92761659622,1.88974130154 --4.26787090302,1.92762029171,1.88151872158 --4.28185272217,1.9306268692,1.87213337421 --4.28383493423,1.92863368988,1.85571122169 --4.29981613159,1.93364048004,1.8463050127 --4.29579973221,1.92864704132,1.82790005207 --4.30078220367,1.92765378952,1.81349313259 --4.31176376343,1.93066084385,1.80106925964 --4.32175445557,1.93366372585,1.7978836298 --4.32373666763,1.93167066574,1.78146004677 --4.32971954346,1.93167710304,1.76806759834 --4.33570194244,1.93168377876,1.75364983082 --4.33668470383,1.92969048023,1.73723530769 --4.35166597366,1.93369722366,1.72682249546 --4.36064863205,1.93470358849,1.71442437172 --4.36563968658,1.93570697308,1.70822024345 --4.36562347412,1.93371331692,1.69181525707 --4.37860488892,1.93671989441,1.68040180206 --4.37358856201,1.93172633648,1.66199636459 --4.37757253647,1.93073272705,1.64759933949 --4.39055395126,1.93473923206,1.63618719578 --4.39154529572,1.93374252319,1.6279733181 --4.38652896881,1.92874908447,1.60956382751 --4.3975110054,1.93075561523,1.59714758396 --4.41849184036,1.93876194954,1.5887362957 --4.42747497559,1.93976807594,1.57634246349 --4.41545915604,1.93177473545,1.55492091179 --4.41244363785,1.92778122425,1.53751277924 --4.43343305588,1.93678414822,1.53731215 --4.44641542435,1.93979036808,1.52590715885 --4.43540000916,1.9327968359,1.5054962635 --4.46138143539,1.94280266762,1.49909996986 --4.46136474609,1.93980908394,1.4826887846 --4.47734737396,1.94481503963,1.47228586674 --4.46333217621,1.93582165241,1.45087122917 --4.47732257843,1.9418245554,1.44766795635 --4.47030735016,1.93583083153,1.42926549911 --4.48428869247,1.93983721733,1.41683101654 --4.48027276993,1.93584358692,1.39942574501 --4.48225688934,1.93484961987,1.3840187788 --4.50423908234,1.94285535812,1.37562191486 --4.51022195816,1.9428614378,1.36120808125 --4.49921560287,1.93686461449,1.35001516342 --4.50219917297,1.93587088585,1.33459937572 --4.5081820488,1.93687689304,1.3201842308 --4.52016448975,1.93988287449,1.30777263641 --4.52114915848,1.93888878822,1.29237294197 --4.53413200378,1.9428948164,1.27995502949 --4.52511692047,1.9359010458,1.26155638695 --4.53210783005,1.9389039278,1.2553435564 --4.54609107971,1.94290959835,1.24394583702 --4.54507493973,1.93991565704,1.22753489017 --4.5450592041,1.9389218092,1.21111488342 --4.55504322052,1.94092738628,1.19872403145 --4.55802631378,1.93993341923,1.18330740929 --4.5650177002,1.94293630123,1.17709743977 --4.57300138474,1.9439419508,1.16369712353 --4.57698535919,1.94394803047,1.14827370644 --4.5769701004,1.942953825,1.13287878036 --4.5829539299,1.94295954704,1.11846721172 --4.59093761444,1.94496512413,1.10506820679 --4.59692144394,1.94597089291,1.09065747261 --4.60391330719,1.94797360897,1.08445119858 --4.61089658737,1.94997930527,1.07003438473 --4.61688089371,1.9499849081,1.05562520027 --4.61886501312,1.94999074936,1.04021608829 --4.62284994125,1.94999623299,1.02582013607 --4.62983369827,1.95100188255,1.01140511036 --4.62281894684,1.94700789452,0.993999958038 --4.63180971146,1.95001065731,0.987783968449 --4.63579511642,1.95001602173,0.973388195038 --4.64477825165,1.95202171803,0.958961963654 --4.64976263046,1.95302712917,0.944560587406 --4.65174722672,1.95203280449,0.929151117802 --4.66373109818,1.95603811741,0.91573548317 --4.67471504211,1.95904326439,0.902327299118 --4.65670919418,1.95004665852,0.891139507294 --4.65969371796,1.95005238056,0.875723361969 --4.66867733002,1.95305776596,0.861300051212 --4.67166280746,1.95306301117,0.846911013126 --4.67664670944,1.95406866074,0.83148431778 --4.68663167953,1.9570735693,0.818084776402 --4.67361688614,1.95007991791,0.799673676491 --4.67160987854,1.94808280468,0.791470468044 --4.69259405136,1.95608723164,0.780068278313 --4.68857908249,1.9530929327,0.763661682606 --4.69156360626,1.95309841633,0.748245894909 --4.69954824448,1.95510351658,0.733832597733 --4.68453359604,1.94710993767,0.715423166752 --4.69451904297,1.95011472702,0.702027022839 --4.72850942612,1.96511554718,0.699814796448 --4.6854968071,1.94512367249,0.676397144794 --4.69948101044,1.95012843609,0.662984192371 --4.71646547318,1.95613276958,0.650586843491 --4.69745111465,1.94713950157,0.631159186363 --4.70743656158,1.95014417171,0.617766559124 --4.7264213562,1.95714819431,0.605364739895 --4.70541477203,1.94715225697,0.594155728817 --4.72239875793,1.95415687561,0.580736517906 --4.72838401794,1.9551615715,0.566336512566 --4.71637010574,1.94916784763,0.54892539978 --4.72335529327,1.95117259026,0.534521222115 --4.73834085464,1.95717680454,0.521115243435 --4.73232603073,1.95318257809,0.504706263542 --4.74031829834,1.95618486404,0.497489154339 --4.74930334091,1.95918953419,0.48308095336 --4.73528909683,1.95219564438,0.465670526028 --4.7422747612,1.954200387,0.451269328594 --4.75525999069,1.95920479298,0.436849713326 --4.74524641037,1.954210639,0.420449644327 --4.7462387085,1.95421338081,0.412230372429 --4.75822496414,1.95821726322,0.398843228817 --4.74221038818,1.95022368431,0.381430923939 --4.75319576263,1.95422816277,0.36702054739 --4.76218080521,1.95823276043,0.351590037346 --4.74316692352,1.94923949242,0.334180772305 --4.75815343857,1.95424318314,0.320789605379 --4.77514600754,1.96224415302,0.314584106207 --4.7661318779,1.95724999905,0.298174142838 --4.75811767578,1.9532558918,0.281759828329 --4.77010393143,1.95825994015,0.267352849245 --4.75208950043,1.94926667213,0.249931737781 --4.76607513428,1.95427048206,0.235521912575 --4.77506113052,1.95827448368,0.221123948693 --4.76605463028,1.95427775383,0.212924808264 --4.77803993225,1.95828187466,0.197495296597 --4.77002668381,1.95428740978,0.182103142142 --4.77201271057,1.95429217815,0.166692495346 --4.77099943161,1.95429718494,0.151286527514 --4.7759847641,1.95530164242,0.135871440172 --4.77097082138,1.953307271,0.119443930686 --4.7679643631,1.95130980015,0.112257860601 --4.77395057678,1.95431423187,0.0968414470553 --4.78593635559,1.95831799507,0.0814190357924 --4.76892280579,1.95032429695,0.0660313442349 --4.78390932083,1.9573277235,0.0506065972149 --4.77389574051,1.95233345032,0.035208798945 --4.77688264847,1.953338027,0.0197976026684 --4.77687501907,1.9533405304,0.0115797547624 --4.78086137772,1.95434498787,-0.00383159145713 --4.77984809875,1.95434975624,-0.0192393567413 --4.77083492279,1.95035529137,-0.0346426032484 --4.77682113647,1.95235943794,-0.0500547587872 --4.77580738068,1.95136427879,-0.0654630959034 --4.77980041504,1.95336639881,-0.0736827775836 --4.76578712463,1.94737255573,-0.0890877097845 --4.77277374268,1.95037651062,-0.104499071836 --4.77176046371,1.94938135147,-0.119908295572 --4.75874662399,1.94338738918,-0.135317549109 --4.76073312759,1.94439184666,-0.150728240609 --4.76872014999,1.94739544392,-0.166137501597 --4.76270675659,1.94540083408,-0.181549072266 --4.77170133591,1.94940185547,-0.188738137484 --4.76868772507,1.9474067688,-0.204148754478 --4.77567386627,1.95041072369,-0.220582827926 --4.7646613121,1.94641649723,-0.23497107625 --4.76064777374,1.94442152977,-0.250383794308 --4.76063489914,1.94442605972,-0.265794426203 --4.7606215477,1.94443058968,-0.281205028296 --4.75661468506,1.94343340397,-0.289427578449 --4.7676024437,1.9474363327,-0.304827958345 --4.76658964157,1.94744098186,-0.320238977671 --4.76457643509,1.94744563103,-0.3356513381 --4.76056289673,1.94545066357,-0.351066023111 --4.75254964828,1.94245624542,-0.366486698389 --4.75454378128,1.94345808029,-0.373675853014 --4.74852991104,1.94046330452,-0.389094859362 --4.75151777267,1.94246721268,-0.404501646757 --4.75450515747,1.94347119331,-0.419907510281 --4.74449157715,1.93947696686,-0.435334712267 --4.76748085022,1.95047795773,-0.451732933521 --4.74446630478,1.94048559666,-0.466157048941 --4.75146102905,1.94348657131,-0.473335534334 --4.75244760513,1.94449102879,-0.489771217108 --4.74043416977,1.9394967556,-0.504178583622 --4.74542284012,1.94250023365,-0.519578874111 --4.74841022491,1.94350397587,-0.534982323647 --4.73739671707,1.93950998783,-0.550417840481 --4.73638486862,1.93951416016,-0.564803540707 --4.74337863922,1.94351541996,-0.574032902718 --4.72636461258,1.93552207947,-0.587430953979 --4.73735380173,1.94152450562,-0.603840768337 --4.7363409996,1.94152891636,-0.619253456593 --4.73332834244,1.94053351879,-0.63467168808 --4.72431516647,1.93753886223,-0.649080336094 --4.73630475998,1.94354104996,-0.665482461452 --4.74029874802,1.94554245472,-0.673688650131 --4.71728372574,1.93555033207,-0.68711400032 --4.7302737236,1.94255208969,-0.703510463238 --4.7272605896,1.94155669212,-0.718929290771 --4.72024822235,1.93956172466,-0.733334720135 --4.72023582458,1.93956565857,-0.748743951321 --4.71422290802,1.93857085705,-0.764174580574 --4.72121810913,1.94157159328,-0.772367715836 --4.7212061882,1.94257545471,-0.787776350975 --4.71219348907,1.93958091736,-0.802191257477 --4.71218156815,1.93958473206,-0.817599892616 --4.70116758347,1.93559074402,-0.832024335861 --4.69515562057,1.93459546566,-0.84643048048 --4.7061457634,1.93959724903,-0.862821698189 --4.69613742828,1.93560123444,-0.870053589344 --4.68812465668,1.93360650539,-0.884469091892 --4.69511413574,1.93760895729,-0.900875091553 --4.69110250473,1.93661344051,-0.915273547173 --4.68909025192,1.93661761284,-0.930690526962 --4.69207906723,1.93962085247,-0.94711202383 --4.68106603622,1.93562650681,-0.960516214371 --4.68706178665,1.93862724304,-0.968705356121 --4.67404842377,1.93363332748,-0.982120335102 --4.67703723907,1.93563652039,-0.998540580273 --4.68002557755,1.93863976002,-1.01496005058 --4.66801261902,1.93464553356,-1.0283728838 --4.66600084305,1.93464958668,-1.04379022121 --4.65398740768,1.93065559864,-1.05720555782 --4.65098190308,1.9296579361,-1.06441152096 --4.65397119522,1.93166089058,-1.07980263233 --4.65095949173,1.93166518211,-1.0952256918 --4.64694786072,1.93166947365,-1.10962748528 --4.64193582535,1.93067383766,-1.12403488159 --4.63692331314,1.9296785593,-1.13946974277 --4.63591766357,1.92968034744,-1.14666509628 --4.63290596008,1.92968463898,-1.16208875179 --4.63189506531,1.9306883812,-1.17750060558 --4.62688302994,1.92969274521,-1.19190907478 --4.62987279892,1.93169546127,-1.20729601383 --4.61685943604,1.92870163918,-1.22072732449 --4.61384773254,1.9287058115,-1.23615145683 --4.61084270477,1.92770791054,-1.24233222008 --4.60583019257,1.92671263218,-1.25776922703 --4.60081863403,1.92571699619,-1.27217936516 --4.61381053925,1.93271744251,-1.290579319 --4.59579610825,1.92672467232,-1.30199468136 --4.58678388596,1.92472982407,-1.31540572643 --4.58377218246,1.92473387718,-1.33083033562 --4.58176660538,1.92473590374,-1.33803260326 --4.58575725555,1.92773830891,-1.35443532467 --4.57174396515,1.92274463177,-1.36685609818 --4.56773281097,1.92274868488,-1.38126122952 --4.57872438431,1.9287494421,-1.39966523647 --4.57971429825,1.93175256252,-1.41608643532 --4.55469799042,1.92176139355,-1.42551124096 --4.55469369888,1.92276275158,-1.43269920349 --4.54968214035,1.92176711559,-1.44711184502 --4.54066991806,1.91977226734,-1.46052873135 --4.53065681458,1.9167778492,-1.47395420074 --4.53564739227,1.92077982426,-1.49137091637 --4.53863859177,1.92478215694,-1.5077753067 --4.53162717819,1.92278671265,-1.52117741108 --4.51861906052,1.91779136658,-1.5253881216 --4.5186085701,1.91979444027,-1.54181563854 --4.52459955215,1.92479598522,-1.55922019482 --4.49758386612,1.91380548477,-1.56662869453 --4.49357223511,1.9138096571,-1.58206260204 --4.49956417084,1.91881108284,-1.59946537018 --4.48855161667,1.9158166647,-1.61187827587 --4.50054979324,1.92181515694,-1.62306797504 --4.48053455353,1.91482305527,-1.63350594044 --4.47052240372,1.91282844543,-1.64591240883 --4.48151540756,1.91982841492,-1.665320158 --4.44649744034,1.90584027767,-1.66973745823 --4.45248937607,1.90984141827,-1.6871355772 --4.4614815712,1.9168419838,-1.70655810833 --4.43947076797,1.90784919262,-1.70778512955 --4.44246196747,1.91085112095,-1.72418177128 --4.44445323944,1.91385340691,-1.74058651924 --4.4274392128,1.90886056423,-1.75101006031 --4.44243335724,1.91685926914,-1.77242255211 --4.43042087555,1.91386520863,-1.78382623196 --4.40440416336,1.90487492085,-1.79126107693 --4.40439987183,1.90587615967,-1.79844605923 --4.40439033508,1.90787887573,-1.81486797333 --4.39937925339,1.90788292885,-1.82928574085 --4.38936758041,1.90588819981,-1.84170091152 --4.38935804367,1.90789091587,-1.85812139511 --4.37034368515,1.90189862251,-1.86652374268 --4.36133623123,1.89790248871,-1.87174654007 --4.37433099747,1.90690147877,-1.89316546917 --4.35231494904,1.89891028404,-1.90057587624 --4.35030555725,1.90091335773,-1.91599059105 --4.35229730606,1.90391516685,-1.93238854408 --4.33828401566,1.89992177486,-1.94382429123 --4.32627153397,1.89692747593,-1.95421409607 --4.33927106857,1.90392506123,-1.96741437912 --4.31325387955,1.89393508434,-1.97385120392 --4.30624294281,1.8939396143,-1.98726773262 --4.31023597717,1.89794075489,-2.0046672821 --4.28821992874,1.8909497261,-2.01209354401 --4.281208992,1.88995409012,-2.02551102638 --4.2922039032,1.89795315266,-2.04590821266 --4.27119255066,1.88896048069,-2.04511904716 --4.27018356323,1.89096331596,-2.06154680252 --4.27817773819,1.89796304703,-2.08094835281 --4.25916242599,1.89097118378,-2.0893740654 --4.24314880371,1.88697838783,-2.09879374504 --4.25014305115,1.89297842979,-2.1182038784 --4.23412847519,1.88798570633,-2.12762498856 --4.23011922836,1.88898897171,-2.14203429222 --4.23211574554,1.89098954201,-2.151242733 --4.22010326385,1.88799548149,-2.16164422035 --4.20008802414,1.88200390339,-2.16906714439 --4.20608186722,1.88700413704,-2.18848347664 --4.19506931305,1.88500976562,-2.19990110397 --4.19206047058,1.88701283932,-2.21532344818 --4.19605827332,1.89001250267,-2.22450470924 --4.1680393219,1.87902367115,-2.22793054581 --4.17503404617,1.88602352142,-2.24835538864 --4.17002439499,1.88702714443,-2.26277637482 --4.14100503922,1.87503886223,-2.26519656181 --4.14499902725,1.88003945351,-2.28360557556 --4.14999341965,1.88603961468,-2.30199980736 --4.13298273087,1.87904632092,-2.30221986771 --4.12397146225,1.87805140018,-2.31464314461 --4.11596012115,1.87705588341,-2.32705354691 --4.10594892502,1.87506115437,-2.33846521378 --4.11194372177,1.88206100464,-2.35889291763 --4.09592914581,1.87706840038,-2.36730885506 --4.09292125702,1.87907111645,-2.38170361519 --4.08091259003,1.87507629395,-2.3839161396 --4.07290172577,1.87408077717,-2.39632821083 --4.06389045715,1.87308585644,-2.40875434875 --4.0708861351,1.87908494473,-2.4291613102 --4.06087446213,1.87809026241,-2.44057559967 --4.04385995865,1.87309813499,-2.44901251793 --4.03384828568,1.87210345268,-2.46042895317 --4.03884744644,1.87510228157,-2.47060894966 --4.0248336792,1.87210917473,-2.48105669022 --4.01982450485,1.87311255932,-2.49445271492 --4.02682065964,1.88011157513,-2.51587557793 --4.00380277634,1.87212157249,-2.52030467987 --3.99379229546,1.87112689018,-2.53069806099 --3.98978304863,1.87212979794,-2.54612851143 --3.98277664185,1.87113320827,-2.55033016205 --3.96976423264,1.8681396246,-2.55974388123 --3.97375917435,1.87313950062,-2.57915496826 --3.95674443245,1.86814749241,-2.58657932281 --3.94273090363,1.86515426636,-2.59601068497 --3.94872736931,1.87215328217,-2.61641335487 --3.93771576881,1.87015891075,-2.62682437897 --3.93871283531,1.87215912342,-2.63602972031 --3.92069792747,1.86716747284,-2.6424498558 --3.9196908474,1.87016916275,-2.65885663033 --3.90367627144,1.86617672443,-2.66729784012 --3.89366531372,1.86418187618,-2.67769598961 --3.89365911484,1.8681832552,-2.69511032104 --3.8816473484,1.8661891222,-2.70451617241 --3.87764215469,1.86619126797,-2.71072435379 --3.8746342659,1.86819374561,-2.72715902328 --3.86062097549,1.86520063877,-2.7355735302 --3.86761856079,1.87319886684,-2.75799322128 --3.84660196304,1.8662084341,-2.76139950752 --3.83559036255,1.86421406269,-2.77181625366 --3.83358359337,1.86821591854,-2.78823304176 --3.82557654381,1.86521983147,-2.79143381119 --3.81256365776,1.86322629452,-2.80086064339 --3.81555938721,1.86822593212,-2.82128953934 --3.8075492382,1.86823022366,-2.8337059021 --3.80554294586,1.8722319603,-2.8501188755 --3.80853915215,1.87723135948,-2.86951875687 --3.77151322365,1.86224830151,-2.86194181442 --3.76750850677,1.86225044727,-2.86815071106 --3.77750849724,1.87224674225,-2.89357447624 --3.75849246979,1.8662558794,-2.89798641205 --3.75648641586,1.8692574501,-2.91439628601 --3.74447417259,1.86826348305,-2.92483377457 --3.73646450043,1.86826777458,-2.93725037575 --3.72945833206,1.86627113819,-2.94043970108 --3.7204477787,1.86627578735,-2.95287394524 --3.71243786812,1.86627995968,-2.96529078484 --3.70242738724,1.86528515816,-2.97569584846 --3.70142197609,1.86928606033,-2.99310731888 --3.68440675735,1.86429440975,-2.99954175949 --3.67139434814,1.86230099201,-3.00795435905 --3.67139196396,1.86430108547,-3.01716184616 --3.65938019753,1.86330723763,-3.02658104897 --3.64536714554,1.86031424999,-3.03398990631 --3.6483643055,1.86631309986,-3.05541849136 --3.63134932518,1.86132144928,-3.0608355999 --3.61933732033,1.86032760143,-3.07025671005 --3.62633728981,1.8683245182,-3.09467720985 --3.6163289547,1.8653293848,-3.09587979317 --3.61032104492,1.8673324585,-3.10928297043 --3.57829618454,1.85434830189,-3.10372877121 --3.54026722908,1.83836722374,-3.09215378761 --2.95066523552,1.82666635513,-3.69765233994 --2.93364858627,1.82267594337,-3.7010948658 --2.94065642357,1.83466923237,-3.72947597504 --2.92764353752,1.82967710495,-3.72671294212 --2.9126291275,1.82668554783,-3.73011183739 --2.92063784599,1.83867752552,-3.76253914833 --2.90061831474,1.8326895237,-3.76095700264 --2.90262150764,1.84168565273,-3.78638315201 --2.8846039772,1.83669614792,-3.78679490089 --2.86358332634,1.83070886135,-3.78524041176 --2.85957932472,1.83071053028,-3.79144477844 --2.84957027435,1.83171522617,-3.80186295509 --2.82955026627,1.82572746277,-3.80028963089 --2.8225440979,1.82773005962,-3.81369423866 --2.80752968788,1.82573843002,-3.81913709641 --2.79651927948,1.82574391365,-3.82856106758 --2.7785012722,1.82075476646,-3.82898402214 --2.77449798584,1.82175636292,-3.83518838882 --2.75147390366,1.81277120113,-3.82758593559 --2.74046349525,1.81277680397,-3.83701229095 --2.73946452141,1.81977462769,-3.85943675041 --2.71343708038,1.80979180336,-3.84885787964 --2.70543026924,1.81179499626,-3.8622853756 --2.68941402435,1.8078045845,-3.86470603943 --2.68340826035,1.80780768394,-3.86892294884 --2.66639113426,1.80381786823,-3.8703520298 --2.67039847374,1.81481182575,-3.89773869514 --2.65938854218,1.8158172369,-3.908182621 --2.65939164162,1.82281386852,-3.93260598183 --2.64938259125,1.82381868362,-3.94200587273 --2.63036298752,1.81883060932,-3.94043254852 --2.62736105919,1.82083129883,-3.94966220856 --2.61434841156,1.81883847713,-3.95506620407 --2.60433959961,1.81984317303,-3.96548390388 --2.60834860802,1.83183598518,-3.99691915512 --2.60334658623,1.83683633804,-4.01433086395 --2.58432650566,1.83084845543,-4.01276111603 --2.56029987335,1.82186484337,-4.00318145752 --2.55829977989,1.82486450672,-4.01340007782 --2.54328489304,1.82287335396,-4.01682138443 --2.52927088737,1.81988143921,-4.021235466 --2.52627182007,1.82687985897,-4.04266119003 --2.5082526207,1.82189142704,-4.04107522964 --2.49624180794,1.82189762592,-4.04950714111 --2.5012512207,1.83089113235,-4.06971311569 --2.47822523117,1.82190704346,-4.06113910675 --2.46821689606,1.82291173935,-4.07155370712 --2.46221423149,1.82691240311,-4.08898115158 --2.44319367409,1.82192492485,-4.08641052246 --2.43719124794,1.82692563534,-4.10383653641 --2.43018746376,1.83092749119,-4.11925411224 --2.40215301514,1.81694865227,-4.10065793991 --2.40916633606,1.82693970203,-4.12486362457 --2.39014554024,1.82195234299,-4.12229824066 --2.37513017654,1.81896138191,-4.1257276535 --2.36011528969,1.81697046757,-4.12915849686 --2.35811877251,1.82496726513,-4.15257072449 --2.34110069275,1.82097840309,-4.15199041367 --2.32307696342,1.81099307537,-4.13620376587 --2.3180770874,1.81699240208,-4.15664386749 --2.28803801537,1.80101668835,-4.13203287125 --2.27903199196,1.80401980877,-4.146484375 --2.27102732658,1.80802249908,-4.15989303589 --2.25000214577,1.80003774166,-4.15231895447 --2.23899245262,1.8000433445,-4.1607298851 --2.26002955437,1.82301926613,-4.2109375 --2.2370018959,1.81503629684,-4.20138692856 --2.23200201988,1.82003581524,-4.21978616714 --2.21498322487,1.81604707241,-4.2192158699 --2.20297241211,1.8160533905,-4.22663402557 --2.1859536171,1.81206476688,-4.22606658936 --2.18095445633,1.8190639019,-4.24547719955 --2.1649324894,1.81007754803,-4.23169469833 --2.15793037415,1.81507837772,-4.249127388 --2.14491772652,1.81408572197,-4.25454330444 --2.12890028954,1.81109631062,-4.25496816635 --2.11288309097,1.80810701847,-4.25539445877 --2.1108891964,1.81610250473,-4.28080320358 --2.08585619926,1.80512285233,-4.26524448395 --2.08686327934,1.81211841106,-4.28144407272 --2.07485246658,1.81212472916,-4.28886318207 --2.06384396553,1.81312978268,-4.29929685593 --2.04582214355,1.80814301968,-4.29471111298 --2.03681778908,1.81214559078,-4.30914735794 --2.02781271935,1.81514847279,-4.32256746292 --2.0087890625,1.80816268921,-4.31699800491 --2.00078010559,1.80716824532,-4.31620121002 --1.99478113651,1.81316745281,-4.33663368225 --1.96173012257,1.79319870472,-4.30003356934 --1.95372736454,1.79720032215,-4.31646776199 --1.93971300125,1.7962089777,-4.31989145279 --1.92369413376,1.79222047329,-4.31830453873 -2.2179582119,1.76801979542,-3.43262934685 -2.22195744514,1.76201808453,-3.41402673721 -2.23196578026,1.76101982594,-3.40443539619 -2.23997426033,1.76202225685,-3.40365242958 -2.2640042305,1.77203190327,-3.41704702377 -2.26099276543,1.7600260973,-3.38548088074 -2.27701020241,1.76403141022,-3.38686442375 -2.27600240707,1.75302708149,-3.35929131508 -2.29502439499,1.75903379917,-3.36370062828 -2.31004023552,1.76203846931,-3.36308956146 -2.31804919243,1.76404094696,-3.3632876873 -2.32705616951,1.76104223728,-3.35170722008 -2.35008382797,1.77105093002,-3.36309313774 -2.35007810593,1.7610476017,-3.33752250671 -2.37410640717,1.77105665207,-3.34892916679 -2.38111114502,1.76805698872,-3.3353331089 -2.39612674713,1.77006137371,-3.3327498436 -2.39312028885,1.76405858994,-3.31694507599 -2.41013860703,1.76806390285,-3.3173596859 -2.41914606094,1.76606547832,-3.30676484108 -2.43516278267,1.76907038689,-3.30616998672 -2.44116663933,1.76507055759,-3.29157185555 -2.44416642189,1.75906932354,-3.27198839188 -2.46018314362,1.7620742321,-3.2704102993 -2.47219705582,1.76707851887,-3.27561235428 -2.48721265793,1.77008283138,-3.2740073204 -2.49421787262,1.76708388329,-3.26140165329 -2.51824498177,1.77609217167,-3.27179956436 -2.51223349571,1.76308703423,-3.23825407028 -2.53125429153,1.76909339428,-3.24263620377 -2.55227708817,1.77610039711,-3.24902749062 -2.54126167297,1.76409447193,-3.22126483917 -2.54426240921,1.75809371471,-3.20267677307 -2.55627417564,1.7590970993,-3.19706964493 -2.56327986717,1.75609815121,-3.18348932266 -2.57729434967,1.75810205936,-3.17989325523 -2.58229756355,1.75310242176,-3.16332244873 -2.59130740166,1.75610518456,-3.16353416443 -2.60632276535,1.75910973549,-3.16192340851 -2.61032533646,1.75410985947,-3.14533138275 -2.62634205818,1.75711464882,-3.14374303818 -2.63835382462,1.75811779499,-3.13715314865 -2.66037750244,1.76612496376,-3.14355158806 -2.66337919235,1.76112473011,-3.12497639656 -2.69241142273,1.77713513374,-3.15213918686 -2.68740367889,1.7661318779,-3.1235678196 -2.70542240143,1.77113735676,-3.12398052216 -2.71743416786,1.77214062214,-3.11738681793 -2.72343921661,1.76814162731,-3.10378956795 -2.73144698143,1.76714360714,-3.09220027924 -2.74846434593,1.77114856243,-3.09160518646 -2.74846386909,1.76714813709,-3.07983589172 -2.76347875595,1.7701523304,-3.07723259926 -2.78149747849,1.77515769005,-3.07763767242 -2.7834982872,1.76915764809,-3.05905056 -2.79551053047,1.77016091347,-3.0524559021 -2.8045194149,1.76916325092,-3.04187202454 -2.82053542137,1.77216792107,-3.03928756714 -2.81653094292,1.76716637611,-3.02547359467 -2.83154606819,1.7691706419,-3.02090597153 -2.84155607224,1.76917338371,-3.01230549812 -2.84856295586,1.7671751976,-2.99971866608 -2.87458920479,1.77718293667,-3.00911140442 -2.87559008598,1.77118289471,-2.98953270912 -2.88559985161,1.77418577671,-2.99073147774 -2.89360809326,1.77218806744,-2.97914743423 -2.9016160965,1.77119016647,-2.96756339073 -2.90962433815,1.7691924572,-2.95598053932 -2.92964434624,1.77619814873,-2.95837283134 -2.92964458466,1.76919817924,-2.93878078461 -2.9386537075,1.76820063591,-2.92820000648 -2.95166635513,1.77320444584,-2.93239760399 -2.96267771721,1.77420759201,-2.92479729652 -2.97669148445,1.77621161938,-2.91921973228 -2.99070549011,1.77921557426,-2.91462016106 -2.99170732498,1.77321600914,-2.8960351944 -3.00472021103,1.77521979809,-2.88945603371 -3.00472140312,1.76822006702,-2.86987447739 -3.01473140717,1.77222299576,-2.8710641861 -3.0297460556,1.77522718906,-2.8674633503 -3.02574372292,1.76622653008,-2.84388589859 -3.03675508499,1.76722991467,-2.83530688286 -3.04976820946,1.76823365688,-2.82872748375 -3.06278133392,1.77123749256,-2.82410407066 -3.0727918148,1.771240592,-2.81452488899 -3.07379341125,1.76824116707,-2.8057384491 -3.09681510925,1.77624738216,-2.80914783478 -3.10382318497,1.77524971962,-2.79754900932 -3.12284111977,1.78025496006,-2.7969584465 -3.12784743309,1.77725696564,-2.78238391876 -3.12484693527,1.77025699615,-2.76177835464 -3.14086151123,1.77626121044,-2.7669942379 -3.15487551689,1.77926528454,-2.7614068985 -3.15587854385,1.7742664814,-2.74382019043 -3.17189407349,1.77827084064,-2.74120688438 -3.18190455437,1.7782740593,-2.7316262722 -3.18591022491,1.77527594566,-2.71703624725 -3.19692206383,1.77627944946,-2.70845341682 -3.21093440056,1.78128290176,-2.71264243126 -3.225949049,1.78428721428,-2.70707035065 -3.24196457863,1.78829169273,-2.70347213745 -3.23996567726,1.78129255772,-2.68289995193 -3.25998401642,1.78729772568,-2.68328928947 -3.25798535347,1.78129863739,-2.66369748116 -3.26999759674,1.78330230713,-2.65610909462 -3.27400231361,1.78230392933,-2.64934396744 -3.27900958061,1.78030610085,-2.63575553894 -3.27400875092,1.77230668068,-2.61415863037 -3.29702925682,1.78031241894,-2.61655402184 -3.2920293808,1.77231311798,-2.59398293495 -3.30404138565,1.7733168602,-2.58639550209 -3.60652732849,1.70549881458,-1.93156898022 -3.56751537323,1.68249988556,-1.89301466942 -3.5605199337,1.67550349236,-1.87345170975 -3.56553006172,1.67450749874,-1.86185932159 -3.55953478813,1.66851079464,-1.84426188469 -3.55653762817,1.66551280022,-1.83449172974 -3.56755042076,1.66751718521,-1.82688426971 -3.56455683708,1.66252100468,-1.81031012535 -3.56556606293,1.65952527523,-1.79574406147 -3.58158183098,1.66453015804,-1.79015612602 -3.59559583664,1.6685346365,-1.78453588486 -3.59060168266,1.66253864765,-1.76696431637 -3.60361170769,1.66754126549,-1.76715958118 -3.60862278938,1.66654574871,-1.75459873676 -3.62463831902,1.67155063152,-1.74900436401 -3.62964868546,1.67055511475,-1.73741483688 -3.62465524673,1.66555917263,-1.71984827518 -3.6286649704,1.66456329823,-1.70824575424 -3.62866902351,1.66256535053,-1.70144426823 -3.63167953491,1.66156995296,-1.68788480759 -3.64269208908,1.66357433796,-1.68027091026 -3.64870357513,1.66357898712,-1.66869807243 -3.6567158699,1.66458380222,-1.65812540054 -3.65972590446,1.66258835793,-1.64553904533 -3.65573263168,1.65859234333,-1.6299405098 -3.66374111176,1.66059505939,-1.62616765499 -3.67275357246,1.66259980202,-1.61657989025 -3.6807653904,1.66260433197,-1.60697817802 -3.67677307129,1.65860879421,-1.59041237831 -3.68878650665,1.66161346436,-1.58280742168 -3.69779920578,1.66261827946,-1.57321858406 -3.69880867004,1.66062283516,-1.55963671207 -3.68380761147,1.65162491798,-1.54487037659 -3.7088265419,1.66162991524,-1.54326319695 -3.699832201,1.65463447571,-1.52469623089 -3.70884490013,1.65563929081,-1.51510727406 -3.71785783768,1.65764415264,-1.50551736355 -3.71386551857,1.65264868736,-1.48993337154 -3.7318816185,1.65865361691,-1.48434233665 -3.72688508034,1.6546561718,-1.47457110882 -3.73589754105,1.65666103363,-1.46497988701 -3.72790431976,1.65066576004,-1.44740772247 -3.74992203712,1.65867066383,-1.44380390644 -3.74793052673,1.6546754837,-1.42922103405 -3.74894070625,1.65268051624,-1.4156472683 -3.75594806671,1.65468299389,-1.41185247898 -3.75195646286,1.65068781376,-1.39627730846 -3.75296640396,1.64869260788,-1.38367605209 -3.76898217201,1.65369784832,-1.3761087656 -3.76198887825,1.64770257473,-1.36050105095 -3.77000212669,1.64970767498,-1.34992539883 -3.78901839256,1.65571248531,-1.34433031082 -3.78002047539,1.65071511269,-1.33355236053 -3.78603219986,1.65072000027,-1.32295238972 -3.79804611206,1.65472507477,-1.31436145306 -3.78105068207,1.64373028278,-1.29379546642 -3.79606604576,1.64873540401,-1.28620898724 -3.80607938766,1.65074038506,-1.27662396431 -3.79408621788,1.6437458992,-1.258061409 -3.79809212685,1.64374828339,-1.25325810909 -3.82311034203,1.65375316143,-1.24965786934 -3.81111717224,1.64575874805,-1.23109972477 -3.80712628365,1.64176404476,-1.21651124954 -3.83014392853,1.65076887608,-1.21191370487 -3.81414937973,1.64077448845,-1.19234931469 -3.81916165352,1.64077985287,-1.1807693243 -3.83117008209,1.64578211308,-1.17895817757 -3.82717943192,1.64178752899,-1.16437399387 -3.8321917057,1.6417927742,-1.15279388428 -3.84520626068,1.6457978487,-1.14420437813 -3.84621763229,1.6438035965,-1.13064348698 -3.83122324944,1.63580906391,-1.11304318905 -3.84923434258,1.64281153679,-1.11225688457 -3.85124564171,1.64181697369,-1.09967684746 -3.85425686836,1.64082217216,-1.08807659149 -3.8672721386,1.6448277235,-1.07851302624 -3.85728049278,1.6388335228,-1.06193971634 -3.86429309845,1.63983881474,-1.05134809017 -3.88130879402,1.64584386349,-1.04375827312 -3.87431240082,1.64184689522,-1.03496980667 -3.87332344055,1.63985264301,-1.02139425278 -3.89133858681,1.64585721493,-1.01477980614 -3.87434506416,1.63586354256,-0.996212244034 -3.88135790825,1.63786900043,-0.985619008541 -3.89937400818,1.64387404919,-0.978031516075 -3.88238143921,1.63488054276,-0.959470748901 -3.88938808441,1.63688290119,-0.955658495426 -3.89440083504,1.63788855076,-0.944077551365 -3.88641047478,1.63189470768,-0.92850881815 -3.89342331886,1.63390016556,-0.917914688587 -3.90743875504,1.63890564442,-0.908348083496 -3.9114511013,1.63891112804,-0.896758198738 -3.92246508598,1.64191639423,-0.887163519859 -3.91446900368,1.63791978359,-0.878379583359 -3.91448020935,1.63592553139,-0.865788519382 -3.91449260712,1.63493180275,-0.852229475975 -3.92750620842,1.63893663883,-0.843617498875 -3.92651820183,1.63694286346,-0.830050766468 -3.93753194809,1.63994812965,-0.820452332497 -3.93253684044,1.63695144653,-0.812665879726 -3.93554973602,1.636957407,-0.800099551678 -3.93556141853,1.63596332073,-0.787510633469 -3.93857336044,1.63596892357,-0.775913178921 -3.93458509445,1.63197565079,-0.761359572411 -3.93259596825,1.629981637,-0.748758256435 -3.94761180878,1.63598692417,-0.739184200764 -3.94061565399,1.63199031353,-0.731388747692 -3.9416282177,1.63099646568,-0.718810081482 -3.9536421299,1.6350017786,-0.709212303162 -3.95265460014,1.63300824165,-0.695651531219 -3.96166872978,1.63601374626,-0.685063004494 -3.95567917824,1.63202023506,-0.671469807625 -3.95868587494,1.63202309608,-0.665681540966 -3.93969416618,1.62303042412,-0.649101912975 -3.95170927048,1.62703621387,-0.638532757759 -3.96372318268,1.63104140759,-0.628929674625 -3.96073532104,1.62904810905,-0.615359961987 -3.97074961662,1.63205373287,-0.604774475098 -3.96976137161,1.63006007671,-0.592185914516 -3.96876788139,1.62906336784,-0.585404992104 -3.97378087044,1.63006937504,-0.573820352554 -3.97579336166,1.6300753355,-0.562217891216 -3.98180699348,1.63208127022,-0.550638020039 -3.98482060432,1.63208770752,-0.538073182106 -3.97983217239,1.62909460068,-0.524496912956 -3.97984480858,1.62810099125,-0.511916637421 -3.98885273933,1.63110363483,-0.507125973701 -3.98886442184,1.63010966778,-0.495513230562 -3.98087644577,1.62511706352,-0.480957299471 -3.99189066887,1.62912261486,-0.470368772745 -3.98890280724,1.62712919712,-0.457774609327 -3.98891568184,1.6261357069,-0.445195972919 -3.9979300499,1.62914180756,-0.433627635241 -3.98493432999,1.62314593792,-0.425826430321 -3.99794912338,1.62815153599,-0.415243446827 -3.99996304512,1.6281580925,-0.402674257755 -3.99797511101,1.62616479397,-0.390087783337 -4.00898933411,1.63017046452,-0.379492223263 -4.00800228119,1.62917709351,-0.366910010576 -4.01200914383,1.63018023968,-0.36112138629 -4.00502157211,1.62618744373,-0.347548305988 -4.01403617859,1.62919354439,-0.335974186659 -4.00704860687,1.62520110607,-0.322403132915 -4.00606107712,1.62520742416,-0.310790359974 -4.00607395172,1.62421417236,-0.298214763403 -4.01008844376,1.62522101402,-0.285653442144 -4.02009630203,1.6292232275,-0.280851125717 -4.0231089592,1.62922954559,-0.269252419472 -4.01912260056,1.62723708153,-0.255695730448 -4.02613687515,1.62924313545,-0.244109585881 -4.02615022659,1.62925004959,-0.231533423066 -4.02216291428,1.62625718117,-0.218946263194 -4.03417682648,1.63126254082,-0.20833979547 -4.03318405151,1.63026642799,-0.201565414667 -4.02719640732,1.62727367878,-0.188973635435 -4.02620983124,1.6262806654,-0.176396250725 -4.03822469711,1.63128650188,-0.164818644524 -4.03423786163,1.6292937994,-0.152233704925 -4.03025054932,1.62630105019,-0.139650076628 -4.04026556015,1.63030707836,-0.128064826131 -4.03727197647,1.62931108475,-0.121287189424 -4.02928447723,1.62531864643,-0.108696565032 -4.03429937363,1.62632536888,-0.0961328819394 -4.04231357574,1.62933146954,-0.0845407769084 -4.0413274765,1.6293387413,-0.0719644129276 -4.04634141922,1.63034510612,-0.0603657886386 -4.03334665298,1.62534987926,-0.053574424237 -4.03436088562,1.62535703182,-0.041002843529 -4.04237508774,1.62836301327,-0.0294079072773 -4.03238868713,1.6233716011,-0.015854658559 -4.03840208054,1.62537789345,-0.00425632297993 -4.04641819,1.62938439846,0.00830851029605 -4.03443050385,1.62339270115,0.0208933297545 -4.04043769836,1.62539565563,0.0266904104501 -4.05145215988,1.63040137291,0.0382874980569 -4.04146528244,1.62540960312,0.050868164748 -4.0344786644,1.62241768837,0.063445135951 -4.05549526215,1.63142299652,0.0760068893433 -4.04250860214,1.62543165684,0.0885857641697 -4.0435218811,1.62543845177,0.100190863013 -4.0545296669,1.63044071198,0.105991110206 -4.03454303741,1.62145066261,0.119534507394 -4.05155801773,1.62945580482,0.13113874197 -4.05357265472,1.62946295738,0.143711999059 -4.0515871048,1.62947070599,0.156285390258 -4.040599823,1.62447881699,0.167888373137 -4.05361509323,1.62948477268,0.180465221405 -4.04462099075,1.62548935413,0.186264455318 -4.02863502502,1.61849880219,0.198828428984 -4.0556511879,1.63050305843,0.211416453123 -4.04266500473,1.62551224232,0.223980650306 -4.049680233,1.62851881981,0.236558809876 -4.05769395828,1.63152480125,0.248172044754 -4.04270172119,1.62553095818,0.254927814007 -4.04071521759,1.62453818321,0.266530811787 -4.05473041534,1.63054394722,0.279119700193 -4.03674459457,1.6225540638,0.291669905186 -4.04375934601,1.6255607605,0.304251611233 -4.05577468872,1.63156652451,0.316842556 -4.03978872299,1.62457597256,0.32842361927 -4.03879499435,1.62457966805,0.334224700928 -4.05180978775,1.62958550453,0.346819698811 -4.0328245163,1.6215955019,0.358391106129 -4.03083896637,1.62160348892,0.370959281921 -4.0478553772,1.62960922718,0.384533524513 -4.04586935043,1.62861657143,0.396135658026 -4.0418844223,1.62662506104,0.408700108528 -4.05389213562,1.63262724876,0.415498405695 -4.03190517426,1.6226375103,0.426085323095 -4.0329208374,1.62364506721,0.438660502434 -4.04493618011,1.62965142727,0.452232152224 -4.02695035934,1.62166118622,0.462822854519 -4.03596591949,1.62566804886,0.4763879776 -4.0369811058,1.62667572498,0.488964676857 -4.02898788452,1.62368011475,0.493777096272 -4.02400302887,1.62168896198,0.506334841251 -4.0340180397,1.62669491768,0.518939733505 -4.02803277969,1.62470340729,0.530527055264 -4.02304840088,1.62271225452,0.543083846569 -4.02906322479,1.62571907043,0.55567830801 -4.01807022095,1.62172412872,0.560475885868 -4.00708580017,1.61773371696,0.572041988373 -4.02310180664,1.62473976612,0.586608767509 -4.01011610031,1.61974906921,0.597198665142 -4.01313114166,1.62175643444,0.609783887863 -4.00614643097,1.61876523495,0.621362090111 -4.01016187668,1.62177240849,0.633952379227 -4.00217008591,1.6177778244,0.639721870422 -4.00318527222,1.61878561974,0.652299702168 -4.00520086288,1.62079334259,0.664882600307 -4.01121520996,1.62379992008,0.677484035492 -3.98923110962,1.61481106281,0.687056064606 -3.99624681473,1.61881816387,0.70062983036 -4.02325439453,1.630818367,0.710431337357 -4.01826953888,1.62982678413,0.722017228603 -3.99428606033,1.61983859539,0.731573224068 -3.98930120468,1.61784720421,0.743155479431 -3.98531651497,1.61785566807,0.754742801189 -3.9853322506,1.6178637743,0.767317593098 -3.98734784126,1.61987137794,0.779903769493 -3.98135495186,1.61787605286,0.784708201885 -3.99037146568,1.62188315392,0.799268126488 -4.00238752365,1.6288895607,0.813847720623 -3.96840286255,1.61390244961,0.820426523685 -3.98441767693,1.62190783024,0.835030198097 -4.00243330002,1.63091337681,0.850616931915 -4.07944822311,1.66591024399,0.877207100391 -4.11647033691,1.68291652203,0.902607262135 -4.06148815155,1.65993320942,0.906146645546 -4.00850486755,1.63794922829,0.908719718456 -3.97952055931,1.62596142292,0.915308594704 -3.98553705215,1.62996912003,0.929863572121 -3.96454524994,1.62197613716,0.931660532951 -3.95756196976,1.61898565292,0.943224787712 -3.94057774544,1.61299622059,0.951817154884 -3.94859409332,1.61800348759,0.966385781765 -3.95160913467,1.62001085281,0.978985965252 -3.93262600899,1.613022089,0.987559556961 -3.9536421299,1.62302744389,1.00512862206 -3.94564938545,1.62003231049,1.00894153118 -3.94966554642,1.62304008007,1.02251946926 -3.95268177986,1.62604808807,1.03609156609 -3.93069863319,1.61705970764,1.04366803169 -3.95271372795,1.62806451321,1.06125712395 -3.92473173141,1.61707746983,1.06781578064 -3.93774747849,1.62408363819,1.08340334892 -3.93875551224,1.62508785725,1.09018683434 -3.9357714653,1.62509644032,1.10177862644 -3.63022994995,1.65888261795,2.09469437599 -3.59525299072,1.64489853382,2.09025621414 -3.58927106857,1.6449085474,2.10084652901 -3.59127926826,1.64691245556,2.10865044594 -3.55430364609,1.63192915916,2.10319781303 -3.55932021141,1.63793706894,2.11979317665 -3.54734015465,1.63394856453,2.127368927 -3.53935909271,1.63395917416,2.13695311546 -3.53737807274,1.63596904278,2.15052175522 -3.5443854332,1.64097201824,2.16132569313 -3.51040816307,1.62698757648,2.15590238571 -3.51342654228,1.63199663162,2.17246985435 -3.50544571877,1.63100731373,2.18205213547 -3.48846673965,1.62601983547,2.18662261963 -3.48048591614,1.62503051758,2.19620323181 -3.47050571442,1.62304186821,2.20477700233 -3.46751451492,1.62304675579,2.20958399773 -3.48253059387,1.63405323029,2.23316788673 -3.45555377007,1.62406790257,2.23172807693 -3.46356964111,1.63107514381,2.25033521652 -3.45858883858,1.63208556175,2.2619125843 -3.44860887527,1.6310968399,2.27048635483 -3.43862891197,1.62910819054,2.27905917168 -3.44663619995,1.63411104679,2.29086756706 -3.42865777016,1.62912392616,2.29443693161 -3.41267871857,1.62413644791,2.29901146889 -3.41169762611,1.62714636326,2.31357812881 -3.40471768379,1.6271572113,2.32414770126 -3.40773415565,1.63216531277,2.33976173401 -3.40574455261,1.63317072392,2.34653329849 -3.39076495171,1.62918281555,2.3511223793 -3.38078522682,1.62719428539,2.35969185829 -3.38480305672,1.63320291042,2.37727403641 -3.37482237816,1.63121378422,2.38487100601 -3.36884260178,1.6322247982,2.39643359184 -3.36986088753,1.63623392582,2.41201877594 -3.36287117004,1.63424003124,2.4148068428 -3.34989142418,1.63125157356,2.42040038109 -3.35190963745,1.6362606287,2.4369802475 -3.33793187141,1.63327348232,2.44352722168 -3.33794975281,1.63728260994,2.45812487602 -3.3309700489,1.63729357719,2.46869754791 -3.32697987556,1.63729906082,2.47348761559 -3.32499837875,1.63930881023,2.4870762825 -3.32501721382,1.64331829548,2.50265240669 -3.30403876305,1.63633143902,2.50224661827 -3.30705690384,1.64234042168,2.51982927322 -3.30107712746,1.64235138893,2.53139638901 -3.28609848022,1.63836371899,2.53597164154 -3.28610801697,1.64136850834,2.54376196861 -3.28312730789,1.64337873459,2.55733656883 -3.27014803886,1.64039075375,2.56292295456 -3.26216816902,1.64040184021,2.57250356674 -3.25018906593,1.63841354847,2.57908248901 -3.24920892715,1.64242374897,2.59464693069 -3.24322795868,1.64243412018,2.60524225235 -3.25523614883,1.65143680573,2.62301969528 -3.2362575531,1.64544987679,2.62361192703 -3.22227859497,1.64246189594,2.62820005417 -3.22829723358,1.65047085285,2.64975905418 -3.21231818199,1.64548313618,2.6523566246 -3.20133924484,1.64349496365,2.65992736816 -3.20435786247,1.65050411224,2.6785068512 -3.19036984444,1.64451158047,2.67529463768 -3.18438911438,1.64552199841,2.6858921051 -3.18740868568,1.65153157711,2.70545005798 -3.16943120956,1.6465446949,2.70702576637 -3.16445016861,1.64755499363,2.71862030029 -3.15447163582,1.64656686783,2.72718548775 -3.14448308945,1.64357364178,2.72697520256 -3.14650130272,1.64958262444,2.74456882477 -3.14252138138,1.65159332752,2.75813674927 -3.12454319,1.64660620689,2.75873041153 -3.11756372452,1.64661729336,2.76930904388 -3.11858272552,1.65262687206,2.78688716888 -3.10360431671,1.64863932133,2.79046797752 -3.09761595726,1.64764583111,2.79424071312 -3.09663486481,1.65165543556,2.80982804298 -3.09065532684,1.65366637707,2.82140636444 -3.07567644119,1.64967858791,2.82400846481 -3.07469654083,1.6536886692,2.84057450294 -3.06271719933,1.65170049667,2.84616827965 -3.04973936081,1.64971292019,2.85173892975 -3.06074690819,1.65771579742,2.87052369118 -3.04076981544,1.65172934532,2.86910843849 -3.03079175949,1.65074145794,2.87767243385 -3.02781057358,1.65375125408,2.89127206802 -3.0098335743,1.64876461029,2.89184856415 -3.01585149765,1.65777301788,2.91443729401 -3.00087499619,1.65378642082,2.91898441315 -2.98788666725,1.64879357815,2.91478729248 -2.98690629005,1.65380358696,2.93136453629 -2.9749276638,1.65181553364,2.93695354462 -2.96994900703,1.65382671356,2.95051288605 -2.96396827698,1.65583717823,2.96112108231 -2.95399022102,1.65484929085,2.96968483925 -2.9480009079,1.65385520458,2.97247862816 -2.93602347374,1.65286779404,2.97904276848 -2.9390411377,1.65987634659,2.99865102768 -2.92506289482,1.65688872337,3.00223851204 -2.92308354378,1.66189920902,3.01880407333 -2.90910553932,1.6579117775,3.02239012718 -2.90311717987,1.65791833401,3.02616047859 -2.89113903046,1.65593039989,3.03174614906 -2.88715982437,1.65894114971,3.04631400108 -2.87218117714,1.65495347977,3.04791879654 -2.87020158768,1.65996384621,3.0644903183 -2.86422276497,1.66197514534,3.07705926895 -2.84424567223,1.65498864651,3.07365584373 -2.84825515747,1.66099298,3.08743882179 -2.84627532959,1.66600334644,3.10401535034 -2.82829785347,1.66001629829,3.10261201859 -2.82331967354,1.66302788258,3.1171631813 -2.81833958626,1.66603839397,3.12975978851 -2.80336260796,1.66205120087,3.13233709335 -2.79638409615,1.66406273842,3.14390873909 -2.79139471054,1.66406857967,3.1477022171 -2.78341555595,1.66507971287,3.15729379654 -2.77043795586,1.66209220886,3.16187310219 -2.76745915413,1.66710317135,3.17843580246 -2.75248026848,1.66311526299,3.17905187607 -2.74850177765,1.66712629795,3.19461369514 -2.73652410507,1.66613864899,3.20019483566 -2.73153471947,1.66614449024,3.20398855209 -2.72655558586,1.66915547848,3.21757078171 -2.71557831764,1.66816794872,3.22513413429 -2.70160150528,1.66618084908,3.22870731354 -2.69262170792,1.66619181633,3.23631858826 -2.69164276123,1.67220234871,3.25587821007 -2.67965531349,1.66720974445,3.25166535378 -2.67367529869,1.67022037506,3.26326918602 -2.66669750214,1.67223227024,3.27582836151 -2.65772008896,1.6732442379,3.28540062904 -2.65174078941,1.67525517941,3.29798674583 -2.64076185226,1.67426681519,3.30359125137 -2.62878537178,1.67327964306,3.3101503849 -2.62279677391,1.67328584194,3.31293964386 -2.61281847954,1.67329764366,3.32052826881 -2.60184049606,1.67230963707,3.32711172104 -2.59386229515,1.67332136631,3.33769035339 -2.58788394928,1.6773327589,3.35126137733 -2.57990574837,1.67834436893,3.36184215546 -2.56592941284,1.6763573885,3.36540913582 -2.56893801689,1.68136155605,3.37921047211 -2.55895972252,1.68137335777,3.38680124283 -2.54398322105,1.6783863306,3.38838148117 -2.54500293732,1.68639612198,3.41096162796 -2.52302837372,1.6784106493,3.40353560448 -2.52004909515,1.6844214201,3.42111349106 -2.51305985451,1.68242740631,3.42191505432 -2.50108385086,1.6814404726,3.42847371101 -2.50010347366,1.68845033646,3.44806885719 -2.50012350082,1.69646024704,3.46965527534 -2.51414060593,1.71446764469,3.51123118401 -3.19107794762,2.25737833977,4.57535457611 -3.13211131096,2.22440028191,4.52092838287 -3.11413526535,2.22141385078,4.52450704575 -3.11515450478,2.23242354393,4.55509376526 -2.39456224442,1.7906883955,3.80003476143 -2.3625895977,1.77370476723,3.77462291718 -2.36959815025,1.78470826149,3.79841375351 -2.34462475777,1.7737237215,3.78498196602 -2.33664679527,1.776735425,3.7975666523 -2.32866859436,1.77974689007,3.81015253067 -2.30069518089,1.7657623291,3.7897465229 -2.30471515656,1.77977204323,3.82331061363 -2.30072665215,1.78077805042,3.83009672165 -2.25975584984,1.75679588318,3.7876906395 -2.24877953529,1.75780856609,3.79625940323 -2.23880243301,1.75882077217,3.80583906174 -2.21982741356,1.7528346777,3.80041599274 -2.20085191727,1.7468483448,3.7940056324 -2.20487165451,1.75985777378,3.82758450508 -2.18488621712,1.74786686897,3.80637764931 -2.17790818214,1.75187826157,3.82096004486 -2.16793107986,1.75389051437,3.83054041862 -2.15295529366,1.75090348721,3.83112478256 -2.14297795296,1.75191557407,3.84070563316 -2.14199852943,1.76192605495,3.86628866196 -2.11202597618,1.74594199657,3.83987307549 -2.10803747177,1.74694788456,3.8466603756 -2.10106015205,1.7519595623,3.8622341156 -2.07808589935,1.74197423458,3.84781956673 -1.80764830112,1.7632727623,4.02875423431 -1.79067289829,1.75828611851,4.02334356308 -1.77469658852,1.75429904461,4.01894617081 -1.75972187519,1.75131249428,4.01951313019 -1.73874855042,1.74332714081,4.00608253479 -1.73175954819,1.74133312702,4.00489711761 -1.72778189182,1.75134444237,4.03046512604 -1.70680761337,1.7413585186,4.01505374908 -1.69983065128,1.74737036228,4.03362560272 -1.6798555851,1.73938417435,4.01922607422 -1.6728785038,1.74539577961,4.03780031204 -1.65290486813,1.73741018772,4.02537250519 -1.65191531181,1.74341547489,4.0401673317 -1.63494098186,1.73842918873,4.034740448 -1.63296222687,1.75043976307,4.06532335281 -1.61398768425,1.74345362186,4.05390787125 -1.60201072693,1.74346578121,4.05850696564 -1.5870360136,1.74047923088,4.05807685852 -1.5770585537,1.74349093437,4.06767749786 -1.57007193565,1.74349808693,4.07044267654 -1.55109751225,1.73551189899,4.05802869797 -1.54012060165,1.73652398586,4.06562280655 -1.52914476395,1.73953664303,4.0751953125 -1.51616859436,1.73854911327,4.07778739929 -1.50619196892,1.7415612936,4.08936834335 -1.49720573425,1.73956871033,4.08614015579 -1.4832290411,1.73658108711,4.08474493027 -1.47025406361,1.73659420013,4.08931446075 -1.45627748966,1.73460650444,4.08791732788 -1.44730174541,1.73961913586,4.10447883606 -1.43132710457,1.7356325388,4.10005378723 -1.41835105419,1.73564505577,4.10264396667 -1.41436254978,1.73865103722,4.1114358902 -1.40038716793,1.73666393757,4.11201715469 -1.38841080666,1.73767626286,4.11760616302 -1.37343633175,1.73568975925,4.11617708206 -1.35846078396,1.73270273209,4.11276626587 -1.34748375416,1.73371469975,4.12036514282 -1.33350944519,1.73272812366,4.12292432785 -1.32752096653,1.73273408413,4.12472867966 -1.31554508209,1.73474669456,4.13130903244 -1.30456900597,1.73675918579,4.14089107513 -1.29359233379,1.73977124691,4.14948368073 -1.27561914921,1.73278546333,4.13904476166 -1.26264286041,1.73279774189,4.1406416893 -1.25665509701,1.73280417919,4.14442825317 -1.24267923832,1.73081684113,4.14302206039 -1.23070430756,1.73282980919,4.15158605576 -1.21572935581,1.72984290123,4.14816761017 -1.21375072002,1.74685359001,4.18875265121 --1.36142921448,1.76924347878,3.97086977959 --1.36840593815,1.7612541914,3.9484436512 --1.38738024235,1.77026641369,3.9630382061 --1.39136922359,1.76827144623,3.95483994484 --1.40334522724,1.76728272438,3.94842743874 --1.41931951046,1.77129483223,3.95200181007 --1.4282964468,1.76630556583,3.93759346008 --1.44327139854,1.76931726933,3.9391772747 --1.45624732971,1.77032852173,3.93576788902 --1.46323466301,1.77133440971,3.93455386162 --1.47521173954,1.77134513855,3.93016290665 --1.48818778992,1.77235639095,3.9267539978 --1.49916434288,1.77036726475,3.9183485508 --1.51513898373,1.77437901497,3.92193055153 --1.53011441231,1.77739048004,3.92352104187 --1.54208993912,1.7764018774,3.91609835625 --1.5470790863,1.77640688419,3.91190981865 --1.56505346298,1.78241884708,3.92049598694 --1.57303023338,1.77642953396,3.90307402611 --1.58300626278,1.77344059944,3.89065003395 --1.60298037529,1.78245282173,3.90424084663 --1.61395657063,1.78146374226,3.89482355118 --1.62493443489,1.78047406673,3.88844037056 --1.63592123985,1.78548026085,3.89723420143 --1.64689660072,1.78349149227,3.88680458069 --1.65487360954,1.77850198746,3.87038731575 --1.67584860325,1.78951382637,3.88699817657 --1.67882728577,1.77852344513,3.85958719254 --1.69680070877,1.78453576565,3.86515235901 --1.71078705788,1.79354226589,3.88095521927 --1.71376609802,1.78355169296,3.85455155373 --1.72374200821,1.78056287766,3.8421216011 --1.74171698093,1.78657436371,3.8497171402 --1.75369393826,1.78658497334,3.84431910515 --1.76567029953,1.78659582138,3.83790826797 --1.78464388847,1.79360806942,3.84548163414 --1.77863526344,1.78061187267,3.81627726555 --1.79861009121,1.78962349892,3.82787537575 --1.81258559227,1.79063475132,3.82546162605 --1.82056212425,1.78564548492,3.80903196335 --1.83953690529,1.79365718365,3.81762480736 --2.14196920395,1.80791473389,3.68676257133 --2.16294503212,1.81692588329,3.69737887383 --2.1719224453,1.81493592262,3.6849629879 --2.17191195488,1.80894064903,3.67075037956 --2.18388795853,1.80895137787,3.66333031654 --2.19886445999,1.81196200848,3.66192483902 --2.21284151077,1.81497228146,3.65953111649 --2.22081756592,1.81098294258,3.64409136772 --2.23579478264,1.81399321556,3.64370393753 --2.24677109718,1.81300365925,3.63427972794 --2.25476002693,1.81600880623,3.63508963585 --2.26273775101,1.81201863289,3.62167906761 --2.27971196175,1.81603014469,3.62124347687 --2.29268932343,1.81804025173,3.61684775352 --2.30966544151,1.8230509758,3.61844682693 --2.31564378738,1.81806051731,3.60203814507 --2.33061933517,1.82107162476,3.59860920906 --2.34260678291,1.82607710361,3.60541915894 --2.35458350182,1.82608747482,3.59800362587 --2.37655830383,1.83509874344,3.60659742355 --2.38453602791,1.83210861683,3.59318590164 --2.40451145172,1.83911955357,3.59878587723 --2.45447969437,1.87013399601,3.64938426018 --2.72491693497,1.86038076878,3.41712784767 --2.71890854836,1.85238444805,3.39792156219 --2.72788667679,1.85139381886,3.38651180267 --2.73886394501,1.85140371323,3.37709212303 --2.74384307861,1.84741282463,3.36068153381 --2.7618188858,1.85142326355,3.36026716232 --2.76679801941,1.84743237495,3.34385514259 --2.77877569199,1.84844195843,3.33644914627 --2.78476500511,1.84944665432,3.33325576782 --2.80873942375,1.85845756531,3.33984041214 --2.81671833992,1.85646677017,3.32743382454 --2.82769560814,1.85647654533,3.31801557541 --2.83567523956,1.8554854393,3.30662679672 --2.85565090179,1.86149585247,3.30821537971 --2.85464024544,1.85650038719,3.29499077797 --2.86561894417,1.85750973225,3.28659152985 --2.8755967617,1.85651910305,3.27617669106 --2.88357543945,1.85552835464,3.26376748085 --2.9045522213,1.86253833771,3.26737856865 --2.91652941704,1.86354804039,3.25895905495 --2.91950893402,1.85855674744,3.24054384232 --2.92949700356,1.86156189442,3.24134302139 --2.94947361946,1.86857199669,3.24294400215 --2.95645260811,1.8655809164,3.22953772545 --2.95343327522,1.85658919811,3.20411205292 --2.97140955925,1.86159932613,3.20270037651 --2.98338723183,1.86260890961,3.1942820549 --2.99336624146,1.8626178503,3.18488764763 --3.00835299492,1.86862337589,3.19068360329 --3.024330616,1.87363302708,3.18728113174 --3.02231144905,1.86464118958,3.16386556625 --3.04528713226,1.87365162373,3.16745495796 --3.05326581001,1.87166047096,3.15504479408 --3.06724286079,1.87367022038,3.14862823486 --3.06223487854,1.86767375469,3.13343143463 --3.07221317291,1.86768293381,3.12301778793 --3.09818840027,1.87769329548,3.12961387634 --3.0981695652,1.87170135975,3.10920763016 --3.1111471653,1.87371087074,3.1017935276 --3.12112569809,1.87372004986,3.091381073 --3.14410114288,1.88173007965,3.09396696091 --3.14109325409,1.87673354149,3.08178257942 --3.15407013893,1.87774336338,3.07335066795 --3.17904639244,1.88775312901,3.07896232605 --3.17202854156,1.87776076794,3.05154776573 --3.18700623512,1.88077020645,3.04613852501 --3.20898246765,1.8877799511,3.04773426056 --3.20696353912,1.88078808784,3.02531671524 --3.21895051003,1.88479340076,3.02609586716 --3.23892855644,1.89080250263,3.02671599388 --3.23291015625,1.88181042671,3.00029087067 --3.24788808823,1.88481962681,2.99488639832 --3.26786541939,1.89082896709,2.99448943138 --3.26684594154,1.88483726978,2.97306537628 --3.27382612228,1.88284552097,2.96067261696 --3.29481267929,1.89285099506,2.97047185898 --3.29679250717,1.88785946369,2.95205020905 --3.31176996231,1.89086890221,2.94562935829 --3.32774829865,1.8948777914,2.94123339653 --3.32372975349,1.8868855238,2.91781783104 --3.32771062851,1.88389372826,2.90241718292 --3.33969831467,1.88789868355,2.90320706367 --3.3496773243,1.88890743256,2.89279866219 --3.36465620995,1.89191615582,2.88740324974 --3.38163280487,1.89592576027,2.88197159767 --3.38061499596,1.89093327522,2.86257719994 --3.38859415054,1.88994181156,2.8501636982 --3.41357064247,1.89895153046,2.85275864601 --3.40956163406,1.89395523071,2.83954930305 --3.41854095459,1.89396381378,2.82813930511 --3.43951797485,1.89997303486,2.82672643661 --3.4384996891,1.89498066902,2.80732655525 --3.44048047066,1.89098882675,2.78991317749 --3.47045636177,1.90299844742,2.7965157032 --3.46643733978,1.89500653744,2.77307868004 --3.47142791748,1.89501023293,2.76889824867 --3.4934053421,1.90301942825,2.76849746704 --3.48738694191,1.89402723312,2.74407029152 --3.49736666679,1.89503550529,2.73366475105 --3.51734423637,1.90104448795,2.73125982285 --3.51832485199,1.89605259895,2.7128367424 --3.53230452538,1.90006065369,2.7064511776 --3.54129362106,1.9020652771,2.70424604416 --3.54327392578,1.89807319641,2.6868262291 --3.55225372314,1.89808154106,2.67541718483 --3.56923174858,1.90309035778,2.67000436783 --3.57021331787,1.89909803867,2.65259957314 --3.57819318771,1.89810621738,2.64018559456 --3.60218000412,1.90911126137,2.64999723434 --3.60116147995,1.90411901474,2.63058018684 --3.6151406765,1.90712726116,2.62317872047 --3.62212061882,1.90613543987,2.60976004601 --3.62710142136,1.90414345264,2.59535241127 --3.64507985115,1.90915179253,2.59095430374 --3.64806056023,1.90615975857,2.57453370094 --3.6480512619,1.90416371822,2.56532502174 --3.66603016853,1.9091719389,2.56092977524 --3.67501020432,1.90917992592,2.54952406883 --3.6739923954,1.90418732166,2.53112101555 --3.6949698925,1.91119611263,2.5277030468 --3.7039501667,1.91220414639,2.51629781723 --3.71392965317,1.91321229935,2.50487661362 --3.7109208107,1.9082159996,2.49366760254 --3.72590112686,1.91322386265,2.48728203773 --3.74087905884,1.9162324667,2.47885131836 --3.74286079407,1.91324007511,2.46244215965 --3.7458422184,1.91024756432,2.44703936577 --3.75182318687,1.90825521946,2.43363547325 --3.77280163765,1.91626358032,2.43023014069 --3.77379226685,1.91426742077,2.42202425003 --3.78677153587,1.91727566719,2.41260528564 --3.78975296021,1.91428303719,2.39720129967 --3.81173110008,1.92229151726,2.39378666878 --3.80671405792,1.91529846191,2.37338662148 --3.81169509888,1.91330611706,2.35897374153 --3.83067393303,1.91931438446,2.35356140137 --3.83766365051,1.92131829262,2.34935832024 --3.85264372826,1.92532610893,2.34196233749 --3.85262584686,1.9213334322,2.32455348969 --3.84860801697,1.91434085369,2.30413079262 --3.86158871651,1.91734826565,2.29574155807 --3.87756824493,1.9223562479,2.28833293915 --3.88255786896,1.92236030102,2.28211331367 --3.89453864098,1.92536783218,2.27271747589 --3.89951968193,1.92337524891,2.25830411911 --3.90650129318,1.92338252068,2.24590969086 --3.91248178482,1.92239034176,2.23148059845 --3.92446255684,1.92539775372,2.22208714485 --3.93544244766,1.92640554905,2.21065974236 --3.93143463135,1.9224088192,2.20047211647 --3.94341492653,1.92541658878,2.19005537033 --3.94739675522,1.92342364788,2.17565441132 --3.95737743378,1.92543125153,2.16424226761 --3.96335911751,1.92443847656,2.150837183 --3.97333979607,1.926445961,2.13942551613 --3.98332047462,1.9274533987,2.12801504135 --3.99031090736,1.92945694923,2.1238193512 --3.99229359627,1.9264639616,2.10842013359 --4.01227235794,1.9334717989,2.10199809074 --4.02425289154,1.93547928333,2.09158802032 --4.02523517609,1.93248641491,2.07517695427 --4.03521633148,1.93449366093,2.0637691021 --4.03819894791,1.93250048161,2.04938030243 --4.04718828201,1.93550443649,2.04516124725 --4.0521697998,1.93451166153,2.03074526787 --4.0651512146,1.93751871586,2.02135014534 --4.07713222504,1.93952596188,2.01094412804 --4.08311414719,1.93953299522,1.99754106998 --4.08509588242,1.93754029274,1.98111355305 --4.08907794952,1.93554723263,1.96670997143 --4.10006809235,1.9395506382,1.96452009678 --4.10505008698,1.93955779076,1.95010411739 --4.1100320816,1.93856489658,1.93568778038 --4.12501192093,1.94257211685,1.92627370358 --4.13399457932,1.94357895851,1.91488432884 --4.13797569275,1.94258606434,1.89945554733 --4.14195966721,1.94159245491,1.88607704639 --4.151948452,1.9445964098,1.88185417652 --4.15493202209,1.94360303879,1.86746203899 --4.16191244125,1.94361042976,1.85302197933 --4.16789484024,1.94361722469,1.83961904049 --4.17187738419,1.94262397289,1.82521438599 --4.19185829163,1.94863069057,1.818826437 --4.18785047531,1.94563412666,1.80861771107 --4.1938328743,1.94564080238,1.79521536827 --4.19981431961,1.94564795494,1.78078734875 --4.21479558945,1.94965457916,1.77138507366 --4.21877861023,1.94866132736,1.75698041916 --4.22276115417,1.94866800308,1.74257552624 --4.22874355316,1.94867455959,1.72917366028 --4.23073387146,1.94767832756,1.72094535828 --4.24471616745,1.95168459415,1.71155846119 --4.23069953918,1.94169175625,1.68811810017 --4.25968027115,1.95269834995,1.68472397327 --4.24666500092,1.94370484352,1.66332101822 --4.26564598083,1.95071148872,1.6549090147 --4.27162885666,1.95071804523,1.64150798321 --4.2626209259,1.94472146034,1.62929165363 --4.27160310745,1.9467279911,1.61688411236 --4.2835855484,1.94973421097,1.60649812222 --4.28256845474,1.94674110413,1.58906495571 --4.30954933167,1.95674717426,1.58468329906 --4.31753158569,1.95775389671,1.57126367092 --4.3255147934,1.95976006985,1.55887043476 --4.32850551605,1.95976340771,1.55165791512 --4.32848882675,1.95676994324,1.53524053097 --4.3354716301,1.95777642727,1.52183151245 --4.3424539566,1.9587829113,1.50842273235 --4.34443759918,1.95678925514,1.49301040173 --4.34742116928,1.95679545403,1.47861385345 --4.35840320587,1.958802104,1.4661937952 --4.35739517212,1.95680510998,1.45799314976 --4.36537885666,1.95881128311,1.44560205936 --4.36936044693,1.9578179121,1.43016982079 --4.37734460831,1.95982384682,1.41777944565 --4.38032722473,1.95883047581,1.40235626698 --4.38531017303,1.9588367939,1.38794100285 --4.38130235672,1.95583999157,1.37873888016 --4.39228582382,1.95884585381,1.3673491478 --4.40126800537,1.96085214615,1.35392510891 --4.40225172043,1.95885848999,1.33851885796 --4.40523576736,1.95786440372,1.32412111759 --4.4102191925,1.95787072182,1.30970597267 --4.41420221329,1.95787680149,1.2952991724 --4.42319345474,1.96187984943,1.29008972645 --4.42817640305,1.96188604832,1.27567529678 --4.42916059494,1.95989215374,1.26026725769 --4.43314409256,1.95989823341,1.24586069584 --4.44712686539,1.96390414238,1.2344533205 --4.44911050797,1.96291029453,1.21903681755 --4.44809484482,1.96091628075,1.20364356041 --4.45908641815,1.96491885185,1.1994497776 --4.46306943893,1.96492528915,1.1840171814 --4.47105360031,1.96593081951,1.17163431644 --4.47903633118,1.96793699265,1.15719854832 --4.47602081299,1.96494305134,1.14079236984 --4.48500490189,1.96694874763,1.12840330601 --4.49798774719,1.97095441818,1.11598551273 --4.46098232269,1.95295870304,1.09777295589 --4.4579668045,1.94996488094,1.08136177063 --4.47994947433,1.95797014236,1.07195913792 --4.47093391418,1.95297658443,1.05353581905 --4.47691822052,1.95298218727,1.04014110565 --4.50190067291,1.96298742294,1.03072345257 --4.49488544464,1.9579937458,1.01331114769 --4.49687719345,1.95799660683,1.00610780716 --4.51086139679,1.96300172806,0.99471539259 --4.50084590912,1.95700824261,0.976293385029 --4.50982952118,1.9590139389,0.962880909443 --4.52181339264,1.96301925182,0.950477182865 --4.51079845428,1.95702564716,0.932057678699 --4.51778268814,1.95803117752,0.918659389019 --4.54677295685,1.97003281116,0.917451739311 --4.52875900269,1.96103942394,0.898045957088 --4.52674245834,1.95804560184,0.881621897221 --4.54072761536,1.96305036545,0.870237767696 --4.52571201324,1.95505714417,0.850807249546 --4.53669691086,1.95806229115,0.838414669037 --4.5536813736,1.965067029,0.827016294003 --4.53767299652,1.9570710659,0.814778864384 --4.54765844345,1.96007609367,0.802393972874 --4.56164216995,1.9650810957,0.789988279343 --4.55762672424,1.96208703518,0.773572027683 --4.55461168289,1.95909321308,0.757149219513 --4.58059597015,1.97009706497,0.747765958309 --4.55558156967,1.95710420609,0.727346837521 --4.56157302856,1.95910704136,0.720123529434 --4.57155847549,1.9621117115,0.707743287086 --4.56254339218,1.95711803436,0.690320074558 --4.57252788544,1.96012306213,0.676913201809 --4.58551168442,1.96512806416,0.663493394852 --4.57349729538,1.95813441277,0.646081566811 --4.5694899559,1.95613741875,0.637879133224 --4.59547472,1.96614122391,0.627484917641 --4.58045959473,1.95814800262,0.609055817127 --4.59644412994,1.96515238285,0.596654236317 --4.59943008423,1.96515750885,0.582255482674 --4.58941459656,1.9591640234,0.564828276634 --4.59539937973,1.96116912365,0.550416171551 --4.60839223862,1.96617078781,0.545225441456 --4.58937740326,1.95717763901,0.526803314686 --4.60436296463,1.96218192577,0.514412403107 --4.62434768677,1.9701859951,0.502004802227 --4.59733295441,1.95719349384,0.482579737902 --4.60731887817,1.96119809151,0.4691824615 --4.61630344391,1.96420300007,0.454762518406 --4.60429620743,1.95820653439,0.445554792881 --4.61328220367,1.96221101284,0.432162731886 --4.63026666641,1.96821522713,0.41874602437 --4.61925268173,1.96222126484,0.402338325977 --4.62123775482,1.96222662926,0.38691547513 --4.62822294235,1.96523141861,0.372505158186 --4.6262087822,1.96323692799,0.357094705105 --4.63120174408,1.96523880959,0.350913465023 --4.63118743896,1.96424424648,0.335496932268 --4.62717342377,1.96224975586,0.320090740919 --4.6391582489,1.96625423431,0.305669605732 --4.63714361191,1.965259552,0.290257751942 --4.64013004303,1.9662643671,0.275860905647 --4.64011573792,1.96526968479,0.260443776846 --4.64110851288,1.96527206898,0.253246694803 --4.6490945816,1.9682765007,0.238839149475 --4.64407920837,1.96528244019,0.222405001521 --4.64506626129,1.96528720856,0.208013027906 --4.65205192566,1.96729171276,0.193609401584 --4.64003753662,1.96229791641,0.177186354995 --4.65003013611,1.96629977226,0.169972658157 --4.64901685715,1.96530461311,0.155584320426 --4.65200233459,1.96630966663,0.140161022544 --4.65998888016,1.96931385994,0.125758200884 --4.649974823,1.96431970596,0.110355392098 --4.65296077728,1.96532452106,0.0949324443936 --4.64994621277,1.96332991123,0.0795178040862 --4.65993309021,1.96733391285,0.0651145428419 --4.64592599869,1.96133780479,0.0569077022374 --4.65391206741,1.96434187889,0.042507391423 --4.64389705658,1.95934820175,0.0260703470558 --4.6498837471,1.96235227585,0.0116726215929 --4.65587091446,1.96435654163,-0.0027239031624 --4.64885663986,1.96136212349,-0.0181381590664 --4.64284276962,1.95736765862,-0.0335540100932 --4.64983606339,1.96136939526,-0.0407547801733 --4.65982246399,1.96537327766,-0.056179843843 --4.64780807495,1.95937955379,-0.0715939700603 --4.65479516983,1.96238338947,-0.0859886929393 --4.64778137207,1.95938920975,-0.101406924427 --4.64876747131,1.95939397812,-0.116827532649 --4.65376138687,1.96239566803,-0.124024540186 --4.64474725723,1.95740151405,-0.139444217086 --4.64173412323,1.95640659332,-0.153837412596 --4.65072011948,1.96041035652,-0.169257253408 --4.64370727539,1.95741569996,-0.183651432395 --4.64569377899,1.95742022991,-0.199071630836 --4.64868021011,1.95942485332,-0.214491471648 --4.64667367935,1.95842730999,-0.221688687801 --4.64165973663,1.95643270016,-0.237112388015 --4.64164686203,1.95643723011,-0.251505583525 --4.64263343811,1.95744180679,-0.266926229 --4.63761997223,1.95444703102,-0.281323194504 --4.63560676575,1.95345199108,-0.296746522188 --4.64059352875,1.95645606518,-0.312163382769 --4.64258766174,1.95745790005,-0.319357872009 --4.63757324219,1.95546329021,-0.334784567356 --4.6305603981,1.95246863365,-0.349186390638 --4.6295466423,1.95247352123,-0.364609748125 --4.63853549957,1.95647656918,-0.378990888596 --4.62852096558,1.95248270035,-0.394426912069 --4.63950920105,1.9574855566,-0.409831285477 --4.63850259781,1.95748794079,-0.417029380798 --4.61948823929,1.94949519634,-0.431454718113 --4.626475811,1.95249867439,-0.446864336729 --4.63146305084,1.95450246334,-0.462276309729 --4.62144947052,1.95050823689,-0.476689130068 --4.62943744659,1.95451152325,-0.492094367743 --4.62442493439,1.95351660252,-0.506498277187 --4.62041807175,1.95151937008,-0.513703584671 --4.61940479279,1.95152401924,-0.52912735939 --4.62739276886,1.95552706718,-0.544529676437 --4.61937952042,1.95253252983,-0.558941960335 --4.60936594009,1.94853842258,-0.573360562325 --4.60035228729,1.94454431534,-0.587777972221 --4.6083407402,1.9495472908,-0.603178620338 --4.60833454132,1.94954931736,-0.610375225544 --4.60832166672,1.9495537281,-0.625796437263 --4.60730981827,1.94955790043,-0.640192389488 --4.60629701614,1.94956243038,-0.655616343021 --4.59728288651,1.94656813145,-0.670037508011 --4.60327148438,1.94957137108,-0.685439407825 --4.59425830841,1.94657707214,-0.699861943722 --4.60225296021,1.9505777359,-0.708059608936 --4.60124111176,1.95058190823,-0.722455263138 --4.59722757339,1.9495869875,-0.737889528275 --4.58521461487,1.94459307194,-0.75129711628 --4.58920288086,1.94759631157,-0.766703307629 --4.58919048309,1.94860053062,-0.782123625278 --4.59417915344,1.95160365105,-0.797524034977 --4.5881729126,1.94960665703,-0.803715527058 --4.59316110611,1.95260989666,-0.820142805576 --4.59014844894,1.95161437988,-0.834545850754 --4.58213567734,1.94961988926,-0.848970532417 --4.58412361145,1.95062351227,-0.864380776882 --4.58411216736,1.95162725449,-0.878771424294 --4.5731048584,1.94763123989,-0.884987592697 --4.57009267807,1.94663572311,-0.899392068386 --4.57608127594,1.95063865185,-0.915811300278 --4.57206916809,1.94964325428,-0.930220127106 --4.56705665588,1.94864809513,-0.944634199142 --4.57204532623,1.95165109634,-0.961055576801 --4.56903362274,1.95165538788,-0.975459873676 --4.56402635574,1.94965839386,-0.982679367065 --4.55801439285,1.9486631155,-0.996071755886 --4.56000328064,1.9496666193,-1.01147842407 --4.55899143219,1.95067059994,-1.02690052986 --4.55497932434,1.94967520237,-1.04131042957 --4.54996681213,1.94967985153,-1.05572652817 --4.53895378113,1.94468581676,-1.06914770603 --4.54794931412,1.94968593121,-1.07834768295 --4.53993701935,1.94769108295,-1.09175336361 --4.5319237709,1.9446965456,-1.10618746281 --4.52691221237,1.94470107555,-1.11957776546 --4.52790117264,1.94570446014,-1.13498783112 --4.52488851547,1.94570887089,-1.15042150021 --4.5198764801,1.94471359253,-1.16483974457 --4.51386976242,1.94271659851,-1.17104279995 --4.51185846329,1.94372045994,-1.18544340134 --4.51084709167,1.94472444057,-1.20086491108 --4.50783586502,1.94472849369,-1.21527123451 --4.50282335281,1.94373309612,-1.22969055176 --4.49681138992,1.94173789024,-1.24308896065 --4.50380134583,1.94674003124,-1.26051187515 --4.49379444122,1.94274377823,-1.26571679115 --4.48978281021,1.94274806976,-1.28013026714 --4.48877191544,1.94375169277,-1.29452323914 --4.47975969315,1.94075715542,-1.30794394016 --4.47974872589,1.94276046753,-1.32335734367 --4.46973514557,1.93976616859,-1.33678662777 --4.46372365952,1.93877089024,-1.35018825531 --4.48372220993,1.94876825809,-1.36339974403 --4.45670557022,1.93777763844,-1.37181758881 --4.45169353485,1.93678224087,-1.38624000549 --4.47068786621,1.94778096676,-1.40561842918 --4.44767189026,1.9387897253,-1.41606736183 --4.44566106796,1.93979334831,-1.43046677113 --4.45265245438,1.94479513168,-1.44787752628 --4.44064474106,1.93979930878,-1.45208108425 --4.41662788391,1.93080842495,-1.46151852608 --4.43562221527,1.94080710411,-1.48191380501 --4.40360450745,1.92781794071,-1.48833787441 --4.4135966301,1.93481874466,-1.50674915314 --4.41558694839,1.93682134151,-1.52214217186 --4.39857196808,1.93182885647,-1.53358542919 --4.4025683403,1.93382930756,-1.54176998138 --4.40655946732,1.93783128262,-1.55817234516 --4.38154268265,1.92784070969,-1.56660532951 --4.37353086472,1.92684590816,-1.58003056049 --4.38852453232,1.93584501743,-1.59941673279 --4.36150789261,1.92485487461,-1.60684669018 --4.36350297928,1.92685592175,-1.61504709721 --4.37249517441,1.93285667896,-1.63345575333 --4.34747886658,1.92386627197,-1.64190101624 --4.34646844864,1.92486929893,-1.6562911272 --4.35646104813,1.93186986446,-1.67571425438 --4.32744407654,1.91988015175,-1.68112146854 --4.32443284988,1.92088413239,-1.69655787945 --4.33043003082,1.92488384247,-1.70574498177 --4.31541633606,1.91989076138,-1.71616029739 --4.30240249634,1.91589725018,-1.72758507729 --4.31839704514,1.92589581013,-1.74899768829 --4.29638195038,1.91790449619,-1.75640392303 --4.29337120056,1.91890823841,-1.77081298828 --4.30036354065,1.92390918732,-1.78922867775 --4.2703499794,1.91091883183,-1.78645098209 --4.27434110641,1.91492056847,-1.8038700819 --4.28333520889,1.92192077637,-1.82226336002 --4.27032136917,1.91792714596,-1.83369374275 --4.25430727005,1.91293430328,-1.84310340881 --4.26530170441,1.91993391514,-1.86249864101 --4.24128437042,1.91094350815,-1.86994147301 --4.23927497864,1.91294670105,-1.88433969021 --4.24827289581,1.91894567013,-1.89656484127 --4.22625684738,1.90995442867,-1.90296387672 --4.22324705124,1.91095793247,-1.91737234592 --4.22323799133,1.91396069527,-1.93380093575 --4.20222187042,1.90596938133,-1.94122159481 --4.19521093369,1.90597403049,-1.95362198353 --4.20921087265,1.91397130489,-1.96783852577 --4.19419670105,1.9089782238,-1.97724831104 --4.181183815,1.90598464012,-1.98766410351 --4.18317556381,1.90898644924,-2.00406765938 --4.16916227341,1.90499317646,-2.01449632645 --4.16715192795,1.90599644184,-2.02991890907 --4.15313863754,1.90200304985,-2.03932332993 --4.15313434601,1.9040043354,-2.04753613472 --4.14412212372,1.90200960636,-2.05996203423 --4.1501159668,1.90801012516,-2.07836747169 --4.13810300827,1.90501618385,-2.08877682686 --4.1200876236,1.89902436733,-2.09720778465 --4.12608146667,1.90502464771,-2.1156103611 --4.11206817627,1.90103149414,-2.125020504 --4.10906267166,1.90103363991,-2.1322426796 --4.11205530167,1.90503489971,-2.1496527195 --4.10604524612,1.90503895283,-2.16204333305 --4.08502864838,1.89704823494,-2.16949224472 --4.08902168274,1.90204906464,-2.18688797951 --4.08101081848,1.90205383301,-2.19930529594 --4.06799697876,1.89806044102,-2.20973443985 --4.07299518585,1.90205979347,-2.21993136406 --4.05598068237,1.89706754684,-2.22733592987 --4.04796934128,1.8960723877,-2.23975467682 --4.06296682358,1.90606951714,-2.26418161392 --4.03694868088,1.89708042145,-2.26760482788 --4.03894233704,1.90108168125,-2.28399372101 --4.03293180466,1.90108585358,-2.2974114418 --4.01492023468,1.89309298992,-2.29662847519 --4.01291179657,1.89609575272,-2.31204533577 --4.01490449905,1.90009701252,-2.32945752144 --3.99388837814,1.89310634136,-2.33487534523 --3.9888780117,1.89311015606,-2.34930634499 --3.99687385559,1.9011092186,-2.3697104454 --3.97585725784,1.89311850071,-2.37513232231 --3.96885085106,1.89212191105,-2.37933397293 --3.97384524345,1.89712202549,-2.39875102043 --3.96683502197,1.89712631702,-2.41115784645 --3.94681882858,1.89113557339,-2.41759753227 --3.94481039047,1.89313805103,-2.4330098629 --3.93880057335,1.89314186573,-2.44540286064 --3.92178583145,1.88914990425,-2.45282936096 --3.9357881546,1.89714562893,-2.46903181076 --3.91477155685,1.89015519619,-2.47446680069 --3.91576457024,1.8941565752,-2.49188375473 --3.90375232697,1.89216268063,-2.50128984451 --3.88573694229,1.88617122173,-2.50771093369 --3.88372898102,1.88917338848,-2.52312088013 --3.88572263718,1.89317440987,-2.54154443741 --3.87271356583,1.8891800642,-2.54174184799 --3.87170600891,1.89218199253,-2.55815982819 --3.87269973755,1.89618325233,-2.57557082176 --3.84868144989,1.88719403744,-2.57798957825 --3.84067058563,1.8871986866,-2.59041428566 --3.84266495705,1.89219927788,-2.60883331299 --3.82364869118,1.8852083683,-2.61425447464 --3.82564687729,1.88920819759,-2.62344813347 --3.82263875008,1.89121091366,-2.63886857033 --3.81562876701,1.89121496677,-2.65127682686 --3.80661773682,1.89021992683,-2.66269230843 --3.81961798668,1.90121591091,-2.68810200691 --3.80660486221,1.89822256565,-2.69753074646 --3.79559636116,1.89422774315,-2.69873166084 --3.8005926609,1.90122675896,-2.71914172173 --3.7865793705,1.89723372459,-2.72756361961 --3.77856874466,1.89723825455,-2.73998689651 --3.77856302261,1.90223932266,-2.75740122795 --3.75954675674,1.89624857903,-2.76283431053 --3.75253772736,1.89625251293,-2.77421736717 --3.75853776932,1.90225040913,-2.78743338585 --3.73551917076,1.89326131344,-2.78986334801 --3.73551344872,1.89726233482,-2.80727434158 --3.73050498962,1.89926552773,-2.8216958046 --3.71048855782,1.89327514172,-2.82510495186 --3.68546843529,1.8842869997,-2.8265542984 --3.68046021461,1.88529014587,-2.83995294571 --3.65244102478,1.87230300903,-2.83019351959 --3.68845677376,1.89628791809,-2.87155914307 --1.10680353642,0.512512266636,-1.13116145134 --3.15788340569,1.87156534195,-3.44215869904 --3.14987492561,1.87256908417,-3.45560216904 --3.12985610962,1.86658036709,-3.45500922203 --3.13285779953,1.87157809734,-3.46821713448 --3.11283874512,1.86458921432,-3.46864700317 --3.12084460258,1.87658333778,-3.49705719948 --3.09782290459,1.86759650707,-3.49347114563 --3.09481906891,1.87259721756,-3.51190829277 --3.07079648972,1.8636111021,-3.50732827187 --3.07079529762,1.87060987949,-3.52876019478 --3.07079482079,1.87360930443,-3.53896474838 --3.06779122353,1.87760984898,-3.55535650253 --2.80253243446,1.8657476902,-3.76223564148 --2.78451442719,1.86075842381,-3.7636783123 --2.76949858665,1.85476827621,-3.75690174103 --2.76449465752,1.85876965523,-3.77230215073 --2.76850056648,1.86876404285,-3.80072951317 --2.73846888542,1.85478401184,-3.78514504433 --2.73146295547,1.85878658295,-3.80059146881 --2.71945118904,1.85779297352,-3.80800819397 --2.70443606377,1.85480177402,-3.81142401695 --2.69742918015,1.85380589962,-3.81362938881 --2.69342660904,1.85880625248,-3.83103775978 --2.67841124535,1.85481500626,-3.83445453644 --2.66840195656,1.85581994057,-3.84487867355 --2.6533870697,1.8538287878,-3.84931635857 --2.6483836174,1.85782968998,-3.86572670937 --2.63937425613,1.85483527184,-3.86594605446 --2.62836384773,1.85484099388,-3.87435817719 --2.61735343933,1.85484671593,-3.88277053833 --2.6043407917,1.85485386848,-3.89021515846 --2.59333062172,1.85485959053,-3.89862775803 --2.57531142235,1.84987092018,-3.89805531502 --2.57231092453,1.85487008095,-3.91746306419 --2.55228924751,1.84888327122,-3.91389012337 --2.55929994583,1.85887563229,-3.9361000061 --2.54728865623,1.85788214207,-3.94351935387 --2.52426290512,1.84889793396,-3.93493747711 --2.51825904846,1.85289931297,-3.95136404037 --2.50724887848,1.85390484333,-3.96079444885 --2.49023079872,1.84891581535,-3.96020483971 --2.48422503471,1.848919034,-3.96442461014 --2.48122525215,1.85491764545,-3.98483967781 --2.45519542694,1.84393632412,-3.9722776413 --2.45219612122,1.85093522072,-3.99167490005 --2.44719409943,1.85593521595,-4.01111984253 --2.42516899109,1.84795057774,-4.00354623795 --2.4051463604,1.84096443653,-3.99795794487 --2.40815329552,1.84795951843,-4.01618003845 --2.3911345005,1.84297072887,-4.01458311081 --2.37611913681,1.84097993374,-4.01801919937 --2.37111759186,1.84598004818,-4.03644323349 --2.35409903526,1.84199118614,-4.03586626053 --2.33908295631,1.83900046349,-4.03828811646 --2.33408212662,1.84500038624,-4.05772542953 --2.32006454468,1.83801150322,-4.0469121933 --2.32107210159,1.84800577164,-4.07533550262 --2.30505490303,1.84501600266,-4.07676839828 --2.2880358696,1.84002745152,-4.07518100739 --2.27602434158,1.84003400803,-4.08260679245 --2.27302646637,1.84703195095,-4.10401582718 --2.25600790977,1.84304308891,-4.10446214676 --2.2479994297,1.84204828739,-4.10467338562 --2.24099588394,1.84605002403,-4.12009096146 --2.21095609665,1.83007442951,-4.09752893448 --2.21096348763,1.84006917477,-4.12393045425 --2.19895243645,1.84007573128,-4.13135671616 --2.17992949486,1.83308959007,-4.12577104568 --2.17693305016,1.84208679199,-4.14920091629 --2.19196152687,1.86006855965,-4.18940353394 -2.04477214813,1.78496074677,-3.41536045074 -2.06279397011,1.78996765614,-3.42075586319 -2.0667924881,1.78296530247,-3.40017819405 -2.07279419899,1.77796459198,-3.38457918167 -2.07779860497,1.77696549892,-3.37978696823 -2.08279848099,1.77096390724,-3.36022639275 -2.09581279755,1.7729678154,-3.3576130867 -2.11082983017,1.77597296238,-3.35800433159 -2.12584638596,1.777977705,-3.35642552376 -2.13285040855,1.7739777565,-3.34184360504 -2.14285969734,1.77297985554,-3.33423018456 -2.15287208557,1.77698373795,-3.33744096756 -2.16388201714,1.7759860754,-3.32886886597 -2.17288970947,1.77398765087,-3.31926202774 -2.18590331078,1.77499127388,-3.3146777153 -2.20192170143,1.77899682522,-3.31607222557 -2.21493554115,1.78100061417,-3.31246972084 -2.22093820572,1.77600038052,-3.296885252 -2.22894716263,1.77700304985,-3.2961063385 -2.23995780945,1.77700579166,-3.28950214386 -2.25797915459,1.78301227093,-3.29389333725 -2.27199435234,1.78601646423,-3.29129695892 -2.28400611877,1.78601956367,-3.28471660614 -2.29401540756,1.78502178192,-3.2761194706 -2.31103467941,1.79002761841,-3.27851247787 -2.31503772736,1.78802812099,-3.27271461487 -2.32805109024,1.789031744,-3.26714134216 -2.33605742455,1.78603291512,-3.25554585457 -2.35207509995,1.79003822803,-3.25594425201 -2.3580789566,1.78603851795,-3.24135160446 -2.36608576775,1.78303968906,-3.22877550125 -2.37309336662,1.78504192829,-3.22796607018 -2.39612007141,1.79405033588,-3.23737812042 -2.39811849594,1.78604888916,-3.21679472923 -2.40412282944,1.7820494175,-3.20220637321 -2.4191391468,1.78605401516,-3.20061087608 -2.43015003204,1.78605687618,-3.19302272797 -2.43615412712,1.78105735779,-3.17843818665 -2.44616556168,1.78506088257,-3.18064689636 -2.45917916298,1.786064744,-3.1770362854 -2.4701898098,1.78606760502,-3.1694483757 -2.48620724678,1.79007267952,-3.16885447502 -2.49020934105,1.78507256508,-3.15127825737 -2.50422406197,1.78707683086,-3.14867186546 -2.52124261856,1.79208230972,-3.15006303787 -2.53525876999,1.799087286,-3.15825200081 -2.54727077484,1.79909062386,-3.15166711807 -2.54326319695,1.7880872488,-3.12310671806 -2.55627679825,1.79009115696,-3.11851000786 -2.56027936935,1.78509128094,-3.10192298889 -2.57429432869,1.78709554672,-3.09931325912 -2.58830904961,1.79009974003,-3.09572052956 -2.58630537987,1.78409826756,-3.08193778992 -2.6123342514,1.79510724545,-3.09432530403 -2.61233234406,1.78710591793,-3.07176184654 -2.62334370613,1.78710901737,-3.06417393684 -2.63335371017,1.78711175919,-3.05558109283 -2.65237379074,1.79311776161,-3.05798721313 -2.65637803078,1.79211878777,-3.05317687988 -2.66638803482,1.79212152958,-3.04458332062 -2.68841123581,1.80012869835,-3.05097723007 -2.70843243599,1.80713486671,-3.05437970161 -2.87760400772,1.80818295479,-2.92292952538 -2.8695962429,1.79918050766,-2.90316510201 -2.87560296059,1.79718232155,-2.89056611061 -2.88561344147,1.79718542099,-2.88197278976 -2.88461375237,1.7901853323,-2.86041021347 -2.90062999725,1.79419004917,-2.85880279541 -2.91564512253,1.79719460011,-2.85521388054 -2.92865777016,1.80219829082,-2.85941195488 -2.92966008186,1.79619896412,-2.84083414078 -2.94467520714,1.79920339584,-2.83724308014 -2.95368504524,1.79920625687,-2.82764863968 -2.96169376373,1.79820883274,-2.81705474854 -2.97170424461,1.79821193218,-2.80846118927 -2.98171520233,1.79821515083,-2.79888916016 -2.98672056198,1.79821681976,-2.79410290718 -3.00674009323,1.80422246456,-2.79648447037 -2.99873495102,1.79322111607,-2.76891994476 -3.0127491951,1.79622542858,-2.76432442665 -3.02676343918,1.79922962189,-2.75972795486 -3.02476382256,1.7912299633,-2.73914504051 -3.03677630424,1.79323375225,-2.73255038261 -3.06179881096,1.80624008179,-2.74872088432 -3.06580471992,1.80224204063,-2.73217654228 -1.1689658165,0.522164285183,-0.552456796169 -1.1359629631,0.503168523312,-0.523908853531 -3.33624720573,1.69740450382,-2.06522655487 -3.35826659203,1.70541012287,-2.06561803818 -3.36127543449,1.70341384411,-2.05204463005 -3.36227917671,1.70141541958,-2.04524993896 -3.3602848053,1.696418643,-2.02867102623 -3.36929678917,1.69742298126,-2.02007126808 -3.37230587006,1.69542682171,-2.00650167465 -3.37931704521,1.69543099403,-1.99592113495 -3.38932919502,1.69643521309,-1.98831164837 -3.39834165573,1.69743967056,-1.97873806953 -3.39734530449,1.69544160366,-1.96996557713 -3.40435600281,1.69544565678,-1.96035814285 -3.39535832405,1.68644833565,-1.93978011608 -3.40437102318,1.68745303154,-1.93020832539 -3.42338871956,1.69445824623,-1.92761158943 -3.41639184952,1.68646121025,-1.90901792049 -3.42240309715,1.68646562099,-1.89745032787 -3.43641424179,1.69146859646,-1.89865648746 -3.42641663551,1.68247163296,-1.87807297707 -3.43142724037,1.68247580528,-1.86649036407 -3.44444155693,1.68548071384,-1.85990011692 -3.4464507103,1.68248474598,-1.84632468224 -3.45646381378,1.68448936939,-1.83773994446 -3.45646739006,1.68249130249,-1.83093655109 -3.45647549629,1.67949521542,-1.81635868549 -3.46848964691,1.68250012398,-1.80877757072 -3.47650170326,1.68250465393,-1.79918849468 -3.47651004791,1.67950868607,-1.78461301327 -3.48151993752,1.67851281166,-1.77400457859 -3.4975361824,1.68351817131,-1.7684276104 -3.48453426361,1.6755194664,-1.75365006924 -3.50355124474,1.68252444267,-1.75103318691 -3.51656627655,1.68552947044,-1.74346327782 -3.51457309723,1.68153333664,-1.72886061668 -3.51758313179,1.67953777313,-1.71627926826 -3.52559518814,1.68054234982,-1.70668876171 -3.52860498428,1.67854678631,-1.69410848618 -3.52860999107,1.67754924297,-1.68633890152 -3.54562616348,1.682554245,-1.68173956871 -3.54763531685,1.68055856228,-1.66914474964 -3.55064558983,1.67856299877,-1.65656578541 -3.56265974045,1.68256795406,-1.64897489548 -3.55266427994,1.67357194424,-1.62940907478 -3.56067657471,1.67457675934,-1.6198182106 -3.57168626785,1.67857944965,-1.61803686619 -3.57269573212,1.67658412457,-1.60446000099 -3.57370448112,1.67358839512,-1.59185528755 -3.58371782303,1.67659318447,-1.58326232433 -3.58172678947,1.67259800434,-1.56770408154 -3.58973908424,1.67360270023,-1.55811226368 -3.60174846649,1.67760539055,-1.55731117725 -3.59475517273,1.67160987854,-1.53974366188 -3.60076665878,1.67161464691,-1.52915298939 -3.61077976227,1.67361950874,-1.52055847645 -3.60478711128,1.66862404346,-1.50398027897 -3.61179947853,1.66962909698,-1.49340379238 -3.63781857491,1.67863404751,-1.49278724194 -3.62081718445,1.66963648796,-1.4770334959 -3.62482833862,1.66864132881,-1.46544611454 -3.64184427261,1.67364633083,-1.45985329151 -3.63385105133,1.66765129566,-1.44228577614 -3.63586163521,1.66565620899,-1.42970311642 -3.65087628365,1.67066085339,-1.42408037186 -3.64588475227,1.66566610336,-1.40752708912 -3.64588975906,1.66466856003,-1.40073847771 -3.66090512276,1.66967356205,-1.39414334297 -3.65391230583,1.66367840767,-1.37756812572 -3.65792393684,1.66268360615,-1.36598360538 -3.67493963242,1.66868841648,-1.36038029194 -3.66594672203,1.661693573,-1.34281480312 -3.67596006393,1.66469860077,-1.33421361446 -3.68196678162,1.66570103168,-1.33041000366 -3.67097377777,1.65770637989,-1.31185519695 -3.67398548126,1.65671169758,-1.29929077625 -3.69200181961,1.66371679306,-1.29369318485 -3.69201135635,1.66072177887,-1.28109228611 -3.69502329826,1.6607272625,-1.26852738857 -3.70103025436,1.6617295742,-1.26472210884 -3.69403886795,1.65673518181,-1.24816322327 -3.6970500946,1.65574014187,-1.23656964302 -3.71806716919,1.66374516487,-1.23196840286 -3.71107506752,1.65775060654,-1.21638262272 -3.70908546448,1.65475618839,-1.20182514191 -3.72610139847,1.66076135635,-1.19523561001 -3.71610331535,1.654763937,-1.18543362617 -3.72411704063,1.65676939487,-1.17486584187 -3.74013233185,1.6617743969,-1.16826152802 -3.73514103889,1.65677976608,-1.15367388725 -3.7421541214,1.65878510475,-1.14309334755 -3.75216817856,1.66079056263,-1.13351392746 -3.73117280006,1.64879643917,-1.1129462719 -3.74018144608,1.65179932117,-1.1091684103 -3.75919747353,1.65980422497,-1.10355746746 -3.74820494652,1.6518099308,-1.08697628975 -3.75721859932,1.65481519699,-1.07738471031 -3.76323127747,1.65582048893,-1.06679296494 -3.75523996353,1.64982640743,-1.05121636391 -3.76825475693,1.65383160114,-1.04263269901 -3.77026104927,1.65383446217,-1.0368424654 -3.76427125931,1.64884066582,-1.02128946781 -3.76928329468,1.64984595776,-1.01068794727 -3.78629970551,1.65585124493,-1.0031080246 -3.78130960464,1.65185725689,-0.988535702229 -3.78632187843,1.65186262131,-0.977933645248 -3.79733037949,1.65686500072,-0.975133299828 -3.78533840179,1.6488713026,-0.958561420441 -3.79835319519,1.65287661552,-0.949970185757 -3.80036568642,1.65188252926,-0.937403321266 -3.79837608337,1.64988815784,-0.924800217152 -3.80438971519,1.65089404583,-0.913238525391 -3.81840491295,1.65589928627,-0.904651403427 -3.79740571976,1.6449034214,-0.89188182354 -3.81342101097,1.65090835094,-0.88427978754 -3.82343506813,1.65391373634,-0.874687433243 -3.81344437599,1.64792025089,-0.859115362167 -3.82045769691,1.64892590046,-0.848529458046 -3.8284714222,1.65193152428,-0.837950468063 -3.82547616959,1.64893460274,-0.831151306629 -3.82348823547,1.64694094658,-0.817586481571 -3.83850264549,1.65194582939,-0.809967279434 -3.82951331139,1.64695262909,-0.794411480427 -3.82952523232,1.64495873451,-0.781832873821 -3.8385386467,1.64796411991,-0.772227883339 -3.83454966545,1.64397037029,-0.758651196957 -3.84255838394,1.64797341824,-0.753874838352 -3.84257030487,1.64597952366,-0.74129730463 -3.83457994461,1.64098572731,-0.727692902088 -3.84359431267,1.64399158955,-0.717118442059 -3.85160827637,1.64599728584,-0.706535696983 -3.85262107849,1.64500379562,-0.69396674633 -3.84863162041,1.64200985432,-0.681362807751 -3.86264061928,1.64801204205,-0.678559482098 -3.85865211487,1.64401865005,-0.664988934994 -3.86066555977,1.64402508736,-0.652427792549 -3.86967897415,1.64703047276,-0.642815768719 -3.85969042778,1.64103794098,-0.627273201942 -3.86970424652,1.64404332638,-0.617667138577 -3.8757174015,1.64604902267,-0.607066452503 -3.8607211113,1.63905346394,-0.597298741341 -3.87073588371,1.64205932617,-0.586724162102 -3.88575077057,1.64806437492,-0.578112840652 -3.87576174736,1.64207160473,-0.563544869423 -3.8767747879,1.64107823372,-0.55097925663 -3.88578820229,1.64408349991,-0.541361987591 -3.89079594612,1.64608669281,-0.535588562489 -3.88280701637,1.64109361172,-0.522004067898 -3.88682055473,1.64209997654,-0.510422825813 -3.88383245468,1.63910651207,-0.497836023569 -3.88784599304,1.64011287689,-0.486254870892 -3.89886116982,1.64411866665,-0.475677400827 -3.88487148285,1.63712632656,-0.461100399494 -3.88587808609,1.637129426,-0.455304771662 -3.90089321136,1.64313483238,-0.445712804794 -3.90290737152,1.64314162731,-0.43315333128 -3.9019203186,1.64114844799,-0.420579582453 -3.90593385696,1.64215481281,-0.408996731043 -3.90694665909,1.64216113091,-0.397399544716 -3.90895962715,1.642167449,-0.38580712676 -3.91896796227,1.6461700201,-0.381018042564 -3.90097784996,1.6371781826,-0.366436868906 -3.90699243546,1.63918447495,-0.354862630367 -3.91400694847,1.6411908865,-0.343291848898 -3.91401958466,1.64019739628,-0.331691414118 -3.91403317451,1.63920426369,-0.319124668837 -3.92304754257,1.64321017265,-0.308526158333 -3.91705298424,1.63921403885,-0.301736652851 -3.91506648064,1.63822114468,-0.289162814617 -3.92508077621,1.64222693443,-0.278566420078 -3.92509460449,1.64123392105,-0.266000151634 -3.92110753059,1.63924121857,-0.253420352936 -3.93712210655,1.64524626732,-0.24380774796 -3.93412899971,1.6442501545,-0.23703110218 -3.92814135551,1.64025747776,-0.224446251988 -3.93715643883,1.64426374435,-0.212874665856 -3.92016768456,1.63527226448,-0.199292570353 -3.92918276787,1.63927841187,-0.187720552087 -3.9541990757,1.64928293228,-0.178123831749 -3.92620921135,1.63629257679,-0.163550570607 -3.92621588707,1.63629591465,-0.157751828432 -3.9492328167,1.6463009119,-0.14717784524 -3.93424487114,1.63930952549,-0.133610188961 -3.9392592907,1.64031612873,-0.12202423811 -3.94427323341,1.64232254028,-0.110437177122 -3.93728637695,1.63933026791,-0.097858145833 -3.93330001831,1.63633787632,-0.0852870494127 -3.94630789757,1.64233994484,-0.0804796665907 -3.93432021141,1.63634812832,-0.0678940340877 -3.94633579254,1.64135420322,-0.0563178919256 -3.95435023308,1.6443605423,-0.0447331443429 -3.93036222458,1.63337028027,-0.0311668012291 -3.94337773323,1.63937616348,-0.0195890255272 -3.94739174843,1.64038288593,-0.00799756590277 -3.94239783287,1.63838672638,-0.00219290377572 -3.93841171265,1.63539457321,0.0103739826009 -3.9564268589,1.64439940453,0.0209856089205 -3.93043899536,1.63140976429,0.0345390960574 -3.9374537468,1.63541615009,0.046128552407 -3.95446944237,1.6424216032,0.0577119812369 -3.94047570229,1.63542699814,0.0644856393337 -3.94248986244,1.6364338398,0.0760802030563 -3.95250463486,1.64043998718,0.0876714214683 -3.94751882553,1.63844811916,0.100236147642 -3.94053316116,1.63545644283,0.112800113857 -3.96054768562,1.64446079731,0.123426675797 -3.9395608902,1.63447082043,0.135990515351 -3.95056867599,1.63947308064,0.141788452864 -3.95358395576,1.64048051834,0.154351308942 -3.94159698486,1.63548910618,0.16594491899 -3.93761181831,1.63349735737,0.178504928946 -3.95962738991,1.64350187778,0.190109759569 -3.9376411438,1.63351225853,0.202660694718 -3.94365549088,1.63551878929,0.214259251952 -3.95066285133,1.63952147961,0.220062196255 -3.93067717552,1.63053190708,0.232608094811 -3.939691782,1.63453793526,0.244210496545 -3.95470738411,1.64054381847,0.256787091494 -3.93572115898,1.63255357742,0.2683621943 -3.950735569,1.63955879211,0.279975503683 -3.94975113869,1.63956677914,0.292536884546 -3.94775795937,1.63857078552,0.298332154751 -3.93677210808,1.63357973099,0.309911668301 -3.94578766823,1.637586236,0.322487354279 -3.92680191994,1.62959647179,0.334050893784 -3.95683979988,1.64361155033,0.365028262138 -3.97388458252,1.65163195133,0.401792556047 -3.96389913559,1.64764094353,0.413368374109 -3.95591402054,1.64464962482,0.42494726181 -3.95492959023,1.64465785027,0.437509208918 -3.97093701363,1.65165936947,0.444316923618 -3.98295211792,1.65766525269,0.456916242838 -3.94596624374,1.64067792892,0.466478794813 -3.94898176193,1.64268553257,0.479051798582 -3.95499682426,1.64569246769,0.491634696722 -3.9650118351,1.6506986618,0.504231750965 -3.96101927757,1.6487030983,0.510018765926 -3.94903492928,1.64471280575,0.521579086781 -3.94804954529,1.64472043514,0.533174395561 -3.94306468964,1.64272892475,0.544755578041 -3.95708012581,1.64873504639,0.558337926865 -3.94809556007,1.64574420452,0.569904744625 -3.94211101532,1.64375305176,0.581481337547 -3.94811892509,1.64675605297,0.588270902634 -3.94513368607,1.64576423168,0.599858880043 -3.94914937019,1.64877164364,0.612441956997 -3.94316482544,1.64578044415,0.624017119408 -3.92917990685,1.63979029655,0.634590446949 -3.92719507217,1.63979828358,0.646180808544 -3.91521048546,1.63580799103,0.656759440899 -3.93021821976,1.64280974865,0.664560258389 -3.91823482513,1.63782000542,0.676104068756 -3.92225027084,1.63982737064,0.68868881464 -3.92026543617,1.63983547688,0.700278937817 -3.92228126526,1.64184319973,0.712855637074 -3.92829632759,1.64485013485,0.725453197956 -3.91630482674,1.63985610008,0.730225503445 -3.91631960869,1.64086389542,0.741825997829 -3.90633511543,1.63687324524,0.752406537533 -3.90035152435,1.63588249683,0.763974130154 -3.91536712646,1.64288842678,0.778557300568 -3.91138291359,1.64189696312,0.790136516094 -3.91839885712,1.6459043026,0.803712189198 -3.93240571022,1.6529058218,0.811528563499 -3.74542832375,1.6554557085,1.53270053864 -3.72243881226,1.64546406269,1.53048813343 -3.69545960426,1.63547801971,1.53403520584 -3.6944770813,1.63648712635,1.54661250114 -3.69349431992,1.63849616051,1.55919075012 -3.67751312256,1.63250756264,1.56577122211 -3.68152999878,1.63651585579,1.58034920692 -3.68454647064,1.64052379131,1.59394812584 -3.69355368614,1.64552652836,1.60374927521 -3.68257212639,1.64253723621,1.61232841015 -3.68658900261,1.64654541016,1.62691223621 -3.65760946274,1.63555955887,1.62847507 -3.65662693977,1.6365686655,1.64105570316 -3.66864418983,1.6455757618,1.65962231159 -3.6476547718,1.63658392429,1.65740716457 -3.64167308807,1.63559389114,1.66798472404 -3.65568852425,1.64460015297,1.6865824461 -3.63070845604,1.63461363316,1.68915259838 -3.63072538376,1.63662219048,1.7017493248 -3.64474201202,1.64562880993,1.7213228941 -3.6227619648,1.63764166832,1.72489738464 -3.6187710762,1.63664698601,1.72968757153 -3.62178850174,1.64065539837,1.74426722527 -3.59880805016,1.63266825676,1.74685251713 -3.59182691574,1.63167893887,1.75741398335 -3.59684443474,1.63668715954,1.77299284935 -3.58486294746,1.63269805908,1.78057515621 -3.57788228989,1.63270878792,1.79113650322 -3.58088922501,1.63471198082,1.79796528816 -3.57090806961,1.6327227354,1.80654394627 -3.56692647934,1.63273262978,1.8181180954 -3.57694387436,1.64074027538,1.83668637276 -3.5649626255,1.63675153255,1.84426534176 -3.55898141861,1.63676166534,1.85484182835 -3.5559990406,1.6377710104,1.86643278599 -3.54301023483,1.63277816772,1.86720633507 -3.54302692413,1.63578677177,1.8798122406 -3.54004597664,1.63679695129,1.89237332344 -3.5320649147,1.63580751419,1.90194880962 -3.52108359337,1.63281834126,1.90953743458 -3.52710103989,1.63882648945,1.92611908913 -3.52111077309,1.63683223724,1.92990529537 -3.52012825012,1.63984119892,1.94249999523 -3.51814627647,1.64085066319,1.95507967472 -3.50616598129,1.63786220551,1.96265089512 -3.49818539619,1.63687300682,1.97222483158 -3.49420404434,1.63788282871,1.98380303383 -3.48222398758,1.63489460945,1.99137127399 -3.49423074722,1.64189660549,2.00417947769 -3.48824954033,1.6419069767,2.01475667953 -3.47926855087,1.6409175396,2.0233438015 -3.470287323,1.63892829418,2.03192996979 -3.46430635452,1.63893866539,2.04250621796 -3.45932602882,1.63994932175,2.05406999588 -3.44534564018,1.63596081734,2.05965948105 -3.45335388184,1.64096415043,2.07144117355 -3.44437289238,1.63997495174,2.08002614975 -3.44139194489,1.64098501205,2.0925951004 -3.43740940094,1.64199435711,2.1032063961 -3.43542909622,1.64500451088,2.11676502228 -3.42744851112,1.64401531219,2.12633752823 -3.42145752907,1.64202070236,2.12914705276 -3.41647720337,1.6430311203,2.14071297646 -3.41049647331,1.64304161072,2.15129041672 -3.41251349449,1.64705014229,2.16589307785 -3.39153599739,1.64006412029,2.16843771935 -3.39755320549,1.64607214928,2.18602633476 -3.3925716877,1.64708209038,2.19662261009 -3.38858151436,1.64608752728,2.20140862465 -3.37060308456,1.64110052586,2.20497250557 -3.37662029266,1.64710855484,2.2225663662 -3.36564016342,1.64512014389,2.23014068604 -3.35865926743,1.6451305151,2.23972964287 -3.35967850685,1.64914000034,2.25529456139 -3.34868884087,1.64514660835,2.25509381294 -3.34870743752,1.64815604687,2.26966977119 -3.34372591972,1.64916598797,2.28026843071 -3.34074497223,1.6511759758,2.29284787178 -3.33176469803,1.65018713474,2.30142879486 -3.32478499413,1.65019822121,2.31199073792 -3.30280637741,1.6412115097,2.31157755852 -3.30781531334,1.64621531963,2.32236433029 -3.30283474922,1.64722597599,2.33393549919 -3.29385495186,1.64623713493,2.34251451492 -3.27687549591,1.64124941826,2.34510660172 -3.28789281845,1.6502571106,2.36767983437 -3.27191400528,1.64626944065,2.37126231194 -3.27093219757,1.64927887917,2.38485693932 -3.2749414444,1.6532831192,2.39563202858 -3.26196217537,1.65029501915,2.40121555328 -3.24998283386,1.6473069191,2.40778946877 -3.25600099564,1.65431547165,2.42736101151 -3.23602175713,1.64732813835,2.42696785927 -3.22904229164,1.64733934402,2.43753004074 -3.23605942726,1.65534722805,2.45712661743 -3.21507263184,1.64635634422,2.44989848137 -3.20909261703,1.64636695385,2.46048045158 -3.221108675,1.65737390518,2.48407411575 -3.19813203812,1.64938819408,2.48263907433 -3.19115161896,1.64939880371,2.49222874641 -3.19117069244,1.65340852737,2.50780057907 -3.17718219757,1.6474159956,2.50459575653 -3.17520236969,1.65042638779,2.51915407181 -3.17422032356,1.6544355154,2.53276181221 -3.15624237061,1.64844858646,2.53433823586 -3.14826321602,1.64845991135,2.54390764236 -3.15128135681,1.654468894,2.56149435043 -3.13330364227,1.64848196507,2.56306695938 -3.12631487846,1.64648854733,2.56584143639 -3.13133215904,1.65449666977,2.58444738388 -3.11835360527,1.65050899982,2.59001708031 -3.11237335205,1.65151953697,2.60060310364 -3.11239218712,1.65652906895,2.61618685722 -3.09641385078,1.65154182911,2.61876964569 -3.09043359756,1.65255248547,2.62935638428 -3.08844447136,1.65455794334,2.63613271713 -3.07846522331,1.65256953239,2.64371204376 -3.07448506355,1.65457999706,2.65629172325 -3.07250356674,1.65858960152,2.66988992691 -3.0585258007,1.6546022892,2.6744594574 -3.05354547501,1.65661275387,2.68604493141 -3.05256533623,1.66062283516,2.70161700249 -3.03857707977,1.65463018417,2.69741272926 -3.03459668159,1.65764069557,2.70999622345 -3.02861785889,1.6596518755,2.72156190872 -3.01364016533,1.65466475487,2.72513008118 -3.00566005707,1.65467560291,2.73372650146 -3.01267814636,1.66368401051,2.75630688667 -3.00568890572,1.66269004345,2.75810194016 -2.99171113968,1.65970289707,2.7626657486 -2.98873090744,1.66271305084,2.77625131607 -2.96975398064,1.65572667122,2.77582454681 -2.96377491951,1.65773785114,2.78739261627 -2.9677927494,1.66474640369,2.80699110031 -2.95980381966,1.66275274754,2.80778574944 -2.95182347298,1.66276359558,2.81638431549 -2.94784426689,1.66577446461,2.82995200157 -2.93186640739,1.66078722477,2.83153820038 -2.9218878746,1.65979897976,2.83911466599 -2.92090821266,1.66480922699,2.85568070412 -2.89893221855,1.6568236351,2.85224556923 -2.9029405117,1.66182744503,2.86404895782 -2.89696073532,1.66383814812,2.87464594841 -2.88698196411,1.66284990311,2.88222241402 -2.88200283051,1.66486084461,2.89479589462 -2.87902188301,1.66787087917,2.90839362144 -2.8580467701,1.66088533401,2.90594887733 -2.85306620598,1.6638957262,2.91754770279 -2.85107660294,1.66490101814,2.92433547974 -2.84009838104,1.66391324997,2.93091130257 -2.83211970329,1.66392469406,2.94048714638 -2.83413767815,1.67093360424,2.95909166336 -2.82216095924,1.66894638538,2.96564412117 -2.81718039513,1.67195665836,2.97724747658 -2.80520391464,1.66996955872,2.98379945755 -2.79621458054,1.66697573662,2.98260688782 -2.78823566437,1.66798734665,2.99218463898 -2.78525567055,1.67199766636,3.00676894188 -2.77127861977,1.66801047325,3.01033973694 -2.76229906082,1.66802167892,3.01793980598 -2.7583193779,1.67203223705,3.03152537346 -2.7493326664,1.66903972626,3.03228378296 -2.73835372925,1.66805136204,3.03788018227 -2.73837375641,1.67406141758,3.05645346642 -2.72239637375,1.66907441616,3.05703902245 -2.71141886711,1.66808652878,3.06361222267 -2.70943808556,1.67309653759,3.07920742035 -2.69546151161,1.67010951042,3.0827729702 -2.69147229195,1.6711152792,3.08756351471 -2.68949246407,1.67612576485,3.10413980484 -2.68051338196,1.67613697052,3.11174154282 -2.67653417587,1.68014776707,3.12631511688 -2.66855549812,1.68115925789,3.13589906693 -2.65657806396,1.67917180061,3.14146995544 -2.64859962463,1.68018317223,3.15105414391 -2.650608778,1.6851875782,3.16284704208 -2.64263010025,1.68619906902,3.17243313789 -2.62765312195,1.68221187592,3.17401337624 -2.62067389488,1.68422317505,3.1846036911 -2.61369490623,1.68623423576,3.1951944828 -2.58972096443,1.67624938488,3.18675422668 -2.59273052216,1.68125402927,3.20053577423 -2.57575488091,1.67726755142,3.20010232925 -2.42237639427,1.79059183598,3.62181901932 -2.39840149879,1.77960646152,3.60940814018 -2.39142251015,1.78261768818,3.62200021744 -2.38744354248,1.78862857819,3.63958525658 -2.36247086525,1.77764415741,3.62714147568 -2.35349345207,1.77965605259,3.63771724701 -2.34451508522,1.78166782856,3.6473107338 -2.33352828026,1.77767515182,3.64309072495 -2.32355070114,1.77768719196,3.65167474747 -2.30857396126,1.77470004559,3.65226268768 -2.28759932518,1.7667144537,3.64384198189 -2.28662037849,1.77572500706,3.6674118042 -1.99322140217,1.7820469141,3.84352755547 -1.96223986149,1.75805842876,3.79930496216 -1.95226252079,1.76007032394,3.80789399147 -1.94328641891,1.7630828619,3.82045388222 -1.92831075191,1.76009607315,3.82003307343 -1.91833341122,1.76110804081,3.82862329483 -1.9013582468,1.75612163544,3.82420110703 -1.89338040352,1.76013314724,3.83679175377 -1.8873924017,1.76013946533,3.83958029747 -1.87641513348,1.76015162468,3.84617137909 -1.85644125938,1.75216603279,3.83574318886 -1.85046267509,1.75817704201,3.85233736038 -1.83748686314,1.75718998909,3.85591292381 -1.82151210308,1.75320363045,3.85348415375 -1.81253504753,1.75621557236,3.86506438255 -1.8025482893,1.75222277641,3.85984611511 -1.79357004166,1.75523424149,3.86945390701 -1.7805942297,1.75424718857,3.87302780151 -1.7666182518,1.75225996971,3.87361240387 -1.76064074039,1.75827157497,3.89218974113 -1.74366593361,1.7532851696,3.8867661953 -1.72969079018,1.7522983551,3.88833642006 -1.7227025032,1.75030469894,3.88813400269 -1.71272563934,1.75231683254,3.89771604538 -1.70174872875,1.75332903862,3.90430808067 -1.68977332115,1.75434207916,3.91087174416 -1.67879641056,1.75535404682,3.91746473312 -1.66482126713,1.75336742401,3.91903328896 -1.6648311615,1.76037228107,3.9348347187 -1.64585614204,1.75238585472,3.92243075371 -1.63388073444,1.75239884853,3.92899465561 -1.61590659618,1.74641287327,3.920566082 -1.61092841625,1.75442397594,3.94215345383 -1.59795236588,1.7534365654,3.94473695755 -1.58497595787,1.75244903564,3.94633245468 -1.57898747921,1.75245511532,3.94813299179 -1.56401324272,1.74946892262,3.94769215584 -1.55203664303,1.74948132038,3.95228028297 -1.54105985165,1.75049328804,3.95887494087 -1.52808392048,1.74950611591,3.96145677567 -1.51710867882,1.75251889229,3.97101807594 -1.50513219833,1.75253129005,3.97560715675 -1.5001437664,1.75353729725,3.98040318489 -1.48416924477,1.74955093861,3.97597432137 -1.47319328785,1.75156342983,3.98454856873 -1.45721793175,1.74657654762,3.97813940048 -1.44524097443,1.74658870697,3.98173832893 -1.43626487255,1.75160098076,3.9963080883 -1.42927658558,1.74960720539,3.99511027336 -1.41530156136,1.74762034416,3.99568223953 -1.40532433987,1.75063216686,4.0052781105 -1.39134955406,1.74864542484,4.00584936142 -1.38037347794,1.7516579628,4.01442718506 -1.36739683151,1.74967026711,4.01502799988 -1.35542213917,1.75168335438,4.02258729935 -1.34343552589,1.74369072914,4.00737905502 -1.33145987988,1.74370336533,4.01295757294 -1.3184838295,1.74371600151,4.01454544067 --1.4632037878,1.79334914684,3.87491130829 --1.45619487762,1.77635288239,3.83669757843 --1.46617174149,1.77336359024,3.8262898922 --1.48114657402,1.77737545967,3.82786893845 --1.4901239872,1.77338588238,3.8154668808 --1.50309944153,1.7743973732,3.81204891205 --1.52207267284,1.78240990639,3.82261705399 --1.52505290508,1.77241897583,3.79723787308 --1.53803789616,1.77942597866,3.81000828743 --1.55101299286,1.78043758869,3.80558085442 --1.55899131298,1.77644753456,3.79219245911 --1.57296705246,1.77845883369,3.79178309441 --1.58894181252,1.78247058392,3.79536485672 --1.59691953659,1.7784807682,3.78096222878 --1.60790538788,1.78348731995,3.78874015808 --1.61988174915,1.7834982872,3.78333067894 --1.6298583746,1.781509161,3.7729177475 --1.64083528519,1.7805198431,3.76551198959 --1.66180932522,1.79153192043,3.78110599518 --1.66478717327,1.78054201603,3.75367975235 --1.6817625761,1.78655338287,3.7602789402 --1.6917488575,1.79055988789,3.76505541801 --1.70072591305,1.78757035732,3.75264406204 --1.71170282364,1.78658092022,3.74523878098 --1.73067700863,1.79359292984,3.75482583046 --1.73065745831,1.7816016674,3.72443366051 --1.75063097477,1.78961396217,3.73500776291 --1.76460683346,1.79262506962,3.73359656334 --1.76159787178,1.78262913227,3.71240234375 --1.78257131577,1.79264140129,3.72497987747 --1.79654717445,1.79465246201,3.72357082367 --1.8035248518,1.78966259956,3.70715665817 --1.82149887085,1.79567468166,3.71273064613 --1.83047711849,1.79268455505,3.70234084129 --1.83446502686,1.79069006443,3.69411802292 --1.85044121742,1.79570102692,3.69772410393 --1.86341691017,1.7967120409,3.69330453873 --1.87539291382,1.79672288895,3.68688559532 --1.88736975193,1.7977335453,3.68148064613 --1.89734697342,1.79574394226,3.67207479477 --1.91632080078,1.80275595188,3.6786468029 --1.91731131077,1.79776012897,3.66746211052 --1.92728865147,1.79677045345,3.6580555439 --1.94226264954,1.79878234863,3.65561175346 --1.94724154472,1.79279184341,3.6372115612 --1.95821857452,1.79280233383,3.62980461121 --1.9761929512,1.79781401157,3.63438224792 --2.31559085846,1.84108483791,3.53190755844 --2.32456851006,1.83909487724,3.52049469948 --2.33154654503,1.83510458469,3.50608205795 --2.3295276165,1.82411313057,3.47867918015 --2.33850479126,1.8221231699,3.46726155281 --2.35548090935,1.82713377476,3.46886086464 --2.36245894432,1.82414352894,3.45444297791 --2.36944675446,1.82514882088,3.45222997665 --2.37742471695,1.82215869427,3.43981957436 --2.39340114594,1.82716917992,3.4394133091 --2.40537834167,1.82717931271,3.43300580978 --2.41135644913,1.82318878174,3.41759204865 --2.42633295059,1.82719933987,3.41517853737 --2.4443089962,1.83220982552,3.41777968407 --2.45429635048,1.83621549606,3.41956496239 --2.83161330223,1.87751328945,3.22925114632 --2.82260584831,1.86751663685,3.20804548264 --2.81458902359,1.8555239439,3.17865657806 --2.83156466484,1.85953426361,3.17622971535 --2.83354401588,1.85354316235,3.15680646896 --2.85052084923,1.85855305195,3.15540146828 --2.86949729919,1.86456334591,3.15599346161 --2.87247729301,1.85957193375,3.13858532906 --2.87446713448,1.85757637024,3.1303794384 --2.8954436779,1.86558628082,3.13399028778 --2.89242458344,1.85659456253,3.10957193375 --2.90640163422,1.85860419273,3.10415816307 --2.92437887192,1.86461412907,3.10375905037 --2.92835831642,1.86062300205,3.0873439312 --2.94333529472,1.86363255978,3.08293151855 --2.9543235302,1.86763775349,3.08473110199 --2.96130204201,1.86564695835,3.07131075859 --2.9722802639,1.86665606499,3.06290555 --2.98925709724,1.87166583538,3.06049489975 --2.98823785782,1.86367416382,3.03908061981 --2.99721598625,1.86268353462,3.02765631676 --3.01420283318,1.87168896198,3.03545665741 --3.01418399811,1.86469709873,3.01605939865 --3.02416181564,1.86470651627,3.00563454628 --3.050137043,1.87571692467,3.01222681999 --3.04811859131,1.86772477627,2.99082660675 --3.06209588051,1.8707344532,2.98440217972 --3.07707357407,1.87374377251,2.98000073433 --3.07106590271,1.86674714088,2.96480822563 --3.08504319191,1.86975669861,2.95838522911 --3.10302066803,1.8757661581,2.95698690414 --3.10500121117,1.87077450752,2.93958067894 --3.11897850037,1.87278401852,2.93316054344 --3.14095473289,1.88179385662,2.93474817276 --3.13193798065,1.86980116367,2.90735077858 --3.1359269619,1.86880576611,2.90113782883 --3.15990304947,1.87781560421,2.90473127365 --3.16488313675,1.87582409382,2.89032459259 --3.16886305809,1.87183248997,2.87491559982 --3.18683934212,1.87684237957,2.8714838028 --3.19282007217,1.87585055828,2.85909867287 --3.19979906082,1.87385952473,2.84567093849 --3.21678566933,1.88186478615,2.85146141052 --3.21476745605,1.87487256527,2.83105969429 --3.22674655914,1.8768812418,2.8236644268 --3.24372434616,1.88189041615,2.82025933266 --3.24470448494,1.87689876556,2.8018386364 --3.25868272781,1.87890791893,2.79542779922 --3.26567196846,1.88091242313,2.79222297668 --3.2696518898,1.87692070007,2.77680802345 --3.28762984276,1.88292980194,2.77441072464 --3.29460883141,1.8819385767,2.76098179817 --3.30058956146,1.87994658947,2.74859452248 --3.30956816673,1.87995541096,2.73717093468 --3.3225467205,1.8819642067,2.72976136208 --3.32953619957,1.8839687109,2.7265586853 --3.33551597595,1.88197696209,2.71314787865 --3.3504948616,1.88598585129,2.70774793625 --3.36047363281,1.88699448109,2.69732952118 --3.36545348167,1.88400292397,2.68291425705 --3.37343454361,1.88401079178,2.67253351212 --3.39141130447,1.88902020454,2.66810393333 --3.39840078354,1.89102447033,2.66490411758 --3.40538072586,1.89003264904,2.65249705315 --3.41535997391,1.89104127884,2.64208054543 --3.42034006119,1.88804960251,2.62766337395 --3.43431925774,1.89205813408,2.62126660347 --3.44529819489,1.89306652546,2.61185574532 --3.45527839661,1.89407467842,2.60246372223 --3.45426893234,1.89107871056,2.59224820137 --3.470246315,1.89508771896,2.58581805229 --3.47122836113,1.89109528065,2.56942439079 --3.48220777512,1.89210379124,2.56001496315 --3.48818778992,1.89111185074,2.54660081863 --3.50616669655,1.89612030983,2.54320979118 --3.51614618301,1.89712870121,2.5327963829 --3.50813817978,1.89113223553,2.51758146286 --3.52611613274,1.89614105225,2.51316952705 --3.53109741211,1.8941488266,2.49977254868 --3.55107474327,1.90115773678,2.49635267258 --3.55505561829,1.8981654644,2.48194932938 --3.56703543663,1.90117359161,2.47355079651 --3.57402467728,1.90217804909,2.46933484077 --3.57300710678,1.89718532562,2.45194387436 --3.57998657227,1.89619362354,2.43851113319 --3.5959649086,1.90120220184,2.43209457397 --3.60194635391,1.9002096653,2.41970348358 --3.61592578888,1.90321791172,2.41229891777 --3.62690496445,1.90522634983,2.40187287331 --3.62789535522,1.90323030949,2.39366197586 --3.63687634468,1.90423798561,2.38326954842 --3.64785647392,1.90624594688,2.37386894226 --3.65583634377,1.90625405312,2.3614449501 --3.66181755066,1.90526151657,2.34905362129 --3.66879725456,1.90426981449,2.33562111855 --3.68077778816,1.90627753735,2.32723069191 --3.68576788902,1.90728151798,2.32202720642 --3.68874907494,1.90528917313,2.30660963058 --3.6997282505,1.90629732609,2.29618740082 --3.71170926094,1.90930497646,2.28779888153 --3.71768951416,1.90831279755,2.27438235283 --3.72267007828,1.90632069111,2.25995659828 --3.74364876747,1.91432881355,2.2565536499 --3.74863910675,1.91533267498,2.25135183334 --3.75162124634,1.91233992577,2.23695755005 --3.76260089874,1.91434788704,2.22653913498 --3.7685816288,1.91335558891,2.2131228447 --3.77056384087,1.91136300564,2.19771695137 --3.78454327583,1.91437089443,2.18930387497 --3.79752373695,1.91737854481,2.18090748787 --3.79651451111,1.91538214684,2.1716966629 --3.7994966507,1.91238951683,2.15729951859 --3.81147623062,1.91539752483,2.14686870575 --3.8214571476,1.91640496254,2.13646864891 --3.82743811607,1.91641259193,2.12305164337 --3.83541941643,1.9164198637,2.11165595055 --3.8414003849,1.9164274931,2.09823894501 --3.84339118004,1.91543114185,2.0910320282 --3.84837293625,1.9144384861,2.07762908936 --3.86435270309,1.91944611073,2.07022094727 --3.88133192062,1.92445397377,2.06280112267 --3.88131546974,1.92146074772,2.04741859436 --3.88429641724,1.91846823692,2.03199291229 --3.88728761673,1.9184718132,2.02579712868 --3.90326786041,1.92347919941,2.01839447021 --3.91024827957,1.92348694801,2.00496411324 --3.91823029518,1.92449402809,1.99357163906 --3.92721033096,1.92550182343,1.9811398983 --3.94119119644,1.92950892448,1.97274410725 --3.94217395782,1.92651581764,1.95734417439 --3.9431655407,1.92551934719,1.95015001297 --3.95114660263,1.92652666569,1.93773257732 --3.9551281929,1.9245339632,1.92331707478 --3.97110819817,1.92954146862,1.91489839554 --3.97909021378,1.93054831028,1.90350818634 --3.98407149315,1.92955577374,1.88907957077 --3.99505233765,1.93156278133,1.87867736816 --3.99504375458,1.93056643009,1.87046921253 --3.998026371,1.92857325077,1.85606563091 --4.01400661469,1.93358051777,1.84765326977 --4.01498937607,1.93158745766,1.83224880695 --4.03097009659,1.93559479713,1.8238389492 --4.03395223618,1.93460154533,1.80943512917 --4.04493427277,1.93660843372,1.79903721809 --4.0469250679,1.93561208248,1.79182934761 --4.04790687561,1.93361926079,1.77539670467 --4.05888843536,1.93562614918,1.76499998569 --4.05787181854,1.93263304234,1.74859035015 --4.07385253906,1.93763995171,1.74018752575 --4.07983446121,1.93764686584,1.72677326202 --4.0888171196,1.93965351582,1.71537637711 --4.08380889893,1.93565702438,1.70517063141 --4.09478998184,1.93766403198,1.6937507391 --4.10677146912,1.94067084789,1.68334674835 --4.11275339127,1.94067776203,1.66993319988 --4.11273670197,1.93868422508,1.65453469753 --4.12671899796,1.94269096851,1.64513683319 --4.12870883942,1.94169473648,1.63690161705 --4.1326918602,1.94070124626,1.62351071835 --4.1346745491,1.93970811367,1.60808825493 --4.14465618134,1.94171476364,1.59668409824 --4.15063858032,1.94172155857,1.5832709074 --4.16462087631,1.94572806358,1.57387852669 --4.16660356522,1.94473481178,1.55845558643 --4.16559505463,1.94273817539,1.55025196075 --4.17957639694,1.94674491882,1.53983509541 --4.18256044388,1.94575107098,1.52645468712 --4.18954229355,1.94675779343,1.51303231716 --4.20652341843,1.95276451111,1.50361454487 --4.19050884247,1.94177103043,1.48221409321 --4.19149160385,1.94077777863,1.4667981863 --4.20948123932,1.94778096676,1.46558868885 --4.20746612549,1.94478714466,1.45020365715 --4.21444797516,1.94579386711,1.43678188324 --4.22443056107,1.94780004025,1.42538511753 --4.22741413116,1.94680655003,1.41097652912 --4.23839569092,1.94981324673,1.39854419231 --4.24137830734,1.94881975651,1.3841356039 --4.23337173462,1.94382297993,1.37394022942 --4.2583527565,1.95382905006,1.36753952503 --4.28933238983,1.96583521366,1.36211419106 --4.27831840515,1.95884144306,1.34372889996 --4.28330039978,1.95884799957,1.3293030262 --4.29328298569,1.96085441113,1.3168861866 --4.28026819229,1.95286083221,1.29748630524 --4.28426027298,1.95386385918,1.29128658772 --4.30924081802,1.9638698101,1.28387355804 --4.29322624207,1.95387637615,1.26346898079 --4.29920959473,1.95488262177,1.25006079674 --4.32319021225,1.96388876438,1.24163520336 --4.30517673492,1.95289516449,1.22124183178 --4.31415987015,1.95590114594,1.20883595943 --4.33015012741,1.96190404892,1.2056196928 --4.31913471222,1.95491051674,1.18721747398 --4.32711744308,1.95591688156,1.17379415035 --4.34510040283,1.96292233467,1.16440021992 --4.33108568192,1.95492899418,1.14499044418 --4.34106826782,1.95693492889,1.13257980347 --4.36005115509,1.96494042873,1.12318205833 --4.34904336929,1.95794403553,1.11196517944 --4.35102796555,1.95694994926,1.09756326675 --4.36701011658,1.96295595169,1.08613681793 --4.35999536514,1.95796203613,1.0697478056 --4.36297941208,1.95696806908,1.05533790588 --4.38396215439,1.96597349644,1.04593324661 --4.37894535065,1.96098005772,1.02849984169 --4.38093805313,1.96098268032,1.02231907845 --4.39492034912,1.96598863602,1.00988650322 --4.38790559769,1.96099472046,0.993492603302 --4.39388990402,1.96200037003,0.980089724064 --4.40387296677,1.9660063982,0.966659665108 --4.39185857773,1.95801270008,0.949268996716 --4.40084886551,1.96101570129,0.943041145802 --4.41683340073,1.96702075005,0.932655990124 --4.40081787109,1.95802748203,0.913232564926 --4.40880203247,1.96103322506,0.899817168713 --4.4287853241,1.96803832054,0.889410257339 --4.41077041626,1.95804512501,0.869993984699 --4.41375541687,1.95805060863,0.856611192226 --4.42974662781,1.96505284309,0.852400302887 --4.41973114014,1.95905935764,0.834985852242 --4.42171621323,1.95806503296,0.820581197739 --4.43869924545,1.96507012844,0.809171795845 --4.42968416214,1.9590767622,0.791747868061 --4.4396686554,1.96208178997,0.779353439808 --4.45465230942,1.96808707714,0.766931891441 --4.43664503098,1.95909106731,0.755724012852 --4.44662952423,1.96209597588,0.743331074715 --4.43061494827,1.95310282707,0.724911391735 --4.42759943008,1.95110881329,0.709503233433 --4.4375834465,1.95411419868,0.696082532406 --4.44556760788,1.95611953735,0.682673513889 --4.4395532608,1.9521253109,0.667279839516 --4.45154523849,1.95712757111,0.662077724934 --4.44853067398,1.95513343811,0.646668016911 --4.45151519775,1.95513904095,0.632256746292 --4.45049953461,1.95314502716,0.616836309433 --4.45448446274,1.95415055752,0.602420032024 --4.45646905899,1.95415604115,0.588013231754 --4.46645402908,1.95716071129,0.57562738657 --4.46744728088,1.9571634531,0.568424284458 --4.45743083954,1.95117020607,0.55098515749 --4.46541595459,1.95417523384,0.537580549717 --4.47940063477,1.96017980576,0.525180399418 --4.46738672256,1.95318615437,0.508774936199 --4.47337055206,1.95519149303,0.494351834059 --4.48536348343,1.96019327641,0.489162027836 --4.48534822464,1.95919907093,0.473735511303 --4.47833395004,1.95520496368,0.458334833384 --4.47331905365,1.95121085644,0.442925453186 --4.49730396271,1.96121454239,0.431524813175 --4.48228979111,1.95422112942,0.415121495724 --4.49127388,1.95722603798,0.400690793991 --4.49325942993,1.9572314024,0.386284559965 --4.50025272369,1.96023344994,0.380090355873 --4.5032377243,1.96123874187,0.365681409836 --4.49922275543,1.95824444294,0.350265920162 --4.49220848083,1.9542504549,0.334858208895 --4.49919319153,1.95625543594,0.320437014103 --4.50217914581,1.95726048946,0.306027889252 --4.50616407394,1.95826566219,0.291616410017 --4.4991569519,1.95526897907,0.283406078815 --4.50814294815,1.9582734108,0.270010262728 --4.5131278038,1.96027827263,0.255596935749 --4.50911331177,1.9572840929,0.240177437663 --4.50109910965,1.95329010487,0.224766016006 --4.50808525085,1.95629453659,0.211376875639 --4.50307750702,1.95329785347,0.203158348799 --4.51006317139,1.95630264282,0.18874129653 --4.51304864883,1.9563075304,0.174333631992 --4.51603460312,1.9573123455,0.159926041961 --4.51302051544,1.9563177824,0.145529478788 --4.51300573349,1.9553232193,0.13009865582 --4.52099275589,1.95832741261,0.116711936891 --4.52098560333,1.958329916,0.109510958195 --4.5189704895,1.95633554459,0.094083443284 --4.5179567337,1.95634067059,0.079682290554 --4.5199432373,1.95634555817,0.0652772337198 --4.52092838287,1.95635092258,0.0498447231948 --4.51491451263,1.95335638523,0.0354488901794 --4.5169005394,1.95436131954,0.0210434217006 --4.5208940506,1.95636343956,0.0138377482072 --4.52888011932,1.95936763287,-0.000572312274016 --4.52186536789,1.95637357235,-0.0159978475422 --4.52085208893,1.95537865162,-0.0304001048207 --4.51983833313,1.95438373089,-0.0448026321828 --4.52382421494,1.95638823509,-0.0592083372176 --4.51480960846,1.95139443874,-0.0746360719204 --4.52580308914,1.95639574528,-0.0818425342441 --4.52078962326,1.95440113544,-0.0962441861629 --4.5197763443,1.9534060955,-0.110647454858 --4.52176141739,1.95441114902,-0.126080363989 --4.51474809647,1.95141673088,-0.140483796597 --4.51473426819,1.95142161846,-0.154888108373 --4.52372121811,1.95542526245,-0.169291138649 --4.51671409607,1.95142865181,-0.176493987441 --4.51169967651,1.9494343996,-0.191928550601 --4.51468658447,1.9514387846,-0.20633225143 --4.50967264175,1.94844412804,-0.220738738775 --4.51865959167,1.95244777203,-0.2351385355 --4.50964593887,1.94845366478,-0.249548345804 --4.51763248444,1.9524576664,-0.264976203442 --4.51262521744,1.95046067238,-0.272182226181 --4.50461149216,1.94646656513,-0.286593616009 --4.50659894943,1.9474709034,-0.300996810198 --4.50958585739,1.94947528839,-0.315398722887 --4.51357221603,1.95147967339,-0.330827623606 --4.50355768204,1.94648575783,-0.345244079828 --4.50454473495,1.9474902153,-0.359647870064 --4.50153827667,1.94649302959,-0.366854518652 --4.49852466583,1.94549798965,-0.381264060736 --4.50951290131,1.95050096512,-0.39565205574 --4.50349903107,1.94750642776,-0.410065978765 --4.48948478699,1.94151329994,-0.424495071173 --4.49247169495,1.94351732731,-0.438895404339 --4.4904589653,1.94252216816,-0.453304499388 --4.49345207214,1.94452428818,-0.461530357599 --4.48843955994,1.94252932072,-0.474916815758 --4.50042772293,1.94853210449,-0.490325301886 --4.48841285706,1.94353866577,-0.504756450653 --4.48839998245,1.94354307652,-0.519161403179 --4.48838758469,1.9445476532,-0.533566474915 --4.48638105392,1.94355010986,-0.540773749352 --4.47436714172,1.93855631351,-0.554180502892 --4.4783539772,1.94156038761,-0.569604754448 --4.48334121704,1.94356417656,-0.585024774075 --4.48032855988,1.94256901741,-0.599437832832 --4.47731590271,1.94157373905,-0.612822294235 --4.47030210495,1.93957924843,-0.627248346806 --4.4822974205,1.94557952881,-0.635442912579 --4.47228288651,1.94158577919,-0.649878442287 --4.47827148438,1.94458901882,-0.664263308048 --4.46725845337,1.94059503078,-0.677675127983 --4.47324609756,1.94359838963,-0.693087697029 --4.47123336792,1.94360303879,-0.70749849081 --4.46622037888,1.94160830975,-0.721920013428 --4.46021366119,1.93961119652,-0.728115260601 --4.46020078659,1.9406157732,-0.743548333645 --4.4621887207,1.94161963463,-0.75794428587 --4.4621758461,1.94262397289,-0.773376524448 --4.45716333389,1.94162893295,-0.786771178246 --4.45715093613,1.94163310528,-0.801174163818 --4.4591383934,1.94363701344,-0.816597402096 --4.458132267,1.94363927841,-0.823802947998 --4.44111824036,1.93664646149,-0.836221814156 --4.45010757446,1.94164896011,-0.851614058018 --4.44509410858,1.94065403938,-0.866039216518 --4.4410815239,1.93965888023,-0.880460202694 --4.4440703392,1.94166231155,-0.89484834671 --4.44005775452,1.94166719913,-0.909269690514 --4.4370508194,1.94066977501,-0.916485130787 --4.44203996658,1.94367289543,-0.931890785694 --4.42602491379,1.93668007851,-0.944314956665 --4.43101406097,1.94068300724,-0.959720253944 --4.44100379944,1.94668519497,-0.976126611233 --4.43299055099,1.94369065762,-0.989540219307 --4.41797637939,1.93769752979,-1.00196421146 --4.42897224426,1.94369733334,-1.01116216183 --4.41595840454,1.93870377541,-1.02357685566 --4.40794563293,1.93670940399,-1.03699421883 --4.42193603516,1.94371044636,-1.05440044403 --4.40492153168,1.93671774864,-1.06581270695 --4.40591049194,1.93872117996,-1.08020722866 --4.41890048981,1.9467227459,-1.09864318371 --4.38888978958,1.93273055553,-1.09985220432 --4.40088129044,1.93973171711,-1.11623620987 --4.41187095642,1.94673347473,-1.13365232944 --4.39685678482,1.94074046612,-1.14608728886 --4.37784194946,1.93274796009,-1.15649330616 --4.3948340416,1.94174826145,-1.17489612103 --4.37581920624,1.93475580215,-1.18530511856 --4.38081407547,1.93775677681,-1.19452822208 --4.37980222702,1.93876075745,-1.20893275738 --4.36778926849,1.93476700783,-1.22135519981 --4.37377977371,1.93876922131,-1.2367401123 --4.37576818466,1.94177269936,-1.25317978859 --4.3637547493,1.9367787838,-1.26457571983 --4.36174869537,1.93678104877,-1.27178835869 --4.37073945999,1.94278264046,-1.28920483589 --4.3487238884,1.93379116058,-1.29861927032 --4.33571052551,1.92979741096,-1.31002724171 --4.35170221329,1.93879759312,-1.32944583893 --4.33268785477,1.93180525303,-1.33884382248 --4.3276758194,1.93081009388,-1.3532782793 --4.34167289734,1.93780863285,-1.3644810915 --4.31865739822,1.9288173914,-1.37288582325 --4.31364536285,1.92782187462,-1.38629293442 --4.32163667679,1.93382358551,-1.40370941162 --4.30062055588,1.92583203316,-1.41313266754 --4.29660987854,1.92583632469,-1.42653286457 --4.30360031128,1.93083810806,-1.44395458698 --4.28959178925,1.92484307289,-1.44715547562 --4.29058170319,1.92784631252,-1.46257030964 --4.29557228088,1.931848526,-1.47897803783 --4.27955770493,1.9258556366,-1.48939585686 --4.28254747391,1.92885839939,-1.5058195591 --4.29053926468,1.93485963345,-1.52322626114 --4.26452207565,1.92386949062,-1.53065145016 --4.26351165771,1.92587292194,-1.54505360126 --4.27250862122,1.93087220192,-1.55525267124 --4.24549198151,1.91988217831,-1.56166517735 --4.25648403168,1.92788279057,-1.5810970068 --4.24547052383,1.92388880253,-1.59250593185 --4.23945856094,1.92289352417,-1.60592544079 --4.22844552994,1.91989946365,-1.61733686924 --4.23144197464,1.9229003191,-1.62553203106 --4.21542787552,1.9169074297,-1.63493657112 --4.20741558075,1.91491270065,-1.64734959602 --4.21640777588,1.92191362381,-1.66576445103 --4.19639253616,1.91392195225,-1.67418420315 --4.1973824501,1.91692471504,-1.68959283829 --4.19437122345,1.91792869568,-1.70401287079 --4.18336343765,1.9129332304,-1.7082349062 --4.19635725021,1.92193281651,-1.72763133049 --4.18434381485,1.91793906689,-1.73905873299 --4.16632890701,1.91194689274,-1.74746727943 --4.1633181572,1.91295075417,-1.76188755035 --4.16530942917,1.91595304012,-1.77728223801 --4.15329551697,1.91295945644,-1.78871417046 --4.14928913116,1.91196203232,-1.79492294788 --4.14927959442,1.91396510601,-1.8103376627 --4.13426542282,1.90897214413,-1.81974923611 --4.1282544136,1.90797662735,-1.83214652538 --4.1312456131,1.91297876835,-1.84958279133 --4.11623096466,1.90798592567,-1.8589977026 --4.1112203598,1.90799021721,-1.87241208553 --4.11021566391,1.90799188614,-1.8796159029 --4.1032037735,1.90799677372,-1.89202582836 --4.10019302368,1.90800046921,-1.90644454956 --4.09318208694,1.90800523758,-1.91885471344 --4.07716751099,1.90301287174,-1.92828786373 --4.07615756989,1.9040157795,-1.94268333912 --4.08214998245,1.91001665592,-1.96110522747 --4.0661406517,1.90302276611,-1.96129465103 --4.06012916565,1.90302729607,-1.97472202778 --4.05711889267,1.90403103828,-1.98914039135 --4.0501074791,1.90303575993,-2.00155234337 --4.04109573364,1.90204107761,-2.01296234131 --4.03908634186,1.90304422379,-2.02736783028 --4.0330748558,1.90304875374,-2.04079532623 --4.04007291794,1.90804791451,-2.0520067215 --4.03106117249,1.90705323219,-2.06341695786 --4.02104854584,1.90405881405,-2.07381296158 --4.01203727722,1.90306413174,-2.08522462845 --4.01903057098,1.90906453133,-2.10464811325 --4.00201511383,1.90307247639,-2.11308121681 --4.00700807571,1.90907335281,-2.1315009594 --4.00600385666,1.91007483006,-2.13870167732 --3.9789853096,1.89908599854,-2.1411075592 --3.96997356415,1.89809131622,-2.1525220871 --3.97196578979,1.90209293365,-2.16892528534 --3.96695518494,1.90309715271,-2.18336677551 --3.9479393959,1.8961057663,-2.18978238106 --3.94693040848,1.89810848236,-2.20519733429 --3.94692611694,1.9001096487,-2.21341085434 --3.94291639328,1.9011131525,-2.22681212425 --3.94290852547,1.90411543846,-2.24221086502 --3.92589330673,1.89812338352,-2.24963116646 --3.91888237,1.89812803268,-2.2620472908 --3.91787409782,1.90113055706,-2.27745890617 --3.90986227989,1.90013551712,-2.2898888588 --3.91786170006,1.90613389015,-2.3020927906 --3.92085528374,1.91113483906,-2.3194975853 --3.90984249115,1.90814077854,-2.32991576195 --3.90983462334,1.9121427536,-2.34633469582 --3.90682554245,1.91314589977,-2.36074328423 --3.88580918312,1.90615534782,-2.3651509285 --3.88480496407,1.90815675259,-2.37337470055 --3.88979887962,1.91315698624,-2.39279603958 --3.87178373337,1.90816545486,-2.39921593666 --3.86677384377,1.90816915035,-2.41262698174 --3.86976790428,1.91316986084,-2.43002271652 --3.86075615883,1.91317522526,-2.44246697426 --3.85074424744,1.91118073463,-2.45287442207 --3.85274147987,1.91318082809,-2.4620757103 --3.83572673798,1.90818893909,-2.46848702431 --3.83071708679,1.90919268131,-2.48189735413 --3.8367125988,1.91619205475,-2.50231838226 --3.81069326401,1.9062037468,-2.50374293327 --3.80468297005,1.90720772743,-2.5171687603 --3.8056769371,1.91120910645,-2.53356170654 --3.78966546059,1.90421617031,-2.53278541565 --3.78765749931,1.90721845627,-2.54819965363 --3.79065227509,1.91321897507,-2.56661009789 --3.7606306076,1.90023243427,-2.56503367424 --3.76062369347,1.9042340517,-2.58144021034 --3.76762032509,1.91223263741,-2.60285973549 --3.74460196495,1.90324342251,-2.60527896881 --3.7415971756,1.90324544907,-2.61147904396 --3.74759340286,1.9112445116,-2.63291120529 --3.72457528114,1.90325534344,-2.6353354454 --3.71556425095,1.9022603035,-2.64573431015 --3.72056031227,1.90825974941,-2.66615319252 --3.7015440464,1.90226888657,-2.67056727409 --3.69853615761,1.90427160263,-2.68496656418 --3.70453596115,1.91026973724,-2.69819068909 --3.68651986122,1.90427863598,-2.70361542702 --3.67350721359,1.90128529072,-2.7110080719 --3.67450141907,1.90628623962,-2.72943782806 --3.66048741341,1.90329349041,-2.73787331581 --3.65247702599,1.90329802036,-2.74928188324 --3.65147042274,1.90629971027,-2.7656929493 --3.63545870781,1.89930713177,-2.76289391518 --3.63044977188,1.90131056309,-2.77732491493 --3.63444662094,1.90830981731,-2.79672193527 --3.61342835426,1.90032017231,-2.8001601696 --3.60641860962,1.90132439137,-2.81257629395 --3.6094148159,1.90732395649,-2.83198666573 --3.58639597893,1.89833521843,-2.83239197731 --3.56638145447,1.88934469223,-2.82660079002 --3.56137275696,1.89134812355,-2.84103155136 --3.54735898972,1.88835537434,-2.84845352173 --3.54034924507,1.88935947418,-2.86087155342 --3.53834295273,1.8923612833,-2.87627148628 --3.52532958984,1.88936817646,-2.88470077515 --3.51331686974,1.88737463951,-2.89311337471 --3.51631593704,1.89137375355,-2.90432357788 --3.49829936028,1.88538300991,-2.90875029564 --3.49529242516,1.88938510418,-2.92416667938 --3.4972884655,1.89438509941,-2.9435839653 --3.48727726936,1.89439046383,-2.95400834084 --3.47026157379,1.88939917088,-2.95842075348 --3.46225142479,1.88940370083,-2.96983242035 --3.4462389946,1.88241183758,-2.96603870392 --3.44623398781,1.88741254807,-2.98446631432 --1.1177097559,0.545552432537,-1.17885947227 --1.27480947971,0.636476814747,-1.30286467075 --3.41620922089,1.87442779541,-2.9788942337 --1.12069618702,0.548557758331,-1.18726432323 --1.13768982887,0.560557126999,-1.2077229023 --1.17669785023,0.585545539856,-1.2461848259 --1.21470499039,0.609534502029,-1.28466641903 --1.26772427559,0.642514944077,-1.33509838581 --1.24469351768,0.630533099174,-1.32352733612 --1.2136670351,0.613551199436,-1.30068945885 --1.20364570618,0.609562575817,-1.29909360409 --1.21463704109,0.617563843727,-1.31553137302 --1.04431045055,0.540742695332,-1.25815105438 --1.03217017651,0.549806654453,-1.30373322964 --2.91565179825,1.88369762897,-3.56490278244 --2.88862514496,1.86871504784,-3.54511809349 --2.88862466812,1.8757134676,-3.5675637722 --2.88161754608,1.87771677971,-3.5789475441 --2.85459017754,1.8657336235,-3.5693731308 --2.86059617996,1.87772786617,-3.59779548645 --2.83857369423,1.86974143982,-3.59422922134 --2.82756257057,1.86474823952,-3.59142684937 --2.81354808807,1.8627563715,-3.5968568325 --2.81755256653,1.87275183201,-3.62327861786 --2.79252672195,1.86276757717,-3.61571121216 --2.39512753487,1.8519859314,-3.90264511108 --2.38211202621,1.84599554539,-3.89586257935 --2.37610840797,1.85099720955,-3.91127753258 --2.35908913612,1.8460085392,-3.91070461273 --2.35909366608,1.85500466824,-3.9351131916 --2.35108733177,1.85800778866,-3.94854187965 --2.31504130363,1.83703649044,-3.91796541214 --2.33206796646,1.85601890087,-3.95717382431 --2.31705188751,1.85302853584,-3.95960187912 --2.29202079773,1.84104752541,-3.94501280785 --2.28802061081,1.84804677963,-3.96545171738 --2.26999950409,1.84205949306,-3.9618639946 --2.25898885727,1.84206557274,-3.96927309036 --2.25098323822,1.84606850147,-3.98371648788 --2.23496484756,1.84107935429,-3.98312807083 --2.22996020317,1.8420817852,-3.98834371567 --2.2289648056,1.85107815266,-4.01275873184 --2.2029311657,1.83809888363,-3.99516773224 --2.19192123413,1.8391045332,-4.00461006165 --2.18391513824,1.84210753441,-4.01803398132 --2.17390608788,1.84311270714,-4.02744722366 --2.161891222,1.83812189102,-4.02167797089 --2.14787554741,1.83613109589,-4.02409076691 --2.13586378098,1.83613812923,-4.03051280975 --2.12485289574,1.83614420891,-4.03792333603 --2.11784911156,1.84014594555,-4.05334806442 --2.1168551445,1.85014164448,-4.07876062393 --2.09282326698,1.83816111088,-4.0641875267 --2.08481407166,1.83616650105,-4.06440734863 --2.07280230522,1.83617329597,-4.07184505463 --2.06479716301,1.8401761055,-4.08526325226 --2.04977965355,1.836186409,-4.08567714691 --2.04077291489,1.83919024467,-4.0970916748 --2.03276824951,1.84319281578,-4.11152219772 --2.01775097847,1.84020316601,-4.11193799973 --2.01374864578,1.84120440483,-4.11915206909 -2.22894477844,1.8039958477,-3.24199986458 -2.22593545914,1.79299128056,-3.21341323853 -2.23594522476,1.79199385643,-3.20580792427 -2.24295067787,1.78899466991,-3.19321131706 -2.24895453453,1.7839949131,-3.17665958405 -2.26597428322,1.78900098801,-3.17906212807 -2.27097725868,1.78400099277,-3.16346979141 -2.27898645401,1.78600382805,-3.16465759277 -2.28999781609,1.78600692749,-3.1580619812 -2.29600214958,1.78200757504,-3.14348077774 -2.3170273304,1.79001557827,-3.15187382698 -2.32102918625,1.78401517868,-3.13429641724 -2.33804869652,1.78902113438,-3.13669157028 -2.34305381775,1.78902244568,-3.13288974762 -2.35206246376,1.78802454472,-3.12329697609 -2.36307406425,1.78802764416,-3.11571907997 -2.3730840683,1.78703033924,-3.10713434219 -2.39110469818,1.79303658009,-3.11053085327 -2.38909935951,1.78303396702,-3.08593940735 -2.41412878036,1.79404330254,-3.09736132622 -2.42113637924,1.79504561424,-3.09655380249 -2.43114638329,1.79404830933,-3.08796858788 -2.44115662575,1.79405105114,-3.07938289642 -2.45216822624,1.79405426979,-3.07376694679 -2.45416855812,1.78805363178,-3.05419111252 -2.46417880058,1.78705644608,-3.04560804367 -2.46818208694,1.78205692768,-3.03001046181 -2.48520183563,1.79106318951,-3.04220032692 -2.48820376396,1.78506326675,-3.02461719513 -2.51923918724,1.80007457733,-3.04303002357 -2.52724719048,1.79907655716,-3.03243398666 -2.53225159645,1.79407739639,-3.01784396172 -2.5402598381,1.79307949543,-3.00725007057 -2.5512714386,1.79308283329,-2.99967122078 -2.56228351593,1.79708659649,-3.00287818909 -2.56628727913,1.79308724403,-2.9882671833 -2.57930111885,1.79409134388,-2.98269701004 -2.5933163166,1.7970957756,-2.98009109497 -2.60032343864,1.79409766197,-2.96751475334 -2.61533951759,1.79810237885,-2.96591114998 -2.62134599686,1.79910433292,-2.96311283112 -2.62635111809,1.79410541058,-2.94755077362 -2.6383638382,1.79610919952,-2.94293451309 -2.65337991714,1.79911398888,-2.94034838676 -2.65237855911,1.79111325741,-2.91876864433 -2.67139911652,1.79811942577,-2.92215371132 -2.6804087162,1.79712224007,-2.91256737709 -2.68341183662,1.79512310028,-2.9057803154 -2.70443415642,1.803129673,-2.91018724442 -2.70343351364,1.79512929916,-2.88959407806 -2.72946095467,1.8061375618,-2.89901065826 -2.73746943474,1.80414009094,-2.88842082024 -2.72645878792,1.7901365757,-2.85683035851 -2.73747062683,1.7911400795,-2.85023021698 -2.74848222733,1.79514360428,-2.85244107246 -2.74648094177,1.78714311123,-2.83085656166 -3.03179049492,1.81623649597,-2.65909385681 -3.02578830719,1.8062363863,-2.6345334053 -3.02979469299,1.80323863029,-2.61995863914 -3.02579450607,1.7942391634,-2.59837865829 -3.03080177307,1.79224169254,-2.58578276634 -3.05182218552,1.79924750328,-2.58817529678 -3.04181575775,1.79024624825,-2.56940627098 -3.04882478714,1.78924918175,-2.55880784988 -3.07384824753,1.79925596714,-2.56420946121 -3.06884813309,1.79025673866,-2.54164266586 -3.08686566353,1.79626190662,-2.54103636742 -3.10488367081,1.80226719379,-2.5404279232 -3.09287810326,1.78926646709,-2.51186466217 -3.10088634491,1.79126894474,-2.51007533073 -3.11390042305,1.79427325726,-2.50448155403 -3.11690616608,1.79027569294,-2.4908747673 -3.1249165535,1.78927910328,-2.47932243347 -1.30014002323,0.602223396301,-0.610856890678 -1.2911503315,0.596229791641,-0.599270403385 -1.21411800385,0.553227543831,-0.543614804745 -1.17410743237,0.529229521751,-0.512955009937 -1.17411637306,0.528233766556,-0.510185599327 -1.24117553234,0.563250362873,-0.547701954842 -1.28321444988,0.585261702538,-0.570081830025 -1.39830040932,0.64528298378,-0.636623203754 -3.39940643311,1.71646761894,-1.86885547638 -3.39341115952,1.70947098732,-1.85028851032 -3.37840771675,1.69947195053,-1.83351707458 -3.37041139603,1.6924751997,-1.81492245197 -3.36941862106,1.68747913837,-1.800334692 -3.39043784142,1.69548463821,-1.7987421751 -3.39044618607,1.69248878956,-1.78417122364 -3.39245510101,1.6894929409,-1.77157795429 -3.41146850586,1.69749629498,-1.77577507496 -3.41948080063,1.69850099087,-1.76619231701 -3.41648817062,1.69350516796,-1.74963283539 -3.42550086975,1.69550979137,-1.7410377264 -3.42851042747,1.69351398945,-1.7294331789 -3.43052053452,1.69151842594,-1.71587097645 -3.4545404911,1.70052409172,-1.71528112888 -3.43353414536,1.68752479553,-1.69747197628 -3.44554877281,1.69152975082,-1.68989479542 -3.46056437492,1.69553494453,-1.68430519104 -3.45356988907,1.68853890896,-1.66672229767 -3.46558427811,1.69254398346,-1.65914273262 -3.47659802437,1.69454872608,-1.65154707432 -3.45759868622,1.68155252934,-1.62699151039 -3.4716091156,1.6875551939,-1.62817656994 -3.49362826347,1.69556081295,-1.62559938431 -3.48163151741,1.6865645647,-1.60600876808 -3.48264050484,1.68356907368,-1.5934098959 -3.50165867805,1.690574646,-1.58884251118 -3.5026679039,1.68757903576,-1.57624387741 -3.49667453766,1.68258345127,-1.55966162682 -3.50468254089,1.68458604813,-1.55686962605 -3.50769329071,1.68259096146,-1.54430270195 -3.51170444489,1.68259572983,-1.53272044659 -3.52571988106,1.68660092354,-1.52613329887 -3.52072691917,1.68160533905,-1.51054227352 -3.51973581314,1.6776099205,-1.49695074558 -3.54074931145,1.68761301041,-1.50015902519 -3.5287539959,1.67761766911,-1.48059344292 -3.54376935959,1.68262255192,-1.47498643398 -3.54878091812,1.6826274395,-1.4643894434 -3.54478883743,1.67763233185,-1.44881999493 -3.55180191994,1.67863738537,-1.43825161457 -3.57682132721,1.68864285946,-1.43665456772 -3.55681848526,1.67764484882,-1.42086935043 -3.55682778358,1.67464959621,-1.40826737881 -3.57384419441,1.68065488338,-1.40268063545 -3.56885242462,1.67565989494,-1.38710427284 -3.57086324692,1.67366492748,-1.37453103065 -3.59288191795,1.68267035484,-1.37094449997 -3.57588553429,1.67167520523,-1.35036861897 -3.58889532089,1.67667782307,-1.3495695591 -3.59590768814,1.67768275738,-1.33996927738 -3.59091615677,1.67268800735,-1.32439994812 -3.59092664719,1.66969335079,-1.31083512306 -3.61194419861,1.67769837379,-1.30722641945 -3.60395169258,1.67170357704,-1.29065382481 -3.60196137428,1.66770875454,-1.27706587315 -3.61897206306,1.67571115494,-1.27824652195 -3.61598157883,1.67171645164,-1.26367747784 -3.62199425697,1.67272186279,-1.2530952692 -3.63700938225,1.67772686481,-1.24649703503 -3.63201880455,1.67273247242,-1.23093760014 -3.63603019714,1.67273747921,-1.22033083439 -3.64003658295,1.67274010181,-1.21553599834 -3.63704657555,1.66874563694,-1.20097255707 -3.63605737686,1.66675126553,-1.18740260601 -3.64907217026,1.67075645924,-1.17980742455 -3.65008330345,1.6687618494,-1.16723001003 -3.64409184456,1.66376721859,-1.15263676643 -3.67411255836,1.67677235603,-1.15104150772 -3.65111041069,1.66377532482,-1.13625729084 -3.66112494469,1.66678094864,-1.12668800354 -3.67514014244,1.67178618908,-1.11909854412 -3.66214728355,1.66379213333,-1.10152828693 -3.67216086388,1.66579735279,-1.09292590618 -3.68317484856,1.66880249977,-1.08433294296 -3.67517876625,1.6638058424,-1.07456636429 -3.68419265747,1.6668112278,-1.06498301029 -3.68520355225,1.66481661797,-1.05337846279 -3.68021345139,1.66082262993,-1.03880774975 -3.68822693825,1.6628279686,-1.02921330929 -3.69724082947,1.66483342648,-1.01962852478 -3.7082555294,1.66783905029,-1.01006281376 -3.70125865936,1.6638417244,-1.00224936008 -3.71927499771,1.6708470583,-0.995656132698 -3.70928406715,1.66385340691,-0.979104697704 -3.71829819679,1.66685891151,-0.969516634941 -3.71630835533,1.66386449337,-0.956917822361 -3.72032165527,1.66387033463,-0.945345580578 -3.73333644867,1.66787588596,-0.936761856079 -3.73634243011,1.66887831688,-0.931952118874 -3.7123477459,1.65588510036,-0.912375628948 -3.73836636543,1.66689002514,-0.907781600952 -3.74237918854,1.66689586639,-0.896208703518 -3.73338890076,1.66090250015,-0.880647957325 -3.73740124702,1.66090810299,-0.870043754578 -3.74941658974,1.66491377354,-0.860477685928 -3.74642157555,1.66291677952,-0.853679716587 -3.75643587112,1.66592240334,-0.844094395638 -3.75644779205,1.66392838955,-0.831519663334 -3.74545645714,1.65793466568,-0.816917061806 -3.76347279549,1.66393995285,-0.8093329072 -3.76148509979,1.66194653511,-0.795775592327 -3.76949262619,1.66494905949,-0.791973292828 -3.76250243187,1.65995526314,-0.778376162052 -3.78151917458,1.66796052456,-0.770793318748 -3.77052927017,1.66096746922,-0.755231738091 -3.76453995705,1.65697383881,-0.741646468639 -3.77855491638,1.66197919846,-0.733053684235 -3.77456665039,1.6589858532,-0.719485521317 -3.78457427025,1.66298794746,-0.716661214828 -3.78758716583,1.66299414635,-0.705080628395 -3.79060029984,1.66300022602,-0.693499922752 -3.78161072731,1.6570070982,-0.678931057453 -3.79862713814,1.66401255131,-0.670352995396 -3.78863739967,1.65801954269,-0.65577930212 -3.79565119743,1.65902543068,-0.645194888115 -3.7986574173,1.66002810001,-0.640381991863 -3.80467200279,1.66203451157,-0.628822147846 -3.79668259621,1.65704119205,-0.615233898163 -3.80469679832,1.65904712677,-0.604654550552 -3.80070829391,1.65605354309,-0.592061936855 -3.81172275543,1.66005921364,-0.582467377186 -3.81273603439,1.65906596184,-0.569907784462 -3.81374263763,1.65906906128,-0.564114511013 -3.80575370789,1.65407598019,-0.550533115864 -3.82076883316,1.66008126736,-0.541926562786 -3.81378054619,1.65608823299,-0.528352975845 -3.8237953186,1.65909433365,-0.51778113842 -3.82280755043,1.65810060501,-0.50617736578 -3.82181429863,1.65710425377,-0.499406546354 -3.82282710075,1.65611052513,-0.487815380096 -3.83184146881,1.65911650658,-0.477234959602 -3.8268532753,1.65612328053,-0.464644372463 -3.83986949921,1.66112947464,-0.454083621502 -3.84588289261,1.66313540936,-0.443484216928 -3.83689451218,1.6581428051,-0.429908454418 -3.83089971542,1.65414643288,-0.423114150763 -3.85791707039,1.66615092754,-0.415517777205 -3.82992601395,1.65215992928,-0.398953557014 -3.838940382,1.65516591072,-0.388368576765 -3.85295557976,1.66117143631,-0.37877124548 -3.8429672718,1.65517902374,-0.365198075771 -3.84598112106,1.65618550777,-0.353617012501 -3.85398864746,1.65918815136,-0.348821163177 -3.84500098228,1.65419590473,-0.335255682468 -3.84301352501,1.65320265293,-0.323653668165 -3.86703133583,1.66320776939,-0.314090430737 -3.84504103661,1.65221643448,-0.299510240555 -3.85605621338,1.65622222424,-0.288926333189 -3.8700709343,1.66222763062,-0.279317647219 -3.8560757637,1.6552323103,-0.271536678076 -3.8580892086,1.65523898602,-0.259951204062 -3.89410853386,1.67124307156,-0.251381695271 -3.86111760139,1.6552529335,-0.235810369253 -3.86613225937,1.65725958347,-0.22423428297 -3.87114548683,1.65926551819,-0.21362349391 -3.87315249443,1.65926885605,-0.207833483815 -3.85816431046,1.65227735043,-0.194263413548 -3.88718223572,1.66428184509,-0.184688508511 -3.86119174957,1.65229094028,-0.171090111136 -3.86420607567,1.65329778194,-0.159507334232 -3.87222099304,1.65630412102,-0.147937178612 -3.86523413658,1.65231204033,-0.135362520814 -3.8672413826,1.65331542492,-0.129572018981 -3.89025735855,1.66331994534,-0.119966574013 -3.85826778412,1.64833033085,-0.105405196548 -3.86328244209,1.6493370533,-0.0938268005848 -3.87629747391,1.6553426981,-0.0832290202379 -3.86631035805,1.6503508091,-0.0706534460187 -3.86632514,1.64935839176,-0.058098372072 -3.88833355904,1.6593593359,-0.0542735494673 -3.86534571648,1.6493691206,-0.0407125540078 -3.86835980415,1.64937591553,-0.0291284937412 -3.87237429619,1.65138268471,-0.0175449438393 -3.87538862228,1.65238964558,-0.00595954526216 -3.87040305138,1.64939761162,0.00660169264302 -3.88341784477,1.65540313721,0.0172105561942 -3.86942386627,1.64940845966,0.0239862520248 -3.86643743515,1.64741587639,0.0355775654316 -3.8954539299,1.66041994095,0.0461756326258 -3.86546635628,1.64643096924,0.0597201660275 -3.88248133659,1.65443599224,0.0703317821026 -3.89049649239,1.65744245052,0.0819170325994 -3.87250256538,1.64944827557,0.0886864215136 -3.87251663208,1.64945554733,0.100274838507 -3.88953256607,1.65646100044,0.111858665943 -3.87354636192,1.6494705677,0.124416872859 -3.8785610199,1.65147733688,0.136004924774 -3.87757515907,1.65048480034,0.14759349823 -3.87958955765,1.65149176121,0.159182503819 -3.87759637833,1.65049576759,0.164976447821 -3.8886115551,1.65550172329,0.176568672061 -3.87562608719,1.64951121807,0.189118430018 -3.88564109802,1.65451729298,0.200712382793 -3.88165521622,1.65252518654,0.212299108505 -3.87766933441,1.6505330801,0.223885014653 -3.87967681885,1.65153646469,0.229680940509 -3.88869261742,1.65554332733,0.24224370718 -3.89070725441,1.65655040741,0.253835529089 -3.87372112274,1.64956009388,0.265406519175 -3.87873578072,1.65156686306,0.277000874281 -3.87575006485,1.64957475662,0.288585484028 -3.88076615334,1.65258216858,0.301147222519 -3.88077330589,1.65258586407,0.306941777468 -3.87778782845,1.65159380436,0.318526238203 -3.89080381393,1.65759992599,0.331103295088 -3.87581706047,1.65060913563,0.341700524092 -3.88583278656,1.65561568737,0.354274600744 -3.87484765053,1.65062499046,0.365842282772 -3.89386320114,1.6596300602,0.378437846899 -3.86987018585,1.64963710308,0.383215218782 -3.88288521767,1.65464305878,0.395799309015 -3.86589956284,1.64765286446,0.406382977962 -3.87191534042,1.6506601572,0.41895237565 -3.86793041229,1.64966833591,0.430531412363 -3.88194561005,1.65567421913,0.443124294281 -3.87195253372,1.651679039,0.447926133871 -3.86796760559,1.6496874094,0.459504246712 -3.87098360062,1.65169513226,0.472068607807 -3.86399912834,1.6497040987,0.483637154102 -3.86201405525,1.6487121582,0.495220065117 -3.86202907562,1.64971983433,0.506809711456 -3.85804438591,1.64772832394,0.518385529518 -3.85405087471,1.64573228359,0.523200511932 -3.8490664959,1.64474093914,0.534771978855 -3.85008263588,1.64474916458,0.547330021858 -3.84709835052,1.64475750923,0.558908104897 -3.84611344337,1.64476549625,0.570493340492 -3.85712862015,1.64977157116,0.583092391491 -3.85814356804,1.65077912807,0.594687223434 -3.85715246201,1.65078389645,0.601444482803 -3.84916734695,1.64779269695,0.612035632133 -3.83818292618,1.64380228519,0.622612297535 -3.8871986866,1.66680324078,0.640217006207 -3.85521459579,1.65281605721,0.648767709732 -3.83022975922,1.6418274641,0.657344579697 -3.8292453289,1.64183557034,0.668929517269 -3.83925247192,1.64683783054,0.675738990307 -3.83926916122,1.64784634113,0.688296198845 -3.85428452492,1.65485203266,0.701895475388 -3.84029960632,1.64986181259,0.711484789848 -3.86031484604,1.65986680984,0.726080656052 -3.88933086395,1.67387092113,0.742661714554 -3.83933925629,1.65088236332,0.741426885128 -3.84335517883,1.65388989449,0.754008352757 -3.84337043762,1.65489768982,0.76560229063 -3.84138631821,1.65490603447,0.777185201645 -3.83540296555,1.65291547775,0.788744688034 -3.8414182663,1.65592253208,0.801340639591 -3.82643437386,1.64993286133,0.810912907124 -3.82344293594,1.6499376297,0.816691815853 -3.82345819473,1.64994561672,0.828285634518 -3.82347488403,1.65095424652,0.84084635973 -3.8164908886,1.64896333218,0.851430177689 -3.80650639534,1.644972682,0.861027002335 -3.8115234375,1.64898061752,0.874586880207 -3.81153893471,1.64998853207,0.886181890965 -3.82254624367,1.65499079227,0.89398676157 -3.79356312752,1.64300358295,0.900552272797 -3.79557967186,1.64501166344,0.913126826286 -3.80359530449,1.65001869202,0.926711440086 -3.77061271667,1.63503217697,0.932271420956 -3.78462815285,1.64303815365,0.946866452694 -3.8186352253,1.6600369215,0.959679603577 -3.80965185165,1.65604686737,0.9702450037 -3.81066846848,1.65805518627,0.982818067074 -3.80768489838,1.65806400776,0.994394659996 -3.78570127487,1.64907538891,1.0009906292 -3.78671765327,1.65008366108,1.0135627985 -3.7947332859,1.65509057045,1.02715837955 -3.7617430687,1.6401001215,1.02592694759 -3.76975870132,1.64510703087,1.03952205181 -3.78977537155,1.65611290932,1.05708503723 -3.7607922554,1.64412546158,1.06167733669 -3.7618086338,1.64513385296,1.07425069809 -3.78682470322,1.6591385603,1.09283089638 -3.74484276772,1.64015352726,1.09440219402 -3.73685121536,1.6371588707,1.09819829464 -3.79686498642,1.66715788841,1.12579345703 -3.60968613625,1.66560256481,1.65884566307 -3.59069728851,1.6566106081,1.65761947632 -3.59271430969,1.66061902046,1.67120659351 -3.58073282242,1.65663003922,1.67879033089 -3.57275152206,1.6556404829,1.68836557865 -3.56176924706,1.65165102482,1.69596040249 -3.5577878952,1.65266096592,1.70752751827 -3.54380702972,1.64767241478,1.71410894394 -3.53881692886,1.6466782093,1.71888065338 -3.53283429146,1.64568781853,1.72848057747 -3.51785445213,1.64069986343,1.7350435257 -3.5098733902,1.63971054554,1.744612813 -3.51789021492,1.64571809769,1.76119792461 -3.50790810585,1.64372837543,1.76880061626 -3.49792718887,1.64073944092,1.7773706913 -3.50693511963,1.6467423439,1.78816235065 -3.50295376778,1.64775240421,1.79972970486 -3.49497175217,1.64576244354,1.80832958221 -3.49599075317,1.64977216721,1.82288038731 -3.48300981522,1.64578330517,1.82946515083 -3.47602844238,1.64479374886,1.83904826641 -3.48603630066,1.65079653263,1.85083258152 -3.46405601501,1.6428091526,1.85242950916 -3.46207475662,1.64481902122,1.86499750614 -3.47209072113,1.65182590485,1.88260173798 -3.45211172104,1.64483904839,1.88616323471 -3.45912837982,1.65084660053,1.90275418758 -3.45714688301,1.65285634995,1.91532599926 -3.45115709305,1.65086221695,1.91910791397 -3.44317650795,1.65087306499,1.92867493629 -3.44619369507,1.65488147736,1.94326806068 -3.42721438408,1.64789426327,1.94683730602 -3.43123197556,1.65290272236,1.96241807938 -3.44224762917,1.66090941429,1.98102641106 -3.42625975609,1.65491747856,1.97979271412 -3.41727876663,1.65292823315,1.9883723259 -3.42529559135,1.66093575954,2.00596570969 -3.41231560707,1.65594756603,2.01253843307 -3.4093337059,1.65795707703,2.0241291523 -3.40135335922,1.65696811676,2.03369522095 -3.40237092972,1.66097676754,2.04729580879 -3.39738154411,1.65998291969,2.05206179619 -3.39139962196,1.65999281406,2.06166219711 -3.40141654015,1.66800022125,2.08124303818 -3.37943863869,1.66001391411,2.0828037262 -3.38545608521,1.66602218151,2.10037779808 -3.36847662926,1.66103458405,2.10396337509 -3.37549328804,1.6670422554,2.12155795097 -3.37950253487,1.67104649544,2.13133645058 -3.35452389717,1.66106021404,2.12992358208 -3.34554362297,1.66007137299,2.1384999752 -3.35156106949,1.66607940197,2.15608263016 -3.33258223534,1.66009259224,2.15865373611 -3.32960033417,1.6611020565,2.17025017738 -3.33062005043,1.6661118269,2.1858048439 -3.31862998009,1.66111826897,2.18461513519 -3.31664824486,1.66312789917,2.19720244408 -3.3176677227,1.66713762283,2.2127597332 -3.29868841171,1.66115021706,2.21435141563 -3.29870724678,1.66415989399,2.22892022133 -3.29972529411,1.6681689024,2.2435092926 -3.28073763847,1.66017723083,2.23829722404 -3.28475642204,1.66618621349,2.25585770607 -3.28577423096,1.67019534111,2.27044963837 -3.27179431915,1.66620695591,2.27504277229 -3.26481509209,1.66621828079,2.28559780121 -3.25883340836,1.66622829437,2.29520010948 -3.24885344505,1.664239645,2.3027818203 -3.24386334419,1.66324532032,2.3065726757 -3.24588155746,1.66825425625,2.32216048241 -3.22990274429,1.66326677799,2.32573771477 -3.22792220116,1.66627681255,2.33930587769 -3.22994017601,1.67028570175,2.3548977375 -3.2059636116,1.66130018234,2.35345363617 -3.20398187637,1.66430974007,2.36605143547 -3.21098947525,1.67031288147,2.37785673141 -3.19001269341,1.66232693195,2.37841129303 -3.19203019142,1.66733562946,2.3940076828 -3.18505001068,1.66734647751,2.40359139442 -3.17207121849,1.66435849667,2.40916419029 -3.17309141159,1.66936850548,2.42571687698 -3.17910814285,1.67637646198,2.44431853294 -3.15512156487,1.66538596153,2.4341044426 -3.14914155006,1.66639661789,2.44468069077 -3.14815974236,1.66940593719,2.45827841759 -3.13518118858,1.66641819477,2.46384739876 -3.13519954681,1.67042756081,2.47844052315 -3.13222002983,1.67243814468,2.49199986458 -3.12923049927,1.67344391346,2.49777603149 -3.1132516861,1.6684564352,2.5003619194 -3.11327004433,1.67246556282,2.51495862007 -3.10429120064,1.67147707939,2.52352881432 -3.09231185913,1.66948890686,2.52911520004 -3.10032939911,1.67849695683,2.55069875717 -3.07634305954,1.66650640965,2.53948187828 -3.07936143875,1.6725153923,2.55706739426 -3.07538175583,1.67552602291,2.56963801384 -3.06040334702,1.67053866386,2.57321071625 -3.04742431641,1.66755068302,2.57779860497 -3.05644154549,1.67755830288,2.60038852692 -3.04046368599,1.67257118225,2.60296344757 -3.04247331619,1.67557585239,2.61274552345 -3.04249215126,1.68058538437,2.62832903862 -3.03051328659,1.67859733105,2.63391208649 -3.02453327179,1.67960810661,2.64449620247 -3.01255464554,1.67662000656,2.65007710457 -3.00257587433,1.67563188076,2.65765023232 -2.99659585953,1.67664253712,2.6682343483 -2.99860548973,1.68064713478,2.67802262306 -2.98362779617,1.67666006088,2.68158650398 -2.9856467247,1.68266928196,2.6991724968 -2.97866654396,1.68368017673,2.70876216888 -2.9696867466,1.68269121647,2.71635770798 -2.96970653534,1.68770110607,2.73292922974 -2.952729702,1.68271446228,2.73449540138 -2.95473837852,1.685718894,2.74428963661 -2.93676066399,1.68073189259,2.74388122559 -2.94177985191,1.68874108791,2.76544570923 -2.925801754,1.68375372887,2.76703071594 -2.91682338715,1.68376553059,2.77560091019 -2.91184329987,1.68577599525,2.78718900681 -2.89785504341,1.67978334427,2.78198957443 -2.89987421036,1.68579280376,2.8005669117 -2.88789606094,1.68380510807,2.8061413765 -2.87891769409,1.68381690979,2.81471157074 -2.87093806267,1.68382799625,2.82330465317 -2.86695885658,1.68683886528,2.83687019348 -2.86098027229,1.6888500452,2.84843850136 -2.85099077225,1.68485629559,2.84625196457 -2.84900999069,1.68886637688,2.86084246635 -2.83303403854,1.68487989902,2.86339211464 -2.83005332947,1.6878900528,2.87698483467 -2.82107496262,1.68790185452,2.88555574417 -2.81809449196,1.69091200829,2.89915060997 -2.80411624908,1.68792414665,2.90174508095 -2.80712556839,1.69292855263,2.91353297234 -2.79214859009,1.68894171715,2.91610217094 -2.79216837883,1.69495153427,2.93367862701 -2.77818989754,1.69096386433,2.93627095222 -2.7712123394,1.69297575951,2.94782114029 -2.75623464584,1.68898844719,2.94941020012 -2.76424241066,1.69699156284,2.96621012688 -2.74826478958,1.69200444221,2.96679735184 -2.74428534508,1.69601511955,2.98037648201 -2.73530721664,1.69602692127,2.98894953728 -2.71733045578,1.69004023075,2.98753023148 -2.72035002708,1.69804978371,3.00910115242 -2.71737003326,1.70206022263,3.02368712425 -2.72037863731,1.70706427097,3.03549003601 -2.71340084076,1.70907604694,3.04704761505 -2.70142245293,1.70708811283,3.05163955688 -2.6814467907,1.70010209084,3.04821014404 -2.66946840286,1.69811415672,3.05279898643 -2.66748929024,1.70312464237,3.06937026978 -2.65151143074,1.69813728333,3.06896924973 -2.64952135086,1.70014250278,3.07576417923 -2.6485414505,1.70515275002,3.09334206581 -2.63756394386,1.70516502857,3.09991168976 -2.62358665466,1.70117783546,3.10249233246 -2.62360644341,1.70818758011,3.12107872963 -2.61162853241,1.70619976521,3.12566590309 -2.60464024544,1.7052063942,3.12744498253 -2.60465955734,1.71121609211,3.14603567123 -2.58768367767,1.70622980595,3.14560246468 -2.57970428467,1.70724081993,3.15420532227 -2.57572627068,1.71125209332,3.16976189613 -2.55574989319,1.70426571369,3.16435432434 -2.55976915359,1.71427500248,3.18892884254 -2.56177806854,1.71927940845,3.20072841644 -2.54480266571,1.7142932415,3.20029091835 -2.54482150078,1.720302701,3.2188949585 -2.53784441948,1.72331464291,3.23144507408 -2.52486610413,1.72032678127,3.23404717445 -2.52588701248,1.72933721542,3.25660133362 -2.54289269447,1.74433839321,3.28740930557 -2.52491664886,1.73935198784,3.28498673439 -2.52193808556,1.74436306953,3.302546978 -2.52795624733,1.75637149811,3.33014297485 -2.51197934151,1.75238454342,3.32973098755 -2.50800013542,1.75639533997,3.34531140327 -2.50502157211,1.76240622997,3.36288118362 -2.49303412437,1.75741374493,3.35766863823 -2.4930536747,1.76442348957,3.37825965881 -2.18378138542,1.79881262779,3.66563725471 -2.1638071537,1.79182696342,3.65820717812 -2.14083194733,1.78084123135,3.64380574226 -2.12685585022,1.7788541317,3.6453871727 -2.11786913872,1.77586150169,3.64415478706 -2.12588810921,1.79387021065,3.68372917175 -2.09391522408,1.7748862505,3.65332770348 -2.08093905449,1.77289915085,3.65690159798 -2.07696032524,1.77891004086,3.67548680305 -1.78458726406,1.80124258995,3.87018632889 -1.7676024437,1.78925132751,3.84996438026 -1.74462795258,1.77726566792,3.82956528664 -1.72365415096,1.76728022099,3.81513929367 -1.70967805386,1.76529288292,3.81472873688 -1.7067002058,1.77530395985,3.84029746056 -1.69372427464,1.77431678772,3.842877388 -1.682736516,1.76732373238,3.83268475533 -1.67076158524,1.76833689213,3.83924055099 -1.65878403187,1.76734888554,3.84184789658 -1.6468077898,1.76736140251,3.84642958641 -1.62983334064,1.76137518883,3.84000253677 -1.62185525894,1.76538646221,3.85260081291 -1.61087989807,1.76739943027,3.86116194725 -1.60589230061,1.76940584183,3.86693882942 -1.59191524982,1.76541805267,3.86454796791 -1.57994031906,1.76643133163,3.87110471725 -1.56896317005,1.76744329929,3.87670397758 -1.55398738384,1.7634562254,3.87329268456 -1.54201185703,1.76446914673,3.87886166573 -1.52803635597,1.76148211956,3.87844228745 -1.52404689789,1.76348745823,3.88425111771 -1.51407027245,1.76549959183,3.8938331604 -1.501095891,1.76551318169,3.89838480949 -1.48911869526,1.76552510262,3.90098953247 -1.47914266586,1.76853752136,3.91156244278 -1.46516728401,1.7655506134,3.91114139557 -1.45817840099,1.76455664635,3.90895342827 -1.44820272923,1.76756930351,3.92051649094 -1.43722558022,1.76858103275,3.92611789703 -1.41925239563,1.76159548759,3.91667342186 -1.41227352619,1.7676063776,3.93228578568 -1.39729905128,1.76461982727,3.92985343933 -1.38332343102,1.76163268089,3.92843914032 -1.38033461571,1.76563835144,3.93922996521 -1.36635899544,1.76365125179,3.93781518936 -1.35238456726,1.76166462898,3.93837857246 -1.3434073925,1.7656763792,3.95096826553 -1.32743287086,1.76068985462,3.94454264641 -1.31345748901,1.75870287418,3.94312500954 --1.41523897648,1.79033255577,3.78432846069 --1.42621481419,1.78834366798,3.77590727806 --1.44319021702,1.79535531998,3.78550958633 --1.45316672325,1.79236614704,3.77509617805 --1.46414268017,1.79137730598,3.76667499542 --1.47413027287,1.79738330841,3.77547955513 --1.48110675812,1.78939402103,3.75604987144 --1.49608314037,1.79440510273,3.76066040993 --1.51005852222,1.7974165678,3.76024365425 --1.51603543758,1.78842711449,3.73881530762 --1.53601050377,1.7994389534,3.75542449951 --1.54798531532,1.79845070839,3.74798512459 --1.55597436428,1.80245578289,3.7528090477 --1.56495118141,1.79846644402,3.74039745331 --1.57692730427,1.79847753048,3.7349820137 --1.58490407467,1.79348826408,3.71956038475 --1.60687708855,1.80550086498,3.73713731766 --1.61385476589,1.79951107502,3.72073173523 --1.6198438406,1.80051612854,3.71954321861 --1.63481855392,1.80352795124,3.7201166153 --1.6487942934,1.80653905869,3.71970796585 --1.65777122974,1.80354976654,3.70729184151 --1.67274737358,1.80756080151,3.7098941803 --1.6817240715,1.80357146263,3.69747638702 --1.69469976425,1.80458259583,3.69405984879 --1.70268750191,1.80758833885,3.69585442543 --1.71666359901,1.80959928036,3.69545006752 --1.73163878918,1.81361079216,3.6960310936 --1.74961292744,1.81962275505,3.70260810852 --2.06500220299,1.83590102196,3.5649459362 --2.06498146057,1.82491016388,3.53752446175 --2.07596921921,1.82991576195,3.54433465004 --2.08894443512,1.83092689514,3.53890323639 --2.10292100906,1.83293759823,3.53649258614 --2.11689710617,1.83594834805,3.53408312798 --2.1218764782,1.83095741272,3.51769280434 --2.13385224342,1.83096849918,3.51025724411 --2.14882874489,1.83397912979,3.50985431671 --2.14981746674,1.82998406887,3.49763274193 --2.59198045731,1.86835503578,3.27768230438 --2.5859708786,1.85935926437,3.25745034218 --2.59794926643,1.86036872864,3.2520635128 --2.61792397499,1.86737978458,3.25463628769 --2.62490344048,1.86438882351,3.24223852158 --2.63288187981,1.8633980751,3.23083496094 --2.6578567028,1.87440919876,3.24042773247 --2.65483760834,1.86441743374,3.21501755714 --2.66982412338,1.87142312527,3.22281432152 --2.68280076981,1.87343347073,3.21638917923 --2.68478131294,1.86744189262,3.19799160957 --2.69375944138,1.86645126343,3.18758273125 --2.71873378754,1.87646234035,3.19616913795 --2.72171378136,1.8714710474,3.1787648201 --2.7396903038,1.87748122215,3.1793627739 --2.75167798996,1.8824865818,3.18316197395 --2.74865841866,1.8724950552,3.1577372551 --2.76163625717,1.87550473213,3.15233492851 --2.77561283112,1.87751483917,3.14691066742 --2.78459119797,1.87652409077,3.13650274277 --2.78757095337,1.87153279781,3.11909151077 --2.80555796623,1.88153851032,3.12989878654 --2.81353569031,1.87954807281,3.11747336388 --2.81751585007,1.87555658817,3.10207796097 --2.8394908905,1.88356733322,3.10565781593 --2.84947013855,1.88357627392,3.09726834297 --2.86344718933,1.88658607006,3.09185004234 --2.8714261055,1.88559520245,3.08044457436 --2.86841630936,1.87959933281,3.06622457504 --2.8863940239,1.88560891151,3.06684064865 --2.90037107468,1.88761866093,3.06142473221 --2.89835119247,1.87962722778,3.03799247742 --2.91432881355,1.88363683224,3.03559470177 --2.93230605125,1.88964653015,3.03519582748 --2.93228602409,1.88265502453,3.01477766037 --2.94227361679,1.88666033745,3.01455712318 --2.95325279236,1.88666915894,3.007168293 --2.95423269272,1.88167786598,2.98774504662 --2.97520923615,1.88868772984,2.99034953117 --2.98718738556,1.89069700241,2.98294019699 --2.99316596985,1.88770616055,2.96851229668 --3.00414443016,1.88871538639,2.96010398865 --3.01113367081,1.89071989059,2.95791006088 --3.02211236954,1.89172899723,2.94950246811 --3.02309179306,1.88573777676,2.93007230759 --3.05006814003,1.89774763584,2.93868970871 --3.04704833031,1.88875615597,2.91525697708 --3.05802679062,1.88976514339,2.90684962273 --3.06901574135,1.89376986027,2.90866041183 --3.07399535179,1.89177846909,2.8942501545 --3.09297180176,1.89778828621,2.89282917976 --3.10195183754,1.89779675007,2.88344454765 --3.10493183136,1.8928052187,2.86703109741 --3.11391091347,1.89281404018,2.8566236496 --3.12988805771,1.89782357216,2.85220384598 --3.12987756729,1.8938280344,2.84198260307 --3.14785575867,1.89983713627,2.84058976173 --3.15883350372,1.90084648132,2.83116483688 --3.16781282425,1.9008551836,2.82075858116 --3.183791399,1.9048640728,2.81736707687 --3.18877100945,1.90287256241,2.80295300484 --3.19675064087,1.90188133717,2.79154515266 --3.19973993301,1.90088582039,2.78432750702 --3.20871901512,1.90089440346,2.77392148972 --3.21869826317,1.90190315247,2.76451802254 --3.23567724228,1.90691184998,2.76213431358 --3.25065422058,1.90992128849,2.75570178032 --3.25863385201,1.90892994404,2.7442946434 --3.26761221886,1.90893888474,2.73286771774 --3.26660275459,1.90594279766,2.72265934944 --3.27958226204,1.90895140171,2.71626806259 --3.28556203842,1.90695989132,2.70285320282 --3.28954267502,1.90396785736,2.68845391273 --3.30852007866,1.90997707844,2.68604016304 --3.31150078773,1.9069852829,2.67063641548 --3.32747840881,1.91099441051,2.66521382332 --3.33246874809,1.91199851036,2.66102576256 --3.33844852448,1.91000676155,2.64760971069 --3.34742832184,1.9100151062,2.63720631599 --3.35740804672,1.91102349758,2.62780737877 --3.37038588524,1.91403269768,2.61937594414 --3.36436843872,1.90504002571,2.5969722271 --3.37035799026,1.90604436398,2.59276556969 --3.39433503151,1.91505348682,2.59436535835 --3.39031672478,1.90806126595,2.57294440269 --3.40529561043,1.91206991673,2.56754875183 --3.41227531433,1.91107809544,2.55513548851 --3.42825365067,1.91508686543,2.54972362518 --3.42823529243,1.9100946188,2.53231906891 --3.43622517586,1.91309869289,2.5301258564 --3.44320511818,1.91210711002,2.51771235466 --3.45618319511,1.91411590576,2.50928640366 --3.46216440201,1.91412365437,2.49689054489 --3.47214341164,1.91413223743,2.48647141457 --3.48612308502,1.91814029217,2.48007774353 --3.49310302734,1.91714859009,2.46766448021 --3.50109195709,1.92015302181,2.46445083618 --3.5120716095,1.92116129398,2.45504045486 --3.51305294037,1.91716897488,2.43863511086 --3.52103352547,1.91717708111,2.42722845078 --3.53601241112,1.92118537426,2.42082214355 --3.5349946022,1.91619277,2.40342473984 --3.54497408867,1.91720116138,2.39300751686 --3.55496239662,1.92020571232,2.39078760147 --3.56394314766,1.92121350765,2.38038897514 --3.57492280006,1.92322158813,2.37098121643 --3.57790470123,1.92022919655,2.35658621788 --3.58588385582,1.9202375412,2.34415531158 --3.59386444092,1.92024552822,2.33274960518 --3.61484289169,1.92825376987,2.33035063744 --3.60683488846,1.92125737667,2.31613659859 --3.62781357765,1.92926561832,2.31374001503 --3.62779474258,1.92527341843,2.29631781578 --3.64177441597,1.92828130722,2.28891515732 --3.64475512505,1.92528927326,2.27349233627 --3.65473628044,1.9272967577,2.2641055584 --3.66271615028,1.92730498314,2.25167632103 --3.66670703888,1.92730867863,2.24648690224 --3.67568707466,1.92831659317,2.23506689072 --3.68766641617,1.93132472038,2.22565031052 --3.69264888763,1.93033182621,2.21326899529 --3.70062851906,1.93033993244,2.20084047318 --3.70661020279,1.92934727669,2.18844342232 --3.71260070801,1.93135106564,2.18424844742 --3.72657990456,1.93435919285,2.17582917213 --3.72856163979,1.93136668205,2.16041779518 --3.74054145813,1.93437457085,2.1510052681 --3.74352312088,1.93138182163,2.13660311699 --3.75150442123,1.93238937855,2.12520098686 --3.75848531723,1.93239700794,2.1127884388 --3.77147459984,1.93740093708,2.1125934124 --3.77445554733,1.93540871143,2.09716486931 --3.78543663025,1.93741607666,2.08777070045 --3.79541730881,1.9394235611,2.07736635208 --3.7983982563,1.93643128872,2.06193685532 --3.80138039589,1.93543863297,2.04753184319 --3.81436109543,1.93844592571,2.03913664818 --3.82335066795,1.9414498806,2.03592920303 --3.82633280754,1.93945717812,2.0215241909 --3.83631396294,1.94146454334,2.01112246513 --3.83829545975,1.93847191334,1.9957048893 --3.85127544403,1.94247961044,1.986287117 --3.85625720024,1.94148683548,1.97287881374 --3.85823988914,1.93849384785,1.95848608017 --3.86822891235,1.94249796867,1.95526862144 --3.88120913506,1.94550549984,1.94585418701 --3.88219189644,1.94251251221,1.93044865131 --3.88717341423,1.94251978397,1.9170396328 --3.89515542984,1.94252681732,1.90564262867 --3.90313601494,1.94353437424,1.89321935177 --3.91111779213,1.94454133511,1.88182282448 --3.91310858727,1.94354510307,1.87461161613 --3.92708969116,1.94755220413,1.86621534824 --3.93407011032,1.94755983353,1.85278058052 --3.93805289268,1.94756674767,1.83938467503 --3.94603490829,1.9475736618,1.82799005508 --3.95901584625,1.95158076286,1.81858408451 --3.96300649643,1.95258438587,1.81237375736 --3.96998810768,1.95259141922,1.79996681213 --3.97596955299,1.95259869099,1.78654587269 --3.97495222092,1.94860577583,1.7701331377 --3.993932724,1.95561277866,1.76373565197 --3.99491524696,1.95361983776,1.74832379818 --4.00289678574,1.95362699032,1.73590517044 --4.00588798523,1.95363032818,1.72970831394 --4.01687002182,1.95663714409,1.71930706501 --4.02385187149,1.95764398575,1.70690155029 --4.02483415604,1.95465099812,1.69148802757 --4.03181648254,1.95565783978,1.67908251286 --4.04279851913,1.95866465569,1.66868376732 --4.04577970505,1.9566719532,1.65324544907 --4.06176996231,1.96367514133,1.65305864811 --4.05375337601,1.95668196678,1.63364052773 --4.06073570251,1.95768880844,1.62123596668 --4.07671737671,1.96269547939,1.6128371954 --4.07870054245,1.96070218086,1.59843695164 --4.08768177032,1.96270918846,1.58601117134 --4.09466457367,1.96371591091,1.57360851765 --4.08365726471,1.95671916008,1.56140565872 --4.104637146,1.96372616291,1.55398380756 --4.1046204567,1.96173274517,1.53857672215 --4.09860372543,1.95573973656,1.52015221119 --4.10858678818,1.95874595642,1.50977122784 --4.12856817245,1.96575248241,1.50236666203 --4.12055110931,1.95875966549,1.48293352127 --4.12254333496,1.95876264572,1.47674822807 --4.14152383804,1.96576929092,1.46833050251 --4.13350820541,1.95877599716,1.44992125034 --4.13349151611,1.95678257942,1.43450951576 --4.15347290039,1.963788867,1.42711293697 --4.14645671844,1.9587957859,1.40868914127 --4.15443897247,1.95980226994,1.39627826214 --4.17042970657,1.96680521965,1.39509117603 --4.17241334915,1.96481156349,1.38068664074 --4.16839599609,1.96081852913,1.36325740814 --4.1833782196,1.96582460403,1.35386312008 --4.16636371613,1.95483136177,1.33244657516 --4.18434429169,1.96183788776,1.32302451134 --4.19532823563,1.96484375,1.31264364719 --4.18132019043,1.95684754848,1.29941487312 --4.1893029213,1.95885396004,1.28700625896 --4.2022857666,1.96285998821,1.27660787106 --4.19826936722,1.95886659622,1.2601994276 --4.21125125885,1.96287298203,1.24877488613 --4.22223424911,1.96587908268,1.23737001419 --4.20621919632,1.95588600636,1.21695435047 --4.20821142197,1.95588886738,1.21076869965 --4.23619222641,1.96789467335,1.20435523987 --4.22017717361,1.95790159702,1.18393492699 --4.22416067123,1.9579076767,1.17053580284 --4.24214315414,1.96391355991,1.16113054752 --4.23912811279,1.96091973782,1.14573502541 --4.26611661911,1.97292244434,1.14551019669 --4.27709960938,1.97592830658,1.13411259651 --4.27008390427,1.97093498707,1.11669433117 --4.271068573,1.96994102001,1.10229361057 --4.28905105591,1.9759465456,1.09289813042 --4.27503585815,1.96795344353,1.07347524166 --4.28101921082,1.96895956993,1.06006264687 --4.29700994492,1.97496211529,1.05685484409 --4.28799438477,1.96996867657,1.03944551945 --4.29597806931,1.97097444534,1.02704715729 --4.30796146393,1.97497999668,1.01564764977 --4.30094575882,1.96998667717,0.998220205307 --4.30692911148,1.97099268436,0.984809279442 --4.30491352081,1.96899902821,0.969399511814 --4.30690526962,1.96900212765,0.962186932564 --4.32388973236,1.97500693798,0.952812194824 --4.32787275314,1.97501313686,0.938388645649 --4.32085752487,1.97001945972,0.9219840765 --4.32884073257,1.97302544117,0.908560693264 --4.32882547379,1.97103130817,0.894163548946 --4.33280897141,1.97103738785,0.879739463329 --4.33380079269,1.97104036808,0.872533857822 --4.34078550339,1.97304570675,0.860147118568 --4.33876991272,1.97005188465,0.84473335743 --4.33975458145,1.97005784512,0.830327868462 --4.34173774719,1.96906423569,0.814887464046 --4.34772253036,1.97006940842,0.802508175373 --4.35870695114,1.97407495975,0.790099263191 --4.35269880295,1.97007834911,0.78087836504 --4.35768318176,1.97108399868,0.767477273941 --4.3656668663,1.9740896225,0.754059135914 --4.36865091324,1.97409546375,0.739641904831 --4.36763620377,1.97210121155,0.725247144699 --4.37262105942,1.9731066227,0.711847186089 --4.37561273575,1.97410964966,0.704630315304 --4.37659740448,1.97311532497,0.690223932266 --4.37758207321,1.9721211195,0.675817191601 --4.37656641006,1.97012722492,0.660391867161 --4.38055086136,1.97113263607,0.646997630596 --4.39053487778,1.97513794899,0.633573591709 --4.38752031326,1.97214365005,0.619186341763 --4.39050531387,1.9721493721,0.604769051075 --4.38649749756,1.97015249729,0.596557796001 --4.40248250961,1.97615706921,0.585165679455 --4.39246702194,1.97016346455,0.568751454353 --4.39845132828,1.97216916084,0.554320335388 --4.40143537521,1.97217476368,0.539903342724 --4.40342140198,1.97218000889,0.526519596577 --4.41040658951,1.97518503666,0.513114392757 --4.41139888763,1.97518789768,0.505908250809 --4.403383255,1.97019433975,0.489479213953 --4.41036844254,1.97219955921,0.476074963808 --4.41435241699,1.97320497036,0.461654365063 --4.4183382988,1.97421002388,0.448263019323 --4.41632318497,1.97221601009,0.432836622 --4.40831613541,1.96821928024,0.424634307623 --4.41630077362,1.97022426128,0.411228358746 --4.40528535843,1.96423089504,0.394802778959 --4.40027141571,1.96123659611,0.380412429571 --4.40525627136,1.96324193478,0.365987449884 --4.41224145889,1.96524679661,0.352586001158 --4.41222667694,1.96425235271,0.33817833662 --4.40721893311,1.96225559711,0.329960465431 --4.41820430756,1.96626031399,0.316548079252 --4.41219043732,1.96326601505,0.302157431841 --4.41417503357,1.96327137947,0.287743091583 --4.4211602211,1.96527647972,0.273315280676 --4.42414617538,1.96628141403,0.25992795825 --4.42413187027,1.96528673172,0.245519578457 --4.41512441635,1.9612903595,0.237308382988 --4.42910957336,1.96729457378,0.22389420867 --4.42709493637,1.96529996395,0.209490299225 --4.42808103561,1.96530532837,0.195078969002 --4.44006633759,1.97030949593,0.181673496962 --4.43605136871,1.96831548214,0.166243985295 --4.43703699112,1.96832072735,0.151833131909 --4.43003034592,1.96432387829,0.144642010331 --4.43301534653,1.96532893181,0.130226805806 --4.43100166321,1.96433436871,0.115820430219 --4.43498706818,1.96533930302,0.101404026151 --4.4339723587,1.96434473991,0.0869957134128 --4.43695831299,1.96534967422,0.0725812986493 --4.43594408035,1.96435499191,0.0581726655364 --4.43493747711,1.96435773373,0.0509686507285 --4.43892288208,1.96536254883,0.0365535803139 --4.44290876389,1.96736741066,0.0221388526261 --4.43689489365,1.96437311172,0.0077349212952 --4.44488143921,1.96737718582,-0.00565363746136 --4.43186616898,1.96138393879,-0.0210823081434 --4.4348526001,1.96238863468,-0.0354958027601 --4.4408454895,1.9643907547,-0.0427052937448 --4.43183135986,1.96039664745,-0.0571107231081 --4.43581724167,1.96240139008,-0.0715243890882 --4.43980312347,1.9644061327,-0.0859373882413 --4.43278932571,1.96041190624,-0.100345999002 --4.43177509308,1.95941710472,-0.114757366478 --4.43476200104,1.96142184734,-0.129169791937 --4.42975473404,1.95942497253,-0.136375293136 --4.43774080276,1.96242892742,-0.150787129998 --4.42972707748,1.95943498611,-0.165199577808 --4.43571329117,1.9614392519,-0.179610356688 --4.43969964981,1.9634437561,-0.194020867348 --4.43368530273,1.96044945717,-0.208434388041 --4.4246711731,1.95645558834,-0.222850576043 --4.43366479874,1.96045684814,-0.230052128434 --4.43565177917,1.96146154404,-0.244462713599 --4.42963886261,1.9594669342,-0.257849365473 --4.42262458801,1.95547270775,-0.272266894579 --4.42061090469,1.95447790623,-0.286681413651 --4.42559719086,1.95748209953,-0.301089555025 --4.43059110641,1.95948386192,-0.308290481567 --4.42657709122,1.95848929882,-0.322707116604 --4.41956281662,1.95449519157,-0.337127655745 --4.4265499115,1.95849895477,-0.351531416178 --4.4235367775,1.95750415325,-0.365947753191 --4.42352294922,1.95750892162,-0.380359977484 --4.41750907898,1.9545147419,-0.39478161931 --4.41650247574,1.95451724529,-0.401989668608 --4.41448974609,1.95452201366,-0.415376543999 --4.42447662354,1.95952546597,-0.43080046773 --4.41646337509,1.95553100109,-0.444197952747 --4.41044950485,1.95353674889,-0.458622515202 --4.40643501282,1.95154213905,-0.473043560982 --4.41842412949,1.95754480362,-0.487430095673 --4.41741752625,1.95754718781,-0.494638264179 --4.41340351105,1.95555257797,-0.50905919075 --4.41239023209,1.95555734634,-0.52347356081 --4.40937709808,1.95456254482,-0.537892997265 --4.39936304092,1.95056855679,-0.551301777363 --4.40935182571,1.95557141304,-0.56568723917 --4.40033721924,1.95257747173,-0.580124258995 --4.40133142471,1.95357966423,-0.587327599525 --4.39831733704,1.9525847435,-0.601748406887 --4.39730548859,1.95258915424,-0.615134060383 --4.3982925415,1.95359349251,-0.629542827606 --4.39828014374,1.95459794998,-0.643954575062 --4.39726686478,1.95460271835,-0.65836918354 --4.39025259018,1.95160841942,-0.672804176807 --4.38724660873,1.95061087608,-0.678991019726 --4.39323425293,1.95461452007,-0.694410920143 --4.38622093201,1.95161998272,-0.707817912102 --4.38120746613,1.9496254921,-0.722247779369 --4.38519573212,1.95262885094,-0.736643970013 --4.37618207932,1.9486348629,-0.750060677528 --4.38017034531,1.95163846016,-0.764456033707 --4.39316558838,1.95863842964,-0.773667275906 --4.37415027618,1.9496461153,-0.78609675169 --4.37213802338,1.94965064526,-0.79948669672 --4.37512588501,1.95265448093,-0.814913749695 --4.37011289597,1.95065951347,-0.828316509724 --4.3660993576,1.94966471195,-0.842744708061 --4.37508916855,1.95466721058,-0.858142375946 --4.35107898712,1.9436737299,-0.862371206284 --4.3630695343,1.95067548752,-0.877754330635 --4.35905599594,1.949680686,-0.892183184624 --4.35004329681,1.94668626785,-0.904578864574 --4.34602975845,1.94569134712,-0.919008910656 --4.3510184288,1.94869458675,-0.934422194958 --4.34100532532,1.94570052624,-0.946825325489 --4.33699893951,1.94370317459,-0.95302182436 --4.34898805618,1.95070528984,-0.970454692841 --4.32997274399,1.94371306896,-0.981879472733 --4.3329615593,1.94571638107,-0.996272087097 --4.33995103836,1.94971907139,-1.01167035103 --4.32293653488,1.94372630119,-1.0230884552 --4.31992959976,1.94272899628,-1.03031027317 --4.33692073822,1.95172965527,-1.04770636559 --4.31290435791,1.9417386055,-1.05814015865 --4.31389331818,1.94374227524,-1.0725427866 --4.32388353348,1.94874417782,-1.08894693851 --4.30886936188,1.94375109673,-1.10036039352 --4.30885791779,1.94475507736,-1.11476767063 --4.30385112762,1.94375801086,-1.1209744215 --4.29283714294,1.93876421452,-1.13339447975 --4.29682636261,1.94276726246,-1.14880514145 --4.29881477356,1.9447709322,-1.16422736645 --4.28580093384,1.93977725506,-1.17563426495 --4.28578948975,1.94178116322,-1.19004118443 --4.28877878189,1.94378435612,-1.20545518398 --4.27677106857,1.93878877163,-1.20965504646 --4.26975822449,1.93779408932,-1.22308218479 --4.27874851227,1.94379591942,-1.23948156834 --4.26373386383,1.93780303001,-1.25090873241 --4.27072381973,1.94280517101,-1.26732063293 --4.26071023941,1.93881130219,-1.27974152565 --4.24969768524,1.93581724167,-1.29114305973 --4.24468517303,1.93482208252,-1.30455756187 --4.24868059158,1.93782293797,-1.31275820732 --4.23266506195,1.9318305254,-1.3242007494 --4.22765254974,1.93083536625,-1.33761644363 --4.23964452744,1.93783605099,-1.35501194 --4.22363042831,1.93284344673,-1.3654294014 --4.21861791611,1.93184828758,-1.37884545326 --4.22761487961,1.93684780598,-1.38803100586 --4.20459890366,1.92685675621,-1.39645195007 --4.21158885956,1.93285882473,-1.41388380527 --4.20757722855,1.93286323547,-1.42729187012 --4.19656419754,1.92886948586,-1.43870258331 --4.18955183029,1.9268746376,-1.45110869408 --4.19654226303,1.9328764677,-1.46853625774 --4.18953514099,1.92987990379,-1.47374129295 --4.19252538681,1.93288254738,-1.4891449213 --4.18451309204,1.93188810349,-1.50156068802 --4.16349697113,1.92289662361,-1.50998055935 --4.16948795319,1.92789852619,-1.52638459206 --4.16747665405,1.92890250683,-1.54080379009 --4.15646362305,1.92590868473,-1.55222153664 --4.15445756912,1.92591071129,-1.55841195583 --4.15544700623,1.92791390419,-1.57383096218 --4.14043283463,1.92292106152,-1.58426058292 --4.13342046738,1.92192625999,-1.59667158127 --4.13541078568,1.92492902279,-1.61208021641 --4.13640022278,1.92693209648,-1.6274971962 --4.11838579178,1.92093992233,-1.63590443134 --4.12838315964,1.92693912983,-1.64711737633 --4.10836696625,1.91894769669,-1.65554666519 --4.10935783386,1.92195045948,-1.66993498802 --4.10334539413,1.92095541954,-1.68336594105 --4.0983338356,1.92095994949,-1.6967869997 --4.09232234955,1.91996467113,-1.70919001102 --4.08631086349,1.91896939278,-1.72159337997 --4.08730554581,1.92097079754,-1.72980940342 --4.06828975677,1.91397917271,-1.73823952675 --4.0652794838,1.91498303413,-1.75164055824 --4.05526638031,1.91198897362,-1.7630610466 --4.05625629425,1.91499173641,-1.77847445011 --4.05124521255,1.91499626637,-1.79189693928 --4.04423332214,1.91400134563,-1.80431365967 --4.0372262001,1.91100478172,-1.80850493908 --4.03021430969,1.91100978851,-1.82092320919 --4.025203228,1.91101431847,-1.83434665203 --4.02419281006,1.91201746464,-1.84875166416 --4.02018213272,1.91302156448,-1.86216330528 --4.007168293,1.90902853012,-1.87259590626 --3.99815583229,1.9070340395,-1.88401091099 --4.00615406036,1.91203296185,-1.8941962719 --3.99113893509,1.90704035759,-1.90362691879 --3.99713158607,1.91304147243,-1.92103052139 --4.00512552261,1.92004179955,-1.93943536282 --3.99711322784,1.91804695129,-1.95083761215 --3.99010157585,1.91705191135,-1.96325612068 --3.99409365654,1.92205357552,-1.98067772388 --3.98208498955,1.91705846786,-1.98288118839 --3.98107528687,1.92006158829,-1.9983086586 --3.97206282616,1.91806709766,-2.00972485542 --3.96505117416,1.91707205772,-2.02214407921 --3.95804023743,1.91607677937,-2.03353619576 --3.96103191376,1.92107856274,-2.05096554756 --3.94401717186,1.9150865078,-2.05837678909 --3.94201159477,1.91608858109,-2.06559514999 --3.94500398636,1.92009007931,-2.08199477196 --3.92898917198,1.91509783268,-2.09042334557 --3.92397880554,1.9151018858,-2.10281801224 --3.92396950722,1.91810464859,-2.1192548275 --3.90895557404,1.91311192513,-2.12664651871 --3.9109518528,1.91611254215,-2.13586521149 --3.91094350815,1.91911506653,-2.15127325058 --3.89692878723,1.91512215137,-2.16070795059 --3.8849158287,1.91112864017,-2.17011642456 --3.88390731812,1.91413128376,-2.18451046944 --3.87389445305,1.91213715076,-2.19594717026 --3.86288142204,1.9101433754,-2.20637202263 --3.86487841606,1.91214370728,-2.21456003189 --3.85686635971,1.91114902496,-2.22699689865 --3.84485316277,1.90815544128,-2.23641014099 --3.85284852982,1.91615486145,-2.25580811501 --3.83183121681,1.9081646204,-2.26124358177 --3.83082318306,1.91116702557,-2.27563452721 --3.83081459999,1.91416943073,-2.29206299782 --3.81480383873,1.90717601776,-2.29126954079 --3.8047914505,1.90518188477,-2.30168437958 --3.81478762627,1.9141805172,-2.3230984211 --3.7937707901,1.90619027615,-2.32751607895 --3.78776025772,1.90619456768,-2.33992576599 --3.7907538414,1.91119551659,-2.35733294487 --3.77073693275,1.90520501137,-2.36276817322 --3.76272916794,1.9022090435,-2.36699581146 --3.76472234726,1.90621030331,-2.3833899498 --3.75471019745,1.90521609783,-2.39380812645 --3.75570297241,1.90921771526,-2.41021561623 --3.74769186974,1.90822267532,-2.42162919044 --3.7326772213,1.90423035622,-2.4290471077 --3.72566628456,1.90423500538,-2.4414730072 --3.72866368294,1.90723478794,-2.45168828964 --3.71064805984,1.90124368668,-2.45710372925 --3.70363712311,1.90124833584,-2.46952986717 --3.70663142204,1.90624892712,-2.48692655563 --3.69161677361,1.90225660801,-2.49435019493 --3.68160438538,1.9002623558,-2.5047724247 --3.68860077858,1.90826141834,-2.52517938614 --3.67459058762,1.90226769447,-2.52438092232 --3.66557860374,1.90127325058,-2.53581380844 --3.66257023811,1.90427613258,-2.55022621155 --3.64355349541,1.89728546143,-2.55464363098 --3.64254617691,1.90028750896,-2.57004785538 --3.63953733444,1.90329051018,-2.58548498154 --3.62152147293,1.89729940891,-2.58988976479 --3.62151813507,1.89930033684,-2.59809589386 --3.62051081657,1.90230214596,-2.61349749565 --3.60649633408,1.89930975437,-2.62194037437 --3.59948635101,1.89931416512,-2.63334131241 --3.60448265076,1.90531349182,-2.65273976326 --3.57646036148,1.89432692528,-2.65219640732 --3.56144571304,1.89033472538,-2.65861034393 --3.56544470787,1.89433383942,-2.66982078552 --3.54742836952,1.88934290409,-2.67423772812 --3.53241348267,1.88435089588,-2.68065476418 --3.53941130638,1.89334928989,-2.70206403732 --3.53540277481,1.89435231686,-2.71546316147 --3.52939295769,1.89535629749,-2.72889733315 --3.51938080788,1.89436209202,-2.73932743073 --1.02243149281,0.525695323944,-1.18456614017 --2.56830048561,1.86390161514,-3.68238162994 --2.54327249527,1.8529188633,-3.67180514336 --2.54527640343,1.86291468143,-3.6982486248 --2.53026008606,1.8599241972,-3.70066785812 --2.52425479889,1.86292648315,-3.71508431435 --2.52025079727,1.86392855644,-3.72028017044 --2.500228405,1.85694181919,-3.71671700478 --2.49722671509,1.86294174194,-3.7351295948 --2.48621559143,1.86294794083,-3.74254226685 -2.20991396904,1.80897879601,-3.15401005745 -2.20991206169,1.80497765541,-3.14320135117 -2.22192525864,1.80598115921,-3.13761997223 -2.23994636536,1.81098794937,-3.14201855659 -2.24494957924,1.80598807335,-3.12643051147 -2.24995279312,1.80098831654,-3.11084461212 -2.27197980881,1.81099689007,-3.12025332451 -2.28098869324,1.80899906158,-3.11066436768 -2.29200196266,1.81400346756,-3.11585736275 -2.29099726677,1.80400085449,-3.09128236771 -2.31102108955,1.81100833416,-3.09768748283 -2.32103157043,1.81101119518,-3.09106993675 -2.33304429054,1.8120149374,-3.08548569679 -2.35106539726,1.81802141666,-3.08888816833 -2.35606884956,1.81302189827,-3.0733089447 -2.36407828331,1.81602454185,-3.07449269295 -2.36707949638,1.80902421474,-3.0549390316 -2.38409924507,1.81503033638,-3.0583126545 -2.40011715889,1.81903576851,-3.05871486664 -2.79854774475,1.82716047764,-2.77428030968 -2.79654717445,1.81816053391,-2.75271105766 -2.79955172539,1.81416189671,-2.73810553551 -2.80856156349,1.81716477871,-2.73733067513 -2.81056499481,1.81116604805,-2.72074866295 -2.83258748055,1.82017278671,-2.72613382339 -2.84460091591,1.82217681408,-2.71955609322 -3.24517846107,1.75337982178,-2.06839966774 -3.24418449402,1.7483830452,-2.05281257629 -3.22818231583,1.73538482189,-2.02527570724 -3.23319220543,1.73438870907,-2.01466917992 -3.24420571327,1.73539340496,-2.00709176064 -3.24221205711,1.73039674759,-1.99052155018 -3.24922299385,1.73040091991,-1.98092556 -3.25923252106,1.73440384865,-1.98013567924 -3.25823879242,1.73040699959,-1.96553194523 -3.26425004005,1.7294113636,-1.95397341251 -3.28026652336,1.73441660404,-1.95037305355 -3.28127408028,1.73042023182,-1.93678033352 -3.28228259087,1.72742414474,-1.92221689224 -3.29129099846,1.73042678833,-1.92140543461 -3.28929758072,1.72543025017,-1.90581810474 -3.30131220818,1.72843527794,-1.89825487137 -3.30932402611,1.7294396162,-1.88964867592 -3.30833077431,1.72444319725,-1.87505447865 -3.31634306908,1.72544789314,-1.86547684669 -3.33235907555,1.73045289516,-1.86186754704 -3.32435965538,1.72445452213,-1.8481259346 -3.33337187767,1.72545897961,-1.84050881863 -3.34338521957,1.72746384144,-1.83193612099 -3.33338832855,1.71846711636,-1.8113656044 -3.33339595795,1.71447098255,-1.79776823521 -3.35041284561,1.72047626972,-1.7941712141 -3.34041643143,1.71147978306,-1.77360844612 -3.34542369843,1.71248233318,-1.76883745193 -3.36243963242,1.71848726273,-1.76620900631 -3.35944700241,1.71349155903,-1.74965167046 -3.36745905876,1.71349596977,-1.74104678631 -3.37847304344,1.71650099754,-1.73346066475 -3.36947751045,1.70850479603,-1.71389698982 -3.378490448,1.70950949192,-1.70530831814 -3.38949990273,1.71351242065,-1.70451653004 -3.40251493454,1.71751749516,-1.69793152809 -3.39452004433,1.70952141285,-1.67936122417 -3.40653419495,1.71352636814,-1.67275941372 -3.40054059029,1.70653057098,-1.65519583225 -3.40955352783,1.70853543282,-1.64660537243 -3.41856145859,1.71153771877,-1.64577710629 -3.41056704521,1.70354199409,-1.62721598148 -3.42558288574,1.70854723454,-1.62162923813 -3.4395980835,1.71355223656,-1.6160248518 -3.42159938812,1.70055603981,-1.59246373177 -3.43861603737,1.70656144619,-1.58787548542 -3.4526309967,1.71056628227,-1.58226895332 -3.44663357735,1.70556867123,-1.57150781155 -3.45164489746,1.7055734396,-1.56091427803 -3.46265864372,1.70857834816,-1.55332052708 -3.45566534996,1.70158290863,-1.53575921059 -3.46567845345,1.70358777046,-1.52815043926 -3.46868991852,1.70259284973,-1.51558876038 -3.46469783783,1.69759750366,-1.50001645088 -3.47370624542,1.70060014725,-1.49820959568 -3.48572063446,1.70360529423,-1.49062800407 -3.48172903061,1.69861018658,-1.47505843639 -3.48373913765,1.69761478901,-1.46345436573 -3.49375295639,1.69961988926,-1.45487356186 -3.49276232719,1.69662475586,-1.44128906727 -3.49777388573,1.69662976265,-1.43069851398 -3.5087826252,1.70063221455,-1.42988407612 -3.50179052353,1.69363749027,-1.41234135628 -3.50180029869,1.69164228439,-1.39974367619 -3.51981711388,1.69764745235,-1.39514744282 -3.5188267231,1.69465255737,-1.38156759739 -3.51583600044,1.69065761566,-1.36699306965 -3.52984595299,1.69666016102,-1.36718297005 -3.51985239983,1.68866527081,-1.34960913658 -3.53186750412,1.69167077541,-1.34105145931 -3.54688286781,1.69767582417,-1.33543777466 -3.53989100456,1.69168102741,-1.31887710094 -3.54190158844,1.68968605995,-1.30728018284 -3.55291557312,1.69269108772,-1.29967474937 -3.54591846466,1.6876938343,-1.28989863396 -3.55593252182,1.69069910049,-1.28131091595 -3.55894398689,1.68970441818,-1.26972782612 -3.55995488167,1.68770968914,-1.25715136528 -3.56196665764,1.68671524525,-1.24458825588 -3.56997990608,1.68772065639,-1.23500573635 -3.57398581505,1.6887229681,-1.23118245602 -3.57899904251,1.68872869015,-1.21962511539 -3.59201407433,1.69273388386,-1.21203839779 -3.58102059364,1.68573927879,-1.19544529915 -3.58603310585,1.685744524,-1.18485713005 -3.59504723549,1.68775010109,-1.17528438568 -3.59805870056,1.68675553799,-1.16370379925 -3.60406589508,1.68875813484,-1.15990257263 -3.61508059502,1.69176352024,-1.15131914616 -3.60708904266,1.68676900864,-1.13573861122 -3.61710262299,1.68877446651,-1.1271430254 -3.61611318588,1.68677973747,-1.11454927921 -3.61512446404,1.68378567696,-1.10098934174 -3.62513852119,1.68679094315,-1.09239208698 -3.63914871216,1.69179368019,-1.09061276913 -3.6341574192,1.68779909611,-1.07700848579 -3.64217114449,1.68980455399,-1.06741917133 -3.6501853466,1.69181036949,-1.05686128139 -3.64319419861,1.68681609631,-1.04227125645 -3.64420604706,1.68482196331,-1.02970409393 -3.64821839333,1.68482732773,-1.01910412312 -3.6552259922,1.68683004379,-1.0153080225 -3.64923548698,1.68183600903,-1.00073373318 -3.65824985504,1.68484163284,-0.991152882576 -3.6552605629,1.68084764481,-0.977579712868 -3.67127609253,1.68685269356,-0.97097069025 -3.67528891563,1.68685853481,-0.959402501583 -3.6632912159,1.68086183071,-0.949610114098 -3.67030501366,1.6818677187,-0.939040601254 -3.67931842804,1.68487286568,-0.930423796177 -3.68433141708,1.68587851524,-0.91983294487 -3.67834186554,1.6808848381,-0.905268669128 -3.6853556633,1.68189072609,-0.894697725773 -3.69036841393,1.68289637566,-0.884106934071 -3.69537591934,1.68489921093,-0.879318058491 -3.69938826561,1.68490481377,-0.868717610836 -3.69439983368,1.68091154099,-0.854167282581 -3.69741177559,1.68091702461,-0.843558371067 -3.70742630959,1.68392276764,-0.833978712559 -3.7004365921,1.67892932892,-0.819414079189 -3.70544981956,1.67993509769,-0.808822989464 -3.71445822716,1.68293786049,-0.805033862591 -3.71747016907,1.68294346333,-0.794424533844 -3.70848107338,1.67695045471,-0.778880655766 -3.71849489212,1.68095576763,-0.770264089108 -3.71150588989,1.67596256733,-0.755706608295 -3.72352027893,1.67996788025,-0.74710547924 -3.72853446007,1.68097424507,-0.73554623127 -3.72153902054,1.67597782612,-0.72775810957 -3.73255300522,1.68098306656,-0.719145894051 -3.73756623268,1.68098890781,-0.708552956581 -3.73757910728,1.67999541759,-0.69598788023 -3.72758936882,1.67400228977,-0.681415081024 -3.74260497093,1.68000781536,-0.672829866409 -3.73961043358,1.67701113224,-0.666042983532 -3.73462152481,1.67401754856,-0.653443396091 -3.74463701248,1.67702376842,-0.642886459827 -3.74965000153,1.67802965641,-0.632292449474 -3.75066280365,1.67703592777,-0.620703756809 -3.76067733765,1.68104159832,-0.611109614372 -3.76069045067,1.68004822731,-0.598547399044 -3.76069664955,1.67905139923,-0.592749774456 -3.76371002197,1.67905771732,-0.581174731255 -3.75672149658,1.67506480217,-0.56760185957 -3.75773429871,1.67407107353,-0.556014895439 -3.7777504921,1.68207609653,-0.548412621021 -3.76476097107,1.67508363724,-0.533838927746 -3.75977230072,1.67109036446,-0.521249771118 -3.787784338,1.68409180641,-0.520453333855 -3.764793396,1.67210006714,-0.503892064095 -3.77280783653,1.67510616779,-0.493313133717 -3.77882146835,1.6761122942,-0.482721924782 -3.77183389664,1.67211961746,-0.469158470631 -3.77784776688,1.67412567139,-0.458566665649 -3.78386163712,1.67613184452,-0.447974056005 -3.77686667442,1.6721354723,-0.441175073385 -3.77787971497,1.67114210129,-0.429590255022 -3.79089474678,1.67614769936,-0.419999212027 -3.77490663528,1.66815638542,-0.404464066029 -3.77791976929,1.66916239262,-0.39385586977 -3.78893518448,1.67316854,-0.383286416531 -3.77993965149,1.66817235947,-0.37648293376 -3.78295373917,1.66917896271,-0.364908695221 -3.80296969414,1.67718398571,-0.356309473515 -3.78898072243,1.67019188404,-0.342725455761 -3.78699469566,1.66819918156,-0.330163151026 -3.8030102253,1.67520463467,-0.320575118065 -3.789021492,1.66721272469,-0.306997179985 -3.79302930832,1.6692160368,-0.301219910383 -3.80504393578,1.67422151566,-0.291611909866 -3.78905487061,1.66522967815,-0.278030663729 -3.79607009888,1.66823649406,-0.266471028328 -3.81208586693,1.67524182796,-0.256874412298 -3.79409646988,1.66525018215,-0.243291571736 -3.7931098938,1.6652572155,-0.231702148914 -3.80311799049,1.6692596674,-0.226909264922 -3.80413198471,1.66926658154,-0.215326428413 -3.79714488983,1.66527438164,-0.202752679586 -3.80916023254,1.67028033733,-0.192170366645 -3.8031733036,1.66628813744,-0.179601326585 -3.80218696594,1.66529512405,-0.168013483286 -3.81120157242,1.66930115223,-0.157419115305 -3.7992079258,1.66330647469,-0.149663105607 -3.80222129822,1.6643127203,-0.13905236125 -3.82323741913,1.67331755161,-0.129451826215 -3.80825018883,1.66532659531,-0.115899257362 -3.80726408958,1.66533374786,-0.104312509298 -3.8222796917,1.67133939266,-0.0937268659472 -3.81728577614,1.66934323311,-0.0879234448075 -3.80629849434,1.66335165501,-0.0753513947129 -3.81431412697,1.66635835171,-0.0637835562229 -3.82232832909,1.67036426067,-0.0531792417169 -3.81434202194,1.66537261009,-0.0406160205603 -3.82235741615,1.66937923431,-0.0290449354798 -3.81237006187,1.6643871069,-0.017445936799 -3.82337903976,1.66938996315,-0.0116700520739 -3.81839203835,1.66639757156,-7.94648658484e-05 -3.81740617752,1.66540491581,0.0115051111206 -3.81642007828,1.66541230679,0.0230896286666 -3.82243514061,1.66741895676,0.0346664860845 -3.81344938278,1.66342771053,0.0472233071923 -3.81545567513,1.66443049908,0.0520476922393 -3.81947040558,1.66543757915,0.0636271834373 -3.82048511505,1.66544485092,0.0752093940973 -3.82049942017,1.66545212269,0.0867923721671 -3.82151389122,1.66545939445,0.0983747392893 -3.82152819633,1.66546678543,0.109957665205 -3.82054400444,1.66547489166,0.122506067157 -3.82155108452,1.66547858715,0.128297165036 -3.82756519318,1.66848468781,0.138914600015 -3.82258009911,1.66549324989,0.151462584734 -3.81859469414,1.66450119019,0.163044825196 -3.84961009026,1.67850446701,0.173671081662 -3.84462428093,1.67651247978,0.185254737735 -3.85163927078,1.67951893806,0.196843326092 -3.82464599609,1.66652667522,0.203586056828 -3.83766150475,1.67253255844,0.215177819133 -3.83067584038,1.66954088211,0.226756677032 -3.81778621674,1.66459941864,0.313613891602 -3.84280252457,1.67660403252,0.326204419136 -3.83581709862,1.67261266708,0.337776839733 -3.83382463455,1.67161691189,0.343565404415 -3.829839468,1.6706250906,0.355142205954 -3.83585453033,1.6736317873,0.366738885641 -3.8278696537,1.67064070702,0.378306478262 -3.82188463211,1.66764938831,0.389876782894 -3.81589865685,1.66565740108,0.400480926037 -3.81791377068,1.66566479206,0.412068814039 -3.81892251968,1.66666924953,0.418828547001 -3.82693719864,1.67167556286,0.430433988571 -3.82695221901,1.67168331146,0.442018657923 -3.82596731186,1.67169117928,0.453600734472 -3.83198332787,1.67469835281,0.466169089079 -3.83299827576,1.67570602894,0.477758079767 -3.82501292229,1.67171466351,0.488352954388 -3.80802059174,1.66472101212,0.493125021458 -3.80403590202,1.66272962093,0.504695117474 -3.81705141068,1.66973555088,0.517289400101 -3.82906675339,1.67574167252,0.529882967472 -3.82308244705,1.67275059223,0.541447401047 -3.82309770584,1.67375850677,0.553033769131 -3.84410572052,1.68375945091,0.56083881855 -3.81812143326,1.67177128792,0.570393800735 -3.8331360817,1.67977654934,0.583006680012 -3.8211517334,1.67478621006,0.593579411507 -3.82116699219,1.6757941246,0.605166733265 -3.81518292427,1.67280328274,0.616727769375 -3.79919815063,1.66581332684,0.626311957836 -3.79820609093,1.66581749916,0.632100224495 -3.80822253227,1.67182457447,0.64566385746 -3.80623841286,1.67183291912,0.65724158287 -3.82525324821,1.68083775043,0.67085236311 -3.81626868248,1.67684710026,0.681431531906 -3.82328414917,1.68185400963,0.694021999836 -3.81630086899,1.67886352539,0.705575823784 -3.82830762863,1.68486535549,0.712399065495 -3.80132436752,1.67287766933,0.720948934555 -3.80534029007,1.67588531971,0.733525156975 -3.70683598518,1.66115307808,1.07572031021 -3.70385336876,1.66116225719,1.08728790283 -3.69687080383,1.66017210484,1.09785366058 -3.68888711929,1.6571816206,1.10744309425 -3.69790387154,1.66318893433,1.12201821804 -3.68991231918,1.66019439697,1.12580990791 -3.68992829323,1.66120266914,1.13740491867 -3.71694278717,1.67620635033,1.15601873398 -3.68096184731,1.66022086143,1.15857899189 -3.68997788429,1.66622805595,1.1731607914 -3.6989941597,1.67223513126,1.18774533272 -3.67500448227,1.66124355793,1.18751204014 -3.68702077866,1.66825020313,1.20309340954 -3.69103646278,1.67225778103,1.21569907665 -3.67705464363,1.66626894474,1.22425889969 -3.65807271004,1.65928077698,1.23083245754 -3.68108773232,1.67228531837,1.24943327904 -3.6651058197,1.6662967205,1.25700223446 -3.65811443329,1.66330206394,1.2607960701 -3.66913080215,1.67030882835,1.2763787508 -3.64514899254,1.66032135487,1.28095853329 -3.65216565132,1.66532897949,1.29553425312 -3.66018176079,1.67133629322,1.31012320518 -3.64619970322,1.66634714603,1.3177062273 -3.64221787453,1.6663569212,1.32926476002 -3.64622497559,1.66836023331,1.33607721329 -3.62824392319,1.66137206554,1.3426450491 -3.6232612133,1.6613817215,1.35322451591 -3.63127851486,1.66638946533,1.3687864542 -3.62229537964,1.66439926624,1.37738668919 -3.6013147831,1.65541195869,1.38294506073 -3.61533021927,1.6644179821,1.3995475769 -3.6013405323,1.6584250927,1.4013171196 -3.60235762596,1.66143369675,1.41390061378 -3.60037469864,1.66144275665,1.42548191547 -3.59239292145,1.66045296192,1.43505716324 -3.59240913391,1.66146123409,1.44666302204 -3.59442687035,1.66547000408,1.46022927761 -3.58743619919,1.66247582436,1.464012146 -3.59045338631,1.66648411751,1.47759211063 -3.58147072792,1.66349411011,1.48618602753 -3.57548928261,1.66250443459,1.49675178528 -3.56950640678,1.66151380539,1.50634968281 -3.57352423668,1.66652238369,1.52091300488 -3.56254315376,1.66253352165,1.52947878838 -3.56355047226,1.66453719139,1.53529715538 -3.56256866455,1.66654646397,1.54786288738 -3.55858588219,1.6665558815,1.55845463276 -3.55260467529,1.66556608677,1.56901967525 -3.55362129211,1.66757464409,1.58161354065 -3.54163980484,1.66458559036,1.58919489384 -3.53265762329,1.66159582138,1.59778285027 -3.5386660099,1.66659927368,1.60657477379 -3.52268576622,1.66061139107,1.61313056946 -3.52570271492,1.66461968422,1.62672197819 -3.5297203064,1.66862809658,1.64129686356 -3.51973938942,1.66663897038,1.6498695612 -3.51375675201,1.6656485796,1.65946543217 -3.51976466179,1.66965198517,1.66826319695 -3.50678443909,1.66566359997,1.67582368851 -3.49980258942,1.66467380524,1.68540477753 -3.49882078171,1.66668319702,1.69797682762 -3.49583768845,1.66669213772,1.70858383179 -3.48385715485,1.66370344162,1.71615481377 -3.4908747673,1.66971170902,1.73271965981 -3.48288440704,1.66671764851,1.73550665379 -3.47690224648,1.66672742367,1.74510192871 -3.47992014885,1.67073619366,1.75967395306 -3.46693897247,1.66674745083,1.76625835896 -3.45795798302,1.6647580862,1.77483868599 -3.46297550201,1.6697665453,1.7904125452 -3.44898605347,1.66377353668,1.79019808769 -3.45400214195,1.66878116131,1.80480492115 -3.44802165031,1.66879177094,1.81536853313 -3.44304013252,1.66880178452,1.82594752312 -3.4330599308,1.66681313515,1.83451032639 -3.4340763092,1.66982138157,1.84712147713 -3.42409610748,1.66683268547,1.85568320751 -3.42410564423,1.66883742809,1.86246621609 -3.42712306976,1.67284607887,1.87704992294 -3.4101433754,1.66685843468,1.88162195683 -3.41316103935,1.67186689377,1.89620757103 -3.40817809105,1.6718763113,1.90581834316 -3.40419745445,1.67288661003,1.91738426685 -3.39521694183,1.67089748383,1.92596006393 -3.39822602272,1.67390191555,1.93473386765 -3.38624548912,1.67091310024,1.94132077694 -3.38626265526,1.67292189598,1.95392334461 -3.38328099251,1.67493164539,1.96550774574 -3.3683013916,1.66994392872,1.97107207775 -3.36431956291,1.67095339298,1.98166954517 -3.36933755875,1.67696201801,1.998239398 -3.35035014153,1.66797065735,1.99500489235 -3.35136771202,1.67197942734,2.00859808922 -3.34638667107,1.67298960686,2.01917934418 -3.33240652084,1.66800165176,2.02475452423 -3.33142471313,1.67101073265,2.03734517097 -3.33244204521,1.67401957512,2.05094194412 -3.3214533329,1.67002654076,2.0517179966 -3.31547307968,1.67003726959,2.06228160858 -3.31549143791,1.6730465889,2.07586288452 -3.30151200294,1.66905868053,2.08143305779 -3.29553079605,1.66906881332,2.09102630615 -3.30354809761,1.67707669735,2.10960626602 -3.28257012367,1.66909039021,2.11116528511 -3.28957653046,1.67409288883,2.12099647522 -3.28759694099,1.67710328102,2.13454651833 -3.26861739159,1.67011594772,2.13613796234 -3.26263737679,1.67012679577,2.14670205116 -3.26865506172,1.67713499069,2.16428422928 -3.25167512894,1.67114710808,2.16687917709 -3.24569392204,1.67115736008,2.17647314072 -3.25470209122,1.67816054821,2.18926215172 -3.2327246666,1.66917443275,2.18981742859 -3.2307434082,1.6721842289,2.2023999691 -3.23176193237,1.67619335651,2.21698284149 -3.21578288078,1.67120587826,2.22056031227 -3.20980167389,1.67121613026,2.23015451431 -3.21081995964,1.67522525787,2.24473977089 -3.19483208656,1.66823339462,2.24151587486 -3.19885015488,1.67424178123,2.25810337067 -3.19586968422,1.67625212669,2.27067112923 -3.18389081955,1.67326426506,2.27723479271 -3.17291116714,1.6712757349,2.28381705284 -3.17492938042,1.67628479004,2.29939961433 -3.16394090652,1.67229175568,2.29918074608 -3.16095924377,1.67330145836,2.31077861786 -3.15397810936,1.67331182957,2.31938266754 -3.14199948311,1.67132389545,2.32594251633 -3.14101839066,1.67433357239,2.33952569962 -3.13403844833,1.67434453964,2.34910130501 -3.12904882431,1.67335045338,2.35288691521 -3.12206888199,1.67336142063,2.3624625206 -3.12708640099,1.68036949635,2.38006043434 -3.10810923576,1.67338335514,2.38161373138 -3.10112833977,1.67339372635,2.39021730423 -3.09714770317,1.6754039526,2.4017996788 -3.09916543961,1.68041276932,2.41739726067 -3.08617854118,1.67542076111,2.41615366936 -3.08519721031,1.67843031883,2.4297451973 -3.07221794128,1.67544209957,2.43433380127 -3.0662381649,1.67645299435,2.44490385056 -3.06625676155,1.68046247959,2.45949196815 -3.05927705765,1.68047344685,2.46906971931 -3.05329632759,1.68148374557,2.47866916656 -3.04730796814,1.68049037457,2.48243165016 -3.0393280983,1.6795014143,2.49101495743 -3.02834963799,1.67851340771,2.49758815765 -3.02536892891,1.68052351475,2.510171175 -3.01339006424,1.67853546143,2.51574826241 -3.00141143799,1.67554748058,2.52132415771 -3.00442862511,1.6815558672,2.53793287277 -2.99744057655,1.67956256866,2.54069876671 -2.99045968056,1.67957305908,2.54930377007 -2.98648047447,1.6825838089,2.56186890602 -2.97750067711,1.68159496784,2.5694565773 -2.96552205086,1.67860722542,2.57503008842 -2.96354150772,1.6826171875,2.58861494064 -2.95655369759,1.68062400818,2.59137892723 -2.95557284355,1.68463373184,2.6059615612 -2.95259094238,1.68764317036,2.61757969856 -2.93761396408,1.68365633488,2.62113666534 -2.93263292313,1.6846665144,2.63173604012 -2.92965364456,1.68867719173,2.64530396461 -2.91067671776,1.68169081211,2.64487051964 -2.90968632698,1.68369579315,2.6516661644 -2.90870547295,1.68770551682,2.66625547409 -2.90172600746,1.6887165308,2.67583727837 -2.88874793053,1.68472898006,2.68040895462 -2.88176846504,1.68574011326,2.6899907589 -2.87778902054,1.68875074387,2.70256614685 -2.87280797958,1.68976080418,2.71316981316 -2.87281727791,1.69276559353,2.72096705437 -2.85384130478,1.68577969074,2.72052264214 -2.8518614769,1.68978989124,2.73509693146 -2.84488201141,1.69080102444,2.7446808815 -2.83290314674,1.68881285191,2.74927210808 -2.82492399216,1.68882405758,2.75785708427 -2.8269340992,1.69282901287,2.76863002777 -2.81695508957,1.69184064865,2.77521824837 -2.80597734451,1.68985283375,2.78178191185 -2.8019964695,1.6928627491,2.79338955879 -2.79101848602,1.69087517262,2.79995274544 -2.78004002571,1.6898869276,2.80553984642 -2.77805972099,1.69389712811,2.8201239109 -2.77406954765,1.69390249252,2.82392954826 -2.76109242439,1.69091522694,2.82849216461 -2.76011180878,1.69592511654,2.84407925606 -2.74713373184,1.69293725491,2.84766530991 -2.74615311623,1.69794714451,2.86325502396 -2.73417592049,1.69595980644,2.86881685257 -2.72219753265,1.69397187233,2.87340164185 -2.72620677948,1.69997608662,2.88618969917 -2.732224226,1.70898425579,2.90879130363 -2.72024703026,1.70699691772,2.91435432434 -2.70027089119,1.70001077652,2.91093015671 -2.70328879356,1.70701956749,2.93053412437 -2.68631291389,1.70203340054,2.93108797073 -2.68432354927,1.70403885841,2.93787431717 -2.67934346199,1.70604932308,2.94946980476 -2.66336655617,1.70106244087,2.95004558563 -2.66038703918,1.70607304573,2.9646229744 -2.65340852737,1.70708453655,2.97519302368 -2.6374309063,1.70209729671,2.97478890419 -2.63845014572,1.70910668373,2.99337911606 -2.63946056366,1.71311175823,3.0041539669 -2.61548542976,1.70312654972,2.99572658539 -2.61050534248,1.70613706112,3.00732636452 -2.61352467537,1.71414649487,3.02890610695 -2.59854698181,1.71015906334,3.02950072289 -2.58557057381,1.70717215538,3.03405475616 -2.58957862854,1.71317577362,3.04686713219 -2.57360243797,1.70918917656,3.04743313789 -2.57162308693,1.71419978142,3.06400442123 -2.56764245033,1.71720981598,3.07661437988 -2.5486664772,1.71122360229,3.07318854332 -2.54768681526,1.71723389626,3.09076786041 -2.55870485306,1.73224198818,3.12333607674 -2.54571771622,1.7262493372,3.11712932587 -2.53174066544,1.72326231003,3.11970067024 -1.22815561295,0.797589063644,1.61879336834 -1.04360985756,0.727826476097,1.56243908405 -1.92819225788,1.78303575516,3.6555211544 -1.91121733189,1.7780495882,3.6510913372 -1.89924037457,1.77706193924,3.65468215942 -1.89125299454,1.7740688324,3.65346479416 -1.88227558136,1.7770806551,3.66305136681 -1.86829972267,1.77409374714,3.66362810135 -1.8553237915,1.77310657501,3.66620349884 -1.85134530067,1.78011739254,3.68578863144 -1.83836936951,1.77813029289,3.68836426735 -1.82438349724,1.77013838291,3.67514562607 -1.81840455532,1.77514922619,3.68974876404 -1.80342936516,1.77216267586,3.68832230568 -1.79445099831,1.77317392826,3.69692611694 -1.77947580814,1.77018737793,3.69549775124 -1.77149868011,1.77319920063,3.70807480812 -1.75852298737,1.77321219444,3.71064758301 -1.75053524971,1.77021884918,3.70843839645 -1.74255752563,1.77323031425,3.72003173828 -1.72958183289,1.77224338055,3.72260355949 -1.72160458565,1.77625513077,3.73518514633 -1.70762789249,1.77326774597,3.73378229141 -1.69465303421,1.77228116989,3.73733949661 -1.68467569351,1.77329289913,3.74493145943 -1.68368625641,1.77829813957,3.75772571564 -1.66871023178,1.77431106567,3.75431799889 -1.6547358036,1.77332472801,3.75587177277 -1.64475774765,1.77333629131,3.76247859001 -1.63378155231,1.77434873581,3.76905584335 -1.61780631542,1.76936209202,3.76363992691 -1.61181926727,1.77036881447,3.76740670204 -1.60384166241,1.77438044548,3.77999663353 -1.58986568451,1.77139317989,3.77858662605 -1.57689034939,1.77040624619,3.78115487099 -1.56491327286,1.76941847801,3.78375291824 -1.55393719673,1.77043092251,3.79033088684 -1.54396104813,1.77344334126,3.7999022007 -1.53797161579,1.77244901657,3.79971981049 -1.52199685574,1.7674626112,3.79429459572 -1.51402020454,1.77247452736,3.80886626244 -1.50404393673,1.77448689938,3.81843996048 -1.4850692749,1.76550066471,3.80402874947 -1.47909080982,1.77251160145,3.82162904739 -1.47011458874,1.77652382851,3.8341999054 -1.45512878895,1.76453197002,3.81298804283 -1.44515264034,1.76754438877,3.82256293297 -1.43817555904,1.77355599403,3.84013843536 -1.41920161247,1.764570117,3.82571578026 -1.50719618797,1.89556109905,4.09237527847 diff --git a/utils/README.md b/utils/README.md deleted file mode 100644 index cbdff5e..0000000 --- a/utils/README.md +++ /dev/null @@ -1,10 +0,0 @@ -### UTILS - ------------ -- parse_bin.py: binary -> txt.
- Each line in the txt represents one point, and the x, y, z coordinates are seperated by commas. - -- sample (dir):
- Includes two Kitti binary data samples (the first two frames from the 00 sequence). - ------------ diff --git a/utils/parse_bin.py b/utils/parse_bin.py deleted file mode 100644 index 0614aac..0000000 --- a/utils/parse_bin.py +++ /dev/null @@ -1,62 +0,0 @@ -import struct -import os - -def parse_bin(data): - ''' - Args: - - data: path to the Kitti binary file - Returns: - - a list in which each element is a list containing - the coordinates of one point - ''' - points = list() - with open(data, "rb") as f: - byte_ = f.read(4 * 4) - x0, y0, z0, i_ = struct.unpack('4f', byte_) - - # coordinate system conversion - x_ = -y0 - y_ = - z0 - z_ = x0 - - points.append([x_, y_, z_]) - while byte_ != b"": - byte_ = f.read(4 * 4) - if byte_ != b"": - x0, y0, z0, i_ = struct.unpack('4f', byte_) - - # coordinate system conversion - x_ = -y0 - y_ = - z0 - z_ = x0 - points.append([x_, y_, z_]) - return points - -if __name__ == '__main__': - - # dataset = "./sample/000000.bin" - # dst = "000000.txt" - - for j in range(10): - i = j + 1 - seq_id = "%02d" % i - dataset = "/localdisk/pointCloud_bin/Dataset/sequences/" + seq_id + "/velodyne/" - all_bins =[b for b in os.listdir(dataset) if ".bin" in b] - print(len(all_bins)) - - dst_dir = "/localdisk/pointCloud_txt/Dataset/sequences/" + seq_id + "/velodyne/" - if not os.path.exists(dst_dir): - os.makedirs(dst_dir) - - for bin_ in all_bins[:]: - src_ = dataset + bin_ - points = parse_bin(src_) - dst_ = dst_dir + bin_.split(".")[0] + ".txt" - # print(dst_) - # print(points) - - with open(dst_, 'w') as f: - for p_ in points: - f.write("%s," % p_[0]) - f.write("%s," % p_[1]) - f.write("%s\n" % p_[2])